From f4ceaae4c601705ea53964e6dca3fe66503412a0 Mon Sep 17 00:00:00 2001 From: sjentzsch Date: Wed, 24 Jun 2015 15:20:54 +0200 Subject: [PATCH] migrated from private SVN to public GitHub, started renaming from to --- .gitignore | 10 + CMakeLists.txt | 48 + Modules/FindAtidaq.cmake | 33 + Modules/FindBullet.cmake | 171 + Modules/FindCgal.cmake | 103 + Modules/FindCoin.cmake | 83 + Modules/FindComedi.cmake | 33 + Modules/FindEigen.cmake | 38 + Modules/FindIce.cmake | 303 + Modules/FindIconv.cmake | 59 + Modules/FindLibXml2.cmake | 52 + Modules/FindLibdc1394.cmake | 66 + Modules/FindOde.cmake | 100 + Modules/FindPqp.cmake | 53 + Modules/FindSoQt.cmake | 83 + Modules/FindSolid.cmake | 73 + Modules/FindZLIB.cmake | 55 + Modules/LICENSE.md | 10 + README.md | 7 + .../kuka-lwr4/rlkin/kuka-lwr4-right.xml | 190 + data/models/kuka-lwr4/rlkin/rlkin.xsd | 203 + .../rlmdl/kuka-lwr4-right_scene3.xml | 307 + .../rlmdl/kuka-lwr4-right_scene3_relaxed.xml | 307 + data/models/kuka-lwr4/rlsg/bottle-blue.wrl | 2119 + data/models/kuka-lwr4/rlsg/bottle-green.wrl | 2119 + data/models/kuka-lwr4/rlsg/bottle-red.wrl | 2119 + data/models/kuka-lwr4/rlsg/cylinder-blue.wrl | 22 + data/models/kuka-lwr4/rlsg/cylinder-green.wrl | 22 + data/models/kuka-lwr4/rlsg/cylinder-red.wrl | 22 + .../rlsg/kuka-lwr4-right_wall.convex.wrl | 15 + .../rlsg/kuka-lwr4-right_wall.convex.xml | 18 + .../kuka-lwr4/rlsg/kuka-lwr4-right_wall.wrl | 15 + .../kuka-lwr4/rlsg/kuka-lwr4-right_wall.xml | 18 + .../rlsg/kuka-lwr4.convex/kuka-link1.wrl | 6547 +++ .../rlsg/kuka-lwr4.convex/kuka-link2.wrl | 6713 +++ .../rlsg/kuka-lwr4.convex/kuka-link3.wrl | 6463 +++ .../rlsg/kuka-lwr4.convex/kuka-link4.wrl | 6707 +++ .../rlsg/kuka-lwr4.convex/kuka-link5.wrl | 7163 +++ .../rlsg/kuka-lwr4.convex/kuka-link6.wrl | 5883 ++ .../rlsg/kuka-lwr4.convex/kuka-link7.wrl | 455 + .../rlsg/kuka-lwr4.convex/kuka-lwr4-right.wrl | 83 + .../rlsg/kuka-lwr4.convex/kuka-swiwel.wrl | 479 + .../rlsg/kuka-lwr4.convex/link0-right.wrl | 12 + .../rlsg/kuka-lwr4.convex/link1-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link2-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link3-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link4-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link5-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link6-right.wrl | 13 + .../rlsg/kuka-lwr4.convex/link7-right.wrl | 12 + .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link1.wrl | 44404 ++++++++++++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link2.wrl | 44120 ++++++++++++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link3.wrl | 45650 +++++++++++++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link4.wrl | 44121 ++++++++++++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link5.wrl | 48339 ++++++++++++++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link6.wrl | 15354 +++++ .../kuka-lwr4/rlsg/kuka-lwr4/kuka-link7.wrl | 2968 + .../rlsg/kuka-lwr4/kuka-lwr4-right.wrl | 161 + .../kuka-lwr4/rlsg/kuka-lwr4/kuka-swiwel.wrl | 9206 +++ .../kuka-lwr4/rlsg/kuka-lwr4/link0-right.wrl | 12 + .../kuka-lwr4/rlsg/kuka-lwr4/link1-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link2-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link3-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link4-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link5-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link6-right.wrl | 13 + .../kuka-lwr4/rlsg/kuka-lwr4/link7-right.wrl | 12 + .../kuka-lwr4/rlsg/kuka-lwr4_scene1.wrl | 34 + .../kuka-lwr4/rlsg/kuka-lwr4_scene1.xml | 21 + .../kuka-lwr4/rlsg/kuka-lwr4_scene2.wrl | 52 + .../kuka-lwr4/rlsg/kuka-lwr4_scene2.xml | 24 + .../rlsg/kuka-lwr4_scene2_collision.wrl | 52 + .../rlsg/kuka-lwr4_scene2_collision.xml | 24 + .../kuka-lwr4/rlsg/kuka-lwr4_scene3.wrl | 68 + .../kuka-lwr4/rlsg/kuka-lwr4_scene3.xml | 27 + .../rlsg/kuka-scenario1-workspace.wrl | 38 + data/models/kuka-lwr4/rlsg/kuka-scenario1.wrl | 68 + data/models/kuka-lwr4/rlsg/kuka-scenario1.xml | 27 + .../rlsg/kuka-scenario2-hd-bottles.wrl | 98 + .../kuka-lwr4/rlsg/kuka-scenario2-hd.wrl | 41 + .../kuka-lwr4/rlsg/kuka-scenario2-hd.xml | 27 + .../rlsg/kuka-scenario2-workspace.wrl | 151 + data/models/kuka-lwr4/rlsg/kuka-scenario2.wrl | 68 + data/models/kuka-lwr4/rlsg/kuka-scenario2.xml | 27 + .../kuka-lwr4/rlsg/meka-scenario1-hd.wrl | 126 + data/models/kuka-lwr4/rlsg/scene1.wrl | 37 + data/models/kuka-lwr4/rlsg/table.wrl | 86 + .../mekabot-convex/bottle-blue-trans.wrl | 2119 + data/models/mekabot-convex/bottle-blue.wrl | 2119 + .../mekabot-convex/bottle-green-trans.wrl | 2119 + data/models/mekabot-convex/bottle-green.wrl | 2119 + .../mekabot-convex/bottle-invisible.wrl | 2119 + .../mekabot-convex/bottle-red-trans.wrl | 2119 + data/models/mekabot-convex/bottle-red.wrl | 2119 + .../mekabot-convex/environment.original1m.wrl | 200 + .../environment.rightHeight.wrl | 216 + data/models/mekabot-convex/environment.wrl | 251 + .../models/mekabot-convex/environment_old.wrl | 152 + .../mekabot-convex/meka-scenario1-hd.wrl | 126 + .../mekabot-convex/meka-scenario1-hd.xml | 47 + data/models/mekabot-convex/meka-scenario1.wrl | 99 + data/models/mekabot-convex/meka-scenario1.xml | 47 + .../rlmdl/mekabot-torso-rightarm-grasp.xml | 549 + .../rlmdl/mekabot-torso-rightarm.xml | 549 + .../rlmdl/mekabot-torso-rightarm.xml.original | 547 + .../rlsg/mekabot-torso-rightarm.convex-hd.wrl | 111 + .../rlsg/mekabot-torso-rightarm.convex-hd.xml | 22 + .../rlsg/mekabot-torso-rightarm.convex.wrl | 111 + .../rlsg/mekabot-torso-rightarm.convex.xml | 22 + .../A2R3/A2R3_LT1_shoulderRoll.wrl | 3114 + .../A2R3/A2R3_LT2_shoulderPitch.wrl | 994 + .../mekabot.convex/A2R3/A2R3_LT3_bicep.wrl | 3332 ++ .../mekabot.convex/A2R3/A2R3_LT4_elbow.wrl | 3322 ++ .../A2R3/A2R3_RT1_shoulderRoll.wrl | 3096 + .../A2R3/A2R3_RT2_shoulderPitch.wrl | 944 + .../mekabot.convex/A2R3/A2R3_RT3_bicep.wrl | 3306 ++ .../mekabot.convex/A2R3/A2R3_RT4_elbow.wrl | 3318 ++ .../mekabot.convex/A2R3/A2R3_T4_Chest.wrl | 1190 + .../A2R3/A2R3_T5_forearmRoll.wrl | 4350 ++ .../mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl | 2472 + .../mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl | 890 + .../rlsg/mekabot.convex/A2R3/hand-grasp.blend | Bin 0 -> 515768 bytes .../mekabot-h2r3-right.minimal.original.wrl | 350 + ...abot-h2r3-right.minimal.thumbfix.grasp.wrl | 192 + .../mekabot-h2r3-right.minimal.thumbfix.wrl | 285 + .../A2R3/mekabot-h2r3-right.minimal.wrl | 284 + .../rlsg/mekabot.convex/A2R3/pliers 1.wrl | 1772 + .../rlsg/mekabot.convex/A2R3/pliers 2.wrl | 1772 + .../rlsg/mekabot.convex/A2R3/pliers 3.wrl | 1772 + .../rlsg/mekabot.convex/A2R3/pliers.wrl | 2202 + .../mekabot.convex/T2R3/T2R3_TJ0_base.wrl | 1564 + .../rlsg/mekabot.convex/T2R3/T2R3_TJ1_pan.wrl | 1884 + .../rlsg/mekabot.convex/T2R3/T2R3_TJ2.wrl | 3954 ++ .../rlsg/mekabot.convex/T2R3/T2R3_TJ3.wrl | 2906 + data/models/mekabot-convex/scene-hd.xml | 60 + data/models/mekabot-convex/scene.xml | 51 + data/models/mekabot-convex/workspace-hd.wrl | 126 + data/models/mekabot-convex/workspace.wrl | 99 + data/models/mobile-robot/LICENSE.md | 10 + .../box-2d-050505_boxes.onePackage.wrl | 128 + .../box-2d-050505_boxes.onePackage.xml | 22 + .../mobile-robot/box-2d-050505_boxes.wrl | 128 + .../mobile-robot/box-2d-050505_boxes.xml | 22 + data/models/mobile-robot/boxes-scenario1.wrl | 146 + .../models/mobile-robot/boxes.noObstacles.wrl | 146 + data/models/mobile-robot/boxes.wrl | 146 + data/models/mobile-robot/mobile-robot-kin.xml | 94 + data/models/mobile-robot/mobile-robot-mdl.xml | 118 + .../mobile-robot/mobile-robot-scenario1.wrl | 158 + .../mobile-robot/mobile-robot-scenario1.xml | 25 + data/scripts/DamaRrt-graph.py | 245 + data/scripts/LICENSE.md | 10 + data/tasks-test/LICENSE.md | 10 + data/tasks-test/kuka-transfer-3-objects.xml | 92 + data/tasks-test/meka-simple-push.xml | 97 + .../mobile-robot-move-blocked-object.xml | 81 + data/tasks/LICENSE.md | 10 + data/tasks/kuka-scenario1.xml | 92 + data/tasks/kuka-scenario2.xml | 92 + data/tasks/kuka-test-push.xml | 94 + data/tasks/meka-scenario1.xml | 112 + data/tasks/meka-simple-test.xml | 98 + data/tasks/meka-simple.xml | 97 + data/tasks/meka-swap.xml | 98 + data/tasks/meka-test.xml | 98 + data/tasks/mobile-robot-scenario1.xml | 88 + data/tasks/mobile-robot-test.xml | 81 + src/CMakeLists.txt | 90 + src/DamaModel.cpp | 1436 + src/DamaModel.h | 243 + src/DamaPrim.h | 34 + src/DamaPrimPickup.cpp | 211 + src/DamaPrimPickup.h | 47 + src/DamaPrimPush.cpp | 26 + src/DamaPrimPush.h | 43 + src/DamaPrimPushExterior.cpp | 270 + src/DamaPrimPushExterior.h | 34 + src/DamaPrimPushFrontal.cpp | 270 + src/DamaPrimPushFrontal.h | 34 + src/DamaPrimPushInterior.cpp | 270 + src/DamaPrimPushInterior.h | 34 + src/DamaPrimPushMobile.cpp | 132 + src/DamaPrimPushMobile.h | 34 + src/DamaPrimTransferRigid.cpp | 160 + src/DamaPrimTransferRigid.h | 34 + src/DamaPrimTransit.cpp | 58 + src/DamaPrimTransit.h | 34 + src/DamaRrt.cpp | 2200 + src/DamaRrt.h | 136 + src/DamaRrtAction.cpp | 447 + src/DamaRrtAction.h | 188 + src/DamaRrtCon.cpp | 58 + src/DamaRrtCon.h | 31 + src/DamaRrtGoalBias.cpp | 51 + src/DamaRrtGoalBias.h | 41 + src/DamaSampler.cpp | 156 + src/DamaSampler.h | 49 + src/DamaSupportSurface.cpp | 51 + src/DamaSupportSurface.h | 38 + src/LICENSE.md | 10 + src/Timer.h | 56 + src/XmlFactory.cpp | 521 + src/XmlFactory.h | 39 + src/rlDamaDemoGUI/CMakeLists.txt | 108 + src/rlDamaDemoGUI/ConfigurationDelegate.cpp | 76 + src/rlDamaDemoGUI/ConfigurationDelegate.h | 37 + src/rlDamaDemoGUI/ConfigurationModel.cpp | 140 + src/rlDamaDemoGUI/ConfigurationModel.h | 38 + src/rlDamaDemoGUI/ConfigurationSpaceScene.cpp | 272 + src/rlDamaDemoGUI/ConfigurationSpaceScene.h | 92 + .../ConfigurationSpaceThread.cpp | 94 + src/rlDamaDemoGUI/ConfigurationSpaceThread.h | 42 + src/rlDamaDemoGUI/DamaPlanner.cpp | 292 + src/rlDamaDemoGUI/DamaPlanner.h | 49 + src/rlDamaDemoGUI/MainWindow.cpp | 1007 + src/rlDamaDemoGUI/MainWindow.h | 242 + src/rlDamaDemoGUI/PlannerModel.cpp | 312 + src/rlDamaDemoGUI/PlannerModel.h | 38 + src/rlDamaDemoGUI/Thread.cpp | 318 + src/rlDamaDemoGUI/Thread.h | 108 + src/rlDamaDemoGUI/Viewer.cpp | 991 + src/rlDamaDemoGUI/Viewer.h | 267 + src/rlDamaDemoGUI/rlDamaDemoGUI.cpp | 61 + src/rlDamaRun/CMakeLists.txt | 119 + src/rlDamaRun/DamaExecutor.cpp | 311 + src/rlDamaRun/DamaExecutor.h | 60 + src/rlDamaRun/DamaKukaFRIExecutor.cpp | 380 + src/rlDamaRun/DamaKukaFRIExecutor.h | 93 + src/rlDamaRun/KukaFRI.cpp | 145 + src/rlDamaRun/KukaFRI.h | 63 + src/rlDamaRun/meka-robot.ice | 55 + src/rlDamaRun/rlDamaKukaFRIRun.cpp | 49 + src/rlDamaRun/rlDamaRun.cpp | 48 + tests/LICENSE.md | 10 + tests/testIK/CMakeLists.txt | 30 + tests/testIK/testIK.cpp | 72 + tests/testMoplPlan/CMakeLists.txt | 60 + tests/testMoplPlan/testDamaPlan.cpp | 166 + 238 files changed, 388924 insertions(+) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 Modules/FindAtidaq.cmake create mode 100644 Modules/FindBullet.cmake create mode 100644 Modules/FindCgal.cmake create mode 100644 Modules/FindCoin.cmake create mode 100644 Modules/FindComedi.cmake create mode 100644 Modules/FindEigen.cmake create mode 100644 Modules/FindIce.cmake create mode 100644 Modules/FindIconv.cmake create mode 100644 Modules/FindLibXml2.cmake create mode 100644 Modules/FindLibdc1394.cmake create mode 100644 Modules/FindOde.cmake create mode 100644 Modules/FindPqp.cmake create mode 100644 Modules/FindSoQt.cmake create mode 100644 Modules/FindSolid.cmake create mode 100644 Modules/FindZLIB.cmake create mode 100644 Modules/LICENSE.md create mode 100644 README.md create mode 100644 data/models/kuka-lwr4/rlkin/kuka-lwr4-right.xml create mode 100644 data/models/kuka-lwr4/rlkin/rlkin.xsd create mode 100644 data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3.xml create mode 100644 data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3_relaxed.xml create mode 100644 data/models/kuka-lwr4/rlsg/bottle-blue.wrl create mode 100644 data/models/kuka-lwr4/rlsg/bottle-green.wrl create mode 100644 data/models/kuka-lwr4/rlsg/bottle-red.wrl create mode 100644 data/models/kuka-lwr4/rlsg/cylinder-blue.wrl create mode 100644 data/models/kuka-lwr4/rlsg/cylinder-green.wrl create mode 100644 data/models/kuka-lwr4/rlsg/cylinder-red.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link1.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link2.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link3.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link4.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link5.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link6.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link7.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-lwr4-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-swiwel.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link0-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link1-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link2-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link3-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link4-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link5-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link6-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link7-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link1.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link2.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link3.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link4.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link5.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link6.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link7.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-lwr4-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-swiwel.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link0-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link1-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link2-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link3-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link4-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link5-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link6-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4/link7-right.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario1-workspace.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario1.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario1.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2-hd-bottles.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.xml create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2-workspace.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2.wrl create mode 100644 data/models/kuka-lwr4/rlsg/kuka-scenario2.xml create mode 100644 data/models/kuka-lwr4/rlsg/meka-scenario1-hd.wrl create mode 100644 data/models/kuka-lwr4/rlsg/scene1.wrl create mode 100644 data/models/kuka-lwr4/rlsg/table.wrl create mode 100644 data/models/mekabot-convex/bottle-blue-trans.wrl create mode 100644 data/models/mekabot-convex/bottle-blue.wrl create mode 100644 data/models/mekabot-convex/bottle-green-trans.wrl create mode 100644 data/models/mekabot-convex/bottle-green.wrl create mode 100644 data/models/mekabot-convex/bottle-invisible.wrl create mode 100644 data/models/mekabot-convex/bottle-red-trans.wrl create mode 100644 data/models/mekabot-convex/bottle-red.wrl create mode 100644 data/models/mekabot-convex/environment.original1m.wrl create mode 100644 data/models/mekabot-convex/environment.rightHeight.wrl create mode 100644 data/models/mekabot-convex/environment.wrl create mode 100644 data/models/mekabot-convex/environment_old.wrl create mode 100644 data/models/mekabot-convex/meka-scenario1-hd.wrl create mode 100644 data/models/mekabot-convex/meka-scenario1-hd.xml create mode 100644 data/models/mekabot-convex/meka-scenario1.wrl create mode 100644 data/models/mekabot-convex/meka-scenario1.xml create mode 100644 data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm-grasp.xml create mode 100644 data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml create mode 100644 data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml.original create mode 100644 data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.xml create mode 100644 data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.xml create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT1_shoulderRoll.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT2_shoulderPitch.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT3_bicep.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT4_elbow.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT1_shoulderRoll.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT2_shoulderPitch.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT3_bicep.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT4_elbow.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T4_Chest.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T5_forearmRoll.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/hand-grasp.blend create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.original.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.grasp.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 1.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 2.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 3.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ0_base.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ1_pan.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ2.wrl create mode 100644 data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ3.wrl create mode 100644 data/models/mekabot-convex/scene-hd.xml create mode 100644 data/models/mekabot-convex/scene.xml create mode 100644 data/models/mekabot-convex/workspace-hd.wrl create mode 100644 data/models/mekabot-convex/workspace.wrl create mode 100644 data/models/mobile-robot/LICENSE.md create mode 100644 data/models/mobile-robot/box-2d-050505_boxes.onePackage.wrl create mode 100644 data/models/mobile-robot/box-2d-050505_boxes.onePackage.xml create mode 100644 data/models/mobile-robot/box-2d-050505_boxes.wrl create mode 100644 data/models/mobile-robot/box-2d-050505_boxes.xml create mode 100644 data/models/mobile-robot/boxes-scenario1.wrl create mode 100644 data/models/mobile-robot/boxes.noObstacles.wrl create mode 100644 data/models/mobile-robot/boxes.wrl create mode 100644 data/models/mobile-robot/mobile-robot-kin.xml create mode 100644 data/models/mobile-robot/mobile-robot-mdl.xml create mode 100644 data/models/mobile-robot/mobile-robot-scenario1.wrl create mode 100644 data/models/mobile-robot/mobile-robot-scenario1.xml create mode 100644 data/scripts/DamaRrt-graph.py create mode 100644 data/scripts/LICENSE.md create mode 100644 data/tasks-test/LICENSE.md create mode 100644 data/tasks-test/kuka-transfer-3-objects.xml create mode 100644 data/tasks-test/meka-simple-push.xml create mode 100644 data/tasks-test/mobile-robot-move-blocked-object.xml create mode 100644 data/tasks/LICENSE.md create mode 100644 data/tasks/kuka-scenario1.xml create mode 100644 data/tasks/kuka-scenario2.xml create mode 100644 data/tasks/kuka-test-push.xml create mode 100644 data/tasks/meka-scenario1.xml create mode 100644 data/tasks/meka-simple-test.xml create mode 100644 data/tasks/meka-simple.xml create mode 100644 data/tasks/meka-swap.xml create mode 100644 data/tasks/meka-test.xml create mode 100644 data/tasks/mobile-robot-scenario1.xml create mode 100644 data/tasks/mobile-robot-test.xml create mode 100644 src/CMakeLists.txt create mode 100644 src/DamaModel.cpp create mode 100644 src/DamaModel.h create mode 100644 src/DamaPrim.h create mode 100644 src/DamaPrimPickup.cpp create mode 100644 src/DamaPrimPickup.h create mode 100644 src/DamaPrimPush.cpp create mode 100644 src/DamaPrimPush.h create mode 100644 src/DamaPrimPushExterior.cpp create mode 100644 src/DamaPrimPushExterior.h create mode 100644 src/DamaPrimPushFrontal.cpp create mode 100644 src/DamaPrimPushFrontal.h create mode 100644 src/DamaPrimPushInterior.cpp create mode 100644 src/DamaPrimPushInterior.h create mode 100644 src/DamaPrimPushMobile.cpp create mode 100644 src/DamaPrimPushMobile.h create mode 100644 src/DamaPrimTransferRigid.cpp create mode 100644 src/DamaPrimTransferRigid.h create mode 100644 src/DamaPrimTransit.cpp create mode 100644 src/DamaPrimTransit.h create mode 100644 src/DamaRrt.cpp create mode 100644 src/DamaRrt.h create mode 100644 src/DamaRrtAction.cpp create mode 100644 src/DamaRrtAction.h create mode 100644 src/DamaRrtCon.cpp create mode 100644 src/DamaRrtCon.h create mode 100644 src/DamaRrtGoalBias.cpp create mode 100644 src/DamaRrtGoalBias.h create mode 100644 src/DamaSampler.cpp create mode 100644 src/DamaSampler.h create mode 100644 src/DamaSupportSurface.cpp create mode 100644 src/DamaSupportSurface.h create mode 100644 src/LICENSE.md create mode 100644 src/Timer.h create mode 100644 src/XmlFactory.cpp create mode 100644 src/XmlFactory.h create mode 100644 src/rlDamaDemoGUI/CMakeLists.txt create mode 100644 src/rlDamaDemoGUI/ConfigurationDelegate.cpp create mode 100644 src/rlDamaDemoGUI/ConfigurationDelegate.h create mode 100644 src/rlDamaDemoGUI/ConfigurationModel.cpp create mode 100644 src/rlDamaDemoGUI/ConfigurationModel.h create mode 100644 src/rlDamaDemoGUI/ConfigurationSpaceScene.cpp create mode 100644 src/rlDamaDemoGUI/ConfigurationSpaceScene.h create mode 100644 src/rlDamaDemoGUI/ConfigurationSpaceThread.cpp create mode 100644 src/rlDamaDemoGUI/ConfigurationSpaceThread.h create mode 100644 src/rlDamaDemoGUI/DamaPlanner.cpp create mode 100644 src/rlDamaDemoGUI/DamaPlanner.h create mode 100644 src/rlDamaDemoGUI/MainWindow.cpp create mode 100644 src/rlDamaDemoGUI/MainWindow.h create mode 100644 src/rlDamaDemoGUI/PlannerModel.cpp create mode 100644 src/rlDamaDemoGUI/PlannerModel.h create mode 100644 src/rlDamaDemoGUI/Thread.cpp create mode 100644 src/rlDamaDemoGUI/Thread.h create mode 100644 src/rlDamaDemoGUI/Viewer.cpp create mode 100644 src/rlDamaDemoGUI/Viewer.h create mode 100644 src/rlDamaDemoGUI/rlDamaDemoGUI.cpp create mode 100644 src/rlDamaRun/CMakeLists.txt create mode 100644 src/rlDamaRun/DamaExecutor.cpp create mode 100644 src/rlDamaRun/DamaExecutor.h create mode 100644 src/rlDamaRun/DamaKukaFRIExecutor.cpp create mode 100644 src/rlDamaRun/DamaKukaFRIExecutor.h create mode 100644 src/rlDamaRun/KukaFRI.cpp create mode 100644 src/rlDamaRun/KukaFRI.h create mode 100644 src/rlDamaRun/meka-robot.ice create mode 100644 src/rlDamaRun/rlDamaKukaFRIRun.cpp create mode 100644 src/rlDamaRun/rlDamaRun.cpp create mode 100644 tests/LICENSE.md create mode 100644 tests/testIK/CMakeLists.txt create mode 100644 tests/testIK/testIK.cpp create mode 100644 tests/testMoplPlan/CMakeLists.txt create mode 100644 tests/testMoplPlan/testDamaPlan.cpp diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..ab17d30 --- /dev/null +++ b/.gitignore @@ -0,0 +1,10 @@ +*~ + +Release/ +Debug/ +output/ +data/models/mekabot-convex/rlsg/mekabot/ + +.settings/ +.project +.cproject diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..354591e --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 2.8.11) + +project(mopl) + +set(VERSION_MAJOR 0) +set(VERSION_MINOR 0) +set(VERSION_PATCH 1) +set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) + +set(CMAKE_VERBOSE_MAKEFILE 1) +set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/Modules) + +set(Boost_ADDITIONAL_VERSIONS "1.56.0" "1.56" "1.55.0" "1.55" "1.54.0" "1.54" "1.53.0" "1.53" "1.52.0" "1.52" "1.51.0" "1.51" "1.50.0" "1.50" "1.49.0" "1.49" "1.48.0" "1.48" "1.47.0" "1.47") + +if(CMAKE_SIZEOF_VOID_P EQUAL 4) + add_definitions(-DEIGEN_DONT_ALIGN) +endif(CMAKE_SIZEOF_VOID_P EQUAL 4) + +include(CheckCXXCompilerFlag) + +if(WIN32) + add_definitions( + -D_SCL_SECURE_NO_WARNINGS + -D_USE_MATH_DEFINES + -D_WIN32_WINNT=0x400 + -DNOMINMAX + ) +else() + check_cxx_compiler_flag("-std=c++0x" HAS_CXX_COMPILER_FLAG_STDCXX0X) + if(HAS_CXX_COMPILER_FLAG_STDCXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") + endif() +endif() + +add_subdirectory(src) +add_subdirectory(src/rlDamaDemoGUI) +add_subdirectory(src/rlDamaRun) + +# create symlink to models +execute_process( + COMMAND ${CMAKE_COMMAND} -E create_symlink + ${CMAKE_CURRENT_SOURCE_DIR}/data + ${CMAKE_CURRENT_BINARY_DIR}/data +) + +enable_testing() +add_subdirectory(tests/testMoplPlan) +add_subdirectory(tests/testIK) diff --git a/Modules/FindAtidaq.cmake b/Modules/FindAtidaq.cmake new file mode 100644 index 0000000..3323b7a --- /dev/null +++ b/Modules/FindAtidaq.cmake @@ -0,0 +1,33 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FIND_PATH( + ATIDAQ_INCLUDE_DIRS + NAMES + atidaq/ftconfig.h + HINTS + $ENV{HOME}/include + /usr/local/include + /usr/include +) + +FIND_LIBRARY( + ATIDAQ_LIBRARIES + NAMES + atidaq + HINTS + $ENV{HOME}/lib + /usr/local/lib + /usr/lib +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + ATIDAQ + DEFAULT_MSG + ATIDAQ_INCLUDE_DIRS + ATIDAQ_LIBRARIES +) + +MARK_AS_ADVANCED( + ATIDAQ_INCLUDE_DIRS + ATIDAQ_LIBRARIES +) diff --git a/Modules/FindBullet.cmake b/Modules/FindBullet.cmake new file mode 100644 index 0000000..3e39798 --- /dev/null +++ b/Modules/FindBullet.cmake @@ -0,0 +1,171 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + BULLET_INCLUDE_PATHS + $ENV{BULLETDIR}/include/bullet + $ENV{HOME}/include/bullet + /usr/local/include/bullet + /usr/include/bullet + $ENV{ProgramW6432}/bullet*/include/bullet + $ENV{ProgramFiles}/bullet*/include/bullet + $ENV{ProgramW6432}/rl*/include/bullet + $ENV{ProgramFiles}/rl*/include/bullet +) + +FILE( + GLOB + BULLET_LIBRARY_PATHS + $ENV{BULLETDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/bullet*/lib + $ENV{ProgramFiles}/bullet*/lib + $ENV{ProgramW6432}/rl*/lib + $ENV{ProgramFiles}/rl*/lib +) + +FIND_PATH( + BULLET_INCLUDE_DIRS + NAMES + Bullet-C-Api.h + HINTS + ${BULLET_INCLUDE_PATHS} +) + +FIND_LIBRARY( + BULLET_COLLISION_LIBRARY_DEBUG + NAMES + bulletcollisiond BulletCollisiond BulletCollision_debug + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_COLLISION_LIBRARY_RELEASE + NAMES + bulletcollision BulletCollision + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG + NAMES + convexdecompositiond ConvexDecompositiond ConvexDecomposition_debug + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE + NAMES + convexdecomposition ConvexDecomposition + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_DYNAMICS_LIBRARY_DEBUG + NAMES + bulletdynamicsd BulletDynamicsd BulletDynamics_debug + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_DYNAMICS_LIBRARY_RELEASE + NAMES + bulletdynamics BulletDynamics + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_MATH_LIBRARY_DEBUG + NAMES + bulletmathd LinearMathd LinearMath_debug + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_MATH_LIBRARY_RELEASE + NAMES + bulletmath LinearMath + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_SOFTBODY_LIBRARY_DEBUG + NAMES + bulletsoftbodyd BulletSoftBodyd BulletSoftBody_debug + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FIND_LIBRARY( + BULLET_SOFTBODY_LIBRARY_RELEASE + NAMES + bulletsoftbody BulletSoftBody + HINTS + ${BULLET_LIBRARY_PATHS} +) + +FOREACH(LIBRARY BULLET_COLLISION_LIBRARY BULLET_CONVEXDECOMPOSITION_LIBRARY BULLET_DYNAMICS_LIBRARY BULLET_MATH_LIBRARY BULLET_SOFTBODY_LIBRARY) + SET(BULLET_LIBRARY ${LIBRARY}) + + IF(${LIBRARY}_DEBUG AND NOT ${LIBRARY}_RELEASE) + SET(${BULLET_LIBRARY} ${${LIBRARY}_DEBUG}) + ENDIF(${LIBRARY}_DEBUG AND NOT ${LIBRARY}_RELEASE) + + IF(${LIBRARY}_RELEASE AND NOT ${LIBRARY}_DEBUG) + SET(${BULLET_LIBRARY} ${${LIBRARY}_RELEASE}) + ENDIF(${LIBRARY}_RELEASE AND NOT ${LIBRARY}_DEBUG) + + IF(${LIBRARY}_DEBUG AND ${LIBRARY}_RELEASE) + SET(${BULLET_LIBRARY} debug ${${LIBRARY}_DEBUG} optimized ${${LIBRARY}_RELEASE}) + ENDIF(${LIBRARY}_DEBUG AND ${LIBRARY}_RELEASE) +ENDFOREACH(LIBRARY) + +SET( + BULLET_LIBRARIES + ${BULLET_COLLISION_LIBRARY} + ${BULLET_CONVEXDECOMPOSITION_LIBRARY} + ${BULLET_DYNAMICS_LIBRARY} + ${BULLET_MATH_LIBRARY} + ${BULLET_SOFTBODY_LIBRARY} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + Bullet + DEFAULT_MSG + BULLET_INCLUDE_DIRS + BULLET_COLLISION_LIBRARY +# BULLET_CONVEXDECOMPOSITION_LIBRARY + BULLET_DYNAMICS_LIBRARY + BULLET_MATH_LIBRARY + BULLET_SOFTBODY_LIBRARY +) + +MARK_AS_ADVANCED( + BULLET_INCLUDE_DIRS + BULLET_COLLISION_LIBRARY + BULLET_COLLISION_LIBRARY_DEBUG + BULLET_COLLISION_LIBRARY_RELEASE + BULLET_CONVEXDECOMPOSITION_LIBRARY + BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG + BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE + BULLET_DYNAMICS_LIBRARY + BULLET_DYNAMICS_LIBRARY_DEBUG + BULLET_DYNAMICS_LIBRARY_RELEASE + BULLET_LIBRARIES + BULLET_MATH_LIBRARY + BULLET_MATH_LIBRARY_DEBUG + BULLET_MATH_LIBRARY_RELEASE + BULLET_SOFTBODY_LIBRARY + BULLET_SOFTBODY_LIBRARY_DEBUG + BULLET_SOFTBODY_LIBRARY_RELEASE +) diff --git a/Modules/FindCgal.cmake b/Modules/FindCgal.cmake new file mode 100644 index 0000000..062ed51 --- /dev/null +++ b/Modules/FindCgal.cmake @@ -0,0 +1,103 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + CGAL_COMPILER_INCLUDE_PATHS + $ENV{CGALROOT}/include/CGAL/config/* + $ENV{HOME}/include/CGAL/config/* + /usr/local/include/CGAL/config/* + /usr/include/CGAL/config/* + $ENV{ProgramW6432}/CGAL*/include/CGAL/config/* + $ENV{ProgramFiles}/CGAL*/include/CGAL/config/* +) +FILE( + GLOB + CGAL_INCLUDE_PATHS + $ENV{CGALROOT}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{ProgramW6432}/CGAL*/include + $ENV{ProgramFiles}/CGAL*/include +) +FILE( + GLOB + CGAL_LIBRARY_PATHS + $ENV{CGALROOT}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/CGAL*/lib + $ENV{ProgramFiles}/CGAL*/lib +) + +FIND_PATH( + CGAL_COMPILER_INCLUDE_DIR + NAMES + CGAL/compiler_config.h + HINTS + ${CGAL_COMPILER_INCLUDE_PATHS} + ${CGAL_INCLUDE_PATHS} +) + +FIND_PATH( + CGAL_INCLUDE_DIR + NAMES + CGAL/CORE/CORE.h + HINTS + ${CGAL_INCLUDE_PATHS} +) + +FIND_LIBRARY( + CGAL_LIBRARY_DEBUG + NAMES + CGALd + cgal-vc100-mt-gd-4.1 cgal-vc100-mt-gd-4.0 cgal-vc100-mt-gd + cgal-vc90-mt-gd-4.1 cgal-vc90-mt-gd-4.0 cgal-vc90-mt-gd + cgal-vc80-mt-gd-4.1 cgal-vc80-mt-gd-4.0 cgal-vc80-mt-gd + cgal-vc71-mt-gd-4.1 cgal-vc71-mt-gd-4.0 cgal-vc71-mt-gd + HINTS + ${CGAL_LIBRARY_PATHS} +) + +FIND_LIBRARY( + CGAL_LIBRARY_RELEASE + NAMES + CGAL + cgal-vc100-mt-4.1 cgal-vc100-mt-4.0 cgal-vc100-mt + cgal-vc90-mt-4.1 cgal-vc90-mt-4.0 cgal-vc90-mt + cgal-vc80-mt-4.1 cgal-vc80-mt-4.0 cgal-vc80-mt + cgal-vc71-mt-4.1 cgal-vc71-mt-4.0 cgal-vc71-mt + HINTS + ${CGAL_LIBRARY_PATHS} +) + +IF(CGAL_LIBRARY_DEBUG AND NOT CGAL_LIBRARY_RELEASE) + SET(CGAL_LIBRARIES ${CGAL_LIBRARY_DEBUG}) +ENDIF(CGAL_LIBRARY_DEBUG AND NOT CGAL_LIBRARY_RELEASE) + +IF(CGAL_LIBRARY_RELEASE AND NOT CGAL_LIBRARY_DEBUG) + SET(CGAL_LIBRARIES ${CGAL_LIBRARY_RELEASE}) +ENDIF(CGAL_LIBRARY_RELEASE AND NOT CGAL_LIBRARY_DEBUG) + +IF(CGAL_LIBRARY_DEBUG AND CGAL_LIBRARY_RELEASE) + SET(CGAL_LIBRARIES debug ${CGAL_LIBRARY_DEBUG} optimized ${CGAL_LIBRARY_RELEASE}) +ENDIF(CGAL_LIBRARY_DEBUG AND CGAL_LIBRARY_RELEASE) + +SET(CGAL_INCLUDE_DIRS ${CGAL_INCLUDE_DIR} ${CGAL_COMPILER_INCLUDE_DIR}) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + CGAL + DEFAULT_MSG + CGAL_INCLUDE_DIRS + CGAL_LIBRARIES +) + +MARK_AS_ADVANCED( + CGAL_COMPILER_INCLUDE_DIR + CGAL_INCLUDE_DIR + CGAL_INCLUDE_DIRS + CGAL_LIBRARIES + CGAL_LIBRARY_DEBUG + CGAL_LIBRARY_RELEASE +) diff --git a/Modules/FindCoin.cmake b/Modules/FindCoin.cmake new file mode 100644 index 0000000..cc220a5 --- /dev/null +++ b/Modules/FindCoin.cmake @@ -0,0 +1,83 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + COIN_INCLUDE_PATHS + $ENV{COINDIR}/include + $ENV{COIN3DDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include/Coin* + /usr/include + $ENV{SystemDrive}/Coin*/include + $ENV{ProgramW6432}/Coin*/include + $ENV{ProgramFiles}/Coin*/include +) + +FILE( + GLOB + COIN_LIBRARY_PATHS + $ENV{COINDIR}/lib + $ENV{COIN3DDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{SystemDrive}/Coin*/lib + $ENV{ProgramW6432}/Coin*/lib + $ENV{ProgramFiles}/Coin*/lib +) + +FIND_PATH( + COIN_INCLUDE_DIRS + NAMES + Inventor/So.h + HINTS + ${COIN_INCLUDE_PATHS} +) + +FIND_LIBRARY( + COIN_LIBRARY_DEBUG + NAMES + Coind coin2d coin3d + HINTS + ${COIN_LIBRARY_PATHS} +) + +FIND_LIBRARY( + COIN_LIBRARY_RELEASE + NAMES + Coin coin2 coin3 + HINTS + ${COIN_LIBRARY_PATHS} +) + +IF(WIN32) + SET(COIN_DEFINITIONS -DCOIN_NOT_DLL) +ENDIF(WIN32) + +IF(COIN_LIBRARY_DEBUG AND NOT COIN_LIBRARY_RELEASE) + SET(COIN_LIBRARIES ${COIN_LIBRARY_DEBUG}) +ENDIF(COIN_LIBRARY_DEBUG AND NOT COIN_LIBRARY_RELEASE) + +IF(COIN_LIBRARY_RELEASE AND NOT COIN_LIBRARY_DEBUG) + SET(COIN_LIBRARIES ${COIN_LIBRARY_RELEASE}) +ENDIF(COIN_LIBRARY_RELEASE AND NOT COIN_LIBRARY_DEBUG) + +IF(COIN_LIBRARY_DEBUG AND COIN_LIBRARY_RELEASE) + SET(COIN_LIBRARIES debug ${COIN_LIBRARY_DEBUG} optimized ${COIN_LIBRARY_RELEASE}) +ENDIF(COIN_LIBRARY_DEBUG AND COIN_LIBRARY_RELEASE) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + Coin + DEFAULT_MSG + COIN_INCLUDE_DIRS + COIN_LIBRARIES +) + +MARK_AS_ADVANCED( + COIN_DEFINITIONS + COIN_INCLUDE_DIRS + COIN_LIBRARIES + COIN_LIBRARY_DEBUG + COIN_LIBRARY_RELEASE +) diff --git a/Modules/FindComedi.cmake b/Modules/FindComedi.cmake new file mode 100644 index 0000000..4c3942e --- /dev/null +++ b/Modules/FindComedi.cmake @@ -0,0 +1,33 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FIND_PATH( + COMEDI_INCLUDE_DIRS + NAMES + comedilib.h + HINTS + $ENV{HOME}/include + /usr/local/include + /usr/include +) + +FIND_LIBRARY( + COMEDI_LIBRARIES + NAMES + comedi + HINTS + $ENV{HOME}/lib + /usr/local/lib + /usr/lib +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + Comedi + DEFAULT_MSG + COMEDI_INCLUDE_DIRS + COMEDI_LIBRARIES +) + +MARK_AS_ADVANCED( + COMEDI_INCLUDE_DIRS + COMEDI_LIBRARIES +) diff --git a/Modules/FindEigen.cmake b/Modules/FindEigen.cmake new file mode 100644 index 0000000..e2f0b43 --- /dev/null +++ b/Modules/FindEigen.cmake @@ -0,0 +1,38 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + EIGEN_INCLUDE_PATHS + $ENV{EIGENDIR} + $ENV{HOME}/include + /usr/local/include/eigen3 + /usr/local/include/eigen* + /usr/local/include + /usr/include/eigen3 + /usr/include/eigen* + /usr/include + /opt/local/include/eigen* + $ENV{ProgramW6432}/eigen*/include/eigen3 + $ENV{ProgramFiles}/eigen*/include/eigen3 + $ENV{ProgramW6432}/eigen* + $ENV{ProgramFiles}/eigen* +) + +FIND_PATH( + EIGEN_INCLUDE_DIRS + NAMES + Eigen/Core + HINTS + ${EIGEN_INCLUDE_PATHS} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + Eigen + DEFAULT_MSG + EIGEN_INCLUDE_DIRS +) + +MARK_AS_ADVANCED( + EIGEN_FOUND + EIGEN_INCLUDE_DIRS +) diff --git a/Modules/FindIce.cmake b/Modules/FindIce.cmake new file mode 100644 index 0000000..7e1dd90 --- /dev/null +++ b/Modules/FindIce.cmake @@ -0,0 +1,303 @@ +# FindIce.cmake -- based on a module written by Markus Rickert for the JAST project. + +# Doesn't seem to work properly with CMake 2.6 +cmake_minimum_required(VERSION 2.8.5) +# does not work with 2.8.3--2.8.4 +# http://www.cmake.org/Bug/bug_relationship_graph.php?bug_id=11973&graph=relation + +# Workaround for missing library links on DICE +SET(CMAKE_FIND_LIBRARY_SUFFIXES .so.34 ${CMAKE_FIND_LIBRARY_SUFFIXES}) + +# Hack for finding the right files for various Windows compilers +# See http://doc.zeroc.com/display/Ice/Using+the+Windows+Binary+Distribution +IF (CMAKE_GENERATOR MATCHES "Visual Studio 10 Win64") + SET (SUBDIR "/vc100/x64") +ELSEIF (CMAKE_GENERATOR MATCHES "Visual Studio 10") + SET (SUBDIR "/vc100") +ELSEIF (CMAKE_GENERATOR MATCHES "Visual 9 2008 Win64") + SET (SUBDIR "/x64") +ELSEIF (ICE_SUBDIR) + # (e.g., if you're using NMake makefiles and you still need 64-bitness) + SET (SUBDIR ${ICE_SUBDIR}) +ENDIF () + +FILE( + GLOB + ICE_BIN_DIRS + $ENV{ICE_HOME}/bin${SUBDIR} + $ENV{HOME}/bin${SUBDIR} + /opt/Ice-*/bin${SUBDIR} + /usr/local/bin${SUBDIR} + /usr/bin${SUBDIR} + $ENV{SystemDrive}/Ice-*/bin${SUBDIR} + $ENV{ProgramFiles}/ZeroC/Ice-*/bin${SUBDIR} + $ENV{ProgramFilesW6432}/ZeroC/Ice-*/bin${SUBDIR} +) +FILE( + GLOB + ICE_INCLUDE_DIRS + $ENV{ICE_HOME}/include + $ENV{HOME}/include + /opt/Ice-*/include + /usr/local/include + /usr/include + $ENV{SystemDrive}/Ice-*/include + $ENV{ProgramFiles}/ZeroC/Ice-*/include + $ENV{ProgramFilesW6432}/ZeroC/Ice-*/include +) +FILE( + GLOB + ICE_LIBRARY_DIRS + $ENV{ICE_HOME}/lib${SUBDIR} + $ENV{HOME}/lib${SUBDIR} + /opt/Ice-*/lib${SUBDIR} + /usr/local/lib${SUBDIR} + /usr/lib${SUBDIR} + $ENV{SystemDrive}/Ice-*/lib${SUBDIR} + $ENV{ProgramFiles}/ZeroC/Ice-*/lib${SUBDIR} + $ENV{ProgramFilesW6432}/ZeroC/Ice-*/lib${SUBDIR} +) +FILE( + GLOB + ICE_SLICE_DIRS + $ENV{ICE_HOME}/slice + $ENV{HOME}/share/slice + /opt/Ice-*/slice + /usr/local/share/slice + /usr/share/slice + /usr/share/Ice-*/slice + $ENV{SystemDrive}/Ice-*/slice + $ENV{ProgramFiles}/ZeroC/Ice-*/slice + $ENV{ProgramFilesW6432}/ZeroC/Ice-*/slice +) + +FIND_PATH( + ICE_INCLUDE_DIR + Ice/Application.h + ${ICE_INCLUDE_DIRS} +) + +FIND_PATH( + ICE_SLICE_DIR + Ice/BuiltinSequences.ice + ${ICE_SLICE_DIRS} +) + +MACRO(ICE_ADJUST_LIB_VARS basename) + IF (ICE_${basename}_LIBRARY_DEBUG AND NOT ICE_${basename}_LIBRARY_RELEASE) + SET(ICE_${basename}_LIBRARY ${ICE_${basename}_LIBRARY_DEBUG}) + ENDIF (ICE_${basename}_LIBRARY_DEBUG AND NOT ICE_${basename}_LIBRARY_RELEASE) + + IF (ICE_${basename}_LIBRARY_RELEASE AND NOT ICE_${basename}_LIBRARY_DEBUG) + SET(ICE_${basename}_LIBRARY ${ICE_${basename}_LIBRARY_RELEASE}) + ENDIF (ICE_${basename}_LIBRARY_RELEASE AND NOT ICE_${basename}_LIBRARY_DEBUG) + + IF (ICE_${basename}_LIBRARY_DEBUG AND ICE_${basename}_LIBRARY_RELEASE) + SET(ICE_${basename}_LIBRARY debug ${ICE_${basename}_LIBRARY_DEBUG} optimized ${ICE_${basename}_LIBRARY_RELEASE}) + ENDIF (ICE_${basename}_LIBRARY_DEBUG AND ICE_${basename}_LIBRARY_RELEASE) + + IF (ICE_${basename}_LIBRARY) + SET(ICE_${basename}_FOUND TRUE) + ENDIF (ICE_${basename}_LIBRARY) +ENDMACRO(ICE_ADJUST_LIB_VARS) + +FIND_LIBRARY(ICE_FREEZE_LIBRARY_DEBUG NAMES Freezed PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_FREEZE_LIBRARY_RELEASE NAMES Freeze PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(FREEZE) + +FIND_LIBRARY(ICE_GLACIER2_LIBRARY_DEBUG NAMES Glacier2d PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_GLACIER2_LIBRARY_RELEASE NAMES Glacier2 PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(GLACIER2) + +FIND_LIBRARY(ICE_ICE_LIBRARY_DEBUG NAMES Iced PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICE_LIBRARY_RELEASE NAMES Ice PATHS ${ICE_LIBRARY_DIRS} NO_DEFAULT_PATH) +ICE_ADJUST_LIB_VARS(ICE) + +FIND_LIBRARY(ICE_ICEBOX_LIBRARY_DEBUG NAMES IceBoxd PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICEBOX_LIBRARY_RELEASE NAMES IceBox PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICEBOX) + +FIND_LIBRARY(ICE_ICEGRID_LIBRARY_DEBUG NAMES IceGridd PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICEGRID_LIBRARY_RELEASE NAMES IceGrid PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICEGRID) + +FIND_LIBRARY(ICE_ICEPATCH2_LIBRARY_DEBUG NAMES IcePatch2d PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICEPATCH2_LIBRARY_RELEASE NAMES IcePatch2 PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICEPATCH2) + +FIND_LIBRARY(ICE_ICESSL_LIBRARY_DEBUG NAMES IceSSLd PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICESSL_LIBRARY_RELEASE NAMES IceSSL PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICESSL) + +FIND_LIBRARY(ICE_ICESTORM_LIBRARY_DEBUG NAMES IceStormd PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICESTORM_LIBRARY_RELEASE NAMES IceStorm PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICESTORM) + +FIND_LIBRARY(ICE_ICESTORMSERVICE_LIBRARY_DEBUG NAMES IceStormServiced PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICESTORMSERVICE_LIBRARY_RELEASE NAMES IceStormService PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICESTORMSERVICE) + +FIND_LIBRARY(ICE_ICEUTIL_LIBRARY_DEBUG NAMES IceUtild PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICEUTIL_LIBRARY_RELEASE NAMES IceUtil PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICEUTIL) + +FIND_LIBRARY(ICE_ICEXML_LIBRARY_DEBUG NAMES IceXMLd PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_ICEXML_LIBRARY_RELEASE NAMES IceXML PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(ICEXML) + +FIND_LIBRARY(ICE_SLICE_LIBRARY_DEBUG NAMES Sliced PATHS ${ICE_LIBRARY_DIRS}) +FIND_LIBRARY(ICE_SLICE_LIBRARY_RELEASE NAMES Slice PATHS ${ICE_LIBRARY_DIRS}) +ICE_ADJUST_LIB_VARS(SLICE) + +FIND_PROGRAM(ICE_SLICE2CPP slice2cpp ${ICE_BIN_DIRS}) + +IF (ICE_SLICE2CPP) + SET(ICE_SLICE2CPP_FOUND TRUE) +ENDIF (ICE_SLICE2CPP) + +IF(NOT (CMAKE_SYSTEM MATCHES Windows)) + SET (PTHREAD_IF_NECESSARY pthread) +ENDIF() + +IF ( + ICE_INCLUDE_DIR AND + ICE_FREEZE_FOUND AND + ICE_GLACIER2_FOUND AND + ICE_ICE_FOUND AND + ICE_ICEBOX_FOUND AND + ICE_ICEGRID_FOUND AND + ICE_ICEPATCH2_FOUND AND + ICE_ICESSL_FOUND AND + ICE_ICESTORM_FOUND AND + ICE_ICESTORMSERVICE_FOUND AND + ICE_ICEUTIL_FOUND AND + ICE_ICEXML_FOUND AND + ICE_SLICE_DIR AND + ICE_SLICE_FOUND AND + ICE_SLICE2CPP_FOUND +) + SET(ICE_FOUND TRUE) + + SET( + ICE_LIBRARIES + ${ICE_FREEZE_LIBRARY} + ${ICE_GLACIER2_LIBRARY} + ${ICE_ICE_LIBRARY} + ${ICE_ICEBOX_LIBRARY} + ${ICE_ICEGRID_LIBRARY} + ${ICE_ICEPATCH2_LIBRARY} + ${ICE_ICESSL_LIBRARY} + ${ICE_ICESTORM_LIBRARY} + ${ICE_ICESTORMSERVICE} + ${ICE_ICEUTIL_LIBRARY} + ${ICE_ICEXML_LIBRARY} + ${ICE_SLICE_LIBRARY} + ${PTHREAD_IF_NECESSARY} + ) +ENDIF ( + ICE_INCLUDE_DIR AND + ICE_FREEZE_FOUND AND + ICE_GLACIER2_FOUND AND + ICE_ICE_FOUND AND + ICE_ICEBOX_FOUND AND + ICE_ICEGRID_FOUND AND + ICE_ICEPATCH2_FOUND AND + ICE_ICESSL_FOUND AND + ICE_ICESTORM_FOUND AND + ICE_ICESTORMSERVICE_FOUND AND + ICE_ICEUTIL_FOUND AND + ICE_ICEXML_FOUND AND + ICE_SLICE_DIR AND + ICE_SLICE_FOUND AND + ICE_SLICE2CPP_FOUND +) + +MACRO(ICE_WRAP_CPP_2 outfiles) + SET(SLICE_INCLUDES -I${ICE_SLICE_DIR}) + FILE(TO_CMAKE_PATH "${ARGN}" argn_cmake) + FOREACH(i ${argn_cmake}) + IF(IS_DIRECTORY ${i}) + # If the argument is a directory, it's the directory where the next set of files exist + # -- also add it to the persistent include path + SET(base ${i}) + SET(SLICE_INCLUDES -I${base} ${SLICE_INCLUDES}) + ELSE() + # Otherwise, it's a file to process + GET_FILENAME_COMPONENT(name ${i} NAME) + GET_FILENAME_COMPONENT(name_we ${i} NAME_WE) + GET_FILENAME_COMPONENT(relative ${i} PATH) + SET(infile ${base}/${relative}/${name}) + SET(outfile1 ${CMAKE_CURRENT_BINARY_DIR}/${relative}/${name_we}.cpp) + SET(outfile2 ${CMAKE_CURRENT_BINARY_DIR}/${relative}/${name_we}.h) + FILE(MAKE_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/${relative}) + ADD_CUSTOM_COMMAND( + OUTPUT ${outfile1} ${outfile2} + COMMAND ${ICE_SLICE2CPP} + ARGS ${SLICE_INCLUDES} -I${base}/${relative} --output-dir ${CMAKE_CURRENT_BINARY_DIR}/${relative} ${infile} + MAIN_DEPENDENCY ${infile} + ) + Message("Running: ${ICE_SLICE2CPP} ${SLICE_INCLUDES} -I${base}/${relative} --output-dir ${CMAKE_CURRENT_BINARY_DIR}/${relative} ${infile}") + SET(${outfiles} ${${outfiles}} ${outfile1} ${outfile2}) + INCLUDE_DIRECTORIES(${CMAKE_CURRENT_BINARY_DIR}) + INCLUDE_DIRECTORIES(${CMAKE_CURRENT_BINARY_DIR}/${relative}) + ENDIF() + ENDFOREACH(i) +ENDMACRO(ICE_WRAP_CPP_2) + +MARK_AS_ADVANCED( + ICE_FOUND + ICE_FREEZE_FOUND + ICE_FREEZE_LIBRARY + ICE_FREEZE_LIBRARY_DEBUG + ICE_FREEZE_LIBRARY_RELEASE + ICE_GLACIER2_FOUND + ICE_GLACIER2_LIBRARY + ICE_GLACIER2_LIBRARY_DEBUG + ICE_GLACIER2_LIBRARY_RELEASE + ICE_ICE_FOUND + ICE_ICE_LIBRARY + ICE_ICE_LIBRARY_DEBUG + ICE_ICE_LIBRARY_RELEASE + ICE_ICEBOX_FOUND + ICE_ICEBOX_LIBRARY + ICE_ICEBOX_LIBRARY_DEBUG + ICE_ICEBOX_LIBRARY_RELEASE + ICE_ICEGRID_FOUND + ICE_ICEGRID_LIBRARY + ICE_ICEGRID_LIBRARY_DEBUG + ICE_ICEGRID_LIBRARY_RELEASE + ICE_ICEPATCH2_FOUND + ICE_ICEPATCH2_LIBRARY + ICE_ICEPATCH2_LIBRARY_DEBUG + ICE_ICEPATCH2_LIBRARY_RELEASE + ICE_ICESSL_FOUND + ICE_ICESSL_LIBRARY + ICE_ICESSL_LIBRARY_DEBUG + ICE_ICESSL_LIBRARY_RELEASE + ICE_ICESTORM_FOUND + ICE_ICESTORM_LIBRARY + ICE_ICESTORM_LIBRARY_DEBUG + ICE_ICESTORM_LIBRARY_RELEASE + ICE_ICESTORMSERVICE_FOUND + ICE_ICESTORMSERVICE_LIBRARY + ICE_ICESTORMSERVICE_LIBRARY_DEBUG + ICE_ICESTORMSERVICE_LIBRARY_RELEASE + ICE_ICEUTIL_FOUND + ICE_ICEUTIL_LIBRARY + ICE_ICEUTIL_LIBRARY_DEBUG + ICE_ICEUTIL_LIBRARY_RELEASE + ICE_ICEXML_FOUND + ICE_ICEXML_LIBRARY + ICE_ICEXML_LIBRARY_DEBUG + ICE_ICEXML_LIBRARY_RELEASE + ICE_INCLUDE_DIR + ICE_LIBRARIES + ICE_SLICE_DIR + ICE_SLICE_FOUND + ICE_SLICE_LIBRARY + ICE_SLICE_LIBRARY_DEBUG + ICE_SLICE_LIBRARY_RELEASE + ICE_SLICE2CPP + ICE_WRAP_CPP + ICE_WRAP_CPP_2 +) diff --git a/Modules/FindIconv.cmake b/Modules/FindIconv.cmake new file mode 100644 index 0000000..d88f3c5 --- /dev/null +++ b/Modules/FindIconv.cmake @@ -0,0 +1,59 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + ICONV_INCLUDE_PATHS + $ENV{ICONVDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{ProgramW6432}/iconv*/include + $ENV{ProgramFiles}/iconv*/include + $ENV{ProgramW6432}/libiconv*/include + $ENV{ProgramFiles}/libiconv*/include + $ENV{ProgramW6432}/GnuWin32/include + $ENV{ProgramFiles}/GnuWin32/include +) + +FILE( + GLOB + ICONV_LIBRARY_PATHS + $ENV{ICONVDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/iconv*/lib + $ENV{ProgramFiles}/iconv*/lib + $ENV{ProgramW6432}/libiconv*/lib + $ENV{ProgramFiles}/libiconv*/lib + $ENV{ProgramW6432}/GnuWin32/lib + $ENV{ProgramFiles}/GnuWin32/lib +) + +FIND_PATH( + ICONV_INCLUDE_DIRS + NAMES + iconv.h + HINTS + ${ICONV_INCLUDE_PATHS} +) + +FIND_LIBRARY( + ICONV_LIBRARIES + NAMES + iconv libiconv libiconv_a + HINTS + ${ICONV_LIBRARY_PATHS} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + ICONV + DEFAULT_MSG + ICONV_INCLUDE_DIRS + ICONV_LIBRARIES +) + +MARK_AS_ADVANCED( + ICONV_INCLUDE_DIRS + ICONV_LIBRARIES +) diff --git a/Modules/FindLibXml2.cmake b/Modules/FindLibXml2.cmake new file mode 100644 index 0000000..6634f15 --- /dev/null +++ b/Modules/FindLibXml2.cmake @@ -0,0 +1,52 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + LIBXML2_INCLUDE_PATHS + $ENV{LIBXML2DIR}/include/libxml2 + $ENV{HOME}/include + $ENV{HOME}/include/libxml2 + /usr/local/include/libxml2 + /usr/include/libxml2 + $ENV{ProgramW6432}/libxml2*/include + $ENV{ProgramFiles}/libxml2*/include +) + +FILE( + GLOB + LIBXML2_LIBRARY_PATHS + $ENV{LIBXML2DIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/libxml2*/lib + $ENV{ProgramFiles}/libxml2*/lib +) + +FIND_PATH( + LIBXML2_INCLUDE_DIRS + NAMES + libxml/parser.h + HINTS + ${LIBXML2_INCLUDE_PATHS} +) + +FIND_LIBRARY( + LIBXML2_LIBRARIES + NAMES + libxml2 xml2 + HINTS + ${LIBXML2_LIBRARY_PATHS} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + LibXml2 + DEFAULT_MSG + LIBXML2_INCLUDE_DIRS + LIBXML2_LIBRARIES +) + +MARK_AS_ADVANCED( + LIBXML2_INCLUDE_DIRS + LIBXML2_LIBRARIES +) diff --git a/Modules/FindLibdc1394.cmake b/Modules/FindLibdc1394.cmake new file mode 100644 index 0000000..d0d7986 --- /dev/null +++ b/Modules/FindLibdc1394.cmake @@ -0,0 +1,66 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FIND_PATH( + LIBDC1394_V1_INCLUDE_DIR + libdc1394/dc1394_control.h + $ENV{HOME}/include + /usr/local/include + /usr/include +) + +FIND_PATH( + LIBDC1394_V2_INCLUDE_DIR + dc1394/dc1394.h + $ENV{HOME}/include + /usr/local/include + /usr/include +) + +FIND_LIBRARY( + LIBDC1394_V1_LIBRARY + NAMES + dc1394_control + PATHS + $ENV{HOME}/lib + /usr/local/lib + /usr/lib +) + +FIND_LIBRARY( + LIBDC1394_V2_LIBRARY + NAMES + dc1394 + PATHS + $ENV{HOME}/lib + /usr/local/lib + /usr/lib +) + +IF(LIBDC1394_V1_INCLUDE_DIR AND LIBDC1394_V1_LIBRARY) + SET(LIBDC1394_DEFINITIONS -DLIBDC1394_VERSION_MAJOR=10) + SET(LIBDC1394_INCLUDE_DIRS ${LIBDC1394_V1_INCLUDE_DIR}) + SET(LIBDC1394_LIBRARIES ${LIBDC1394_V1_LIBRARY}) +ENDIF(LIBDC1394_V1_INCLUDE_DIR AND LIBDC1394_V1_LIBRARY) + +IF(LIBDC1394_V2_INCLUDE_DIR AND LIBDC1394_V2_LIBRARY) + SET(LIBDC1394_DEFINITIONS -DLIBDC1394_VERSION_MAJOR=20) + SET(LIBDC1394_INCLUDE_DIRS ${LIBDC1394_V2_INCLUDE_DIR}) + SET(LIBDC1394_LIBRARIES ${LIBDC1394_V2_LIBRARY}) +ENDIF(LIBDC1394_V2_INCLUDE_DIR AND LIBDC1394_V2_LIBRARY) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + libdc1394 + DEFAULT_MSG + LIBDC1394_INCLUDE_DIRS + LIBDC1394_LIBRARIES +) + +MARK_AS_ADVANCED( + LIBDC1394_DEFINITIONS + LIBDC1394_INCLUDE_DIRS + LIBDC1394_LIBRARIES + LIBDC1394_V1_INCLUDE_DIR + LIBDC1394_V1_LIBRARY + LIBDC1394_V2_INCLUDE_DIR + LIBDC1394_V2_LIBRARY +) diff --git a/Modules/FindOde.cmake b/Modules/FindOde.cmake new file mode 100644 index 0000000..4d920d4 --- /dev/null +++ b/Modules/FindOde.cmake @@ -0,0 +1,100 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + ODE_INCLUDE_PATHS + $ENV{ODEDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{SystemDrive}/ode*/include + $ENV{ProgramW6432}/ode*/include + $ENV{ProgramFiles}/ode*/include +) + +FILE( + GLOB + ODE_LIBRARY_PATHS + $ENV{ODEDIR}/lib + $ENV{HOME}/lib/ReleaseSingleDLL + $ENV{HOME}/lib/DebugSingleDLL + $ENV{HOME}/lib/ReleaseDoubleDLL + $ENV{HOME}/lib/DebugDoubleDLL + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{SystemDrive}/ode*/lib/ReleaseSingleDLL + $ENV{ProgramW6432}/ode*/lib/ReleaseSingleDLL + $ENV{ProgramFiles}/ode*/lib/ReleaseSingleDLL + $ENV{SystemDrive}/ode*/lib/DebugSingleDLL + $ENV{ProgramW6432}/ode*/lib/DebugSingleDLL + $ENV{ProgramFiles}/ode*/lib/DebugSingleDLL + $ENV{SystemDrive}/ode*/lib/ReleaseDoubleDLL + $ENV{ProgramW6432}/ode*/lib/ReleaseDoubleDLL + $ENV{ProgramFiles}/ode*/lib/ReleaseDoubleDLL + $ENV{SystemDrive}/ode*/lib/DebugDoubleDLL + $ENV{ProgramW6432}/ode*/lib/DebugDoubleDLL + $ENV{ProgramFiles}/ode*/lib/DebugDoubleDLL + $ENV{SystemDrive}/ode*/lib + $ENV{ProgramW6432}/ode*/lib + $ENV{ProgramFiles}/ode*/lib +) + +FIND_PATH( + ODE_INCLUDE_DIRS + NAMES + ode/ode.h + HINTS + ${ODE_INCLUDE_PATHS} +) + +FIND_LIBRARY( + ODE_LIBRARY_DEBUG + NAMES + oded ode_singled ode_doubled + HINTS + ${ODE_LIBRARY_PATHS} +) + +FIND_LIBRARY( + ODE_LIBRARY_RELEASE + NAMES + ode ode_single ode_double + HINTS + ${ODE_LIBRARY_PATHS} +) + +OPTION(ODE_USE_DOUBLE_PRECISION "ODE use double precision" FALSE) + +IF(ODE_USE_DOUBLE_PRECISION) + SET(ODE_DEFINITIONS -DdDOUBLE) +ELSE(ODE_USE_DOUBLE_PRECISION) + SET(ODE_DEFINITIONS -DdSINGLE) +ENDIF(ODE_USE_DOUBLE_PRECISION) + +IF(ODE_LIBRARY_DEBUG AND NOT ODE_LIBRARY_RELEASE) + SET(ODE_LIBRARIES ${ODE_LIBRARY_DEBUG}) +ENDIF(ODE_LIBRARY_DEBUG AND NOT ODE_LIBRARY_RELEASE) + +IF(ODE_LIBRARY_RELEASE AND NOT ODE_LIBRARY_DEBUG) + SET(ODE_LIBRARIES ${ODE_LIBRARY_RELEASE}) +ENDIF(ODE_LIBRARY_RELEASE AND NOT ODE_LIBRARY_DEBUG) + +IF(ODE_LIBRARY_DEBUG AND ODE_LIBRARY_RELEASE) + SET(ODE_LIBRARIES debug ${ODE_LIBRARY_DEBUG} optimized ${ODE_LIBRARY_RELEASE}) +ENDIF(ODE_LIBRARY_DEBUG AND ODE_LIBRARY_RELEASE) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + ODE + DEFAULT_MSG + ODE_INCLUDE_DIRS + ODE_LIBRARIES +) + +MARK_AS_ADVANCED( + ODE_DEFINITIONS + ODE_INCLUDE_DIRS + ODE_LIBRARIES + ODE_LIBRARY_DEBUG + ODE_LIBRARY_RELEASE +) diff --git a/Modules/FindPqp.cmake b/Modules/FindPqp.cmake new file mode 100644 index 0000000..d34be81 --- /dev/null +++ b/Modules/FindPqp.cmake @@ -0,0 +1,53 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + PQP_INCLUDE_PATHS + $ENV{PQPDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{SystemDrive}/pqp*/include + $ENV{ProgramW6432}/pqp*/include + $ENV{ProgramFiles}/pqp*/include +) + +FILE( + GLOB + PQP_LIBRARY_PATHS + $ENV{PQPDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{SystemDrive}/pqp*/lib + $ENV{ProgramW6432}/pqp*/lib + $ENV{ProgramFiles}/pqp*/lib +) + +FIND_PATH( + PQP_INCLUDE_DIRS + NAMES + PQP.h + HINTS + ${PQP_INCLUDE_PATHS} +) + +FIND_LIBRARY( + PQP_LIBRARIES + NAMES + PQP + HINTS + ${PQP_LIBRARY_PATHS} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + PQP + DEFAULT_MSG + PQP_INCLUDE_DIRS + PQP_LIBRARIES +) + +MARK_AS_ADVANCED( + PQP_INCLUDE_DIRS + PQP_LIBRARIES +) diff --git a/Modules/FindSoQt.cmake b/Modules/FindSoQt.cmake new file mode 100644 index 0000000..e206e77 --- /dev/null +++ b/Modules/FindSoQt.cmake @@ -0,0 +1,83 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + SOQT_INCLUDE_PATHS + $ENV{COINDIR}/include + $ENV{COIN3DDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include/Coin* + /usr/include + $ENV{SystemDrive}/Coin*/include + $ENV{ProgramW6432}/Coin*/include + $ENV{ProgramFiles}/Coin*/include +) + +FILE( + GLOB + SOQT_LIBRARY_PATHS + $ENV{COINDIR}/lib + $ENV{COIN3DDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{SystemDrive}/Coin*/lib + $ENV{ProgramW6432}/Coin*/lib + $ENV{ProgramFiles}/Coin*/lib +) + +FIND_PATH( + SOQT_INCLUDE_DIRS + NAMES + Inventor/Qt/SoQt.h + HINTS + ${SOQT_INCLUDE_PATHS} +) + +FIND_LIBRARY( + SOQT_LIBRARY_DEBUG + NAMES + SoQtd soqt1d + HINTS + ${SOQT_LIBRARY_PATHS} +) + +FIND_LIBRARY( + SOQT_LIBRARY_RELEASE + NAMES + SoQt soqt1 + HINTS + ${SOQT_LIBRARY_PATHS} +) + +IF(WIN32) + SET(SOQT_DEFINITIONS -DSOQT_NOT_DLL) +ENDIF(WIN32) + +IF(SOQT_LIBRARY_DEBUG AND NOT SOQT_LIBRARY_RELEASE) + SET(SOQT_LIBRARIES ${SOQT_LIBRARY_DEBUG}) +ENDIF(SOQT_LIBRARY_DEBUG AND NOT SOQT_LIBRARY_RELEASE) + +IF(SOQT_LIBRARY_RELEASE AND NOT SOQT_LIBRARY_DEBUG) + SET(SOQT_LIBRARIES ${SOQT_LIBRARY_RELEASE}) +ENDIF(SOQT_LIBRARY_RELEASE AND NOT SOQT_LIBRARY_DEBUG) + +IF(SOQT_LIBRARY_DEBUG AND SOQT_LIBRARY_RELEASE) + SET(SOQT_LIBRARIES debug ${SOQT_LIBRARY_DEBUG} optimized ${SOQT_LIBRARY_RELEASE}) +ENDIF(SOQT_LIBRARY_DEBUG AND SOQT_LIBRARY_RELEASE) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + SoQt + DEFAULT_MSG + SOQT_INCLUDE_DIRS + SOQT_LIBRARIES +) + +MARK_AS_ADVANCED( + SOQT_DEFINITIONS + SOQT_INCLUDE_DIRS + SOQT_LIBRARIES + SOQT_LIBRARY_DEBUG + SOQT_LIBRARY_RELEASE +) diff --git a/Modules/FindSolid.cmake b/Modules/FindSolid.cmake new file mode 100644 index 0000000..37cf228 --- /dev/null +++ b/Modules/FindSolid.cmake @@ -0,0 +1,73 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + SOLID_INCLUDE_PATHS + $ENV{SOLIDDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{ProgramW6432}/solid*/include + $ENV{ProgramFiles}/solid*/include +) + +FILE( + GLOB + SOLID_LIBRARY_PATHS + $ENV{SOLIDDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/solid*/lib + $ENV{ProgramFiles}/solid*/lib +) + +FIND_PATH( + SOLID_INCLUDE_DIRS + NAMES + SOLID/SOLID.h + HINTS + ${SOLID_INCLUDE_PATHS} +) + +FIND_LIBRARY( + SOLID_LIBRARY_DEBUG + NAMES + solidd solidsd + HINTS + ${SOLID_LIBRARY_PATHS} +) + +FIND_LIBRARY( + SOLID_LIBRARY_RELEASE + NAMES + solid solids + HINTS + ${SOLID_LIBRARY_PATHS} +) + +IF(SOLID_LIBRARY_DEBUG AND NOT SOLID_LIBRARY_RELEASE) + SET(SOLID_LIBRARIES ${SOLID_LIBRARY_DEBUG}) +ENDIF(SOLID_LIBRARY_DEBUG AND NOT SOLID_LIBRARY_RELEASE) + +IF(SOLID_LIBRARY_RELEASE AND NOT SOLID_LIBRARY_DEBUG) + SET(SOLID_LIBRARIES ${SOLID_LIBRARY_RELEASE}) +ENDIF(SOLID_LIBRARY_RELEASE AND NOT SOLID_LIBRARY_DEBUG) + +IF(SOLID_LIBRARY_DEBUG AND SOLID_LIBRARY_RELEASE) + SET(SOLID_LIBRARIES debug ${SOLID_LIBRARY_DEBUG} optimized ${SOLID_LIBRARY_RELEASE}) +ENDIF(SOLID_LIBRARY_DEBUG AND SOLID_LIBRARY_RELEASE) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + SOLID + DEFAULT_MSG + SOLID_INCLUDE_DIRS + SOLID_LIBRARIES +) + +MARK_AS_ADVANCED( + SOLID_INCLUDE_DIRS + SOLID_LIBRARIES + SOLID_LIBRARY_DEBUG + SOLID_LIBRARY_RELEASE +) diff --git a/Modules/FindZLIB.cmake b/Modules/FindZLIB.cmake new file mode 100644 index 0000000..3d5b207 --- /dev/null +++ b/Modules/FindZLIB.cmake @@ -0,0 +1,55 @@ +INCLUDE(FindPackageHandleStandardArgs) + +FILE( + GLOB + ZLIB_INCLUDE_PATHS + $ENV{ZLIBDIR}/include + $ENV{HOME}/include + /usr/local/include + /usr/include + $ENV{ProgramW6432}/zlib*/include + $ENV{ProgramFiles}/zlib*/include + $ENV{ProgramW6432}/GnuWin32/include + $ENV{ProgramFiles}/GnuWin32/include +) + +FILE( + GLOB + ZLIB_LIBRARY_PATHS + $ENV{ZLIBDIR}/lib + $ENV{HOME}/lib + /usr/local/lib + /usr/lib + $ENV{ProgramW6432}/zlib*/lib + $ENV{ProgramFiles}/zlib*/lib + $ENV{ProgramW6432}/GnuWin32/lib + $ENV{ProgramFiles}/GnuWin32/lib +) + +FIND_PATH( + ZLIB_INCLUDE_DIRS + NAMES + zlib.h + HINTS + ${ZLIB_INCLUDE_PATHS} +) + +FIND_LIBRARY( + ZLIB_LIBRARIES + NAMES + z zlib zlib_a zlibstat zlibwapi zdll + HINTS + ${ZLIB_LIBRARY_PATHS} +) + +FIND_PACKAGE_HANDLE_STANDARD_ARGS( + ZLIB + DEFAULT_MSG + ZLIB_INCLUDE_DIRS + ZLIB_LIBRARIES +) + +MARK_AS_ADVANCED( + ZLIB_INCLUDE_DIRS + ZLIB_LIBRARIES +) diff --git a/Modules/LICENSE.md b/Modules/LICENSE.md new file mode 100644 index 0000000..8b513a6 --- /dev/null +++ b/Modules/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Markus Rickert +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/README.md b/README.md new file mode 100644 index 0000000..a027550 --- /dev/null +++ b/README.md @@ -0,0 +1,7 @@ +MOPL: A Multi-Modal Path Planner for Generic Manipulation Tasks +======= + +MOPL: A Multi-Modal Path Planner for Generic Manipulation Tasks, inspired by the diverse action manipulation (DAMA) algorithm, and build upon the Robotics Library (RL). + +Installation: + diff --git a/data/models/kuka-lwr4/rlkin/kuka-lwr4-right.xml b/data/models/kuka-lwr4/rlkin/kuka-lwr4-right.xml new file mode 100644 index 0000000..b4026d4 --- /dev/null +++ b/data/models/kuka-lwr4/rlkin/kuka-lwr4-right.xml @@ -0,0 +1,190 @@ + + + + KUKA + LWR IV Right + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + 0.31 + 0 + 0 + 90 + + 170 + -170 + 100 + + + + + + + + + + + + 0 + 0 + 0 + -90 + + 50 + -50 + 110 + + + + + + + + + + + + 0.4 + 0 + 0 + -90 + + 170 + -170 + 100 + + + + + + + + + + + + 0 + 0 + 0 + 90 + + 120 + -120 + 130 + + + + + + + + + + + + 0.39 + 0 + 0 + 90 + + 170 + -170 + 130 + + + + + + + + + + + + + 0 + 0 + 0 + -90 + + 120 + -120 + 180 + + + + + + + + + + + + 0 + 0 + 0 + 0 + + 170 + -170 + 180 + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.24 + + + + + diff --git a/data/models/kuka-lwr4/rlkin/rlkin.xsd b/data/models/kuka-lwr4/rlkin/rlkin.xsd new file mode 100644 index 0000000..a7e7b55 --- /dev/null +++ b/data/models/kuka-lwr4/rlkin/rlkin.xsd @@ -0,0 +1,203 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3.xml b/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3.xml new file mode 100644 index 0000000..29824ac --- /dev/null +++ b/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3.xml @@ -0,0 +1,307 @@ + + + + KUKA + LWR IV Right + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + 0 + 0 + 9.86055 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.31 + + + + + + + + 170 + -170 + 100 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 50 + -50 + 110 + + + + + + + + -90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.4 + + + + + + + + 170 + -170 + 100 + + + + + + + + -90 + 0 + + + + 0 + 0 + 0 + + + + + + + + 120 + -120 + 130 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.39 + + + + + + + + 170 + -170 + 130 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 120 + -120 + 180 + + + + + + + + -90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 170 + -170 + 180 + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.285 + + + + diff --git a/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3_relaxed.xml b/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3_relaxed.xml new file mode 100644 index 0000000..cc68613 --- /dev/null +++ b/data/models/kuka-lwr4/rlmdl/kuka-lwr4-right_scene3_relaxed.xml @@ -0,0 +1,307 @@ + + + + KUKA + LWR IV Right + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + 0 + 0 + 9.86055 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.31 + + + + + + + + 190 + -190 + 100 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 70 + -70 + 110 + + + + + + + + -90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.4 + + + + + + + + 190 + -190 + 100 + + + + + + + + -90 + 0 + + + + 0 + 0 + 0 + + + + + + + + 140 + -140 + 130 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.39 + + + + + + + + 190 + -190 + 130 + + + + + + + + 90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 140 + -140 + 180 + + + + + + + + -90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 190 + -190 + 180 + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.285 + + + + diff --git a/data/models/kuka-lwr4/rlsg/bottle-blue.wrl b/data/models/kuka-lwr4/rlsg/bottle-blue.wrl new file mode 100644 index 0000000..794c5f4 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/bottle-blue.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.17 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.2 0.2 0.8 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/bottle-green.wrl b/data/models/kuka-lwr4/rlsg/bottle-green.wrl new file mode 100644 index 0000000..f8768d0 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/bottle-green.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.17 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.2 0.8 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/bottle-red.wrl b/data/models/kuka-lwr4/rlsg/bottle-red.wrl new file mode 100644 index 0000000..e080266 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/bottle-red.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.17 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.8 0.2 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/cylinder-blue.wrl b/data/models/kuka-lwr4/rlsg/cylinder-blue.wrl new file mode 100644 index 0000000..51f4fc5 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/cylinder-blue.wrl @@ -0,0 +1,22 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF cylinder Transform { + translation 0.0 0.0 -0.03 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 1.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.178 + } + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/cylinder-green.wrl b/data/models/kuka-lwr4/rlsg/cylinder-green.wrl new file mode 100644 index 0000000..72a98bc --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/cylinder-green.wrl @@ -0,0 +1,22 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF cylinder Transform { + translation 0.0 0.0 -0.03 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.178 + } + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/cylinder-red.wrl b/data/models/kuka-lwr4/rlsg/cylinder-red.wrl new file mode 100644 index 0000000..c067d82 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/cylinder-red.wrl @@ -0,0 +1,22 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF cylinder Transform { + translation 0.0 0.0 -0.03 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.178 + } + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.wrl new file mode 100644 index 0000000..1bdd44c --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.wrl @@ -0,0 +1,15 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF kuka-lwr4-right Transform { + translation -0.625 0 0 + children [ + Inline { + url "kuka-lwr4.convex/kuka-lwr4-right.wrl" + } ] + } + DEF wall Inline { + url "wall.wrl" + } ] +} + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.xml new file mode 100644 index 0000000..ad48e82 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.convex.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.wrl new file mode 100644 index 0000000..46728ab --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.wrl @@ -0,0 +1,15 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF kuka-lwr4-right Transform { + translation -0.625 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } ] + } + DEF wall Inline { + url "wall.wrl" + } ] +} + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.xml new file mode 100644 index 0000000..a082040 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4-right_wall.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link1.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link1.wrl new file mode 100644 index 0000000..dd6ea50 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link1.wrl @@ -0,0 +1,6547 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.00559822 0.049685601 -0.208, + -0.0574052 -0.017454101 -0.171, + -0.030219801 0.0125 0.05232, + 0.059725199 -0.0057364102 -0.171, + 0.057460099 -0.017272299 -0.171, + 0.045048401 -0.0216942 -0.208, + 0.0583959 -0.0137813 -0.191, + -0.039091598 -0.0311745 -0.208, + -0.0353553 -0.0353553 -0.208, + -0.059999999 0.00011747901 -0.164307, + -0.059999999 -4.7589998e-005 -0.171, + -0.052960701 0.0074999998 0.028698999, + 7.1926545e-012 0.050000001 -0.208, + -0.00559822 0.049685601 -0.208, + -0.0311745 0.039091598 -0.208, + -0.016514 0.047194201 -0.208, + -0.011126 0.0487464 -0.208, + -0.059706699 -0.0059254402 -0.171, + -0.0583959 -0.0137813 -0.191, + -0.0216942 0.045048401 -0.208, + -0.0266016 0.042336199 -0.208, + -0.00308463 -0.0094999997 0.060341001, + 0.051830001 -0.030079201 -0.165544, + 0.048467699 -0.035053998 -0.163118, + 0.016514 0.047194201 -0.208, + 0.011126 0.0487464 -0.208, + 0.0487464 0.011126 -0.208, + 0.047194201 0.016514 -0.208, + 0.045048401 0.0216942 -0.208, + 0.054340299 -0.025434 -0.171, + 0.0557741 -0.0220806 -0.171, + 0.056669399 -0.0197125 -0.191, + 0.0554916 -0.0228185 -0.171, + 0.056543902 -0.0200695 -0.171, + -0.0266016 -0.042336199 -0.208, + -0.0216942 -0.045048401 -0.208, + 0.049685601 -0.00559822 -0.208, + 0.042336199 -0.0266016 -0.208, + 0.049685601 0.00559822 -0.208, + 0.047194201 -0.016514 -0.208, + 0.0487464 -0.011126 -0.208, + 0.050000001 -3.4248511e-012 -0.208, + 0.059503399 -0.0077038999 -0.191, + 0.059980098 -0.00154487 -0.191, + 0.0353553 -0.0353553 -0.208, + 0.016514 -0.047194201 -0.208, + 0.011126 -0.0487464 -0.208, + -0.041876599 0.0074999998 0.043469001, + -0.051830001 0.032898299 0.027930001, + 0.0353553 0.0353553 -0.208, + 0.0216942 0.045048401 -0.208, + -0.056480099 -0.0202484 -0.171, + -0.056669399 -0.0197125 -0.191, + -0.042336199 0.0266016 -0.208, + -0.045048401 0.0216942 -0.208, + -0.039091598 0.0311745 -0.208, + -0.0353553 0.0353553 -0.208, + -0.059999999 0.0377554 -0.055597, + -0.059757002 0.042797599 -0.051054999, + -0.059999999 0.038623098 -0.052645002, + -0.0599402 0.040266801 -0.053335, + -0.0599402 0.041093901 -0.050308, + -0.047194201 0.016514 -0.208, + -0.049685601 -0.00559822 -0.208, + -0.059503399 -0.0077038999 -0.191, + -0.059980098 -0.00154487 -0.191, + -0.045048401 -0.0216942 -0.208, + -0.047194201 -0.016514 -0.208, + -0.0487464 -0.011126 -0.208, + -0.042336199 -0.0266016 -0.208, + -0.054602101 -0.024834299 -0.171, + -0.055419099 -0.022994 -0.171, + -0.0546159 -0.024723699 -0.165327, + 0.0418211 -0.0094999997 0.043412, + 0.00308463 -0.0094999997 0.060341001, + 0.0053973799 -0.058139499 -0.156012, + 0.0081428103 -0.0578265 -0.155968, + -0.047047202 0.0074999998 0.037737001, + -0.0465803 0.034741599 0.036235001, + -0.048467699 0.016535901 0.035654001, + -0.0465803 0.016593199 0.038127001, + -0.0429691 0.0074999998 0.042376999, + -0.040174201 0.0167506 0.044934001, + -0.042376 0.0125 0.042977002, + -0.0378174 0.016797701 0.046967998, + 0.059999801 0.00014234401 -0.171, + 0.058203701 0.0125 0.015071, + 0.053285599 -0.0275524 -0.171, + 0.0532961 -0.0274105 -0.165435, + 0.0529892 -0.028145101 -0.171, + 0.054305699 -0.0255125 -0.171, + 0.054342099 -0.0254349 -0.191, + 0.048467699 -0.0352217 -0.165755, + 0.019305199 -0.055619501 -0.157805, + 0.057608999 0.0167691 -0.191, + 0.059999999 0.036782298 -0.058527, + -0.011126 -0.0487464 -0.208, + -0.00559822 -0.049685601 -0.208, + -0.016514 -0.047194201 -0.208, + 1.5568702e-012 -0.050000001 -0.208, + 0.00559822 -0.049685601 -0.208, + -0.0311745 -0.039091598 -0.208, + 0.0266016 -0.042336199 -0.208, + 0.0216942 -0.045048401 -0.208, + 0.039091598 -0.0311745 -0.208, + 0.0311745 -0.039091598 -0.208, + -0.044564299 0.035313901 0.038812999, + -0.055579402 0.0074999998 0.023104001, + -0.054342099 -0.0094999997 0.025935, + 0.021165101 0.056143001 -0.191, + 0.0460728 0.038435601 -0.191, + 0.042336199 0.0266016 -0.208, + 0.039091598 0.0311745 -0.208, + -0.049685601 0.00559822 -0.208, + -0.0487464 0.011126 -0.208, + -0.059821099 0.0046305298 -0.191, + -0.050000001 -1.9469117e-014 -0.208, + -0.059027899 0.0107568 -0.191, + 0.0137813 0.0074999998 0.058896001, + -0.048467699 0.0145366 0.035817999, + -0.048467699 0.034146599 0.033553999, + -0.050219599 0.033531301 0.030781999, + -0.050219599 0.0164767 0.033096999, + -0.050219599 0.036764201 0.030301999, + -0.053669199 0.0074999998 0.027326001, + -0.0532961 0.014452 0.027992001, + -0.053653602 0.0125 0.027318001, + -0.054204401 0.0125 0.026226999, + -0.0546159 0.0144225 0.025269, + -0.0532832 0.0125 0.028051, + -0.051830001 0.0164157 0.030466, + 0.0165099 -0.056061201 -0.155717, + 0.0092211897 -0.0094999997 0.059707001, + 0.00616926 -0.0094999997 0.060182001, + 0.01526 -0.0094999997 0.058444999, + 0.0122731 -0.0094999997 0.059230998, + 0.0152803 0.0074999998 0.058522001, + 0.0053973799 -0.058573399 -0.15816499, + -0.044564299 0.0145888 0.040635999, + -0.044564299 0.016648199 0.040504999, + -0.0465803 0.0145632 0.038274001, + -0.044408198 0.0125 0.040847, + -0.044560701 0.0125 0.040670998, + -0.0424264 0.0146132 0.042893, + -0.046333499 0.0125 0.038621001, + -0.0328269 0.0125 0.050710998, + -0.0307914 0.0125 0.051996998, + -0.0322018 0.0074999998 0.051127002, + -0.033491299 0.0125 0.050276, + -0.0332799 0.0125 0.050423998, + -0.035366699 0.0146786 0.048946999, + -0.033494599 0.0074999998 0.050280999, + -0.038435601 0.0074999998 0.046572998, + -0.0402418 0.0125 0.045003999, + -0.040174201 0.0146363 0.045035001, + -0.00267513 0.0309045 0.060435999, + -0.00289505 0.0125 0.060430001, + -6.1690045e-012 0.021718301 0.060501002, + 4.138048e-012 -0.0094999997 0.0605, + -0.0030887299 0.0074999998 0.060419999, + 0.059999999 0.0381759 -0.018461, + 0.059999999 0.0368995 -0.016124001, + 0.0532961 0.046883099 0.019452, + 0.055787299 0.044315301 0.013206, + 0.0532961 0.019684801 0.027191, + 0.0465803 0.020327499 0.037725002, + 0.046011701 -0.0094999997 0.038885001, + 0.058949601 -0.0094999997 0.011243, + 0.058731299 0.0074999998 0.012773, + 0.044033099 -0.040756401 -0.191, + 0.048467699 -0.035325501 -0.168383, + 0.0484627 -0.035363302 -0.171, + 0.051434901 -0.0308851 -0.171, + 0.051545098 -0.030710001 -0.171, + 0.050219599 -0.0326868 -0.16565099, + 0.049977001 -0.033201002 -0.171, + 0.051438902 -0.0308876 -0.191, + 0.0220857 -0.0545961 -0.15768, + 0.055579402 0.0226037 -0.191, + 0.059999999 0.041396499 -0.029168, + 0.059999999 0.0386055 -0.052646998, + 0.059999999 0.037741099 -0.055597, + 0.0599402 0.040252399 -0.053335, + 0.0182469 -0.057158101 -0.191, + 0.0165099 -0.056495 -0.157912, + -0.0424264 0.035860699 0.041276999, + -0.0424264 0.016700801 0.042777002, + -0.0378174 0.036869299 0.045821, + -0.040174201 0.036379799 0.043614998, + -0.0328326 0.016882399 0.050639998, + -0.035366699 0.0168416 0.048872001, + -0.035366699 0.0412581 0.047657002, + -0.035366699 0.039368901 0.047789998, + -0.059999999 0.00120578 -0.150841, + -0.059999999 0.0393949 -0.049674001, + -0.059999999 0.0165808 -0.098866999, + -0.0532961 0.0163533 0.027774001, + -0.055771999 0.0125 0.02258, + -0.055400901 0.0125 0.023538001, + -0.056143001 0.0074999998 0.021664999, + -0.056809202 0.0143624 0.019722, + -0.056464098 0.0125 0.020793, + -0.055787299 0.0143926 0.022507999, + -0.056793701 0.0125 0.0198, + -0.055787299 0.033674501 0.018373, + -0.019305199 -0.055630598 -0.157803, + -0.046011701 -0.0094999997 0.038885001, + -0.0460728 0.0074999998 0.038936, + -0.0165099 -0.056069199 -0.15571401, + -0.0371872 -0.0094999997 0.047485001, + -0.039609101 -0.0094999997 0.045568001, + -0.044033099 -0.0094999997 0.041255999, + -0.0053973799 -0.0592383 -0.16247199, + -0.056809202 0.035402901 0.014383, + -0.0576833 0.034474801 0.011243, + 0.037236601 0.047047202 -0.191, + 0.0266016 0.042336199 -0.208, + 0.0311745 0.039091598 -0.208, + 0.026825599 0.053669199 -0.191, + 0.052960701 0.0281986 -0.191, + 0.0030887299 0.0074999998 0.060419999, + 0.0137106 0.021618299 0.058871001, + 0.0137106 0.0170689 0.058894001, + -0.048459399 0.0125 0.035861, + -0.048147298 0.0125 0.036302999, + -0.0479904 -0.0094999997 0.036513001, + -0.050219599 0.0145092 0.033279002, + -0.051817998 0.0125 0.030719001, + -0.051830001 0.0144809 0.030665999, + -0.0528774 0.0125 0.028853999, + -0.058998398 0.047143999 -0.049648002, + -0.059445001 0.045362301 -0.048744999, + -0.00268824 -0.059649602 -0.16463099, + 0.00268824 -0.059122201 -0.160338, + -0.00268824 -0.0594205 -0.162487, + -6.2532523e-012 -0.059479401 -0.16249201, + 4.83825e-012 -0.058818001 -0.158195, + -7.8986834e-012 -0.058384001 -0.156046, + -5.5010488e-012 -0.059182901 -0.160344, + 0.00268824 -0.058757398 -0.158188, + 0.00268824 -0.058323398 -0.156038, + -0.00268824 -0.058324799 -0.156038, + -0.034765299 -0.0094999997 0.049401999, + -0.0053973799 -0.058576498 -0.15816499, + -0.00268824 -0.058759 -0.158187, + -0.00268824 -0.0591239 -0.160338, + -0.0053973799 -0.058941599 -0.160319, + -0.0081428103 -0.057830401 -0.155966, + 0.0088465102 0.0125 0.059843998, + 0.0081421202 0.021683199 0.059930999, + 0.00923343 0.0074999998 0.059785001, + 0.0081421202 0.039992899 0.059893001, + 0.0109179 0.017083 0.059486002, + -0.037814599 0.0125 0.047077, + -0.0356883 0.0125 0.048732001, + -0.0378174 0.0146582 0.047056001, + -0.038010798 0.0125 0.046923999, + -0.037236601 0.0074999998 0.047547001, + -0.0302257 0.0212081 0.052113999, + -0.0302257 0.040262401 0.051495001, + -0.0328326 0.039834399 0.049720999, + -0.01526 -0.0094999997 0.058444999, + -0.0081421202 0.039992899 0.059893001, + -0.0053918599 0.040068701 0.060235001, + -0.0053918599 0.0308768 0.060242001, + -0.0046305298 0.0074999998 0.060320999, + -0.0081406701 0.0125 0.059932999, + -0.0081421202 0.0308295 0.059911001, + -0.0058307201 0.0125 0.060215998, + 0.0599402 0.0410101 -0.017967001, + 0.059999999 0.033951499 -0.012003, + 0.0599402 0.036864899 -0.010902, + 0.059445001 0.0414504 -0.0068849898, + 0.050219599 0.049358401 0.025473, + 0.050219599 0.0478095 0.026357999, + 0.051830001 0.046645898 0.023383999, + 0.051830001 0.048135102 0.022498, + 0.0546159 0.042859402 0.018056, + 0.0546159 0.045607999 0.016349999, + 0.0532961 0.045455098 0.020339999, + 0.0532961 0.044009902 0.021151001, + 0.056809202 0.043010499 0.010032, + 0.055787299 0.046847001 0.011209, + 0.0424264 0.062186401 0.030701, + 0.0546159 0.040061701 0.019462001, + 0.055787299 0.041693199 0.014917, + 0.055787299 0.039021801 0.016341001, + 0.051830001 0.0164031 0.030432999, + 0.051830001 0.032898098 0.027930999, + 0.051830001 0.019851901 0.029929999, + 0.0532961 0.016340399 0.02774, + 0.051830001 0.034513101 0.027682999, + 0.0532961 0.042553 0.021884, + 0.051830001 0.045139499 0.024191, + 0.057608999 0.0074999998 0.017269, + 0.044564299 0.020475101 0.040144999, + 0.040756401 0.0074999998 0.044532999, + 0.0460728 0.0074999998 0.038936, + 0.055579402 0.0074999998 0.023104001, + 0.0546159 0.0195146 0.024401, + 0.0532961 0.0322503 0.025012, + 0.058412101 0.023887301 0.011411, + 0.058412101 0.0188176 0.012974, + 0.0464839 -0.037937399 -0.171, + 0.044567399 -0.0401715 -0.171, + 0.047982302 -0.0360066 -0.171, + 0.0465803 -0.037776601 -0.16843399, + 0.046578299 -0.037815802 -0.171, + 0.048288502 -0.035611998 -0.171, + 0.0479904 -0.036012899 -0.191, + 0.042423699 -0.042423598 -0.171, + 0.042543601 -0.0423088 -0.171, + 0.0404175 -0.044344399 -0.171, + 0.040169802 -0.0445593 -0.171, + 0.039609101 -0.045067899 -0.191, + 0.0248404 -0.053787999 -0.159794, + 0.0220857 -0.0552576 -0.162147, + 0.0220857 -0.054960899 -0.159914, + 0.0248404 -0.053423099 -0.157536, + 0.027557701 -0.052466702 -0.159659, + 0.027557701 -0.052101601 -0.15737399, + 0.059027899 0.0107568 -0.191, + 0.059821099 0.0046305298 -0.191, + 0.059999999 0.039375201 -0.049681999, + 0.018242801 -0.057145901 -0.171, + 0.020382199 -0.056432001 -0.171, + 0.019305199 -0.056280799 -0.16223, + 0.019305199 -0.055984199 -0.160018, + 0.0118856 -0.058811001 -0.171, + 7.2808114e-012 -0.059999999 -0.191, + -0.053283598 -0.0275514 -0.171, + -0.0532961 -0.027440799 -0.16543899, + -0.0542247 -0.025684301 -0.171, + -0.054342099 -0.0254349 -0.191, + -0.0479904 -0.036012899 -0.191, + -0.051818501 -0.0302191 -0.171, + -0.0528998 -0.0283127 -0.171, + -0.051830001 -0.0301087 -0.165548, + -0.0514476 -0.030873001 -0.171, + -0.051438902 -0.0308876 -0.191, + -0.044561401 -0.040171701 -0.171, + -0.0463636 -0.038084399 -0.171, + -0.044033099 -0.040756401 -0.191, + -0.048467699 0.0374927 0.033115, + -0.0465803 0.038197201 0.035835002, + -0.0424264 0.041284502 0.040695, + -0.0424264 0.039521899 0.040950999, + -0.044564299 0.0388746 0.038451001, + -0.0465803 0.0398583 0.035546999, + -0.044564299 0.0405876 0.038178999, + -0.044564299 0.044087 0.037384, + -0.044564299 0.0423318 0.037822999, + -0.059757002 0.044268101 -0.044835001, + -0.059445001 0.046107199 -0.045566, + -0.059757002 0.0435839 -0.047952998, + -0.0599402 0.041822098 -0.047263999, + -0.0599402 0.042450201 -0.044206999, + -0.059999999 0.0415163 -0.037817001, + -0.059999999 0.040647101 -0.043697, + -0.059999999 0.041131798 -0.040713999, + -0.059999999 0.040069599 -0.046689, + -0.059999999 0.0417105 -0.034931999, + -0.0599204 0.0074999998 0.0035890001, + -0.059999999 0.00052004401 -0.157581, + -0.058412101 0.0335453 0.008099, + -0.058021698 0.0074999998 0.01578, + -0.059285302 0.0074999998 0.0097329998, + -0.059337199 0.0125 0.0093930103, + -0.059027899 0.0074999998 0.011257, + -0.058829699 0.0125 0.012293, + -0.0576833 0.032071199 0.012183, + -0.0576833 0.029568 0.012927, + -0.027557701 -0.0521175 -0.157372, + -0.056669399 -0.0094999997 0.020213, + -0.0583959 -0.0094999997 0.014281, + -0.058949601 -0.0094999997 0.011243, + -0.0576679 0.0125 0.017006001, + -0.057391401 0.0125 0.017999001, + -0.057608999 0.0074999998 0.017269, + -0.0581805 0.0125 0.015164, + -0.0546159 0.0315907 0.022039, + -0.0546159 0.019519299 0.024405001, + -0.055787299 0.0193469 0.021577001, + -0.055787299 0.016225301 0.022252001, + -0.055787299 0.0309218 0.019026, + -0.0576833 0.0160947 0.016625, + -0.056809202 0.019172801 0.018723, + -0.056809202 0.016160199 0.019446, + -0.0576833 0.0143321 0.016921001, + -0.056809202 0.030246699 0.015984001, + -0.0576833 0.0189978 0.015853001, + -0.056809202 0.032875001 0.015286, + -0.058412101 0.0143017 0.014115, + -0.0165099 -0.056504499 -0.15791, + -0.0109179 -0.057818901 -0.15807199, + -0.0137106 -0.057232998 -0.15800001, + -0.0137106 -0.056798 -0.155819, + -0.0109179 -0.0573841 -0.155902, + -0.0081428103 -0.058265001 -0.158126, + -0.0081428103 -0.058630198 -0.16028699, + -0.0081428103 -0.058927 -0.16244701, + -0.0109179 -0.0581843 -0.16024201, + -0.018242201 -0.0571438 -0.171, + 0.040174201 0.077137597 -0.034772001, + 0.0302257 0.083423898 -0.033824001, + 0.0465803 0.070508301 -0.039671998, + 0.041876599 0.0429691 -0.191, + 0.048467699 0.068971097 -0.037579998, + 0.0424264 0.063701898 0.029306, + 0.0424264 0.0606126 0.032016002, + 0.0424264 0.058986802 0.033248998, + 0.040174201 0.069259599 0.027059, + 0.0424264 0.067844503 0.024692999, + 0.040174201 0.071718201 0.023645001, + 0.040174201 0.070530698 0.025379, + 0.040174201 0.072819598 0.021862, + 0.0081421202 0.0487285 0.059462, + 0.040174201 0.0167409 0.044909, + 0.0371872 -0.0094999997 0.047485001, + 0.039609101 -0.0094999997 0.045568001, + 0.026790099 -0.0094999997 0.054097999, + 0.00267513 0.0401132 0.060435001, + 0.0029901101 0.0125 0.060424998, + 0.00267513 0.021714401 0.06044, + 0.0053918599 0.040068701 0.060235001, + 0.0059254402 0.0125 0.060206998, + 0.0053918599 0.021702901 0.060252, + 0.0053918599 0.042367399 0.060231999, + 0.0077038999 0.0074999998 0.060003001, + 0.0109179 0.0398845 0.059404999, + 0.0109179 0.021655099 0.059473, + 0.0117463 0.0125 0.059339002, + 0.0081421202 0.042284299 0.059888002, + 0.0328326 0.043685101 0.049392998, + 0.0328326 0.0456644 0.049095001, + -0.050626501 0.0074999998 0.032701999, + -0.051423199 0.0125 0.031413998, + -0.051438902 -0.0094999997 0.031388, + -0.0502089 0.0125 0.033326, + -0.0498452 0.0125 0.033898, + -0.0497806 0.0074999998 0.033994999, + -6.4673249e-012 -0.059999999 -0.171, + -0.00923343 0.0074999998 0.059785001, + -0.0107568 0.0074999998 0.059528001, + -0.00875236 0.0125 0.059858002, + -0.00616926 -0.0094999997 0.060182001, + -0.0092211897 -0.0094999997 0.059707001, + -0.0053973799 -0.0581421 -0.156011, + -0.0248347 0.0125 0.055103, + -0.026825599 0.0074999998 0.054168999, + -0.0255982 0.0125 0.054765001, + -0.0275518 0.0125 0.053785, + -0.028228801 0.0125 0.053445, + -0.0281986 0.0074999998 0.053461, + -0.026790099 -0.0094999997 0.054097999, + -0.029552899 -0.0094999997 0.052717, + 1.9170884e-012 0.059936602 0.057360999, + -0.027557701 0.042645201 0.053017002, + -0.0328326 0.041761398 0.049601998, + -0.0302257 0.042224102 0.051389001, + -0.0248404 0.045055401 0.054310001, + -0.0165099 0.030562401 0.058042999, + -0.0211371 -0.0094999997 0.056568999, + -0.0226037 0.0074999998 0.056079, + -0.0240272 -0.0094999997 0.055479001, + -0.0167691 0.0074999998 0.058109, + -0.0152803 0.0074999998 0.058522001, + -0.0122731 -0.0094999997 0.059230998, + -0.0109179 0.0398845 0.059404999, + -0.0116529 0.0125 0.059358001, + -0.0109179 0.030761801 0.059438001, + -0.0081421202 0.042285401 0.059888002, + 3.9887312e-012 0.057745099 0.058120001, + 0.058998398 0.047133502 -0.049647, + 0.059999999 0.0392836 -0.020961, + 0.059999999 0.040908299 -0.026342999, + 0.059999999 0.040200599 -0.023597, + 0.059757002 0.041423 -0.012385, + 0.059757002 0.039916001 -0.0099999998, + 0.059757002 0.042750102 -0.014949, + 0.0599402 0.0397931 -0.015435, + 0.0599402 0.038401902 -0.013074, + 0.059757002 0.036484201 -0.005843, + 0.059757002 0.038259 -0.0078140004, + 0.0599402 0.035213001 -0.0089349998, + 0.059445001 0.037772499 -0.0027089999, + 0.059445001 0.039671801 -0.0046840101, + 0.0576833 0.041698799 0.0068410002, + 0.058412101 0.0381473 0.0053760102, + 0.058412101 0.040385202 0.0036460001, + 0.058998398 0.0390747 0.00045799301, + 0.059445001 0.03579 -0.00096600299, + 0.058998398 0.036964901 0.00219501, + 0.059999999 0.00015159399 -0.164303, + 0.059999999 0.00056166499 -0.157579, + 0.059757002 0.0307806 -0.001259, + 0.059445001 0.033758201 0.00054200698, + 0.059999999 0.0273 -0.00614799, + 0.059999999 0.032342501 -0.010242, + 0.059999999 0.035481598 -0.013966, + 0.0599402 0.0133294 0.0031699999, + 0.059927799 0.0125 0.0034419999, + 0.059821099 0.0074999998 0.0051310002, + 0.059757002 0.0133443 0.0058809998, + 0.0597114 0.0125 0.0063780099, + 0.059682 0.0074999998 0.00666901, + 0.0546159 0.049543701 0.01324, + 0.051830001 0.053792901 0.018170999, + 0.0424264 0.065153196 0.027836001, + 0.0424264 0.0665356 0.026296999, + 0.0424264 0.069075398 0.023029, + 0.0424264 0.070224203 0.021313, + 0.0546159 0.037236702 0.020583, + 0.0576833 0.039332502 0.0085650003, + 0.056809202 0.040516 0.01175, + 0.056809202 0.0379721 0.01319, + 0.054979 0.0074999998 0.024527, + 0.055437401 0.0125 0.02345, + 0.048467699 0.0358801 0.033349998, + 0.050219599 0.035206299 0.030556999, + 0.050219599 0.020015201 0.032607, + 0.050219599 0.0164645 0.033064999, + 0.048467699 0.020174 0.035209, + 0.0465803 0.036531799 0.036051001, + 0.0532961 0.038139001 0.023635, + 0.051830001 0.039024901 0.026633, + 0.0532961 0.035227001 0.024442, + 0.040174201 0.0207502 0.044652, + 0.044564299 0.0371585 0.038648002, + 0.0424264 0.0206162 0.042456999, + 0.0424264 0.0166905 0.042750001, + 0.044564299 0.0166374 0.040476002, + 0.044472098 0.0125 0.040777002, + 0.044564299 0.0145868 0.040624, + 0.045067899 0.0074999998 0.040109001, + 0.044033099 -0.0094999997 0.041255999, + 0.040748298 0.0125 0.044525001, + 0.041876599 0.0074999998 0.043469001, + 0.042443302 0.0125 0.042909998, + 0.040312301 0.0125 0.044939999, + 0.0424264 0.0146113 0.042881999, + 0.051472198 0.0125 0.031332001, + 0.0522171 0.0074999998 0.030053001, + 0.048467699 0.016524101 0.035622999, + 0.0465803 0.0165819 0.038097002, + 0.0465759 0.0125 0.038314, + 0.046393901 0.0125 0.038547002, + 0.0465803 0.0145612 0.038261998, + 0.0479904 -0.0094999997 0.036513001, + 0.058412101 0.0160149 0.013763, + 0.044564299 -0.040030699 -0.165953, + 0.044564299 -0.0401337 -0.16848201, + 0.0424264 -0.042386401 -0.168529, + 0.044564299 -0.039863698 -0.163414, + 0.0465803 -0.037673201 -0.165856, + 0.0465803 -0.037505802 -0.163269, + 0.0424264 -0.0421171 -0.163552, + 0.0424264 -0.042283799 -0.166045, + 0.040174201 -0.044024602 -0.161228, + 0.0424264 -0.041885201 -0.161053, + 0.059503399 -0.0094999997 0.0082039898, + 0.0378174 -0.0460421 -0.161393, + 0.0258127 -0.054163702 -0.171, + 0.0248404 -0.054084901 -0.16205101, + 0.027557701 -0.0527637 -0.161943, + 0.0240207 -0.054964401 -0.171, + 0.0248338 -0.054601099 -0.171, + 0.0231252 -0.055364501 -0.171, + 0.0240272 -0.054979 -0.191, + 0.029552899 -0.0522171 -0.191, + 0.0302257 -0.051792402 -0.168723, + 0.030994801 -0.051374301 -0.171, + 0.0302184 -0.051817201 -0.171, + 0.028437899 -0.0528326 -0.171, + 0.027557701 -0.053259 -0.168753, + 0.0328326 -0.049915101 -0.164032, + 0.0302257 -0.051526699 -0.164131, + 0.0302257 -0.0516917 -0.16643199, + 0.0328326 -0.0500804 -0.166366, + 0.035366699 -0.048161998 -0.16392399, + 0.035366699 -0.047931001 -0.16154701, + 0.0328326 -0.0493869 -0.159345, + 0.0302257 -0.051296201 -0.16182201, + 0.0302257 -0.050999001 -0.15951, + 0.0328326 -0.049684402 -0.161691, + 0.0583959 -0.0094999997 0.014281, + 0.035366699 -0.047633301 -0.15916599, + 0.059999999 0.041506398 -0.037815999, + 0.059999999 0.0411194 -0.040732998, + 0.059999999 0.041694898 -0.034935001, + 0.059999999 0.041658498 -0.03204, + 0.059999999 0.040049698 -0.046707001, + 0.059999999 0.040629499 -0.043724999, + 0.0165099 -0.057156201 -0.162302, + 0.0165099 -0.056859601 -0.160108, + 0.0137106 -0.057589799 -0.160182, + 0.0137106 -0.057886299 -0.16236199, + 0.0137069 -0.058396202 -0.171, + 0.0122713 -0.0587232 -0.171, + 0.0165099 -0.057385799 -0.164491, + 0.019305199 -0.056510501 -0.164437, + -0.0087992204 -0.059351299 -0.171, + -0.0061684698 -0.0596756 -0.171, + -0.00616926 -0.059682 -0.191, + -0.0058778701 -0.0597114 -0.171, + -0.0053966301 -0.059746899 -0.171, + -0.00294237 -0.059927799 -0.171, + -0.0229499 -0.055437401 -0.171, + -0.0202034 -0.056496199 -0.171, + -0.048175599 -0.035764702 -0.171, + -0.048459999 -0.035361301 -0.171, + -0.049871601 -0.033358999 -0.171, + -0.040174201 -0.0440524 -0.161229, + -0.0378174 0.040715698 0.045561999, + -0.040174201 0.040136401 0.043324001, + -0.040174201 0.041946001 0.043083001, + -0.0424264 0.046695601 0.039409999, + -0.0424264 0.044886 0.039925002, + -0.040174201 0.047502801 0.041832, + -0.0424264 0.0430796 0.040353, + -0.0378174 0.042569801 0.045334999, + -0.0328326 0.043695599 0.049400002, + -0.035366699 0.043153699 0.047442999, + -0.00267513 0.088293999 0.030407, + -0.00267513 0.087336101 0.032476999, + -0.0328326 0.055571899 0.046213001, + -0.0599402 0.0434107 -0.038093999, + -0.0599402 0.042978201 -0.041145001, + -0.059757002 0.044849198 -0.041706, + -0.059821099 0.0074999998 0.0051310002, + -0.059702002 0.0125 0.0064730099, + -0.059445001 0.0142413 0.0085349996, + -0.059923101 0.0125 0.0035369999, + -0.059999902 0.0125 0.00059500098, + -0.059999999 0.0157077 -3.7994392e-005, + -0.058412101 0.035853699 0.006877, + -0.058998398 0.0142714 0.011316, + -0.058412101 0.016029101 0.0138, + -0.058412101 0.018822599 0.012979, + -0.058412101 0.0288883 0.0098639997, + -0.059999999 0.0409371 -0.026324, + -0.0599402 0.043740101 -0.035135001, + -0.059445001 0.046746898 -0.042373002, + -0.0465803 0.070511602 -0.039675001, + -0.041876599 0.0429691 -0.191, + -0.0576833 0.036910601 0.010049, + -0.035366699 -0.047656398 -0.15916499, + -0.027557701 -0.052484602 -0.159659, + -0.0248404 -0.0541021 -0.16205101, + -0.0532961 0.032250501 0.025012, + -0.0546159 0.0162897 0.025032001, + -0.051830001 0.036014799 0.027408, + -0.0532961 0.0196894 0.027194999, + -0.0532961 0.036683202 0.024086, + -0.0546159 0.034466501 0.021431001, + -0.0532961 0.035247799 0.024447, + -0.051830001 0.037508901 0.027066, + -0.051830001 0.039028801 0.026649, + -0.0109179 -0.058481202 -0.16241001, + -0.0137106 -0.057598699 -0.160182, + -0.0165099 -0.056870401 -0.160107, + -0.019305199 -0.056780402 -0.168826, + -0.0220857 -0.0555024 -0.16437601, + 0.027557701 0.084877104 -0.032800999, + 0.0424264 0.072266102 0.017746, + 0.0424264 0.071288399 0.019548999, + 0.0328326 0.082613803 0.014288, + 0.0465803 0.072637796 -0.02777, + 0.050219599 0.068667501 -0.0050509898, + 0.050219599 0.068953998 -0.0087299999, + 0.056809202 0.054278102 -0.046282999, + 0.0546159 0.061437398 -0.031052001, + 0.0532961 0.0613777 -0.043481, + 0.0497806 0.033494599 -0.191, + 0.051830001 0.064770803 -0.037714999, + 0.0532961 0.062909998 -0.036114, + 0.0532961 0.0622073 -0.039808001, + 0.051830001 0.063971996 -0.041464999, + 0.050219599 0.0665069 -0.039494999, + 0.048467699 0.069710597 -0.033681002, + 0.050219599 0.067275703 -0.035668999, + 0.0532961 0.063485898 -0.032405999, + 0.051830001 0.065439597 -0.033944, + 0.0532961 0.063935101 -0.028689999, + 0.0378174 0.053946 0.042043999, + 0.040174201 0.045647401 0.042321999, + 0.0378174 0.048268098 0.044098999, + 0.040174201 0.0475072 0.041813999, + 0.040174201 0.049362499 0.041216001, + 0.040174201 0.051210102 0.040527001, + 0.048467699 0.042385198 0.031939, + 0.050219599 0.041486301 0.029079, + 0.0378174 0.073127098 0.025844, + 0.035366699 0.073187999 0.02967, + 0.0378174 0.071903102 0.027595, + 0.0328326 0.074380703 0.031594999, + 0.0053918599 0.051035199 0.059475999, + 0.0081421202 0.050924599 0.059122998, + 0.0081421202 0.046545099 0.059702002, + 0.0053918599 0.048832301 0.059813, + 0.0081421202 0.044406701 0.059841, + 0.035366699 0.016833 0.04885, + 0.0328326 0.041748699 0.049598999, + 0.0328326 0.0377529 0.049802002, + 0.0328326 0.039829899 0.04972, + 0.0197125 0.0074999998 0.057169002, + 0.0211371 -0.0094999997 0.056568999, + 0.0182469 -0.0094999997 0.057658002, + 0.0202484 0.0125 0.056979999, + 0.021165101 0.0074999998 0.056643002, + 0.017454101 0.0125 0.057905, + 0.019305199 0.014768 0.057300001, + 0.035366699 0.0528627 0.044973999, + 0.035366699 0.0547885 0.044197001, + 0.035366699 0.0509253 0.045653999, + 0.0378174 0.052063599 0.042824, + 0.0378174 0.050169699 0.043508001, + 0.035366699 0.047031801 0.046728, + 0.0378174 0.0463624 0.044597, + 0.035366699 0.048980501 0.046238001, + 0.035366699 0.045082599 0.047127001, + 0.0328326 0.047653101 0.048705999, + 0.00268824 -0.0599076 -0.16889, + 0.0026879699 -0.059931099 -0.171, + 0.000344617 -0.059999 -0.171, + -5.292998e-013 -0.059967902 -0.168891, + -3.3722311e-012 -0.059870999 -0.166768, + 1.4751904e-012 -0.059708498 -0.164634, + -0.0109179 0.065847099 0.053300001, + -0.027557701 0.040651999 0.053111002, + -0.027557701 0.021299699 0.053619999, + -0.0248404 0.043024302 0.054481, + -0.0229061 0.0125 0.055955, + -0.0137106 0.039742202 0.058763999, + -0.0145255 0.0125 0.058715001, + -0.0137106 0.0306729 0.058816001, + -0.0109179 0.042166799 0.059395999, + 3.2279095e-012 0.042432401 0.0605, + 0.00267513 0.042416301 0.060433999, + 0.00154487 0.0074999998 0.060479999, + 1.2865608e-012 0.040127698 0.060501002, + -0.00267513 0.0401132 0.060435001, + 2.5651814e-012 0.044567902 0.060456999, + -0.00267513 0.042416699 0.060433999, + -0.0053918599 0.042368099 0.060231999, + -0.0081421202 0.044409901 0.059841, + 0.058998398 0.0447441 -0.0061699999, + 0.059445001 0.044513501 -0.011891, + 0.059445001 0.0430746 -0.0092940098, + 0.058998398 0.046295799 -0.0088, + 0.056809202 0.045416102 0.0080390004, + 0.0576833 0.0439776 0.0048529999, + 0.0599402 0.042833 -0.023436001, + 0.0599402 0.042029899 -0.020643, + 0.0599402 0.031699002 -0.0056380001, + 0.0599402 0.0334807 -0.0071799899, + 0.059999999 0.0306841 -0.0086840102, + 0.059999999 0.0289884 -0.0073220101, + 0.0599402 0.029881001 -0.0043020002, + 0.059757002 0.032721698 -0.002569, + 0.059757002 0.034627698 -0.0040939902, + 0.0576833 0.0369169 0.010023, + 0.059999999 0.0125 0.00050000002, + 0.059980098 -0.0094999997 0.002045, + 0.059999999 0.0218067 -0.0031290001, + 0.0599402 0.028073199 -0.0031640001, + 0.059999999 0.025559001 -0.0051330002, + 0.059999999 0.0141502 0.000358002, + 0.059999999 0.0179592 -0.00110201, + 0.059999999 0.0156931 -7.6003991e-005, + 0.059999999 0.0133147 0.00048100299, + 0.0599402 0.0141794 0.003052, + 0.059999999 0.0074999998 0.00050000002, + 0.0599402 0.015756199 0.0026380001, + 0.059999999 0.0049663298 -0.130769, + 0.0599402 0.022214601 -0.00027799999, + 0.0599402 0.026211699 -0.0021929899, + 0.059999999 0.0169411 -0.00060299702, + 0.0599402 0.018127499 0.0016580001, + 0.059757002 0.028852399 -0.00015699799, + 0.059757002 0.0226257 0.002595, + 0.0599402 0.017051401 0.002134, + 0.059757002 0.0268695 0.00077099598, + 0.058998398 0.0133745 0.011404, + 0.059445001 0.0133593 0.0086280098, + 0.059351299 0.0125 0.0092989998, + 0.058998398 0.0142688 0.0113, + 0.059027899 0.0074999998 0.011257, + 0.058848299 0.0125 0.012199, + 0.058412101 0.0133899 0.014198, + 0.058412101 0.0142991 0.014099, + 0.0546159 0.054209001 0.008134, + 0.0532961 0.049663 0.017447, + 0.0546159 0.0482646 0.014349, + 0.0532961 0.048287801 0.018487001, + 0.0532961 0.0510028 0.016331, + 0.051830001 0.052435402 0.019367, + 0.056809202 0.032852899 0.015281, + 0.056809202 0.035398699 0.014365, + 0.055787299 0.036321901 0.017488001, + 0.0576833 0.0295678 0.012927, + 0.0576833 0.018992901 0.015849, + 0.0532961 0.0134663 0.028051, + 0.0546159 0.0134512 0.025333, + 0.054245099 0.0125 0.026141001, + 0.0532961 0.0144496 0.027977999, + 0.052922402 0.0125 0.028771, + 0.052960701 0.0074999998 0.028698999, + 0.051830001 0.0134811 0.030720999, + 0.054342099 -0.0094999997 0.025935, + 0.051830001 0.0144786 0.030652, + 0.051830001 0.042094599 0.025565, + 0.051830001 0.040561698 0.026136, + 0.051830001 0.043621302 0.024917001, + 0.0532961 0.0410874 0.022542, + 0.0532961 0.0396153 0.023125, + 0.050219599 0.038299602 0.029967999, + 0.051830001 0.037492301 0.027055999, + 0.050219599 0.039890599 0.029561, + 0.050219599 0.036744699 0.030298, + 0.051830001 0.035994601 0.027403999, + 0.048467699 0.040732101 0.032407999, + 0.0378174 0.038862102 0.045708999, + 0.035366699 0.041244298 0.047653999, + 0.035366699 0.043142401 0.047435999, + 0.040174201 0.038325898 0.043487001, + 0.0424264 0.0377574 0.041131001, + 0.0378174 0.040700998 0.045559, + 0.050209999 0.0125 0.033326998, + 0.050219599 0.014507 0.033264998, + 0.0497806 0.0074999998 0.033994999, + 0.051438902 -0.0094999997 0.031388, + 0.056809202 0.019168001 0.018718001, + 0.0576833 0.0160807 0.016588001, + 0.056809202 0.0302465 0.015985001, + 0.055787299 0.033652801 0.018368, + 0.055787299 0.0193421 0.021573, + 0.055787299 0.030921601 0.019026, + 0.0546159 0.034445301 0.021426, + 0.0546159 0.031590499 0.02204, + 0.056809202 0.016146399 0.019409999, + 0.0576833 0.0143296 0.016905, + 0.0378174 -0.046273399 -0.163808, + 0.040174201 -0.044256199 -0.163684, + 0.0220857 -0.055487499 -0.16437399, + 0.034765299 -0.048901699 -0.191, + 0.0248404 -0.054479301 -0.166547, + 0.027557701 -0.0531587 -0.166492, + 0.0248404 -0.054579299 -0.16878, + 0.0220857 -0.055651698 -0.166595, + 0.0248404 -0.0543149 -0.16430201, + 0.027557701 -0.052994002 -0.164221, + 0.0220857 -0.055751201 -0.168804, + 0.059757002 0.042783201 -0.051054999, + 0.0599402 0.041802399 -0.047272, + 0.0599402 0.041076299 -0.050310001, + 0.0599402 0.0424302 -0.044225, + 0.0109179 -0.057812601 -0.15807199, + 0.0137106 -0.057225201 -0.15800101, + 0.0137106 -0.056791399 -0.155821, + 0.0109179 -0.057378799 -0.155904, + 0.0081428103 -0.058260299 -0.15812699, + 0.0109179 -0.058177199 -0.16024201, + 0.0053963801 -0.059744101 -0.171, + 0.0031320599 -0.059918199 -0.171, + 0.0165099 -0.057648201 -0.168843, + 0.0137106 -0.058377601 -0.16885801, + 0.0147556 -0.058157299 -0.171, + 0.0165099 -0.057549398 -0.166673, + 0.0175901 -0.0573637 -0.171, + 0.019305199 -0.056773599 -0.168825, + 0.019305199 -0.056674398 -0.166637, + -0.0081428103 -0.059414301 -0.16888, + -0.024834501 -0.0546025 -0.171, + -0.0240272 -0.054979 -0.191, + -0.029552899 -0.0522171 -0.191, + -0.048467699 -0.0352493 -0.165759, + -0.048467699 -0.0353426 -0.168386, + -0.050219599 -0.032715399 -0.165655, + -0.059980098 -0.0094999997 0.002045, + -0.048467699 -0.035086699 -0.163121, + -0.0465803 -0.037792999 -0.168437, + -0.059503399 -0.0094999997 0.0082039898, + -0.0424264 -0.041914601 -0.161054, + -0.044564299 -0.039893702 -0.163417, + -0.0465803 -0.037699699 -0.165859, + -0.0465803 -0.037537199 -0.16327199, + -0.0424264 -0.042401399 -0.168531, + -0.042409498 -0.042443302 -0.171, + -0.044024602 -0.040748298 -0.171, + -0.044564299 -0.040056001 -0.16595601, + -0.044564299 -0.040149398 -0.168485, + -0.044440001 -0.040312301 -0.171, + -0.0424264 -0.042307898 -0.166049, + -0.0424264 -0.042145699 -0.163555, + -0.0424264 0.048503399 0.038805999, + -0.035366699 0.0509228 0.045671001, + -0.0378174 0.046359599 0.044613, + -0.040174201 0.045644399 0.042337999, + -0.0378174 0.048264001 0.044116002, + -0.0378174 0.044458698 0.045019001, + -0.040174201 0.043789301 0.042753998, + -0.035366699 0.048976701 0.046254002, + -0.035366699 0.047029201 0.046742, + -0.035366699 0.0450853 0.047138002, + -1.092005e-012 0.086318098 0.034584001, + -0.0081421202 0.091132499 0.019416001, + -0.0081421202 0.090973496 -0.028511999, + 0.00923343 0.059285302 -0.191, + 0.0109179 0.090529501 -0.028824, + 0.0081421202 0.090972401 -0.028511999, + 0.0137106 0.090744801 -0.024713, + 0.0030887299 0.0599204 -0.191, + -0.0030887299 0.0599204 -0.191, + -0.0109179 0.063761003 0.05438, + -0.019305199 0.066714697 0.049628001, + -0.0137106 0.063472703 0.053711001, + -0.027557701 0.062913999 0.046805002, + -0.0302257 0.058276299 0.047177002, + -0.059999999 0.032341901 -0.010212, + -0.059999999 0.039306398 -0.020934001, + -0.059999999 0.038194198 -0.018432001, + -0.059999999 0.040227201 -0.023574, + -0.0599402 0.042056501 -0.020618999, + -0.059999999 0.0141529 0.00037399301, + -0.059757002 0.038268201 -0.0077829999, + -0.059757002 0.0364893 -0.005812, + -0.0599402 0.035218101 -0.0089040101, + -0.0599402 0.026211901 -0.0021929899, + -0.0599402 0.022218101 -0.00027900701, + -0.059999999 0.016961601 -0.00059899897, + -0.058412101 0.031266298 0.0090760002, + -0.0599402 0.043872099 -0.032189999, + -0.059999999 0.0416812 -0.032032002, + -0.059999999 0.041424301 -0.029154001, + -0.0599402 0.042861801 -0.023415999, + -0.0053918599 0.088151999 0.030215999, + -0.021165101 0.056143001 -0.191, + -0.026825599 0.053669199 -0.191, + -0.0248404 0.086188801 -0.031881001, + -0.044564299 0.045845199 0.036858998, + -0.0576833 0.039331902 0.0085939895, + -0.058412101 0.038146701 0.0054049999, + -0.058412101 0.040390201 0.00367599, + -0.059445001 0.039680898 -0.0046540098, + -0.0220857 -0.054975301 -0.159913, + -0.0220857 -0.055273 -0.162147, + -0.0248404 -0.0538042 -0.159794, + -0.0248404 -0.053437401 -0.157534, + -0.0220857 -0.0546088 -0.15767799, + -0.019305199 -0.055996802 -0.160018, + -0.019305199 -0.056294199 -0.162231, + -0.0137106 -0.058125 -0.164537, + -0.0137106 -0.057895798 -0.16236199, + -0.0109179 -0.0587104 -0.164573, + -0.0109179 -0.058872402 -0.166728, + -0.0165099 -0.057167601 -0.162302, + -0.016505901 -0.057668701 -0.171, + -0.0145714 -0.058203701 -0.171, + -0.017408401 -0.057419099 -0.171, + -0.0182469 -0.057158101 -0.191, + -0.0165099 -0.057558801 -0.166674, + -0.019305199 -0.056685399 -0.166638, + -0.0165099 -0.057654001 -0.168844, + -0.0165099 -0.0573969 -0.164492, + -0.0137106 -0.058286902 -0.166704, + -0.019305199 -0.056523599 -0.16443899, + -0.0116994 -0.058848299 -0.171, + -0.0137106 -0.058382399 -0.168859, + -0.0109179 -0.058968201 -0.168871, + -0.0109154 -0.058984298 -0.171, + -0.0137073 -0.058397699 -0.171, + -0.0122731 -0.058731299 -0.191, + 0.0465803 0.073071197 -0.023771999, + 0.044564299 0.0748723 -0.025853001, + 0.044564299 0.073645703 -0.033946998, + 0.044564299 0.074329801 -0.029909, + 0.0424264 0.075835802 -0.032246001, + 0.0424264 0.075037003 -0.036325, + 0.044564299 0.072824001 -0.037960999, + 0.0465803 0.071354099 -0.035728, + 0.0465803 0.072065398 -0.031757999, + 0.0424264 0.077684604 -0.01164, + 0.048467699 0.071102597 -0.0062599899, + 0.0465803 0.073010802 -0.00192799, + 0.048467699 0.070957698 -0.0043459898, + 0.027557701 0.081294097 0.027458001, + 0.0302257 0.081136599 0.023940001, + 0.0328326 0.079906397 0.022244999, + 0.0302257 0.080196202 0.025900001, + 0.040174201 0.073832802 0.020037999, + 0.044564299 0.070615597 0.01533, + 0.035366699 0.078568198 0.020401999, + 0.0378174 0.076265298 0.020322001, + 0.0328326 0.080726303 0.020277999, + 0.050219599 0.068423197 -0.0032540001, + 0.048467699 0.070763998 -0.0025220001, + 0.050219599 0.068096504 -0.0014440001, + 0.050219599 0.067688398 0.00036500499, + 0.055787299 0.056949601 -0.044101998, + 0.0546159 0.059596401 -0.04194, + 0.0532961 0.0644546 -0.021260999, + 0.0532961 0.064257897 -0.024972999, + 0.051830001 0.0668175 -0.018797001, + 0.051830001 0.066667102 -0.02258, + 0.050219599 0.068414003 -0.027967, + 0.051830001 0.065978497 -0.030161001, + 0.050219599 0.067911401 -0.031824, + 0.050219599 0.068783797 -0.024103999, + 0.048467699 0.070781603 -0.025834, + 0.051830001 0.066387497 -0.02637, + 0.048467699 0.070314102 -0.029763, + 0.0378174 0.055810001 0.041168001, + 0.0424264 0.0556041 0.035456002, + 0.040174201 0.0566561 0.037896, + 0.0424264 0.057315201 0.034396999, + 0.040174201 0.058415499 0.036834002, + 0.044564299 0.052803699 0.033854, + 0.0378174 0.069204397 0.030924, + 0.040174201 0.066483803 0.030231999, + 0.040174201 0.067909099 0.028678, + 0.0378174 0.070594102 0.029291, + 0.035366699 0.070417002 0.033027001, + 0.035366699 0.071843497 0.031380001, + 0.040174201 0.0618077 0.034442, + 0.040174201 0.060134798 0.035682, + 0.0378174 0.0677386 0.032490999, + 0.040174201 0.064988397 0.031713001, + 0.040174201 0.063427597 0.033117998, + 0.035366699 0.0689134 0.034605, + 0.0378174 0.066201597 0.033984002, + 0.0302257 0.069360897 0.039896, + 0.0424264 0.0520918 0.037303999, + 0.040174201 0.0530461 0.039742999, + 0.040174201 0.0548639 0.038865998, + 0.0424264 0.053860601 0.036424998, + 0.0465803 0.053336199 0.030196, + 0.048467699 0.0505476 0.028365999, + 0.048467699 0.052130301 0.027399, + 0.0465803 0.051697701 0.031164, + 0.044564299 0.0544958 0.032885998, + 0.044564299 0.056155998 0.031829, + 0.048467699 0.0489407 0.029248999, + 0.050219599 0.046243198 0.027161, + 0.048467699 0.039084502 0.032799002, + 0.048467699 0.037473898 0.033110999, + 0.0465803 0.043254402 0.034705002, + 0.0424264 0.046700198 0.039391, + 0.035366699 0.076693699 0.024224, + 0.0378174 0.074263602 0.024042999, + 0.0378174 0.075310402 0.0222, + 0.035366699 0.077678502 0.022328001, + 0.0328326 0.078990303 0.024188999, + 0.0328326 0.076870397 0.02798, + 0.035366699 0.074446201 0.027902, + 0.0328326 0.075670697 0.029812999, + 0.035366699 0.075615503 0.026085, + 0.0328326 0.077977702 0.026102999, + 0.0302257 0.079158098 0.027829999, + -0.0109179 0.075473599 0.046411999, + -0.0165099 0.069146 0.049341001, + -0.0053918599 0.087196797 0.032285001, + -0.0081421202 0.085904598 0.033994999, + -0.00267513 0.074244902 0.049033999, + 0.019305199 0.077366397 0.040615, + 0.027557701 0.0822566 0.025482999, + 0.0137106 0.090642802 0.016208, + 0.0220857 0.087158501 0.019905999, + 0.0248404 0.084147297 0.024858, + 0.0248404 0.083264798 0.026872, + 0.0220857 0.084159903 0.028105, + 0.0081421202 0.080664001 0.041738, + -3.8715819e-012 0.0742805 0.0491, + 0.0165099 0.079463303 0.039799999, + 0.0302257 0.0562893 0.048034001, + 0.0302257 0.058273699 0.047161002, + 0.0328326 0.055570502 0.046195999, + 0.0328326 0.053604402 0.046971001, + 0.0302257 0.0482243 0.050524, + 0.0053918599 0.053240899 0.059036002, + 0.00267513 0.055518001 0.058701001, + 0.00267513 0.057719801 0.058051001, + 0.0137106 0.0483854 0.058301002, + 0.0109179 0.048580099 0.058959998, + 0.0109179 0.0507663 0.058618002, + 0.0137106 0.046224501 0.058547001, + 0.0165099 0.0438984 0.057884999, + 0.0109179 0.046406399 0.059202, + 0.00267513 0.0466993 0.060254999, + 0.0053918599 0.046642099 0.060051002, + 0.00267513 0.048893198 0.060019001, + 0.00267513 0.044550199 0.060391001, + 0.0053918599 0.044496998 0.060187001, + 0.0378174 0.016788499 0.046944, + 0.0378174 0.020876501 0.046721999, + 0.040174201 0.0146346 0.045024, + 0.035366699 0.039363999 0.047789, + 0.035366699 0.037327498 0.047885999, + 0.035366699 0.020994799 0.048659999, + 0.035764702 0.0125 0.048675999, + 0.037236601 0.0074999998 0.047547001, + 0.038084399 0.0125 0.046863999, + 0.036012899 0.0074999998 0.048489999, + 0.034765299 -0.0094999997 0.049401999, + 0.0378174 0.0146565 0.047045, + 0.0328326 0.016874401 0.050618999, + 0.0328326 0.0211046 0.050459001, + 0.035366699 0.0146771 0.048937, + 0.0302257 0.0402583 0.051495001, + 0.0302257 0.038143899 0.051564001, + 0.0254349 0.0074999998 0.054841999, + 0.022994 0.0125 0.055918999, + 0.0240272 -0.0094999997 0.055479001, + 0.019305199 0.039352901 0.057009999, + 0.019305199 0.0215177 0.057225, + 0.027557701 0.042634498 0.053013999, + 0.0302257 0.0422123 0.051387001, + 0.019305199 0.0436465 0.056914002, + 0.0165099 0.045998398 0.057732999, + 0.0165099 0.048143301 0.057482, + 0.0137106 0.0505585 0.057955999, + 0.0328326 0.049641799 0.048223, + 0.0328326 0.051626801 0.047646001, + 0.0302257 0.054286201 0.048806001, + -0.058412101 0.049791701 -0.047377001, + -0.058998398 0.0479546 -0.046409, + -0.057608999 0.0167691 -0.191, + -0.055579402 0.0226037 -0.191, + -0.0532961 0.061381798 -0.043481998, + -0.0220857 0.041313902 0.055856999, + -0.0248404 0.041002698 0.054566, + -0.0248404 0.0213823 0.054974001, + -0.019305199 0.041585401 0.056983002, + -0.0220857 0.045417599 0.055619001, + -0.0220857 0.043360598 0.055782001, + -0.0137106 0.044113901 0.058695, + -0.0137106 0.042011201 0.05875, + -0.0109179 0.044282001 0.059346002, + -0.0109179 0.046409901 0.059204999, + -0.021165101 0.0074999998 0.056643002, + -0.019305199 0.030429799 0.057116002, + -0.0226011 0.0125 0.056072999, + -0.0220857 0.0214555 0.056177001, + -0.019305199 0.039352998 0.057009999, + -0.0109179 0.050765499 0.058623001, + -0.0109179 0.0485809 0.058963999, + -0.0081421202 0.050923999 0.059126001, + -0.0053918599 0.0488327 0.059815001, + -0.0081421202 0.048729099 0.059464999, + -0.0081421202 0.0465477 0.059703, + -0.00267513 0.046700101 0.060256001, + -3.927749e-015 0.046718199 0.060323, + -8.6283099e-012 0.048913099 0.060086999, + -0.00267513 0.0488934 0.06002, + -0.00267513 0.044551302 0.060391001, + -0.0053918599 0.046643902 0.060052, + -0.0053918599 0.044499099 0.060187999, + 0.058412101 0.044562198 -0.00056799297, + 0.0576833 0.046126802 0.0026089901, + 0.058412101 0.042537 0.001662, + 0.058412101 0.046424299 -0.003026, + 0.058998398 0.043001398 -0.00373599, + 0.058998398 0.041099899 -0.0015210001, + 0.0576833 0.048108499 0.000126007, + 0.058998398 0.047630299 -0.011599, + 0.0576833 0.051436 -0.0054539898, + 0.0576833 0.049887601 -0.00257201, + 0.058412101 0.049530901 -0.0085300002, + 0.058412101 0.048089601 -0.00569, + 0.058412101 0.0497812 -0.047375999, + 0.059445001 0.046738502 -0.017535999, + 0.059445001 0.0457418 -0.014649, + 0.059757002 0.044772699 -0.020505, + 0.059757002 0.0438735 -0.017666001, + 0.058412101 0.028888101 0.0098650102, + 0.0576833 0.032048799 0.012178, + 0.0576833 0.034470499 0.011224, + 0.058998398 0.032613602 0.0049429899, + 0.058412101 0.033541001 0.0080800001, + 0.058998398 0.034805801 0.0036869999, + 0.059445001 0.031692199 0.001825, + 0.058412101 0.035860099 0.0068509998, + 0.058412101 0.031243499 0.0090709999, + 0.058998398 0.028209999 0.0068100002, + 0.058998398 0.023463501 0.0084490096, + 0.051830001 0.061698701 0.008006, + 0.051830001 0.062550902 0.0063510002, + 0.0532961 0.058954898 0.0066880002, + 0.051830001 0.060770798 0.0096199997, + 0.0532961 0.0580035 0.0082350001, + 0.0532961 0.056984 0.0097339898, + 0.051830001 0.059769299 0.011188, + 0.050219599 0.062545098 0.012485, + 0.051830001 0.058697801 0.012706, + 0.050219599 0.0614946 0.014074, + 0.0465803 0.0549431 0.029143, + 0.044564299 0.057777401 0.030687001, + 0.050219599 0.052377701 0.023460001, + 0.051830001 0.051036101 0.020488, + 0.051830001 0.049600601 0.021531999, + 0.050219599 0.050883301 0.024506999, + 0.048467699 0.053681899 0.026349001, + 0.0532961 0.0559 0.011178, + 0.051830001 0.057560299 0.014167, + 0.0532961 0.0535542 0.013887, + 0.0532961 0.052301601 0.015144, + 0.0546159 0.0507828 0.012061, + 0.0532961 0.054755401 0.012564, + 0.051830001 0.055103101 0.016904, + 0.051830001 0.056360599 0.015568, + 0.055787299 0.0503776 0.0077, + 0.055787299 0.051463101 0.0064040101, + 0.0546159 0.053120501 0.009505, + 0.0546159 0.0519768 0.010815, + 0.055787299 0.0492431 0.0089349998, + 0.056809202 0.047689099 0.0057799998, + 0.056809202 0.0497902 0.00327299, + 0.044564299 0.0623466 0.026769999, + 0.044564299 0.063751496 0.025312999, + 0.040174201 0.041933201 0.043074999, + 0.0424264 0.0395054 0.040948, + 0.040174201 0.040120699 0.043320999, + 0.040174201 0.043786298 0.042741001, + 0.0378174 0.042557701 0.045327, + 0.0378174 0.0444558 0.045006, + 0.048460599 0.0125 0.035861999, + 0.048467699 0.0145345 0.035805002, + 0.048204001 0.0125 0.036226001, + 0.0498982 0.0125 0.033819001, + 0.048901699 0.0074999998 0.035264999, + 0.055787299 0.0162117 0.022216, + 0.0546159 0.0144201 0.025255, + 0.0546159 0.016276499 0.024997, + 0.056809202 0.0134207 0.019795001, + 0.056496199 0.0125 0.020702999, + 0.055787299 0.013436 0.022577001, + 0.055787299 0.0143901 0.022492999, + 0.056809202 0.0143599 0.019707, + 0.057419099 0.0125 0.017907999, + 0.057158101 0.0074999998 0.018747, + 0.056669399 -0.0094999997 0.020213, + 0.0576833 0.0134053 0.016999001, + 0.040174201 -0.0444225 -0.166133, + 0.040174201 -0.044524699 -0.16857301, + 0.038194101 -0.046273202 -0.171, + 0.059757002 0.043566398 -0.047954999, + 0.059445001 0.045348 -0.048744999, + 0.058998398 0.0479405 -0.046409, + 0.0599402 0.0437495 -0.029239999, + 0.0599402 0.043408599 -0.026311999, + 0.0599402 0.042960599 -0.041173, + 0.059445001 0.0474912 -0.020517001, + 0.059757002 0.0454363 -0.023434, + 0.0599402 0.043856502 -0.032193001, + 0.0137106 -0.058279101 -0.166703, + 0.0137106 -0.058115698 -0.164536, + 0.0109179 -0.058473699 -0.16241001, + 0.0122731 -0.058731299 -0.191, + 0.010915 -0.058982499 -0.171, + 0.0109179 -0.058964301 -0.168871, + 0.0081428103 -0.058624901 -0.16028801, + 0.0053973799 -0.058938101 -0.16032, + 0.00268824 -0.059418701 -0.162487, + -0.0053973799 -0.0596296 -0.166759, + -0.0081428103 -0.0593183 -0.16674601, + -0.0053973799 -0.059725899 -0.168887, + -0.0053973799 -0.059467301 -0.16462, + -0.00268824 -0.059811998 -0.166766, + -0.0081428103 -0.059156101 -0.1646, + -0.00268824 -0.059908599 -0.16889, + -0.0256411 -0.054245099 -0.171, + -0.0282706 -0.052922402 -0.171, + -0.040172402 -0.044562198 -0.171, + -0.0402769 -0.044472098 -0.171, + -0.0378174 0.052063201 0.042842001, + -0.040174201 0.051209699 0.040546998, + -0.035366699 0.052862301 0.044992, + -0.0378174 0.050166901 0.043527, + -0.040174201 0.0493595 0.041235998, + -0.035366699 0.054790001 0.044215001, + -0.00267513 0.090549998 0.024095999, + -0.0053918599 0.090944998 0.021817001, + -4.241709e-012 0.085150696 0.036594, + -0.0053918599 0.084973998 0.036334999, + -0.0081421202 0.084746003 0.035999998, + -0.0081421202 0.083485298 0.037965, + -0.0053918599 0.0837081 0.038302001, + -0.0053918599 0.0861376 0.034325998, + -0.00267513 0.085107498 0.036531001, + -0.00267513 0.086273998 0.034520999, + 0.00267513 0.090549499 0.024095999, + 3.7926754e-012 0.089948103 0.026269, + -2.0798101e-012 0.090598501 0.024156, + -0.00267513 0.089900397 0.026209, + -0.00267513 0.089148499 0.028315, + -0.00267513 0.0936165 -0.0097780004, + -0.0053918599 0.092978701 0.0084779998, + -0.0081421202 0.092702799 0.0081909904, + -0.0053918599 0.093148202 -0.014544, + -0.0081421202 0.092848599 -0.014789, + -0.0053918599 0.093443103 -0.0099269999, + -0.0081421202 0.093147501 -0.010181, + -0.0053918599 0.091282599 -0.028294999, + -0.0081421202 0.0917603 -0.023963001, + -0.0081421202 0.092385799 -0.019386001, + 0.0109179 0.091320902 -0.024287, + 0.0165099 0.089225799 -0.029741, + 0.0165099 0.090028502 -0.025242001, + 0.0137106 0.089948401 -0.029232999, + 0.0152803 0.058021698 -0.191, + 0.019305199 0.088359296 -0.030351, + 0.019305199 0.089169599 -0.025877001, + -0.0081421202 0.061848599 0.055863, + -0.0109179 0.061639201 0.055353999, + -0.0081421202 0.063980602 0.054887999, + -0.0109179 0.059489701 0.056221001, + -0.0053918599 0.064133897 0.055243999, + -0.0165099 0.0567641 0.055484999, + -0.0137106 0.0592281 0.055553, + -0.0137106 0.0613642 0.054685, + -0.019305199 0.058512799 0.053725999, + -0.019305199 0.060612202 0.052857, + -0.0220857 0.058056802 0.052561, + -0.0165099 0.058902901 0.054722998, + -0.0165099 0.0610223 0.053854, + -0.0220857 0.060132898 0.051692002, + -0.0165099 0.065170802 0.051801998, + -0.019305199 0.064721197 0.050806999, + -0.0165099 0.0671838 0.050620999, + -0.0165099 0.0631143 0.05288, + -0.0137106 0.065545604 0.052632999, + -0.019305199 0.062684402 0.051883999, + -0.059999999 0.035490699 -0.013935, + -0.059999999 0.033956699 -0.011973, + -0.0599402 0.036874101 -0.010871, + -0.059999999 0.036913101 -0.016093001, + -0.0599402 0.038415499 -0.013043, + -0.0599402 0.041032899 -0.01794, + -0.0599402 0.039811399 -0.015406, + -0.059445001 0.0184741 0.0072630001, + -0.058998398 0.0159637 0.010981, + -0.058998398 0.018647799 0.010112, + -0.058998398 0.0234669 0.0084480001, + -0.058998398 0.0282102 0.0068090102, + -0.059757002 0.0150458 0.00563, + -0.0599402 0.0150006 0.002907, + -0.059757002 0.0158343 0.0054100002, + -0.059757002 0.0142115 0.005783, + -0.059445001 0.0150916 0.0083900001, + -0.0599402 0.014182 0.0030679901, + -0.059445001 0.0158986 0.0081799896, + -0.059999999 0.021810099 -0.0031300001, + -0.059999999 0.0255592 -0.005134, + -0.059999999 0.027323401 -0.0061430102, + -0.059999999 0.0179643 -0.00109801, + -0.059999999 0.0149558 0.000205002, + -0.0599402 0.028096501 -0.0031590001, + -0.059999999 0.0067396299 -0.124159, + -0.059445001 0.023045801 0.005506, + -0.058998398 0.0304632 0.0059759999, + -0.058998398 0.032618102 0.0049620098, + -0.059757002 0.0183022 0.0044439998, + -0.0599402 0.0157708 0.0026750001, + -0.059757002 0.017183 0.0048969998, + -0.059445001 0.0275364 0.0037740001, + -0.059757002 0.0268698 0.000770004, + -0.059445001 0.0296652 0.0028959999, + -0.059757002 0.028875601 -0.00015199299, + -0.059757002 0.0226292 0.0025939899, + -0.0599402 0.0170718 0.002138, + -0.0599402 0.018132599 0.001662, + -0.0599402 0.031692401 -0.0056109899, + -0.0599402 0.029885501 -0.0042829998, + -0.059999999 0.028992901 -0.0073020002, + -0.059999999 0.030677499 -0.008657, + -0.0599402 0.0334801 -0.0071499902, + -0.0599402 0.043772198 -0.029231001, + -0.0599402 0.043436401 -0.026298, + -0.059757002 0.045707401 -0.035452999, + -0.059757002 0.045327399 -0.038573001, + -0.059445001 0.047280401 -0.039170999, + -0.059757002 0.045981199 -0.032430999, + -0.059757002 0.0460504 -0.029426999, + -0.059445001 0.048034798 -0.032777999, + -0.059445001 0.047708001 -0.035966001, + -0.058998398 0.050547902 -0.026922001, + -0.059445001 0.048252299 -0.029691, + -0.058412101 0.052858099 -0.024134999, + -0.0378174 0.053947601 0.042063002, + -0.0328326 0.057520699 0.045338999, + -0.0302257 0.060235199 0.046204999, + -0.027557701 0.077834003 0.033179, + -0.0053918599 0.089004003 0.028125999, + -0.0081421202 0.086959101 0.031957, + -0.0152803 0.058021698 -0.191, + -0.00923343 0.059285302 -0.191, + -0.0109179 0.090531103 -0.028824, + -0.0328326 0.081832498 -0.034947999, + -0.0302257 0.083428301 -0.033824001, + -0.027557701 0.084881097 -0.032802001, + -0.0532961 0.064472303 -0.021245001, + -0.0532961 0.038142901 0.023653001, + -0.056809202 0.037965901 0.013216, + -0.044564299 0.047601499 0.036247, + -0.0576833 0.041703701 0.0068709999, + -0.059757002 0.041441198 -0.012356, + -0.059757002 0.039929502 -0.0099689905, + -0.059757002 0.044801399 -0.020486001, + -0.030832 -0.051472198 -0.171, + -0.035366699 -0.047955502 -0.161548, + -0.0378174 -0.0460683 -0.161394, + 0.044564299 0.075532399 -0.017720999, + 0.044564299 0.075273097 -0.021787999, + 0.044564299 0.075650699 -0.013659, + 0.0424264 0.077602804 -0.015763, + 0.0424264 0.077377297 -0.019893, + 0.035366699 0.080973104 -0.031936001, + 0.0322018 0.050626501 -0.191, + 0.0378174 0.079118602 -0.033307001, + 0.0328326 0.082694598 -0.030664001, + 0.035366699 0.081710398 -0.02768, + 0.040174201 0.079567999 -0.013905, + 0.040174201 0.078548104 -0.026464, + 0.0424264 0.077007897 -0.024022, + 0.0424264 0.076493897 -0.028142, + 0.040174201 0.077914603 -0.03063, + 0.0378174 0.079875 -0.029107001, + 0.0248404 0.086185202 -0.031881001, + 0.0220857 0.087346397 -0.031064, + 0.040174201 0.079517096 -0.0055559999, + 0.040174201 0.079615302 -0.0097230095, + 0.050219599 0.069021098 -0.020243, + 0.048467699 0.071113199 -0.021901, + 0.0465803 0.073366001 -0.01977, + 0.0378174 0.080352202 0.0067199999, + 0.0248404 0.087994203 0.008134, + 0.0220857 0.089010403 0.0092469901, + 0.044564299 0.075468302 -0.0055809901, + 0.0465803 0.073424399 -0.0078189997, + 0.0465803 0.073180303 -0.0038709999, + 0.044564299 0.0751784 -0.00157401, + 0.044564299 0.075628698 -0.0096109901, + 0.0424264 0.077421598 -0.0034419999, + 0.0424264 0.077623501 -0.0075310101, + 0.0424264 0.076872103 0.0026199999, + 0.040174201 0.078663103 0.0047300002, + 0.0424264 0.077087998 0.00062199403, + 0.044564299 0.074985199 0.000397995, + 0.0465803 0.067003399 0.016286001, + 0.048467699 0.064269997 0.01527, + 0.044564299 0.068650298 0.018856, + 0.044564299 0.069675401 0.017113, + 0.040174201 0.074755803 0.01818, + 0.0378174 0.0771266 0.018416001, + 0.035366699 0.0793631 0.018452, + 0.0424264 0.0766045 0.00452299, + 0.040174201 0.078373201 0.0066560102, + 0.0328326 0.081450403 0.018291, + 0.0328326 0.0820795 0.016292, + 0.0532961 0.064481899 -0.013872, + 0.0532961 0.064526796 -0.017561, + 0.0546159 0.062178198 -0.016520999, + 0.0546159 0.0620557 -0.013027, + 0.051830001 0.066743903 -0.011271, + 0.051830001 0.0668405 -0.015028, + 0.0465803 0.072491497 0.00177499, + 0.048467699 0.070491403 -0.00069700601, + 0.048467699 0.070134401 0.00114101, + 0.0465803 0.072791502 -7.6995806e-005, + 0.044564299 0.074414998 0.0041530002, + 0.044564299 0.0747412 0.0022749901, + 0.044564299 0.072910301 0.0098120002, + 0.050219599 0.066627003 0.0039490098, + 0.050219599 0.067198701 0.0021639999, + 0.0546159 0.060947299 -0.034692999, + 0.0546159 0.060333699 -0.038323998, + 0.055787299 0.057721801 -0.040564999, + 0.0302257 0.064036801 0.043951001, + 0.027557701 0.068497799 0.042993002, + 0.0378174 0.061217502 0.037976, + 0.0328326 0.0594391 0.044351, + 0.035366699 0.0566958 0.043322999, + 0.0328326 0.057517901 0.045322999, + 0.0302257 0.0602316 0.046188999, + 0.0302257 0.062155101 0.045118999, + 0.035366699 0.060424499 0.041285001, + 0.0328326 0.061326198 0.043281998, + 0.035366699 0.058577001 0.042351998, + 0.0378174 0.0594531 0.039133001, + 0.0378174 0.057648201 0.040197, + 0.044564299 0.047604699 0.036226001, + 0.0465803 0.044960398 0.034168001, + 0.044564299 0.045850001 0.036839001, + 0.0424264 0.048506498 0.038786002, + 0.0424264 0.050305001 0.038091, + 0.048467699 0.044035301 0.031390999, + 0.050219599 0.044665098 0.02788, + 0.050219599 0.043078698 0.028519001, + 0.0465803 0.048353601 0.032839999, + 0.048467699 0.0473161 0.030048, + 0.0465803 0.050034601 0.032044999, + 0.0465803 0.046661101 0.033546999, + 0.044564299 0.049351402 0.035525002, + 0.048467699 0.0456798 0.030761, + 0.044564299 0.0510865 0.034734, + 0.0424264 0.041271001 0.040686, + 0.044564299 0.0388573 0.038447, + 0.0465803 0.0381791 0.035831001, + 0.027557701 0.076475397 0.034977, + 0.0302257 0.075477198 0.033365998, + 0.0328326 0.0730033 0.033319, + -0.0109179 0.067889303 0.052115999, + -0.0137106 0.067574799 0.051449999, + -0.0053918599 0.066237003 0.054163001, + -0.0081421202 0.066076703 0.053808, + -0.0081421202 0.082125001 0.039880998, + -0.0109179 0.083166197 0.037482999, + -0.0053918599 0.075944699 0.047261, + -0.0053918599 0.074135102 0.048827998, + -0.00267513 0.076058201 0.047465, + -0.0081421202 0.075750999 0.046912, + 0.0220857 0.076689601 0.039483, + 0.0248404 0.077374101 0.036428001, + 0.0248404 0.075913899 0.038185999, + 0.019305199 0.080277197 0.037002001, + 0.0220857 0.078171901 0.037716001, + 0.019305199 0.078867897 0.038839001, + 0.0137106 0.082740597 0.036844, + 0.0165099 0.080888502 0.037955999, + 0.0165099 0.082218103 0.036056001, + 0.027557701 0.077821098 0.033169001, + 0.0302257 0.078024 0.029722, + 0.0302257 0.076796301 0.031569999, + 0.0248404 0.082282603 0.028860999, + 0.027557701 0.080232799 0.029402001, + 0.027557701 0.079074301 0.031309001, + 0.0248404 0.078743704 0.034609001, + 0.0220857 0.079562701 0.035886999, + 0.019305199 0.081591599 0.035110001, + 0.00267513 0.085106201 0.036529999, + 0.0053918599 0.0837055 0.0383, + 0.0220857 0.071742803 0.044353001, + 0.0302257 0.084384598 0.013907, + 0.027557701 0.0863043 0.011219, + 0.019305199 0.090364099 0.00575301, + 0.0220857 0.089458697 0.0048090098, + 0.0220857 0.0892535 0.007032, + 0.019305199 0.088922299 0.016814001, + 0.019305199 0.088504396 0.018874999, + 0.0165099 0.089654699 0.017677, + 0.0220857 0.0876588 0.017855, + 0.0165099 0.090655297 0.011049, + 0.019305199 0.089896902 0.010218, + 0.0165099 0.091138601 0.0065600001, + 0.0165099 0.090024598 0.015497, + 0.019305199 0.089283302 0.014644, + 0.0165099 0.087359399 0.025986999, + 0.019305199 0.085854404 0.027143, + 0.0220857 0.085059002 0.026079001, + 0.0137106 0.089830898 0.020475, + 0.0165099 0.089227699 0.019747, + 0.0137106 0.090265498 0.018395999, + 0.0137106 0.0893014 0.022554001, + 0.019305199 0.084940702 0.02918, + 0.0248404 0.0727406 0.041494999, + 0.0220857 0.0734699 0.042808, + 0.0248404 0.071037598 0.043033, + 0.027557701 0.071919002 0.040015999, + 0.0248404 0.074367702 0.039877001, + 0.0220857 0.075120598 0.041182, + 0.027557701 0.070243299 0.041547, + 1.1883117e-012 0.076094903 0.047532, + 8.1914007e-012 0.077830501 0.045878999, + 0.0109179 0.081808597 0.039391, + 0.0109179 0.083160996 0.037478998, + 0.0137106 0.081398398 0.038750999, + 0.0137106 0.079960003 0.040601999, + 0.0109179 0.080359504 0.041246999, + 0.0081421202 0.082121201 0.039878, + 0.0081421202 0.083481401 0.037962001, + 0.027557701 0.050802998 0.051709998, + 0.0302257 0.0522715 0.049477, + 0.0302257 0.050249599 0.050048999, + 0.0248404 0.055465698 0.05198, + 0.027557701 0.054906901 0.050476, + 0.027557701 0.052858502 0.051144, + 0.0248404 0.0533868 0.052643999, + 0.027557701 0.0569437 0.049706999, + 0.0109179 0.0529548 0.058175001, + 0.0081421202 0.053123299 0.058681998, + 0.0053918599 0.055444799 0.058492001, + 0.0137106 0.0527336 0.05751, + 4.3863381e-012 0.051121201 0.059751, + 0.00267513 0.053309899 0.059243999, + 0.00267513 0.051100101 0.059682999, + -0.00267513 0.053309601 0.059245002, + -0.0053918599 0.051034801 0.059478, + -0.00267513 0.0510999 0.059684001, + 7.2369597e-012 0.0533324 0.059312999, + 2.9908439e-012 0.055541899 0.058770001, + 0.0137106 0.042009301 0.05875, + 0.0137106 0.044108599 0.058694001, + 0.0165099 0.0418153 0.057946999, + 0.0165099 0.021572599 0.058122002, + 0.0109179 0.042165302 0.059395999, + 0.0137106 0.039742101 0.058763999, + 0.0165099 0.017051499 0.058157001, + 0.0109179 0.044277702 0.059344999, + 0.0146178 0.0125 0.058692001, + 0.027557701 0.021297401 0.053617001, + 0.0308876 0.0074999998 0.051938999, + 0.029552899 -0.0094999997 0.052717, + 0.0308873 0.0125 0.051938999, + 0.033358999 0.0125 0.050372001, + 0.0322018 0.0074999998 0.051127002, + 0.030873001 0.0125 0.051948, + 0.0302257 0.016912499 0.052244999, + 0.0328326 0.0146962 0.050693002, + 0.0302257 0.0212055 0.052111998, + 0.027557701 0.0406482 0.053111002, + 0.0220857 0.041310899 0.055856999, + 0.027557701 0.046686102 0.052552, + 0.027557701 0.044638399 0.052831002, + 0.027557701 0.048744202 0.052179001, + 0.0302257 0.046199199 0.050905, + 0.0302257 0.0441841 0.051192999, + 0.0220857 0.045410499 0.055613998, + 0.0248404 0.045047399 0.054304998, + 0.0220857 0.043352 0.055780001, + 0.0248404 0.043014601 0.054478999, + 0.019305199 0.045727301 0.056756001, + -0.058998398 0.049252398 -0.039884999, + -0.058998398 0.0486577 -0.043152999, + -0.0546159 0.062066302 -0.023754001, + -0.055787299 0.059627 -0.026296999, + -0.0137106 0.054905601 0.056968, + -0.0137106 0.052732199 0.057517, + -0.0109179 0.0573209 0.056981001, + -0.0137106 0.057072699 0.056313999, + -0.0165099 0.054613601 0.056141, + -0.0165099 0.0524568 0.056690998, + -0.0053918599 0.053240299 0.059039, + -0.00267513 0.0555178 0.058701999, + -0.0081421202 0.059689 0.056729998, + -0.0053918599 0.061994899 0.056217998, + -0.00267513 0.062080801 0.056426998, + -0.0165099 0.0439048 0.057886001, + -0.019305199 0.043653999 0.056915998, + -0.0137106 0.0462288 0.05855, + -0.0193005 0.0125 0.057294998, + -0.017363001 0.0125 0.057932999, + -0.0182469 -0.0094999997 0.057658002, + -0.020158799 0.0125 0.057011999, + -0.0165099 0.041817602 0.057946999, + 0.0576833 0.052729499 -0.0084849996, + 0.056809202 0.055846501 -0.008657, + 0.056809202 0.056675401 -0.011929, + 0.058412101 0.051658701 -0.014601, + 0.058998398 0.0487254 -0.014534, + 0.058998398 0.0495684 -0.017568, + 0.058412101 0.050725002 -0.011513, + 0.0576833 0.053754099 -0.011627, + 0.0576833 0.053164698 -0.041703001, + 0.058412101 0.0512073 -0.040727999, + 0.058412101 0.0505495 -0.044059001, + 0.0576833 0.052435402 -0.045099001, + 0.056809202 0.055085599 -0.042826001, + 0.056809202 0.055776101 -0.039351001, + 0.055787299 0.0589054 -0.033447001, + 0.055787299 0.058373701 -0.037011001, + 0.0546159 0.061804298 -0.027409, + 0.058998398 0.050151002 -0.020667, + 0.059445001 0.029642001 0.0028910099, + 0.059757002 0.0182971 0.004439, + 0.059445001 0.0158842 0.0081430096, + 0.058998398 0.0159494 0.010944, + 0.058998398 0.0186428 0.010107, + 0.059445001 0.0142387 0.0085190004, + 0.059757002 0.015819799 0.0053719901, + 0.059757002 0.0142088 0.0057669999, + 0.055787299 0.052494802 0.0050479998, + 0.0546159 0.0552385 0.0067070001, + 0.055787299 0.054382201 0.0021790001, + 0.056809202 0.051683102 0.00054200698, + 0.055787299 0.053469099 0.00363901, + 0.0546159 0.056205198 0.0052280002, + 0.048467699 0.059454001 0.021357, + 0.050219599 0.057929199 0.018503999, + 0.0465803 0.060928602 0.024116, + 0.050219599 0.0566165 0.019851999, + 0.050219599 0.060372401 0.01561, + 0.050219599 0.059182599 0.017088, + 0.044564299 0.059353601 0.02946, + 0.044564299 0.060878798 0.028154001, + 0.0465803 0.056511901 0.028005, + 0.044564299 0.065088697 0.023788, + 0.0465803 0.062284801 0.022673, + 0.048467699 0.0607596 0.019927001, + 0.035366699 -0.048429102 -0.168653, + 0.0378174 -0.046439402 -0.166216, + 0.035366699 -0.048327599 -0.16629399, + 0.0378174 -0.046541199 -0.168614, + 0.035878699 -0.0480907 -0.171, + 0.034754898 -0.048886999 -0.171, + 0.033477101 -0.049792401 -0.171, + 0.0328326 -0.050181501 -0.168689, + 0.059445001 0.0467274 -0.042381, + 0.059757002 0.044829398 -0.041724, + 0.059757002 0.044248499 -0.044842999, + 0.059445001 0.046089798 -0.045568001, + 0.058998398 0.0486404 -0.043156002, + 0.058998398 0.049233001 -0.039893001, + 0.0599402 0.043730199 -0.035133, + 0.0599402 0.043398298 -0.038113002, + 0.0081428103 -0.059313599 -0.16674501, + 0.0053973799 -0.059723999 -0.16888601, + 0.0109179 -0.058866199 -0.16672701, + 0.0109179 -0.058703002 -0.164572, + 0.0061689499 -0.059679601 -0.171, + 0.0081428103 -0.059411399 -0.16888, + 0.0060668602 -0.059692498 -0.171, + 0.0089870598 -0.059323099 -0.171, + 0.00616926 -0.059682 -0.191, + 0.0053973799 -0.059463698 -0.164619, + 0.0081428103 -0.059150599 -0.1646, + 0.0053973799 -0.059626501 -0.166758, + 0.0053973799 -0.0592345 -0.16247199, + 0.00268824 -0.059647799 -0.16463, + 0.0081428103 -0.0589214 -0.16244601, + 0.00268824 -0.059810501 -0.166766, + -0.0220857 -0.0556642 -0.166596, + -0.0220857 -0.055759002 -0.168805, + -0.00267513 0.0838385 0.0385, + -0.0109179 0.091142297 0.016783001, + -0.0081421202 0.0915206 0.017217999, + -0.0081421202 0.092186503 0.012727, + -0.0109179 0.091799699 0.012304, + -0.0109179 0.090758599 0.018975001, + -0.0081421202 0.093281902 -0.0055709998, + -0.0137106 0.091291703 0.011748, + -0.0053918599 0.092456698 0.013023, + -0.00267513 0.091096297 0.021999, + -4.7545106e-012 0.091145597 0.022058999, + 0.0081421202 0.090685703 0.021505, + 0.0109179 0.090316102 0.021059999, + 0.0081421202 0.091131203 0.019415, + 0.0109179 0.090756796 0.018975001, + 0.0220857 0.0896248 0.0025780001, + -0.0220857 0.087349601 -0.031064, + -0.0109179 0.091951601 -0.019723, + -0.0109179 0.091321602 -0.024288001, + -0.00267513 0.093323998 -0.0144, + -6.9079716e-012 0.093672998 -0.00973, + 0.0053918599 0.093571797 -0.0053079999, + 0.00267513 0.093616098 -0.0097780004, + 4.9327959e-012 0.093381301 -0.014353, + -3.8459682e-012 0.092925198 -0.018966001, + -0.0053918599 0.093538597 -0.00069599901, + -0.0053918599 0.093573101 -0.0053079999, + -0.0053918599 0.093340203 0.0039029999, + -0.00267513 0.093743898 -0.0051540099, + -0.0109179 0.092419602 -0.015139, + -0.00267513 0.092246696 -0.023603, + -0.0053918599 0.092066899 -0.023737, + -0.00267513 0.091463998 -0.028167, + -1.2637284e-013 0.091522999 -0.028124999, + -3.7556473e-012 0.092305399 -0.023560001, + -0.00267513 0.092867099 -0.019012, + -0.0053918599 0.092689097 -0.01915, + 0.0137106 0.0913807 -0.020166, + -0.00267513 0.093706504 -0.00053700298, + -0.00267513 0.093505099 0.004067, + -0.019305199 0.054263499 0.055148002, + -0.019305199 0.056394 0.05449, + -0.019305199 0.052126698 0.055702001, + -0.019305199 0.049988601 0.056154002, + -0.0220857 0.047515199 0.055358, + -0.0302257 0.044193801 0.051199, + -0.027557701 0.044647198 0.052836001, + -0.0220857 0.049626101 0.055001002, + -0.0248404 0.047126301 0.054042999, + -0.027557701 0.046688199 0.052561, + -0.0302257 0.048222002 0.050535999, + -0.0328326 0.047650699 0.048719, + -0.0328326 0.0456669 0.049106002, + -0.0302257 0.046201501 0.050914001, + -0.0328326 0.049638201 0.048238002, + -0.0248404 0.061605599 0.049382001, + -0.027557701 0.0609564 0.047876999, + -0.0248404 0.063592903 0.048308, + -0.0248404 0.059583299 0.050354999, + -0.0220857 0.062181801 0.050717998, + -0.027557701 0.0589641 0.04885, + -0.0220857 0.064195499 0.049642999, + -0.059757002 0.030785101 -0.00124001, + -0.059445001 0.031696599 0.0018439899, + -0.058998398 0.034799401 0.0037130001, + -0.059445001 0.048014801 -0.023549, + -0.059757002 0.045879401 -0.026409, + -0.059445001 0.048257999 -0.026626, + -0.058998398 0.050173301 -0.020657999, + -0.059445001 0.047518801 -0.020502999, + -0.059757002 0.045464002 -0.023419, + -0.058998398 0.050489299 -0.023796, + -0.058998398 0.0497378 -0.036609001, + -0.0248404 0.078755297 0.034618001, + -0.0424264 0.050304499 0.038112, + -0.040174201 0.058421601 0.036855001, + -0.035366699 0.056698799 0.043341, + -0.0328326 0.059443001 0.044367999, + -0.0302257 0.076810397 0.031580999, + -0.0302257 0.078038603 0.029732, + -0.0302257 0.079172596 0.027838999, + -0.0137106 0.083990701 0.034894001, + -0.0109179 0.084419496 0.035521999, + -0.0109179 0.085570998 0.033521, + -0.0137106 0.082747199 0.036849, + -0.0137106 0.085132897 0.032898001, + -0.0053918599 0.089753397 0.026022, + -0.0053918599 0.0904008 0.023910999, + -0.0081421202 0.087909803 0.029890999, + -0.0109179 0.086618699 0.031486999, + -0.0220857 0.086563602 0.021973001, + -0.0322018 0.050626501 -0.191, + -0.037236601 0.047047202 -0.191, + -0.0302257 0.084279001 -0.029495001, + -0.044564299 0.072827101 -0.037962999, + -0.0424264 0.075039998 -0.036327001, + -0.0465803 0.0713576 -0.035728998, + -0.040174201 0.0795798 -0.013903, + -0.0424264 0.0774341 -0.003422, + -0.0424264 0.077698603 -0.011634, + -0.0424264 0.077615201 -0.015761999, + -0.0546159 0.037240699 0.0206, + -0.055787299 0.036326099 0.017506, + -0.055787299 0.039015699 0.016365999, + -0.0546159 0.041460998 0.018821999, + -0.0546159 0.0400557 0.019486999, + -0.0532961 0.0425491 0.021910001, + -0.0532961 0.0410816 0.022566, + -0.0532961 0.039611399 0.023146, + -0.0465803 0.0466577 0.033569001, + -0.050219599 0.0430732 0.028542001, + -0.051830001 0.042089 0.025589, + -0.048467699 0.045676298 0.030784, + -0.051830001 0.040557802 0.026156999, + -0.050219599 0.041482601 0.029099001, + -0.048467699 0.04403 0.031413, + -0.0465803 0.044955298 0.034189001, + -0.058998398 0.041108899 -0.0014909999, + -0.058998398 0.043014701 -0.00370599, + -0.059445001 0.043092798 -0.009265, + -0.059445001 0.0414638 -0.0068549998, + -0.059757002 0.043900002 -0.017642001, + -0.059757002 0.0427729 -0.014922, + -0.051830001 0.066684201 -0.022573, + -0.050219599 0.068798497 -0.024102001, + -0.035366699 -0.048185799 -0.16392601, + -0.0328326 -0.050193101 -0.16869099, + -0.038047399 -0.046393901 -0.171, + -0.040174201 -0.0445389 -0.168575, + -0.039599199 -0.045056298 -0.171, + -0.039609101 -0.045067899 -0.191, + -0.033319298 -0.0498982 -0.171, + -0.0302257 -0.0510187 -0.159509, + -0.0328326 -0.0497071 -0.16169199, + -0.0328326 -0.049408302 -0.159344, + -0.0302257 -0.0513172 -0.161823, + -0.027557701 -0.0527828 -0.161943, + -0.0248404 -0.054331701 -0.164304, + -0.027557701 -0.053012598 -0.164223, + -0.0248404 -0.054493502 -0.166548, + -0.0248404 -0.054588001 -0.168781, + -0.0302257 -0.051708899 -0.166434, + -0.0328326 -0.0499373 -0.16403399, + -0.0328326 -0.050099101 -0.16636799, + -0.0302257 -0.051547099 -0.164133, + -0.0302257 -0.051803101 -0.168724, + -0.027557701 -0.053174399 -0.166494, + -0.027557701 -0.053268701 -0.168754, + 0.0302257 0.0842769 -0.029494001, + 0.040174201 0.079034999 -0.022283001, + 0.040174201 0.079374798 -0.018093999, + 0.0378174 0.080485299 -0.024882, + 0.027557701 0.087314598 -0.015182, + 0.0302257 0.0860634 -0.014177, + 0.0302257 0.085924402 -0.016373999, + 0.0248404 0.088566102 -0.014108, + 0.0248404 0.088206701 -0.018578, + 0.0220857 0.088828102 -0.022149, + 0.0220857 0.088165402 -0.026620001, + 0.048467699 0.071370803 -0.01405, + 0.048467699 0.071309499 -0.017969999, + 0.050219599 0.069126397 -0.01639, + 0.050219599 0.069101296 -0.012552, + 0.048467699 0.071299002 -0.010146, + 0.0465803 0.073541299 -0.011787, + 0.0465803 0.073522501 -0.015773, + 0.0248404 0.088766702 -0.0096349902, + 0.0220857 0.089861304 -0.008649, + 0.035366699 0.083108 -0.012659, + 0.0328326 0.084658802 -0.013335, + 0.0378174 0.081421301 -0.012152, + 0.027557701 0.087533399 -0.010746, + 0.0302257 0.086163498 -0.011979, + 0.027557701 0.087583996 -0.0085279997, + 0.0248404 0.088808797 -0.0051660002, + 0.040174201 0.079275802 -0.001412, + 0.040174201 0.078900598 0.0027059901, + 0.0378174 0.0800412 0.0086679999, + 0.035366699 0.081183903 0.012521, + 0.048467699 0.066232502 0.011912, + 0.050219599 0.064417697 0.00917101, + 0.048467699 0.065291002 0.013613, + 0.050219599 0.063520201 0.010849, + 0.0465803 0.067987598 0.014563, + 0.0465803 0.068888597 0.012803, + 0.048467699 0.067869902 0.0084070005, + 0.050219599 0.065972701 0.005715, + 0.050219599 0.065235801 0.0074579902, + 0.048467699 0.067092799 0.010175, + 0.048467699 0.068562299 0.0066150101, + 0.0465803 0.0697046 0.011011, + 0.0465803 0.0704339 0.0091939997, + 0.044564299 0.072233804 0.011674, + 0.0424264 0.073155098 0.015907999, + 0.044564299 0.071468897 0.013515, + 0.0424264 0.076253198 0.0064249998, + 0.0424264 0.074662603 0.012158, + 0.040174201 0.075586803 0.016294001, + 0.0424264 0.073953897 0.014044, + 0.0378174 0.078569703 0.014539, + 0.0378174 0.077894501 0.016486, + 0.035366699 0.080063596 0.016485, + 0.040174201 0.076325901 0.014386, + 0.035366699 0.080670498 0.014505, + 0.0532961 0.064303599 -0.010315, + 0.051830001 0.066295698 -0.0058849901, + 0.051830001 0.066510797 -0.0076529998, + 0.0465803 0.071633801 0.005504, + 0.0465803 0.071076803 0.0073569901, + 0.044564299 0.073499098 0.0079340097, + 0.044564299 0.0740005 0.0060450002, + 0.0465803 0.072105303 0.00364101, + 0.048467699 0.069694102 0.0029770101, + 0.048467699 0.069170199 0.0048039998, + 0.0328326 0.0649691 0.040860001, + 0.0302257 0.065869503 0.042688001, + 0.0328326 0.063171901 0.042118002, + 0.0302257 0.067646399 0.041335002, + 0.035366699 0.062231101 0.040123999, + 0.035366699 0.065694101 0.037533, + 0.035366699 0.063989803 0.038872, + 0.0328326 0.066711299 0.039514001, + 0.035366699 0.067337401 0.036109, + 0.0328326 0.068391703 0.038082, + 0.0378174 0.064598203 0.035397999, + 0.0378174 0.062934697 0.036729999, + 0.044564299 0.042328499 0.037808999, + 0.044564299 0.044090301 0.037365999, + 0.0465803 0.041545901 0.035161, + 0.0465803 0.039843399 0.035537001, + 0.044564299 0.0405734 0.038169999, + 0.0424264 0.0430764 0.040339001, + 0.0424264 0.0448891 0.039907999, + 0.0302257 0.072577499 0.036773, + 0.0302257 0.074069403 0.035101999, + 0.0328326 0.071542703 0.034979001, + 0.0328326 0.070003897 0.036568001, + 0.0302257 0.071006298 0.038373001, + 0.027557701 0.073519602 0.038407002, + 0.027557701 0.075040102 0.036725, + -0.0109179 0.071812801 0.049449999, + -0.0137106 0.071472898 0.048788, + -0.0137106 0.069553003 0.050167002, + -0.0109179 0.069880299 0.050832, + -0.0109179 0.073679604 0.047975, + -0.0081421202 0.072071701 0.049954001, + -0.0081421202 0.073947802 0.048478, + -0.0053918599 0.070303701 0.051690999, + -0.0053918599 0.068296097 0.052978002, + -0.00267513 0.0723584 0.050512999, + -0.0053918599 0.072252497 0.050306, + -0.0081421202 0.070129603 0.051337998, + -0.0081421202 0.068128802 0.052623998, + -0.0081421202 0.0806676 0.041740999, + -0.0053918599 0.082342401 0.040220998, + -0.00267513 0.082469702 0.04042, + -0.0109179 0.080364302 0.041251, + -0.0109179 0.081813604 0.039395001, + -0.00267513 0.077792503 0.045813002, + -2.9451517e-012 0.079481803 0.044149999, + 1.0192692e-012 0.081043497 0.042350002, + 0.00267513 0.082468398 0.040419001, + 0.0053918599 0.082339898 0.040219001, + 0.0053918599 0.080876999 0.042082001, + 0.00267513 0.081002198 0.042282999, + 0.00267513 0.083837301 0.038499001, + 6.5938601e-014 0.082510799 0.040484998, + -5.6135049e-012 0.0838807 0.038564, + 0.0220857 0.082059197 0.032074001, + 0.0248404 0.081200302 0.030818, + 0.0248404 0.080019899 0.032737002, + 0.0220857 0.080859303 0.034003999, + 0.0220857 0.083159998 0.030106001, + 0.019305199 0.082808398 0.03317, + 0.019305199 0.083925501 0.031191999, + 0.0053918599 0.090399697 0.023910999, + 0.0053918599 0.089752004 0.026022, + 0.00267513 0.089899696 0.026208, + 0.0378174 0.081024297 0.00050300598, + 0.0378174 0.080609903 0.0046710102, + 0.0328326 0.083401203 0.010311, + 0.035366699 0.081933402 0.0085819997, + 0.035366699 0.0816027 0.010551, + 0.0328326 0.083052203 0.0123, + 0.0302257 0.084750399 0.0119, + 0.0248404 0.087084502 0.014649, + 0.027557701 0.085978702 0.013347, + 0.0248404 0.087423399 0.012506, + 0.0220857 0.088065997 0.015806001, + 0.0220857 0.088416703 0.013648, + 0.019305199 0.087379903 0.023014, + 0.019305199 0.086667202 0.025086001, + 0.0165099 0.088083103 0.023906, + 0.0165099 0.0887063 0.021818999, + 0.019305199 0.087992698 0.020936999, + 0.0220857 0.086557798 0.021972001, + 0.0220857 0.085858099 0.024032, + 0.0137106 0.085126497 0.032894999, + 0.0137106 0.083984099 0.03489, + 0.0165099 0.084580302 0.032120999, + 0.0165099 0.083449498 0.034108002, + 0.0137106 0.086165898 0.030867999, + 0.0165099 0.086534798 0.028054001, + 0.0165099 0.085608698 0.030099999, + 0.00267513 0.074244097 0.049033001, + -0.00267513 0.070405804 0.051897999, + -0.00267513 0.068394199 0.053185001, + 0.0220857 0.055961601 0.053316001, + 0.0248404 0.047124401 0.054035001, + 0.027557701 0.066689096 0.044351999, + 0.027557701 0.064824097 0.045619, + 0.0248404 0.069264203 0.044486001, + 0.027557701 0.062909797 0.04679, + 0.0081421202 0.0575101 0.057486001, + 0.0081421202 0.055319902 0.058137, + 0.0053918599 0.057642199 0.057842001, + 0.0109179 0.057321101 0.056976002, + 0.0109179 0.055141199 0.057629, + 0.0137106 0.054906599 0.056961998, + 0.0081421202 0.059688699 0.056726001, + 0.0220857 0.058055799 0.052549999, + 0.0248404 0.057532899 0.051213, + 0.0053918599 0.064133301 0.055241, + 0.019305199 0.064718202 0.050797001, + 0.0220857 0.060130998 0.051679999, + 0.019305199 0.066711098 0.049617998, + 0.0165099 0.067180701 0.050613001, + 0.027557701 0.0147297 0.053778, + 0.0283127 0.0125 0.053399999, + 0.026825599 0.0074999998 0.054168999, + 0.025684301 0.0125 0.054724999, + 0.027557701 0.016947299 0.053725999, + 0.0302257 0.0147137 0.052308001, + 0.0248404 0.0169785 0.055059001, + 0.0248404 0.0213801 0.054972999, + 0.0248404 0.040999301 0.054566, + 0.0220857 0.017006399 0.056242, + 0.0248404 0.0147441 0.055101, + 0.0220857 0.0147568 0.056274999, + 0.0220857 0.0214536 0.056175001, + 0.019305199 0.0415827 0.056983002, + -0.0576833 0.0551278 -0.024622999, + -0.056809202 0.0571649 -0.028865, + -0.056809202 0.057387002 -0.025369, + -0.052960701 0.0281986 -0.191, + -0.056809202 0.054285102 -0.046284001, + -0.055787299 0.058921698 -0.033445001, + -0.055787299 0.059335299 -0.029872, + -0.0220857 0.066166297 0.048466001, + -0.0248404 0.067432597 0.045862999, + -0.0248404 0.065537699 0.047134001, + -0.019305199 0.068657801 0.048349999, + -0.0220857 0.068086997 0.047191001, + -0.0248404 0.069270797 0.044498999, + -0.0081421202 0.053122401 0.058685999, + -0.0109179 0.055140398 0.057634, + -0.0109179 0.052953601 0.058180001, + -0.0053918599 0.057642199 0.057844002, + -0.0053918599 0.0598283 0.057085, + -0.0081421202 0.05751 0.057489999, + -0.0081421202 0.055319302 0.058141001, + -0.0053918599 0.055444401 0.058495, + -0.00267513 0.0577197 0.058052, + -0.00267513 0.059909899 0.057294, + -0.0165099 0.048144501 0.057487, + -0.0165099 0.046003599 0.057735998, + -0.0137106 0.048386399 0.058306001, + -0.0137106 0.050557401 0.057962, + -0.0165099 0.050298799 0.05714, + -0.019305199 0.047854401 0.056506, + -0.019305199 0.0457335 0.056759998, + 0.0532961 0.059834499 0.0050959899, + 0.0546159 0.0571055 0.003701, + 0.0532961 0.060640302 0.0034650001, + 0.051830001 0.063325599 0.0046620001, + 0.051830001 0.0640212 0.0029450101, + 0.0532961 0.061370701 0.00180099, + 0.0576833 0.0542823 -0.034878999, + 0.056809202 0.056349698 -0.035863999, + 0.0576833 0.053780299 -0.038293999, + 0.058412101 0.051754601 -0.037388999, + 0.056809202 0.0568063 -0.032372002, + 0.055787299 0.0593169 -0.029879, + 0.059445001 0.023042399 0.005506, + 0.059445001 0.018469 0.0072579999, + 0.058998398 0.0304402 0.0059709898, + 0.059445001 0.0275362 0.0037740001, + 0.059757002 0.017162601 0.00489301, + 0.048467699 0.056666501 0.024005, + 0.0465803 0.059510499 0.025489001, + 0.048467699 0.058087699 0.022717001, + 0.0465803 0.058036301 0.026786, + 0.048467699 0.055195902 0.025217, + 0.050219599 0.05525 0.021128999, + 0.050219599 0.053835198 0.022333, + 0.0465803 0.0647939 0.019591, + 0.0465803 0.063574702 0.021163, + 0.044564299 0.066353701 0.0222, + 0.044564299 0.0675423 0.020554001, + 0.0465803 0.0659381 0.017964, + 0.048467699 0.063171797 0.016879, + 0.048467699 0.062000301 0.018433001, + 0.0576833 0.054670502 -0.031463001, + 0.058412101 0.052191399 -0.034047, + 0.058412101 0.052518699 -0.030708, + 0.059757002 0.0459713 -0.032428999, + 0.058998398 0.050375 -0.030091999, + 0.058412101 0.052848399 -0.024133001, + 0.058412101 0.0527426 -0.027369, + 0.059445001 0.048242498 -0.026629001, + 0.059445001 0.048242401 -0.029689999, + 0.059757002 0.046034899 -0.029429, + 0.059757002 0.0458568 -0.026418, + 0.059445001 0.047992401 -0.023558, + 0.058998398 0.050473999 -0.023798, + 0.058998398 0.0505381 -0.02692, + -0.0109179 0.092656098 0.0032230101, + -0.0109179 0.092842102 -0.001355, + -0.0137106 0.092127301 0.0026970101, + -0.0081421202 0.093058899 0.0036230001, + -0.0109179 0.092307799 0.0077790101, + -0.0081421202 0.093252197 -0.00096699502, + -0.0137106 0.091789097 0.0072380099, + -0.0053918599 0.091784902 0.017521, + -0.0053918599 0.091393702 0.019724, + 4.0888824e-012 0.093193002 0.0087019997, + -0.00267513 0.092615098 0.013196, + -0.00267513 0.093140401 0.0086470004, + 0.00267513 0.093139596 0.0086460002, + 8.4302563e-013 0.093558699 0.0041200002, + 0.00267513 0.092614397 0.013195, + 0.0053918599 0.091783799 0.017519999, + 0.0165099 0.091475099 -0.011614, + 0.019305199 0.090825498 -0.0032589999, + 0.019305199 0.090816297 -0.0077889999, + 0.0220857 0.089885898 -0.0041470001, + 0.019305199 0.090674497 0.001258, + 0.0165099 0.091633201 -0.0070540002, + 0.0220857 0.0897514 0.000341003, + 0.0137106 0.091287702 0.011741, + 0.0165099 0.091629297 -0.0024989899, + 0.0165099 0.091464199 0.00204201, + 0.0109179 0.0926525 0.0032209901, + 0.0081421202 0.093249798 -0.00096699502, + 0.0137106 0.092122801 0.00269501, + 0.0109179 0.092304103 0.0077760001, + 0.0137106 0.091784596 0.0072339899, + 0.0109179 0.092838898 -0.001356, + 0.0137106 0.0923144 -0.0064400001, + 0.0137106 0.0922997 -0.00186501, + -0.019305199 0.088362098 -0.030351, + -0.0220857 0.088166997 -0.026621001, + 0.00267513 0.092246503 -0.023603, + 0.0053918599 0.091281898 -0.028294999, + 0.00267513 0.091463603 -0.028167, + 0.0081421202 0.093280002 -0.0055709998, + 0.0109179 0.092862397 -0.0059470101, + 0.0081421202 0.091759801 -0.023963001, + 0.0053918599 0.092066497 -0.023736, + 0.0053918599 0.093147598 -0.014544, + 0.00267513 0.0933237 -0.0144, + 0.0053918599 0.093442202 -0.0099269999, + 0.0081421202 0.093145996 -0.010181, + 0.0053918599 0.092688702 -0.01915, + 0.00267513 0.092866898 -0.019012, + 0.0109179 0.092418298 -0.015139, + 0.0137106 0.0918549 -0.015599, + 0.0109179 0.091950797 -0.019723, + 0.0081421202 0.092385203 -0.019386001, + 0.0081421202 0.092847601 -0.014789, + 0.0109179 0.092722401 -0.010544, + 0.0137106 0.092166297 -0.011021, + 0.0081421202 0.092184097 0.012723, + 0.0053918599 0.092455097 0.01302, + 0.0109179 0.091796398 0.012298, + 0.0081421202 0.091518998 0.017215, + 0.0109179 0.091140099 0.016779, + -0.019305199 0.090820901 -0.0077889999, + -0.0137106 0.0923177 -0.0064400001, + -0.0165099 0.091637202 -0.0070540002, + -0.0137106 0.092168801 -0.011021, + -0.0109179 0.092864998 -0.0059470101, + -0.0109179 0.092724301 -0.010544, + -0.0137106 0.092303701 -0.00186501, + 0.019305199 0.090314403 -0.016857, + 0.0165099 0.091154397 -0.016171001, + 0.019305199 0.090646103 -0.012324, + 0.0220857 0.089332402 -0.017658001, + 0.0220857 0.089676999 -0.013156, + 0.019305199 0.089821801 -0.021376999, + 0.0165099 0.0906718 -0.020717001, + 5.0705716e-012 0.093799397 -0.0051040002, + 0.00267513 0.093743198 -0.0051540099, + -3.8433345e-012 0.093761101 -0.00048500099, + -0.027557701 0.048742201 0.052189998, + -0.0248404 0.049210399 0.053679001, + -0.0220857 0.051740699 0.054544002, + -0.0328326 0.051624399 0.047662001, + -0.0328326 0.0536041 0.046987001, + -0.0302257 0.0562906 0.048048999, + -0.0302257 0.050246298 0.050062001, + -0.059445001 0.0357894 -0.00093699602, + -0.059757002 0.034627099 -0.0040640002, + -0.059757002 0.032715201 -0.00254201, + -0.059445001 0.0337517 0.00056900003, + -0.059445001 0.037777599 -0.0026789999, + -0.058998398 0.036964301 0.0022239999, + -0.058998398 0.0390797 0.000488007, + -0.058412101 0.052535899 -0.030680999, + -0.058998398 0.0501143 -0.033332001, + -0.058998398 0.050387301 -0.030073, + -0.058412101 0.0527547 -0.027350999, + -0.0576833 0.054963201 -0.028023001, + -0.051830001 0.063975997 -0.041466001, + -0.0497806 0.033494599 -0.191, + -0.0460728 0.038435601 -0.191, + -0.0532961 0.062213901 -0.039809, + -0.0546159 0.060960401 -0.034692999, + -0.050219599 0.0665107 -0.039496001, + -0.048467699 0.0689748 -0.037581, + -0.0165099 0.082226001 0.036061, + -0.0220857 0.079572998 0.035895001, + -0.0248404 0.071045198 0.043044999, + -0.035366699 0.078583397 0.020408999, + -0.0328326 0.080738701 0.020283001, + -0.0328326 0.079920501 0.022252001, + -0.027557701 0.081306897 0.027465001, + -0.0302257 0.080210201 0.025908001, + -0.0248404 0.0812122 0.030825, + -0.0248404 0.082294099 0.028867001, + -0.027557701 0.080246001 0.029410001, + -0.0248404 0.080031797 0.032745, + -0.027557701 0.0790876 0.031316999, + -0.0220857 0.083170198 0.030111, + -0.044564299 0.051088501 0.034756999, + -0.044564299 0.049350999 0.035546999, + -0.0465803 0.050036602 0.032069001, + -0.0465803 0.048353199 0.032862999, + -0.040174201 0.054867301 0.038887002, + -0.0378174 0.055813201 0.041187, + -0.040174201 0.053047799 0.039763, + -0.040174201 0.056660902 0.037916999, + -0.0424264 0.0538642 0.036447, + -0.0424264 0.0520937 0.037324999, + -0.0302257 0.069370098 0.03991, + -0.027557701 0.068505101 0.043007001, + -0.027557701 0.070251703 0.041560002, + -0.035366699 0.060429901 0.041303001, + -0.0378174 0.0594589 0.039152998, + -0.035366699 0.058581199 0.042369999, + -0.0378174 0.057652701 0.040217001, + -0.0302257 0.064042397 0.043965999, + -0.027557701 0.064829297 0.045632999, + -0.0302257 0.062159799 0.045134, + -0.0328326 0.061331298 0.043299001, + -0.027557701 0.066695303 0.044365998, + -0.0378174 0.076282799 0.020331001, + -0.0302257 0.074081898 0.035115, + -0.0302257 0.075490601 0.033376999, + -0.027557701 0.076487698 0.034988001, + -0.035366699 0.0776949 0.022336001, + -0.0328326 0.079005502 0.024196999, + -0.019305199 0.084949002 0.029184001, + -0.0220857 0.073477499 0.042817999, + -0.019305199 0.075784802 0.042330001, + -0.019305199 0.080286302 0.037009001, + -0.0137106 0.076813303 0.044114001, + -0.0165099 0.076345697 0.043303002, + -0.0137106 0.078433901 0.042396002, + -0.0109179 0.0771892 0.044766001, + -0.0109179 0.078821301 0.043044001, + -0.0109179 0.090317897 0.021059001, + -0.0081421202 0.090687104 0.021505, + -0.0081421202 0.088757403 0.027805001, + -0.0220857 0.085067399 0.026082, + -0.0220857 0.0858652 0.024033999, + -0.019305199 0.085861698 0.027146, + -0.0220857 0.084169298 0.028108999, + -0.0248404 0.083275497 0.026877001, + -0.019305199 0.086673401 0.025087999, + -0.0378174 0.075328499 0.022211, + -0.0424264 0.070243999 0.021328, + -0.040174201 0.072838902 0.021875, + -0.040174201 0.078006297 0.0085819997, + -0.040174201 0.077541597 0.010525, + -0.040174201 0.078379899 0.0066550002, + -0.040174201 0.0769867 0.012464, + -0.0165099 0.090660103 0.011056, + -0.0165099 0.091634199 -0.0024979999, + -0.0220857 0.089866601 -0.008649, + -0.040174201 0.077140398 -0.034773, + -0.0378174 0.079121202 -0.033309001, + -0.040174201 0.077917702 -0.030631, + -0.027557701 0.085719503 -0.02843, + -0.0248404 0.087016098 -0.027472001, + -0.0248404 0.0876908 -0.023034999, + -0.0220857 0.0888298 -0.022150001, + -0.0532961 0.063950799 -0.028688001, + -0.051830001 0.066402704 -0.026368, + -0.0532961 0.064275503 -0.024964999, + -0.0546159 0.061453499 -0.03105, + -0.0546159 0.061822299 -0.027402001, + -0.044564299 0.073649101 -0.033948999, + -0.0424264 0.075838998 -0.032246999, + -0.0465803 0.073018298 -0.001925, + -0.048467699 0.070965499 -0.0043439898, + -0.048467699 0.070772097 -0.0025239999, + -0.044564299 0.075187698 -0.00155901, + -0.040174201 0.0796225 -0.011809, + -0.040174201 0.079597801 -0.0076290001, + -0.040174201 0.079628497 -0.0097169997, + -0.0424264 0.077686101 -0.00957401, + -0.0424264 0.077637598 -0.0075180102, + -0.040174201 0.079530403 -0.0055440101, + -0.0424264 0.077015497 -0.024022, + -0.0424264 0.076499097 -0.028143, + -0.044564299 0.075283803 -0.021788999, + -0.0424264 0.077387497 -0.019893, + -0.050219599 0.056629799 0.019877, + -0.0532961 0.044009302 0.021176999, + -0.048467699 0.053689301 0.026373999, + -0.050219599 0.053844601 0.022359001, + -0.050219599 0.055261299 0.021155, + -0.050219599 0.046242598 0.027185, + -0.048467699 0.048942801 0.029274, + -0.048467699 0.047315601 0.030072, + -0.050219599 0.0446615 0.027904, + -0.051830001 0.045138899 0.024216, + -0.051830001 0.043617502 0.024941999, + -0.048467699 0.040735699 0.032423999, + -0.048467699 0.0423816 0.031959001, + -0.050219599 0.039894301 0.029577, + -0.050219599 0.038315699 0.029978, + -0.048467699 0.039099999 0.032809, + -0.0465803 0.041549399 0.035176001, + -0.0465803 0.0432509 0.034724001, + -0.059445001 0.046767 -0.017516, + -0.058998398 0.049595699 -0.017554, + -0.058412101 0.0527348 -0.020947, + -0.0576833 0.055173799 -0.021342, + -0.0378174 -0.0464609 -0.166219, + -0.0378174 -0.046554599 -0.168617, + -0.035366699 -0.0483477 -0.16629601, + -0.0378174 -0.046298899 -0.16381, + -0.040174201 -0.044445299 -0.166136, + -0.040174201 -0.0442832 -0.16368601, + -0.0353618 -0.048460599 -0.171, + -0.035726301 -0.048204001 -0.171, + -0.035366699 -0.0484416 -0.16865499, + -0.034755301 -0.048887499 -0.171, + -0.034765299 -0.048901699 -0.191, + 0.0328326 0.083982296 -0.022027001, + 0.035366699 0.082298897 -0.023402, + 0.0328326 0.083413899 -0.026357001, + 0.035366699 0.082897998 -0.016959, + 0.0378174 0.081258401 -0.016396999, + 0.035366699 0.083021902 -0.014809, + 0.0328326 0.084547304 -0.015509, + 0.0378174 0.080946602 -0.020643, + 0.035366699 0.082736202 -0.019107999, + 0.0328326 0.084397398 -0.017684, + 0.027557701 0.086405501 -0.024032, + 0.0248404 0.087688901 -0.023034999, + 0.027557701 0.0869385 -0.019613, + 0.0302257 0.0855297 -0.020763, + 0.0302257 0.084979899 -0.025140001, + 0.027557701 0.085717499 -0.028429, + 0.0248404 0.087014399 -0.02747, + 0.0328326 0.084766999 -0.0089880098, + 0.0328326 0.084732004 -0.01116, + 0.035366699 0.083156399 -0.010511, + 0.0302257 0.086224899 -0.0097829998, + 0.0378174 0.081435896 -0.0079149902, + 0.035366699 0.083167203 -0.0083650099, + 0.027557701 0.087595403 -0.0063129999, + 0.0302257 0.086247496 -0.007588, + 0.035366699 0.082210198 0.006511, + 0.027557701 0.087501302 -0.00189301, + 0.027557701 0.087567799 -0.0041009998, + 0.0248404 0.088693298 -0.00070899999, + 0.0248404 0.088770702 -0.002935, + 0.027557701 0.087395899 0.00031100499, + 0.0248404 0.088576697 0.00151199, + 0.040174201 0.077531204 0.010523, + 0.0424264 0.075281702 0.010256, + 0.040174201 0.0769739 0.01246, + 0.0424264 0.075811803 0.008343, + 0.040174201 0.077997997 0.0085819997, + 0.0378174 0.079152502 0.01258, + 0.0378174 0.079643399 0.010617, + 0.027557701 0.085124999 0.017392, + 0.0248404 0.086202197 0.018724, + 0.0248404 0.086689502 0.016687, + 0.027557701 0.085597597 0.01537, + 0.0302257 0.083928302 0.015913, + 0.0302257 0.083374798 0.017935, + 0.027557701 0.083885796 0.021464, + 0.0248404 0.085615501 0.020777, + 0.0248404 0.084930703 0.022824001, + 0.027557701 0.084554002 0.019431001, + 0.027557701 0.083120301 0.023483001, + 0.0302257 0.082725197 0.019951999, + 0.0302257 0.081979401 0.021956, + 0.0546159 0.061669499 -0.0095959902, + 0.0546159 0.061900701 -0.011318, + 0.055787299 0.0594543 -0.012406, + 0.0532961 0.064118303 -0.0085770003, + -0.0053918599 0.0793221 0.043882001, + -0.0053918599 0.080879398 0.042084001, + -0.0081421202 0.079116203 0.043536998, + -0.0081421202 0.077475503 0.045263, + -0.0053918599 0.077675402 0.045609999, + -0.00267513 0.079442702 0.044084001, + -0.00267513 0.081003398 0.042284001, + -0.0165099 0.079470702 0.039806999, + -0.0137106 0.079966001 0.040607002, + -0.0165099 0.077952199 0.041590001, + -0.0165099 0.080896199 0.037962001, + -0.0137106 0.081404798 0.038756002, + 0.0109179 0.089780003 0.023146, + 0.0081421202 0.090144798 0.023596, + 0.0137106 0.088669501 0.02465, + 0.019305199 0.0723579 0.045504, + 0.0165099 0.076339401 0.043295, + 0.0165099 0.077945396 0.041583002, + 0.0137106 0.078428201 0.04239, + 0.019305199 0.075777397 0.042321, + 0.019305199 0.074106202 0.043953001, + 0.0165099 0.0691422 0.049332999, + 0.0081421202 0.079112798 0.043533999, + 0.0109179 0.078816697 0.043039002, + 0.0165099 0.074650601 0.044932999, + 0.0137106 0.076807998 0.044108, + 0.0109179 0.077185102 0.044760998, + 0.00267513 0.072357699 0.050510999, + -5.9867072e-012 0.070438899 0.051964998, + 2.4528238e-012 0.072392799 0.050579999, + 0.0053918599 0.0741335 0.048826002, + 0.00267513 0.076057203 0.047463998, + 5.5163572e-013 0.066361703 0.054439001, + 6.6201094e-012 0.068426102 0.053252999, + 0.00267513 0.066330701 0.054370001, + -0.00267513 0.066331103 0.054370999, + -0.00267513 0.0642239 0.055452, + 0.019305199 0.058511999 0.053716, + 0.019305199 0.049990099 0.056146, + 0.0165099 0.050299998 0.057133, + 0.019305199 0.0478529 0.056499999, + 0.0220857 0.0475135 0.055351, + 0.0165099 0.052458599 0.056683999, + 0.0220857 0.051743198 0.054533999, + 0.0248404 0.049212299 0.053668998, + 0.0248404 0.051301099 0.053206, + 0.0220857 0.049627699 0.054992002, + 0.0220857 0.053855799 0.053975999, + 0.019305199 0.052128799 0.055693001, + 0.0220857 0.068081997 0.047180001, + 0.0248404 0.067427002 0.045850001, + 0.0220857 0.069944501 0.045811001, + 0.0220857 0.066162199 0.048455, + 0.019305199 0.068653397 0.04834, + 0.0248404 0.065532997 0.047121, + 0.019305199 0.070538104 0.046967, + 0.0248404 0.0616026 0.049369998, + 0.0248404 0.063589104 0.048294999, + 0.027557701 0.060953099 0.047862999, + 0.027557701 0.058961801 0.048836, + 0.0248404 0.059581202 0.050342999, + 0.0220857 0.0621791 0.050707001, + 0.0220857 0.064192101 0.049631, + 0.00267513 0.062080499 0.056425001, + 0.0053918599 0.0619945 0.056214999, + 0.00267513 0.064223602 0.055450998, + 1.4721859e-012 0.062108699 0.056494001, + 0.00267513 0.059909798 0.057291999, + 0.0053918599 0.059827998 0.057082999, + -4.2180356e-012 0.064253204 0.055520002, + 0.00267513 0.0683937 0.053183999, + 0.00267513 0.0704052 0.051897001, + 0.0053918599 0.070302501 0.051688001, + 0.0053918599 0.072251 0.050303999, + 0.0053918599 0.066236198 0.054161001, + 0.0053918599 0.068295099 0.052974999, + 0.0081421202 0.061847899 0.055858999, + 0.0109179 0.059489299 0.056216002, + 0.019305199 0.0626821 0.051874001, + 0.0165099 0.065168202 0.051794, + 0.019305199 0.0606106 0.052847002, + -0.0576833 0.0531785 -0.041703001, + -0.058412101 0.0512245 -0.040725999, + -0.058412101 0.050563499 -0.044059001, + -0.0576833 0.052445699 -0.0451, + -0.0576833 0.054301199 -0.034871001, + -0.058412101 0.0522108 -0.034030002, + -0.058412101 0.051773801 -0.037381001, + -0.0576833 0.053797301 -0.038291998, + -0.0576833 0.054689702 -0.031445, + -0.056809202 0.056825001 -0.032365002, + -0.056809202 0.056366298 -0.035861999, + -0.055787299 0.0577318 -0.040564999, + -0.055787299 0.0569565 -0.044103, + -0.056809202 0.055095799 -0.042826999, + -0.056809202 0.055789702 -0.039351001, + -0.055787299 0.058387101 -0.037011001, + -0.0546159 0.0603434 -0.038325001, + -0.0546159 0.059603199 -0.041940998, + -0.0165099 0.071050197 0.047965001, + -0.0137106 0.073327303 0.047316, + -0.0137106 0.075109303 0.045756001, + -0.019305199 0.072363801 0.045513, + -0.019305199 0.0741129 0.043962002, + -0.0220857 0.071749501 0.044362999, + -0.0220857 0.069950402 0.045821998, + -0.019305199 0.0705432 0.046976998, + -0.0165099 0.072889298 0.046496, + -0.0165099 0.0746563 0.044939999, + 0.051830001 0.064636201 0.001205, + 0.051830001 0.065170698 -0.00055200199, + 0.055787299 0.0588383 -0.0090319999, + 0.0532961 0.063513599 -0.0050740102, + 0.0546159 0.061363101 -0.0078760097, + 0.0532961 0.063854598 -0.006825, + 0.0532961 0.0630951 -0.003332, + 0.051830001 0.065625198 -0.002323, + 0.0546159 0.0609813 -0.0061629899, + 0.051830001 0.066000096 -0.0041029998, + 0.0546159 0.059989899 -0.0027769899, + 0.055787299 0.057927798 -0.0057029999, + 0.0546159 0.0605237 -0.0044610002, + 0.0546159 0.059379701 -0.001112, + 0.0532961 0.0620239 0.000110001, + 0.0532961 0.062598698 -0.00160201, + 0.055787299 0.0560112 -0.00087199401, + 0.0546159 0.057935901 0.0021319999, + 0.0546159 0.0586945 0.00052600098, + 0.055787299 0.056722 -0.00245399, + 0.055787299 0.055230699 0.00067399599, + 0.056809202 0.053338401 -0.002382, + 0.056809202 0.054731 -0.0054620099, + 0.0576833 0.054501001 -0.014841, + 0.058412101 0.0527196 -0.020949, + 0.058412101 0.052323401 -0.017757, + 0.059445001 0.0476905 -0.035994999, + 0.059445001 0.048022401 -0.032795999, + 0.059757002 0.045694999 -0.035471998, + 0.059757002 0.045309801 -0.038601, + 0.059445001 0.047260702 -0.039188001, + 0.058998398 0.049718201 -0.036626, + 0.058998398 0.050096899 -0.033360001, + -0.00267513 0.091939896 0.0177, + -8.0619062e-012 0.092666604 0.013252, + -0.00267513 0.091546901 0.019904001, + 0.0053918599 0.0933384 0.0039019899, + 0.00267513 0.093504302 0.00406599, + 0.0053918599 0.092976898 0.0084770098, + 0.0081421202 0.092700101 0.0081879999, + 0.0081421202 0.093056202 0.0036219901, + 0.0053918599 0.093537003 -0.00069599901, + 0.00267513 0.093705699 -0.00053700298, + 0.00267513 0.091546401 0.019904001, + 1.6896639e-012 0.091596797 0.019963, + 0.00267513 0.091095902 0.021999, + 0.00267513 0.0919393 0.017698999, + 0.0053918599 0.0913928 0.019723, + 3.7901288e-012 0.0919903 0.017757, + 0.0053918599 0.090944096 0.021817001, + -0.019305199 0.089170903 -0.025877999, + -0.0165099 0.089228198 -0.029741, + -0.0137106 0.089950398 -0.029232999, + -0.027557701 0.087591402 -0.0085279997, + -0.019305199 0.089823298 -0.021377999, + -0.0165099 0.090029702 -0.025242999, + -0.0137106 0.090745702 -0.024714001, + -0.027557701 0.054906599 0.050489999, + -0.0302257 0.054285899 0.048820999, + -0.0302257 0.052269299 0.049490999, + -0.027557701 0.056944899 0.049720999, + -0.0248404 0.057534002 0.051226001, + -0.0248404 0.053385001 0.052655999, + -0.0248404 0.051298302 0.053218, + -0.027557701 0.050799999 0.051723, + -0.027557701 0.052856501 0.051157001, + -0.0248404 0.0554654 0.051993001, + -0.0220857 0.053854201 0.053987, + -0.0220857 0.0559614 0.053326, + -0.058412101 0.0481118 -0.0056639998, + -0.058998398 0.044762101 -0.0061410102, + -0.058412101 0.046442099 -0.00299699, + -0.0532961 0.062919497 -0.036114998, + -0.051830001 0.064777203 -0.037716001, + -0.0532961 0.063498601 -0.032405999, + -0.019305199 0.082817703 0.033176001, + -0.0220857 0.082069799 0.032081001, + -0.019305199 0.083934397 0.031196, + -0.019305199 0.0816008 0.035115998, + -0.0165099 0.083457403 0.034113001, + -0.0220857 0.080869898 0.034010999, + -0.0165099 0.084587999 0.032124002, + -0.035366699 0.0793764 0.018457999, + -0.0378174 0.078581698 0.014543, + -0.027557701 0.083130702 0.023487, + -0.0302257 0.081990801 0.02196, + -0.0302257 0.081149504 0.023946, + -0.027557701 0.082268402 0.025488, + -0.0248404 0.084156699 0.024862001, + -0.0248404 0.084938601 0.022826999, + -0.0424264 0.0556092 0.035478, + -0.044564299 0.052807499 0.033877, + -0.0424264 0.057321701 0.034419, + -0.044564299 0.057785802 0.030710001, + -0.0378174 0.061224598 0.037996002, + -0.0328326 0.071555197 0.034993999, + -0.0302257 0.071016699 0.038387001, + -0.0302257 0.072589003 0.036787, + -0.035366699 0.0673481 0.036125999, + -0.035366699 0.065703399 0.037549999, + -0.0328326 0.068401702 0.038098, + -0.0328326 0.070015199 0.036584001, + -0.035366699 0.0689255 0.034621999, + -0.0378174 0.066213101 0.034001999, + -0.0328326 0.064976603 0.040876999, + -0.0328326 0.0631781 0.042135, + -0.035366699 0.062237699 0.040142, + -0.035366699 0.063997798 0.03889, + -0.0328326 0.066720001 0.039530002, + -0.0302257 0.065876298 0.042704001, + -0.0302257 0.067654401 0.04135, + -0.035366699 0.071858197 0.031394999, + -0.035366699 0.070430502 0.033043001, + -0.0328326 0.073016897 0.033333, + -0.0328326 0.074395299 0.031608, + -0.040174201 0.071736902 0.023659, + -0.019305199 0.077374399 0.040623002, + -0.019305199 0.078876503 0.038846999, + -0.0081421202 0.089502901 0.025703, + -0.0081421202 0.0901464 0.023596, + -0.0109179 0.087562896 0.029425999, + -0.0137106 0.086171702 0.03087, + -0.0165099 0.085615799 0.030104, + -0.0165099 0.088709697 0.021818999, + -0.019305199 0.087996602 0.020936999, + -0.019305199 0.087384902 0.023015, + -0.0137106 0.0898332 0.020474, + -0.0165099 0.089657404 0.017678, + -0.0165099 0.0892305 0.019747, + -0.0137106 0.090267703 0.018397, + -0.0137106 0.090645596 0.016212, + -0.0165099 0.090028003 0.015502, + -0.044564299 0.067561999 0.020571001, + -0.044564299 0.0686711 0.018872, + -0.0424264 0.069094203 0.023046, + -0.044564299 0.066372201 0.022219, + -0.0378174 0.067751601 0.032508001, + -0.0378174 0.069218799 0.030941, + -0.051830001 0.0666591 -0.0094170095, + -0.050219599 0.068842798 -0.0068439902, + -0.0424264 0.0762619 0.0064249998, + -0.040174201 0.079287603 -0.00139301, + -0.0424264 0.076878801 0.0026229999, + -0.040174201 0.078669503 0.0047319899, + -0.0424264 0.076611601 0.0045210002, + -0.044564299 0.074992299 0.00039999399, + -0.0424264 0.077096798 0.000634995, + -0.040174201 0.078908898 0.00271899, + -0.048467699 0.069709599 0.0029819901, + -0.0378174 0.077142797 0.018423, + -0.040174201 0.0763411 0.014392, + -0.0378174 0.077908799 0.016492, + -0.019305199 0.0885076 0.018874999, + -0.019305199 0.090776101 -0.00099699397, + -0.0220857 0.089016899 0.0092580002, + -0.019305199 0.089902602 0.010227, + -0.027557701 0.083894603 0.021466, + -0.035366699 0.0809756 -0.031938002, + -0.0328326 0.082696803 -0.030665001, + -0.040174201 0.079384401 -0.018093999, + -0.040174201 0.079500496 -0.015998, + -0.0378174 0.081129096 -0.018521, + -0.0378174 0.081267498 -0.016396999, + -0.0248404 0.088772602 -0.0096349902, + -0.0220857 0.089793801 -0.010902, + -0.0328326 0.084403299 -0.017684, + -0.0302257 0.085929804 -0.016373999, + -0.0328326 0.084554203 -0.01551, + -0.035366699 0.082742497 -0.019109, + -0.035366699 0.082905397 -0.016959, + -0.0465803 0.072646096 -0.027771, + -0.0465803 0.072071098 -0.031759001, + -0.0465803 0.073082402 -0.023771999, + -0.044564299 0.074880302 -0.025854001, + -0.048467699 0.070793197 -0.025834, + -0.044564299 0.074335299 -0.02991, + -0.0378174 0.081368603 -0.014273, + -0.0378174 0.081432402 -0.01215, + -0.035366699 0.083030403 -0.014809, + -0.0378174 0.0806178 0.004683, + -0.055787299 0.044319998 0.013234, + -0.056809202 0.043015402 0.010061, + -0.056809202 0.0405154 0.011778, + -0.055787299 0.0492558 0.008963, + -0.056809202 0.0454248 0.0080690002, + -0.0546159 0.044244599 0.017268, + -0.055787299 0.0416926 0.014945, + -0.0546159 0.042858899 0.018082, + -0.0546159 0.0456126 0.016378, + -0.0532961 0.0454574 0.020367, + -0.051830001 0.0496068 0.021559, + -0.0532961 0.046887599 0.019478999, + -0.050219599 0.052385401 0.023486, + -0.050219599 0.0493627 0.025498999, + -0.051830001 0.048139501 0.022523999, + -0.050219599 0.050889298 0.024533, + -0.050219599 0.047811698 0.026382999, + -0.051830001 0.046648201 0.02341, + -0.048467699 0.055204999 0.025241001, + -0.0465803 0.0565206 0.028029, + -0.044564299 0.0593637 0.029483, + -0.0576833 0.049909599 -0.0025460101, + -0.0576833 0.0514616 -0.0054310001, + -0.0576833 0.046139799 0.0026380001, + -0.0576833 0.048126101 0.00015400699, + -0.058412101 0.044575401 -0.00053799403, + -0.058412101 0.042546 0.001692, + -0.0576833 0.043986399 0.0048830002, + -0.056809202 0.047701899 0.00580901, + -0.058998398 0.047656499 -0.011576, + -0.058998398 0.048753701 -0.014515, + -0.059445001 0.045768201 -0.014625, + -0.059445001 0.044536099 -0.011865, + -0.058998398 0.0463183 -0.0087740002, + -0.058412101 0.049556799 -0.0085070003, + -0.055787299 0.059797902 -0.02273, + -0.056809202 0.057497401 -0.021898, + -0.058412101 0.052345399 -0.017749, + -0.0576833 0.054985698 -0.018091001, + -0.056809202 0.054758299 -0.00544299, + -0.055787299 0.0579536 -0.00569, + -0.055787299 0.057388101 -0.0040509901, + -0.051830001 0.066754602 -0.011255, + 0.0378174 0.081387803 -0.0058019999, + 0.0302257 0.085061103 0.0097890003, + 0.0328326 0.083695598 0.0082189897, + 0.0328326 0.084371798 0.00181599, + 0.0328326 0.084180802 0.0039590001, + 0.0302257 0.085952997 0.00115401, + 0.035366699 0.082661301 0.002295, + 0.027557701 0.087069102 0.0046979999, + 0.027557701 0.0872517 0.002508, + 0.0302257 0.085783698 0.0033249999, + 0.0302257 0.085577697 0.0054880101, + 0.027557701 0.086849302 0.006881, + 0.0248404 0.088226303 0.0059349998, + 0.0248404 0.088420898 0.00372701, + 0.0109179 0.088400997 0.027342999, + 0.0109179 0.089141302 0.025248, + 0.0137106 0.087936603 0.026738999, + 0.0137106 0.087102301 0.028813999, + 0.0081421202 0.089500703 0.025703, + 2.5411628e-012 0.0891954 0.028377, + 0.0053918599 0.084971398 0.036332998, + 0.0081421202 0.088754803 0.027804, + 0.0109179 0.087558798 0.029425001, + 0.0081421202 0.084742099 0.035998002, + 0.0109179 0.084414199 0.035519, + 0.0137106 0.073323101 0.047309998, + 0.0137106 0.075104602 0.04575, + 0.0165099 0.072884202 0.046487998, + 0.0165099 0.071045801 0.047956001, + 0.0109179 0.075469799 0.046406999, + 0.0053918599 0.077673398 0.045607999, + 0.0053918599 0.075942799 0.047258001, + 0.00267513 0.077791497 0.045812, + 0.00267513 0.0794416 0.044082999, + 0.0053918599 0.079319902 0.043880001, + 0.0081421202 0.077472404 0.045258999, + 0.0081421202 0.075748198 0.046907999, + 0.0165099 0.056764301 0.055477001, + 0.0165099 0.0589022 0.054714002, + 0.019305199 0.056394201 0.054480001, + 0.019305199 0.054264899 0.055137999, + 0.0165099 0.054614801 0.056132998, + 0.0137106 0.0570729 0.056308001, + 0.0137106 0.059227601 0.055546001, + 0.0109179 0.061638199 0.055348001, + 0.0081421202 0.063979603 0.054884002, + 0.0081421202 0.0660754 0.053803999, + 0.0109179 0.067887299 0.052111, + 0.0137106 0.067572303 0.051442999, + 0.0081421202 0.068127297 0.052618999, + 0.0081421202 0.0701278 0.051332999, + 0.0109179 0.071809903 0.049445, + 0.0137106 0.071469299 0.048781, + 0.0109179 0.073676199 0.047970001, + 0.0109179 0.069877803 0.050825998, + 0.0081421202 0.072069503 0.04995, + 0.0137106 0.069549903 0.050159998, + 0.0081421202 0.073945299 0.048473999, + 0.0576833 0.0551158 -0.024641, + 0.0576833 0.054946199 -0.028051, + 0.056809202 0.057146002 -0.028881, + 0.055787299 0.059781399 -0.022756999, + 0.0546159 0.062170301 -0.020141, + 0.056809202 0.057370301 -0.025397001, + 0.055787299 0.0596085 -0.026314, + 0.0546159 0.0620481 -0.023770001, + 0.056809202 0.057476599 -0.018549999, + 0.056809202 0.057485599 -0.021916, + 0.0576833 0.055164199 -0.02134, + 0.0576833 0.0549707 -0.018093999, + 0.056809202 0.057218399 -0.015243, + 0.055787299 0.059776802 -0.015776001, + 0.055787299 0.059842799 -0.019206, + -0.0328326 0.084740803 -0.01116, + -0.0302257 0.086232997 -0.0097820004, + -0.035366699 0.0831175 -0.012659, + -0.0328326 0.084666699 -0.013335, + -0.0165099 0.091156401 -0.016171001, + -0.0165099 0.090673096 -0.020717001, + -0.019305199 0.090316802 -0.016857, + -0.0165099 0.091477998 -0.011614, + -0.0137106 0.091856599 -0.015599, + -0.0137106 0.091381699 -0.020166, + -0.019305199 0.0906495 -0.012325, + -0.050219599 0.067920402 -0.031824999, + -0.051830001 0.065448903 -0.033945002, + -0.050219599 0.067281798 -0.035670001, + -0.048467699 0.070322797 -0.029764, + -0.050219599 0.068425998 -0.027967, + -0.051830001 0.065990902 -0.030161001, + -0.048467699 0.069716603 -0.033682, + -0.0465803 0.053341798 0.03022, + -0.044564299 0.056162801 0.031851999, + -0.0465803 0.054950301 0.029167, + -0.044564299 0.054501198 0.032908998, + -0.0465803 0.051701698 0.031188, + -0.048467699 0.052136101 0.027424, + -0.048467699 0.050551798 0.028391, + -0.040174201 0.0618168 0.034463, + -0.040174201 0.063438296 0.033137999, + -0.0424264 0.0606222 0.032037999, + -0.0424264 0.0589948 0.033271, + -0.040174201 0.060142402 0.035703, + -0.0378174 0.062943198 0.036749002, + -0.0378174 0.064608201 0.035417002, + -0.035366699 0.073203698 0.029684, + -0.0328326 0.075686 0.029825, + -0.0248404 0.077385202 0.036437999, + -0.0220857 0.078181699 0.037725002, + -0.027557701 0.075051501 0.036736999, + -0.0109179 0.089782298 0.023146, + -0.0137106 0.089304201 0.022554001, + -0.0165099 0.088087402 0.023907, + -0.0465803 0.068911001 0.012816, + -0.040174201 0.070548497 0.025395, + -0.0378174 0.070609801 0.029307, + -0.0378174 0.071919903 0.02761, + -0.0546159 0.0587207 0.00054299901, + -0.0546159 0.059405901 -0.001097, + -0.055787299 0.056748699 -0.0024359999, + -0.050219599 0.068109602 -0.001442, + -0.050219599 0.057944499 0.018528, + -0.044564299 0.073513299 0.0079380004, + -0.0424264 0.075295299 0.01026, + -0.0424264 0.075822897 0.00834399, + -0.044564299 0.074012101 0.0060470002, + -0.0465803 0.071648598 0.0055089998, + -0.0465803 0.071094401 0.0073640002, + -0.0465803 0.072501101 0.00177499, + -0.048467699 0.070501402 -0.00069799798, + -0.0465803 0.072799198 -7.8002908e-005, + -0.0465803 0.072117403 0.00364301, + -0.044564299 0.074424103 0.0041519902, + -0.048467699 0.070147 0.00114301, + -0.044564299 0.074748598 0.0022740001, + -0.040174201 0.075603999 0.016302001, + -0.044564299 0.072252899 0.011683, + -0.0424264 0.073972099 0.014052, + -0.044564299 0.071489602 0.013526, + -0.044564299 0.072927199 0.009819, + -0.0424264 0.0746786 0.012165, + -0.048467699 0.069188498 0.0048110001, + -0.0532961 0.060665902 0.00348199, + -0.048467699 0.068582997 0.0066249999, + -0.0465803 0.069726102 0.011022, + -0.0465803 0.0704538 0.009203, + -0.0248404 0.085621998 0.020778, + -0.0220857 0.087163001 0.019905999, + -0.0248404 0.0862073 0.018724, + -0.019305199 0.090831198 -0.0032579999, + -0.019305199 0.090545699 0.003513, + -0.0165099 0.091469601 0.00204401, + -0.0165099 0.0911441 0.0065649999, + -0.019305199 0.090370499 0.0057589998, + -0.019305199 0.090680897 0.00125999, + -0.027557701 0.084561102 0.019432001, + -0.027557701 0.085130602 0.017392, + -0.0302257 0.082734898 0.019955, + -0.0328326 0.081460901 0.018294999, + -0.035366699 0.080074899 0.016488999, + -0.0302257 0.083382599 0.017936001, + -0.0328326 0.083963402 0.0061089899, + -0.035366699 0.0822175 0.0065229898, + -0.0378174 0.0803582 0.006722, + -0.0378174 0.080047503 0.0086670099, + -0.0248404 0.088409998 -0.016344, + -0.027557701 0.087150402 -0.017399, + -0.0248404 0.0882098 -0.018578, + -0.0220857 0.089335099 -0.017658999, + -0.0220857 0.089681 -0.013156, + -0.027557701 0.087449498 -0.012964, + -0.0248404 0.088691399 -0.011872, + -0.027557701 0.087540001 -0.010746, + -0.0302257 0.086069703 -0.014177, + -0.027557701 0.087319598 -0.015182, + -0.0248404 0.088570602 -0.014109, + -0.0302257 0.0861708 -0.011979, + -0.048467699 0.071127497 -0.021899, + -0.050219599 0.069143102 -0.016375, + -0.050219599 0.069037601 -0.020236, + -0.051830001 0.0668348 -0.018781999, + -0.051830001 0.066855803 -0.015003, + -0.050219599 0.069116101 -0.012528, + -0.050219599 0.068964504 -0.0087139998, + -0.0302257 0.085793398 0.00333701, + -0.0378174 0.081315398 -0.0036830001, + -0.0378174 0.081193298 -0.001577, + -0.0378174 0.080740303 -0.022764999, + -0.040174201 0.079042204 -0.022283999, + -0.040174201 0.078553103 -0.026465001, + -0.0378174 0.0809533 -0.020644, + -0.035366699 0.082541801 -0.021257, + -0.035366699 0.082027003 -0.025544001, + -0.035366699 0.081713103 -0.027681001, + -0.0378174 0.079877898 -0.029108001, + -0.0378174 0.080490001 -0.024883, + -0.035366699 0.082303204 -0.023402, + -0.0328326 0.083416402 -0.026357001, + -0.055787299 0.048075099 0.010134, + -0.055787299 0.046855502 0.011238, + -0.0532961 0.0535684 0.013914, + -0.0546159 0.051991299 0.010842, + -0.0546159 0.050795201 0.012088, + -0.0532961 0.054771598 0.01259, + -0.051830001 0.055116799 0.016930001, + -0.051830001 0.056376401 0.015594, + -0.0546159 0.046957299 0.015414, + -0.0532961 0.048294201 0.018515, + -0.051830001 0.051043998 0.020515, + -0.0465803 0.059522901 0.025512001, + -0.048467699 0.0581006 0.022741999, + -0.048467699 0.056677401 0.02403, + -0.0465803 0.058046799 0.02681, + -0.055787299 0.0503924 0.0077280002, + -0.056809202 0.049807601 0.00330099, + -0.0532961 0.064424202 -0.012049, + -0.058412101 0.051685799 -0.014588, + -0.058412101 0.050753102 -0.011494, + -0.0576833 0.052757099 -0.008467, + -0.0576833 0.054522701 -0.014833, + -0.0576833 0.053780802 -0.011614, + -0.056809202 0.055872802 -0.0086439997, + 0.035366699 0.082835898 0.00017500301, + 0.0378174 0.081302799 -0.003694, + 0.035366699 0.082974598 -0.001951, + 0.0328326 0.084526397 -0.00033299299, + 0.0302257 0.086084202 -0.001024, + 0.00267513 0.087334901 0.032476999, + 0.0053918599 0.086135 0.034325, + 0.00267513 0.086272798 0.03452, + 7.1718499e-012 0.087381199 0.032540001, + -1.6261878e-013 0.088339999 0.030469, + 0.0053918599 0.089002296 0.028125999, + 0.00267513 0.088293001 0.030406, + 0.00267513 0.089147598 0.028315, + 0.0081421202 0.086955599 0.031955, + 0.0081421202 0.085900798 0.033992998, + 0.0053918599 0.087194502 0.032283999, + 0.0053918599 0.088150002 0.030215001, + 0.0081421202 0.087906703 0.029890001, + 0.0109179 0.086613998 0.031484999, + 0.0109179 0.085565902 0.033518001, + 0.0137106 0.063471101 0.053704001, + 0.0109179 0.063759699 0.054373998, + 0.0137106 0.061363 0.054678001, + 0.0165099 0.063112304 0.052871998, + 0.0137106 0.065543503 0.052625, + 0.0109179 0.0658454 0.053293999, + 0.0165099 0.0610209 0.053846002, + -0.035366699 0.075632498 0.026095999, + -0.0378174 0.073144801 0.025857, + -0.0378174 0.074281797 0.024055, + -0.035366699 0.074462697 0.027915001, + -0.035366699 0.076710597 0.024234001, + -0.0328326 0.076886199 0.027991001, + -0.0328326 0.077993497 0.026112, + -0.0248404 0.074377201 0.039887998, + -0.0220857 0.076698802 0.039492, + -0.0220857 0.075129002 0.041191999, + -0.0248404 0.075924203 0.038197, + -0.0248404 0.072749101 0.041506, + -0.027557701 0.0735301 0.038419001, + -0.027557701 0.071928397 0.040029, + -0.0137106 0.087940998 0.02674, + -0.0137106 0.0886731 0.02465, + -0.0165099 0.087364703 0.025989, + -0.0165099 0.086541101 0.028057, + -0.0137106 0.087107502 0.028816, + -0.0109179 0.088404499 0.027345, + -0.0109179 0.089144103 0.025248, + -0.0424264 0.066551797 0.026316, + -0.0424264 0.067862101 0.024711, + -0.040174201 0.067924403 0.028696001, + -0.040174201 0.069276199 0.027076, + -0.0424264 0.063714802 0.029327, + -0.0424264 0.0651678 0.027856, + -0.044564299 0.062360201 0.026791999, + -0.044564299 0.0608906 0.028176, + -0.0424264 0.0621976 0.030722, + -0.040174201 0.065000601 0.031732999, + -0.040174201 0.066497602 0.030251, + -0.0546159 0.060015202 -0.0027640101, + -0.051830001 0.066306397 -0.0058849901, + -0.051830001 0.066519499 -0.0076540099, + -0.051830001 0.066013597 -0.0041009998, + -0.050219599 0.068433598 -0.0032550001, + -0.050219599 0.068675801 -0.0050529898, + -0.050219599 0.059199799 0.017112, + -0.051830001 0.0587175 0.012729, + -0.051830001 0.057578102 0.014192, + -0.0424264 0.072286502 0.017757, + -0.0424264 0.073174797 0.015919, + -0.044564299 0.070637003 0.015343, + -0.044564299 0.069696799 0.017127, + -0.0424264 0.071308799 0.019563001, + -0.040174201 0.073852099 0.020049, + -0.040174201 0.074774399 0.01819, + -0.0465803 0.0670252 0.016302001, + -0.0465803 0.068009898 0.014578, + -0.048467699 0.063191898 0.016899001, + -0.0465803 0.065958701 0.017982, + -0.0465803 0.064813197 0.019610999, + -0.048467699 0.062018801 0.018454, + -0.050219599 0.060391501 0.015632, + -0.051830001 0.064045198 0.0029569999, + -0.050219599 0.066648498 0.0039579901, + -0.0532961 0.062048599 0.00012300099, + -0.0532961 0.061396301 0.00181599, + -0.050219599 0.065259904 0.0074720001, + -0.051830001 0.063350499 0.004677, + -0.051830001 0.062575802 0.0063680001, + -0.050219599 0.065995999 0.0057270098, + -0.048467699 0.067116 0.010189, + -0.048467699 0.067892298 0.0084190099, + -0.051830001 0.061722901 0.0080239996, + -0.050219599 0.0644418 0.0091869999, + -0.048467699 0.0662558 0.011928, + -0.0220857 0.087662503 0.017855, + -0.019305199 0.088925399 0.016814999, + -0.019305199 0.089287303 0.01465, + -0.0248404 0.088816099 -0.0051649902, + -0.0220857 0.089892402 -0.0041470001, + -0.0248404 0.088814199 -0.0073990002, + -0.0220857 0.089899503 -0.006397, + -0.027557701 0.087603502 -0.0063120001, + -0.0220857 0.089260504 0.0070409998, + -0.0220857 0.089466102 0.0048159901, + -0.0220857 0.089845397 -0.001899, + -0.027557701 0.086857498 0.0068939999, + -0.0302257 0.085344099 0.0076580001, + -0.027557701 0.086309999 0.011228, + -0.0248404 0.088001497 0.0081460001, + -0.0302257 0.0855866 0.00550301, + -0.027557701 0.087077901 0.0047089998, + -0.0248404 0.088234201 0.0059450101, + -0.0328326 0.082088098 0.016294001, + -0.0302257 0.083934501 0.015913, + -0.0302257 0.084389597 0.013906, + -0.0328326 0.083406404 0.010313, + -0.0302257 0.084755197 0.011902, + -0.0302257 0.085067399 0.0097989999, + -0.0328326 0.083702497 0.0082299998, + -0.035366699 0.081938997 0.0085840002, + -0.0328326 0.083720498 -0.024195001, + -0.0302257 0.084982201 -0.025140001, + -0.027557701 0.086407602 -0.024033001, + -0.0465803 0.073438101 -0.007797, + -0.048467699 0.071112603 -0.0062449998, + -0.0465803 0.073190004 -0.003856, + -0.048467699 0.071313299 -0.010123, + -0.044564299 0.0754814 -0.00556, + -0.044564299 0.075643502 -0.0095969997, + -0.0465803 0.073537797 -0.015767001, + -0.048467699 0.071325399 -0.017964, + -0.048467699 0.071386904 -0.014036, + -0.0465803 0.073556803 -0.011773, + -0.0465803 0.073379703 -0.019768, + -0.044564299 0.075665399 -0.013654, + -0.044564299 0.075545497 -0.017719001, + -0.0378174 0.081400499 -0.0057940101, + -0.035366699 0.082671702 0.0023119999, + -0.035366699 0.082461402 0.0044240002, + -0.0378174 0.081035502 0.00052099599, + -0.0328326 0.084190503 0.003974, + -0.0465803 0.062300801 0.022694999, + -0.044564299 0.0637668 0.025334001, + -0.0465803 0.060942799 0.024139, + -0.0465803 0.063592397 0.021183001, + -0.048467699 0.060776301 0.019950001, + -0.044564299 0.065105602 0.023808001, + -0.048467699 0.059468701 0.02138, + -0.0532961 0.051012799 0.016359, + -0.0546159 0.049554002 0.013268, + -0.0532961 0.0523136 0.015171, + -0.0532961 0.049671199 0.017473999, + -0.051830001 0.052445099 0.019393999, + -0.0546159 0.048273001 0.014377, + -0.051830001 0.053804599 0.018198, + -0.056809202 0.051704701 0.000567001, + -0.055787299 0.056037299 -0.00085200497, + -0.056809202 0.053363599 -0.00235899, + -0.0546159 0.062186401 -0.020114999, + -0.0532961 0.064493001 -0.013855, + -0.0532961 0.064542502 -0.017535999, + -0.0532961 0.0638685 -0.00682201, + -0.055787299 0.0588594 -0.0090239998, + -0.056809202 0.056696899 -0.011921, + -0.055787299 0.058444001 -0.0073489998, + -0.0546159 0.061380502 -0.0078699999, + 0.0328326 0.084722698 -0.0046519898, + 0.035366699 0.083076201 -0.0040839999, + 0.035366699 0.0831405 -0.0062230099, + 0.0328326 0.084643498 -0.0024900101, + 0.0328326 0.084763899 -0.00681799, + 0.0302257 0.086177103 -0.003207, + 0.0302257 0.086231597 -0.0053960001, + -0.0546159 0.061001901 -0.0061550001, + -0.0532961 0.063530602 -0.0050690002, + -0.0546159 0.060547002 -0.0044510001, + -0.050219599 0.062567398 0.012505, + -0.050219599 0.063543603 0.010867, + -0.051830001 0.060793798 0.0096399998, + -0.050219599 0.061515398 0.014095, + -0.051830001 0.059790801 0.01121, + -0.048467699 0.0642915 0.015289, + -0.048467699 0.0653136 0.01363, + -0.0248404 0.087088503 0.014651, + -0.027557701 0.085983098 0.013349, + -0.0248404 0.087428503 0.012514, + -0.0220857 0.088069603 0.015807001, + -0.0248404 0.086693697 0.016686, + -0.027557701 0.085602097 0.015369, + -0.0220857 0.0884213 0.013655, + -0.027557701 0.087510303 -0.00188901, + -0.027557701 0.087576501 -0.0040989998, + -0.0248404 0.088778503 -0.002933, + -0.0248404 0.088584997 0.001517, + -0.0248404 0.088701501 -0.00070599403, + -0.027557701 0.0874051 0.000315994, + -0.027557701 0.087260902 0.0025160101, + -0.0248404 0.088429101 0.00373399, + -0.0220857 0.089632198 0.0025829901, + -0.0220857 0.089758702 0.000343994, + -0.035366699 0.081191197 0.01252, + -0.0328326 0.082620598 0.014288, + -0.035366699 0.0806797 0.014507, + -0.035366699 0.081608601 0.01055, + -0.0378174 0.079651199 0.010616, + -0.0328326 0.083057597 0.012299, + -0.0378174 0.079162396 0.012582, + -0.0302257 0.085533403 -0.020764001, + -0.0302257 0.085277103 -0.022954, + -0.0328326 0.083986297 -0.022027999, + -0.0328326 0.084214002 -0.019857001, + -0.0302257 0.085750997 -0.01857, + -0.027557701 0.086941898 -0.019614, + -0.0378174 0.081459001 -0.010029, + -0.0378174 0.081448399 -0.0079100002, + -0.035366699 0.0831668 -0.01051, + -0.035366699 0.083178297 -0.0083619999, + -0.0328326 0.084776603 -0.0089870002, + -0.0302257 0.0862564 -0.00758701, + -0.0328326 0.084733501 -0.0046470002, + -0.035366699 0.0831521 -0.0062179998, + -0.035366699 0.0830881 -0.0040770001, + -0.0328326 0.084774204 -0.006815, + -0.0302257 0.086186998 -0.0032029999, + -0.0302257 0.086241104 -0.0053930101, + -0.0328326 0.084537402 -0.000324005, + -0.0302257 0.086094297 -0.00101801, + -0.0302257 0.085963003 0.00116299, + -0.0328326 0.084654503 -0.002483, + -0.0328326 0.084382303 0.00183, + -0.035366699 0.0829864 -0.00194099, + -0.035366699 0.0828472 0.00018899501, + -0.055787299 0.0597861 -0.015776999, + -0.0546159 0.062189601 -0.016503001, + -0.055787299 0.059854399 -0.019188, + -0.056809202 0.057486098 -0.018552, + -0.055787299 0.059200801 -0.01071, + -0.056809202 0.057233199 -0.01524, + -0.0546159 0.0619119 -0.011319, + -0.055787299 0.0596641 -0.014098, + -0.0546159 0.0620648 -0.013028, + -0.0546159 0.061683699 -0.0095939897, + -0.0532961 0.0641293 -0.0085770003, + -0.055787299 0.059468798 -0.012404, + -0.0532961 0.064312503 -0.010317, + -0.051830001 0.065190203 -0.00054499798, + -0.0532961 0.062621497 -0.001592, + -0.051830001 0.064658299 0.0012150001, + -0.0532961 0.063115202 -0.0033240099, + -0.051830001 0.065641701 -0.0023179899, + -0.050219599 0.0672177 0.00217101, + -0.050219599 0.067704402 0.00036900301, + -0.0546159 0.054227799 0.0081599997, + -0.0532961 0.057004299 0.0097580003, + -0.0532961 0.055918299 0.011203, + -0.0546159 0.053137101 0.0095319999, + -0.055787299 0.052514002 0.0050750002, + -0.055787299 0.0514801 0.0064309998, + -0.0532961 0.058025599 0.008258, + -0.0546159 0.055259299 0.0067319898, + -0.055787299 0.0534903 0.003664, + -0.0546159 0.0571297 0.00372301, + -0.0546159 0.0562279 0.0052510099, + -0.0532961 0.058978502 0.0067090001, + -0.0532961 0.059859298 0.0051150098, + -0.0546159 0.057961401 0.0021519901, + -0.055787299 0.055255398 0.00069599901, + -0.055787299 0.054405302 0.002203 ] + + } + coordIndex [ 193, 1357, 194, -1, 10, 57, 65, -1, + 10, 65, 879, -1, 10, 193, 194, -1, + 10, 194, 57, -1, 18, 1, 879, -1, + 25, 12, 0, -1, 25, 0, 908, -1, + 59, 57, 194, -1, 61, 194, 355, -1, + 61, 59, 194, -1, 61, 60, 59, -1, + 360, 355, 194, -1, 452, 455, 453, -1, + 3, 763, 42, -1, 41, 38, 322, -1, + 31, 4, 763, -1, 37, 5, 176, -1, + 37, 104, 38, -1, 37, 176, 309, -1, + 37, 309, 104, -1, 99, 329, 603, -1, + 99, 1722, 329, -1, 169, 104, 309, -1, + 101, 38, 104, -1, 101, 34, 2382, -1, + 334, 339, 69, -1, 13, 16, 1395, -1, + 13, 25, 16, -1, 13, 12, 25, -1, + 912, 0, 12, -1, 912, 908, 0, -1, + 52, 1, 18, -1, 52, 879, 1, -1, + 55, 16, 25, -1, 55, 25, 38, -1, + 55, 38, 101, -1, 64, 18, 879, -1, + 67, 52, 18, -1, 1309, 25, 908, -1, + 229, 124, 11, -1, 229, 11, 437, -1, + 258, 146, 730, -1, 354, 61, 355, -1, + 195, 194, 1357, -1, 1823, 14, 1824, -1, + 1394, 1395, 16, -1, 445, 158, 21, -1, + 445, 237, 158, -1, 153, 47, 210, -1, + 2, 146, 455, -1, 2, 455, 452, -1, + 2, 730, 146, -1, 2, 452, 730, -1, + 809, 831, 93, -1, 22, 763, 174, -1, + 92, 174, 763, -1, 216, 38, 25, -1, + 321, 322, 38, -1, 112, 49, 110, -1, + 27, 38, 216, -1, 27, 216, 217, -1, + 27, 217, 49, -1, 27, 49, 112, -1, + 43, 41, 322, -1, 43, 3, 42, -1, + 43, 763, 3, -1, 43, 322, 181, -1, + 91, 176, 5, -1, 91, 89, 176, -1, + 91, 31, 32, -1, 6, 40, 42, -1, + 6, 42, 763, -1, 6, 4, 31, -1, + 6, 763, 4, -1, 33, 31, 763, -1, + 1257, 46, 183, -1, 568, 325, 183, -1, + 44, 169, 314, -1, 44, 104, 169, -1, + 874, 98, 960, -1, 39, 5, 37, -1, + 39, 91, 5, -1, 39, 31, 91, -1, + 39, 40, 6, -1, 39, 6, 31, -1, + 103, 569, 568, -1, 100, 101, 104, -1, + 100, 104, 103, -1, 100, 1722, 99, -1, + 100, 46, 1257, -1, 100, 1257, 1722, -1, + 1862, 101, 2382, -1, 1862, 342, 8, -1, + 1862, 8, 101, -1, 7, 334, 69, -1, + 7, 101, 8, -1, 7, 8, 342, -1, + 7, 342, 334, -1, 7, 69, 114, -1, + 7, 114, 101, -1, 9, 10, 879, -1, + 9, 879, 363, -1, 9, 193, 10, -1, + 9, 363, 193, -1, 108, 437, 11, -1, + 108, 11, 124, -1, 913, 912, 12, -1, + 913, 13, 1395, -1, 913, 12, 13, -1, + 56, 14, 55, -1, 644, 1824, 14, -1, + 644, 14, 56, -1, 15, 19, 937, -1, + 15, 1394, 16, -1, 15, 937, 1394, -1, + 20, 55, 14, -1, 20, 14, 1823, -1, + 20, 19, 15, -1, 20, 16, 55, -1, + 20, 15, 16, -1, 62, 55, 101, -1, + 62, 101, 114, -1, 62, 1127, 54, -1, + 17, 879, 65, -1, 17, 65, 64, -1, + 17, 64, 879, -1, 68, 116, 114, -1, + 68, 114, 69, -1, 68, 18, 64, -1, + 68, 67, 18, -1, 333, 52, 67, -1, + 333, 71, 52, -1, 73, 535, 419, -1, + 187, 84, 192, -1, 127, 108, 124, -1, + 127, 128, 198, -1, 127, 198, 108, -1, + 58, 61, 354, -1, 58, 354, 231, -1, + 58, 231, 117, -1, 938, 937, 19, -1, + 938, 19, 20, -1, 938, 20, 1823, -1, + 859, 166, 535, -1, 184, 93, 831, -1, + 184, 594, 93, -1, 147, 455, 146, -1, + 147, 242, 455, -1, 147, 151, 242, -1, + 76, 1611, 75, -1, 76, 1103, 1611, -1, + 1112, 706, 75, -1, 707, 75, 706, -1, + 224, 119, 223, -1, 83, 47, 153, -1, + 81, 47, 83, -1, 140, 80, 119, -1, + 140, 119, 224, -1, 79, 119, 80, -1, + 79, 344, 122, -1, 139, 80, 140, -1, + 189, 146, 258, -1, 82, 84, 187, -1, + 82, 187, 188, -1, 159, 445, 21, -1, + 159, 21, 158, -1, 474, 499, 589, -1, + 807, 831, 809, -1, 560, 763, 502, -1, + 294, 1240, 585, -1, 86, 1241, 294, -1, + 86, 294, 585, -1, 88, 90, 763, -1, + 88, 763, 22, -1, 88, 22, 89, -1, + 173, 176, 89, -1, 173, 89, 22, -1, + 173, 22, 174, -1, 23, 763, 554, -1, + 23, 92, 763, -1, 23, 554, 92, -1, + 311, 314, 169, -1, 571, 569, 845, -1, + 318, 1240, 809, -1, 24, 109, 50, -1, + 24, 1309, 109, -1, 24, 25, 1309, -1, + 24, 216, 25, -1, 24, 50, 216, -1, + 26, 94, 321, -1, 26, 27, 94, -1, + 26, 321, 38, -1, 26, 38, 27, -1, + 111, 28, 27, -1, 111, 27, 112, -1, + 111, 219, 28, -1, 178, 27, 28, -1, + 178, 28, 219, -1, 178, 94, 27, -1, + 1169, 94, 178, -1, 855, 182, 322, -1, + 85, 493, 763, -1, 85, 763, 43, -1, + 85, 43, 181, -1, 29, 91, 32, -1, + 29, 90, 91, -1, 29, 32, 763, -1, + 29, 763, 90, -1, 30, 32, 31, -1, + 30, 31, 33, -1, 30, 763, 32, -1, + 30, 33, 763, -1, 867, 1257, 183, -1, + 864, 329, 1722, -1, 35, 98, 874, -1, + 35, 101, 98, -1, 35, 34, 101, -1, + 875, 2382, 34, -1, 875, 34, 35, -1, + 875, 35, 874, -1, 97, 99, 603, -1, + 97, 603, 972, -1, 36, 37, 38, -1, + 36, 39, 37, -1, 36, 40, 39, -1, + 36, 38, 41, -1, 36, 42, 40, -1, + 36, 43, 42, -1, 36, 41, 43, -1, + 105, 104, 44, -1, 105, 314, 845, -1, + 105, 44, 314, -1, 45, 46, 100, -1, + 45, 100, 103, -1, 45, 183, 46, -1, + 45, 568, 183, -1, 45, 103, 568, -1, + 341, 334, 342, -1, 259, 189, 258, -1, + 629, 879, 882, -1, 647, 373, 374, -1, + 202, 198, 128, -1, 205, 393, 437, -1, + 205, 437, 108, -1, 205, 108, 949, -1, + 225, 437, 393, -1, 225, 207, 77, -1, + 225, 77, 224, -1, 211, 210, 47, -1, + 211, 47, 81, -1, 608, 874, 960, -1, + 48, 123, 651, -1, 48, 651, 196, -1, + 48, 130, 123, -1, 48, 196, 130, -1, + 406, 49, 217, -1, 406, 217, 215, -1, + 406, 110, 49, -1, 406, 215, 979, -1, + 218, 50, 109, -1, 218, 216, 50, -1, + 678, 677, 110, -1, 72, 332, 879, -1, + 72, 879, 71, -1, 51, 879, 52, -1, + 51, 71, 879, -1, 51, 52, 71, -1, + 2076, 54, 1127, -1, 53, 2246, 55, -1, + 53, 62, 54, -1, 53, 55, 62, -1, + 53, 54, 2076, -1, 53, 2076, 2246, -1, + 2247, 55, 2246, -1, 2247, 56, 55, -1, + 2247, 644, 56, -1, 115, 116, 65, -1, + 115, 65, 57, -1, 115, 58, 117, -1, + 115, 59, 60, -1, 115, 57, 59, -1, + 115, 60, 61, -1, 115, 61, 58, -1, + 1126, 62, 114, -1, 1126, 114, 117, -1, + 1126, 1127, 62, -1, 63, 116, 68, -1, + 63, 68, 64, -1, 63, 65, 116, -1, + 63, 64, 65, -1, 66, 333, 67, -1, + 66, 68, 69, -1, 66, 67, 68, -1, + 66, 69, 339, -1, 66, 339, 333, -1, + 70, 333, 332, -1, 70, 71, 333, -1, + 70, 332, 72, -1, 70, 72, 71, -1, + 739, 157, 158, -1, 739, 158, 220, -1, + 739, 740, 157, -1, 426, 220, 133, -1, + 226, 119, 79, -1, 226, 79, 122, -1, + 343, 2365, 123, -1, 126, 127, 124, -1, + 327, 93, 594, -1, 860, 535, 73, -1, + 860, 859, 535, -1, 860, 73, 419, -1, + 860, 1103, 76, -1, 860, 76, 861, -1, + 548, 184, 831, -1, 548, 831, 830, -1, + 548, 166, 859, -1, 232, 1266, 1267, -1, + 241, 237, 445, -1, 209, 257, 210, -1, + 209, 242, 257, -1, 74, 158, 237, -1, + 74, 237, 133, -1, 74, 220, 158, -1, + 74, 133, 220, -1, 420, 75, 1611, -1, + 420, 1112, 75, -1, 240, 135, 132, -1, + 240, 239, 75, -1, 240, 133, 237, -1, + 240, 132, 133, -1, 240, 75, 707, -1, + 137, 75, 239, -1, 137, 861, 76, -1, + 137, 76, 75, -1, 144, 140, 224, -1, + 144, 224, 77, -1, 144, 77, 207, -1, + 144, 207, 142, -1, 78, 80, 347, -1, + 78, 79, 80, -1, 78, 347, 344, -1, + 78, 344, 79, -1, 106, 347, 80, -1, + 106, 80, 139, -1, 141, 83, 143, -1, + 141, 81, 83, -1, 141, 211, 81, -1, + 141, 142, 207, -1, 141, 207, 211, -1, + 186, 185, 139, -1, 186, 143, 82, -1, + 186, 82, 188, -1, 190, 150, 189, -1, + 190, 84, 255, -1, 190, 255, 150, -1, + 190, 192, 84, -1, 149, 189, 150, -1, + 149, 151, 147, -1, 254, 150, 255, -1, + 254, 257, 242, -1, 254, 242, 151, -1, + 152, 153, 210, -1, 152, 210, 257, -1, + 154, 82, 143, -1, 154, 143, 83, -1, + 154, 83, 153, -1, 154, 255, 84, -1, + 154, 84, 82, -1, 156, 159, 158, -1, + 156, 741, 159, -1, 95, 494, 493, -1, + 95, 493, 85, -1, 95, 85, 181, -1, + 774, 589, 499, -1, 774, 95, 589, -1, + 774, 494, 95, -1, 179, 474, 589, -1, + 161, 481, 499, -1, 161, 474, 160, -1, + 161, 499, 474, -1, 269, 160, 474, -1, + 293, 275, 274, -1, 750, 282, 281, -1, + 298, 809, 1240, -1, 528, 523, 1506, -1, + 1507, 1506, 523, -1, 542, 831, 807, -1, + 561, 560, 580, -1, 789, 86, 585, -1, + 789, 1241, 86, -1, 87, 88, 89, -1, + 87, 90, 88, -1, 87, 89, 91, -1, + 87, 91, 90, -1, 306, 92, 554, -1, + 303, 169, 309, -1, 303, 309, 307, -1, + 303, 307, 306, -1, 170, 174, 92, -1, + 170, 92, 306, -1, 175, 174, 170, -1, + 175, 170, 171, -1, 175, 309, 176, -1, + 175, 171, 309, -1, 1704, 571, 845, -1, + 319, 585, 1240, -1, 177, 809, 93, -1, + 177, 318, 809, -1, 177, 93, 327, -1, + 586, 580, 560, -1, 1665, 1169, 178, -1, + 473, 321, 94, -1, 473, 94, 1169, -1, + 323, 95, 181, -1, 323, 592, 589, -1, + 323, 589, 95, -1, 869, 867, 183, -1, + 606, 603, 329, -1, 606, 329, 441, -1, + 312, 1243, 313, -1, 312, 313, 314, -1, + 96, 97, 972, -1, 96, 960, 98, -1, + 96, 972, 960, -1, 96, 99, 97, -1, + 96, 100, 99, -1, 96, 98, 101, -1, + 96, 101, 100, -1, 102, 103, 104, -1, + 102, 104, 105, -1, 102, 569, 103, -1, + 102, 845, 569, -1, 102, 105, 845, -1, + 331, 879, 332, -1, 331, 337, 879, -1, + 611, 339, 334, -1, 346, 347, 106, -1, + 346, 139, 185, -1, 346, 106, 139, -1, + 349, 344, 347, -1, 361, 360, 194, -1, + 1362, 1369, 634, -1, 1355, 1357, 193, -1, + 1355, 1362, 634, -1, 630, 882, 631, -1, + 630, 629, 882, -1, 948, 108, 373, -1, + 948, 949, 108, -1, 107, 199, 373, -1, + 107, 198, 199, -1, 107, 373, 108, -1, + 107, 108, 198, -1, 390, 371, 637, -1, + 378, 374, 373, -1, 650, 381, 383, -1, + 650, 202, 128, -1, 650, 383, 202, -1, + 650, 128, 196, -1, 654, 1833, 204, -1, + 201, 203, 373, -1, 201, 373, 199, -1, + 950, 205, 949, -1, 400, 1268, 1266, -1, + 2364, 123, 2365, -1, 2364, 651, 123, -1, + 2364, 656, 651, -1, 364, 931, 214, -1, + 942, 635, 941, -1, 391, 371, 390, -1, + 391, 389, 204, -1, 1402, 213, 1835, -1, + 1402, 214, 213, -1, 1834, 1835, 213, -1, + 1834, 204, 1833, -1, 1834, 391, 204, -1, + 1834, 213, 391, -1, 978, 979, 215, -1, + 1428, 1427, 109, -1, 1428, 1310, 1890, -1, + 1428, 109, 1309, -1, 1428, 1309, 1310, -1, + 663, 404, 218, -1, 663, 109, 1427, -1, + 663, 218, 109, -1, 407, 110, 406, -1, + 407, 678, 110, -1, 673, 110, 677, -1, + 673, 219, 111, -1, 673, 112, 110, -1, + 673, 111, 112, -1, 1025, 1479, 1016, -1, + 113, 117, 114, -1, 113, 115, 117, -1, + 113, 114, 116, -1, 113, 116, 115, -1, + 230, 117, 231, -1, 230, 1126, 117, -1, + 1619, 1629, 2067, -1, 1619, 2067, 1609, -1, + 423, 739, 220, -1, 425, 133, 428, -1, + 425, 426, 133, -1, 136, 1608, 118, -1, + 136, 118, 135, -1, 136, 707, 710, -1, + 136, 710, 1606, -1, 136, 1606, 1608, -1, + 431, 135, 118, -1, 222, 118, 1608, -1, + 222, 431, 118, -1, 439, 223, 119, -1, + 439, 119, 226, -1, 228, 122, 130, -1, + 228, 226, 122, -1, 228, 436, 226, -1, + 120, 122, 344, -1, 120, 344, 343, -1, + 120, 343, 122, -1, 121, 130, 122, -1, + 121, 122, 343, -1, 121, 123, 130, -1, + 121, 343, 123, -1, 129, 124, 229, -1, + 129, 126, 124, -1, 125, 127, 126, -1, + 125, 196, 128, -1, 125, 128, 127, -1, + 125, 126, 129, -1, 125, 129, 229, -1, + 125, 229, 228, -1, 125, 130, 196, -1, + 125, 228, 130, -1, 353, 231, 354, -1, + 326, 600, 316, -1, 418, 860, 419, -1, + 418, 1103, 860, -1, 131, 548, 859, -1, + 131, 184, 548, -1, 131, 859, 858, -1, + 131, 858, 184, -1, 1229, 548, 830, -1, + 233, 239, 238, -1, 233, 137, 239, -1, + 234, 232, 727, -1, 244, 237, 241, -1, + 447, 241, 1651, -1, 447, 244, 241, -1, + 250, 132, 135, -1, 250, 135, 431, -1, + 250, 431, 252, -1, 250, 428, 133, -1, + 250, 133, 132, -1, 134, 135, 240, -1, + 134, 240, 707, -1, 134, 136, 135, -1, + 134, 707, 136, -1, 1261, 861, 137, -1, + 1261, 233, 1262, -1, 1261, 137, 233, -1, + 138, 139, 140, -1, 138, 142, 141, -1, + 138, 141, 143, -1, 138, 144, 142, -1, + 138, 140, 144, -1, 138, 143, 186, -1, + 138, 186, 139, -1, 145, 146, 189, -1, + 145, 189, 149, -1, 145, 147, 146, -1, + 145, 149, 147, -1, 148, 149, 150, -1, + 148, 150, 254, -1, 148, 151, 149, -1, + 148, 254, 151, -1, 256, 153, 152, -1, + 256, 154, 153, -1, 256, 255, 154, -1, + 256, 152, 257, -1, 451, 730, 452, -1, + 2506, 456, 1081, -1, 1092, 432, 700, -1, + 155, 740, 741, -1, 155, 741, 156, -1, + 155, 157, 740, -1, 155, 158, 157, -1, + 155, 156, 158, -1, 265, 445, 159, -1, + 265, 159, 741, -1, 268, 445, 265, -1, + 590, 179, 589, -1, 475, 179, 1249, -1, + 475, 474, 179, -1, 480, 160, 269, -1, + 480, 161, 160, -1, 480, 481, 161, -1, + 271, 499, 481, -1, 271, 270, 499, -1, + 271, 484, 270, -1, 271, 481, 478, -1, + 272, 746, 1161, -1, 479, 269, 1173, -1, + 479, 480, 269, -1, 1162, 490, 485, -1, + 505, 560, 502, -1, 501, 502, 763, -1, + 276, 275, 279, -1, 276, 1199, 1200, -1, + 292, 814, 284, -1, 280, 279, 275, -1, + 280, 275, 293, -1, 280, 293, 292, -1, + 1043, 293, 274, -1, 1043, 274, 1042, -1, + 163, 278, 285, -1, 163, 281, 282, -1, + 162, 278, 794, -1, 162, 279, 278, -1, + 162, 276, 279, -1, 162, 794, 1199, -1, + 162, 1199, 276, -1, 487, 751, 750, -1, + 487, 750, 281, -1, 514, 163, 285, -1, + 514, 281, 163, -1, 793, 794, 278, -1, + 793, 282, 506, -1, 793, 163, 282, -1, + 793, 278, 163, -1, 512, 284, 814, -1, + 164, 290, 1232, -1, 164, 291, 290, -1, + 806, 542, 807, -1, 1231, 1232, 290, -1, + 287, 521, 810, -1, 289, 287, 290, -1, + 289, 519, 287, -1, 839, 838, 526, -1, + 300, 164, 1232, -1, 300, 291, 164, -1, + 819, 519, 291, -1, 819, 1045, 519, -1, + 1239, 1240, 294, -1, 544, 528, 295, -1, + 544, 531, 547, -1, 544, 295, 531, -1, + 165, 543, 523, -1, 165, 523, 528, -1, + 165, 544, 543, -1, 165, 528, 544, -1, + 297, 535, 166, -1, 297, 166, 548, -1, + 533, 547, 531, -1, 533, 531, 530, -1, + 829, 810, 521, -1, 829, 521, 543, -1, + 522, 523, 543, -1, 522, 543, 521, -1, + 167, 787, 585, -1, 167, 560, 787, -1, + 167, 585, 586, -1, 167, 586, 560, -1, + 168, 788, 789, -1, 168, 789, 585, -1, + 168, 787, 788, -1, 168, 585, 787, -1, + 800, 302, 1175, -1, 800, 549, 302, -1, + 553, 763, 560, -1, 553, 560, 556, -1, + 304, 311, 169, -1, 304, 169, 303, -1, + 308, 170, 306, -1, 308, 171, 170, -1, + 308, 309, 171, -1, 172, 173, 174, -1, + 172, 174, 175, -1, 172, 176, 173, -1, + 172, 175, 176, -1, 552, 1243, 312, -1, + 583, 319, 564, -1, 583, 585, 319, -1, + 579, 561, 580, -1, 320, 1240, 318, -1, + 320, 319, 1240, -1, 563, 564, 319, -1, + 317, 318, 177, -1, 317, 177, 327, -1, + 317, 327, 326, -1, 317, 326, 316, -1, + 670, 1665, 178, -1, 670, 219, 999, -1, + 670, 178, 219, -1, 1246, 321, 473, -1, + 1248, 1249, 179, -1, 1248, 179, 590, -1, + 591, 592, 323, -1, 180, 323, 181, -1, + 180, 181, 322, -1, 180, 322, 182, -1, + 180, 182, 855, -1, 180, 855, 323, -1, + 324, 183, 325, -1, 324, 869, 183, -1, + 599, 600, 326, -1, 595, 594, 184, -1, + 595, 184, 858, -1, 1254, 599, 1255, -1, + 724, 441, 329, -1, 602, 603, 604, -1, + 605, 604, 603, -1, 605, 603, 606, -1, + 1269, 606, 441, -1, 336, 337, 331, -1, + 336, 333, 339, -1, 609, 334, 341, -1, + 338, 339, 611, -1, 892, 342, 889, -1, + 884, 879, 886, -1, 884, 882, 879, -1, + 614, 346, 185, -1, 614, 186, 188, -1, + 614, 185, 186, -1, 350, 2367, 2366, -1, + 613, 187, 192, -1, 613, 188, 187, -1, + 613, 614, 188, -1, 1294, 623, 2790, -1, + 624, 623, 1061, -1, 624, 1061, 1287, -1, + 260, 189, 259, -1, 260, 458, 192, -1, + 260, 190, 189, -1, 260, 192, 190, -1, + 191, 621, 622, -1, 191, 458, 621, -1, + 191, 192, 458, -1, 191, 613, 192, -1, + 191, 622, 613, -1, 356, 355, 360, -1, + 641, 361, 932, -1, 934, 361, 922, -1, + 924, 193, 363, -1, 924, 1355, 193, -1, + 1374, 1375, 919, -1, 1374, 361, 194, -1, + 1374, 922, 361, -1, 1374, 194, 195, -1, + 1374, 195, 1357, -1, 1360, 364, 635, -1, + 379, 388, 392, -1, 375, 368, 882, -1, + 375, 374, 368, -1, 367, 631, 882, -1, + 369, 368, 374, -1, 369, 374, 379, -1, + 369, 379, 392, -1, 639, 931, 1341, -1, + 372, 373, 647, -1, 1410, 1409, 882, -1, + 377, 373, 203, -1, 377, 378, 373, -1, + 652, 196, 651, -1, 652, 650, 196, -1, + 380, 383, 381, -1, 380, 654, 383, -1, + 1401, 1833, 654, -1, 1401, 657, 1845, -1, + 197, 198, 202, -1, 197, 202, 201, -1, + 197, 199, 198, -1, 197, 201, 199, -1, + 384, 654, 204, -1, 384, 204, 387, -1, + 200, 201, 202, -1, 200, 202, 383, -1, + 200, 383, 387, -1, 200, 203, 201, -1, + 200, 377, 203, -1, 200, 387, 388, -1, + 200, 388, 377, -1, 386, 204, 389, -1, + 386, 387, 204, -1, 660, 393, 205, -1, + 660, 205, 950, -1, 208, 225, 393, -1, + 208, 396, 225, -1, 206, 225, 396, -1, + 206, 396, 211, -1, 206, 207, 225, -1, + 206, 211, 207, -1, 395, 208, 393, -1, + 395, 396, 208, -1, 397, 242, 209, -1, + 397, 209, 210, -1, 397, 210, 211, -1, + 397, 211, 396, -1, 212, 400, 1266, -1, + 212, 234, 246, -1, 212, 1266, 232, -1, + 212, 232, 234, -1, 399, 401, 400, -1, + 399, 246, 398, -1, 399, 212, 246, -1, + 399, 400, 212, -1, 402, 608, 960, -1, + 958, 960, 972, -1, 370, 371, 391, -1, + 370, 214, 931, -1, 370, 213, 214, -1, + 370, 391, 213, -1, 370, 931, 639, -1, + 645, 214, 1402, -1, 645, 941, 635, -1, + 645, 364, 214, -1, 645, 635, 364, -1, + 403, 215, 1418, -1, 403, 978, 215, -1, + 1417, 1418, 215, -1, 1417, 216, 218, -1, + 1417, 217, 216, -1, 1417, 215, 217, -1, + 1419, 218, 404, -1, 1419, 1417, 218, -1, + 665, 415, 511, -1, 665, 511, 1450, -1, + 665, 1450, 1451, -1, 405, 407, 406, -1, + 1000, 999, 219, -1, 1000, 219, 673, -1, + 1015, 1025, 1016, -1, 1037, 1042, 274, -1, + 1488, 1016, 1479, -1, 686, 714, 719, -1, + 1049, 415, 1050, -1, 414, 412, 510, -1, + 1510, 1022, 1023, -1, 1588, 1589, 1084, -1, + 697, 1084, 1589, -1, 697, 696, 416, -1, + 2047, 2506, 1081, -1, 1614, 1611, 1103, -1, + 702, 433, 1625, -1, 1115, 1629, 1619, -1, + 1628, 2067, 1629, -1, 422, 220, 426, -1, + 422, 423, 220, -1, 738, 422, 426, -1, + 427, 249, 251, -1, 427, 428, 249, -1, + 427, 251, 432, -1, 427, 432, 1092, -1, + 427, 1092, 1091, -1, 427, 1091, 738, -1, + 1603, 1606, 710, -1, 430, 252, 431, -1, + 430, 432, 252, -1, 1604, 431, 222, -1, + 1604, 700, 432, -1, 221, 1608, 1605, -1, + 221, 222, 1608, -1, 221, 1605, 1604, -1, + 221, 1604, 222, -1, 1122, 719, 714, -1, + 720, 721, 434, -1, 823, 1096, 822, -1, + 823, 702, 1096, -1, 823, 433, 702, -1, + 440, 223, 439, -1, 440, 224, 223, -1, + 440, 225, 224, -1, 440, 437, 225, -1, + 438, 439, 226, -1, 438, 226, 436, -1, + 227, 228, 229, -1, 227, 436, 228, -1, + 227, 229, 437, -1, 227, 437, 436, -1, + 642, 1632, 353, -1, 642, 628, 1380, -1, + 1125, 353, 1632, -1, 1125, 230, 231, -1, + 1125, 231, 353, -1, 1125, 1126, 230, -1, + 567, 852, 325, -1, 567, 325, 568, -1, + 726, 232, 1267, -1, 726, 727, 232, -1, + 235, 234, 727, -1, 235, 727, 1262, -1, + 235, 1262, 233, -1, 235, 233, 238, -1, + 245, 246, 234, -1, 245, 238, 244, -1, + 245, 235, 238, -1, 245, 234, 235, -1, + 236, 237, 244, -1, 236, 244, 238, -1, + 236, 238, 239, -1, 236, 240, 237, -1, + 236, 239, 240, -1, 446, 241, 445, -1, + 446, 467, 241, -1, 261, 1651, 241, -1, + 261, 241, 467, -1, 443, 471, 470, -1, + 443, 444, 471, -1, 464, 463, 732, -1, + 247, 454, 455, -1, 247, 464, 454, -1, + 247, 447, 464, -1, 247, 455, 242, -1, + 247, 242, 397, -1, 247, 397, 398, -1, + 243, 244, 447, -1, 243, 246, 245, -1, + 243, 245, 244, -1, 243, 398, 246, -1, + 243, 247, 398, -1, 243, 447, 247, -1, + 248, 249, 428, -1, 248, 428, 250, -1, + 248, 251, 249, -1, 248, 432, 251, -1, + 248, 252, 432, -1, 248, 250, 252, -1, + 253, 254, 255, -1, 253, 255, 256, -1, + 253, 257, 254, -1, 253, 256, 257, -1, + 1142, 1131, 732, -1, 450, 1131, 730, -1, + 450, 730, 451, -1, 2505, 456, 2506, -1, + 472, 1081, 456, -1, 472, 1080, 1081, -1, + 472, 1599, 1080, -1, 699, 416, 696, -1, + 699, 696, 1594, -1, 729, 457, 259, -1, + 729, 259, 258, -1, 729, 258, 730, -1, + 731, 457, 729, -1, 459, 259, 457, -1, + 459, 260, 259, -1, 459, 458, 260, -1, + 466, 1651, 261, -1, 466, 261, 467, -1, + 1650, 1136, 461, -1, 1137, 1136, 736, -1, + 469, 443, 470, -1, 469, 467, 443, -1, + 743, 265, 741, -1, 745, 736, 471, -1, + 745, 1137, 736, -1, 264, 268, 265, -1, + 262, 471, 444, -1, 262, 444, 267, -1, + 262, 744, 471, -1, 262, 267, 744, -1, + 263, 744, 267, -1, 263, 267, 268, -1, + 263, 268, 264, -1, 263, 264, 265, -1, + 263, 743, 744, -1, 263, 265, 743, -1, + 266, 267, 444, -1, 266, 268, 267, -1, + 266, 444, 445, -1, 266, 445, 268, -1, + 753, 269, 474, -1, 753, 1173, 269, -1, + 498, 270, 484, -1, 498, 499, 270, -1, + 748, 272, 478, -1, 748, 746, 272, -1, + 486, 1162, 485, -1, 486, 272, 1161, -1, + 486, 1161, 1162, -1, 483, 484, 271, -1, + 483, 271, 478, -1, 483, 478, 272, -1, + 483, 272, 486, -1, 755, 756, 498, -1, + 755, 498, 484, -1, 1159, 490, 1162, -1, + 491, 485, 490, -1, 491, 760, 485, -1, + 491, 759, 760, -1, 1179, 488, 1181, -1, + 765, 779, 776, -1, 765, 497, 758, -1, + 765, 766, 497, -1, 1672, 779, 1180, -1, + 1672, 782, 779, -1, 1678, 1679, 771, -1, + 500, 501, 763, -1, 500, 763, 770, -1, + 500, 770, 771, -1, 500, 771, 1679, -1, + 785, 787, 560, -1, 273, 274, 275, -1, + 273, 275, 276, -1, 273, 276, 1200, -1, + 273, 1037, 274, -1, 273, 1200, 1038, -1, + 273, 1038, 1037, -1, 277, 285, 278, -1, + 277, 278, 279, -1, 277, 279, 280, -1, + 277, 292, 284, -1, 277, 280, 292, -1, + 277, 286, 285, -1, 277, 284, 286, -1, + 513, 1181, 488, -1, 513, 488, 487, -1, + 513, 487, 281, -1, 513, 281, 514, -1, + 1214, 282, 750, -1, 1214, 506, 282, -1, + 1214, 1206, 506, -1, 1205, 506, 1206, -1, + 1217, 508, 408, -1, 1217, 408, 1693, -1, + 2129, 510, 412, -1, 2129, 412, 1695, -1, + 283, 1693, 408, -1, 283, 1028, 409, -1, + 283, 408, 1027, -1, 283, 1027, 1028, -1, + 1692, 409, 1196, -1, 1692, 283, 409, -1, + 1692, 1693, 283, -1, 524, 526, 838, -1, + 524, 838, 512, -1, 524, 525, 526, -1, + 799, 798, 286, -1, 799, 284, 512, -1, + 799, 286, 284, -1, 515, 514, 285, -1, + 515, 285, 286, -1, 515, 286, 798, -1, + 805, 1231, 290, -1, 805, 287, 810, -1, + 805, 290, 287, -1, 520, 287, 519, -1, + 520, 521, 287, -1, 288, 291, 519, -1, + 288, 519, 289, -1, 288, 290, 291, -1, + 288, 289, 290, -1, 1044, 1045, 819, -1, + 691, 818, 525, -1, 820, 291, 300, -1, + 820, 300, 526, -1, 820, 819, 291, -1, + 813, 814, 292, -1, 813, 292, 293, -1, + 813, 1043, 1496, -1, 813, 293, 1043, -1, + 1238, 294, 1241, -1, 1238, 1239, 294, -1, + 516, 809, 298, -1, 516, 298, 517, -1, + 826, 295, 528, -1, 826, 531, 295, -1, + 417, 527, 822, -1, 417, 530, 527, -1, + 539, 1095, 1101, -1, 539, 1101, 419, -1, + 539, 419, 296, -1, 540, 417, 1095, -1, + 540, 530, 417, -1, 540, 1095, 539, -1, + 540, 533, 530, -1, 537, 535, 538, -1, + 537, 419, 535, -1, 537, 296, 419, -1, + 537, 539, 296, -1, 534, 535, 297, -1, + 546, 547, 533, -1, 546, 297, 548, -1, + 546, 534, 297, -1, 828, 541, 829, -1, + 828, 831, 541, -1, 1227, 548, 1229, -1, + 1675, 302, 549, -1, 1675, 1676, 1174, -1, + 1675, 549, 786, -1, 1675, 786, 1677, -1, + 841, 1241, 789, -1, 801, 834, 833, -1, + 801, 833, 549, -1, 801, 549, 800, -1, + 1235, 298, 1240, -1, 1235, 517, 298, -1, + 299, 1232, 1230, -1, 299, 1230, 839, -1, + 299, 839, 526, -1, 299, 300, 1232, -1, + 299, 526, 300, -1, 301, 1175, 302, -1, + 301, 1174, 1175, -1, 301, 302, 1675, -1, + 301, 1675, 1174, -1, 555, 554, 763, -1, + 555, 763, 553, -1, 551, 303, 306, -1, + 551, 304, 303, -1, 551, 306, 554, -1, + 551, 311, 304, -1, 551, 552, 311, -1, + 305, 306, 307, -1, 305, 308, 306, -1, + 305, 307, 309, -1, 305, 309, 308, -1, + 310, 311, 552, -1, 310, 552, 312, -1, + 310, 314, 311, -1, 310, 312, 314, -1, + 557, 553, 556, -1, 557, 1243, 552, -1, + 559, 556, 560, -1, 559, 843, 556, -1, + 582, 583, 564, -1, 851, 582, 564, -1, + 851, 576, 582, -1, 848, 852, 567, -1, + 842, 561, 579, -1, 1705, 571, 1704, -1, + 584, 582, 576, -1, 584, 580, 586, -1, + 1244, 313, 1243, -1, 1244, 314, 313, -1, + 1244, 845, 314, -1, 1244, 1702, 845, -1, + 844, 563, 316, -1, 844, 316, 600, -1, + 315, 316, 563, -1, 315, 317, 316, -1, + 315, 318, 317, -1, 315, 563, 319, -1, + 315, 320, 318, -1, 315, 319, 320, -1, + 853, 321, 1246, -1, 853, 322, 321, -1, + 853, 855, 322, -1, 588, 592, 1250, -1, + 588, 589, 592, -1, 588, 587, 589, -1, + 1712, 589, 587, -1, 854, 323, 855, -1, + 854, 591, 323, -1, 870, 869, 324, -1, + 870, 324, 325, -1, 870, 325, 852, -1, + 593, 1255, 599, -1, 593, 599, 326, -1, + 593, 327, 594, -1, 593, 326, 327, -1, + 1258, 1257, 328, -1, 1258, 328, 1259, -1, + 598, 328, 1257, -1, 866, 1259, 328, -1, + 866, 1254, 1259, -1, 866, 328, 598, -1, + 723, 329, 864, -1, 723, 724, 329, -1, + 872, 602, 604, -1, 330, 331, 332, -1, + 330, 336, 331, -1, 330, 332, 333, -1, + 330, 333, 336, -1, 878, 879, 337, -1, + 878, 337, 338, -1, 878, 338, 611, -1, + 610, 611, 334, -1, 610, 334, 609, -1, + 881, 609, 341, -1, 881, 891, 885, -1, + 881, 341, 891, -1, 335, 337, 336, -1, + 335, 338, 337, -1, 335, 336, 339, -1, + 335, 339, 338, -1, 888, 342, 1862, -1, + 888, 889, 342, -1, 340, 891, 341, -1, + 340, 892, 891, -1, 340, 341, 342, -1, + 340, 342, 892, -1, 348, 2366, 2365, -1, + 348, 2365, 343, -1, 348, 343, 344, -1, + 348, 344, 349, -1, 615, 346, 614, -1, + 615, 900, 901, -1, 895, 1806, 1403, -1, + 1279, 1389, 1808, -1, 345, 619, 349, -1, + 345, 347, 346, -1, 345, 349, 347, -1, + 345, 346, 615, -1, 345, 901, 619, -1, + 345, 615, 901, -1, 351, 350, 2366, -1, + 351, 348, 349, -1, 351, 2366, 348, -1, + 351, 349, 619, -1, 940, 2367, 350, -1, + 940, 350, 616, -1, 940, 895, 1403, -1, + 940, 616, 895, -1, 617, 616, 350, -1, + 617, 618, 616, -1, 617, 351, 619, -1, + 617, 350, 351, -1, 899, 1277, 618, -1, + 1392, 1294, 1293, -1, 1289, 624, 1287, -1, + 1304, 1303, 1749, -1, 907, 913, 1395, -1, + 1308, 1309, 908, -1, 1311, 1890, 1310, -1, + 917, 2285, 1390, -1, 352, 356, 628, -1, + 352, 353, 354, -1, 352, 354, 355, -1, + 352, 355, 356, -1, 352, 628, 642, -1, + 352, 642, 353, -1, 358, 356, 360, -1, + 627, 359, 626, -1, 627, 628, 356, -1, + 627, 356, 358, -1, 627, 358, 359, -1, + 1378, 626, 641, -1, 357, 361, 641, -1, + 357, 359, 358, -1, 357, 626, 359, -1, + 357, 641, 626, -1, 357, 360, 361, -1, + 357, 358, 360, -1, 923, 935, 922, -1, + 933, 932, 361, -1, 933, 361, 934, -1, + 640, 922, 935, -1, 640, 934, 922, -1, + 362, 879, 629, -1, 362, 632, 879, -1, + 362, 629, 632, -1, 633, 363, 879, -1, + 633, 924, 363, -1, 1359, 931, 364, -1, + 1359, 364, 1360, -1, 1359, 1343, 931, -1, + 2238, 942, 943, -1, 365, 374, 378, -1, + 365, 379, 374, -1, 365, 378, 379, -1, + 366, 882, 368, -1, 366, 367, 882, -1, + 366, 368, 367, -1, 636, 367, 368, -1, + 636, 368, 369, -1, 636, 631, 367, -1, + 636, 392, 637, -1, 636, 369, 392, -1, + 638, 370, 639, -1, 638, 637, 371, -1, + 638, 371, 370, -1, 1348, 631, 636, -1, + 2251, 644, 2247, -1, 1826, 1824, 644, -1, + 1826, 644, 1828, -1, 2363, 657, 656, -1, + 2363, 656, 2364, -1, 947, 372, 647, -1, + 947, 647, 648, -1, 947, 948, 373, -1, + 947, 373, 372, -1, 662, 1869, 1730, -1, + 662, 648, 1869, -1, 1864, 647, 374, -1, + 1864, 374, 1866, -1, 646, 1866, 374, -1, + 646, 374, 375, -1, 646, 882, 1409, -1, + 646, 375, 882, -1, 612, 1410, 882, -1, + 612, 882, 883, -1, 612, 883, 2377, -1, + 376, 378, 377, -1, 376, 379, 378, -1, + 376, 377, 388, -1, 376, 388, 379, -1, + 655, 380, 381, -1, 655, 381, 650, -1, + 655, 651, 656, -1, 655, 654, 380, -1, + 382, 387, 383, -1, 382, 384, 387, -1, + 382, 383, 654, -1, 382, 654, 384, -1, + 385, 387, 386, -1, 385, 388, 387, -1, + 385, 386, 389, -1, 385, 390, 637, -1, + 385, 389, 391, -1, 385, 391, 390, -1, + 385, 637, 392, -1, 385, 392, 388, -1, + 659, 393, 660, -1, 659, 395, 393, -1, + 659, 401, 395, -1, 394, 396, 395, -1, + 394, 397, 396, -1, 394, 395, 401, -1, + 394, 398, 397, -1, 394, 401, 399, -1, + 394, 399, 398, -1, 658, 1268, 400, -1, + 658, 954, 1268, -1, 658, 400, 401, -1, + 658, 401, 659, -1, 959, 402, 960, -1, + 956, 660, 950, -1, 956, 950, 951, -1, + 661, 1730, 1731, -1, 661, 1731, 608, -1, + 661, 608, 402, -1, 661, 402, 959, -1, + 977, 978, 403, -1, 1425, 403, 1418, -1, + 1425, 977, 403, -1, 1425, 1424, 977, -1, + 1880, 404, 663, -1, 1880, 1419, 404, -1, + 1889, 1890, 1311, -1, 1009, 1011, 667, -1, + 994, 2434, 988, -1, 992, 994, 988, -1, + 990, 1050, 415, -1, 990, 415, 665, -1, + 980, 679, 407, -1, 980, 407, 405, -1, + 980, 406, 979, -1, 980, 405, 406, -1, + 669, 1463, 1894, -1, 1461, 1462, 2842, -1, + 1003, 1004, 1431, -1, 1003, 1431, 1893, -1, + 676, 673, 677, -1, 671, 683, 1670, -1, + 671, 1670, 2114, -1, 681, 1474, 675, -1, + 681, 675, 682, -1, 681, 683, 671, -1, + 681, 671, 1474, -1, 1475, 675, 1474, -1, + 1475, 676, 675, -1, 1475, 1000, 676, -1, + 680, 678, 407, -1, 680, 407, 679, -1, + 1040, 1041, 1015, -1, 410, 1025, 1015, -1, + 410, 1196, 409, -1, 410, 1041, 1196, -1, + 410, 1015, 1041, -1, 1019, 508, 1020, -1, + 1019, 408, 508, -1, 1019, 1027, 408, -1, + 509, 1020, 508, -1, 509, 1695, 412, -1, + 1024, 409, 1028, -1, 1024, 410, 409, -1, + 1024, 1025, 410, -1, 1487, 1012, 1489, -1, + 716, 714, 686, -1, 684, 1033, 1012, -1, + 684, 689, 1033, -1, 687, 688, 716, -1, + 687, 716, 686, -1, 1493, 689, 688, -1, + 1495, 691, 1497, -1, 694, 414, 692, -1, + 411, 1021, 1020, -1, 411, 694, 1021, -1, + 411, 414, 694, -1, 411, 412, 414, -1, + 411, 509, 412, -1, 411, 1020, 509, -1, + 413, 692, 414, -1, 413, 415, 1049, -1, + 413, 1049, 692, -1, 413, 511, 415, -1, + 413, 510, 511, -1, 413, 414, 510, -1, + 1967, 1029, 1022, -1, 1967, 1022, 1510, -1, + 1054, 694, 692, -1, 695, 1510, 1023, -1, + 695, 1509, 1510, -1, 1513, 1316, 2474, -1, + 3002, 2790, 623, -1, 3002, 623, 624, -1, + 1569, 1568, 1521, -1, 1569, 1521, 1064, -1, + 1523, 1521, 1568, -1, 1999, 1997, 1282, -1, + 2461, 2462, 1071, -1, 1577, 1071, 2462, -1, + 1577, 2462, 2457, -1, 1078, 434, 721, -1, + 1478, 1949, 1570, -1, 2041, 1478, 2043, -1, + 2044, 1484, 2042, -1, 1593, 1594, 696, -1, + 1593, 1080, 1599, -1, 1083, 416, 1087, -1, + 1083, 697, 416, -1, 1083, 1084, 697, -1, + 698, 1087, 416, -1, 698, 416, 699, -1, + 1094, 1095, 417, -1, 1094, 822, 1096, -1, + 1094, 417, 822, -1, 1100, 418, 419, -1, + 1100, 419, 1101, -1, 1100, 1103, 418, -1, + 1613, 1614, 1103, -1, 1108, 1115, 1619, -1, + 704, 1097, 1096, -1, 704, 1096, 702, -1, + 2061, 1112, 420, -1, 2061, 420, 1611, -1, + 1624, 434, 1078, -1, 1624, 1625, 433, -1, + 1624, 433, 434, -1, 1086, 1117, 1118, -1, + 1086, 2072, 1117, -1, 421, 423, 422, -1, + 421, 422, 738, -1, 421, 739, 423, -1, + 421, 738, 739, -1, 424, 426, 425, -1, + 424, 738, 426, -1, 424, 427, 738, -1, + 424, 425, 428, -1, 424, 428, 427, -1, + 429, 430, 431, -1, 429, 431, 1604, -1, + 429, 432, 430, -1, 429, 1604, 432, -1, + 1607, 700, 1604, -1, 1607, 698, 700, -1, + 1607, 1087, 698, -1, 1121, 719, 1122, -1, + 1077, 1122, 714, -1, 1077, 1123, 1122, -1, + 824, 434, 433, -1, 824, 720, 434, -1, + 824, 433, 823, -1, 824, 1223, 720, -1, + 718, 686, 719, -1, 435, 436, 437, -1, + 435, 438, 436, -1, 435, 439, 438, -1, + 435, 437, 440, -1, 435, 440, 439, -1, + 725, 441, 724, -1, 725, 1269, 441, -1, + 725, 1267, 1269, -1, 725, 726, 1267, -1, + 1729, 727, 726, -1, 442, 444, 443, -1, + 442, 445, 444, -1, 442, 446, 445, -1, + 442, 467, 446, -1, 442, 443, 467, -1, + 462, 447, 1651, -1, 462, 464, 447, -1, + 711, 705, 708, -1, 711, 710, 707, -1, + 711, 707, 705, -1, 1620, 1628, 1117, -1, + 1620, 1117, 2072, -1, 1620, 2067, 1628, -1, + 1620, 2066, 2067, -1, 1114, 711, 708, -1, + 448, 732, 1131, -1, 448, 1131, 450, -1, + 448, 464, 732, -1, 448, 450, 464, -1, + 449, 450, 451, -1, 449, 452, 453, -1, + 449, 451, 452, -1, 449, 464, 450, -1, + 449, 454, 464, -1, 449, 453, 455, -1, + 449, 455, 454, -1, 2475, 2474, 1316, -1, + 2095, 2505, 1645, -1, 2095, 456, 2505, -1, + 2095, 2094, 472, -1, 2095, 472, 456, -1, + 1060, 1328, 1974, -1, 1060, 2083, 915, -1, + 1060, 915, 1328, -1, 1512, 1974, 1328, -1, + 460, 457, 731, -1, 460, 1776, 1780, -1, + 1778, 459, 457, -1, 1778, 457, 460, -1, + 1778, 460, 1780, -1, 1777, 1785, 621, -1, + 1777, 621, 458, -1, 1777, 458, 459, -1, + 1777, 459, 1778, -1, 1132, 1142, 1143, -1, + 1133, 1776, 460, -1, 1133, 460, 731, -1, + 1653, 461, 1136, -1, 1653, 1650, 461, -1, + 1653, 1132, 1143, -1, 1139, 462, 1651, -1, + 1139, 732, 463, -1, 1139, 463, 464, -1, + 1139, 464, 462, -1, 465, 1651, 466, -1, + 465, 1650, 1651, -1, 465, 466, 1650, -1, + 734, 1136, 1650, -1, 734, 1650, 466, -1, + 734, 736, 735, -1, 734, 466, 467, -1, + 734, 469, 736, -1, 734, 467, 469, -1, + 468, 736, 469, -1, 468, 469, 470, -1, + 468, 471, 736, -1, 468, 470, 471, -1, + 1090, 699, 1594, -1, 742, 738, 1091, -1, + 1156, 471, 744, -1, 1156, 745, 471, -1, + 1156, 1155, 745, -1, 1642, 472, 2094, -1, + 1642, 1599, 472, -1, 1596, 1146, 1148, -1, + 2436, 2842, 1462, -1, 2436, 2437, 2842, -1, + 1247, 473, 1169, -1, 1247, 1246, 473, -1, + 1171, 747, 479, -1, 1171, 479, 1173, -1, + 1171, 1164, 747, -1, 2841, 1656, 2571, -1, + 2841, 2842, 2437, -1, 2841, 2437, 1656, -1, + 476, 474, 475, -1, 476, 753, 474, -1, + 752, 475, 1249, -1, 752, 1249, 1252, -1, + 752, 476, 475, -1, 752, 753, 476, -1, + 757, 498, 756, -1, 757, 497, 498, -1, + 757, 758, 497, -1, 477, 748, 478, -1, + 477, 480, 479, -1, 477, 479, 747, -1, + 477, 747, 748, -1, 477, 478, 481, -1, + 477, 481, 480, -1, 482, 484, 483, -1, + 482, 755, 484, -1, 482, 760, 755, -1, + 482, 485, 760, -1, 482, 486, 485, -1, + 482, 483, 486, -1, 489, 490, 1159, -1, + 489, 487, 488, -1, 489, 751, 487, -1, + 489, 1159, 751, -1, 492, 488, 1179, -1, + 492, 489, 488, -1, 492, 490, 489, -1, + 492, 491, 490, -1, 496, 1179, 1180, -1, + 496, 759, 491, -1, 496, 491, 492, -1, + 496, 492, 1179, -1, 769, 777, 781, -1, + 772, 763, 493, -1, 772, 493, 494, -1, + 772, 494, 774, -1, 495, 779, 765, -1, + 495, 759, 496, -1, 495, 758, 759, -1, + 495, 765, 758, -1, 495, 1180, 779, -1, + 495, 496, 1180, -1, 768, 776, 777, -1, + 768, 765, 776, -1, 768, 497, 766, -1, + 768, 777, 769, -1, 768, 499, 498, -1, + 768, 498, 497, -1, 768, 774, 499, -1, + 778, 781, 777, -1, 778, 779, 782, -1, + 778, 782, 781, -1, 1673, 2119, 781, -1, + 503, 500, 1679, -1, 503, 501, 500, -1, + 503, 502, 501, -1, 503, 505, 502, -1, + 503, 504, 505, -1, 503, 1679, 1677, -1, + 784, 1677, 786, -1, 784, 503, 1677, -1, + 784, 504, 503, -1, 784, 505, 504, -1, + 784, 560, 505, -1, 784, 785, 560, -1, + 1190, 1193, 1202, -1, 1190, 1202, 791, -1, + 1198, 1199, 794, -1, 1203, 1202, 1193, -1, + 2125, 796, 507, -1, 2125, 507, 1689, -1, + 1176, 798, 1175, -1, 1176, 515, 798, -1, + 1212, 791, 1202, -1, 1208, 507, 1205, -1, + 1208, 1689, 507, -1, 795, 793, 506, -1, + 795, 506, 1205, -1, 795, 507, 796, -1, + 795, 1205, 507, -1, 1218, 508, 1217, -1, + 1218, 509, 508, -1, 1218, 1695, 509, -1, + 2130, 510, 2129, -1, 2130, 511, 510, -1, + 2130, 1450, 511, -1, 2130, 2131, 1450, -1, + 2122, 2125, 1689, -1, 1913, 1192, 1914, -1, + 1913, 1449, 1192, -1, 815, 512, 814, -1, + 815, 524, 512, -1, 835, 838, 837, -1, + 835, 512, 838, -1, 835, 799, 512, -1, + 761, 513, 514, -1, 761, 514, 515, -1, + 761, 515, 1176, -1, 761, 1181, 513, -1, + 803, 1231, 805, -1, 803, 516, 517, -1, + 803, 1235, 1231, -1, 803, 517, 1235, -1, + 803, 804, 809, -1, 803, 809, 516, -1, + 518, 519, 1045, -1, 518, 520, 519, -1, + 518, 521, 520, -1, 518, 523, 522, -1, + 518, 1507, 523, -1, 518, 1045, 1507, -1, + 518, 522, 521, -1, 812, 1497, 691, -1, + 812, 691, 525, -1, 812, 525, 524, -1, + 812, 524, 815, -1, 817, 525, 818, -1, + 817, 526, 525, -1, 817, 820, 526, -1, + 825, 822, 527, -1, 825, 527, 530, -1, + 1220, 528, 1506, -1, 1220, 826, 528, -1, + 529, 530, 531, -1, 529, 531, 826, -1, + 529, 825, 530, -1, 529, 826, 825, -1, + 532, 533, 540, -1, 532, 546, 533, -1, + 532, 540, 538, -1, 532, 534, 546, -1, + 532, 538, 535, -1, 532, 535, 534, -1, + 536, 537, 538, -1, 536, 539, 537, -1, + 536, 538, 540, -1, 536, 540, 539, -1, + 808, 810, 829, -1, 808, 829, 541, -1, + 808, 542, 806, -1, 808, 831, 542, -1, + 808, 541, 831, -1, 1226, 829, 543, -1, + 1226, 547, 1227, -1, 1226, 544, 547, -1, + 1226, 543, 544, -1, 545, 547, 546, -1, + 545, 1227, 547, -1, 545, 546, 548, -1, + 545, 548, 1227, -1, 790, 786, 549, -1, + 790, 841, 789, -1, 790, 549, 833, -1, + 790, 833, 841, -1, 840, 841, 833, -1, + 550, 552, 551, -1, 550, 557, 552, -1, + 550, 553, 557, -1, 550, 551, 554, -1, + 550, 554, 555, -1, 550, 555, 553, -1, + 1242, 556, 843, -1, 1242, 557, 556, -1, + 1242, 1243, 557, -1, 558, 559, 560, -1, + 558, 843, 559, -1, 558, 560, 561, -1, + 558, 561, 842, -1, 558, 842, 843, -1, + 562, 568, 569, -1, 562, 569, 573, -1, + 562, 566, 568, -1, 562, 573, 574, -1, + 562, 848, 566, -1, 562, 574, 848, -1, + 850, 564, 563, -1, 850, 851, 564, -1, + 850, 563, 844, -1, 565, 566, 848, -1, + 565, 848, 567, -1, 565, 568, 566, -1, + 565, 567, 568, -1, 1700, 842, 579, -1, + 1700, 579, 578, -1, 1700, 578, 1705, -1, + 572, 569, 571, -1, 572, 573, 569, -1, + 847, 574, 577, -1, 847, 848, 574, -1, + 847, 576, 851, -1, 847, 577, 576, -1, + 570, 578, 577, -1, 570, 1705, 578, -1, + 570, 571, 1705, -1, 570, 572, 571, -1, + 570, 573, 572, -1, 570, 574, 573, -1, + 570, 577, 574, -1, 575, 584, 576, -1, + 575, 576, 577, -1, 575, 577, 578, -1, + 575, 578, 579, -1, 575, 579, 580, -1, + 575, 580, 584, -1, 581, 583, 582, -1, + 581, 582, 584, -1, 581, 585, 583, -1, + 581, 586, 585, -1, 581, 584, 586, -1, + 1671, 2573, 1659, -1, 1713, 1712, 587, -1, + 1713, 587, 588, -1, 1713, 588, 1250, -1, + 1253, 589, 1712, -1, 1253, 590, 589, -1, + 1253, 1248, 590, -1, 856, 592, 591, -1, + 856, 591, 854, -1, 856, 1250, 592, -1, + 856, 854, 1708, -1, 871, 844, 600, -1, + 596, 1255, 593, -1, 596, 595, 1256, -1, + 596, 594, 595, -1, 596, 593, 594, -1, + 1260, 861, 1261, -1, 862, 595, 858, -1, + 862, 1256, 595, -1, 1717, 1255, 596, -1, + 1717, 596, 1256, -1, 1715, 1725, 1729, -1, + 597, 867, 866, -1, 597, 866, 598, -1, + 597, 1257, 867, -1, 597, 598, 1257, -1, + 868, 599, 1254, -1, 868, 1254, 866, -1, + 868, 600, 599, -1, 868, 871, 600, -1, + 601, 602, 872, -1, 601, 603, 602, -1, + 601, 872, 969, -1, 601, 972, 603, -1, + 601, 969, 970, -1, 601, 970, 972, -1, + 955, 969, 872, -1, 955, 965, 969, -1, + 1265, 872, 604, -1, 1265, 604, 605, -1, + 1265, 605, 606, -1, 1265, 606, 1269, -1, + 607, 873, 874, -1, 607, 874, 608, -1, + 607, 608, 1731, -1, 607, 1731, 1872, -1, + 607, 1872, 873, -1, 1271, 1408, 875, -1, + 880, 886, 879, -1, 880, 885, 886, -1, + 877, 609, 881, -1, 877, 610, 609, -1, + 877, 878, 611, -1, 877, 611, 610, -1, + 2375, 612, 2377, -1, 2375, 1410, 612, -1, + 620, 614, 613, -1, 620, 615, 614, -1, + 620, 900, 615, -1, 620, 613, 622, -1, + 1278, 895, 616, -1, 1278, 616, 618, -1, + 1278, 618, 1277, -1, 625, 1389, 1279, -1, + 625, 2230, 2231, -1, 1276, 2230, 625, -1, + 1276, 625, 1279, -1, 1388, 1279, 1808, -1, + 898, 618, 617, -1, 898, 899, 618, -1, + 898, 619, 901, -1, 898, 617, 619, -1, + 904, 903, 900, -1, 904, 620, 622, -1, + 904, 900, 620, -1, 1784, 621, 1785, -1, + 1784, 622, 621, -1, 1784, 904, 622, -1, + 1786, 2229, 902, -1, 1786, 902, 903, -1, + 936, 623, 1294, -1, 936, 1294, 1392, -1, + 936, 1061, 623, -1, 3001, 624, 1289, -1, + 3001, 3002, 624, -1, 906, 1737, 2303, -1, + 906, 2156, 2155, -1, 2583, 2156, 1281, -1, + 1761, 1304, 1749, -1, 1761, 1749, 2852, -1, + 1396, 907, 1395, -1, 909, 1308, 908, -1, + 911, 1308, 909, -1, 2186, 2185, 912, -1, + 2220, 1898, 1887, -1, 918, 1390, 1389, -1, + 918, 1389, 625, -1, 918, 625, 2231, -1, + 918, 2231, 1792, -1, 1319, 916, 1324, -1, + 1319, 914, 916, -1, 2614, 2616, 1322, -1, + 2080, 1793, 915, -1, 2080, 915, 2083, -1, + 1789, 2082, 917, -1, 1789, 2080, 2082, -1, + 1789, 1793, 2080, -1, 1379, 626, 1378, -1, + 1379, 627, 626, -1, 1379, 628, 627, -1, + 1379, 1380, 628, -1, 1407, 935, 923, -1, + 1335, 1338, 921, -1, 1337, 921, 1338, -1, + 927, 919, 1375, -1, 927, 1375, 926, -1, + 1347, 632, 629, -1, 1347, 629, 630, -1, + 1347, 630, 631, -1, 1347, 631, 1348, -1, + 1349, 879, 632, -1, 1349, 633, 879, -1, + 1349, 632, 1347, -1, 1349, 924, 633, -1, + 944, 926, 2237, -1, 944, 2237, 1849, -1, + 2234, 926, 1375, -1, 2234, 2237, 926, -1, + 1367, 929, 1370, -1, 930, 1370, 929, -1, + 930, 634, 1369, -1, 930, 1369, 1370, -1, + 930, 1355, 634, -1, 930, 1354, 1355, -1, + 1373, 1374, 1353, -1, 2239, 2238, 943, -1, + 2239, 1849, 2237, -1, 1796, 1360, 635, -1, + 1796, 635, 942, -1, 1796, 942, 2238, -1, + 1339, 1358, 1363, -1, 1339, 1359, 1358, -1, + 1339, 1343, 1359, -1, 1340, 1348, 636, -1, + 1340, 636, 637, -1, 1340, 637, 638, -1, + 1340, 639, 1341, -1, 1340, 638, 639, -1, + 1377, 640, 935, -1, 1377, 934, 640, -1, + 1381, 641, 932, -1, 1381, 932, 1382, -1, + 1381, 1378, 641, -1, 1631, 1380, 1804, -1, + 1631, 1632, 642, -1, 1631, 642, 1380, -1, + 2284, 2285, 917, -1, 2284, 917, 2082, -1, + 1393, 1061, 936, -1, 1399, 937, 938, -1, + 643, 1828, 644, -1, 643, 644, 2251, -1, + 643, 2251, 1828, -1, 1846, 1845, 657, -1, + 1846, 657, 2363, -1, 2730, 2729, 941, -1, + 2730, 941, 645, -1, 2730, 645, 1402, -1, + 946, 947, 648, -1, 946, 648, 662, -1, + 946, 662, 966, -1, 946, 966, 951, -1, + 1865, 646, 1409, -1, 1865, 1866, 646, -1, + 1863, 2382, 875, -1, 1863, 875, 1408, -1, + 1868, 647, 1864, -1, 1868, 648, 647, -1, + 1868, 1869, 648, -1, 649, 655, 650, -1, + 649, 651, 655, -1, 649, 652, 651, -1, + 649, 650, 652, -1, 653, 1401, 654, -1, + 653, 654, 655, -1, 653, 655, 656, -1, + 653, 656, 657, -1, 653, 657, 1401, -1, + 953, 954, 658, -1, 953, 658, 659, -1, + 953, 659, 660, -1, 953, 660, 956, -1, + 963, 661, 959, -1, 964, 951, 966, -1, + 964, 956, 951, -1, 962, 1730, 661, -1, + 962, 662, 1730, -1, 962, 966, 662, -1, + 962, 661, 963, -1, 971, 958, 972, -1, + 968, 969, 965, -1, 968, 958, 971, -1, + 968, 963, 958, -1, 1423, 974, 1424, -1, + 973, 667, 974, -1, 973, 1009, 667, -1, + 976, 1424, 974, -1, 976, 977, 1424, -1, + 976, 974, 667, -1, 2398, 663, 1427, -1, + 2398, 1880, 663, -1, 1413, 982, 1441, -1, + 1413, 1441, 1896, -1, 1443, 1441, 982, -1, + 1903, 1887, 1898, -1, 2221, 1889, 1311, -1, + 1432, 973, 1433, -1, 1432, 1009, 973, -1, + 1895, 983, 669, -1, 1895, 669, 1894, -1, + 989, 1057, 1052, -1, 1454, 994, 992, -1, + 1051, 988, 1052, -1, 1051, 992, 988, -1, + 1935, 2420, 1910, -1, 1935, 1458, 1933, -1, + 664, 1452, 990, -1, 664, 1925, 1452, -1, + 664, 990, 665, -1, 664, 991, 1925, -1, + 664, 665, 1451, -1, 664, 1451, 991, -1, + 666, 2426, 1458, -1, 666, 1542, 2426, -1, + 666, 2015, 1542, -1, 666, 1910, 2015, -1, + 666, 1935, 1910, -1, 666, 1458, 1935, -1, + 1457, 1933, 1458, -1, 1457, 1454, 1933, -1, + 1457, 994, 1454, -1, 981, 679, 980, -1, + 981, 667, 1011, -1, 981, 1011, 679, -1, + 981, 976, 667, -1, 985, 996, 668, -1, + 985, 669, 983, -1, 985, 668, 669, -1, + 985, 983, 1439, -1, 995, 668, 996, -1, + 995, 1937, 668, -1, 1938, 668, 1937, -1, + 1938, 1463, 669, -1, 1938, 669, 668, -1, + 1666, 1665, 670, -1, 1666, 670, 999, -1, + 1668, 671, 2114, -1, 1668, 1474, 671, -1, + 1002, 1670, 683, -1, 1002, 2836, 1670, -1, + 1002, 683, 1010, -1, 1002, 1010, 1004, -1, + 1460, 1461, 2833, -1, 672, 1000, 673, -1, + 672, 673, 676, -1, 672, 676, 1000, -1, + 674, 682, 675, -1, 674, 675, 676, -1, + 674, 676, 677, -1, 674, 680, 682, -1, + 674, 677, 678, -1, 674, 678, 680, -1, + 1007, 679, 1011, -1, 1007, 680, 679, -1, + 1007, 682, 680, -1, 1006, 681, 682, -1, + 1006, 682, 1007, -1, 1006, 683, 681, -1, + 1006, 1010, 683, -1, 1008, 1432, 1431, -1, + 1008, 1009, 1432, -1, 1008, 1431, 1004, -1, + 1008, 1004, 1010, -1, 1014, 1016, 1488, -1, + 1014, 1488, 1489, -1, 1026, 1027, 1019, -1, + 1026, 1022, 1029, -1, 1956, 1024, 1028, -1, + 1482, 1076, 713, -1, 1482, 1075, 1076, -1, + 1481, 1012, 1487, -1, 1481, 684, 1012, -1, + 1481, 713, 684, -1, 1481, 1482, 713, -1, + 715, 689, 684, -1, 715, 688, 689, -1, + 715, 716, 688, -1, 715, 684, 713, -1, + 685, 1964, 687, -1, 685, 1222, 1963, -1, + 685, 1963, 1964, -1, 685, 718, 1222, -1, + 685, 687, 686, -1, 685, 686, 718, -1, + 1047, 688, 687, -1, 1047, 1493, 688, -1, + 1047, 687, 1964, -1, 1494, 1033, 689, -1, + 1494, 689, 1493, -1, 1017, 1504, 1500, -1, + 1017, 1035, 1504, -1, 1039, 1042, 1037, -1, + 1039, 1500, 1042, -1, 1039, 1040, 1017, -1, + 1039, 1017, 1500, -1, 1501, 1491, 1495, -1, + 690, 691, 1495, -1, 690, 821, 818, -1, + 690, 818, 691, -1, 690, 1046, 821, -1, + 690, 1495, 1491, -1, 690, 1491, 1046, -1, + 1960, 1044, 821, -1, 1960, 821, 1046, -1, + 1056, 692, 1049, -1, 1056, 1054, 692, -1, + 693, 694, 1054, -1, 693, 1023, 1021, -1, + 693, 1021, 694, -1, 693, 695, 1023, -1, + 693, 1054, 1055, -1, 693, 1055, 695, -1, + 1508, 1509, 1530, -1, 1532, 1055, 1531, -1, + 1532, 1509, 695, -1, 1532, 695, 1055, -1, + 1532, 1530, 1509, -1, 2037, 2467, 2468, -1, + 2508, 1645, 2505, -1, 2508, 2475, 1645, -1, + 1515, 1285, 1989, -1, 1515, 1989, 1988, -1, + 1516, 1989, 1285, -1, 1284, 1516, 1285, -1, + 1063, 2468, 1072, -1, 1063, 1072, 1571, -1, + 1063, 1571, 1519, -1, 1536, 1537, 1522, -1, + 1536, 1522, 1508, -1, 1536, 1508, 1530, -1, + 2454, 1541, 2459, -1, 1543, 2019, 2018, -1, + 2021, 2019, 1436, -1, 2425, 1542, 2018, -1, + 2425, 2426, 1542, -1, 1066, 1549, 1554, -1, + 2208, 1066, 2206, -1, 2027, 2028, 2430, -1, + 1556, 2034, 1557, -1, 1533, 1070, 2004, -1, + 1533, 1069, 1070, -1, 1539, 1997, 1540, -1, + 1539, 1282, 1997, -1, 1578, 1579, 1540, -1, + 1578, 1071, 1577, -1, 1995, 2805, 2461, -1, + 1995, 2461, 1071, -1, 1566, 1541, 2043, -1, + 1566, 2043, 1478, -1, 1566, 1478, 1570, -1, + 2458, 1569, 1064, -1, 1031, 1955, 1969, -1, + 1031, 1570, 1949, -1, 1031, 1969, 1567, -1, + 1031, 1567, 1570, -1, 1968, 1969, 1955, -1, + 1968, 1029, 1967, -1, 2795, 2030, 3012, -1, + 1575, 1073, 1528, -1, 1587, 1584, 1123, -1, + 2497, 2498, 1075, -1, 1079, 1593, 696, -1, + 1079, 697, 1589, -1, 1079, 696, 697, -1, + 1079, 1080, 1593, -1, 1592, 1090, 1594, -1, + 1592, 1152, 1090, -1, 1120, 1591, 1588, -1, + 1120, 1588, 1084, -1, 1085, 1083, 1087, -1, + 1085, 1086, 1118, -1, 1089, 698, 699, -1, + 1089, 699, 1090, -1, 1089, 1092, 700, -1, + 1089, 700, 698, -1, 1098, 1097, 704, -1, + 701, 704, 1107, -1, 701, 1098, 704, -1, + 1104, 1101, 1095, -1, 1104, 701, 1107, -1, + 1104, 1098, 701, -1, 1102, 1103, 1100, -1, + 2064, 1619, 1609, -1, 1617, 1613, 1107, -1, + 1109, 1108, 1619, -1, 1109, 1617, 1108, -1, + 1116, 1115, 1108, -1, 1116, 702, 1625, -1, + 1116, 704, 702, -1, 1116, 1108, 704, -1, + 703, 1106, 1107, -1, 703, 1107, 704, -1, + 703, 1108, 1106, -1, 703, 704, 1108, -1, + 1110, 1112, 2061, -1, 1110, 2061, 2062, -1, + 709, 1112, 1111, -1, 709, 708, 705, -1, + 709, 706, 1112, -1, 709, 707, 706, -1, + 709, 705, 707, -1, 2070, 1114, 708, -1, + 2070, 708, 709, -1, 2070, 709, 1111, -1, + 2065, 2066, 1620, -1, 1627, 1629, 1115, -1, + 1602, 2072, 1086, -1, 1602, 1603, 710, -1, + 1602, 710, 711, -1, 1602, 711, 1114, -1, + 1582, 1078, 721, -1, 1582, 721, 1121, -1, + 1582, 1580, 1078, -1, 712, 713, 1076, -1, + 712, 1076, 1077, -1, 712, 1077, 714, -1, + 712, 715, 713, -1, 712, 714, 716, -1, + 712, 716, 715, -1, 1224, 720, 1223, -1, + 1224, 1222, 718, -1, 717, 718, 719, -1, + 717, 721, 720, -1, 717, 720, 1224, -1, + 717, 1224, 718, -1, 717, 719, 1121, -1, + 717, 1121, 721, -1, 2522, 1125, 1632, -1, + 2077, 2076, 1127, -1, 2077, 1127, 2523, -1, + 722, 724, 723, -1, 722, 725, 724, -1, + 722, 723, 864, -1, 722, 864, 1715, -1, + 722, 1715, 1729, -1, 722, 726, 725, -1, + 722, 1729, 726, -1, 1727, 1262, 727, -1, + 1727, 727, 1729, -1, 728, 916, 914, -1, + 728, 914, 1514, -1, 728, 1514, 1984, -1, + 728, 1984, 1511, -1, 1314, 1514, 914, -1, + 1314, 1513, 1514, -1, 1314, 1316, 1513, -1, + 1643, 1315, 1637, -1, 2538, 2083, 1060, -1, + 1330, 916, 728, -1, 1330, 1511, 1512, -1, + 1330, 728, 1511, -1, 2100, 1640, 1775, -1, + 1130, 731, 729, -1, 1130, 729, 730, -1, + 1130, 730, 1131, -1, 1134, 1133, 731, -1, + 1134, 731, 1130, -1, 2101, 2100, 1775, -1, + 2101, 1775, 1776, -1, 2101, 1776, 1133, -1, + 1646, 1647, 1132, -1, 1646, 1132, 1653, -1, + 1141, 1142, 732, -1, 1141, 732, 1139, -1, + 1140, 1653, 1143, -1, 733, 734, 735, -1, + 733, 1136, 734, -1, 733, 735, 736, -1, + 733, 736, 1136, -1, 1151, 742, 1091, -1, + 737, 738, 742, -1, 737, 740, 739, -1, + 737, 739, 738, -1, 737, 742, 743, -1, + 737, 741, 740, -1, 737, 743, 741, -1, + 1154, 743, 742, -1, 1154, 744, 743, -1, + 1154, 1156, 744, -1, 1154, 742, 1151, -1, + 1149, 745, 1155, -1, 1149, 1148, 1138, -1, + 1149, 1138, 1137, -1, 1149, 1137, 745, -1, + 1145, 1148, 1146, -1, 1145, 1138, 1148, -1, + 1145, 1648, 1138, -1, 1145, 2098, 1648, -1, + 1153, 1152, 1592, -1, 1641, 2086, 1146, -1, + 1641, 1146, 1596, -1, 1160, 1168, 1166, -1, + 1160, 1161, 746, -1, 1160, 746, 1168, -1, + 749, 1168, 746, -1, 749, 747, 1164, -1, + 749, 748, 747, -1, 749, 746, 748, -1, + 1167, 749, 1164, -1, 1167, 1168, 749, -1, + 1158, 751, 1159, -1, 1215, 1214, 750, -1, + 1215, 1158, 1216, -1, 1215, 750, 751, -1, + 1215, 751, 1158, -1, 1211, 791, 1212, -1, + 2550, 1656, 2437, -1, 1680, 1211, 1216, -1, + 1680, 791, 1211, -1, 1710, 1663, 1711, -1, + 1658, 1164, 1171, -1, 1172, 752, 1252, -1, + 1172, 1173, 753, -1, 1172, 753, 752, -1, + 1251, 1671, 1659, -1, 1251, 1172, 1252, -1, + 2843, 1461, 2842, -1, 2843, 2833, 1461, -1, + 754, 756, 755, -1, 754, 757, 756, -1, + 754, 758, 757, -1, 754, 759, 758, -1, + 754, 755, 760, -1, 754, 760, 759, -1, + 1178, 1181, 761, -1, 1178, 761, 1176, -1, + 773, 769, 781, -1, 773, 1678, 771, -1, + 773, 781, 2119, -1, 773, 2119, 1678, -1, + 762, 770, 763, -1, 762, 763, 772, -1, + 762, 772, 770, -1, 764, 766, 765, -1, + 764, 768, 766, -1, 764, 765, 768, -1, + 767, 768, 769, -1, 767, 771, 770, -1, + 767, 770, 772, -1, 767, 773, 771, -1, + 767, 769, 773, -1, 767, 772, 774, -1, + 767, 774, 768, -1, 775, 777, 776, -1, + 775, 778, 777, -1, 775, 776, 779, -1, + 775, 779, 778, -1, 780, 781, 782, -1, + 780, 1673, 781, -1, 780, 782, 1672, -1, + 780, 1672, 1673, -1, 783, 785, 784, -1, + 783, 784, 786, -1, 783, 787, 785, -1, + 783, 788, 787, -1, 783, 789, 788, -1, + 783, 790, 789, -1, 783, 786, 790, -1, + 1681, 1190, 791, -1, 1681, 791, 1680, -1, + 1681, 1685, 1189, -1, 1681, 1189, 1190, -1, + 1187, 1189, 1685, -1, 2104, 1187, 1685, -1, + 1188, 1914, 1192, -1, 1188, 1189, 1187, -1, + 2106, 1186, 2105, -1, 2106, 1919, 1186, -1, + 1691, 1209, 1203, -1, 1201, 1038, 1200, -1, + 1195, 1196, 1041, -1, 1195, 1038, 1201, -1, + 2126, 1198, 796, -1, 2126, 796, 2125, -1, + 1213, 1206, 1214, -1, 792, 794, 793, -1, + 792, 793, 795, -1, 792, 1198, 794, -1, + 792, 796, 1198, -1, 792, 795, 796, -1, + 1688, 1218, 1217, -1, 1912, 1186, 1919, -1, + 797, 835, 834, -1, 797, 1175, 798, -1, + 797, 798, 799, -1, 797, 799, 835, -1, + 797, 800, 1175, -1, 797, 834, 801, -1, + 797, 801, 800, -1, 802, 804, 803, -1, + 802, 803, 805, -1, 802, 806, 807, -1, + 802, 808, 806, -1, 802, 809, 804, -1, + 802, 807, 809, -1, 802, 805, 810, -1, + 802, 810, 808, -1, 811, 1497, 812, -1, + 811, 1496, 1497, -1, 811, 813, 1496, -1, + 811, 814, 813, -1, 811, 815, 814, -1, + 811, 812, 815, -1, 816, 817, 818, -1, + 816, 1044, 819, -1, 816, 819, 820, -1, + 816, 820, 817, -1, 816, 818, 821, -1, + 816, 821, 1044, -1, 827, 822, 825, -1, + 827, 823, 822, -1, 827, 1223, 824, -1, + 827, 824, 823, -1, 1505, 1963, 1222, -1, + 1505, 1220, 1506, -1, 1221, 825, 826, -1, + 1221, 826, 1220, -1, 1221, 1223, 827, -1, + 1221, 827, 825, -1, 1228, 828, 829, -1, + 1228, 829, 1226, -1, 1228, 830, 831, -1, + 1228, 831, 828, -1, 1228, 1229, 830, -1, + 832, 840, 833, -1, 832, 833, 834, -1, + 832, 837, 840, -1, 832, 834, 835, -1, + 832, 835, 837, -1, 836, 840, 837, -1, + 836, 1230, 840, -1, 836, 837, 838, -1, + 836, 838, 839, -1, 836, 839, 1230, -1, + 1234, 1235, 1240, -1, 1237, 840, 1230, -1, + 1237, 841, 840, -1, 1237, 1241, 841, -1, + 1699, 842, 1700, -1, 1699, 843, 842, -1, + 1699, 1242, 843, -1, 849, 850, 844, -1, + 849, 844, 871, -1, 849, 870, 852, -1, + 849, 871, 870, -1, 1703, 1704, 845, -1, + 1703, 845, 1702, -1, 846, 848, 847, -1, + 846, 850, 849, -1, 846, 851, 850, -1, + 846, 847, 851, -1, 846, 852, 848, -1, + 846, 849, 852, -1, 1245, 853, 1246, -1, + 1245, 1708, 854, -1, 1245, 855, 853, -1, + 1245, 854, 855, -1, 1707, 1250, 856, -1, + 1707, 856, 1708, -1, 2143, 1248, 1253, -1, + 857, 862, 858, -1, 857, 858, 859, -1, + 857, 859, 860, -1, 857, 860, 861, -1, + 857, 861, 1260, -1, 857, 1260, 862, -1, + 1719, 1715, 1720, -1, 1728, 1256, 862, -1, + 1728, 862, 1260, -1, 863, 1715, 864, -1, + 863, 1720, 1715, -1, 863, 864, 1722, -1, + 863, 1722, 1720, -1, 865, 866, 867, -1, + 865, 868, 866, -1, 865, 867, 869, -1, + 865, 869, 870, -1, 865, 870, 871, -1, + 865, 871, 868, -1, 1264, 955, 872, -1, + 1264, 872, 1265, -1, 1264, 1268, 954, -1, + 1264, 954, 955, -1, 1270, 873, 1872, -1, + 1270, 874, 873, -1, 1270, 875, 874, -1, + 1270, 1271, 875, -1, 876, 878, 877, -1, + 876, 879, 878, -1, 876, 880, 879, -1, + 876, 885, 880, -1, 876, 881, 885, -1, + 876, 877, 881, -1, 1273, 888, 1862, -1, + 894, 884, 893, -1, 894, 882, 884, -1, + 894, 883, 882, -1, 894, 2377, 883, -1, + 890, 893, 884, -1, 890, 885, 891, -1, + 890, 886, 885, -1, 890, 884, 886, -1, + 887, 889, 888, -1, 887, 890, 891, -1, + 887, 893, 890, -1, 887, 1860, 893, -1, + 887, 891, 892, -1, 887, 892, 889, -1, + 887, 888, 1273, -1, 887, 1273, 1860, -1, + 2376, 893, 1860, -1, 2376, 2377, 894, -1, + 2376, 894, 893, -1, 1275, 1806, 895, -1, + 1275, 895, 1278, -1, 1275, 2272, 1806, -1, + 1275, 1388, 2272, -1, 896, 1276, 1277, -1, + 896, 1277, 899, -1, 896, 899, 902, -1, + 896, 902, 2229, -1, 896, 2229, 2230, -1, + 896, 2230, 1276, -1, 897, 899, 898, -1, + 897, 900, 903, -1, 897, 901, 900, -1, + 897, 898, 901, -1, 897, 903, 902, -1, + 897, 902, 899, -1, 1783, 1786, 903, -1, + 1783, 903, 904, -1, 1783, 904, 1784, -1, + 1818, 1392, 1293, -1, 1818, 1293, 1280, -1, + 1286, 1515, 1986, -1, 1286, 1285, 1515, -1, + 905, 3001, 1289, -1, 905, 1288, 1282, -1, + 905, 1289, 1288, -1, 905, 3000, 3001, -1, + 905, 1282, 1539, -1, 905, 1539, 3000, -1, + 1739, 2679, 2678, -1, 2304, 2667, 1281, -1, + 2304, 1281, 2156, -1, 2304, 2156, 906, -1, + 2304, 906, 2303, -1, 1292, 1742, 1280, -1, + 1292, 1280, 1293, -1, 2007, 2597, 2593, -1, + 2007, 2452, 2597, -1, 1741, 1280, 1742, -1, + 1741, 2583, 1281, -1, 1545, 2784, 1747, -1, + 1545, 1546, 2783, -1, 1545, 2783, 2784, -1, + 2173, 2176, 1553, -1, 1734, 906, 2155, -1, + 1734, 2155, 1740, -1, 1734, 1740, 1735, -1, + 1734, 1737, 906, -1, 1297, 2151, 2152, -1, + 1297, 1759, 2151, -1, 1299, 1304, 1761, -1, + 1299, 1768, 1304, -1, 1299, 1761, 2214, -1, + 1750, 1303, 907, -1, 1750, 907, 1396, -1, + 1750, 1396, 2604, -1, 1750, 1749, 1303, -1, + 1302, 907, 1303, -1, 1302, 913, 907, -1, + 1302, 1764, 913, -1, 910, 2185, 2189, -1, + 910, 909, 908, -1, 910, 908, 912, -1, + 910, 912, 2185, -1, 1769, 2222, 911, -1, + 1305, 911, 909, -1, 1305, 910, 2189, -1, + 1305, 909, 910, -1, 1305, 1769, 911, -1, + 1307, 1308, 911, -1, 1307, 911, 2222, -1, + 1307, 2222, 2221, -1, 1307, 2221, 1311, -1, + 1765, 2186, 912, -1, 1765, 912, 913, -1, + 1765, 913, 1764, -1, 1899, 1898, 2220, -1, + 1899, 2166, 2167, -1, 2219, 2220, 1887, -1, + 2219, 1889, 2221, -1, 1638, 1637, 1315, -1, + 1318, 1317, 1638, -1, 1318, 1638, 1315, -1, + 1313, 914, 1319, -1, 1313, 1314, 914, -1, + 1313, 1318, 1315, -1, 1313, 1319, 1318, -1, + 1639, 1317, 1772, -1, 1639, 1638, 1317, -1, + 1774, 1775, 1640, -1, 1774, 1640, 1639, -1, + 1774, 1639, 1772, -1, 1773, 1772, 1317, -1, + 1321, 1325, 1322, -1, 1321, 1331, 1325, -1, + 2608, 1792, 2231, -1, 2609, 1322, 1325, -1, + 2609, 2614, 1322, -1, 1791, 1325, 1331, -1, + 1327, 915, 1793, -1, 1327, 1328, 915, -1, + 1327, 1793, 1791, -1, 1327, 1791, 1331, -1, + 1329, 1324, 916, -1, 1329, 916, 1330, -1, + 1329, 1321, 1324, -1, 1329, 1331, 1321, -1, + 1788, 1789, 917, -1, 1788, 917, 1390, -1, + 1788, 918, 1792, -1, 1788, 1390, 918, -1, + 1333, 1374, 919, -1, 1333, 1335, 1374, -1, + 1333, 919, 927, -1, 1333, 927, 1334, -1, + 1336, 1338, 1335, -1, 1336, 1334, 1406, -1, + 1336, 1405, 1338, -1, 1336, 1406, 1405, -1, + 920, 921, 1337, -1, 920, 1335, 921, -1, + 920, 923, 922, -1, 920, 1337, 923, -1, + 920, 922, 1374, -1, 920, 1374, 1335, -1, + 1853, 1407, 923, -1, 1853, 923, 1337, -1, + 1346, 1363, 1362, -1, 1346, 1339, 1363, -1, + 1345, 1355, 924, -1, 1345, 924, 1349, -1, + 1345, 1362, 1355, -1, 1345, 1346, 1362, -1, + 925, 926, 944, -1, 925, 1406, 1334, -1, + 925, 1852, 1406, -1, 925, 944, 1852, -1, + 925, 927, 926, -1, 925, 1334, 927, -1, + 1352, 1356, 1353, -1, 928, 929, 1367, -1, + 928, 1367, 1356, -1, 928, 930, 929, -1, + 928, 1356, 1354, -1, 928, 1354, 930, -1, + 1794, 1356, 1367, -1, 1366, 1359, 1360, -1, + 1372, 1353, 1356, -1, 1372, 1373, 1353, -1, + 1372, 1794, 2235, -1, 1372, 1356, 1794, -1, + 1342, 1341, 931, -1, 1342, 931, 1343, -1, + 1376, 1382, 932, -1, 1376, 932, 933, -1, + 1376, 933, 934, -1, 1376, 934, 1377, -1, + 1802, 1407, 1801, -1, 1802, 935, 1407, -1, + 1802, 1377, 935, -1, 1383, 1378, 1381, -1, + 2763, 3152, 1633, -1, 2073, 2371, 2764, -1, + 2073, 2243, 1387, -1, 2073, 1387, 2371, -1, + 2248, 2246, 1128, -1, 1805, 1391, 2291, -1, + 3066, 2288, 3067, -1, 2290, 2291, 1391, -1, + 2081, 2085, 2287, -1, 2081, 2284, 2082, -1, + 2081, 2287, 2284, -1, 1820, 936, 1392, -1, + 1820, 1393, 936, -1, 3089, 2679, 3090, -1, + 2599, 1394, 2182, -1, 1748, 1394, 937, -1, + 1748, 2182, 1394, -1, 1397, 938, 1823, -1, + 1397, 2706, 938, -1, 939, 937, 1399, -1, + 939, 1748, 937, -1, 939, 2326, 1748, -1, + 1398, 938, 2706, -1, 1398, 1399, 938, -1, + 2325, 2326, 939, -1, 2325, 939, 1399, -1, + 2722, 2859, 1856, -1, 1832, 2349, 3129, -1, + 1832, 2708, 2349, -1, 2269, 2268, 2357, -1, + 1848, 2367, 940, -1, 1848, 940, 1403, -1, + 1848, 1403, 1841, -1, 1404, 941, 2729, -1, + 1404, 2755, 943, -1, 1404, 943, 942, -1, + 1404, 942, 941, -1, 2754, 943, 2755, -1, + 2754, 2239, 943, -1, 2754, 1849, 2239, -1, + 1850, 944, 1849, -1, 1850, 1852, 944, -1, + 2952, 2951, 3154, -1, 945, 947, 946, -1, + 945, 949, 948, -1, 945, 948, 947, -1, + 945, 950, 949, -1, 945, 951, 950, -1, + 945, 946, 951, -1, 1874, 1865, 1409, -1, + 1877, 1408, 1271, -1, 952, 954, 953, -1, + 952, 965, 955, -1, 952, 955, 954, -1, + 952, 964, 965, -1, 952, 953, 956, -1, + 952, 956, 964, -1, 957, 958, 963, -1, + 957, 963, 959, -1, 957, 960, 958, -1, + 957, 959, 960, -1, 961, 962, 963, -1, + 961, 965, 964, -1, 961, 964, 966, -1, + 961, 966, 962, -1, 961, 968, 965, -1, + 961, 963, 968, -1, 967, 969, 968, -1, + 967, 970, 969, -1, 967, 968, 971, -1, + 967, 972, 970, -1, 967, 971, 972, -1, + 1412, 1433, 973, -1, 1412, 973, 974, -1, + 1412, 1423, 1415, -1, 1412, 974, 1423, -1, + 975, 977, 976, -1, 975, 979, 978, -1, + 975, 978, 977, -1, 975, 980, 979, -1, + 975, 981, 980, -1, 975, 976, 981, -1, + 1426, 1425, 1418, -1, 1426, 1420, 1883, -1, + 2388, 2389, 1901, -1, 1881, 1415, 1423, -1, + 1881, 1882, 1415, -1, 1888, 2219, 1887, -1, + 1888, 1889, 2219, -1, 1414, 1421, 982, -1, + 1414, 982, 1413, -1, 1414, 1415, 1882, -1, + 1414, 1882, 1421, -1, 1430, 982, 1421, -1, + 1430, 1443, 982, -1, 1430, 1902, 2404, -1, + 1430, 1421, 1902, -1, 1897, 1413, 1896, -1, + 1446, 1907, 1908, -1, 1442, 1907, 1446, -1, + 1438, 1896, 1441, -1, 1438, 1895, 1896, -1, + 1438, 1439, 983, -1, 1438, 983, 1895, -1, + 1440, 1446, 1447, -1, 1440, 1442, 1446, -1, + 984, 1447, 1468, -1, 984, 985, 1439, -1, + 984, 1440, 1447, -1, 984, 1439, 1440, -1, + 984, 1468, 996, -1, 984, 996, 985, -1, + 1058, 1534, 1531, -1, 1058, 1057, 989, -1, + 986, 989, 1065, -1, 986, 1533, 1534, -1, + 986, 1534, 1058, -1, 986, 1058, 989, -1, + 986, 1065, 1069, -1, 986, 1069, 1533, -1, + 987, 1052, 988, -1, 987, 989, 1052, -1, + 987, 988, 2434, -1, 987, 1065, 989, -1, + 987, 2434, 2432, -1, 987, 2432, 1065, -1, + 993, 1050, 990, -1, 993, 990, 1452, -1, + 993, 1051, 1050, -1, 993, 992, 1051, -1, + 1434, 1909, 1456, -1, 1434, 2011, 2408, -1, + 2421, 1910, 2420, -1, 1445, 1456, 1455, -1, + 1445, 1434, 1456, -1, 1445, 1908, 2011, -1, + 1445, 2011, 1434, -1, 1470, 1468, 1447, -1, + 1470, 1455, 1469, -1, 1915, 991, 1451, -1, + 1916, 991, 1915, -1, 1926, 1925, 991, -1, + 1926, 1916, 1922, -1, 1926, 991, 1916, -1, + 1453, 1454, 992, -1, 1453, 992, 993, -1, + 1453, 993, 1452, -1, 2419, 1456, 1909, -1, + 2419, 1909, 2421, -1, 2433, 2434, 994, -1, + 2433, 994, 1457, -1, 1936, 2436, 1462, -1, + 1936, 1463, 1938, -1, 2557, 997, 2555, -1, + 2557, 995, 997, -1, 2557, 1937, 995, -1, + 1466, 997, 995, -1, 1466, 1467, 997, -1, + 1466, 995, 996, -1, 1466, 996, 1468, -1, + 1943, 1469, 1942, -1, 1943, 1944, 1467, -1, + 1945, 1473, 1944, -1, 1918, 2106, 2107, -1, + 1918, 1919, 2106, -1, 998, 1944, 1473, -1, + 998, 997, 1467, -1, 998, 1467, 1944, -1, + 998, 2555, 997, -1, 2549, 1473, 2548, -1, + 2549, 2555, 998, -1, 2549, 998, 1473, -1, + 1476, 1666, 999, -1, 1476, 1667, 1666, -1, + 1476, 999, 1000, -1, 1476, 1000, 1475, -1, + 1464, 1460, 1003, -1, 1464, 1894, 1463, -1, + 1464, 1893, 1894, -1, 1464, 1003, 1893, -1, + 1001, 2833, 2836, -1, 1001, 1460, 2833, -1, + 1001, 2836, 1002, -1, 1001, 1003, 1460, -1, + 1001, 1004, 1003, -1, 1001, 1002, 1004, -1, + 1005, 1006, 1007, -1, 1005, 1009, 1008, -1, + 1005, 1010, 1006, -1, 1005, 1008, 1010, -1, + 1005, 1011, 1009, -1, 1005, 1007, 1011, -1, + 1034, 1035, 1014, -1, 1034, 1012, 1033, -1, + 1034, 1489, 1012, -1, 1034, 1014, 1489, -1, + 1013, 1014, 1035, -1, 1013, 1040, 1015, -1, + 1013, 1015, 1016, -1, 1013, 1016, 1014, -1, + 1013, 1017, 1040, -1, 1013, 1035, 1017, -1, + 1018, 1019, 1020, -1, 1018, 1026, 1019, -1, + 1018, 1020, 1021, -1, 1018, 1022, 1026, -1, + 1018, 1021, 1023, -1, 1018, 1023, 1022, -1, + 1957, 1024, 1956, -1, 1957, 1479, 1025, -1, + 1957, 1025, 1024, -1, 1030, 1027, 1026, -1, + 1030, 1028, 1027, -1, 1030, 1956, 1028, -1, + 1030, 1026, 1029, -1, 1954, 1029, 1968, -1, + 1954, 1968, 1955, -1, 1954, 1030, 1029, -1, + 1954, 1956, 1030, -1, 1477, 2042, 1484, -1, + 1477, 2041, 2042, -1, 1953, 1031, 1949, -1, + 1953, 1955, 1031, -1, 1950, 1488, 1479, -1, + 1483, 1075, 1482, -1, 1483, 2497, 1075, -1, + 1483, 1484, 2044, -1, 1483, 2044, 2497, -1, + 1486, 1477, 1484, -1, 1486, 1948, 1477, -1, + 1492, 1046, 1491, -1, 1492, 1493, 1047, -1, + 1032, 1033, 1494, -1, 1032, 1034, 1033, -1, + 1032, 1035, 1034, -1, 1032, 1504, 1035, -1, + 1032, 1502, 1504, -1, 1032, 1494, 1502, -1, + 1036, 1037, 1038, -1, 1036, 1039, 1037, -1, + 1036, 1038, 1195, -1, 1036, 1040, 1039, -1, + 1036, 1041, 1040, -1, 1036, 1195, 1041, -1, + 1499, 1042, 1500, -1, 1499, 1496, 1043, -1, + 1499, 1043, 1042, -1, 1961, 1044, 1960, -1, + 1961, 1507, 1045, -1, 1961, 1045, 1044, -1, + 1959, 1960, 1046, -1, 1959, 1046, 1492, -1, + 1959, 1047, 1964, -1, 1959, 1492, 1047, -1, + 1048, 1049, 1050, -1, 1048, 1056, 1049, -1, + 1048, 1050, 1051, -1, 1048, 1057, 1056, -1, + 1048, 1052, 1057, -1, 1048, 1051, 1052, -1, + 1053, 1055, 1054, -1, 1053, 1054, 1056, -1, + 1053, 1056, 1057, -1, 1053, 1531, 1055, -1, + 1053, 1057, 1058, -1, 1053, 1058, 1531, -1, + 1971, 1522, 1523, -1, 1971, 1508, 1522, -1, + 1059, 2442, 2301, -1, 1059, 2301, 2540, -1, + 1059, 2540, 2539, -1, 1059, 2539, 1976, -1, + 1520, 2443, 2442, -1, 1520, 2442, 1059, -1, + 1520, 1976, 1978, -1, 1520, 1059, 1976, -1, + 1983, 1511, 1984, -1, 2038, 1513, 2474, -1, + 1973, 1976, 2539, -1, 1973, 2539, 2538, -1, + 1973, 1060, 1974, -1, 1973, 2538, 1060, -1, + 2441, 2302, 2301, -1, 2441, 2301, 2442, -1, + 1062, 1284, 1287, -1, 1062, 1287, 1061, -1, + 1062, 1061, 1393, -1, 1062, 1393, 1815, -1, + 1814, 1516, 1284, -1, 1814, 1816, 1516, -1, + 1814, 1062, 1815, -1, 1814, 1284, 1062, -1, + 1572, 1519, 1571, -1, 1572, 2803, 1991, -1, + 2804, 1991, 2803, -1, 1518, 1063, 1519, -1, + 1518, 1982, 1063, -1, 1981, 2037, 2468, -1, + 1981, 2468, 1063, -1, 1981, 1063, 1982, -1, + 2456, 1064, 1073, -1, 2456, 2458, 1064, -1, + 1526, 1073, 1064, -1, 1526, 1064, 1521, -1, + 1526, 1528, 1073, -1, 2002, 1536, 1530, -1, + 2464, 2457, 2462, -1, 2772, 2782, 1543, -1, + 1552, 1555, 2021, -1, 1552, 2021, 1436, -1, + 1552, 1436, 1546, -1, 2020, 2021, 1555, -1, + 1068, 2432, 2430, -1, 1068, 1065, 2432, -1, + 1068, 1069, 1065, -1, 1068, 2430, 2028, -1, + 2171, 2206, 1066, -1, 2171, 1066, 1554, -1, + 1561, 1549, 1066, -1, 1561, 1066, 2208, -1, + 1746, 1561, 2208, -1, 2024, 1562, 2453, -1, + 2024, 2453, 1556, -1, 2429, 2027, 2430, -1, + 1067, 2423, 1550, -1, 1067, 2026, 2027, -1, + 1067, 2429, 2423, -1, 1067, 2027, 2429, -1, + 1067, 1550, 1548, -1, 1067, 1548, 2026, -1, + 1560, 2026, 1548, -1, 1560, 1548, 1549, -1, + 1560, 1549, 1561, -1, 1743, 2597, 2452, -1, + 2451, 1562, 1744, -1, 2451, 1744, 1743, -1, + 2451, 1743, 2452, -1, 2451, 2453, 1562, -1, + 1558, 1557, 1070, -1, 1558, 1068, 2028, -1, + 1558, 1070, 1069, -1, 1558, 1069, 1068, -1, + 1563, 2004, 1070, -1, 1563, 1070, 1557, -1, + 1563, 1557, 2034, -1, 1563, 2034, 2035, -1, + 1994, 1578, 1540, -1, 1994, 1540, 1997, -1, + 1994, 1071, 1578, -1, 1994, 1995, 1071, -1, + 1565, 1541, 1566, -1, 1565, 2459, 1541, -1, + 1565, 2458, 2459, -1, 1565, 1569, 2458, -1, + 2036, 1072, 2468, -1, 2036, 1571, 1072, -1, + 1574, 2794, 1579, -1, 1574, 2795, 2794, -1, + 1576, 1073, 1575, -1, 1576, 2457, 2456, -1, + 1576, 2456, 1073, -1, 1576, 1577, 2457, -1, + 1586, 2486, 2484, -1, 1586, 2484, 1580, -1, + 1074, 1075, 2498, -1, 1074, 2498, 1587, -1, + 1074, 1587, 1123, -1, 1074, 1076, 1075, -1, + 1074, 1123, 1077, -1, 1074, 1077, 1076, -1, + 2053, 1584, 1587, -1, 1623, 1580, 2484, -1, + 1623, 1624, 1078, -1, 1623, 1078, 1580, -1, + 2049, 1588, 1591, -1, 2813, 2516, 2048, -1, + 2051, 2048, 2516, -1, 2051, 2516, 2515, -1, + 1590, 1080, 1079, -1, 1590, 2047, 1081, -1, + 1590, 1081, 1080, -1, 1590, 1079, 1589, -1, + 1597, 1153, 1592, -1, 1082, 1083, 1085, -1, + 1082, 1084, 1083, -1, 1082, 1120, 1084, -1, + 1082, 1119, 1120, -1, 1082, 1118, 1119, -1, + 1082, 1085, 1118, -1, 1601, 1086, 1085, -1, + 1601, 1602, 1086, -1, 1601, 1087, 1607, -1, + 1601, 1085, 1087, -1, 1088, 1089, 1090, -1, + 1088, 1151, 1091, -1, 1088, 1091, 1092, -1, + 1088, 1092, 1089, -1, 1088, 1090, 1152, -1, + 1088, 1152, 1151, -1, 1093, 1095, 1094, -1, + 1093, 1104, 1095, -1, 1093, 1094, 1096, -1, + 1093, 1096, 1097, -1, 1093, 1097, 1098, -1, + 1093, 1098, 1104, -1, 1099, 1100, 1101, -1, + 1099, 1102, 1100, -1, 1099, 1103, 1102, -1, + 1099, 1104, 1107, -1, 1099, 1101, 1104, -1, + 1099, 1107, 1613, -1, 1099, 1613, 1103, -1, + 1615, 1617, 2064, -1, 1105, 1107, 1106, -1, + 1105, 1617, 1107, -1, 1105, 1106, 1108, -1, + 1105, 1108, 1617, -1, 1618, 1617, 1109, -1, + 1618, 1109, 1619, -1, 2069, 1110, 2062, -1, + 2069, 1111, 1112, -1, 2069, 1112, 1110, -1, + 2069, 2070, 1111, -1, 2069, 2065, 1620, -1, + 1113, 2070, 2072, -1, 1113, 1114, 2070, -1, + 1113, 2072, 1602, -1, 1113, 1602, 1114, -1, + 1622, 1627, 1115, -1, 1622, 2040, 1627, -1, + 1622, 1116, 1625, -1, 1622, 1115, 1116, -1, + 1630, 1117, 1628, -1, 1630, 1118, 1117, -1, + 1630, 1119, 1118, -1, 1630, 2479, 1119, -1, + 2480, 1627, 2040, -1, 2478, 1119, 2479, -1, + 2478, 1120, 1119, -1, 2478, 2481, 1591, -1, + 2478, 1591, 1120, -1, 1581, 1121, 1122, -1, + 1581, 1582, 1121, -1, 1581, 1122, 1123, -1, + 1581, 1123, 1584, -1, 1124, 1126, 1125, -1, + 1124, 1125, 2522, -1, 1124, 2522, 2523, -1, + 1124, 1127, 1126, -1, 1124, 2523, 1127, -1, + 2526, 1631, 1804, -1, 2537, 2246, 2076, -1, + 2537, 1128, 2246, -1, 2537, 2248, 1128, -1, + 2300, 2302, 1988, -1, 1636, 2088, 2087, -1, + 1636, 2099, 2088, -1, 1636, 1640, 2100, -1, + 1636, 2100, 2099, -1, 1644, 1645, 2475, -1, + 1644, 2475, 1316, -1, 2091, 1637, 2087, -1, + 2091, 1643, 1637, -1, 1129, 1134, 1130, -1, + 1129, 1130, 1131, -1, 1129, 1131, 1142, -1, + 1129, 1142, 1132, -1, 1129, 1132, 1647, -1, + 1129, 1647, 1134, -1, 2102, 2101, 1133, -1, + 2102, 1134, 1647, -1, 2102, 1133, 1134, -1, + 1135, 1653, 1136, -1, 1135, 1646, 1653, -1, + 1135, 1648, 1646, -1, 1135, 1136, 1137, -1, + 1135, 1138, 1648, -1, 1135, 1137, 1138, -1, + 1652, 1139, 1651, -1, 1652, 1653, 1140, -1, + 1652, 1141, 1139, -1, 1652, 1142, 1141, -1, + 1652, 1143, 1142, -1, 1652, 1140, 1143, -1, + 1144, 1145, 1146, -1, 1144, 2086, 2088, -1, + 1144, 1146, 2086, -1, 1144, 2088, 2099, -1, + 1144, 2099, 2098, -1, 1144, 2098, 1145, -1, + 1147, 1155, 1153, -1, 1147, 1596, 1148, -1, + 1147, 1597, 1596, -1, 1147, 1153, 1597, -1, + 1147, 1149, 1155, -1, 1147, 1148, 1149, -1, + 1150, 1151, 1152, -1, 1150, 1152, 1153, -1, + 1150, 1154, 1151, -1, 1150, 1153, 1155, -1, + 1150, 1155, 1156, -1, 1150, 1156, 1154, -1, + 1163, 1160, 1166, -1, 1163, 1216, 1158, -1, + 1157, 1158, 1159, -1, 1157, 1161, 1160, -1, + 1157, 1160, 1163, -1, 1157, 1163, 1158, -1, + 1157, 1162, 1161, -1, 1157, 1159, 1162, -1, + 1655, 1656, 2550, -1, 1655, 2570, 1654, -1, + 1683, 1166, 2569, -1, 1683, 1163, 1166, -1, + 1683, 1216, 1163, -1, 1683, 1680, 1216, -1, + 1660, 1654, 1167, -1, 1660, 1167, 1164, -1, + 1660, 1164, 1658, -1, 1165, 2570, 2569, -1, + 1165, 1654, 2570, -1, 1165, 2569, 1166, -1, + 1165, 1167, 1654, -1, 1165, 1166, 1168, -1, + 1165, 1168, 1167, -1, 1664, 1663, 1710, -1, + 1664, 1169, 1665, -1, 1664, 1247, 1169, -1, + 1664, 1710, 1247, -1, 2113, 1668, 2114, -1, + 2112, 1711, 1663, -1, 2112, 1663, 2111, -1, + 1170, 1659, 1658, -1, 1170, 1251, 1659, -1, + 1170, 1658, 1171, -1, 1170, 1172, 1251, -1, + 1170, 1171, 1173, -1, 1170, 1173, 1172, -1, + 1182, 2117, 1178, -1, 1182, 1183, 2117, -1, + 1182, 1175, 1174, -1, 1182, 1174, 1676, -1, + 1182, 1176, 1175, -1, 1182, 1178, 1176, -1, + 1177, 1178, 2117, -1, 1177, 1180, 1179, -1, + 1177, 1179, 1181, -1, 1177, 1181, 1178, -1, + 1177, 1672, 1180, -1, 1177, 2117, 1672, -1, + 1184, 1182, 1676, -1, 1184, 1183, 1182, -1, + 2116, 2117, 1183, -1, 2116, 1183, 1184, -1, + 2116, 1678, 2119, -1, 2116, 1184, 1676, -1, + 2103, 1187, 2104, -1, 2103, 2105, 1186, -1, + 1185, 1914, 1188, -1, 1185, 1912, 1914, -1, + 1185, 1186, 1912, -1, 1185, 2103, 1186, -1, + 1185, 1188, 1187, -1, 1185, 1187, 2103, -1, + 1191, 1188, 1192, -1, 1191, 1189, 1188, -1, + 1191, 1193, 1190, -1, 1191, 1190, 1189, -1, + 1687, 1209, 1691, -1, 1687, 1208, 1209, -1, + 1687, 1689, 1208, -1, 1687, 1691, 1697, -1, + 2132, 1449, 2131, -1, 1194, 1191, 1192, -1, + 1194, 1193, 1191, -1, 1194, 1192, 1449, -1, + 1194, 1449, 2132, -1, 1690, 1203, 1193, -1, + 1690, 1691, 1203, -1, 1690, 1193, 1194, -1, + 1690, 1194, 2132, -1, 1694, 1201, 2124, -1, + 1694, 1195, 1201, -1, 1694, 1692, 1196, -1, + 1694, 1196, 1195, -1, 1197, 1198, 2126, -1, + 1197, 1200, 1199, -1, 1197, 1199, 1198, -1, + 1197, 1201, 1200, -1, 1197, 2124, 1201, -1, + 1197, 2126, 2124, -1, 1207, 1212, 1202, -1, + 1207, 1213, 1212, -1, 1207, 1202, 1203, -1, + 1207, 1203, 1209, -1, 1204, 1205, 1206, -1, + 1204, 1206, 1213, -1, 1204, 1213, 1207, -1, + 1204, 1208, 1205, -1, 1204, 1209, 1208, -1, + 1204, 1207, 1209, -1, 1210, 1211, 1212, -1, + 1210, 1212, 1213, -1, 1210, 1213, 1214, -1, + 1210, 1214, 1215, -1, 1210, 1215, 1216, -1, + 1210, 1216, 1211, -1, 2121, 1217, 1693, -1, + 2121, 1688, 1217, -1, 2121, 2122, 1688, -1, + 1696, 1695, 1218, -1, 1696, 1218, 1688, -1, + 1219, 1220, 1505, -1, 1219, 1221, 1220, -1, + 1219, 1505, 1222, -1, 1219, 1223, 1221, -1, + 1219, 1222, 1224, -1, 1219, 1224, 1223, -1, + 1225, 1226, 1227, -1, 1225, 1228, 1226, -1, + 1225, 1227, 1229, -1, 1225, 1229, 1228, -1, + 1236, 1237, 1230, -1, 1236, 1231, 1235, -1, + 1236, 1232, 1231, -1, 1236, 1230, 1232, -1, + 1233, 1235, 1234, -1, 1233, 1236, 1235, -1, + 1233, 1237, 1236, -1, 1233, 1239, 1238, -1, + 1233, 1240, 1239, -1, 1233, 1234, 1240, -1, + 1233, 1238, 1241, -1, 1233, 1241, 1237, -1, + 1701, 1243, 1242, -1, 1701, 1242, 1699, -1, + 1701, 1244, 1243, -1, 1701, 1702, 1244, -1, + 1709, 1245, 1246, -1, 1709, 1708, 1245, -1, + 1709, 1246, 1247, -1, 1709, 1247, 1710, -1, + 2144, 1248, 2143, -1, 2144, 1249, 1248, -1, + 2144, 1252, 1249, -1, 2577, 1707, 2578, -1, + 2577, 1713, 1250, -1, 2577, 1250, 1707, -1, + 2145, 2146, 1671, -1, 2145, 1671, 1251, -1, + 2145, 1251, 1252, -1, 2145, 1252, 2144, -1, + 2137, 1253, 1712, -1, 2137, 2143, 1253, -1, + 1716, 1719, 1259, -1, 1716, 1259, 1254, -1, + 1716, 1254, 1255, -1, 1716, 1255, 1717, -1, + 1724, 1717, 1256, -1, 1724, 1256, 1728, -1, + 1721, 1722, 1257, -1, 1721, 1257, 1258, -1, + 1721, 1258, 1259, -1, 1721, 1259, 1719, -1, + 1726, 1260, 1261, -1, 1726, 1728, 1260, -1, + 1726, 1261, 1262, -1, 1726, 1262, 1727, -1, + 1263, 1264, 1265, -1, 1263, 1267, 1266, -1, + 1263, 1266, 1268, -1, 1263, 1268, 1264, -1, + 1263, 1269, 1267, -1, 1263, 1265, 1269, -1, + 1879, 1270, 1872, -1, 1879, 1271, 1270, -1, + 1879, 1877, 1271, -1, 1272, 1861, 1860, -1, + 1272, 1860, 1273, -1, 1272, 1862, 1861, -1, + 1272, 1273, 1862, -1, 1274, 1388, 1275, -1, + 1274, 1277, 1276, -1, 1274, 1278, 1277, -1, + 1274, 1275, 1278, -1, 1274, 1276, 1279, -1, + 1274, 1279, 1388, -1, 1819, 1818, 1280, -1, + 1819, 1741, 1281, -1, 1819, 1280, 1741, -1, + 1819, 1281, 2667, -1, 1732, 1288, 1286, -1, + 1732, 1999, 1282, -1, 1732, 1282, 1288, -1, + 1732, 1286, 1986, -1, 1283, 1284, 1285, -1, + 1283, 1285, 1286, -1, 1283, 1287, 1284, -1, + 1283, 1286, 1288, -1, 1283, 1289, 1287, -1, + 1283, 1288, 1289, -1, 1736, 2152, 1739, -1, + 1736, 1297, 2152, -1, 1736, 1735, 1297, -1, + 1736, 1739, 2678, -1, 1290, 2593, 1742, -1, + 1290, 1742, 1292, -1, 1290, 1292, 2009, -1, + 1290, 2007, 2593, -1, 1290, 2009, 2008, -1, + 1290, 2008, 2007, -1, 1291, 2009, 1292, -1, + 1291, 2790, 3005, -1, 1291, 3005, 2009, -1, + 1291, 1292, 1293, -1, 1291, 1294, 2790, -1, + 1291, 1293, 1294, -1, 2202, 2180, 2203, -1, + 1301, 1738, 1300, -1, 1301, 1299, 2214, -1, + 1295, 1760, 1752, -1, 1295, 1751, 1300, -1, + 1295, 1752, 1755, -1, 1295, 1755, 1751, -1, + 1758, 1300, 1738, -1, 1758, 1295, 1300, -1, + 1758, 1760, 1295, -1, 1758, 1738, 2153, -1, + 2213, 1301, 2214, -1, 2213, 1738, 1301, -1, + 1771, 2159, 2161, -1, 1771, 1770, 1759, -1, + 1296, 1759, 1297, -1, 1296, 2159, 1771, -1, + 1296, 1771, 1759, -1, 1296, 1740, 2159, -1, + 1296, 1735, 1740, -1, 1296, 1297, 1735, -1, + 1298, 1768, 1299, -1, 1298, 1767, 1768, -1, + 1298, 1751, 1767, -1, 1298, 1300, 1751, -1, + 1298, 1301, 1300, -1, 1298, 1299, 1301, -1, + 1763, 1302, 1303, -1, 1763, 1304, 1768, -1, + 1763, 1303, 1304, -1, 1763, 1764, 1302, -1, + 2199, 1305, 2189, -1, 2199, 1769, 1305, -1, + 1306, 1308, 1307, -1, 1306, 1310, 1309, -1, + 1306, 1309, 1308, -1, 1306, 1311, 1310, -1, + 1306, 1307, 1311, -1, 2198, 2203, 2164, -1, + 2198, 1769, 2199, -1, 2218, 2164, 2166, -1, + 2218, 2166, 1899, -1, 2218, 1899, 2220, -1, + 1753, 2224, 2589, -1, 1753, 2589, 2175, -1, + 1753, 2175, 2187, -1, 1753, 2187, 2193, -1, + 2223, 1752, 1760, -1, 2223, 2224, 1752, -1, + 2223, 1760, 1770, -1, 1312, 1314, 1313, -1, + 1312, 1643, 1644, -1, 1312, 1315, 1643, -1, + 1312, 1313, 1315, -1, 1312, 1316, 1314, -1, + 1312, 1644, 1316, -1, 2228, 1774, 1772, -1, + 1323, 1773, 1317, -1, 1323, 1317, 1318, -1, + 1323, 1319, 1324, -1, 1323, 1318, 1319, -1, + 1320, 1321, 1322, -1, 1320, 1322, 2616, -1, + 1320, 2616, 1773, -1, 1320, 1773, 1323, -1, + 1320, 1324, 1321, -1, 1320, 1323, 1324, -1, + 2232, 1786, 1783, -1, 1790, 2609, 1325, -1, + 1790, 1325, 1791, -1, 1790, 1792, 2608, -1, + 1790, 2608, 2609, -1, 1326, 1328, 1327, -1, + 1326, 1329, 1330, -1, 1326, 1327, 1331, -1, + 1326, 1331, 1329, -1, 1326, 1512, 1328, -1, + 1326, 1330, 1512, -1, 1332, 1333, 1334, -1, + 1332, 1335, 1333, -1, 1332, 1334, 1336, -1, + 1332, 1336, 1335, -1, 1854, 1853, 1337, -1, + 1854, 1338, 1405, -1, 1854, 1337, 1338, -1, + 1854, 1405, 2760, -1, 1350, 1339, 1346, -1, + 1350, 1340, 1341, -1, 1350, 1348, 1340, -1, + 1350, 1341, 1342, -1, 1350, 1343, 1339, -1, + 1350, 1342, 1343, -1, 1344, 1346, 1345, -1, + 1344, 1347, 1348, -1, 1344, 1349, 1347, -1, + 1344, 1345, 1349, -1, 1344, 1348, 1350, -1, + 1344, 1350, 1346, -1, 1351, 1352, 1353, -1, + 1351, 1355, 1354, -1, 1351, 1354, 1356, -1, + 1351, 1356, 1352, -1, 1351, 1353, 1374, -1, + 1351, 1357, 1355, -1, 1351, 1374, 1357, -1, + 1364, 1363, 1358, -1, 1364, 1358, 1359, -1, + 1364, 1359, 1366, -1, 1795, 1794, 1367, -1, + 1795, 1367, 1366, -1, 1795, 1360, 1796, -1, + 1795, 1366, 1360, -1, 1361, 1368, 1369, -1, + 1361, 1369, 1362, -1, 1361, 1362, 1363, -1, + 1361, 1366, 1368, -1, 1361, 1363, 1364, -1, + 1361, 1364, 1366, -1, 1365, 1366, 1367, -1, + 1365, 1368, 1366, -1, 1365, 1369, 1368, -1, + 1365, 1370, 1369, -1, 1365, 1367, 1370, -1, + 1371, 1373, 1372, -1, 1371, 1375, 1374, -1, + 1371, 1374, 1373, -1, 1371, 2234, 1375, -1, + 1371, 2235, 2234, -1, 1371, 1372, 2235, -1, + 1798, 1799, 1382, -1, 1798, 1382, 1376, -1, + 1798, 1376, 1377, -1, 1798, 1377, 1802, -1, + 1384, 1378, 1383, -1, 1384, 1380, 1379, -1, + 1384, 1379, 1378, -1, 1384, 1804, 1380, -1, + 1386, 1383, 1381, -1, 1386, 1381, 1382, -1, + 1386, 1382, 1799, -1, 1386, 2242, 1383, -1, + 2241, 1383, 2242, -1, 2241, 1804, 1384, -1, + 2241, 1384, 1383, -1, 2075, 2764, 2763, -1, + 2075, 2073, 2764, -1, 1385, 1803, 1387, -1, + 1385, 2242, 1386, -1, 1385, 2243, 2242, -1, + 1385, 1387, 2243, -1, 1385, 1799, 1803, -1, + 1385, 1386, 1799, -1, 2370, 1387, 1803, -1, + 2370, 1800, 2765, -1, 2370, 1803, 1800, -1, + 2370, 2371, 1387, -1, 2989, 2750, 2767, -1, + 2369, 1800, 1801, -1, 2369, 2765, 1800, -1, + 2369, 2987, 2765, -1, 2250, 2251, 2247, -1, + 2263, 1391, 1805, -1, 2263, 2264, 1391, -1, + 2263, 1805, 2628, -1, 2262, 1811, 2264, -1, + 2271, 2272, 1388, -1, 2271, 1388, 1808, -1, + 1809, 1808, 1389, -1, 1809, 1389, 1390, -1, + 1809, 1390, 2285, -1, 1809, 2285, 2286, -1, + 1810, 2290, 1391, -1, 1810, 1391, 2264, -1, + 1810, 2264, 1811, -1, 1810, 2662, 2290, -1, + 2292, 2255, 2288, -1, 2292, 2293, 2257, -1, + 2292, 2257, 2255, -1, 2277, 2287, 2085, -1, + 3033, 3032, 2644, -1, 2252, 2297, 2449, -1, + 2252, 2449, 1816, -1, 2305, 1392, 1818, -1, + 2305, 1820, 1392, -1, 1821, 1393, 1820, -1, + 1821, 1815, 1393, -1, 1821, 1817, 1815, -1, + 1821, 2669, 1817, -1, 2672, 2918, 1822, -1, + 2307, 1822, 2637, -1, 2674, 2882, 2303, -1, + 2674, 2303, 1737, -1, 2674, 1737, 2677, -1, + 3200, 3198, 2316, -1, 2600, 1395, 1394, -1, + 2600, 1394, 2599, -1, 2600, 1396, 1395, -1, + 2600, 2604, 1396, -1, 2705, 2706, 1397, -1, + 2705, 1397, 1823, -1, 1825, 1399, 1398, -1, + 1825, 2325, 1399, -1, 1825, 3115, 2325, -1, + 1825, 1398, 2706, -1, 1400, 3154, 2951, -1, + 1400, 2331, 1633, -1, 1400, 3152, 3154, -1, + 1400, 1633, 3152, -1, 1855, 1400, 2951, -1, + 1855, 2331, 1400, -1, 2861, 1828, 2251, -1, + 2948, 2722, 1856, -1, 2345, 1830, 2689, -1, + 2345, 2956, 3130, -1, 1831, 3122, 2343, -1, + 1831, 2340, 1832, -1, 1827, 1824, 1826, -1, + 1827, 2322, 1824, -1, 1827, 2335, 2322, -1, + 1840, 1401, 1845, -1, 1840, 1833, 1401, -1, + 1840, 1839, 1833, -1, 1836, 2351, 2735, -1, + 1836, 2735, 1835, -1, 2734, 1835, 2735, -1, + 2734, 1402, 1835, -1, 2734, 2730, 1402, -1, + 2354, 2353, 2982, -1, 2892, 2975, 2350, -1, + 2267, 1841, 1403, -1, 2267, 2269, 1841, -1, + 2267, 1403, 1806, -1, 2743, 2867, 2352, -1, + 1847, 1848, 1841, -1, 2732, 1404, 2729, -1, + 2732, 2755, 1404, -1, 1851, 2761, 2760, -1, + 1851, 2760, 1405, -1, 1851, 1405, 1406, -1, + 1851, 1406, 1852, -1, 2368, 1801, 1407, -1, + 2368, 1407, 1853, -1, 2368, 2369, 1801, -1, + 1858, 2380, 1863, -1, 1858, 1863, 1408, -1, + 1858, 1408, 1877, -1, 1858, 1877, 1875, -1, + 1857, 1874, 1409, -1, 1857, 1875, 1874, -1, + 1857, 1409, 1410, -1, 1857, 1410, 2375, -1, + 2373, 2376, 1860, -1, 2379, 2380, 2373, -1, + 1876, 1865, 1874, -1, 1411, 1433, 1412, -1, + 1411, 1897, 1433, -1, 1411, 1413, 1897, -1, + 1411, 1414, 1413, -1, 1411, 1412, 1415, -1, + 1411, 1415, 1414, -1, 1416, 1418, 1417, -1, + 1416, 1426, 1418, -1, 1416, 1420, 1426, -1, + 1416, 1419, 1420, -1, 1416, 1417, 1419, -1, + 2385, 1420, 1419, -1, 2385, 1419, 1880, -1, + 2384, 1883, 1420, -1, 2384, 1420, 2385, -1, + 2387, 1902, 1421, -1, 2387, 1421, 1882, -1, + 1422, 1423, 1424, -1, 1422, 1881, 1423, -1, + 1422, 1424, 1425, -1, 1422, 1883, 1881, -1, + 1422, 1425, 1426, -1, 1422, 1426, 1883, -1, + 1885, 2389, 1886, -1, 1885, 1901, 2389, -1, + 1885, 1904, 1901, -1, 1885, 1903, 1904, -1, + 2395, 1886, 2396, -1, 2399, 2398, 1427, -1, + 2399, 1428, 1890, -1, 2399, 1427, 1428, -1, + 2771, 1430, 2404, -1, 1429, 1443, 1430, -1, + 1429, 1907, 1442, -1, 1429, 1442, 1443, -1, + 1429, 2994, 1907, -1, 1429, 2771, 2994, -1, + 1429, 1430, 2771, -1, 1892, 1893, 1431, -1, + 1892, 1431, 1432, -1, 1892, 1432, 1433, -1, + 1892, 1433, 1897, -1, 1905, 1903, 1898, -1, + 2414, 1747, 2784, -1, 2013, 1909, 1434, -1, + 2013, 1434, 2408, -1, 1435, 2019, 1543, -1, + 1435, 1543, 2782, -1, 1435, 2782, 2783, -1, + 1435, 1436, 2019, -1, 1435, 2783, 1546, -1, + 1435, 1546, 1436, -1, 1437, 1439, 1438, -1, + 1437, 1440, 1439, -1, 1437, 1438, 1441, -1, + 1437, 1442, 1440, -1, 1437, 1441, 1443, -1, + 1437, 1443, 1442, -1, 1444, 1445, 1455, -1, + 1444, 1447, 1446, -1, 1444, 1446, 1908, -1, + 1444, 1908, 1445, -1, 1444, 1470, 1447, -1, + 1444, 1455, 1470, -1, 1448, 1913, 1915, -1, + 1448, 2131, 1449, -1, 1448, 1449, 1913, -1, + 1448, 1450, 2131, -1, 1448, 1451, 1450, -1, + 1448, 1915, 1451, -1, 1920, 1912, 1919, -1, + 1920, 1922, 1916, -1, 1924, 1923, 1471, -1, + 1924, 1471, 1928, -1, 1924, 1922, 1923, -1, + 1924, 1926, 1922, -1, 2416, 1471, 1941, -1, + 2416, 1928, 1471, -1, 2416, 2417, 1928, -1, + 1929, 1453, 1452, -1, 1929, 1452, 1925, -1, + 1932, 1453, 1929, -1, 1932, 1933, 1454, -1, + 1932, 1454, 1453, -1, 1927, 1455, 1456, -1, + 1927, 1456, 2419, -1, 1927, 1942, 1469, -1, + 1927, 1469, 1455, -1, 2427, 1457, 1458, -1, + 2427, 2433, 1457, -1, 2427, 1458, 2426, -1, + 1459, 1461, 1460, -1, 1459, 1462, 1461, -1, + 1459, 1936, 1462, -1, 1459, 1463, 1936, -1, + 1459, 1464, 1463, -1, 1459, 1460, 1464, -1, + 2553, 1937, 2557, -1, 1465, 1467, 1466, -1, + 1465, 1943, 1467, -1, 1465, 1466, 1468, -1, + 1465, 1469, 1943, -1, 1465, 1468, 1470, -1, + 1465, 1470, 1469, -1, 1940, 1941, 1471, -1, + 1940, 1471, 1923, -1, 1940, 1923, 1921, -1, + 1940, 1921, 1945, -1, 1472, 1921, 1918, -1, + 1472, 1945, 1921, -1, 1472, 1473, 1945, -1, + 1472, 2548, 1473, -1, 1472, 2107, 2548, -1, + 1472, 1918, 2107, -1, 1669, 1474, 1668, -1, + 1669, 1475, 1474, -1, 1669, 1476, 1475, -1, + 1669, 1667, 1476, -1, 1947, 1477, 1948, -1, + 1947, 2041, 1477, -1, 1947, 1949, 1478, -1, + 1947, 1478, 2041, -1, 1952, 1479, 1957, -1, + 1952, 1950, 1479, -1, 1480, 1487, 1486, -1, + 1480, 1481, 1487, -1, 1480, 1482, 1481, -1, + 1480, 1483, 1482, -1, 1480, 1484, 1483, -1, + 1480, 1486, 1484, -1, 1485, 1950, 1948, -1, + 1485, 1948, 1486, -1, 1485, 1486, 1487, -1, + 1485, 1488, 1950, -1, 1485, 1489, 1488, -1, + 1485, 1487, 1489, -1, 1490, 1491, 1501, -1, + 1490, 1492, 1491, -1, 1490, 1501, 1502, -1, + 1490, 1493, 1492, -1, 1490, 1494, 1493, -1, + 1490, 1502, 1494, -1, 1503, 1501, 1495, -1, + 1503, 1496, 1499, -1, 1503, 1497, 1496, -1, + 1503, 1495, 1497, -1, 1498, 1499, 1500, -1, + 1498, 1502, 1501, -1, 1498, 1501, 1503, -1, + 1498, 1503, 1499, -1, 1498, 1500, 1504, -1, + 1498, 1504, 1502, -1, 1962, 1505, 1506, -1, + 1962, 1963, 1505, -1, 1962, 1506, 1507, -1, + 1962, 1507, 1961, -1, 1970, 1568, 1567, -1, + 1970, 1523, 1568, -1, 1970, 1971, 1523, -1, + 1970, 1567, 1969, -1, 1966, 1509, 1508, -1, + 1966, 1508, 1971, -1, 1966, 1510, 1509, -1, + 1966, 1967, 1510, -1, 1977, 1983, 1982, -1, + 1977, 1982, 1518, -1, 1977, 1518, 1978, -1, + 1975, 1511, 1983, -1, 1975, 1974, 1512, -1, + 1975, 1512, 1511, -1, 1975, 1983, 1977, -1, + 1980, 1513, 2038, -1, 1980, 1514, 1513, -1, + 1980, 1984, 1514, -1, 1980, 2038, 2037, -1, + 1985, 1986, 1515, -1, 1985, 1515, 1988, -1, + 1985, 1988, 2302, -1, 1985, 2302, 2441, -1, + 2450, 1816, 2449, -1, 2450, 1989, 1516, -1, + 2450, 1516, 1816, -1, 1990, 1519, 1572, -1, + 1990, 1572, 1991, -1, 1992, 1998, 2445, -1, + 1992, 1991, 2804, -1, 1996, 2805, 1995, -1, + 1996, 2804, 2805, -1, 1996, 1992, 2804, -1, + 1996, 1998, 1992, -1, 1517, 1518, 1519, -1, + 1517, 1990, 2443, -1, 1517, 1519, 1990, -1, + 1517, 2443, 1520, -1, 1517, 1520, 1978, -1, + 1517, 1978, 1518, -1, 1525, 1526, 1521, -1, + 1525, 1522, 1537, -1, 1525, 1521, 1523, -1, + 1525, 1523, 1522, -1, 1524, 1537, 1538, -1, + 1524, 1525, 1537, -1, 1524, 1526, 1525, -1, + 1524, 1528, 1526, -1, 1524, 1529, 1528, -1, + 1524, 1538, 1529, -1, 1527, 1529, 2030, -1, + 1527, 1574, 1575, -1, 1527, 1575, 1528, -1, + 1527, 1528, 1529, -1, 1527, 2030, 2795, -1, + 1527, 2795, 1574, -1, 2032, 1538, 2005, -1, + 2032, 1529, 1538, -1, 2032, 2005, 2031, -1, + 2032, 2030, 1529, -1, 1535, 2002, 1530, -1, + 1535, 1531, 1534, -1, 1535, 1530, 1532, -1, + 1535, 1532, 1531, -1, 2001, 1534, 1533, -1, + 2001, 1535, 1534, -1, 2001, 2002, 1535, -1, + 2001, 1533, 2004, -1, 2003, 1537, 1536, -1, + 2003, 1536, 2002, -1, 2003, 1538, 1537, -1, + 2003, 2005, 1538, -1, 2791, 3000, 1539, -1, + 2791, 1539, 1540, -1, 2791, 1540, 1579, -1, + 2791, 1579, 2794, -1, 2787, 1556, 2453, -1, + 2787, 2034, 1556, -1, 2806, 2461, 2805, -1, + 2490, 1541, 2454, -1, 2490, 2043, 1541, -1, + 2016, 1542, 2015, -1, 2016, 2018, 1542, -1, + 2016, 1543, 2018, -1, 2016, 2772, 1543, -1, + 2773, 2013, 2408, -1, 1544, 1553, 1552, -1, + 1544, 1546, 1545, -1, 1544, 1552, 1546, -1, + 1544, 2173, 1553, -1, 1544, 2168, 2173, -1, + 1544, 1545, 1747, -1, 1544, 1747, 2168, -1, + 2424, 1550, 2423, -1, 2424, 2020, 1550, -1, + 1547, 2020, 1555, -1, 1547, 1549, 1548, -1, + 1547, 1548, 1550, -1, 1547, 1550, 2020, -1, + 1547, 1555, 1554, -1, 1547, 1554, 1549, -1, + 2178, 1553, 2176, -1, 1551, 1552, 1553, -1, + 1551, 1553, 2178, -1, 1551, 2178, 2171, -1, + 1551, 2171, 1554, -1, 1551, 1554, 1555, -1, + 1551, 1555, 1552, -1, 2023, 2024, 1556, -1, + 2023, 1556, 1557, -1, 2023, 1558, 2028, -1, + 2023, 1557, 1558, -1, 2025, 1562, 2024, -1, + 2025, 2026, 1560, -1, 1559, 1560, 1561, -1, + 1559, 1744, 1562, -1, 1559, 1562, 2025, -1, + 1559, 2025, 1560, -1, 1559, 1746, 1744, -1, + 1559, 1561, 1746, -1, 2033, 2031, 2035, -1, + 2006, 2004, 1563, -1, 2006, 2031, 2005, -1, + 2006, 2035, 2031, -1, 2006, 1563, 2035, -1, + 1564, 1565, 1566, -1, 1564, 1567, 1568, -1, + 1564, 1568, 1569, -1, 1564, 1569, 1565, -1, + 1564, 1570, 1567, -1, 1564, 1566, 1570, -1, + 2470, 1571, 2036, -1, 2470, 1572, 1571, -1, + 2470, 2803, 1572, -1, 2473, 2513, 2509, -1, + 2054, 2513, 2473, -1, 1573, 1575, 1574, -1, + 1573, 1577, 1576, -1, 1573, 1576, 1575, -1, + 1573, 1578, 1577, -1, 1573, 1579, 1578, -1, + 1573, 1574, 1579, -1, 1585, 1586, 1580, -1, + 1585, 1581, 1584, -1, 1585, 1580, 1582, -1, + 1585, 1582, 1581, -1, 2039, 2486, 1586, -1, + 2039, 2052, 2476, -1, 1583, 1584, 2053, -1, + 1583, 1585, 1584, -1, 1583, 1586, 1585, -1, + 1583, 2039, 1586, -1, 1583, 2053, 2052, -1, + 1583, 2052, 2039, -1, 2499, 1587, 2498, -1, + 2499, 2053, 1587, -1, 2483, 1623, 2484, -1, + 2493, 2044, 2042, -1, 2046, 1589, 1588, -1, + 2046, 1588, 2049, -1, 2046, 1590, 1589, -1, + 2046, 2047, 1590, -1, 2050, 2048, 2049, -1, + 2050, 2813, 2048, -1, 2050, 2049, 1591, -1, + 2050, 1591, 2481, -1, 2814, 2516, 2813, -1, + 2507, 2506, 2047, -1, 2519, 2476, 2052, -1, + 2519, 3019, 2476, -1, 2501, 2055, 2500, -1, + 2057, 2491, 2492, -1, 2057, 2058, 2055, -1, + 2057, 2501, 2491, -1, 2057, 2055, 2501, -1, + 2518, 2055, 2058, -1, 1598, 1597, 1592, -1, + 1598, 1593, 1599, -1, 1598, 1594, 1593, -1, + 1598, 1592, 1594, -1, 1595, 1641, 1596, -1, + 1595, 1596, 1597, -1, 1595, 1642, 1641, -1, + 1595, 1597, 1598, -1, 1595, 1599, 1642, -1, + 1595, 1598, 1599, -1, 1600, 1602, 1601, -1, + 1600, 1603, 1602, -1, 1600, 1604, 1605, -1, + 1600, 1606, 1603, -1, 1600, 1607, 1604, -1, + 1600, 1601, 1607, -1, 1600, 1605, 1608, -1, + 1600, 1608, 1606, -1, 2063, 2064, 1609, -1, + 2063, 1609, 2067, -1, 2060, 1611, 1615, -1, + 2060, 1615, 2064, -1, 2060, 2061, 1611, -1, + 1610, 1611, 1614, -1, 1610, 1615, 1611, -1, + 1610, 1614, 1615, -1, 1612, 1614, 1613, -1, + 1612, 1615, 1614, -1, 1612, 1613, 1617, -1, + 1612, 1617, 1615, -1, 1616, 2064, 1617, -1, + 1616, 1617, 1618, -1, 1616, 1619, 2064, -1, + 1616, 1618, 1619, -1, 2071, 2069, 1620, -1, + 2071, 1620, 2072, -1, 1621, 2040, 1622, -1, + 1621, 2483, 2040, -1, 1621, 1623, 2483, -1, + 1621, 1624, 1623, -1, 1621, 1625, 1624, -1, + 1621, 1622, 1625, -1, 1626, 1627, 2480, -1, + 1626, 1628, 1629, -1, 1626, 1629, 1627, -1, + 1626, 1630, 1628, -1, 1626, 2479, 1630, -1, + 1626, 2480, 2479, -1, 2521, 1631, 2526, -1, + 2521, 1632, 1631, -1, 2521, 2522, 1632, -1, + 2529, 2074, 2079, -1, 2528, 2074, 2529, -1, + 2533, 2077, 2523, -1, 1634, 2763, 1633, -1, + 1634, 2079, 2074, -1, 1634, 2074, 2075, -1, + 1634, 2075, 2763, -1, 2078, 2535, 2530, -1, + 2078, 2249, 2535, -1, 2078, 2530, 2529, -1, + 2078, 2529, 2079, -1, 2333, 1633, 2331, -1, + 2333, 1634, 1633, -1, 2333, 2079, 1634, -1, + 2536, 2248, 2537, -1, 2536, 2535, 2249, -1, + 2544, 2085, 2081, -1, 2544, 2543, 2085, -1, + 2542, 2295, 2543, -1, 2542, 2296, 2295, -1, + 1635, 1636, 2087, -1, 1635, 2087, 1637, -1, + 1635, 1637, 1638, -1, 1635, 1638, 1639, -1, + 1635, 1639, 1640, -1, 1635, 1640, 1636, -1, + 2093, 2086, 1641, -1, 2093, 1641, 1642, -1, + 2093, 1642, 2094, -1, 2090, 1643, 2091, -1, + 2090, 1644, 1643, -1, 2090, 2095, 1645, -1, + 2090, 1645, 1644, -1, 2097, 1647, 1646, -1, + 2097, 2102, 1647, -1, 2097, 1646, 1648, -1, + 2097, 1648, 2098, -1, 1649, 1651, 1650, -1, + 1649, 1652, 1651, -1, 1649, 1650, 1653, -1, + 1649, 1653, 1652, -1, 2562, 2548, 2107, -1, + 2559, 1655, 2550, -1, 2559, 2550, 2560, -1, + 2559, 2570, 1655, -1, 1661, 1654, 1660, -1, + 1661, 1655, 1654, -1, 1661, 2571, 1656, -1, + 1661, 1656, 1655, -1, 1657, 1658, 1659, -1, + 1657, 1660, 1658, -1, 1657, 1659, 2573, -1, + 1657, 1661, 1660, -1, 1657, 2573, 2571, -1, + 1657, 2571, 1661, -1, 1662, 2111, 1663, -1, + 1662, 1663, 1664, -1, 1662, 1664, 1665, -1, + 1662, 1667, 2111, -1, 1662, 1665, 1666, -1, + 1662, 1666, 1667, -1, 2110, 2111, 1667, -1, + 2110, 1668, 2113, -1, 2110, 1667, 1669, -1, + 2110, 1669, 1668, -1, 2835, 2114, 1670, -1, + 2835, 1670, 2836, -1, 2572, 1671, 2146, -1, + 2572, 2573, 1671, -1, 2118, 1672, 2117, -1, + 2118, 2119, 1673, -1, 2118, 1673, 1672, -1, + 1674, 1676, 1675, -1, 1674, 2116, 1676, -1, + 1674, 1675, 1677, -1, 1674, 1678, 2116, -1, + 1674, 1677, 1679, -1, 1674, 1679, 1678, -1, + 1684, 1680, 1683, -1, 1684, 1685, 1681, -1, + 1684, 1681, 1680, -1, 1682, 1683, 2569, -1, + 1682, 2569, 2568, -1, 1682, 1684, 1683, -1, + 1682, 1685, 1684, -1, 1682, 2104, 1685, -1, + 1682, 2568, 2104, -1, 1686, 1687, 1697, -1, + 1686, 1688, 2122, -1, 1686, 2122, 1689, -1, + 1686, 1689, 1687, -1, 1686, 1697, 1696, -1, + 1686, 1696, 1688, -1, 2133, 1690, 2132, -1, + 2133, 1697, 1691, -1, 2133, 1691, 1690, -1, + 2123, 1693, 1692, -1, 2123, 2121, 1693, -1, + 2123, 1692, 1694, -1, 2123, 1694, 2124, -1, + 2128, 2129, 1695, -1, 2128, 1695, 1696, -1, + 2128, 1696, 1697, -1, 2128, 1697, 2133, -1, + 1698, 1699, 1700, -1, 1698, 1701, 1699, -1, + 1698, 1702, 1701, -1, 1698, 1703, 1702, -1, + 1698, 1704, 1703, -1, 1698, 1705, 1704, -1, + 1698, 1700, 1705, -1, 1706, 1707, 1708, -1, + 1706, 1708, 1709, -1, 1706, 2578, 1707, -1, + 1706, 1709, 1710, -1, 1706, 1710, 1711, -1, + 1706, 1711, 2578, -1, 2579, 2578, 1711, -1, + 2579, 1711, 2112, -1, 2579, 2112, 2135, -1, + 2576, 2137, 1712, -1, 2576, 1712, 1713, -1, + 2576, 1713, 2577, -1, 2142, 2143, 2137, -1, + 1714, 1724, 1725, -1, 1714, 1725, 1715, -1, + 1714, 1715, 1719, -1, 1714, 1719, 1716, -1, + 1714, 1716, 1717, -1, 1714, 1717, 1724, -1, + 1718, 1719, 1720, -1, 1718, 1721, 1719, -1, + 1718, 1720, 1722, -1, 1718, 1722, 1721, -1, + 1723, 1725, 1724, -1, 1723, 1726, 1727, -1, + 1723, 1724, 1728, -1, 1723, 1728, 1726, -1, + 1723, 1729, 1725, -1, 1723, 1727, 1729, -1, + 1871, 1730, 1869, -1, 1871, 1731, 1730, -1, + 1871, 1872, 1731, -1, 1987, 1732, 1986, -1, + 1987, 2445, 1998, -1, 1987, 1998, 1999, -1, + 1987, 1999, 1732, -1, 1733, 1734, 1735, -1, + 1733, 1735, 1736, -1, 1733, 1737, 1734, -1, + 1733, 1736, 2678, -1, 1733, 2678, 2677, -1, + 1733, 2677, 1737, -1, 2149, 2215, 2150, -1, + 2149, 2213, 2215, -1, 2149, 2153, 1738, -1, + 2149, 1738, 2213, -1, 2319, 3090, 2679, -1, + 2319, 2679, 1739, -1, 2922, 2923, 2150, -1, + 2922, 2150, 2215, -1, 2922, 2215, 2320, -1, + 2154, 1739, 2152, -1, 2154, 2150, 2923, -1, + 2154, 2319, 1739, -1, 2154, 2923, 2319, -1, + 2158, 2159, 1740, -1, 2158, 1740, 2155, -1, + 2592, 1741, 1742, -1, 2592, 2583, 1741, -1, + 2592, 1742, 2593, -1, 2595, 2597, 1743, -1, + 1745, 2163, 2595, -1, 1745, 2595, 1743, -1, + 1745, 1744, 1746, -1, 1745, 1743, 1744, -1, + 2207, 2163, 1745, -1, 2207, 1746, 2208, -1, + 2207, 1745, 1746, -1, 2170, 2168, 1747, -1, + 2170, 2412, 2167, -1, 2170, 1747, 2414, -1, + 2172, 2173, 2168, -1, 2588, 2175, 2589, -1, + 2179, 2187, 2175, -1, 2183, 1748, 2326, -1, + 2183, 2182, 1748, -1, 2853, 2852, 1749, -1, + 2853, 1749, 1750, -1, 2853, 1750, 2604, -1, + 1756, 1751, 1755, -1, 1756, 1767, 1751, -1, + 1756, 1766, 1767, -1, 1756, 2196, 1766, -1, + 2184, 1766, 2196, -1, 2184, 1765, 1766, -1, + 2184, 2186, 1765, -1, 2184, 2196, 2195, -1, + 1754, 1755, 1752, -1, 1754, 1752, 2224, -1, + 1754, 2224, 1753, -1, 1754, 1753, 2193, -1, + 2192, 1754, 2193, -1, 2192, 1755, 1754, -1, + 2192, 1756, 1755, -1, 2192, 2196, 1756, -1, + 1757, 1758, 2153, -1, 1757, 1759, 1770, -1, + 1757, 1770, 1760, -1, 1757, 1760, 1758, -1, + 1757, 2153, 2151, -1, 1757, 2151, 1759, -1, + 2205, 2162, 2163, -1, 2205, 2160, 2162, -1, + 2205, 2586, 2160, -1, 2205, 2163, 2207, -1, + 2920, 2209, 3094, -1, 2212, 2852, 2851, -1, + 2212, 2214, 1761, -1, 2212, 1761, 2852, -1, + 2854, 2209, 2851, -1, 2854, 2712, 2209, -1, + 2854, 2940, 2712, -1, 2211, 2851, 2209, -1, + 2211, 2209, 2920, -1, 2211, 2920, 2320, -1, + 2211, 2212, 2851, -1, 1762, 1764, 1763, -1, + 1762, 1766, 1765, -1, 1762, 1765, 1764, -1, + 1762, 1767, 1766, -1, 1762, 1768, 1767, -1, + 1762, 1763, 1768, -1, 2217, 2198, 2164, -1, + 2217, 2164, 2218, -1, 2217, 2222, 1769, -1, + 2217, 1769, 2198, -1, 2225, 2223, 1770, -1, + 2225, 1770, 1771, -1, 2225, 1771, 2161, -1, + 2615, 2228, 1772, -1, 2615, 1773, 2616, -1, + 2615, 1772, 1773, -1, 1779, 1775, 1774, -1, + 1779, 1774, 2228, -1, 1779, 1776, 1775, -1, + 1779, 1780, 1776, -1, 1781, 2226, 1785, -1, + 1781, 1785, 1777, -1, 1781, 1777, 1778, -1, + 1781, 1778, 1780, -1, 2227, 1780, 1779, -1, + 2227, 1779, 2228, -1, 2227, 1781, 1780, -1, + 2227, 2226, 1781, -1, 1782, 2232, 1783, -1, + 1782, 1784, 1785, -1, 1782, 1783, 1784, -1, + 1782, 1785, 2226, -1, 1782, 2226, 2612, -1, + 1782, 2612, 2232, -1, 2607, 2229, 1786, -1, + 2607, 1786, 2232, -1, 1787, 1789, 1788, -1, + 1787, 1790, 1791, -1, 1787, 1788, 1792, -1, + 1787, 1792, 1790, -1, 1787, 1793, 1789, -1, + 1787, 1791, 1793, -1, 2236, 2235, 1794, -1, + 2236, 1794, 1795, -1, 2236, 1796, 2238, -1, + 2236, 1795, 1796, -1, 1797, 1799, 1798, -1, + 1797, 1801, 1800, -1, 1797, 1802, 1801, -1, + 1797, 1798, 1802, -1, 1797, 1800, 1803, -1, + 1797, 1803, 1799, -1, 2525, 2526, 1804, -1, + 2525, 1804, 2241, -1, 3057, 3056, 2338, -1, + 2625, 2294, 2265, -1, 2625, 2670, 2294, -1, + 2253, 2879, 2297, -1, 2253, 2628, 1805, -1, + 2878, 2291, 2880, -1, 2878, 1805, 2291, -1, + 2878, 2253, 1805, -1, 2878, 2879, 2253, -1, + 2636, 2307, 2637, -1, 2917, 2704, 2637, -1, + 2917, 1822, 2918, -1, 2917, 2637, 1822, -1, + 2697, 2288, 2255, -1, 2697, 3067, 2288, -1, + 2256, 2255, 2257, -1, 2256, 2928, 2929, -1, + 2634, 2257, 2293, -1, 2634, 2293, 2259, -1, + 1812, 2258, 2259, -1, 1812, 2262, 2258, -1, + 1812, 1811, 2262, -1, 1812, 3025, 1811, -1, + 2261, 2310, 2258, -1, 2261, 2258, 2262, -1, + 2275, 1806, 2272, -1, 2275, 2267, 1806, -1, + 2639, 2866, 2268, -1, 2280, 2642, 1807, -1, + 2280, 2654, 2642, -1, 2873, 1807, 2642, -1, + 2873, 2640, 1807, -1, 2638, 1807, 2640, -1, + 2638, 2639, 2274, -1, 2273, 2282, 2280, -1, + 2273, 2280, 1807, -1, 2273, 2638, 2274, -1, + 2273, 1807, 2638, -1, 2276, 3033, 2644, -1, + 2276, 2278, 3033, -1, 2276, 2644, 2648, -1, + 2276, 2648, 2656, -1, 2657, 2287, 2277, -1, + 2281, 2271, 1808, -1, 2281, 2282, 2271, -1, + 2281, 1808, 1809, -1, 2281, 1809, 2286, -1, + 2647, 2656, 2648, -1, 2661, 2290, 2662, -1, + 2661, 2660, 2643, -1, 2645, 3032, 2880, -1, + 2645, 2644, 3032, -1, 2877, 2662, 1810, -1, + 2877, 1811, 3025, -1, 2877, 1810, 1811, -1, + 3026, 3025, 1812, -1, 3026, 2259, 2293, -1, + 3026, 1812, 2259, -1, 3037, 2294, 2670, -1, + 1813, 1814, 1815, -1, 1813, 1815, 1817, -1, + 1813, 1816, 1814, -1, 1813, 1817, 2627, -1, + 1813, 2627, 2252, -1, 1813, 2252, 1816, -1, + 2629, 2669, 2670, -1, 2629, 1817, 2669, -1, + 2629, 2627, 1817, -1, 2629, 2670, 2625, -1, + 2664, 2296, 2448, -1, 2299, 2448, 2296, -1, + 2299, 2542, 2547, -1, 2299, 2296, 2542, -1, + 2299, 2300, 2448, -1, 2666, 2305, 1818, -1, + 2666, 1819, 2667, -1, 2666, 1818, 1819, -1, + 2668, 1820, 2305, -1, 2668, 1821, 1820, -1, + 2668, 2669, 1821, -1, 2700, 2918, 2672, -1, + 2673, 2311, 2883, -1, 2673, 2672, 1822, -1, + 2673, 1822, 2307, -1, 2673, 2307, 2311, -1, + 2309, 2265, 2294, -1, 2309, 2310, 2261, -1, + 2309, 2261, 2265, -1, 2663, 2682, 2885, -1, + 3248, 2974, 3060, -1, 3248, 3249, 2974, -1, + 3245, 2696, 2904, -1, 2318, 3200, 2316, -1, + 2318, 2631, 3200, -1, 2323, 2705, 1823, -1, + 2323, 1823, 1824, -1, 2323, 1824, 2322, -1, + 2327, 2183, 2326, -1, 2327, 2328, 2183, -1, + 2968, 1825, 2706, -1, 2968, 3115, 1825, -1, + 2330, 2331, 1855, -1, 2330, 1856, 2859, -1, + 2330, 1855, 1856, -1, 2334, 1826, 1828, -1, + 2334, 1827, 1826, -1, 2334, 2335, 1827, -1, + 2719, 1828, 2861, -1, 2719, 2334, 1828, -1, + 2720, 2722, 2948, -1, 2337, 3057, 2338, -1, + 3121, 3119, 2339, -1, 3121, 2339, 1830, -1, + 1829, 2708, 1832, -1, 1829, 1832, 2340, -1, + 1829, 2340, 2725, -1, 1829, 2725, 2724, -1, + 1829, 2724, 2708, -1, 2694, 1830, 2339, -1, + 2694, 2689, 1830, -1, 2957, 2689, 3133, -1, + 2957, 2345, 2689, -1, 2957, 2956, 2345, -1, + 2342, 1831, 2343, -1, 2342, 2340, 1831, -1, + 2344, 1830, 2345, -1, 2344, 3121, 1830, -1, + 2344, 2343, 3122, -1, 2344, 3122, 3121, -1, + 3128, 3122, 1831, -1, 3128, 1832, 3129, -1, + 3128, 1831, 1832, -1, 2981, 2354, 2982, -1, + 2981, 2350, 2354, -1, 1837, 1833, 1839, -1, + 1837, 1834, 1833, -1, 1837, 1835, 1834, -1, + 1837, 1836, 1835, -1, 2356, 2268, 2866, -1, + 2356, 2866, 2868, -1, 2356, 2357, 2268, -1, + 2746, 2982, 2353, -1, 2864, 2352, 2867, -1, + 3148, 2354, 2350, -1, 3148, 2350, 2975, -1, + 2976, 2975, 2892, -1, 2976, 3060, 2974, -1, + 1838, 1839, 2360, -1, 1838, 2351, 1836, -1, + 1838, 1837, 1839, -1, 1838, 1836, 1837, -1, + 2359, 2745, 2351, -1, 2359, 2351, 1838, -1, + 2359, 1838, 2360, -1, 1843, 2360, 1839, -1, + 1843, 1840, 1845, -1, 1843, 1839, 1840, -1, + 1843, 2358, 2360, -1, 2740, 2353, 2979, -1, + 2740, 2743, 2352, -1, 2740, 2746, 2353, -1, + 2740, 2352, 2746, -1, 2744, 2745, 2359, -1, + 2744, 2356, 2868, -1, 1844, 2357, 2358, -1, + 1844, 1847, 1841, -1, 1844, 2269, 2357, -1, + 1844, 1841, 2269, -1, 1842, 1846, 1847, -1, + 1842, 2358, 1843, -1, 1842, 1844, 2358, -1, + 1842, 1847, 1844, -1, 1842, 1845, 1846, -1, + 1842, 1843, 1845, -1, 2362, 1846, 2363, -1, + 2362, 1847, 1846, -1, 2362, 2367, 1848, -1, + 2362, 1848, 1847, -1, 2753, 2619, 1850, -1, + 2753, 1849, 2754, -1, 2753, 1850, 1849, -1, + 2618, 1850, 2619, -1, 2618, 2761, 1851, -1, + 2618, 1852, 1850, -1, 2618, 1851, 1852, -1, + 2756, 2755, 2732, -1, 2756, 2732, 2731, -1, + 2984, 2756, 2731, -1, 2984, 2985, 2756, -1, + 2759, 2368, 1853, -1, 2759, 1853, 1854, -1, + 2759, 1854, 2760, -1, 2770, 2953, 2952, -1, + 2770, 2686, 2954, -1, 2770, 2954, 2953, -1, + 2950, 1855, 2951, -1, 2950, 1856, 1855, -1, + 2950, 2948, 1856, -1, 3118, 2337, 3119, -1, + 2374, 1875, 1857, -1, 2374, 1858, 1875, -1, + 2374, 2380, 1858, -1, 2374, 1857, 2375, -1, + 1859, 1860, 1861, -1, 1859, 2373, 1860, -1, + 1859, 1861, 1862, -1, 1859, 2379, 2373, -1, + 1859, 1862, 2382, -1, 1859, 2382, 2379, -1, + 2381, 1863, 2380, -1, 2381, 2382, 1863, -1, + 1867, 1868, 1864, -1, 1867, 1865, 1876, -1, + 1867, 1864, 1866, -1, 1867, 1866, 1865, -1, + 1870, 1868, 1867, -1, 1870, 1867, 1876, -1, + 1870, 1869, 1868, -1, 1870, 1871, 1869, -1, + 1878, 1870, 1876, -1, 1878, 1871, 1870, -1, + 1878, 1879, 1872, -1, 1878, 1872, 1871, -1, + 1873, 1874, 1875, -1, 1873, 1876, 1874, -1, + 1873, 1875, 1877, -1, 1873, 1878, 1876, -1, + 1873, 1877, 1879, -1, 1873, 1879, 1878, -1, + 2397, 2385, 1880, -1, 2397, 1880, 2398, -1, + 2392, 1886, 2389, -1, 2392, 2396, 1886, -1, + 2390, 1882, 1881, -1, 2390, 2387, 1882, -1, + 2390, 1881, 1883, -1, 2390, 1883, 2384, -1, + 2390, 2384, 2391, -1, 1884, 1903, 1885, -1, + 1884, 1885, 1886, -1, 1884, 1887, 1903, -1, + 1884, 1886, 2395, -1, 1884, 1888, 1887, -1, + 1884, 2395, 1888, -1, 2394, 1888, 2395, -1, + 2394, 1889, 1888, -1, 2394, 1890, 1889, -1, + 2394, 2399, 1890, -1, 1891, 1893, 1892, -1, + 1891, 1894, 1893, -1, 1891, 1895, 1894, -1, + 1891, 1896, 1895, -1, 1891, 1897, 1896, -1, + 1891, 1892, 1897, -1, 1906, 2412, 2410, -1, + 1906, 1905, 1898, -1, 1906, 2167, 2412, -1, + 1906, 1899, 2167, -1, 1906, 1898, 1899, -1, + 2411, 2412, 2170, -1, 2411, 2170, 2414, -1, + 1900, 2388, 1901, -1, 1900, 2402, 1902, -1, + 1900, 1902, 2387, -1, 1900, 2387, 2388, -1, + 2401, 1900, 1901, -1, 2401, 2402, 1900, -1, + 2401, 1901, 1904, -1, 2405, 2404, 1902, -1, + 2405, 1902, 2402, -1, 2403, 1905, 2407, -1, + 2403, 1904, 1903, -1, 2403, 1903, 1905, -1, + 2403, 2401, 1904, -1, 2406, 2407, 1905, -1, + 2406, 1906, 2410, -1, 2406, 1905, 1906, -1, + 2010, 2994, 2993, -1, 2010, 1907, 2994, -1, + 2010, 1908, 1907, -1, 2010, 2011, 1908, -1, + 2014, 1909, 2013, -1, 2014, 1910, 2421, -1, + 2014, 2421, 1909, -1, 2014, 2015, 1910, -1, + 2413, 2411, 2414, -1, 1911, 1912, 1920, -1, + 1911, 1913, 1914, -1, 1911, 1914, 1912, -1, + 1911, 1915, 1913, -1, 1911, 1916, 1915, -1, + 1911, 1920, 1916, -1, 1917, 1919, 1918, -1, + 1917, 1920, 1919, -1, 1917, 1918, 1921, -1, + 1917, 1922, 1920, -1, 1917, 1921, 1923, -1, + 1917, 1923, 1922, -1, 1930, 1924, 1928, -1, + 1930, 1929, 1925, -1, 1930, 1925, 1926, -1, + 1930, 1926, 1924, -1, 2418, 1941, 1942, -1, + 2418, 2416, 1941, -1, 2418, 1942, 1927, -1, + 2418, 1927, 2419, -1, 1934, 1928, 2417, -1, + 1934, 1932, 1929, -1, 1934, 1930, 1928, -1, + 1934, 1929, 1930, -1, 1931, 2417, 2420, -1, + 1931, 1933, 1932, -1, 1931, 1934, 2417, -1, + 1931, 1932, 1934, -1, 1931, 1935, 1933, -1, + 1931, 2420, 1935, -1, 2431, 2423, 2429, -1, + 2431, 2433, 2427, -1, 2438, 2436, 1936, -1, + 2438, 1937, 2553, -1, 2438, 1938, 1937, -1, + 2438, 1936, 1938, -1, 2552, 2550, 2437, -1, + 1939, 1941, 1940, -1, 1939, 1942, 1941, -1, + 1939, 1943, 1942, -1, 1939, 1944, 1943, -1, + 1939, 1945, 1944, -1, 1939, 1940, 1945, -1, + 1946, 1947, 1948, -1, 1946, 1952, 1953, -1, + 1946, 1953, 1949, -1, 1946, 1949, 1947, -1, + 1946, 1948, 1950, -1, 1946, 1950, 1952, -1, + 1951, 1953, 1952, -1, 1951, 1954, 1955, -1, + 1951, 1955, 1953, -1, 1951, 1956, 1954, -1, + 1951, 1957, 1956, -1, 1951, 1952, 1957, -1, + 1958, 1960, 1959, -1, 1958, 1961, 1960, -1, + 1958, 1962, 1961, -1, 1958, 1963, 1962, -1, + 1958, 1964, 1963, -1, 1958, 1959, 1964, -1, + 1965, 1967, 1966, -1, 1965, 1969, 1968, -1, + 1965, 1968, 1967, -1, 1965, 1970, 1969, -1, + 1965, 1971, 1970, -1, 1965, 1966, 1971, -1, + 1972, 1973, 1974, -1, 1972, 1974, 1975, -1, + 1972, 1976, 1973, -1, 1972, 1975, 1977, -1, + 1972, 1978, 1976, -1, 1972, 1977, 1978, -1, + 1979, 1980, 2037, -1, 1979, 1981, 1982, -1, + 1979, 2037, 1981, -1, 1979, 1982, 1983, -1, + 1979, 1983, 1984, -1, 1979, 1984, 1980, -1, + 2440, 1986, 1985, -1, 2440, 1987, 1986, -1, + 2440, 2445, 1987, -1, 2440, 1985, 2441, -1, + 2447, 2300, 1988, -1, 2447, 1988, 1989, -1, + 2447, 1989, 2450, -1, 2447, 2448, 2300, -1, + 2444, 1990, 1991, -1, 2444, 1991, 1992, -1, + 2444, 1992, 2445, -1, 2444, 2443, 1990, -1, + 1993, 1995, 1994, -1, 1993, 1996, 1995, -1, + 1993, 1994, 1997, -1, 1993, 1998, 1996, -1, + 1993, 1997, 1999, -1, 1993, 1999, 1998, -1, + 2000, 2002, 2001, -1, 2000, 2003, 2002, -1, + 2000, 2001, 2004, -1, 2000, 2005, 2003, -1, + 2000, 2006, 2005, -1, 2000, 2004, 2006, -1, + 2789, 2008, 2792, -1, 2789, 2007, 2008, -1, + 2789, 2452, 2007, -1, 3003, 2792, 2008, -1, + 3003, 2008, 2009, -1, 3003, 2009, 3005, -1, + 2463, 2454, 2459, -1, 2494, 2490, 2454, -1, + 2494, 2799, 2492, -1, 2777, 2010, 2993, -1, + 2777, 2408, 2011, -1, 2777, 2011, 2010, -1, + 2012, 2013, 2773, -1, 2012, 2015, 2014, -1, + 2012, 2014, 2013, -1, 2012, 2016, 2015, -1, + 2012, 2772, 2016, -1, 2012, 2773, 2772, -1, + 2017, 2425, 2018, -1, 2017, 2424, 2425, -1, + 2017, 2018, 2019, -1, 2017, 2020, 2424, -1, + 2017, 2019, 2021, -1, 2017, 2021, 2020, -1, + 2022, 2024, 2023, -1, 2022, 2026, 2025, -1, + 2022, 2025, 2024, -1, 2022, 2027, 2026, -1, + 2022, 2028, 2027, -1, 2022, 2023, 2028, -1, + 3011, 2033, 2793, -1, 2029, 3012, 2030, -1, + 2029, 2031, 2033, -1, 2029, 3011, 3012, -1, + 2029, 2033, 3011, -1, 2029, 2030, 2032, -1, + 2029, 2032, 2031, -1, 2788, 2793, 2033, -1, + 2788, 2034, 2787, -1, 2788, 2035, 2034, -1, + 2788, 2033, 2035, -1, 2466, 2511, 2512, -1, + 2466, 2036, 2468, -1, 2466, 2512, 2036, -1, + 2469, 2512, 2826, -1, 2469, 2036, 2512, -1, + 2469, 2470, 2036, -1, 2472, 2467, 2037, -1, + 2472, 2037, 2038, -1, 2472, 2473, 2509, -1, + 2472, 2038, 2474, -1, 2504, 2054, 2473, -1, + 2810, 2039, 2476, -1, 2810, 2811, 2486, -1, + 2810, 2486, 2039, -1, 2485, 2480, 2040, -1, + 2485, 2040, 2483, -1, 2489, 2042, 2041, -1, + 2489, 2493, 2042, -1, 2489, 2041, 2043, -1, + 2489, 2043, 2490, -1, 2496, 2497, 2044, -1, + 2496, 2044, 2493, -1, 2496, 2493, 2491, -1, + 2496, 2491, 2501, -1, 2045, 2047, 2046, -1, + 2045, 2507, 2047, -1, 2045, 2051, 2507, -1, + 2045, 2048, 2051, -1, 2045, 2049, 2048, -1, + 2045, 2046, 2049, -1, 2812, 2813, 2050, -1, + 2812, 2050, 2481, -1, 2812, 2487, 2811, -1, + 2812, 2481, 2487, -1, 2503, 2051, 2515, -1, + 2503, 2507, 2051, -1, 2503, 2515, 2054, -1, + 2503, 2054, 2504, -1, 2056, 2519, 2052, -1, + 2056, 2499, 2500, -1, 2056, 2052, 2053, -1, + 2056, 2053, 2499, -1, 2816, 2054, 2515, -1, + 2816, 2513, 2054, -1, 2517, 2055, 2518, -1, + 2517, 2500, 2055, -1, 2517, 2056, 2500, -1, + 2517, 2519, 2056, -1, 2460, 2827, 2058, -1, + 2460, 2492, 2799, -1, 2460, 2058, 2057, -1, + 2460, 2057, 2492, -1, 2819, 2058, 2827, -1, + 2819, 2518, 2058, -1, 2819, 3017, 2518, -1, + 2059, 2061, 2060, -1, 2059, 2062, 2061, -1, + 2059, 2064, 2063, -1, 2059, 2060, 2064, -1, + 2059, 2069, 2062, -1, 2059, 2065, 2069, -1, + 2059, 2066, 2065, -1, 2059, 2067, 2066, -1, + 2059, 2063, 2067, -1, 2068, 2070, 2069, -1, + 2068, 2069, 2071, -1, 2068, 2072, 2070, -1, + 2068, 2071, 2072, -1, 2527, 2521, 2526, -1, + 2244, 2243, 2073, -1, 2244, 2074, 2528, -1, + 2244, 2075, 2074, -1, 2244, 2073, 2075, -1, + 2534, 2530, 2535, -1, 2534, 2527, 2530, -1, + 2532, 2537, 2076, -1, 2532, 2076, 2077, -1, + 2532, 2077, 2533, -1, 2332, 2078, 2079, -1, + 2332, 2079, 2333, -1, 2332, 2249, 2078, -1, + 2332, 2622, 2249, -1, 2084, 2080, 2083, -1, + 2084, 2544, 2081, -1, 2084, 2082, 2080, -1, + 2084, 2081, 2082, -1, 2545, 2083, 2538, -1, + 2545, 2084, 2083, -1, 2545, 2544, 2084, -1, + 2254, 2085, 2543, -1, 2254, 2543, 2295, -1, + 2254, 2277, 2085, -1, 2254, 2278, 2277, -1, + 2092, 2086, 2093, -1, 2092, 2091, 2087, -1, + 2092, 2088, 2086, -1, 2092, 2087, 2088, -1, + 2089, 2090, 2091, -1, 2089, 2091, 2092, -1, + 2089, 2092, 2093, -1, 2089, 2093, 2094, -1, + 2089, 2094, 2095, -1, 2089, 2095, 2090, -1, + 2096, 2097, 2098, -1, 2096, 2098, 2099, -1, + 2096, 2099, 2100, -1, 2096, 2100, 2101, -1, + 2096, 2101, 2102, -1, 2096, 2102, 2097, -1, + 2554, 2555, 2549, -1, 2565, 2105, 2103, -1, + 2565, 2566, 2105, -1, 2565, 2103, 2104, -1, + 2565, 2104, 2568, -1, 2108, 2105, 2566, -1, + 2108, 2106, 2105, -1, 2108, 2107, 2106, -1, + 2108, 2562, 2107, -1, 2561, 2562, 2108, -1, + 2561, 2108, 2566, -1, 2567, 2570, 2559, -1, + 2567, 2561, 2566, -1, 2567, 2559, 2561, -1, + 2109, 2113, 2134, -1, 2109, 2111, 2110, -1, + 2109, 2110, 2113, -1, 2109, 2134, 2135, -1, + 2109, 2112, 2111, -1, 2109, 2135, 2112, -1, + 2831, 2134, 2113, -1, 2831, 2113, 2114, -1, + 2831, 2114, 2835, -1, 2115, 2117, 2116, -1, + 2115, 2118, 2117, -1, 2115, 2116, 2119, -1, + 2115, 2119, 2118, -1, 2120, 2122, 2121, -1, + 2120, 2121, 2123, -1, 2120, 2123, 2124, -1, + 2120, 2125, 2122, -1, 2120, 2124, 2126, -1, + 2120, 2126, 2125, -1, 2127, 2129, 2128, -1, + 2127, 2131, 2130, -1, 2127, 2130, 2129, -1, + 2127, 2132, 2131, -1, 2127, 2133, 2132, -1, + 2127, 2128, 2133, -1, 2136, 2135, 2134, -1, + 2136, 2140, 2138, -1, 2830, 2829, 2140, -1, + 2830, 2134, 2831, -1, 2830, 2136, 2134, -1, + 2830, 2140, 2136, -1, 2139, 2572, 2146, -1, + 2139, 2839, 2572, -1, 2139, 2140, 2829, -1, + 2139, 2829, 2839, -1, 2580, 2579, 2135, -1, + 2580, 2135, 2136, -1, 2580, 2136, 2138, -1, + 2575, 2137, 2576, -1, 2575, 2142, 2137, -1, + 2575, 2138, 2142, -1, 2575, 2580, 2138, -1, + 2147, 2142, 2138, -1, 2147, 2139, 2146, -1, + 2147, 2138, 2140, -1, 2147, 2140, 2139, -1, + 2141, 2143, 2142, -1, 2141, 2144, 2143, -1, + 2141, 2145, 2144, -1, 2141, 2146, 2145, -1, + 2141, 2147, 2146, -1, 2141, 2142, 2147, -1, + 2148, 2149, 2150, -1, 2148, 2152, 2151, -1, + 2148, 2151, 2153, -1, 2148, 2153, 2149, -1, + 2148, 2154, 2152, -1, 2148, 2150, 2154, -1, + 2581, 2158, 2155, -1, 2581, 2155, 2156, -1, + 2581, 2156, 2583, -1, 2581, 2582, 2158, -1, + 2157, 2582, 2162, -1, 2157, 2162, 2160, -1, + 2157, 2159, 2158, -1, 2157, 2158, 2582, -1, + 2157, 2161, 2159, -1, 2157, 2160, 2161, -1, + 2585, 2160, 2586, -1, 2585, 2161, 2160, -1, + 2585, 2225, 2161, -1, 2594, 2162, 2582, -1, + 2594, 2163, 2162, -1, 2594, 2595, 2163, -1, + 2169, 2180, 2172, -1, 2169, 2166, 2164, -1, + 2169, 2164, 2203, -1, 2169, 2203, 2180, -1, + 2165, 2167, 2166, -1, 2165, 2172, 2168, -1, + 2165, 2166, 2169, -1, 2165, 2169, 2172, -1, + 2165, 2170, 2167, -1, 2165, 2168, 2170, -1, + 2177, 2588, 2587, -1, 2177, 2587, 2206, -1, + 2177, 2206, 2171, -1, 2177, 2171, 2178, -1, + 2181, 2172, 2180, -1, 2181, 2179, 2176, -1, + 2181, 2176, 2173, -1, 2181, 2173, 2172, -1, + 2174, 2175, 2588, -1, 2174, 2179, 2175, -1, + 2174, 2176, 2179, -1, 2174, 2588, 2177, -1, + 2174, 2178, 2176, -1, 2174, 2177, 2178, -1, + 2188, 2187, 2179, -1, 2188, 2180, 2202, -1, + 2188, 2181, 2180, -1, 2188, 2179, 2181, -1, + 2598, 2599, 2182, -1, 2598, 2182, 2183, -1, + 2598, 2183, 2328, -1, 2602, 2328, 2939, -1, + 2602, 2598, 2328, -1, 2190, 2184, 2195, -1, + 2190, 2189, 2185, -1, 2190, 2185, 2186, -1, + 2190, 2186, 2184, -1, 2194, 2202, 2201, -1, + 2194, 2193, 2187, -1, 2194, 2187, 2188, -1, + 2194, 2188, 2202, -1, 2200, 2195, 2201, -1, + 2200, 2199, 2189, -1, 2200, 2189, 2190, -1, + 2200, 2190, 2195, -1, 2191, 2192, 2193, -1, + 2191, 2193, 2194, -1, 2191, 2194, 2201, -1, + 2191, 2201, 2195, -1, 2191, 2195, 2196, -1, + 2191, 2196, 2192, -1, 2197, 2198, 2199, -1, + 2197, 2199, 2200, -1, 2197, 2200, 2201, -1, + 2197, 2201, 2202, -1, 2197, 2202, 2203, -1, + 2197, 2203, 2198, -1, 2204, 2587, 2586, -1, + 2204, 2586, 2205, -1, 2204, 2206, 2587, -1, + 2204, 2205, 2207, -1, 2204, 2208, 2206, -1, + 2204, 2207, 2208, -1, 2321, 3094, 2209, -1, + 2321, 2209, 2712, -1, 2321, 2712, 2711, -1, + 2850, 2939, 2940, -1, 2850, 2940, 2854, -1, + 2850, 2602, 2939, -1, 2210, 2212, 2211, -1, + 2210, 2213, 2214, -1, 2210, 2214, 2212, -1, + 2210, 2215, 2213, -1, 2210, 2320, 2215, -1, + 2210, 2211, 2320, -1, 2216, 2217, 2218, -1, + 2216, 2220, 2219, -1, 2216, 2218, 2220, -1, + 2216, 2219, 2221, -1, 2216, 2221, 2222, -1, + 2216, 2222, 2217, -1, 2590, 2224, 2223, -1, + 2590, 2223, 2225, -1, 2590, 2589, 2224, -1, + 2590, 2225, 2585, -1, 2611, 2612, 2226, -1, + 2611, 2226, 2227, -1, 2611, 2228, 2615, -1, + 2611, 2227, 2228, -1, 2606, 2230, 2229, -1, + 2606, 2229, 2607, -1, 2606, 2231, 2230, -1, + 2606, 2608, 2231, -1, 2613, 2232, 2612, -1, + 2613, 2607, 2232, -1, 2233, 2234, 2235, -1, + 2233, 2235, 2236, -1, 2233, 2237, 2234, -1, + 2233, 2236, 2238, -1, 2233, 2239, 2237, -1, + 2233, 2238, 2239, -1, 2240, 2241, 2242, -1, + 2240, 2525, 2241, -1, 2240, 2242, 2243, -1, + 2240, 2528, 2525, -1, 2240, 2243, 2244, -1, + 2240, 2244, 2528, -1, 2687, 2954, 2686, -1, + 2687, 3057, 2337, -1, 2687, 3118, 2954, -1, + 2687, 2337, 3118, -1, 2762, 2750, 2989, -1, + 2762, 2989, 2988, -1, 2245, 2246, 2248, -1, + 2245, 2248, 2621, -1, 2245, 2247, 2246, -1, + 2245, 2250, 2247, -1, 2245, 2621, 2250, -1, + 2620, 2621, 2248, -1, 2620, 2248, 2536, -1, + 2620, 2249, 2622, -1, 2620, 2536, 2249, -1, + 2860, 2330, 2859, -1, 2857, 2250, 2621, -1, + 2857, 2251, 2250, -1, 2857, 2861, 2251, -1, + 2626, 2252, 2627, -1, 2626, 2297, 2252, -1, + 2626, 2253, 2297, -1, 2626, 2628, 2253, -1, + 2624, 2625, 2265, -1, 2624, 2263, 2628, -1, + 3031, 2254, 2295, -1, 3031, 3033, 2278, -1, + 3031, 2278, 2254, -1, 2630, 2697, 2255, -1, + 2630, 2255, 2256, -1, 2630, 2929, 2930, -1, + 2630, 2256, 2929, -1, 2633, 2256, 2257, -1, + 2633, 2257, 2634, -1, 2633, 2928, 2256, -1, + 2633, 2704, 2928, -1, 2635, 2258, 2310, -1, + 2635, 2310, 2636, -1, 2635, 2259, 2258, -1, + 2635, 2634, 2259, -1, 2260, 2261, 2262, -1, + 2260, 2264, 2263, -1, 2260, 2262, 2264, -1, + 2260, 2263, 2624, -1, 2260, 2265, 2261, -1, + 2260, 2624, 2265, -1, 2863, 2641, 2864, -1, + 2266, 2267, 2275, -1, 2266, 2639, 2268, -1, + 2266, 2275, 2274, -1, 2266, 2274, 2639, -1, + 2266, 2268, 2269, -1, 2266, 2269, 2267, -1, + 2270, 2272, 2271, -1, 2270, 2273, 2274, -1, + 2270, 2271, 2282, -1, 2270, 2282, 2273, -1, + 2270, 2275, 2272, -1, 2270, 2274, 2275, -1, + 2650, 2643, 2660, -1, 2650, 2660, 2684, -1, + 2658, 2276, 2656, -1, 2658, 2657, 2277, -1, + 2658, 2277, 2278, -1, 2658, 2278, 2276, -1, + 2279, 2654, 2280, -1, 2279, 2281, 2286, -1, + 2279, 2280, 2282, -1, 2279, 2282, 2281, -1, + 2279, 2286, 2653, -1, 2279, 2653, 2654, -1, + 2655, 2656, 2647, -1, 2655, 2642, 2654, -1, + 2283, 2657, 2653, -1, 2283, 2285, 2284, -1, + 2283, 2286, 2285, -1, 2283, 2653, 2286, -1, + 2283, 2284, 2287, -1, 2283, 2287, 2657, -1, + 2685, 2684, 2660, -1, 2876, 2662, 2877, -1, + 2312, 2292, 2288, -1, 2312, 2288, 3066, -1, + 2887, 2886, 2876, -1, 2289, 2661, 2643, -1, + 2289, 2643, 2645, -1, 2289, 2290, 2661, -1, + 2289, 2645, 2880, -1, 2289, 2880, 2291, -1, + 2289, 2291, 2290, -1, 3024, 2292, 2312, -1, + 3024, 2312, 3022, -1, 3024, 2293, 2292, -1, + 3024, 3026, 2293, -1, 3036, 2883, 2311, -1, + 2308, 2294, 3037, -1, 2308, 2309, 2294, -1, + 2308, 3036, 2311, -1, 2308, 3037, 3036, -1, + 3029, 3031, 2295, -1, 3029, 2295, 2296, -1, + 3029, 2296, 2664, -1, 2665, 2297, 2879, -1, + 2665, 2449, 2297, -1, 2298, 2300, 2299, -1, + 2298, 2540, 2301, -1, 2298, 2547, 2540, -1, + 2298, 2299, 2547, -1, 2298, 2301, 2302, -1, + 2298, 2302, 2300, -1, 2881, 2303, 2882, -1, + 2881, 2304, 2303, -1, 2881, 2667, 2304, -1, + 3039, 2305, 2666, -1, 3039, 2668, 2305, -1, + 2676, 2700, 2672, -1, 2676, 2674, 2677, -1, + 2306, 2307, 2636, -1, 2306, 2309, 2308, -1, + 2306, 2636, 2310, -1, 2306, 2310, 2309, -1, + 2306, 2311, 2307, -1, 2306, 2308, 2311, -1, + 2680, 2683, 2682, -1, 3072, 3138, 2683, -1, + 3072, 2683, 2680, -1, 3043, 2685, 2886, -1, + 2314, 3066, 3065, -1, 2314, 2663, 3022, -1, + 2314, 2312, 3066, -1, 2314, 3022, 2312, -1, + 2313, 2682, 2663, -1, 2313, 3065, 2681, -1, + 2313, 2314, 3065, -1, 2313, 2663, 2314, -1, + 2313, 2680, 2682, -1, 2313, 2681, 2680, -1, + 2688, 2896, 2895, -1, 2688, 2317, 2692, -1, + 2894, 2911, 2318, -1, 2894, 2316, 2895, -1, + 2894, 2318, 2316, -1, 2693, 2901, 2905, -1, + 2693, 2694, 2339, -1, 2935, 2934, 2317, -1, + 2935, 3198, 3197, -1, 2315, 2316, 3198, -1, + 2315, 3198, 2935, -1, 2315, 2935, 2317, -1, + 2315, 2317, 2688, -1, 2315, 2895, 2316, -1, + 2315, 2688, 2895, -1, 2691, 2934, 2727, -1, + 2691, 2317, 2934, -1, 2691, 2692, 2317, -1, + 2900, 2901, 2338, -1, 2900, 2338, 3056, -1, + 2891, 3243, 3245, -1, 2891, 3245, 2904, -1, + 2891, 2900, 3056, -1, 2891, 2904, 2900, -1, + 3244, 2696, 3245, -1, 2884, 2915, 3083, -1, + 2884, 2909, 2915, -1, 2884, 3063, 2909, -1, + 2698, 2631, 2318, -1, 2698, 2318, 2911, -1, + 2703, 3090, 2319, -1, 2703, 2319, 2923, -1, + 3183, 3090, 2703, -1, 3183, 2703, 2702, -1, + 2701, 3193, 2925, -1, 2701, 2320, 2920, -1, + 2701, 2925, 2922, -1, 2701, 2922, 2320, -1, + 3093, 2711, 2601, -1, 3093, 2321, 2711, -1, + 3093, 3094, 2321, -1, 2933, 2727, 2934, -1, + 3196, 2631, 2930, -1, 3196, 3200, 2631, -1, + 2324, 2323, 2322, -1, 2324, 2322, 2335, -1, + 2324, 2335, 2347, -1, 2324, 2347, 2960, -1, + 2965, 2705, 2323, -1, 2965, 2324, 2960, -1, + 2965, 2323, 2324, -1, 3116, 3206, 2327, -1, + 3116, 2325, 3115, -1, 3116, 2326, 2325, -1, + 3116, 2327, 2326, -1, 2938, 2327, 3206, -1, + 2938, 2939, 2328, -1, 2938, 2328, 2327, -1, + 2943, 2601, 2711, -1, 2329, 2331, 2330, -1, + 2329, 2622, 2332, -1, 2329, 2860, 2622, -1, + 2329, 2330, 2860, -1, 2329, 2333, 2331, -1, + 2329, 2332, 2333, -1, 2858, 2719, 2861, -1, + 2858, 2859, 2722, -1, 2723, 2334, 2719, -1, + 2723, 2721, 2347, -1, 2723, 2335, 2334, -1, + 2723, 2347, 2335, -1, 2348, 2721, 2720, -1, + 2348, 3129, 2349, -1, 3127, 2720, 2948, -1, + 3127, 3129, 2348, -1, 3127, 2348, 2720, -1, + 2336, 3119, 2337, -1, 2336, 2901, 2693, -1, + 2336, 2338, 2901, -1, 2336, 2337, 2338, -1, + 2336, 2339, 3119, -1, 2336, 2693, 2339, -1, + 3207, 2725, 2340, -1, 3207, 2340, 2342, -1, + 3207, 2342, 3208, -1, 3209, 2725, 3207, -1, + 2341, 2342, 2343, -1, 2341, 2343, 2344, -1, + 2341, 2344, 2345, -1, 2341, 2345, 3130, -1, + 2341, 3130, 3208, -1, 2341, 3208, 2342, -1, + 2707, 2349, 2708, -1, 2707, 2959, 2349, -1, + 2707, 2709, 2959, -1, 2961, 2959, 2709, -1, + 2346, 2347, 2721, -1, 2346, 2348, 2349, -1, + 2346, 2721, 2348, -1, 2346, 2349, 2959, -1, + 2346, 2959, 2960, -1, 2346, 2960, 2347, -1, + 3141, 3139, 2892, -1, 3141, 2892, 2350, -1, + 3141, 2350, 2981, -1, 3140, 2683, 3138, -1, + 2748, 2641, 2871, -1, 2970, 2732, 2729, -1, + 2736, 2978, 2977, -1, 2736, 2739, 2978, -1, + 2737, 2735, 2351, -1, 2737, 2351, 2745, -1, + 2742, 2737, 2745, -1, 2742, 2739, 2737, -1, + 2747, 2746, 2352, -1, 2747, 2352, 2864, -1, + 2747, 2864, 2641, -1, 2747, 2641, 2748, -1, + 3146, 2979, 2353, -1, 3146, 2353, 2354, -1, + 3146, 2354, 3148, -1, 2355, 2357, 2356, -1, + 2355, 2356, 2744, -1, 2355, 2358, 2357, -1, + 2355, 2744, 2359, -1, 2355, 2360, 2358, -1, + 2355, 2359, 2360, -1, 2361, 2362, 2363, -1, + 2361, 2364, 2365, -1, 2361, 2363, 2364, -1, + 2361, 2365, 2366, -1, 2361, 2366, 2367, -1, + 2361, 2367, 2362, -1, 2752, 2619, 2753, -1, + 2752, 2749, 2619, -1, 2752, 2985, 3149, -1, + 2752, 3149, 2749, -1, 2758, 2369, 2368, -1, + 2758, 2368, 2759, -1, 2758, 2987, 2369, -1, + 2758, 2988, 2987, -1, 3229, 2764, 2371, -1, + 2766, 2370, 2765, -1, 2766, 2371, 2370, -1, + 2766, 3229, 2371, -1, 2766, 3231, 3229, -1, + 2890, 2767, 3150, -1, 2992, 2989, 2767, -1, + 2986, 3238, 2686, -1, 2986, 2686, 2770, -1, + 2372, 2373, 2380, -1, 2372, 2380, 2374, -1, + 2372, 2374, 2375, -1, 2372, 2376, 2373, -1, + 2372, 2375, 2377, -1, 2372, 2377, 2376, -1, + 2378, 2380, 2379, -1, 2378, 2381, 2380, -1, + 2378, 2379, 2382, -1, 2378, 2382, 2381, -1, + 2383, 2384, 2385, -1, 2383, 2396, 2392, -1, + 2383, 2391, 2384, -1, 2383, 2392, 2391, -1, + 2383, 2397, 2396, -1, 2383, 2385, 2397, -1, + 2386, 2388, 2387, -1, 2386, 2389, 2388, -1, + 2386, 2387, 2390, -1, 2386, 2390, 2391, -1, + 2386, 2392, 2389, -1, 2386, 2391, 2392, -1, + 2393, 2394, 2395, -1, 2393, 2395, 2396, -1, + 2393, 2396, 2397, -1, 2393, 2397, 2398, -1, + 2393, 2398, 2399, -1, 2393, 2399, 2394, -1, + 2400, 2402, 2401, -1, 2400, 3164, 2405, -1, + 2400, 2405, 2402, -1, 2400, 2407, 3164, -1, + 2400, 2403, 2407, -1, 2400, 2401, 2403, -1, + 3162, 2771, 2404, -1, 3162, 2404, 2405, -1, + 3162, 2405, 3164, -1, 3166, 2410, 3165, -1, + 3166, 2406, 2410, -1, 3166, 2407, 2406, -1, + 3166, 3164, 2407, -1, 2997, 2776, 2996, -1, + 2997, 2413, 2776, -1, 2775, 2773, 2408, -1, + 2775, 2408, 2777, -1, 2409, 3165, 2410, -1, + 2409, 2411, 2413, -1, 2409, 2997, 3165, -1, + 2409, 2413, 2997, -1, 2409, 2410, 2412, -1, + 2409, 2412, 2411, -1, 2779, 2780, 2776, -1, + 2779, 2776, 2413, -1, 2779, 2414, 2784, -1, + 2779, 2413, 2414, -1, 2415, 2417, 2416, -1, + 2415, 2416, 2418, -1, 2415, 2418, 2419, -1, + 2415, 2420, 2417, -1, 2415, 2421, 2420, -1, + 2415, 2419, 2421, -1, 2422, 2423, 2431, -1, + 2422, 2424, 2423, -1, 2422, 2425, 2424, -1, + 2422, 2426, 2425, -1, 2422, 2427, 2426, -1, + 2422, 2431, 2427, -1, 2428, 2429, 2430, -1, + 2428, 2431, 2429, -1, 2428, 2430, 2432, -1, + 2428, 2433, 2431, -1, 2428, 2432, 2434, -1, + 2428, 2434, 2433, -1, 2435, 2437, 2436, -1, + 2435, 2552, 2437, -1, 2435, 2553, 2552, -1, + 2435, 2436, 2438, -1, 2435, 2438, 2553, -1, + 2439, 2440, 2441, -1, 2439, 2442, 2443, -1, + 2439, 2441, 2442, -1, 2439, 2443, 2444, -1, + 2439, 2445, 2440, -1, 2439, 2444, 2445, -1, + 2446, 2448, 2447, -1, 2446, 2449, 2665, -1, + 2446, 2450, 2449, -1, 2446, 2447, 2450, -1, + 2446, 2664, 2448, -1, 2446, 2665, 2664, -1, + 2786, 2451, 2452, -1, 2786, 2452, 2789, -1, + 2786, 2453, 2451, -1, 2786, 2787, 2453, -1, + 2798, 2454, 2463, -1, 2798, 2494, 2454, -1, + 2798, 2799, 2494, -1, 2455, 2464, 2463, -1, + 2455, 2456, 2457, -1, 2455, 2457, 2464, -1, + 2455, 2458, 2456, -1, 2455, 2459, 2458, -1, + 2455, 2463, 2459, -1, 2823, 2460, 2799, -1, + 2823, 2827, 2460, -1, 2465, 2806, 2800, -1, + 2465, 2462, 2461, -1, 2465, 2461, 2806, -1, + 2465, 2464, 2462, -1, 2797, 2463, 2464, -1, + 2797, 2464, 2465, -1, 2797, 2465, 2800, -1, + 2797, 2798, 2463, -1, 2510, 2511, 2466, -1, + 2510, 2467, 2472, -1, 2510, 2472, 2509, -1, + 2510, 2468, 2467, -1, 2510, 2466, 2468, -1, + 2828, 2469, 2826, -1, 2802, 2470, 2469, -1, + 2802, 2803, 2470, -1, 2802, 2469, 2828, -1, + 2471, 2473, 2472, -1, 2471, 2508, 2504, -1, + 2471, 2504, 2473, -1, 2471, 2472, 2474, -1, + 2471, 2474, 2475, -1, 2471, 2475, 2508, -1, + 2809, 2810, 2476, -1, 2809, 2476, 3019, -1, + 2809, 3019, 3015, -1, 2809, 3015, 2814, -1, + 2477, 2485, 2487, -1, 2477, 2478, 2479, -1, + 2477, 2479, 2480, -1, 2477, 2480, 2485, -1, + 2477, 2481, 2478, -1, 2477, 2487, 2481, -1, + 2482, 2483, 2484, -1, 2482, 2485, 2483, -1, + 2482, 2484, 2486, -1, 2482, 2487, 2485, -1, + 2482, 2486, 2811, -1, 2482, 2811, 2487, -1, + 2488, 2489, 2490, -1, 2488, 2492, 2491, -1, + 2488, 2491, 2493, -1, 2488, 2493, 2489, -1, + 2488, 2494, 2492, -1, 2488, 2490, 2494, -1, + 2495, 2497, 2496, -1, 2495, 2498, 2497, -1, + 2495, 2499, 2498, -1, 2495, 2500, 2499, -1, + 2495, 2501, 2500, -1, 2495, 2496, 2501, -1, + 2502, 2503, 2504, -1, 2502, 2505, 2506, -1, + 2502, 2506, 2507, -1, 2502, 2507, 2503, -1, + 2502, 2508, 2505, -1, 2502, 2504, 2508, -1, + 2514, 2820, 2511, -1, 2514, 2509, 2513, -1, + 2514, 2511, 2510, -1, 2514, 2510, 2509, -1, + 2821, 2511, 2820, -1, 2821, 2512, 2511, -1, + 2821, 2826, 2512, -1, 2817, 3018, 2820, -1, + 2817, 2513, 2816, -1, 2817, 2514, 2513, -1, + 2817, 2820, 2514, -1, 2815, 2816, 2515, -1, + 2815, 2515, 2516, -1, 2815, 2516, 2814, -1, + 2815, 2814, 3015, -1, 3016, 2517, 2518, -1, + 3016, 2518, 3017, -1, 3016, 3019, 2519, -1, + 3016, 2519, 2517, -1, 2825, 2819, 2827, -1, + 2825, 2826, 2821, -1, 2520, 2522, 2521, -1, + 2520, 2521, 2527, -1, 2520, 2523, 2522, -1, + 2520, 2527, 2534, -1, 2520, 2533, 2523, -1, + 2520, 2534, 2533, -1, 2524, 2526, 2525, -1, + 2524, 2527, 2526, -1, 2524, 2525, 2528, -1, + 2524, 2528, 2529, -1, 2524, 2529, 2530, -1, + 2524, 2530, 2527, -1, 2531, 2532, 2533, -1, + 2531, 2534, 2535, -1, 2531, 2533, 2534, -1, + 2531, 2535, 2536, -1, 2531, 2536, 2537, -1, + 2531, 2537, 2532, -1, 2546, 2545, 2538, -1, + 2546, 2538, 2539, -1, 2546, 2540, 2547, -1, + 2546, 2539, 2540, -1, 2541, 2542, 2543, -1, + 2541, 2543, 2544, -1, 2541, 2544, 2545, -1, + 2541, 2545, 2546, -1, 2541, 2547, 2542, -1, + 2541, 2546, 2547, -1, 2563, 2560, 2554, -1, + 2563, 2548, 2562, -1, 2563, 2549, 2548, -1, + 2563, 2554, 2549, -1, 2556, 2554, 2560, -1, + 2556, 2560, 2550, -1, 2556, 2550, 2552, -1, + 2551, 2552, 2553, -1, 2551, 2555, 2554, -1, + 2551, 2556, 2552, -1, 2551, 2554, 2556, -1, + 2551, 2557, 2555, -1, 2551, 2553, 2557, -1, + 2558, 2559, 2560, -1, 2558, 2561, 2559, -1, + 2558, 2562, 2561, -1, 2558, 2560, 2563, -1, + 2558, 2563, 2562, -1, 2564, 2566, 2565, -1, + 2564, 2567, 2566, -1, 2564, 2565, 2568, -1, + 2564, 2568, 2569, -1, 2564, 2569, 2570, -1, + 2564, 2570, 2567, -1, 2838, 2839, 2829, -1, + 2840, 2841, 2571, -1, 2840, 2572, 2839, -1, + 2840, 2571, 2573, -1, 2840, 2573, 2572, -1, + 2574, 2575, 2576, -1, 2574, 2577, 2578, -1, + 2574, 2576, 2577, -1, 2574, 2578, 2579, -1, + 2574, 2579, 2580, -1, 2574, 2580, 2575, -1, + 2596, 2582, 2581, -1, 2596, 2594, 2582, -1, + 2596, 2583, 2592, -1, 2596, 2581, 2583, -1, + 2584, 2585, 2586, -1, 2584, 2586, 2587, -1, + 2584, 2587, 2588, -1, 2584, 2588, 2589, -1, + 2584, 2589, 2590, -1, 2584, 2590, 2585, -1, + 2591, 2592, 2593, -1, 2591, 2595, 2594, -1, + 2591, 2596, 2592, -1, 2591, 2594, 2596, -1, + 2591, 2593, 2597, -1, 2591, 2597, 2595, -1, + 2603, 2598, 2602, -1, 2603, 2599, 2598, -1, + 2603, 2604, 2600, -1, 2603, 2600, 2599, -1, + 3095, 2601, 3212, -1, 3095, 3093, 2601, -1, + 2845, 3212, 2601, -1, 2845, 2943, 2947, -1, + 2845, 2601, 2943, -1, 2845, 3211, 3212, -1, + 3218, 3095, 3212, -1, 2849, 2602, 2850, -1, + 2849, 2603, 2602, -1, 2849, 2853, 2604, -1, + 2849, 2604, 2603, -1, 2605, 2606, 2607, -1, + 2605, 2607, 2613, -1, 2605, 2608, 2606, -1, + 2605, 2613, 2614, -1, 2605, 2614, 2609, -1, + 2605, 2609, 2608, -1, 2610, 2612, 2611, -1, + 2610, 2613, 2612, -1, 2610, 2614, 2613, -1, + 2610, 2611, 2615, -1, 2610, 2616, 2614, -1, + 2610, 2615, 2616, -1, 2617, 2762, 2761, -1, + 2617, 2761, 2618, -1, 2617, 2618, 2619, -1, + 2617, 2619, 2749, -1, 2617, 2749, 2750, -1, + 2617, 2750, 2762, -1, 2856, 2621, 2620, -1, + 2856, 2857, 2621, -1, 2856, 2620, 2622, -1, + 2856, 2622, 2860, -1, 2623, 2625, 2624, -1, + 2623, 2626, 2627, -1, 2623, 2628, 2626, -1, + 2623, 2624, 2628, -1, 2623, 2627, 2629, -1, + 2623, 2629, 2625, -1, 2699, 2697, 2630, -1, + 2699, 2631, 2698, -1, 2699, 2930, 2631, -1, + 2699, 2630, 2930, -1, 2632, 2633, 2634, -1, + 2632, 2634, 2635, -1, 2632, 2704, 2633, -1, + 2632, 2635, 2636, -1, 2632, 2637, 2704, -1, + 2632, 2636, 2637, -1, 2865, 2638, 2640, -1, + 2865, 2640, 2863, -1, 2865, 2639, 2638, -1, + 2865, 2866, 2639, -1, 2872, 2640, 2873, -1, + 2872, 2871, 2641, -1, 2872, 2863, 2640, -1, + 2872, 2641, 2863, -1, 2874, 2873, 2642, -1, + 2874, 2642, 2655, -1, 2874, 2647, 2875, -1, + 2874, 2655, 2647, -1, 2651, 2684, 3050, -1, + 2651, 2650, 2684, -1, 2651, 3050, 2870, -1, + 2651, 2870, 2875, -1, 2649, 2643, 2650, -1, + 2649, 2648, 2644, -1, 2649, 2644, 2645, -1, + 2649, 2645, 2643, -1, 2646, 2647, 2648, -1, + 2646, 2648, 2649, -1, 2646, 2649, 2650, -1, + 2646, 2650, 2651, -1, 2646, 2875, 2647, -1, + 2646, 2651, 2875, -1, 2652, 2654, 2653, -1, + 2652, 2655, 2654, -1, 2652, 2656, 2655, -1, + 2652, 2653, 2657, -1, 2652, 2658, 2656, -1, + 2652, 2657, 2658, -1, 2659, 2876, 2886, -1, + 2659, 2685, 2660, -1, 2659, 2886, 2685, -1, + 2659, 2660, 2661, -1, 2659, 2661, 2662, -1, + 2659, 2662, 2876, -1, 3021, 2663, 2885, -1, + 3021, 2885, 2887, -1, 3021, 3022, 2663, -1, + 3028, 3029, 2664, -1, 3028, 2665, 2879, -1, + 3028, 2664, 2665, -1, 3040, 3039, 2666, -1, + 3040, 2666, 2667, -1, 3040, 2667, 2881, -1, + 3038, 2668, 3039, -1, 3038, 2669, 2668, -1, + 3038, 2670, 2669, -1, 3038, 3037, 2670, -1, + 2671, 2676, 2672, -1, 2671, 2673, 2883, -1, + 2671, 2672, 2673, -1, 2671, 2883, 2882, -1, + 2671, 2882, 2674, -1, 2671, 2674, 2676, -1, + 2675, 2676, 2677, -1, 2675, 2677, 2678, -1, + 2675, 2678, 2679, -1, 2675, 2679, 3089, -1, + 2675, 3089, 2700, -1, 2675, 2700, 2676, -1, + 3064, 3068, 2681, -1, 3064, 2681, 3065, -1, + 3071, 3072, 2680, -1, 3071, 2681, 3068, -1, + 3071, 2680, 2681, -1, 3042, 2885, 2682, -1, + 3042, 2682, 2683, -1, 3042, 2683, 3140, -1, + 3051, 3050, 2684, -1, 3051, 2684, 2685, -1, + 3051, 2685, 3043, -1, 3078, 3077, 2889, -1, + 3054, 2686, 3238, -1, 3054, 3238, 3236, -1, + 3054, 2687, 2686, -1, 3054, 3057, 2687, -1, + 3059, 3248, 3060, -1, 3173, 3174, 3059, -1, + 2903, 2692, 2905, -1, 2903, 2688, 2692, -1, + 2903, 2896, 2688, -1, 2910, 2911, 2894, -1, + 2695, 2691, 2727, -1, 2695, 3133, 2689, -1, + 2695, 2727, 3133, -1, 2695, 2689, 2694, -1, + 2690, 2692, 2691, -1, 2690, 2694, 2693, -1, + 2690, 2695, 2694, -1, 2690, 2691, 2695, -1, + 2690, 2905, 2692, -1, 2690, 2693, 2905, -1, + 2902, 2904, 2696, -1, 2902, 2696, 2897, -1, + 2902, 2897, 2896, -1, 2902, 2896, 2903, -1, + 2908, 2698, 2911, -1, 3087, 2884, 3083, -1, + 2912, 2914, 2898, -1, 2912, 2897, 2696, -1, + 2912, 2898, 2897, -1, 2912, 2696, 3244, -1, + 2906, 3067, 2697, -1, 2906, 2698, 2908, -1, + 2906, 2697, 2699, -1, 2906, 2699, 2698, -1, + 3088, 2918, 2700, -1, 3088, 2700, 3089, -1, + 3179, 2702, 3102, -1, 3179, 3183, 2702, -1, + 3098, 2701, 2920, -1, 3098, 3193, 2701, -1, + 3096, 3102, 2702, -1, 3096, 2702, 2703, -1, + 2924, 2703, 2923, -1, 2924, 3096, 2703, -1, + 2924, 3097, 3096, -1, 2926, 2704, 2917, -1, + 2926, 2928, 2704, -1, 3107, 2927, 3182, -1, + 3192, 2925, 3193, -1, 3103, 3134, 2932, -1, + 3103, 2955, 3134, -1, 3103, 3104, 2955, -1, + 3112, 2932, 2933, -1, 2964, 2705, 2965, -1, + 2964, 2706, 2705, -1, 2964, 2968, 2706, -1, + 2710, 2717, 2709, -1, 2710, 2709, 2707, -1, + 2710, 2708, 2724, -1, 2710, 2707, 2708, -1, + 3114, 3115, 2968, -1, 2716, 3204, 2962, -1, + 2716, 2962, 2961, -1, 2716, 2709, 2717, -1, + 2716, 2961, 2709, -1, 2726, 2715, 2717, -1, + 2726, 2847, 2715, -1, 2726, 2710, 2724, -1, + 2726, 2717, 2710, -1, 2937, 2938, 3206, -1, + 2937, 3206, 3205, -1, 2937, 3205, 2714, -1, + 2937, 2714, 2945, -1, 2942, 2943, 2711, -1, + 2942, 2711, 2712, -1, 2942, 2940, 2946, -1, + 2942, 2712, 2940, -1, 2944, 2945, 2714, -1, + 2944, 2714, 2715, -1, 2944, 2847, 2947, -1, + 2944, 2715, 2847, -1, 2713, 2715, 2714, -1, + 2713, 3204, 2716, -1, 2713, 3205, 3204, -1, + 2713, 2714, 3205, -1, 2713, 2717, 2715, -1, + 2713, 2716, 2717, -1, 2718, 2719, 2858, -1, + 2718, 2720, 2721, -1, 2718, 2722, 2720, -1, + 2718, 2858, 2722, -1, 2718, 2721, 2723, -1, + 2718, 2723, 2719, -1, 2846, 2724, 2725, -1, + 2846, 2725, 3209, -1, 2846, 2726, 2724, -1, + 2846, 2847, 2726, -1, 3132, 2933, 2932, -1, + 3132, 2932, 3134, -1, 3132, 3133, 2727, -1, + 3132, 2727, 2933, -1, 3224, 2956, 2957, -1, + 2966, 2965, 2960, -1, 3137, 3141, 2981, -1, + 3049, 2748, 2871, -1, 3049, 3048, 2748, -1, + 3049, 2870, 3050, -1, 3049, 2871, 2870, -1, + 2728, 2970, 2729, -1, 2728, 2729, 2730, -1, + 2728, 2730, 2734, -1, 2728, 2977, 2970, -1, + 2728, 2734, 2736, -1, 2728, 2736, 2977, -1, + 2972, 3249, 2984, -1, 2972, 2974, 3249, -1, + 2972, 2984, 2731, -1, 2972, 2731, 2973, -1, + 2969, 2973, 2731, -1, 2969, 2731, 2732, -1, + 2969, 2732, 2970, -1, 3147, 2970, 2977, -1, + 3144, 3148, 2975, -1, 2733, 2734, 2735, -1, + 2733, 2736, 2734, -1, 2733, 2735, 2737, -1, + 2733, 2739, 2736, -1, 2733, 2737, 2739, -1, + 2738, 2978, 2739, -1, 2738, 2739, 2742, -1, + 2738, 2979, 2978, -1, 2738, 2742, 2743, -1, + 2738, 2740, 2979, -1, 2738, 2743, 2740, -1, + 2741, 2743, 2742, -1, 2741, 2744, 2868, -1, + 2741, 2745, 2744, -1, 2741, 2742, 2745, -1, + 2741, 2868, 2867, -1, 2741, 2867, 2743, -1, + 2983, 2982, 2746, -1, 2983, 2746, 2747, -1, + 2983, 2748, 3048, -1, 2983, 2747, 2748, -1, + 3151, 2750, 2749, -1, 3151, 2749, 3149, -1, + 3151, 2767, 2750, -1, 3151, 3150, 2767, -1, + 3250, 3149, 2985, -1, 2751, 2752, 2753, -1, + 2751, 2754, 2755, -1, 2751, 2753, 2754, -1, + 2751, 2755, 2756, -1, 2751, 2756, 2985, -1, + 2751, 2985, 2752, -1, 2757, 2758, 2759, -1, + 2757, 2760, 2761, -1, 2757, 2759, 2760, -1, + 2757, 2761, 2762, -1, 2757, 2762, 2988, -1, + 2757, 2988, 2758, -1, 3228, 2763, 2764, -1, + 3228, 2764, 3229, -1, 3228, 3152, 2763, -1, + 2990, 2765, 2987, -1, 2990, 2766, 2765, -1, + 2990, 3231, 2766, -1, 2769, 2890, 2889, -1, + 2769, 2767, 2890, -1, 2769, 2992, 2767, -1, + 2769, 2768, 2992, -1, 3158, 2992, 2768, -1, + 3158, 2768, 3169, -1, 3052, 3169, 2768, -1, + 3052, 2769, 2889, -1, 3052, 2768, 2769, -1, + 3052, 2889, 3077, -1, 3153, 2770, 2952, -1, + 3153, 2986, 2770, -1, 3153, 2952, 3154, -1, + 3161, 2994, 2771, -1, 3161, 2771, 3162, -1, + 2781, 2775, 2780, -1, 2781, 2782, 2772, -1, + 2781, 2772, 2773, -1, 2781, 2773, 2775, -1, + 2774, 2780, 2775, -1, 2774, 2996, 2776, -1, + 2774, 2776, 2780, -1, 2774, 2993, 2996, -1, + 2774, 2777, 2993, -1, 2774, 2775, 2777, -1, + 2778, 2780, 2779, -1, 2778, 2782, 2781, -1, + 2778, 2781, 2780, -1, 2778, 2783, 2782, -1, + 2778, 2784, 2783, -1, 2778, 2779, 2784, -1, + 2785, 2787, 2786, -1, 2785, 2793, 2788, -1, + 2785, 2788, 2787, -1, 2785, 2792, 2793, -1, + 2785, 2789, 2792, -1, 2785, 2786, 2789, -1, + 3004, 2790, 3002, -1, 3004, 3005, 2790, -1, + 2999, 3000, 2791, -1, 2999, 2791, 2794, -1, + 3010, 2792, 3003, -1, 3010, 2793, 2792, -1, + 3010, 3011, 2793, -1, 3007, 3008, 2999, -1, + 3007, 2999, 2794, -1, 3007, 2795, 3012, -1, + 3007, 2794, 2795, -1, 2796, 2800, 2824, -1, + 2796, 2797, 2800, -1, 2796, 2824, 2823, -1, + 2796, 2798, 2797, -1, 2796, 2799, 2798, -1, + 2796, 2823, 2799, -1, 2807, 2802, 2828, -1, + 2807, 2800, 2806, -1, 2807, 2824, 2800, -1, + 2807, 2828, 2824, -1, 2801, 2803, 2802, -1, + 2801, 2805, 2804, -1, 2801, 2804, 2803, -1, + 2801, 2806, 2805, -1, 2801, 2807, 2806, -1, + 2801, 2802, 2807, -1, 2808, 2810, 2809, -1, + 2808, 2811, 2810, -1, 2808, 2812, 2811, -1, + 2808, 2813, 2812, -1, 2808, 2814, 2813, -1, + 2808, 2809, 2814, -1, 3014, 2816, 2815, -1, + 3014, 3018, 2817, -1, 3014, 2817, 2816, -1, + 3014, 2815, 3015, -1, 2818, 2819, 2825, -1, + 2818, 3018, 3017, -1, 2818, 3017, 2819, -1, + 2818, 2820, 3018, -1, 2818, 2821, 2820, -1, + 2818, 2825, 2821, -1, 2822, 2823, 2824, -1, + 2822, 2826, 2825, -1, 2822, 2827, 2823, -1, + 2822, 2825, 2827, -1, 2822, 2828, 2826, -1, + 2822, 2824, 2828, -1, 2834, 2838, 2829, -1, + 2834, 2829, 2830, -1, 2834, 2830, 2831, -1, + 2834, 2831, 2835, -1, 2832, 2843, 2838, -1, + 2832, 2833, 2843, -1, 2832, 2834, 2835, -1, + 2832, 2838, 2834, -1, 2832, 2836, 2833, -1, + 2832, 2835, 2836, -1, 2837, 2839, 2838, -1, + 2837, 2841, 2840, -1, 2837, 2840, 2839, -1, + 2837, 2842, 2841, -1, 2837, 2843, 2842, -1, + 2837, 2838, 2843, -1, 2844, 3211, 2845, -1, + 2844, 2847, 2846, -1, 2844, 2947, 2847, -1, + 2844, 2845, 2947, -1, 2844, 3209, 3211, -1, + 2844, 2846, 3209, -1, 2848, 2849, 2850, -1, + 2848, 2851, 2852, -1, 2848, 2852, 2853, -1, + 2848, 2853, 2849, -1, 2848, 2854, 2851, -1, + 2848, 2850, 2854, -1, 2855, 2857, 2856, -1, + 2855, 2859, 2858, -1, 2855, 2860, 2859, -1, + 2855, 2856, 2860, -1, 2855, 2861, 2857, -1, + 2855, 2858, 2861, -1, 2862, 2863, 2864, -1, + 2862, 2865, 2863, -1, 2862, 2866, 2865, -1, + 2862, 2864, 2867, -1, 2862, 2868, 2866, -1, + 2862, 2867, 2868, -1, 2869, 2870, 2871, -1, + 2869, 2872, 2873, -1, 2869, 2871, 2872, -1, + 2869, 2873, 2874, -1, 2869, 2875, 2870, -1, + 2869, 2874, 2875, -1, 3023, 2887, 2876, -1, + 3023, 3021, 2887, -1, 3023, 2877, 3025, -1, + 3023, 2876, 2877, -1, 3030, 2879, 2878, -1, + 3030, 3028, 2879, -1, 3030, 2880, 3032, -1, + 3030, 2878, 2880, -1, 3035, 2881, 2882, -1, + 3035, 3040, 2881, -1, 3035, 2882, 2883, -1, + 3035, 2883, 3036, -1, 3069, 3063, 2884, -1, + 3069, 3064, 3063, -1, 3069, 3068, 3064, -1, + 3069, 2884, 3087, -1, 3044, 2885, 3042, -1, + 3044, 3043, 2886, -1, 3044, 2887, 2885, -1, + 3044, 2886, 2887, -1, 3046, 3051, 3043, -1, + 2888, 3259, 2913, -1, 2888, 3078, 2889, -1, + 2888, 2913, 3078, -1, 2888, 2889, 2890, -1, + 2888, 2890, 3150, -1, 2888, 3150, 3259, -1, + 3055, 3168, 3243, -1, 3055, 3243, 2891, -1, + 3055, 2891, 3056, -1, 3073, 3139, 3138, -1, + 3073, 3138, 3072, -1, 3058, 3060, 2976, -1, + 3058, 2976, 2892, -1, 3058, 2892, 3139, -1, + 3058, 3139, 3073, -1, 3247, 3248, 3059, -1, + 3247, 3059, 3174, -1, 3258, 2913, 3259, -1, + 3258, 3081, 2913, -1, 2893, 2910, 2894, -1, + 2893, 2895, 2896, -1, 2893, 2894, 2895, -1, + 2893, 2896, 2897, -1, 2893, 2897, 2898, -1, + 2893, 2898, 2910, -1, 2916, 2910, 2898, -1, + 2916, 2898, 2914, -1, 2899, 2901, 2900, -1, + 2899, 2902, 2903, -1, 2899, 2900, 2904, -1, + 2899, 2904, 2902, -1, 2899, 2905, 2901, -1, + 2899, 2903, 2905, -1, 3062, 2909, 3063, -1, + 3062, 2908, 2909, -1, 3062, 3067, 2906, -1, + 3062, 2906, 2908, -1, 2907, 2909, 2908, -1, + 2907, 2910, 2916, -1, 2907, 2911, 2910, -1, + 2907, 2908, 2911, -1, 2907, 2915, 2909, -1, + 2907, 2916, 2915, -1, 3175, 3071, 3068, -1, + 3076, 3082, 2914, -1, 3076, 2912, 3244, -1, + 3076, 2914, 2912, -1, 3076, 3244, 3241, -1, + 3080, 2913, 3081, -1, 3080, 3078, 2913, -1, + 3084, 2914, 3082, -1, 3084, 3083, 2915, -1, + 3084, 2915, 2916, -1, 3084, 2916, 2914, -1, + 3086, 3087, 3083, -1, 2919, 2926, 2917, -1, + 2919, 2927, 2926, -1, 2919, 2917, 2918, -1, + 2919, 2918, 3088, -1, 3101, 3179, 3102, -1, + 3101, 3111, 3110, -1, 3181, 2919, 3088, -1, + 3181, 3182, 2927, -1, 3181, 2927, 2919, -1, + 3092, 2920, 3094, -1, 3092, 3098, 2920, -1, + 3186, 3098, 3092, -1, 2921, 2923, 2922, -1, + 2921, 2924, 2923, -1, 2921, 2922, 2925, -1, + 2921, 2925, 3192, -1, 2921, 3097, 2924, -1, + 2921, 3192, 3097, -1, 2931, 2926, 2927, -1, + 2931, 2927, 3107, -1, 2931, 2928, 2926, -1, + 2931, 2929, 2928, -1, 3106, 2930, 2929, -1, + 3106, 3196, 2930, -1, 3106, 2929, 2931, -1, + 3106, 2931, 3107, -1, 3191, 3097, 3192, -1, + 3100, 3103, 2932, -1, 3100, 2932, 3112, -1, + 3100, 3112, 3111, -1, 3100, 3111, 3101, -1, + 3113, 3112, 2933, -1, 3113, 2933, 2934, -1, + 3113, 2934, 2935, -1, 3113, 2935, 3197, -1, + 3203, 3114, 2967, -1, 3203, 2967, 2962, -1, + 3203, 2962, 3204, -1, 2936, 2938, 2937, -1, + 2936, 2939, 2938, -1, 2936, 2945, 2946, -1, + 2936, 2937, 2945, -1, 2936, 2940, 2939, -1, + 2936, 2946, 2940, -1, 2941, 2943, 2942, -1, + 2941, 2945, 2944, -1, 2941, 2946, 2945, -1, + 2941, 2942, 2946, -1, 2941, 2947, 2943, -1, + 2941, 2944, 2947, -1, 3124, 3127, 2948, -1, + 3124, 2948, 2950, -1, 2949, 2953, 3125, -1, + 2949, 2950, 2951, -1, 2949, 3124, 2950, -1, + 2949, 3125, 3124, -1, 2949, 2951, 2952, -1, + 2949, 2952, 2953, -1, 3120, 3125, 2953, -1, + 3120, 2953, 2954, -1, 3120, 2954, 3118, -1, + 3126, 3122, 3128, -1, 3126, 3125, 3120, -1, + 3190, 3189, 3221, -1, 3190, 3104, 3191, -1, + 3190, 2955, 3104, -1, 3190, 3221, 2955, -1, + 3223, 3134, 2955, -1, 3223, 2955, 3221, -1, + 3215, 3130, 2956, -1, 3215, 2956, 3224, -1, + 3225, 2957, 3133, -1, 3225, 3224, 2957, -1, + 2958, 2960, 2959, -1, 2958, 2966, 2960, -1, + 2958, 2959, 2961, -1, 2958, 2961, 2962, -1, + 2958, 2962, 2967, -1, 2958, 2967, 2966, -1, + 2963, 2964, 2965, -1, 2963, 2965, 2966, -1, + 2963, 2966, 2967, -1, 2963, 2967, 3114, -1, + 2963, 2968, 2964, -1, 2963, 3114, 2968, -1, + 3136, 3137, 3047, -1, 3136, 3047, 3046, -1, + 3143, 2973, 2969, -1, 3143, 3144, 2973, -1, + 3143, 2969, 2970, -1, 3143, 2970, 3147, -1, + 2971, 2972, 2973, -1, 2971, 2973, 3144, -1, + 2971, 2974, 2972, -1, 2971, 3144, 2975, -1, + 2971, 2976, 2974, -1, 2971, 2975, 2976, -1, + 3145, 2977, 2978, -1, 3145, 3147, 2977, -1, + 3145, 2978, 2979, -1, 3145, 2979, 3146, -1, + 2980, 3137, 2981, -1, 2980, 2981, 2982, -1, + 2980, 2982, 2983, -1, 2980, 2983, 3048, -1, + 2980, 3048, 3047, -1, 2980, 3047, 3137, -1, + 3251, 2985, 2984, -1, 3251, 3250, 2985, -1, + 3251, 2984, 3249, -1, 3261, 3151, 3149, -1, + 3234, 2986, 3153, -1, 3234, 3238, 2986, -1, + 2991, 2990, 2987, -1, 2991, 2987, 2988, -1, + 2991, 2988, 2989, -1, 2991, 2989, 2992, -1, + 3157, 3231, 2990, -1, 3157, 3230, 3231, -1, + 3157, 2991, 2992, -1, 3157, 2990, 2991, -1, + 3157, 2992, 3158, -1, 3167, 3158, 3169, -1, + 3167, 3168, 3159, -1, 2995, 2996, 2993, -1, + 2995, 2993, 2994, -1, 2995, 2994, 3161, -1, + 3163, 2996, 2995, -1, 3163, 2995, 3161, -1, + 3163, 2997, 2996, -1, 3163, 3165, 2997, -1, + 2998, 3008, 3004, -1, 2998, 3000, 2999, -1, + 2998, 2999, 3008, -1, 2998, 3001, 3000, -1, + 2998, 3002, 3001, -1, 2998, 3004, 3002, -1, + 3009, 3010, 3003, -1, 3009, 3004, 3008, -1, + 3009, 3003, 3005, -1, 3009, 3005, 3004, -1, + 3006, 3008, 3007, -1, 3006, 3009, 3008, -1, + 3006, 3010, 3009, -1, 3006, 3011, 3010, -1, + 3006, 3012, 3011, -1, 3006, 3007, 3012, -1, + 3013, 3014, 3015, -1, 3013, 3016, 3017, -1, + 3013, 3017, 3018, -1, 3013, 3018, 3014, -1, + 3013, 3015, 3019, -1, 3013, 3019, 3016, -1, + 3020, 3022, 3021, -1, 3020, 3021, 3023, -1, + 3020, 3024, 3022, -1, 3020, 3023, 3025, -1, + 3020, 3025, 3026, -1, 3020, 3026, 3024, -1, + 3027, 3029, 3028, -1, 3027, 3028, 3030, -1, + 3027, 3031, 3029, -1, 3027, 3030, 3032, -1, + 3027, 3032, 3033, -1, 3027, 3033, 3031, -1, + 3034, 3035, 3036, -1, 3034, 3036, 3037, -1, + 3034, 3037, 3038, -1, 3034, 3038, 3039, -1, + 3034, 3039, 3040, -1, 3034, 3040, 3035, -1, + 3041, 3042, 3140, -1, 3041, 3140, 3136, -1, + 3041, 3136, 3046, -1, 3041, 3046, 3043, -1, + 3041, 3043, 3044, -1, 3041, 3044, 3042, -1, + 3045, 3046, 3047, -1, 3045, 3047, 3048, -1, + 3045, 3048, 3049, -1, 3045, 3049, 3050, -1, + 3045, 3050, 3051, -1, 3045, 3051, 3046, -1, + 3155, 3159, 3168, -1, 3155, 3168, 3055, -1, + 3240, 3052, 3077, -1, 3240, 3169, 3052, -1, + 3240, 3077, 3241, -1, 3053, 3054, 3236, -1, + 3053, 3236, 3155, -1, 3053, 3155, 3055, -1, + 3053, 3055, 3056, -1, 3053, 3056, 3057, -1, + 3053, 3057, 3054, -1, 3074, 3058, 3073, -1, + 3074, 3173, 3059, -1, 3074, 3059, 3060, -1, + 3074, 3060, 3058, -1, 3252, 3247, 3174, -1, + 3252, 3174, 3172, -1, 3252, 3172, 3257, -1, + 3085, 3257, 3172, -1, 3085, 3258, 3257, -1, + 3085, 3081, 3258, -1, 3085, 3086, 3081, -1, + 3061, 3062, 3063, -1, 3061, 3064, 3065, -1, + 3061, 3063, 3064, -1, 3061, 3065, 3066, -1, + 3061, 3066, 3067, -1, 3061, 3067, 3062, -1, + 3176, 3175, 3068, -1, 3176, 3068, 3069, -1, + 3176, 3069, 3087, -1, 3070, 3072, 3071, -1, + 3070, 3071, 3175, -1, 3070, 3073, 3072, -1, + 3070, 3175, 3173, -1, 3070, 3173, 3074, -1, + 3070, 3074, 3073, -1, 3075, 3080, 3082, -1, + 3075, 3076, 3241, -1, 3075, 3082, 3076, -1, + 3075, 3241, 3077, -1, 3075, 3077, 3078, -1, + 3075, 3078, 3080, -1, 3079, 3080, 3081, -1, + 3079, 3081, 3086, -1, 3079, 3082, 3080, -1, + 3079, 3086, 3083, -1, 3079, 3083, 3084, -1, + 3079, 3084, 3082, -1, 3171, 3085, 3172, -1, + 3171, 3086, 3085, -1, 3171, 3087, 3086, -1, + 3171, 3176, 3087, -1, 3178, 3179, 3101, -1, + 3178, 3101, 3110, -1, 3180, 3181, 3088, -1, + 3180, 3088, 3089, -1, 3180, 3089, 3090, -1, + 3180, 3090, 3183, -1, 3185, 3218, 3217, -1, + 3185, 3095, 3218, -1, 3091, 3186, 3092, -1, + 3091, 3094, 3093, -1, 3091, 3092, 3094, -1, + 3091, 3093, 3095, -1, 3091, 3095, 3185, -1, + 3091, 3185, 3186, -1, 3105, 3191, 3104, -1, + 3105, 3102, 3096, -1, 3105, 3096, 3097, -1, + 3105, 3097, 3191, -1, 3188, 3193, 3098, -1, + 3188, 3098, 3186, -1, 3099, 3100, 3101, -1, + 3099, 3101, 3102, -1, 3099, 3104, 3103, -1, + 3099, 3103, 3100, -1, 3099, 3102, 3105, -1, + 3099, 3105, 3104, -1, 3108, 3110, 3199, -1, + 3108, 3107, 3182, -1, 3108, 3182, 3178, -1, + 3108, 3178, 3110, -1, 3195, 3106, 3107, -1, + 3195, 3107, 3108, -1, 3195, 3108, 3199, -1, + 3195, 3196, 3106, -1, 3109, 3199, 3110, -1, + 3109, 3110, 3111, -1, 3109, 3111, 3112, -1, + 3109, 3112, 3113, -1, 3109, 3197, 3199, -1, + 3109, 3113, 3197, -1, 3202, 3115, 3114, -1, + 3202, 3114, 3203, -1, 3202, 3206, 3116, -1, + 3202, 3116, 3115, -1, 3117, 3118, 3119, -1, + 3117, 3120, 3118, -1, 3117, 3126, 3120, -1, + 3117, 3119, 3121, -1, 3117, 3121, 3122, -1, + 3117, 3122, 3126, -1, 3123, 3124, 3125, -1, + 3123, 3125, 3126, -1, 3123, 3127, 3124, -1, + 3123, 3126, 3128, -1, 3123, 3128, 3129, -1, + 3123, 3129, 3127, -1, 3220, 3221, 3189, -1, + 3214, 3208, 3130, -1, 3214, 3130, 3215, -1, + 3222, 3220, 3217, -1, 3222, 3215, 3224, -1, + 3131, 3133, 3132, -1, 3131, 3225, 3133, -1, + 3131, 3132, 3134, -1, 3131, 3134, 3223, -1, + 3131, 3223, 3225, -1, 3135, 3137, 3136, -1, + 3135, 3138, 3139, -1, 3135, 3140, 3138, -1, + 3135, 3136, 3140, -1, 3135, 3139, 3141, -1, + 3135, 3141, 3137, -1, 3142, 3144, 3143, -1, + 3142, 3145, 3146, -1, 3142, 3143, 3147, -1, + 3142, 3147, 3145, -1, 3142, 3146, 3148, -1, + 3142, 3148, 3144, -1, 3254, 3149, 3250, -1, + 3254, 3261, 3149, -1, 3260, 3259, 3150, -1, + 3260, 3150, 3151, -1, 3260, 3151, 3261, -1, + 3227, 3152, 3228, -1, 3227, 3234, 3153, -1, + 3227, 3154, 3152, -1, 3227, 3153, 3154, -1, + 3235, 3230, 3159, -1, 3235, 3155, 3236, -1, + 3235, 3159, 3155, -1, 3233, 3229, 3231, -1, + 3156, 3230, 3157, -1, 3156, 3157, 3158, -1, + 3156, 3158, 3167, -1, 3156, 3159, 3230, -1, + 3156, 3167, 3159, -1, 3160, 3161, 3162, -1, + 3160, 3163, 3161, -1, 3160, 3162, 3164, -1, + 3160, 3165, 3163, -1, 3160, 3164, 3166, -1, + 3160, 3166, 3165, -1, 3242, 3168, 3167, -1, + 3242, 3243, 3168, -1, 3242, 3167, 3169, -1, + 3242, 3169, 3240, -1, 3253, 3247, 3252, -1, + 3253, 3254, 3250, -1, 3170, 3171, 3172, -1, + 3170, 3174, 3173, -1, 3170, 3172, 3174, -1, + 3170, 3173, 3175, -1, 3170, 3175, 3176, -1, + 3170, 3176, 3171, -1, 3177, 3179, 3178, -1, + 3177, 3181, 3180, -1, 3177, 3182, 3181, -1, + 3177, 3178, 3182, -1, 3177, 3183, 3179, -1, + 3177, 3180, 3183, -1, 3184, 3185, 3217, -1, + 3184, 3217, 3220, -1, 3184, 3220, 3189, -1, + 3184, 3189, 3188, -1, 3184, 3186, 3185, -1, + 3184, 3188, 3186, -1, 3187, 3188, 3189, -1, + 3187, 3189, 3190, -1, 3187, 3190, 3191, -1, + 3187, 3191, 3192, -1, 3187, 3192, 3193, -1, + 3187, 3193, 3188, -1, 3194, 3196, 3195, -1, + 3194, 3197, 3198, -1, 3194, 3199, 3197, -1, + 3194, 3195, 3199, -1, 3194, 3198, 3200, -1, + 3194, 3200, 3196, -1, 3201, 3202, 3203, -1, + 3201, 3204, 3205, -1, 3201, 3203, 3204, -1, + 3201, 3205, 3206, -1, 3201, 3206, 3202, -1, + 3210, 3207, 3208, -1, 3210, 3208, 3214, -1, + 3210, 3209, 3207, -1, 3210, 3211, 3209, -1, + 3216, 3211, 3210, -1, 3216, 3210, 3214, -1, + 3216, 3212, 3211, -1, 3216, 3218, 3212, -1, + 3213, 3214, 3215, -1, 3213, 3215, 3222, -1, + 3213, 3216, 3214, -1, 3213, 3222, 3217, -1, + 3213, 3217, 3218, -1, 3213, 3218, 3216, -1, + 3219, 3221, 3220, -1, 3219, 3220, 3222, -1, + 3219, 3223, 3221, -1, 3219, 3222, 3224, -1, + 3219, 3224, 3225, -1, 3219, 3225, 3223, -1, + 3226, 3233, 3234, -1, 3226, 3227, 3228, -1, + 3226, 3234, 3227, -1, 3226, 3228, 3229, -1, + 3226, 3229, 3233, -1, 3237, 3230, 3235, -1, + 3237, 3231, 3230, -1, 3237, 3233, 3231, -1, + 3232, 3234, 3233, -1, 3232, 3235, 3236, -1, + 3232, 3237, 3235, -1, 3232, 3233, 3237, -1, + 3232, 3236, 3238, -1, 3232, 3238, 3234, -1, + 3239, 3240, 3241, -1, 3239, 3242, 3240, -1, + 3239, 3243, 3242, -1, 3239, 3241, 3244, -1, + 3239, 3245, 3243, -1, 3239, 3244, 3245, -1, + 3246, 3248, 3247, -1, 3246, 3247, 3253, -1, + 3246, 3249, 3248, -1, 3246, 3253, 3250, -1, + 3246, 3251, 3249, -1, 3246, 3250, 3251, -1, + 3256, 3252, 3257, -1, 3256, 3253, 3252, -1, + 3256, 3261, 3254, -1, 3256, 3254, 3253, -1, + 3255, 3256, 3257, -1, 3255, 3258, 3259, -1, + 3255, 3257, 3258, -1, 3255, 3259, 3260, -1, + 3255, 3260, 3261, -1, 3255, 3261, 3256, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link2.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link2.wrl new file mode 100644 index 0000000..229fbfc --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link2.wrl @@ -0,0 +1,6713 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.056669399 0.191514 -0.01756, + 0.056661699 0.171514 -0.017573399, + 0.00185474 0.208459 0.052131601, + 0.0599402 0.050776001 0.0431167, + 0.0307144 0.20845699 0.053708401, + -0.0307144 0.191539 -0.049389899, + -0.053759102 0.20847701 0.028811, + 0.056809202 0.165609 -0.0170244, + 2.7000421e-008 -0.0600104 0.0144522, + 4.7590005e-005 -0.060011499 0.0144522, + 0.00267513 -0.0599587 0.0236667, + 0.054342099 0.19151901 -0.023282399, + 0.051830001 0.15507001 -0.026884999, + 0.059316002 0.191506 -0.0068815602, + 0.0521175 0.20847499 0.0318943, + 0.059445001 0.049206901 0.047387201, + 0.058689699 0.208488 0.0146365, + 0.0596609 0.20849299 0.0085359104, + 0.059999999 0.047173601 0.042087302, + 0.059999999 0.058995701 0.038829301, + 0.0137106 0.0296595 0.091972001, + 0.0135848 0.208452 0.060607899, + 0.025251999 0.208455 0.056593299, + -0.0576833 0.045556799 0.054482002, + -0.0562139 0.208482 0.0231422, + -0.056809202 0.043281302 0.0571303, + -0.0053918599 -0.025594899 0.091733001, + -0.0195219 0.191544 -0.054582801, + -0.00616926 0.19154599 -0.057529502, + -0.0122731 0.19154499 -0.0565788, + -0.0105583 0.208545 -0.0568977, + -0.055787299 0.154062 -0.018771101, + -0.0248404 0.151315 -0.0497979, + -0.027557701 0.151072 -0.048477098, + -0.0048316298 0.208451 0.061971098, + -0.0546159 0.042392101 0.061636999, + 0.056809202 0.15967201 -0.016624101, + 0.0597114 -0.0058894102 0.0144953, + 0.059927799 -0.00295392 0.0144977, + 0.059503399 0.191504 -0.0055514099, + 0.0597024 0.20850299 -0.00380253, + 0.0599305 0.19150101 -0.00073475501, + -3.1054957e-013 -0.059994102 0.046520099, + -0.0053918599 -0.059768301 0.042021099, + -0.0053918599 -0.059768301 0.032829199, + 0.00267513 -0.059969399 0.044368599, + 0.00267513 -0.059968699 0.042065501, + 0.0059254402 -0.059718199 0.0144525, + 0.0053918599 -0.059768401 0.042021099, + 0.0053918599 -0.059770498 0.023655299, + 0.0029901101 -0.0599369 0.0144523, + 0.040171701 -0.044572901 0.0144645, + 0.038084399 -0.0463751 0.0144631, + 0.053759102 0.19152001 -0.0244925, + 0.051438902 0.191523 -0.028735099, + 0.0340195 0.208528 -0.0344765, + -0.0233503 0.208534 -0.0420467, + -0.0326031 0.208529 -0.035742301, + 0.031060301 0.20853899 -0.049168698, + 0.0465803 -0.0372428 0.0222978, + 0.059351299 -0.0088107605 0.014493, + 0.059372 0.171505 -0.0065220501, + 0.058998398 0.16525801 -0.0086359698, + 0.0572192 0.20851301 -0.0158886, + 0.057460099 0.17151199 -0.0151357, + 0.059999999 0.131263 0.0070708501, + 0.0378174 0.033742599 0.081145503, + 0.0546159 0.042390998 0.061630201, + 0.048784502 0.208471 0.037095498, + 0.0449345 0.20846701 0.041926399, + 0.0576833 0.0455558 0.054471701, + 0.0570965 0.20848399 0.020605, + 0.054897901 0.208479 0.0263779, + 0.056809202 0.0432803 0.0571201, + 0.0546159 -0.0103579 0.053968601, + 0.059999999 0.053114899 0.040647801, + 0.059999999 0.050149299 0.041415099, + 0.0109179 0.0292501 0.092552803, + 0.0075038001 0.208451 0.061694901, + 0.0013432 0.208451 0.062151, + 0.0195219 0.208453 0.058901299, + -0.0596609 0.191503 -0.0042174002, + -0.059503399 0.191504 -0.0055514099, + -0.059706699 0.17150301 -0.0037888801, + -0.0599402 0.158301 -4.3027601e-005, + -0.059757002 0.158525 -0.0027528401, + -0.059757002 0.165032 -0.0031489199, + -0.059999999 0.158079 0.00264592, + -0.059980098 0.19149999 0.00060761301, + -0.059909701 0.208501 -0.00112414, + -0.0599402 0.16491801 -0.00043966901, + -0.0599254 0.171501 -0.00085355103, + -0.059999701 0.19149899 0.00195076, + -0.058072701 0.20848601 0.0172511, + -0.058998398 0.046869598 0.049991898, + -0.058412101 0.044517301 0.052599002, + -0.055787299 0.041017801 0.059764501, + 0.0061689499 0.171546 -0.057542998, + 0.00616926 0.19154599 -0.057529502, + 0.0079039196 0.208546 -0.057311099, + -4.3848761e-012 -0.059861299 0.048670501, + 0.00267513 -0.0595599 0.050845802, + 0.0053918599 -0.0597241 0.046449501, + 0.0053918599 -0.0595893 0.048594698, + 0.0081421202 -0.059377398 0.046359401, + 0.00267513 -0.059927501 0.046502501, + 0.00267513 -0.059794199 0.048651699, + -0.0109179 -0.0557702 0.0614453, + -0.0137106 -0.0565136 0.0568606, + -1.3990485e-012 -0.059627499 0.050865602, + 1.6125718e-012 -0.0592933 0.053073999, + 0.0081421202 0.0106051 0.095154501, + 0.0053918599 0.0103511 0.095450498, + 0.00267513 0.0102021 0.095624298, + 0.0053918599 -0.0170945 0.093770199, + -0.0248404 -0.039448999 0.076345801, + -0.044564299 -0.037358802 0.044302098, + -0.029552899 0.19154 -0.050064601, + -0.0044293702 0.208546 -0.057670299, + -0.0075038001 0.19154599 -0.0573764, + -0.0479904 0.19152699 -0.0338604, + -0.048784502 0.191526 -0.032777, + -0.038280498 0.208535 -0.0440358, + -0.0358513 0.19153699 -0.045958702, + -0.0546159 0.16013201 -0.0221994, + -0.0532961 0.154737 -0.024245599, + -0.0546159 0.154402 -0.021527199, + -0.048459999 0.171527 -0.033224698, + -0.0532961 0.160357 -0.0249169, + -0.0465803 -0.037641399 0.0185632, + -0.0465803 -0.035764098 0.036713101, + -0.0109154 0.171545 -0.056847699, + -0.059431199 -0.0081526199 0.0144935, + -0.059702002 -0.0059841401 0.0144952, + -0.050219599 0.16079199 -0.0301922, + -0.051830001 0.155066 -0.026914701, + -0.051830001 0.160577 -0.0275851, + -0.050734501 0.208473 0.034197401, + 0.055787299 0.15990201 -0.0194056, + 0.059445001 -0.0081399204 0.0153528, + 0.058998398 -0.0108133 0.016260199, + 0.059999801 0.171498 0.0022789, + 0.059999999 0.164801 0.0022828199, + 0.059999701 0.208498 0.00236775, + 0.059980098 0.19149999 0.00060761301, + -0.00267513 -0.059969399 0.044369001, + 8.4062262e-012 -0.0600354 0.044384599, + -0.00267513 -0.059560802 0.050845999, + -0.0081421202 -0.058668301 0.052877299, + -0.0081421202 -0.059241898 0.048500501, + -0.0081421202 -0.059005301 0.050682101, + -0.0053918599 -0.059355501 0.0507854, + -0.0109179 -0.0585039 0.050534301, + -0.0137106 -0.0580885 0.048182599, + -0.0109179 -0.058743201 0.048363101, + -0.0053973799 0.154406 -0.055514701, + -0.00268824 0.156583 -0.056200098, + -1.4039118e-012 0.160889 -0.057054799, + 8.4928731e-012 0.15874 -0.056691598, + 0.0378174 -0.043638799 0.050233401, + 0.035361301 -0.048471499 0.0144614, + 0.035764702 -0.048187099 0.0144616, + 0.0378174 -0.046459101 0.0187515, + 0.022994 -0.055430599 0.0144559, + 0.0254349 -0.054349601 0.0094567202, + 0.036012899 -0.047997899 0.0094617801, + 0.054340299 0.171519 -0.023297399, + 0.0550595 0.208517 -0.0216762, + 0.0557741 0.171516 -0.019943999, + 0.0562139 0.191515 -0.0188237, + 0.056543902 0.171514 -0.017932899, + 0.0554916 0.171517 -0.020681901, + 0.055787299 0.16572601 -0.019805299, + 0.0532961 0.16595399 -0.025278401, + 0.0529892 0.17152099 -0.0260085, + 0.0546159 0.165841 -0.0225606, + 0.053285599 0.17151999 -0.025415801, + 0.054305699 0.171519 -0.0233759, + 0.051545098 0.171523 -0.028573399, + 0.0169627 0.191544 -0.055399802, + 0.0139775 0.208545 -0.0561832, + 0.0109552 0.19154499 -0.0568389, + 0.050219599 -0.0327783 0.0164809, + 0.051472198 -0.0308435 0.0144754, + 0.0532961 -0.0267085 0.0216635, + 0.050219599 -0.029500101 0.040276099, + 0.048467699 -0.031942099 0.042706698, + 0.050219599 -0.028054999 0.045056399, + 0.048467699 -0.029587099 0.049292602, + 0.039609101 0.191534 -0.0429154, + 0.038590301 0.191535 -0.043790799, + 0.033661801 0.19153801 -0.047515199, + 0.036173999 0.208536 -0.045703001, + 0.032825101 0.171538 -0.048071299, + 0.050219599 0.15809201 -0.029859601, + 0.050219599 0.15539201 -0.0294939, + 0.051830001 0.15782399 -0.027251, + 0.0479904 0.19152699 -0.0338604, + 0.048467699 -0.034726501 0.0221464, + 0.048467699 -0.035137899 0.0184961, + 0.0465803 -0.035581499 0.038503502, + 0.058412101 -0.012491 0.0208077, + 0.058998398 -0.0109163 0.0153658, + 0.058848299 -0.0117109 0.0144907, + 0.058203701 -0.0145829 0.0144884, + 0.058412101 -0.0093893697 0.0308806, + 0.058412101 -0.0109313 0.025878601, + 0.058998398 -0.0104582 0.017941101, + 0.0576833 -0.0107534 0.036461901, + 0.059725199 0.17150301 -0.00359985, + 0.0599402 0.164913 -0.00040559101, + 0.059934601 0.171501 -0.000663838, + 0.058412101 0.15921 -0.0110273, + 0.058998398 0.15898 -0.0082336403, + 0.0576833 0.15944199 -0.0138277, + 0.058772299 0.208508 -0.0099095702, + 0.059999999 -1.1546094e-005 0.0145, + 0.055787299 0.037462801 0.0604035, + 0.056809202 0.039804801 0.057807799, + 0.055787299 0.041016899 0.059754498, + 0.0465803 0.0282107 0.074660301, + 0.048467699 0.038023699 0.071001403, + 0.0465803 0.036169901 0.073382899, + 0.0465803 0.032198999 0.074091099, + 0.0599402 0.044689599 0.044465799, + 0.0599402 0.047736999 0.043840401, + 0.059757002 0.048418801 0.045605, + 0.0599402 0.041637398 0.044993799, + 0.0109179 0.024713 0.093340598, + 0.0081421202 0.028938301 0.092995502, + -0.058412101 -0.00493709 0.040142801, + -0.0576833 -0.00640547 0.043698601, + -0.058412101 -0.0032094701 0.042387702, + -0.0576833 -0.00217615 0.048138101, + -0.058412101 -0.00122764 0.044544999, + -0.0576833 -0.0044193701 0.045982901, + -0.0599402 0.0238805 0.0448808, + -0.059999999 0.0296189 0.043447901, + -0.059999999 0.026789701 0.042958401, + -0.059999999 0.0589967 0.03884, + -0.059999999 0.056065701 0.0398001, + -0.059999999 0.0531126 0.040665399, + -0.059999999 0.047155801 0.042107198, + -0.059999999 0.171498 0.00208897, + -0.059999999 0.050141301 0.041434798, + -0.059999999 0.164805 0.00224871, + -0.059999999 0.032496799 0.043707099, + -0.059316002 0.208491 0.0112001, + -0.0599402 0.050773598 0.043134298, + -0.0599305 0.208496 0.0050532599, + -0.058998398 0.043613002 0.050692402, + -0.0576833 0.038747601 0.055828199, + -0.058412101 0.0411832 0.053257301, + -0.0576833 0.0421593 0.055212099, + -0.056809202 0.039804898 0.0578214, + -0.055787299 0.037462901 0.0604169, + -5.6844629e-012 0.19154599 -0.0578475, + -0.0053973799 0.16730499 -0.057496399, + -0.0053966301 0.171546 -0.057610299, + 0.0081421202 -0.0592403 0.0484979, + 0.0109179 -0.058881499 0.0462308, + -0.035366699 -0.0483873 0.018803099, + -0.0255982 -0.054276899 0.0144568, + -0.0248404 -0.0541001 0.042959601, + -0.0081421202 -0.058229499 0.055075999, + -0.0165099 -0.055685598 0.056569301, + -0.0137106 -0.055861399 0.059028201, + -0.0137106 -0.055101998 0.061184201, + -0.0109179 -0.058164701 0.052719198, + -0.0137106 -0.057845701 0.050340399, + -0.0109179 -0.057723898 0.054907698, + -0.0165099 -0.057274301 0.047958001, + -0.00267513 -0.059226301 0.053052802, + -0.0053918599 -0.059020098 0.052987799, + -0.0302257 -0.049604099 0.052206799, + -0.0248404 -0.054492999 0.023338901, + -0.019305199 -0.056641702 0.032384701, + -0.0226037 -0.055586901 0.0094557405, + -0.0229061 -0.055466998 0.0144558, + 0.0053918599 0.0057322499 0.095576398, + 0.0081421202 0.0059951101 0.095284797, + 0.0220857 -0.0354519 0.081534497, + 0.0248404 -0.035991199 0.079345502, + 0.0248404 -0.034173299 0.080716498, + 0.027557701 -0.034539599 0.078447901, + 0.0302257 -0.0329272 0.077450998, + 0.0053918599 -0.0080525 0.094970502, + 0.0053918599 -0.0125952 0.094445102, + 0.0081421202 -0.0122981 0.094174303, + -0.00267513 -0.0236696 0.092531197, + 5.0043615e-012 -0.021633301 0.093128398, + 0.0109179 -0.0185485 0.0927421, + 0.0081421202 -0.0189896 0.093116097, + 0.0081421202 -0.0167896 0.093505703, + 0.0109179 -0.0163536 0.093127102, + 0.0109179 -0.0206332 0.0922997, + 0.0137106 -0.0179695 0.092251197, + 0.00267513 0.00096041098 0.0957065, + 0.00267513 0.0055779698 0.095747702, + -0.050219599 0.016818499 0.071156502, + -0.038590301 0.208462 0.0481093, + -0.0431097 0.208465 0.043897901, + -0.0424264 0.032684602 0.077864997, + -0.028376499 0.20845599 0.055031601, + -0.00267513 -0.021573501 0.093079098, + 4.239338e-012 -0.019537801 0.093581297, + -0.00267513 0.028592501 0.093486801, + -0.0053918599 -0.0234848 0.092382103, + 0.00267513 -0.034090199 0.088245697, + 0.00267513 -0.036099199 0.087077498, + -0.0248404 -0.041065902 0.074716397, + -0.044564299 -0.038342599 0.037283398, + -0.044564299 -0.0400194 0.0186163, + -0.0424264 -0.0408068 0.0378282, + -0.042958502 -0.041878 0.0144667, + -0.044560701 -0.040182602 0.014468, + -0.044408198 -0.040358901 0.0144679, + -0.044564299 -0.0401491 0.016556799, + -0.046333499 -0.038132399 0.0144696, + -0.0424264 -0.042291999 0.0186671, + -0.040174201 -0.043145798 0.038345501, + -0.0378174 -0.045351502 0.038833201, + -0.027557701 -0.041117501 0.072218999, + -0.0081428103 0.152207 -0.0546294, + -0.0281986 -0.0529682 0.0094578201, + -0.00268824 0.158732 -0.056632601, + -0.0053973799 0.156556 -0.056017499, + -0.025251999 0.191542 -0.052274801, + -0.028020401 0.20854101 -0.050889201, + -0.018242201 0.171544 -0.055007201, + -0.0182469 0.191544 -0.055005599, + -0.058689699 0.191508 -0.010318, + -0.059253901 0.208506 -0.0072666798, + -0.058983799 0.171507 -0.0087787397, + -0.059344199 0.171505 -0.00670995, + -0.059445001 0.16514701 -0.00589443, + -0.059445001 0.158751 -0.0054989201, + -0.0576833 0.15944301 -0.0138677, + -0.0583959 0.19150899 -0.0116288, + -0.057668298 0.17151099 -0.0143692, + -0.057969999 0.20851099 -0.0133093, + -0.033327099 0.208538 -0.047727, + -0.055787299 0.16573 -0.0198371, + -0.056809202 0.159674 -0.016663499, + -0.055787299 0.159905 -0.0194443, + -0.0498452 -0.033409901 0.0144734, + -0.051423199 -0.030925101 0.0144754, + -0.0502089 -0.032837301 0.0144739, + -0.0465803 -0.0342604 0.045223601, + -0.0465803 -0.033726599 0.046928499, + -0.050219599 -0.032791801 0.0164831, + -0.048467699 -0.035168398 0.0185079, + -0.048467699 -0.031957898 0.042710301, + -0.0465803 -0.0350799 0.041830398, + -0.0465803 -0.034711201 0.043521799, + -0.0532961 -0.024538999 0.034231, + -0.050219599 -0.029510399 0.0402922, + -0.048467699 -0.032341801 0.041074298, + -0.0220857 0.151531 -0.0509702, + -0.016575299 0.208544 -0.055498999, + -0.059445001 -0.0080478098 0.016234901, + -0.059337199 -0.0089049097 0.0144929, + -0.040174201 0.151912 -0.0403146, + -0.0469217 0.208528 -0.035228498, + -0.0424264 0.154064 -0.038682502, + -0.040174201 0.15437201 -0.0408215, + -0.050219599 0.15809099 -0.029892299, + -0.050219599 0.155388 -0.029522801, + -0.048467699 0.15305001 -0.031618901, + -0.059285302 -0.0092409896 0.0094926404, + -0.0546159 -0.0239226 0.021500301, + -0.056128498 -0.021171 0.0144831, + -0.055787299 -0.0220215 0.0163751, + -0.055400901 -0.023049301 0.0144817, + -0.056464098 -0.020304499 0.0144838, + -0.056793701 -0.019311599 0.0144846, + -0.056143001 -0.0211727 0.00948314, + -0.056809202 -0.0095967203 0.045007799, + -2.0778858e-013 0.028550699 0.093545802, + 0.0053918599 0.028720301 0.093304798, + 0.00267513 0.028592501 0.093486398, + -0.051830001 0.019227199 0.0688501, + -0.051830001 0.0154481 0.068868101, + -0.0546159 0.038775299 0.062374301, + -0.0532961 0.040258002 0.064245999, + -0.0546159 0.035142701 0.0629884, + -0.047172099 0.208469 0.039244201, + -0.048467699 0.038024899 0.071005099, + 0.0546159 0.154406 -0.0214958, + 0.055787299 0.15406699 -0.018739101, + 0.059682 -0.0061768098 0.0094950804, + 0.0546159 0.16013101 -0.022161501, + 0.0532961 0.154741 -0.024215, + 0.0532961 0.160355 -0.024879901, + 0.059999999 0.00056159502 0.0176936, + 0.059445001 -0.0080318796 0.016232301, + 0.059757002 -0.0053930799 0.01534, + -0.00267513 -0.0599626 0.0328568, + -2.147857e-012 -0.0600341 0.042079899, + -2.3822749e-012 -0.060020201 0.0236705, + -0.00267513 -0.059968699 0.042065501, + -0.00289505 -0.059941601 0.0144523, + -0.0053918599 -0.059590399 0.048596501, + -0.00267513 -0.059927698 0.0465036, + -0.00267513 -0.059794798 0.0486525, + -0.0081421202 -0.059437301 0.032782201, + -0.0058307201 -0.059727501 0.0144524, + -0.0137106 -0.058341801 0.032626498, + -0.0137106 -0.0582317 0.046067499, + -0.0137106 -0.0582968 0.0416958, + -0.0109179 -0.0588824 0.046235099, + -0.0145255 -0.058226701 0.0144536, + -1.0145478e-012 0.15018301 -0.054540101, + 0.00154487 -0.059987601 0.0094522396, + -0.0046305298 -0.059828501 0.0094523598, + -0.00268824 0.152298 -0.0551241, + -0.00268824 0.15017 -0.054480601, + -0.00268824 0.15443601 -0.0556974, + -0.0053973799 0.152265 -0.054941401, + -0.0053973799 0.150133 -0.054297801, + 0.0081421202 -0.0594499 0.0236359, + 0.0081421202 -0.0594269 0.041945599, + 0.0053918599 -0.0597675 0.044319801, + 0.0077038999 -0.059510902 0.0094526103, + 0.0109179 -0.058938298 0.041837599, + 0.0109179 -0.058741 0.048359599, + 0.0109179 -0.058500402 0.0505335, + 0.0053973799 0.150134 -0.054295901, + 0.00268824 0.150171 -0.0544797, + -6.0915847e-012 0.15231 -0.0551835, + 0.040174201 -0.043019101 0.040291701, + 0.0248404 -0.046675 0.067495801, + 0.035366699 -0.045778502 0.050944101, + 0.019305199 -0.0560393 0.049808301, + 0.040174201 -0.044170301 0.022715, + 0.0378174 -0.0462403 0.022839701, + 0.048467699 -0.030299 0.047655702, + 0.033358999 -0.049883101 0.0144603, + 0.0328326 -0.049977101 0.0230648, + 0.0328326 -0.050133899 0.0188345, + 0.040174201 -0.042277601 0.0457527, + 0.0378174 -0.044135898 0.048327301, + 0.0378174 -0.045241602 0.040826101, + 0.019305199 -0.056743301 0.023472499, + 0.0202484 -0.056491598 0.014455, + 0.0137106 -0.058408801 0.0190224, + 0.0197125 -0.056676898 0.0094548697, + 0.019305199 -0.056812901 0.0167228, + 0.0165099 -0.057640899 0.0235267, + 0.0165099 -0.057499502 0.041519299, + 0.0532961 -0.027563799 0.0154444, + 0.051830001 -0.030232901 0.015457, + 0.052922402 -0.0282821 0.0144775, + 0.0522171 -0.029560501 0.0094764596, + 0.054245099 -0.0256526 0.0144796, + 0.051830001 -0.0301654 0.0164546, + 0.0248404 0.153567 -0.050362401, + 0.027557701 0.151079 -0.048466899, + 0.0248404 0.15132099 -0.049788699, + 0.0220857 0.158222 -0.052470099, + 0.0109179 0.152126 -0.0541788, + 0.040169802 0.171534 -0.042422701, + 0.0424264 0.154071 -0.038661901, + 0.020382199 0.171543 -0.054295398, + 0.0227904 0.191543 -0.053350601, + 0.019903 0.208543 -0.054436799, + 0.0182469 0.191544 -0.055005599, + 0.018242801 0.171544 -0.055009302, + 0.0165099 0.169387 -0.0555133, + 0.0175901 0.171544 -0.055227101, + 0.019305199 0.169369 -0.054638799, + 0.010915 0.171545 -0.0568459, + 0.0118856 0.171545 -0.056674398, + 0.0089870598 0.171546 -0.057186499, + 0.048467699 -0.032331899 0.041058801, + 0.050219599 -0.032579601 0.0184386, + 0.050219599 -0.030086299 0.037182398, + 0.050219599 -0.0298285 0.038720999, + 0.051830001 -0.027212501 0.036491401, + 0.051830001 -0.0294479 0.021828501, + 0.048467699 -0.032642201 0.0394479, + 0.051830001 -0.029947899 0.018379301, + 0.048467699 -0.032880001 0.0378539, + 0.050219599 -0.032124501 0.021989601, + 0.055787299 -0.018552501 0.032906801, + 0.0532961 -0.0226577 0.041597299, + 0.051830001 -0.0269341 0.037973199, + 0.0546159 -0.020954801 0.036428601, + 0.051830001 -0.0261652 0.041004099, + 0.051830001 -0.025669999 0.042541299, + 0.0532961 -0.023167299 0.040120602, + 0.051830001 -0.026587 0.039471101, + 0.050219599 -0.0290945 0.041867401, + 0.050219599 -0.0286132 0.043463498, + 0.051830001 -0.021073001 0.0515838, + 0.051830001 -0.0229227 0.048627701, + 0.050219599 -0.0258979 0.0497889, + 0.050219599 -0.0250143 0.051338501, + 0.051830001 -0.0220374 0.050117601, + 0.051830001 -0.0251 0.044074599, + 0.050219599 -0.0274175 0.046643302, + 0.050219599 -0.026698999 0.048222002, + 0.042423699 0.17153201 -0.040286999, + 0.0404175 0.171534 -0.0422078, + 0.042543601 0.17153201 -0.040172201, + 0.0424264 0.16906101 -0.040251799, + 0.045200799 0.20852999 -0.0372914, + 0.0256174 0.208542 -0.052090298, + 0.040904202 0.208533 -0.0417298, + 0.0431097 0.191532 -0.039579399, + 0.044033099 0.191531 -0.038603898, + 0.0523162 0.20852201 -0.0272112, + 0.044567399 0.17152999 -0.038034901, + 0.0240207 0.171542 -0.052827802, + 0.0231252 0.171542 -0.053227901, + 0.0248338 0.171542 -0.0524645, + 0.0240272 0.191542 -0.052826501, + 0.030994801 0.17153899 -0.049237698, + 0.034754898 0.171537 -0.0467504, + 0.034765299 0.19153699 -0.046749201, + 0.033477101 0.171538 -0.047655798, + 0.035366699 0.16919 -0.046294399, + 0.038194101 0.171535 -0.044136599, + 0.035878699 0.171537 -0.045954101, + 0.048467699 0.155705 -0.032030001, + 0.048467699 0.15305699 -0.031595401, + 0.050219599 0.163486 -0.030388501, + 0.050219599 0.16079099 -0.0301574, + 0.051830001 0.160576 -0.0275492, + 0.051830001 0.16606601 -0.027946999, + 0.0464839 0.171529 -0.0358008, + 0.048460599 -0.0353733 0.0144718, + 0.048467699 -0.035318501 0.0165064, + 0.0498982 -0.033330798 0.0144735, + 0.048204001 -0.035737801 0.0144715, + 0.058412101 -0.013277 0.0180043, + 0.055787299 -0.0072418302 0.0523718, + 0.055787299 -0.0084758298 0.051236399, + 0.0532961 -0.0189909 0.048868001, + 0.055787299 -0.0107478 0.0488385, + 0.0576833 -0.0139003 0.026301, + 0.0576833 -0.0124521 0.031557899, + 0.0576833 -0.0117056 0.034039501, + 0.059757002 0.15852299 -0.0027113899, + 0.059445001 0.165142 -0.00586063, + 0.059445001 0.15875 -0.0054576802, + 0.059757002 0.16502699 -0.0031149399, + 0.059999999 -7.5646799e-006 0.0094999997, + 0.058072701 0.19151001 -0.0129326, + 0.057670102 0.17151099 -0.0143697, + 0.0576833 0.165492 -0.0142287, + 0.059999999 0.044191401 0.042664699, + 0.059999999 0.041198801 0.043152198, + 0.059999999 0.0382808 0.043536901, + 0.058998398 0.046869401 0.049977802, + 0.044564299 0.0140977 0.077661902, + 0.0465803 0.0122267 0.075551003, + 0.050219599 0.020686001 0.071037598, + 0.044564299 0.034387201 0.075673103, + 0.040608101 0.208463 0.046335898, + 0.0358513 0.20846 0.0502772, + 0.0465803 0.0202101 0.075382099, + 0.048467699 0.022342499 0.073131002, + 0.0465803 0.0242119 0.075090498, + 0.044564299 0.0181596 0.077546902, + 0.0465803 0.016212599 0.075535402, + 0.048467699 0.0184118 0.073324203, + 0.044564299 0.0222269 0.077290803, + 0.0532961 0.040256899 0.064239398, + 0.0546159 0.038774598 0.062364601, + 0.0576833 0.0152961 0.056513201, + 0.058412101 0.0150587 0.053670701, + 0.055787299 -0.00594613 0.0534584, + 0.056809202 -0.00281437 0.051787999, + 0.0576833 0.0120829 0.055763699, + 0.050219599 -0.0240491 0.052864201, + 0.050219599 -0.0151594 0.062360302, + 0.0165099 0.0256691 0.092049003, + 0.0137106 0.025139101 0.092764802, + -0.059999999 0.016562 0.0389263, + -0.059999999 0.0144051 0.037502199, + -0.0599402 0.0158724 0.041824099, + -0.058998398 -0.00175509 0.038962901, + -0.058412101 -0.0064076101 0.037848599, + -0.0576833 -0.0081266603 0.041325402, + -0.0576833 0.00030609299 0.0501264, + -0.059757002 0.018105701 0.0459144, + -0.059757002 0.0153867 0.044785202, + -0.059757002 0.020948701 0.0468181, + -0.059999999 0.021400901 0.041323502, + -0.059999999 0.0189001 0.040209301, + -0.059999999 0.0240399 0.042246401, + -0.0599402 0.0184054 0.043047599, + -0.0599402 0.021084299 0.044073299, + -0.059757002 0.0268708 0.0479008, + -0.0599402 0.0296946 0.045795899, + -0.059757002 0.0298885 0.048074201, + -0.059757002 0.023881501 0.047483001, + -0.0599402 0.026761301 0.045457698, + -0.059445001 0.027086301 0.050279599, + -0.059999999 0.044162702 0.042682301, + -0.059999999 0.041179799 0.0431646, + -0.059999999 0.038282599 0.0435468, + -0.0599402 0.032653801 0.045898098, + -0.059999999 0.0353976 0.0437387, + -0.050219599 -0.018075701 0.059930101, + -0.048467699 -0.0209294 0.061452001, + -0.058998398 0.0273802 0.052569699, + -0.055787299 0.0078012398 0.0604502, + -0.059757002 0.048416398 0.045622502, + -0.059445001 0.046027601 0.048143901, + -0.0599402 0.047729 0.0438601, + -0.056809202 0.0363153 0.058395199, + -0.055787299 0.0338961 0.0609487, + -0.0576833 0.035326201 0.056329299, + -0.056809202 0.0293175 0.059188299, + -0.056809202 0.0328178 0.058851101, + -0.056809202 0.025822099 0.059407599, + -0.055787299 0.030322799 0.061359499, + -0.0026880901 0.171546 -0.057797499, + -0.00268824 0.16943599 -0.057773702, + -0.00294237 0.171546 -0.0577912, + -1.1760328e-012 0.171546 -0.057863399, + -0.0013432 0.19154599 -0.057832502, + -0.0061684698 0.171546 -0.057539001, + -0.0058778701 0.171546 -0.057574801, + -0.0053973799 0.169433 -0.057590999, + -0.0087992204 0.171546 -0.0572147, + -0.0332799 -0.049936 0.0144602, + -0.035366699 -0.0484601 0.01664, + -0.0356883 -0.048243701 0.0144616, + -0.0302257 -0.0516329 0.023166999, + -0.028228801 -0.052956201 0.0144578, + -0.0307914 -0.051507998 0.014459, + -0.027557701 -0.053137999 0.023257401, + -0.027557701 -0.052645199 0.042610101, + -0.0328326 -0.0501546 0.0188425, + -0.0109179 -0.057179399 0.057094902, + -0.0109179 -0.056528602 0.059275899, + -0.0081421202 -0.0576864 0.057273399, + -0.0220857 -0.052108899 0.060015298, + -0.0220857 -0.051240999 0.062092099, + -0.019305199 -0.0524069 0.062570497, + -0.0165099 -0.056681201 0.052253701, + -0.0137106 -0.057503499 0.052511599, + -0.0165099 -0.057027198 0.050099101, + -0.0165099 -0.056234699 0.054412, + -0.0137106 -0.057060201 0.0546868, + -0.019305199 -0.056297999 0.0476887, + -0.0220857 -0.0553177 0.045316599, + -0.0248404 -0.054017201 0.044981301, + -0.027557701 -0.051265001 0.0527592, + -0.019305199 -0.055244699 0.054082699, + -0.019305199 -0.0532743 0.060470399, + -0.0165099 -0.055031601 0.058720302, + -0.0165099 -0.054271001 0.060859699, + -0.0248404 -0.053220101 0.051167998, + -0.0302257 -0.050924499 0.044183601, + -0.0328326 -0.0492539 0.041795202, + -0.0302257 -0.051029101 0.042221799, + -0.027557701 -0.052552 0.0446034, + -0.027557701 -0.052373402 0.046605501, + -0.0378174 -0.044151202 0.048324499, + -0.040174201 -0.041875701 0.047611099, + -0.019305199 -0.056518 0.0435404, + -0.0220857 -0.055695701 0.023411199, + -0.0220857 -0.055391502 0.043269798, + -0.019305199 -0.056452099 0.045609102, + -0.019305199 -0.056543 0.041308001, + -0.0165099 -0.0574225 0.045859098, + -0.0193005 -0.0568063 0.0144548, + -0.020158799 -0.056523599 0.014455, + -0.0167691 -0.057616498 0.00945412, + 0.0137106 -0.058230501 0.046062201, + 0.0137106 -0.058085699 0.0481783, + 0.019305199 -0.056294002 0.047682501, + 0.0165099 -0.057271 0.047952801, + 0.0328326 -0.034537401 0.073515199, + 0.0302257 -0.034662601 0.076041803, + 0.0053918599 -0.033895198 0.088108003, + 0.0053918599 0.00111985 0.095537901, + 0.0053918599 -0.00347784 0.0953357, + 0.0081421202 -0.0077637001 0.094694003, + 0.0220857 -0.025647899 0.087038599, + 0.0220857 -0.033569999 0.082832597, + 0.019305199 -0.030759901 0.085901, + 0.019305199 -0.0327379 0.084782399, + 0.0220857 -0.037279699 0.0801422, + 0.019305199 -0.038403701 0.080837302, + 0.027557701 -0.037966698 0.075489402, + 0.027557701 -0.036286298 0.077011198, + 0.0302257 -0.036332499 0.074548602, + 0.027557701 -0.039574601 0.073887497, + 0.0248404 -0.037748098 0.077883899, + 0.035366699 -0.0160504 0.0820508, + 0.0248404 -0.022393599 0.0869129, + 0.0248404 -0.024426701 0.0861279, + 0.027557701 -0.0230508 0.085101999, + 0.027557701 -0.0189995 0.086538903, + 0.027557701 -0.021032 0.085869104, + 0.0220857 -0.0316412 0.084034003, + 0.0109179 -0.028995899 0.089535698, + 0.0109179 -0.0118731 0.093787, + 0.0137106 -0.015781401 0.092630297, + 0.0137106 -0.0242217 0.090650201, + 0.0220857 -0.019477 0.089143001, + 0.0248404 -0.018294301 0.088187702, + 0.0248404 -0.020346699 0.0875993, + -0.0220857 -0.037288301 0.080151998, + -0.0248404 -0.0377586 0.077894203, + -0.0302257 -0.039466999 0.071338698, + -0.027557701 -0.039587598 0.0738969, + -0.019305199 -0.0142231 0.091275997, + -0.0465803 0.032199901 0.074096799, + -0.048467699 0.034124698 0.071743801, + -0.0465803 0.036171101 0.073386401, + -0.044564299 0.0343883 0.075676501, + -0.0424264 0.0120707 0.079708204, + -0.044564299 0.030348901 0.076359503, + -0.0465803 0.028211299 0.074668601, + -0.0424264 0.028580001 0.0785219, + -0.0053918599 0.028720301 0.093305498, + -0.0081421202 0.0289384 0.092996597, + -0.00267513 0.024028299 0.094265901, + -0.0053918599 0.0241616 0.0940862, + 0.00267513 -0.00364236 0.095501401, + 0.00267513 -0.0082221497 0.095133103, + 0.00267513 -0.032047801 0.089309402, + -1.5836136e-012 -0.032111 0.0893557, + -0.0137106 -0.030440601 0.088147499, + -0.0137106 -0.032467902 0.0871071, + -0.0109179 -0.028997401 0.089539804, + -0.0081421202 -0.027377101 0.090735599, + -0.0109179 -0.031057499 0.088593997, + -0.0081421202 -0.0252764 0.091482803, + -0.0109179 -0.0269165 0.090383098, + -0.0137106 -0.0283866 0.089084901, + -0.0165099 -0.027627099 0.088519096, + 0.0053918599 -0.029787101 0.090126298, + 0.0081421202 -0.0294616 0.089883298, + 0.0053918599 -0.0318547 0.089169197, + -0.0165099 -0.031693399 0.086562797, + -0.0165099 -0.0296735 0.087592199, + -0.019305199 -0.038411401 0.0808459, + -0.0165099 -0.0393718 0.081439398, + -0.0220857 -0.039055198 0.0786677, + -0.0137106 -0.045317698 0.077073202, + -0.0137106 -0.0468762 0.075290002, + -0.0165099 -0.046055902 0.074852601, + -0.0220857 -0.050269499 0.064141802, + 0.0137106 -0.049717199 0.0715103, + 0.0165099 -0.050168101 0.069140799, + 0.0137106 -0.0509983 0.069531702, + 0.0081421202 -0.059002601 0.050681502, + 0.0053918599 -0.059353702 0.050785001, + 0.00267513 -0.059225202 0.053052999, + -5.1159103e-012 -0.058856599 0.055285498, + 0.0053918599 -0.0590179 0.052988201, + 0.0137106 -0.0578412 0.050339401, + 0.0165099 -0.056674499 0.0522549, + 0.0165099 -0.0570218 0.050097901, + -0.00267513 -0.058789499 0.0552628, + -0.0053918599 -0.0580405 0.0573982, + -0.0053918599 -0.0585826 0.0551937, + -0.00267513 -0.058248099 0.057471398, + -0.0109179 -0.054904401 0.063595504, + -0.0053918599 -0.0573918 0.059596501, + -0.0081421202 -0.057036899 0.0594646, + -0.0081421202 -0.055413499 0.0638045, + -0.0081421202 -0.0562791 0.0616442, + -0.0424264 -0.039889 0.045047902, + -0.044564299 -0.037713099 0.042557601, + -0.044564299 -0.037983801 0.040844399, + -0.048459399 -0.035372298 0.0144718, + -0.048467699 -0.035331499 0.016508499, + -0.040174201 -0.0445484 0.016600801, + -0.040174201 -0.044449002 0.018715199, + -0.0424264 -0.042406101 0.016579401, + -0.042376 -0.042488299 0.0144662, + -0.0402418 -0.044515401 0.0144646, + -0.038010798 -0.046435501 0.014463, + -0.0378174 -0.046568699 0.0166211, + -0.0378174 -0.046483099 0.0187607, + -0.044564299 -0.036397099 0.047816198, + -0.044564299 -0.0369206 0.046057601, + -0.0424264 -0.0394627 0.0468546, + -0.0424264 -0.038949199 0.0486646, + -0.0424264 -0.0383467 0.0504729, + -0.0081428103 0.154355 -0.055202901, + -0.0081428103 0.15651099 -0.055705801, + -0.0081428103 0.16514499 -0.057024602, + -0.0053973799 0.160864 -0.056813501, + -0.0053973799 0.15871 -0.056450099, + -0.00268824 0.16088299 -0.056995802, + -0.0081428103 0.15867101 -0.056138702, + -0.027557701 0.169295 -0.051133901, + -0.0256411 0.171542 -0.0521085, + -0.0282706 0.17154001 -0.050785799, + -0.0229499 0.171542 -0.053300802, + -0.0202034 0.171543 -0.0543596, + -0.0224167 0.208543 -0.0534891, + -0.0240272 0.191542 -0.052826501, + -0.024834501 0.171542 -0.052465901, + -0.058412101 0.165379 -0.0114622, + -0.058412101 0.15921199 -0.0110678, + -0.058998398 0.15898199 -0.0082745701, + -0.058998398 0.165263 -0.0086695198, + -0.058839001 0.171508 -0.0096097104, + -0.0583813 0.171509 -0.0116414, + -0.0581921 0.17151 -0.0124812, + -0.0576833 0.16549601 -0.0142615, + -0.056669399 0.191514 -0.01756, + -0.056071501 0.208515 -0.019187801, + -0.0566587 0.171514 -0.017572399, + -0.0570965 0.191513 -0.0162865, + -0.056480099 0.171514 -0.018111801, + -0.0574052 0.17151199 -0.0153175, + -0.056809202 0.16561399 -0.0170567, + -0.039609101 0.191534 -0.0429154, + -0.030832 0.17153899 -0.049335599, + -0.0302257 0.169264 -0.049668301, + -0.0532961 0.165959 -0.0253087, + -0.053283598 0.17151999 -0.0254148, + -0.051438902 0.191523 -0.028735099, + -0.050517999 0.208524 -0.030205799, + -0.050219599 0.166179 -0.0305831, + -0.049871601 0.171525 -0.031222399, + -0.050626501 -0.0322094 0.0094743501, + -0.051817998 -0.030230399 0.0144759, + -0.0546159 -0.0247823 0.0164028, + -0.0546159 -0.0245462 0.0182702, + -0.0532961 -0.0267125 0.021668101, + -0.051830001 -0.026597699 0.039487701, + -0.048467699 -0.033082802 0.036120299, + -0.0465803 -0.035367299 0.040169001, + -0.0137073 0.171545 -0.0562611, + -0.0116994 0.171545 -0.0567117, + -0.0135848 0.19154499 -0.056289401, + -0.0109179 0.169416 -0.056833301, + -0.0081428103 0.167292 -0.057185099, + -0.0081428103 0.16942599 -0.057279401, + -0.0109179 0.16511799 -0.056578901, + -0.0109179 0.167273 -0.0567392, + -0.0137106 0.16724899 -0.0561537, + -0.0109179 0.160787 -0.056056298, + -0.0137106 0.160726 -0.055470701, + -0.0109179 0.162955 -0.056351501, + -0.0081428103 0.160832 -0.0565021, + -0.0081428103 0.162991 -0.056797199, + -0.035366699 0.15255199 -0.044220801, + -0.0378174 0.152243 -0.042332102, + -0.0302257 0.155415 -0.048090398, + -0.0302257 0.157731 -0.048525602, + -0.0328326 0.155184 -0.0464794, + -0.0328326 0.152841 -0.045973901, + -0.0302257 0.15310401 -0.047585301, + -0.0248404 0.169323 -0.052453201, + -0.0220857 0.169348 -0.053624202, + -0.0248404 0.16709 -0.052360501, + -0.0599402 -0.0025810599 0.016179901, + -0.059923101 -0.0030489999 0.0144976, + -0.059757002 -0.0052962699 0.0162073, + -0.059757002 -0.0051438198 0.0170417, + -0.059999902 -0.000106517 0.0144999, + -0.0599204 -0.0030962699 0.0094975401, + -0.048175599 0.171527 -0.033628099, + -0.048467699 0.16891199 -0.033208098, + -0.040174201 0.156835 -0.041258398, + -0.058829699 -0.0118043 0.0144906, + -0.051830001 0.0343915 0.067476302, + -0.0532961 0.0365634 0.064948604, + -0.051830001 0.0381625 0.066807598, + -0.050219599 0.036114998 0.069310598, + -0.0532961 0.032853801 0.065524802, + -0.0546159 0.0314993 0.063478597, + 0.059999999 0.00012932099 0.016150299, + 0.059999999 7.0921633e-006 0.0153147, + 0.0599402 -0.0026825599 0.0153273, + 0.0599402 -0.0025649699 0.016177399, + 0.059757002 -0.00528024 0.016204599, + -0.0165099 -0.057499401 0.0415194, + -0.0137106 -0.058285002 0.043964799, + -0.0165099 -0.057481602 0.0437718, + -0.0165099 -0.0575688 0.032516599, + -0.017363001 -0.057444301 0.0144543, + 0.0109179 -0.0590013 0.019036001, + 0.0109153 -0.058995299 0.014453, + 0.0088465102 -0.059355699 0.0144527, + 0.0081421202 -0.059423398 0.044236999, + 0.0109179 -0.058991302 0.0236081, + 0.0117463 -0.058850501 0.0144531, + 0.00268824 0.152299 -0.055123098, + 3.0981451e-013 0.15444601 -0.0557568, + -5.9543629e-012 0.156591 -0.056259301, + 0.0424264 -0.040480699 0.041473199, + 0.044564299 -0.038179599 0.039128099, + 0.019305199 -0.0478963 0.070615299, + 0.0220857 -0.0480089 0.068124004, + 0.019305199 -0.049172599 0.068672001, + 0.0165099 -0.048889101 0.071103297, + 0.0328326 -0.0482453 0.049614701, + 0.035366699 -0.046266999 0.048994999, + 0.0328326 -0.047764599 0.051603802, + 0.0220857 -0.054533001 0.0515843, + 0.019305199 -0.0556872 0.051945802, + 0.0220857 -0.054890599 0.049469799, + 0.0248404 -0.053574 0.049081799, + 0.0302257 -0.048350599 0.0562477, + 0.0302257 -0.04902 0.0542325, + 0.027557701 -0.050021801 0.0568671, + 0.0328326 -0.047188599 0.053589199, + 0.045056298 -0.039610699 0.0144685, + 0.046393901 -0.038058899 0.0144697, + 0.044564299 -0.039991301 0.018605599, + 0.0424264 -0.0419752 0.022582799, + 0.0424264 -0.0406623 0.039724998, + 0.044564299 -0.0396626 0.022443499, + 0.0465803 -0.037774902 0.0165311, + 0.0465803 -0.037611999 0.018552, + 0.040748298 -0.044036102 0.0144649, + 0.040312301 -0.044451501 0.0144646, + 0.040174201 -0.044537701 0.0165991, + 0.040174201 -0.044423599 0.0187055, + 0.0424264 -0.042265199 0.0186568, + 0.048467699 -0.030927399 0.046010699, + 0.048467699 -0.0314744 0.044360101, + 0.040174201 -0.0418594 0.047614101, + 0.040174201 -0.041353401 0.049474299, + 0.0424264 -0.033944301 0.0592882, + 0.035366699 -0.045196202 0.052889299, + 0.0378174 -0.043049902 0.0521354, + 0.0465803 -0.034696098 0.043518301, + 0.0424264 -0.039445501 0.0468577, + 0.0328326 -0.050206799 0.016656199, + 0.0302191 -0.051830001 0.0144587, + 0.030873001 -0.0514591 0.014459, + 0.0308876 -0.051446401 0.0094590401, + 0.0220857 -0.0553158 0.045308001, + 0.0220857 -0.055151898 0.0473666, + 0.0378174 -0.0445433 0.046420299, + 0.040174201 -0.0426098 0.043899301, + 0.040174201 -0.042854398 0.042086601, + 0.035366699 -0.0483649 0.018794499, + 0.0378174 -0.046558499 0.016619399, + 0.035366699 -0.0484506 0.016638501, + 0.035366699 -0.0481782 0.022956399, + 0.0328326 -0.049133699 0.043709598, + 0.035366699 -0.047322199 0.041326299, + 0.0328326 -0.049253501 0.041790701, + 0.0302257 -0.050729401 0.046143699, + 0.0137106 -0.0582969 0.041695699, + 0.0137106 -0.058284901 0.0439629, + 0.0137106 -0.058389299 0.0235718, + 0.0109179 -0.058931101 0.044118401, + 0.0165058 -0.057679798 0.0144541, + 0.0146178 -0.0582036 0.0144537, + 0.0137813 -0.058403399 0.0094534997, + 0.017454101 -0.0574167 0.0144543, + 0.0165099 -0.057672098 0.0190056, + 0.0328326 0.169227 -0.048046801, + 0.035366699 0.166831 -0.046194799, + 0.0220857 0.169347 -0.053616401, + 0.0220857 0.167138 -0.053518601, + 0.0328326 0.15284701 -0.0459604, + 0.040756401 -0.044040602 0.0094649298, + 0.0220857 0.160456 -0.052833099, + 0.0248404 0.15582 -0.050864998, + 0.027557701 0.15335099 -0.049040899, + 0.0302257 0.153111 -0.0475729, + 0.0165099 0.160652 -0.054731701, + 0.019305199 0.160561 -0.053856399, + 0.0165099 0.162846 -0.055026501, + 0.00268824 0.158733 -0.056630999, + 0.035366699 0.164461 -0.046031099, + 0.040174201 0.166667 -0.042289801, + 0.0378174 0.166751 -0.044306599, + 0.040174201 0.16910701 -0.042390101, + 0.0378174 0.169149 -0.0444065, + 0.035366699 0.15256 -0.044206299, + 0.0137069 0.171545 -0.056259599, + 0.0147556 0.171545 -0.056020699, + 0.0122713 0.171545 -0.056586601, + 0.0122731 0.19154499 -0.0565788, + 0.0137106 0.169403 -0.056242701, + 0.0137106 0.16290601 -0.055756599, + 0.0532961 -0.027491201 0.016427699, + 0.0532961 -0.0272546 0.0183187, + 0.0546159 -0.0247676 0.016400401, + 0.055787299 -0.0210901 0.0213253, + 0.051830001 -0.0244534 0.0456018, + 0.051830001 -0.023728199 0.047120601, + 0.0465803 -0.030706501 0.053673301, + 0.048467699 -0.027907999 0.052525401, + 0.044564299 -0.032430701 0.056469999, + 0.048467699 -0.028790001 0.050917801, + 0.0532961 -0.0107246 0.057891499, + 0.0546159 -0.0090489602 0.055113301, + 0.0532961 -0.0121097 0.056745801, + 0.051830001 -0.0137148 0.059549399, + 0.051830001 -0.0122541 0.060688101, + 0.0532961 -0.0169877 0.0516495, + 0.0532961 -0.018027199 0.0502735, + 0.0546159 -0.013889 0.0502536, + 0.0532961 -0.0146871 0.0542899, + 0.0546159 -0.0127807 0.051533502, + 0.0546159 -0.0116027 0.052773599, + 0.0532961 -0.015873499 0.052990202, + 0.0532961 -0.0134315 0.055543501, + 0.028437899 0.17154001 -0.050696, + 0.029552899 0.19154 -0.050064601, + 0.028376499 0.19154 -0.0507131, + 0.0302184 0.17154001 -0.049680602, + 0.0258127 0.17154101 -0.052027099, + 0.048467699 0.161 -0.032692801, + 0.048467699 0.158353 -0.0323954, + 0.0465803 0.15860599 -0.034847699, + 0.0465803 0.166384 -0.0355407, + 0.044564299 0.169012 -0.037999101, + 0.048467699 0.166281 -0.033089299, + 0.048467699 0.163644 -0.032923698, + 0.044564299 0.16394401 -0.037733201, + 0.0465803 0.16379701 -0.035375401, + 0.044564299 0.166483 -0.037898101, + 0.0424264 0.164084 -0.039986499, + 0.044564299 0.16139799 -0.0375029, + 0.0465803 0.161203 -0.035144798, + 0.0424264 0.166577 -0.040151201, + 0.047982302 0.171527 -0.03387, + 0.0465803 0.168962 -0.035642099, + 0.046578299 0.171528 -0.035679199, + 0.047172099 0.19152801 -0.034925699, + 0.050219599 0.16617499 -0.030554499, + 0.051434901 0.171523 -0.028748499, + 0.050734501 0.191524 -0.029878899, + 0.0532961 -0.020687699 0.045993399, + 0.0532961 -0.019878 0.0474393, + 0.056809202 -0.0112837 0.042507, + 0.055787299 -0.0127427 0.046305198, + 0.0546159 -0.0158881 0.0475954, + 0.058412101 -0.0085974801 0.033236701, + 0.0576833 -0.0095539102 0.038909301, + 0.0576833 -0.0080983099 0.041326098, + 0.056809202 -0.0095678195 0.0450029, + 0.056809202 -0.0155105 0.032234199, + 0.0576833 -0.0153652 0.020980701, + 0.056809202 -0.0148091 0.034841102, + 0.056809202 -0.018235199 0.0211535, + 0.055787299 -0.0178963 0.035638601, + 0.058383498 0.171509 -0.0116419, + 0.0583959 0.19150899 -0.0116288, + 0.0588759 0.171508 -0.0094234003, + 0.0582381 0.17151 -0.0122969, + 0.058412101 0.16537499 -0.011429, + 0.059999999 0.032505602 0.043684401, + 0.059999999 0.0354001 0.043723099, + 0.058998398 0.018027401 0.051582798, + 0.0546159 0.0351425 0.062975302, + 0.0599402 0.032656301 0.045882501, + 0.019305199 0.026304699 0.091190599, + 0.050219599 0.016833499 0.071139798, + 0.048467699 0.0105876 0.073307499, + 0.048467699 0.0144916 0.0733824, + 0.0424264 0.0285792 0.078516699, + 0.0424264 0.032683499 0.077861801, + 0.044564299 0.030347999 0.076353997, + 0.044564299 0.026292199 0.0768933, + 0.0424264 0.0244588 0.079027399, + 0.040174201 0.0269001 0.080569498, + 0.040174201 0.0310665 0.079939403, + 0.051830001 0.038161501 0.066801198, + 0.0532961 0.036562499 0.064939097, + 0.048467699 0.0262761 0.072802499, + 0.050219599 0.024547501 0.070803396, + 0.058998398 0.0149936 0.0507374, + 0.0546159 -0.0032484101 0.0591029, + 0.0546159 -0.0076791602 0.0562029, + 0.055787299 -0.0031829299 0.0554666, + 0.055787299 -0.00459179 0.0544912, + 0.0532961 -0.0077831601 0.059997302, + 0.0546159 -0.0047743199 0.058201399, + 0.0532961 -0.00623621 0.060949899, + 0.0532961 -0.0092808502 0.058976602, + 0.0546159 -0.0062527298 0.057233501, + 0.056809202 0.0091113402 0.057853799, + 0.051830001 -0.0177157 0.055778801, + 0.0465803 -0.029740101 0.055312499, + 0.048467699 -0.026942199 0.054108899, + 0.044564299 -0.031375699 0.058130998, + 0.050219599 -0.016636699 0.061169401, + 0.051830001 -0.0151149 0.0583486, + 0.051830001 -0.0164496 0.057089999, + 0.048467699 -0.019477099 0.062744103, + 0.050219599 -0.0180513 0.059914801, + 0.050219599 -0.0193986 0.0586011, + 0.050219599 -0.0120364 0.064535499, + 0.050219599 -0.0136243 0.063483797, + 0.050219599 -0.010401 0.065511897, + 0.051830001 -0.0091698803 0.062763497, + 0.048467699 -0.0131663 0.067280501, + 0.051830001 -0.0107375 0.061760802, + 0.048467699 0.0067017102 0.073108003, + 0.044564299 -0.0018362 0.076739803, + 0.044564299 0.0100487 0.077636696, + 0.0465803 0.0082588801 0.075430997, + 0.0465803 -0.0141191 0.069976397, + 0.0465803 -0.0013345 0.074490502, + 0.048467699 0.00113976 0.072492301, + -0.0599402 0.0135109 0.040426299, + -0.059757002 0.0082509797 0.040274799, + -0.0599402 0.0113399 0.038883101, + -0.058998398 -0.0108291 0.0162628, + -0.059445001 -0.0079036197 0.017085301, + -0.056809202 -0.012748 0.039955799, + -0.0576833 -0.0095801102 0.038903002, + -0.056809202 -0.0113116 0.0425064, + -0.056809202 -0.0139128 0.0373918, + -0.0576833 -0.0107721 0.0364662, + -0.059445001 0.0150874 0.047780201, + -0.0576833 0.0030046201 0.051911999, + -0.058998398 0.00417051 0.045017999, + -0.058412101 0.00100093 0.046576198, + -0.058412101 0.0034587299 0.048444901, + -0.059445001 0.0097292596 0.0451006, + -0.058998398 0.0066039301 0.046767399, + -0.059445001 0.0073201 0.0434696, + -0.059757002 0.0128213 0.043451399, + -0.059445001 0.0123276 0.0465459, + -0.059757002 0.0104361 0.041937798, + -0.059445001 0.00314718 0.039780099, + -0.058998398 -2.1084108e-005 0.0410797, + -0.058998398 0.0019565499 0.043110501, + -0.059445001 0.0051206201 0.041685, + -0.059445001 0.00140683 0.0377905, + -0.0532961 0.00377209 0.065118201, + -0.0546159 0.00321417 0.062017798, + -0.0546159 0.0049010902 0.062550902, + -0.055787299 0.0061422898 0.059958499, + -0.055787299 0.0045032199 0.0593917, + -0.051830001 -0.0042288899 0.065347202, + -0.0546159 0.0015481201 0.0614071, + -0.0532961 -0.00136683 0.063395202, + -0.0546159 0.0066044 0.063007198, + -0.058412101 0.031137099 0.054560699, + -0.058412101 0.0278074 0.0547769, + -0.0576833 0.031900201 0.056715101, + -0.0576833 0.0284776 0.0569859, + -0.055787299 0.0111617 0.061209701, + -0.055787299 0.0094757099 0.060867, + -0.056809202 0.012374 0.058706801, + -0.0546159 0.0083198901 0.063387103, + -0.0546159 0.0100433 0.063691698, + -0.055787299 0.012855 0.061479099, + -0.0576833 0.0152876 0.056534901, + -0.058412101 0.037838198 0.053803898, + -0.058412101 0.034486901 0.054238301, + -0.058998398 0.033790201 0.052141201, + -0.058998398 0.0305312 0.052411601, + -0.059445001 0.030151401 0.050276302, + -0.059445001 0.033237699 0.0500613, + -0.059757002 0.032892901 0.048007399, + -0.0599402 0.0355982 0.045768499, + -0.0599402 0.0446718 0.0444858, + -0.059757002 0.045297898 0.0463042, + -0.0546159 0.011768 0.063921303, + -0.0546159 0.016952399 0.064203098, + -0.0532961 0.0179825 0.066556796, + 4.6839537e-012 0.163038 -0.0573496, + 0.00268824 0.165176 -0.057516299, + 0.0060668602 0.171546 -0.057555899, + 0.0048316298 0.19154599 -0.0576526, + -0.0165099 -0.047522798 0.073012397, + -0.0248404 -0.042603299 0.073011301, + -0.0248404 -0.0466878 0.067500502, + -0.0109179 -0.053931899 0.065718099, + -0.0137106 -0.054235701 0.063321002, + -0.0165099 -0.053404301 0.062979802, + -0.0220857 -0.0548978 0.049471501, + -0.0248404 -0.0538477 0.0470125, + -0.0248404 -0.053582001 0.049083602, + -0.0220857 -0.055156399 0.047373701, + -0.0220857 -0.054542001 0.051582702, + -0.019305199 -0.056045499 0.049809799, + -0.019305199 -0.055695001 0.051944301, + -0.0220857 -0.053531501 0.055811599, + -0.0248404 -0.052200399 0.055343401, + -0.0220857 -0.052872501 0.057919301, + -0.0220857 -0.054087199 0.053697601, + -0.019305199 -0.054692499 0.056219999, + -0.0248404 -0.052760102 0.053256299, + -0.019305199 -0.054036301 0.058350999, + -0.0302257 -0.050452799 0.048161302, + -0.0302257 -0.050076202 0.0501821, + -0.027557701 -0.052099701 0.0486467, + -0.0302257 -0.0507356 0.0461534, + -0.027557701 -0.0517307 0.050701, + -0.035366699 -0.047191501 0.043220501, + -0.0378174 -0.0450962 0.042679802, + -0.035366699 -0.047322601 0.041331202, + -0.0328326 -0.049136501 0.043722302, + -0.0328326 -0.048936401 0.045656599, + -0.035366699 -0.046675801 0.047048099, + -0.035366699 -0.046281401 0.048992399, + -0.035366699 -0.046978999 0.045116302, + -0.0328326 -0.048643801 0.047628202, + -0.0328326 -0.048258699 0.049612299, + 0.019305199 -0.056517798 0.043537699, + 0.019305199 -0.056450501 0.045601599, + 0.0220857 -0.0554251 0.041060701, + 0.019305199 -0.056543101 0.0413079, + 0.0165099 -0.057481401 0.043769501, + 0.0220857 -0.055693999 0.0234093, + 0.0165099 -0.057421099 0.045852698, + 0.0220857 -0.0557568 0.018962, + 0.0220857 -0.055788402 0.016712399, + 0.0302257 -0.039452299 0.071329497, + 0.0302257 -0.037930999 0.072976097, + 0.0109179 -0.035087701 0.086386301, + 0.0081421202 -0.0335632 0.0878741, + 0.0081421202 -0.031525798 0.088930503, + 0.00267513 -0.0380673 0.085807003, + 0.0109179 -0.0027966499 0.094650298, + 0.0081421202 0.00139144 0.095250897, + 0.0081421202 -0.0031976099 0.095053703, + 0.0109179 -0.0073506301 0.094298303, + 0.0165099 0.021143001 0.092688702, + 0.0137106 0.0205917 0.093397103, + 3.4999284e-012 0.0101534 0.095681101, + 5.8993799e-012 0.0055275899 0.095803797, + -5.2965241e-012 0.0147773 0.095393099, + 0.0165099 -0.0276246 0.088512801, + 0.0137106 -0.0283846 0.0890797, + 0.0165099 -0.029670199 0.087585099, + 0.019305199 -0.0267132 0.087833203, + 0.0165099 -0.025558401 0.0893391, + 0.0137106 -0.0263106 0.0899157, + 0.019305199 -0.028749701 0.086917803, + 0.0137106 -0.032464601 0.0871007, + 0.0165099 -0.031689402 0.086555101, + 0.0137106 -0.0304379 0.088141702, + 0.0109179 -0.033087999 0.087539598, + 0.0109179 -0.0310554 0.088589303, + 0.0165099 -0.0356226 0.084189802, + 0.0137106 -0.036412001 0.084711596, + 0.0165099 -0.037521701 0.0828586, + 0.019305199 -0.034676298 0.083563998, + 0.0165099 -0.033675998 0.085422702, + 0.0137106 -0.034458499 0.0859567, + 0.019305199 -0.036567401 0.082248099, + 0.0165099 -0.0460479 0.074847497, + 0.0137106 -0.048339602 0.073430799, + 0.0165099 -0.047514498 0.073008001, + 0.0248404 -0.042591199 0.073003702, + 0.027557701 -0.041104201 0.072210602, + 0.027557701 -0.042549599 0.070463903, + 0.0220857 -0.045368701 0.071908399, + 0.019305199 -0.046525098 0.072501101, + 0.019305199 -0.045062799 0.074322, + 0.0220857 -0.0439112 0.073707901, + 0.0220857 -0.046735801 0.070044801, + 0.0248404 -0.044043001 0.0712291, + 0.0248404 -0.0454056 0.0693909, + 0.0220857 -0.040743802 0.0770882, + 0.0220857 -0.039045699 0.078658499, + 0.0248404 -0.039437901 0.076336302, + 0.0248404 -0.041054301 0.074707903, + 0.0220857 -0.0423677 0.075436197, + 0.019305199 -0.0401778 0.079334401, + 0.0378174 -0.0121445 0.081142798, + 0.0328326 -0.019843601 0.082710497, + 0.035366699 -0.018017299 0.081348799, + 0.0328326 -0.0178579 0.083436199, + 0.0328326 -0.021810699 0.0818891, + 0.0302257 -0.021522401 0.083962299, + 0.0302257 -0.0195194 0.084709696, + 0.0302257 -0.017503001 0.0853609, + 0.027557701 -0.016961901 0.087111503, + 0.027557701 -0.030873099 0.081049703, + 0.0302257 -0.0292861 0.080000699, + 0.027557701 -0.0327328 0.0797951, + 0.0248404 -0.032301798 0.081994198, + 0.0302257 -0.0311327 0.078771502, + 0.0302257 -0.025465799 0.082175903, + 0.0302257 -0.023506399 0.083117902, + 0.0302257 -0.027394701 0.081136301, + 0.027557701 -0.025050201 0.084236696, + 0.0248404 -0.0284278 0.084260002, + 0.027557701 -0.027024601 0.083272599, + 0.027557701 -0.0289679 0.082209803, + 0.0248404 -0.030384099 0.083176099, + 0.0248404 -0.02644 0.085243799, + 0.0220857 -0.029673399 0.085136399, + 0.0220857 -0.0276735 0.086137898, + 0.0248404 -0.0162571 0.088676602, + 0.019305199 -0.024656599 0.088647597, + 0.0220857 -0.0215423 0.088540703, + 0.0220857 -0.023602299 0.087839298, + 0.0165099 -0.021391099 0.090689301, + 0.0165099 -0.01932 0.091212302, + 0.019305199 -0.020508699 0.0899764, + 0.019305199 -0.0225855 0.089361899, + 0.0165099 -0.023477601 0.090064399, + 0.0137106 -0.022127001 0.091283798, + 0.0137106 -0.020047899 0.091815002, + 0.0165099 -0.0172497 0.091641001, + 0.019305199 -0.0184473 0.0904897, + 0.0220857 -0.017426901 0.089644998, + 0.0109179 -0.0269155 0.090379603, + 0.00267513 -0.021573599 0.0930788, + 0.00267513 -0.019478699 0.093530901, + 0.0053918599 -0.019297799 0.093377501, + -0.0165099 -0.0106303 0.092651702, + -0.0137106 -0.0022722499 0.094125502, + -0.0137106 -0.0068126 0.093783699, + -0.0081421202 -0.016792201 0.093507297, + -0.019305199 -0.034682602 0.0835732, + -0.019305199 -0.032743301 0.084791698, + -0.0220857 -0.035459898 0.081544802, + -0.019305199 -0.036574401 0.082257196, + -0.0165099 -0.0336807 0.0854306, + -0.027557701 -0.037978999 0.0754999, + -0.0328326 -0.036141101 0.0719864, + -0.0328326 -0.0376538 0.070371702, + -0.0302257 -0.0379452 0.072986498, + -0.0302257 -0.036346 0.074560098, + -0.0248404 -0.0142218 0.089077197, + -0.0220857 -0.0132269 0.090410799, + -0.0220857 -0.0153786 0.090057403, + -0.0248404 -0.016256399 0.088680796, + -0.019305199 -0.026716201 0.087840497, + -0.019305199 -0.024658499 0.088653803, + -0.027557701 -0.016961601 0.087117098, + -0.0220857 -0.033577099 0.082843199, + -0.035366699 -0.0356814 0.069319703, + -0.048467699 -0.022289401 0.060082901, + -0.048467699 -0.023576301 0.0586586, + -0.048467699 0.030206401 0.072346903, + -0.050219599 0.032269299 0.069946103, + -0.051830001 0.00454664 0.0680172, + -0.0532961 0.00726985 0.065874301, + -0.0532961 0.0055167298 0.065535001, + -0.048467699 -0.0148421 0.066279702, + -0.0424264 0.0100109 0.0796941, + -0.044564299 0.0100355 0.077651501, + -0.0378174 0.033744399 0.081148103, + -0.040174201 0.0310675 0.079942502, + -0.033661801 0.208459 0.0518337, + -0.035366699 0.0323718 0.083001398, + -0.0328326 0.031097701 0.084721602, + -0.048467699 0.022340599 0.0731453, + -0.048467699 0.026276199 0.072814099, + -0.050219599 0.020679399 0.071054101, + -0.0465803 0.0162064 0.075550698, + -0.048467699 0.0184054 0.073340103, + -0.044564299 0.0140918 0.077676602, + -0.0424264 0.016198101 0.079628102, + -0.0220857 -0.0088302502 0.0910099, + -0.0109179 0.0201486 0.093967699, + -0.0081421202 0.019810701 0.094401598, + -0.0081421202 0.0243886 0.093779698, + -0.0165099 0.016597001 0.0931696, + -0.0137106 0.016024601 0.093869403, + -0.0109179 0.0155641 0.094431996, + -0.00267513 0.00096032 0.095707297, + -3.409506e-012 0.00090833602 0.095761903, + -0.0053918599 -0.0034785401 0.095337503, + -0.0053918599 -0.0297879 0.090128303, + -0.0081421202 -0.0315274 0.088933997, + -0.0081421202 -0.029462799 0.089886397, + -0.0053918599 -0.027698999 0.090981998, + -0.0081421202 -0.018990099 0.093117401, + -0.0053918599 -0.0213906 0.092928, + -0.0109179 -0.0185491 0.092743903, + -0.0165099 -0.0150753 0.092015997, + -0.0137106 -0.017970299 0.092253402, + -0.019305199 -0.018446701 0.090492897, + -0.0220857 -0.0174262 0.089648701, + -0.019305199 -0.0163876 0.090912402, + -0.0165099 -0.017250599 0.091643699, + -0.0165099 -0.0213909 0.090692699, + -0.0165099 -0.019319501 0.091215096, + -0.019305199 -0.0205085 0.089980297, + -0.019305199 -0.022586299 0.089366898, + -0.0137106 -0.020047501 0.091817297, + -0.0081421202 -0.0231697 0.092128001, + -0.0081421202 -0.0210789 0.092670299, + -0.0109179 -0.0206329 0.092301503, + -0.0137106 -0.024222299 0.090653799, + -0.0165099 -0.023478299 0.090068698, + -0.0165099 -0.0255602 0.089344397, + -0.0137106 -0.0263119 0.089920104, + -0.0137106 -0.022126799 0.0912866, + -0.0109179 -0.0248206 0.0911244, + -0.0109179 -0.0227187 0.091764197, + -0.0165099 -0.035628099 0.084197603, + -0.0165099 -0.037527598 0.082866304, + -0.0109179 -0.0350908 0.086391598, + -0.0137106 -0.034462299 0.085963301, + -0.0109179 -0.033090599 0.087544702, + -0.0137106 -0.0364164 0.084718198, + -0.00267513 -0.0436491 0.081408001, + -0.00267513 -0.039987601 0.084437899, + -0.00267513 -0.0418505 0.082970098, + -6.4729524e-012 -0.0381325 0.085850403, + -0.0109179 -0.037050299 0.085136697, + -0.0137106 -0.0383224 0.083374299, + -0.0137106 -0.0401727 0.081933998, + -0.0081421202 -0.046473801 0.077714004, + -0.0053918599 -0.046822801 0.077907398, + -0.0053918599 -0.045173399 0.079639502, + -0.0109179 -0.045974001 0.077436998, + -0.0109179 -0.047535699 0.075641803, + 0.0137106 -0.053256501 0.065428697, + 0.0137106 -0.052179199 0.067501999, + 0.0109179 -0.0516661 0.069846198, + 0.0137106 -0.045311201 0.0770685, + 0.0137106 -0.046869598 0.0752858, + 0.0109179 -0.054898798 0.063594498, + 0.00267513 -0.0539244 0.068287797, + 0.00267513 -0.052740101 0.070351698, + 0.0109179 -0.0490034 0.073770903, + 0.0109179 -0.050383199 0.071837701, + 0.00267513 -0.058246799 0.057471599, + 0.00267513 -0.0587883 0.055263098, + -5.3131557e-012 -0.058315501 0.057495501, + 6.8563193e-012 -0.056910399 0.061891299, + -0.00267513 -0.057599802 0.059673801, + 6.9278363e-012 -0.057667401 0.0596992, + 0.00267513 -0.0568415 0.0618646, + 0.00267513 -0.057598501 0.059673999, + 2.3720023e-012 -0.053993199 0.068318702, + -0.0081421202 -0.048038099 0.0759096, + -0.0053918599 -0.048388898 0.076096602, + -0.00267513 -0.050071999 0.074318603, + -4.7565667e-012 -0.050138898 0.074352898, + -1.0726531e-012 -0.048661198 0.076241799, + -0.00267513 -0.048594501 0.0762062, + -0.048467699 -0.0288142 0.050919902, + -0.050219599 -0.025923001 0.049791101, + -0.051830001 -0.022063799 0.0501219, + -0.050219599 -0.0250398 0.0513428, + -0.051830001 -0.022948699 0.048629899, + -0.0546159 -0.0190208 0.042040601, + -0.0546159 -0.017618001 0.044844899, + -0.0532961 -0.020713899 0.045992799, + -0.0546159 -0.0183565 0.043446399, + -0.0546159 -0.0168043 0.046231199, + -0.055787299 -0.0144795 0.0436811, + -0.0532961 -0.019904699 0.047441602, + -0.055787299 -0.015899001 0.041003101, + -0.056809202 -0.0076064202 0.047418799, + -0.056809202 -0.0053485902 0.049697701, + -0.056809202 -0.0028419399 0.051805299, + -0.055787299 -0.0127711 0.046309799, + -0.0532961 -0.019018 0.048872501, + -0.0546159 -0.0149533 0.048945401, + -0.0546159 -0.0159159 0.047599901, + -0.051830001 -0.020057 0.053027999, + -0.0532961 -0.0170152 0.051657699, + -0.0532961 -0.018054601 0.0502798, + -0.051830001 -0.0210997 0.051589999, + -0.050219599 -0.021903399 0.0558272, + -0.051830001 -0.017742099 0.055790499, + -0.051830001 -0.016475501 0.057103701, + -0.051830001 -0.0189369 0.05443, + -0.050219599 -0.020700499 0.0572448, + -0.050219599 -0.0194236 0.058614299, + -0.040174201 -0.042617999 0.043912102, + -0.0424264 -0.040229499 0.043252502, + -0.040174201 -0.042290699 0.045755599, + -0.0378174 -0.0448705 0.044534098, + -0.040174201 -0.0428578 0.0421023, + -0.0424264 -0.040484399 0.041489702, + -0.0378174 -0.044555601 0.046423201, + -0.047033701 -0.037237499 0.0144704, + -0.046574499 -0.0378244 0.0144699, + -0.0465803 -0.0377874 0.016533099, + -0.048147298 -0.0358142 0.0144715, + -0.047047202 -0.037244201 0.0094703501, + -0.0302257 -0.042257499 0.0678427, + -0.0302257 -0.0409058 0.069621801, + -0.027557701 -0.043920901 0.068660296, + -0.027557701 -0.042563301 0.070471197, + -0.0248404 -0.0489331 0.0635667, + -0.0248404 -0.047860499 0.065554798, + -0.027557701 -0.0474273 0.0629187, + -0.0248404 -0.049904201 0.061543599, + -0.027557701 -0.048397999 0.060925599, + -0.027557701 -0.050035302 0.056866799, + -0.027557701 -0.050700601 0.054816101, + -0.027557701 -0.049267702 0.058905698, + -0.0248404 -0.0515384 0.0574244, + -0.0248404 -0.050772998 0.059493601, + -0.040174201 -0.040776599 0.051327001, + -0.040174201 -0.041371599 0.049469899, + -0.0378174 -0.043655999 0.0502293, + -0.0220857 0.164919 -0.053371102, + -0.019305199 0.16498201 -0.0543922, + -0.0220857 0.16713899 -0.053531099, + -0.034765299 0.19153699 -0.046749201, + -0.034755301 0.171537 -0.046750899, + -0.033319298 0.171538 -0.0477616, + -0.0328326 0.169229 -0.048058402, + -0.0353618 0.171537 -0.046324, + -0.035726301 0.171537 -0.046067402, + -0.054602101 0.171518 -0.0226977, + -0.055419099 0.171517 -0.020857399, + -0.0546159 0.16584501 -0.0225916, + -0.054342099 0.19151901 -0.023282399, + -0.054897901 0.19151799 -0.0220594, + -0.053578701 0.20852 -0.0248399, + -0.0542247 0.171519 -0.0235477, + -0.051818501 0.17152201 -0.028082499, + -0.0528998 0.17152099 -0.026176101, + -0.0521175 0.191522 -0.0275758, + -0.0514476 0.171523 -0.028736399, + -0.051830001 0.16607 -0.0279765, + -0.0528774 -0.028365999 0.0144774, + -0.051830001 -0.0269386 0.037993401, + -0.051830001 -0.030179201 0.0164569, + -0.0532961 -0.027288301 0.0183316, + -0.051830001 -0.027458001 0.034876399, + -0.0546159 -0.021565899 0.033573501, + -0.0532961 -0.023976499 0.0372287, + -0.0532961 -0.0236167 0.038664401, + -0.019305199 0.151719 -0.0519927, + -0.0429691 -0.041884098 0.00946665, + -0.0109179 0.15861601 -0.055692598, + -0.0165099 0.156257 -0.0539448, + -0.019305199 0.15392201 -0.0525668, + -0.0165099 0.158453 -0.054378301, + -0.0137106 0.158544 -0.0551068, + -0.0165099 0.169388 -0.0555191, + -0.019305199 0.167181 -0.054552302, + -0.019305199 0.16937 -0.054645501, + -0.0165099 0.167218 -0.0554257, + -0.017408401 0.171544 -0.0552825, + -0.016505901 0.171544 -0.055532102, + -0.0145714 0.171545 -0.056067102, + -0.0137106 0.169404 -0.056247499, + -0.0165099 0.162846 -0.055037901, + -0.0165099 0.160651 -0.0547425, + -0.0137106 0.16290601 -0.055766098, + -0.0137106 0.16508199 -0.055993602, + -0.0165099 0.16503599 -0.055265501, + -0.035366699 0.157316 -0.0451627, + -0.035366699 0.15493301 -0.0447267, + -0.0328326 0.15753201 -0.046914998, + -0.0328326 0.15988199 -0.047281001, + -0.035366699 0.159701 -0.045529202, + -0.0378174 0.157083 -0.043274902, + -0.0378174 0.154661 -0.0428386, + -0.0424264 0.164087 -0.040015001, + -0.019305199 0.160561 -0.053869002, + -0.019305199 0.162774 -0.0541646, + -0.019305199 0.156131 -0.053070702, + -0.019305199 0.158346 -0.053504501, + -0.0220857 0.153754 -0.051544599, + -0.027557701 0.16248301 -0.050653402, + -0.0302257 0.16004799 -0.048891298, + -0.0248404 0.164846 -0.0522005, + -0.027557701 0.164764 -0.050881401, + -0.0302257 0.16236199 -0.049187899, + -0.027557701 0.167035 -0.051041398, + -0.0576833 -0.0153695 0.0209856, + -0.044561401 0.17152999 -0.038035098, + -0.0463636 0.171529 -0.0359478, + -0.044440001 0.17152999 -0.038175698, + -0.0449345 0.19153 -0.037607901, + -0.044564299 0.15374 -0.0364291, + -0.0465803 0.153402 -0.034071099, + -0.0465803 0.15860499 -0.034878101, + -0.044564299 0.16139901 -0.037533801, + -0.0465803 0.156003 -0.034509499, + -0.048467699 0.158352 -0.032427002, + -0.048467699 0.155701 -0.0320579, + -0.0424264 0.156571 -0.039119899, + -0.044564299 0.158847 -0.0372352, + -0.044564299 0.156293 -0.036867, + -0.0424264 0.161586 -0.039785899, + -0.0424264 0.159079 -0.0394876, + -0.058021698 -0.0152879 0.0094878301, + -0.055787299 -0.0210943 0.0213301, + -0.055787299 -0.0217661 0.018208001, + 0.00267513 0.019436 0.094882399, + 0.00267513 0.024028201 0.094265699, + 8.6627918e-012 0.023984799 0.094324499, + -8.5977466e-012 0.0193907 0.0949407, + 0.00267513 0.0148243 0.095335498, + 0.0053918599 0.0149681 0.095159501, + 0.0081421202 0.0198105 0.094401002, + 0.0053918599 0.019574501 0.0947043, + 0.0081421202 0.0152132 0.094859697, + 0.0109179 0.0201483 0.093966901, + 0.0081421202 0.0243882 0.093779303, + 0.0053918599 0.0241614 0.094085798, + -0.051830001 0.0268136 0.068424098, + -0.051830001 0.0230186 0.068702497, + -0.0532961 0.029135101 0.065973997, + -0.051830001 0.030606501 0.0680153, + -0.050219599 0.024545399 0.070818096, + -0.050219599 0.0284108 0.0704486, + -0.0081421202 -0.059378099 0.046362601, + -0.0107568 -0.059035402 0.0094529903, + -0.0081421202 -0.059426799 0.041945599, + -0.0053918599 -0.0597676 0.044320501, + -0.00875236 -0.059369698 0.0144527, + -0.0053918599 -0.059724499 0.046451598, + 0.0053973799 0.15440699 -0.055512499, + 0.00268824 0.15443701 -0.055696301, + 0.0053973799 0.152266 -0.0549394, + 0.00268824 0.156583 -0.056198701, + 0.0081428103 0.152209 -0.054626402, + 0.0302257 -0.050443001 0.048159, + 0.027557701 -0.0520906 0.048644599, + 0.0248404 -0.053210001 0.051169898, + 0.027557701 -0.0492539 0.058904499, + 0.019305199 -0.055236001 0.0540848, + 0.044472098 -0.0402884 0.0144679, + 0.0424264 -0.042394701 0.016577501, + 0.042443302 -0.042420998 0.0144662, + 0.044562198 -0.040183902 0.014468, + 0.044564299 -0.040137202 0.016554801, + 0.040174201 -0.040757399 0.051330101, + 0.044564299 -0.036376901 0.047821, + 0.0465803 -0.033705398 0.046933599, + 0.044564299 -0.036902498 0.046060901, + 0.0424264 -0.038929999 0.0486692, + 0.0465803 -0.034241501 0.045227099, + 0.0424264 -0.038326401 0.050476, + 0.040174201 -0.035231698 0.062106799, + 0.035366699 -0.0418997 0.060543701, + 0.027557701 -0.046342202 0.064872898, + 0.0302257 -0.040890701 0.069613896, + 0.044564299 -0.037703902 0.0425434, + 0.044564299 -0.0373444 0.044298802, + 0.0465803 -0.035070401 0.041815501, + 0.0465803 -0.035363302 0.040151, + 0.044564299 -0.037980001 0.040827099, + 0.0424264 -0.0402207 0.043239001, + 0.0424264 -0.039875299 0.045044702, + 0.0302257 -0.050921801 0.044171799, + 0.027557701 -0.052367698 0.046596698, + 0.0248404 -0.0538426 0.047004499, + 0.0283127 -0.0529113 0.0144579, + 0.0275514 -0.053295098 0.0144576, + 0.025684301 -0.0542362 0.0144568, + 0.0248404 -0.054613899 0.016700599, + 0.0248404 -0.054573599 0.018935001, + 0.035366699 -0.046971802 0.045104999, + 0.0378174 -0.044862699 0.044521999, + 0.035366699 -0.046664398 0.047045499, + 0.035366699 -0.047188502 0.043206699, + 0.0328326 -0.048929699 0.045646202, + 0.0378174 -0.045092899 0.042665102, + 0.0328326 -0.048633099 0.047625698, + 0.0328326 0.15518899 -0.0464634, + 0.035366699 0.154938 -0.0447095, + 0.019305199 0.16497999 -0.054379102, + 0.0220857 0.162689 -0.053128101, + 0.019305199 0.162773 -0.0541512, + 0.0220857 0.16491801 -0.0533562, + 0.019305199 0.16718 -0.054541301, + 0.0165099 0.16503499 -0.0552544, + 0.0165099 0.167217 -0.055416301, + 0.019305199 0.151724 -0.051985499, + 0.0220857 0.151537 -0.050961901, + 0.045067899 -0.0396166 0.0094684605, + 0.048901699 -0.034772899 0.0094723096, + 0.019305199 0.15613399 -0.053061299, + 0.0220857 0.153758 -0.051535599, + 0.0220857 0.15598699 -0.052037999, + 0.019305199 0.153926 -0.052558899, + 0.019305199 0.15834799 -0.053493399, + 0.0248404 0.158077 -0.051297199, + 0.027557701 0.15563001 -0.049543601, + 0.0302257 0.15542001 -0.048075799, + 0.0137106 0.15418801 -0.0541646, + 0.0165099 0.15406901 -0.053434402, + 0.0165099 0.151885 -0.052861199, + 0.0137106 0.15201899 -0.0535914, + 0.0137106 0.158545 -0.055098999, + 0.0165099 0.158455 -0.054368801, + 0.0137106 0.160726 -0.055461802, + 0.0137106 0.15636501 -0.054666899, + 0.0165099 0.15626 -0.053936802, + 0.00268824 0.16088299 -0.056994099, + 0.00268824 0.16303299 -0.0572889, + 0.0053973799 0.15655699 -0.056014899, + 0.0081428103 0.154357 -0.0551995, + 0.0109179 0.154284 -0.054752, + 0.040174201 0.151921 -0.040298101, + 0.040174201 0.154378 -0.040801998, + 0.0378174 0.154667 -0.0428202, + 0.0378174 0.15225101 -0.042316601, + 0.058731299 -0.0122807 0.0094902199, + 0.0137106 0.167248 -0.056145899, + 0.0109179 0.169416 -0.0568294, + 0.0137106 0.16508099 -0.0559843, + 0.055437401 -0.0229614 0.0144817, + 0.054979 -0.0240348 0.0094808601, + 0.0546159 -0.0248453 0.0154314, + 0.0546159 -0.0239185 0.021495599, + 0.055787299 -0.0217309 0.0181944, + 0.0546159 -0.0245116 0.018257, + 0.0546159 -0.0215664 0.0335733, + 0.0532961 -0.0239718 0.037207901, + 0.0532961 -0.0245394 0.034230798, + 0.044564299 0.156297 -0.0368414, + 0.044564299 0.158848 -0.037206098, + 0.0465803 0.15600701 -0.034482699, + 0.0465803 0.153409 -0.034048501, + 0.044564299 0.15374701 -0.036407501, + 0.0424264 0.156574 -0.039095499, + 0.0484627 0.171527 -0.033226699, + 0.048467699 0.168909 -0.033190999, + 0.048288502 0.171527 -0.033475399, + 0.049977001 0.171525 -0.0310644, + 0.049018301 0.208526 -0.032434698, + 0.056809202 -0.019307701 0.0154053, + 0.057419099 -0.017419901 0.0144861, + 0.057158101 -0.0182545 0.0094854701, + 0.056496199 -0.0202149 0.0144839, + 0.055787299 -0.022089399 0.0154184, + 0.055787299 -0.022006501 0.016372601, + 0.0576833 -0.016418001 0.0163165, + 0.056809202 -0.0192197 0.016344599, + 0.0576833 -0.016511099 0.0153922, + 0.0576833 -0.0161027 0.0180679, + 0.058412101 -0.0136123 0.016288299, + 0.056809202 -0.0189243 0.018131301, + 0.058412101 -0.0137104 0.015379, + 0.0546159 -0.0201139 0.039220698, + 0.0532961 -0.0214199 0.044535998, + 0.0532961 -0.022075901 0.043069798, + 0.058998398 -0.0063338899 0.030205, + 0.058998398 -0.0079693701 0.0254572, + 0.059445001 -0.0076571498 0.0178781, + 0.058998398 -0.0096236104 0.0206351, + 0.056809202 -0.0075771199 0.047410101, + 0.056809202 -0.0053197402 0.049684901, + 0.0576833 -0.0063760998 0.043693699, + 0.0576833 -0.0043896101 0.045974098, + 0.058412101 0.00103064 0.046562999, + 0.058412101 -0.00119748 0.044536099, + 0.0576833 -0.0021468401 0.048125099, + 0.0576833 0.00033409201 0.050108802, + 0.058998398 0.00198701 0.043101501, + 0.059999999 0.0560655 0.039785799, + 0.059999999 0.099369697 0.018683, + 0.059445001 0.0051513002 0.041675899, + 0.058412101 0.021405799 0.0547367, + 0.0576833 0.0185485 0.056985501, + 0.058412101 0.018214099 0.0543379, + 0.0576833 0.021794399 0.0571816, + 0.058998398 0.021125199 0.052167799, + 0.056809202 0.032825399 0.0588325, + 0.055787299 0.0303303 0.061341099, + 0.056809202 0.036317602 0.0583786, + 0.055787299 0.033898398 0.060932402, + 0.0532961 0.0291372 0.065958299, + 0.0546159 0.031501502 0.063462503, + 0.0532961 0.0328537 0.065512098, + 0.051830001 0.026815699 0.068408899, + 0.058412101 0.041185498 0.053240102, + 0.058412101 0.0445171 0.052584998, + 0.0576833 0.0421593 0.055198301, + 0.0576833 0.0387499 0.0558112, + 0.0576833 0.035333801 0.056310501, + 0.058412101 0.037845898 0.053784799, + 0.0576833 0.031917501 0.056695901, + 0.059757002 0.039063498 0.0473409, + 0.0599402 0.0355964 0.045758601, + 0.0599402 0.0385768 0.045428999, + 0.0328326 0.0181148 0.086411797, + 0.035366699 0.032370199 0.082998902, + 0.0378174 0.0295415 0.081898503, + 0.019305199 0.0218042 0.091839202, + 0.055787299 0.0196566 0.061858501, + 0.056809202 0.019003 0.059491701, + 0.050219599 0.032268502 0.069937102, + 0.051830001 0.034390699 0.067466997, + 0.051830001 0.030606501 0.068002902, + 0.050219599 0.0284106 0.070436597, + 0.050219599 0.036114 0.069304504, + 0.048467699 0.0302056 0.072338201, + 0.048467699 0.0341237 0.071737804, + 0.051830001 -0.0059024398 0.064546198, + 0.0532961 -0.0046449401 0.0618308, + 0.051830001 -0.0075562699 0.063692696, + 0.051830001 -0.0042143101 0.065322302, + 0.056809202 0.00283767 0.0553407, + 0.055787299 -0.000219522 0.057230499, + 0.056809202 0.0059164301 0.056735702, + 0.056809202 -8.4463907e-005 0.053683002, + 0.055787299 -0.00172404 0.056380801, + 0.0576833 0.0030304899 0.051890001, + 0.0546159 -7.4055992e-005 0.060694501, + 0.055787299 0.0029072801 0.058724299, + 0.055787299 0.001326 0.058012299, + 0.0546159 -0.00167987 0.059934601, + 0.0532961 -0.00301491 0.062637903, + 0.0532961 -0.00135182 0.063369602, + 0.055787299 0.0061555901 0.059932701, + 0.0546159 0.00156349 0.061381001, + 0.0532961 0.0020506999 0.064600296, + 0.0546159 0.0049116998 0.062527597, + 0.0532961 0.00033854501 0.064024203, + 0.0546159 0.0032271901 0.0619925, + 0.0424264 -0.032798 0.060960699, + 0.040174201 -0.033992998 0.063780703, + 0.040174201 -0.0326703 0.065401599, + 0.0424264 -0.031565901 0.0625875, + 0.0424264 -0.0302517 0.064162299, + 0.050219599 -0.020675 0.057233602, + 0.051830001 -0.018910199 0.0544204, + 0.051830001 -0.0200302 0.053020202, + 0.0465803 -0.023666499 0.062909797, + 0.048467699 -0.020905901 0.061437398, + 0.0465803 -0.022223899 0.064267099, + 0.044564299 -0.026321299 0.064325698, + 0.048467699 -0.0222652 0.060070001, + 0.044564299 -0.0248654 0.065731697, + 0.048467699 -0.014823 0.0662582, + 0.0465803 -0.015840599 0.068990797, + 0.044564299 -0.0184124 0.070635699, + 0.040174201 -0.0139481 0.078314804, + 0.0378174 -0.0160497 0.079881698, + 0.0378174 -0.0141033 0.080558501, + 0.040174201 -0.0120233 0.0789643, + 0.044564299 -0.016669899 0.071662098, + 0.0465803 0.00236828 0.075012699, + 0.044564299 4.1022999e-005 0.0769853, + 0.0465803 0.00051716599 0.074791901, + 0.0465803 0.0043111001 0.075183697, + 0.048467699 0.0047883401 0.072961502, + 0.048467699 0.00296437 0.072766401, + 0.0424264 0.00387902 0.079424702, + 0.044564299 0.0060192998 0.077473097, + 0.0424264 -0.000184955 0.079087898, + 0.044564299 0.0020121201 0.077179998, + 0.0424264 0.0079672299 0.079629898, + 0.040174201 0.0227185 0.081053101, + 0.0424264 0.0203298 0.079393499, + 0.035366699 -0.0101179 0.083594702, + 0.0424264 -0.0021830699 0.078870401, + 0.040174201 -0.0100867 0.079523198, + 0.0378174 -0.0101815 0.081635296, + 0.0378174 -0.00823317 0.0820347, + 0.0424264 -0.0098176897 0.077273898, + 0.0424264 -0.0117194 0.076653302, + 0.044564299 -0.0093716597 0.0749029, + 0.044564299 -0.0112333 0.074224897, + 0.0465803 -0.0032001201 0.074102797, + 0.044564299 -0.0074941101 0.075493097, + 0.050219599 8.0006292e-005 0.069688499, + 0.048467699 -0.000698674 0.072133899, + 0.050219599 0.00188797 0.070097998, + 0.051830001 0.00099882297 0.067171499, + 0.051830001 -0.00075841398 0.066635601, + 0.051830001 -0.0024977301 0.0660192, + 0.048467699 -0.0043602898 0.071166702, + 0.050219599 -0.0017186099 0.069197297, + 0.048467699 -0.00253442 0.071692102, + 0.0465803 -0.0069149402 0.073071301, + 0.050219599 -0.0035032299 0.068624198, + 0.0465803 -0.0050627501 0.073629797, + -0.059999999 0.000113206 0.016153, + -0.059757002 0.0045350399 0.036630701, + -0.059757002 0.0062816702 0.0384943, + -0.059999999 0.0106851 0.034350399, + -0.0599402 0.0093747796 0.0372256, + -0.059999999 0.0124441 0.035966601, + -0.059999999 0.0091309603 0.032684799, + -0.0599402 0.00762195 0.035486199, + -0.0599402 0.00475732 0.031889301, + -0.0599402 0.00608422 0.0336973, + -0.059757002 0.00301386 0.034717601, + -0.058412101 -0.0124954 0.0208127, + -0.058412101 -0.013314 0.018018501, + -0.0576833 -0.0117106 0.034061901, + -0.0576833 -0.0124516 0.0315581, + -0.058998398 -0.0104954 0.017955299, + -0.058412101 -0.0093888799 0.0308808, + -0.058412101 -0.0076269298 0.035539199, + -0.059445001 -0.0067788102 0.020468701, + -0.056809202 0.0090977997 0.0578801, + -0.050219599 -0.0136455 0.063504599, + -0.051830001 -0.0091903498 0.062786497, + -0.050219599 -0.0120562 0.064557798, + -0.050219599 -0.0104191 0.065535299, + -0.0532961 0.0020403401 0.064623103, + -0.0532961 0.00032583001 0.064048901, + -0.055787299 0.00130587 0.058038399, + -0.056809202 0.0058981301 0.056763001, + -0.055787299 0.00288929 0.058750998, + -0.0546159 -9.168579e-005 0.0607206, + -0.048467699 -0.0180053 0.064004503, + -0.048467699 -0.016450999 0.065178797, + -0.050219599 -0.0151819 0.062379401, + -0.050219599 -0.0166602 0.0611866, + -0.048467699 -0.019499799 0.0627608, + -0.0465803 -0.020735599 0.065575898, + -0.0465803 -0.019164 0.066798002, + -0.059445001 0.0179777 0.048781302, + -0.058412101 0.0245915 0.054877698, + -0.0576833 0.025077101 0.057147801, + -0.0599402 0.041608799 0.045011301, + -0.0599402 0.038557801 0.0454414, + -0.059757002 0.035915501 0.047736, + -0.0532961 0.0124966 0.066434197, + -0.0546159 0.0134774 0.0640755, + -0.0532961 0.0143022 0.066504396, + -0.0532961 0.0107639 0.066321097, + -0.051830001 0.0063308901 0.068311498, + -0.0532961 0.00902458 0.066136502, + -0.0546159 0.024203099 0.064085603, + -0.055787299 0.023180701 0.061816402, + -0.055787299 0.0267483 0.061648302, + -0.0546159 0.0205639 0.0642028, + -0.0546159 0.027851 0.063844502, + -0.0532961 0.021692401 0.0664896, + -0.0532961 0.025412699 0.066295803, + -0.00268824 0.16303299 -0.057290699, + -0.0053973799 0.16516501 -0.057335801, + -0.0053973799 0.163018 -0.057108499, + 8.4271834e-012 0.16731501 -0.057737801, + 5.1695421e-013 0.16518 -0.057576999, + 0.00268824 0.167312 -0.057677299, + 2.9020408e-012 0.16943701 -0.057833001, + -0.00268824 0.167312 -0.0576788, + -0.00268824 0.165177 -0.057518099, + 0.0026879699 0.171546 -0.0577945, + 0.00268824 0.16943599 -0.0577727, + 0.000344617 0.171546 -0.057862401, + 0.0031320599 0.171546 -0.057781599, + 0.0017465299 0.208546 -0.0578086, + -0.019305199 -0.047906101 0.070619702, + -0.0220857 -0.0480203 0.068128102, + -0.0220857 -0.049195498 0.066156298, + -0.019305199 -0.051435299 0.064643502, + -0.0137106 -0.0483464 0.073434398, + -0.0109179 -0.049008802 0.073773801, + -0.0220857 -0.045379698 0.0719143, + -0.0248404 -0.044055399 0.071235701, + -0.0248404 -0.045418199 0.069396503, + -0.0220857 -0.046746999 0.0700498, + -0.019305199 -0.046534698 0.072506197, + 0.0328326 -0.032878902 0.0749771, + 0.0328326 -0.0311561 0.076355897, + 0.035366699 -0.032584701 0.0723911, + 0.0053918599 -0.039786302 0.0843082, + 0.0137106 0.0022901699 0.094301596, + 0.0109179 0.00178007 0.094840303, + 0.0109179 0.0063712699 0.094867498, + 0.0137106 -0.0022704201 0.094121002, + 0.0137106 0.0114458 0.094175398, + 0.0137106 0.016024301 0.093867697, + 0.0109179 0.0155639 0.0944307, + 0.0109179 0.0109687 0.094731197, + 0.0137106 0.0068650199 0.094319902, + -0.00267513 0.0102021 0.0956247, + -0.00267513 0.0055780001 0.095748402, + -0.0053918599 0.0149682 0.095160097, + -0.0081421202 0.0152134 0.094860703, + -0.0053918599 0.019574599 0.094704702, + -0.00267513 0.0194361 0.0948826, + -0.00267513 0.0148243 0.095335796, + 0.0165099 -0.044493701 0.076615199, + 0.019305199 -0.0418831 0.077744097, + 0.019305199 -0.043513499 0.076071598, + 0.0165099 -0.042857699 0.078305297, + 0.0328326 -0.0138559 0.084602803, + 0.035366699 -0.0120871 0.083174303, + 0.0328326 -0.0118672 0.085042797, + 0.0302257 -0.0154817 0.085915998, + 0.0328326 -0.0158592 0.084066898, + 0.035366699 -0.014071 0.082659297, + 0.035366699 -0.0081489496 0.083926901, + 0.0328326 -0.0098789698 0.085393399, + 0.0165099 -0.00161617 0.093462899, + 0.0165099 -0.0061345799 0.093133703, + 0.0137106 -0.0113155 0.093278699, + 0.0137106 -0.0068085399 0.093779199, + 0.027557701 -0.0129171 0.087968402, + 0.027557701 -0.0107892 0.088295698, + 0.0302257 -0.0114693 0.086741298, + 0.0302257 -0.0134754 0.086373903, + 0.027557701 -0.0149392 0.087585703, + 0.0248404 -0.0142204 0.089073204, + 0.0248404 -0.0120768 0.089413799, + -4.9907669e-012 -0.02373 0.092579603, + -0.00267513 -0.0257817 0.091879897, + 0.0053918599 -0.0255946 0.0917316, + 0.00267513 -0.0257816 0.091879196, + 0.0053918599 -0.027698399 0.090980299, + 0.00267513 -0.023669699 0.092530698, + 0.0081421202 -0.0273763 0.090732999, + 0.019305199 -0.014217 0.091271996, + 0.019305199 -0.016386401 0.090909302, + 0.0165099 -0.01507 0.092012599, + 0.0165099 -0.0106224 0.092646897, + 0.0220857 -0.0132199 0.090406202, + 0.0220857 -0.0153772 0.090053797, + 0.0081421202 -0.0231697 0.092126399, + 0.0081421202 -0.0252761 0.091480598, + 0.0053918599 -0.0234848 0.092381001, + 0.0053918599 -0.021390701 0.092927098, + 0.0081421202 -0.021079199 0.092668898, + 0.0109179 -0.022718901 0.091761902, + 0.0109179 -0.024820101 0.091121599, + -0.019305199 -0.0098004397 0.091894798, + -0.0165099 -0.0061395098 0.093139201, + -0.0053918599 -0.017096199 0.093771301, + -0.0053918599 -0.019298101 0.093378402, + -0.00267513 -0.0194789 0.0935314, + 7.0699236e-012 -0.0128274 0.0946564, + 0.00267513 -0.0127698 0.094604298, + 0.00267513 -0.017273501 0.093925603, + 8.6444836e-012 -0.0173322 0.093976498, + -0.00267513 -0.0172744 0.093926199, + -0.0109179 -0.0118783 0.0937903, + -0.0109179 -0.0073538702 0.094301999, + -0.0081421202 -0.0077661402 0.094696604, + -0.0081421202 -0.012302 0.094176702, + -0.0137106 -0.0113221 0.0932827, + -0.0109179 -0.0163571 0.0931293, + -0.0137106 -0.0157857 0.092633098, + -0.0328326 -0.040430401 0.066944398, + -0.0328326 -0.039085001 0.068688899, + -0.0248404 -0.0120847 0.089418903, + -0.0248404 -0.00771796 0.089995399, + -0.0220857 -0.023604499 0.087846398, + -0.019305199 -0.0307645 0.085909903, + -0.019305199 -0.0287534 0.086926103, + -0.0302257 -0.0311436 0.078785598, + -0.027557701 -0.034550499 0.078460202, + -0.027557701 -0.032742798 0.0798079, + -0.0302257 -0.032939099 0.077464402, + -0.027557701 -0.036297999 0.077022597, + -0.0302257 -0.0346753 0.076054297, + -0.0248404 -0.036001001 0.079356603, + -0.0248404 -0.034182299 0.080728099, + -0.0248404 -0.0323098 0.082006097, + -0.0220857 -0.031647399 0.084044598, + -0.0220857 -0.0296786 0.085146599, + -0.050219599 -0.023029 0.054367099, + -0.050219599 -0.024074901 0.052870099, + -0.0465803 -0.027575601 0.058498699, + -0.048467699 -0.024786901 0.0571853, + -0.0465803 -0.026357399 0.0600258, + -0.048467699 -0.0259181 0.0556687, + -0.048467699 -0.026967101 0.054114599, + -0.048467699 -0.0279327 0.0525296, + -0.051830001 0.0027643801 0.067643903, + -0.044564299 -0.021772901 0.068354897, + -0.048467699 -0.0131838 0.067303099, + -0.044564299 0.0059980201 0.077486202, + -0.0424264 0.0079546496 0.079644002, + -0.0378174 0.00201123 0.083194897, + -0.0465803 0.0122129 0.0755665, + -0.048467699 0.0144772 0.073398501, + -0.035366699 0.025977099 0.084047697, + -0.0378174 0.025317499 0.082510203, + -0.0378174 0.0295424 0.081901401, + -0.035366699 0.0281146 0.083735503, + -0.035366699 0.0195415 0.084758103, + -0.035366699 0.023835201 0.084322199, + -0.035366699 0.021689599 0.084559098, + -0.040174201 0.0122441 0.081632301, + -0.040174201 0.0101525 0.0816366, + -0.035366699 0.017391801 0.084919304, + -0.044564299 0.022227 0.077301502, + -0.044564299 0.0181577 0.07756, + -0.044564299 0.0262929 0.076901302, + -0.0465803 0.0242121 0.075101703, + -0.0465803 0.020208299 0.0753958, + -0.0302257 0.025571199 0.087002598, + -0.0328326 0.026789401 0.085437797, + -0.0302257 0.0299266 0.086302899, + -0.0328326 0.0246264 0.085740097, + -0.0328326 0.018115301 0.086417697, + -0.0328326 0.0159408 0.086566903, + -0.0220857 0.022577699 0.090847798, + -0.019305199 0.026305599 0.091191903, + -0.0169627 0.208452 0.0597183, + -0.019305199 0.0218047 0.091840699, + -0.0109552 0.208451 0.061157402, + -0.019305199 0.0172836 0.092330597, + -0.0165099 -0.00161838 0.093468301, + -0.00267513 -0.0082229497 0.095133901, + -2.2529704e-012 -0.00369621 0.095555797, + -3.0845508e-012 -0.0082777999 0.095186397, + -0.00267513 -0.0036427299 0.095502198, + -0.0053918599 -0.0080541195 0.094972298, + -0.00267513 -0.0127711 0.094604999, + -0.0053918599 -0.0125978 0.094446696, + -0.0081421202 -0.0335651 0.087877899, + -0.0053918599 -0.031855699 0.089171499, + -0.00267513 -0.0320483 0.089310601, + 5.5221162e-012 -0.045442998 0.079794303, + -5.1146266e-012 -0.043714799 0.081446998, + -0.00267513 -0.045376901 0.079756401, + -6.1320337e-012 -0.047093902 0.078057401, + -0.00267513 -0.047027402 0.078020804, + 0.00267513 -0.045375701 0.079755403, + -0.019305199 -0.040185899 0.079342403, + -0.0220857 -0.0407537 0.077096596, + -0.0165099 -0.041153099 0.079919398, + -0.0081421202 -0.039448299 0.084093601, + -0.0053918599 -0.039788298 0.084310703, + -0.0109179 -0.0389615 0.083782598, + -0.0053918599 -0.041649699 0.082846299, + -0.0053918599 -0.043446802 0.081287503, + -0.0081421202 -0.044826299 0.079439797, + 0.0081421202 -0.053358302 0.068032898, + 0.0109179 -0.052848302 0.067803301, + 0.0081421202 -0.054436799 0.065936297, + 0.0053918599 -0.053714801 0.068193398, + 0.0109179 -0.0539263 0.065716803, + 0.0053918599 -0.048386302 0.076095, + 0.0081421202 -0.049509201 0.074030101, + 0.00267513 -0.048593201 0.076205403, + 0.00267513 -0.047026198 0.078019798, + 0.0053918599 -0.046820302 0.077905498, + 0.0081421202 -0.048034199 0.075907104, + 0.0109179 -0.047530401 0.075638399, + 0.0053918599 -0.0557664 0.063950099, + 0.0053918599 -0.0566318 0.0617829, + 0.0081421202 -0.055409402 0.063803799, + 0.0053918599 -0.054793701 0.066089697, + 0.00267513 -0.055976201 0.0640359, + 0.00267513 -0.055003501 0.066179797, + 0.0165099 -0.0562272 0.054413799, + 0.0137106 -0.057054002 0.0546882, + 0.0137106 -0.0574979 0.052512702, + 0.0109179 -0.056523301 0.0592761, + 0.0109179 -0.055764701 0.061444901, + 0.0137106 -0.056506999 0.056861602, + 0.0081421202 -0.056274999 0.061643898, + 0.0053918599 -0.051245701 0.072261699, + 0.0081421202 -0.0508908 0.072087303, + 0.0053918599 -0.049862798 0.074211299, + 0.0053918599 -0.052531101 0.070253298, + 0.00267513 -0.051454201 0.0723643, + 0.0081421202 -0.052175101 0.070085801, + 0.00267513 -0.050070599 0.074317798, + -0.00267513 -0.055977602 0.064036101, + -0.00267513 -0.055004898 0.066180103, + -0.0053918599 -0.055769101 0.063950501, + -0.0053918599 -0.056634501 0.061783198, + -0.00267513 -0.056842901 0.0618647, + 2.9467941e-012 -0.0560451 0.0640641, + -6.0972555e-012 -0.055072401 0.066209398, + -0.00267513 -0.051455598 0.072364897, + 4.2681462e-012 -0.052808899 0.0703841, + 7.251253e-012 -0.051522899 0.072397903, + -0.0053918599 -0.053717598 0.068194203, + -0.0053918599 -0.052533802 0.070254304, + -0.0081421202 -0.0533625 0.068034202, + -0.0081421202 -0.054441001 0.065937303, + -0.0053918599 -0.054796498 0.066090301, + -0.00267513 -0.053925801 0.0682882, + -0.00267513 -0.052741501 0.070352197, + -0.0081421202 -0.050894901 0.072089098, + -0.0081421202 -0.049513299 0.074032299, + -0.0081421202 -0.052179299 0.070087299, + -0.0053918599 -0.051248498 0.072262898, + -0.0053918599 -0.049865499 0.074212797, + -0.055787299 -0.0085041597 0.051249001, + -0.0532961 -0.0134581 0.055557702, + -0.051830001 -0.0151401 0.058364399, + -0.0302257 -0.044685401 0.064124197, + -0.0302257 -0.0435187 0.0660078, + -0.0302257 -0.0457545 0.062198799, + -0.027557701 -0.046356399 0.0648771, + -0.027557701 -0.045186501 0.0667933, + -0.0302257 -0.0475954 0.0582527, + -0.0302257 -0.046724901 0.060239099, + -0.035366699 -0.0445356 0.0548269, + -0.0378174 -0.0423855 0.054029498, + -0.0328326 -0.045758501 0.057535499, + -0.0378174 -0.043067999 0.052132599, + -0.0328326 -0.047204301 0.0535868, + -0.0328326 -0.0465311 0.055567101, + -0.035366699 -0.0452132 0.052886799, + -0.035366699 -0.045794599 0.050940201, + -0.0328326 -0.0477795 0.051600199, + -0.0302257 -0.049034499 0.054230299, + -0.0302257 -0.048365399 0.056247398, + -0.053653602 -0.0268292 0.0144786, + -0.0532961 -0.0275055 0.0164301, + -0.054204401 -0.025738601 0.0144795, + -0.0532832 -0.0275626 0.0144781, + -0.053669199 -0.026833201 0.0094786398, + -0.050219599 -0.030310201 0.035507198, + -0.050219599 -0.032611299 0.0184507, + -0.048467699 -0.032646399 0.039466701, + -0.051830001 -0.0299807 0.018391799, + -0.050219599 -0.029833 0.038740501, + -0.0546159 -0.0209595 0.036449801, + -0.055787299 -0.018552 0.032907002, + -0.055787299 -0.0170366 0.038312498, + -0.0546159 -0.020131599 0.039224699, + -0.051830001 -0.0237536 0.047120001, + -0.0532961 -0.021445399 0.044532001, + -0.0532961 -0.0221001 0.043063998, + -0.0532961 -0.022679299 0.041593399, + -0.0532961 -0.023184501 0.040124401, + -0.038435601 -0.046080299 0.0094633102, + -0.033494599 -0.049788099 0.0094603598, + -0.0109179 0.152124 -0.054182801, + -0.042409498 0.17153201 -0.040306699, + -0.044024602 0.17153101 -0.038611699, + -0.044033099 0.191531 -0.038603898, + -0.042828102 0.20853201 -0.039854899, + -0.040608101 0.191534 -0.0420174, + -0.040174201 0.169109 -0.042404301, + -0.0424264 0.166581 -0.0401753, + -0.0424264 0.169063 -0.040266801, + -0.0402769 0.171534 -0.042335499, + -0.040172402 0.171534 -0.042425599, + -0.039599199 0.171534 -0.042919699, + -0.038047399 0.171535 -0.044257302, + -0.0328326 0.164572 -0.0478063, + -0.0328326 0.16223 -0.047577899, + -0.0328326 0.166906 -0.047966201, + -0.0302257 0.164672 -0.049415998, + -0.0302257 0.16697399 -0.049575999, + -0.0576833 -0.0164335 0.016318999, + -0.0580099 -0.0152885 0.0144878, + -0.0581805 -0.0146752 0.0144883, + -0.058412101 -0.013628 0.016290899, + -0.057391401 -0.017511001 0.0144861, + -0.056809202 -0.019234899 0.016347099, + -0.056809202 -0.0189602 0.018145099, + -0.0109179 -0.058938202 0.041837599, + -0.0081421202 -0.059423499 0.044238102, + -0.0109179 -0.058931202 0.044119898, + -0.0109179 -0.058963601 0.0327149, + -0.0116529 -0.058869001 0.0144531, + 0.027557701 -0.051252499 0.052762199, + 0.0302257 -0.050063901 0.050184399, + 0.0302257 -0.049590301 0.0522101, + 0.027557701 -0.051719502 0.050703, + 0.027557701 -0.050687399 0.054818202, + 0.027557701 -0.0474132 0.0629154, + 0.027557701 -0.048384 0.060923301, + 0.0248404 -0.047847699 0.065550998, + 0.0137106 -0.054228701 0.063319802, + 0.0248404 -0.0515262 0.057424702, + 0.0165099 -0.051347401 0.067127302, + 0.0220857 -0.054077201 0.053700201, + 0.0248404 -0.0521884 0.055345301, + 0.0248404 -0.0527489 0.053259101, + 0.0220857 -0.052861702 0.057919499, + 0.0220857 -0.053520899 0.055813201, + 0.044564299 -0.033397801 0.054777101, + 0.0465803 -0.0315868 0.052009501, + 0.035366699 -0.0384246 0.0659592, + 0.0378174 -0.036281899 0.0649058, + 0.0378174 -0.0375266 0.063187599, + 0.0328326 -0.039068598 0.068680197, + 0.035366699 -0.035664201 0.069309004, + 0.0378174 -0.033537898 0.068174899, + 0.0378174 -0.034951098 0.066570401, + 0.035366699 -0.037086502 0.067664601, + 0.035366699 -0.034161899 0.070886202, + 0.0328326 -0.037637901 0.0703618, + 0.0328326 -0.036125701 0.071975201, + 0.040174201 -0.0374429 0.058626302, + 0.0378174 -0.039744802 0.059616599, + 0.040174201 -0.038411401 0.056833301, + 0.0424264 -0.035002101 0.057576202, + 0.040174201 -0.036382601 0.060386501, + 0.0378174 -0.038681898 0.0614223, + 0.0424264 -0.035969902 0.055831999, + 0.0378174 -0.040713701 0.057777599, + 0.040174201 -0.039287001 0.0550148, + 0.040174201 -0.0400692 0.053178199, + 0.0328326 -0.043900199 0.061404198, + 0.0302257 -0.045738999 0.0621952, + 0.0302257 -0.0446698 0.064119503, + 0.027557701 -0.0451723 0.0667881, + 0.027557701 -0.043906901 0.068654202, + 0.027557701 -0.052645002 0.042606302, + 0.0302257 -0.0517601 0.0188713, + 0.0302257 -0.051630698 0.023164401, + 0.0248404 -0.0540151 0.0449716, + 0.027557701 -0.052549701 0.044592701, + 0.0302257 -0.051028799 0.042217702, + 0.027557701 -0.053240702 0.0189049, + 0.027557701 -0.053135999 0.0232551, + 0.0302257 -0.051821101 0.016672401, + 0.0248404 -0.0541435 0.040777199, + 0.027557701 -0.0532909 0.0166873, + 0.0248404 -0.054491099 0.023336699, + 0.0248404 -0.054099798 0.042956199, + 0.0220857 -0.0553913 0.043266799, + 0.0248404 0.167089 -0.0523463, + 0.0248404 0.169322 -0.052444499, + 0.0248404 0.16484401 -0.052183699, + 0.0328326 0.157535 -0.0468961, + 0.035366699 0.15731899 -0.045142401, + 0.0109179 0.162955 -0.056343999, + 0.0053973799 0.16516501 -0.057332199, + 0.0053973799 0.15871 -0.056446999, + 0.0081428103 0.15651201 -0.0557019, + 0.0109179 0.15644801 -0.055254199, + 0.040174201 0.161761 -0.041895799, + 0.0424264 0.15908 -0.03946, + 0.0424264 0.161584 -0.039756499, + 0.040174201 0.16421799 -0.0421254, + 0.0378174 0.164343 -0.0441425, + 0.0378174 0.159508 -0.0436172, + 0.040174201 0.1593 -0.041599501, + 0.040174201 0.156838 -0.041235302, + 0.0378174 0.157086 -0.043253198, + 0.0378174 0.161928 -0.0439132, + 0.035366699 0.159702 -0.045506101, + 0.035366699 0.162084 -0.0458019, + 0.0081428103 0.167291 -0.057180401, + 0.0109179 0.165117 -0.056571499, + 0.0081428103 0.16514499 -0.0570191, + 0.0109179 0.167272 -0.056733001, + 0.0081428103 0.16942599 -0.057276499, + 0.0053973799 0.16730399 -0.057493299, + 0.0053973799 0.169432 -0.057589099, + 0.055787299 -0.0158737 0.041009199, + 0.0546159 -0.018996 0.042046599, + 0.055787299 -0.017018599 0.038308401, + 0.055787299 -0.0144521 0.0436817, + 0.056809202 -0.0127221 0.039962001, + 0.0546159 -0.017591201 0.044845399, + 0.056809202 -0.0138944 0.037387598, + 0.058412101 -0.0049084001 0.0401434, + 0.058412101 -0.00317978 0.042382699, + 0.058412101 -0.0063810698 0.037854999, + 0.058412101 -0.00760801 0.035535, + 0.059999999 0.00662508 0.0293053, + 0.059999999 0.00561126 0.027563499, + 0.059999999 0.00361019 0.023809601, + 0.0599402 0.00477676 0.031884801, + 0.059999999 0.0296332 0.043420099, + 0.0599402 0.0297036 0.045773201, + 0.059999999 0.021427801 0.041300699, + 0.0546159 0.0278582 0.063826501, + 0.056809202 0.0258493 0.059390899, + 0.055787299 0.026764899 0.061629798, + 0.056809202 0.029334299 0.0591694, + 0.056809202 0.0223688 0.059503399, + 0.0576833 0.025095301 0.057135802, + 0.055787299 0.0232074 0.061799899, + 0.0576833 0.028505201 0.056968901, + 0.059445001 0.042842198 0.048761498, + 0.058998398 0.040352002 0.051265098, + 0.058998398 0.043615501 0.050675102, + 0.059445001 0.0396493 0.0492923, + 0.059445001 0.04603 0.0481265, + 0.059757002 0.042186201 0.046863001, + 0.059757002 0.0453059 0.046284601, + 0.059757002 0.032891098 0.047997501, + 0.059757002 0.0359344 0.047723599, + 0.059757002 0.029890999 0.0480587, + 0.058412101 0.024589701 0.054868001, + 0.058998398 0.0242563 0.0524933, + 0.059445001 0.0270888 0.050264101, + 0.027557701 0.028859099 0.087740503, + 0.0220857 0.0225772 0.090846099, + 0.0248404 0.0278995 0.089036599, + 0.0220857 0.0270478 0.090186998, + 0.0328326 0.0310962 0.084719397, + 0.0302257 0.0255704 0.087000303, + 0.0302257 0.0299253 0.086300798, + 0.035366699 0.0238344 0.0843179, + 0.035366699 0.0195409 0.0847518, + 0.0328326 0.022458401 0.086000197, + 0.0328326 0.0267886 0.085435301, + 0.035366699 0.028113799 0.083732799, + 0.0378174 0.0253167 0.082505502, + 0.0378174 0.021077299 0.0829634, + 0.035366699 0.0152412 0.085034102, + 0.035366699 0.0173914 0.084911898, + 0.051830001 0.0230255 0.068685502, + 0.0532961 0.025419701 0.066278197, + 0.0546159 0.024219301 0.064067401, + 0.0532961 0.018007999 0.066541202, + 0.0546159 0.02059 0.0641867, + 0.0532961 0.0217082 0.066471897, + 0.051830001 0.0192426 0.0688328, + 0.051830001 0.0154729 0.068852797, + 0.050219599 0.0129957 0.071111701, + 0.058412101 0.0089890799 0.051538099, + 0.058998398 0.0120597 0.049639899, + 0.058412101 0.0119712 0.052734502, + 0.0576833 0.00591115 0.053440701, + 0.0576833 0.0089416504 0.054736599, + 0.058998398 0.0066325502 0.046749402, + 0.058998398 0.0092619602 0.048303202, + 0.059445001 0.0097580804 0.045082401, + 0.059445001 0.0073502902 0.043456301, + 0.058998398 0.0042004902 0.0450048, + 0.058412101 0.0034870701 0.048427101, + 0.058412101 0.0061499602 0.0500945, + 0.0465803 -0.0250376 0.061490599, + 0.044564299 -0.027703799 0.062856801, + 0.050219599 -0.0218776 0.055817802, + 0.048467699 -0.023551701 0.0586478, + 0.050219599 -0.023003099 0.054359399, + 0.0465803 -0.0191443 0.066778697, + 0.0465803 -0.0175178 0.067924201, + 0.048467699 -0.0164304 0.065158702, + 0.048467699 -0.0179836 0.063986003, + 0.0465803 -0.0207147 0.065558203, + 0.0424264 -0.025851401 0.068515003, + 0.044564299 -0.023341199 0.067070097, + 0.035366699 -0.023786901 0.078674801, + 0.0328326 -0.025666701 0.079957299, + 0.0328326 -0.0237536 0.080971397, + 0.0424264 -0.019107601 0.073273197, + 0.0424264 -0.0136048 0.075943097, + 0.044564299 -0.0130739 0.0734585, + 0.044564299 -0.0148882 0.072603799, + 0.040174201 0.0143396 0.081579402, + 0.0378174 0.016830901 0.083271801, + 0.040174201 0.0185291 0.081389599, + 0.0424264 0.016199799 0.079615697, + 0.0424264 0.0120764 0.079694197, + 0.0424264 -0.0059877601 0.078248501, + 0.040174201 -0.0081461603 0.079991497, + 0.0424264 -0.0079045501 0.077805497, + 0.044564299 -0.00371387 0.076412097, + 0.0424264 -0.0040851999 0.078601301, + 0.040174201 -0.0062200101 0.080368303, + 0.044564299 -0.0056056599 0.075996101, + 0.0465803 -0.0123595 0.070878796, + 0.048467699 -0.0114666 0.068223402, + 0.050219599 -0.0087238997 0.066410802, + -0.059757002 -0.0021136701 0.024627499, + -0.0599402 -0.0024204601 0.016998701, + -0.059757002 -0.00492378 0.0178304, + -0.059757002 -0.00029346501 0.028869599, + -0.059999999 0.0056117801 0.0275637, + -0.0599402 0.00075967598 0.024218701, + -0.0599402 -0.00117841 0.0201317, + -0.058998398 -0.0079687396 0.025460601, + -0.058412101 -0.00860254 0.0332595, + -0.058998398 -0.00633338 0.030205199, + -0.058998398 -0.0096280398 0.020640099, + -0.059445001 -0.00769467 0.0178925, + -0.058412101 0.0150447 0.053697798, + -0.0576833 0.0120691 0.055790398, + -0.058998398 0.0149746 0.0507656, + -0.0532961 -0.0030321099 0.062663503, + -0.051830001 -0.0075749699 0.063716903, + -0.051830001 -0.0059191901 0.064571097, + -0.051830001 -0.0025100801 0.066043198, + -0.056809202 -0.00010993299 0.053704601, + -0.056809202 0.0028152501 0.055365901, + -0.055787299 -0.0032079399 0.0554878, + -0.0546159 -0.00326998 0.0591271, + -0.055787299 -0.000241544 0.057255201, + -0.0546159 -0.00169957 0.059960101, + -0.0546159 -0.00479746 0.058224101, + -0.0532961 -0.0062572602 0.060973499, + -0.055787299 -0.00174767 0.056403901, + -0.0532961 -0.0046641901 0.061855599, + -0.058998398 0.0211164 0.052190099, + -0.058998398 0.0180133 0.051610101, + -0.058412101 0.018205401 0.054359902, + -0.058998398 0.024253899 0.0525086, + -0.058412101 0.0214034 0.054751899, + -0.059445001 0.024009099 0.050033901, + -0.059445001 0.020963199 0.049535502, + -0.056809202 0.019004701 0.059501201, + -0.0576833 0.018546101 0.057000499, + -0.056809202 0.015692901 0.059245698, + -0.0576833 0.0217961 0.057191201, + -0.056809202 0.022350799 0.059515201, + -0.055787299 0.019639 0.061870102, + -0.055787299 0.016228201 0.061799001, + -0.055787299 0.0145492 0.061675701, + -0.059445001 0.039631501 0.049311999, + -0.059757002 0.039034899 0.047358502, + -0.059445001 0.0364266 0.049736999, + -0.059445001 0.042834401 0.048781, + -0.058998398 0.040344201 0.051284499, + -0.059757002 0.042168502 0.046882801, + -0.058998398 0.037067398 0.051767301, + -0.019305199 -0.049182501 0.0686756, + -0.0165099 -0.048897501 0.071107097, + -0.019305199 -0.050359901 0.066681102, + 0.040174201 -0.0297863 0.068460099, + 0.0378174 -0.032046098 0.069713101, + 0.040174201 -0.0312667 0.066963501, + 0.0424264 -0.027389999 0.0671314, + 0.0424264 -0.028858401 0.065678902, + 0.0109179 -0.0426034 0.080782801, + 0.0081421202 -0.041303899 0.082631104, + 0.0137106 -0.043670502 0.078773201, + 0.0081421202 -0.035567202 0.086713798, + 0.0053918599 -0.037868701 0.085675403, + 0.0053918599 -0.0359024 0.086942799, + 0.0081421202 -0.0394454 0.084089801, + 0.0109179 -0.037046801 0.085131504, + 0.0081421202 -0.037530601 0.085451499, + 0.0137106 -0.040167298 0.081928, + 0.0165099 -0.0411461 0.0799127, + 0.0165099 -0.039365299 0.081432, + 0.0137106 -0.041953702 0.080394797, + 0.0137106 -0.038317502 0.083367899, + 0.0109179 -0.040812299 0.082327001, + 0.0109179 -0.0389576 0.083777599, + 0.0302257 -0.0093588103 0.087053701, + 0.0328326 -0.0035274201 0.086177997, + 0.0328326 -0.0077876798 0.085689403, + 0.035366699 -0.0060785199 0.084205396, + 0.0378174 -0.00628511 0.082347199, + 0.040174201 -0.0042942399 0.080659702, + 0.040174201 0.0101578 0.081623398, + 0.0220857 -0.0066049499 0.091248304, + 0.0248404 -0.0077060899 0.089988098, + 0.0220857 -0.00881969 0.091003403, + 0.019305199 -0.0097911898 0.091889098, + -4.8596565e-012 -0.0279493 0.091173202, + -8.4755347e-013 -0.0258427 0.091927499, + 0.00267513 -0.027887501 0.091125399, + 0.00267513 -0.029978201 0.090269201, + 2.1196744e-012 -0.0300407 0.090316102, + -0.00267513 -0.027887801 0.0911263, + -0.00267513 -0.029978599 0.090270199, + -0.0137106 0.00686508 0.094323203, + -0.0137106 0.0114461 0.094177902, + -0.0137106 0.00228963 0.094305597, + -0.0109179 0.0109689 0.094733097, + -0.0165099 0.0029237601 0.093636602, + -0.0109179 0.0063713002 0.094870098, + -0.0081421202 0.0106052 0.095155999, + -0.0053918599 0.0103512 0.0954514, + -0.040174201 -0.028252101 0.069901899, + -0.040174201 -0.0298051 0.068473898, + -0.035366699 -0.029243501 0.075180396, + -0.0328326 -0.0311691 0.0763705, + -0.0378174 -0.0288644 0.072586797, + -0.0328326 -0.0293869 0.077662602, + -0.040174201 -0.024952799 0.072528698, + -0.0378174 -0.0271689 0.073898301, + -0.040174201 -0.0266327 0.071254998, + -0.0424264 -0.0226027 0.071076199, + -0.0424264 -0.0242662 0.0698428, + -0.035366699 -0.0371041 0.067673899, + -0.035366699 -0.038442601 0.065967098, + -0.027557701 -0.00646473 0.088852398, + -0.0302257 -0.0134744 0.086378902, + -0.0328326 -0.0118663 0.085048199, + -0.027557701 -0.0149385 0.087590203, + -0.027557701 -0.0129188 0.087972797, + -0.0302257 -0.021526899 0.083973698, + -0.0248404 -0.0203477 0.087605797, + -0.0248404 -0.022396 0.086920798, + -0.0220857 -0.0215433 0.0885465, + -0.0220857 -0.019476701 0.089147501, + -0.0248404 -0.018293999 0.088192798, + -0.027557701 -0.019000599 0.086545996, + -0.027557701 -0.021034701 0.085877903, + -0.0220857 -0.027677899 0.086147301, + -0.0220857 -0.0256512 0.087047003, + -0.027557701 -0.0250556 0.084248498, + -0.027557701 -0.0230549 0.0851124, + -0.0248404 -0.0264448 0.085254498, + -0.0248404 -0.024430299 0.086137302, + -0.040174201 -0.031286199 0.066975698, + -0.0378174 -0.033556301 0.068186402, + -0.0424264 -0.0302728 0.064173497, + -0.044564299 -0.0290318 0.0613406, + -0.0424264 -0.028879 0.065691799, + -0.044564299 -0.027726 0.062868498, + -0.0465803 -0.0250609 0.061503001, + -0.0328326 -0.042849801 0.063297197, + -0.0328326 -0.041686598 0.065144897, + -0.035366699 -0.0428872 0.058664698, + -0.035366699 -0.043760099 0.0567552, + -0.0328326 -0.044886898 0.059485, + -0.0328326 -0.043917 0.061407998, + -0.040174201 -0.0232177 0.073718399, + -0.048467699 -0.0114822 0.0682467, + -0.050219599 -0.0087400898 0.066434897, + -0.048467699 -0.00797466 0.069885999, + -0.048467699 -0.0061808601 0.070578098, + -0.048467699 -0.0097438097 0.0691083, + -0.050219599 -0.00528104 0.067991801, + -0.050219599 -0.0070253899 0.067254297, + -0.0465803 -0.0050673098 0.073644601, + -0.044564299 -0.0074984799 0.075507298, + -0.0465803 -0.0069218501 0.073088899, + -0.0465803 -0.0087608797 0.072446801, + -0.0465803 -0.0105795 0.071717702, + -0.035366699 -0.00187928 0.084670201, + -0.0328326 -0.0013983099 0.086381197, + -0.035366699 0.000242985 0.084847398, + -0.035366699 0.00237328 0.084988303, + -0.0378174 0.00622808 0.083405502, + -0.040174201 0.00597951 0.081535198, + -0.040174201 0.0080640204 0.081604198, + -0.0378174 0.0041169501 0.083318703, + -0.050219599 0.0129718 0.071126401, + -0.051830001 0.0117001 0.068763897, + -0.0378174 0.0083435504 0.083455101, + -0.0378174 0.0104624 0.083467402, + -0.0378174 0.0147071 0.083380297, + -0.0378174 0.0168311 0.083280899, + -0.040174201 0.0164333 0.081513599, + -0.040174201 0.014338 0.081591196, + -0.0378174 0.012584 0.083442397, + -0.035366699 0.0152413 0.085042603, + -0.040174201 0.022719201 0.081060298, + -0.0424264 0.0203299 0.079403698, + -0.0424264 0.0244595 0.079034999, + -0.040174201 0.018529201 0.081399202, + -0.040174201 0.026900901 0.080574498, + -0.0378174 0.0231991 0.082758799, + -0.0378174 0.021077899 0.082970098, + -0.0378174 0.018954899 0.083144203, + -0.0248404 0.019006301 0.090225004, + -0.0220857 0.018086201 0.091349497, + -0.0302257 0.0211943 0.087550297, + -0.027557701 0.0200429 0.088957898, + -0.0302257 0.023384901 0.087295704, + -0.0302257 0.0190005 0.0877662, + -0.0328326 0.022459099 0.086004198, + -0.0328326 0.0202884 0.086230204, + -0.027557701 -0.0042803399 0.0890745, + -0.0302257 -0.00290695 0.0877911, + -0.0248404 0.0279007 0.089038298, + -0.0248404 0.023463801 0.089709498, + -0.0220857 0.0270488 0.0901886, + -0.027557701 0.024462201 0.088427097, + -0.027557701 0.028860399 0.0877425, + -0.0227904 0.208454 0.057669099, + -0.0137106 0.025139799 0.092765696, + -0.0165099 0.025669901 0.092050202, + -0.0137106 0.029659601 0.091973998, + -0.0109179 0.029250201 0.092554398, + -0.0109179 0.024713499 0.093341298, + -0.0137106 0.020592 0.093398102, + -0.0165099 0.021143399 0.092689998, + -0.0165099 0.0074789999 0.093643203, + -0.019305199 0.00368426 0.092834197, + -0.019305199 0.012751 0.092659697, + -0.0165099 0.0120395 0.093487598, + -0.00267513 -0.038068201 0.085808203, + -5.4641482e-012 -0.036163799 0.087121896, + 6.2506094e-012 -0.034154098 0.0882909, + -0.0053918599 -0.035903901 0.0869454, + -0.0053918599 -0.033896498 0.088110603, + -0.0081421202 -0.0355695 0.086717702, + -0.0081421202 -0.037533201 0.085455403, + -0.0053918599 -0.0378704 0.085677996, + -0.00267513 -0.036100101 0.087078802, + -0.00267513 -0.034090899 0.088246897, + 0.00267513 -0.041849501 0.082968898, + 0.0053918599 -0.041647501 0.0828439, + 0.00267513 -0.0399867 0.084436603, + 0.00267513 -0.0436479 0.081406899, + 7.3808971e-012 -0.0419157 0.0830101, + 1.6304556e-012 -0.0400525 0.0844789, + -0.019305199 -0.0435226 0.076078303, + -0.019305199 -0.041891702 0.077751502, + -0.0220857 -0.042378101 0.075443797, + -0.0220857 -0.043921899 0.073714502, + -0.019305199 -0.045072202 0.074327901, + -0.0165099 -0.044501401 0.076620899, + -0.0165099 -0.042865101 0.0783116, + -0.0109179 -0.042608 0.080787398, + -0.0081421202 -0.043102 0.081081897, + -0.0109179 -0.0443292 0.079153903, + -0.0109179 -0.040816601 0.082331799, + -0.0137106 -0.041959502 0.080400497, + -0.0081421202 -0.041307099 0.082634702, + -0.0137106 -0.0436766 0.078778498, + 0.0081421202 -0.0448227 0.079436697, + 0.0081421202 -0.043098502 0.0810785, + 0.0109179 -0.044324301 0.079149798, + 0.0109179 -0.045968801 0.077433199, + 0.0081421202 -0.046470001 0.077711202, + 0.0053918599 -0.045171 0.079637498, + 0.0053918599 -0.0434446 0.081285298, + 0.0109179 -0.058160301 0.052719999, + 0.0081421202 -0.058665 0.052877899, + 0.0053918599 -0.058580101 0.0551943, + -0.0546159 -0.0128088 0.051543798, + -0.0546159 -0.0116304 0.052786, + -0.055787299 -0.0096740602 0.050067399, + -0.0546159 -0.0139172 0.0502619, + -0.055787299 -0.0107765 0.0488469, + -0.0532961 -0.015900901 0.053000201, + -0.0532961 -0.0147142 0.054301899, + -0.056809202 -0.01551 0.032234401, + -0.055787299 -0.0179011 0.0356603, + -0.056809202 -0.0148141 0.0348632, + -0.056809202 -0.018239601 0.0211583, + -0.0576833 -0.016139099 0.0180819, + -0.050219599 -0.0274415 0.046639699, + -0.051830001 -0.0244783 0.045598, + -0.051830001 -0.0251236 0.044069, + -0.050219599 -0.0267237 0.048221301, + -0.048467699 -0.0303222 0.0476522, + -0.048467699 -0.0296109 0.049291998, + -0.050219599 -0.028633701 0.043459799, + -0.051830001 -0.025691099 0.042537399, + -0.050219599 -0.0280778 0.0450509, + -0.050219599 -0.0291108 0.041871101, + -0.048467699 -0.0314942 0.044356499, + -0.051830001 -0.026182 0.041007999, + -0.048467699 -0.030949401 0.046005402, + -0.0137106 0.154185 -0.054170199, + -0.0165099 0.15188099 -0.052867301, + -0.0165099 0.154066 -0.0534412, + -0.0137106 0.152016 -0.0535965, + -0.0137106 0.156363 -0.0546735, + -0.0109179 0.154282 -0.0547565, + -0.0109179 0.15644699 -0.0552595, + -0.044564299 0.163947 -0.037763201, + -0.0465803 0.161204 -0.0351771, + -0.048467699 0.161002 -0.0327265, + -0.0378174 0.161929 -0.0439394, + -0.040174201 0.161762 -0.041923601, + -0.040174201 0.159299 -0.041625701, + -0.0378174 0.15950701 -0.043641798, + -0.035366699 0.162085 -0.045826498, + -0.035366699 0.164463 -0.0460549, + -0.0378174 0.16675401 -0.044328101, + -0.040174201 0.16666999 -0.0423126, + -0.040174201 0.16422001 -0.042152401, + -0.0378174 0.164345 -0.044167999, + -0.0378174 0.16915201 -0.0444199, + -0.035366699 0.166833 -0.046214901, + -0.035366699 0.169192 -0.046306901, + -0.0248404 0.160335 -0.051676501, + -0.0220857 0.160455 -0.052847501, + -0.0220857 0.162689 -0.053143501, + -0.0248404 0.16259199 -0.051972602, + -0.027557701 0.160199 -0.050356999, + -0.027557701 0.157912 -0.049991801, + -0.0248404 0.155817 -0.050877001, + -0.0220857 0.155984 -0.052048702, + -0.0220857 0.15821999 -0.052482799, + -0.0248404 0.158075 -0.0513115, + -0.0248404 0.153561 -0.050372601, + -0.027557701 0.155627 -0.049557, + -0.027557701 0.153345 -0.049052201, + 0.0599402 -0.0021516799 0.017754501, + 0.059757002 -0.00488608 0.017815899, + 0.059757002 -0.00211434 0.024623999, + 0.059757002 -0.00395549 0.020293999, + 0.0248404 -0.0489203 0.063563697, + 0.0220857 -0.049184099 0.066152997, + 0.019305199 -0.050349999 0.066678099, + 0.019305199 -0.053264599 0.060469601, + 0.0165099 -0.053395901 0.062978402, + 0.0165099 -0.052423701 0.065070599, + 0.0165099 -0.055023499 0.058720499, + 0.019305199 -0.054026801 0.0583512, + 0.0165099 -0.054262701 0.060858998, + 0.0137106 -0.0558546 0.059028398, + 0.0165099 -0.055677701 0.0565705, + 0.019305199 -0.054683302 0.056221399, + 0.0137106 -0.055095099 0.061183698, + 0.044564299 -0.0350658 0.0513235, + 0.0424264 -0.0368471 0.054062501, + 0.0424264 -0.037632599 0.052274998, + 0.044564299 -0.034276601 0.053059202, + 0.044564299 -0.035765398 0.049576201, + 0.0465803 -0.032379899 0.0503278, + 0.0465803 -0.033085499 0.048634801, + 0.0378174 -0.041588102 0.055912901, + 0.035366699 -0.0428693 0.058661699, + 0.0378174 -0.0423669 0.054029901, + 0.0328326 -0.0416697 0.065138698, + 0.0302257 -0.043503199 0.066002198, + 0.0328326 -0.0428329 0.063292101, + 0.0328326 -0.0404137 0.066936903, + 0.035366699 -0.039675198 0.064199403, + 0.0302257 -0.042242199 0.067835897, + 0.035366699 -0.040834598 0.062392, + 0.027557701 0.160199 -0.050339099, + 0.0248404 0.160335 -0.051660299, + 0.0248404 0.16259199 -0.051955398, + 0.027557701 0.157915 -0.049975902, + 0.0302257 0.15773401 -0.048508201, + 0.0302257 0.16236199 -0.049166899, + 0.0328326 0.162229 -0.047555201, + 0.0328326 0.15988301 -0.047259599, + 0.0302257 0.16004901 -0.048871599, + 0.027557701 0.16248301 -0.050634298, + 0.027557701 0.16476201 -0.0508628, + 0.0302257 0.166972 -0.0495588, + 0.0302257 0.16467001 -0.049395598, + 0.027557701 0.167033 -0.0510257, + 0.027557701 0.169294 -0.0511242, + 0.0302257 0.16926301 -0.049657598, + 0.0328326 0.166904 -0.0479475, + 0.0328326 0.16457 -0.047784101, + 0.0081428103 0.160833 -0.056496799, + 0.0081428103 0.158672 -0.056134, + 0.0053973799 0.160864 -0.056809999, + 0.0053973799 0.163018 -0.057104699, + 0.0081428103 0.162991 -0.0567916, + 0.0109179 0.160787 -0.056049202, + 0.0109179 0.15861601 -0.055686299, + 0.059445001 0.00143604 0.0377912, + 0.058998398 -0.0017261 0.0389635, + 0.059445001 0.00317744 0.039774999, + 0.058998398 8.9189134e-006 0.041074701, + 0.059757002 0.0030410099 0.034724101, + 0.059999999 0.0077972198 0.0309946, + 0.0599402 0.0113709 0.038874, + 0.059999999 0.0144361 0.037493099, + 0.059757002 0.0082818102 0.040265601, + 0.059999999 0.0124746 0.035961401, + 0.059757002 0.0104664 0.041924302, + 0.059999999 0.00158619 0.0199605, + 0.0599402 0.0135413 0.040412702, + 0.059999999 0.0189292 0.040190998, + 0.059999999 0.016592501 0.038912699, + 0.059999999 0.026808999 0.042929702, + 0.059999999 0.0240636 0.042219799, + 0.059757002 0.0154136 0.044762399, + 0.0599402 0.018432301 0.043024801, + 0.0599402 0.0159015 0.0418058, + 0.059757002 0.0128502 0.043433201, + 0.059445001 0.0123543 0.0465234, + 0.059445001 0.0151108 0.0477538, + 0.059445001 0.017996799 0.0487528, + 0.059757002 0.018129401 0.045887999, + 0.0599402 0.021107901 0.0440467, + 0.058412101 0.027825801 0.0547648, + 0.058998398 0.0273785 0.052559901, + 0.059445001 0.0301496 0.0502664, + 0.0248404 0.0145361 0.090577699, + 0.0220857 0.0180858 0.0913468, + 0.027557701 0.0200423 0.088954501, + 0.0302257 0.0211937 0.087546602, + 0.0248404 0.0190058 0.090221897, + 0.027557701 0.0244615 0.088425003, + 0.0248404 0.023463201 0.089707598, + 0.0302257 0.0146066 0.088075101, + 0.0302257 0.0168039 0.087937802, + 0.0328326 0.0159404 0.086560003, + 0.0328326 0.0137656 0.086669803, + 0.027557701 0.0156104 0.089327097, + 0.0302257 0.0124091 0.088173397, + 0.027557701 0.0111742 0.0895423, + 0.0165099 0.0120392 0.0934847, + 0.019305199 0.017283199 0.092328198, + 0.0165099 0.016596699 0.093167603, + 0.019305199 0.0036850199 0.092828497, + 0.0165099 0.00292443 0.0936317, + 0.0165099 0.0074789701 0.093639202, + 0.0220857 0.0090759303 0.091868602, + 0.0248404 0.0100626 0.0907747, + 0.0220857 0.0135825 0.091687799, + 0.019305199 0.0127507 0.092656299, + 0.019305199 0.0082152104 0.092822902, + 0.0220857 0.0045742001 0.091889597, + 0.0532961 0.0037799799 0.065098099, + 0.051830001 0.00276945 0.0676274, + 0.0465803 -0.027551601 0.058490001, + 0.048467699 -0.024762001 0.057176199, + 0.0465803 -0.026333701 0.060015298, + 0.0465803 -0.0286879 0.056920301, + 0.044564299 -0.030234201 0.059753299, + 0.048467699 -0.0258931 0.055661298, + 0.044564299 -0.0290091 0.061330501, + 0.035366699 -0.0274632 0.076424301, + 0.035366699 -0.025646601 0.0775951, + 0.0328326 -0.029375101 0.077647299, + 0.0328326 -0.0275429 0.078848504, + 0.0378174 -0.025403401 0.075106896, + 0.040174201 -0.0214216 0.0748026, + 0.0378174 -0.0236036 0.076244801, + 0.0378174 -0.0288484 0.072571203, + 0.035366699 -0.0309387 0.0738189, + 0.035366699 -0.029229499 0.075164698, + 0.0378174 -0.027153799 0.073881499, + 0.0378174 -0.0304811 0.071180202, + 0.040174201 -0.0266157 0.071238399, + 0.040174201 -0.0282341 0.069886602, + 0.0424264 -0.022585901 0.071057402, + 0.0424264 -0.0242482 0.069825202, + 0.040174201 -0.024936801 0.072510898, + 0.040174201 -0.0232033 0.073699698, + 0.0424264 -0.020870199 0.0722076, + 0.044564299 -0.0201093 0.0695263, + 0.044564299 -0.021754 0.068336397, + 0.0378174 -0.021761701 0.077293098, + 0.035366699 -0.021891 0.079661101, + 0.035366699 -0.0199659 0.080552302, + 0.040174201 -0.017741101 0.076741703, + 0.040174201 -0.019598501 0.075817198, + 0.0424264 -0.017304599 0.0742523, + 0.0424264 -0.0154682 0.075142801, + 0.040174201 -0.0158558 0.077574201, + 0.0378174 -0.0198844 0.078249499, + 0.0378174 -0.017978599 0.079112299, + 0.048467699 -0.0079631004 0.069863603, + 0.048467699 -0.00973015 0.069085099, + 0.0465803 -0.0105684 0.071696199, + 0.0465803 -0.0087518198 0.072426997, + 0.048467699 -0.00617145 0.070557401, + 0.050219599 -0.0052690599 0.067968503, + 0.050219599 -0.0070112399 0.067230202, + -0.059445001 -0.00137125 0.0336955, + -0.059757002 0.0006273 0.0308761, + -0.059757002 0.00171342 0.0327865, + -0.059445001 -9.7621392e-005 0.0357516, + -0.058998398 -0.0044891699 0.0346145, + -0.058998398 -0.00324262 0.036796801, + -0.059445001 -0.00329723 0.0295338, + -0.059757002 -0.00441236 0.019179501, + -0.059757002 -0.0039599799 0.020299099, + -0.059445001 -0.0024208699 0.031663299, + -0.059445001 -0.0050254902 0.0250418, + -0.058998398 -0.0055018901 0.032458801, + -0.059999999 0.00158166 0.0199656, + -0.0599402 0.0026705801 0.028214, + -0.0599402 0.00363521 0.030099399, + -0.059999999 0.0036108301 0.023813, + -0.059999999 0.0077777798 0.0309991, + -0.059999999 0.0066198702 0.0293287, + -0.059999999 0.00052374101 0.0177081, + -0.0599402 -0.0021895 0.0177691, + -0.0599402 -0.00165337 0.019070501, + -0.059999999 0.00108433 0.018962501, + -0.059999999 0.00028193899 0.016956, + -0.058412101 0.0089660203 0.051564001, + -0.0576833 0.0089230398 0.0547642, + -0.0576833 0.0058884001 0.053466301, + -0.058412101 0.0119524 0.052762602, + -0.058412101 0.0061237598 0.050116699, + -0.058998398 0.0120364 0.049666099, + -0.058998398 0.0092355097 0.048325699, + -0.055787299 -0.0046179299 0.054510299, + -0.050219599 -0.00172608 0.069216304, + -0.050219599 7.5080592e-005 0.069704503, + -0.051830001 0.00099114701 0.067190997, + -0.051830001 -0.000768503 0.0666577, + -0.050219599 -0.0035129699 0.068645701, + -0.048467699 -0.0043674698 0.071185, + -0.048467699 -0.00253916 0.071707599, + -0.0165099 -0.050176602 0.069143899, + -0.0137106 -0.049724098 0.071513399, + -0.0109179 -0.050388701 0.071840197, + 0.027557701 -0.0042692199 0.089065701, + 0.027557701 -0.00207904 0.089250103, + 0.0302257 -0.0028947601 0.087781399, + 0.0302257 -0.0050580399 0.0875737, + 0.027557701 -0.0064515499 0.088844202, + 0.0248404 -0.00550659 0.090221897, + 0.0302257 -0.00072390499 0.087952502, + 0.0328326 -0.00138506 0.086370699, + 0.035366699 -0.00186236 0.0846598, + 0.0378174 -0.0042372602 0.082606599, + 0.040174201 -0.00227051 0.080898799, + 0.035366699 0.0130915 0.085118398, + 0.0328326 0.0115914 0.086741298, + -0.0081421202 0.0013911 0.095253304, + -0.0081421202 0.0059951101 0.095286697, + -0.0109179 0.00177964 0.094843604, + -0.0053918599 0.0011196299 0.095539503, + -0.0081421202 -0.00319868 0.0950564, + -0.0053918599 0.0057322402 0.095577702, + -0.0109179 -0.00279809 0.094653897, + -0.0248404 0.00336118 0.090781197, + -0.0220857 0.0045733401 0.091896102, + -0.0220857 8.2635095e-005 0.091758803, + -0.019305199 -0.00083417603 0.092680298, + -0.019305199 0.00142298 0.092777297, + -0.0220857 0.002326 0.091847301, + -0.0220857 -0.0043883501 0.091462597, + -0.019305199 -0.0053322199 0.092366301, + -0.019305199 -0.00308623 0.092543297, + -0.0220857 -0.0021558199 0.091630504, + -0.0220857 -0.0066138399 0.0912553, + -0.0248404 -0.0033063199 0.090426497, + -0.0248404 -0.0055165798 0.090229802, + -0.035366699 -0.0199729 0.080567501, + -0.0378174 -0.0217724 0.077311203, + -0.035366699 -0.025658 0.077612102, + -0.0328326 -0.027553501 0.078864299, + -0.035366699 -0.027475899 0.076440804, + -0.0378174 -0.0236158 0.076263003, + -0.0378174 -0.025417 0.075124599, + -0.035366699 -0.0326006 0.072404601, + -0.0378174 -0.030498 0.0711945, + -0.035366699 -0.030953599 0.0738336, + -0.0328326 -0.034552202 0.073527701, + -0.035366699 -0.034178399 0.070898302, + -0.0378174 -0.032063801 0.069726102, + -0.0328326 -0.032892801 0.074990697, + -0.0302257 -0.0114711 0.086746097, + -0.027557701 -0.0107979 0.088301398, + -0.0302257 -0.0093684001 0.087059997, + -0.0328326 -0.00988096 0.0853986, + -0.0328326 -0.0056771799 0.085958898, + -0.0302257 -0.0050724898 0.087582603, + -0.0328326 -0.0035431201 0.086187698, + -0.0302257 -0.0072271102 0.087338403, + -0.0328326 -0.0077980701 0.085696302, + -0.035366699 -0.0180225 0.081362098, + -0.0328326 -0.019848499 0.082722902, + -0.0302257 -0.019522401 0.084719397, + -0.0424264 0.00385872 0.079437204, + -0.027557701 -0.028975699 0.082222998, + -0.0302257 -0.0274032 0.0811508, + -0.027557701 -0.027031099 0.083285399, + -0.0248404 -0.030391101 0.083187997, + -0.027557701 -0.0308821 0.081063002, + -0.0302257 -0.0292958 0.080015302, + -0.0248404 -0.028433699 0.084271498, + -0.040174201 -0.032690302 0.065412298, + -0.0378174 -0.036301099 0.064914301, + -0.0378174 -0.03497 0.0665804, + -0.044564299 -0.0248864 0.065747, + -0.044564299 -0.0263429 0.064339198, + -0.0424264 -0.027409799 0.067146003, + -0.044564299 -0.0233612 0.067087002, + -0.0424264 -0.0258704 0.0685312, + -0.0465803 -0.0222457 0.064283103, + -0.0465803 -0.023689101 0.062923998, + -0.035366699 -0.0396934 0.064206101, + -0.0378174 -0.037546001 0.0631947, + -0.040174201 -0.035252299 0.062114298, + -0.040174201 -0.034013402 0.063789703, + -0.0424264 -0.031587601 0.062597103, + -0.040174201 -0.040089 0.0531778, + -0.0378174 -0.041607 0.055914499, + -0.0378174 -0.016055301 0.079896003, + -0.0378174 -0.014107 0.080570497, + -0.0378174 -0.017985901 0.079128496, + -0.0378174 -0.0198934 0.078267001, + -0.0465803 -0.0032021201 0.074114896, + -0.0465803 -0.0123727 0.0709012, + -0.044564299 0.0019980201 0.077189296, + -0.051830001 0.0098620104 0.068667002, + -0.051830001 0.00809965 0.068526, + -0.048467699 0.0066863499 0.073118001, + -0.050219599 0.0091577796 0.070971802, + -0.048467699 0.0105645 0.0733217, + -0.0465803 0.0082365898 0.075444698, + -0.050219599 0.0072878301 0.070848599, + -0.0465803 0.0042963298 0.075193398, + -0.0465803 0.00236549 0.075020202, + -0.048467699 0.0047854399 0.072969303, + -0.050219599 0.00549642 0.070680201, + -0.027557701 0.0156109 0.089332096, + -0.0248404 0.016772401 0.090423398, + -0.027557701 0.0178279 0.0891646, + -0.0302257 0.016804401 0.087943196, + -0.0302257 0.014607 0.088081397, + -0.0248404 0.0145365 0.090582199, + -0.0220857 0.0135829 0.091691799, + -0.027557701 -0.0020872201 0.089259297, + -0.0248404 -0.00108919 0.090584204, + -0.0248404 0.00113365 0.0907024, + -0.035366699 0.0045093298 0.085091703, + -0.0248404 0.0055925399 0.090820603, + -0.0220857 0.0090759797 0.091873899, + -0.0220857 0.0113294 0.091802798, + -0.0248404 0.0078266701 0.090820499, + -0.0220857 0.0068236399 0.091904998, + -0.019305199 0.00821527 0.092827499, + 0.0081421202 -0.057682499 0.057273999, + 0.0109179 -0.057718899 0.054908901, + 0.0109179 -0.057174101 0.057095699, + 0.0081421202 -0.058225799 0.055077001, + 0.0081421202 -0.057032902 0.059464701, + 0.0053918599 -0.058037899 0.057398599, + 0.0053918599 -0.0573892 0.059596501, + -0.0465803 0.16638801 -0.035567202, + -0.0465803 0.1638 -0.035406802, + -0.044564299 0.166486 -0.037923399, + -0.0465803 0.168965 -0.035658501, + -0.044564299 0.16901501 -0.038014799, + -0.048467699 0.16628499 -0.033116899, + -0.048467699 0.163647 -0.032956399, + 0.059445001 -0.0050261701 0.025038401, + 0.059757002 -0.0044084499 0.019159099, + 0.059445001 -0.0067743598 0.020463601, + 0.059445001 -0.0032977201 0.0295336, + 0.058998398 -0.0054968102 0.032435801, + 0.059445001 -7.0618589e-005 0.035758201, + 0.058998398 -0.0044700601 0.0346101, + 0.058998398 -0.0032158301 0.036803301, + 0.0220857 -0.051229801 0.062090199, + 0.0220857 -0.050258201 0.064139098, + 0.019305199 -0.051425301 0.0646412, + 0.019305199 -0.052397098 0.062568903, + 0.0220857 -0.052097902 0.0600143, + 0.0248404 -0.049891599 0.061541501, + 0.0248404 -0.0507605 0.059492499, + 0.0328326 -0.045742001 0.057534099, + 0.035366699 -0.0437424 0.056753699, + 0.0328326 -0.044870201 0.059482198, + 0.0302257 -0.047580302 0.0582514, + 0.0328326 -0.046514999 0.055567399, + 0.035366699 -0.044518199 0.054827299, + 0.0302257 -0.0467095 0.060236499, + 0.0599402 0.00765137 0.035486799, + 0.0599402 0.0094052702 0.0372205, + 0.059999999 0.0107146 0.034350999, + 0.059999999 0.0091581997 0.0326914, + 0.0599402 0.0061114701 0.033703901, + 0.059757002 0.0045643998 0.036631301, + 0.059757002 0.0063120602 0.0384892, + 0.0599402 0.00364039 0.0300761, + 0.059757002 0.00173278 0.032782, + 0.0599402 0.0026701 0.028213801, + 0.059445001 -0.0024157299 0.031640101, + 0.059445001 -0.00135199 0.033691101, + 0.059757002 0.0238958 0.0474553, + 0.059757002 0.020967901 0.0467894, + 0.059445001 0.0209774 0.049507901, + 0.059757002 0.026879599 0.047878198, + 0.059445001 0.0240178 0.050011501, + 0.0599402 0.0267756 0.0454299, + 0.0599402 0.023899799 0.044852, + 0.058998398 0.033818401 0.0521238, + 0.058998398 0.030549901 0.0523993, + 0.059445001 0.033256602 0.050048899, + 0.059445001 0.036455002 0.049719501, + 0.058998398 0.0370849 0.051747698, + 0.058412101 0.034504201 0.054218899, + 0.058412101 0.031165 0.054543499, + 0.0302257 0.0102124 0.088233098, + 0.0532961 0.0055219298 0.065517999, + 0.0546159 0.0066124802 0.062986597, + 0.0546159 0.0134757 0.064066499, + 0.0532961 0.0143192 0.066493303, + 0.0546159 0.016969699 0.064191699, + 0.051830001 0.0117167 0.068753302, + 0.050219599 0.0091736903 0.070961297, + 0.0532961 0.0107623 0.066312201, + -0.055787299 -0.0059732101 0.053475399, + -0.055787299 -0.0072696302 0.052386601, + -0.0546159 -0.0103851 0.053982999, + -0.0546159 -0.00907546 0.055129901, + -0.0532961 -0.0121355 0.056761999, + -0.051830001 -0.0137391 0.059567198, + -0.0137106 -0.052186299 0.067504101, + -0.0137106 -0.051005401 0.069534197, + -0.0165099 -0.051355898 0.067129903, + -0.0137106 -0.0532635 0.065430298, + -0.0165099 -0.052432202 0.065072604, + -0.0109179 -0.052854002 0.067805, + -0.0109179 -0.051671699 0.069848202, + 0.0220857 -0.0021513 0.091623098, + 0.0248404 -0.0032989299 0.090418302, + 0.0220857 -0.0043818201 0.091455199, + 0.0248404 -0.00108408 0.090575904, + 0.0220857 8.5569904e-005 0.091751501, + 0.019305199 -0.00083160802 0.092673898, + 0.019305199 -0.0053264801 0.0923599, + 0.027557701 0.000118178 0.089396, + 0.0248404 0.00113695 0.090694197, + 0.0248404 0.0033631399 0.090773404, + 0.0328326 0.00076456601 0.086526997, + -0.0328326 -0.0237615 0.080986597, + -0.035366699 -0.021899501 0.0796775, + -0.0328326 -0.021817001 0.081903197, + -0.0302257 -0.025473099 0.082189903, + -0.0328326 -0.0256759 0.079973102, + -0.035366699 -0.023796899 0.078691699, + -0.0302257 -0.0235123 0.083130799, + -0.0328326 -0.015860699 0.084075503, + -0.035366699 -0.0140725 0.082668498, + -0.0328326 -0.0138555 0.084609598, + -0.0328326 -0.0178612 0.083446696, + -0.0302257 -0.017504301 0.0853687, + -0.035366699 -0.0160539 0.082062103, + -0.0302257 -0.0154813 0.085922197, + -0.035366699 -0.0081510702 0.083932497, + -0.0378174 -0.039764199 0.059621099, + -0.035366699 -0.040852901 0.062397402, + -0.035366699 -0.041917901 0.060547799, + -0.0378174 -0.0387014 0.0614281, + -0.0378174 -0.040732998 0.057780799, + -0.044564299 -0.031398699 0.058137801, + -0.0424264 -0.0328198 0.060968701, + -0.044564299 -0.030257201 0.059761699, + -0.0465803 -0.028712001 0.056927498, + -0.0465803 -0.029764 0.055318099, + -0.040174201 -0.037463602 0.0586311, + -0.040174201 -0.036403298 0.0603926, + -0.0424264 -0.033966199 0.059294701, + -0.040174201 -0.039307199 0.055016499, + -0.040174201 -0.038431801 0.056836698, + -0.0424264 -0.0098218601 0.077287503, + -0.040174201 -0.0120273 0.078977101, + -0.044564299 -0.00937826 0.074919701, + -0.0424264 -0.00598722 0.078257203, + -0.044564299 -0.00371329 0.076421201, + -0.0424264 -0.0079063596 0.077816598, + -0.044564299 -0.00560755 0.076007701, + -0.044564299 -0.0018348499 0.076747201, + -0.044564299 3.8332291e-005 0.076992303, + -0.040174201 -0.021434501 0.0748218, + -0.0465803 -0.0141341 0.069998696, + -0.040174201 -0.0196098 0.075836502, + -0.0328326 0.0137657 0.0866777, + -0.035366699 0.013091 0.085127898, + -0.035366699 0.0109418 0.085175499, + -0.027557701 0.0133927 0.089460202, + -0.0248404 0.0100627 0.090780601, + -0.0248404 0.0122997 0.0907012, + -0.048467699 0.0011403901 0.0725023, + -0.0465803 -0.00133389 0.074500099, + -0.0465803 0.00051856402 0.074799597, + -0.048467699 0.00296582 0.0727745, + -0.048467699 -0.00070072903 0.072146498, + -0.050219599 0.0036989099 0.070436597, + -0.050219599 0.0018858199 0.070111103, + -0.0302257 0.00144755 0.088095501, + -0.027557701 0.0023177599 0.089512199, + -0.027557701 0.00011255401 0.089405201, + -0.0302257 -0.00073288498 0.087962396, + -0.0328326 0.0029140001 0.086656801, + -0.0328326 0.00075479102 0.086538002, + 0.0599402 -0.00117393 0.0201266, + 0.059757002 -0.00029395401 0.028869299, + 0.0599402 -0.00164945 0.019050101, + 0.059999999 0.00108828 0.018942, + 0.0599402 0.00075900799 0.024215201, + 0.059757002 0.00063247501 0.030852901, + 0.027557701 0.0089570703 0.089591198, + 0.0248404 0.0055935201 0.090813302, + 0.051830001 0.00633022 0.068300799, + 0.0532961 0.0090238899 0.066125497, + 0.051830001 0.0080980901 0.068517298, + 0.051830001 0.00454885 0.068003699, + 0.050219599 0.0036982801 0.070426203, + 0.0532961 0.0072720801 0.065860398, + 0.050219599 0.0054949098 0.070671901, + -0.0532961 -0.00930476 0.058996901, + -0.0546159 -0.0077047399 0.056221701, + -0.0546159 -0.0062772199 0.0572543, + -0.0532961 -0.0107496 0.057909802, + -0.0532961 -0.00780576 0.0600194, + -0.051830001 -0.0122773 0.0607077, + -0.051830001 -0.0107595 0.0617822, + 0.0302257 0.0080175595 0.0882539, + 0.027557701 0.00674188 0.089600801, + 0.035366699 0.00879726 0.085174203, + 0.035366699 0.0066547301 0.085145801, + 0.0378174 0.0083485702 0.083442599, + 0.0378174 0.0125855 0.083431304, + 0.035366699 0.0109432 0.085165098, + 0.0328326 0.0072488398 0.0867697, + 0.0328326 0.0094187902 0.086774498, + 0.0378174 0.00412816 0.083306096, + 0.0378174 0.0062358198 0.083392799, + 0.040174201 0.00599143 0.081521899, + 0.035366699 0.0045165699 0.085079797, + 0.035366699 0.00238379 0.084976502, + 0.0378174 -6.861279e-005 0.083024301, + 0.035366699 0.00025724599 0.084836103, + 0.040174201 0.00184733 0.081277303, + -0.0378174 -0.0101811 0.081643097, + -0.040174201 -0.0081456397 0.079999797, + -0.0378174 -0.0082320496 0.082041003, + -0.0378174 -0.0121461 0.0811527, + -0.035366699 -0.0120866 0.083181597, + -0.040174201 -0.0100884 0.079533599, + -0.035366699 -0.0101168 0.083600603, + -0.035366699 -0.0039910199 0.084458202, + -0.035366699 -0.0060897302 0.084212698, + -0.040174201 -0.0139541 0.078330003, + -0.0424264 -0.0117258 0.076669298, + -0.044564299 -0.0112419 0.074244, + -0.044564299 -0.018428501 0.070656396, + -0.044564299 -0.016684201 0.071683504, + -0.0465803 -0.015857499 0.069012597, + -0.0465803 -0.0175361 0.067944802, + -0.044564299 -0.0201269 0.069545999, + -0.0424264 -0.020885499 0.072227404, + -0.0424264 -0.0191213 0.073293597, + -0.0424264 -0.0154784 0.0751625, + -0.044564299 -0.0149007 0.072625197, + -0.044564299 -0.0130845 0.073479198, + -0.0424264 -0.0173166 0.0742727, + -0.0424264 -0.013613 0.075961299, + -0.040174201 -0.0177506 0.0767603, + -0.040174201 -0.015863599 0.077591397, + -0.0302257 0.0036331799 0.0881899, + -0.027557701 0.0045274901 0.089580096, + -0.027557701 0.0067407801 0.0896089, + -0.0302257 0.010212 0.088241197, + -0.0328326 0.0115909 0.086750098, + -0.0302257 0.0124092 0.088180698, + -0.027557701 0.0089567099 0.089598604, + -0.027557701 0.0111743 0.089548901, + 0.055787299 0.0128574 0.0614646, + 0.0546159 0.0083252396 0.063369699, + 0.055787299 0.0094839903 0.0608459, + 0.0546159 0.0100456 0.063677497, + 0.055787299 0.0162265 0.061789699, + 0.056809202 0.0156953 0.059230901, + 0.0546159 0.0117673 0.063910097, + 0.056809202 0.0123823 0.058685299, + 0.0302257 0.00363718 0.088179998, + 0.0302257 0.00582546 0.088236302, + 0.0328326 0.0050824601 0.0867268, + 0.0328326 0.00292073 0.086645901, + 0.0302257 0.00145372 0.088085398, + 0.027557701 0.00232143 0.089503199, + 0.027557701 0.0045296601 0.089571401, + -0.0378174 -0.0062873801 0.082353197, + -0.040174201 -0.0062188199 0.080375001, + -0.0424264 -0.00408393 0.078608401, + -0.044564299 -0.033420499 0.0547809, + -0.0424264 -0.035991501 0.055835601, + -0.0424264 -0.035023902 0.057581302, + -0.044564299 -0.0324536 0.056475401, + -0.0465803 -0.0307303 0.053677201, + -0.0465803 -0.031610101 0.0520114, + -0.044564299 -0.035087701 0.051323101, + -0.0424264 -0.0368683 0.0540644, + -0.0424264 -0.037653401 0.052274499, + -0.044564299 -0.034298901 0.053061198, + -0.044564299 -0.0357867 0.049573001, + -0.0465803 -0.032402799 0.050327402, + -0.0465803 -0.033107799 0.048631299, + -0.0328326 0.00724624 0.086779997, + -0.0302257 0.0058231 0.088245802, + -0.0328326 0.0050781202 0.086737603, + -0.035366699 0.0087944698 0.085185297, + -0.0328326 0.0094175003 0.086784102, + -0.0302257 0.00801636 0.088262796, + -0.035366699 0.0066500199 0.085157402, + -0.040174201 -0.00228324 0.080907099, + -0.040174201 -0.0042966502 0.080666102, + -0.0378174 -0.00424923 0.082614399, + -0.0378174 -8.6688691e-005 0.083035499, + -0.040174201 0.00182812 0.081289098, + -0.0424264 -0.00019842001 0.079096697, + -0.0424264 -0.0021856099 0.078877099 ] + + } + coordIndex [ 17, 143, 71, -1, 511, 55, 63, -1, + 14, 72, 71, -1, 69, 21, 22, -1, + 69, 22, 560, -1, 80, 21, 1058, -1, + 80, 22, 21, -1, 89, 249, 24, -1, + 57, 340, 24, -1, 92, 249, 89, -1, + 32, 827, 2193, -1, 855, 2193, 376, -1, + 1580, 849, 376, -1, 2086, 34, 2637, -1, + 2086, 722, 34, -1, 300, 79, 24, -1, + 6, 137, 24, -1, 1602, 672, 419, -1, + 559, 69, 560, -1, 222, 69, 559, -1, + 68, 14, 71, -1, 68, 21, 69, -1, + 68, 79, 21, -1, 68, 71, 63, -1, + 68, 63, 55, -1, 68, 55, 57, -1, + 3, 143, 17, -1, 3, 76, 143, -1, + 577, 1058, 21, -1, 78, 21, 79, -1, + 4, 560, 22, -1, 4, 66, 560, -1, + 4, 1774, 66, -1, 332, 24, 340, -1, + 332, 89, 24, -1, 118, 800, 99, -1, + 181, 99, 180, -1, 359, 118, 30, -1, + 359, 800, 118, -1, 5, 819, 341, -1, + 5, 117, 819, -1, 1509, 340, 2214, -1, + 1509, 2214, 824, -1, 1509, 812, 340, -1, + 33, 32, 2193, -1, 854, 376, 849, -1, + 854, 855, 376, -1, 2084, 2086, 2637, -1, + 386, 301, 300, -1, 386, 24, 137, -1, + 386, 300, 24, -1, 549, 550, 64, -1, + 7, 170, 1, -1, 7, 172, 170, -1, + 7, 36, 172, -1, 7, 64, 550, -1, + 7, 1, 64, -1, 40, 63, 71, -1, + 40, 71, 143, -1, 414, 413, 401, -1, + 414, 1605, 1602, -1, 414, 406, 1605, -1, + 164, 446, 1611, -1, 164, 1645, 1646, -1, + 0, 169, 63, -1, 0, 170, 169, -1, + 0, 1, 170, -1, 0, 63, 64, -1, + 0, 64, 1, -1, 1050, 13, 61, -1, + 219, 72, 14, -1, 568, 14, 68, -1, + 2, 79, 68, -1, 2, 68, 57, -1, + 2, 24, 79, -1, 2, 57, 24, -1, + 16, 17, 71, -1, 554, 16, 71, -1, + 554, 2357, 16, -1, 551, 76, 18, -1, + 225, 18, 76, -1, 225, 76, 3, -1, + 225, 3, 17, -1, 225, 17, 226, -1, + 20, 577, 21, -1, 20, 578, 577, -1, + 1775, 66, 1774, -1, 2366, 2372, 22, -1, + 2370, 4, 22, -1, 2370, 22, 2372, -1, + 2370, 1774, 4, -1, 83, 335, 86, -1, + 83, 86, 89, -1, 85, 86, 335, -1, + 91, 89, 86, -1, 328, 99, 800, -1, + 328, 57, 56, -1, 328, 340, 57, -1, + 328, 2214, 340, -1, 328, 5, 341, -1, + 328, 117, 5, -1, 87, 1866, 245, -1, + 87, 863, 1866, -1, 87, 864, 863, -1, + 25, 6, 24, -1, 25, 24, 253, -1, + 25, 96, 6, -1, 95, 24, 93, -1, + 248, 249, 244, -1, 248, 244, 611, -1, + 247, 24, 249, -1, 247, 93, 24, -1, + 1935, 118, 99, -1, 473, 99, 181, -1, + 45, 48, 422, -1, 45, 42, 146, -1, + 45, 146, 413, -1, 45, 413, 46, -1, + 411, 672, 1602, -1, 263, 666, 649, -1, + 100, 109, 404, -1, 271, 269, 645, -1, + 667, 649, 666, -1, 316, 1477, 1525, -1, + 27, 800, 359, -1, 837, 359, 30, -1, + 623, 621, 118, -1, 623, 1935, 256, -1, + 623, 118, 1935, -1, 336, 864, 85, -1, + 336, 85, 335, -1, 135, 864, 125, -1, + 126, 125, 864, -1, 343, 344, 864, -1, + 1498, 123, 341, -1, 122, 341, 123, -1, + 122, 328, 341, -1, 122, 2214, 328, -1, + 363, 824, 2214, -1, 373, 376, 2193, -1, + 2749, 2193, 855, -1, 2749, 33, 2193, -1, + 2749, 855, 2748, -1, 306, 79, 34, -1, + 306, 378, 79, -1, 387, 715, 301, -1, + 387, 301, 386, -1, 35, 6, 96, -1, + 35, 137, 6, -1, 1345, 303, 2637, -1, + 1345, 2637, 34, -1, 1345, 34, 79, -1, + 1345, 79, 300, -1, 214, 547, 36, -1, + 214, 7, 550, -1, 214, 36, 7, -1, + 389, 547, 390, -1, 545, 547, 213, -1, + 38, 390, 547, -1, 142, 143, 19, -1, + 41, 40, 143, -1, 39, 61, 13, -1, + 39, 13, 40, -1, 399, 9, 413, -1, + 8, 401, 413, -1, 8, 413, 9, -1, + 8, 399, 401, -1, 8, 9, 399, -1, + 145, 146, 42, -1, 416, 1602, 419, -1, + 416, 414, 1602, -1, 44, 406, 414, -1, + 10, 46, 413, -1, 10, 413, 50, -1, + 10, 50, 46, -1, 953, 104, 888, -1, + 428, 956, 423, -1, 428, 423, 413, -1, + 437, 944, 933, -1, 437, 936, 165, -1, + 52, 165, 964, -1, 52, 964, 51, -1, + 52, 51, 921, -1, 1643, 164, 936, -1, + 167, 53, 511, -1, 167, 11, 53, -1, + 167, 511, 63, -1, 167, 63, 169, -1, + 177, 53, 11, -1, 177, 11, 167, -1, + 196, 12, 194, -1, 392, 390, 12, -1, + 392, 196, 393, -1, 392, 12, 196, -1, + 174, 511, 53, -1, 174, 178, 511, -1, + 1007, 1089, 1090, -1, 195, 194, 12, -1, + 195, 12, 390, -1, 1710, 525, 390, -1, + 1710, 390, 1694, -1, 1710, 1694, 1711, -1, + 1017, 530, 1028, -1, 1017, 512, 530, -1, + 533, 1667, 453, -1, 533, 453, 183, -1, + 139, 140, 202, -1, 139, 390, 37, -1, + 1728, 202, 140, -1, 1728, 140, 535, -1, + 74, 1005, 537, -1, 74, 1007, 1005, -1, + 62, 1050, 61, -1, 62, 545, 213, -1, + 215, 13, 1050, -1, 215, 63, 40, -1, + 215, 40, 13, -1, 2820, 547, 142, -1, + 73, 72, 219, -1, 67, 219, 14, -1, + 67, 14, 568, -1, 1783, 68, 69, -1, + 1764, 554, 71, -1, 15, 16, 2357, -1, + 15, 2357, 226, -1, 15, 17, 16, -1, + 15, 226, 17, -1, 224, 551, 18, -1, + 224, 18, 225, -1, 1747, 19, 143, -1, + 1747, 142, 19, -1, 1747, 1748, 142, -1, + 77, 578, 20, -1, 77, 78, 229, -1, + 77, 21, 78, -1, 77, 20, 21, -1, + 380, 79, 378, -1, 2368, 22, 80, -1, + 2368, 2366, 22, -1, 82, 335, 83, -1, + 90, 91, 86, -1, 90, 87, 245, -1, + 327, 328, 800, -1, 241, 249, 92, -1, + 241, 244, 249, -1, 246, 245, 1866, -1, + 94, 250, 95, -1, 94, 95, 93, -1, + 23, 253, 24, -1, 23, 24, 95, -1, + 23, 95, 253, -1, 599, 1157, 596, -1, + 254, 25, 253, -1, 254, 96, 25, -1, + 1169, 1935, 99, -1, 105, 45, 422, -1, + 105, 42, 45, -1, 105, 100, 42, -1, + 110, 109, 101, -1, 110, 101, 755, -1, + 110, 755, 756, -1, 633, 2209, 324, -1, + 275, 666, 263, -1, 275, 262, 278, -1, + 650, 263, 649, -1, 268, 264, 270, -1, + 272, 110, 756, -1, 151, 273, 150, -1, + 151, 272, 273, -1, 630, 2208, 2209, -1, + 669, 271, 667, -1, 289, 304, 307, -1, + 289, 26, 1991, -1, 289, 307, 26, -1, + 2078, 2637, 303, -1, 1368, 1991, 26, -1, + 1368, 26, 732, -1, 734, 26, 307, -1, + 734, 732, 26, -1, 2670, 2669, 748, -1, + 2106, 745, 115, -1, 2106, 115, 310, -1, + 2687, 753, 426, -1, 2158, 3153, 1173, -1, + 321, 782, 1197, -1, 418, 323, 155, -1, + 418, 419, 672, -1, 330, 359, 1535, -1, + 330, 27, 359, -1, 799, 27, 330, -1, + 799, 800, 27, -1, 119, 627, 30, -1, + 119, 30, 118, -1, 119, 118, 28, -1, + 131, 836, 30, -1, 131, 30, 627, -1, + 625, 28, 118, -1, 625, 119, 28, -1, + 29, 30, 836, -1, 29, 837, 30, -1, + 29, 836, 837, -1, 31, 864, 344, -1, + 31, 126, 864, -1, 334, 335, 82, -1, + 334, 82, 332, -1, 805, 864, 336, -1, + 121, 824, 363, -1, 121, 826, 824, -1, + 1567, 363, 2214, -1, 2215, 2214, 122, -1, + 2222, 122, 123, -1, 124, 1506, 821, -1, + 124, 344, 1506, -1, 124, 31, 344, -1, + 124, 126, 31, -1, 1513, 1509, 824, -1, + 136, 135, 125, -1, 136, 825, 134, -1, + 2191, 373, 2193, -1, 358, 827, 32, -1, + 358, 32, 1556, -1, 358, 1477, 827, -1, + 2747, 1556, 32, -1, 2747, 32, 33, -1, + 2747, 33, 2749, -1, 133, 864, 369, -1, + 850, 849, 1580, -1, 364, 369, 1568, -1, + 364, 365, 1580, -1, 364, 1580, 369, -1, + 367, 864, 135, -1, 367, 369, 864, -1, + 374, 375, 376, -1, 231, 584, 377, -1, + 231, 235, 232, -1, 721, 34, 722, -1, + 721, 306, 34, -1, 723, 378, 306, -1, + 383, 384, 137, -1, 383, 137, 35, -1, + 383, 35, 96, -1, 138, 36, 547, -1, + 138, 547, 389, -1, 138, 172, 36, -1, + 138, 175, 172, -1, 877, 547, 216, -1, + 877, 38, 547, -1, 396, 37, 390, -1, + 396, 390, 38, -1, 396, 38, 877, -1, + 396, 139, 37, -1, 210, 142, 547, -1, + 144, 41, 143, -1, 144, 211, 41, -1, + 144, 210, 211, -1, 144, 142, 210, -1, + 209, 39, 40, -1, 209, 41, 211, -1, + 209, 40, 41, -1, 209, 61, 39, -1, + 398, 413, 146, -1, 398, 399, 413, -1, + 403, 145, 42, -1, 403, 100, 404, -1, + 403, 42, 100, -1, 403, 1604, 145, -1, + 2239, 411, 1602, -1, 793, 1922, 1166, -1, + 158, 893, 325, -1, 158, 972, 1610, -1, + 158, 1610, 893, -1, 43, 1604, 406, -1, + 43, 406, 44, -1, 43, 44, 414, -1, + 43, 145, 1604, -1, 43, 414, 145, -1, + 49, 48, 45, -1, 49, 45, 46, -1, + 49, 46, 50, -1, 47, 422, 48, -1, + 47, 423, 422, -1, 47, 48, 49, -1, + 47, 49, 50, -1, 47, 50, 413, -1, + 47, 413, 423, -1, 421, 888, 422, -1, + 890, 423, 956, -1, 890, 956, 445, -1, + 890, 445, 953, -1, 260, 953, 951, -1, + 260, 104, 953, -1, 427, 956, 428, -1, + 427, 446, 956, -1, 1259, 2283, 1253, -1, + 923, 914, 430, -1, 916, 918, 895, -1, + 1639, 926, 440, -1, 1639, 440, 1638, -1, + 159, 926, 927, -1, 159, 927, 930, -1, + 159, 930, 929, -1, 159, 929, 432, -1, + 161, 165, 52, -1, 435, 162, 921, -1, + 920, 964, 919, -1, 920, 51, 964, -1, + 920, 921, 51, -1, 943, 944, 161, -1, + 943, 161, 52, -1, 943, 921, 162, -1, + 943, 52, 921, -1, 1644, 1645, 164, -1, + 1644, 164, 1643, -1, 163, 164, 1646, -1, + 163, 1646, 1213, -1, 163, 446, 164, -1, + 760, 433, 759, -1, 760, 758, 676, -1, + 1699, 453, 967, -1, 458, 453, 1667, -1, + 451, 183, 453, -1, 451, 453, 452, -1, + 2303, 984, 1682, -1, 171, 167, 169, -1, + 171, 172, 175, -1, 176, 53, 177, -1, + 176, 174, 53, -1, 529, 178, 174, -1, + 529, 1031, 178, -1, 54, 511, 178, -1, + 54, 1033, 511, -1, 54, 178, 1033, -1, + 514, 464, 516, -1, 481, 475, 455, -1, + 481, 455, 985, -1, 481, 985, 986, -1, + 184, 478, 986, -1, 184, 1706, 478, -1, + 501, 496, 994, -1, 187, 499, 500, -1, + 436, 924, 187, -1, 436, 187, 500, -1, + 1075, 996, 572, -1, 997, 998, 1089, -1, + 997, 1089, 1007, -1, 997, 74, 996, -1, + 997, 1007, 74, -1, 190, 522, 192, -1, + 190, 192, 508, -1, 1717, 197, 1030, -1, + 1717, 511, 1033, -1, 507, 58, 1010, -1, + 507, 1012, 516, -1, 507, 1010, 1012, -1, + 507, 516, 464, -1, 507, 464, 465, -1, + 507, 465, 180, -1, 507, 55, 511, -1, + 507, 192, 58, -1, 507, 508, 192, -1, + 507, 180, 99, -1, 507, 99, 328, -1, + 507, 328, 56, -1, 507, 57, 55, -1, + 507, 56, 57, -1, 1009, 1010, 58, -1, + 191, 58, 192, -1, 191, 520, 58, -1, + 523, 192, 522, -1, 517, 58, 520, -1, + 517, 1009, 58, -1, 517, 959, 2799, -1, + 1656, 978, 1655, -1, 524, 390, 525, -1, + 524, 195, 390, -1, 527, 194, 1013, -1, + 527, 196, 194, -1, 462, 1712, 1711, -1, + 462, 1711, 1694, -1, 59, 918, 199, -1, + 59, 895, 918, -1, 200, 59, 199, -1, + 200, 895, 59, -1, 200, 1636, 1637, -1, + 200, 1637, 895, -1, 915, 916, 895, -1, + 915, 430, 914, -1, 532, 199, 918, -1, + 532, 918, 917, -1, 207, 1736, 1737, -1, + 207, 535, 140, -1, 60, 1694, 390, -1, + 60, 390, 139, -1, 60, 202, 1694, -1, + 60, 139, 202, -1, 484, 1047, 487, -1, + 1721, 1699, 1720, -1, 203, 1694, 202, -1, + 204, 1720, 1694, -1, 544, 62, 61, -1, + 544, 545, 62, -1, 544, 61, 209, -1, + 1052, 1050, 62, -1, 1052, 62, 213, -1, + 548, 63, 215, -1, 548, 64, 63, -1, + 548, 549, 64, -1, 875, 2820, 3230, -1, + 875, 216, 547, -1, 875, 547, 2820, -1, + 65, 142, 1748, -1, 65, 1748, 2820, -1, + 65, 2820, 142, -1, 2824, 76, 551, -1, + 218, 73, 219, -1, 218, 1765, 73, -1, + 1068, 560, 66, -1, 1068, 1775, 1067, -1, + 1068, 66, 1775, -1, 564, 567, 1842, -1, + 564, 1842, 2425, -1, 569, 67, 568, -1, + 569, 219, 67, -1, 563, 1071, 220, -1, + 1069, 568, 68, -1, 1069, 68, 1783, -1, + 221, 69, 222, -1, 221, 1783, 69, -1, + 223, 1064, 220, -1, 70, 1764, 71, -1, + 70, 1765, 1764, -1, 70, 71, 72, -1, + 70, 72, 73, -1, 70, 73, 1765, -1, + 536, 573, 572, -1, 536, 74, 537, -1, + 536, 572, 996, -1, 536, 996, 74, -1, + 1088, 1089, 998, -1, 227, 552, 551, -1, + 227, 551, 224, -1, 227, 2358, 1770, -1, + 227, 224, 2358, -1, 75, 143, 76, -1, + 75, 1747, 143, -1, 75, 76, 2824, -1, + 75, 2824, 1747, -1, 228, 578, 77, -1, + 228, 1592, 1225, -1, 228, 1225, 578, -1, + 228, 77, 229, -1, 379, 78, 79, -1, + 379, 79, 380, -1, 379, 229, 78, -1, + 2369, 2368, 80, -1, 2369, 80, 1058, -1, + 81, 89, 332, -1, 81, 332, 82, -1, + 81, 83, 89, -1, 81, 82, 83, -1, + 84, 86, 85, -1, 84, 90, 86, -1, + 84, 85, 864, -1, 84, 864, 87, -1, + 84, 87, 90, -1, 88, 243, 92, -1, + 88, 92, 89, -1, 88, 245, 243, -1, + 88, 90, 245, -1, 88, 89, 91, -1, + 88, 91, 90, -1, 590, 591, 246, -1, + 590, 246, 1866, -1, 585, 1121, 1120, -1, + 234, 1120, 1130, -1, 234, 1130, 1129, -1, + 234, 1129, 232, -1, 234, 232, 235, -1, + 593, 236, 591, -1, 240, 92, 243, -1, + 240, 241, 92, -1, 238, 591, 236, -1, + 598, 236, 597, -1, 598, 238, 236, -1, + 604, 246, 603, -1, 1449, 1450, 235, -1, + 1449, 231, 377, -1, 1449, 235, 231, -1, + 1151, 1150, 1163, -1, 610, 93, 247, -1, + 610, 94, 93, -1, 610, 250, 94, -1, + 252, 253, 95, -1, 252, 2485, 1153, -1, + 252, 95, 250, -1, 252, 250, 2485, -1, + 1145, 617, 615, -1, 618, 874, 613, -1, + 255, 96, 254, -1, 255, 383, 96, -1, + 97, 99, 473, -1, 97, 1168, 99, -1, + 97, 473, 2324, -1, 97, 2324, 1168, -1, + 98, 1169, 99, -1, 98, 99, 1168, -1, + 98, 1168, 1169, -1, 2326, 1168, 2324, -1, + 1686, 1685, 1166, -1, 1933, 256, 1935, -1, + 1929, 620, 1928, -1, 1929, 1923, 257, -1, + 1929, 257, 620, -1, 106, 100, 105, -1, + 106, 101, 109, -1, 106, 109, 100, -1, + 106, 103, 101, -1, 754, 101, 103, -1, + 754, 755, 101, -1, 259, 103, 104, -1, + 259, 104, 260, -1, 259, 753, 754, -1, + 259, 754, 103, -1, 102, 104, 103, -1, + 102, 422, 888, -1, 102, 888, 104, -1, + 102, 105, 422, -1, 102, 106, 105, -1, + 102, 103, 106, -1, 632, 324, 262, -1, + 632, 633, 324, -1, 277, 262, 324, -1, + 277, 278, 262, -1, 277, 324, 323, -1, + 277, 418, 672, -1, 277, 323, 418, -1, + 148, 264, 268, -1, 148, 150, 273, -1, + 637, 638, 108, -1, 107, 765, 267, -1, + 107, 638, 769, -1, 107, 768, 765, -1, + 107, 769, 768, -1, 266, 108, 638, -1, + 266, 638, 107, -1, 266, 107, 267, -1, + 265, 646, 108, -1, 265, 108, 266, -1, + 647, 108, 646, -1, 647, 637, 108, -1, + 647, 270, 637, -1, 652, 265, 1187, -1, + 652, 646, 265, -1, 1490, 640, 1491, -1, + 147, 272, 151, -1, 147, 404, 109, -1, + 147, 109, 110, -1, 147, 110, 272, -1, + 763, 762, 264, -1, 763, 264, 148, -1, + 763, 148, 273, -1, 781, 630, 629, -1, + 1198, 1197, 658, -1, 668, 276, 882, -1, + 884, 672, 411, -1, 675, 433, 760, -1, + 675, 760, 676, -1, 675, 938, 433, -1, + 675, 937, 938, -1, 280, 112, 279, -1, + 280, 111, 112, -1, 280, 1953, 111, -1, + 1958, 1591, 111, -1, 1958, 111, 1953, -1, + 1588, 1587, 112, -1, 1588, 112, 111, -1, + 1588, 111, 1591, -1, 113, 112, 1587, -1, + 113, 279, 112, -1, 113, 1228, 1226, -1, + 113, 1587, 1228, -1, 1243, 688, 1247, -1, + 1244, 1247, 281, -1, 1244, 686, 1245, -1, + 696, 1295, 683, -1, 696, 683, 1289, -1, + 696, 1284, 697, -1, 696, 1289, 1284, -1, + 1302, 295, 1301, -1, 682, 702, 1223, -1, + 706, 1292, 1305, -1, 2008, 1301, 295, -1, + 1234, 2009, 1306, -1, 114, 2017, 1309, -1, + 114, 293, 287, -1, 1308, 1309, 2017, -1, + 292, 114, 1309, -1, 292, 293, 114, -1, + 294, 703, 702, -1, 288, 287, 293, -1, + 288, 702, 682, -1, 288, 294, 702, -1, + 288, 293, 294, -1, 298, 680, 279, -1, + 298, 279, 113, -1, 298, 1226, 1227, -1, + 298, 113, 1226, -1, 2016, 287, 726, -1, + 2016, 114, 287, -1, 2016, 2017, 114, -1, + 2016, 726, 2091, -1, 1316, 2040, 708, -1, + 709, 745, 708, -1, 709, 708, 2040, -1, + 709, 115, 745, -1, 709, 1319, 115, -1, + 299, 382, 2604, -1, 299, 2604, 2060, -1, + 1344, 300, 302, -1, 1344, 1345, 300, -1, + 1347, 2078, 303, -1, 2636, 2637, 2078, -1, + 2014, 304, 305, -1, 2641, 722, 2086, -1, + 2641, 2642, 722, -1, 1404, 744, 1405, -1, + 2650, 309, 2651, -1, 741, 1318, 730, -1, + 2112, 2113, 1408, -1, 2112, 1408, 1399, -1, + 2112, 1399, 1401, -1, 1409, 2113, 2674, -1, + 2667, 310, 1171, -1, 2667, 2106, 310, -1, + 2133, 759, 2132, -1, 1174, 267, 765, -1, + 1174, 765, 1173, -1, 1174, 655, 267, -1, + 1452, 1446, 1455, -1, 711, 115, 1319, -1, + 711, 310, 115, -1, 772, 771, 834, -1, + 772, 834, 130, -1, 129, 774, 1475, -1, + 129, 311, 772, -1, 129, 772, 130, -1, + 129, 312, 311, -1, 129, 1475, 312, -1, + 317, 312, 1475, -1, 317, 316, 777, -1, + 318, 317, 1475, -1, 319, 312, 317, -1, + 319, 317, 777, -1, 319, 313, 312, -1, + 319, 1470, 313, -1, 319, 320, 1470, -1, + 1196, 1470, 320, -1, 1196, 321, 1197, -1, + 3329, 2705, 3330, -1, 353, 834, 771, -1, + 116, 784, 354, -1, 116, 771, 770, -1, + 116, 353, 771, -1, 116, 354, 353, -1, + 116, 785, 784, -1, 116, 770, 785, -1, + 349, 3328, 3330, -1, 349, 783, 3328, -1, + 2028, 710, 1321, -1, 788, 155, 323, -1, + 788, 326, 155, -1, 801, 327, 800, -1, + 797, 117, 328, -1, 797, 819, 117, -1, + 258, 118, 621, -1, 258, 625, 118, -1, + 624, 627, 119, -1, 624, 119, 625, -1, + 790, 839, 257, -1, 790, 257, 1923, -1, + 338, 340, 809, -1, 333, 332, 807, -1, + 333, 334, 332, -1, 804, 864, 805, -1, + 816, 817, 810, -1, 120, 363, 865, -1, + 120, 865, 121, -1, 120, 121, 363, -1, + 127, 121, 865, -1, 127, 826, 121, -1, + 818, 2215, 122, -1, 818, 2219, 2215, -1, + 818, 122, 2222, -1, 1503, 123, 1498, -1, + 1503, 2222, 123, -1, 1505, 815, 812, -1, + 128, 124, 821, -1, 128, 136, 125, -1, + 128, 125, 126, -1, 128, 126, 124, -1, + 3084, 2723, 134, -1, 3084, 134, 825, -1, + 866, 825, 826, -1, 866, 127, 865, -1, + 866, 826, 127, -1, 823, 1513, 824, -1, + 1515, 825, 136, -1, 1515, 128, 821, -1, + 1515, 136, 128, -1, 829, 373, 2191, -1, + 345, 827, 773, -1, 345, 773, 774, -1, + 345, 774, 350, -1, 351, 350, 774, -1, + 351, 774, 129, -1, 351, 129, 130, -1, + 351, 130, 834, -1, 2710, 832, 356, -1, + 2710, 356, 352, -1, 2710, 352, 2711, -1, + 2196, 834, 353, -1, 1517, 832, 1522, -1, + 1517, 356, 832, -1, 1524, 1525, 1477, -1, + 1524, 1477, 358, -1, 1537, 359, 837, -1, + 838, 836, 131, -1, 838, 131, 627, -1, + 853, 854, 849, -1, 132, 369, 361, -1, + 132, 133, 369, -1, 360, 133, 132, -1, + 360, 132, 361, -1, 861, 133, 360, -1, + 861, 360, 1111, -1, 861, 864, 133, -1, + 2448, 1884, 2439, -1, 362, 1580, 365, -1, + 362, 850, 1580, -1, 1569, 1568, 369, -1, + 1575, 364, 1568, -1, 366, 134, 2723, -1, + 366, 367, 135, -1, 366, 136, 134, -1, + 366, 135, 136, -1, 1574, 369, 367, -1, + 372, 373, 829, -1, 372, 830, 1582, -1, + 372, 829, 830, -1, 2233, 375, 374, -1, + 2233, 372, 1582, -1, 2233, 374, 372, -1, + 1584, 380, 378, -1, 381, 382, 299, -1, + 381, 1350, 1596, -1, 381, 299, 1350, -1, + 1920, 381, 1596, -1, 871, 137, 384, -1, + 871, 386, 137, -1, 391, 175, 138, -1, + 391, 138, 389, -1, 395, 139, 396, -1, + 395, 140, 139, -1, 395, 207, 140, -1, + 395, 1736, 207, -1, 141, 143, 142, -1, + 141, 144, 143, -1, 141, 142, 144, -1, + 400, 146, 145, -1, 400, 398, 146, -1, + 400, 414, 401, -1, 400, 145, 414, -1, + 402, 404, 147, -1, 402, 147, 151, -1, + 152, 154, 150, -1, 152, 150, 148, -1, + 152, 148, 268, -1, 152, 268, 269, -1, + 149, 150, 154, -1, 149, 1601, 402, -1, + 149, 410, 1601, -1, 149, 154, 410, -1, + 149, 151, 150, -1, 149, 402, 151, -1, + 153, 271, 669, -1, 153, 269, 271, -1, + 153, 152, 269, -1, 153, 154, 152, -1, + 408, 669, 882, -1, 408, 153, 669, -1, + 408, 410, 154, -1, 408, 154, 153, -1, + 407, 409, 411, -1, 156, 155, 326, -1, + 156, 326, 325, -1, 156, 325, 893, -1, + 417, 418, 155, -1, 417, 155, 156, -1, + 417, 893, 892, -1, 417, 156, 893, -1, + 157, 1685, 972, -1, 157, 972, 158, -1, + 157, 1166, 1685, -1, 157, 793, 1166, -1, + 157, 325, 793, -1, 157, 158, 325, -1, + 887, 888, 421, -1, 673, 260, 951, -1, + 673, 951, 1209, -1, 1609, 1611, 446, -1, + 1609, 446, 427, -1, 940, 1638, 440, -1, + 2245, 2280, 1631, -1, 2245, 1631, 2247, -1, + 2245, 2246, 3106, -1, 2245, 3106, 2280, -1, + 1260, 2282, 2283, -1, 1260, 2283, 1259, -1, + 906, 1642, 1641, -1, 910, 929, 3104, -1, + 910, 432, 929, -1, 910, 902, 432, -1, + 908, 2244, 2242, -1, 908, 909, 2244, -1, + 908, 2242, 902, -1, 908, 902, 910, -1, + 434, 923, 430, -1, 1622, 927, 1626, -1, + 1622, 930, 927, -1, 1622, 2776, 930, -1, + 438, 944, 948, -1, 442, 430, 1653, -1, + 442, 434, 430, -1, 441, 159, 432, -1, + 441, 440, 926, -1, 441, 926, 159, -1, + 160, 437, 165, -1, 160, 165, 161, -1, + 160, 944, 437, -1, 160, 161, 944, -1, + 947, 943, 162, -1, 947, 162, 435, -1, + 947, 435, 442, -1, 444, 447, 446, -1, + 444, 446, 163, -1, 444, 163, 1213, -1, + 955, 445, 956, -1, 449, 447, 1209, -1, + 449, 1209, 951, -1, 449, 951, 448, -1, + 968, 1699, 967, -1, 2790, 2319, 2318, -1, + 454, 1699, 1700, -1, 454, 453, 1699, -1, + 1659, 965, 970, -1, 1659, 970, 971, -1, + 457, 967, 453, -1, 457, 453, 458, -1, + 1665, 458, 1667, -1, 460, 165, 936, -1, + 460, 936, 164, -1, 460, 164, 1611, -1, + 460, 1611, 1688, -1, 1679, 964, 165, -1, + 1679, 165, 460, -1, 1697, 971, 984, -1, + 2315, 1712, 462, -1, 166, 177, 167, -1, + 166, 167, 171, -1, 166, 175, 177, -1, + 166, 171, 175, -1, 168, 169, 170, -1, + 168, 171, 169, -1, 168, 170, 172, -1, + 168, 172, 171, -1, 173, 393, 529, -1, + 173, 529, 174, -1, 173, 175, 391, -1, + 173, 391, 393, -1, 173, 174, 176, -1, + 173, 177, 175, -1, 173, 176, 177, -1, + 1032, 178, 1031, -1, 1032, 1033, 178, -1, + 961, 514, 2299, -1, 467, 469, 466, -1, + 179, 466, 469, -1, 179, 180, 465, -1, + 179, 465, 466, -1, 179, 980, 180, -1, + 179, 469, 980, -1, 982, 181, 180, -1, + 982, 472, 181, -1, 982, 180, 980, -1, + 471, 473, 181, -1, 471, 181, 472, -1, + 186, 492, 925, -1, 186, 931, 474, -1, + 186, 925, 1627, -1, 186, 1627, 931, -1, + 482, 1636, 200, -1, 182, 451, 455, -1, + 182, 455, 475, -1, 182, 533, 183, -1, + 182, 183, 451, -1, 182, 532, 533, -1, + 182, 475, 199, -1, 182, 199, 532, -1, + 479, 986, 478, -1, 479, 481, 986, -1, + 1703, 1706, 184, -1, 1703, 184, 986, -1, + 485, 1733, 499, -1, 486, 477, 478, -1, + 486, 478, 1706, -1, 185, 491, 492, -1, + 185, 474, 477, -1, 185, 477, 486, -1, + 185, 486, 491, -1, 185, 186, 474, -1, + 185, 492, 186, -1, 489, 485, 499, -1, + 489, 490, 485, -1, 489, 499, 187, -1, + 575, 1086, 497, -1, 575, 497, 498, -1, + 992, 497, 1086, -1, 992, 994, 496, -1, + 992, 496, 497, -1, 1085, 992, 1086, -1, + 990, 496, 501, -1, 493, 924, 925, -1, + 493, 187, 924, -1, 493, 925, 492, -1, + 493, 489, 187, -1, 188, 500, 501, -1, + 188, 436, 500, -1, 188, 501, 994, -1, + 188, 2772, 436, -1, 188, 2257, 2772, -1, + 188, 994, 2257, -1, 1859, 1789, 1801, -1, + 1004, 537, 1005, -1, 504, 508, 509, -1, + 504, 1017, 505, -1, 504, 509, 512, -1, + 504, 512, 1017, -1, 510, 512, 509, -1, + 189, 508, 503, -1, 189, 190, 508, -1, + 189, 503, 461, -1, 189, 522, 190, -1, + 189, 461, 522, -1, 515, 516, 1012, -1, + 515, 1012, 2299, -1, 519, 520, 191, -1, + 519, 191, 192, -1, 519, 192, 523, -1, + 521, 960, 959, -1, 521, 959, 520, -1, + 521, 975, 960, -1, 193, 520, 959, -1, + 193, 517, 520, -1, 193, 959, 517, -1, + 1014, 1013, 194, -1, 1014, 194, 195, -1, + 1014, 195, 524, -1, 1014, 524, 1015, -1, + 528, 196, 527, -1, 528, 393, 196, -1, + 528, 529, 393, -1, 1019, 527, 1013, -1, + 1715, 1030, 197, -1, 1715, 197, 1717, -1, + 1022, 505, 1017, -1, 1022, 1026, 505, -1, + 198, 199, 475, -1, 198, 200, 199, -1, + 198, 475, 482, -1, 198, 482, 200, -1, + 534, 532, 917, -1, 201, 207, 206, -1, + 201, 535, 207, -1, 201, 541, 535, -1, + 201, 206, 542, -1, 201, 542, 541, -1, + 1730, 202, 1728, -1, 1730, 203, 202, -1, + 1730, 1694, 203, -1, 1730, 204, 1694, -1, + 1726, 1720, 204, -1, 1726, 204, 1730, -1, + 1036, 1041, 1042, -1, 1036, 1040, 1041, -1, + 1036, 2331, 1040, -1, 539, 537, 1004, -1, + 539, 1004, 1002, -1, 539, 1738, 537, -1, + 539, 1042, 1738, -1, 205, 542, 206, -1, + 205, 1039, 542, -1, 205, 1737, 1039, -1, + 205, 206, 207, -1, 205, 207, 1737, -1, + 1735, 1039, 1737, -1, 208, 2337, 1040, -1, + 208, 542, 1039, -1, 208, 1039, 2337, -1, + 208, 2333, 542, -1, 208, 1040, 2331, -1, + 208, 2331, 2333, -1, 540, 535, 541, -1, + 540, 1044, 535, -1, 1046, 1047, 484, -1, + 1046, 484, 1729, -1, 546, 544, 209, -1, + 546, 210, 547, -1, 546, 211, 210, -1, + 546, 209, 211, -1, 212, 213, 547, -1, + 212, 1052, 213, -1, 212, 547, 214, -1, + 212, 214, 550, -1, 212, 550, 1052, -1, + 1049, 215, 1050, -1, 1049, 548, 215, -1, + 876, 877, 216, -1, 876, 216, 875, -1, + 1766, 1765, 218, -1, 1766, 218, 1757, -1, + 217, 1758, 1757, -1, 217, 1757, 218, -1, + 217, 218, 219, -1, 217, 1056, 1758, -1, + 217, 569, 1056, -1, 217, 219, 569, -1, + 1102, 2426, 1840, -1, 2378, 1067, 1775, -1, + 2378, 1841, 1067, -1, 557, 2382, 1072, -1, + 557, 566, 1059, -1, 558, 222, 559, -1, + 558, 223, 222, -1, 558, 1064, 223, -1, + 1065, 220, 1064, -1, 1065, 567, 563, -1, + 1065, 563, 220, -1, 562, 1071, 563, -1, + 562, 1072, 1071, -1, 562, 557, 1072, -1, + 562, 566, 557, -1, 1784, 220, 1071, -1, + 1784, 223, 220, -1, 1785, 221, 222, -1, + 1785, 222, 223, -1, 1785, 223, 1784, -1, + 1785, 1783, 221, -1, 1754, 1752, 1055, -1, + 3307, 570, 3305, -1, 574, 2395, 2393, -1, + 574, 570, 3307, -1, 1745, 2401, 1795, -1, + 1745, 573, 1744, -1, 1793, 573, 1745, -1, + 1793, 1745, 1795, -1, 1793, 1794, 1076, -1, + 1104, 2421, 1829, -1, 1104, 1098, 2435, -1, + 2359, 2358, 224, -1, 2359, 225, 226, -1, + 2359, 224, 225, -1, 2359, 226, 2357, -1, + 1772, 552, 227, -1, 1772, 227, 1770, -1, + 1593, 228, 229, -1, 1593, 229, 379, -1, + 1593, 1592, 228, -1, 1776, 1058, 577, -1, + 579, 581, 590, -1, 579, 590, 580, -1, + 582, 1129, 1132, -1, 582, 232, 1129, -1, + 230, 583, 584, -1, 230, 584, 231, -1, + 230, 231, 232, -1, 230, 232, 582, -1, + 230, 2916, 583, -1, 230, 582, 2916, -1, + 2915, 583, 2916, -1, 2940, 2939, 1126, -1, + 233, 585, 1120, -1, 233, 234, 235, -1, + 233, 1120, 234, -1, 233, 235, 1450, -1, + 233, 1450, 1451, -1, 233, 1451, 585, -1, + 2456, 585, 1451, -1, 1125, 587, 581, -1, + 1125, 1126, 587, -1, 2472, 2471, 597, -1, + 588, 2472, 597, -1, 588, 1903, 2472, -1, + 588, 597, 236, -1, 588, 236, 593, -1, + 1117, 587, 1126, -1, 1117, 1126, 2939, -1, + 592, 590, 581, -1, 592, 581, 587, -1, + 595, 603, 246, -1, 595, 596, 603, -1, + 237, 238, 598, -1, 237, 246, 591, -1, + 237, 591, 238, -1, 237, 595, 246, -1, + 237, 598, 595, -1, 1159, 603, 596, -1, + 1159, 596, 1157, -1, 242, 611, 244, -1, + 1161, 611, 242, -1, 1161, 242, 600, -1, + 239, 241, 240, -1, 239, 600, 242, -1, + 239, 240, 243, -1, 239, 244, 241, -1, + 239, 242, 244, -1, 239, 243, 245, -1, + 239, 245, 246, -1, 239, 246, 600, -1, + 602, 1907, 601, -1, 602, 601, 600, -1, + 602, 600, 246, -1, 602, 246, 604, -1, + 1135, 608, 1136, -1, 606, 3027, 1900, -1, + 606, 3028, 3027, -1, 607, 1157, 599, -1, + 607, 1904, 1143, -1, 609, 610, 247, -1, + 609, 248, 611, -1, 609, 249, 248, -1, + 609, 247, 249, -1, 2484, 2485, 250, -1, + 2484, 250, 610, -1, 612, 613, 255, -1, + 612, 255, 254, -1, 251, 252, 1153, -1, + 251, 1153, 614, -1, 251, 253, 252, -1, + 251, 614, 612, -1, 251, 254, 253, -1, + 251, 612, 254, -1, 1154, 614, 1153, -1, + 1164, 2478, 2479, -1, 1917, 615, 617, -1, + 1917, 618, 615, -1, 385, 383, 255, -1, + 385, 874, 873, -1, 385, 613, 874, -1, + 385, 255, 613, -1, 2325, 2304, 1927, -1, + 2325, 1927, 2326, -1, 622, 1933, 1928, -1, + 622, 1928, 620, -1, 622, 623, 256, -1, + 622, 256, 1933, -1, 626, 620, 257, -1, + 626, 257, 839, -1, 626, 625, 258, -1, + 626, 621, 620, -1, 626, 258, 621, -1, + 425, 259, 260, -1, 425, 260, 673, -1, + 425, 426, 753, -1, 425, 753, 259, -1, + 659, 658, 636, -1, 261, 629, 636, -1, + 261, 636, 658, -1, 261, 658, 1197, -1, + 261, 782, 781, -1, 261, 781, 629, -1, + 261, 1197, 782, -1, 635, 650, 660, -1, + 635, 263, 650, -1, 635, 660, 659, -1, + 634, 262, 275, -1, 634, 632, 262, -1, + 634, 275, 263, -1, 634, 263, 635, -1, + 639, 270, 264, -1, 639, 637, 270, -1, + 639, 264, 762, -1, 639, 762, 766, -1, + 653, 642, 640, -1, 1946, 748, 2669, -1, + 654, 265, 266, -1, 654, 266, 267, -1, + 654, 267, 655, -1, 654, 1187, 265, -1, + 644, 269, 268, -1, 644, 645, 269, -1, + 644, 268, 270, -1, 644, 270, 647, -1, + 648, 271, 645, -1, 648, 645, 1181, -1, + 648, 667, 271, -1, 648, 649, 667, -1, + 1182, 652, 1180, -1, 1182, 646, 652, -1, + 1194, 651, 1191, -1, 1177, 660, 650, -1, + 1188, 651, 1194, -1, 1185, 640, 1490, -1, + 1185, 653, 640, -1, 761, 273, 272, -1, + 761, 763, 273, -1, 761, 272, 756, -1, + 761, 756, 1423, -1, 1204, 2186, 1201, -1, + 274, 1191, 651, -1, 274, 651, 1488, -1, + 274, 1488, 2187, -1, 274, 2187, 2186, -1, + 274, 2186, 1204, -1, 274, 1204, 1191, -1, + 1193, 1199, 1198, -1, 2185, 1201, 2186, -1, + 780, 2208, 630, -1, 780, 630, 781, -1, + 665, 666, 275, -1, 665, 275, 278, -1, + 671, 882, 276, -1, 671, 276, 668, -1, + 671, 277, 672, -1, 671, 665, 278, -1, + 671, 278, 277, -1, 2268, 691, 1215, -1, + 2500, 2501, 309, -1, 1952, 1953, 280, -1, + 1221, 279, 680, -1, 1221, 280, 279, -1, + 1221, 1952, 280, -1, 1957, 1591, 1958, -1, + 1290, 1235, 685, -1, 1231, 685, 1235, -1, + 2507, 688, 1243, -1, 2507, 1243, 2509, -1, + 1967, 1256, 1969, -1, 687, 282, 281, -1, + 687, 1247, 688, -1, 687, 281, 1247, -1, + 687, 693, 282, -1, 283, 281, 282, -1, + 283, 282, 284, -1, 684, 1244, 281, -1, + 684, 281, 283, -1, 684, 283, 1279, -1, + 684, 686, 1244, -1, 692, 1214, 1215, -1, + 692, 1252, 1214, -1, 690, 678, 284, -1, + 690, 691, 678, -1, 690, 284, 282, -1, + 690, 282, 693, -1, 285, 678, 1947, -1, + 285, 284, 678, -1, 1948, 285, 1947, -1, + 1948, 1280, 285, -1, 1278, 283, 284, -1, + 1278, 1279, 283, -1, 1278, 284, 285, -1, + 1278, 285, 1280, -1, 1826, 1827, 694, -1, + 1270, 1274, 1273, -1, 2876, 2416, 1283, -1, + 2895, 2896, 1271, -1, 699, 697, 1272, -1, + 699, 1272, 1273, -1, 1990, 289, 1991, -1, + 1303, 1999, 703, -1, 286, 682, 681, -1, + 286, 681, 725, -1, 286, 725, 726, -1, + 286, 726, 287, -1, 286, 287, 288, -1, + 286, 288, 682, -1, 1275, 1987, 1292, -1, + 1275, 1292, 706, -1, 704, 1234, 1233, -1, + 704, 2009, 1234, -1, 704, 1301, 2008, -1, + 704, 2008, 2009, -1, 1293, 1233, 1232, -1, + 1293, 683, 1295, -1, 1293, 1232, 683, -1, + 290, 1990, 1995, -1, 290, 305, 304, -1, + 290, 304, 289, -1, 290, 289, 1990, -1, + 1307, 290, 1995, -1, 1307, 1308, 305, -1, + 1307, 305, 290, -1, 2007, 2008, 295, -1, + 2007, 295, 292, -1, 2007, 292, 1309, -1, + 296, 703, 294, -1, 296, 1303, 703, -1, + 296, 1302, 1297, -1, 296, 1297, 1303, -1, + 291, 293, 292, -1, 291, 294, 293, -1, + 291, 292, 295, -1, 291, 296, 294, -1, + 291, 295, 1302, -1, 291, 1302, 296, -1, + 297, 680, 298, -1, 297, 1363, 725, -1, + 297, 1227, 1363, -1, 297, 298, 1227, -1, + 297, 681, 680, -1, 297, 725, 681, -1, + 743, 708, 745, -1, 2538, 2546, 3026, -1, + 1352, 1350, 299, -1, 1352, 299, 2060, -1, + 2605, 382, 1911, -1, 2605, 2604, 382, -1, + 1914, 1163, 1150, -1, 717, 2068, 1354, -1, + 717, 1354, 1353, -1, 714, 715, 387, -1, + 714, 1336, 1335, -1, 716, 718, 302, -1, + 716, 302, 300, -1, 716, 300, 301, -1, + 716, 301, 715, -1, 720, 302, 718, -1, + 720, 1344, 302, -1, 720, 2618, 1344, -1, + 2072, 1353, 1354, -1, 1346, 303, 1345, -1, + 1346, 1347, 303, -1, 1370, 304, 2014, -1, + 1370, 307, 304, -1, 2018, 2014, 305, -1, + 2018, 305, 1308, -1, 2018, 1308, 2017, -1, + 2026, 2024, 1372, -1, 712, 1376, 1372, -1, + 712, 2010, 1325, -1, 1310, 1372, 2024, -1, + 1310, 712, 1372, -1, 1310, 2010, 712, -1, + 1310, 2024, 1312, -1, 724, 306, 721, -1, + 724, 723, 306, -1, 1362, 1363, 1227, -1, + 728, 2658, 2651, -1, 2528, 1991, 1368, -1, + 1383, 734, 307, -1, 1383, 307, 1370, -1, + 735, 736, 731, -1, 735, 732, 734, -1, + 735, 731, 732, -1, 1394, 744, 1404, -1, + 1394, 743, 744, -1, 1396, 730, 1318, -1, + 1396, 1318, 1393, -1, 1396, 1397, 730, -1, + 740, 727, 679, -1, 740, 679, 1217, -1, + 740, 2526, 727, -1, 308, 679, 727, -1, + 308, 309, 2501, -1, 308, 2501, 679, -1, + 308, 2651, 309, -1, 308, 728, 2651, -1, + 308, 727, 728, -1, 1219, 309, 2650, -1, + 1219, 2500, 309, -1, 1315, 1318, 741, -1, + 1315, 2043, 1331, -1, 1328, 737, 1388, -1, + 1328, 2033, 737, -1, 1328, 2564, 2033, -1, + 729, 741, 730, -1, 729, 731, 736, -1, + 742, 737, 2033, -1, 742, 741, 729, -1, + 742, 736, 737, -1, 742, 729, 736, -1, + 2107, 1405, 744, -1, 2111, 2112, 1401, -1, + 747, 1940, 1410, -1, 747, 1410, 1409, -1, + 1941, 1410, 1940, -1, 1480, 2172, 2175, -1, + 1483, 1937, 1172, -1, 899, 1250, 1249, -1, + 1429, 2154, 2161, -1, 2686, 2687, 426, -1, + 2686, 426, 758, -1, 2763, 2766, 2136, -1, + 1425, 2150, 766, -1, 1425, 766, 762, -1, + 2103, 1431, 1435, -1, 2103, 1407, 1431, -1, + 2102, 2103, 1435, -1, 2121, 2122, 2102, -1, + 2203, 1437, 1440, -1, 2693, 1449, 377, -1, + 2693, 377, 1452, -1, 1459, 2046, 2045, -1, + 1460, 1334, 1464, -1, 1462, 2170, 2169, -1, + 322, 711, 710, -1, 322, 1481, 1171, -1, + 322, 1171, 310, -1, 322, 310, 711, -1, + 1471, 772, 311, -1, 1471, 311, 312, -1, + 1471, 312, 313, -1, 1471, 313, 1470, -1, + 314, 777, 316, -1, 314, 778, 777, -1, + 314, 316, 1525, -1, 314, 1525, 778, -1, + 779, 1525, 2208, -1, 779, 778, 1525, -1, + 779, 2208, 780, -1, 315, 1477, 316, -1, + 315, 318, 1477, -1, 315, 316, 317, -1, + 315, 317, 318, -1, 1474, 1477, 318, -1, + 1474, 318, 1475, -1, 776, 320, 319, -1, + 776, 1196, 320, -1, 776, 321, 1196, -1, + 776, 782, 321, -1, 776, 319, 777, -1, + 787, 3328, 783, -1, 663, 1494, 1493, -1, + 663, 1493, 785, -1, 663, 785, 770, -1, + 663, 770, 1468, -1, 2174, 1172, 2175, -1, + 2174, 1483, 1172, -1, 1479, 710, 2028, -1, + 1479, 1481, 322, -1, 1479, 322, 710, -1, + 2210, 788, 323, -1, 2210, 323, 324, -1, + 2210, 324, 2209, -1, 792, 793, 325, -1, + 792, 325, 326, -1, 789, 2720, 794, -1, + 789, 326, 788, -1, 789, 792, 326, -1, + 789, 794, 792, -1, 1526, 794, 2720, -1, + 1526, 847, 794, -1, 796, 327, 801, -1, + 796, 801, 802, -1, 796, 328, 327, -1, + 796, 797, 328, -1, 796, 802, 856, -1, + 820, 819, 797, -1, 329, 1535, 1533, -1, + 329, 1533, 799, -1, 329, 330, 1535, -1, + 329, 799, 330, -1, 857, 799, 1533, -1, + 331, 807, 332, -1, 331, 338, 807, -1, + 331, 332, 340, -1, 331, 340, 338, -1, + 806, 334, 333, -1, 806, 335, 334, -1, + 806, 333, 807, -1, 806, 336, 335, -1, + 806, 805, 336, -1, 337, 864, 804, -1, + 337, 343, 864, -1, 337, 804, 810, -1, + 337, 810, 817, -1, 337, 817, 343, -1, + 808, 807, 338, -1, 808, 338, 809, -1, + 339, 809, 340, -1, 339, 340, 816, -1, + 339, 810, 809, -1, 339, 816, 810, -1, + 814, 340, 812, -1, 814, 816, 340, -1, + 2221, 818, 2222, -1, 2227, 2225, 820, -1, + 1500, 341, 819, -1, 1500, 1498, 341, -1, + 1508, 812, 1509, -1, 1508, 1505, 812, -1, + 342, 817, 815, -1, 342, 815, 1505, -1, + 342, 344, 343, -1, 342, 343, 817, -1, + 342, 1506, 344, -1, 342, 1505, 1506, -1, + 1512, 1509, 1513, -1, 1512, 822, 1509, -1, + 1512, 821, 822, -1, 1512, 1515, 821, -1, + 3083, 3084, 825, -1, 3083, 825, 866, -1, + 2190, 829, 2191, -1, 1445, 1455, 1446, -1, + 1523, 1522, 832, -1, 347, 345, 350, -1, + 347, 827, 345, -1, 346, 350, 1518, -1, + 346, 1518, 828, -1, 346, 347, 350, -1, + 346, 828, 827, -1, 346, 827, 347, -1, + 348, 349, 2711, -1, 348, 354, 784, -1, + 348, 352, 354, -1, 348, 2711, 352, -1, + 348, 784, 783, -1, 348, 783, 349, -1, + 2713, 2711, 349, -1, 2713, 3330, 2705, -1, + 2713, 349, 3330, -1, 2195, 1518, 350, -1, + 2195, 350, 351, -1, 2195, 351, 834, -1, + 357, 352, 356, -1, 357, 2196, 353, -1, + 357, 354, 352, -1, 357, 353, 354, -1, + 355, 1522, 830, -1, 355, 1517, 1522, -1, + 355, 830, 831, -1, 355, 831, 1517, -1, + 2198, 356, 1517, -1, 2198, 357, 356, -1, + 2198, 2196, 357, -1, 1528, 358, 1556, -1, + 1528, 1524, 358, -1, 1536, 1535, 359, -1, + 1536, 359, 1537, -1, 1538, 836, 838, -1, + 1538, 838, 843, -1, 841, 846, 1541, -1, + 841, 839, 790, -1, 841, 790, 846, -1, + 845, 1541, 846, -1, 845, 1530, 1529, -1, + 1549, 2727, 1548, -1, 852, 853, 1546, -1, + 852, 1546, 1558, -1, 2741, 852, 1558, -1, + 2741, 2742, 852, -1, 868, 369, 1580, -1, + 862, 2439, 2438, -1, 862, 861, 1111, -1, + 862, 1111, 2448, -1, 862, 2448, 2439, -1, + 860, 864, 861, -1, 1110, 868, 2231, -1, + 1110, 1111, 360, -1, 1110, 360, 361, -1, + 1110, 361, 369, -1, 1110, 369, 868, -1, + 1550, 362, 365, -1, 1550, 850, 362, -1, + 1550, 365, 1549, -1, 1565, 363, 1567, -1, + 1565, 865, 363, -1, 867, 365, 364, -1, + 867, 364, 1575, -1, 867, 1549, 365, -1, + 867, 2727, 1549, -1, 1573, 367, 366, -1, + 1573, 1574, 367, -1, 1573, 366, 2723, -1, + 368, 369, 1574, -1, 368, 1574, 1572, -1, + 368, 1569, 369, -1, 368, 1572, 1569, -1, + 370, 1582, 830, -1, 370, 1521, 1582, -1, + 370, 830, 1522, -1, 370, 1522, 1521, -1, + 371, 373, 372, -1, 371, 372, 374, -1, + 371, 376, 373, -1, 371, 374, 376, -1, + 2232, 375, 2233, -1, 2232, 1580, 376, -1, + 2232, 376, 375, -1, 1448, 1115, 2201, -1, + 1448, 2201, 1441, -1, 1448, 1441, 1444, -1, + 1114, 377, 584, -1, 1114, 1452, 377, -1, + 1114, 1446, 1452, -1, 1585, 378, 723, -1, + 1585, 1584, 378, -1, 1585, 723, 1965, -1, + 1594, 379, 380, -1, 1594, 380, 1584, -1, + 1594, 1593, 379, -1, 1165, 382, 381, -1, + 1165, 381, 1920, -1, 1165, 1911, 382, -1, + 1165, 1164, 1911, -1, 870, 384, 383, -1, + 870, 871, 384, -1, 870, 383, 385, -1, + 870, 385, 873, -1, 1921, 1920, 1596, -1, + 872, 386, 871, -1, 872, 387, 386, -1, + 872, 714, 387, -1, 872, 1336, 714, -1, + 388, 389, 390, -1, 388, 391, 389, -1, + 388, 390, 392, -1, 388, 392, 393, -1, + 388, 393, 391, -1, 394, 875, 3230, -1, + 394, 3230, 3229, -1, 2750, 875, 394, -1, + 2750, 394, 3229, -1, 879, 1736, 395, -1, + 879, 395, 396, -1, 879, 396, 877, -1, + 397, 399, 398, -1, 397, 398, 400, -1, + 397, 401, 399, -1, 397, 400, 401, -1, + 1606, 402, 1601, -1, 1606, 1604, 403, -1, + 1606, 403, 404, -1, 1606, 404, 402, -1, + 405, 1603, 1605, -1, 405, 1604, 1603, -1, + 405, 1605, 406, -1, 405, 406, 1604, -1, + 2237, 1601, 410, -1, 2237, 409, 407, -1, + 2237, 411, 2239, -1, 2237, 407, 411, -1, + 881, 408, 882, -1, 881, 409, 2237, -1, + 881, 883, 884, -1, 881, 410, 408, -1, + 881, 2237, 410, -1, 881, 411, 409, -1, + 881, 884, 411, -1, 412, 428, 413, -1, + 412, 429, 428, -1, 412, 413, 414, -1, + 412, 414, 416, -1, 412, 416, 429, -1, + 415, 429, 416, -1, 415, 418, 417, -1, + 415, 417, 892, -1, 415, 892, 429, -1, + 415, 416, 419, -1, 415, 419, 418, -1, + 420, 423, 887, -1, 420, 887, 421, -1, + 420, 422, 423, -1, 420, 421, 422, -1, + 886, 423, 890, -1, 886, 887, 423, -1, + 424, 890, 953, -1, 424, 889, 890, -1, + 424, 953, 888, -1, 424, 888, 889, -1, + 674, 676, 758, -1, 674, 425, 673, -1, + 674, 758, 426, -1, 674, 426, 425, -1, + 1687, 1610, 972, -1, 891, 427, 428, -1, + 891, 1609, 427, -1, 891, 428, 429, -1, + 891, 429, 892, -1, 941, 430, 915, -1, + 941, 1653, 430, -1, 431, 2282, 1260, -1, + 431, 1631, 2282, -1, 431, 2247, 1631, -1, + 431, 897, 2247, -1, 431, 1260, 1258, -1, + 431, 1258, 897, -1, 901, 432, 902, -1, + 901, 441, 432, -1, 1612, 1654, 2241, -1, + 1612, 1652, 1654, -1, 1612, 949, 1652, -1, + 2253, 2251, 1614, -1, 905, 938, 1642, -1, + 905, 1642, 906, -1, 905, 433, 938, -1, + 2249, 2244, 909, -1, 2249, 2252, 2244, -1, + 904, 2132, 759, -1, 904, 759, 433, -1, + 904, 433, 905, -1, 3103, 3106, 2246, -1, + 3103, 2246, 1615, -1, 922, 923, 434, -1, + 922, 434, 442, -1, 922, 435, 921, -1, + 922, 442, 435, -1, 912, 1666, 1667, -1, + 912, 1667, 534, -1, 912, 534, 917, -1, + 1621, 912, 917, -1, 1619, 964, 1666, -1, + 1619, 919, 964, -1, 2773, 436, 2772, -1, + 2773, 924, 436, -1, 1625, 931, 1627, -1, + 2782, 1253, 2283, -1, 1635, 474, 931, -1, + 935, 933, 2292, -1, 935, 936, 437, -1, + 935, 437, 933, -1, 439, 933, 944, -1, + 439, 944, 438, -1, 2289, 438, 948, -1, + 2289, 439, 438, -1, 2289, 933, 439, -1, + 2289, 2286, 933, -1, 939, 940, 440, -1, + 939, 440, 441, -1, 939, 901, 1650, -1, + 939, 441, 901, -1, 945, 943, 947, -1, + 945, 947, 948, -1, 1651, 442, 1653, -1, + 1651, 947, 442, -1, 443, 447, 444, -1, + 443, 1209, 447, -1, 443, 444, 1213, -1, + 443, 1208, 1209, -1, 443, 1213, 1208, -1, + 952, 445, 955, -1, 952, 953, 445, -1, + 958, 448, 951, -1, 958, 951, 955, -1, + 957, 956, 446, -1, 957, 446, 447, -1, + 957, 448, 958, -1, 957, 447, 449, -1, + 957, 449, 448, -1, 963, 1699, 968, -1, + 963, 1720, 1699, -1, 963, 978, 1720, -1, + 963, 1655, 978, -1, 2801, 2319, 2790, -1, + 450, 451, 452, -1, 450, 452, 453, -1, + 450, 453, 454, -1, 450, 1700, 985, -1, + 450, 454, 1700, -1, 450, 455, 451, -1, + 450, 985, 455, -1, 1658, 965, 1659, -1, + 1669, 458, 1665, -1, 456, 966, 967, -1, + 456, 967, 457, -1, 456, 457, 458, -1, + 456, 458, 1669, -1, 456, 1670, 966, -1, + 456, 1669, 1670, -1, 459, 966, 1670, -1, + 459, 1670, 1672, -1, 459, 970, 965, -1, + 459, 1672, 970, -1, 1673, 459, 965, -1, + 1673, 966, 459, -1, 1689, 1679, 460, -1, + 1689, 460, 1688, -1, 2322, 2304, 2325, -1, + 2312, 960, 975, -1, 2312, 975, 2311, -1, + 976, 461, 503, -1, 976, 503, 505, -1, + 976, 505, 1026, -1, 976, 522, 461, -1, + 1692, 1656, 2302, -1, 1691, 2315, 462, -1, + 1691, 462, 1694, -1, 470, 962, 1661, -1, + 470, 961, 962, -1, 470, 469, 467, -1, + 463, 514, 961, -1, 463, 465, 464, -1, + 463, 464, 514, -1, 463, 466, 465, -1, + 463, 961, 470, -1, 463, 467, 466, -1, + 463, 470, 467, -1, 468, 980, 469, -1, + 468, 983, 980, -1, 468, 1663, 983, -1, + 468, 469, 470, -1, 468, 1661, 1663, -1, + 468, 470, 1661, -1, 1662, 971, 1697, -1, + 1662, 1659, 971, -1, 981, 472, 982, -1, + 981, 983, 472, -1, 1696, 471, 472, -1, + 1696, 472, 983, -1, 1696, 2324, 473, -1, + 1696, 473, 471, -1, 480, 477, 474, -1, + 480, 1636, 482, -1, 480, 474, 1635, -1, + 480, 1635, 1636, -1, 483, 475, 481, -1, + 483, 482, 475, -1, 476, 478, 477, -1, + 476, 479, 478, -1, 476, 477, 480, -1, + 476, 481, 479, -1, 476, 480, 482, -1, + 476, 483, 481, -1, 476, 482, 483, -1, + 988, 1729, 484, -1, 988, 484, 487, -1, + 988, 487, 1704, -1, 1035, 538, 498, -1, + 1731, 1733, 485, -1, 1731, 490, 487, -1, + 1731, 485, 490, -1, 1731, 487, 1047, -1, + 1731, 1047, 2329, -1, 1705, 486, 1706, -1, + 1705, 491, 486, -1, 1705, 487, 490, -1, + 1705, 1704, 487, -1, 488, 490, 489, -1, + 488, 1705, 490, -1, 488, 491, 1705, -1, + 488, 492, 491, -1, 488, 493, 492, -1, + 488, 489, 493, -1, 494, 575, 498, -1, + 494, 1001, 1815, -1, 494, 1815, 2407, -1, + 494, 2407, 575, -1, 494, 498, 538, -1, + 494, 538, 1001, -1, 1087, 993, 1085, -1, + 1087, 928, 993, -1, 1087, 2870, 1808, -1, + 1087, 1808, 928, -1, 495, 496, 990, -1, + 495, 497, 496, -1, 495, 498, 497, -1, + 495, 1035, 498, -1, 495, 990, 1034, -1, + 495, 1034, 1035, -1, 989, 499, 1733, -1, + 989, 500, 499, -1, 989, 501, 500, -1, + 989, 990, 501, -1, 1788, 1097, 1080, -1, + 1006, 1002, 1004, -1, 1006, 1084, 1814, -1, + 502, 503, 508, -1, 502, 508, 504, -1, + 502, 505, 503, -1, 502, 504, 505, -1, + 506, 508, 507, -1, 506, 509, 508, -1, + 506, 510, 509, -1, 506, 1717, 1030, -1, + 506, 511, 1717, -1, 506, 507, 511, -1, + 506, 1030, 530, -1, 506, 530, 512, -1, + 506, 512, 510, -1, 513, 2299, 514, -1, + 513, 515, 2299, -1, 513, 514, 516, -1, + 513, 516, 515, -1, 2798, 2299, 1012, -1, + 1011, 1009, 517, -1, 1011, 517, 2799, -1, + 518, 520, 519, -1, 518, 519, 523, -1, + 518, 521, 520, -1, 518, 523, 521, -1, + 977, 975, 521, -1, 977, 522, 976, -1, + 977, 523, 522, -1, 977, 521, 523, -1, + 1709, 1015, 524, -1, 1709, 525, 1710, -1, + 1709, 524, 525, -1, 526, 527, 1019, -1, + 526, 528, 527, -1, 526, 1018, 1031, -1, + 526, 1019, 1018, -1, 526, 1031, 529, -1, + 526, 529, 528, -1, 1021, 1019, 1013, -1, + 1029, 1028, 530, -1, 1029, 530, 1030, -1, + 1714, 1018, 1028, -1, 1714, 1028, 1715, -1, + 1714, 1031, 1018, -1, 1023, 1024, 2310, -1, + 1023, 2310, 2311, -1, 531, 533, 532, -1, + 531, 532, 534, -1, 531, 1667, 533, -1, + 531, 534, 1667, -1, 1719, 1720, 1726, -1, + 1727, 1046, 1729, -1, 1727, 535, 1044, -1, + 1727, 1728, 535, -1, 1739, 536, 537, -1, + 1739, 537, 1738, -1, 1739, 573, 536, -1, + 1739, 1744, 573, -1, 1038, 538, 1035, -1, + 1038, 1001, 538, -1, 1038, 1002, 1001, -1, + 1037, 1036, 1042, -1, 1037, 1042, 539, -1, + 1037, 539, 1002, -1, 1037, 1002, 1038, -1, + 3089, 2337, 1039, -1, 1045, 1044, 540, -1, + 1045, 540, 541, -1, 1045, 2329, 1047, -1, + 1045, 2333, 2329, -1, 1045, 541, 542, -1, + 1045, 542, 2333, -1, 543, 545, 544, -1, + 543, 544, 546, -1, 543, 547, 545, -1, + 543, 546, 547, -1, 1051, 548, 1049, -1, + 1051, 549, 548, -1, 1051, 550, 549, -1, + 1051, 1052, 550, -1, 553, 1772, 1771, -1, + 553, 552, 1772, -1, 2343, 2362, 3122, -1, + 1054, 1053, 2824, -1, 1054, 551, 552, -1, + 1054, 2824, 551, -1, 1054, 552, 553, -1, + 1054, 553, 1771, -1, 1751, 3305, 570, -1, + 1751, 570, 1752, -1, 1778, 3305, 1751, -1, + 2355, 554, 1764, -1, 2355, 2357, 554, -1, + 1835, 3241, 1834, -1, 1835, 1832, 1106, -1, + 1061, 566, 565, -1, 1061, 1059, 566, -1, + 1100, 1060, 1103, -1, 556, 1102, 1103, -1, + 556, 1061, 565, -1, 556, 1103, 1060, -1, + 556, 1060, 1061, -1, 555, 565, 564, -1, + 555, 556, 565, -1, 555, 1102, 556, -1, + 555, 2426, 1102, -1, 555, 2425, 2426, -1, + 555, 564, 2425, -1, 2381, 1773, 2847, -1, + 3140, 1060, 1100, -1, 3140, 1834, 3241, -1, + 3140, 1100, 1834, -1, 2388, 1059, 2389, -1, + 2388, 557, 1059, -1, 2388, 2382, 557, -1, + 1063, 558, 559, -1, 1063, 559, 560, -1, + 1063, 560, 1068, -1, 1063, 1064, 558, -1, + 1066, 1067, 1841, -1, 1066, 1841, 1842, -1, + 1066, 1842, 567, -1, 1066, 567, 1065, -1, + 561, 562, 563, -1, 561, 564, 565, -1, + 561, 565, 566, -1, 561, 566, 562, -1, + 561, 567, 564, -1, 561, 563, 567, -1, + 1070, 568, 1069, -1, 1070, 569, 568, -1, + 1070, 1056, 569, -1, 1070, 1761, 1056, -1, + 571, 1055, 1752, -1, 571, 574, 2393, -1, + 571, 1752, 570, -1, 571, 570, 574, -1, + 1073, 2831, 2832, -1, 1073, 2832, 1055, -1, + 1073, 571, 2393, -1, 1073, 1055, 571, -1, + 1077, 1075, 572, -1, 1077, 572, 573, -1, + 1077, 573, 1793, -1, 1077, 1793, 1076, -1, + 1787, 1788, 1080, -1, 1079, 1076, 1794, -1, + 1083, 2395, 574, -1, 1083, 574, 3307, -1, + 1083, 3307, 3302, -1, 1798, 1799, 1791, -1, + 2414, 1818, 2412, -1, 2414, 1821, 1818, -1, + 2414, 2413, 1821, -1, 2404, 1819, 2495, -1, + 1093, 1084, 1090, -1, 2871, 575, 2407, -1, + 2871, 1086, 575, -1, 1091, 1088, 2411, -1, + 1091, 2411, 2412, -1, 1091, 2412, 1818, -1, + 1822, 2410, 1095, -1, 999, 1099, 1095, -1, + 999, 1081, 1099, -1, 576, 2410, 2411, -1, + 576, 1095, 2410, -1, 576, 2411, 1088, -1, + 576, 999, 1095, -1, 576, 1088, 998, -1, + 576, 998, 999, -1, 1096, 2436, 2435, -1, + 1096, 2435, 1098, -1, 1096, 1097, 1788, -1, + 1096, 1788, 2436, -1, 2431, 1101, 1844, -1, + 1848, 1828, 1849, -1, 1848, 1845, 1828, -1, + 1105, 1106, 1832, -1, 1105, 1832, 1101, -1, + 3239, 1106, 1856, -1, 3239, 3241, 1835, -1, + 3239, 1835, 1106, -1, 1224, 1776, 577, -1, + 1224, 577, 578, -1, 1224, 578, 1225, -1, + 1224, 2853, 1776, -1, 1871, 1109, 580, -1, + 1871, 580, 590, -1, 1871, 590, 1866, -1, + 1107, 579, 580, -1, 1107, 580, 1109, -1, + 1107, 581, 579, -1, 1107, 1125, 581, -1, + 1883, 583, 2915, -1, 2914, 1132, 1876, -1, + 2914, 2916, 582, -1, 2914, 582, 1132, -1, + 2446, 1884, 2448, -1, 1879, 1115, 1116, -1, + 1113, 584, 583, -1, 1113, 1114, 584, -1, + 1113, 583, 1883, -1, 1113, 1883, 1116, -1, + 1118, 2456, 2457, -1, 1118, 585, 2456, -1, + 1118, 2938, 1121, -1, 1118, 1121, 585, -1, + 1123, 1121, 2938, -1, 1123, 2938, 2940, -1, + 1131, 1108, 1868, -1, 1131, 1124, 1108, -1, + 2469, 599, 2471, -1, 2469, 607, 599, -1, + 2469, 2470, 1904, -1, 2469, 1904, 607, -1, + 586, 587, 1117, -1, 586, 588, 593, -1, + 586, 1903, 588, -1, 586, 1117, 1903, -1, + 586, 592, 587, -1, 586, 593, 592, -1, + 589, 591, 590, -1, 589, 590, 592, -1, + 589, 593, 591, -1, 589, 592, 593, -1, + 594, 596, 595, -1, 594, 597, 2471, -1, + 594, 598, 597, -1, 594, 595, 598, -1, + 594, 2471, 599, -1, 594, 599, 596, -1, + 1906, 600, 601, -1, 1906, 1161, 600, -1, + 1906, 601, 1907, -1, 1160, 1907, 602, -1, + 1160, 603, 1159, -1, 1160, 604, 603, -1, + 1160, 602, 604, -1, 2053, 1339, 1133, -1, + 2053, 1133, 2944, -1, 1141, 608, 1135, -1, + 1141, 1133, 1339, -1, 1141, 1135, 1133, -1, + 605, 1899, 2170, -1, 605, 1462, 1465, -1, + 605, 2170, 1462, -1, 605, 1465, 606, -1, + 605, 1900, 1899, -1, 605, 606, 1900, -1, + 1333, 606, 1465, -1, 1333, 1465, 1464, -1, + 1333, 1464, 1334, -1, 1333, 3028, 606, -1, + 1905, 617, 1145, -1, 1905, 2477, 617, -1, + 1905, 1145, 1143, -1, 1905, 1143, 1904, -1, + 1156, 1157, 607, -1, 1156, 607, 1143, -1, + 1147, 1148, 608, -1, 1147, 608, 1141, -1, + 1152, 2450, 1148, -1, 1152, 2449, 2450, -1, + 2475, 1152, 1148, -1, 1885, 1136, 608, -1, + 1885, 608, 1148, -1, 1885, 1137, 1136, -1, + 1885, 1893, 1137, -1, 1885, 1148, 2450, -1, + 1162, 610, 609, -1, 1162, 2484, 610, -1, + 1162, 611, 1161, -1, 1162, 609, 611, -1, + 616, 612, 614, -1, 616, 615, 618, -1, + 616, 618, 613, -1, 616, 613, 612, -1, + 1144, 614, 1154, -1, 1144, 1145, 615, -1, + 1144, 615, 616, -1, 1144, 616, 614, -1, + 1910, 1164, 2479, -1, 1910, 1911, 1164, -1, + 1916, 1917, 617, -1, 1916, 617, 2477, -1, + 1916, 2477, 2478, -1, 1919, 874, 618, -1, + 1919, 618, 1917, -1, 1167, 1927, 2304, -1, + 1167, 2304, 2805, -1, 1167, 2805, 1686, -1, + 1932, 2326, 1927, -1, 1932, 1928, 1933, -1, + 619, 620, 621, -1, 619, 622, 620, -1, + 619, 621, 623, -1, 619, 623, 622, -1, + 840, 624, 625, -1, 840, 625, 626, -1, + 840, 627, 624, -1, 840, 626, 839, -1, + 840, 838, 627, -1, 628, 633, 636, -1, + 628, 2209, 633, -1, 628, 636, 629, -1, + 628, 630, 2209, -1, 628, 629, 630, -1, + 631, 633, 632, -1, 631, 632, 634, -1, + 631, 634, 635, -1, 631, 636, 633, -1, + 631, 635, 659, -1, 631, 659, 636, -1, + 767, 638, 637, -1, 767, 637, 639, -1, + 767, 769, 638, -1, 767, 639, 766, -1, + 1170, 1946, 1936, -1, 1170, 748, 1946, -1, + 1170, 747, 748, -1, 1170, 1940, 747, -1, + 1943, 1171, 1481, -1, 1943, 1481, 1480, -1, + 1945, 1937, 1936, -1, 1945, 1936, 1946, -1, + 1945, 1172, 1937, -1, 641, 749, 1485, -1, + 641, 640, 642, -1, 641, 1491, 640, -1, + 641, 1485, 1491, -1, 1939, 2490, 749, -1, + 1939, 641, 642, -1, 1939, 749, 641, -1, + 1175, 655, 1174, -1, 1175, 642, 653, -1, + 1175, 653, 655, -1, 3152, 1939, 642, -1, + 3152, 642, 1175, -1, 643, 645, 644, -1, + 643, 646, 1182, -1, 643, 647, 646, -1, + 643, 644, 647, -1, 643, 1181, 645, -1, + 643, 1182, 1181, -1, 1179, 649, 648, -1, + 1179, 648, 1181, -1, 1179, 650, 649, -1, + 1179, 1177, 650, -1, 661, 660, 1177, -1, + 661, 1177, 1178, -1, 1184, 1488, 651, -1, + 1184, 651, 1188, -1, 1184, 1490, 1488, -1, + 1184, 1185, 1490, -1, 1186, 652, 1187, -1, + 1186, 1180, 652, -1, 656, 1188, 1194, -1, + 656, 1178, 1180, -1, 656, 1180, 1186, -1, + 656, 1186, 1188, -1, 1189, 653, 1185, -1, + 1189, 1187, 654, -1, 1189, 655, 653, -1, + 1189, 654, 655, -1, 1203, 1191, 1204, -1, + 1192, 1193, 661, -1, 1192, 661, 1178, -1, + 1192, 1178, 656, -1, 1192, 656, 1194, -1, + 657, 1193, 1198, -1, 657, 1198, 658, -1, + 657, 658, 659, -1, 657, 659, 660, -1, + 657, 660, 661, -1, 657, 661, 1193, -1, + 662, 1472, 1201, -1, 662, 2185, 1494, -1, + 662, 1201, 2185, -1, 662, 1494, 663, -1, + 662, 1468, 1472, -1, 662, 663, 1468, -1, + 1202, 1199, 1203, -1, 664, 666, 665, -1, + 664, 667, 666, -1, 664, 671, 668, -1, + 664, 665, 671, -1, 664, 668, 882, -1, + 664, 882, 669, -1, 664, 669, 667, -1, + 670, 884, 882, -1, 670, 882, 671, -1, + 670, 672, 884, -1, 670, 671, 672, -1, + 1212, 1213, 1646, -1, 1212, 1646, 1210, -1, + 2297, 1646, 1647, -1, 2297, 1647, 2295, -1, + 2297, 2296, 937, -1, 1211, 673, 1209, -1, + 1211, 676, 674, -1, 1211, 674, 673, -1, + 1206, 937, 675, -1, 1206, 2297, 937, -1, + 1206, 675, 676, -1, 1206, 676, 1211, -1, + 1632, 1253, 2782, -1, 1632, 1214, 1252, -1, + 1632, 1252, 1253, -1, 2261, 1214, 1632, -1, + 677, 691, 2268, -1, 677, 1947, 678, -1, + 677, 678, 691, -1, 677, 1949, 1947, -1, + 677, 2268, 2266, -1, 677, 2266, 1949, -1, + 2499, 679, 2501, -1, 2499, 1217, 679, -1, + 2499, 1216, 1217, -1, 2499, 2503, 1216, -1, + 1240, 1238, 701, -1, 1240, 701, 739, -1, + 1959, 1958, 1953, -1, 1222, 680, 681, -1, + 1222, 1221, 680, -1, 1222, 681, 682, -1, + 1222, 682, 1223, -1, 1956, 1225, 1592, -1, + 1956, 1592, 1957, -1, 1960, 1226, 1228, -1, + 1291, 1289, 683, -1, 1291, 1235, 1290, -1, + 1291, 1232, 1235, -1, 1291, 683, 1232, -1, + 700, 685, 686, -1, 700, 1290, 685, -1, + 700, 686, 684, -1, 700, 684, 1279, -1, + 1230, 1238, 1231, -1, 1230, 701, 1238, -1, + 1230, 1306, 701, -1, 1230, 1234, 1306, -1, + 1237, 685, 1231, -1, 1237, 1245, 686, -1, + 1237, 686, 685, -1, 1237, 1231, 1238, -1, + 1242, 2509, 1243, -1, 1242, 2503, 2509, -1, + 1242, 1216, 2503, -1, 1242, 1246, 1216, -1, + 1266, 688, 2507, -1, 2506, 1266, 2507, -1, + 1248, 1967, 1414, -1, 1248, 1256, 1967, -1, + 1248, 1255, 1256, -1, 1248, 1250, 1255, -1, + 1264, 1252, 692, -1, 1264, 692, 1263, -1, + 1257, 1969, 1256, -1, 1257, 1265, 1969, -1, + 1262, 1263, 693, -1, 1262, 693, 687, -1, + 1262, 687, 688, -1, 1262, 688, 1266, -1, + 689, 691, 690, -1, 689, 1215, 691, -1, + 689, 692, 1215, -1, 689, 1263, 692, -1, + 689, 693, 1263, -1, 689, 690, 693, -1, + 1976, 694, 1827, -1, 1977, 2516, 2515, -1, + 1269, 694, 1270, -1, 1269, 1826, 694, -1, + 1269, 2896, 2903, -1, 1269, 2903, 1826, -1, + 1975, 1274, 1270, -1, 1975, 1270, 694, -1, + 1975, 694, 1976, -1, 1282, 1271, 1272, -1, + 1282, 1272, 697, -1, 1282, 697, 1284, -1, + 1277, 2876, 1283, -1, 1277, 1283, 1287, -1, + 2875, 1280, 1948, -1, 2875, 1277, 1280, -1, + 2875, 2876, 1277, -1, 2875, 1948, 2882, -1, + 2417, 2895, 1271, -1, 2417, 1271, 1282, -1, + 695, 699, 707, -1, 695, 1295, 696, -1, + 695, 696, 697, -1, 695, 697, 699, -1, + 695, 1294, 1295, -1, 695, 707, 1294, -1, + 698, 1273, 1274, -1, 698, 699, 1273, -1, + 698, 1274, 1275, -1, 698, 707, 699, -1, + 698, 706, 707, -1, 698, 1275, 706, -1, + 1286, 1287, 1283, -1, 1286, 1284, 1289, -1, + 1288, 700, 1279, -1, 1288, 1290, 700, -1, + 2002, 1305, 1292, -1, 1996, 1994, 739, -1, + 1996, 701, 1306, -1, 1996, 739, 701, -1, + 1981, 1223, 702, -1, 1981, 1982, 1223, -1, + 1981, 702, 703, -1, 1981, 703, 1999, -1, + 1300, 704, 1233, -1, 1300, 1233, 1293, -1, + 1300, 1301, 704, -1, 1304, 1303, 1297, -1, + 1304, 1297, 1298, -1, 705, 1298, 1294, -1, + 705, 1305, 1304, -1, 705, 1304, 1298, -1, + 705, 706, 1305, -1, 705, 707, 706, -1, + 705, 1294, 707, -1, 2005, 1307, 1995, -1, + 1313, 1369, 2012, -1, 1313, 2012, 2095, -1, + 1317, 1394, 1393, -1, 1317, 743, 1394, -1, + 1317, 1316, 708, -1, 1317, 708, 743, -1, + 2038, 1319, 709, -1, 2038, 709, 2040, -1, + 1322, 1321, 710, -1, 1322, 711, 1319, -1, + 1322, 710, 711, -1, 1332, 2996, 2571, -1, + 2542, 2546, 2538, -1, 1355, 2010, 2982, -1, + 1355, 1325, 2010, -1, 2029, 1325, 1355, -1, + 1326, 1327, 1375, -1, 1326, 1375, 1376, -1, + 1326, 1376, 712, -1, 1326, 712, 1325, -1, + 2041, 2040, 1316, -1, 2041, 1316, 1331, -1, + 1349, 2074, 719, -1, 1349, 719, 1335, -1, + 1338, 1913, 1914, -1, 1338, 1914, 1150, -1, + 2587, 2593, 2947, -1, 2587, 2594, 2593, -1, + 1342, 717, 1353, -1, 1342, 1353, 2059, -1, + 1341, 717, 1342, -1, 713, 714, 1335, -1, + 713, 1335, 719, -1, 713, 715, 714, -1, + 713, 719, 718, -1, 713, 716, 715, -1, + 713, 718, 716, -1, 2620, 2621, 2065, -1, + 2063, 1344, 2618, -1, 2069, 2068, 717, -1, + 2069, 717, 1341, -1, 2069, 1341, 2602, -1, + 2073, 720, 718, -1, 2073, 719, 2074, -1, + 2073, 718, 719, -1, 2611, 1354, 2068, -1, + 2611, 2610, 1354, -1, 2616, 720, 2073, -1, + 2616, 2618, 720, -1, 2077, 2078, 1347, -1, + 2623, 2087, 2085, -1, 2634, 2084, 2637, -1, + 2640, 2641, 2086, -1, 1358, 721, 722, -1, + 1358, 724, 721, -1, 1358, 722, 2642, -1, + 1358, 1357, 724, -1, 1964, 1965, 723, -1, + 1964, 723, 724, -1, 1964, 724, 1357, -1, + 2643, 1359, 1360, -1, 2648, 1360, 1359, -1, + 2090, 725, 1363, -1, 2090, 2091, 726, -1, + 2090, 726, 725, -1, 1364, 2968, 2969, -1, + 1364, 1362, 2968, -1, 1364, 2969, 2022, -1, + 2098, 2658, 728, -1, 2527, 727, 2526, -1, + 2527, 728, 727, -1, 2527, 2529, 2098, -1, + 2527, 2098, 728, -1, 2097, 2098, 2529, -1, + 733, 1397, 1366, -1, 733, 731, 729, -1, + 733, 730, 1397, -1, 733, 729, 730, -1, + 1367, 732, 731, -1, 1367, 1368, 732, -1, + 1367, 731, 733, -1, 1367, 733, 1366, -1, + 1385, 1382, 1390, -1, 1371, 1382, 1385, -1, + 1371, 1385, 1369, -1, 1371, 1313, 2025, -1, + 1371, 1369, 1313, -1, 1391, 734, 1383, -1, + 1391, 735, 734, -1, 1389, 736, 735, -1, + 1389, 1388, 737, -1, 1389, 737, 736, -1, + 1389, 735, 1391, -1, 1403, 2655, 2654, -1, + 1218, 740, 1217, -1, 1218, 1240, 739, -1, + 738, 739, 1994, -1, 738, 1218, 739, -1, + 738, 740, 1218, -1, 738, 2526, 740, -1, + 738, 2525, 2526, -1, 738, 1994, 2525, -1, + 2663, 1401, 1399, -1, 2663, 2664, 1401, -1, + 1402, 2661, 1219, -1, 1402, 2664, 2661, -1, + 1402, 1219, 2650, -1, 1402, 2650, 2649, -1, + 2032, 1315, 741, -1, 2032, 742, 2033, -1, + 2032, 741, 742, -1, 2032, 2043, 1315, -1, + 1329, 1381, 2031, -1, 1329, 1328, 1388, -1, + 1329, 1388, 1387, -1, 1329, 1387, 1381, -1, + 2105, 744, 743, -1, 2105, 2107, 744, -1, + 2105, 743, 745, -1, 2105, 745, 2106, -1, + 2676, 1405, 2107, -1, 2675, 1405, 2676, -1, + 746, 747, 1409, -1, 746, 2674, 2678, -1, + 746, 1409, 2674, -1, 746, 2678, 2670, -1, + 746, 2670, 748, -1, 746, 748, 747, -1, + 1430, 1410, 1941, -1, 1430, 1431, 1407, -1, + 1938, 1937, 1483, -1, 1938, 749, 2490, -1, + 1482, 1485, 749, -1, 1482, 749, 1938, -1, + 1482, 1938, 1483, -1, 1482, 1486, 1485, -1, + 2759, 1411, 2758, -1, 1412, 2250, 752, -1, + 1412, 2759, 2250, -1, 1412, 1411, 2759, -1, + 2248, 2758, 1411, -1, 2248, 1411, 2118, -1, + 1419, 1249, 2125, -1, 1419, 2125, 2124, -1, + 1416, 2248, 2118, -1, 1416, 2136, 2766, -1, + 1416, 2766, 2248, -1, 2116, 1416, 2118, -1, + 3075, 2138, 2127, -1, 751, 898, 899, -1, + 751, 2250, 2756, -1, 751, 2756, 898, -1, + 751, 752, 2250, -1, 750, 899, 1249, -1, + 750, 1420, 752, -1, 750, 752, 751, -1, + 750, 751, 899, -1, 750, 1419, 1420, -1, + 750, 1249, 1419, -1, 2155, 2143, 1433, -1, + 2155, 2154, 1418, -1, 2155, 1418, 2143, -1, + 1413, 752, 1420, -1, 1413, 1412, 752, -1, + 2140, 1413, 1420, -1, 2140, 2144, 1413, -1, + 757, 2687, 2688, -1, 757, 753, 2687, -1, + 757, 754, 753, -1, 757, 755, 754, -1, + 1422, 756, 755, -1, 1422, 1423, 756, -1, + 1422, 755, 757, -1, 1422, 757, 2688, -1, + 2134, 2686, 758, -1, 2134, 759, 2133, -1, + 2134, 758, 760, -1, 2134, 760, 759, -1, + 764, 761, 1423, -1, 764, 1425, 762, -1, + 764, 762, 763, -1, 764, 763, 761, -1, + 3077, 1428, 3076, -1, 3077, 3075, 2127, -1, + 3077, 2127, 1427, -1, 3077, 1427, 1428, -1, + 1426, 764, 1423, -1, 1426, 1425, 764, -1, + 2130, 2151, 1427, -1, 2130, 1427, 2127, -1, + 2152, 2131, 1429, -1, 2152, 2151, 2130, -1, + 2152, 2130, 2131, -1, 2159, 768, 2160, -1, + 2159, 2158, 1173, -1, 2159, 765, 768, -1, + 2159, 1173, 765, -1, 2149, 766, 2150, -1, + 2149, 767, 766, -1, 2149, 769, 767, -1, + 2148, 2160, 768, -1, 2148, 768, 769, -1, + 2148, 769, 2149, -1, 2165, 3153, 2158, -1, + 2165, 3154, 3153, -1, 2167, 1435, 1431, -1, + 2153, 2155, 1433, -1, 2101, 1408, 1407, -1, + 2101, 1407, 2103, -1, 2101, 1399, 1408, -1, + 2145, 1433, 2143, -1, 2145, 2141, 2121, -1, + 1434, 2121, 2102, -1, 1434, 2102, 1435, -1, + 1434, 1433, 2145, -1, 1434, 2145, 2121, -1, + 1439, 2051, 2046, -1, 1439, 1440, 1437, -1, + 2706, 2705, 3329, -1, 2706, 3329, 3323, -1, + 2706, 3323, 1436, -1, 1443, 1440, 1447, -1, + 1443, 2203, 1440, -1, 2704, 1437, 2203, -1, + 2704, 1436, 1437, -1, 2704, 2706, 1436, -1, + 2168, 1450, 1449, -1, 1453, 1455, 1445, -1, + 1453, 1445, 1447, -1, 3147, 2170, 1899, -1, + 3147, 1899, 1898, -1, 2695, 1462, 2169, -1, + 1463, 1460, 1464, -1, 1467, 1468, 770, -1, + 1467, 770, 771, -1, 1467, 771, 772, -1, + 1467, 772, 1471, -1, 1476, 774, 773, -1, + 1476, 1475, 774, -1, 1476, 827, 1477, -1, + 1476, 773, 827, -1, 775, 776, 777, -1, + 775, 777, 778, -1, 775, 778, 779, -1, + 775, 780, 781, -1, 775, 779, 780, -1, + 775, 781, 782, -1, 775, 782, 776, -1, + 786, 787, 783, -1, 786, 784, 785, -1, + 786, 783, 784, -1, 786, 785, 1493, -1, + 1492, 3034, 787, -1, 1492, 786, 1493, -1, + 1492, 787, 786, -1, 3326, 3328, 787, -1, + 3326, 787, 3034, -1, 2027, 3029, 2578, -1, + 2027, 1479, 2028, -1, 2577, 2172, 2578, -1, + 2177, 2176, 1486, -1, 2179, 3034, 1492, -1, + 2719, 788, 2210, -1, 2719, 2720, 789, -1, + 2719, 789, 788, -1, 848, 1924, 847, -1, + 848, 1923, 1924, -1, 848, 790, 1923, -1, + 848, 846, 790, -1, 791, 847, 1924, -1, + 791, 793, 792, -1, 791, 792, 794, -1, + 791, 794, 847, -1, 791, 1924, 1922, -1, + 791, 1922, 793, -1, 795, 797, 796, -1, + 795, 820, 797, -1, 795, 856, 1562, -1, + 795, 796, 856, -1, 795, 1562, 2227, -1, + 795, 2227, 820, -1, 1497, 1533, 1532, -1, + 1497, 857, 1533, -1, 798, 800, 799, -1, + 798, 799, 857, -1, 798, 801, 800, -1, + 798, 802, 801, -1, 798, 857, 856, -1, + 798, 856, 802, -1, 803, 804, 805, -1, + 803, 805, 806, -1, 803, 806, 807, -1, + 803, 807, 808, -1, 803, 808, 809, -1, + 803, 809, 810, -1, 803, 810, 804, -1, + 811, 812, 815, -1, 811, 814, 812, -1, + 811, 815, 814, -1, 813, 814, 815, -1, + 813, 816, 814, -1, 813, 815, 817, -1, + 813, 817, 816, -1, 2220, 2219, 818, -1, + 2220, 818, 2221, -1, 1499, 1498, 1500, -1, + 1501, 1500, 819, -1, 1501, 819, 820, -1, + 1501, 820, 2225, -1, 1501, 2225, 2735, -1, + 1510, 821, 1506, -1, 1510, 822, 821, -1, + 1510, 1509, 822, -1, 1514, 1513, 823, -1, + 1514, 823, 824, -1, 1514, 825, 1515, -1, + 1514, 824, 826, -1, 1514, 826, 825, -1, + 1516, 2193, 827, -1, 1516, 827, 828, -1, + 1516, 828, 1518, -1, 1516, 1518, 2190, -1, + 1519, 830, 829, -1, 1519, 829, 2190, -1, + 1519, 831, 830, -1, 1519, 1517, 831, -1, + 2202, 1441, 2201, -1, 2202, 2207, 2206, -1, + 2202, 2205, 1441, -1, 2202, 2206, 2205, -1, + 2712, 832, 2710, -1, 2712, 1523, 832, -1, + 2712, 2207, 1523, -1, 833, 834, 2196, -1, + 833, 2195, 834, -1, 833, 2196, 2195, -1, + 1554, 1528, 1556, -1, 1554, 1555, 1529, -1, + 2716, 1524, 1528, -1, 835, 836, 1538, -1, + 835, 1538, 1537, -1, 835, 837, 836, -1, + 835, 1537, 837, -1, 842, 843, 838, -1, + 842, 839, 841, -1, 842, 840, 839, -1, + 842, 838, 840, -1, 1542, 1543, 843, -1, + 1542, 841, 1541, -1, 1542, 843, 842, -1, + 1542, 842, 841, -1, 1534, 1496, 1532, -1, + 1534, 1543, 1496, -1, 1534, 1538, 843, -1, + 1534, 843, 1543, -1, 1553, 1496, 1543, -1, + 1553, 2739, 1496, -1, 1540, 1529, 1555, -1, + 1540, 1555, 1552, -1, 1540, 845, 1529, -1, + 1540, 1541, 845, -1, 844, 1526, 1530, -1, + 844, 1530, 845, -1, 844, 845, 846, -1, + 844, 847, 1526, -1, 844, 846, 848, -1, + 844, 848, 847, -1, 1547, 1548, 2224, -1, + 1547, 1558, 1546, -1, 1547, 2224, 1561, -1, + 1547, 1561, 1558, -1, 1545, 853, 849, -1, + 1545, 1546, 853, -1, 1545, 849, 850, -1, + 1545, 850, 1550, -1, 2728, 1548, 2727, -1, + 2728, 2224, 1548, -1, 2734, 2222, 1503, -1, + 851, 853, 852, -1, 851, 855, 854, -1, + 851, 854, 853, -1, 851, 2748, 855, -1, + 851, 2742, 2748, -1, 851, 852, 2742, -1, + 858, 1562, 856, -1, 858, 1497, 1559, -1, + 858, 856, 857, -1, 858, 857, 1497, -1, + 2745, 1552, 1555, -1, 1560, 1562, 858, -1, + 1560, 858, 1559, -1, 859, 860, 861, -1, + 859, 862, 2438, -1, 859, 861, 862, -1, + 859, 1866, 863, -1, 859, 2438, 1866, -1, + 859, 863, 864, -1, 859, 864, 860, -1, + 1878, 1110, 2231, -1, 1878, 2231, 2700, -1, + 2213, 1567, 2214, -1, 1566, 1567, 2213, -1, + 1566, 2213, 2212, -1, 3081, 865, 1565, -1, + 3081, 866, 865, -1, 3081, 3083, 866, -1, + 3081, 1565, 3082, -1, 2722, 1573, 2723, -1, + 1576, 1571, 1578, -1, 2726, 867, 1575, -1, + 2726, 2727, 867, -1, 2230, 868, 1580, -1, + 2230, 2231, 868, -1, 2698, 1879, 1880, -1, + 2698, 1115, 1879, -1, 2698, 2201, 1115, -1, + 2234, 2233, 1582, -1, 1586, 1585, 1965, -1, + 1586, 1228, 1587, -1, 1590, 1594, 1584, -1, + 1590, 1588, 1591, -1, 869, 871, 870, -1, + 869, 1598, 1336, -1, 869, 873, 1598, -1, + 869, 870, 873, -1, 869, 1336, 872, -1, + 869, 872, 871, -1, 1597, 873, 874, -1, + 1597, 874, 1919, -1, 1597, 1919, 1921, -1, + 1597, 1598, 873, -1, 878, 875, 2750, -1, + 878, 877, 876, -1, 878, 876, 875, -1, + 878, 879, 877, -1, 2751, 878, 2750, -1, + 2751, 879, 878, -1, 2751, 1736, 879, -1, + 2238, 2239, 1602, -1, 880, 881, 882, -1, + 880, 883, 881, -1, 880, 882, 884, -1, + 880, 884, 883, -1, 885, 887, 886, -1, + 885, 888, 887, -1, 885, 889, 888, -1, + 885, 890, 889, -1, 885, 886, 890, -1, + 1608, 1609, 891, -1, 1608, 891, 892, -1, + 1608, 893, 1610, -1, 1608, 892, 893, -1, + 894, 941, 915, -1, 894, 1637, 1638, -1, + 894, 1638, 940, -1, 894, 940, 941, -1, + 894, 895, 1637, -1, 894, 915, 895, -1, + 2755, 898, 2756, -1, 2755, 897, 898, -1, + 2755, 2247, 897, -1, 896, 1258, 1255, -1, + 896, 898, 897, -1, 896, 897, 1258, -1, + 896, 899, 898, -1, 896, 1250, 899, -1, + 896, 1255, 1250, -1, 900, 901, 902, -1, + 900, 2241, 1654, -1, 900, 1654, 1650, -1, + 900, 1650, 901, -1, 900, 902, 2242, -1, + 900, 2242, 2241, -1, 1613, 1641, 949, -1, + 1613, 949, 1612, -1, 1613, 906, 1641, -1, + 1613, 1614, 906, -1, 3099, 909, 1615, -1, + 3099, 2249, 909, -1, 2254, 2252, 2249, -1, + 1616, 2764, 2132, -1, 1616, 2132, 904, -1, + 903, 904, 905, -1, 903, 1614, 2251, -1, + 903, 2251, 1616, -1, 903, 1616, 904, -1, + 903, 906, 1614, -1, 903, 905, 906, -1, + 907, 909, 908, -1, 907, 1615, 909, -1, + 907, 3103, 1615, -1, 907, 3104, 3103, -1, + 907, 910, 3104, -1, 907, 908, 910, -1, + 911, 1620, 1666, -1, 911, 1666, 912, -1, + 911, 1621, 1620, -1, 911, 912, 1621, -1, + 913, 914, 923, -1, 913, 923, 1621, -1, + 913, 915, 914, -1, 913, 916, 915, -1, + 913, 1621, 917, -1, 913, 917, 918, -1, + 913, 918, 916, -1, 1618, 919, 1619, -1, + 1618, 921, 920, -1, 1618, 920, 919, -1, + 1618, 922, 921, -1, 1618, 923, 922, -1, + 1618, 1621, 923, -1, 2272, 993, 928, -1, + 2272, 2256, 993, -1, 2272, 2275, 2256, -1, + 2272, 928, 2273, -1, 1624, 2773, 2771, -1, + 1624, 924, 2773, -1, 1624, 925, 924, -1, + 1624, 1627, 925, -1, 932, 1625, 1626, -1, + 932, 926, 1639, -1, 932, 927, 926, -1, + 932, 1626, 927, -1, 1629, 928, 1808, -1, + 1629, 2273, 928, -1, 3105, 3104, 929, -1, + 3105, 929, 930, -1, 3105, 930, 2776, -1, + 2279, 1630, 2779, -1, 1634, 931, 1625, -1, + 1634, 1635, 931, -1, 1634, 932, 1639, -1, + 1634, 1625, 932, -1, 2285, 2292, 933, -1, + 2285, 933, 2286, -1, 934, 2292, 1643, -1, + 934, 935, 2292, -1, 934, 1643, 936, -1, + 934, 936, 935, -1, 2287, 937, 2296, -1, + 2287, 1642, 938, -1, 2287, 938, 937, -1, + 1640, 2289, 948, -1, 1640, 949, 1641, -1, + 1649, 940, 939, -1, 1649, 1653, 941, -1, + 1649, 941, 940, -1, 1649, 939, 1650, -1, + 942, 944, 943, -1, 942, 943, 945, -1, + 942, 948, 944, -1, 942, 945, 948, -1, + 946, 948, 947, -1, 946, 947, 1651, -1, + 946, 1651, 1652, -1, 946, 1640, 948, -1, + 946, 1652, 949, -1, 946, 949, 1640, -1, + 950, 955, 951, -1, 950, 952, 955, -1, + 950, 951, 953, -1, 950, 953, 952, -1, + 954, 955, 956, -1, 954, 956, 957, -1, + 954, 958, 955, -1, 954, 957, 958, -1, + 2800, 2799, 959, -1, 2800, 959, 960, -1, + 973, 2319, 2801, -1, 973, 960, 2312, -1, + 973, 2800, 960, -1, 973, 2801, 2800, -1, + 2298, 2300, 962, -1, 2298, 961, 2299, -1, + 2298, 962, 961, -1, 1660, 2300, 2786, -1, + 1660, 2786, 1658, -1, 1660, 962, 2300, -1, + 1660, 1661, 962, -1, 1675, 2788, 1655, -1, + 1675, 1655, 963, -1, 1675, 963, 968, -1, + 1671, 1669, 1665, -1, 1678, 964, 1679, -1, + 1678, 1666, 964, -1, 2785, 1673, 965, -1, + 2785, 965, 1658, -1, 2785, 1658, 2786, -1, + 1674, 967, 966, -1, 1674, 966, 1673, -1, + 1674, 968, 967, -1, 1674, 1675, 968, -1, + 1683, 2307, 2808, -1, 969, 970, 1672, -1, + 969, 1672, 1681, -1, 969, 971, 970, -1, + 969, 1681, 1682, -1, 969, 1682, 984, -1, + 969, 984, 971, -1, 2807, 2303, 1682, -1, + 2305, 972, 1685, -1, 2305, 1687, 972, -1, + 2317, 2319, 973, -1, 2317, 973, 2312, -1, + 974, 2311, 975, -1, 974, 976, 1026, -1, + 974, 975, 977, -1, 974, 977, 976, -1, + 974, 1023, 2311, -1, 974, 1026, 1023, -1, + 1693, 1694, 1720, -1, 1693, 1720, 978, -1, + 1693, 978, 1656, -1, 1693, 1656, 1692, -1, + 979, 980, 983, -1, 979, 983, 981, -1, + 979, 982, 980, -1, 979, 981, 982, -1, + 1695, 1696, 983, -1, 1695, 983, 1663, -1, + 1695, 1662, 1697, -1, 1695, 1663, 1662, -1, + 2321, 984, 2303, -1, 2321, 1697, 984, -1, + 2321, 2303, 2322, -1, 987, 1723, 1703, -1, + 987, 985, 1700, -1, 987, 986, 985, -1, + 987, 1703, 986, -1, 1722, 987, 1700, -1, + 1722, 1723, 987, -1, 1722, 1699, 1721, -1, + 1702, 1729, 988, -1, 1702, 1703, 1723, -1, + 1702, 988, 1704, -1, 1732, 989, 1733, -1, + 1732, 1034, 990, -1, 1732, 990, 989, -1, + 991, 2256, 2257, -1, 991, 992, 1085, -1, + 991, 1085, 993, -1, 991, 993, 2256, -1, + 991, 2257, 994, -1, 991, 994, 992, -1, + 995, 1075, 1081, -1, 995, 996, 1075, -1, + 995, 997, 996, -1, 995, 998, 997, -1, + 995, 999, 998, -1, 995, 1081, 999, -1, + 1000, 1001, 1002, -1, 1000, 1002, 1006, -1, + 1000, 1815, 1001, -1, 1000, 1814, 1815, -1, + 1000, 1006, 1814, -1, 1003, 1004, 1005, -1, + 1003, 1006, 1004, -1, 1003, 1005, 1007, -1, + 1003, 1084, 1006, -1, 1003, 1007, 1090, -1, + 1003, 1090, 1084, -1, 1008, 1010, 1009, -1, + 1008, 1009, 1011, -1, 1008, 1012, 1010, -1, + 1008, 2798, 1012, -1, 1008, 2799, 2798, -1, + 1008, 1011, 2799, -1, 1708, 1024, 1015, -1, + 1708, 1015, 1709, -1, 1708, 2310, 1024, -1, + 1708, 2309, 2310, -1, 1025, 1021, 1013, -1, + 1025, 1013, 1014, -1, 1025, 1014, 1015, -1, + 1025, 1015, 1024, -1, 1016, 1021, 1022, -1, + 1016, 1017, 1028, -1, 1016, 1022, 1017, -1, + 1016, 1028, 1018, -1, 1016, 1018, 1019, -1, + 1016, 1019, 1021, -1, 1020, 1022, 1021, -1, + 1020, 1024, 1023, -1, 1020, 1025, 1024, -1, + 1020, 1021, 1025, -1, 1020, 1026, 1022, -1, + 1020, 1023, 1026, -1, 1027, 1715, 1028, -1, + 1027, 1028, 1029, -1, 1027, 1030, 1715, -1, + 1027, 1029, 1030, -1, 1716, 1031, 1714, -1, + 1716, 1032, 1031, -1, 1716, 1033, 1032, -1, + 1716, 1717, 1033, -1, 1725, 1729, 1702, -1, + 1725, 1702, 1723, -1, 2332, 1034, 1732, -1, + 2332, 1035, 1034, -1, 2332, 1038, 1035, -1, + 2330, 2331, 1036, -1, 2330, 1036, 1037, -1, + 2330, 1037, 1038, -1, 2330, 1038, 2332, -1, + 1734, 1039, 1735, -1, 1734, 3089, 1039, -1, + 2336, 1041, 1040, -1, 2336, 2334, 1041, -1, + 2336, 1040, 2337, -1, 1740, 1041, 2334, -1, + 1740, 1042, 1041, -1, 1740, 1738, 1042, -1, + 1743, 2812, 1746, -1, 2400, 1746, 1749, -1, + 1043, 1727, 1044, -1, 1043, 1044, 1045, -1, + 1043, 1046, 1727, -1, 1043, 1047, 1046, -1, + 1043, 1045, 1047, -1, 1048, 1049, 1050, -1, + 1048, 1051, 1049, -1, 1048, 1050, 1052, -1, + 1048, 1052, 1051, -1, 2338, 2339, 2340, -1, + 2338, 2820, 2814, -1, 2338, 2340, 2820, -1, + 2829, 2830, 2398, -1, 2342, 2824, 1053, -1, + 2342, 1053, 2343, -1, 1057, 2343, 1053, -1, + 1057, 1053, 1054, -1, 1057, 1054, 1771, -1, + 1057, 2362, 2343, -1, 3121, 1055, 2832, -1, + 3121, 3123, 1754, -1, 3121, 1754, 1055, -1, + 2363, 2835, 2350, -1, 1760, 1758, 1056, -1, + 1760, 1056, 1761, -1, 1760, 1756, 1758, -1, + 1760, 2345, 1756, -1, 1753, 1778, 1751, -1, + 1753, 2363, 2350, -1, 2349, 1753, 2350, -1, + 2349, 1778, 1753, -1, 2352, 1769, 2348, -1, + 2352, 2350, 2835, -1, 2354, 1768, 3130, -1, + 1767, 1768, 1766, -1, 1767, 1766, 1757, -1, + 3132, 2352, 2835, -1, 3132, 1769, 2352, -1, + 2360, 1057, 1771, -1, 2360, 2362, 1057, -1, + 2364, 1754, 3123, -1, 2375, 2841, 1773, -1, + 2374, 1773, 2381, -1, 2374, 2375, 1773, -1, + 2367, 2369, 1058, -1, 2367, 1058, 1776, -1, + 2390, 2389, 1059, -1, 2390, 1060, 3140, -1, + 2390, 1059, 1061, -1, 2390, 1061, 1060, -1, + 3304, 3305, 1778, -1, 3238, 3239, 1856, -1, + 1062, 1064, 1063, -1, 1062, 1065, 1064, -1, + 1062, 1066, 1065, -1, 1062, 1067, 1066, -1, + 1062, 1068, 1067, -1, 1062, 1063, 1068, -1, + 1780, 1069, 1783, -1, 1780, 1070, 1069, -1, + 1780, 1761, 1070, -1, 1780, 1781, 1761, -1, + 1782, 1071, 1072, -1, 1782, 1784, 1071, -1, + 1762, 1072, 2382, -1, 1762, 1782, 1072, -1, + 1762, 1781, 1782, -1, 1762, 2382, 2383, -1, + 2392, 2830, 2831, -1, 2392, 2831, 1073, -1, + 2392, 1073, 2393, -1, 1800, 1787, 1799, -1, + 1800, 1801, 1789, -1, 1074, 1080, 1079, -1, + 1074, 1787, 1080, -1, 1074, 1799, 1787, -1, + 1074, 1791, 1799, -1, 1074, 1079, 1794, -1, + 1074, 1794, 1791, -1, 1082, 1081, 1075, -1, + 1082, 1076, 1079, -1, 1082, 1075, 1077, -1, + 1082, 1077, 1076, -1, 1078, 1079, 1080, -1, + 1078, 1099, 1081, -1, 1078, 1081, 1082, -1, + 1078, 1082, 1079, -1, 1078, 1080, 1097, -1, + 1078, 1097, 1099, -1, 1792, 2394, 2395, -1, + 1792, 2395, 1083, -1, 1792, 1797, 1798, -1, + 1802, 1083, 3302, -1, 1802, 3302, 1805, -1, + 1802, 1797, 1792, -1, 1802, 1792, 1083, -1, + 1803, 1797, 1802, -1, 1806, 1801, 1803, -1, + 1806, 1859, 1801, -1, 1806, 1858, 1859, -1, + 3135, 1805, 3302, -1, 3135, 2864, 1805, -1, + 2893, 2414, 2412, -1, 2263, 2264, 1810, -1, + 2263, 1810, 2493, -1, 1812, 2404, 2495, -1, + 1812, 2493, 1810, -1, 1812, 2495, 2493, -1, + 2403, 1819, 2404, -1, 1813, 1814, 1084, -1, + 1813, 1084, 1093, -1, 1813, 1093, 1820, -1, + 2869, 1085, 1086, -1, 2869, 1086, 2871, -1, + 2869, 2870, 1087, -1, 2869, 1087, 1085, -1, + 1092, 1088, 1091, -1, 1092, 1089, 1088, -1, + 1092, 1090, 1089, -1, 1092, 1093, 1090, -1, + 1817, 1091, 1818, -1, 1817, 1092, 1091, -1, + 1817, 1820, 1093, -1, 1817, 1093, 1092, -1, + 1823, 1098, 1104, -1, 1823, 1822, 1098, -1, + 1823, 1104, 1829, -1, 1823, 1829, 1824, -1, + 1094, 1822, 1095, -1, 1094, 1097, 1096, -1, + 1094, 1098, 1822, -1, 1094, 1096, 1098, -1, + 1094, 1099, 1097, -1, 1094, 1095, 1099, -1, + 2901, 1826, 2903, -1, 2891, 2892, 1824, -1, + 2418, 2878, 2891, -1, 2418, 1824, 1829, -1, + 2418, 2891, 1824, -1, 2430, 1101, 2431, -1, + 2430, 1105, 1101, -1, 2430, 2433, 1852, -1, + 2430, 1852, 1105, -1, 1833, 1100, 1103, -1, + 1833, 1834, 1100, -1, 1831, 1101, 1832, -1, + 1831, 1844, 1101, -1, 1838, 1844, 1831, -1, + 1838, 1831, 1839, -1, 1838, 2962, 1844, -1, + 1838, 3265, 2962, -1, 1837, 1102, 1840, -1, + 1837, 1103, 1102, -1, 1837, 1833, 1103, -1, + 1837, 1839, 1833, -1, 1267, 1845, 1846, -1, + 1267, 1827, 1828, -1, 1267, 1828, 1845, -1, + 1267, 1976, 1827, -1, 2429, 1845, 1848, -1, + 1850, 1848, 1849, -1, 2434, 2421, 1104, -1, + 2434, 2420, 2421, -1, 2434, 1104, 2435, -1, + 2909, 1789, 1859, -1, 2909, 2910, 1789, -1, + 1855, 1852, 1862, -1, 1855, 1106, 1105, -1, + 1855, 1105, 1852, -1, 1855, 1856, 1106, -1, + 1863, 1850, 2907, -1, 1863, 2907, 2908, -1, + 1861, 1858, 1857, -1, 1870, 1109, 1871, -1, + 1870, 1868, 1108, -1, 1870, 1108, 1109, -1, + 1127, 1125, 1107, -1, 1127, 1108, 1124, -1, + 1127, 1109, 1108, -1, 1127, 1107, 1109, -1, + 2918, 2439, 1884, -1, 2918, 1884, 2921, -1, + 1867, 1875, 1876, -1, 1867, 1876, 1132, -1, + 2913, 2914, 1876, -1, 2933, 1866, 2438, -1, + 2925, 2928, 2441, -1, 2925, 2912, 2913, -1, + 1881, 1110, 1878, -1, 1881, 2448, 1111, -1, + 1881, 1111, 1110, -1, 2445, 1882, 1879, -1, + 2445, 1116, 1883, -1, 2445, 1879, 1116, -1, + 1112, 1114, 1113, -1, 1112, 1115, 1448, -1, + 1112, 1116, 1115, -1, 1112, 1113, 1116, -1, + 1112, 1448, 1446, -1, 1112, 1446, 1114, -1, + 2451, 1903, 1117, -1, 2451, 1117, 2939, -1, + 2936, 2938, 1118, -1, 2936, 2457, 1893, -1, + 2936, 1118, 2457, -1, 1119, 1123, 1124, -1, + 1119, 1131, 1130, -1, 1119, 1124, 1131, -1, + 1119, 1130, 1120, -1, 1119, 1120, 1121, -1, + 1119, 1121, 1123, -1, 1122, 1124, 1123, -1, + 1122, 1126, 1125, -1, 1122, 2940, 1126, -1, + 1122, 1123, 2940, -1, 1122, 1127, 1124, -1, + 1122, 1125, 1127, -1, 1128, 1129, 1130, -1, + 1128, 1130, 1131, -1, 1128, 1132, 1129, -1, + 1128, 1131, 1868, -1, 1128, 1868, 1867, -1, + 1128, 1867, 1132, -1, 2941, 2456, 1451, -1, + 2941, 2458, 2456, -1, 2941, 1451, 3142, -1, + 2585, 1889, 2584, -1, 2585, 2590, 2454, -1, + 1888, 1886, 1340, -1, 1888, 3248, 1886, -1, + 2055, 2584, 1889, -1, 2055, 1340, 3280, -1, + 2055, 1888, 1340, -1, 2055, 1889, 1888, -1, + 2453, 2585, 2454, -1, 2453, 1889, 2585, -1, + 1890, 1133, 1135, -1, 1890, 2944, 1133, -1, + 1138, 2452, 2454, -1, 1138, 2454, 2590, -1, + 2589, 1138, 2590, -1, 2589, 2455, 1138, -1, + 1894, 1137, 1893, -1, 1894, 1139, 1137, -1, + 1134, 1139, 1891, -1, 1134, 1891, 1890, -1, + 1134, 1890, 1135, -1, 1134, 1135, 1136, -1, + 1134, 1136, 1137, -1, 1134, 1137, 1139, -1, + 1140, 1891, 1139, -1, 1140, 2452, 1138, -1, + 1140, 2455, 1891, -1, 1140, 1138, 2455, -1, + 1895, 2461, 2452, -1, 1895, 1139, 1894, -1, + 1895, 2452, 1140, -1, 1895, 1140, 1139, -1, + 1149, 1141, 1339, -1, 1149, 1338, 1150, -1, + 1149, 1339, 1338, -1, 1149, 1147, 1141, -1, + 1897, 1340, 1886, -1, 1897, 1886, 1898, -1, + 1142, 1154, 1155, -1, 1142, 1155, 1156, -1, + 1142, 1156, 1143, -1, 1142, 1144, 1154, -1, + 1142, 1143, 1145, -1, 1142, 1145, 1144, -1, + 1146, 1148, 1147, -1, 1146, 1151, 2475, -1, + 1146, 2475, 1148, -1, 1146, 1147, 1149, -1, + 1146, 1150, 1151, -1, 1146, 1149, 1150, -1, + 2468, 2449, 1152, -1, 2480, 2475, 1151, -1, + 2480, 1151, 1163, -1, 2480, 1910, 2479, -1, + 2480, 1163, 1910, -1, 2474, 1152, 2475, -1, + 2474, 2470, 2468, -1, 2474, 2468, 1152, -1, + 2487, 2483, 1155, -1, 2487, 1153, 2485, -1, + 2487, 1154, 1153, -1, 2487, 1155, 1154, -1, + 1158, 1155, 2483, -1, 1158, 1157, 1156, -1, + 1158, 1156, 1155, -1, 1158, 1159, 1157, -1, + 1908, 1159, 1158, -1, 1908, 1158, 2483, -1, + 1908, 1907, 1160, -1, 1908, 1160, 1159, -1, + 2486, 1161, 1906, -1, 2486, 1162, 1161, -1, + 2486, 2484, 1162, -1, 1912, 1163, 1914, -1, + 1912, 1910, 1163, -1, 1918, 2478, 1164, -1, + 1918, 1916, 2478, -1, 1918, 1165, 1920, -1, + 1918, 1164, 1165, -1, 1926, 1686, 1166, -1, + 1926, 1167, 1686, -1, 1926, 1166, 1922, -1, + 1926, 1927, 1167, -1, 1934, 2326, 1932, -1, + 1934, 1168, 2326, -1, 1934, 1169, 1168, -1, + 1934, 1935, 1169, -1, 2489, 1170, 1936, -1, + 2489, 1940, 1170, -1, 2668, 1171, 1943, -1, + 2668, 2667, 1171, -1, 1944, 1172, 1945, -1, + 1944, 1943, 1480, -1, 1944, 2175, 1172, -1, + 1944, 1480, 2175, -1, 3151, 1173, 3153, -1, + 3151, 1174, 1173, -1, 3151, 1175, 1174, -1, + 3151, 3152, 1175, -1, 1176, 1178, 1177, -1, + 1176, 1177, 1179, -1, 1176, 1180, 1178, -1, + 1176, 1179, 1181, -1, 1176, 1182, 1180, -1, + 1176, 1181, 1182, -1, 1183, 1185, 1184, -1, + 1183, 1186, 1187, -1, 1183, 1184, 1188, -1, + 1183, 1188, 1186, -1, 1183, 1187, 1189, -1, + 1183, 1189, 1185, -1, 1190, 1191, 1203, -1, + 1190, 1193, 1192, -1, 1190, 1199, 1193, -1, + 1190, 1203, 1199, -1, 1190, 1194, 1191, -1, + 1190, 1192, 1194, -1, 1469, 1196, 1202, -1, + 1469, 1470, 1196, -1, 1195, 1196, 1197, -1, + 1195, 1202, 1196, -1, 1195, 1197, 1198, -1, + 1195, 1198, 1199, -1, 1195, 1199, 1202, -1, + 1200, 1201, 1472, -1, 1200, 1202, 1203, -1, + 1200, 1472, 1469, -1, 1200, 1469, 1202, -1, + 1200, 1204, 1201, -1, 1200, 1203, 1204, -1, + 1207, 1210, 1646, -1, 1207, 1646, 2297, -1, + 1205, 2297, 1206, -1, 1205, 1207, 2297, -1, + 1205, 1209, 1208, -1, 1205, 1210, 1207, -1, + 1205, 1211, 1209, -1, 1205, 1206, 1211, -1, + 1205, 1212, 1210, -1, 1205, 1208, 1213, -1, + 1205, 1213, 1212, -1, 2267, 1214, 2261, -1, + 2267, 1215, 1214, -1, 2267, 2268, 1215, -1, + 2494, 2413, 2886, -1, 2494, 1821, 2413, -1, + 2494, 1819, 1821, -1, 2494, 2495, 1819, -1, + 1239, 1216, 1246, -1, 1239, 1217, 1216, -1, + 1239, 1218, 1217, -1, 1239, 1240, 1218, -1, + 1950, 1219, 2661, -1, 1950, 2500, 1219, -1, + 2856, 2857, 1959, -1, 2856, 1979, 3160, -1, + 1220, 1952, 1221, -1, 1220, 1221, 1222, -1, + 1220, 1954, 1952, -1, 1220, 1222, 1223, -1, + 1220, 1223, 1982, -1, 1220, 1982, 1954, -1, + 2854, 2853, 1224, -1, 2854, 1224, 1225, -1, + 2854, 1225, 1956, -1, 2852, 2854, 1956, -1, + 1961, 1227, 1226, -1, 1961, 1226, 1960, -1, + 1961, 1362, 1227, -1, 1961, 2968, 1362, -1, + 1966, 1960, 1228, -1, 1966, 1586, 1965, -1, + 1966, 1228, 1586, -1, 1966, 2537, 1960, -1, + 1963, 1357, 1361, -1, 1963, 1964, 1357, -1, + 1963, 1361, 2533, -1, 1963, 2533, 2536, -1, + 1229, 1230, 1231, -1, 1229, 1232, 1233, -1, + 1229, 1233, 1234, -1, 1229, 1234, 1230, -1, + 1229, 1231, 1235, -1, 1229, 1235, 1232, -1, + 1236, 1237, 1238, -1, 1236, 1239, 1246, -1, + 1236, 1246, 1245, -1, 1236, 1245, 1237, -1, + 1236, 1238, 1240, -1, 1236, 1240, 1239, -1, + 1241, 1242, 1243, -1, 1241, 1244, 1245, -1, + 1241, 1245, 1246, -1, 1241, 1246, 1242, -1, + 1241, 1243, 1247, -1, 1241, 1247, 1244, -1, + 2498, 2681, 1414, -1, 2498, 1414, 1967, -1, + 1968, 1266, 2506, -1, 1968, 1969, 1265, -1, + 1415, 1248, 1414, -1, 1415, 2125, 1249, -1, + 1415, 1249, 1250, -1, 1415, 1250, 1248, -1, + 1251, 1252, 1264, -1, 1251, 1253, 1252, -1, + 1251, 1259, 1253, -1, 1251, 1257, 1259, -1, + 1251, 1264, 1265, -1, 1251, 1265, 1257, -1, + 1254, 1256, 1255, -1, 1254, 1257, 1256, -1, + 1254, 1255, 1258, -1, 1254, 1259, 1257, -1, + 1254, 1260, 1259, -1, 1254, 1258, 1260, -1, + 1261, 1263, 1262, -1, 1261, 1264, 1263, -1, + 1261, 1265, 1264, -1, 1261, 1968, 1265, -1, + 1261, 1262, 1266, -1, 1261, 1266, 1968, -1, + 1985, 1986, 1973, -1, 1972, 1843, 1973, -1, + 1972, 1846, 1843, -1, 1972, 1267, 1846, -1, + 1972, 1976, 1267, -1, 1978, 1973, 1843, -1, + 1978, 1843, 1977, -1, 1978, 2512, 1985, -1, + 1978, 1985, 1973, -1, 1268, 1269, 1270, -1, + 1268, 1272, 1271, -1, 1268, 1271, 2896, -1, + 1268, 2896, 1269, -1, 1268, 1273, 1272, -1, + 1268, 1270, 1273, -1, 1974, 1274, 1975, -1, + 1974, 1275, 1274, -1, 1974, 1987, 1275, -1, + 1974, 1986, 1987, -1, 1276, 1277, 1287, -1, + 1276, 1279, 1278, -1, 1276, 1278, 1280, -1, + 1276, 1280, 1277, -1, 1276, 1288, 1279, -1, + 1276, 1287, 1288, -1, 1281, 2417, 1282, -1, + 1281, 1286, 1283, -1, 1281, 1283, 2416, -1, + 1281, 2416, 2417, -1, 1281, 1282, 1284, -1, + 1281, 1284, 1286, -1, 1285, 1287, 1286, -1, + 1285, 1288, 1287, -1, 1285, 1286, 1289, -1, + 1285, 1290, 1288, -1, 1285, 1289, 1291, -1, + 1285, 1291, 1290, -1, 2521, 2522, 2001, -1, + 2521, 2001, 1989, -1, 1980, 1979, 1954, -1, + 1980, 1954, 1982, -1, 2520, 2956, 2957, -1, + 2520, 2521, 1989, -1, 1988, 1292, 1987, -1, + 1988, 2002, 1292, -1, 1988, 2001, 2002, -1, + 1988, 1989, 2001, -1, 1984, 2512, 2956, -1, + 1984, 1985, 2512, -1, 1984, 2956, 2520, -1, + 1984, 2520, 1989, -1, 1993, 1995, 1990, -1, + 1993, 2525, 1994, -1, 1299, 1300, 1293, -1, + 1299, 1294, 1298, -1, 1299, 1293, 1295, -1, + 1299, 1295, 1294, -1, 1296, 1298, 1297, -1, + 1296, 1299, 1298, -1, 1296, 1300, 1299, -1, + 1296, 1301, 1300, -1, 1296, 1302, 1301, -1, + 1296, 1297, 1302, -1, 1998, 1999, 1303, -1, + 1998, 1303, 1304, -1, 1998, 1305, 2002, -1, + 1998, 1304, 1305, -1, 2004, 1306, 2009, -1, + 2004, 1996, 1306, -1, 2006, 1307, 2005, -1, + 2006, 1309, 1308, -1, 2006, 1308, 1307, -1, + 2006, 2007, 1309, -1, 2011, 2010, 1310, -1, + 2011, 1310, 1312, -1, 1311, 2532, 2088, -1, + 1311, 2967, 2532, -1, 1311, 2971, 2967, -1, + 1311, 1312, 2971, -1, 1311, 2011, 1312, -1, + 1311, 2088, 2011, -1, 2980, 2011, 2088, -1, + 2975, 2980, 2088, -1, 2021, 2969, 2971, -1, + 2021, 2022, 2969, -1, 2021, 2971, 1312, -1, + 2021, 1312, 2024, -1, 2013, 2012, 1369, -1, + 2013, 1370, 2014, -1, 2094, 2095, 2012, -1, + 2023, 1313, 2095, -1, 2023, 2025, 1313, -1, + 1314, 1315, 1331, -1, 1314, 1331, 1316, -1, + 1314, 1316, 1317, -1, 1314, 1317, 1393, -1, + 1314, 1393, 1318, -1, 1314, 1318, 1315, -1, + 2549, 2028, 1321, -1, 2549, 1321, 1332, -1, + 1323, 2039, 2995, -1, 1323, 1322, 1319, -1, + 1323, 1319, 2038, -1, 1323, 2038, 2039, -1, + 1320, 2995, 2996, -1, 1320, 1332, 1321, -1, + 1320, 2996, 1332, -1, 1320, 1321, 1322, -1, + 1320, 1322, 1323, -1, 1320, 1323, 2995, -1, + 2998, 2995, 2039, -1, 2998, 2037, 2541, -1, + 2998, 2039, 2037, -1, 2997, 2571, 2996, -1, + 2997, 2570, 2571, -1, 2997, 2539, 2570, -1, + 1330, 1327, 2554, -1, 1330, 2554, 3179, -1, + 2630, 2551, 2984, -1, 3224, 3226, 2597, -1, + 3224, 2597, 2631, -1, 1324, 1325, 2029, -1, + 1324, 1326, 1325, -1, 1324, 1327, 1326, -1, + 1324, 2029, 2555, -1, 1324, 2554, 1327, -1, + 1324, 2555, 2554, -1, 2559, 2031, 1381, -1, + 2559, 1381, 1380, -1, 2559, 1380, 2560, -1, + 2561, 1327, 1330, -1, 2561, 1330, 2562, -1, + 2561, 1375, 1327, -1, 2561, 2560, 1375, -1, + 2565, 2031, 2569, -1, 2565, 2564, 1328, -1, + 2565, 1329, 2031, -1, 2565, 1328, 1329, -1, + 3177, 3010, 2562, -1, 3177, 1330, 3179, -1, + 3177, 2562, 1330, -1, 2042, 1331, 2043, -1, + 2042, 2041, 1331, -1, 2042, 3016, 2036, -1, + 2042, 2036, 2041, -1, 2574, 2570, 2539, -1, + 3021, 1332, 2571, -1, 3021, 2549, 1332, -1, + 2048, 2049, 1334, -1, 2048, 1334, 1460, -1, + 2048, 1460, 2045, -1, 3322, 1436, 3323, -1, + 2576, 3028, 1333, -1, 2576, 1333, 1334, -1, + 2576, 1334, 2049, -1, 1599, 1596, 1350, -1, + 1600, 1335, 1336, -1, 1600, 1349, 1335, -1, + 1600, 1599, 1349, -1, 1600, 1336, 1598, -1, + 3219, 3053, 1913, -1, 1337, 1913, 1338, -1, + 1337, 2053, 3220, -1, 1337, 1339, 2053, -1, + 1337, 1338, 1339, -1, 1337, 3219, 1913, -1, + 1337, 3220, 3219, -1, 2054, 3282, 1902, -1, + 2548, 3026, 2546, -1, 2548, 3025, 3026, -1, + 2548, 2054, 3025, -1, 1901, 1900, 3027, -1, + 1901, 3027, 3025, -1, 1901, 3025, 2054, -1, + 1901, 2054, 1902, -1, 3281, 3280, 1340, -1, + 3281, 1340, 1897, -1, 3281, 1897, 1902, -1, + 3281, 1902, 3282, -1, 2057, 2602, 1341, -1, + 2057, 1342, 2056, -1, 2057, 1341, 1342, -1, + 3011, 2057, 2056, -1, 3201, 3202, 2592, -1, + 3201, 2592, 3196, -1, 3341, 2058, 3342, -1, + 2606, 2069, 2602, -1, 3048, 3050, 2056, -1, + 3048, 2056, 1342, -1, 3048, 1342, 2059, -1, + 2062, 2618, 2619, -1, 2062, 2063, 2618, -1, + 2062, 2619, 2066, -1, 1343, 1345, 1344, -1, + 1343, 1344, 2063, -1, 1343, 1346, 1345, -1, + 1343, 2063, 1346, -1, 2064, 1346, 2063, -1, + 2064, 1347, 1346, -1, 2064, 2077, 1347, -1, + 2081, 3057, 2080, -1, 2081, 2613, 3208, -1, + 2629, 2065, 2080, -1, 2070, 2065, 2621, -1, + 2070, 2613, 2081, -1, 2070, 2080, 2065, -1, + 2070, 2081, 2080, -1, 1348, 1352, 2075, -1, + 1348, 1349, 1599, -1, 1348, 2074, 1349, -1, + 1348, 2075, 2074, -1, 1348, 1350, 1352, -1, + 1348, 1599, 1350, -1, 1351, 2075, 1352, -1, + 1351, 1352, 2060, -1, 1351, 2060, 2059, -1, + 1351, 2059, 1353, -1, 1351, 1353, 2072, -1, + 1351, 2072, 2075, -1, 2612, 2611, 2068, -1, + 2615, 1354, 2610, -1, 2615, 2072, 1354, -1, + 2983, 2630, 2984, -1, 2030, 2029, 1355, -1, + 2030, 1355, 2982, -1, 2030, 2982, 2984, -1, + 2030, 2984, 2551, -1, 2082, 2623, 2085, -1, + 2082, 2622, 2623, -1, 2083, 2082, 2085, -1, + 2083, 2634, 2082, -1, 2083, 2084, 2634, -1, + 2644, 1359, 2643, -1, 2644, 2085, 2087, -1, + 2644, 2087, 1359, -1, 1356, 1360, 1361, -1, + 1356, 2643, 1360, -1, 1356, 1361, 1357, -1, + 1356, 2642, 2643, -1, 1356, 1358, 2642, -1, + 1356, 1357, 1358, -1, 2647, 1359, 2087, -1, + 2647, 2648, 1359, -1, 2531, 1360, 2648, -1, + 2531, 2533, 1361, -1, 2531, 1361, 1360, -1, + 2531, 2648, 2645, -1, 2092, 1362, 1364, -1, + 2092, 1363, 1362, -1, 2092, 2090, 1363, -1, + 2093, 1364, 2022, -1, 2093, 2023, 2095, -1, + 2093, 2022, 2023, -1, 2093, 2092, 1364, -1, + 2096, 1366, 1397, -1, 2096, 2097, 1366, -1, + 2656, 2109, 2649, -1, 1365, 1366, 2097, -1, + 1365, 1367, 1366, -1, 1365, 1368, 1367, -1, + 1365, 2097, 2529, -1, 1365, 2528, 1368, -1, + 1365, 2529, 2528, -1, 1384, 1369, 1385, -1, + 1384, 1383, 1370, -1, 1384, 2013, 1369, -1, + 1384, 1370, 2013, -1, 1373, 1379, 1382, -1, + 1373, 1382, 1371, -1, 1373, 2025, 2026, -1, + 1373, 1371, 2025, -1, 1377, 1372, 1376, -1, + 1377, 1379, 1373, -1, 1377, 2026, 1372, -1, + 1377, 1373, 2026, -1, 1374, 1380, 1379, -1, + 1374, 1376, 1375, -1, 1374, 1377, 1376, -1, + 1374, 1379, 1377, -1, 1374, 2560, 1380, -1, + 1374, 1375, 2560, -1, 1378, 1379, 1380, -1, + 1378, 1380, 1381, -1, 1378, 1381, 1387, -1, + 1378, 1387, 1390, -1, 1378, 1390, 1382, -1, + 1378, 1382, 1379, -1, 1392, 1391, 1383, -1, + 1392, 1383, 1384, -1, 1392, 1384, 1385, -1, + 1392, 1385, 1390, -1, 1386, 1387, 1388, -1, + 1386, 1388, 1389, -1, 1386, 1390, 1387, -1, + 1386, 1389, 1391, -1, 1386, 1392, 1390, -1, + 1386, 1391, 1392, -1, 1398, 1404, 1403, -1, + 1398, 1396, 1393, -1, 1398, 1393, 1394, -1, + 1398, 1394, 1404, -1, 1395, 1397, 1396, -1, + 1395, 1403, 2654, -1, 1395, 1396, 1398, -1, + 1395, 1398, 1403, -1, 1395, 2096, 1397, -1, + 1395, 2654, 2096, -1, 2100, 2663, 1399, -1, + 2100, 1399, 2101, -1, 2671, 2670, 2678, -1, + 2671, 2678, 2676, -1, 2671, 2676, 2107, -1, + 1400, 2649, 2109, -1, 1400, 1401, 2664, -1, + 1400, 2111, 1401, -1, 1400, 2109, 2111, -1, + 1400, 2664, 1402, -1, 1400, 1402, 2649, -1, + 2677, 2111, 2109, -1, 2110, 1403, 1404, -1, + 2110, 1404, 1405, -1, 2110, 1405, 2675, -1, + 2110, 2655, 1403, -1, 1406, 1430, 1407, -1, + 1406, 1408, 2113, -1, 1406, 1407, 1408, -1, + 1406, 2113, 1409, -1, 1406, 1409, 1410, -1, + 1406, 1410, 1430, -1, 2115, 2118, 1411, -1, + 2115, 1411, 1412, -1, 2115, 1412, 1413, -1, + 2115, 1413, 2144, -1, 2123, 2684, 2104, -1, + 2123, 2104, 2122, -1, 2682, 1414, 2681, -1, + 2682, 1415, 1414, -1, 2682, 2125, 1415, -1, + 2128, 1416, 2116, -1, 2128, 2138, 2136, -1, + 2128, 2136, 1416, -1, 2129, 2116, 2117, -1, + 2129, 2128, 2116, -1, 1417, 1429, 2131, -1, + 1417, 2154, 1429, -1, 1417, 1418, 2154, -1, + 1417, 2117, 1418, -1, 1417, 2129, 2117, -1, + 1417, 2131, 2129, -1, 2142, 2143, 1418, -1, + 2142, 1418, 2117, -1, 2120, 1419, 2124, -1, + 2120, 2141, 2140, -1, 2120, 1420, 1419, -1, + 2120, 2140, 1420, -1, 1421, 3076, 1428, -1, + 1421, 2688, 3076, -1, 1421, 1422, 2688, -1, + 1421, 1423, 1422, -1, 1421, 1426, 1423, -1, + 1421, 1428, 1426, -1, 1424, 2150, 1425, -1, + 1424, 1425, 1426, -1, 1424, 2151, 2150, -1, + 1424, 1427, 2151, -1, 1424, 1428, 1427, -1, + 1424, 1426, 1428, -1, 2147, 2161, 2160, -1, + 2147, 1429, 2161, -1, 2147, 2152, 1429, -1, + 2147, 2160, 2148, -1, 2157, 2166, 2165, -1, + 2157, 2153, 2166, -1, 2157, 2165, 2158, -1, + 2164, 1430, 1941, -1, 2164, 1941, 2951, -1, + 2164, 1431, 1430, -1, 2164, 2167, 1431, -1, + 1432, 2153, 1433, -1, 1432, 1434, 1435, -1, + 1432, 1433, 1434, -1, 1432, 1435, 2167, -1, + 1432, 2167, 2166, -1, 1432, 2166, 2153, -1, + 2052, 1437, 1436, -1, 2052, 1439, 1437, -1, + 2052, 2051, 1439, -1, 2052, 1436, 3322, -1, + 1438, 2046, 1459, -1, 1438, 1439, 2046, -1, + 1438, 1440, 1439, -1, 1438, 1459, 1453, -1, + 1438, 1447, 1440, -1, 1438, 1453, 1447, -1, + 2204, 2203, 1443, -1, 2204, 1443, 1444, -1, + 2204, 1441, 2205, -1, 2204, 1444, 1441, -1, + 1442, 1444, 1443, -1, 1442, 1445, 1446, -1, + 1442, 1447, 1445, -1, 1442, 1443, 1447, -1, + 1442, 1446, 1448, -1, 1442, 1448, 1444, -1, + 2691, 1449, 2693, -1, 2691, 2168, 1449, -1, + 3143, 1450, 2168, -1, 3143, 3142, 1451, -1, + 3143, 1451, 1450, -1, 1454, 1457, 2692, -1, + 1454, 1452, 1455, -1, 1454, 2693, 1452, -1, + 1454, 2692, 2693, -1, 3144, 3143, 2168, -1, + 1458, 1453, 1459, -1, 1458, 1457, 1454, -1, + 1458, 1455, 1453, -1, 1458, 1454, 1455, -1, + 2694, 2692, 1457, -1, 2694, 1457, 1463, -1, + 1456, 1463, 1457, -1, 1456, 1457, 1458, -1, + 1456, 1458, 1459, -1, 1456, 1459, 2045, -1, + 1456, 2045, 1460, -1, 1456, 1460, 1463, -1, + 1461, 1462, 2695, -1, 1461, 1463, 1464, -1, + 1461, 2695, 2694, -1, 1461, 2694, 1463, -1, + 1461, 1464, 1465, -1, 1461, 1465, 1462, -1, + 1466, 1468, 1467, -1, 1466, 1470, 1469, -1, + 1466, 1471, 1470, -1, 1466, 1467, 1471, -1, + 1466, 1472, 1468, -1, 1466, 1469, 1472, -1, + 1473, 1474, 1475, -1, 1473, 1475, 1476, -1, + 1473, 1477, 1474, -1, 1473, 1476, 1477, -1, + 1478, 1479, 2027, -1, 1478, 2172, 1480, -1, + 1478, 2578, 2172, -1, 1478, 2027, 2578, -1, + 1478, 1480, 1481, -1, 1478, 1481, 1479, -1, + 1484, 2177, 1486, -1, 1484, 1486, 1482, -1, + 1484, 1483, 2174, -1, 1484, 1482, 1483, -1, + 2173, 2581, 2177, -1, 2173, 1484, 2174, -1, + 2173, 2177, 1484, -1, 1489, 1491, 1485, -1, + 1489, 1485, 1486, -1, 1489, 1486, 2176, -1, + 1489, 2176, 2188, -1, 1487, 2187, 1488, -1, + 1487, 2188, 2187, -1, 1487, 1489, 2188, -1, + 1487, 1488, 1490, -1, 1487, 1490, 1491, -1, + 1487, 1491, 1489, -1, 2184, 1494, 2185, -1, + 2183, 2188, 2176, -1, 2181, 2179, 1492, -1, + 2181, 1493, 1494, -1, 2181, 1492, 1493, -1, + 2181, 1494, 2184, -1, 1495, 1532, 1496, -1, + 1495, 1497, 1532, -1, 1495, 1496, 2739, -1, + 1495, 1559, 1497, -1, 1495, 2740, 1559, -1, + 1495, 2739, 2740, -1, 1502, 1503, 1498, -1, + 1502, 1498, 1499, -1, 2736, 1499, 1500, -1, + 2736, 1500, 1501, -1, 2736, 1502, 1499, -1, + 2736, 1503, 1502, -1, 2736, 1501, 2735, -1, + 2736, 2734, 1503, -1, 1504, 1505, 1508, -1, + 1504, 1508, 1510, -1, 1504, 1506, 1505, -1, + 1504, 1510, 1506, -1, 1507, 1508, 1509, -1, + 1507, 1509, 1510, -1, 1507, 1510, 1508, -1, + 1511, 1512, 1513, -1, 1511, 1513, 1514, -1, + 1511, 1515, 1512, -1, 1511, 1514, 1515, -1, + 2192, 1516, 2190, -1, 2192, 2193, 1516, -1, + 1520, 2198, 1517, -1, 1520, 1517, 1519, -1, + 2197, 2190, 1518, -1, 2197, 1519, 2190, -1, + 2197, 2198, 1520, -1, 2197, 1520, 1519, -1, + 2197, 1518, 2195, -1, 2199, 1582, 1521, -1, + 2199, 1521, 1522, -1, 2199, 1522, 1523, -1, + 2199, 1523, 2207, -1, 2199, 2207, 2202, -1, + 2703, 2205, 2206, -1, 2715, 1524, 2716, -1, + 2715, 1525, 1524, -1, 2715, 2208, 1525, -1, + 2718, 1526, 2720, -1, 2718, 1530, 1526, -1, + 1527, 1528, 1554, -1, 1527, 2716, 1528, -1, + 1527, 1554, 1529, -1, 1527, 2718, 2716, -1, + 1527, 1529, 1530, -1, 1527, 1530, 2718, -1, + 1531, 1532, 1533, -1, 1531, 1534, 1532, -1, + 1531, 1533, 1535, -1, 1531, 1535, 1536, -1, + 1531, 1536, 1537, -1, 1531, 1537, 1538, -1, + 1531, 1538, 1534, -1, 1539, 1541, 1540, -1, + 1539, 1542, 1541, -1, 1539, 1543, 1542, -1, + 1539, 1553, 1543, -1, 1539, 1552, 1553, -1, + 1539, 1540, 1552, -1, 1544, 1546, 1545, -1, + 1544, 1547, 1546, -1, 1544, 1548, 1547, -1, + 1544, 1549, 1548, -1, 1544, 1550, 1549, -1, + 1544, 1545, 1550, -1, 1551, 2732, 1578, -1, + 1551, 1578, 1571, -1, 2721, 1571, 2722, -1, + 2721, 1551, 1571, -1, 2721, 2217, 1551, -1, + 2731, 2732, 1551, -1, 2731, 1551, 2217, -1, + 2218, 3082, 1566, -1, 2218, 1566, 2212, -1, + 2729, 2735, 2225, -1, 2738, 1552, 2745, -1, + 2738, 1553, 1552, -1, 2738, 2739, 1553, -1, + 2744, 1555, 1554, -1, 2744, 2745, 1555, -1, + 2744, 1554, 1556, -1, 2744, 1556, 2747, -1, + 1557, 1561, 1560, -1, 1557, 2741, 1558, -1, + 1557, 1558, 1561, -1, 1557, 2740, 2741, -1, + 1557, 1559, 2740, -1, 1557, 1560, 1559, -1, + 2226, 1560, 1561, -1, 2226, 1561, 2224, -1, + 2226, 2227, 1562, -1, 2226, 1562, 1560, -1, + 1563, 1880, 1878, -1, 1563, 1878, 2700, -1, + 1563, 2698, 1880, -1, 1563, 2700, 2698, -1, + 1564, 3082, 1565, -1, 1564, 1566, 3082, -1, + 1564, 1565, 1567, -1, 1564, 1567, 1566, -1, + 1577, 1575, 1568, -1, 1577, 1572, 1576, -1, + 1577, 1568, 1569, -1, 1577, 1569, 1572, -1, + 1570, 2722, 1571, -1, 1570, 1571, 1576, -1, + 1570, 1576, 1572, -1, 1570, 1573, 2722, -1, + 1570, 1572, 1574, -1, 1570, 1574, 1573, -1, + 1579, 2726, 1575, -1, 1579, 1576, 1578, -1, + 1579, 1575, 1577, -1, 1579, 1577, 1576, -1, + 2725, 1578, 2732, -1, 2725, 1579, 1578, -1, + 2725, 2726, 1579, -1, 2229, 1580, 2232, -1, + 2229, 2230, 1580, -1, 1581, 2234, 1582, -1, + 1581, 2200, 2234, -1, 1581, 1582, 2199, -1, + 1581, 2199, 2200, -1, 2699, 2700, 2234, -1, + 1583, 1590, 1584, -1, 1583, 1584, 1585, -1, + 1583, 1585, 1586, -1, 1583, 1586, 1587, -1, + 1583, 1587, 1588, -1, 1583, 1588, 1590, -1, + 1589, 1590, 1591, -1, 1589, 1957, 1592, -1, + 1589, 1591, 1957, -1, 1589, 1592, 1593, -1, + 1589, 1593, 1594, -1, 1589, 1594, 1590, -1, + 1595, 1921, 1596, -1, 1595, 1597, 1921, -1, + 1595, 1598, 1597, -1, 1595, 1596, 1599, -1, + 1595, 1600, 1598, -1, 1595, 1599, 1600, -1, + 2236, 1601, 2237, -1, 2236, 2238, 1602, -1, + 2236, 1603, 1604, -1, 2236, 1602, 1605, -1, + 2236, 1605, 1603, -1, 2236, 1604, 1606, -1, + 2236, 1606, 1601, -1, 1607, 1609, 1608, -1, + 1607, 1687, 1688, -1, 1607, 1610, 1687, -1, + 1607, 1608, 1610, -1, 1607, 1688, 1611, -1, + 1607, 1611, 1609, -1, 2243, 1612, 2241, -1, + 2243, 1613, 1612, -1, 2243, 2253, 1614, -1, + 2243, 1614, 1613, -1, 3098, 1615, 2246, -1, + 3098, 3099, 1615, -1, 2765, 1616, 2251, -1, + 2765, 2764, 1616, -1, 1617, 1618, 1619, -1, + 1617, 1666, 1620, -1, 1617, 1619, 1666, -1, + 1617, 1620, 1621, -1, 1617, 1621, 1618, -1, + 2278, 2776, 1622, -1, 2768, 2275, 2271, -1, + 1628, 1622, 1626, -1, 1628, 2771, 2769, -1, + 1628, 2278, 1622, -1, 1628, 2769, 2278, -1, + 1623, 1624, 2771, -1, 1623, 1626, 1625, -1, + 1623, 1625, 1627, -1, 1623, 1627, 1624, -1, + 1623, 1628, 1626, -1, 1623, 2771, 1628, -1, + 2265, 2259, 2264, -1, 2265, 2267, 2261, -1, + 1809, 1629, 1808, -1, 1809, 2259, 1629, -1, + 1809, 1810, 2264, -1, 1809, 2264, 2259, -1, + 2783, 2274, 2781, -1, 2783, 2779, 1630, -1, + 2260, 2781, 2274, -1, 2260, 1629, 2259, -1, + 2260, 2273, 1629, -1, 2260, 2274, 2273, -1, + 2270, 1630, 2276, -1, 2270, 2783, 1630, -1, + 2270, 2274, 2783, -1, 2270, 2276, 2271, -1, + 2775, 2276, 1630, -1, 2775, 1630, 2279, -1, + 2281, 2282, 1631, -1, 2281, 1631, 2280, -1, + 2281, 2280, 2279, -1, 2281, 2279, 2779, -1, + 2780, 1632, 2782, -1, 2780, 2261, 1632, -1, + 1633, 1635, 1634, -1, 1633, 1637, 1636, -1, + 1633, 1636, 1635, -1, 1633, 1638, 1637, -1, + 1633, 1639, 1638, -1, 1633, 1634, 1639, -1, + 2288, 1640, 1641, -1, 2288, 2289, 1640, -1, + 2288, 1641, 1642, -1, 2288, 1642, 2287, -1, + 2294, 1643, 2292, -1, 2294, 1644, 1643, -1, + 2294, 1645, 1644, -1, 2294, 1646, 1645, -1, + 2294, 1647, 1646, -1, 2294, 2295, 1647, -1, + 1648, 1649, 1650, -1, 1648, 1652, 1651, -1, + 1648, 1651, 1653, -1, 1648, 1653, 1649, -1, + 1648, 1650, 1654, -1, 1648, 1654, 1652, -1, + 2794, 2300, 2298, -1, 2301, 1655, 2788, -1, + 2301, 2788, 2792, -1, 2301, 2302, 1656, -1, + 2301, 1656, 1655, -1, 1657, 1658, 1659, -1, + 1657, 1660, 1658, -1, 1657, 1661, 1660, -1, + 1657, 1659, 1662, -1, 1657, 1663, 1661, -1, + 1657, 1662, 1663, -1, 1664, 1671, 1665, -1, + 1664, 1667, 1666, -1, 1664, 1665, 1667, -1, + 1664, 1666, 1678, -1, 1664, 1677, 1671, -1, + 1664, 1678, 1677, -1, 1684, 1671, 1677, -1, + 1684, 1677, 1683, -1, 1668, 1670, 1669, -1, + 1668, 1669, 1671, -1, 1668, 1672, 1670, -1, + 1668, 1671, 1684, -1, 1668, 1681, 1672, -1, + 1668, 1684, 1681, -1, 2787, 1673, 2785, -1, + 2787, 1674, 1673, -1, 2787, 2788, 1675, -1, + 2787, 1675, 1674, -1, 1676, 1683, 1677, -1, + 1676, 1677, 1678, -1, 1676, 1678, 1679, -1, + 1676, 1679, 1689, -1, 1676, 1689, 2307, -1, + 1676, 2307, 1683, -1, 1680, 1682, 1681, -1, + 1680, 1683, 2808, -1, 1680, 1681, 1684, -1, + 1680, 1684, 1683, -1, 1680, 2807, 1682, -1, + 1680, 2808, 2807, -1, 2804, 2305, 1685, -1, + 2804, 1685, 1686, -1, 2804, 1686, 2805, -1, + 2306, 1687, 2305, -1, 2306, 1688, 1687, -1, + 2306, 1689, 1688, -1, 2306, 2307, 1689, -1, + 2314, 1712, 2315, -1, 2314, 2309, 1712, -1, + 2316, 2315, 1691, -1, 2316, 1691, 1692, -1, + 2316, 2302, 2318, -1, 2316, 1692, 2302, -1, + 1690, 1692, 1691, -1, 1690, 1693, 1692, -1, + 1690, 1691, 1694, -1, 1690, 1694, 1693, -1, + 2323, 1696, 1695, -1, 2323, 2324, 1696, -1, + 2323, 1695, 1697, -1, 2323, 1697, 2321, -1, + 1698, 1700, 1699, -1, 1698, 1722, 1700, -1, + 1698, 1699, 1722, -1, 1701, 1703, 1702, -1, + 1701, 1702, 1704, -1, 1701, 1704, 1705, -1, + 1701, 1706, 1703, -1, 1701, 1705, 1706, -1, + 1707, 1708, 1709, -1, 1707, 1710, 1711, -1, + 1707, 1709, 1710, -1, 1707, 1711, 1712, -1, + 1707, 1712, 2309, -1, 1707, 2309, 1708, -1, + 1713, 1714, 1715, -1, 1713, 1716, 1714, -1, + 1713, 1715, 1717, -1, 1713, 1717, 1716, -1, + 1718, 1719, 1726, -1, 1718, 1726, 1725, -1, + 1718, 1720, 1719, -1, 1718, 1721, 1720, -1, + 1718, 1722, 1721, -1, 1718, 1723, 1722, -1, + 1718, 1725, 1723, -1, 1724, 1725, 1726, -1, + 1724, 1728, 1727, -1, 1724, 1727, 1729, -1, + 1724, 1729, 1725, -1, 1724, 1730, 1728, -1, + 1724, 1726, 1730, -1, 2328, 1731, 2329, -1, + 2328, 2332, 1732, -1, 2328, 1733, 1731, -1, + 2328, 1732, 1733, -1, 3087, 3089, 1734, -1, + 3087, 1734, 1735, -1, 3087, 1736, 2751, -1, + 3087, 1737, 1736, -1, 3087, 1735, 1737, -1, + 3092, 2334, 2336, -1, 1741, 1743, 1744, -1, + 1741, 1738, 1740, -1, 1741, 1744, 1739, -1, + 1741, 1739, 1738, -1, 2335, 1740, 2334, -1, + 2335, 2812, 1743, -1, 2335, 1741, 1740, -1, + 2335, 1743, 1741, -1, 2399, 2400, 1749, -1, + 2399, 1749, 2817, -1, 1742, 1743, 1746, -1, + 1742, 1746, 2400, -1, 1742, 2400, 2401, -1, + 1742, 1744, 1743, -1, 1742, 2401, 1745, -1, + 1742, 1745, 1744, -1, 2811, 1749, 1746, -1, + 2811, 1746, 2812, -1, 2818, 1747, 2824, -1, + 2818, 2814, 2820, -1, 2818, 2820, 1748, -1, + 2818, 1748, 1747, -1, 2341, 2338, 2814, -1, + 2341, 2814, 3111, -1, 3113, 2811, 3112, -1, + 3113, 2817, 1749, -1, 3113, 1749, 2811, -1, + 1750, 1751, 1752, -1, 1750, 2364, 2363, -1, + 1750, 1753, 1751, -1, 1750, 2363, 1753, -1, + 1750, 1752, 1754, -1, 1750, 1754, 2364, -1, + 2347, 1756, 2345, -1, 2347, 2348, 1756, -1, + 1755, 1756, 2348, -1, 1755, 1767, 1757, -1, + 1755, 1757, 1758, -1, 1755, 1758, 1756, -1, + 1755, 2348, 1769, -1, 1755, 1769, 1767, -1, + 1759, 2383, 2345, -1, 1759, 2345, 1760, -1, + 1759, 1760, 1761, -1, 1759, 1762, 2383, -1, + 1759, 1761, 1781, -1, 1759, 1781, 1762, -1, + 2356, 3130, 3129, -1, 2356, 2354, 3130, -1, + 2356, 1770, 2358, -1, 2356, 3129, 1770, -1, + 1763, 1768, 2354, -1, 1763, 1764, 1765, -1, + 1763, 2355, 1764, -1, 1763, 2354, 2355, -1, + 1763, 1765, 1766, -1, 1763, 1766, 1768, -1, + 3131, 1768, 1767, -1, 3131, 3130, 1768, -1, + 3131, 1767, 1769, -1, 3131, 1769, 3132, -1, + 2361, 1770, 3129, -1, 2361, 2360, 1771, -1, + 2361, 1771, 1772, -1, 2361, 1772, 1770, -1, + 2837, 2362, 2360, -1, 2843, 2366, 2368, -1, + 2846, 2847, 1773, -1, 2846, 1773, 2841, -1, + 2377, 1774, 2370, -1, 2377, 1775, 1774, -1, + 2377, 2378, 1775, -1, 2963, 3254, 2423, -1, + 2963, 2848, 2964, -1, 2863, 3164, 3234, -1, + 2863, 3159, 3164, -1, 2839, 2853, 2860, -1, + 2839, 2842, 2367, -1, 2839, 1776, 2853, -1, + 2839, 2367, 1776, -1, 1777, 3138, 3304, -1, + 1777, 2351, 2386, -1, 1777, 2386, 3138, -1, + 1777, 2349, 2351, -1, 1777, 1778, 2349, -1, + 1777, 3304, 1778, -1, 2865, 3238, 1856, -1, + 2865, 1857, 2864, -1, 1779, 1781, 1780, -1, + 1779, 1782, 1781, -1, 1779, 1780, 1783, -1, + 1779, 1784, 1782, -1, 1779, 1783, 1785, -1, + 1779, 1785, 1784, -1, 2402, 1795, 2401, -1, + 2402, 2394, 1795, -1, 2397, 2398, 2830, -1, + 2397, 2830, 2392, -1, 1786, 1788, 1787, -1, + 1786, 1787, 1800, -1, 1786, 1800, 1789, -1, + 1786, 2436, 1788, -1, 1786, 1789, 2910, -1, + 1786, 2910, 2436, -1, 1790, 1798, 1791, -1, + 1790, 1792, 1798, -1, 1790, 1794, 1793, -1, + 1790, 1791, 1794, -1, 1790, 2394, 1792, -1, + 1790, 1795, 2394, -1, 1790, 1793, 1795, -1, + 1796, 1797, 1803, -1, 1796, 1799, 1798, -1, + 1796, 1798, 1797, -1, 1796, 1800, 1799, -1, + 1796, 1801, 1800, -1, 1796, 1803, 1801, -1, + 1807, 1802, 1805, -1, 1807, 1803, 1802, -1, + 1807, 1806, 1803, -1, 1804, 1805, 2864, -1, + 1804, 1858, 1806, -1, 1804, 1807, 1805, -1, + 1804, 1806, 1807, -1, 1804, 2864, 1857, -1, + 1804, 1857, 1858, -1, 1811, 1808, 2870, -1, + 1811, 1809, 1808, -1, 1811, 1812, 1810, -1, + 1811, 1810, 1809, -1, 2406, 1820, 2403, -1, + 2406, 1813, 1820, -1, 2872, 1811, 2870, -1, + 2872, 2404, 1812, -1, 2872, 1812, 1811, -1, + 2405, 1814, 1813, -1, 2405, 2407, 1815, -1, + 2405, 1815, 1814, -1, 2405, 1813, 2406, -1, + 1816, 1817, 1818, -1, 1816, 1819, 2403, -1, + 1816, 2403, 1820, -1, 1816, 1820, 1817, -1, + 1816, 1821, 1819, -1, 1816, 1818, 1821, -1, + 2409, 2410, 1822, -1, 2409, 1822, 1823, -1, + 2409, 1824, 2892, -1, 2409, 1823, 1824, -1, + 2874, 2416, 2876, -1, 2894, 2879, 2878, -1, + 1825, 1826, 2901, -1, 1825, 1827, 1826, -1, + 1825, 1828, 1827, -1, 1825, 1849, 1828, -1, + 1825, 2419, 1849, -1, 1825, 2901, 2419, -1, + 2899, 1829, 2421, -1, 2899, 2418, 1829, -1, + 1830, 1831, 1832, -1, 1830, 1834, 1833, -1, + 1830, 1833, 1839, -1, 1830, 1839, 1831, -1, + 1830, 1832, 1835, -1, 1830, 1835, 1834, -1, + 1836, 1837, 1840, -1, 1836, 3265, 1838, -1, + 1836, 1838, 1839, -1, 1836, 1839, 1837, -1, + 1836, 1840, 3260, -1, 1836, 3260, 3265, -1, + 2518, 1840, 2426, -1, 2518, 3260, 1840, -1, + 2379, 2374, 2381, -1, 2379, 2381, 2423, -1, + 2379, 1841, 2378, -1, 2424, 1842, 1841, -1, + 2424, 2425, 1842, -1, 2424, 1841, 2379, -1, + 2424, 2379, 2423, -1, 1847, 2432, 2516, -1, + 1847, 1843, 1846, -1, 1847, 2516, 1977, -1, + 1847, 1977, 1843, -1, 2517, 2431, 1844, -1, + 2517, 2432, 2431, -1, 2517, 1844, 2962, -1, + 2517, 2516, 2432, -1, 2428, 1845, 2429, -1, + 2428, 1846, 1845, -1, 2428, 1847, 1846, -1, + 2428, 2432, 1847, -1, 1853, 1848, 1850, -1, + 1853, 2433, 2429, -1, 1853, 2429, 1848, -1, + 1853, 1850, 1863, -1, 1851, 1849, 2419, -1, + 1851, 1850, 1849, -1, 1851, 2419, 2420, -1, + 1851, 2907, 1850, -1, 2906, 2420, 2434, -1, + 2906, 1851, 2420, -1, 2906, 2907, 1851, -1, + 1865, 1862, 1852, -1, 1865, 1853, 1863, -1, + 1865, 1852, 2433, -1, 1865, 2433, 1853, -1, + 1854, 1862, 1861, -1, 1854, 1856, 1855, -1, + 1854, 1855, 1862, -1, 1854, 2865, 1856, -1, + 1854, 1861, 1857, -1, 1854, 1857, 2865, -1, + 1864, 1858, 1861, -1, 1864, 1859, 1858, -1, + 1864, 2909, 1859, -1, 1864, 2908, 2909, -1, + 1860, 1861, 1862, -1, 1860, 1863, 2908, -1, + 1860, 2908, 1864, -1, 1860, 1864, 1861, -1, + 1860, 1862, 1865, -1, 1860, 1865, 1863, -1, + 2927, 1872, 1871, -1, 2927, 1875, 1872, -1, + 2927, 1871, 1866, -1, 2927, 1866, 2933, -1, + 1873, 1872, 1875, -1, 1873, 1875, 1867, -1, + 1873, 1868, 1870, -1, 1873, 1867, 1868, -1, + 1869, 1870, 1871, -1, 1869, 1871, 1872, -1, + 1869, 1873, 1870, -1, 1869, 1872, 1873, -1, + 2931, 2437, 2440, -1, 2931, 2919, 2437, -1, + 1874, 2928, 2925, -1, 1874, 1875, 2927, -1, + 1874, 2927, 2928, -1, 1874, 1876, 1875, -1, + 1874, 2913, 1876, -1, 1874, 2925, 2913, -1, + 2924, 2442, 2912, -1, 2924, 2912, 2925, -1, + 1877, 1882, 1881, -1, 1877, 1881, 1878, -1, + 1877, 1879, 1882, -1, 1877, 1880, 1879, -1, + 1877, 1878, 1880, -1, 2447, 2448, 1881, -1, + 2447, 1881, 1882, -1, 2447, 1882, 2445, -1, + 2922, 2446, 2445, -1, 2922, 1883, 2915, -1, + 2922, 2445, 1883, -1, 2922, 2921, 1884, -1, + 2922, 1884, 2446, -1, 2935, 2936, 1893, -1, + 2935, 1885, 2450, -1, 2935, 1893, 1885, -1, + 2462, 3246, 2463, -1, 3247, 3147, 1898, -1, + 3247, 1886, 3248, -1, 3247, 1898, 1886, -1, + 1887, 1888, 1889, -1, 1887, 1889, 2453, -1, + 1887, 3248, 1888, -1, 1887, 2453, 2463, -1, + 1887, 3246, 3248, -1, 1887, 2463, 3246, -1, + 2945, 2944, 1890, -1, 2945, 1891, 2455, -1, + 2945, 1890, 1891, -1, 1892, 1893, 2457, -1, + 1892, 1894, 1893, -1, 1892, 2457, 2460, -1, + 1892, 2460, 2461, -1, 1892, 2461, 1895, -1, + 1892, 1895, 1894, -1, 1896, 1897, 1898, -1, + 1896, 1899, 1900, -1, 1896, 1898, 1899, -1, + 1896, 1900, 1901, -1, 1896, 1902, 1897, -1, + 1896, 1901, 1902, -1, 2467, 2451, 2449, -1, + 2467, 2449, 2468, -1, 2467, 2472, 1903, -1, + 2467, 1903, 2451, -1, 2476, 1904, 2470, -1, + 2476, 2470, 2474, -1, 2476, 1905, 1904, -1, + 2476, 2477, 1905, -1, 2482, 1906, 1907, -1, + 2482, 2486, 1906, -1, 2482, 1907, 1908, -1, + 2482, 1908, 2483, -1, 1909, 1911, 1910, -1, + 1909, 1910, 1912, -1, 1909, 2605, 1911, -1, + 1909, 3043, 2605, -1, 1909, 1912, 3043, -1, + 3044, 3043, 1912, -1, 3044, 1913, 3053, -1, + 3044, 1914, 1913, -1, 3044, 1912, 1914, -1, + 1915, 1917, 1916, -1, 1915, 1916, 1918, -1, + 1915, 1919, 1917, -1, 1915, 1918, 1920, -1, + 1915, 1920, 1921, -1, 1915, 1921, 1919, -1, + 1930, 1926, 1922, -1, 1930, 1923, 1929, -1, + 1930, 1922, 1924, -1, 1930, 1924, 1923, -1, + 1925, 1927, 1926, -1, 1925, 1928, 1932, -1, + 1925, 1932, 1927, -1, 1925, 1929, 1928, -1, + 1925, 1930, 1929, -1, 1925, 1926, 1930, -1, + 1931, 1932, 1933, -1, 1931, 1934, 1932, -1, + 1931, 1933, 1935, -1, 1931, 1935, 1934, -1, + 2488, 2489, 1936, -1, 2488, 1936, 1937, -1, + 2488, 1937, 1938, -1, 2488, 1938, 2490, -1, + 3150, 2490, 1939, -1, 3150, 1939, 3152, -1, + 2950, 1940, 2489, -1, 2950, 2951, 1941, -1, + 2950, 1941, 1940, -1, 1942, 2668, 1943, -1, + 1942, 1943, 1944, -1, 1942, 1944, 1945, -1, + 1942, 1945, 1946, -1, 1942, 1946, 2669, -1, + 1942, 2669, 2668, -1, 2881, 1949, 2884, -1, + 2881, 1947, 1949, -1, 2881, 1948, 1947, -1, + 2881, 2882, 1948, -1, 2492, 1949, 2266, -1, + 2492, 2884, 1949, -1, 2492, 2266, 2263, -1, + 2492, 2263, 2493, -1, 2660, 1950, 2661, -1, + 2660, 2497, 1950, -1, 2660, 2680, 2497, -1, + 2660, 2685, 2680, -1, 2502, 2500, 1950, -1, + 2502, 1950, 2497, -1, 2502, 2497, 2510, -1, + 1951, 2856, 1959, -1, 1951, 1953, 1952, -1, + 1951, 1959, 1953, -1, 1951, 1952, 1954, -1, + 1951, 1954, 1979, -1, 1951, 1979, 2856, -1, + 1955, 2852, 1956, -1, 1955, 1957, 1958, -1, + 1955, 1956, 1957, -1, 1955, 1958, 1959, -1, + 1955, 1959, 2857, -1, 1955, 2857, 2852, -1, + 2970, 1960, 2537, -1, 2970, 1961, 1960, -1, + 2970, 2968, 1961, -1, 1962, 1964, 1963, -1, + 1962, 1965, 1964, -1, 1962, 1966, 1965, -1, + 1962, 2537, 1966, -1, 1962, 2536, 2537, -1, + 1962, 1963, 2536, -1, 1970, 2498, 1967, -1, + 1970, 1968, 2506, -1, 1970, 1967, 1969, -1, + 1970, 1969, 1968, -1, 2508, 1970, 2506, -1, + 2508, 2498, 1970, -1, 1971, 1972, 1973, -1, + 1971, 1974, 1975, -1, 1971, 1975, 1976, -1, + 1971, 1976, 1972, -1, 1971, 1973, 1986, -1, + 1971, 1986, 1974, -1, 2514, 1977, 2515, -1, + 2514, 1978, 1977, -1, 2514, 2512, 1978, -1, + 2960, 3264, 2959, -1, 3259, 3260, 2518, -1, + 3161, 3160, 1979, -1, 3161, 1979, 1980, -1, + 3161, 1980, 2522, -1, 2000, 2522, 1980, -1, + 2000, 1981, 1999, -1, 2000, 1982, 1981, -1, + 2000, 1980, 1982, -1, 1983, 1985, 1984, -1, + 1983, 1987, 1986, -1, 1983, 1986, 1985, -1, + 1983, 1988, 1987, -1, 1983, 1989, 1988, -1, + 1983, 1984, 1989, -1, 2524, 1990, 1991, -1, + 2524, 1993, 1990, -1, 2524, 1991, 2528, -1, + 2524, 2525, 1993, -1, 1992, 1993, 1994, -1, + 1992, 2004, 2005, -1, 1992, 2005, 1995, -1, + 1992, 1995, 1993, -1, 1992, 1994, 1996, -1, + 1992, 1996, 2004, -1, 1997, 1999, 1998, -1, + 1997, 2000, 1999, -1, 1997, 2522, 2000, -1, + 1997, 2001, 2522, -1, 1997, 2002, 2001, -1, + 1997, 1998, 2002, -1, 2003, 2005, 2004, -1, + 2003, 2007, 2006, -1, 2003, 2006, 2005, -1, + 2003, 2008, 2007, -1, 2003, 2009, 2008, -1, + 2003, 2004, 2009, -1, 2535, 2532, 2967, -1, + 2535, 2536, 2533, -1, 2979, 2982, 2010, -1, + 2979, 2010, 2011, -1, 2979, 2011, 2980, -1, + 2977, 2646, 2973, -1, 2019, 2094, 2012, -1, + 2019, 2013, 2014, -1, 2019, 2012, 2013, -1, + 2019, 2014, 2018, -1, 2015, 2016, 2091, -1, + 2015, 2091, 2094, -1, 2015, 2017, 2016, -1, + 2015, 2018, 2017, -1, 2015, 2019, 2018, -1, + 2015, 2094, 2019, -1, 2020, 2022, 2021, -1, + 2020, 2023, 2022, -1, 2020, 2021, 2024, -1, + 2020, 2025, 2023, -1, 2020, 2026, 2025, -1, + 2020, 2024, 2026, -1, 3038, 3008, 3036, -1, + 2556, 3172, 2567, -1, 2985, 3038, 3039, -1, + 2985, 3008, 3038, -1, 3037, 3269, 3197, -1, + 2994, 2998, 2541, -1, 2545, 2989, 2991, -1, + 2545, 2546, 2542, -1, 2550, 2027, 2028, -1, + 2550, 2028, 2549, -1, 2550, 3029, 2027, -1, + 3005, 2631, 2597, -1, 3000, 2999, 2555, -1, + 3000, 2555, 2029, -1, 3000, 2030, 2551, -1, + 3000, 2029, 2030, -1, 3004, 2551, 2630, -1, + 3004, 2630, 2631, -1, 3004, 2631, 3005, -1, + 2553, 2999, 3002, -1, 2553, 3002, 3272, -1, + 2553, 3270, 3175, -1, 2553, 3272, 3270, -1, + 3178, 3036, 3008, -1, 3178, 3037, 3036, -1, + 3180, 3272, 3002, -1, 2558, 2567, 2569, -1, + 2558, 2569, 2031, -1, 2558, 2031, 2559, -1, + 2044, 2564, 3018, -1, 2044, 2043, 2032, -1, + 2044, 2033, 2564, -1, 2044, 2032, 2033, -1, + 2563, 2562, 3010, -1, 2563, 2567, 2558, -1, + 2563, 3010, 2556, -1, 2563, 2556, 2567, -1, + 2034, 2037, 2036, -1, 2034, 3017, 2543, -1, + 2034, 3016, 3017, -1, 2034, 2036, 3016, -1, + 2034, 2541, 2037, -1, 2034, 2543, 2541, -1, + 2035, 2036, 2037, -1, 2035, 2039, 2038, -1, + 2035, 2037, 2039, -1, 2035, 2038, 2040, -1, + 2035, 2040, 2041, -1, 2035, 2041, 2036, -1, + 3015, 3016, 2042, -1, 3015, 2042, 2043, -1, + 3015, 2043, 2044, -1, 3015, 2044, 3018, -1, + 3024, 2574, 2539, -1, 3024, 2538, 3026, -1, + 3024, 2539, 2538, -1, 2572, 2570, 2574, -1, + 2575, 2573, 2572, -1, 2575, 2572, 2574, -1, + 2575, 2049, 2573, -1, 2575, 2576, 2049, -1, + 3030, 3029, 2550, -1, 3035, 3034, 2179, -1, + 3035, 2179, 2580, -1, 2050, 2051, 3189, -1, + 2050, 2048, 2045, -1, 2050, 2046, 2051, -1, + 2050, 2045, 2046, -1, 2047, 2049, 2048, -1, + 2047, 3189, 3188, -1, 2047, 2050, 3189, -1, + 2047, 2048, 2050, -1, 2047, 2573, 2049, -1, + 2047, 3188, 2573, -1, 3190, 3189, 2051, -1, + 3190, 2051, 2052, -1, 3190, 2052, 3322, -1, + 2943, 3218, 3220, -1, 2943, 2053, 2944, -1, + 2943, 3220, 2053, -1, 2547, 2583, 3283, -1, + 2547, 3283, 3282, -1, 2547, 3282, 2054, -1, + 2547, 2054, 2548, -1, 3206, 3041, 2584, -1, + 3206, 2584, 2055, -1, 3206, 2055, 3280, -1, + 2591, 2592, 3202, -1, 2591, 3202, 3040, -1, + 2591, 2593, 2592, -1, 2591, 2947, 2593, -1, + 3042, 3011, 2056, -1, 3042, 2056, 3050, -1, + 2601, 2602, 2057, -1, 2601, 2057, 3011, -1, + 2601, 3011, 3342, -1, 2601, 3342, 2058, -1, + 3277, 2594, 2595, -1, 3225, 2599, 3226, -1, + 2598, 2058, 3341, -1, 2598, 2599, 2058, -1, + 2598, 2597, 3226, -1, 2598, 3226, 2599, -1, + 2603, 2058, 2599, -1, 2603, 2601, 2058, -1, + 3047, 2059, 2060, -1, 3047, 3048, 2059, -1, + 3047, 2060, 2604, -1, 2061, 2063, 2062, -1, + 2061, 2064, 2063, -1, 2061, 2062, 2066, -1, + 2061, 2066, 2079, -1, 2061, 2079, 2077, -1, + 2061, 2077, 2064, -1, 2067, 2065, 2629, -1, + 2067, 2066, 2619, -1, 2067, 2619, 2620, -1, + 2067, 2620, 2065, -1, 2628, 2626, 2079, -1, + 2628, 2079, 2066, -1, 2628, 2066, 2067, -1, + 2628, 2067, 2629, -1, 3209, 2612, 3210, -1, + 3209, 3208, 2613, -1, 2607, 3210, 2612, -1, + 2607, 2612, 2068, -1, 2607, 2068, 2069, -1, + 2607, 2069, 2606, -1, 2609, 2070, 2621, -1, + 2609, 2613, 2070, -1, 2617, 2615, 2610, -1, + 2617, 2609, 2621, -1, 2617, 2610, 2609, -1, + 2071, 2072, 2615, -1, 2071, 2073, 2074, -1, + 2071, 2616, 2073, -1, 2071, 2615, 2616, -1, + 2071, 2074, 2075, -1, 2071, 2075, 2072, -1, + 2076, 2626, 2635, -1, 2076, 2078, 2077, -1, + 2076, 2636, 2078, -1, 2076, 2635, 2636, -1, + 2076, 2077, 2079, -1, 2076, 2079, 2626, -1, + 2627, 3057, 3056, -1, 2627, 2080, 3057, -1, + 2627, 2629, 2080, -1, 2625, 2635, 2626, -1, + 2625, 2627, 3056, -1, 2625, 3056, 2622, -1, + 3058, 2081, 3208, -1, 3058, 3057, 2081, -1, + 3068, 3212, 3298, -1, 2633, 2082, 2634, -1, + 2633, 2622, 2082, -1, 2633, 2625, 2622, -1, + 2633, 2635, 2625, -1, 2639, 2084, 2083, -1, + 2639, 2083, 2085, -1, 2639, 2085, 2644, -1, + 2639, 2086, 2084, -1, 2639, 2640, 2086, -1, + 3060, 2087, 2623, -1, 3060, 2647, 2087, -1, + 3069, 2973, 2646, -1, 3069, 3065, 2973, -1, + 3069, 3068, 3065, -1, 2976, 2975, 2088, -1, + 2976, 2646, 2977, -1, 2534, 2645, 2646, -1, + 2534, 2088, 2532, -1, 2534, 2976, 2088, -1, + 2534, 2646, 2976, -1, 2089, 2091, 2090, -1, + 2089, 2090, 2092, -1, 2089, 2092, 2093, -1, + 2089, 2094, 2091, -1, 2089, 2095, 2094, -1, + 2089, 2093, 2095, -1, 2653, 2097, 2096, -1, + 2653, 2658, 2098, -1, 2653, 2098, 2097, -1, + 2653, 2096, 2654, -1, 2662, 2663, 2100, -1, + 2662, 2100, 2104, -1, 2662, 2104, 2684, -1, + 2662, 2684, 2685, -1, 2099, 2100, 2101, -1, + 2099, 2103, 2102, -1, 2099, 2101, 2103, -1, + 2099, 2104, 2100, -1, 2099, 2122, 2104, -1, + 2099, 2102, 2122, -1, 2666, 2105, 2106, -1, + 2666, 2106, 2667, -1, 2666, 2107, 2105, -1, + 2666, 2671, 2107, -1, 2108, 2677, 2109, -1, + 2108, 2656, 2655, -1, 2108, 2109, 2656, -1, + 2108, 2655, 2110, -1, 2108, 2675, 2677, -1, + 2108, 2110, 2675, -1, 2673, 2112, 2111, -1, + 2673, 2111, 2677, -1, 2673, 2113, 2112, -1, + 2673, 2674, 2113, -1, 2114, 2115, 2144, -1, + 2114, 2117, 2116, -1, 2114, 2116, 2118, -1, + 2114, 2118, 2115, -1, 2114, 2142, 2117, -1, + 2114, 2144, 2142, -1, 2119, 2124, 2123, -1, + 2119, 2141, 2120, -1, 2119, 2120, 2124, -1, + 2119, 2121, 2141, -1, 2119, 2122, 2121, -1, + 2119, 2123, 2122, -1, 2683, 2684, 2123, -1, + 2683, 2123, 2124, -1, 2683, 2124, 2125, -1, + 2683, 2125, 2682, -1, 2126, 2127, 2138, -1, + 2126, 2138, 2128, -1, 2126, 2128, 2129, -1, + 2126, 2130, 2127, -1, 2126, 2131, 2130, -1, + 2126, 2129, 2131, -1, 2137, 3073, 2133, -1, + 2137, 2764, 2763, -1, 2137, 2132, 2764, -1, + 2137, 2133, 2132, -1, 3072, 2133, 3073, -1, + 3072, 2134, 2133, -1, 3072, 2686, 2134, -1, + 2135, 2763, 2136, -1, 2135, 3075, 3073, -1, + 2135, 2137, 2763, -1, 2135, 3073, 2137, -1, + 2135, 2136, 2138, -1, 2135, 2138, 3075, -1, + 2139, 2140, 2141, -1, 2139, 2143, 2142, -1, + 2139, 2144, 2140, -1, 2139, 2142, 2144, -1, + 2139, 2141, 2145, -1, 2139, 2145, 2143, -1, + 2146, 2147, 2148, -1, 2146, 2149, 2150, -1, + 2146, 2148, 2149, -1, 2146, 2150, 2151, -1, + 2146, 2151, 2152, -1, 2146, 2152, 2147, -1, + 2162, 2153, 2157, -1, 2162, 2161, 2154, -1, + 2162, 2154, 2155, -1, 2162, 2155, 2153, -1, + 2156, 2157, 2158, -1, 2156, 2158, 2159, -1, + 2156, 2159, 2160, -1, 2156, 2160, 2161, -1, + 2156, 2161, 2162, -1, 2156, 2162, 2157, -1, + 2163, 2164, 2951, -1, 2163, 2951, 3154, -1, + 2163, 3154, 2165, -1, 2163, 2165, 2166, -1, + 2163, 2166, 2167, -1, 2163, 2167, 2164, -1, + 2690, 2695, 2169, -1, 2690, 2169, 3144, -1, + 2690, 2168, 2691, -1, 2690, 3144, 2168, -1, + 3146, 3144, 2169, -1, 3146, 2169, 2170, -1, + 3146, 2170, 3147, -1, 2582, 2581, 2173, -1, + 2582, 2577, 3183, -1, 2171, 2172, 2577, -1, + 2171, 2173, 2174, -1, 2171, 2577, 2582, -1, + 2171, 2582, 2173, -1, 2171, 2175, 2172, -1, + 2171, 2174, 2175, -1, 2180, 2581, 2580, -1, + 2180, 2183, 2176, -1, 2180, 2177, 2581, -1, + 2180, 2176, 2177, -1, 2178, 2184, 2183, -1, + 2178, 2580, 2179, -1, 2178, 2180, 2580, -1, + 2178, 2183, 2180, -1, 2178, 2179, 2181, -1, + 2178, 2181, 2184, -1, 2182, 2183, 2184, -1, + 2182, 2185, 2186, -1, 2182, 2184, 2185, -1, + 2182, 2186, 2187, -1, 2182, 2187, 2188, -1, + 2182, 2188, 2183, -1, 2189, 2190, 2191, -1, + 2189, 2192, 2190, -1, 2189, 2191, 2193, -1, + 2189, 2193, 2192, -1, 2194, 2195, 2196, -1, + 2194, 2197, 2195, -1, 2194, 2196, 2198, -1, + 2194, 2198, 2197, -1, 2697, 2200, 2199, -1, + 2697, 2201, 2698, -1, 2697, 2202, 2201, -1, + 2697, 2199, 2202, -1, 2697, 2234, 2200, -1, + 2697, 2699, 2234, -1, 2702, 2704, 2203, -1, + 2702, 2203, 2204, -1, 2702, 2204, 2205, -1, + 2702, 2205, 2703, -1, 2709, 2713, 2705, -1, + 2708, 2703, 2206, -1, 2708, 2206, 2207, -1, + 2708, 2207, 2712, -1, 2708, 2709, 2703, -1, + 2717, 2208, 2715, -1, 2717, 2209, 2208, -1, + 2717, 2210, 2209, -1, 2717, 2719, 2210, -1, + 3080, 2217, 2721, -1, 3080, 3082, 2218, -1, + 3080, 2218, 2217, -1, 2211, 2218, 2212, -1, + 2211, 2213, 2214, -1, 2211, 2212, 2213, -1, + 2211, 2214, 2215, -1, 2211, 2215, 2219, -1, + 2211, 2219, 2218, -1, 2216, 2731, 2217, -1, + 2216, 2217, 2218, -1, 2216, 2218, 2219, -1, + 2216, 2734, 2731, -1, 2216, 2219, 2220, -1, + 2216, 2220, 2221, -1, 2216, 2221, 2222, -1, + 2216, 2222, 2734, -1, 2733, 2725, 2732, -1, + 2733, 2735, 2729, -1, 2223, 2224, 2728, -1, + 2223, 2728, 2729, -1, 2223, 2729, 2225, -1, + 2223, 2226, 2224, -1, 2223, 2225, 2227, -1, + 2223, 2227, 2226, -1, 2746, 2738, 2745, -1, + 2746, 2748, 2742, -1, 2228, 2230, 2229, -1, + 2228, 2700, 2231, -1, 2228, 2231, 2230, -1, + 2228, 2229, 2232, -1, 2228, 2232, 2233, -1, + 2228, 2233, 2234, -1, 2228, 2234, 2700, -1, + 2235, 2236, 2237, -1, 2235, 2238, 2236, -1, + 2235, 2237, 2239, -1, 2235, 2239, 2238, -1, + 2240, 2241, 2242, -1, 2240, 2243, 2241, -1, + 2240, 2242, 2244, -1, 2240, 2253, 2243, -1, + 2240, 2244, 2252, -1, 2240, 2252, 2253, -1, + 2754, 2246, 2245, -1, 2754, 3098, 2246, -1, + 2754, 2245, 2247, -1, 2754, 2247, 2755, -1, + 2762, 2757, 2758, -1, 2762, 2248, 2766, -1, + 2762, 2758, 2248, -1, 3097, 2757, 2254, -1, + 3097, 2249, 3099, -1, 3097, 2254, 2249, -1, + 3095, 2756, 2250, -1, 3095, 2250, 2759, -1, + 2255, 2765, 2251, -1, 2255, 2252, 2254, -1, + 2255, 2253, 2252, -1, 2255, 2251, 2253, -1, + 2761, 2254, 2757, -1, 2761, 2255, 2254, -1, + 2761, 2765, 2255, -1, 2761, 2757, 2762, -1, + 2277, 2768, 2271, -1, 2277, 2271, 2276, -1, + 2277, 2278, 2769, -1, 2277, 2769, 2768, -1, + 2770, 2256, 2275, -1, 2770, 2275, 2768, -1, + 2770, 2772, 2257, -1, 2770, 2257, 2256, -1, + 2258, 2259, 2265, -1, 2258, 2781, 2260, -1, + 2258, 2260, 2259, -1, 2258, 2780, 2781, -1, + 2258, 2265, 2261, -1, 2258, 2261, 2780, -1, + 2262, 2264, 2263, -1, 2262, 2265, 2264, -1, + 2262, 2263, 2266, -1, 2262, 2267, 2265, -1, + 2262, 2266, 2268, -1, 2262, 2268, 2267, -1, + 2269, 2270, 2271, -1, 2269, 2272, 2273, -1, + 2269, 2273, 2274, -1, 2269, 2274, 2270, -1, + 2269, 2271, 2275, -1, 2269, 2275, 2272, -1, + 2774, 2276, 2775, -1, 2774, 2277, 2276, -1, + 2774, 2776, 2278, -1, 2774, 2278, 2277, -1, + 3102, 2775, 2279, -1, 3102, 2280, 3106, -1, + 3102, 2279, 2280, -1, 2778, 2282, 2281, -1, + 2778, 2283, 2282, -1, 2778, 2782, 2283, -1, + 2778, 2281, 2779, -1, 2284, 2291, 2292, -1, + 2284, 2292, 2285, -1, 2284, 2296, 2291, -1, + 2284, 2285, 2286, -1, 2284, 2287, 2296, -1, + 2284, 2288, 2287, -1, 2284, 2286, 2289, -1, + 2284, 2289, 2288, -1, 2290, 2292, 2291, -1, + 2290, 2294, 2292, -1, 2290, 2291, 2296, -1, + 2290, 2296, 2294, -1, 2293, 2295, 2294, -1, + 2293, 2294, 2296, -1, 2293, 2297, 2295, -1, + 2293, 2296, 2297, -1, 2797, 2794, 2298, -1, + 2797, 2299, 2798, -1, 2797, 2298, 2299, -1, + 2793, 2786, 2300, -1, 2793, 2300, 2794, -1, + 2796, 2801, 2790, -1, 2796, 2794, 2797, -1, + 2791, 2301, 2792, -1, 2791, 2790, 2318, -1, + 2791, 2318, 2302, -1, 2791, 2302, 2301, -1, + 2806, 2303, 2807, -1, 2806, 2322, 2303, -1, + 2806, 2805, 2304, -1, 2806, 2304, 2322, -1, + 2803, 2305, 2804, -1, 2803, 2306, 2305, -1, + 2803, 2808, 2307, -1, 2803, 2307, 2306, -1, + 2308, 2310, 2309, -1, 2308, 2309, 2314, -1, + 2308, 2311, 2310, -1, 2308, 2314, 2317, -1, + 2308, 2312, 2311, -1, 2308, 2317, 2312, -1, + 2313, 2314, 2315, -1, 2313, 2315, 2316, -1, + 2313, 2317, 2314, -1, 2313, 2316, 2318, -1, + 2313, 2318, 2319, -1, 2313, 2319, 2317, -1, + 2320, 2321, 2322, -1, 2320, 2323, 2321, -1, + 2320, 2324, 2323, -1, 2320, 2322, 2325, -1, + 2320, 2326, 2324, -1, 2320, 2325, 2326, -1, + 2327, 2328, 2329, -1, 2327, 2331, 2330, -1, + 2327, 2330, 2332, -1, 2327, 2332, 2328, -1, + 2327, 2333, 2331, -1, 2327, 2329, 2333, -1, + 2810, 2334, 3092, -1, 2810, 2812, 2335, -1, + 2810, 2335, 2334, -1, 2810, 3092, 3090, -1, + 3091, 2336, 2337, -1, 3091, 3092, 2336, -1, + 3091, 2337, 3089, -1, 2819, 2399, 2817, -1, + 2819, 2821, 2829, -1, 2819, 2829, 2398, -1, + 2819, 2398, 2399, -1, 2822, 2823, 2818, -1, + 2816, 2823, 2821, -1, 2816, 2818, 2823, -1, + 3108, 3109, 2818, -1, 3108, 2817, 3113, -1, + 3114, 2339, 2338, -1, 3114, 2338, 2341, -1, + 3114, 2340, 2339, -1, 3114, 2820, 2340, -1, + 3114, 2341, 3115, -1, 2813, 3111, 3112, -1, + 2813, 3115, 2341, -1, 2813, 2341, 3111, -1, + 2813, 3090, 3115, -1, 2827, 2344, 2834, -1, + 2827, 2822, 2344, -1, 3124, 2824, 2342, -1, + 3124, 2342, 2343, -1, 3124, 2343, 3122, -1, + 2825, 2834, 2344, -1, 2825, 2344, 2822, -1, + 2825, 2818, 2824, -1, 2825, 2822, 2818, -1, + 2833, 2832, 2831, -1, 2833, 2827, 2834, -1, + 2384, 2347, 2345, -1, 2384, 2345, 2383, -1, + 2384, 2386, 2351, -1, 2384, 2351, 2347, -1, + 2346, 2348, 2347, -1, 2346, 2349, 2350, -1, + 2346, 2351, 2349, -1, 2346, 2347, 2351, -1, + 2346, 2350, 2352, -1, 2346, 2352, 2348, -1, + 2353, 2355, 2354, -1, 2353, 2354, 2356, -1, + 2353, 2357, 2355, -1, 2353, 2356, 2358, -1, + 2353, 2359, 2357, -1, 2353, 2358, 2359, -1, + 3128, 2837, 2360, -1, 3128, 2361, 3129, -1, + 3128, 2360, 2361, -1, 2365, 2362, 2837, -1, + 2365, 3122, 2362, -1, 2365, 3123, 3122, -1, + 2365, 2364, 3123, -1, 2836, 2835, 2363, -1, + 2836, 2363, 2364, -1, 2836, 2364, 2365, -1, + 2836, 2365, 2837, -1, 2371, 2843, 2841, -1, + 2371, 2841, 2375, -1, 2371, 2372, 2366, -1, + 2371, 2366, 2843, -1, 2844, 2367, 2842, -1, + 2844, 2843, 2368, -1, 2844, 2368, 2369, -1, + 2844, 2369, 2367, -1, 2376, 2377, 2370, -1, + 2376, 2371, 2375, -1, 2376, 2370, 2372, -1, + 2376, 2372, 2371, -1, 2373, 2375, 2374, -1, + 2373, 2376, 2375, -1, 2373, 2377, 2376, -1, + 2373, 2378, 2377, -1, 2373, 2379, 2378, -1, + 2373, 2374, 2379, -1, 2850, 2964, 2848, -1, + 2380, 2423, 2381, -1, 2380, 2963, 2423, -1, + 2380, 2848, 2963, -1, 2380, 2381, 2847, -1, + 2380, 2847, 2848, -1, 2862, 2852, 2857, -1, + 2387, 2383, 2382, -1, 2387, 2382, 2388, -1, + 2387, 2384, 2383, -1, 2387, 2386, 2384, -1, + 2385, 3138, 2386, -1, 2385, 3137, 3138, -1, + 2385, 2386, 2387, -1, 2385, 2389, 3137, -1, + 2385, 2388, 2389, -1, 2385, 2387, 2388, -1, + 3139, 3137, 2389, -1, 3139, 2389, 2390, -1, + 3139, 2390, 3140, -1, 2391, 2392, 2393, -1, + 2391, 2394, 2402, -1, 2391, 2397, 2392, -1, + 2391, 2402, 2397, -1, 2391, 2393, 2395, -1, + 2391, 2395, 2394, -1, 2396, 2398, 2397, -1, + 2396, 2399, 2398, -1, 2396, 2400, 2399, -1, + 2396, 2401, 2400, -1, 2396, 2402, 2401, -1, + 2396, 2397, 2402, -1, 2868, 2406, 2403, -1, + 2868, 2403, 2404, -1, 2868, 2404, 2872, -1, + 2867, 2405, 2406, -1, 2867, 2406, 2868, -1, + 2867, 2871, 2407, -1, 2867, 2407, 2405, -1, + 2408, 2410, 2409, -1, 2408, 2412, 2411, -1, + 2408, 2411, 2410, -1, 2408, 2893, 2412, -1, + 2408, 2892, 2893, -1, 2408, 2409, 2892, -1, + 2877, 2879, 2874, -1, 2883, 2889, 2877, -1, + 2885, 2886, 2413, -1, 2885, 2889, 2883, -1, + 2888, 2885, 2413, -1, 2888, 2889, 2885, -1, + 2888, 2413, 2414, -1, 2888, 2414, 2893, -1, + 2415, 2874, 2879, -1, 2415, 2879, 2894, -1, + 2415, 2894, 2895, -1, 2415, 2416, 2874, -1, + 2415, 2417, 2416, -1, 2415, 2895, 2417, -1, + 2898, 2894, 2878, -1, 2898, 2878, 2418, -1, + 2898, 2418, 2899, -1, 2900, 2419, 2901, -1, + 2900, 2420, 2419, -1, 2900, 2421, 2420, -1, + 2900, 2899, 2421, -1, 2422, 3254, 2518, -1, + 2422, 2423, 3254, -1, 2422, 2424, 2423, -1, + 2422, 2425, 2424, -1, 2422, 2426, 2425, -1, + 2422, 2518, 2426, -1, 2427, 2428, 2429, -1, + 2427, 2430, 2431, -1, 2427, 2431, 2432, -1, + 2427, 2432, 2428, -1, 2427, 2433, 2430, -1, + 2427, 2429, 2433, -1, 2905, 2434, 2435, -1, + 2905, 2906, 2434, -1, 2905, 2435, 2436, -1, + 2905, 2436, 2910, -1, 2920, 2440, 2437, -1, + 2920, 2912, 2440, -1, 2920, 2437, 2919, -1, + 2920, 2922, 2915, -1, 2930, 2933, 2438, -1, + 2930, 2438, 2439, -1, 2930, 2439, 2918, -1, + 2930, 2918, 2919, -1, 2930, 2919, 2931, -1, + 2443, 2912, 2442, -1, 2443, 2440, 2912, -1, + 2443, 2931, 2440, -1, 2926, 2441, 2928, -1, + 2926, 2925, 2441, -1, 2932, 2442, 2924, -1, + 2932, 2443, 2442, -1, 2932, 2931, 2443, -1, + 2444, 2445, 2446, -1, 2444, 2447, 2445, -1, + 2444, 2446, 2448, -1, 2444, 2448, 2447, -1, + 2937, 2450, 2449, -1, 2937, 2935, 2450, -1, + 2937, 2451, 2939, -1, 2937, 2449, 2451, -1, + 2465, 2452, 2461, -1, 2465, 2463, 2453, -1, + 2465, 2454, 2452, -1, 2465, 2453, 2454, -1, + 3244, 2458, 2941, -1, 3244, 2462, 2458, -1, + 3244, 3246, 2462, -1, 2946, 2455, 2589, -1, + 2946, 2945, 2455, -1, 2946, 2587, 2947, -1, + 2946, 2589, 2587, -1, 2464, 2457, 2456, -1, + 2464, 2460, 2457, -1, 2464, 2456, 2458, -1, + 2464, 2458, 2462, -1, 2459, 2461, 2460, -1, + 2459, 2462, 2463, -1, 2459, 2464, 2462, -1, + 2459, 2460, 2464, -1, 2459, 2465, 2461, -1, + 2459, 2463, 2465, -1, 2466, 2467, 2468, -1, + 2466, 2470, 2469, -1, 2466, 2468, 2470, -1, + 2466, 2469, 2471, -1, 2466, 2471, 2472, -1, + 2466, 2472, 2467, -1, 2473, 2474, 2475, -1, + 2473, 2476, 2474, -1, 2473, 2477, 2476, -1, + 2473, 2479, 2478, -1, 2473, 2478, 2477, -1, + 2473, 2480, 2479, -1, 2473, 2475, 2480, -1, + 2481, 2482, 2483, -1, 2481, 2485, 2484, -1, + 2481, 2484, 2486, -1, 2481, 2486, 2482, -1, + 2481, 2487, 2485, -1, 2481, 2483, 2487, -1, + 2949, 2489, 2488, -1, 2949, 2950, 2489, -1, + 2949, 2488, 2490, -1, 2949, 2490, 3150, -1, + 2491, 2886, 2884, -1, 2491, 2884, 2492, -1, + 2491, 2492, 2493, -1, 2491, 2494, 2886, -1, + 2491, 2493, 2495, -1, 2491, 2495, 2494, -1, + 2496, 2510, 2497, -1, 2496, 2497, 2680, -1, + 2496, 2680, 2681, -1, 2496, 2508, 2510, -1, + 2496, 2681, 2498, -1, 2496, 2498, 2508, -1, + 2504, 2503, 2499, -1, 2504, 2500, 2502, -1, + 2504, 2501, 2500, -1, 2504, 2499, 2501, -1, + 2511, 2502, 2510, -1, 2511, 2509, 2503, -1, + 2511, 2503, 2504, -1, 2511, 2504, 2502, -1, + 2505, 2506, 2507, -1, 2505, 2508, 2506, -1, + 2505, 2507, 2509, -1, 2505, 2510, 2508, -1, + 2505, 2509, 2511, -1, 2505, 2511, 2510, -1, + 2955, 2512, 2514, -1, 2955, 2956, 2512, -1, + 3156, 3157, 2957, -1, 3233, 2859, 3234, -1, + 3233, 2851, 2859, -1, 2958, 2954, 2959, -1, + 2958, 2953, 2954, -1, 2958, 3312, 3162, -1, + 2958, 3162, 2953, -1, 2513, 2960, 2959, -1, + 2513, 2955, 2514, -1, 2513, 2514, 2515, -1, + 2513, 2515, 2960, -1, 2513, 2959, 2954, -1, + 2513, 2954, 2955, -1, 2961, 2515, 2516, -1, + 2961, 2960, 2515, -1, 2961, 2516, 2517, -1, + 2961, 2517, 2962, -1, 3253, 2518, 3254, -1, + 3253, 3259, 2518, -1, 2519, 2957, 3157, -1, + 2519, 2520, 2957, -1, 2519, 2521, 2520, -1, + 2519, 3157, 3161, -1, 2519, 2522, 2521, -1, + 2519, 3161, 2522, -1, 2523, 2525, 2524, -1, + 2523, 2526, 2525, -1, 2523, 2527, 2526, -1, + 2523, 2524, 2528, -1, 2523, 2528, 2529, -1, + 2523, 2529, 2527, -1, 2530, 2531, 2645, -1, + 2530, 2532, 2535, -1, 2530, 2533, 2531, -1, + 2530, 2535, 2533, -1, 2530, 2534, 2532, -1, + 2530, 2645, 2534, -1, 2966, 2536, 2535, -1, + 2966, 2537, 2536, -1, 2966, 2970, 2537, -1, + 2966, 2535, 2967, -1, 2981, 2980, 2975, -1, + 2981, 3062, 2983, -1, 3168, 3172, 2556, -1, + 2988, 2989, 2543, -1, 2988, 2543, 3017, -1, + 2993, 2994, 2542, -1, 2993, 2542, 2538, -1, + 2993, 2538, 2539, -1, 2993, 2539, 2997, -1, + 2540, 2989, 2545, -1, 2540, 2994, 2541, -1, + 2540, 2542, 2994, -1, 2540, 2545, 2542, -1, + 2540, 2541, 2543, -1, 2540, 2543, 2989, -1, + 2544, 2991, 2583, -1, 2544, 2545, 2991, -1, + 2544, 2546, 2545, -1, 2544, 2583, 2547, -1, + 2544, 2548, 2546, -1, 2544, 2547, 2548, -1, + 2986, 3039, 3207, -1, 2990, 3171, 2986, -1, + 2990, 2583, 2991, -1, 3020, 2549, 3021, -1, + 3020, 2550, 2549, -1, 3020, 3030, 2550, -1, + 3020, 3031, 3030, -1, 3006, 3000, 2551, -1, + 3006, 2551, 3004, -1, 2552, 2999, 2553, -1, + 2552, 3179, 2554, -1, 2552, 3175, 3179, -1, + 2552, 2553, 3175, -1, 2552, 2554, 2555, -1, + 2552, 2555, 2999, -1, 3009, 2556, 3010, -1, + 3009, 3168, 2556, -1, 3009, 3008, 2985, -1, + 3009, 2985, 3168, -1, 3174, 3175, 3270, -1, + 3174, 3270, 3269, -1, 3174, 3269, 3037, -1, + 3174, 3037, 3178, -1, 2557, 2558, 2559, -1, + 2557, 2559, 2560, -1, 2557, 2560, 2561, -1, + 2557, 2561, 2562, -1, 2557, 2562, 2563, -1, + 2557, 2563, 2558, -1, 2568, 3014, 3018, -1, + 2568, 3018, 2564, -1, 2568, 2564, 2565, -1, + 2568, 2565, 2569, -1, 2566, 2567, 3172, -1, + 2566, 3172, 3169, -1, 2566, 3169, 3014, -1, + 2566, 3014, 2568, -1, 2566, 2569, 2567, -1, + 2566, 2568, 2569, -1, 3013, 3014, 3169, -1, + 3013, 3169, 3170, -1, 3013, 3170, 2988, -1, + 3013, 2988, 3017, -1, 3019, 2570, 2572, -1, + 3019, 2571, 2570, -1, 3019, 3021, 2571, -1, + 3033, 3019, 2572, -1, 3033, 2573, 3188, -1, + 3033, 2572, 2573, -1, 3023, 2574, 3024, -1, + 3023, 2575, 2574, -1, 3023, 3028, 2576, -1, + 3023, 2576, 2575, -1, 3182, 3183, 2577, -1, + 3182, 2578, 3029, -1, 3182, 2577, 2578, -1, + 2579, 3183, 3185, -1, 2579, 3035, 2580, -1, + 2579, 3185, 3035, -1, 2579, 2580, 2581, -1, + 2579, 2581, 2582, -1, 2579, 2582, 3183, -1, + 3205, 3283, 2583, -1, 3205, 2583, 2990, -1, + 3205, 2986, 3207, -1, 3205, 2990, 2986, -1, + 3291, 3038, 3036, -1, 2588, 2584, 3041, -1, + 2588, 3041, 2595, -1, 2588, 2585, 2584, -1, + 2588, 2590, 2585, -1, 2586, 2594, 2587, -1, + 2586, 2595, 2594, -1, 2586, 2588, 2595, -1, + 2586, 2587, 2589, -1, 2586, 2589, 2590, -1, + 2586, 2590, 2588, -1, 3200, 3040, 3202, -1, + 3216, 3203, 3204, -1, 2948, 2947, 2591, -1, + 2948, 3218, 2943, -1, 2948, 3040, 3218, -1, + 2948, 2591, 3040, -1, 3198, 3196, 2592, -1, + 3198, 2592, 2593, -1, 3198, 2593, 2594, -1, + 3198, 2594, 3277, -1, 3287, 2595, 3041, -1, + 3287, 3277, 2595, -1, 2596, 3005, 2597, -1, + 2596, 2597, 2598, -1, 2596, 3273, 3005, -1, + 2596, 2598, 3341, -1, 2596, 3341, 3273, -1, + 3064, 2603, 2599, -1, 3064, 2599, 3225, -1, + 2600, 2602, 2601, -1, 2600, 2601, 2603, -1, + 2600, 2606, 2602, -1, 2600, 2603, 3064, -1, + 2600, 3337, 2606, -1, 2600, 3064, 3337, -1, + 3046, 3047, 2604, -1, 3046, 2604, 2605, -1, + 3046, 2605, 3043, -1, 3334, 2606, 3337, -1, + 3334, 2607, 2606, -1, 3334, 3210, 2607, -1, + 3334, 3335, 3210, -1, 2608, 2609, 2610, -1, + 2608, 2610, 2611, -1, 2608, 2611, 2612, -1, + 2608, 2612, 3209, -1, 2608, 3209, 2613, -1, + 2608, 2613, 2609, -1, 2614, 2616, 2615, -1, + 2614, 2615, 2617, -1, 2614, 2618, 2616, -1, + 2614, 2619, 2618, -1, 2614, 2620, 2619, -1, + 2614, 2621, 2620, -1, 2614, 2617, 2621, -1, + 3055, 2622, 3056, -1, 3055, 2623, 2622, -1, + 3055, 3060, 2623, -1, 3055, 3059, 3060, -1, + 2624, 2625, 2626, -1, 2624, 2627, 2625, -1, + 2624, 2626, 2628, -1, 2624, 2628, 2629, -1, + 2624, 2629, 2627, -1, 3061, 2983, 3062, -1, + 3061, 2630, 2983, -1, 3061, 2631, 2630, -1, + 3061, 3224, 2631, -1, 3292, 3222, 3293, -1, + 2632, 2633, 2634, -1, 2632, 2636, 2635, -1, + 2632, 2635, 2633, -1, 2632, 2637, 2636, -1, + 2632, 2634, 2637, -1, 2638, 2640, 2639, -1, + 2638, 2642, 2641, -1, 2638, 2641, 2640, -1, + 2638, 2643, 2642, -1, 2638, 2644, 2643, -1, + 2638, 2639, 2644, -1, 3067, 2647, 3060, -1, + 3070, 2646, 2645, -1, 3070, 3069, 2646, -1, + 3070, 2648, 2647, -1, 3070, 2645, 2648, -1, + 3070, 2647, 3067, -1, 2657, 2656, 2649, -1, + 2657, 2649, 2650, -1, 2657, 2651, 2658, -1, + 2657, 2650, 2651, -1, 2652, 2653, 2654, -1, + 2652, 2654, 2655, -1, 2652, 2655, 2656, -1, + 2652, 2656, 2657, -1, 2652, 2658, 2653, -1, + 2652, 2657, 2658, -1, 2659, 2660, 2661, -1, + 2659, 2663, 2662, -1, 2659, 2685, 2660, -1, + 2659, 2662, 2685, -1, 2659, 2661, 2664, -1, + 2659, 2664, 2663, -1, 2665, 2666, 2667, -1, + 2665, 2668, 2669, -1, 2665, 2667, 2668, -1, + 2665, 2669, 2670, -1, 2665, 2670, 2671, -1, + 2665, 2671, 2666, -1, 2672, 2674, 2673, -1, + 2672, 2675, 2676, -1, 2672, 2677, 2675, -1, + 2672, 2673, 2677, -1, 2672, 2678, 2674, -1, + 2672, 2676, 2678, -1, 2679, 2681, 2680, -1, + 2679, 2682, 2681, -1, 2679, 2683, 2682, -1, + 2679, 2684, 2683, -1, 2679, 2685, 2684, -1, + 2679, 2680, 2685, -1, 3074, 2687, 2686, -1, + 3074, 2686, 3072, -1, 3074, 2688, 2687, -1, + 3074, 3076, 2688, -1, 2689, 2690, 2691, -1, + 2689, 2693, 2692, -1, 2689, 2691, 2693, -1, + 2689, 2692, 2694, -1, 2689, 2694, 2695, -1, + 2689, 2695, 2690, -1, 2696, 2697, 2698, -1, + 2696, 2699, 2697, -1, 2696, 2698, 2700, -1, + 2696, 2700, 2699, -1, 2701, 2702, 2703, -1, + 2701, 2703, 2709, -1, 2701, 2704, 2702, -1, + 2701, 2709, 2705, -1, 2701, 2705, 2706, -1, + 2701, 2706, 2704, -1, 2707, 2709, 2708, -1, + 2707, 2710, 2711, -1, 2707, 2712, 2710, -1, + 2707, 2708, 2712, -1, 2707, 2711, 2713, -1, + 2707, 2713, 2709, -1, 2714, 2715, 2716, -1, + 2714, 2717, 2715, -1, 2714, 2716, 2718, -1, + 2714, 2719, 2717, -1, 2714, 2720, 2719, -1, + 2714, 2718, 2720, -1, 3079, 2721, 2722, -1, + 3079, 3080, 2721, -1, 3079, 2723, 3084, -1, + 3079, 2722, 2723, -1, 2724, 2725, 2733, -1, + 2724, 2727, 2726, -1, 2724, 2726, 2725, -1, + 2724, 2728, 2727, -1, 2724, 2729, 2728, -1, + 2724, 2733, 2729, -1, 2730, 2732, 2731, -1, + 2730, 2733, 2732, -1, 2730, 2731, 2734, -1, + 2730, 2735, 2733, -1, 2730, 2736, 2735, -1, + 2730, 2734, 2736, -1, 2737, 2738, 2746, -1, + 2737, 2740, 2739, -1, 2737, 2739, 2738, -1, + 2737, 2741, 2740, -1, 2737, 2742, 2741, -1, + 2737, 2746, 2742, -1, 2743, 2745, 2744, -1, + 2743, 2746, 2745, -1, 2743, 2744, 2747, -1, + 2743, 2748, 2746, -1, 2743, 2749, 2748, -1, + 2743, 2747, 2749, -1, 2752, 3229, 3228, -1, + 2752, 2753, 3229, -1, 3086, 2750, 3229, -1, + 3086, 3229, 2753, -1, 3086, 2751, 2750, -1, + 3086, 3087, 2751, -1, 3086, 2753, 3088, -1, + 3117, 2752, 3228, -1, 3117, 3089, 3088, -1, + 3117, 3091, 3089, -1, 3117, 3088, 2753, -1, + 3117, 2753, 2752, -1, 3094, 2754, 2755, -1, + 3094, 3098, 2754, -1, 3094, 2755, 2756, -1, + 3094, 2756, 3095, -1, 3096, 2757, 3097, -1, + 3096, 2758, 2757, -1, 3096, 2759, 2758, -1, + 3096, 3095, 2759, -1, 2760, 2761, 2762, -1, + 2760, 2763, 2764, -1, 2760, 2764, 2765, -1, + 2760, 2765, 2761, -1, 2760, 2766, 2763, -1, + 2760, 2762, 2766, -1, 2767, 2768, 2769, -1, + 2767, 2770, 2768, -1, 2767, 2769, 2771, -1, + 2767, 2772, 2770, -1, 2767, 2773, 2772, -1, + 2767, 2771, 2773, -1, 3101, 2774, 2775, -1, + 3101, 2775, 3102, -1, 3101, 3105, 2776, -1, + 3101, 2776, 2774, -1, 2777, 2778, 2779, -1, + 2777, 2781, 2780, -1, 2777, 2780, 2782, -1, + 2777, 2782, 2778, -1, 2777, 2783, 2781, -1, + 2777, 2779, 2783, -1, 2784, 2785, 2786, -1, + 2784, 2786, 2793, -1, 2784, 2787, 2785, -1, + 2784, 2793, 2792, -1, 2784, 2792, 2788, -1, + 2784, 2788, 2787, -1, 2789, 2796, 2790, -1, + 2789, 2790, 2791, -1, 2789, 2791, 2792, -1, + 2789, 2792, 2793, -1, 2789, 2793, 2794, -1, + 2789, 2794, 2796, -1, 2795, 2796, 2797, -1, + 2795, 2798, 2799, -1, 2795, 2797, 2798, -1, + 2795, 2799, 2800, -1, 2795, 2800, 2801, -1, + 2795, 2801, 2796, -1, 2802, 2803, 2804, -1, + 2802, 2804, 2805, -1, 2802, 2805, 2806, -1, + 2802, 2806, 2807, -1, 2802, 2807, 2808, -1, + 2802, 2808, 2803, -1, 2809, 2810, 3090, -1, + 2809, 3112, 2811, -1, 2809, 2811, 2812, -1, + 2809, 2812, 2810, -1, 2809, 3090, 2813, -1, + 2809, 2813, 3112, -1, 3110, 3111, 2814, -1, + 3110, 2814, 2818, -1, 3110, 2818, 3109, -1, + 2815, 2816, 2821, -1, 2815, 2817, 3108, -1, + 2815, 2818, 2816, -1, 2815, 3108, 2818, -1, + 2815, 2821, 2819, -1, 2815, 2819, 2817, -1, + 3116, 3230, 2820, -1, 3116, 2820, 3114, -1, + 2828, 2829, 2821, -1, 2828, 2822, 2827, -1, + 2828, 2821, 2823, -1, 2828, 2823, 2822, -1, + 3125, 2824, 3124, -1, 3125, 2825, 2824, -1, + 3125, 2834, 2825, -1, 2826, 2827, 2833, -1, + 2826, 2829, 2828, -1, 2826, 2828, 2827, -1, + 2826, 2830, 2829, -1, 2826, 2831, 2830, -1, + 2826, 2833, 2831, -1, 3120, 3121, 2832, -1, + 3120, 2832, 2833, -1, 3120, 2833, 2834, -1, + 3120, 2834, 3125, -1, 3127, 3132, 2835, -1, + 3127, 2835, 2836, -1, 3127, 2837, 3128, -1, + 3127, 2836, 2837, -1, 2838, 2859, 2851, -1, + 2838, 2851, 2849, -1, 2838, 2860, 2859, -1, + 2838, 2849, 2842, -1, 2838, 2842, 2839, -1, + 2838, 2839, 2860, -1, 2840, 2846, 2841, -1, + 2840, 2849, 2846, -1, 2840, 2842, 2849, -1, + 2840, 2841, 2843, -1, 2840, 2844, 2842, -1, + 2840, 2843, 2844, -1, 2845, 2847, 2846, -1, + 2845, 2848, 2847, -1, 2845, 2850, 2848, -1, + 2845, 2846, 2849, -1, 2845, 2849, 2851, -1, + 2845, 2851, 2850, -1, 3133, 3257, 2964, -1, + 3133, 2964, 2850, -1, 3133, 2850, 2851, -1, + 3133, 2851, 3233, -1, 2861, 2852, 2862, -1, + 2861, 2860, 2853, -1, 2861, 2853, 2854, -1, + 2861, 2854, 2852, -1, 2855, 2857, 2856, -1, + 2855, 2862, 2857, -1, 2855, 2863, 2862, -1, + 2855, 2856, 3160, -1, 2855, 3160, 3159, -1, + 2855, 3159, 2863, -1, 2858, 2859, 2860, -1, + 2858, 2860, 2861, -1, 2858, 2861, 2862, -1, + 2858, 2862, 2863, -1, 2858, 2863, 3234, -1, + 2858, 3234, 2859, -1, 3134, 2864, 3135, -1, + 3134, 2865, 2864, -1, 3134, 3238, 2865, -1, + 3134, 3240, 3238, -1, 3141, 3137, 3139, -1, + 2866, 2867, 2868, -1, 2866, 2870, 2869, -1, + 2866, 2869, 2871, -1, 2866, 2871, 2867, -1, + 2866, 2872, 2870, -1, 2866, 2868, 2872, -1, + 2873, 2877, 2874, -1, 2873, 2875, 2882, -1, + 2873, 2882, 2883, -1, 2873, 2883, 2877, -1, + 2873, 2876, 2875, -1, 2873, 2874, 2876, -1, + 2890, 2877, 2889, -1, 2890, 2891, 2878, -1, + 2890, 2878, 2879, -1, 2890, 2879, 2877, -1, + 2880, 2882, 2881, -1, 2880, 2883, 2882, -1, + 2880, 2881, 2884, -1, 2880, 2885, 2883, -1, + 2880, 2884, 2886, -1, 2880, 2886, 2885, -1, + 2887, 2889, 2888, -1, 2887, 2891, 2890, -1, + 2887, 2890, 2889, -1, 2887, 2892, 2891, -1, + 2887, 2893, 2892, -1, 2887, 2888, 2893, -1, + 2902, 2894, 2898, -1, 2902, 2895, 2894, -1, + 2902, 2903, 2896, -1, 2902, 2896, 2895, -1, + 2897, 2898, 2899, -1, 2897, 2899, 2900, -1, + 2897, 2900, 2901, -1, 2897, 2902, 2898, -1, + 2897, 2901, 2903, -1, 2897, 2903, 2902, -1, + 2904, 2906, 2905, -1, 2904, 2908, 2907, -1, + 2904, 2907, 2906, -1, 2904, 2909, 2908, -1, + 2904, 2910, 2909, -1, 2904, 2905, 2910, -1, + 2911, 2912, 2920, -1, 2911, 2913, 2912, -1, + 2911, 2914, 2913, -1, 2911, 2920, 2915, -1, + 2911, 2915, 2916, -1, 2911, 2916, 2914, -1, + 2917, 2919, 2918, -1, 2917, 2920, 2919, -1, + 2917, 2918, 2921, -1, 2917, 2921, 2922, -1, + 2917, 2922, 2920, -1, 2923, 2924, 2925, -1, + 2923, 2932, 2924, -1, 2923, 2925, 2926, -1, + 2923, 2933, 2932, -1, 2923, 2927, 2933, -1, + 2923, 2928, 2927, -1, 2923, 2926, 2928, -1, + 2929, 2930, 2931, -1, 2929, 2931, 2932, -1, + 2929, 2933, 2930, -1, 2929, 2932, 2933, -1, + 2934, 2936, 2935, -1, 2934, 2935, 2937, -1, + 2934, 2938, 2936, -1, 2934, 2937, 2939, -1, + 2934, 2940, 2938, -1, 2934, 2939, 2940, -1, + 3243, 2941, 3142, -1, 3243, 3244, 2941, -1, + 2942, 2943, 2944, -1, 2942, 2944, 2945, -1, + 2942, 2945, 2946, -1, 2942, 2946, 2947, -1, + 2942, 2947, 2948, -1, 2942, 2948, 2943, -1, + 3149, 2950, 2949, -1, 3149, 3154, 2951, -1, + 3149, 2951, 2950, -1, 3149, 2949, 3150, -1, + 3158, 2953, 3162, -1, 3158, 3156, 2953, -1, + 2952, 2954, 2953, -1, 2952, 2956, 2955, -1, + 2952, 2955, 2954, -1, 2952, 2957, 2956, -1, + 2952, 3156, 2957, -1, 2952, 2953, 3156, -1, + 3314, 3234, 3164, -1, 3165, 2958, 2959, -1, + 3165, 2959, 3264, -1, 3165, 3311, 3312, -1, + 3165, 3312, 2958, -1, 3263, 3264, 2960, -1, + 3263, 2960, 2961, -1, 3263, 2962, 3265, -1, + 3263, 2961, 2962, -1, 3255, 3254, 2963, -1, + 3255, 2964, 3257, -1, 3255, 2963, 2964, -1, + 2965, 2966, 2967, -1, 2965, 2969, 2968, -1, + 2965, 2968, 2970, -1, 2965, 2970, 2966, -1, + 2965, 2971, 2969, -1, 2965, 2967, 2971, -1, + 2972, 3063, 2977, -1, 2972, 2973, 3065, -1, + 2972, 2977, 2973, -1, 2972, 3065, 3293, -1, + 2972, 3222, 3063, -1, 2972, 3293, 3222, -1, + 2974, 2981, 2975, -1, 2974, 2975, 2976, -1, + 2974, 2976, 2977, -1, 2974, 2977, 3063, -1, + 2974, 3063, 3062, -1, 2974, 3062, 2981, -1, + 2978, 2979, 2980, -1, 2978, 2980, 2981, -1, + 2978, 2982, 2979, -1, 2978, 2981, 2983, -1, + 2978, 2984, 2982, -1, 2978, 2983, 2984, -1, + 3167, 3168, 2985, -1, 3167, 2985, 3039, -1, + 3167, 3039, 2986, -1, 3167, 2986, 3171, -1, + 2987, 2989, 2988, -1, 2987, 3171, 2990, -1, + 2987, 3170, 3171, -1, 2987, 2988, 3170, -1, + 2987, 2991, 2989, -1, 2987, 2990, 2991, -1, + 2992, 2994, 2993, -1, 2992, 2996, 2995, -1, + 2992, 2997, 2996, -1, 2992, 2993, 2997, -1, + 2992, 2995, 2998, -1, 2992, 2998, 2994, -1, + 3001, 3002, 2999, -1, 3001, 2999, 3000, -1, + 3001, 3000, 3006, -1, 3007, 3002, 3001, -1, + 3007, 3001, 3006, -1, 3007, 3274, 3180, -1, + 3007, 3180, 3002, -1, 3003, 3004, 3005, -1, + 3003, 3006, 3004, -1, 3003, 3007, 3006, -1, + 3003, 3005, 3273, -1, 3003, 3273, 3274, -1, + 3003, 3274, 3007, -1, 3176, 3178, 3008, -1, + 3176, 3008, 3009, -1, 3176, 3010, 3177, -1, + 3176, 3009, 3010, -1, 3271, 3197, 3269, -1, + 3271, 3196, 3197, -1, 3271, 3201, 3196, -1, + 3268, 3272, 3180, -1, 3343, 3042, 3204, -1, + 3343, 3011, 3042, -1, 3343, 3342, 3011, -1, + 3012, 3014, 3013, -1, 3012, 3016, 3015, -1, + 3012, 3017, 3016, -1, 3012, 3013, 3017, -1, + 3012, 3018, 3014, -1, 3012, 3015, 3018, -1, + 3032, 3019, 3033, -1, 3032, 3031, 3020, -1, + 3032, 3020, 3021, -1, 3032, 3021, 3019, -1, + 3022, 3023, 3024, -1, 3022, 3026, 3025, -1, + 3022, 3024, 3026, -1, 3022, 3025, 3027, -1, + 3022, 3027, 3028, -1, 3022, 3028, 3023, -1, + 3184, 3029, 3030, -1, 3184, 3182, 3029, -1, + 3192, 3031, 3193, -1, 3192, 3191, 3184, -1, + 3192, 3030, 3031, -1, 3192, 3184, 3030, -1, + 3187, 3193, 3031, -1, 3187, 3031, 3032, -1, + 3187, 3032, 3033, -1, 3187, 3033, 3188, -1, + 3321, 3190, 3322, -1, 3194, 3326, 3034, -1, + 3194, 3034, 3035, -1, 3194, 3035, 3185, -1, + 3194, 3185, 3195, -1, 3319, 3195, 3191, -1, + 3275, 3291, 3036, -1, 3275, 3036, 3037, -1, + 3275, 3037, 3197, -1, 3290, 3039, 3038, -1, + 3290, 3038, 3291, -1, 3290, 3207, 3039, -1, + 3317, 3203, 3200, -1, 3215, 3218, 3040, -1, + 3215, 3040, 3200, -1, 3215, 3200, 3203, -1, + 3215, 3203, 3216, -1, 3286, 3041, 3206, -1, + 3286, 3287, 3041, -1, 3297, 3058, 3208, -1, + 3297, 3211, 3058, -1, 3051, 3050, 3052, -1, + 3051, 3216, 3204, -1, 3051, 3204, 3042, -1, + 3051, 3042, 3050, -1, 3049, 3053, 3052, -1, + 3049, 3046, 3043, -1, 3049, 3044, 3053, -1, + 3049, 3043, 3044, -1, 3045, 3047, 3046, -1, + 3045, 3048, 3047, -1, 3045, 3046, 3049, -1, + 3045, 3049, 3052, -1, 3045, 3050, 3048, -1, + 3045, 3052, 3050, -1, 3217, 3216, 3051, -1, + 3217, 3051, 3052, -1, 3217, 3053, 3219, -1, + 3217, 3052, 3053, -1, 3054, 3211, 3059, -1, + 3054, 3055, 3056, -1, 3054, 3059, 3055, -1, + 3054, 3056, 3057, -1, 3054, 3057, 3058, -1, + 3054, 3058, 3211, -1, 3213, 3059, 3211, -1, + 3213, 3212, 3067, -1, 3213, 3060, 3059, -1, + 3213, 3067, 3060, -1, 3223, 3061, 3062, -1, + 3223, 3062, 3063, -1, 3223, 3063, 3222, -1, + 3223, 3224, 3061, -1, 3333, 3225, 3292, -1, + 3333, 3064, 3225, -1, 3333, 3337, 3064, -1, + 3294, 3293, 3065, -1, 3294, 3065, 3068, -1, + 3294, 3068, 3298, -1, 3066, 3067, 3212, -1, + 3066, 3212, 3068, -1, 3066, 3068, 3069, -1, + 3066, 3069, 3070, -1, 3066, 3070, 3067, -1, + 3071, 3072, 3073, -1, 3071, 3074, 3072, -1, + 3071, 3073, 3075, -1, 3071, 3076, 3074, -1, + 3071, 3077, 3076, -1, 3071, 3075, 3077, -1, + 3078, 3080, 3079, -1, 3078, 3081, 3082, -1, + 3078, 3082, 3080, -1, 3078, 3083, 3081, -1, + 3078, 3084, 3083, -1, 3078, 3079, 3084, -1, + 3085, 3087, 3086, -1, 3085, 3086, 3088, -1, + 3085, 3089, 3087, -1, 3085, 3088, 3089, -1, + 3118, 3115, 3090, -1, 3118, 3091, 3117, -1, + 3118, 3090, 3092, -1, 3118, 3092, 3091, -1, + 3093, 3094, 3095, -1, 3093, 3095, 3096, -1, + 3093, 3096, 3097, -1, 3093, 3098, 3094, -1, + 3093, 3099, 3098, -1, 3093, 3097, 3099, -1, + 3100, 3101, 3102, -1, 3100, 3103, 3104, -1, + 3100, 3104, 3105, -1, 3100, 3105, 3101, -1, + 3100, 3106, 3103, -1, 3100, 3102, 3106, -1, + 3107, 3109, 3108, -1, 3107, 3110, 3109, -1, + 3107, 3111, 3110, -1, 3107, 3112, 3111, -1, + 3107, 3113, 3112, -1, 3107, 3108, 3113, -1, + 3231, 3230, 3116, -1, 3232, 3114, 3115, -1, + 3232, 3116, 3114, -1, 3232, 3117, 3228, -1, + 3232, 3231, 3116, -1, 3232, 3115, 3118, -1, + 3232, 3118, 3117, -1, 3119, 3121, 3120, -1, + 3119, 3122, 3123, -1, 3119, 3123, 3121, -1, + 3119, 3124, 3122, -1, 3119, 3125, 3124, -1, + 3119, 3120, 3125, -1, 3126, 3127, 3128, -1, + 3126, 3129, 3130, -1, 3126, 3128, 3129, -1, + 3126, 3130, 3131, -1, 3126, 3131, 3132, -1, + 3126, 3132, 3127, -1, 3249, 3256, 3257, -1, + 3249, 3257, 3133, -1, 3249, 3133, 3233, -1, + 3301, 3134, 3135, -1, 3301, 3240, 3134, -1, + 3301, 3135, 3302, -1, 3136, 3138, 3137, -1, + 3136, 3137, 3141, -1, 3136, 3141, 3306, -1, + 3136, 3304, 3138, -1, 3136, 3306, 3304, -1, + 3237, 3141, 3139, -1, 3237, 3140, 3241, -1, + 3237, 3139, 3140, -1, 3236, 3306, 3141, -1, + 3236, 3141, 3237, -1, 3145, 3243, 3142, -1, + 3145, 3142, 3143, -1, 3145, 3143, 3144, -1, + 3145, 3144, 3146, -1, 3245, 3145, 3146, -1, + 3245, 3243, 3145, -1, 3245, 3147, 3247, -1, + 3245, 3146, 3147, -1, 3148, 3149, 3150, -1, + 3148, 3152, 3151, -1, 3148, 3150, 3152, -1, + 3148, 3151, 3153, -1, 3148, 3153, 3154, -1, + 3148, 3154, 3149, -1, 3163, 3158, 3162, -1, + 3163, 3164, 3159, -1, 3163, 3159, 3158, -1, + 3155, 3157, 3156, -1, 3155, 3156, 3158, -1, + 3155, 3158, 3159, -1, 3155, 3159, 3160, -1, + 3155, 3160, 3161, -1, 3155, 3161, 3157, -1, + 3313, 3162, 3312, -1, 3313, 3163, 3162, -1, + 3313, 3314, 3164, -1, 3313, 3164, 3163, -1, + 3310, 3311, 3261, -1, 3252, 3259, 3253, -1, + 3252, 3261, 3259, -1, 3252, 3256, 3310, -1, + 3252, 3310, 3261, -1, 3262, 3261, 3311, -1, + 3262, 3311, 3165, -1, 3262, 3165, 3264, -1, + 3166, 3168, 3167, -1, 3166, 3170, 3169, -1, + 3166, 3171, 3170, -1, 3166, 3167, 3171, -1, + 3166, 3169, 3172, -1, 3166, 3172, 3168, -1, + 3173, 3175, 3174, -1, 3173, 3176, 3177, -1, + 3173, 3174, 3178, -1, 3173, 3178, 3176, -1, + 3173, 3179, 3175, -1, 3173, 3177, 3179, -1, + 3267, 3268, 3316, -1, 3267, 3201, 3271, -1, + 3315, 3180, 3274, -1, 3315, 3268, 3180, -1, + 3315, 3316, 3268, -1, 3181, 3183, 3182, -1, + 3181, 3182, 3184, -1, 3181, 3185, 3183, -1, + 3181, 3184, 3191, -1, 3181, 3195, 3185, -1, + 3181, 3191, 3195, -1, 3186, 3321, 3193, -1, + 3186, 3187, 3188, -1, 3186, 3193, 3187, -1, + 3186, 3188, 3189, -1, 3186, 3189, 3190, -1, + 3186, 3190, 3321, -1, 3320, 3319, 3191, -1, + 3320, 3191, 3192, -1, 3320, 3192, 3193, -1, + 3320, 3193, 3321, -1, 3325, 3194, 3195, -1, + 3325, 3195, 3319, -1, 3325, 3326, 3194, -1, + 3276, 3197, 3196, -1, 3276, 3275, 3197, -1, + 3276, 3196, 3198, -1, 3276, 3198, 3277, -1, + 3199, 3317, 3200, -1, 3199, 3202, 3201, -1, + 3199, 3200, 3202, -1, 3199, 3201, 3267, -1, + 3199, 3316, 3317, -1, 3199, 3267, 3316, -1, + 3344, 3204, 3203, -1, 3344, 3203, 3317, -1, + 3344, 3343, 3204, -1, 3284, 3283, 3205, -1, + 3284, 3205, 3207, -1, 3279, 3206, 3280, -1, + 3279, 3286, 3206, -1, 3288, 3207, 3290, -1, + 3288, 3284, 3207, -1, 3288, 3286, 3279, -1, + 3288, 3279, 3284, -1, 3296, 3297, 3208, -1, + 3296, 3208, 3209, -1, 3296, 3209, 3210, -1, + 3296, 3210, 3335, -1, 3299, 3211, 3297, -1, + 3299, 3298, 3212, -1, 3299, 3212, 3213, -1, + 3299, 3213, 3211, -1, 3336, 3294, 3298, -1, + 3214, 3215, 3216, -1, 3214, 3216, 3217, -1, + 3214, 3218, 3215, -1, 3214, 3217, 3219, -1, + 3214, 3220, 3218, -1, 3214, 3219, 3220, -1, + 3221, 3222, 3292, -1, 3221, 3223, 3222, -1, + 3221, 3224, 3223, -1, 3221, 3292, 3225, -1, + 3221, 3226, 3224, -1, 3221, 3225, 3226, -1, + 3227, 3228, 3229, -1, 3227, 3229, 3230, -1, + 3227, 3230, 3231, -1, 3227, 3232, 3228, -1, + 3227, 3231, 3232, -1, 3250, 3249, 3233, -1, + 3250, 3233, 3234, -1, 3250, 3234, 3314, -1, + 3303, 3240, 3301, -1, 3303, 3236, 3240, -1, + 3303, 3306, 3236, -1, 3235, 3236, 3237, -1, + 3235, 3239, 3238, -1, 3235, 3238, 3240, -1, + 3235, 3240, 3236, -1, 3235, 3241, 3239, -1, + 3235, 3237, 3241, -1, 3242, 3244, 3243, -1, + 3242, 3243, 3245, -1, 3242, 3246, 3244, -1, + 3242, 3245, 3247, -1, 3242, 3248, 3246, -1, + 3242, 3247, 3248, -1, 3309, 3256, 3249, -1, + 3309, 3310, 3256, -1, 3309, 3250, 3314, -1, + 3309, 3249, 3250, -1, 3251, 3252, 3253, -1, + 3251, 3253, 3254, -1, 3251, 3254, 3255, -1, + 3251, 3256, 3252, -1, 3251, 3257, 3256, -1, + 3251, 3255, 3257, -1, 3258, 3260, 3259, -1, + 3258, 3259, 3261, -1, 3258, 3261, 3262, -1, + 3258, 3264, 3263, -1, 3258, 3262, 3264, -1, + 3258, 3265, 3260, -1, 3258, 3263, 3265, -1, + 3266, 3268, 3267, -1, 3266, 3269, 3270, -1, + 3266, 3271, 3269, -1, 3266, 3267, 3271, -1, + 3266, 3270, 3272, -1, 3266, 3272, 3268, -1, + 3340, 3274, 3273, -1, 3340, 3315, 3274, -1, + 3340, 3273, 3341, -1, 3327, 3325, 3319, -1, + 3327, 3323, 3329, -1, 3289, 3291, 3275, -1, + 3289, 3275, 3276, -1, 3289, 3277, 3287, -1, + 3289, 3276, 3277, -1, 3278, 3279, 3280, -1, + 3278, 3281, 3282, -1, 3278, 3280, 3281, -1, + 3278, 3282, 3283, -1, 3278, 3283, 3284, -1, + 3278, 3284, 3279, -1, 3285, 3287, 3286, -1, + 3285, 3286, 3288, -1, 3285, 3289, 3287, -1, + 3285, 3288, 3290, -1, 3285, 3290, 3291, -1, + 3285, 3291, 3289, -1, 3332, 3333, 3292, -1, + 3332, 3292, 3293, -1, 3332, 3293, 3294, -1, + 3332, 3294, 3336, -1, 3295, 3296, 3335, -1, + 3295, 3335, 3336, -1, 3295, 3297, 3296, -1, + 3295, 3336, 3298, -1, 3295, 3298, 3299, -1, + 3295, 3299, 3297, -1, 3300, 3301, 3302, -1, + 3300, 3303, 3301, -1, 3300, 3305, 3304, -1, + 3300, 3304, 3306, -1, 3300, 3306, 3303, -1, + 3300, 3307, 3305, -1, 3300, 3302, 3307, -1, + 3308, 3310, 3309, -1, 3308, 3312, 3311, -1, + 3308, 3311, 3310, -1, 3308, 3313, 3312, -1, + 3308, 3314, 3313, -1, 3308, 3309, 3314, -1, + 3339, 3316, 3315, -1, 3339, 3315, 3340, -1, + 3339, 3317, 3316, -1, 3339, 3344, 3317, -1, + 3318, 3327, 3319, -1, 3318, 3320, 3321, -1, + 3318, 3319, 3320, -1, 3318, 3321, 3322, -1, + 3318, 3322, 3323, -1, 3318, 3323, 3327, -1, + 3324, 3326, 3325, -1, 3324, 3325, 3327, -1, + 3324, 3328, 3326, -1, 3324, 3327, 3329, -1, + 3324, 3330, 3328, -1, 3324, 3329, 3330, -1, + 3331, 3333, 3332, -1, 3331, 3335, 3334, -1, + 3331, 3336, 3335, -1, 3331, 3332, 3336, -1, + 3331, 3334, 3337, -1, 3331, 3337, 3333, -1, + 3338, 3339, 3340, -1, 3338, 3341, 3342, -1, + 3338, 3340, 3341, -1, 3338, 3342, 3343, -1, + 3338, 3343, 3344, -1, 3338, 3344, 3339, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link3.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link3.wrl new file mode 100644 index 0000000..89a4faf --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link3.wrl @@ -0,0 +1,6463 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.016514 -0.049194202 -0.2085, + 0.011126 -0.0507464 -0.2085, + -5.0382133e-012 -0.052000001 -0.2085, + 0.0266016 -0.0443362 -0.2085, + 0.0322018 -0.052626502 -0.19149999, + 0.0353553 -0.0373553 -0.2085, + 0.0311745 -0.041091599 -0.2085, + 0.039091598 -0.0331745 -0.2085, + 0.042336199 -0.0286016 -0.2085, + 0.059821099 -0.0066305301 -0.19149999, + 0.059027899 -0.0127568 -0.19149999, + 0.050000001 -0.0020000001 -0.2085, + 0.059980098 -0.000455125 -0.19149999, + 0.049685601 0.0035982199 -0.2085, + 0.0216942 -0.047048401 -0.2085, + 0.0493031 0.0074999998 0.034054, + -0.061000001 0.0057000001 -0.1313, + -0.0216942 0.0430484 -0.2085, + -0.0266016 0.040336199 -0.2085, + -0.0353553 -0.0373553 -0.2085, + 0.0328326 -0.083832502 -0.035448, + -0.0030887299 -0.061920401 -0.19149999, + -0.0266016 -0.0443362 -0.2085, + 0.00559822 -0.051685601 -0.2085, + -0.039091598 -0.0331745 -0.2085, + -0.0311745 -0.041091599 -0.2085, + -0.045048401 -0.0236942 -0.2085, + -0.042336199 -0.0286016 -0.2085, + -0.057608999 -0.0187691 -0.19149999, + -0.047194201 -0.018514 -0.2085, + -0.055579402 -0.0246037 -0.19149999, + -0.0487464 -0.013126 -0.2085, + -0.011126 -0.0507464 -0.2085, + -0.00559822 -0.051685601 -0.2085, + -0.00923343 -0.061285298 -0.19149999, + 0.047194201 -0.018514 -0.2085, + 0.049685601 -0.0075982199 -0.2085, + 0.0487464 -0.013126 -0.2085, + 0.045048401 -0.0236942 -0.2085, + 0.055579402 -0.0246037 -0.19149999, + 0.057608999 -0.0187691 -0.19149999, + 0.00559822 0.047685601 -0.2085, + 0.045048401 0.0196942 -0.2085, + 0.042336199 0.024601599 -0.2085, + 0.039091598 0.029174499 -0.2085, + 0.016514 0.045194201 -0.2085, + 0.011126 0.046746399 -0.2085, + 0.0353553 0.033355299 -0.2085, + 0.0311745 0.037091602 -0.2085, + 0.0532961 0.025440799 -0.165939, + 0.048467699 0.033086699 -0.16362099, + 0.044561401 0.038171701 -0.1715, + 0.0463636 0.036084399 -0.1715, + 0.0465803 0.035792999 -0.168937, + 0.0552264 0.0074999998 0.023249, + 0.019305199 0.053630602 -0.15830299, + 0.0165099 0.054870401 -0.160607, + -0.042336199 0.024601599 -0.2085, + -0.0311745 0.037091602 -0.2085, + -0.055787299 -0.053463101 0.00590401, + -0.058998398 -0.043099899 -0.002021, + -0.058412101 -0.040147301 0.0048760101, + -0.058412101 -0.044537 0.001162, + -0.058412101 -0.042385198 0.003146, + -0.021165101 -0.058143001 -0.19149999, + -0.026825599 -0.0556692 -0.19149999, + -0.016514 -0.049194202 -0.2085, + -0.0216942 -0.047048401 -0.2085, + 0.021165101 -0.058143001 -0.19149999, + -0.0152803 -0.060021698 -0.19149999, + -0.0302257 -0.085423902 -0.034324002, + -0.0220857 -0.089346401 -0.031564001, + -0.019305199 -0.0903593 -0.030851001, + -0.027557701 -0.0868771 -0.033301, + -0.0248404 -0.088185199 -0.032381002, + 4.4690757e-012 -0.023718299 0.060001001, + -4.7590009e-005 -0.0145 0.059999999, + -0.058412101 -0.046562199 -0.00106799, + -0.0576833 -0.048126802 0.00210899, + -0.055787299 -0.055469099 0.0031390099, + -0.0576833 -0.0501085 -0.00037399301, + -0.056809202 -0.0517902 0.0027729899, + -0.055787299 -0.054494798 0.0045480002, + 0.052960701 -0.0301986 -0.19149999, + -0.011126 0.046746399 -0.2085, + -0.016514 0.045194201 -0.2085, + 0.0583959 0.0117813 -0.19149999, + 0.0487464 0.0091260504 -0.2085, + 0.047194201 0.014514 -0.2085, + 0.056669399 0.0177125 -0.19149999, + 0.059503399 0.0057039 -0.19149999, + 0.044033099 0.0387564 -0.19149999, + 0.0266016 0.040336199 -0.2085, + 0.0216942 0.0430484 -0.2085, + 0.051818501 0.0282191 -0.1715, + 0.051438902 0.0288876 -0.19149999, + 0.053283598 0.025551399 -0.1715, + 0.0528998 0.0263127 -0.1715, + 0.054342099 0.0234349 -0.19149999, + 0.0465803 0.035699699 -0.16636001, + 0.0465803 0.035537198 -0.163772, + 0.044564299 0.037893701 -0.16391701, + 0.061000001 -0.00079999998 -0.1797, + 0.061000001 -0.0153 -0.14083301, + 0.058412101 -0.0208226 0.012479, + 0.0576833 -0.0209978 0.015353, + 0.0576833 -0.031567998 0.012427, + 0.0220857 0.052975301 -0.160413, + 0.019305199 0.053996801 -0.16051801, + 0.0220857 0.052608799 -0.158178, + 0.0248404 0.0514374 -0.158034, + 0.019305199 0.054294199 -0.16273101, + 0.056793701 -0.0145 0.019300001, + 0.057400201 -0.0094999997 0.01747, + 0.0193005 -0.0145 0.056795001, + 0.031582098 -0.0094999997 0.051015001, + 0.026134601 0.0074999998 0.053920999, + 0.033494599 -0.0094999997 0.049780998, + 0.0302257 -0.0232081 0.051614001, + 0.0302257 -0.042262401 0.050995, + 0.0328269 -0.0145 0.050211001, + 0.0532961 -0.034250502 0.024512, + 0.0532961 -0.0216894 0.026695, + 0.055787299 -0.032921799 0.018526001, + 0.055787299 -0.021346901 0.021077, + 0.0576833 -0.0340712 0.011683, + 0.0546159 -0.0335907 0.021539001, + 0.0546159 -0.0215193 0.023905, + -0.0109179 -0.094652496 0.00272099, + -0.059027899 -0.0127568 -0.19149999, + -0.050000001 -0.0020000001 -0.2085, + -0.059980098 -0.000455125 -0.19149999, + -0.049685601 0.0035982199 -0.2085, + -0.049685601 -0.0075982199 -0.2085, + -0.059821099 -0.0066305301 -0.19149999, + -0.045048401 0.0196942 -0.2085, + -0.055787299 -0.0523776 0.0071999999, + -0.0532961 -0.0416153 0.022624999, + -0.058998398 -0.036805801 0.0031870001, + -0.059999999 -0.0388995 -0.016624, + -0.0546159 -0.036445301 0.020926001, + -0.055787299 -0.032921601 0.018526001, + -0.058731299 -0.0094999997 0.012273, + -0.053285599 0.025552399 -0.1715, + -0.054342099 0.0234349 -0.19149999, + -0.061000001 0.0097000003 -0.12549999, + -0.044564299 -0.074823998 -0.038461, + -0.0424264 -0.077036999 -0.036825001, + -0.0465803 -0.072508298 -0.040171999, + -0.041876599 -0.044969101 -0.19149999, + -0.0465803 -0.073354103 -0.036228001, + -0.044564299 -0.0756457 -0.034446999, + -0.058412101 -0.035541002 0.00758, + -0.058412101 -0.037860099 0.0063510002, + -0.058998398 -0.034613598 0.0044429898, + -0.058412101 -0.0332435 0.0085709998, + -0.056809202 -0.042516001 0.01125, + -0.0576833 -0.041332498 0.0080650002, + -0.0576833 -0.038916901 0.0095229903, + -0.055787299 -0.0436932 0.014417, + -0.055787299 -0.046315301 0.012706, + -0.056809202 -0.0399721 0.01269, + -0.0576833 -0.036470499 0.010724, + -0.056809202 -0.047416098 0.0075389999, + -0.0576833 -0.0459776 0.0043529999, + -0.056809202 -0.049689099 0.0052800002, + -0.056809202 -0.0450105 0.0095319999, + -0.055787299 -0.048847001 0.010709, + -0.0576833 -0.043698799 0.0063410001, + -0.055787299 -0.0512431 0.0084349997, + -0.027557701 0.050101601 -0.157874, + 0.0240272 0.052979 -0.19149999, + 0.024834501 0.0526025 -0.1715, + -0.0081421202 -0.095249802 -0.001467, + -0.0109179 -0.094838902 -0.001856, + 0.0053918599 -0.093282603 -0.028795, + 0.0030887299 -0.061920401 -0.19149999, + 0.00267513 -0.0942467 -0.024103001, + 0.00267513 -0.093464002 -0.028666999, + 0.0053918599 -0.094066903 -0.024236999, + 0.0053918599 -0.095148198 -0.015044, + 0.0053918599 -0.094689101 -0.019649999, + 0.0081421202 -0.095147498 -0.010681, + -2.6350504e-012 -0.094925202 -0.019466, + 0.00267513 -0.094867103 -0.019512, + 0.0081421202 -0.094848603 -0.015289, + 0.0081421202 -0.094385803 -0.019886, + 0.026825599 -0.0556692 -0.19149999, + 0.0248404 -0.088188797 -0.032381002, + -0.0081421202 -0.092972398 -0.029012, + -0.0109179 -0.092529498 -0.029324001, + -0.0328326 -0.084694602 -0.031164, + -0.0220857 -0.089158498 0.019406, + -0.0220857 -0.090828098 -0.022648999, + -0.0220857 -0.090165399 -0.02712, + -0.0248404 -0.089014404 -0.027969999, + -0.019305199 -0.091283299 0.014144, + -0.0220857 -0.089658797 0.017355001, + -0.00267513 -0.023714401 0.059939999, + -0.0029901101 -0.0145 0.059925001, + -0.00267513 -0.0421132 0.059935, + -8.5748604e-012 -0.044432402 0.059999999, + -0.00154487 -0.0094999997 0.059980001, + -0.0081421202 -0.0236832 0.059431002, + -0.0099555897 -0.0094999997 0.059168, + 0.0165099 -0.032562401 0.057542998, + 0.017363001 -0.0145 0.057433002, + 0.0145717 -0.0094999997 0.058203999, + 0.0167691 -0.0094999997 0.057608999, + 0.0053918599 -0.032876801 0.059742, + 0.0053918599 -0.042068701 0.059735, + 0.00268824 0.056324799 -0.15653799, + -0.00073155703 0.0074999998 0.059996001, + -0.00381402 0.0074999998 0.059799001, + 0.045540299 0.0074999998 0.038943, + 0.041294798 0.0074999998 0.043419, + -0.0546159 -0.058205198 0.0047280001, + -0.0546159 -0.057238501 0.006207, + -0.058998398 -0.0507254 -0.015034, + -0.058412101 -0.051530901 -0.0090300003, + -0.0532961 -0.060954899 0.0061880001, + -0.0424264 -0.079088002 0.00012199401, + -0.0532961 -0.0579 0.010679, + -0.0546159 -0.056209002 0.0076339999, + -0.0546159 -0.055120502 0.0090049999, + -0.0378174 -0.068201602 0.033484001, + -0.0424264 -0.057604101 0.034956001, + -0.0327731 0.0074999998 0.050163999, + -0.035366699 -0.018833 0.048349999, + -0.0465803 -0.022327499 0.037225001, + -0.0465803 -0.038531799 0.035551, + -0.044564299 -0.039158501 0.038148001, + -0.044564299 -0.022475099 0.039645001, + -0.040312301 -0.0145 0.044440001, + -0.050219599 -0.049809501 0.025858, + -0.048467699 -0.0525476 0.027866, + -0.044564299 -0.056495801 0.032386001, + -0.040174201 -0.022750201 0.044151999, + -0.0424264 -0.0226162 0.041956998, + -0.040174201 -0.040325899 0.042987, + -0.0424264 -0.039757401 0.040631, + -0.0424264 -0.0186905 0.04225, + -0.044564299 -0.0186374 0.039976001, + -0.0378174 -0.050268099 0.043598998, + -0.0218191 0.0074999998 0.055806998, + 0.0576833 -0.054445699 -0.045600001, + 0.055787299 -0.0589565 -0.044603001, + 0.056809202 -0.0570958 -0.043327, + 0.0328326 -0.085986301 -0.022528, + 0.044024602 0.038748302 -0.1715, + 0.044564299 0.038149402 -0.16898499, + 0.044440001 0.038312301 -0.1715, + 0.044564299 0.038056001 -0.166456, + 0.042409498 0.040443301 -0.1715, + 0.0424264 0.039914601 -0.16155399, + 0.030832 0.049472202 -0.1715, + 0.029552899 0.050217099 -0.19149999, + 0.050219599 0.0307154 -0.166155, + 0.051830001 0.028108699 -0.16604801, + 0.0514476 0.028873 -0.1715, + 0.048467699 0.0332493 -0.16625901, + 0.048459999 0.033361301 -0.1715, + 0.048175599 0.033764701 -0.1715, + 0.0479904 0.034012899 -0.19149999, + 0.049871601 0.031358998 -0.1715, + 0.048467699 0.0333426 -0.16888601, + 0.061000001 0.0097000003 -0.1715, + 0.061000001 0.0097000003 -0.1855, + 0.0542247 0.0236843 -0.1715, + 0.061000001 0.0057000001 -0.1825, + 0.059757002 -0.0246292 0.0020939901, + 0.059757002 -0.0288698 0.00027099601, + 0.059757002 -0.020302201 0.0039440002, + 0.0599402 -0.0458721 -0.03269, + 0.059757002 -0.032785099 -0.00174001, + 0.059757002 -0.034715202 -0.0030420099, + 0.058998398 -0.036799401 0.003213, + 0.058412101 -0.037853699 0.0063769999, + 0.059445001 -0.0357517 6.9000191e-005, + 0.059445001 -0.033696599 0.00134399, + 0.058412101 -0.0515568 -0.0090070004, + 0.058998398 -0.049656499 -0.012076, + 0.059999999 -0.0161529 -0.000126007, + 0.059999902 -0.0145 9.5001204e-005, + 0.0599402 -0.017000601 0.0024069999, + 0.045600802 -0.0094999997 0.038995001, + 0.0378174 -0.048359599 0.044112999, + 0.0378174 -0.050264001 0.043616001, + 0.035366699 -0.0470853 0.046638001, + 0.0378174 -0.046458699 0.044519, + 0.035366699 -0.049029201 0.046241999, + 0.0328326 -0.049650699 0.048218999, + 0.018242201 0.0551438 -0.1715, + 0.0165099 0.055167601 -0.162802, + 0.058814298 0.0074999998 0.011461, + 0.035366699 0.045656402 -0.159665, + 0.055787299 -0.018225299 0.021752, + 0.057391401 -0.0145 0.017499, + 0.056809202 -0.016362401 0.019222001, + 0.058412101 -0.018029099 0.0133, + 0.035366699 0.045955501 -0.162048, + 0.0248404 -0.045024302 0.053980999, + 0.027557701 -0.042652 0.052611001, + 0.0220857 -0.045360599 0.055282, + 0.0248404 -0.043002699 0.054065999, + 0.0204519 0.0074999998 0.056322001, + 0.0175486 0.0074999998 0.057376001, + 0.0226037 -0.0094999997 0.055578999, + 0.020478999 -0.0094999997 0.056396998, + 0.0220857 -0.043313898 0.055357002, + 0.030219801 -0.0145 0.051819999, + 0.0307914 -0.0145 0.051497001, + 0.0315402 0.0074999998 0.050948001, + 0.0281986 -0.0094999997 0.052960999, + 0.028914001 0.0074999998 0.052574001, + 0.035366699 -0.0166786 0.048447002, + 0.033491299 -0.0145 0.049775999, + 0.0332799 -0.0145 0.049924001, + 0.0328326 -0.018882399 0.050140001, + 0.036611602 0.0074999998 0.047435001, + 0.034166399 0.0074999998 0.049322002, + 0.041349601 -0.0094999997 0.043476999, + 0.052613001 -0.0094999997 0.028842, + 0.056809202 -0.021172799 0.018223001, + 0.056809202 -0.0181602 0.018945999, + 0.056809202 -0.032246701 0.015484, + 0.0576833 -0.0180947 0.016124999, + 0.055787299 -0.035674501 0.017873, + 0.056809202 -0.034875002 0.014786, + 0.0328326 -0.057571899 0.045713, + -0.0137106 -0.0937846 0.0067339898, + -0.0165099 -0.092655301 0.010549, + -0.0137106 -0.093287699 0.011241, + -0.0109179 -0.0943041 0.007276, + 0.0220857 -0.091016904 0.0087580001, + -0.061000001 -0.0033 -0.1313, + -0.061000001 -0.0153 -0.170167, + -0.0583959 0.0117813 -0.19149999, + -0.056669399 0.0177125 -0.19149999, + -0.059503399 0.0057039 -0.19149999, + -0.0487464 0.0091260504 -0.2085, + -0.047194201 0.014514 -0.2085, + -0.0353553 0.033355299 -0.2085, + -0.039091598 0.029174499 -0.2085, + -0.044033099 0.0387564 -0.19149999, + -0.044564299 -0.016586799 0.040123999, + -0.045067899 -0.0094999997 0.039609, + -0.046393901 -0.0145 0.038047001, + -0.050219599 -0.022015201 0.032106999, + -0.048467699 -0.022174001 0.034708999, + -0.0465759 -0.0145 0.037813999, + -0.046476301 0.0074999998 0.037820999, + -0.046537999 -0.0094999997 0.037870999, + -0.0532961 -0.040139001 0.023135001, + -0.0532961 -0.0430874 0.022042001, + -0.059999999 -0.027558999 -0.0056329998, + -0.059999999 -0.0401759 -0.018960999, + -0.059999999 -0.0412836 -0.021461001, + -0.059999999 -0.037481599 -0.014466, + -0.059999999 -0.035951499 -0.012503, + -0.055787299 -0.021342101 0.021073001, + -0.0576833 -0.031567801 0.012427, + -0.0576833 -0.034048799 0.011678, + -0.058203701 -0.0145 0.014571, + -0.0578092 -0.0094999997 0.016065, + -0.058412101 -0.0208176 0.012474, + -0.058412101 -0.025887299 0.010911, + -0.058412101 -0.030888099 0.0093650101, + -0.058998398 -0.0153745 0.010904, + -0.0591546 -0.0094999997 0.010036, + -0.058848299 -0.0145 0.011699, + -0.059351299 -0.0145 0.0087989997, + -0.059445001 -0.0250424 0.0050059999, + -0.058998398 -0.0324402 0.0054709902, + -0.058998398 -0.03021 0.0063100001, + -0.058998398 -0.025463499 0.0079490095, + -0.058998398 -0.0206428 0.00960699, + -0.059445001 -0.029536201 0.003274, + -0.0532961 0.025410499 -0.165934, + -0.058998398 -0.016268799 0.0108, + -0.058998398 -0.0179494 0.010444, + -0.0328326 -0.086371802 0.00131599, + -0.035366699 -0.084661298 0.001795, + -0.0328326 -0.086526401 -0.00083299301, + -0.040174201 -0.081568003 -0.014405, + -0.0378174 -0.083302803 -0.0041950098, + -0.0378174 -0.083024301 3.0059809e-006, + -0.040174201 -0.081275798 -0.001912, + -0.035366699 -0.084974602 -0.002451, + -0.035366699 -0.084835902 -0.000324997, + -0.059999999 -0.042200599 -0.024096999, + -0.059999999 -0.0429083 -0.026843, + -0.059999999 -0.043396499 -0.029668, + -0.058998398 -0.0515684 -0.018068001, + -0.058998398 -0.049630299 -0.012099, + -0.059445001 -0.047741801 -0.015149, + -0.0599402 -0.043010101 -0.018467, + -0.059445001 -0.046513502 -0.012391, + -0.059757002 -0.044750098 -0.015449, + -0.0599402 -0.041793101 -0.015935, + -0.055787299 -0.038321901 0.016988, + -0.055787299 -0.035652801 0.017867999, + -0.056809202 -0.0348529 0.014781, + -0.056809202 -0.0373987 0.013865, + -0.055787299 -0.041021802 0.015841, + -0.0546159 -0.039236698 0.020083001, + -0.0546159 -0.042061701 0.018962, + -0.059445001 -0.03779 -0.001466, + -0.058998398 -0.038964901 0.00169501, + -0.058998398 -0.041074701 -4.2007396e-005, + -0.059445001 -0.039772499 -0.003209, + -0.0220857 0.0525961 -0.15818, + -0.0248404 0.051423099 -0.15803599, + -0.027557701 0.050466701 -0.16015901, + -0.018242801 0.055145901 -0.1715, + -0.0175901 0.0553637 -0.1715, + -0.020382199 0.054432001 -0.1715, + -0.0182469 0.055158101 -0.19149999, + -0.040155701 0.0074999998 0.044581998, + -0.0377573 0.0074999998 0.046528, + -0.00559822 0.047685601 -0.2085, + 2.7929597e-012 0.048 -0.2085, + 0.0229499 0.053437401 -0.1715, + 0.0202034 0.054496199 -0.1715, + -0.0109179 -0.094862401 -0.0064470102, + -0.0109179 -0.094722398 -0.011044, + -0.0137106 -0.094314396 -0.0069400002, + 0.0109179 -0.094724298 -0.011044, + 0.0109179 -0.094419599 -0.015639, + 0.00267513 -0.095324002 -0.0149, + 0.0081421202 -0.093760297 -0.024463, + 0.0302257 -0.087533399 -0.021264, + 0.0302257 -0.085428298 -0.034324002, + 0.027557701 -0.086881101 -0.033302002, + 0.0328326 -0.0846968 -0.031165, + -0.0053918599 -0.093281902 -0.028795, + -0.0081421202 -0.093759798 -0.024463, + -0.0109179 -0.094418302 -0.015639, + -0.0109179 -0.093320899 -0.024786999, + -0.0109179 -0.093950801 -0.020222999, + -0.035366699 -0.083710402 -0.028179999, + -0.0460728 -0.040435601 -0.19149999, + -0.019305199 -0.089992702 0.020437, + -0.019305199 -0.089379899 0.022514001, + -0.019305199 -0.0923144 -0.017356999, + -0.0137106 -0.093380697 -0.020666, + -0.0165099 -0.092028499 -0.025742, + -0.019305199 -0.091821797 -0.021877, + -0.019305199 -0.091169603 -0.026377, + -0.0165099 -0.092671797 -0.021217, + -0.0137106 -0.092744797 -0.025212999, + -0.0165099 -0.091225803 -0.030241, + -0.0137106 -0.091948397 -0.029733, + -0.0248404 -0.089688897 -0.023535, + -0.0302257 -0.086979903 -0.02564, + -0.0328326 -0.085413903 -0.026857, + -0.0302257 -0.086276896 -0.029994, + -0.027557701 -0.087717503 -0.028929001, + -0.027557701 -0.088405497 -0.024532, + -0.0302257 -0.087529697 -0.021263, + -0.0165099 -0.091654703 0.017177001, + -0.019305199 -0.090922303 0.016314, + -0.0165099 -0.092024602 0.014997, + -0.019305199 -0.0905044 0.018375, + -0.0137106 -0.092642799 0.015707999, + -0.0220857 -0.091010399 0.00874699, + -0.0137813 -0.0094999997 0.058396, + -0.0146178 -0.0145 0.058192, + -0.0059254402 -0.0145 0.059707001, + -0.0038190801 -0.0094999997 0.059877999, + -0.0053918599 -0.023702901 0.059751999, + -0.0077038999 -0.0094999997 0.059503, + -0.0053918599 -0.042068701 0.059735, + 0.0137106 -0.041742198 0.058263998, + 0.0145255 -0.0145 0.058215, + 0.0137106 -0.032672901 0.058316, + 0.0053973799 0.056142099 -0.15651099, + 0.0081428103 0.0558304 -0.15646701, + 0.0054411199 0.0074999998 0.059753001, + 0.0084986202 0.0074999998 0.059315, + 0.0115561 0.0074999998 0.058876999, + 0.0107568 -0.0094999997 0.059028, + 0.00267513 -0.0421132 0.059935, + 0.00267513 -0.0444167 0.059934001, + 0.0046305298 -0.0094999997 0.059820998, + 0.00289505 -0.0145 0.05993, + 0.0023579099 -0.0094999997 0.059953999, + -6.6699576e-012 -0.042127699 0.060001001, + 0.0081421202 -0.041992899 0.059393, + 0.0081406701 -0.0145 0.059432998, + 0.0081421202 -0.032829501 0.059411, + 0.00875236 -0.0145 0.059358001, + 0.0058307201 -0.0145 0.059716001, + 0.0085099004 -0.0094999997 0.059393, + 0.0109179 -0.041884501 0.058905002, + 0.0116529 -0.0145 0.058858, + 0.0109179 -0.032761801 0.058938, + 0.00268824 0.056759 -0.158687, + 0.0053973799 0.0574673 -0.16512001, + 0.0165099 0.054504499 -0.15841, + 0.0165099 0.054069199 -0.156214, + -0.051830001 -0.061769299 0.010688, + -0.0532961 -0.0600035 0.007735, + -0.051830001 -0.062770799 0.0091199996, + -0.0532961 -0.058984 0.0092339898, + -0.058998398 -0.052150998 -0.021167001, + -0.058998398 -0.046744101 -0.00667, + -0.058998398 -0.0482958 -0.0093, + -0.058998398 -0.045001399 -0.0042359899, + -0.058412101 -0.0484243 -0.0035260001, + -0.058412101 -0.050089601 -0.0061900001, + -0.058412101 -0.053658701 -0.015101, + -0.058412101 -0.052724998 -0.012013, + -0.0576833 -0.054435398 -0.045598999, + -0.0599402 -0.045398299 -0.038612999, + -0.058412101 -0.0525495 -0.044558998, + -0.048467699 -0.073113203 -0.022400999, + -0.0465803 -0.0746378 -0.028270001, + -0.0465803 -0.074065402 -0.032258, + -0.048467699 -0.0727816 -0.026334001, + -0.048467699 -0.072314098 -0.030262999, + -0.048467699 -0.071710601 -0.034180999, + -0.048467699 -0.070971102 -0.038079999, + -0.0532961 -0.063370697 0.00130099, + -0.048467699 -0.0724914 -0.001198, + -0.044564299 -0.077178396 -0.00207401, + -0.0424264 -0.078253202 0.0059250002, + -0.044564299 -0.076741204 0.00177499, + -0.044564299 -0.076985203 -0.000102005, + -0.0465803 -0.074791498 -0.00057699601, + -0.0424264 -0.0778118 0.0078429999, + -0.0576833 -0.055754099 -0.012127, + -0.051830001 -0.068000101 -0.0046029999, + -0.050219599 -0.0700965 -0.001944, + -0.050219599 -0.070423201 -0.0037539999, + -0.050219599 -0.051358402 0.024972999, + -0.040174201 -0.065427601 0.032618001, + -0.0465803 -0.066793904 0.019091001, + -0.0465803 -0.065574698 0.020662, + -0.048467699 -0.062759601 0.019427, + -0.050219599 -0.062372401 0.01511, + -0.048467699 -0.064000301 0.017933, + -0.051830001 -0.060697801 0.012206, + -0.050219599 -0.055835199 0.021833001, + -0.0220857 -0.075469904 0.042307999, + -0.0248404 -0.073037602 0.042532999, + -0.0220857 -0.077120602 0.040681999, + -0.0220857 -0.080171898 0.037216, + -0.0220857 -0.081562698 0.035386998, + -0.0220857 -0.078689598 0.038982999, + -0.019305199 -0.080867901 0.038339, + -0.044564299 -0.068353698 0.0217, + -0.0378174 -0.072594099 0.028790999, + -0.0378174 -0.073903099 0.027094999, + -0.027557701 -0.073918998 0.039515998, + -0.027557701 -0.072243303 0.041046999, + -0.0248404 -0.074740604 0.040995002, + -0.0248404 -0.076367699 0.039377, + -0.0378174 -0.066598199 0.034898002, + -0.0378174 -0.071204402 0.030424001, + -0.0378174 -0.069738597 0.031991001, + -0.035366699 -0.073843502 0.03088, + -0.035366699 -0.072416998 0.032527, + -0.0328326 -0.072003901 0.036068, + -0.035366699 -0.070913397 0.034104999, + -0.035366699 -0.069337398 0.035608999, + -0.0302257 -0.073006302 0.037873, + -0.035366699 -0.075188003 0.029170001, + -0.040174201 -0.079998001 0.0080819996, + -0.0424264 -0.055860601 0.035925001, + -0.0283127 -0.0145 0.052900001, + -0.0308876 -0.0094999997 0.051438998, + -0.0301874 0.0074999998 0.051853001, + -0.044564299 -0.0408573 0.037946999, + -0.042443302 -0.0145 0.042408999, + -0.0424264 -0.0166113 0.042381998, + -0.040748298 -0.0145 0.044025, + -0.040756401 -0.0094999997 0.044032998, + -0.042397399 -0.0094999997 0.042454999, + -0.044472098 -0.0145 0.040277001, + -0.044526801 0.0074999998 0.040215999, + -0.0465803 -0.052034602 0.031544998, + -0.0465803 -0.053697702 0.030664001, + -0.048467699 -0.0509407 0.028749, + -0.044564299 -0.053086501 0.034233999, + -0.044564299 -0.054803699 0.033353999, + -0.051830001 -0.041024901 0.026133001, + -0.051830001 -0.039492302 0.026556, + -0.044564299 -0.0425734 0.037670001, + -0.0328326 -0.039752901 0.049302001, + -0.0328326 -0.018874399 0.050119001, + -0.0328326 -0.023104601 0.049959, + -0.0328326 -0.0516418 0.047722999, + -0.035366699 -0.050980501 0.045738, + -0.0378174 -0.0483624 0.044096999, + -0.0378174 -0.042700998 0.045058999, + -0.040174201 -0.043933202 0.042575002, + -0.040174201 -0.042120699 0.042821001, + -0.040174201 -0.045786299 0.042241, + -0.0424264 -0.043271001 0.040185999, + -0.0424264 -0.0415054 0.040447999, + -0.035366699 -0.0529253 0.045154002, + -0.0378174 -0.052169699 0.043008, + -0.0424264 -0.0450764 0.039839, + -0.040174201 -0.047647402 0.041820999, + -0.0302257 -0.071360901 0.039395999, + -0.0328326 -0.0703917 0.037581999, + -0.035366699 -0.067694098 0.037032999, + -0.021848099 -0.0094999997 0.055881001, + -0.022994 -0.0145 0.055419002, + -0.0220857 -0.019006399 0.055741999, + -0.015986601 -0.0094999997 0.057831001, + -0.019305199 -0.058394201 0.05398, + 0.0220857 -0.0474176 0.055119, + 0.0220857 -0.051626101 0.054501001, + 0.0220857 -0.049515199 0.054857999, + 0.0302257 -0.052246299 0.049563002, + 0.055787299 -0.0597318 -0.041065, + 0.055787299 -0.061797898 -0.023229999, + 0.055787299 -0.061335299 -0.030371999, + 0.055787299 -0.061627001 -0.026797, + 0.0532961 -0.066424198 -0.012549, + 0.055787299 -0.0618544 -0.019688001, + 0.055787299 -0.0617861 -0.016277, + 0.0328326 -0.086213998 -0.020357, + 0.035366699 -0.084742501 -0.019609001, + 0.0465803 -0.07519 -0.0043560001, + 0.0424264 0.040401399 -0.16903099, + 0.0378174 0.044068299 -0.16189399, + 0.040174201 0.042052399 -0.16172899, + 0.061000001 0.0057000001 -0.1337, + 0.061000001 0.0057000001 -0.163167, + 0.061000001 0.0029360701 -0.166971, + 0.061000001 0.0097000003 -0.14083301, + 0.061000001 -0.0090360697 -0.13014901, + 0.061000001 0.0097000003 -0.12549999, + 0.058412101 -0.040146701 0.0049049999, + 0.0576833 -0.043703701 0.0063709999, + 0.0576833 -0.045986399 0.0043830001, + 0.059445001 -0.031665199 0.0023960001, + 0.058998398 -0.034618098 0.0044620102, + 0.058412101 -0.035545301 0.0075989999, + 0.056809202 -0.051807601 0.0028009899, + 0.055787299 -0.0534801 0.0059310002, + 0.059757002 -0.038489301 -0.0063120001, + 0.059757002 -0.036627099 -0.0045639998, + 0.059757002 -0.040268201 -0.0082830004, + 0.059445001 -0.046536099 -0.012365, + 0.059757002 -0.047981199 -0.032931, + 0.0599402 -0.045740101 -0.035634998, + 0.059445001 -0.047768202 -0.015125, + 0.059445001 -0.0502523 -0.030191001, + 0.056809202 -0.059486099 -0.019052001, + 0.056809202 -0.059497401 -0.022398001, + 0.0576833 -0.0547571 -0.0089670001, + 0.059923101 -0.0145 0.0030370001, + 0.059760101 -0.0094999997 0.0053599998, + 0.0599204 -0.0094999997 0.003089, + 0.0599402 -0.016182 0.00256799, + 0.0599568 0.0074999998 0.0022760001, + 0.059757002 -0.0170458 0.0051299999, + 0.059285302 -0.0094999997 0.0092329998, + 0.0599402 -0.031885501 -0.0047829999, + 0.0328326 -0.0476669 0.048606001, + 0.035366699 -0.0451537 0.046943001, + 0.0378174 -0.044569802 0.044835001, + 0.0424264 -0.046886001 0.039425001, + 0.040174201 -0.047644399 0.041838001, + 0.044564299 -0.049601499 0.035746999, + 0.019305199 0.054523598 -0.164939, + 0.019305199 0.054780401 -0.16932601, + 0.017408401 0.055419099 -0.1715, + 0.019305199 0.054685399 -0.167138, + 0.027557701 0.0501175 -0.15787201, + 0.0564248 0.0074999998 0.020401999, + 0.056464098 -0.0145 0.020292999, + 0.0576833 -0.016332099 0.016419999, + 0.0576679 -0.0145 0.016505999, + 0.058021698 -0.0094999997 0.01528, + 0.059445001 -0.016241301 0.0080350004, + 0.059445001 -0.0170916 0.00789, + 0.059337199 -0.0145 0.0088930102, + 0.059404999 0.0074999998 0.0084290002, + 0.059702002 -0.0145 0.0059730099, + 0.059757002 -0.0162115 0.0052829999, + 0.058829699 -0.0145 0.011793, + 0.058998398 -0.016271399 0.010816, + 0.058892298 -0.0094999997 0.011476, + 0.058412101 -0.016301701 0.013615, + 0.058223501 0.0074999998 0.014492, + 0.0581805 -0.0145 0.014664, + 0.035366699 0.046185799 -0.164426, + 0.0328326 0.047707099 -0.162192, + 0.0328326 0.047408301 -0.159844, + 0.027557701 -0.046647198 0.052336, + 0.027557701 -0.044645201 0.052517001, + 0.0248404 -0.047055401 0.05381, + 0.0248404 -0.049126301 0.053543001, + 0.027557701 -0.050742202 0.051690001, + 0.0302257 -0.050221998 0.050035998, + 0.0302257 -0.048201501 0.050414, + 0.027557701 -0.048688199 0.052060999, + 0.0248404 -0.0512104 0.053179, + 0.019305199 -0.041352998 0.056510001, + 0.019305199 -0.032429799 0.056616001, + 0.020158799 -0.0145 0.056511998, + 0.0220857 -0.023455501 0.055677, + 0.037814599 -0.0145 0.046576999, + 0.036660202 -0.0094999997 0.047497999, + 0.0356883 -0.0145 0.048232, + 0.0378174 -0.0166582 0.046555001, + 0.038435601 -0.0094999997 0.046073001, + 0.038010798 -0.0145 0.046424001, + 0.0390567 0.0074999998 0.045547001, + 0.0384284 -0.0145 0.046064999, + 0.0402418 -0.0145 0.044504002, + 0.0429691 -0.0094999997 0.041877002, + 0.043532901 0.0074999998 0.04129, + 0.042376 -0.0145 0.042477001, + 0.040174201 -0.016636301 0.044535, + 0.019305199 -0.090507597 0.018375, + 0.054028001 0.0074999998 0.026095999, + 0.0546159 -0.0182897 0.024532, + 0.0532961 -0.038683198 0.023585999, + 0.0532961 -0.037247799 0.023947001, + 0.0546159 -0.036466502 0.020931, + 0.0532961 -0.040142901 0.023153, + 0.051830001 -0.042557798 0.025657, + 0.055787299 -0.0383261 0.017006001, + 0.0424264 -0.0710942 0.022546001, + 0.044564299 -0.067105599 0.023308, + 0.044564299 -0.068372197 0.021718999, + 0.0424264 -0.069862098 0.024211001, + 0.040174201 -0.072548501 0.024894999, + 0.0465803 -0.053701699 0.030688001, + 0.048467699 -0.050942801 0.028774001, + 0.048467699 -0.049315602 0.029572001, + 0.044564299 -0.069562003 0.020071, + 0.050219599 -0.065543599 0.010367, + 0.048467699 -0.067313597 0.01313, + 0.051830001 -0.062793799 0.0091399997, + 0.048467699 -0.068255797 0.011428, + 0.044564299 -0.065766796 0.024834, + 0.0465803 -0.061522901 0.025012, + 0.044564299 -0.062890597 0.027675999, + 0.0465803 -0.060046799 0.026310001, + 0.044564299 -0.064360201 0.026292, + -0.0137106 -0.094122797 0.00219501, + -0.0137106 -0.094299696 -0.0023650101, + -0.0109179 -0.093796402 0.011798, + 0.00267513 -0.095505103 0.0035669999, + 7.389268e-012 -0.095761098 -0.00098500098, + 0.0053918599 -0.0954431 -0.010427, + 0.0109179 -0.094865002 -0.0064470102, + 0.0081421202 -0.095281899 -0.0060709999, + 0.0137106 -0.094303697 -0.0023650101, + -0.00267513 -0.093939297 0.017199, + -0.0081421202 -0.092685699 0.021005001, + -0.0109179 -0.091779999 0.022646001, + -0.0081421202 -0.092144802 0.023096001, + -0.0053918599 -0.093392797 0.019223001, + -0.019305199 -0.084808402 0.032669999, + -0.0220857 -0.0828593 0.033504002, + 0.0424264 -0.079434097 -0.0039220001, + 0.044564299 -0.077187702 -0.0020590101, + 0.0378174 -0.081651203 0.010116, + 0.0165099 -0.093144096 0.0060649998, + -0.061000001 0.0057000001 -0.16796701, + -0.061000001 -0.0070360699 -0.18230399, + -0.061000001 -0.0057999999 -0.1797, + -0.044567399 0.0381715 -0.1715, + -0.042543601 0.0403088 -0.1715, + -0.0532961 -0.051663 0.016946999, + -0.0546159 -0.050264601 0.013849, + -0.051830001 -0.054435398 0.018866999, + -0.0546159 -0.0539768 0.010315, + -0.0532961 -0.054301601 0.014644, + -0.0546159 -0.051543701 0.01274, + -0.0546159 -0.0527828 0.011561, + -0.0532961 -0.053002801 0.015830999, + -0.0501853 -0.0094999997 0.032885, + -0.048901699 -0.0094999997 0.034765001, + -0.0546159 -0.047607999 0.01585, + -0.0522171 -0.0094999997 0.029553, + -0.056809202 -0.0322465 0.015485, + -0.056809202 -0.021167999 0.018217999, + -0.0576833 -0.020992899 0.015349, + -0.058412101 -0.0180149 0.013263, + -0.059445001 -0.0178842 0.00764301, + -0.059445001 -0.020469001 0.0067579998, + -0.059445001 -0.0153593 0.0081280097, + -0.0597114 -0.0145 0.0058780098, + -0.059445001 -0.016238701 0.0080190003, + -0.059682 -0.0094999997 0.00616901, + -0.059757002 -0.0246257 0.0020949999, + -0.059757002 -0.0288695 0.00027099601, + -0.059445001 -0.031642001 0.0023910101, + -0.059757002 -0.020297101 0.003939, + -0.0484627 0.033363301 -0.1715, + -0.051830001 0.028079201 -0.166044, + -0.0529892 0.026145101 -0.1715, + -0.048467699 0.033054002 -0.163618, + -0.0328326 -0.086643502 -0.00299001, + -0.0302257 -0.087783702 0.0028250001, + -0.0328326 -0.086180799 0.003459, + -0.035366699 -0.085076198 -0.004584, + -0.0378174 -0.0833878 -0.006302, + -0.0328326 -0.0865473 -0.016008999, + -0.0465803 -0.075522497 -0.016272999, + -0.0424264 -0.0796028 -0.016263001, + -0.044564299 -0.077273101 -0.022288, + -0.0465803 -0.075365998 -0.020269999, + -0.0465803 -0.075071201 -0.024272, + -0.044564299 -0.077532403 -0.018221, + -0.0424264 -0.079377301 -0.020393001, + -0.059445001 -0.048738498 -0.018036, + -0.059757002 -0.0458735 -0.018166, + -0.0599402 -0.044029899 -0.021143001, + -0.059445001 -0.035758201 4.2007396e-005, + -0.059445001 -0.0336922 0.001325, + -0.059757002 -0.0308524 -0.00065699802, + -0.059445001 -0.041671801 -0.0051850001, + -0.019305199 0.053984199 -0.16051801, + -0.0165099 0.0556482 -0.16934299, + -0.0137069 0.056396201 -0.1715, + -0.0147556 0.056157298 -0.1715, + -0.0122713 0.0567232 -0.1715, + -0.0220857 0.053257599 -0.16264699, + -0.0220857 0.052960899 -0.160414, + -0.019305199 0.054280799 -0.16272999, + -0.019305199 0.0545105 -0.164937, + -0.0248404 0.0520849 -0.162551, + -0.0248404 0.051787999 -0.160294, + -0.0240272 0.052979 -0.19149999, + -0.0220857 0.053651702 -0.16709501, + -0.019305199 0.054674398 -0.167137, + -0.0220857 0.053487498 -0.164874, + -0.019305199 0.054773599 -0.16932499, + -0.0026879699 0.057931099 -0.1715, + -0.000344617 0.057999 -0.1715, + 0.0165099 0.055558801 -0.167174, + 0.0165099 0.0553969 -0.164992, + 0.0182469 0.055158101 -0.19149999, + 0.016505901 0.0556687 -0.1715, + 0.0165099 0.055654 -0.16934399, + 0.00268824 0.057908598 -0.16938999, + -7.6425827e-012 0.057999998 -0.19149999, + -9.7031021e-015 0.057999998 -0.1715, + -0.0053918599 -0.095442198 -0.010427, + -0.0081421202 -0.095146 -0.010681, + -0.00267513 -0.095323697 -0.0149, + -0.0053918599 -0.095571801 -0.005808, + -0.0081421202 -0.095279999 -0.0060709999, + -0.0220857 -0.0918613 -0.009149, + -0.0165099 -0.093475103 -0.012114, + -0.0137106 -0.094166301 -0.011521, + -0.0165099 -0.093154401 -0.016671, + -0.019305199 -0.0926461 -0.012824, + -0.0137106 -0.093854897 -0.016099, + 0.0137106 -0.094317697 -0.0069400002, + 0.0137106 -0.094168797 -0.011521, + -0.00267513 -0.095616102 -0.010278, + 2.1712742e-012 -0.095381297 -0.014853, + -0.00267513 -0.095743202 -0.00565401, + 0.035366699 -0.084905401 -0.017459, + 0.035366699 -0.085030399 -0.015309, + 0.0109179 -0.093951598 -0.020222999, + 0.0165099 -0.091228202 -0.030241, + 0.0152803 -0.060021698 -0.19149999, + 0.0081421202 -0.0929735 -0.029012, + 0.00923343 -0.061285298 -0.19149999, + 0.0137106 -0.091950402 -0.029733, + 0.0109179 -0.093321599 -0.024788, + 0.0109179 -0.0925311 -0.029324001, + 0.0302257 -0.086982198 -0.025641, + 0.0302257 -0.086278997 -0.029995, + 0.0328326 -0.085416399 -0.026857, + 0.0328326 -0.085720502 -0.024695, + 0.0302257 -0.087277099 -0.023453999, + 0.027557701 -0.088407598 -0.024533, + 0.027557701 -0.0877195 -0.028929999, + -0.00267513 -0.0934636 -0.028666999, + -1.1360454e-012 -0.093523003 -0.028625, + -6.7823629e-012 -0.094305404 -0.02406, + -0.0053918599 -0.094688699 -0.019649999, + -0.0081421202 -0.094385199 -0.019886, + -0.0053918599 -0.094066501 -0.024235999, + -0.00267513 -0.094246499 -0.024103001, + -0.00267513 -0.094866902 -0.019512, + -0.0053918599 -0.095147602 -0.015044, + -0.0081421202 -0.094847597 -0.015289, + -0.0424264 -0.078493901 -0.028642001, + -0.040174201 -0.0805481 -0.026963999, + -0.0424264 -0.079007901 -0.024522001, + -0.044564299 -0.076329798 -0.030409001, + -0.0424264 -0.077835798 -0.032745998, + -0.044564299 -0.076872297 -0.026353, + -0.0378174 -0.081118599 -0.033806998, + -0.0378174 -0.081874996 -0.029607, + -0.035366699 -0.0829731 -0.032435998, + -0.0322018 -0.052626502 -0.19149999, + -0.040174201 -0.0799146 -0.031129999, + -0.040174201 -0.079137601 -0.035271998, + -0.037236601 -0.049047198 -0.19149999, + -0.0378174 -0.082485303 -0.025381999, + -0.040174201 -0.081035003 -0.022783, + -0.040174201 -0.081374802 -0.018594, + -0.0220857 -0.087858103 0.023531999, + -0.0220857 -0.088557802 0.021472, + -0.0220857 -0.084059201 0.031574, + -0.0109179 -0.091141298 0.024746999, + -0.0165099 -0.0900831 0.023406001, + -0.0137106 -0.090669498 0.024149001, + -0.019305199 -0.085925497 0.030692, + -0.0137106 -0.091830902 0.019974999, + -0.0137106 -0.091301396 0.022054, + -0.0109179 -0.092316099 0.02056, + -0.0137106 -0.092265502 0.017896, + -0.0165099 -0.091227703 0.019246999, + -0.0165099 -0.090706304 0.021319, + -0.027557701 -0.087125003 0.016892999, + -0.0248404 -0.088202201 0.018224001, + -0.0248404 -0.089084499 0.014149, + -0.027557701 -0.087597601 0.01487, + -0.0248404 -0.088689499 0.016186999, + -0.0220857 -0.090066001 0.015306, + -0.0220857 -0.0904167 0.013148, + -0.027557701 -0.088938497 -0.020113001, + -0.0302257 -0.087924398 -0.016874, + -0.0302257 -0.088063397 -0.014677, + -0.0248404 -0.090420902 0.0032270099, + -0.019305199 -0.092364103 0.00525301, + -0.0165099 -0.093138598 0.00606, + -0.019305199 -0.091896899 0.009718, + -0.0220857 -0.091253497 0.0065319999, + -0.0220857 -0.091458701 0.0043090102, + -0.0165099 -0.093464203 0.00154201, + -0.0220857 -0.091624796 0.002078, + 0.0053918599 -0.044368099 0.059732001, + 0.0081421202 -0.044285402 0.059388001, + -0.0165099 -0.0190515 0.057657, + 0.00267513 -0.048700102 0.059756, + 0.0053918599 -0.0464991 0.059687998, + 0.00267513 -0.046551298 0.059891, + 0.0053918599 -0.048643898 0.059551999, + -0.00267513 -0.044416301 0.059934001, + -7.8755214e-012 -0.046567898 0.059957001, + -7.1600061e-013 -0.048718199 0.059822999, + 0.019305199 -0.051988602 0.055654, + 0.0053973799 0.056576502 -0.158665, + -0.0081428103 0.0569214 -0.162946, + -0.00268824 0.056323402 -0.15653799, + -4.1353934e-012 0.056384001 -0.156546, + -0.00689648 0.0074999998 0.059602, + -0.00994239 0.0074999998 0.05909, + -0.0129883 0.0074999998 0.058577001, + 3.6813968e-012 0.056818001 -0.158695, + -0.0159654 0.0074999998 0.057753999, + 0.0053973799 0.057238299 -0.162972, + 0.0053973799 0.056941599 -0.16081899, + 0.0109154 0.056984302 -0.1715, + 0.0053973799 0.0576296 -0.16725899, + 0.0109179 0.0558189 -0.158572, + 0.0109179 0.055384099 -0.15640201, + 0.0137106 0.054798 -0.15631901, + 0.0137106 0.055233002 -0.1585, + 0.0081428103 0.056265 -0.15862601, + 0.0081428103 0.056630202 -0.160787, + -0.058998398 -0.0520969 -0.033860002, + -0.0576833 -0.056501001 -0.015341, + -0.058412101 -0.054323401 -0.018257, + -0.056809202 -0.058675401 -0.012429, + -0.0546159 -0.063363098 -0.0083760098, + -0.058412101 -0.053754602 -0.037889, + -0.058412101 -0.053207301 -0.041228, + -0.058998398 -0.0506404 -0.043655999, + -0.059445001 -0.049260698 -0.039687999, + -0.059445001 -0.0496905 -0.036495, + -0.058998398 -0.051718201 -0.037126001, + -0.058998398 -0.051233001 -0.040392999, + -0.059445001 -0.048727401 -0.042881001, + -0.059757002 -0.047309801 -0.039101001, + -0.059757002 -0.046829399 -0.042224001, + -0.061000001 -0.0153 -0.1855, + -0.051830001 -0.065972 -0.041965, + -0.050219599 -0.068506896 -0.039995, + -0.0546159 -0.0619899 -0.00327699, + -0.055787299 -0.060838301 -0.0095319999, + -0.0546159 -0.061379701 -0.0016120001, + -0.0532961 -0.065095097 -0.0038320001, + -0.051830001 -0.067625202 -0.0028230001, + -0.0532961 -0.065513603 -0.0055740098, + -0.0546159 -0.0629813 -0.00666299, + -0.0546159 -0.0625237 -0.0049609998, + -0.0546159 -0.059935901 0.001632, + -0.0546159 -0.060694501 2.6001e-005, + -0.0532961 -0.061834499 0.0045959898, + -0.0546159 -0.059105501 0.0032009999, + -0.0532961 -0.062640302 0.002965, + -0.055787299 -0.0572307 0.00017399598, + -0.056809202 -0.053683098 4.2007399e-005, + -0.055787299 -0.056382202 0.001679, + -0.0576833 -0.051887602 -0.0030720099, + -0.050219599 -0.064545102 0.011985, + -0.050219599 -0.0634946 0.013574, + -0.048467699 -0.065171801 0.016379001, + -0.051830001 -0.063698702 0.0075059999, + -0.040174201 -0.080900602 0.00220599, + -0.0424264 -0.0788721 0.0021200001, + -0.0424264 -0.078604497 0.0040229899, + -0.048467699 -0.072764002 -0.003022, + -0.0465803 -0.075010799 -0.0024279901, + -0.0465803 -0.0751803 -0.004371, + -0.0424264 -0.079421602 -0.0039420002, + -0.040174201 -0.0815171 -0.006056, + -0.040174201 -0.081615299 -0.010223, + -0.0532961 -0.0661183 -0.0090770004, + -0.0532961 -0.065854602 -0.0073250001, + -0.051830001 -0.068295702 -0.0063849902, + -0.0546159 -0.063669503 -0.010096, + -0.0465803 -0.0569431 0.028643001, + -0.048467699 -0.055681899 0.025849, + -0.048467699 -0.054130301 0.026899001, + -0.0465803 -0.0553362 0.029696001, + -0.0465803 -0.060036302 0.026286, + -0.048467699 -0.057195898 0.024715999, + -0.048467699 -0.058666501 0.023505, + -0.0465803 -0.058511902 0.027504999, + -0.0465803 -0.0615105 0.024989, + -0.044564299 -0.061353602 0.028960001, + -0.0424264 -0.060986798 0.032749001, + -0.0424264 -0.062612601 0.031516001, + -0.044564299 -0.059777401 0.030187, + -0.0424264 -0.059315201 0.033897001, + -0.044564299 -0.058155999 0.031328999, + -0.040174201 -0.063807704 0.033941999, + -0.0424264 -0.065701902 0.028805999, + -0.044564299 -0.062878802 0.027654, + -0.0424264 -0.064186402 0.030200999, + -0.040174201 -0.066988401 0.031213, + -0.040174201 -0.0684838 0.029732, + -0.044564299 -0.064346597 0.02627, + -0.0465803 -0.064284801 0.022173, + -0.0465803 -0.062928602 0.023615999, + -0.0424264 -0.068535604 0.025797, + -0.0424264 -0.069844499 0.024193, + -0.044564299 -0.067088701 0.023288, + -0.044564299 -0.0657515 0.024813, + -0.0424264 -0.067153201 0.027336, + -0.040174201 -0.069909103 0.028178001, + -0.040174201 -0.071259603 0.026559001, + -0.050219599 -0.0586165 0.019352, + -0.051830001 -0.055792902 0.017671, + -0.050219599 -0.057250001 0.020629, + -0.048467699 -0.060087699 0.022217, + -0.048467699 -0.061454002 0.020857001, + -0.051830001 -0.058360599 0.015068, + -0.050219599 -0.0611826 0.016588001, + -0.051830001 -0.059560299 0.013667, + -0.050219599 -0.0599292 0.018004, + -0.051830001 -0.057103101 0.016403999, + -0.0532961 -0.056755401 0.012064, + -0.0532961 -0.0555542 0.013387, + -0.051830001 -0.051600602 0.021032, + -0.050219599 -0.052883301 0.024007, + -0.050219599 -0.054377701 0.02296, + -0.051830001 -0.053036101 0.019988, + -0.051830001 -0.050135098 0.021996999, + -0.0532961 -0.050287802 0.017987, + -0.0532961 -0.048883099 0.018952001, + -0.0137106 -0.078808002 0.043607999, + -0.019305199 -0.076106198 0.043453, + -0.0220857 -0.073742799 0.043853, + -0.0220857 -0.071944498 0.045311, + -0.027557701 -0.0686891 0.043852001, + -0.0248404 -0.069426998 0.04535, + -0.0248404 -0.0712642 0.043986, + -0.027557701 -0.070497803 0.042493001, + -0.027557701 -0.066824101 0.045118999, + -0.0328326 -0.0809903 0.023689, + -0.044564299 -0.069542304 0.020053999, + -0.0424264 -0.073288403 0.019049, + -0.0328326 -0.084079497 0.015791999, + -0.0328326 -0.0846138 0.013788, + -0.0302257 -0.085374802 0.017434999, + -0.0302257 -0.085928299 0.015413, + -0.0328326 -0.0827263 0.019778, + -0.0328326 -0.081906401 0.021745, + -0.0328326 -0.083450399 0.017792, + -0.035366699 -0.076446198 0.027402001, + -0.0328326 -0.079977699 0.025603, + -0.040174201 -0.062134799 0.035181999, + -0.0378174 -0.064934701 0.036230002, + -0.0302257 -0.066036798 0.043451, + -0.035366699 -0.083602697 0.010051, + -0.035366699 -0.039327499 0.047386002, + -0.035366699 -0.0229948 0.048160002, + -0.0308873 -0.0145 0.051438998, + -0.030873001 -0.0145 0.051447999, + -0.0328166 -0.0094999997 0.05023, + -0.0328326 -0.0166962 0.050193001, + -0.035764702 -0.0145 0.048176002, + -0.033358999 -0.0145 0.049872, + -0.035366699 -0.0166771 0.048436999, + -0.0378174 -0.016656499 0.046544999, + -0.038084399 -0.0145 0.046363998, + -0.036012899 -0.0094999997 0.047990002, + -0.037807401 -0.0094999997 0.04659, + -0.035358898 0.0074999998 0.048473999, + -0.0254349 -0.0094999997 0.054342002, + -0.027478 -0.0094999997 0.053337999, + -0.024695801 0.0074999998 0.054682001, + -0.025684301 -0.0145 0.054225001, + -0.048467699 -0.039473899 0.032611001, + -0.048467699 -0.0378801 0.032850001, + -0.0465803 -0.0401791 0.035331, + -0.0465803 -0.041843399 0.035037, + -0.050219599 -0.038744699 0.029797999, + -0.051830001 -0.037994601 0.026904, + -0.050219599 -0.0372063 0.030057, + -0.044564299 -0.0443285 0.037308998, + -0.0220857 -0.055855799 0.053475998, + -0.0328326 -0.041829899 0.049219999, + -0.027557701 -0.016729699 0.053277999, + -0.0109179 -0.073809899 0.048944999, + -0.0328326 -0.045685101 0.048893001, + -0.035366699 -0.043244299 0.047153998, + -0.0328326 -0.043748699 0.049098998, + -0.0302257 -0.0461841 0.050693002, + -0.0302257 -0.048199199 0.050404999, + -0.035366699 -0.047082599 0.046627, + -0.0328326 -0.0476644 0.048595, + -0.035366699 -0.045142401 0.046936002, + -0.035366699 -0.049031802 0.046227999, + -0.0378174 -0.046455801 0.044505998, + -0.0328326 -0.049653102 0.048206002, + -0.0378174 -0.044557702 0.044826999, + -0.027557701 -0.064909801 0.046289999, + -0.0302257 -0.060273699 0.046661001, + -0.0328326 -0.066969097 0.04036, + -0.0302257 -0.069646403 0.040835001, + -0.0302257 -0.067869499 0.042188, + -0.0328326 -0.068711303 0.039014, + -0.035366699 -0.0659898 0.038371999, + -0.0302257 -0.0502243 0.050023999, + -0.027557701 -0.050744198 0.051679, + -0.0248404 -0.0533011 0.052705999, + -0.019305199 -0.062610596 0.052347001, + -0.019305199 -0.060511999 0.053215999, + 0.0328326 -0.053624399 0.047162, + 0.0302257 -0.054269299 0.048990998, + 0.0328326 -0.051638201 0.047738001, + 0.0328326 -0.0556041 0.046487, + 0.035366699 -0.0529228 0.045171, + 0.0302257 -0.056285899 0.048321001, + 0.035366699 -0.050976701 0.045754001, + 0.0248404 -0.059533998 0.050726, + 0.027557701 -0.0569066 0.049989998, + 0.0220857 -0.060056798 0.052060999, + 0.027557701 -0.0589449 0.049221002, + 0.0302257 -0.058290601 0.047548998, + 0.0248404 -0.061583299 0.049855001, + 0.027557701 -0.0609641 0.048349999, + 0.0220857 -0.064181797 0.050218001, + 0.0220857 -0.062132899 0.051192001, + 0.0109179 -0.059320901 0.056481, + 3.6294854e-012 -0.061936598 0.056860998, + -0.0081421202 -0.0740695 0.049449999, + 0.0137106 -0.056905601 0.056467999, + 0.0165099 -0.0544568 0.056191001, + 0.019305199 -0.054126699 0.055202, + 0.0248404 -0.057465401 0.051493, + 0.027557701 -0.054856502 0.050657, + 0.027557701 -0.0528 0.051222999, + 0.0220857 -0.055854201 0.053486999, + 0.0220857 -0.053740699 0.054044001, + 0.0248404 -0.055385001 0.052156001, + 0.0220857 -0.057961401 0.052825999, + 0.0248404 -0.053298298 0.052717999, + 0.058412101 -0.0525635 -0.044558998, + 0.0465803 -0.0746461 -0.028271001, + 0.044564299 -0.076880299 -0.026354, + 0.055787299 -0.060387101 -0.037510999, + 0.055787299 -0.060921699 -0.033945002, + 0.037236601 -0.049047198 -0.19149999, + 0.040174201 -0.079140402 -0.035273001, + 0.044564299 -0.075649098 -0.034449, + 0.044564299 -0.076335303 -0.030409999, + 0.0424264 -0.077839002 -0.032747, + 0.0424264 -0.077040002 -0.036826, + 0.044564299 -0.074827097 -0.038463, + 0.035366699 -0.085088097 -0.0045770002, + 0.035366699 -0.085152097 -0.0067179999, + 0.044564299 -0.077545501 -0.018219, + 0.044564299 -0.0772838 -0.022289, + 0.0465803 -0.0755568 -0.012273, + 0.0465803 -0.075438097 -0.0082970001, + 0.044564299 -0.077481396 -0.00606, + 0.044564299 -0.077665403 -0.014154, + 0.050219599 -0.070842803 -0.0073439898, + 0.051830001 -0.068659097 -0.0099170096, + 0.051830001 -0.068519503 -0.0081540104, + 0.048467699 -0.0731126 -0.0067449999, + 0.034765299 0.046901699 -0.19149999, + 0.0424264 0.040307902 -0.166549, + 0.0424264 0.040145699 -0.164055, + 0.038047399 0.044393901 -0.1715, + 0.059999999 -0.029323401 -0.0066430098, + 0.058998398 -0.0410797 -1.1993393e-005, + 0.058412101 -0.042390201 0.00317599, + 0.058998398 -0.038964301 0.001724, + 0.059445001 -0.039777599 -0.003179, + 0.059445001 -0.037789401 -0.001437, + 0.050219599 -0.070109598 -0.001942, + 0.050219599 -0.068648502 0.00345799, + 0.0546159 -0.0582279 0.0047510099, + 0.055787299 -0.0554903 0.0031640001, + 0.055787299 -0.054513998 0.0045750001, + 0.0532961 -0.061859298 0.0046150102, + 0.0532961 -0.060978498 0.006209, + 0.0546159 -0.0591297 0.0032230101, + 0.051830001 -0.063722901 0.007524, + 0.051830001 -0.068306401 -0.0063849902, + 0.055787299 -0.0512558 0.0084629999, + 0.055787299 -0.052392401 0.0072280001, + 0.056809202 -0.049701899 0.0053090099, + 0.056809202 -0.047424801 0.0075690001, + 0.055787299 -0.050075099 0.0096340002, + 0.059757002 -0.047327399 -0.039073002, + 0.059757002 -0.046849199 -0.042206001, + 0.061000001 -0.0153 -0.1855, + 0.059757002 -0.047707401 -0.035953, + 0.0599402 -0.0454107 -0.038594, + 0.059445001 -0.050257999 -0.027125999, + 0.059757002 -0.0480504 -0.029927, + 0.059445001 -0.049518801 -0.021003, + 0.059445001 -0.050014801 -0.024049001, + 0.059445001 -0.048767 -0.018015999, + 0.058412101 -0.044546001 0.001192, + 0.0576833 -0.048139799 0.002138, + 0.0576833 -0.050126102 -0.000345993, + 0.058412101 -0.0501118 -0.0061639999, + 0.058998398 -0.0483183 -0.0092740003, + 0.059445001 -0.045092799 -0.0097650001, + 0.056809202 -0.0592332 -0.01574, + 0.056809202 -0.055363599 -0.0028589901, + 0.055787299 -0.057255398 0.000195999, + 0.055787299 -0.056405298 0.001703, + 0.056809202 -0.053704701 6.7001303e-005, + 0.0576833 -0.0534616 -0.0059310002, + 0.0576833 -0.051909599 -0.0030460099, + 0.058998398 -0.0179637 0.010481, + 0.058412101 -0.0308883 0.0093639996, + 0.059757002 -0.0178343 0.0049100001, + 0.0599402 -0.033692401 -0.00611099, + 0.059999999 -0.030992899 -0.0078019998, + 0.0328326 -0.045695599 0.048900001, + 0.0302257 -0.044224098 0.050889, + 0.0302257 -0.046193801 0.050698999, + 0.035366699 -0.043258101 0.047157001, + 0.0328326 -0.041834399 0.049221002, + 0.035366699 -0.0188416 0.048372, + 0.0328326 -0.043761399 0.049102001, + 0.0378174 -0.038869299 0.045320999, + 0.0378174 -0.042715698 0.045062002, + 0.035366699 -0.041368902 0.047290001, + 0.0378174 -0.018797699 0.046468001, + 0.044564299 -0.037313901 0.038313001, + 0.047047202 -0.0094999997 0.037237, + 0.047547702 0.0074999998 0.036595002, + 0.0532961 -0.0183533 0.027274, + 0.040174201 -0.049502801 0.041331999, + 0.0424264 -0.050503399 0.038306002, + 0.0424264 -0.048695602 0.038910002, + 0.0465803 -0.052036598 0.031569, + 0.0465803 -0.050353199 0.032363001, + 0.051830001 -0.041028801 0.026148999, + 0.0109179 0.056481201 -0.16291, + 0.0081428103 0.056926999 -0.162947, + 0.0081428103 0.057156101 -0.16509999, + 0.0109179 0.056184299 -0.160742, + 0.0137106 0.055895802 -0.162862, + 0.0137106 0.055598699 -0.16068199, + 0.0248404 0.0518042 -0.160294, + 0.0220857 0.053273 -0.16264699, + 0.0302257 0.049547099 -0.16463301, + 0.0328326 0.0479373 -0.164534, + 0.0328326 0.048099101 -0.166868, + 0.0302257 0.0493172 -0.162323, + 0.027557701 0.050484601 -0.16015901, + 0.0302257 0.0490187 -0.160009, + 0.0275518 -0.0145 0.053284999, + 0.027557701 -0.0232997 0.053119998, + 0.028228801 -0.0145 0.052944999, + 0.0261693 -0.0094999997 0.053991999, + 0.0248347 -0.0145 0.054602999, + 0.0248404 -0.023382301 0.054474, + 0.0229061 -0.0145 0.055456001, + 0.0255982 -0.0145 0.054265, + 0.0233551 0.0074999998 0.055268001, + 0.044408198 -0.0145 0.040346999, + 0.044560701 -0.0145 0.040171001, + 0.046333499 -0.0145 0.038121, + 0.0424264 -0.018700801 0.042277001, + 0.040174201 -0.0383798 0.043115001, + 0.040174201 -0.018750601 0.044434, + 0.0424264 -0.0166132 0.042392999, + 0.040174201 -0.042136401 0.042824, + 0.0424264 -0.037860699 0.040777002, + 0.044564299 -0.0186482 0.040004998, + 0.044564299 -0.0165888 0.040135998, + 0.0165099 -0.091230497 0.019246999, + 0.019305199 -0.091902599 0.0097270096, + 0.0165099 -0.092660099 0.010556, + 0.0532832 -0.0145 0.027550999, + 0.053653602 -0.0145 0.026818, + 0.053669199 -0.0094999997 0.026826, + 0.055400901 -0.0145 0.023038, + 0.055771999 -0.0145 0.02208, + 0.055787299 -0.0163926 0.022008, + 0.0546159 -0.016422501 0.024769001, + 0.056143001 -0.0094999997 0.021165, + 0.055299699 -0.0094999997 0.02328, + 0.054204401 -0.0145 0.025727, + 0.0546159 -0.039240699 0.020099999, + 0.0532961 -0.0416114 0.022646001, + 0.056809202 -0.045015398 0.0095610004, + 0.0576833 -0.041331898 0.0080939904, + 0.0378174 -0.0739199 0.027109999, + 0.0424264 -0.072244003 0.020827999, + 0.0302257 -0.083990797 0.02146, + 0.0302257 -0.0831495 0.023445999, + 0.0328326 -0.081920497 0.021752, + 0.050219599 -0.0672599 0.006972, + 0.050219599 -0.066441797 0.0086869998, + 0.050219599 -0.067996003 0.0052270102, + 0.051830001 -0.064575799 0.005868, + 0.0424264 -0.068551801 0.025815999, + 0.040174201 -0.071276203 0.026575999, + 0.0378174 -0.072609797 0.028806999, + 0.0465803 -0.056950301 0.028666999, + 0.0465803 -0.0585206 0.027528999, + 0.044564299 -0.058162801 0.031351998, + 0.0465803 -0.055341799 0.029720001, + 0.048467699 -0.057204999 0.024741, + 0.048467699 -0.055689301 0.025874, + 0.048467699 -0.052551799 0.027891001, + 0.050219599 -0.049811698 0.025883, + 0.048467699 -0.054136101 0.026923999, + 0.048467699 -0.058677401 0.023530001, + 0.0424264 -0.062622197 0.031537998, + 0.044564299 -0.061363701 0.028983001, + 0.0424264 -0.0641976 0.030222001, + 0.040174201 -0.063816801 0.033962999, + 0.0424264 -0.0609948 0.032770999, + 0.044564299 -0.059785798 0.03021, + 0.040174201 -0.0654383 0.032637998, + 0.050219599 -0.064567402 0.012005, + 0.048467699 -0.069892302 0.0079190098, + 0.048467699 -0.069115996 0.0096890004, + 0.0465803 -0.062942803 0.023638999, + 0.0465803 -0.064300798 0.022195, + 0.048467699 -0.0601006 0.022242, + 0.050219599 -0.063515402 0.013595, + 0.048467699 -0.066291504 0.014789, + 0.0465803 -0.067958698 0.017481999, + -0.0053918599 -0.095338397 0.00340199, + -0.00267513 -0.095504299 0.0035659899, + -0.0081421202 -0.094700098 0.0076879999, + -0.0081421202 -0.095056199 0.00312199, + -0.0053918599 -0.095536999 -0.001196, + -0.00267513 -0.095705703 -0.001037, + -0.0053918599 -0.094976902 0.0079770098, + -0.0081421202 -0.093519002 0.016714999, + -0.0081421202 -0.093131199 0.018914999, + -0.0053918599 -0.093783803 0.01702, + -0.0053918599 -0.094455101 0.01252, + -0.0081421202 -0.094184101 0.012223, + -0.0109179 -0.093140103 0.016279001, + -0.0109179 -0.0927568 0.018475, + -5.286676e-012 -0.095192999 0.0082019996, + -0.00267513 -0.0951396 0.0081460001, + -6.420153e-012 -0.095558703 0.0036200001, + 0.00267513 -0.095140398 0.0081470003, + -0.00267513 -0.094614401 0.012695, + -6.1516148e-012 -0.0946666 0.012752, + 0.00267513 -0.094615102 0.012696, + -0.00267513 -0.093095899 0.021499, + -0.00267513 -0.093546398 0.019404, + -0.0053918599 -0.0929441 0.021317, + 0.00267513 -0.095743902 -0.00565401, + 0.0053918599 -0.095573097 -0.005808, + 0.00267513 -0.095616497 -0.010278, + 8.0153982e-012 -0.095673002 -0.01023, + -8.2480342e-012 -0.095799401 -0.0056039998, + 0.00267513 -0.0957065 -0.001036, + 0.0053918599 -0.095538601 -0.001196, + 0.0137106 -0.0926456 0.015712, + 0.0165099 -0.092027999 0.015002, + 0.0165099 -0.0916574 0.017178001, + -0.0109179 -0.080816701 0.042539001, + -0.0109179 -0.079185098 0.044261001, + -0.019305199 -0.083591603 0.03461, + -0.0165099 -0.082888499 0.037455998, + -0.019305199 -0.082277201 0.036502, + 0.0053918599 -0.094456702 0.012523, + 0.0137106 -0.091304198 0.022054, + 0.027557701 -0.085130699 0.022987001, + 0.0220857 -0.089162998 0.019406, + 0.0248404 -0.086938597 0.022327, + 0.0220857 -0.088563599 0.021473, + 0.019305199 -0.089996599 0.020437, + 0.0165099 -0.090709701 0.021319, + 0.0302257 -0.087793402 0.00283701, + 0.0328326 -0.086537398 -0.00082400499, + 0.0302257 -0.087963 0.00066299399, + 0.040174201 -0.079541601 0.010025, + 0.0378174 -0.081162401 0.012081, + 0.0378174 -0.083193302 -0.002078, + 0.035366699 -0.084986404 -0.0024409899, + 0.0378174 -0.083315402 -0.004183, + 0.035366699 -0.084671699 0.0018119999, + 0.035366699 -0.084847197 -0.00031100499, + 0.0328326 -0.0863823 0.00133, + 0.040174201 -0.080006301 0.0080819996, + 0.0424264 -0.078611597 0.0040210001, + 0.044564299 -0.076992303 -0.000100006, + 0.044564299 -0.076748602 0.001774, + 0.0378174 -0.082358196 0.0062219999, + 0.0378174 -0.0820475 0.0081670098, + 0.040174201 -0.080379903 0.0061550001, + 0.040174201 -0.080908902 0.0022189899, + 0.040174201 -0.0806695 0.0042319898, + 0.0378174 -0.082617797 0.004183, + 0.0378174 -0.083035499 2.0996091e-005, + 0.040174201 -0.0812876 -0.00189301, + 0.0424264 -0.079096802 0.000134995, + 0.0424264 -0.078878798 0.0021230001, + 0.027557701 -0.086561099 0.018932, + 0.0302257 -0.084734902 0.019455001, + 0.027557701 -0.0858946 0.020966001, + 0.0248404 -0.087622002 0.020277999, + 0.0248404 -0.088207297 0.018224001, + 0.027557701 -0.089260899 0.00201601, + 0.027557701 -0.089077897 0.0042090002, + 0.0248404 -0.089428499 0.012014, + 0.0248404 -0.090001501 0.007646, + 0.035366699 -0.084461398 0.0039240001, + 0.0328326 -0.086190499 0.0034739999, + 0.035366699 -0.084217504 0.0060229902, + 0.0165099 -0.093634203 -0.002998, + -0.061000001 0.0097000003 -0.170167, + -0.061000001 0.0057000001 -0.1825, + -0.061000001 0.0097000003 -0.1855, + -0.054305699 0.023512499 -0.1715, + -0.061000001 0.0097000003 -0.13950001, + -0.027557701 0.0507637 -0.162443, + -0.0248404 0.0523149 -0.164802, + -0.027557701 0.050994001 -0.164721, + -0.0328326 0.0473869 -0.15984499, + -0.035366699 0.045633301 -0.159666, + -0.0585596 0.0074999998 0.013068, + -0.0328326 0.047684401 -0.162191, + -0.0302257 0.048999 -0.16001, + -0.0302257 0.0492962 -0.162322, + -0.0479904 0.034012899 -0.19149999, + -0.048460599 -0.0145 0.035362002, + -0.048204001 -0.0145 0.035726, + -0.0465803 -0.016561201 0.037762001, + -0.0465803 -0.018581901 0.037597001, + -0.0532961 -0.046009898 0.020651, + -0.0532961 -0.044553 0.021384001, + -0.0546159 -0.044859398 0.017555, + -0.0532961 -0.047455098 0.01984, + -0.051830001 -0.047139499 0.023691, + -0.051830001 -0.048645899 0.022884, + -0.0599402 -0.0354807 -0.00767999, + -0.059999999 -0.032684099 -0.0091840103, + -0.0599402 -0.037213001 -0.0094349999, + -0.059999999 -0.034342501 -0.010742, + -0.059757002 -0.036627699 -0.0045939898, + -0.059757002 -0.038484201 -0.0063430001, + -0.0599402 -0.031881001 -0.0048019998, + -0.059999999 -0.030988401 -0.0078220097, + -0.059999999 -0.029300001 -0.0066479901, + -0.0599402 -0.033698998 -0.0061380002, + -0.059757002 -0.034721699 -0.0030690001, + -0.059757002 -0.032780599 -0.001759, + -0.0546159 -0.0215146 0.023901001, + -0.055787299 -0.0182117 0.021716001, + -0.0546159 -0.033590499 0.021539999, + -0.0532961 -0.037227001 0.023941999, + -0.0532961 -0.0342503 0.024512, + -0.055850901 -0.0094999997 0.021924, + -0.055776902 0.0074999998 0.021895001, + -0.056809202 -0.0154207 0.019295, + -0.057158101 -0.0094999997 0.018247001, + -0.056905501 0.0074999998 0.01902, + -0.056496199 -0.0145 0.020203, + -0.057419099 -0.0145 0.017408, + -0.055787299 -0.0163901 0.021994, + -0.055787299 -0.015436 0.022077, + -0.052922402 -0.0145 0.028271001, + -0.0532961 -0.018340399 0.027240001, + -0.0546159 -0.0182765 0.024497001, + -0.0532961 -0.021684799 0.026691001, + -0.0546159 -0.0164201 0.024754999, + -0.0532961 -0.0164496 0.027478, + -0.051830001 -0.034898099 0.027431, + -0.051830001 -0.021851899 0.02943, + -0.051830001 -0.0184031 0.029933, + -0.051830001 -0.036513101 0.027183, + -0.054245099 -0.0145 0.025641, + -0.0533006 -0.0094999997 0.027550999, + -0.0532961 -0.0154663 0.027550999, + -0.054979 -0.0094999997 0.024026999, + -0.054648198 0.0074999998 0.024769999, + -0.0546159 -0.0154512 0.024832999, + -0.055437401 -0.0145 0.022949999, + -0.0576833 -0.0163296 0.016404999, + -0.0576833 -0.0180807 0.016088, + -0.058412101 -0.016299101 0.013599, + -0.0576833 -0.0154053 0.016499, + -0.058412101 -0.0153899 0.013698, + -0.056809202 -0.016359899 0.019207001, + -0.056809202 -0.018146399 0.01891, + -0.059757002 -0.019162601 0.0043930099, + -0.0597937 0.0074999998 0.0038960001, + -0.0599402 -0.020127499 0.001158, + -0.0599402 -0.024214599 -0.00077799999, + -0.059999999 -0.0145 1.1758697e-012, + -0.051434901 0.0288851 -0.1715, + -0.049977001 0.031200999 -0.1715, + -0.050219599 0.030686799 -0.166151, + -0.051545098 0.02871 -0.1715, + -0.051438902 0.0288876 -0.19149999, + -0.0465803 0.0357766 -0.168934, + -0.048467699 0.033221699 -0.166255, + -0.048467699 0.033325501 -0.168883, + -0.046578299 0.035815801 -0.1715, + -0.0464839 0.035937399 -0.1715, + -0.047982302 0.034006599 -0.1715, + -0.048288502 0.033612002 -0.1715, + -0.044564299 0.038030699 -0.166453, + -0.0465803 0.035673201 -0.166356, + -0.044564299 0.038133699 -0.168982, + -0.044564299 0.037863702 -0.163914, + -0.0465803 0.035505801 -0.16376901, + -0.027557701 -0.089567803 -0.0046009999, + -0.0248404 -0.090808801 -0.0056659998, + -0.0302257 -0.0881771 -0.0037070001, + -0.0302257 -0.088084199 -0.001524, + -0.0302257 -0.087953001 0.00065400702, + -0.027557701 -0.089251697 0.0020079999, + -0.0248404 -0.089423403 0.012006, + -0.0302257 -0.088163503 -0.012479, + -0.0378174 -0.083435901 -0.0084149903, + -0.0302257 -0.088224903 -0.010283, + -0.027557701 -0.0895954 -0.006813, + -0.027557701 -0.089584 -0.0090279998, + -0.0599402 -0.0457495 -0.02974, + -0.058412101 -0.054848399 -0.024633, + -0.058412101 -0.054742601 -0.027868999, + -0.058412101 -0.054719601 -0.021449, + -0.058998398 -0.052474 -0.024297999, + -0.0576833 -0.057115801 -0.025141001, + -0.058998398 -0.052538101 -0.027419999, + -0.058998398 -0.052375 -0.030592, + -0.059445001 -0.050242499 -0.027129, + -0.044564299 -0.077628702 -0.010111, + -0.044564299 -0.077650703 -0.014159, + -0.0465803 -0.075541303 -0.012287, + -0.0465803 -0.075424403 -0.0083189998, + -0.044564299 -0.077468298 -0.0060809902, + -0.0424264 -0.079623498 -0.0080310097, + -0.0424264 -0.0796846 -0.01214, + -0.059757002 -0.047436301 -0.023933999, + -0.059757002 -0.0467727 -0.021005001, + -0.059445001 -0.049491201 -0.021017, + -0.059445001 -0.049992401 -0.024057999, + -0.059757002 -0.0478568 -0.026918, + -0.0599402 -0.045408599 -0.026812, + -0.0599402 -0.044833001 -0.023936, + -0.059757002 -0.041916002 -0.0105, + -0.059757002 -0.040259 -0.0083140004, + -0.059445001 -0.0434504 -0.0073849899, + -0.059445001 -0.045074601 -0.0097940098, + -0.059757002 -0.043423001 -0.012885, + -0.0599402 -0.040401898 -0.013574, + -0.0599402 -0.038864899 -0.011402, + -0.0165099 0.055549402 -0.167173, + -0.0165099 0.055385798 -0.16499101, + -0.0137106 0.054791398 -0.156321, + -0.0109179 0.056177199 -0.160742, + -0.0165099 0.055156201 -0.162802, + -0.0165099 0.054494999 -0.15841199, + -0.0165099 0.054859601 -0.16060799, + -0.019305199 0.0536195 -0.158305, + -0.051811699 0.0074999998 0.030258, + -0.0137106 0.055225201 -0.158501, + -0.0165099 0.0540612 -0.15621699, + -0.0501188 0.0074999998 0.032841999, + -0.0137106 0.055589799 -0.16068199, + -0.048425902 0.0074999998 0.035425, + -0.0248404 0.052579299 -0.16927999, + -0.0248338 0.052601099 -0.1715, + -0.0240207 0.052964401 -0.1715, + -0.0231252 0.0533645 -0.1715, + -0.0258127 0.052163702 -0.1715, + -0.0220857 0.0537512 -0.169304, + -0.0248404 0.052479301 -0.16704699, + -0.0081428103 0.057150599 -0.16509999, + -0.0109179 0.056473698 -0.16291, + -0.0137106 0.055886298 -0.162862, + -0.0053973799 0.057626501 -0.16725799, + 0.0109179 0.056872401 -0.167228, + 0.0109179 0.0567104 -0.16507301, + 0.0137106 0.056125 -0.16503701, + 0.0137106 0.056286901 -0.16720399, + 0.0109179 0.056968201 -0.16937099, + 0.0081428103 0.0573183 -0.167246, + 0.0137073 0.056397699 -0.1715, + 0.0137106 0.056382399 -0.169359, + 0.0116994 0.056848299 -0.1715, + 0.0145714 0.056203701 -0.1715, + 0.0122731 0.056731299 -0.19149999, + 0.0165099 -0.093637198 -0.0075539998, + 0.0109179 -0.094842099 -0.001855, + 0.0137106 -0.094127297 0.00219701, + 0.0081421202 -0.095252201 -0.001467, + 0.0053918599 -0.0953402 0.0034030001, + 0.0053918599 -0.094978698 0.0079779997, + 0.0081421202 -0.0941865 0.012227, + 0.019305199 -0.092820898 -0.008289, + 0.0220857 -0.091793798 -0.011402, + 0.0248404 -0.090691403 -0.012372, + 0.0328326 -0.086403303 -0.018184001, + 0.0328326 -0.086554199 -0.016009999, + 0.0302257 -0.087751001 -0.019069999, + 0.027557701 -0.088941902 -0.020114001, + 0.0302257 -0.0879298 -0.016874, + 0.0248404 -0.090772599 -0.010135, + 0.0220857 -0.091866598 -0.009149, + 0.0220857 -0.090167001 -0.027121, + 0.019305199 -0.090362102 -0.030851001, + 0.0220857 -0.089349598 -0.031564001, + 0.019305199 -0.0911709 -0.026378, + 0.0248404 -0.089016102 -0.027972, + 0.0220857 -0.090829797 -0.02265, + 0.0248404 -0.089690797 -0.023535, + -0.035366699 -0.084736198 -0.019608, + -0.0378174 -0.082946599 -0.021143001, + -0.035366699 -0.084898002 -0.017459, + -0.035366699 -0.084298901 -0.023902001, + -0.0328326 -0.086397402 -0.018184001, + -0.0328326 -0.0859823 -0.022527, + -0.0302257 -0.082196198 0.0254, + -0.0165099 -0.0842181 0.035556, + -0.0137106 -0.089102298 0.028314, + -0.0137106 -0.089936599 0.026239, + -0.0165099 -0.087608702 0.029601, + -0.0109179 -0.090401001 0.026843, + -0.019305199 -0.0878544 0.026643001, + -0.019305199 -0.086940698 0.02868, + -0.0165099 -0.088534802 0.027554, + -0.0165099 -0.089359403 0.025487, + -0.019305199 -0.088667199 0.024586, + -0.0220857 -0.087058999 0.025579, + -0.0328326 -0.0850522 0.011799, + -0.0302257 -0.086384602 0.013407, + -0.027557701 -0.087978698 0.012847, + -0.0248404 -0.087615497 0.020276999, + -0.027557701 -0.086553998 0.018931, + -0.0302257 -0.084725201 0.019452, + -0.0248404 -0.090566099 -0.014608, + -0.027557701 -0.089314602 -0.015682001, + -0.0248404 -0.090206698 -0.019078, + -0.0220857 -0.091677003 -0.013656, + -0.0220857 -0.091332398 -0.018159, + -0.0248404 -0.090766698 -0.010135, + -0.027557701 -0.089533404 -0.011246, + -0.0248404 -0.090693302 -0.001209, + -0.0248404 -0.090770699 -0.0034350001, + -0.027557701 -0.089501299 -0.0023930101, + -0.027557701 -0.089395903 -0.00018899499, + -0.0248404 -0.090576701 0.00101199, + -0.019305199 -0.092825502 -0.003759, + -0.019305199 -0.092674501 0.00075799599, + -0.0165099 -0.093629301 -0.00299899, + -0.019305199 -0.092816301 -0.008289, + -0.0220857 -0.091885902 -0.0046470002, + -0.0220857 -0.091751397 -0.00015899701, + -0.0165099 -0.093633197 -0.0075539998, + 0.0081421202 -0.046409901 0.059340999, + 0.0109179 -0.0441668 0.058896001, + 0.0137106 -0.044011202 0.058249999, + -0.0081421202 -0.041992899 0.059393, + -0.0109179 -0.0236551 0.058972999, + -0.0109179 -0.019083001 0.058986001, + -0.0088465102 -0.0145 0.059344001, + -0.0165099 -0.0235726 0.057622001, + -0.0165099 -0.0458984 0.057385001, + -0.0137106 -0.0461086 0.058194, + -0.0165099 -0.047998399 0.057232998, + -0.0137106 -0.050385401 0.057801001, + -0.0137106 -0.048224501 0.058047, + -0.0109179 -0.0484064 0.058701999, + -0.0109179 -0.061489299 0.055716, + -0.0081421202 -0.061688699 0.056226, + -0.0081421202 -0.063847899 0.055358998, + 6.2989636e-013 -0.050913099 0.059587002, + -0.00267513 -0.053100102 0.059183002, + 0.0137106 -0.0547322 0.057016999, + 0.0165099 -0.043817598 0.057447001, + 0.019305199 -0.045653999 0.056416001, + 0.019305199 -0.043585401 0.056483001, + 0.0165099 -0.050144501 0.056986999, + 0.0137106 -0.052557401 0.057461999, + 0.0165099 -0.052298799 0.056639999, + 0.019305199 -0.049854401 0.056005999, + 0.019305199 -0.047733501 0.056260001, + -0.0081428103 0.056624901 -0.160788, + -0.0109179 0.055812601 -0.158572, + -0.0109179 0.055378798 -0.156404, + -0.0053973799 0.056573398 -0.158665, + -0.00268824 0.056757402 -0.15868799, + -0.0053973799 0.056139499 -0.15651201, + -0.0081428103 0.056260299 -0.158627, + -0.0053973799 0.056938101 -0.16082001, + -0.0081428103 0.0558265 -0.156468, + 5.6390175e-012 0.0574794 -0.162992, + 0.00268824 0.0574205 -0.16298699, + 0.00268824 0.057123899 -0.16083799, + 2.8608749e-012 0.057182901 -0.160844, + -0.00268824 0.057122201 -0.16083799, + -0.058412101 -0.054191399 -0.034547001, + -0.058412101 -0.0545187 -0.031207999, + -0.0546159 -0.064170301 -0.020640999, + -0.0546159 -0.063900702 -0.011818, + -0.055787299 -0.0614543 -0.012906, + -0.0532961 -0.066481903 -0.014372, + -0.0546159 -0.064178199 -0.017021, + -0.0532961 -0.066303603 -0.010815, + -0.0546159 -0.064055704 -0.013527, + -0.050219599 -0.070783801 -0.024604, + -0.050219599 -0.070413999 -0.028467, + -0.051830001 -0.067439601 -0.034444001, + -0.050219599 -0.069911398 -0.032324001, + -0.050219599 -0.0692757 -0.036169, + -0.051830001 -0.066770799 -0.038215, + -0.0532961 -0.065935098 -0.02919, + -0.051830001 -0.068387501 -0.026869999, + -0.0532961 -0.066257901 -0.025472, + -0.051830001 -0.067978501 -0.030661, + -0.056809202 -0.056731001 -0.00596201, + -0.055787299 -0.0580112 -0.00137199, + -0.055787299 -0.058722001 -0.0029539899, + -0.056809202 -0.055338401 -0.0028820001, + -0.055787299 -0.059927799 -0.006203, + -0.056809202 -0.057846501 -0.0091570001, + -0.0576833 -0.054729499 -0.0089849997, + -0.0576833 -0.053436 -0.0059539899, + -0.044564299 -0.075499102 0.00743401, + -0.051830001 -0.065325603 0.004162, + -0.051830001 -0.064550899 0.0058510001, + -0.051830001 -0.066021197 0.00244501, + -0.0532961 -0.064598702 -0.00210201, + -0.0532961 -0.064023897 -0.00038999901, + -0.050219599 -0.069198698 0.001664, + -0.050219599 -0.069688402 -0.000134995, + -0.051830001 -0.067170702 -0.001052, + -0.051830001 -0.066636197 0.00070500199, + -0.0378174 -0.082352199 0.0062199999, + -0.0378174 -0.082041197 0.0081679998, + -0.040174201 -0.080373198 0.0061560101, + -0.040174201 -0.0806631 0.0042300001, + -0.0378174 -0.082609899 0.0041710101, + -0.035366699 -0.083933398 0.0080819996, + -0.035366699 -0.084210202 0.0060109999, + -0.0465803 -0.0741053 0.0031410099, + -0.0465803 -0.073633797 0.0050039999, + -0.044564299 -0.076000497 0.0055450001, + -0.0465803 -0.074491501 0.00127499, + -0.044564299 -0.076415002 0.0036530001, + -0.048467699 -0.072134398 0.00064100599, + -0.048467699 -0.071694098 0.00247701, + -0.0378174 -0.081643403 0.010117, + -0.035366699 -0.082670502 0.014005, + -0.035366699 -0.0831839 0.012021, + -0.040174201 -0.0795312 0.010023, + -0.0378174 -0.081152499 0.01208, + -0.0378174 -0.080569699 0.014039, + -0.035366699 -0.0820636 0.015985001, + -0.0165099 -0.0799454 0.041083001, + -0.019305199 -0.079366401 0.040114999, + -0.019305199 -0.077777401 0.041820999, + -0.0165099 -0.078339398 0.042794999, + -0.0165099 -0.0814633 0.039299998, + -0.0137106 -0.080428198 0.041889999, + -0.019305199 -0.074357897 0.045003999, + -0.0165099 -0.076650597 0.044433001, + -0.0137106 -0.077104598 0.045249999, + -0.0165099 -0.0651123 0.052372001, + -0.027557701 -0.0629531 0.047363002, + -0.027557701 -0.060961802 0.048335999, + -0.027557701 -0.075519599 0.037907001, + -0.0248404 -0.077913903 0.037686002, + -0.0248404 -0.079374097 0.035928, + -0.0328326 -0.0763807 0.031095, + -0.0424264 -0.071075402 0.022529, + -0.040174201 -0.072530702 0.024878999, + -0.0424264 -0.0722242 0.020812999, + -0.040174201 -0.075832799 0.019538, + -0.035366699 -0.079678498 0.021828, + -0.0378174 -0.079126596 0.017916, + -0.0378174 -0.078265302 0.019822, + -0.0378174 -0.079894498 0.015985999, + -0.035366699 -0.080568202 0.019902, + -0.035366699 -0.081363097 0.017952001, + -0.0378174 -0.022876499 0.046222001, + -0.0378174 -0.0187885 0.046443999, + -0.035366699 -0.041363999 0.047288999, + -0.0378174 -0.040862098 0.045209002, + -0.040174201 -0.0187409 0.044408999, + -0.040174201 -0.0166346 0.044523999, + -0.027557701 -0.0189473 0.053226002, + -0.0465803 -0.048661102 0.033047002, + -0.0465803 -0.050353602 0.032340001, + -0.0465803 -0.046960399 0.033668, + -0.048467699 -0.049316101 0.029548001, + -0.050219599 -0.048243199 0.026660999, + -0.051830001 -0.045621298 0.024417, + -0.048467699 -0.042732101 0.031908002, + -0.0465803 -0.043545902 0.034660999, + -0.0465803 -0.045254402 0.034205999, + -0.048467699 -0.044385199 0.031438999, + -0.048467699 -0.041084498 0.032299001, + -0.050219599 -0.041890599 0.029061001, + -0.050219599 -0.040299602 0.029468, + -0.0424264 -0.052305002 0.037590999, + -0.044564299 -0.049604699 0.035726, + -0.044564299 -0.051351398 0.035025001, + -0.0424264 -0.0540918 0.036804002, + -0.040174201 -0.053210098 0.040027, + -0.0424264 -0.048700199 0.038890999, + -0.0424264 -0.050506499 0.038286, + -0.044564299 -0.047850002 0.036339, + -0.044564299 -0.046090301 0.036866002, + -0.0424264 -0.0468891 0.039407998, + -0.040174201 -0.049507201 0.041313998, + -0.040174201 -0.0513625 0.040716, + -0.027557701 -0.048686098 0.052051999, + -0.0248404 -0.0512123 0.053169001, + -0.0248404 -0.049124401 0.053534999, + -0.019305199 -0.047727302 0.056256, + -0.027557701 -0.046638399 0.052331001, + -0.0302257 -0.0442123 0.050887, + -0.0137106 -0.0695723 0.050942998, + -0.0137106 -0.0715499 0.049660001, + -0.0165099 -0.069180697 0.050113, + -0.0165099 -0.067168199 0.051293999, + -0.0137106 -0.067543499 0.052124999, + -0.0109179 -0.0718778 0.050326001, + -0.0302257 -0.056286201 0.048305999, + -0.0302257 -0.058289301 0.047534, + -0.0328326 -0.055604398 0.046471, + -0.0328326 -0.053626802 0.047146, + -0.027557701 -0.0589437 0.049206998, + -0.027557701 -0.052802999 0.051210999, + -0.0302257 -0.054271501 0.048976999, + -0.0302257 -0.052249599 0.049548998, + -0.0248404 -0.057465699 0.051479999, + -0.0248404 -0.059532899 0.050712999, + -0.027557701 -0.056906901 0.049977001, + -0.027557701 -0.054858498 0.050643999, + -0.0248404 -0.0553868 0.052143998, + -0.0220857 -0.057961602 0.052816, + -0.0220857 -0.0600558 0.052049998, + -0.0137106 -0.063363001 0.054177999, + -0.0137106 -0.061227601 0.055046, + -0.0165099 -0.060902201 0.054214001, + -0.0165099 -0.0630209 0.053346001, + -0.0137106 -0.065471098 0.053204, + -0.0109179 -0.063638203 0.054848, + -0.0081421202 -0.072127797 0.050833002, + -0.0109179 -0.069887303 0.051610999, + -0.0053918599 -0.059642199 0.057342, + -0.0053918599 -0.061827999 0.056582998, + -0.0081421202 -0.059510101 0.056984998, + -0.00267513 -0.059719801 0.057551, + -0.00267513 -0.061909799 0.056791998, + 0.0248404 -0.063605599 0.048882, + 0.0220857 -0.066195503 0.049143001, + 0.019305199 -0.0605128 0.053226002, + 0.019305199 -0.062612198 0.052356999, + 0.019305199 -0.064684398 0.051383998, + 0.0220857 -0.068166301 0.047966, + 0.0302257 -0.0602763 0.046677001, + 0.0165099 -0.088541098 0.027557001, + 0.027557701 -0.084268399 0.024987999, + 0.0248404 -0.086156704 0.024362, + 0.0165099 -0.084225997 0.035560999, + 0.00267513 -0.061909899 0.056793999, + -7.0357331e-012 -0.0641087 0.055994, + -0.0109179 -0.077469803 0.045906998, + -0.0109179 -0.075676203 0.04747, + 0.0248404 -0.083212197 0.030324999, + 0.027557701 -0.081087597 0.030817, + 0.0378174 -0.068213098 0.033502001, + 0.035366699 -0.072430499 0.032543, + 0.0165099 -0.0587641 0.054985002, + 0.0165099 -0.056613602 0.055640999, + 0.0137106 -0.059072699 0.055814002, + 0.0165099 -0.060902901 0.054223001, + 0.019305199 -0.058394 0.053989999, + 0.019305199 -0.056263499 0.054648001, + 0.0576833 -0.055178501 -0.042203002, + 0.056809202 -0.057789698 -0.039850999, + 0.056809202 -0.0591649 -0.029364999, + 0.056809202 -0.059386998 -0.025869001, + 0.048467699 -0.072322801 -0.030263999, + 0.0465803 -0.074071102 -0.032258999, + 0.0546159 -0.063822299 -0.027902, + 0.048467699 -0.071716599 -0.034182001, + 0.050219599 -0.069920398 -0.032325, + 0.048467699 -0.072772101 -0.003024, + 0.050219599 -0.070433602 -0.003755, + 0.050219599 -0.070675798 -0.0055529899, + 0.048467699 -0.072501399 -0.001198, + 0.048467699 -0.072965503 -0.0048439899, + 0.0465803 -0.074799202 -0.000578003, + 0.0465803 -0.075018302 -0.0024250001, + 0.0465803 -0.074501097 0.00127499, + 0.0465803 -0.073094398 0.0068640001, + 0.048467699 -0.070583001 0.0061249998, + 0.0465803 -0.072453797 0.0087029999, + 0.0546159 -0.064066298 -0.024254, + 0.0378174 -0.082953297 -0.021144001, + 0.035366699 -0.084541798 -0.021756999, + 0.035366699 -0.0843032 -0.023902001, + 0.0424264 -0.078499101 -0.028643001, + 0.0378174 -0.082740299 -0.023265, + 0.0424264 -0.079015501 -0.024522001, + 0.0378174 -0.081877902 -0.029608, + 0.040174201 -0.079917699 -0.031130999, + 0.0378174 -0.081121199 -0.033808999, + 0.040174201 -0.0805531 -0.026965, + 0.0378174 -0.082489997 -0.025382999, + 0.035366699 -0.082975604 -0.032437999, + 0.035366699 -0.083713099 -0.028181, + 0.035366699 -0.084027 -0.026044, + 0.0465803 -0.072511598 -0.040174998, + 0.041876599 -0.044969101 -0.19149999, + 0.0465803 -0.073357597 -0.036228999, + 0.035366699 -0.085117497 -0.013159, + 0.040174201 -0.0815304 -0.0060440102, + 0.0378174 -0.083400503 -0.0062940102, + 0.040174201 -0.081384398 -0.018594, + 0.0378174 -0.083129101 -0.019021001, + 0.0378174 -0.083267502 -0.016897, + 0.040174201 -0.0810422 -0.022784, + 0.0424264 -0.079387501 -0.020393001, + 0.050219599 -0.0709645 -0.0092139998, + 0.048467699 -0.073313303 -0.010623, + 0.051830001 -0.068754598 -0.011755, + 0.0465803 -0.075537801 -0.016267, + 0.0424264 -0.079686098 -0.010074, + 0.044564299 -0.077643499 -0.010097, + 0.0424264 -0.079637602 -0.0080180103, + 0.040174201 -0.081597798 -0.0081289997, + 0.0353618 0.046460599 -0.1715, + 0.034755301 0.046887498 -0.1715, + 0.0328326 0.048193101 -0.169191, + 0.033319298 0.047898199 -0.1715, + 0.035726301 0.046204001 -0.1715, + 0.0378174 0.0444609 -0.166719, + 0.0378174 0.044298898 -0.16430999, + 0.040174201 0.0422832 -0.164186, + 0.040174201 0.042445298 -0.16663601, + 0.0378174 0.044554599 -0.169117, + 0.035366699 0.0463477 -0.166796, + 0.035366699 0.0464416 -0.169155, + 0.040172402 0.042562202 -0.1715, + 0.040174201 0.0425389 -0.169075, + 0.0402769 0.042472102 -0.1715, + 0.039599199 0.043056302 -0.1715, + 0.039609101 0.043067899 -0.19149999, + 0.059999999 -0.0238101 -0.0036299999, + 0.059999999 -0.0199643 -0.00159801, + 0.0599402 -0.030096499 -0.0036589999, + 0.059999999 -0.0275592 -0.0056340001, + 0.0599402 -0.024218099 -0.00077900698, + 0.0599402 -0.028211899 -0.00269299, + 0.0599402 -0.020132599 0.001162, + 0.059757002 -0.030875601 -0.00065199297, + 0.059999999 -0.0177077 -0.00053799403, + 0.0599402 -0.017770801 0.002175, + 0.0599402 -0.019071801 0.001638, + 0.059999999 -0.018961599 -0.001099, + 0.059999999 -0.0169558 -0.000294998, + 0.048467699 -0.071709603 0.00248199, + 0.050219599 -0.069704399 -0.00013099698, + 0.048467699 -0.072146997 0.00064300501, + 0.048467699 -0.071188502 0.004311, + 0.050219599 -0.069217697 0.00167101, + 0.0532961 -0.059004299 0.0092580002, + 0.0546159 -0.0562278 0.0076600001, + 0.0546159 -0.057259299 0.0062319902, + 0.0532961 -0.060025599 0.0077579999, + 0.051830001 -0.060717501 0.012229, + 0.051830001 -0.061790802 0.01071, + 0.051830001 -0.066045202 0.0024579901, + 0.051830001 -0.065350503 0.0041769999, + 0.0546159 -0.0639119 -0.011819, + 0.0532961 -0.066129297 -0.0090770004, + 0.0532961 -0.066312499 -0.010817, + 0.0546159 -0.064064801 -0.013528, + 0.055787299 -0.061664101 -0.014598, + 0.055787299 -0.061468799 -0.012904, + 0.055787299 -0.048855498 0.010738, + 0.0546159 -0.043460999 0.018322, + 0.0546159 -0.0420557 0.018987, + 0.051830001 -0.045617498 0.024442, + 0.051830001 -0.0471389 0.023716001, + 0.0532961 -0.0445491 0.02141, + 0.0532961 -0.0430816 0.022066001, + 0.051830001 -0.044089001 0.025088999, + 0.050219599 -0.0466615 0.027403999, + 0.050219599 -0.048242599 0.026684999, + 0.059757002 -0.041929498 -0.010469, + 0.0599402 -0.041811399 -0.015906001, + 0.059757002 -0.043441199 -0.012856, + 0.059757002 -0.044772901 -0.015422, + 0.0599402 -0.040415499 -0.013543, + 0.059999999 -0.040194198 -0.018932, + 0.059999999 -0.038913101 -0.016593, + 0.059757002 -0.047879402 -0.026908999, + 0.0599402 -0.045772199 -0.029731, + 0.059999999 -0.043424301 -0.029654, + 0.059757002 -0.045899998 -0.018142, + 0.0599402 -0.043032899 -0.018440001, + 0.059999999 -0.041306399 -0.021434, + 0.059445001 -0.049280401 -0.039671, + 0.059445001 -0.048746899 -0.042872999, + 0.058998398 -0.050657701 -0.043653, + 0.059445001 -0.050034799 -0.033278, + 0.059445001 -0.049708001 -0.036465999, + 0.058998398 -0.045014702 -0.0042059901, + 0.058412101 -0.046575401 -0.00103799, + 0.058412101 -0.048442099 -0.0034969901, + 0.058998398 -0.046762101 -0.0066410098, + 0.058998398 -0.043108899 -0.001991, + 0.059445001 -0.0434638 -0.0073549999, + 0.059445001 -0.041680899 -0.0051540099, + 0.058412101 -0.0547348 -0.021446999, + 0.0576833 -0.056985699 -0.018591, + 0.0576833 -0.0571738 -0.021841999, + 0.058998398 -0.052489299 -0.024296001, + 0.058998398 -0.052173302 -0.021158, + 0.058412101 -0.053685799 -0.015088, + 0.0576833 -0.056522701 -0.015333, + 0.0576833 -0.055780798 -0.012114, + 0.058412101 -0.054345399 -0.018248999, + 0.058412101 -0.052753098 -0.011994, + 0.058998398 -0.051595699 -0.018053999, + 0.058998398 -0.050753701 -0.015015, + 0.058998398 -0.0254669 0.007948, + 0.059445001 -0.017898601 0.00767999, + 0.058998398 -0.030210201 0.0063090101, + 0.058998398 -0.0206478 0.0096119996, + 0.058412101 -0.033266298 0.0085760001, + 0.059445001 -0.025045799 0.0050059999, + 0.058998398 -0.0324632 0.0054759998, + 0.059445001 -0.0295364 0.003274, + 0.059445001 -0.0204741 0.006763, + 0.059757002 -0.019183001 0.0043970002, + 0.0599402 -0.035480101 -0.0076499898, + 0.059999999 -0.032677501 -0.0091570001, + 0.0465803 -0.036741599 0.035735, + 0.0424264 -0.043284498 0.040194999, + 0.0424264 -0.0450796 0.039852999, + 0.040174201 -0.043946002 0.042583, + 0.0424264 -0.041521899 0.040451001, + 0.044564299 -0.0408746 0.037951, + 0.040174201 -0.045789301 0.042254001, + 0.051058501 0.0074999998 0.031512, + 0.051817998 -0.0145 0.030219, + 0.0528774 -0.0145 0.028354, + 0.0532961 -0.016452 0.027492, + 0.0378174 -0.054063201 0.042342, + 0.040174201 -0.0532097 0.040047001, + 0.040174201 -0.051359501 0.040736001, + 0.0378174 -0.052166902 0.043026999, + 0.035366699 -0.054862302 0.044491999, + 0.035366699 -0.056790002 0.043715, + 0.0328326 -0.059520699 0.044838998, + 0.0424264 -0.052304499 0.037611999, + 0.044564299 -0.051351 0.035046998, + 0.048467699 -0.0361466 0.033054002, + 0.051830001 -0.039508902 0.026566001, + 0.0465803 -0.041858301 0.035046998, + 0.0465803 -0.040197201 0.035335001, + 0.044564299 -0.042587601 0.037679002, + 0.044564299 -0.0443318 0.037323002, + 0.048467699 -0.04603 0.030913001, + 0.0465803 -0.0486577 0.033069, + 0.048467699 -0.047676299 0.030284001, + 0.050219599 -0.0450732 0.028042, + 0.050219599 -0.043482602 0.028599, + 0.0465803 -0.046955299 0.033689, + 0.044564299 -0.046087001 0.036883999, + 0.044564299 -0.0478452 0.036359001, + 0.048467699 -0.0427357 0.031923998, + 0.048467699 -0.0443816 0.031459, + 0.050219599 -0.041894302 0.029077001, + 0.0465803 -0.0435494 0.034676, + 0.0465803 -0.0452509 0.034224, + 0.027557701 0.0507828 -0.162443, + 0.0248404 0.0521021 -0.162551, + 0.0220857 0.053502399 -0.164876, + 0.027557701 0.051268701 -0.169254, + 0.0256411 0.052245099 -0.1715, + 0.0282706 0.050922401 -0.1715, + 0.0302257 0.049803101 -0.16922399, + 0.0302257 0.049708899 -0.166934, + 0.056809202 -0.037402902 0.013883, + 0.0576833 -0.038910601 0.0095490003, + 0.0576833 -0.036474802 0.010743, + 0.0220857 -0.090069599 0.015307, + 0.0220857 -0.0896625 0.017355001, + 0.0220857 -0.090421297 0.013155, + 0.019305199 -0.090925403 0.016315, + 0.019305199 -0.0912873 0.01415, + 0.035366699 -0.073858202 0.030895, + 0.048467699 -0.061468702 0.020880001, + 0.048467699 -0.064018801 0.017953999, + 0.048467699 -0.065191902 0.016399, + 0.050219599 -0.062391501 0.015132, + 0.050219599 -0.061199799 0.016612001, + 0.048467699 -0.062776297 0.01945, + 0.0465803 -0.065592401 0.020683, + 0.0465803 -0.066813201 0.019111, + 5.7836192e-012 -0.093990304 0.017256999, + 0.00267513 -0.0939399 0.017200001, + -0.0137106 -0.084740601 0.036343999, + 0.0109179 -0.093142301 0.016283, + 0.0137106 -0.0922677 0.017897001, + 0.0137106 -0.091833197 0.019974001, + 0.0137106 -0.090673096 0.024150001, + 0.0109179 -0.091782302 0.022646001, + 0.0081421202 -0.092146397 0.023096001, + 0.044564299 -0.076012097 0.0055470001, + 0.044564299 -0.075513303 0.0074379998, + 0.0424264 -0.077822901 0.0078439899, + 0.0424264 -0.078261897 0.0059250002, + 0.044564299 -0.0764241 0.0036519901, + 0.0465803 -0.0741174 0.00314301, + 0.0465803 -0.073648602 0.0050090002, + 0.0424264 -0.076678596 0.011665, + 0.044564299 -0.074927203 0.0093189999, + 0.0424264 -0.077295303 0.0097599896, + 0.040174201 -0.078986697 0.011964, + 0.0328326 -0.0854064 0.0098130004, + 0.0302257 -0.086755201 0.011402, + 0.035366699 -0.083939001 0.0080840001, + 0.035366699 -0.083608598 0.01005, + 0.0328326 -0.085057601 0.011799, + 0.035366699 -0.083191201 0.01202, + 0.0220857 -0.091466099 0.00431599, + 0.0248404 -0.090429097 0.0032339899, + 0.019305199 -0.092370503 0.0052590002, + 0.0220857 -0.0912605 0.0065410002, + 0.0248404 -0.090234198 0.00544501, + 0.027557701 -0.087602101 0.014869, + 0.0248404 -0.0890885 0.014151, + 0.0248404 -0.088693701 0.016186001, + 0.027557701 -0.087983102 0.012849, + 0.027557701 -0.087130599 0.016891999, + 0.0302257 -0.086389601 0.013406, + 0.0302257 -0.087344103 0.007158, + 0.0328326 -0.085963398 0.0056089899, + 0.0328326 -0.085702501 0.0077300002, + 0.0302257 -0.087067403 0.0092989998, + 0.0302257 -0.087586597 0.0050030099, + 0.027557701 -0.088857502 0.0063939998, + 0.027557701 -0.088310003 0.010728, + 0.019305199 -0.092545703 0.0030129999, + 0.0165099 -0.093469597 0.00154401, + 0.0220857 -0.091758698 -0.00015600602, + 0.0248404 -0.090585001 0.0010169999, + 0.0220857 -0.091632202 0.00208299, + 0.019305199 -0.092680901 0.00075999502, + 0.019305199 -0.092776097 -0.00149699, + 0.0220857 -0.091892399 -0.004646, + 0.0220857 -0.091845401 -0.0023990001, + 0.0220857 -0.091899499 -0.0068970001, + 0.019305199 -0.092831202 -0.003758, + -0.0302257 0.049691699 -0.166932, + -0.0328326 0.047915101 -0.16453201, + -0.0302257 0.049526699 -0.16463099, + -0.027557701 0.0511587 -0.16699199, + -0.027557701 0.051259 -0.16925301, + -0.059592899 0.0074999998 0.006978, + -0.035366699 0.045931 -0.162047, + -0.0302184 0.049817201 -0.1715, + -0.028437899 0.050832599 -0.1715, + -0.029552899 0.050217099 -0.19149999, + -0.0302257 0.049792401 -0.169223, + -0.0328326 0.0480804 -0.166866, + -0.0328326 0.0481815 -0.16918901, + -0.030994801 0.049374301 -0.1715, + -0.050219599 -0.016507 0.032765001, + -0.048467699 -0.0165345 0.035305001, + -0.0498982 -0.0145 0.033319, + -0.050219599 -0.0184645 0.032565001, + -0.048467699 -0.018524099 0.035123002, + -0.051830001 -0.0164786 0.030152, + -0.051830001 -0.0154811 0.030221, + -0.051472198 -0.0145 0.030832, + -0.059999999 -0.0199592 -0.00160201, + -0.059999999 -0.0238067 -0.0036289999, + -0.0599402 -0.0282117 -0.00269299, + -0.0599402 -0.030073199 -0.003664, + -0.059999999 -0.018941101 -0.001103, + -0.0599402 -0.019051399 0.001634, + -0.027557701 -0.089069098 0.0041979998, + -0.0248404 -0.0899942 0.0076339999, + -0.0248404 -0.0902263 0.0054350002, + -0.035366699 -0.085107997 -0.013159, + -0.0328326 -0.086732 -0.01166, + -0.035366699 -0.085156403 -0.011011, + -0.0378174 -0.083421297 -0.012652, + -0.035366699 -0.085021898 -0.015309, + -0.0328326 -0.086658798 -0.013835, + -0.0378174 -0.083258398 -0.016897, + -0.0328326 -0.086763903 -0.0073179901, + -0.035366699 -0.085167199 -0.00886501, + -0.0328326 -0.086767003 -0.0094880098, + -0.0328326 -0.086722702 -0.0051519899, + -0.0302257 -0.088231601 -0.0058960002, + -0.035366699 -0.085140496 -0.00672301, + -0.0302257 -0.0882475 -0.0080880001, + -0.059757002 -0.047971301 -0.032929, + -0.059445001 -0.050242402 -0.03019, + -0.059757002 -0.048034899 -0.029929001, + -0.0599402 -0.0457302 -0.035633001, + -0.059757002 -0.047695 -0.035971999, + -0.059445001 -0.050022401 -0.033296, + -0.0599402 -0.045856498 -0.032692999, + -0.0137106 0.056115702 -0.16503599, + -0.0109179 0.056703001 -0.16507199, + -0.0081428103 0.057313599 -0.167245, + -0.0122731 0.056731299 -0.19149999, + -0.0053963801 0.057744101 -0.1715, + -0.0031320599 0.057918198 -0.1715, + -0.0053973799 0.057723999 -0.169386, + 8.1663114e-012 0.057870999 -0.16726799, + 4.763761e-012 0.057967901 -0.16939101, + -0.00268824 0.0579076 -0.16938999, + 0.00268824 0.057812002 -0.167266, + 0.00268824 0.057649601 -0.165131, + 0.0109179 -0.094307803 0.00727901, + 0.0109179 -0.094656102 0.00272301, + 0.0081421202 -0.095058903 0.003123, + 0.0081421202 -0.094702803 0.0076909899, + 0.0137106 -0.093789101 0.0067380099, + 0.0109179 -0.093799703 0.011804, + 0.0137106 -0.0932917 0.011248, + 0.0248404 -0.090410002 -0.016844001, + 0.027557701 -0.089150399 -0.017898999, + 0.0248404 -0.090209797 -0.019078, + 0.0220857 -0.091335103 -0.018159, + 0.027557701 -0.089319602 -0.015682001, + 0.0248404 -0.090570599 -0.014609, + 0.0220857 -0.091681004 -0.013656, + 0.027557701 -0.089405097 -0.000184006, + 0.0248404 -0.090701498 -0.00120599, + 0.0248404 -0.0907785 -0.0034330001, + 0.0328326 -0.0867742 -0.0073150001, + 0.0302257 -0.088187002 -0.003703, + 0.0328326 -0.086733498 -0.0051469998, + 0.0328326 -0.086654499 -0.0029829999, + 0.0302257 -0.088094302 -0.00151801, + 0.027557701 -0.089510299 -0.00238901, + 0.019305199 -0.091823302 -0.021878, + 0.0165099 -0.092029698 -0.025743, + 0.0137106 -0.092745699 -0.025214, + -0.0248404 -0.084282599 0.028361, + -0.027557701 -0.083294101 0.026958, + -0.0248404 -0.085264802 0.026372001, + -0.0248404 -0.083200298 0.030317999, + -0.0220857 -0.085160002 0.029606, + -0.0220857 -0.0861599 0.027605001, + -0.0109179 -0.089558803 0.028925, + -0.0165099 -0.085449502 0.033608001, + -0.0165099 -0.086580299 0.031621002, + -0.0137106 -0.088165902 0.030368, + -0.0302257 -0.0870611 0.0092890002, + -0.0328326 -0.085695602 0.0077189901, + -0.0328326 -0.0854012 0.009811, + -0.0302257 -0.086750403 0.0114, + -0.0302257 -0.087577701 0.00498801, + -0.027557701 -0.088304304 0.010719, + -0.027557701 -0.088849299 0.0063809999, + -0.027557701 -0.085120298 0.022983, + -0.0248404 -0.0869307 0.022324, + -0.0248404 -0.086147301 0.024358001, + -0.027557701 -0.0858858 0.020964, + -0.027557701 -0.084256597 0.024983, + -0.0302257 -0.083979398 0.021455999, + -0.0302257 -0.083136603 0.02344, + 0.0109179 -0.046282001 0.058846001, + 0.0081421202 -0.0485477 0.059202999, + -0.0053918599 -0.0530352 0.058975998, + -0.0081421202 -0.0507285 0.058961999, + -0.0109179 -0.050580099 0.058460001, + -0.0081421202 -0.0485451 0.059202, + -0.0053918599 -0.050832301 0.059312999, + -0.00267513 -0.050893199 0.059519, + -0.0109179 -0.044165298 0.058896001, + -0.0109179 -0.046277702 0.058844998, + -0.0109179 -0.041884501 0.058905002, + -0.0137106 -0.044009302 0.058249999, + -0.0137106 -0.041742101 0.058263998, + -0.0137106 -0.0236183 0.058371, + -0.0137106 -0.0190689 0.058394, + -0.0117463 -0.0145 0.058839001, + -0.017454101 -0.0145 0.057404999, + -0.0197125 -0.0094999997 0.056669001, + -0.018942401 0.0074999998 0.056931, + -0.0165099 -0.058764301 0.054977, + -0.00267513 -0.057518002 0.058201, + -0.00267513 -0.055309899 0.058743998, + -5.3658761e-012 -0.059745099 0.05762, + -4.0563646e-012 -0.053121202 0.059250999, + 0.00267513 -0.0508934 0.059519999, + 0.0053918599 -0.0508327 0.059315, + -0.00268824 0.057647798 -0.16513, + -0.00268824 0.0578105 -0.167266, + -6.613887e-012 0.057708502 -0.165134, + -0.00268824 0.0574187 -0.16298699, + -0.0053973799 0.057463702 -0.16511901, + -0.0053973799 0.0572345 -0.162972, + 0.0061684698 0.0576756 -0.1715, + 0.0087992204 0.057351299 -0.1715, + 0.0081428103 0.057414301 -0.16937999, + 0.0053966301 0.057746898 -0.1715, + 0.00294237 0.057927798 -0.1715, + 0.00616926 0.057682 -0.19149999, + 0.0058778701 0.0577114 -0.1715, + 0.0053973799 0.057725899 -0.169387, + -0.056809202 -0.059476599 -0.01905, + -0.055787299 -0.061842799 -0.019706, + -0.056809202 -0.059485599 -0.022415999, + -0.055787299 -0.061776798 -0.016276, + -0.056809202 -0.059218399 -0.015743, + -0.0576833 -0.0571642 -0.021840001, + -0.0576833 -0.056970701 -0.018594, + -0.048467699 -0.073309503 -0.01847, + -0.051830001 -0.068817496 -0.019297, + -0.0532961 -0.066454597 -0.021761, + -0.0532961 -0.0665268 -0.018061001, + -0.051830001 -0.068667099 -0.023080001, + -0.050219599 -0.071021102 -0.020742999, + -0.0532961 -0.065485902 -0.032906, + -0.055787299 -0.061781399 -0.023257, + -0.0546159 -0.064048097 -0.02427, + -0.0576833 -0.056282301 -0.035379, + -0.0576833 -0.055164699 -0.042203002, + -0.0576833 -0.055780299 -0.038794, + -0.0465803 -0.069003403 0.015786, + -0.048467699 -0.066270001 0.01477, + -0.0465803 -0.067938097 0.017464001, + -0.044564299 -0.070650302 0.018355999, + -0.044564299 -0.071675397 0.016612999, + -0.0424264 -0.074266098 0.017246, + -0.040174201 -0.076755799 0.017680001, + -0.044564299 -0.074910298 0.0093120001, + -0.0424264 -0.077281699 0.0097559998, + -0.040174201 -0.078973897 0.01196, + -0.050219599 -0.067235798 0.0069579901, + -0.0465803 -0.071704596 0.010511, + -0.044564299 -0.072615601 0.01483, + -0.048467699 -0.068232499 0.011412, + -0.0465803 -0.069987603 0.014063, + -0.048467699 -0.067290999 0.013113, + -0.048467699 -0.069092803 0.0096749999, + -0.050219599 -0.066417702 0.0086710099, + -0.0465803 -0.070888601 0.012303, + -0.050219599 -0.065520197 0.010349, + -0.0165099 -0.073045798 0.047456, + -0.0165099 -0.074884199 0.045988001, + -0.019305199 -0.0725381 0.046466999, + -0.0165099 -0.071142197 0.048833001, + -0.0137106 -0.073469304 0.048280999, + -0.0137106 -0.075323097 0.046810001, + -0.0220857 -0.068162203 0.047954999, + -0.019305199 -0.068711102 0.049118001, + -0.019305199 -0.070653401 0.047839999, + -0.0220857 -0.070082001 0.04668, + -0.0248404 -0.067533001 0.046620999, + -0.0248404 -0.0655891 0.047795001, + -0.0220857 -0.0641791 0.050207, + -0.0248404 -0.063602597 0.048870001, + -0.0220857 -0.066192098 0.049130999, + -0.0220857 -0.062130999 0.051180001, + -0.019305199 -0.064682104 0.051374, + -0.0248404 -0.061581202 0.049842998, + -0.019305199 -0.066718198 0.050297, + -0.027557701 -0.079821102 0.032669, + -0.0248404 -0.0807437 0.034109, + -0.0248404 -0.082019903 0.032237001, + -0.0302257 -0.080023997 0.029222, + -0.0302257 -0.078796297 0.03107, + -0.027557701 -0.081074297 0.030809, + -0.027557701 -0.082232803 0.028902, + -0.0302257 -0.081158102 0.02733, + -0.0328326 -0.078870401 0.027480001, + -0.0328326 -0.077670701 0.029313, + -0.0302257 -0.0760694 0.034602001, + -0.027557701 -0.077040099 0.036224999, + -0.027557701 -0.078475401 0.034476999, + -0.0302257 -0.077477202 0.032866001, + -0.0302257 -0.074577503 0.036272999, + -0.0328326 -0.075003304 0.032818999, + -0.0328326 -0.073542699 0.034479, + -0.0378174 -0.076263599 0.023543, + -0.0378174 -0.077310398 0.0217, + -0.040174201 -0.074819602 0.021361999, + -0.040174201 -0.073718198 0.023145, + -0.0378174 -0.075127102 0.025343999, + -0.035366699 -0.077615499 0.025584999, + -0.035366699 -0.078693703 0.023724001, + -0.040174201 -0.0550461 0.039243001, + -0.0378174 -0.063217498 0.037475999, + -0.040174201 -0.060415499 0.036334001, + -0.0302257 -0.0622316 0.04569, + -0.0302257 -0.064155102 0.044619001, + -0.0328326 -0.061439101 0.043850999, + -0.050219599 -0.045078699 0.028019, + -0.050219599 -0.046665099 0.027380001, + -0.051830001 -0.0440946 0.025064999, + -0.051830001 -0.042561699 0.025636001, + -0.050219599 -0.043486301 0.028579, + -0.048467699 -0.046035301 0.030890999, + -0.048467699 -0.047679801 0.030261001, + -0.0220857 -0.0495135 0.054850999, + -0.0220857 -0.043310899 0.055357002, + -0.0248404 -0.023380101 0.054473002, + -0.0248404 -0.018978501 0.054559, + -0.0248404 -0.0167441 0.054600999, + -0.0220857 -0.023453601 0.055675, + -0.019305199 -0.0456465 0.056414001, + -0.0248404 -0.047047399 0.053805001, + -0.0220857 -0.045352001 0.05528, + -0.0220857 -0.047410499 0.055114001, + -0.027557701 -0.0426482 0.052611001, + -0.027557701 -0.023297399 0.053117, + -0.0248404 -0.042999301 0.054065999, + -0.0248404 -0.045014601 0.053978998, + -0.027557701 -0.044634499 0.052514002, + -0.0302257 -0.016713699 0.051808, + -0.0302257 -0.0189125 0.051745001, + -0.0302257 -0.0232055 0.051612001, + -0.0302257 -0.0401439 0.051064, + -0.0302257 -0.0422583 0.050995, + -0.0109179 -0.067845397 0.052793998, + -0.0109179 -0.065759704 0.053874001, + 0.0109179 -0.063639201 0.054854002, + 0.0109179 -0.061489701 0.055721, + 0.0137106 -0.0612281 0.055052999, + 0.0137106 -0.0633642 0.054184999, + 0.0165099 -0.063022301 0.053353999, + 0.0165099 -0.065114297 0.052379999, + 0.019305199 -0.066721201 0.050306998, + 0.0378174 -0.066608198 0.034917001, + 0.0328326 -0.070401698 0.037597999, + 0.035366699 -0.070925497 0.034122001, + 0.035366699 -0.069348097 0.035626002, + 0.0220857 -0.070087001 0.046691, + 0.0220857 -0.071950398 0.045322001, + 0.019305199 -0.080876499 0.038346998, + 0.0165099 -0.082896203 0.037462, + 0.0137106 -0.083404802 0.038256001, + 0.0109179 -0.0838136 0.038895, + 0.019305199 -0.088673398 0.024588, + 0.0165099 -0.0893647 0.025489001, + 0.0165099 -0.090087399 0.023406999, + 0.019305199 -0.089384899 0.022515001, + 0.0220857 -0.087865204 0.023534, + 0.0165099 -0.087615803 0.029603999, + 0.019305199 -0.085934401 0.030696001, + 0.0165099 -0.085457399 0.033613, + 0.0165099 -0.086588003 0.031624001, + 0.0248404 -0.082031801 0.032244999, + 0.0220857 -0.084069803 0.031580999, + 0.019305199 -0.0848177 0.032676, + 0.0220857 -0.086169302 0.027609, + 0.0220857 -0.085170202 0.029611001, + 0.019305199 -0.086948998 0.028684, + 0.019305199 -0.087861702 0.026645999, + 0.0220857 -0.087067403 0.025582001, + 0.0248404 -0.085275501 0.026377, + 0.0248404 -0.084294103 0.028367, + 0.0053918599 -0.063994899 0.055718001, + 0.0081421202 -0.0638486 0.055362999, + 0.0081421202 -0.061689001 0.056230001, + 0.0053918599 -0.0618283 0.056584999, + 0.00267513 -0.0640807 0.055927001, + -0.0081421202 -0.070127301 0.052119002, + -0.0081421202 -0.082663998 0.041237999, + 0.0328326 -0.073555201 0.034494001, + 0.0328326 -0.072015204 0.036084, + 0.0302257 -0.074588999 0.036286999, + 0.0302257 -0.073016703 0.037887, + 0.0302257 -0.0811726 0.027339, + 0.0302257 -0.082210198 0.025408, + 0.027557701 -0.082245998 0.02891, + 0.027557701 -0.083306901 0.026965, + 0.040174201 -0.068497598 0.029751001, + 0.040174201 -0.069924399 0.028196, + 0.0378174 -0.071218804 0.030440999, + 0.0378174 -0.069751598 0.032008, + 0.040174201 -0.067000598 0.031233, + 0.0424264 -0.067167804 0.027356001, + 0.0424264 -0.065714799 0.028827, + 0.058412101 -0.0532245 -0.041226, + 0.058998398 -0.0517378 -0.037108999, + 0.058998398 -0.051252399 -0.040385, + 0.0576833 -0.056301199 -0.035371002, + 0.058412101 -0.053773802 -0.037881002, + 0.0576833 -0.055797301 -0.038791999, + 0.056809202 -0.058825001 -0.032864999, + 0.056809202 -0.058366299 -0.036362, + 0.0576833 -0.056689698 -0.031945001, + 0.058412101 -0.054210801 -0.034529999, + 0.058998398 -0.0521143 -0.033831999, + 0.0465803 -0.075379699 -0.020268001, + 0.0465803 -0.075082399 -0.024272, + 0.048467699 -0.073127501 -0.022399001, + 0.048467699 -0.072793201 -0.026334001, + 0.051830001 -0.0684027 -0.026868001, + 0.0532961 -0.0662755 -0.025465, + 0.050219599 -0.070798501 -0.024602, + 0.050219599 -0.070426002 -0.028467, + 0.0532961 -0.065950803 -0.029188, + 0.051830001 -0.067990899 -0.030661, + 0.0546159 -0.063453503 -0.031550001, + 0.050219599 -0.069281802 -0.036169998, + 0.048467699 -0.070974797 -0.038081001, + 0.0546159 -0.064186402 -0.020615, + 0.0546159 -0.064189598 -0.017003, + 0.0532961 -0.066492997 -0.014355, + 0.0532961 -0.066472299 -0.021745, + 0.051830001 -0.068684198 -0.023073001, + 0.0532961 -0.066542499 -0.018036, + 0.0378174 -0.083448403 -0.0084100002, + 0.035366699 -0.085178301 -0.008862, + 0.035366699 -0.085166797 -0.01101, + 0.0378174 -0.083458997 -0.010529, + 0.040174201 -0.081628501 -0.010218, + 0.0424264 -0.0796986 -0.012134, + 0.050219599 -0.071143098 -0.016875001, + 0.050219599 -0.071116097 -0.013028, + 0.048467699 -0.0733869 -0.014536, + 0.048467699 -0.073325403 -0.018464001, + 0.050219599 -0.071037598 -0.020736, + 0.051830001 -0.068834797 -0.019282, + 0.051830001 -0.0688558 -0.015503, + 0.056809202 -0.056758299 -0.0059429901, + 0.051830001 -0.067641698 -0.00281799, + 0.051830001 -0.068013601 -0.0046009999, + 0.0532961 -0.064621501 -0.0020920001, + 0.051830001 -0.0671902 -0.001045, + 0.051830001 -0.066658303 0.00071499601, + 0.0532961 -0.064048603 -0.000376999, + 0.056809202 -0.0586969 -0.012421, + 0.0532961 -0.056771599 0.01209, + 0.0546159 -0.055137102 0.0090319999, + 0.0546159 -0.053991299 0.010342, + 0.0532961 -0.057918299 0.010703, + 0.051830001 -0.059578098 0.013692, + 0.051830001 -0.058376402 0.015094, + 0.050219599 -0.059944499 0.018028, + 0.0546159 -0.052795202 0.011588, + 0.0532961 -0.055568401 0.013414, + 0.0532961 -0.046009298 0.020677, + 0.055787299 -0.0436926 0.014445, + 0.0546159 -0.044858899 0.017581999, + 0.055787299 -0.0410157 0.015866, + 0.0546159 -0.046244599 0.016767999, + 0.056809202 -0.042515401 0.011278, + 0.055787299 -0.046319999 0.012734, + 0.0546159 -0.0476126 0.015877999, + 0.056809202 -0.039965902 0.012716, + 0.0599402 -0.044861801 -0.023916001, + 0.0599402 -0.044056501 -0.021119, + 0.059757002 -0.046801399 -0.020986, + 0.059757002 -0.047463998 -0.023918999, + 0.0599402 -0.045436401 -0.026798001, + 0.059999999 -0.0429371 -0.026823999, + 0.059999999 -0.042227201 -0.024073999, + 0.059999999 -0.035956699 -0.012473, + 0.059999999 -0.034341902 -0.010712, + 0.0599402 -0.037218101 -0.0094040101, + 0.0599402 -0.038874101 -0.011371, + 0.059999999 -0.037490699 -0.014435, + 0.061000001 -0.0153 -0.12549999, + 0.0465803 -0.0185932 0.037627, + 0.0465803 -0.016563199 0.037774, + 0.050626501 -0.0094999997 0.032202002, + 0.0378174 -0.055947602 0.041563001, + 0.035366699 -0.058698799 0.042840999, + 0.044564299 -0.056501199 0.032409001, + 0.050219599 -0.038764201 0.029802, + 0.050219599 -0.040315699 0.029478, + 0.051830001 -0.038014799 0.026908001, + 0.051830001 -0.0348983 0.02743, + 0.048467699 -0.0394927 0.032614999, + 0.050219599 -0.035531301 0.030282, + 0.051830001 -0.018415701 0.029966, + 0.048467699 -0.041099999 0.032308999, + 0.0248404 0.052493501 -0.16704801, + 0.027557701 0.051174399 -0.16699401, + 0.0248404 0.052588001 -0.16928101, + 0.0248404 0.052331701 -0.164804, + 0.0220857 0.0536642 -0.167096, + 0.027557701 0.051012602 -0.16472299, + 0.0220857 0.053759001 -0.169305, + 0.0328326 -0.077685997 0.029324999, + 0.0328326 -0.078886203 0.027491, + 0.035366699 -0.076462701 0.027415, + 0.035366699 -0.075203702 0.029184001, + 0.0302257 -0.0800386 0.029231999, + 0.0302257 -0.077490598 0.032876998, + 0.0328326 -0.075016901 0.032832999, + 0.0302257 -0.076081902 0.034614999, + 0.0328326 -0.076395303 0.031107999, + 0.0302257 -0.078810401 0.031081, + 0.027557701 -0.079833999 0.032678999, + 0.044564299 -0.071696803 0.016627001, + 0.0465803 -0.070009902 0.014078, + 0.0465803 -0.069025204 0.015802, + 0.044564299 -0.070671096 0.018371999, + 0.0424264 -0.073308803 0.019063, + 0.0424264 -0.074286498 0.017258, + 0.044564299 -0.073489599 0.013026, + 0.0465803 -0.071726099 0.010522, + 0.0465803 -0.070910998 0.012316, + 0.044564299 -0.072636999 0.014843, + 0.044564299 -0.074252903 0.011183, + 0.0424264 -0.075174801 0.015419, + 0.0424264 -0.075972103 0.013552, + 0.0328326 -0.079993501 0.025612, + 0.0328326 -0.081005499 0.023697, + 0.0378174 -0.076281801 0.023554999, + 0.035366699 -0.077632502 0.025596, + 0.0378174 -0.075144798 0.025357001, + 0.040174201 -0.074838899 0.021375, + 0.035366699 -0.078710601 0.023734, + 0.040174201 -0.073736899 0.023158999, + 0.050219599 -0.054385401 0.022986, + 0.050219599 -0.055844601 0.021859, + 0.051830001 -0.050139502 0.022024, + 0.051830001 -0.0516068 0.021059001, + 0.0532961 -0.048887599 0.018979, + 0.0532961 -0.047457401 0.019866999, + 0.051830001 -0.048648201 0.022910001, + 0.050219599 -0.051362701 0.024999, + 0.050219599 -0.052889299 0.024033001, + 0.00267513 -0.093096301 0.021499, + 0.00267513 -0.093546897 0.019404, + 0.0053918599 -0.092945002 0.021317, + 1.5587031e-012 -0.093145601 0.021559, + -7.2507547e-012 -0.093596801 0.019463001, + 0.0053918599 -0.090152003 0.029716, + -0.0053918599 -0.092399701 0.023411, + -0.0081421202 -0.0915007 0.025203001, + 0.00267513 -0.091148503 0.027814999, + -0.0053918599 -0.089194499 0.031784002, + -0.0081421202 -0.086742103 0.035498001, + -0.0109179 -0.083808601 0.038890999, + -0.0109179 -0.085161 0.036979001, + -0.0137106 -0.083398402 0.038251001, + -0.0137106 -0.08196 0.040102001, + -0.0109179 -0.0823595 0.040747002, + -0.0081421202 -0.084121197 0.039377999, + -0.0081421202 -0.085481398 0.037462, + 0.0081421202 -0.093132503 0.018916, + 0.0109179 -0.092758603 0.018475, + 0.0081421202 -0.093520597 0.016718, + 0.0053918599 -0.093393698 0.019223999, + 0.0081421202 -0.0926871 0.021005001, + 0.0109179 -0.092317902 0.020559, + 0.0053918599 -0.093784899 0.017021, + 0.0109179 -0.0911441 0.024747999, + 0.0137106 -0.089941002 0.026240001, + 0.0137106 -0.089107499 0.028316, + 0.0378174 -0.080581702 0.014043, + 0.040174201 -0.078341097 0.013892, + 0.040174201 -0.077604003 0.015802, + 0.0378174 -0.078282803 0.019831, + 0.040174201 -0.076774403 0.017689999, + 0.040174201 -0.075852104 0.019548999, + 0.0378174 -0.077328503 0.021710999, + 0.035366699 -0.079694897 0.021836, + 0.0328326 -0.084088102 0.015794, + 0.0328326 -0.084620602 0.013788, + 0.035366699 -0.082679696 0.014007, + 0.0302257 -0.085382603 0.017436, + 0.0302257 -0.085934497 0.015413, + -0.042423699 0.040423598 -0.1715, + -0.0424264 0.040386401 -0.169029, + -0.0424264 0.040283799 -0.166545, + -0.034754898 0.046886999 -0.1715, + -0.035366699 0.046429101 -0.169153, + -0.033477101 0.047792401 -0.1715, + -0.059927799 -0.0145 0.0029420001, + -0.0598731 -0.0094999997 0.0039009999, + -0.0599945 0.0074999998 0.00081300398, + -0.059757002 -0.0153443 0.0053810002, + -0.0599402 -0.0153294 0.0026700001, + -0.059757002 -0.0162088 0.0052669998, + -0.059757002 -0.017819799 0.0048719901, + -0.059999999 -0.016150201 -0.000141998, + -0.059999999 -0.0153147 -1.8997198e-005, + -0.061000001 -0.0153 -0.12549999, + -0.059999999 -0.0176931 -0.00057600398, + -0.0599402 -0.0161794 0.0025520001, + -0.0599402 -0.017756199 0.002138, + -0.0109179 0.056964301 -0.16937, + -0.0137106 0.0562791 -0.16720299, + -0.0137106 0.056377601 -0.169358, + -0.0109179 0.056866199 -0.167227, + -0.0118856 0.056811001 -0.1715, + -0.010915 0.056982499 -0.1715, + -0.0061689499 0.057679601 -0.1715, + -0.0060668602 0.057692502 -0.1715, + -0.0081428103 0.057411399 -0.16937999, + -0.0089870598 0.057323098 -0.1715, + -0.00616926 0.057682 -0.19149999, + 0.0328326 -0.086776599 -0.0094870003, + 0.027557701 -0.089603499 -0.0068120002, + 0.0302257 -0.0882411 -0.0058930102, + 0.027557701 -0.089576498 -0.0045989999, + 0.0302257 -0.088256396 -0.0080870101, + 0.027557701 -0.089591399 -0.0090279998, + 0.0248404 -0.090816103 -0.0056649898, + 0.0248404 -0.090814203 -0.0078990003, + 0.0165099 -0.093156397 -0.016671, + 0.0165099 -0.092673101 -0.021217, + 0.019305199 -0.092316799 -0.017356999, + 0.0165099 -0.093478002 -0.012114, + 0.0137106 -0.093856603 -0.016099, + 0.0137106 -0.093381703 -0.020666, + 0.019305199 -0.092649497 -0.012825, + -0.0109179 -0.087565899 0.033018, + -0.0137106 -0.087126501 0.032395002, + -0.0109179 -0.088614002 0.030985, + -0.0109179 -0.086414203 0.035018999, + -0.0081421202 -0.087900802 0.033493001, + -0.0137106 -0.085984103 0.034389999, + -0.0081421202 -0.088955604 0.031454999, + 0.0137106 -0.046113901 0.058194999, + 0.0165099 -0.048003599 0.057236001, + 0.0165099 -0.0459048 0.057386, + 0.0109179 -0.048409902 0.058704998, + 0.0137106 -0.050386399 0.057806, + 0.0137106 -0.0482288 0.058049999, + -0.0081421202 -0.055123299 0.058182001, + -0.0081421202 -0.052924599 0.058623001, + -0.0053918599 -0.055240899 0.058536001, + -0.0053918599 -0.0574448 0.057992, + -0.0081421202 -0.057319898 0.057636999, + -0.0109179 -0.054954801 0.057675, + -0.0109179 -0.052766301 0.058118001, + -0.0053918599 -0.046496999 0.059687, + -0.0053918599 -0.048642099 0.059551001, + -0.0081421202 -0.046406701 0.059340999, + -0.0081421202 -0.044284299 0.059388001, + -0.0053918599 -0.044367399 0.059732001, + -0.00267513 -0.046550199 0.059891, + -0.00267513 -0.048699301 0.059755001, + -0.019305199 -0.016767999 0.0568, + -0.0202484 -0.0145 0.056480002, + -0.0137106 -0.059072901 0.055808, + -0.0109179 -0.0571412 0.057128999, + -0.0109179 -0.059321102 0.056476001, + 0.0081421202 -0.05951 0.056990001, + 0.0109179 -0.057140399 0.057133999, + 0.0109179 -0.054953601 0.05768, + 0.0081421202 -0.0507291 0.058965001, + 0.0109179 -0.0527655 0.058123, + 0.0109179 -0.0505809 0.058463998, + 0.0081421202 -0.057319298 0.057641, + 0.0053918599 -0.059642199 0.057344001, + 0.00267513 -0.0597197 0.057551999, + 0.00267513 -0.0530999 0.059184, + -1.6085983e-012 -0.0553324 0.058812998, + -8.1904934e-012 -0.057541899 0.05827, + -0.048467699 -0.073102601 -0.00675999, + -0.051830001 -0.068510801 -0.0081529999, + -0.050219599 -0.070667498 -0.0055509899, + -0.048467699 -0.072957702 -0.0048459899, + -0.0532961 -0.064910002 -0.036614001, + -0.0576833 -0.056670502 -0.031962998, + -0.056809202 -0.059370302 -0.025897, + -0.0576833 -0.056946199 -0.028550999, + -0.056809202 -0.058349699 -0.036364, + -0.0546159 -0.062947303 -0.035193, + -0.0424264 -0.075953901 0.013544, + -0.044564299 -0.073468901 0.013015, + -0.044564299 -0.0742338 0.011174, + -0.0424264 -0.075155102 0.015408, + -0.0424264 -0.0766626 0.011658, + -0.040174201 -0.0775868 0.015794, + -0.040174201 -0.078325897 0.013886, + -0.048467699 -0.070562303 0.00611501, + -0.050219599 -0.068627 0.00344901, + -0.050219599 -0.067972697 0.0052149999, + -0.048467699 -0.069869898 0.0079070004, + -0.048467699 -0.071170203 0.0043040002, + -0.0465803 -0.072433896 0.0086939996, + -0.0465803 -0.0730768 0.00685699, + -0.035366699 -0.064231001 0.039624002, + -0.0328326 -0.063326202 0.042782001, + -0.0328326 -0.065171897 0.041618001, + -0.0378174 -0.059648201 0.039696999, + -0.0378174 -0.057810001 0.040668, + -0.035366699 -0.060577001 0.041852001, + -0.035366699 -0.0624245 0.040785, + -0.0378174 -0.0614531 0.038633, + -0.040174201 -0.0586561 0.037395999, + -0.040174201 -0.0568639 0.038366001, + -0.035366699 -0.0567885 0.043697, + -0.035366699 -0.058695801 0.042823002, + -0.0378174 -0.055946 0.041544002, + -0.0378174 -0.0540636 0.042323999, + -0.035366699 -0.0548627 0.044473998, + -0.0328326 -0.057570498 0.045696001, + -0.0328326 -0.059517901 0.044822998, + -0.0220857 -0.051627699 0.054492, + -0.0220857 -0.053743199 0.054033998, + -0.019305199 -0.0562649 0.054637998, + -0.019305199 -0.0498529 0.056000002, + -0.0165099 -0.050143301 0.056981999, + -0.0137106 -0.0525585 0.057456002, + -0.0053918599 -0.068236202 0.053661, + -0.0081421202 -0.0659796 0.054384001, + -0.0081421202 -0.068075404 0.053304002, + 0.019305199 -0.079374403 0.040123001, + 0.019305199 -0.077784799 0.04183, + 0.0165099 -0.081470698 0.039306998, + 0.0165099 -0.079952203 0.041088998, + 0.0137106 -0.081965998 0.040107001, + 0.0109179 -0.082364298 0.040750999, + 0.0081421202 -0.065980598 0.054388002, + 0.0081421202 -0.077751003 0.046411999, + 0.019305199 -0.072543196 0.046477001, + 0.0109179 -0.067847103 0.0528, + 0.0081421202 -0.0680767 0.053307999, + 0.0109179 -0.065761 0.053879999, + 0.0137106 -0.0654727 0.053211, + 0.0137106 -0.0675456 0.052133001, + 0.0165099 -0.067170799 0.051302001, + 0.0328326 -0.063331299 0.042799, + 0.035366699 -0.062429901 0.040803, + 0.0328326 -0.061443001 0.043868002, + 0.035366699 -0.0605812 0.041870002, + 0.035366699 -0.065997697 0.038389999, + 0.035366699 -0.067703404 0.037050001, + 0.0378174 -0.064943202 0.036249001, + 0.035366699 -0.064237699 0.039641999, + 0.0220857 -0.073749498 0.043862998, + 0.0220857 -0.075477503 0.042318001, + 0.0248404 -0.073045202 0.042544998, + 0.027557701 -0.064914003 0.046305001, + 0.0302257 -0.064159803 0.044633999, + 0.0248404 -0.0655929 0.047807999, + 0.027557701 -0.0629564 0.047377001, + 0.0302257 -0.062235199 0.045705002, + 0.0248404 -0.067537703 0.046634, + 0.019305199 -0.083600797 0.034616001, + 0.019305199 -0.082286298 0.036509, + 0.0220857 -0.082869902 0.033511002, + -0.00267513 -0.066223599 0.054951001, + 3.5815871e-012 -0.0662532 0.055020001, + -0.00267513 -0.068330698 0.05387, + -0.00267513 -0.064080499 0.055925, + -0.0053918599 -0.066133298 0.054740999, + -0.0053918599 -0.063994497 0.055714998, + -0.0053918599 -0.072302498 0.051188, + -0.0053918599 -0.070295103 0.052475002, + -0.00267513 -0.070393696 0.052684002, + -0.00267513 -0.076244101 0.048532002, + -0.0053918599 -0.074251004 0.049803998, + -0.0053918599 -0.077942804 0.046758, + -0.00267513 -0.0780572 0.046964001, + -0.0053918599 -0.076133497 0.048326001, + -0.0081421202 -0.077748202 0.046408001, + -0.00267513 -0.079791501 0.045311999, + -0.0081421202 -0.075945303 0.047974002, + -0.0053918599 -0.081319898 0.04338, + -0.0053918599 -0.079673402 0.045108002, + -0.0053918599 -0.082877003 0.041582, + -0.0081421202 -0.081112802 0.043033998, + -0.0081421202 -0.0794724 0.044759002, + -0.00267513 -0.083002202 0.041783001, + -0.00267513 -0.081441604 0.043582998, + 0.0081421202 -0.082667597 0.041241001, + 0.0248404 -0.079385199 0.035937998, + 0.0220857 -0.080181703 0.037225001, + 0.0220857 -0.081573002 0.035395, + 0.0248404 -0.080755301 0.034118, + 0.027557701 -0.078487702 0.034488, + 0.027557701 -0.077051498 0.036237001, + 0.058412101 -0.054754701 -0.027851, + 0.058412101 -0.054535899 -0.031181, + 0.0576833 -0.056963202 -0.028523, + 0.058412101 -0.0548581 -0.024635, + 0.0576833 -0.0571278 -0.025123, + 0.058998398 -0.052547898 -0.027422, + 0.058998398 -0.052387301 -0.030572999, + 0.051830001 -0.067448899 -0.034444999, + 0.0532961 -0.065498598 -0.032906, + 0.0546159 -0.062960401 -0.035193, + 0.050219599 -0.068510696 -0.039995998, + 0.0460728 -0.040435601 -0.19149999, + 0.040174201 -0.081579797 -0.014403, + 0.040174201 -0.081622504 -0.012309, + 0.0378174 -0.083432399 -0.01265, + 0.040174201 -0.0815005 -0.016497999, + 0.0378174 -0.083368599 -0.014773, + 0.0424264 -0.079615198 -0.016262, + 0.055787299 -0.0599536 -0.0061900001, + 0.0546159 -0.062015198 -0.00326401, + 0.055787299 -0.059388101 -0.0045509902, + 0.056809202 -0.057872798 -0.0091439998, + 0.0546159 -0.060720701 4.2999302e-005, + 0.055787299 -0.0587487 -0.002936, + 0.0546159 -0.061405901 -0.0015970001, + 0.0546159 -0.059961401 0.00165199, + 0.0532961 -0.062665902 0.0029819901, + 0.055787299 -0.0580373 -0.0013520099, + 0.0532961 -0.063396297 0.00131599, + 0.0532961 -0.065868497 -0.0073220101, + 0.0546159 -0.063683704 -0.010094, + 0.055787299 -0.061200801 -0.01121, + 0.0546159 -0.051553998 0.012768, + 0.051830001 -0.055804599 0.017697999, + 0.0532961 -0.0543136 0.014671, + 0.051830001 -0.057116799 0.01643, + 0.050219599 -0.057261299 0.020655001, + 0.050219599 -0.0586298 0.019377001, + 0.048459399 -0.0145 0.035360999, + 0.048147298 -0.0145 0.035803001, + 0.049368501 -0.0094999997 0.034099001, + 0.050219599 -0.0165092 0.032779001, + 0.048467699 -0.016536601 0.035317998, + 0.0498452 -0.0145 0.033397999, + 0.0502089 -0.0145 0.032825999, + 0.048467699 -0.018535901 0.035154, + 0.050219599 -0.0184767 0.032597002, + 0.051423199 -0.0145 0.030913999, + 0.051830001 -0.0164809 0.030166, + 0.0378174 -0.057813201 0.040686999, + 0.040174201 -0.055047799 0.039262999, + 0.0137106 -0.085990697 0.034394, + 0.0137106 -0.084747203 0.036348999, + 0.0109179 -0.088618703 0.030987, + 0.0137106 -0.087132901 0.032398, + 0.0137106 -0.088171698 0.030370001, + 1.9499361e-012 -0.084510803 0.039985001, + 0.0081421202 -0.084124997 0.039381001, + 0.00267513 -0.088274002 0.034021001, + 0.0081421202 -0.089909799 0.029391, + 0.0109179 -0.090404503 0.026845001, + 0.0109179 -0.0895629 0.028926, + 0.0053918599 -0.091753401 0.025521999, + 0.0053918599 -0.091003999 0.027626, + 0.00267513 -0.091900401 0.025708999, + 0.0053918599 -0.092400797 0.023411, + 0.00267513 -0.092550002 0.023596, + 0.0081421202 -0.091502897 0.025203001, + 0.0081421202 -0.0907574 0.027305, + -0.00267513 -0.092549503 0.023596, + 1.5156827e-012 -0.091948099 0.025769001, + 5.3117347e-013 -0.092598498 0.023655999, + -0.0053918599 -0.0910023 0.027626, + -0.00267513 -0.091147602 0.027814999, + -0.0053918599 -0.090149999 0.029715, + -0.0053918599 -0.091752 0.025521999, + -0.0081421202 -0.0907548 0.027303999, + -0.00267513 -0.0918997 0.025707999, + -0.0081421202 -0.0899067 0.02939, + -4.7659394e-012 -0.090340003 0.029968999, + -0.00267513 -0.090292998 0.029905999, + -7.7773187e-012 -0.091195397 0.027876999, + 0.00267513 -0.090294003 0.029906999, + 0.00267513 -0.089336097 0.031977002, + -0.00267513 -0.084468402 0.039919, + -0.0053918599 -0.084339902 0.039719, + 0.035366699 -0.081376404 0.017958, + 0.0378174 -0.079908803 0.015992001, + 0.035366699 -0.082074903 0.015989, + 0.0328326 -0.082738698 0.019783, + 0.035366699 -0.080583401 0.019909, + 0.0378174 -0.079142801 0.017922999, + 0.0328326 -0.083460897 0.017795, + -0.0378174 0.044541199 -0.16911399, + -0.035878699 0.0460907 -0.1715, + -0.034765299 0.046901699 -0.19149999, + -0.0378174 0.044042099 -0.161893, + -0.035366699 0.046162002 -0.164424, + -0.035366699 0.046327598 -0.166794, + -0.040174201 0.042256199 -0.164184, + -0.040174201 0.0424225 -0.166633, + -0.0424264 0.0401171 -0.16405199, + -0.0424264 0.039885201 -0.161553, + -0.040174201 0.042024601 -0.16172799, + -0.0378174 0.044273399 -0.164308, + -0.0378174 0.044439401 -0.16671599, + 0.0302257 -0.088170797 -0.012479, + 0.0328326 -0.086666703 -0.013835, + 0.0328326 -0.086740799 -0.01166, + 0.0302257 -0.088233002 -0.010282, + 0.0302257 -0.0880697 -0.014677, + 0.027557701 -0.089539997 -0.011246, + 0.027557701 -0.089449503 -0.013464, + -0.019305199 -0.041352902 0.056510001, + -0.0165099 -0.0438153 0.057447001, + -0.019305199 -0.0435827 0.056483001, + -0.019305199 -0.0235177 0.056724999, + -0.0220857 -0.016756799 0.055775002, + 0.0053918599 -0.0552403 0.058538999, + 0.00267513 -0.055309601 0.058745001, + 0.0053918599 -0.053034801 0.058977999, + 0.0053918599 -0.057444401 0.057994999, + 0.0081421202 -0.055122402 0.058185998, + 0.00267513 -0.0575178 0.058201998, + 0.0081421202 -0.052924 0.058626, + -0.050219599 -0.0711013 -0.013052, + -0.050219599 -0.071126401 -0.016890001, + -0.051830001 -0.068840504 -0.015528, + -0.051830001 -0.068743899 -0.011771, + -0.050219599 -0.070954002 -0.00923, + -0.048467699 -0.073298998 -0.010646, + -0.048467699 -0.073370799 -0.01455, + -0.0532961 -0.064207301 -0.040307999, + -0.0532961 -0.063377701 -0.043981001, + -0.0497806 -0.035494599 -0.19149999, + -0.052960701 -0.0301986 -0.19149999, + -0.055787299 -0.059721801 -0.041065, + -0.0546159 -0.062333699 -0.038823999, + -0.055787299 -0.060373701 -0.037510999, + -0.056809202 -0.0570856 -0.043326002, + -0.055787299 -0.058949601 -0.044601999, + -0.0546159 -0.061596401 -0.042440001, + -0.056809202 -0.057776101 -0.039850999, + -0.055787299 -0.0613169 -0.030378999, + -0.055787299 -0.060905401 -0.033946998, + -0.056809202 -0.0588063 -0.032871999, + -0.056809202 -0.059145998 -0.029381, + -0.055787299 -0.061608501 -0.026814001, + -0.0546159 -0.063804299 -0.027908999, + -0.0546159 -0.063437402 -0.031552002, + -0.0165099 -0.0544586 0.056184001, + -0.019305199 -0.0541288 0.055193, + -0.0165099 -0.056614801 0.055633001, + -0.0165099 -0.052299999 0.056632999, + -0.0137106 -0.0547336 0.057009999, + -0.019305199 -0.051990099 0.055645999, + -0.0137106 -0.0569066 0.056462001, + 0.0248404 -0.076377198 0.039388001, + 0.0220857 -0.077128999 0.040692002, + 0.0248404 -0.074749097 0.041005999, + 0.0248404 -0.077924199 0.037696999, + 0.027557701 -0.075530097 0.037919, + 0.0220857 -0.078698799 0.038991999, + 0.027557701 -0.073928401 0.039528999, + 0.00267513 -0.0683311 0.053870998, + 0.0053918599 -0.068236999 0.053663, + 1.8744266e-012 -0.0683617 0.053939, + 0.00267513 -0.066223897 0.054951999, + 0.0053918599 -0.066133901 0.054744001, + 0.0053918599 -0.077944703 0.046760999, + -3.9069204e-012 -0.079830498 0.045379002, + 0.0081421202 -0.070128798 0.052122999, + 0.0081421202 -0.075947799 0.047977999, + 0.0109179 -0.079189204 0.044266, + 0.0109179 -0.080821298 0.042544, + 0.0137106 -0.080433898 0.041896001, + 0.0165099 -0.076656297 0.044440001, + 0.0165099 -0.078345701 0.042803001, + 0.019305199 -0.076112904 0.043462001, + 0.0137106 -0.0788133 0.043614, + 0.019305199 -0.074363798 0.045012999, + 0.0137106 -0.0753273 0.046815999, + 0.0109179 -0.0756796 0.047474999, + 0.0109179 -0.077473603 0.045912001, + 0.0137106 -0.0771093 0.045256, + 0.0165099 -0.074889302 0.045995999, + 0.0165099 -0.071145996 0.048841, + 0.0165099 -0.073050201 0.047465, + 0.019305199 -0.070657797 0.047850002, + 0.019305199 -0.068714701 0.049128, + 0.0165099 -0.069183797 0.050120998, + 0.0137106 -0.073472902 0.048287999, + 0.027557701 -0.066829301 0.045132998, + 0.0248404 -0.069432601 0.045363002, + 0.0248404 -0.071270801 0.043999001, + 0.027557701 -0.0722517 0.041060001, + 0.0302257 -0.071370102 0.039409999, + 0.0328326 -0.068719998 0.039030001, + 0.00267513 -0.070394203 0.052685, + 0.0053918599 -0.070296101 0.052478001, + 0.0053918599 -0.082879402 0.041584, + 0.0081421202 -0.081116199 0.043037001, + 0.0081421202 -0.0794755 0.044762999, + 0.0532961 -0.064213902 -0.040309001, + 0.0532961 -0.064919502 -0.036614999, + 0.051830001 -0.0667772 -0.038215999, + 0.051830001 -0.065976001 -0.041965999, + 0.0532961 -0.063381799 -0.043981999, + 0.0546159 -0.0616032 -0.042440999, + 0.0497806 -0.035494599 -0.19149999, + 0.0546159 -0.0623434 -0.038825002, + 0.0546159 -0.063001901 -0.0066550002, + 0.0532961 -0.065530598 -0.0055689998, + 0.0532961 -0.065115198 -0.00382401, + 0.0546159 -0.063380502 -0.0083699999, + 0.0546159 -0.062546998 -0.0049510002, + 0.055787299 -0.060859401 -0.0095239999, + 0.055787299 -0.060444001 -0.0078490004, + 0.0532961 -0.0516712 0.016974, + 0.0532961 -0.053012799 0.015859, + 0.0546159 -0.050273001 0.013877, + 0.0546159 -0.048957299 0.014914, + 0.0532961 -0.050294202 0.018014999, + 0.051830001 -0.053043999 0.020014999, + 0.051830001 -0.054445099 0.018894, + 0.0424264 -0.0540937 0.036825001, + 0.044564299 -0.054807499 0.033376999, + 0.044564299 -0.053088501 0.034256998, + 0.0378174 -0.059652701 0.039717, + 0.040174201 -0.056867301 0.038387001, + 0.0424264 -0.0558642 0.035946999, + 0.0109179 -0.085166201 0.036982, + 0.0081421202 -0.085485302 0.037464999, + 0.0053918599 -0.086974002 0.035835002, + 0.00267513 -0.085838497 0.037999999, + 0.0053918599 -0.085708097 0.037802, + 0.00267513 -0.087107502 0.036031, + 0.00267513 -0.084469698 0.039919998, + -6.7770598e-012 -0.085880697 0.038063999, + 0.0053918599 -0.084342398 0.039721001, + -0.0053918599 -0.088134997 0.033824999, + -0.00267513 -0.089334898 0.031977002, + 7.441687e-012 -0.089381203 0.03204, + -0.00267513 -0.087106198 0.036029998, + -0.0053918599 -0.085705496 0.037799999, + -0.0053918599 -0.086971402 0.035833001, + -0.00267513 -0.085837297 0.037999, + -0.00267513 -0.088272803 0.034019999, + 3.9717327e-012 -0.0871507 0.036093999, + 2.9437243e-012 -0.088318102 0.034084, + -0.040169802 0.0425593 -0.1715, + -0.0404175 0.042344399 -0.1715, + -0.040174201 0.042524699 -0.169073, + -0.038194101 0.044273201 -0.1715, + -0.039609101 0.043067899 -0.19149999, + 0.0109179 -0.071880303 0.050331999, + 0.0109179 -0.073812798 0.048950002, + 0.0137106 -0.071552999 0.049667001, + 0.0137106 -0.069574803 0.050949998, + 0.0109179 -0.0698893 0.051615998, + 0.0081421202 -0.0721296 0.050838001, + 0.0081421202 -0.074071698 0.049454, + 0.0302257 -0.067876302 0.042204, + 0.027557701 -0.068695299 0.043866001, + 0.027557701 -0.070505098 0.042507, + 0.0302257 -0.069654398 0.040849999, + 0.0302257 -0.066042401 0.043466002, + 0.0328326 -0.066976599 0.040376998, + 0.0328326 -0.065178096 0.041634999, + -4.4302526e-012 -0.070426099 0.052753001, + 0.00267513 -0.081442699 0.043584, + 0.0053918599 -0.081322096 0.043382, + 0.00267513 -0.083003402 0.041784, + 0.00267513 -0.0797925 0.045313001, + 6.0817237e-012 -0.081481799 0.043650001, + 0.0053918599 -0.079675399 0.045109998, + 4.9880954e-012 -0.083043501 0.041850001, + 0.040174201 -0.060421601 0.036355, + 0.040174201 -0.058660898 0.037416998, + 0.0378174 -0.061458901 0.038653001, + 0.040174201 -0.062142398 0.035202999, + 0.0378174 -0.063224599 0.037496001, + 0.0424264 -0.059321702 0.033918999, + 0.0424264 -0.0576092 0.034977999, + 0.0081421202 -0.087904602 0.033495001, + 0.0109179 -0.0864195 0.035022002, + 0.0109179 -0.087571003 0.033020999, + 0.0081421202 -0.086746 0.035500001, + 0.0081421202 -0.088959098 0.031456999, + 0.0053918599 -0.088137597 0.033826001, + 0.0053918599 -0.089196801 0.031785, + 0.0053918599 -0.072303697 0.051190998, + 3.7328821e-012 -0.072438903 0.051465001, + 0.00267513 -0.0724058 0.051398002, + -0.00267513 -0.074357703 0.050011002, + -0.00267513 -0.072405197 0.051397, + 0.00267513 -0.076244898 0.048533998, + 0.0053918599 -0.074252501 0.049805999, + 0.0053918599 -0.076135099 0.048328001, + 0.00267513 -0.074358404 0.050012998, + 0.00267513 -0.078058198 0.046964999, + 1.9822314e-012 -0.076280497 0.048599999, + 5.4775997e-012 -0.0780949 0.047031999, + -6.5207828e-015 -0.074392803 0.050080001 ] + + } + coordIndex [ 8, 7, 14, -1, 34, 33, 21, -1, + 0, 868, 1, -1, 0, 1, 14, -1, + 870, 1, 868, -1, 1184, 1945, 4, -1, + 187, 4, 20, -1, 3125, 7, 8, -1, + 12, 267, 1230, -1, 189, 34, 21, -1, + 25, 900, 903, -1, 1948, 20, 4, -1, + 1948, 4, 1945, -1, 2, 21, 33, -1, + 6, 1184, 4, -1, 6, 1952, 1184, -1, + 68, 0, 14, -1, 68, 14, 187, -1, + 68, 868, 0, -1, 36, 8, 14, -1, + 36, 10, 37, -1, 40, 37, 10, -1, + 40, 10, 1230, -1, 40, 1230, 39, -1, + 2927, 7, 3125, -1, 83, 3125, 8, -1, + 83, 39, 1230, -1, 43, 44, 263, -1, + 87, 13, 88, -1, 91, 263, 44, -1, + 91, 52, 263, -1, 262, 263, 52, -1, + 269, 1230, 267, -1, 656, 659, 682, -1, + 656, 657, 659, -1, 499, 56, 1282, -1, + 1269, 499, 500, -1, 335, 2726, 145, -1, + 3011, 2206, 18, -1, 17, 18, 2206, -1, + 17, 85, 18, -1, 842, 171, 45, -1, + 842, 45, 46, -1, 842, 46, 1625, -1, + 435, 189, 21, -1, 190, 34, 189, -1, + 19, 441, 24, -1, 19, 24, 25, -1, + 3051, 983, 30, -1, 3051, 3056, 983, -1, + 486, 478, 212, -1, 2348, 421, 846, -1, + 569, 585, 226, -1, 246, 83, 1230, -1, + 23, 1, 870, -1, 23, 14, 1, -1, + 66, 2, 33, -1, 66, 67, 25, -1, + 66, 25, 23, -1, 66, 23, 2, -1, + 176, 21, 2, -1, 176, 23, 870, -1, + 176, 2, 23, -1, 176, 882, 21, -1, + 869, 430, 175, -1, 869, 176, 870, -1, + 869, 175, 176, -1, 3, 14, 7, -1, + 3, 7, 6, -1, 3, 6, 4, -1, + 3, 187, 14, -1, 3, 4, 187, -1, + 5, 1952, 6, -1, 5, 6, 7, -1, + 5, 2927, 1952, -1, 5, 7, 2927, -1, + 38, 8, 36, -1, 38, 83, 8, -1, + 38, 39, 83, -1, 11, 13, 12, -1, + 11, 36, 13, -1, 9, 10, 36, -1, + 9, 1230, 10, -1, 9, 12, 1230, -1, + 9, 11, 12, -1, 9, 36, 11, -1, + 41, 421, 2348, -1, 41, 1625, 46, -1, + 41, 2348, 1625, -1, 90, 267, 12, -1, + 90, 12, 13, -1, 90, 13, 87, -1, + 95, 97, 98, -1, 95, 43, 263, -1, + 42, 98, 88, -1, 42, 43, 95, -1, + 42, 95, 98, -1, 42, 88, 13, -1, + 42, 13, 36, -1, 42, 36, 14, -1, + 42, 14, 23, -1, 42, 85, 41, -1, + 42, 340, 85, -1, 42, 23, 340, -1, + 635, 2607, 634, -1, 50, 659, 260, -1, + 50, 260, 99, -1, 53, 262, 52, -1, + 53, 99, 260, -1, 102, 1230, 269, -1, + 279, 278, 274, -1, 15, 2085, 499, -1, + 15, 499, 1269, -1, 2956, 15, 1269, -1, + 2956, 2085, 15, -1, 55, 2085, 721, -1, + 55, 499, 2085, -1, 55, 56, 499, -1, + 109, 55, 721, -1, 322, 2085, 2963, -1, + 322, 721, 2085, -1, 113, 689, 674, -1, + 287, 1271, 667, -1, 336, 2726, 335, -1, + 57, 343, 340, -1, 16, 145, 1455, -1, + 16, 1455, 335, -1, 16, 335, 145, -1, + 833, 17, 2206, -1, 833, 417, 85, -1, + 833, 85, 17, -1, 58, 3011, 18, -1, + 58, 18, 85, -1, 1465, 343, 57, -1, + 376, 375, 155, -1, 522, 985, 441, -1, + 149, 441, 19, -1, 149, 522, 441, -1, + 149, 25, 903, -1, 149, 19, 25, -1, + 508, 60, 821, -1, 160, 166, 167, -1, + 160, 167, 773, -1, 136, 224, 775, -1, + 62, 409, 60, -1, 165, 78, 81, -1, + 165, 81, 136, -1, 1281, 1282, 56, -1, + 72, 71, 69, -1, 65, 73, 70, -1, + 888, 850, 889, -1, 179, 175, 430, -1, + 434, 20, 1948, -1, 434, 187, 20, -1, + 881, 21, 882, -1, 881, 435, 21, -1, + 452, 34, 190, -1, 452, 69, 34, -1, + 191, 65, 70, -1, 191, 900, 65, -1, + 22, 900, 25, -1, 22, 25, 67, -1, + 22, 65, 900, -1, 22, 67, 65, -1, + 3050, 24, 441, -1, 31, 129, 133, -1, + 31, 133, 340, -1, 31, 340, 23, -1, + 31, 23, 25, -1, 27, 24, 3050, -1, + 27, 3050, 3051, -1, 27, 25, 24, -1, + 27, 31, 25, -1, 26, 3051, 30, -1, + 26, 30, 29, -1, 26, 27, 3051, -1, + 26, 29, 31, -1, 26, 31, 27, -1, + 28, 29, 30, -1, 28, 30, 983, -1, + 28, 983, 129, -1, 28, 129, 31, -1, + 28, 31, 29, -1, 443, 1666, 907, -1, + 443, 907, 908, -1, 447, 444, 1678, -1, + 195, 74, 71, -1, 306, 211, 480, -1, + 76, 486, 212, -1, 223, 82, 217, -1, + 223, 217, 504, -1, 1001, 997, 216, -1, + 1054, 1028, 1026, -1, 1111, 1729, 572, -1, + 1205, 682, 659, -1, 1205, 254, 682, -1, + 1205, 659, 101, -1, 1205, 101, 1204, -1, + 247, 246, 1230, -1, 1183, 1182, 2533, -1, + 32, 66, 33, -1, 32, 69, 66, -1, + 32, 33, 34, -1, 32, 34, 69, -1, + 35, 36, 37, -1, 35, 38, 36, -1, + 35, 39, 38, -1, 35, 40, 39, -1, + 35, 37, 40, -1, 420, 41, 85, -1, + 420, 421, 41, -1, 89, 88, 98, -1, + 89, 98, 267, -1, 47, 41, 46, -1, + 47, 42, 41, -1, 47, 43, 42, -1, + 47, 44, 43, -1, 47, 92, 48, -1, + 47, 91, 44, -1, 47, 1986, 91, -1, + 47, 48, 1986, -1, 253, 91, 1986, -1, + 51, 52, 91, -1, 51, 91, 251, -1, + 93, 46, 45, -1, 93, 47, 46, -1, + 93, 92, 47, -1, 93, 45, 171, -1, + 1203, 1986, 48, -1, 1203, 48, 92, -1, + 629, 682, 254, -1, 172, 2624, 2121, -1, + 172, 2121, 171, -1, 49, 635, 97, -1, + 49, 659, 635, -1, 49, 97, 258, -1, + 49, 258, 659, -1, 268, 267, 98, -1, + 100, 659, 50, -1, 100, 50, 99, -1, + 100, 101, 659, -1, 250, 99, 53, -1, + 250, 51, 251, -1, 250, 53, 52, -1, + 250, 52, 51, -1, 265, 53, 260, -1, + 265, 262, 53, -1, 2043, 2044, 1230, -1, + 2051, 2053, 1211, -1, 2063, 280, 654, -1, + 281, 280, 2063, -1, 683, 656, 682, -1, + 283, 659, 658, -1, 283, 2607, 635, -1, + 283, 635, 659, -1, 285, 1269, 214, -1, + 285, 717, 1300, -1, 285, 214, 717, -1, + 293, 111, 841, -1, 293, 1281, 56, -1, + 669, 841, 111, -1, 669, 111, 1284, -1, + 669, 1284, 2119, -1, 2610, 2963, 2085, -1, + 1252, 125, 2070, -1, 106, 328, 125, -1, + 2127, 2070, 125, -1, 54, 674, 109, -1, + 54, 109, 721, -1, 54, 1322, 674, -1, + 54, 721, 1322, -1, 108, 55, 109, -1, + 108, 56, 55, -1, 108, 293, 56, -1, + 108, 111, 293, -1, 1292, 304, 302, -1, + 119, 302, 695, -1, 709, 320, 117, -1, + 122, 1270, 2616, -1, 122, 722, 1270, -1, + 2087, 721, 322, -1, 296, 725, 124, -1, + 1155, 1153, 287, -1, 2092, 287, 1153, -1, + 2092, 1271, 287, -1, 128, 173, 1369, -1, + 128, 1369, 333, -1, 128, 333, 330, -1, + 1371, 1394, 751, -1, 1949, 876, 434, -1, + 1949, 434, 1948, -1, 135, 340, 341, -1, + 135, 57, 340, -1, 131, 983, 1453, -1, + 1454, 1455, 145, -1, 1454, 145, 143, -1, + 1535, 1465, 57, -1, 1535, 57, 135, -1, + 342, 58, 85, -1, 342, 85, 340, -1, + 342, 340, 343, -1, 3170, 3011, 58, -1, + 3170, 58, 342, -1, 353, 405, 137, -1, + 353, 140, 405, -1, 404, 159, 1472, -1, + 404, 1472, 406, -1, 374, 155, 375, -1, + 374, 373, 155, -1, 154, 373, 796, -1, + 390, 2726, 391, -1, 362, 155, 162, -1, + 1497, 1461, 364, -1, 1497, 1463, 1461, -1, + 1497, 413, 1463, -1, 367, 376, 155, -1, + 367, 155, 362, -1, 369, 370, 1461, -1, + 2202, 371, 369, -1, 2202, 369, 1461, -1, + 2202, 1461, 2203, -1, 147, 895, 151, -1, + 147, 903, 902, -1, 147, 902, 895, -1, + 894, 151, 895, -1, 2248, 336, 983, -1, + 2248, 2726, 336, -1, 521, 522, 150, -1, + 812, 516, 519, -1, 157, 168, 166, -1, + 157, 61, 168, -1, 153, 61, 157, -1, + 153, 157, 158, -1, 153, 138, 61, -1, + 153, 154, 138, -1, 161, 159, 404, -1, + 161, 162, 158, -1, 408, 61, 138, -1, + 408, 138, 818, -1, 410, 821, 60, -1, + 410, 60, 409, -1, 782, 160, 773, -1, + 782, 1472, 159, -1, 782, 159, 160, -1, + 782, 1068, 1069, -1, 782, 773, 1068, -1, + 59, 224, 136, -1, 59, 223, 224, -1, + 59, 82, 223, -1, 59, 81, 82, -1, + 59, 136, 81, -1, 77, 78, 62, -1, + 77, 508, 509, -1, 77, 60, 508, -1, + 77, 62, 60, -1, 63, 409, 62, -1, + 63, 61, 408, -1, 63, 408, 409, -1, + 63, 168, 61, -1, 164, 62, 78, -1, + 164, 78, 165, -1, 164, 168, 63, -1, + 164, 63, 62, -1, 825, 2252, 417, -1, + 423, 171, 842, -1, 64, 74, 73, -1, + 64, 73, 65, -1, 64, 69, 71, -1, + 64, 71, 74, -1, 64, 66, 69, -1, + 64, 67, 66, -1, 64, 65, 67, -1, + 174, 748, 424, -1, 174, 173, 128, -1, + 3023, 1954, 3024, -1, 3023, 865, 1954, -1, + 433, 68, 187, -1, 433, 188, 68, -1, + 1645, 868, 68, -1, 1645, 68, 188, -1, + 451, 72, 69, -1, 451, 69, 452, -1, + 451, 448, 72, -1, 438, 190, 189, -1, + 456, 70, 73, -1, 456, 191, 70, -1, + 899, 900, 191, -1, 899, 191, 440, -1, + 442, 443, 908, -1, 924, 197, 921, -1, + 194, 195, 71, -1, 194, 72, 448, -1, + 194, 71, 72, -1, 194, 453, 195, -1, + 457, 73, 74, -1, 457, 74, 195, -1, + 457, 456, 73, -1, 463, 918, 442, -1, + 925, 926, 196, -1, 925, 197, 924, -1, + 933, 196, 926, -1, 933, 331, 196, -1, + 202, 212, 199, -1, 202, 487, 212, -1, + 471, 1699, 203, -1, 471, 953, 1699, -1, + 471, 203, 2780, -1, 1697, 2326, 2321, -1, + 204, 955, 2326, -1, 204, 1699, 953, -1, + 495, 474, 480, -1, 495, 1694, 474, -1, + 1695, 206, 474, -1, 476, 211, 306, -1, + 476, 1299, 116, -1, 208, 474, 206, -1, + 208, 206, 306, -1, 75, 212, 487, -1, + 75, 76, 212, -1, 75, 487, 486, -1, + 75, 486, 76, -1, 479, 480, 211, -1, + 479, 211, 478, -1, 954, 204, 953, -1, + 954, 955, 204, -1, 220, 997, 996, -1, + 220, 216, 997, -1, 79, 217, 82, -1, + 79, 216, 217, -1, 79, 1001, 216, -1, + 80, 509, 1002, -1, 80, 77, 509, -1, + 80, 78, 77, -1, 80, 81, 78, -1, + 1000, 1001, 79, -1, 1000, 81, 80, -1, + 1000, 80, 1002, -1, 1000, 82, 81, -1, + 1000, 79, 82, -1, 511, 393, 970, -1, + 1744, 519, 516, -1, 1784, 533, 524, -1, + 1080, 2372, 2373, -1, 236, 1023, 1034, -1, + 236, 226, 585, -1, 236, 1034, 1033, -1, + 236, 1033, 226, -1, 1043, 1028, 1054, -1, + 1061, 775, 224, -1, 1053, 1054, 1026, -1, + 1035, 1092, 1091, -1, 2435, 226, 1033, -1, + 2435, 1033, 1091, -1, 1107, 418, 1105, -1, + 2450, 609, 1111, -1, 1122, 228, 1096, -1, + 2461, 1123, 570, -1, 231, 232, 1469, -1, + 1468, 345, 347, -1, 240, 231, 600, -1, + 240, 232, 231, -1, 1821, 1127, 1122, -1, + 239, 237, 241, -1, 1865, 1866, 601, -1, + 1160, 1897, 329, -1, 1152, 1160, 329, -1, + 1917, 2533, 1182, -1, 1916, 1917, 247, -1, + 3124, 3125, 83, -1, 3124, 83, 246, -1, + 619, 2547, 1183, -1, 1185, 1945, 1184, -1, + 84, 420, 85, -1, 84, 2252, 420, -1, + 84, 85, 417, -1, 84, 417, 2252, -1, + 86, 87, 88, -1, 86, 88, 89, -1, + 86, 90, 87, -1, 86, 267, 90, -1, + 86, 89, 267, -1, 249, 251, 91, -1, + 249, 91, 253, -1, 256, 1203, 92, -1, + 256, 93, 171, -1, 256, 92, 93, -1, + 256, 171, 2121, -1, 256, 1973, 1203, -1, + 94, 258, 97, -1, 94, 259, 258, -1, + 94, 97, 95, -1, 94, 95, 259, -1, + 264, 259, 95, -1, 264, 95, 263, -1, + 633, 268, 635, -1, 96, 97, 635, -1, + 96, 635, 268, -1, 96, 98, 97, -1, + 96, 268, 98, -1, 252, 99, 250, -1, + 252, 100, 99, -1, 252, 101, 100, -1, + 252, 1204, 101, -1, 103, 634, 2607, -1, + 103, 1230, 102, -1, 103, 632, 634, -1, + 103, 102, 269, -1, 103, 269, 632, -1, + 1232, 1230, 649, -1, 1994, 279, 274, -1, + 1994, 274, 1989, -1, 272, 1997, 1996, -1, + 1327, 637, 636, -1, 1327, 277, 2126, -1, + 1327, 636, 277, -1, 638, 1225, 1239, -1, + 1226, 638, 637, -1, 1226, 1225, 638, -1, + 642, 1217, 1248, -1, 642, 1239, 1225, -1, + 1227, 1226, 2019, -1, 2029, 2052, 1243, -1, + 273, 648, 649, -1, 273, 103, 2607, -1, + 273, 649, 1230, -1, 273, 1230, 103, -1, + 1242, 280, 281, -1, 2061, 2063, 654, -1, + 687, 682, 294, -1, 687, 294, 689, -1, + 662, 1989, 274, -1, 1302, 1269, 285, -1, + 289, 2081, 665, -1, 840, 841, 669, -1, + 104, 1251, 299, -1, 104, 1252, 1251, -1, + 104, 125, 1252, -1, 104, 299, 106, -1, + 104, 106, 125, -1, 105, 326, 328, -1, + 105, 328, 106, -1, 105, 299, 326, -1, + 105, 106, 299, -1, 641, 2070, 2127, -1, + 641, 277, 640, -1, 641, 2126, 277, -1, + 641, 2127, 2126, -1, 110, 109, 674, -1, + 110, 674, 1283, -1, 107, 1283, 1284, -1, + 107, 108, 109, -1, 107, 109, 110, -1, + 107, 110, 1283, -1, 107, 1284, 111, -1, + 107, 111, 108, -1, 297, 113, 674, -1, + 297, 674, 112, -1, 297, 112, 298, -1, + 675, 112, 674, -1, 675, 298, 112, -1, + 678, 689, 113, -1, 678, 113, 297, -1, + 688, 326, 299, -1, 295, 682, 300, -1, + 295, 300, 692, -1, 1286, 692, 300, -1, + 697, 614, 702, -1, 303, 304, 309, -1, + 303, 309, 1714, -1, 303, 1714, 1720, -1, + 303, 1720, 613, -1, 308, 306, 705, -1, + 308, 705, 1297, -1, 114, 306, 206, -1, + 114, 705, 306, -1, 114, 206, 1713, -1, + 114, 1713, 705, -1, 1715, 1714, 309, -1, + 314, 476, 116, -1, 115, 320, 312, -1, + 115, 117, 320, -1, 115, 312, 314, -1, + 115, 314, 311, -1, 115, 311, 120, -1, + 115, 317, 117, -1, 115, 120, 317, -1, + 1294, 116, 1299, -1, 1294, 314, 116, -1, + 118, 1292, 302, -1, 118, 311, 1292, -1, + 118, 302, 119, -1, 1257, 119, 695, -1, + 316, 117, 317, -1, 316, 709, 117, -1, + 708, 320, 709, -1, 1260, 119, 1257, -1, + 1266, 710, 1261, -1, 318, 118, 119, -1, + 318, 317, 120, -1, 318, 119, 1260, -1, + 318, 1260, 1261, -1, 318, 120, 311, -1, + 318, 311, 118, -1, 321, 215, 713, -1, + 321, 713, 715, -1, 321, 717, 215, -1, + 121, 2616, 724, -1, 121, 724, 722, -1, + 121, 122, 2616, -1, 121, 722, 122, -1, + 324, 298, 296, -1, 324, 296, 124, -1, + 123, 725, 327, -1, 123, 124, 725, -1, + 123, 327, 324, -1, 123, 324, 124, -1, + 1324, 327, 725, -1, 2125, 125, 328, -1, + 2125, 2127, 125, -1, 127, 722, 724, -1, + 127, 296, 722, -1, 126, 724, 725, -1, + 126, 725, 296, -1, 126, 127, 724, -1, + 126, 296, 127, -1, 2095, 329, 1897, -1, + 2094, 329, 2095, -1, 2159, 1935, 2650, -1, + 1342, 3198, 1354, -1, 735, 1347, 2028, -1, + 747, 128, 330, -1, 747, 748, 174, -1, + 747, 174, 128, -1, 1370, 1369, 173, -1, + 1370, 173, 851, -1, 462, 196, 331, -1, + 332, 331, 330, -1, 332, 462, 331, -1, + 332, 464, 462, -1, 332, 330, 333, -1, + 2672, 2691, 2692, -1, 1403, 550, 1404, -1, + 2558, 3024, 1954, -1, 1191, 2280, 1192, -1, + 769, 336, 335, -1, 134, 129, 983, -1, + 134, 983, 131, -1, 134, 133, 129, -1, + 339, 131, 1453, -1, 339, 340, 132, -1, + 339, 132, 131, -1, 130, 131, 132, -1, + 130, 340, 133, -1, 130, 132, 340, -1, + 130, 133, 134, -1, 130, 134, 131, -1, + 1456, 1463, 413, -1, 144, 1454, 143, -1, + 144, 1453, 1454, -1, 144, 338, 1453, -1, + 144, 1535, 135, -1, 144, 341, 338, -1, + 144, 135, 341, -1, 1831, 1474, 1830, -1, + 777, 773, 167, -1, 169, 136, 775, -1, + 169, 775, 778, -1, 169, 165, 136, -1, + 169, 777, 167, -1, 169, 778, 777, -1, + 578, 577, 418, -1, 350, 1468, 347, -1, + 352, 347, 346, -1, 352, 350, 347, -1, + 580, 352, 346, -1, 580, 578, 418, -1, + 1119, 1114, 348, -1, 1119, 1509, 1508, -1, + 1119, 348, 1510, -1, 1119, 1510, 1509, -1, + 2442, 137, 2441, -1, 2442, 353, 137, -1, + 354, 137, 405, -1, 354, 405, 406, -1, + 354, 2441, 137, -1, 354, 1831, 2441, -1, + 401, 405, 140, -1, 401, 140, 141, -1, + 1491, 140, 353, -1, 1491, 1490, 140, -1, + 819, 154, 796, -1, 819, 796, 820, -1, + 819, 818, 138, -1, 819, 138, 154, -1, + 377, 796, 373, -1, 377, 373, 372, -1, + 2221, 820, 1529, -1, 357, 390, 817, -1, + 357, 356, 2726, -1, 357, 2726, 390, -1, + 359, 1479, 2726, -1, 359, 2726, 358, -1, + 359, 1478, 1479, -1, 139, 356, 399, -1, + 139, 2726, 356, -1, 139, 358, 2726, -1, + 1588, 358, 139, -1, 1588, 139, 399, -1, + 1477, 2726, 1479, -1, 355, 2220, 2726, -1, + 355, 2726, 1484, -1, 360, 1525, 141, -1, + 360, 141, 140, -1, 360, 140, 1490, -1, + 785, 141, 1525, -1, 785, 401, 141, -1, + 1499, 1497, 364, -1, 170, 1497, 412, -1, + 170, 413, 1497, -1, 1494, 412, 1497, -1, + 366, 362, 365, -1, 366, 367, 362, -1, + 142, 1523, 1461, -1, 142, 1461, 370, -1, + 142, 370, 1523, -1, 1526, 377, 372, -1, + 800, 143, 145, -1, 800, 145, 378, -1, + 800, 144, 143, -1, 800, 1535, 144, -1, + 2719, 145, 2726, -1, 2719, 378, 145, -1, + 790, 371, 2202, -1, 1546, 1527, 2202, -1, + 1546, 2719, 1527, -1, 793, 791, 790, -1, + 793, 790, 2202, -1, 1552, 383, 1551, -1, + 382, 1778, 1776, -1, 382, 804, 1778, -1, + 386, 382, 1776, -1, 386, 389, 382, -1, + 1014, 387, 1013, -1, 1014, 1015, 806, -1, + 146, 147, 151, -1, 146, 151, 150, -1, + 146, 150, 149, -1, 146, 149, 903, -1, + 146, 903, 147, -1, 148, 522, 149, -1, + 148, 150, 522, -1, 148, 149, 150, -1, + 1568, 1564, 1579, -1, 518, 521, 150, -1, + 518, 150, 151, -1, 518, 151, 894, -1, + 811, 516, 812, -1, 1585, 508, 821, -1, + 152, 154, 153, -1, 152, 155, 373, -1, + 152, 373, 154, -1, 152, 162, 155, -1, + 152, 158, 162, -1, 152, 153, 158, -1, + 156, 158, 157, -1, 156, 161, 158, -1, + 156, 157, 166, -1, 156, 159, 161, -1, + 156, 160, 159, -1, 156, 166, 160, -1, + 403, 161, 404, -1, 403, 162, 161, -1, + 403, 362, 162, -1, 403, 402, 362, -1, + 163, 164, 165, -1, 163, 167, 166, -1, + 163, 166, 168, -1, 163, 168, 164, -1, + 163, 169, 167, -1, 163, 165, 169, -1, + 822, 411, 1597, -1, 832, 170, 412, -1, + 832, 413, 170, -1, 415, 825, 417, -1, + 1608, 833, 2206, -1, 416, 417, 833, -1, + 416, 833, 1607, -1, 416, 1607, 1609, -1, + 416, 1609, 837, -1, 1592, 580, 418, -1, + 1592, 1600, 1603, -1, 2255, 2258, 2254, -1, + 292, 842, 671, -1, 292, 423, 842, -1, + 422, 171, 423, -1, 422, 172, 171, -1, + 422, 2624, 172, -1, 852, 851, 173, -1, + 852, 173, 174, -1, 852, 174, 424, -1, + 863, 1394, 1371, -1, 863, 1371, 1370, -1, + 863, 1370, 851, -1, 861, 863, 851, -1, + 861, 850, 862, -1, 426, 425, 424, -1, + 426, 855, 425, -1, 426, 424, 748, -1, + 426, 748, 1688, -1, 753, 754, 182, -1, + 753, 859, 755, -1, 427, 182, 185, -1, + 427, 753, 182, -1, 427, 859, 753, -1, + 752, 182, 754, -1, 178, 175, 179, -1, + 178, 882, 176, -1, 178, 176, 175, -1, + 177, 184, 883, -1, 177, 181, 184, -1, + 177, 179, 181, -1, 177, 178, 179, -1, + 177, 883, 882, -1, 177, 882, 178, -1, + 186, 179, 430, -1, 186, 181, 179, -1, + 186, 430, 866, -1, 186, 185, 181, -1, + 180, 429, 184, -1, 180, 184, 181, -1, + 180, 181, 185, -1, 180, 752, 429, -1, + 180, 185, 182, -1, 180, 182, 752, -1, + 183, 184, 429, -1, 183, 429, 862, -1, + 183, 883, 184, -1, 183, 888, 883, -1, + 183, 850, 888, -1, 183, 862, 850, -1, + 877, 1939, 248, -1, 624, 431, 248, -1, + 428, 866, 2753, -1, 428, 427, 185, -1, + 428, 185, 186, -1, 428, 186, 866, -1, + 432, 187, 434, -1, 432, 433, 187, -1, + 878, 431, 1639, -1, 878, 248, 431, -1, + 878, 877, 248, -1, 880, 188, 433, -1, + 1647, 1645, 188, -1, 1647, 188, 880, -1, + 436, 189, 435, -1, 436, 438, 189, -1, + 436, 439, 438, -1, 450, 452, 190, -1, + 450, 190, 438, -1, 455, 191, 456, -1, + 455, 440, 191, -1, 1559, 1679, 1549, -1, + 1677, 1678, 444, -1, 1677, 444, 857, -1, + 901, 895, 902, -1, 1667, 907, 1666, -1, + 911, 1666, 443, -1, 1660, 2295, 913, -1, + 910, 2677, 1661, -1, 192, 442, 908, -1, + 192, 921, 197, -1, 192, 197, 463, -1, + 192, 463, 442, -1, 192, 908, 1671, -1, + 192, 1671, 921, -1, 920, 924, 921, -1, + 449, 444, 447, -1, 437, 858, 439, -1, + 437, 890, 425, -1, 437, 425, 855, -1, + 437, 855, 858, -1, 193, 453, 194, -1, + 193, 447, 1678, -1, 193, 448, 447, -1, + 193, 194, 448, -1, 193, 1678, 1676, -1, + 193, 1676, 453, -1, 458, 195, 453, -1, + 458, 457, 195, -1, 461, 925, 196, -1, + 461, 196, 462, -1, 461, 463, 197, -1, + 461, 197, 925, -1, 201, 487, 202, -1, + 201, 483, 487, -1, 201, 946, 483, -1, + 2322, 467, 940, -1, 466, 2326, 955, -1, + 466, 955, 467, -1, 611, 957, 2329, -1, + 611, 955, 957, -1, 611, 467, 955, -1, + 611, 940, 467, -1, 198, 199, 200, -1, + 198, 200, 202, -1, 198, 202, 199, -1, + 469, 213, 953, -1, 469, 200, 199, -1, + 469, 199, 212, -1, 469, 212, 213, -1, + 945, 200, 469, -1, 945, 469, 470, -1, + 945, 946, 201, -1, 945, 202, 200, -1, + 945, 201, 202, -1, 1696, 2780, 203, -1, + 1696, 203, 1699, -1, 472, 471, 2780, -1, + 472, 945, 470, -1, 472, 2780, 945, -1, + 1698, 1699, 204, -1, 1698, 2326, 1697, -1, + 1698, 204, 2326, -1, 475, 474, 1694, -1, + 2763, 1713, 1695, -1, 205, 1713, 206, -1, + 205, 206, 1695, -1, 205, 1695, 1713, -1, + 497, 211, 476, -1, 207, 474, 208, -1, + 207, 208, 306, -1, 207, 480, 474, -1, + 207, 306, 480, -1, 492, 478, 484, -1, + 492, 484, 209, -1, 485, 478, 486, -1, + 485, 484, 478, -1, 210, 483, 938, -1, + 210, 484, 483, -1, 210, 209, 484, -1, + 210, 492, 209, -1, 490, 210, 938, -1, + 490, 492, 210, -1, 481, 491, 939, -1, + 481, 495, 480, -1, 481, 496, 495, -1, + 481, 939, 496, -1, 1726, 244, 2329, -1, + 1726, 1729, 1111, -1, 1726, 1111, 244, -1, + 952, 478, 211, -1, 952, 211, 497, -1, + 952, 212, 478, -1, 952, 213, 212, -1, + 952, 953, 213, -1, 2260, 498, 2259, -1, + 2260, 958, 498, -1, 964, 717, 214, -1, + 964, 1269, 500, -1, 964, 214, 1269, -1, + 963, 713, 215, -1, 963, 215, 717, -1, + 963, 717, 964, -1, 502, 216, 220, -1, + 502, 504, 217, -1, 502, 217, 216, -1, + 502, 220, 503, -1, 218, 512, 394, -1, + 218, 393, 511, -1, 218, 511, 512, -1, + 218, 815, 393, -1, 218, 394, 395, -1, + 218, 395, 815, -1, 219, 394, 512, -1, + 219, 512, 1760, -1, 219, 1760, 1761, -1, + 510, 1002, 509, -1, 510, 1761, 1002, -1, + 510, 219, 1761, -1, 507, 394, 219, -1, + 507, 219, 510, -1, 969, 511, 970, -1, + 3055, 983, 3056, -1, 2368, 515, 983, -1, + 975, 983, 515, -1, 2363, 1744, 516, -1, + 1767, 1765, 523, -1, 999, 997, 1001, -1, + 1003, 503, 2389, -1, 1006, 996, 1764, -1, + 1006, 220, 996, -1, 1006, 503, 220, -1, + 1006, 2389, 503, -1, 1763, 523, 1765, -1, + 998, 1764, 996, -1, 998, 995, 523, -1, + 998, 523, 1763, -1, 998, 1763, 1764, -1, + 221, 525, 1013, -1, 221, 1013, 387, -1, + 1007, 386, 1776, -1, 1007, 387, 386, -1, + 1007, 221, 387, -1, 1007, 1008, 221, -1, + 534, 524, 533, -1, 534, 1018, 2802, -1, + 1571, 3047, 808, -1, 1782, 524, 529, -1, + 1782, 1784, 524, -1, 1009, 526, 1783, -1, + 528, 525, 221, -1, 528, 221, 1008, -1, + 528, 1011, 525, -1, 528, 529, 1011, -1, + 530, 526, 568, -1, 530, 2378, 1762, -1, + 1769, 533, 1784, -1, 2801, 2802, 1018, -1, + 990, 533, 1769, -1, 990, 1769, 1770, -1, + 1022, 1023, 235, -1, 1022, 235, 535, -1, + 1025, 1021, 1065, -1, 1067, 535, 1475, -1, + 1041, 1028, 1043, -1, 537, 2372, 1080, -1, + 537, 1080, 551, -1, 1055, 1042, 1043, -1, + 1055, 1043, 1054, -1, 222, 1058, 1061, -1, + 222, 504, 542, -1, 222, 542, 1058, -1, + 222, 223, 504, -1, 222, 224, 223, -1, + 222, 1061, 224, -1, 2399, 1075, 1073, -1, + 2399, 2400, 1075, -1, 545, 1077, 555, -1, + 545, 555, 556, -1, 544, 556, 546, -1, + 544, 546, 1795, -1, 544, 1795, 1071, -1, + 544, 545, 556, -1, 1807, 2410, 548, -1, + 557, 546, 556, -1, 557, 1805, 1806, -1, + 549, 546, 557, -1, 549, 557, 1806, -1, + 1045, 1046, 551, -1, 1087, 2309, 2310, -1, + 2428, 1081, 1812, -1, 1039, 536, 1038, -1, + 1039, 225, 536, -1, 1039, 560, 225, -1, + 1039, 1040, 560, -1, 566, 2423, 1805, -1, + 566, 605, 606, -1, 558, 225, 565, -1, + 558, 536, 225, -1, 558, 1035, 536, -1, + 558, 1092, 1035, -1, 559, 560, 1040, -1, + 559, 1040, 1049, -1, 564, 225, 560, -1, + 564, 565, 225, -1, 567, 1808, 561, -1, + 567, 553, 1089, -1, 2417, 1090, 2416, -1, + 1094, 1788, 1786, -1, 2832, 569, 226, -1, + 2832, 226, 2435, -1, 419, 418, 1107, -1, + 419, 1107, 1108, -1, 227, 1099, 572, -1, + 227, 1108, 1099, -1, 227, 572, 1729, -1, + 227, 1729, 1108, -1, 1104, 1096, 228, -1, + 1104, 1105, 1824, -1, 1103, 228, 1122, -1, + 1103, 1104, 228, -1, 1112, 1123, 2450, -1, + 2463, 1100, 2464, -1, 1098, 1100, 2461, -1, + 1098, 570, 572, -1, 1098, 2461, 570, -1, + 230, 2215, 349, -1, 230, 1114, 1115, -1, + 230, 349, 1114, -1, 229, 1469, 2215, -1, + 229, 231, 1469, -1, 229, 2215, 230, -1, + 229, 230, 231, -1, 573, 1115, 588, -1, + 573, 230, 1115, -1, 573, 231, 230, -1, + 573, 600, 231, -1, 242, 1469, 232, -1, + 242, 1468, 1469, -1, 242, 345, 1468, -1, + 242, 232, 240, -1, 242, 241, 345, -1, + 233, 577, 576, -1, 233, 1824, 1105, -1, + 233, 1105, 418, -1, 233, 418, 577, -1, + 575, 1824, 233, -1, 575, 233, 576, -1, + 575, 345, 241, -1, 1823, 1824, 575, -1, + 1823, 241, 237, -1, 1823, 575, 241, -1, + 234, 535, 235, -1, 234, 235, 583, -1, + 234, 583, 1830, -1, 234, 1475, 535, -1, + 234, 1830, 1474, -1, 234, 1474, 1475, -1, + 1829, 1830, 583, -1, 582, 235, 1023, -1, + 582, 583, 235, -1, 582, 236, 585, -1, + 582, 1023, 236, -1, 584, 1841, 1827, -1, + 584, 1842, 1841, -1, 584, 585, 569, -1, + 584, 569, 1842, -1, 593, 601, 1866, -1, + 593, 243, 601, -1, 2465, 2464, 1100, -1, + 1148, 1877, 1147, -1, 1148, 1880, 612, -1, + 1876, 1877, 1148, -1, 1876, 1148, 612, -1, + 1822, 239, 595, -1, 1822, 237, 239, -1, + 1822, 1823, 237, -1, 1132, 595, 1136, -1, + 598, 603, 604, -1, 597, 1136, 595, -1, + 597, 595, 239, -1, 597, 240, 600, -1, + 597, 239, 240, -1, 238, 240, 239, -1, + 238, 239, 241, -1, 238, 242, 240, -1, + 238, 241, 242, -1, 1843, 2837, 1850, -1, + 1843, 2433, 2836, -1, 1843, 2836, 2837, -1, + 594, 604, 243, -1, 594, 1134, 598, -1, + 594, 598, 604, -1, 594, 243, 593, -1, + 602, 1850, 2837, -1, 602, 601, 243, -1, + 1849, 243, 604, -1, 1849, 1850, 602, -1, + 1849, 602, 243, -1, 1140, 1077, 1141, -1, + 1140, 555, 1077, -1, 1140, 605, 555, -1, + 1870, 1144, 1135, -1, 608, 2329, 244, -1, + 608, 1111, 609, -1, 608, 244, 1111, -1, + 2784, 2328, 2329, -1, 2784, 2329, 608, -1, + 1902, 2507, 2795, -1, 1902, 2333, 1166, -1, + 1889, 1166, 2333, -1, 699, 616, 291, -1, + 1154, 1160, 1152, -1, 1154, 1159, 1160, -1, + 1154, 1157, 1159, -1, 1151, 291, 616, -1, + 1151, 1155, 290, -1, 1151, 290, 291, -1, + 1175, 702, 614, -1, 1175, 614, 1170, -1, + 1719, 613, 1720, -1, 1173, 616, 699, -1, + 1179, 1230, 2044, -1, 1179, 1916, 1230, -1, + 245, 247, 1230, -1, 245, 1230, 1916, -1, + 245, 1916, 247, -1, 617, 3124, 246, -1, + 617, 246, 247, -1, 617, 247, 1917, -1, + 617, 1917, 1182, -1, 1936, 618, 2550, -1, + 1944, 1945, 1185, -1, 1188, 1940, 1944, -1, + 1188, 1944, 1185, -1, 1938, 248, 1939, -1, + 1938, 624, 248, -1, 1959, 865, 864, -1, + 1963, 1202, 1196, -1, 1963, 1196, 1195, -1, + 627, 249, 253, -1, 627, 250, 251, -1, + 627, 251, 249, -1, 627, 1204, 252, -1, + 627, 252, 250, -1, 1984, 253, 1986, -1, + 1984, 627, 253, -1, 628, 682, 629, -1, + 628, 300, 682, -1, 1977, 254, 1205, -1, + 1977, 629, 254, -1, 2122, 256, 2121, -1, + 255, 1973, 256, -1, 255, 1972, 1973, -1, + 255, 2123, 1972, -1, 255, 256, 2122, -1, + 255, 2122, 2123, -1, 257, 258, 259, -1, + 257, 259, 264, -1, 257, 659, 258, -1, + 257, 260, 659, -1, 257, 265, 260, -1, + 257, 264, 265, -1, 261, 263, 262, -1, + 261, 264, 263, -1, 261, 262, 265, -1, + 261, 265, 264, -1, 266, 269, 267, -1, + 266, 633, 269, -1, 266, 267, 268, -1, + 266, 268, 633, -1, 631, 632, 269, -1, + 631, 269, 633, -1, 2600, 2038, 2607, -1, + 2600, 2607, 2601, -1, 2041, 2607, 2034, -1, + 2041, 2601, 2607, -1, 639, 279, 1994, -1, + 639, 640, 279, -1, 639, 1994, 271, -1, + 639, 272, 2073, -1, 1992, 1994, 1989, -1, + 1993, 1997, 271, -1, 1993, 271, 1994, -1, + 270, 271, 1997, -1, 270, 1997, 272, -1, + 270, 639, 271, -1, 270, 272, 639, -1, + 2075, 1996, 1253, -1, 2075, 272, 1996, -1, + 2075, 2073, 272, -1, 1238, 638, 1239, -1, + 1249, 654, 280, -1, 2017, 1244, 2018, -1, + 2017, 652, 1244, -1, 2017, 623, 652, -1, + 2017, 2016, 623, -1, 2014, 1201, 2015, -1, + 1326, 2019, 1226, -1, 1326, 637, 1327, -1, + 1326, 1226, 637, -1, 643, 1217, 642, -1, + 643, 2006, 1217, -1, 643, 2578, 2006, -1, + 1240, 1248, 1250, -1, 1240, 642, 1248, -1, + 1240, 1239, 642, -1, 646, 2053, 2052, -1, + 646, 2052, 2029, -1, 646, 2605, 2604, -1, + 646, 2029, 2605, -1, 1234, 648, 273, -1, + 2037, 1234, 273, -1, 2037, 273, 2607, -1, + 651, 2045, 648, -1, 651, 648, 1234, -1, + 622, 618, 653, -1, 622, 2550, 618, -1, + 622, 652, 623, -1, 622, 653, 652, -1, + 275, 274, 278, -1, 275, 645, 1254, -1, + 275, 662, 274, -1, 275, 1254, 662, -1, + 1212, 1211, 645, -1, 1212, 278, 1210, -1, + 1212, 275, 278, -1, 1212, 645, 275, -1, + 2076, 1254, 645, -1, 276, 640, 277, -1, + 276, 277, 636, -1, 276, 636, 1210, -1, + 276, 1210, 278, -1, 276, 278, 279, -1, + 276, 279, 640, -1, 1241, 280, 1242, -1, + 1241, 1249, 280, -1, 1241, 1250, 1249, -1, + 2055, 1244, 652, -1, 2937, 2061, 654, -1, + 2065, 650, 281, -1, 2065, 281, 2063, -1, + 647, 1242, 281, -1, 647, 281, 650, -1, + 647, 1243, 1242, -1, 647, 650, 2032, -1, + 684, 656, 683, -1, 684, 660, 658, -1, + 680, 660, 684, -1, 284, 658, 660, -1, + 284, 1996, 1999, -1, 284, 1253, 1996, -1, + 284, 660, 1253, -1, 282, 283, 658, -1, + 282, 658, 284, -1, 282, 284, 1999, -1, + 282, 2607, 283, -1, 282, 1999, 2607, -1, + 2035, 2034, 2607, -1, 2035, 2607, 2606, -1, + 1207, 1989, 662, -1, 1301, 285, 1300, -1, + 1301, 1302, 285, -1, 663, 699, 291, -1, + 719, 715, 714, -1, 719, 710, 1266, -1, + 719, 1266, 1305, -1, 2084, 2081, 289, -1, + 2084, 667, 2080, -1, 286, 289, 290, -1, + 286, 290, 1155, -1, 286, 1155, 287, -1, + 286, 287, 667, -1, 286, 667, 2084, -1, + 286, 2084, 289, -1, 288, 665, 664, -1, + 288, 289, 665, -1, 288, 290, 289, -1, + 288, 664, 663, -1, 288, 291, 290, -1, + 288, 663, 291, -1, 1309, 2608, 2609, -1, + 668, 1272, 2096, -1, 2617, 2616, 1270, -1, + 670, 423, 292, -1, 670, 292, 671, -1, + 1617, 293, 841, -1, 1617, 1281, 293, -1, + 693, 1290, 689, -1, 693, 689, 294, -1, + 693, 294, 682, -1, 693, 682, 295, -1, + 693, 295, 692, -1, 1289, 674, 689, -1, + 1289, 689, 1290, -1, 1321, 674, 1322, -1, + 1321, 675, 674, -1, 1319, 722, 296, -1, + 1319, 296, 298, -1, 1319, 298, 675, -1, + 677, 678, 297, -1, 676, 326, 688, -1, + 676, 677, 297, -1, 676, 297, 298, -1, + 676, 298, 324, -1, 676, 324, 326, -1, + 686, 299, 1251, -1, 686, 688, 299, -1, + 686, 1251, 680, -1, 691, 1286, 300, -1, + 691, 300, 628, -1, 1285, 692, 1286, -1, + 701, 697, 702, -1, 301, 696, 695, -1, + 301, 302, 304, -1, 301, 695, 302, -1, + 301, 304, 303, -1, 301, 613, 696, -1, + 301, 303, 613, -1, 1296, 309, 304, -1, + 1296, 304, 1292, -1, 305, 308, 1299, -1, + 305, 306, 308, -1, 305, 1299, 476, -1, + 305, 476, 306, -1, 307, 1297, 1299, -1, + 307, 1299, 308, -1, 307, 308, 1297, -1, + 704, 705, 1713, -1, 706, 1297, 705, -1, + 706, 1296, 1297, -1, 706, 1715, 309, -1, + 706, 309, 1296, -1, 310, 314, 1293, -1, + 310, 311, 314, -1, 310, 1293, 1292, -1, + 310, 1292, 311, -1, 477, 476, 314, -1, + 477, 314, 312, -1, 477, 312, 320, -1, + 477, 320, 963, -1, 477, 963, 966, -1, + 313, 1293, 314, -1, 313, 1294, 1293, -1, + 313, 314, 1294, -1, 315, 709, 316, -1, + 315, 710, 709, -1, 315, 1261, 710, -1, + 315, 316, 317, -1, 315, 317, 318, -1, + 315, 318, 1261, -1, 319, 320, 708, -1, + 319, 708, 713, -1, 319, 963, 320, -1, + 319, 713, 963, -1, 712, 710, 719, -1, + 712, 719, 714, -1, 712, 713, 708, -1, + 718, 717, 321, -1, 718, 321, 715, -1, + 718, 715, 719, -1, 2086, 322, 2963, -1, + 2086, 2087, 322, -1, 1323, 1322, 721, -1, + 2099, 724, 2616, -1, 325, 327, 328, -1, + 325, 328, 326, -1, 323, 324, 327, -1, + 323, 327, 325, -1, 323, 326, 324, -1, + 323, 325, 326, -1, 727, 1276, 2108, -1, + 727, 2107, 2026, -1, 727, 2108, 2107, -1, + 726, 1324, 725, -1, 726, 1276, 727, -1, + 728, 327, 1324, -1, 728, 1324, 2021, -1, + 728, 328, 327, -1, 728, 2125, 328, -1, + 2093, 2092, 1153, -1, 2093, 1153, 1152, -1, + 2093, 1152, 329, -1, 2093, 329, 2094, -1, + 1926, 2571, 1213, -1, 1445, 334, 1446, -1, + 1445, 2130, 334, -1, 2516, 2654, 2653, -1, + 2516, 1331, 2654, -1, 2516, 2518, 1899, -1, + 2516, 1899, 1331, -1, 1934, 1335, 1358, -1, + 1934, 1358, 1935, -1, 738, 739, 741, -1, + 738, 1221, 740, -1, 1337, 742, 2524, -1, + 2027, 2026, 2107, -1, 2027, 2107, 2106, -1, + 1341, 745, 1344, -1, 1355, 1342, 1354, -1, + 2613, 1342, 1343, -1, 2613, 3198, 1342, -1, + 736, 735, 2028, -1, 736, 2027, 2106, -1, + 736, 2028, 2027, -1, 736, 2106, 1275, -1, + 734, 3142, 2613, -1, 734, 2613, 1343, -1, + 1364, 2642, 739, -1, 2641, 741, 739, -1, + 2641, 739, 2642, -1, 2010, 740, 2008, -1, + 2581, 2137, 2009, -1, 1360, 742, 1361, -1, + 2138, 2581, 2582, -1, 2138, 2137, 2581, -1, + 932, 747, 330, -1, 932, 330, 331, -1, + 932, 331, 933, -1, 1368, 333, 1369, -1, + 749, 332, 333, -1, 749, 333, 1368, -1, + 749, 1378, 464, -1, 749, 464, 332, -1, + 1395, 751, 1394, -1, 2694, 2691, 2143, -1, + 2694, 2143, 1386, -1, 1405, 1631, 1632, -1, + 1405, 1383, 1631, -1, 1405, 1386, 1383, -1, + 1405, 2694, 1386, -1, 917, 464, 1378, -1, + 759, 2676, 2677, -1, 759, 2677, 910, -1, + 759, 1389, 2676, -1, 1402, 1404, 548, -1, + 1797, 550, 1403, -1, 2906, 1904, 1401, -1, + 1408, 2129, 1442, -1, 2557, 2556, 1192, -1, + 2281, 2280, 1191, -1, 2167, 765, 1417, -1, + 1312, 334, 2130, -1, 1450, 755, 859, -1, + 1450, 2187, 755, -1, 2276, 2275, 2189, -1, + 2171, 334, 1312, -1, 2171, 1446, 334, -1, + 767, 335, 1455, -1, 767, 769, 335, -1, + 768, 983, 336, -1, 768, 336, 769, -1, + 337, 1453, 338, -1, 337, 339, 1453, -1, + 337, 340, 339, -1, 337, 341, 340, -1, + 337, 338, 341, -1, 1460, 2203, 1461, -1, + 3013, 2203, 2198, -1, 3013, 2198, 2208, -1, + 1542, 1465, 798, -1, 1542, 798, 1538, -1, + 2711, 771, 2712, -1, 2711, 3170, 771, -1, + 344, 1465, 1540, -1, 344, 771, 3170, -1, + 344, 3170, 342, -1, 344, 343, 1465, -1, + 344, 342, 343, -1, 770, 344, 1540, -1, + 770, 771, 344, -1, 779, 773, 777, -1, + 579, 345, 575, -1, 579, 580, 346, -1, + 579, 347, 345, -1, 579, 346, 347, -1, + 2214, 1510, 348, -1, 2214, 349, 2215, -1, + 2214, 348, 1114, -1, 2214, 1114, 349, -1, + 1467, 1468, 350, -1, 1467, 350, 352, -1, + 1467, 352, 1603, -1, 2218, 1598, 2217, -1, + 2218, 780, 1598, -1, 1601, 1598, 780, -1, + 1601, 780, 1603, -1, 781, 1467, 1603, -1, + 781, 1466, 1467, -1, 351, 1603, 352, -1, + 351, 352, 580, -1, 351, 1592, 1603, -1, + 351, 580, 1592, -1, 586, 353, 2442, -1, + 586, 1491, 353, -1, 586, 587, 1491, -1, + 586, 2442, 2443, -1, 1471, 406, 1472, -1, + 1471, 354, 406, -1, 1471, 1474, 1831, -1, + 1471, 1831, 354, -1, 2222, 355, 1484, -1, + 2222, 820, 2221, -1, 2222, 2220, 355, -1, + 396, 399, 356, -1, 396, 356, 357, -1, + 396, 357, 817, -1, 396, 398, 399, -1, + 1589, 358, 1588, -1, 1589, 1478, 359, -1, + 1589, 359, 358, -1, 1483, 1484, 2726, -1, + 1483, 2726, 1477, -1, 1489, 1524, 1525, -1, + 1489, 1525, 360, -1, 1489, 360, 1490, -1, + 363, 1461, 1523, -1, 363, 364, 1461, -1, + 1496, 1497, 1499, -1, 1516, 411, 412, -1, + 1516, 412, 1494, -1, 1516, 1598, 1597, -1, + 1516, 1597, 411, -1, 784, 786, 402, -1, + 784, 402, 401, -1, 784, 401, 785, -1, + 361, 786, 787, -1, 361, 365, 362, -1, + 361, 787, 365, -1, 361, 362, 402, -1, + 361, 402, 786, -1, 1522, 363, 1523, -1, + 1522, 1499, 364, -1, 1522, 364, 363, -1, + 1521, 379, 787, -1, 380, 787, 379, -1, + 380, 365, 787, -1, 380, 788, 376, -1, + 380, 366, 365, -1, 380, 376, 367, -1, + 380, 367, 366, -1, 368, 370, 369, -1, + 368, 1523, 370, -1, 368, 369, 371, -1, + 368, 1521, 1523, -1, 368, 379, 1521, -1, + 368, 371, 790, -1, 368, 790, 379, -1, + 789, 1526, 372, -1, 789, 372, 373, -1, + 789, 373, 374, -1, 789, 374, 375, -1, + 789, 375, 376, -1, 789, 376, 788, -1, + 795, 820, 796, -1, 797, 796, 377, -1, + 797, 377, 1526, -1, 797, 1526, 2224, -1, + 799, 378, 2719, -1, 799, 2719, 1533, -1, + 799, 800, 378, -1, 1537, 2719, 801, -1, + 1537, 1533, 2719, -1, 1537, 1538, 1533, -1, + 792, 379, 790, -1, 792, 788, 380, -1, + 792, 380, 379, -1, 792, 2722, 788, -1, + 1547, 2719, 1546, -1, 3017, 1546, 2202, -1, + 381, 803, 804, -1, 381, 383, 1552, -1, + 381, 1552, 803, -1, 381, 389, 383, -1, + 381, 382, 389, -1, 381, 804, 382, -1, + 2298, 1778, 804, -1, 802, 805, 2238, -1, + 802, 1551, 383, -1, 388, 383, 389, -1, + 388, 802, 383, -1, 388, 805, 802, -1, + 1556, 806, 1015, -1, 1556, 1015, 2231, -1, + 384, 2231, 1015, -1, 384, 809, 906, -1, + 384, 906, 2234, -1, 384, 2234, 2231, -1, + 384, 1575, 809, -1, 384, 1015, 1575, -1, + 385, 386, 387, -1, 385, 387, 1014, -1, + 385, 1014, 806, -1, 385, 806, 805, -1, + 385, 805, 388, -1, 385, 389, 386, -1, + 385, 388, 389, -1, 1582, 391, 1581, -1, + 1582, 817, 390, -1, 1582, 390, 391, -1, + 392, 391, 2726, -1, 392, 1581, 391, -1, + 1560, 2726, 2248, -1, 1560, 392, 2726, -1, + 1560, 1581, 392, -1, 2245, 514, 2246, -1, + 2245, 2248, 983, -1, 2245, 983, 514, -1, + 1578, 393, 815, -1, 505, 1579, 1564, -1, + 505, 393, 1578, -1, 505, 1578, 1579, -1, + 505, 970, 393, -1, 517, 812, 519, -1, + 517, 896, 812, -1, 517, 894, 896, -1, + 517, 518, 894, -1, 813, 808, 811, -1, + 397, 398, 395, -1, 397, 507, 1586, -1, + 397, 395, 394, -1, 397, 394, 507, -1, + 816, 815, 395, -1, 816, 395, 398, -1, + 816, 396, 817, -1, 816, 398, 396, -1, + 1587, 397, 1586, -1, 1587, 398, 397, -1, + 1587, 1588, 399, -1, 1587, 399, 398, -1, + 400, 401, 402, -1, 400, 402, 403, -1, + 400, 403, 404, -1, 400, 405, 401, -1, + 400, 406, 405, -1, 400, 404, 406, -1, + 407, 1480, 410, -1, 407, 408, 818, -1, + 407, 818, 1486, -1, 407, 1486, 1480, -1, + 407, 409, 408, -1, 407, 410, 409, -1, + 1481, 821, 410, -1, 1481, 410, 1480, -1, + 1594, 829, 822, -1, 826, 2734, 2252, -1, + 2732, 2734, 826, -1, 828, 411, 822, -1, + 828, 822, 829, -1, 828, 412, 411, -1, + 828, 832, 412, -1, 831, 836, 1457, -1, + 831, 1457, 1456, -1, 831, 1456, 413, -1, + 831, 413, 832, -1, 823, 415, 837, -1, + 823, 825, 415, -1, 823, 2732, 825, -1, + 823, 1590, 2732, -1, 1606, 1607, 833, -1, + 414, 837, 415, -1, 414, 416, 837, -1, + 414, 415, 417, -1, 414, 417, 416, -1, + 1593, 950, 1612, -1, 1723, 1592, 418, -1, + 1723, 418, 419, -1, 1723, 419, 1108, -1, + 1723, 1108, 1729, -1, 839, 847, 846, -1, + 2740, 420, 2252, -1, 2740, 2254, 846, -1, + 2740, 846, 421, -1, 2740, 421, 420, -1, + 2628, 422, 423, -1, 2628, 670, 2626, -1, + 2628, 423, 670, -1, 2628, 2624, 422, -1, + 960, 1623, 1625, -1, 960, 1619, 1623, -1, + 843, 671, 842, -1, 1622, 1623, 1619, -1, + 849, 424, 425, -1, 849, 852, 424, -1, + 849, 425, 890, -1, 849, 890, 889, -1, + 1692, 426, 1688, -1, 1692, 855, 426, -1, + 860, 859, 427, -1, 860, 428, 2753, -1, + 860, 427, 428, -1, 1392, 429, 752, -1, + 1392, 862, 429, -1, 1628, 755, 2187, -1, + 766, 1313, 2265, -1, 766, 2265, 1628, -1, + 766, 1628, 2187, -1, 766, 2187, 2186, -1, + 766, 1312, 1313, -1, 1644, 868, 1645, -1, + 872, 430, 869, -1, 872, 866, 430, -1, + 871, 870, 868, -1, 1638, 1639, 431, -1, + 1638, 431, 624, -1, 1638, 624, 1636, -1, + 875, 433, 432, -1, 875, 880, 433, -1, + 875, 432, 434, -1, 875, 434, 876, -1, + 879, 878, 1639, -1, 879, 1639, 1649, -1, + 879, 1649, 1647, -1, 879, 1647, 880, -1, + 886, 436, 435, -1, 886, 435, 881, -1, + 885, 439, 436, -1, 885, 437, 439, -1, + 885, 890, 437, -1, 885, 436, 886, -1, + 445, 438, 439, -1, 445, 450, 438, -1, + 445, 449, 450, -1, 445, 439, 858, -1, + 1680, 1679, 1559, -1, 1680, 1559, 1557, -1, + 807, 929, 2233, -1, 807, 928, 929, -1, + 807, 1654, 928, -1, 807, 1652, 1654, -1, + 814, 905, 906, -1, 814, 893, 905, -1, + 814, 906, 809, -1, 814, 809, 813, -1, + 892, 905, 893, -1, 892, 904, 905, -1, + 898, 899, 440, -1, 898, 440, 904, -1, + 898, 892, 901, -1, 898, 904, 892, -1, + 1653, 904, 440, -1, 1653, 455, 1655, -1, + 1653, 440, 455, -1, 984, 3048, 3050, -1, + 984, 441, 985, -1, 984, 3050, 441, -1, + 2306, 907, 1667, -1, 2291, 913, 909, -1, + 919, 443, 442, -1, 919, 911, 443, -1, + 919, 442, 918, -1, 2296, 2295, 1660, -1, + 915, 912, 911, -1, 915, 911, 919, -1, + 1668, 1094, 2299, -1, 1668, 1083, 1788, -1, + 1668, 1788, 1094, -1, 1084, 1673, 1088, -1, + 1084, 1085, 920, -1, 923, 924, 920, -1, + 923, 920, 1085, -1, 856, 444, 449, -1, + 856, 857, 444, -1, 856, 445, 858, -1, + 856, 449, 445, -1, 446, 447, 448, -1, + 446, 449, 447, -1, 446, 450, 449, -1, + 446, 448, 451, -1, 446, 451, 452, -1, + 446, 452, 450, -1, 927, 453, 1676, -1, + 927, 458, 453, -1, 459, 458, 927, -1, + 459, 927, 928, -1, 459, 1654, 1655, -1, + 459, 928, 1654, -1, 454, 455, 456, -1, + 454, 456, 457, -1, 454, 457, 458, -1, + 454, 458, 459, -1, 454, 1655, 455, -1, + 454, 459, 1655, -1, 460, 461, 462, -1, + 460, 917, 918, -1, 460, 918, 463, -1, + 460, 463, 461, -1, 460, 462, 464, -1, + 460, 464, 917, -1, 1682, 1549, 1690, -1, + 935, 930, 937, -1, 2227, 934, 2226, -1, + 2227, 2225, 930, -1, 2227, 930, 935, -1, + 2227, 935, 934, -1, 465, 2226, 934, -1, + 465, 926, 1554, -1, 465, 1554, 2226, -1, + 465, 933, 926, -1, 465, 934, 933, -1, + 1693, 1694, 939, -1, 943, 483, 946, -1, + 943, 946, 947, -1, 943, 938, 483, -1, + 2774, 2775, 2846, -1, 2325, 466, 467, -1, + 2325, 467, 2324, -1, 2325, 2326, 466, -1, + 2323, 467, 2322, -1, 2323, 2324, 467, -1, + 468, 469, 953, -1, 468, 470, 469, -1, + 468, 953, 471, -1, 468, 472, 470, -1, + 468, 471, 472, -1, 473, 1695, 474, -1, + 473, 474, 475, -1, 473, 1694, 1695, -1, + 473, 475, 1694, -1, 1732, 1733, 497, -1, + 949, 497, 476, -1, 949, 476, 477, -1, + 949, 477, 966, -1, 949, 1732, 497, -1, + 2789, 1712, 2790, -1, 493, 478, 492, -1, + 493, 479, 478, -1, 493, 480, 479, -1, + 493, 481, 480, -1, 493, 491, 481, -1, + 482, 483, 484, -1, 482, 484, 485, -1, + 482, 485, 486, -1, 482, 486, 487, -1, + 482, 487, 483, -1, 488, 939, 491, -1, + 488, 491, 490, -1, 488, 938, 939, -1, + 488, 490, 938, -1, 489, 490, 491, -1, + 489, 492, 490, -1, 489, 491, 493, -1, + 489, 493, 492, -1, 494, 1694, 495, -1, + 494, 495, 496, -1, 494, 939, 1694, -1, + 494, 496, 939, -1, 956, 497, 1733, -1, + 956, 952, 497, -1, 2257, 2259, 845, -1, + 2257, 845, 847, -1, 2257, 847, 839, -1, + 2257, 839, 2258, -1, 961, 498, 1279, -1, + 961, 2259, 498, -1, 961, 845, 2259, -1, + 961, 2350, 845, -1, 1278, 498, 958, -1, + 1278, 1279, 498, -1, 1278, 958, 967, -1, + 1278, 967, 1280, -1, 965, 1282, 1280, -1, + 965, 499, 1282, -1, 965, 500, 499, -1, + 965, 964, 500, -1, 501, 502, 503, -1, + 501, 1004, 542, -1, 501, 542, 504, -1, + 501, 504, 502, -1, 501, 1003, 1004, -1, + 501, 503, 1003, -1, 1562, 2807, 1565, -1, + 1563, 970, 505, -1, 1563, 505, 1564, -1, + 2353, 2356, 1565, -1, 506, 1586, 507, -1, + 506, 508, 1585, -1, 506, 1585, 1586, -1, + 506, 509, 508, -1, 506, 510, 509, -1, + 506, 507, 510, -1, 531, 511, 969, -1, + 531, 1760, 512, -1, 531, 512, 511, -1, + 531, 1759, 1760, -1, 513, 983, 3055, -1, + 513, 2368, 983, -1, 513, 3055, 2368, -1, + 981, 977, 2246, -1, 981, 983, 982, -1, + 981, 514, 983, -1, 981, 2246, 514, -1, + 974, 515, 2368, -1, 974, 2368, 2369, -1, + 974, 975, 515, -1, 979, 975, 974, -1, + 2358, 2363, 516, -1, 2358, 808, 3047, -1, + 2358, 516, 811, -1, 2358, 811, 808, -1, + 2362, 1744, 2363, -1, 520, 1747, 521, -1, + 520, 517, 519, -1, 520, 521, 518, -1, + 520, 518, 517, -1, 1745, 519, 1744, -1, + 1745, 520, 519, -1, 1745, 1747, 520, -1, + 1748, 521, 1747, -1, 1748, 985, 522, -1, + 1748, 522, 521, -1, 993, 987, 992, -1, + 1766, 1767, 986, -1, 1766, 986, 993, -1, + 988, 523, 995, -1, 988, 986, 1767, -1, + 988, 1767, 523, -1, 988, 995, 1756, -1, + 1755, 1756, 995, -1, 1005, 2372, 537, -1, + 1005, 537, 541, -1, 2385, 1003, 2389, -1, + 2819, 1763, 1765, -1, 1774, 568, 526, -1, + 1774, 526, 1009, -1, 1010, 529, 524, -1, + 1010, 1011, 529, -1, 1010, 534, 2802, -1, + 1010, 524, 534, -1, 3046, 3047, 1571, -1, + 1012, 525, 1011, -1, 1573, 1013, 525, -1, + 1573, 525, 1012, -1, 1781, 530, 1762, -1, + 1781, 1783, 526, -1, 1781, 526, 530, -1, + 527, 1009, 1783, -1, 527, 529, 528, -1, + 527, 1008, 1009, -1, 527, 528, 1008, -1, + 527, 1782, 529, -1, 527, 1783, 1782, -1, + 1789, 568, 1786, -1, 1789, 530, 568, -1, + 1789, 2378, 530, -1, 1738, 1743, 1742, -1, + 972, 992, 987, -1, 972, 991, 992, -1, + 972, 1019, 1017, -1, 972, 1017, 991, -1, + 971, 987, 1759, -1, 971, 969, 2355, -1, + 971, 531, 969, -1, 971, 1759, 531, -1, + 532, 991, 1017, -1, 532, 990, 991, -1, + 532, 1017, 1018, -1, 532, 533, 990, -1, + 532, 534, 533, -1, 532, 1018, 534, -1, + 1064, 535, 1067, -1, 1064, 1022, 535, -1, + 1064, 1065, 1021, -1, 1064, 1021, 1022, -1, + 1027, 1021, 1025, -1, 1027, 1029, 1032, -1, + 1031, 1029, 1038, -1, 1031, 1032, 1029, -1, + 1031, 1038, 536, -1, 1031, 536, 1035, -1, + 1037, 1028, 1041, -1, 1037, 1038, 1029, -1, + 1048, 1049, 1040, -1, 538, 541, 537, -1, + 538, 1046, 1042, -1, 538, 551, 1046, -1, + 538, 537, 551, -1, 539, 1042, 1055, -1, + 539, 538, 1042, -1, 539, 541, 538, -1, + 539, 1057, 541, -1, 1059, 539, 1055, -1, + 1059, 1057, 539, -1, 540, 541, 1057, -1, + 540, 1004, 1005, -1, 540, 1005, 541, -1, + 540, 542, 1004, -1, 540, 1058, 542, -1, + 540, 1057, 1058, -1, 543, 774, 1053, -1, + 543, 1025, 1065, -1, 543, 1053, 1026, -1, + 543, 1026, 1025, -1, 1066, 543, 1065, -1, + 1066, 774, 543, -1, 1052, 1053, 774, -1, + 1052, 774, 779, -1, 2392, 2399, 1073, -1, + 1078, 1075, 2400, -1, 1076, 1073, 1075, -1, + 1076, 1077, 545, -1, 1072, 545, 544, -1, + 1072, 1073, 1076, -1, 1072, 1076, 545, -1, + 1072, 544, 1071, -1, 762, 548, 2410, -1, + 762, 2410, 2411, -1, 762, 2411, 909, -1, + 762, 1402, 548, -1, 1656, 2416, 1090, -1, + 1794, 1795, 546, -1, 1794, 546, 549, -1, + 1794, 549, 550, -1, 1794, 550, 1797, -1, + 547, 1807, 548, -1, 547, 550, 549, -1, + 547, 1806, 1807, -1, 547, 549, 1806, -1, + 547, 1404, 550, -1, 547, 548, 1404, -1, + 1809, 551, 1080, -1, 1809, 1045, 551, -1, + 1809, 1810, 1045, -1, 1787, 1788, 1083, -1, + 1818, 1792, 1088, -1, 1813, 1817, 1087, -1, + 2430, 553, 1810, -1, 2430, 1089, 553, -1, + 552, 559, 1049, -1, 552, 561, 559, -1, + 552, 553, 567, -1, 552, 567, 561, -1, + 1050, 1045, 1810, -1, 1050, 552, 1049, -1, + 1050, 1810, 553, -1, 1050, 553, 552, -1, + 554, 555, 605, -1, 554, 605, 566, -1, + 554, 566, 1805, -1, 554, 556, 555, -1, + 554, 1805, 557, -1, 554, 557, 556, -1, + 607, 1092, 558, -1, 607, 1143, 1092, -1, + 607, 558, 565, -1, 607, 565, 606, -1, + 562, 560, 559, -1, 562, 564, 560, -1, + 562, 559, 561, -1, 562, 2425, 564, -1, + 2424, 561, 1808, -1, 2424, 562, 561, -1, + 2424, 2425, 562, -1, 563, 564, 2425, -1, + 563, 606, 565, -1, 563, 565, 564, -1, + 563, 566, 606, -1, 563, 2423, 566, -1, + 563, 2425, 2423, -1, 2418, 1089, 2417, -1, + 2418, 1808, 567, -1, 2418, 567, 1089, -1, + 1773, 1094, 1786, -1, 1773, 1786, 568, -1, + 1773, 568, 1774, -1, 2833, 569, 2832, -1, + 2833, 2433, 1842, -1, 2833, 1842, 569, -1, + 1095, 1122, 1096, -1, 1095, 1821, 1122, -1, + 1102, 1103, 1100, -1, 1102, 1099, 1108, -1, + 2449, 2450, 1123, -1, 2449, 1123, 2448, -1, + 1110, 572, 570, -1, 1110, 1111, 572, -1, + 1110, 570, 1123, -1, 1110, 1123, 1112, -1, + 2462, 2461, 1100, -1, 2462, 1100, 2463, -1, + 571, 572, 1099, -1, 571, 1098, 572, -1, + 571, 1099, 1098, -1, 599, 588, 603, -1, + 599, 600, 573, -1, 599, 573, 588, -1, + 599, 603, 598, -1, 574, 575, 576, -1, + 574, 576, 577, -1, 574, 577, 578, -1, + 574, 579, 575, -1, 574, 578, 580, -1, + 574, 580, 579, -1, 581, 583, 582, -1, + 581, 1827, 1829, -1, 581, 1829, 583, -1, + 581, 584, 1827, -1, 581, 582, 585, -1, + 581, 585, 584, -1, 1118, 587, 1838, -1, + 1118, 1491, 587, -1, 1118, 1492, 1491, -1, + 1117, 1838, 1836, -1, 1117, 1118, 1838, -1, + 1837, 586, 2443, -1, 1837, 1838, 587, -1, + 1837, 587, 586, -1, 1116, 588, 1115, -1, + 1116, 1836, 1833, -1, 1120, 603, 588, -1, + 1120, 588, 1116, -1, 1120, 1116, 1833, -1, + 1145, 1129, 1144, -1, 592, 593, 1866, -1, + 592, 1870, 1135, -1, 592, 1866, 1869, -1, + 592, 1869, 1870, -1, 589, 1122, 2465, -1, + 589, 2465, 591, -1, 589, 1103, 1122, -1, + 589, 591, 1103, -1, 590, 2465, 1100, -1, + 590, 591, 2465, -1, 590, 1100, 1103, -1, + 590, 1103, 591, -1, 1905, 2395, 1904, -1, + 2394, 2395, 1905, -1, 1133, 592, 1135, -1, + 1133, 593, 592, -1, 1133, 1134, 594, -1, + 1133, 594, 593, -1, 1131, 1135, 1144, -1, + 1131, 1144, 1129, -1, 1126, 595, 1132, -1, + 1126, 1822, 595, -1, 1126, 1821, 1822, -1, + 1126, 1127, 1821, -1, 596, 1136, 597, -1, + 596, 1134, 1136, -1, 596, 598, 1134, -1, + 596, 599, 598, -1, 596, 597, 600, -1, + 596, 600, 599, -1, 2838, 1865, 601, -1, + 2838, 602, 2837, -1, 2838, 601, 602, -1, + 1848, 603, 1120, -1, 1848, 604, 603, -1, + 1848, 1849, 604, -1, 1142, 606, 605, -1, + 1142, 605, 1140, -1, 1142, 607, 606, -1, + 1142, 1143, 607, -1, 1121, 1875, 1876, -1, + 1121, 2843, 2842, -1, 1121, 612, 2843, -1, + 1121, 1876, 612, -1, 610, 2450, 2451, -1, + 610, 2451, 3031, -1, 3033, 608, 609, -1, + 3033, 2784, 608, -1, 3033, 609, 2450, -1, + 3033, 2450, 610, -1, 3033, 610, 3031, -1, + 2327, 940, 611, -1, 2327, 611, 2329, -1, + 2330, 1880, 1879, -1, 2330, 612, 1880, -1, + 2330, 2843, 612, -1, 2848, 2889, 1709, -1, + 2890, 1708, 1709, -1, 2890, 1709, 2889, -1, + 1883, 2467, 2848, -1, 1883, 2848, 1709, -1, + 1802, 1147, 2406, -1, 1890, 1166, 1889, -1, + 2331, 2772, 1889, -1, 2331, 1889, 2333, -1, + 1150, 1157, 1154, -1, 1150, 1151, 616, -1, + 1894, 1158, 1893, -1, 1894, 1164, 1158, -1, + 1163, 2474, 1892, -1, 1163, 1161, 1164, -1, + 3105, 1892, 2474, -1, 1884, 1885, 1862, -1, + 1168, 1169, 1712, -1, 1168, 1712, 2789, -1, + 1168, 1165, 1912, -1, 1168, 2789, 1165, -1, + 1913, 1893, 1914, -1, 1913, 2470, 2471, -1, + 1178, 702, 1175, -1, 1915, 1175, 1170, -1, + 1177, 1158, 1171, -1, 1177, 1914, 1893, -1, + 1177, 1893, 1158, -1, 615, 613, 1719, -1, + 615, 614, 697, -1, 615, 696, 613, -1, + 615, 697, 696, -1, 948, 1170, 614, -1, + 948, 1169, 1170, -1, 948, 614, 615, -1, + 948, 615, 1719, -1, 1172, 1171, 1157, -1, + 1172, 1157, 1150, -1, 1172, 616, 1173, -1, + 1172, 1150, 616, -1, 2532, 1918, 619, -1, + 2532, 1183, 2533, -1, 2532, 619, 1183, -1, + 1919, 2920, 653, -1, 1919, 653, 618, -1, + 1181, 1194, 1942, -1, 1181, 1942, 1940, -1, + 1181, 2538, 1194, -1, 2549, 1952, 2927, -1, + 3126, 617, 1182, -1, 3126, 3124, 617, -1, + 1426, 764, 1931, -1, 1426, 1931, 1930, -1, + 1426, 1436, 764, -1, 620, 618, 1936, -1, + 620, 619, 1918, -1, 620, 1919, 618, -1, + 620, 1918, 1919, -1, 1922, 2547, 619, -1, + 1922, 619, 620, -1, 1922, 620, 1936, -1, + 1200, 2015, 1201, -1, 621, 1964, 2552, -1, + 621, 1200, 1964, -1, 621, 2015, 1200, -1, + 621, 2016, 2015, -1, 621, 2552, 2016, -1, + 2551, 2016, 2552, -1, 2551, 2550, 622, -1, + 2551, 623, 2016, -1, 2551, 622, 623, -1, + 1950, 1939, 877, -1, 1950, 876, 1949, -1, + 1950, 877, 876, -1, 1187, 1940, 1188, -1, + 1187, 1181, 1940, -1, 1190, 1184, 1952, -1, + 625, 1938, 1937, -1, 625, 864, 1636, -1, + 625, 624, 1938, -1, 625, 1636, 624, -1, + 1958, 1959, 864, -1, 1958, 864, 625, -1, + 1958, 625, 1937, -1, 1958, 1937, 1960, -1, + 2932, 1954, 865, -1, 2932, 865, 1959, -1, + 626, 1931, 764, -1, 626, 1196, 1202, -1, + 626, 1202, 1929, -1, 626, 1929, 1931, -1, + 1197, 626, 764, -1, 1197, 1196, 626, -1, + 1198, 1965, 1195, -1, 1198, 1193, 1965, -1, + 1198, 2933, 1193, -1, 1962, 1964, 1200, -1, + 1962, 1202, 1963, -1, 1206, 1974, 1979, -1, + 1206, 1986, 1203, -1, 1206, 1203, 1974, -1, + 1971, 1203, 1973, -1, 1983, 1206, 1979, -1, + 1983, 1204, 627, -1, 1983, 627, 1984, -1, + 1976, 691, 628, -1, 1976, 628, 629, -1, + 1976, 629, 1977, -1, 630, 632, 631, -1, + 630, 631, 633, -1, 630, 634, 632, -1, + 630, 635, 634, -1, 630, 633, 635, -1, + 1988, 1992, 1989, -1, 1209, 1210, 636, -1, + 1209, 636, 637, -1, 1209, 637, 638, -1, + 1209, 638, 1238, -1, 2072, 639, 2073, -1, + 2072, 640, 639, -1, 2072, 2068, 2070, -1, + 2072, 2070, 641, -1, 2072, 641, 640, -1, + 2570, 1213, 2571, -1, 2004, 2573, 2574, -1, + 1336, 2012, 2942, -1, 2011, 2012, 1335, -1, + 1216, 1248, 1217, -1, 1216, 1247, 1248, -1, + 1219, 740, 1221, -1, 1219, 2008, 740, -1, + 1215, 2008, 1219, -1, 1215, 1219, 1220, -1, + 1215, 1220, 1247, -1, 1215, 1247, 1216, -1, + 1246, 1247, 1220, -1, 2941, 1246, 1220, -1, + 2941, 2943, 1246, -1, 2948, 1227, 2019, -1, + 2948, 2019, 3136, -1, 1224, 642, 1225, -1, + 1224, 643, 642, -1, 1224, 2579, 2578, -1, + 1224, 2578, 643, -1, 644, 645, 1211, -1, + 644, 1211, 2053, -1, 644, 2053, 646, -1, + 644, 646, 2604, -1, 644, 2604, 2076, -1, + 644, 2076, 645, -1, 2031, 2029, 1243, -1, + 2031, 1243, 647, -1, 2031, 647, 2032, -1, + 2039, 2032, 650, -1, 1231, 648, 2045, -1, + 1231, 2045, 2046, -1, 1231, 649, 648, -1, + 1231, 1232, 649, -1, 2042, 2043, 1230, -1, + 2042, 1230, 1229, -1, 2922, 651, 2921, -1, + 2922, 2045, 651, -1, 2058, 2057, 1236, -1, + 1237, 2065, 2064, -1, 1237, 650, 2065, -1, + 1237, 2597, 2039, -1, 1237, 2039, 650, -1, + 1233, 1236, 2057, -1, 1233, 2057, 2921, -1, + 1233, 2921, 651, -1, 1233, 651, 1234, -1, + 2049, 1240, 1250, -1, 2049, 1250, 1241, -1, + 2060, 1244, 2055, -1, 2919, 2921, 2057, -1, + 2056, 2055, 652, -1, 2056, 652, 653, -1, + 2056, 653, 2920, -1, 2056, 2920, 2919, -1, + 2569, 654, 1249, -1, 2569, 2937, 654, -1, + 655, 657, 656, -1, 655, 656, 684, -1, + 655, 684, 658, -1, 655, 659, 657, -1, + 655, 658, 659, -1, 2067, 680, 1251, -1, + 2067, 1253, 660, -1, 2067, 660, 680, -1, + 661, 682, 687, -1, 661, 681, 682, -1, + 661, 687, 686, -1, 661, 686, 681, -1, + 1255, 662, 1254, -1, 1255, 1207, 662, -1, + 1255, 2607, 1207, -1, 1268, 1269, 1302, -1, + 700, 699, 663, -1, 700, 1258, 701, -1, + 1256, 664, 1259, -1, 1256, 663, 664, -1, + 1256, 1258, 700, -1, 1256, 700, 663, -1, + 1264, 664, 665, -1, 1264, 1259, 664, -1, + 1308, 2082, 1309, -1, 1307, 2081, 2082, -1, + 1307, 2082, 1308, -1, 1307, 1304, 1264, -1, + 1307, 665, 2081, -1, 1307, 1264, 665, -1, + 2090, 2096, 1272, -1, 666, 1273, 2110, -1, + 666, 2110, 2103, -1, 666, 2103, 2080, -1, + 666, 2080, 667, -1, 666, 667, 1271, -1, + 666, 1271, 1273, -1, 2111, 668, 2109, -1, + 2111, 2110, 1273, -1, 2111, 1273, 1272, -1, + 2111, 1272, 668, -1, 2105, 2109, 668, -1, + 2105, 1275, 2106, -1, 2097, 668, 2096, -1, + 2097, 1275, 2105, -1, 2097, 2105, 668, -1, + 672, 840, 669, -1, 672, 2626, 670, -1, + 672, 2119, 2626, -1, 672, 669, 2119, -1, + 844, 670, 671, -1, 844, 671, 843, -1, + 844, 840, 672, -1, 844, 672, 670, -1, + 844, 1622, 840, -1, 1616, 1281, 1617, -1, + 673, 1283, 674, -1, 673, 674, 1289, -1, + 673, 1289, 1283, -1, 1318, 675, 1321, -1, + 1318, 1319, 675, -1, 690, 676, 688, -1, + 690, 677, 676, -1, 690, 678, 677, -1, + 690, 689, 678, -1, 679, 686, 680, -1, + 679, 681, 686, -1, 679, 682, 681, -1, + 679, 683, 682, -1, 679, 684, 683, -1, + 679, 680, 684, -1, 685, 686, 687, -1, + 685, 688, 686, -1, 685, 687, 689, -1, + 685, 690, 688, -1, 685, 689, 690, -1, + 1287, 1286, 691, -1, 1287, 1972, 2123, -1, + 1980, 691, 1976, -1, 1980, 1972, 1287, -1, + 1980, 1287, 691, -1, 1288, 692, 1285, -1, + 1288, 693, 692, -1, 1288, 1290, 693, -1, + 1288, 1285, 2627, -1, 694, 701, 1258, -1, + 694, 1258, 1257, -1, 694, 1257, 695, -1, + 694, 695, 696, -1, 694, 696, 697, -1, + 694, 697, 701, -1, 698, 1173, 699, -1, + 698, 699, 700, -1, 698, 700, 701, -1, + 698, 701, 702, -1, 698, 702, 1178, -1, + 698, 1178, 1173, -1, 1298, 1296, 1292, -1, + 1298, 1294, 1299, -1, 703, 705, 704, -1, + 703, 706, 705, -1, 703, 1715, 706, -1, + 703, 1713, 1715, -1, 703, 704, 1713, -1, + 707, 708, 709, -1, 707, 712, 708, -1, + 707, 709, 710, -1, 707, 710, 712, -1, + 711, 713, 712, -1, 711, 712, 714, -1, + 711, 715, 713, -1, 711, 714, 715, -1, + 716, 1300, 717, -1, 716, 717, 718, -1, + 716, 718, 1300, -1, 1306, 1300, 718, -1, + 1306, 719, 1305, -1, 1306, 718, 719, -1, + 720, 1399, 2131, -1, 720, 2131, 2129, -1, + 720, 1408, 1411, -1, 720, 2129, 1408, -1, + 1311, 2146, 1399, -1, 1311, 1399, 720, -1, + 1311, 720, 1411, -1, 1398, 2131, 1399, -1, + 1316, 721, 2087, -1, 1316, 1323, 721, -1, + 1315, 2088, 1323, -1, 1315, 1323, 1316, -1, + 1320, 722, 1319, -1, 1320, 1323, 2088, -1, + 1320, 1270, 722, -1, 1320, 2088, 1270, -1, + 723, 725, 724, -1, 723, 726, 725, -1, + 723, 724, 2099, -1, 723, 2099, 1276, -1, + 723, 1276, 726, -1, 1325, 1324, 726, -1, + 1325, 727, 2026, -1, 1325, 726, 727, -1, + 2589, 2125, 728, -1, 2589, 728, 2021, -1, + 1222, 2571, 1926, -1, 1222, 1201, 2014, -1, + 1222, 1927, 1201, -1, 1222, 1926, 1927, -1, + 2175, 1442, 2129, -1, 1339, 2521, 2133, -1, + 2657, 733, 1328, -1, 2657, 1328, 2631, -1, + 1356, 1908, 2523, -1, 729, 732, 733, -1, + 729, 731, 732, -1, 2660, 733, 2657, -1, + 2660, 729, 733, -1, 2660, 1329, 729, -1, + 2140, 731, 2141, -1, 737, 2141, 731, -1, + 737, 731, 729, -1, 737, 1329, 2643, -1, + 737, 729, 1329, -1, 2644, 2643, 1329, -1, + 1407, 1331, 1899, -1, 1334, 741, 1359, -1, + 1334, 738, 741, -1, 1334, 1221, 738, -1, + 1334, 1336, 1221, -1, 730, 732, 731, -1, + 730, 1337, 732, -1, 730, 742, 1337, -1, + 730, 731, 2140, -1, 730, 1361, 742, -1, + 730, 2140, 1361, -1, 1338, 733, 732, -1, + 1338, 732, 1337, -1, 1338, 1328, 733, -1, + 1338, 1339, 1328, -1, 1352, 2525, 744, -1, + 1352, 2523, 2525, -1, 1352, 1356, 2523, -1, + 3196, 1353, 1354, -1, 3196, 1354, 3198, -1, + 2475, 1356, 1353, -1, 2475, 1908, 1356, -1, + 1345, 1341, 1344, -1, 1345, 2669, 1348, -1, + 1346, 1347, 735, -1, 1346, 735, 734, -1, + 1346, 1343, 1348, -1, 1346, 734, 1343, -1, + 1349, 2662, 1344, -1, 1349, 1344, 745, -1, + 1351, 745, 1341, -1, 1351, 1341, 1355, -1, + 1351, 744, 745, -1, 1351, 1352, 744, -1, + 1274, 734, 735, -1, 1274, 736, 1275, -1, + 1274, 735, 736, -1, 1274, 3142, 734, -1, + 1365, 2642, 1364, -1, 1365, 2141, 737, -1, + 1365, 2643, 2642, -1, 1365, 737, 2643, -1, + 1357, 739, 738, -1, 1357, 1364, 739, -1, + 1357, 738, 740, -1, 1357, 740, 2010, -1, + 2648, 1359, 741, -1, 2648, 741, 2641, -1, + 2580, 2006, 2578, -1, 2580, 2581, 2009, -1, + 746, 742, 1360, -1, 746, 744, 2525, -1, + 746, 2524, 742, -1, 746, 2525, 2524, -1, + 743, 745, 744, -1, 743, 1360, 1362, -1, + 743, 744, 746, -1, 743, 746, 1360, -1, + 743, 1349, 745, -1, 743, 1362, 1349, -1, + 2139, 1361, 2140, -1, 936, 747, 932, -1, + 936, 1688, 748, -1, 936, 748, 747, -1, + 1367, 1381, 1372, -1, 1367, 1382, 1381, -1, + 1367, 751, 1382, -1, 1367, 1371, 751, -1, + 1377, 1368, 1372, -1, 1377, 749, 1368, -1, + 1377, 1378, 749, -1, 756, 2142, 1388, -1, + 756, 1375, 1384, -1, 1385, 756, 1384, -1, + 1385, 2142, 756, -1, 1385, 1386, 2143, -1, + 1385, 2143, 2142, -1, 2150, 2672, 2692, -1, + 2150, 2981, 2672, -1, 750, 1395, 1630, -1, + 750, 1383, 1382, -1, 750, 1382, 751, -1, + 750, 751, 1395, -1, 750, 1630, 1631, -1, + 750, 1631, 1383, -1, 1391, 752, 754, -1, + 1391, 754, 1629, -1, 1391, 1392, 752, -1, + 1627, 754, 753, -1, 1627, 1629, 754, -1, + 1627, 753, 755, -1, 1627, 755, 1628, -1, + 2267, 2265, 1313, -1, 2267, 1313, 1398, -1, + 760, 1374, 1375, -1, 760, 1388, 1389, -1, + 760, 756, 1388, -1, 760, 1375, 756, -1, + 1379, 1374, 916, -1, 1379, 917, 1378, -1, + 758, 759, 910, -1, 758, 915, 916, -1, + 758, 910, 912, -1, 758, 912, 915, -1, + 757, 916, 1374, -1, 757, 758, 916, -1, + 757, 759, 758, -1, 757, 1389, 759, -1, + 757, 760, 1389, -1, 757, 1374, 760, -1, + 1400, 1798, 2685, -1, 1400, 1070, 1798, -1, + 1400, 1401, 1070, -1, 1400, 2685, 2510, -1, + 2683, 1403, 2144, -1, 2683, 1797, 1403, -1, + 2686, 2510, 2685, -1, 2686, 3001, 2510, -1, + 761, 909, 913, -1, 761, 762, 909, -1, + 761, 1402, 762, -1, 761, 2294, 1402, -1, + 761, 913, 2295, -1, 761, 2295, 2294, -1, + 2145, 1632, 2266, -1, 1410, 1411, 1408, -1, + 2486, 1898, 2696, -1, 1415, 2275, 2282, -1, + 2741, 3024, 2558, -1, 2741, 2558, 2557, -1, + 2278, 1192, 2280, -1, 2278, 2557, 1192, -1, + 2278, 2741, 2557, -1, 763, 1436, 1435, -1, + 763, 1435, 1955, -1, 763, 1955, 1968, -1, + 763, 1968, 1197, -1, 763, 764, 1436, -1, + 763, 1197, 764, -1, 1419, 2281, 1191, -1, + 1419, 1191, 1420, -1, 1416, 765, 1424, -1, + 1416, 1417, 765, -1, 1416, 2153, 2160, -1, + 1416, 1424, 2153, -1, 2165, 765, 2167, -1, + 2708, 2167, 1417, -1, 1434, 1433, 1447, -1, + 1429, 1424, 765, -1, 1429, 2165, 2164, -1, + 1429, 765, 2165, -1, 2177, 2710, 2709, -1, + 2177, 1442, 2175, -1, 2172, 1446, 2171, -1, + 1443, 2189, 2275, -1, 1443, 2275, 1415, -1, + 2184, 1446, 2172, -1, 2184, 2172, 1444, -1, + 2184, 1444, 2183, -1, 2170, 2171, 1312, -1, + 2170, 766, 2186, -1, 2170, 1312, 766, -1, + 1452, 767, 1455, -1, 1452, 1453, 983, -1, + 1452, 983, 768, -1, 1452, 769, 767, -1, + 1452, 768, 769, -1, 1464, 1463, 1456, -1, + 1462, 2203, 1460, -1, 1462, 2198, 2203, -1, + 3014, 3013, 2208, -1, 1539, 1540, 1465, -1, + 1545, 770, 1540, -1, 1545, 2712, 771, -1, + 1545, 771, 770, -1, 772, 1068, 773, -1, + 772, 773, 779, -1, 772, 1066, 1068, -1, + 772, 779, 774, -1, 772, 774, 1066, -1, + 1062, 778, 775, -1, 1062, 775, 1061, -1, + 776, 777, 778, -1, 776, 779, 777, -1, + 776, 778, 1062, -1, 776, 1052, 779, -1, + 776, 1060, 1052, -1, 776, 1062, 1060, -1, + 2216, 1510, 2214, -1, 2213, 780, 2218, -1, + 2213, 1466, 781, -1, 2213, 1603, 780, -1, + 2213, 781, 1603, -1, 1473, 782, 1069, -1, + 1473, 1472, 782, -1, 1473, 1069, 1067, -1, + 1473, 1067, 1475, -1, 1485, 1483, 1477, -1, + 1485, 1480, 1486, -1, 1504, 1492, 1505, -1, + 1500, 1524, 1489, -1, 1500, 1489, 1504, -1, + 783, 2217, 1598, -1, 783, 1598, 1502, -1, + 783, 1502, 2217, -1, 1507, 1510, 2216, -1, + 1513, 1502, 1598, -1, 1513, 1598, 1516, -1, + 1518, 1501, 1517, -1, 1520, 784, 785, -1, + 1520, 786, 784, -1, 1520, 785, 1525, -1, + 1520, 787, 786, -1, 1520, 1521, 787, -1, + 2723, 788, 2722, -1, 2723, 789, 788, -1, + 2723, 1526, 789, -1, 2720, 790, 791, -1, + 2720, 792, 790, -1, 2720, 2722, 792, -1, + 2720, 791, 793, -1, 2720, 793, 2202, -1, + 1528, 795, 2224, -1, 1528, 1529, 820, -1, + 1528, 820, 795, -1, 794, 795, 796, -1, + 794, 796, 797, -1, 794, 2224, 795, -1, + 794, 797, 2224, -1, 1532, 1533, 1538, -1, + 1532, 1538, 798, -1, 1532, 798, 1465, -1, + 1532, 1465, 1535, -1, 1534, 799, 1533, -1, + 1534, 1535, 800, -1, 1534, 800, 799, -1, + 1544, 801, 2719, -1, 1544, 2719, 1547, -1, + 1544, 1537, 801, -1, 3018, 2202, 3019, -1, + 3018, 3017, 2202, -1, 2713, 1546, 3017, -1, + 1550, 1683, 1551, -1, 1550, 2238, 2239, -1, + 1550, 802, 2238, -1, 1550, 1551, 802, -1, + 1558, 1559, 1549, -1, 1553, 930, 2225, -1, + 1553, 2225, 803, -1, 1553, 803, 1552, -1, + 853, 1549, 1679, -1, 853, 1690, 1549, -1, + 853, 1679, 1677, -1, 853, 1677, 857, -1, + 2301, 803, 2225, -1, 2301, 804, 803, -1, + 2301, 2298, 804, -1, 2240, 2238, 805, -1, + 2240, 805, 806, -1, 2240, 806, 1556, -1, + 2232, 1652, 807, -1, 2232, 807, 2233, -1, + 2232, 2234, 1652, -1, 1580, 1568, 1579, -1, + 1580, 1581, 1560, -1, 1566, 1564, 1568, -1, + 1566, 1567, 1562, -1, 968, 977, 978, -1, + 968, 978, 1735, -1, 2247, 2246, 977, -1, + 2247, 977, 968, -1, 2247, 968, 1567, -1, + 1570, 1571, 808, -1, 1570, 808, 813, -1, + 1570, 809, 1575, -1, 1570, 813, 809, -1, + 810, 811, 812, -1, 810, 813, 811, -1, + 810, 812, 896, -1, 810, 814, 813, -1, + 810, 896, 893, -1, 810, 893, 814, -1, + 1577, 1578, 815, -1, 1577, 815, 816, -1, + 1577, 817, 1582, -1, 1577, 816, 817, -1, + 1487, 1486, 818, -1, 1487, 818, 819, -1, + 1487, 819, 820, -1, 1487, 820, 2222, -1, + 1584, 1585, 821, -1, 1584, 821, 1481, -1, + 1584, 1478, 1589, -1, 1584, 1481, 1478, -1, + 1602, 1593, 1612, -1, 1596, 822, 1597, -1, + 1596, 1594, 822, -1, 835, 830, 1590, -1, + 835, 823, 837, -1, 835, 1590, 823, -1, + 835, 836, 830, -1, 1591, 1590, 830, -1, + 1591, 1594, 2249, -1, 1591, 829, 1594, -1, + 1591, 830, 829, -1, 824, 825, 2732, -1, + 824, 2732, 826, -1, 824, 2252, 825, -1, + 824, 826, 2252, -1, 827, 828, 829, -1, + 827, 829, 830, -1, 827, 830, 836, -1, + 827, 836, 831, -1, 827, 832, 828, -1, + 827, 831, 832, -1, 1605, 833, 1608, -1, + 1605, 1606, 833, -1, 834, 1609, 1610, -1, + 834, 836, 835, -1, 834, 1457, 836, -1, + 834, 1610, 1457, -1, 834, 837, 1609, -1, + 834, 835, 837, -1, 1611, 1612, 950, -1, + 1611, 950, 2341, -1, 2738, 2251, 2255, -1, + 1614, 2255, 2251, -1, 1614, 1611, 2341, -1, + 1614, 2251, 1611, -1, 1722, 1592, 1723, -1, + 838, 2254, 2258, -1, 838, 2258, 839, -1, + 838, 846, 2254, -1, 838, 839, 846, -1, + 1618, 1622, 1619, -1, 1618, 840, 1622, -1, + 1618, 841, 840, -1, 1618, 1617, 841, -1, + 1624, 842, 1625, -1, 1624, 843, 842, -1, + 1624, 844, 843, -1, 1624, 1622, 844, -1, + 2347, 845, 2350, -1, 2347, 2348, 846, -1, + 2347, 846, 847, -1, 2347, 847, 845, -1, + 848, 849, 889, -1, 848, 889, 850, -1, + 848, 850, 861, -1, 848, 861, 851, -1, + 848, 851, 852, -1, 848, 852, 849, -1, + 1689, 1690, 853, -1, 1689, 853, 857, -1, + 854, 855, 1692, -1, 854, 857, 856, -1, + 854, 1689, 857, -1, 854, 1692, 1689, -1, + 854, 858, 855, -1, 854, 856, 858, -1, + 1626, 859, 860, -1, 1626, 1450, 859, -1, + 1626, 2196, 1450, -1, 2752, 860, 2753, -1, + 2752, 1626, 860, -1, 1393, 861, 862, -1, + 1393, 862, 1392, -1, 1393, 1394, 863, -1, + 1393, 863, 861, -1, 2274, 2755, 2751, -1, + 2274, 2751, 2271, -1, 2270, 1649, 1639, -1, + 2270, 1648, 1649, -1, 2270, 2271, 1648, -1, + 2746, 1641, 3027, -1, 1637, 1636, 864, -1, + 1637, 864, 865, -1, 1637, 865, 3023, -1, + 1637, 3023, 3026, -1, 2754, 866, 872, -1, + 2754, 2753, 866, -1, 867, 2285, 871, -1, + 867, 1646, 2285, -1, 867, 1644, 1646, -1, + 867, 868, 1644, -1, 867, 871, 868, -1, + 873, 869, 870, -1, 873, 870, 871, -1, + 873, 872, 869, -1, 2286, 871, 2285, -1, + 2286, 2754, 872, -1, 2286, 872, 873, -1, + 2286, 873, 871, -1, 874, 875, 876, -1, + 874, 876, 877, -1, 874, 877, 878, -1, + 874, 878, 879, -1, 874, 880, 875, -1, + 874, 879, 880, -1, 887, 886, 881, -1, + 887, 881, 882, -1, 887, 882, 883, -1, + 887, 883, 888, -1, 884, 885, 886, -1, + 884, 887, 888, -1, 884, 886, 887, -1, + 884, 888, 889, -1, 884, 889, 890, -1, + 884, 890, 885, -1, 1555, 929, 1680, -1, + 1555, 1680, 1557, -1, 1555, 2233, 929, -1, + 891, 892, 893, -1, 891, 894, 895, -1, + 891, 895, 901, -1, 891, 901, 892, -1, + 891, 896, 894, -1, 891, 893, 896, -1, + 897, 899, 898, -1, 897, 900, 899, -1, + 897, 901, 902, -1, 897, 898, 901, -1, + 897, 902, 903, -1, 897, 903, 900, -1, + 1651, 904, 1653, -1, 1651, 1652, 2234, -1, + 1651, 905, 904, -1, 1651, 2234, 906, -1, + 1651, 906, 905, -1, 3049, 3050, 3048, -1, + 2305, 907, 2306, -1, 2305, 1671, 908, -1, + 2305, 908, 907, -1, 2308, 1656, 2310, -1, + 2289, 1667, 2292, -1, 2289, 2306, 1667, -1, + 2289, 2308, 2306, -1, 2290, 2414, 2415, -1, + 2290, 2411, 2414, -1, 2290, 909, 2411, -1, + 2290, 2291, 909, -1, 1659, 910, 1661, -1, + 1659, 912, 910, -1, 1665, 1666, 911, -1, + 1665, 1659, 1664, -1, 1665, 911, 912, -1, + 1665, 912, 1659, -1, 1663, 1664, 1660, -1, + 1663, 1660, 913, -1, 1663, 2291, 2292, -1, + 1663, 913, 2291, -1, 914, 916, 915, -1, + 914, 1379, 916, -1, 914, 917, 1379, -1, + 914, 918, 917, -1, 914, 919, 918, -1, + 914, 915, 919, -1, 1669, 923, 1085, -1, + 1669, 1670, 923, -1, 1669, 1085, 1083, -1, + 1669, 1083, 1668, -1, 1672, 1673, 1084, -1, + 1672, 1084, 920, -1, 1672, 921, 1671, -1, + 1672, 920, 921, -1, 922, 1670, 1554, -1, + 922, 924, 923, -1, 922, 923, 1670, -1, + 922, 925, 924, -1, 922, 926, 925, -1, + 922, 1554, 926, -1, 1675, 927, 1676, -1, + 1675, 928, 927, -1, 1675, 929, 928, -1, + 1675, 1680, 929, -1, 1691, 1682, 1690, -1, + 1685, 930, 1553, -1, 1685, 937, 930, -1, + 1685, 1691, 937, -1, 1687, 937, 1691, -1, + 1687, 1688, 936, -1, 931, 932, 933, -1, + 931, 933, 934, -1, 931, 934, 935, -1, + 931, 936, 932, -1, 931, 1687, 936, -1, + 931, 935, 937, -1, 931, 937, 1687, -1, + 2312, 1693, 944, -1, 942, 938, 943, -1, + 942, 944, 1693, -1, 942, 939, 938, -1, + 942, 1693, 939, -1, 2771, 2331, 2332, -1, + 2771, 2772, 2331, -1, 1704, 2846, 2775, -1, + 1704, 1705, 1703, -1, 1700, 2322, 940, -1, + 1700, 940, 2327, -1, 1702, 2320, 2322, -1, + 1854, 1703, 2452, -1, 1706, 1702, 1705, -1, + 1706, 2320, 1702, -1, 2773, 2786, 1888, -1, + 2773, 2774, 2786, -1, 2787, 1888, 2786, -1, + 2787, 1708, 1888, -1, 3070, 2786, 2774, -1, + 3070, 2774, 2846, -1, 1710, 947, 2782, -1, + 941, 2335, 944, -1, 941, 944, 942, -1, + 941, 942, 943, -1, 941, 943, 947, -1, + 941, 947, 1710, -1, 941, 1710, 2335, -1, + 2336, 944, 2335, -1, 2336, 2791, 2312, -1, + 2336, 2312, 944, -1, 2798, 1711, 2332, -1, + 2781, 945, 2780, -1, 2781, 946, 945, -1, + 2781, 947, 946, -1, 2781, 2782, 947, -1, + 2318, 2317, 1711, -1, 2318, 1710, 2782, -1, + 1718, 1169, 948, -1, 1718, 948, 1719, -1, + 1718, 1712, 1169, -1, 2764, 1720, 1714, -1, + 959, 966, 967, -1, 959, 949, 966, -1, + 959, 967, 958, -1, 959, 1732, 949, -1, + 2788, 1165, 2789, -1, 2788, 2506, 1165, -1, + 2788, 2795, 2507, -1, 2788, 2507, 2506, -1, + 2342, 2341, 950, -1, 1721, 950, 1593, -1, + 1721, 2342, 950, -1, 1721, 1728, 2342, -1, + 1721, 1593, 1722, -1, 1725, 956, 1733, -1, + 1725, 1733, 1734, -1, 951, 953, 952, -1, + 951, 954, 953, -1, 951, 955, 954, -1, + 951, 952, 956, -1, 951, 956, 1725, -1, + 951, 1725, 1726, -1, 951, 957, 955, -1, + 951, 2329, 957, -1, 951, 1726, 2329, -1, + 1731, 2260, 2339, -1, 1731, 958, 2260, -1, + 1731, 959, 958, -1, 1731, 1732, 959, -1, + 2344, 1619, 960, -1, 2344, 2345, 1619, -1, + 2344, 1625, 2348, -1, 2344, 960, 1625, -1, + 1620, 961, 1279, -1, 1620, 1279, 1616, -1, + 1620, 2350, 961, -1, 1620, 2345, 2350, -1, + 962, 963, 964, -1, 962, 964, 965, -1, + 962, 965, 1280, -1, 962, 966, 963, -1, + 962, 1280, 967, -1, 962, 967, 966, -1, + 1736, 1562, 1567, -1, 1736, 968, 1735, -1, + 1736, 1567, 968, -1, 1736, 2807, 1562, -1, + 2357, 1563, 2356, -1, 2357, 2355, 969, -1, + 2357, 969, 970, -1, 2357, 970, 1563, -1, + 1739, 971, 2355, -1, 1739, 987, 971, -1, + 1739, 1738, 1019, -1, 1739, 1019, 972, -1, + 1739, 972, 987, -1, 2806, 1565, 2807, -1, + 2806, 2353, 1565, -1, 973, 974, 2369, -1, + 973, 2369, 2367, -1, 973, 2367, 1735, -1, + 973, 1735, 978, -1, 973, 978, 979, -1, + 973, 979, 974, -1, 980, 975, 979, -1, + 980, 983, 975, -1, 976, 978, 977, -1, + 976, 979, 978, -1, 976, 980, 979, -1, + 976, 977, 981, -1, 976, 981, 982, -1, + 976, 982, 983, -1, 976, 983, 980, -1, + 3044, 2801, 1742, -1, 1741, 1737, 2361, -1, + 1741, 2352, 1737, -1, 2360, 1752, 2362, -1, + 2360, 2366, 1752, -1, 2360, 1737, 2366, -1, + 2360, 2361, 1737, -1, 1753, 1747, 1745, -1, + 1749, 3048, 984, -1, 1749, 984, 985, -1, + 1749, 985, 1748, -1, 1758, 993, 986, -1, + 1758, 987, 993, -1, 1758, 986, 988, -1, + 1758, 988, 1756, -1, 1758, 1759, 987, -1, + 989, 1770, 1766, -1, 989, 991, 990, -1, + 989, 990, 1770, -1, 989, 992, 991, -1, + 989, 993, 992, -1, 989, 1766, 993, -1, + 994, 1755, 995, -1, 994, 996, 997, -1, + 994, 997, 999, -1, 994, 999, 1755, -1, + 994, 998, 996, -1, 994, 995, 998, -1, + 1757, 1755, 999, -1, 1757, 1001, 1000, -1, + 1757, 999, 1001, -1, 1757, 1000, 1002, -1, + 1757, 1002, 1761, -1, 2374, 1081, 2373, -1, + 2375, 1812, 1081, -1, 2375, 2376, 1812, -1, + 2375, 1081, 2374, -1, 2375, 2374, 2382, -1, + 2371, 1003, 2385, -1, 2371, 1004, 1003, -1, + 2371, 1005, 1004, -1, 2371, 2372, 1005, -1, + 1785, 1769, 1784, -1, 2387, 2389, 1006, -1, + 2387, 1006, 1764, -1, 2818, 2819, 1765, -1, + 1775, 1007, 1776, -1, 1775, 1008, 1007, -1, + 1775, 1009, 1008, -1, 1775, 1774, 1009, -1, + 2803, 1011, 1010, -1, 2803, 2800, 1012, -1, + 2803, 1012, 1011, -1, 2803, 1010, 2802, -1, + 1572, 3046, 1571, -1, 1572, 1573, 1012, -1, + 1572, 2800, 3046, -1, 1572, 1012, 2800, -1, + 1574, 1013, 1573, -1, 1574, 1014, 1013, -1, + 1574, 1015, 1014, -1, 1574, 1575, 1015, -1, + 1780, 1762, 2823, -1, 1780, 1781, 1762, -1, + 1780, 2823, 2821, -1, 1780, 2821, 1785, -1, + 1791, 1787, 1792, -1, 1016, 1738, 1742, -1, + 1016, 1018, 1017, -1, 1016, 1017, 1019, -1, + 1016, 1019, 1738, -1, 1016, 1742, 2801, -1, + 1016, 2801, 1018, -1, 1020, 1021, 1027, -1, + 1020, 1023, 1022, -1, 1020, 1022, 1021, -1, + 1020, 1034, 1023, -1, 1020, 1032, 1034, -1, + 1020, 1027, 1032, -1, 1024, 1025, 1026, -1, + 1024, 1027, 1025, -1, 1024, 1026, 1028, -1, + 1024, 1029, 1027, -1, 1024, 1028, 1037, -1, + 1024, 1037, 1029, -1, 1030, 1032, 1031, -1, + 1030, 1033, 1034, -1, 1030, 1034, 1032, -1, + 1030, 1091, 1033, -1, 1030, 1035, 1091, -1, + 1030, 1031, 1035, -1, 1036, 1041, 1048, -1, + 1036, 1038, 1037, -1, 1036, 1037, 1041, -1, + 1036, 1039, 1038, -1, 1036, 1040, 1039, -1, + 1036, 1048, 1040, -1, 1047, 1048, 1041, -1, + 1047, 1042, 1046, -1, 1047, 1043, 1042, -1, + 1047, 1041, 1043, -1, 1044, 1046, 1045, -1, + 1044, 1047, 1046, -1, 1044, 1048, 1047, -1, + 1044, 1049, 1048, -1, 1044, 1045, 1050, -1, + 1044, 1050, 1049, -1, 1051, 1060, 1059, -1, + 1051, 1052, 1060, -1, 1051, 1053, 1052, -1, + 1051, 1054, 1053, -1, 1051, 1055, 1054, -1, + 1051, 1059, 1055, -1, 1056, 1058, 1057, -1, + 1056, 1057, 1059, -1, 1056, 1059, 1060, -1, + 1056, 1061, 1058, -1, 1056, 1060, 1062, -1, + 1056, 1062, 1061, -1, 1063, 1065, 1064, -1, + 1063, 1066, 1065, -1, 1063, 1064, 1067, -1, + 1063, 1068, 1066, -1, 1063, 1069, 1068, -1, + 1063, 1067, 1069, -1, 1796, 1798, 1070, -1, + 1796, 1070, 1800, -1, 1796, 1800, 1071, -1, + 1796, 1071, 1795, -1, 1801, 1904, 2395, -1, + 1801, 1800, 1070, -1, 1801, 1401, 1904, -1, + 1801, 1070, 1401, -1, 1799, 1071, 1800, -1, + 1799, 1072, 1071, -1, 1799, 2392, 1073, -1, + 1799, 1073, 1072, -1, 1093, 1078, 2437, -1, + 1093, 2826, 1141, -1, 1074, 1075, 1078, -1, + 1074, 1077, 1076, -1, 1074, 1076, 1075, -1, + 1074, 1141, 1077, -1, 1074, 1093, 1141, -1, + 1074, 1078, 1093, -1, 1137, 1078, 2400, -1, + 1137, 2437, 1078, -1, 1859, 2397, 2393, -1, + 1859, 2408, 2397, -1, 2398, 2399, 2392, -1, + 2398, 2393, 2397, -1, 2405, 1147, 1877, -1, + 2405, 2406, 1147, -1, 2401, 1137, 2400, -1, + 2401, 1803, 1137, -1, 2421, 2410, 1807, -1, + 1079, 1087, 2310, -1, 1079, 2310, 1656, -1, + 1079, 1656, 1090, -1, 1079, 1813, 1087, -1, + 1079, 1090, 2432, -1, 1079, 2432, 1813, -1, + 1811, 1080, 2373, -1, 1811, 1809, 1080, -1, + 1811, 2373, 1081, -1, 1811, 1081, 2428, -1, + 1082, 1787, 1083, -1, 1082, 1084, 1088, -1, + 1082, 1088, 1792, -1, 1082, 1792, 1787, -1, + 1082, 1083, 1085, -1, 1082, 1085, 1084, -1, + 1086, 1087, 1817, -1, 1086, 1817, 1818, -1, + 1086, 1818, 1088, -1, 1086, 2309, 1087, -1, + 1086, 1088, 1673, -1, 1086, 1673, 2309, -1, + 1815, 1812, 2376, -1, 1815, 1817, 1813, -1, + 2431, 1089, 2430, -1, 2431, 2417, 1089, -1, + 2431, 2432, 1090, -1, 2431, 1090, 2417, -1, + 2434, 1091, 1092, -1, 2434, 2435, 1091, -1, + 2434, 1092, 1143, -1, 2434, 1143, 2824, -1, + 2825, 1093, 2437, -1, 2825, 2826, 1093, -1, + 1777, 1094, 1773, -1, 1777, 2299, 1094, -1, + 1777, 2298, 2299, -1, 1777, 1778, 2298, -1, + 1820, 1821, 1095, -1, 1820, 1096, 1104, -1, + 1820, 1095, 1096, -1, 1820, 1104, 1824, -1, + 1097, 1098, 1099, -1, 1097, 1099, 1102, -1, + 1097, 1100, 1098, -1, 1097, 1102, 1100, -1, + 1106, 1108, 1107, -1, 1101, 1103, 1102, -1, + 1101, 1104, 1103, -1, 1101, 1105, 1104, -1, + 1101, 1106, 1107, -1, 1101, 1102, 1108, -1, + 1101, 1108, 1106, -1, 1101, 1107, 1105, -1, + 1109, 1111, 1110, -1, 1109, 1110, 1112, -1, + 1109, 2450, 1111, -1, 1109, 1112, 2450, -1, + 1825, 1123, 2461, -1, 1828, 1846, 1834, -1, + 1828, 1840, 1846, -1, 2445, 1829, 1827, -1, + 1835, 1828, 1834, -1, 1835, 2444, 1828, -1, + 1835, 2443, 2444, -1, 1835, 1837, 2443, -1, + 1113, 1117, 1836, -1, 1113, 1115, 1114, -1, + 1113, 1114, 1119, -1, 1113, 1119, 1117, -1, + 1113, 1116, 1115, -1, 1113, 1836, 1116, -1, + 1511, 1118, 1117, -1, 1511, 1119, 1508, -1, + 1511, 1117, 1119, -1, 1511, 1505, 1492, -1, + 1511, 1492, 1118, -1, 1845, 1843, 1850, -1, + 1845, 1846, 1840, -1, 1847, 1834, 1846, -1, + 1847, 1833, 1834, -1, 1847, 1120, 1833, -1, + 1847, 1848, 1120, -1, 1851, 1129, 1145, -1, + 1851, 1855, 1128, -1, 1851, 1128, 1129, -1, + 1851, 1145, 1852, -1, 1146, 1852, 1145, -1, + 1146, 2842, 1852, -1, 1146, 1121, 2842, -1, + 1146, 1875, 1121, -1, 1856, 1128, 1855, -1, + 1856, 1127, 1128, -1, 1856, 1122, 1127, -1, + 1856, 2465, 1122, -1, 2446, 2455, 2453, -1, + 2458, 1123, 1825, -1, 2458, 2448, 1123, -1, + 1167, 1884, 1862, -1, 1858, 2393, 2394, -1, + 1858, 1859, 2393, -1, 1124, 2394, 1905, -1, + 1124, 1167, 1862, -1, 1124, 1862, 1858, -1, + 1124, 1858, 2394, -1, 1124, 1905, 2901, -1, + 1124, 2901, 1167, -1, 1125, 1132, 1131, -1, + 1125, 1127, 1126, -1, 1125, 1126, 1132, -1, + 1125, 1128, 1127, -1, 1125, 1129, 1128, -1, + 1125, 1131, 1129, -1, 1130, 1131, 1132, -1, + 1130, 1134, 1133, -1, 1130, 1133, 1135, -1, + 1130, 1135, 1131, -1, 1130, 1136, 1134, -1, + 1130, 1132, 1136, -1, 2436, 1803, 1138, -1, + 2436, 2437, 1137, -1, 2436, 1137, 1803, -1, + 2436, 1138, 2840, -1, 1804, 1138, 1803, -1, + 1804, 2407, 1867, -1, 2839, 2840, 1138, -1, + 2839, 1865, 2838, -1, 1864, 1804, 1867, -1, + 1864, 1138, 1804, -1, 1864, 1865, 2839, -1, + 1864, 2839, 1138, -1, 1139, 1140, 1141, -1, + 1139, 1142, 1140, -1, 1139, 1141, 2826, -1, + 1139, 1143, 1142, -1, 1139, 2826, 2824, -1, + 1139, 2824, 1143, -1, 1868, 1144, 1870, -1, + 1868, 1145, 1144, -1, 1868, 1875, 1146, -1, + 1868, 1146, 1145, -1, 1872, 1867, 2407, -1, + 1872, 1873, 1867, -1, 1872, 2405, 1877, -1, + 1872, 2407, 2405, -1, 1881, 1147, 1802, -1, + 1881, 1880, 1148, -1, 1881, 1148, 1147, -1, + 1882, 1802, 1861, -1, 1882, 1881, 1802, -1, + 2466, 1861, 1885, -1, 2466, 2467, 1882, -1, + 2466, 1882, 1861, -1, 1887, 1708, 2890, -1, + 1887, 1888, 1708, -1, 1887, 2890, 2888, -1, + 1887, 2888, 1890, -1, 1149, 1151, 1150, -1, + 1149, 1152, 1153, -1, 1149, 1154, 1152, -1, + 1149, 1150, 1154, -1, 1149, 1153, 1155, -1, + 1149, 1155, 1151, -1, 1156, 1161, 1159, -1, + 1156, 1159, 1157, -1, 1156, 1157, 1171, -1, + 1156, 1171, 1158, -1, 1156, 1158, 1164, -1, + 1156, 1164, 1161, -1, 1162, 1159, 1161, -1, + 1162, 2879, 1897, -1, 1162, 1160, 1159, -1, + 1162, 1897, 1160, -1, 1891, 1163, 1892, -1, + 1891, 1161, 1163, -1, 1891, 2879, 1162, -1, + 1891, 1162, 1161, -1, 1895, 2474, 1163, -1, + 1895, 1164, 1894, -1, 1895, 1163, 1164, -1, + 1896, 1892, 3105, -1, 1896, 3105, 3104, -1, + 2469, 1165, 2506, -1, 2469, 2470, 1912, -1, + 2469, 1912, 1165, -1, 2469, 2506, 2505, -1, + 1903, 1902, 1166, -1, 1903, 1166, 1890, -1, + 1903, 1890, 2888, -1, 2895, 2891, 1884, -1, + 2895, 1884, 1167, -1, 2898, 1167, 2901, -1, + 2898, 2895, 1167, -1, 2639, 2913, 2494, -1, + 2639, 2914, 2913, -1, 2517, 2503, 2518, -1, + 1911, 1169, 1168, -1, 1911, 1170, 1169, -1, + 1911, 1915, 1170, -1, 1911, 1168, 1912, -1, + 1176, 1177, 1171, -1, 1176, 1171, 1172, -1, + 1176, 1173, 1178, -1, 1176, 1172, 1173, -1, + 1174, 1175, 1915, -1, 1174, 1177, 1176, -1, + 1174, 1915, 1914, -1, 1174, 1914, 1177, -1, + 1174, 1178, 1175, -1, 1174, 1176, 1178, -1, + 2526, 1916, 1179, -1, 2526, 1179, 2044, -1, + 2534, 1918, 2532, -1, 2544, 1924, 2546, -1, + 2544, 1920, 1924, -1, 2544, 2540, 1920, -1, + 1180, 2538, 1181, -1, 1180, 1921, 1920, -1, + 1180, 1187, 1921, -1, 1180, 1181, 1187, -1, + 1180, 2540, 2538, -1, 1180, 1920, 2540, -1, + 2925, 3126, 1182, -1, 2925, 1183, 2547, -1, + 2925, 1182, 1183, -1, 1928, 1926, 1213, -1, + 1928, 1213, 2002, -1, 1928, 1932, 1930, -1, + 1928, 2002, 1932, -1, 1427, 1426, 1930, -1, + 1427, 1930, 1932, -1, 1427, 1932, 2155, -1, + 1427, 2155, 1425, -1, 2542, 1922, 1936, -1, + 2568, 2552, 1964, -1, 1947, 1939, 1950, -1, + 1953, 1190, 1952, -1, 1189, 1184, 1190, -1, + 1189, 1185, 1184, -1, 1189, 1188, 1185, -1, + 1186, 1187, 1188, -1, 1186, 1188, 1189, -1, + 1186, 1189, 1190, -1, 1186, 1190, 1953, -1, + 1186, 1921, 1187, -1, 1186, 1953, 1921, -1, + 1961, 1960, 1942, -1, 1961, 1942, 1194, -1, + 1961, 1194, 1193, -1, 1961, 1193, 2933, -1, + 2931, 2932, 1959, -1, 2931, 1961, 2933, -1, + 1956, 1955, 1420, -1, 1956, 1420, 1191, -1, + 1956, 1192, 2556, -1, 1956, 1191, 1192, -1, + 2537, 1965, 1193, -1, 2537, 1194, 2538, -1, + 2537, 1193, 1194, -1, 2564, 1963, 1195, -1, + 2564, 1195, 1965, -1, 1967, 1198, 1195, -1, + 1967, 1195, 1196, -1, 1967, 1196, 1197, -1, + 1967, 1197, 1968, -1, 2561, 2933, 1198, -1, + 2561, 1198, 1967, -1, 1199, 1962, 1200, -1, + 1199, 1201, 1927, -1, 1199, 1200, 1201, -1, + 1199, 1927, 1929, -1, 1199, 1929, 1202, -1, + 1199, 1202, 1962, -1, 1970, 1974, 1203, -1, + 1970, 1203, 1971, -1, 1978, 1983, 1979, -1, + 1978, 1204, 1983, -1, 1978, 1205, 1204, -1, + 1978, 1977, 1205, -1, 1985, 1206, 1983, -1, + 1985, 1986, 1206, -1, 1990, 1989, 1207, -1, + 1990, 1207, 2607, -1, 1998, 1992, 1988, -1, + 1998, 1997, 1993, -1, 1998, 1988, 2607, -1, + 1208, 1210, 1209, -1, 1208, 2051, 1211, -1, + 1208, 1238, 2051, -1, 1208, 1209, 1238, -1, + 1208, 1211, 1212, -1, 1208, 1212, 1210, -1, + 2001, 2002, 1213, -1, 2001, 1213, 2570, -1, + 2001, 2570, 2573, -1, 2001, 2573, 2004, -1, + 1214, 1934, 2003, -1, 1214, 2003, 2004, -1, + 1214, 1335, 1934, -1, 1214, 2004, 2574, -1, + 1214, 2011, 1335, -1, 1214, 2574, 2011, -1, + 2007, 2008, 1215, -1, 2007, 1215, 1216, -1, + 2007, 1217, 2006, -1, 2007, 1216, 1217, -1, + 1218, 1220, 1219, -1, 1218, 2941, 1220, -1, + 1218, 2942, 2941, -1, 1218, 1219, 1221, -1, + 1218, 1336, 2942, -1, 1218, 1221, 1336, -1, + 2575, 2011, 2574, -1, 2945, 2014, 2946, -1, + 2945, 2571, 1222, -1, 2945, 1222, 2014, -1, + 2936, 2937, 2569, -1, 2947, 2018, 1244, -1, + 2947, 2946, 2018, -1, 2584, 1227, 2948, -1, + 2592, 2019, 1326, -1, 2023, 2028, 1347, -1, + 2023, 1347, 2667, -1, 1223, 1224, 1225, -1, + 1223, 1225, 1226, -1, 1223, 1226, 1227, -1, + 1223, 1227, 2584, -1, 1223, 2579, 1224, -1, + 1223, 2584, 2579, -1, 2040, 2032, 2039, -1, + 2040, 2041, 2034, -1, 2527, 2042, 2046, -1, + 1228, 2042, 1229, -1, 1228, 1229, 1230, -1, + 1228, 1231, 2046, -1, 1228, 2046, 2042, -1, + 1228, 1230, 1232, -1, 1228, 1232, 1231, -1, + 2036, 2598, 1236, -1, 2036, 1233, 1234, -1, + 2036, 1236, 1233, -1, 2036, 1234, 2037, -1, + 1235, 1236, 2598, -1, 1235, 1237, 2064, -1, + 1235, 2597, 1237, -1, 1235, 2598, 2597, -1, + 1235, 2064, 2058, -1, 1235, 2058, 1236, -1, + 2048, 2051, 1238, -1, 2048, 1238, 1239, -1, + 2048, 1239, 1240, -1, 2048, 1240, 2049, -1, + 2050, 1241, 1242, -1, 2050, 2049, 1241, -1, + 2050, 1243, 2052, -1, 2050, 1242, 1243, -1, + 2576, 2061, 2937, -1, 2576, 2060, 2061, -1, + 2576, 1244, 2060, -1, 2576, 2947, 1244, -1, + 2062, 2060, 2055, -1, 2062, 2058, 2064, -1, + 1245, 1246, 2943, -1, 1245, 2943, 2569, -1, + 1245, 1248, 1247, -1, 1245, 1247, 1246, -1, + 1245, 2569, 1249, -1, 1245, 1250, 1248, -1, + 1245, 1249, 1250, -1, 2069, 2067, 1251, -1, + 2069, 1252, 2070, -1, 2069, 1251, 1252, -1, + 2074, 2068, 2072, -1, 2074, 2067, 2068, -1, + 2074, 1253, 2067, -1, 2074, 2075, 1253, -1, + 2077, 1254, 2076, -1, 2077, 1255, 1254, -1, + 2077, 2607, 1255, -1, 1262, 1256, 1259, -1, + 1262, 1260, 1257, -1, 1262, 1257, 1258, -1, + 1262, 1258, 1256, -1, 1265, 1259, 1264, -1, + 1265, 1261, 1260, -1, 1265, 1260, 1262, -1, + 1265, 1262, 1259, -1, 1265, 1266, 1261, -1, + 1263, 1304, 1305, -1, 1263, 1264, 1304, -1, + 1263, 1265, 1264, -1, 1263, 1305, 1266, -1, + 1263, 1266, 1265, -1, 1267, 2082, 2083, -1, + 1267, 2083, 2608, -1, 1267, 1309, 2082, -1, + 1267, 2608, 1309, -1, 2078, 2083, 2101, -1, + 2078, 2608, 2083, -1, 2102, 2101, 2083, -1, + 2102, 2080, 2103, -1, 2955, 1302, 2609, -1, + 2955, 1268, 1302, -1, 2955, 2956, 1269, -1, + 2955, 1269, 1268, -1, 2620, 2962, 2619, -1, + 2620, 2617, 1270, -1, 2620, 1270, 2088, -1, + 2091, 1271, 2092, -1, 2091, 2090, 1272, -1, + 2091, 1273, 1271, -1, 2091, 1272, 1273, -1, + 2966, 2096, 2090, -1, 2966, 2090, 2611, -1, + 3143, 3142, 1274, -1, 3143, 1275, 2097, -1, + 3143, 1274, 1275, -1, 2618, 2619, 2962, -1, + 2114, 2108, 1276, -1, 2114, 1276, 2099, -1, + 2115, 2103, 2110, -1, 2113, 2108, 2114, -1, + 1277, 1279, 1278, -1, 1277, 1616, 1279, -1, + 1277, 1278, 1280, -1, 1277, 1281, 1616, -1, + 1277, 1282, 1281, -1, 1277, 1280, 1282, -1, + 2118, 1283, 1289, -1, 2118, 2119, 1284, -1, + 2118, 1284, 1283, -1, 2623, 2627, 1285, -1, + 2124, 1285, 1286, -1, 2124, 1286, 1287, -1, + 2124, 1287, 2123, -1, 2124, 2623, 1285, -1, + 2117, 1288, 2627, -1, 2117, 2118, 1289, -1, + 2117, 1289, 1290, -1, 2117, 1290, 1288, -1, + 1291, 1292, 1293, -1, 1291, 1298, 1292, -1, + 1291, 1293, 1294, -1, 1291, 1294, 1298, -1, + 1295, 1297, 1296, -1, 1295, 1296, 1298, -1, + 1295, 1299, 1297, -1, 1295, 1298, 1299, -1, + 1310, 1300, 1306, -1, 1310, 1309, 2609, -1, + 1310, 1301, 1300, -1, 1310, 2609, 1302, -1, + 1310, 1302, 1301, -1, 1303, 1305, 1304, -1, + 1303, 1306, 1305, -1, 1303, 1304, 1307, -1, + 1303, 1307, 1308, -1, 1303, 1308, 1309, -1, + 1303, 1309, 1310, -1, 1303, 1310, 1306, -1, + 2147, 2146, 1311, -1, 2147, 1406, 2693, -1, + 1412, 2487, 1406, -1, 1412, 1406, 2147, -1, + 1412, 2147, 1311, -1, 1412, 1311, 1411, -1, + 2132, 2131, 1398, -1, 2132, 1312, 2130, -1, + 2132, 1313, 1312, -1, 2132, 1398, 1313, -1, + 1314, 2087, 2088, -1, 1314, 2088, 1315, -1, + 1314, 1316, 2087, -1, 1314, 1315, 1316, -1, + 1317, 1319, 1318, -1, 1317, 1320, 1319, -1, + 1317, 1321, 1322, -1, 1317, 1318, 1321, -1, + 1317, 1322, 1323, -1, 1317, 1323, 1320, -1, + 2025, 2024, 2021, -1, 2025, 2021, 1324, -1, + 2025, 1324, 1325, -1, 2025, 1325, 2026, -1, + 2591, 2592, 1326, -1, 2591, 1327, 2126, -1, + 2591, 1326, 1327, -1, 2174, 2130, 1445, -1, + 2632, 2631, 1328, -1, 2632, 1328, 1339, -1, + 2632, 1339, 2133, -1, 2635, 2511, 2636, -1, + 2645, 2644, 2703, -1, 2658, 1329, 2660, -1, + 2658, 2644, 1329, -1, 2658, 2703, 2644, -1, + 1332, 3005, 3006, -1, 1332, 2705, 2654, -1, + 1332, 3006, 2705, -1, 1332, 2654, 1331, -1, + 1330, 1439, 3005, -1, 1330, 1331, 1407, -1, + 1330, 1332, 1331, -1, 1330, 3005, 1332, -1, + 1330, 1440, 1439, -1, 1330, 1407, 1440, -1, + 3008, 1439, 2709, -1, 3008, 3005, 1439, -1, + 2656, 2631, 2630, -1, 2656, 2630, 2653, -1, + 2656, 2657, 2631, -1, 1900, 2501, 2489, -1, + 1900, 1407, 1899, -1, 1333, 1334, 1359, -1, + 1333, 1358, 1335, -1, 1333, 1359, 1358, -1, + 1333, 1335, 2012, -1, 1333, 2012, 1336, -1, + 1333, 1336, 1334, -1, 2520, 1337, 2524, -1, + 2520, 1338, 1337, -1, 2520, 2521, 1339, -1, + 2520, 1339, 1338, -1, 2871, 2475, 1353, -1, + 2871, 1353, 3196, -1, 2871, 3196, 3197, -1, + 1340, 1341, 1345, -1, 1340, 1343, 1342, -1, + 1340, 1348, 1343, -1, 1340, 1345, 1348, -1, + 1340, 1342, 1355, -1, 1340, 1355, 1341, -1, + 2661, 1344, 2662, -1, 2661, 1345, 1344, -1, + 2661, 2669, 1345, -1, 2668, 1347, 1346, -1, + 2668, 2667, 1347, -1, 2668, 1348, 2669, -1, + 2668, 1346, 1348, -1, 2952, 3140, 2662, -1, + 2952, 2662, 1349, -1, 2952, 1362, 2953, -1, + 2952, 1349, 1362, -1, 3138, 2593, 2665, -1, + 1350, 1352, 1351, -1, 1350, 1354, 1353, -1, + 1350, 1355, 1354, -1, 1350, 1351, 1355, -1, + 1350, 1353, 1356, -1, 1350, 1356, 1352, -1, + 1363, 1364, 1357, -1, 1363, 1357, 2010, -1, + 1363, 2009, 2137, -1, 1363, 2010, 2009, -1, + 2647, 1358, 1359, -1, 2647, 1359, 2648, -1, + 2647, 1935, 1358, -1, 2647, 2650, 1935, -1, + 2134, 1360, 1361, -1, 2134, 1361, 2139, -1, + 2134, 1362, 1360, -1, 2134, 2953, 1362, -1, + 2136, 1363, 2137, -1, 2136, 1364, 1363, -1, + 2136, 2141, 1365, -1, 2136, 1365, 1364, -1, + 1366, 1367, 1372, -1, 1366, 1368, 1369, -1, + 1366, 1372, 1368, -1, 1366, 1369, 1370, -1, + 1366, 1370, 1371, -1, 1366, 1371, 1367, -1, + 1376, 1377, 1372, -1, 1376, 1381, 1384, -1, + 1376, 1372, 1381, -1, 1376, 1384, 1375, -1, + 1373, 1375, 1374, -1, 1373, 1376, 1375, -1, + 1373, 1377, 1376, -1, 1373, 1378, 1377, -1, + 1373, 1379, 1378, -1, 1373, 1374, 1379, -1, + 1380, 1381, 1382, -1, 1380, 1382, 1383, -1, + 1380, 1384, 1381, -1, 1380, 1385, 1384, -1, + 1380, 1383, 1386, -1, 1380, 1386, 1385, -1, + 2674, 1388, 2142, -1, 2987, 2673, 2982, -1, + 2987, 2985, 2673, -1, 1387, 2673, 2985, -1, + 1387, 1389, 1388, -1, 1387, 1388, 2674, -1, + 1387, 2674, 2673, -1, 1387, 2676, 1389, -1, + 1387, 2985, 2676, -1, 2149, 2693, 1406, -1, + 2149, 2692, 2693, -1, 2149, 2150, 2692, -1, + 1396, 1391, 1629, -1, 1396, 1630, 1395, -1, + 1396, 2263, 1630, -1, 1396, 1629, 2263, -1, + 1390, 1392, 1391, -1, 1390, 1394, 1393, -1, + 1390, 1393, 1392, -1, 1390, 1395, 1394, -1, + 1390, 1396, 1395, -1, 1390, 1391, 1396, -1, + 1397, 2267, 1398, -1, 1397, 1399, 2146, -1, + 1397, 1398, 1399, -1, 1397, 2146, 2145, -1, + 1397, 2266, 2267, -1, 1397, 2145, 2266, -1, + 2983, 2981, 2150, -1, 2905, 1400, 2510, -1, + 2905, 2906, 1401, -1, 2905, 1401, 1400, -1, + 2684, 1797, 2683, -1, 2684, 2685, 1798, -1, + 1657, 1402, 2294, -1, 1657, 1403, 1404, -1, + 1657, 1404, 1402, -1, 1657, 2144, 1403, -1, + 2690, 1632, 2145, -1, 2690, 1405, 1632, -1, + 2690, 2694, 1405, -1, 2697, 2971, 2977, -1, + 2697, 2696, 1898, -1, 2148, 1406, 2487, -1, + 2148, 2149, 1406, -1, 2148, 2487, 2486, -1, + 2148, 2486, 2696, -1, 1409, 1440, 1407, -1, + 1409, 1407, 1900, -1, 1409, 2489, 1410, -1, + 1409, 1900, 2489, -1, 1441, 1408, 1442, -1, + 1441, 1410, 1408, -1, 1441, 1409, 1410, -1, + 1441, 1440, 1409, -1, 2488, 1411, 1410, -1, + 2488, 1412, 1411, -1, 2488, 2487, 1412, -1, + 2488, 1410, 2489, -1, 1413, 2183, 1444, -1, + 1413, 1415, 1423, -1, 1413, 1444, 1443, -1, + 1413, 1443, 1415, -1, 1413, 1423, 1448, -1, + 1413, 1448, 2183, -1, 1414, 2281, 1419, -1, + 1414, 1423, 1415, -1, 1414, 1422, 1423, -1, + 1414, 1419, 1422, -1, 1414, 2282, 2281, -1, + 1414, 1415, 2282, -1, 2154, 1425, 2155, -1, + 2154, 2153, 1424, -1, 2152, 2159, 2160, -1, + 2152, 2160, 2153, -1, 2702, 2645, 2703, -1, + 2702, 2651, 2645, -1, 2698, 3004, 2708, -1, + 2698, 2708, 1417, -1, 2161, 1416, 2160, -1, + 2161, 2699, 2698, -1, 2161, 1417, 1416, -1, + 2161, 2698, 1417, -1, 2166, 2165, 2167, -1, + 1449, 1447, 1433, -1, 1449, 2164, 2181, -1, + 1418, 1434, 1422, -1, 1418, 1419, 1420, -1, + 1418, 1422, 1419, -1, 1418, 1435, 1434, -1, + 1418, 1420, 1955, -1, 1418, 1955, 1435, -1, + 1421, 1422, 1434, -1, 1421, 1434, 1447, -1, + 1421, 1447, 1448, -1, 1421, 1423, 1422, -1, + 1421, 1448, 1423, -1, 1430, 1432, 1425, -1, + 1430, 1425, 2154, -1, 1430, 2154, 1424, -1, + 1430, 1424, 1429, -1, 1437, 1425, 1432, -1, + 1437, 1436, 1426, -1, 1437, 1427, 1425, -1, + 1437, 1426, 1427, -1, 1428, 1433, 1432, -1, + 1428, 1429, 2164, -1, 1428, 1430, 1429, -1, + 1428, 1432, 1430, -1, 1428, 2164, 1449, -1, + 1428, 1449, 1433, -1, 1431, 1432, 1433, -1, + 1431, 1434, 1435, -1, 1431, 1433, 1434, -1, + 1431, 1435, 1436, -1, 1431, 1436, 1437, -1, + 1431, 1437, 1432, -1, 1438, 2177, 2709, -1, + 1438, 1439, 1440, -1, 1438, 2709, 1439, -1, + 1438, 1440, 1441, -1, 1438, 1442, 2177, -1, + 1438, 1441, 1442, -1, 2169, 2189, 1443, -1, + 2169, 2190, 2189, -1, 2169, 1444, 2172, -1, + 2169, 1443, 1444, -1, 2176, 2174, 1445, -1, + 2185, 2163, 2176, -1, 2185, 2176, 1445, -1, + 2185, 1445, 1446, -1, 2185, 1446, 2184, -1, + 2180, 1448, 1447, -1, 2180, 2183, 1448, -1, + 2180, 1447, 1449, -1, 2180, 1449, 2181, -1, + 2182, 2163, 2185, -1, 2192, 1450, 2196, -1, + 2192, 2187, 1450, -1, 2194, 2277, 2276, -1, + 2194, 2192, 2196, -1, 1451, 1453, 1452, -1, + 1451, 1454, 1453, -1, 1451, 1452, 1455, -1, + 1451, 1455, 1454, -1, 1458, 1464, 1456, -1, + 1458, 1456, 1457, -1, 1458, 1610, 2200, -1, + 1458, 1457, 1610, -1, 2199, 2198, 1462, -1, + 2199, 1462, 1464, -1, 2199, 1458, 2200, -1, + 2199, 1464, 1458, -1, 1459, 1460, 1461, -1, + 1459, 1462, 1460, -1, 1459, 1461, 1463, -1, + 1459, 1463, 1464, -1, 1459, 1464, 1462, -1, + 2210, 2206, 3011, -1, 2205, 2207, 2201, -1, + 2205, 2201, 1608, -1, 2205, 1608, 2206, -1, + 2715, 3010, 3009, -1, 1541, 1465, 1542, -1, + 1541, 1539, 1465, -1, 2212, 1466, 2213, -1, + 2212, 1467, 1466, -1, 2212, 1468, 1467, -1, + 2212, 2215, 1469, -1, 2212, 1469, 1468, -1, + 1470, 1471, 1472, -1, 1470, 1472, 1473, -1, + 1470, 1474, 1471, -1, 1470, 1475, 1474, -1, + 1470, 1473, 1475, -1, 1476, 1485, 1477, -1, + 1476, 1479, 1478, -1, 1476, 1477, 1479, -1, + 1476, 1480, 1485, -1, 1476, 1478, 1481, -1, + 1476, 1481, 1480, -1, 1482, 1484, 1483, -1, + 1482, 1483, 1485, -1, 1482, 2222, 1484, -1, + 1482, 1485, 1486, -1, 1482, 1487, 2222, -1, + 1482, 1486, 1487, -1, 1488, 1504, 1489, -1, + 1488, 1489, 1490, -1, 1488, 1490, 1491, -1, + 1488, 1491, 1492, -1, 1488, 1492, 1504, -1, + 1493, 1497, 1498, -1, 1493, 1498, 1501, -1, + 1493, 1494, 1497, -1, 1493, 1516, 1494, -1, + 1493, 1501, 1518, -1, 1493, 1518, 1516, -1, + 1495, 1497, 1496, -1, 1495, 1498, 1497, -1, + 1495, 1496, 1499, -1, 1495, 1501, 1498, -1, + 1495, 1522, 1524, -1, 1495, 1499, 1522, -1, + 1495, 1524, 1500, -1, 1495, 1500, 1501, -1, + 1506, 1500, 1504, -1, 1506, 1507, 1517, -1, + 1506, 1517, 1501, -1, 1506, 1501, 1500, -1, + 1514, 1517, 1507, -1, 1514, 1502, 1513, -1, + 1514, 2217, 1502, -1, 1514, 2216, 2217, -1, + 1514, 1507, 2216, -1, 1503, 1504, 1505, -1, + 1503, 1506, 1504, -1, 1503, 1507, 1506, -1, + 1503, 1508, 1509, -1, 1503, 1509, 1510, -1, + 1503, 1510, 1507, -1, 1503, 1505, 1511, -1, + 1503, 1511, 1508, -1, 1512, 1516, 1517, -1, + 1512, 1513, 1516, -1, 1512, 1517, 1514, -1, + 1512, 1514, 1513, -1, 1515, 1517, 1516, -1, + 1515, 1518, 1517, -1, 1515, 1516, 1518, -1, + 1519, 1521, 1520, -1, 1519, 1522, 1523, -1, + 1519, 1523, 1521, -1, 1519, 1524, 1522, -1, + 1519, 1525, 1524, -1, 1519, 1520, 1525, -1, + 2729, 2224, 1526, -1, 2729, 1526, 2723, -1, + 2718, 2202, 1527, -1, 2718, 2720, 2202, -1, + 2718, 1527, 2719, -1, 2223, 1528, 2224, -1, + 2223, 1529, 1528, -1, 2223, 2221, 1529, -1, + 1530, 2719, 2726, -1, 1530, 2726, 2725, -1, + 1530, 2725, 2719, -1, 1531, 1533, 1532, -1, + 1531, 1534, 1533, -1, 1531, 1532, 1535, -1, + 1531, 1535, 1534, -1, 1536, 1538, 1537, -1, + 1536, 1537, 1544, -1, 1536, 1540, 1539, -1, + 1536, 1545, 1540, -1, 1536, 1544, 1545, -1, + 1536, 1539, 1541, -1, 1536, 1542, 1538, -1, + 1536, 1541, 1542, -1, 1543, 1545, 1544, -1, + 1543, 1546, 2713, -1, 1543, 1547, 1546, -1, + 1543, 1544, 1547, -1, 1543, 2712, 1545, -1, + 1543, 2713, 2712, -1, 1548, 1549, 1682, -1, + 1548, 1558, 1549, -1, 1548, 1682, 1683, -1, + 1548, 2239, 1558, -1, 1548, 1550, 2239, -1, + 1548, 1683, 1550, -1, 1684, 1551, 1683, -1, + 1684, 1552, 1551, -1, 1684, 1553, 1552, -1, + 1684, 1685, 1553, -1, 2302, 2226, 1554, -1, + 2302, 1554, 1670, -1, 2229, 2237, 2230, -1, + 2229, 1557, 2237, -1, 2229, 2233, 1555, -1, + 2229, 1555, 1557, -1, 2236, 2230, 2237, -1, + 2236, 2240, 1556, -1, 2236, 1556, 2231, -1, + 2236, 2231, 2230, -1, 2241, 2237, 1557, -1, + 2241, 1558, 2239, -1, 2241, 1557, 1559, -1, + 2241, 1559, 1558, -1, 2244, 1568, 1580, -1, + 2244, 1560, 2248, -1, 2244, 1580, 1560, -1, + 1561, 1566, 1562, -1, 1561, 2356, 1563, -1, + 1561, 1563, 1564, -1, 1561, 1564, 1566, -1, + 1561, 1565, 2356, -1, 1561, 1562, 1565, -1, + 2243, 1567, 1566, -1, 2243, 2247, 1567, -1, + 2243, 1566, 1568, -1, 2243, 1568, 2244, -1, + 1569, 1571, 1570, -1, 1569, 1572, 1571, -1, + 1569, 1573, 1572, -1, 1569, 1574, 1573, -1, + 1569, 1570, 1575, -1, 1569, 1575, 1574, -1, + 1576, 1578, 1577, -1, 1576, 1579, 1578, -1, + 1576, 1580, 1579, -1, 1576, 1581, 1580, -1, + 1576, 1582, 1581, -1, 1576, 1577, 1582, -1, + 1583, 1585, 1584, -1, 1583, 1586, 1585, -1, + 1583, 1587, 1586, -1, 1583, 1588, 1587, -1, + 1583, 1589, 1588, -1, 1583, 1584, 1589, -1, + 2731, 2732, 1590, -1, 2731, 1590, 1591, -1, + 2731, 1591, 2249, -1, 1599, 1600, 1592, -1, + 1599, 1592, 1722, -1, 1599, 1593, 1602, -1, + 1599, 1722, 1593, -1, 1613, 2249, 1594, -1, + 1613, 1594, 1596, -1, 1613, 1596, 1602, -1, + 1613, 1602, 1612, -1, 1595, 1596, 1597, -1, + 1595, 1597, 1598, -1, 1595, 1600, 1599, -1, + 1595, 1598, 1601, -1, 1595, 1602, 1596, -1, + 1595, 1599, 1602, -1, 1595, 1603, 1600, -1, + 1595, 1601, 1603, -1, 1604, 1606, 1605, -1, + 1604, 1607, 1606, -1, 1604, 1605, 1608, -1, + 1604, 1609, 1607, -1, 1604, 1610, 1609, -1, + 1604, 1608, 2201, -1, 1604, 2200, 1610, -1, + 1604, 2201, 2200, -1, 2250, 1612, 1611, -1, + 2250, 1611, 2251, -1, 2250, 1613, 1612, -1, + 2250, 2249, 1613, -1, 2737, 2738, 2255, -1, + 2735, 2252, 2734, -1, 2338, 2258, 2255, -1, + 2338, 2255, 1614, -1, 2338, 1614, 2341, -1, + 1615, 1616, 1617, -1, 1615, 1617, 1618, -1, + 1615, 1618, 1619, -1, 1615, 1620, 1616, -1, + 1615, 1619, 2345, -1, 1615, 2345, 1620, -1, + 1621, 1623, 1622, -1, 1621, 1622, 1624, -1, + 1621, 1625, 1623, -1, 1621, 1624, 1625, -1, + 1633, 2752, 2755, -1, 1633, 1626, 2752, -1, + 1633, 2196, 1626, -1, 1633, 2195, 2196, -1, + 1633, 1642, 2195, -1, 2262, 1627, 1628, -1, + 2262, 1628, 2265, -1, 2262, 1629, 1627, -1, + 2262, 2263, 1629, -1, 2264, 1631, 1630, -1, + 2264, 1630, 2263, -1, 2264, 1632, 1631, -1, + 2264, 2266, 1632, -1, 1634, 2755, 2274, -1, + 1634, 1633, 2755, -1, 1634, 1642, 1633, -1, + 1634, 1641, 1642, -1, 1635, 3027, 1641, -1, + 1635, 1641, 1634, -1, 1635, 2274, 2273, -1, + 1635, 1634, 2274, -1, 3028, 2272, 3026, -1, + 3028, 3027, 1635, -1, 3028, 2273, 2272, -1, + 3028, 1635, 2273, -1, 1640, 3026, 2272, -1, + 1640, 1638, 1636, -1, 1640, 1637, 3026, -1, + 1640, 1636, 1637, -1, 2269, 1639, 1638, -1, + 2269, 2270, 1639, -1, 2269, 1638, 1640, -1, + 2269, 1640, 2272, -1, 2748, 1641, 2746, -1, + 2748, 2747, 2195, -1, 2748, 2195, 1642, -1, + 2748, 1642, 1641, -1, 2744, 2277, 2747, -1, + 2743, 2278, 2280, -1, 2284, 2285, 1646, -1, + 2284, 1646, 1648, -1, 2284, 1648, 2271, -1, + 2284, 2271, 2751, -1, 1643, 1644, 1645, -1, + 1643, 1646, 1644, -1, 1643, 1645, 1647, -1, + 1643, 1648, 1646, -1, 1643, 1649, 1648, -1, + 1643, 1647, 1649, -1, 1650, 1652, 1651, -1, + 1650, 1651, 1653, -1, 1650, 1654, 1652, -1, + 1650, 1655, 1654, -1, 1650, 1653, 1655, -1, + 2288, 1656, 2308, -1, 2288, 2415, 2416, -1, + 2288, 2416, 1656, -1, 2288, 2308, 2289, -1, + 2762, 2679, 2760, -1, 2762, 2990, 2679, -1, + 2992, 2293, 1661, -1, 2992, 1661, 2677, -1, + 2758, 2296, 2293, -1, 2761, 2759, 2144, -1, + 2761, 2144, 1657, -1, 2761, 1657, 2294, -1, + 1658, 1664, 1659, -1, 1658, 2296, 1660, -1, + 1658, 1660, 1664, -1, 1658, 2293, 2296, -1, + 1658, 1661, 2293, -1, 1658, 1659, 1661, -1, + 1662, 1664, 1663, -1, 1662, 1666, 1665, -1, + 1662, 1665, 1664, -1, 1662, 1667, 1666, -1, + 1662, 2292, 1667, -1, 1662, 1663, 2292, -1, + 2300, 1668, 2299, -1, 2300, 1669, 1668, -1, + 2300, 1670, 1669, -1, 2300, 2302, 1670, -1, + 2307, 1671, 2305, -1, 2307, 1672, 1671, -1, + 2307, 2309, 1673, -1, 2307, 1673, 1672, -1, + 1674, 1675, 1676, -1, 1674, 1678, 1677, -1, + 1674, 1676, 1678, -1, 1674, 1677, 1679, -1, + 1674, 1679, 1680, -1, 1674, 1680, 1675, -1, + 1681, 1683, 1682, -1, 1681, 1684, 1683, -1, + 1681, 1685, 1684, -1, 1681, 1682, 1691, -1, + 1681, 1691, 1685, -1, 1686, 1688, 1687, -1, + 1686, 1690, 1689, -1, 1686, 1691, 1690, -1, + 1686, 1687, 1691, -1, 1686, 1692, 1688, -1, + 1686, 1689, 1692, -1, 2311, 1693, 2312, -1, + 2311, 1694, 1693, -1, 2311, 1695, 1694, -1, + 2311, 2763, 1695, -1, 2313, 2317, 2314, -1, + 2313, 1711, 2317, -1, 2313, 2332, 1711, -1, + 2313, 2771, 2332, -1, 2316, 2314, 2317, -1, + 2316, 1706, 2314, -1, 2316, 2778, 2320, -1, + 2316, 2320, 1706, -1, 2779, 2780, 1696, -1, + 2779, 1697, 2321, -1, 2779, 1698, 1697, -1, + 2779, 1696, 1699, -1, 2779, 1699, 1698, -1, + 1701, 3031, 2452, -1, 1701, 2452, 1703, -1, + 1701, 1703, 1705, -1, 1701, 1705, 1702, -1, + 3030, 1700, 2327, -1, 3030, 3031, 1701, -1, + 3030, 2322, 1700, -1, 3030, 1702, 2322, -1, + 3030, 1701, 1702, -1, 2845, 1703, 1854, -1, + 2845, 2846, 1704, -1, 2845, 1704, 1703, -1, + 2315, 1705, 1704, -1, 2315, 1706, 1705, -1, + 2315, 1704, 2775, -1, 2315, 2314, 1706, -1, + 2785, 2330, 1879, -1, 1707, 1879, 1883, -1, + 1707, 2785, 1879, -1, 1707, 2787, 2785, -1, + 1707, 1708, 2787, -1, 1707, 1709, 1708, -1, + 1707, 1883, 1709, -1, 3036, 2791, 2336, -1, + 2796, 2333, 1902, -1, 2796, 1902, 2795, -1, + 2334, 2335, 1710, -1, 2334, 1711, 2798, -1, + 2334, 2318, 1711, -1, 2334, 1710, 2318, -1, + 1717, 2767, 2792, -1, 1717, 1712, 1718, -1, + 1717, 2790, 1712, -1, 1717, 2792, 2790, -1, + 2765, 1713, 2763, -1, 2765, 2764, 1714, -1, + 2765, 1714, 1715, -1, 2765, 1715, 1713, -1, + 1716, 2764, 2767, -1, 1716, 2767, 1717, -1, + 1716, 1717, 1718, -1, 1716, 1718, 1719, -1, + 1716, 1719, 1720, -1, 1716, 1720, 2764, -1, + 1727, 1721, 1722, -1, 1727, 1723, 1729, -1, + 1727, 1722, 1723, -1, 1727, 1728, 1721, -1, + 2340, 2342, 1728, -1, 2340, 1728, 1734, -1, + 1724, 1726, 1725, -1, 1724, 1728, 1727, -1, + 1724, 1734, 1728, -1, 1724, 1725, 1734, -1, + 1724, 1729, 1726, -1, 1724, 1727, 1729, -1, + 1730, 1731, 2339, -1, 1730, 2339, 2340, -1, + 1730, 1733, 1732, -1, 1730, 1732, 1731, -1, + 1730, 1734, 1733, -1, 1730, 2340, 1734, -1, + 2349, 2350, 2345, -1, 2805, 1735, 2367, -1, + 2805, 1736, 1735, -1, 2805, 2807, 1736, -1, + 2365, 2366, 1737, -1, 2365, 1737, 2352, -1, + 2365, 2352, 2353, -1, 2365, 2353, 2806, -1, + 2354, 1743, 1738, -1, 2354, 1738, 1739, -1, + 2354, 1741, 1743, -1, 2354, 2352, 1741, -1, + 2354, 1739, 2355, -1, 1740, 1741, 2361, -1, + 1740, 3044, 1742, -1, 1740, 1742, 1743, -1, + 1740, 1743, 1741, -1, 1740, 2361, 3043, -1, + 1740, 3043, 3044, -1, 1751, 2362, 1752, -1, + 1751, 1744, 2362, -1, 1751, 1745, 1744, -1, + 1751, 1753, 1745, -1, 2804, 3048, 1749, -1, + 1746, 1747, 1753, -1, 1746, 1748, 1747, -1, + 1746, 1749, 1748, -1, 1746, 2804, 1749, -1, + 1746, 1753, 2364, -1, 1746, 2364, 2804, -1, + 3064, 1752, 2366, -1, 1750, 3065, 2364, -1, + 1750, 1751, 1752, -1, 1750, 1752, 3064, -1, + 1750, 3064, 3065, -1, 1750, 2364, 1753, -1, + 1750, 1753, 1751, -1, 2808, 2367, 2369, -1, + 1754, 1756, 1755, -1, 1754, 1755, 1757, -1, + 1754, 1758, 1756, -1, 1754, 1759, 1758, -1, + 1754, 1760, 1759, -1, 1754, 1761, 1760, -1, + 1754, 1757, 1761, -1, 2384, 2382, 2374, -1, + 2811, 2381, 2812, -1, 2377, 2823, 1762, -1, + 2377, 1762, 2378, -1, 2822, 2812, 2381, -1, + 2822, 2823, 2377, -1, 2822, 2377, 2812, -1, + 2380, 1764, 1763, -1, 2380, 2387, 1764, -1, + 2380, 1763, 2819, -1, 2380, 2386, 2387, -1, + 1771, 2818, 1765, -1, 1771, 1766, 1770, -1, + 1771, 1765, 1767, -1, 1771, 1767, 1766, -1, + 1768, 2821, 2818, -1, 1768, 1770, 1769, -1, + 1768, 1769, 1785, -1, 1768, 1785, 2821, -1, + 1768, 1771, 1770, -1, 1768, 2818, 1771, -1, + 1772, 1773, 1774, -1, 1772, 1774, 1775, -1, + 1772, 1775, 1776, -1, 1772, 1777, 1773, -1, + 1772, 1776, 1778, -1, 1772, 1778, 1777, -1, + 1779, 1781, 1780, -1, 1779, 1782, 1783, -1, + 1779, 1783, 1781, -1, 1779, 1784, 1782, -1, + 1779, 1785, 1784, -1, 1779, 1780, 1785, -1, + 1790, 1789, 1786, -1, 1790, 1787, 1791, -1, + 1790, 1786, 1788, -1, 1790, 1788, 1787, -1, + 2379, 1791, 2816, -1, 2379, 2378, 1789, -1, + 2379, 1789, 1790, -1, 2379, 1790, 1791, -1, + 1816, 2815, 2816, -1, 1816, 2816, 1791, -1, + 1816, 1792, 1818, -1, 1816, 1791, 1792, -1, + 1793, 1795, 1794, -1, 1793, 1796, 1795, -1, + 1793, 1794, 1797, -1, 1793, 1798, 1796, -1, + 1793, 2684, 1798, -1, 1793, 1797, 2684, -1, + 2391, 1799, 1800, -1, 2391, 1801, 2395, -1, + 2391, 1800, 1801, -1, 2391, 2392, 1799, -1, + 1860, 2408, 1859, -1, 1860, 2406, 2408, -1, + 1860, 1802, 2406, -1, 1860, 1861, 1802, -1, + 2404, 2397, 2408, -1, 2403, 1803, 2401, -1, + 2403, 1804, 1803, -1, 2403, 2407, 1804, -1, + 2403, 2401, 2404, -1, 2420, 1805, 2423, -1, + 2420, 1806, 1805, -1, 2420, 1807, 1806, -1, + 2420, 2421, 1807, -1, 2413, 1808, 2418, -1, + 2422, 2424, 1808, -1, 2422, 1808, 2413, -1, + 2429, 1810, 1809, -1, 2429, 1809, 1811, -1, + 2429, 1811, 2428, -1, 2429, 2430, 1810, -1, + 2427, 2428, 1812, -1, 2427, 1812, 1815, -1, + 2427, 1813, 2432, -1, 2427, 1815, 1813, -1, + 1814, 2376, 2815, -1, 1814, 1815, 2376, -1, + 1814, 2815, 1816, -1, 1814, 1817, 1815, -1, + 1814, 1818, 1817, -1, 1814, 1816, 1818, -1, + 1819, 1821, 1820, -1, 1819, 1822, 1821, -1, + 1819, 1824, 1823, -1, 1819, 1820, 1824, -1, + 1819, 1823, 1822, -1, 2457, 1825, 2461, -1, + 2457, 2458, 1825, -1, 1826, 2445, 1827, -1, + 1826, 1840, 1828, -1, 1826, 1828, 2444, -1, + 1826, 2444, 2445, -1, 1826, 1827, 1841, -1, + 1826, 1841, 1840, -1, 2440, 1830, 1829, -1, + 2440, 1829, 2445, -1, 2440, 1831, 1830, -1, + 2440, 2441, 1831, -1, 1832, 1834, 1833, -1, + 1832, 1835, 1834, -1, 1832, 1833, 1836, -1, + 1832, 1837, 1835, -1, 1832, 1836, 1838, -1, + 1832, 1838, 1837, -1, 1839, 1840, 1841, -1, + 1839, 1845, 1840, -1, 1839, 1841, 1842, -1, + 1839, 1843, 1845, -1, 1839, 1842, 2433, -1, + 1839, 2433, 1843, -1, 1844, 1846, 1845, -1, + 1844, 1847, 1846, -1, 1844, 1848, 1847, -1, + 1844, 1849, 1848, -1, 1844, 1850, 1849, -1, + 1844, 1845, 1850, -1, 1853, 2446, 2453, -1, + 1853, 1851, 1852, -1, 1853, 2453, 1855, -1, + 1853, 1855, 1851, -1, 2841, 1852, 2842, -1, + 2841, 1853, 1852, -1, 2841, 2446, 1853, -1, + 2844, 1854, 2455, -1, 2844, 2455, 2446, -1, + 2844, 2845, 1854, -1, 2454, 1854, 2452, -1, + 2454, 2455, 1854, -1, 2460, 1855, 2453, -1, + 2460, 1856, 1855, -1, 2460, 2465, 1856, -1, + 1857, 1859, 1858, -1, 1857, 1861, 1860, -1, + 1857, 1860, 1859, -1, 1857, 1885, 1861, -1, + 1857, 1862, 1885, -1, 1857, 1858, 1862, -1, + 1863, 1865, 1864, -1, 1863, 1866, 1865, -1, + 1863, 1869, 1866, -1, 1863, 1873, 1869, -1, + 1863, 1867, 1873, -1, 1863, 1864, 1867, -1, + 1874, 1875, 1868, -1, 1874, 1869, 1873, -1, + 1874, 1870, 1869, -1, 1874, 1868, 1870, -1, + 1871, 1873, 1872, -1, 1871, 1875, 1874, -1, + 1871, 1874, 1873, -1, 1871, 1876, 1875, -1, + 1871, 1877, 1876, -1, 1871, 1872, 1877, -1, + 1878, 1879, 1880, -1, 1878, 1880, 1881, -1, + 1878, 1881, 1882, -1, 1878, 1883, 1879, -1, + 1878, 2467, 1883, -1, 1878, 1882, 2467, -1, + 2509, 1885, 1884, -1, 2509, 2466, 1885, -1, + 2509, 1884, 2891, -1, 1886, 1888, 1887, -1, + 1886, 2772, 2773, -1, 1886, 2773, 1888, -1, + 1886, 1889, 2772, -1, 1886, 1890, 1889, -1, + 1886, 1887, 1890, -1, 2878, 1891, 1892, -1, + 2878, 1892, 1896, -1, 2878, 1896, 2881, -1, + 2878, 2879, 1891, -1, 2472, 1913, 2471, -1, + 2472, 1894, 1893, -1, 2472, 1893, 1913, -1, + 3089, 3118, 3117, -1, 2473, 1895, 1894, -1, + 2473, 1894, 2472, -1, 2864, 2474, 1895, -1, + 2864, 1895, 2473, -1, 2479, 2881, 1896, -1, + 2479, 1896, 3104, -1, 2479, 2858, 2480, -1, + 2479, 3104, 2858, -1, 2478, 1908, 2475, -1, + 2478, 2477, 1908, -1, 2514, 2476, 3112, -1, + 2514, 3112, 3079, -1, 2880, 1897, 2879, -1, + 2880, 2095, 1897, -1, 2880, 2867, 2095, -1, + 3113, 3112, 2476, -1, 2483, 2968, 2482, -1, + 2483, 3147, 2968, -1, 2483, 2482, 2852, -1, + 2500, 2499, 1898, -1, 2500, 1898, 2486, -1, + 2490, 2499, 2491, -1, 2490, 1898, 2499, -1, + 2490, 2697, 1898, -1, 2490, 2971, 2697, -1, + 2502, 1899, 2518, -1, 2502, 2518, 2503, -1, + 2502, 1900, 1899, -1, 2502, 2501, 1900, -1, + 2498, 2491, 2499, -1, 2498, 2495, 2491, -1, + 1901, 2883, 2482, -1, 1901, 2882, 2883, -1, + 1901, 2492, 2882, -1, 1901, 2482, 2968, -1, + 1901, 2967, 2492, -1, 1901, 2968, 2967, -1, + 2508, 2507, 1902, -1, 2508, 1902, 1903, -1, + 3084, 2856, 2505, -1, 2886, 3082, 3083, -1, + 2886, 3083, 2508, -1, 2886, 2508, 1903, -1, + 2886, 1903, 2888, -1, 2899, 1904, 2906, -1, + 2899, 2901, 1905, -1, 2899, 1905, 1904, -1, + 2915, 2914, 2636, -1, 1907, 2638, 2639, -1, + 1907, 2639, 2494, -1, 2633, 2638, 1907, -1, + 2633, 1907, 2517, -1, 1906, 2503, 2517, -1, + 1906, 2494, 2495, -1, 1906, 1907, 2494, -1, + 1906, 2517, 1907, -1, 1906, 2498, 2503, -1, + 1906, 2495, 2498, -1, 2522, 1908, 2477, -1, + 2522, 2523, 1908, -1, 1909, 2477, 2511, -1, + 1909, 2511, 2635, -1, 1909, 2635, 2133, -1, + 1909, 2133, 2521, -1, 1909, 2521, 2522, -1, + 1909, 2522, 2477, -1, 1910, 1911, 1912, -1, + 1910, 1912, 2470, -1, 1910, 2470, 1913, -1, + 1910, 1913, 1914, -1, 1910, 1914, 1915, -1, + 1910, 1915, 1911, -1, 2531, 1916, 2526, -1, + 2531, 2533, 1917, -1, 2531, 1917, 1916, -1, + 2918, 1918, 2534, -1, 2918, 1919, 1918, -1, + 2918, 2920, 1919, -1, 1923, 1920, 1921, -1, + 1923, 1921, 1953, -1, 1923, 1953, 2549, -1, + 1923, 1924, 1920, -1, 2545, 2547, 1922, -1, + 2545, 1922, 2542, -1, 2923, 2546, 1924, -1, + 3123, 3125, 3124, -1, 2548, 1924, 1923, -1, + 2548, 1923, 2549, -1, 2548, 2923, 1924, -1, + 2548, 3121, 2923, -1, 1925, 1927, 1926, -1, + 1925, 1926, 1928, -1, 1925, 1929, 1927, -1, + 1925, 1928, 1930, -1, 1925, 1931, 1929, -1, + 1925, 1930, 1931, -1, 2156, 1932, 2002, -1, + 2156, 2155, 1932, -1, 1933, 2157, 2003, -1, + 1933, 2003, 1934, -1, 1933, 1934, 1935, -1, + 1933, 1935, 2159, -1, 1933, 2159, 2152, -1, + 1933, 2152, 2157, -1, 2553, 1936, 2550, -1, + 2553, 2542, 1936, -1, 2553, 2554, 2542, -1, + 1941, 1960, 1937, -1, 1941, 1937, 1938, -1, + 1941, 1938, 1939, -1, 1941, 1939, 1947, -1, + 1946, 1944, 1940, -1, 1946, 1960, 1941, -1, + 1946, 1941, 1947, -1, 1946, 1940, 1942, -1, + 1946, 1942, 1960, -1, 1943, 1945, 1944, -1, + 1943, 1944, 1946, -1, 1943, 1946, 1947, -1, + 1943, 1948, 1945, -1, 1943, 1949, 1948, -1, + 1943, 1950, 1949, -1, 1943, 1947, 1950, -1, + 1951, 1952, 2549, -1, 1951, 1953, 1952, -1, + 1951, 2549, 1953, -1, 2930, 2558, 1954, -1, + 2930, 1954, 2932, -1, 1969, 1968, 1955, -1, + 1969, 1955, 1956, -1, 1969, 2556, 2560, -1, + 1969, 1956, 2556, -1, 1957, 1959, 1958, -1, + 1957, 2931, 1959, -1, 1957, 1958, 1960, -1, + 1957, 1960, 1961, -1, 1957, 1961, 2931, -1, + 2563, 1962, 1963, -1, 2563, 1963, 2564, -1, + 2563, 1964, 1962, -1, 2563, 2568, 1964, -1, + 2565, 1965, 2537, -1, 2565, 2564, 1965, -1, + 1966, 1967, 1968, -1, 1966, 2561, 1967, -1, + 1966, 1968, 1969, -1, 1966, 2560, 2561, -1, + 1966, 1969, 2560, -1, 1981, 1970, 1971, -1, + 1981, 1973, 1972, -1, 1981, 1971, 1973, -1, + 1981, 1974, 1970, -1, 1981, 1972, 1980, -1, + 1981, 1979, 1974, -1, 1975, 1976, 1977, -1, + 1975, 1977, 1978, -1, 1975, 1978, 1979, -1, + 1975, 1980, 1976, -1, 1975, 1979, 1981, -1, + 1975, 1981, 1980, -1, 1982, 1983, 1984, -1, + 1982, 1985, 1983, -1, 1982, 1984, 1986, -1, + 1982, 1986, 1985, -1, 1987, 1988, 1989, -1, + 1987, 1989, 1990, -1, 1987, 2607, 1988, -1, + 1987, 1990, 2607, -1, 1991, 1992, 1998, -1, + 1991, 1998, 1993, -1, 1991, 1994, 1992, -1, + 1991, 1993, 1994, -1, 1995, 1996, 1997, -1, + 1995, 1997, 1998, -1, 1995, 1999, 1996, -1, + 1995, 2607, 1999, -1, 1995, 1998, 2607, -1, + 2000, 2002, 2001, -1, 2000, 2003, 2157, -1, + 2000, 2004, 2003, -1, 2000, 2001, 2004, -1, + 2000, 2156, 2002, -1, 2000, 2157, 2156, -1, + 2005, 2006, 2580, -1, 2005, 2007, 2006, -1, + 2005, 2008, 2007, -1, 2005, 2580, 2009, -1, + 2005, 2009, 2010, -1, 2005, 2010, 2008, -1, + 2944, 2012, 2011, -1, 2944, 2011, 2575, -1, + 2944, 2942, 2012, -1, 2944, 2575, 2940, -1, + 2013, 2946, 2014, -1, 2013, 2015, 2016, -1, + 2013, 2014, 2015, -1, 2013, 2016, 2017, -1, + 2013, 2017, 2018, -1, 2013, 2018, 2946, -1, + 3129, 2573, 2570, -1, 3133, 2576, 2937, -1, + 2585, 2579, 2584, -1, 3137, 2592, 2593, -1, + 3137, 2593, 3138, -1, 3137, 3136, 2019, -1, + 3137, 2019, 2592, -1, 2586, 2024, 2023, -1, + 2586, 2023, 2667, -1, 2590, 2665, 2593, -1, + 2020, 2021, 2024, -1, 2020, 2589, 2021, -1, + 2020, 2588, 2589, -1, 2020, 2024, 2586, -1, + 2020, 2586, 2588, -1, 2022, 2023, 2024, -1, + 2022, 2025, 2026, -1, 2022, 2024, 2025, -1, + 2022, 2026, 2027, -1, 2022, 2027, 2028, -1, + 2022, 2028, 2023, -1, 2033, 2605, 2029, -1, + 2033, 2029, 2031, -1, 2033, 2606, 2605, -1, + 2033, 2035, 2606, -1, 2030, 2031, 2032, -1, + 2030, 2032, 2040, -1, 2030, 2033, 2031, -1, + 2030, 2040, 2034, -1, 2030, 2034, 2035, -1, + 2030, 2035, 2033, -1, 2599, 2036, 2037, -1, + 2599, 2598, 2036, -1, 2599, 2038, 2600, -1, + 2599, 2607, 2038, -1, 2599, 2037, 2607, -1, + 2596, 2039, 2597, -1, 2596, 2040, 2039, -1, + 2596, 2601, 2041, -1, 2596, 2041, 2040, -1, + 2528, 2042, 2527, -1, 2528, 2044, 2043, -1, + 2528, 2043, 2042, -1, 2528, 2526, 2044, -1, + 2536, 2045, 2922, -1, 2536, 2046, 2045, -1, + 2536, 2527, 2046, -1, 2536, 2535, 2527, -1, + 2047, 2048, 2049, -1, 2047, 2049, 2050, -1, + 2047, 2051, 2048, -1, 2047, 2050, 2052, -1, + 2047, 2052, 2053, -1, 2047, 2053, 2051, -1, + 2054, 2062, 2055, -1, 2054, 2055, 2056, -1, + 2054, 2056, 2919, -1, 2054, 2919, 2057, -1, + 2054, 2057, 2058, -1, 2054, 2058, 2062, -1, + 2059, 2061, 2060, -1, 2059, 2060, 2062, -1, + 2059, 2063, 2061, -1, 2059, 2062, 2064, -1, + 2059, 2064, 2065, -1, 2059, 2065, 2063, -1, + 2066, 2068, 2067, -1, 2066, 2067, 2069, -1, + 2066, 2070, 2068, -1, 2066, 2069, 2070, -1, + 2071, 2072, 2073, -1, 2071, 2074, 2072, -1, + 2071, 2073, 2075, -1, 2071, 2075, 2074, -1, + 2603, 2076, 2604, -1, 2603, 2077, 2076, -1, + 2603, 2607, 2077, -1, 2961, 2608, 2078, -1, + 2961, 2101, 2962, -1, 2961, 2078, 2101, -1, + 2079, 2080, 2102, -1, 2079, 2082, 2081, -1, + 2079, 2083, 2082, -1, 2079, 2102, 2083, -1, + 2079, 2081, 2084, -1, 2079, 2084, 2080, -1, + 2959, 2085, 2956, -1, 2959, 2610, 2085, -1, + 2964, 2962, 2620, -1, 2964, 2086, 2963, -1, + 2964, 2087, 2086, -1, 2964, 2088, 2087, -1, + 2964, 2620, 2088, -1, 2089, 2611, 2090, -1, + 2089, 2091, 2092, -1, 2089, 2090, 2091, -1, + 2089, 2092, 2093, -1, 2089, 2093, 2094, -1, + 2089, 2094, 2611, -1, 2612, 2611, 2094, -1, + 2612, 2094, 2095, -1, 2612, 2867, 2868, -1, + 2612, 2095, 2867, -1, 3144, 2868, 2866, -1, + 3141, 2096, 2966, -1, 3141, 2097, 2096, -1, + 3141, 3143, 2097, -1, 2098, 2962, 2101, -1, + 2098, 2101, 2618, -1, 2098, 2618, 2962, -1, + 2615, 2099, 2616, -1, 2615, 2114, 2099, -1, + 2100, 2115, 2621, -1, 2100, 2618, 2101, -1, + 2100, 2621, 2618, -1, 2100, 2101, 2102, -1, + 2100, 2102, 2103, -1, 2100, 2103, 2115, -1, + 2104, 2113, 2109, -1, 2104, 2105, 2106, -1, + 2104, 2109, 2105, -1, 2104, 2106, 2107, -1, + 2104, 2107, 2108, -1, 2104, 2108, 2113, -1, + 2116, 2109, 2113, -1, 2116, 2115, 2110, -1, + 2116, 2110, 2111, -1, 2116, 2111, 2109, -1, + 2112, 2113, 2114, -1, 2112, 2615, 2621, -1, + 2112, 2114, 2615, -1, 2112, 2621, 2115, -1, + 2112, 2115, 2116, -1, 2112, 2116, 2113, -1, + 2625, 2117, 2627, -1, 2625, 2118, 2117, -1, + 2625, 2626, 2119, -1, 2625, 2119, 2118, -1, + 2120, 2121, 2624, -1, 2120, 2624, 2623, -1, + 2120, 2122, 2121, -1, 2120, 2123, 2122, -1, + 2120, 2124, 2123, -1, 2120, 2623, 2124, -1, + 2594, 2125, 2589, -1, 2594, 2591, 2126, -1, + 2594, 2126, 2127, -1, 2594, 2127, 2125, -1, + 2128, 2175, 2129, -1, 2128, 2174, 2175, -1, + 2128, 2130, 2174, -1, 2128, 2129, 2131, -1, + 2128, 2132, 2130, -1, 2128, 2131, 2132, -1, + 2637, 2632, 2133, -1, 2637, 2133, 2635, -1, + 2649, 2648, 2641, -1, 2649, 2645, 2651, -1, + 2704, 2703, 2658, -1, 2664, 3138, 2665, -1, + 2664, 2669, 2661, -1, 2583, 2139, 2138, -1, + 2583, 2134, 2139, -1, 2583, 2953, 2134, -1, + 2583, 2138, 2582, -1, 2135, 2136, 2137, -1, + 2135, 2137, 2138, -1, 2135, 2138, 2139, -1, + 2135, 2139, 2140, -1, 2135, 2140, 2141, -1, + 2135, 2141, 2136, -1, 2671, 2142, 2143, -1, + 2671, 2674, 2142, -1, 2671, 2143, 2691, -1, + 2671, 2691, 2672, -1, 2980, 2987, 2982, -1, + 2970, 2492, 2967, -1, 2682, 2144, 2759, -1, + 2682, 2683, 2144, -1, 2689, 2690, 2145, -1, + 2689, 2145, 2146, -1, 2689, 2146, 2147, -1, + 2689, 2147, 2693, -1, 2695, 2149, 2148, -1, + 2695, 2150, 2149, -1, 2695, 2983, 2150, -1, + 2695, 2148, 2696, -1, 2151, 2152, 2153, -1, + 2151, 2154, 2155, -1, 2151, 2153, 2154, -1, + 2151, 2155, 2156, -1, 2151, 2157, 2152, -1, + 2151, 2156, 2157, -1, 2158, 2159, 2650, -1, + 2158, 2650, 2652, -1, 2158, 2160, 2159, -1, + 2158, 2652, 2699, -1, 2158, 2161, 2160, -1, + 2158, 2699, 2161, -1, 2700, 2652, 2651, -1, + 2700, 2651, 2702, -1, 2700, 2699, 2652, -1, + 2700, 2702, 3007, -1, 2178, 2163, 2166, -1, + 2178, 2176, 2163, -1, 2162, 2166, 2163, -1, + 2162, 2163, 2182, -1, 2162, 2182, 2181, -1, + 2162, 2181, 2164, -1, 2162, 2164, 2165, -1, + 2162, 2165, 2166, -1, 2707, 2710, 2178, -1, + 2707, 2178, 2166, -1, 2707, 2167, 2708, -1, + 2707, 2166, 2167, -1, 2168, 2190, 2169, -1, + 2168, 2171, 2170, -1, 2168, 2172, 2171, -1, + 2168, 2169, 2172, -1, 2168, 2186, 2190, -1, + 2168, 2170, 2186, -1, 2173, 2175, 2174, -1, + 2173, 2174, 2176, -1, 2173, 2177, 2175, -1, + 2173, 2176, 2178, -1, 2173, 2710, 2177, -1, + 2173, 2178, 2710, -1, 2179, 2180, 2181, -1, + 2179, 2181, 2182, -1, 2179, 2183, 2180, -1, + 2179, 2184, 2183, -1, 2179, 2185, 2184, -1, + 2179, 2182, 2185, -1, 2191, 2190, 2186, -1, + 2191, 2186, 2187, -1, 2191, 2187, 2192, -1, + 2188, 2194, 2276, -1, 2188, 2276, 2189, -1, + 2188, 2189, 2190, -1, 2188, 2190, 2191, -1, + 2188, 2192, 2194, -1, 2188, 2191, 2192, -1, + 2193, 2747, 2277, -1, 2193, 2277, 2194, -1, + 2193, 2195, 2747, -1, 2193, 2196, 2195, -1, + 2193, 2194, 2196, -1, 2197, 2208, 2198, -1, + 2197, 2198, 2199, -1, 2197, 2207, 2208, -1, + 2197, 2199, 2200, -1, 2197, 2200, 2201, -1, + 2197, 2201, 2207, -1, 3168, 2712, 2713, -1, + 3012, 3019, 2202, -1, 3012, 2203, 3013, -1, + 3012, 2202, 2203, -1, 2204, 2210, 2207, -1, + 2204, 2207, 2205, -1, 2204, 2206, 2210, -1, + 2204, 2205, 2206, -1, 2209, 2208, 2207, -1, + 2209, 2207, 2210, -1, 2209, 3014, 2208, -1, + 2209, 2715, 3014, -1, 2716, 2715, 2209, -1, + 2716, 2210, 3011, -1, 2716, 2209, 2210, -1, + 2211, 2212, 2213, -1, 2211, 2214, 2215, -1, + 2211, 2215, 2212, -1, 2211, 2217, 2216, -1, + 2211, 2216, 2214, -1, 2211, 2218, 2217, -1, + 2211, 2213, 2218, -1, 2721, 2719, 2725, -1, + 2721, 2722, 2720, -1, 2219, 2726, 2220, -1, + 2219, 2223, 2726, -1, 2219, 2221, 2223, -1, + 2219, 2220, 2222, -1, 2219, 2222, 2221, -1, + 2727, 2726, 2223, -1, 2727, 2224, 2729, -1, + 2727, 2223, 2224, -1, 2303, 2301, 2225, -1, + 2303, 2226, 2302, -1, 2303, 2225, 2227, -1, + 2303, 2227, 2226, -1, 2228, 2229, 2230, -1, + 2228, 2230, 2231, -1, 2228, 2232, 2233, -1, + 2228, 2233, 2229, -1, 2228, 2231, 2234, -1, + 2228, 2234, 2232, -1, 2235, 2236, 2237, -1, + 2235, 2239, 2238, -1, 2235, 2238, 2240, -1, + 2235, 2240, 2236, -1, 2235, 2241, 2239, -1, + 2235, 2237, 2241, -1, 2242, 2243, 2244, -1, + 2242, 2245, 2246, -1, 2242, 2246, 2247, -1, + 2242, 2247, 2243, -1, 2242, 2248, 2245, -1, + 2242, 2244, 2248, -1, 2733, 2731, 2249, -1, + 2733, 2249, 2250, -1, 2733, 2251, 2738, -1, + 2733, 2250, 2251, -1, 2739, 2740, 2252, -1, + 2739, 2252, 2735, -1, 2253, 2254, 2740, -1, + 2253, 2740, 2737, -1, 2253, 2255, 2254, -1, + 2253, 2737, 2255, -1, 2256, 2257, 2258, -1, + 2256, 2258, 2338, -1, 2256, 2338, 2339, -1, + 2256, 2259, 2257, -1, 2256, 2260, 2259, -1, + 2256, 2339, 2260, -1, 2261, 2263, 2262, -1, + 2261, 2264, 2263, -1, 2261, 2262, 2265, -1, + 2261, 2266, 2264, -1, 2261, 2265, 2267, -1, + 2261, 2267, 2266, -1, 2268, 2270, 2269, -1, + 2268, 2271, 2270, -1, 2268, 2272, 2273, -1, + 2268, 2269, 2272, -1, 2268, 2273, 2274, -1, + 2268, 2274, 2271, -1, 2283, 2282, 2275, -1, + 2283, 2275, 2276, -1, 2283, 2276, 2277, -1, + 2283, 2277, 2744, -1, 2745, 2741, 2278, -1, + 2745, 2278, 2743, -1, 2279, 2743, 2280, -1, + 2279, 2280, 2281, -1, 2279, 2281, 2282, -1, + 2279, 2282, 2283, -1, 2279, 2744, 2743, -1, + 2279, 2283, 2744, -1, 2750, 2284, 2751, -1, + 2750, 2285, 2284, -1, 2750, 2286, 2285, -1, + 2750, 2754, 2286, -1, 2287, 2288, 2289, -1, + 2287, 2291, 2290, -1, 2287, 2290, 2415, -1, + 2287, 2415, 2288, -1, 2287, 2292, 2291, -1, + 2287, 2289, 2292, -1, 2994, 2293, 2992, -1, + 2994, 2758, 2293, -1, 2994, 2762, 2758, -1, + 2994, 2990, 2762, -1, 2757, 2294, 2295, -1, + 2757, 2761, 2294, -1, 2757, 2295, 2296, -1, + 2757, 2296, 2758, -1, 2297, 2299, 2298, -1, + 2297, 2300, 2299, -1, 2297, 2298, 2301, -1, + 2297, 2302, 2300, -1, 2297, 2301, 2303, -1, + 2297, 2303, 2302, -1, 2304, 2305, 2306, -1, + 2304, 2307, 2305, -1, 2304, 2306, 2308, -1, + 2304, 2309, 2307, -1, 2304, 2310, 2309, -1, + 2304, 2308, 2310, -1, 2766, 2311, 2312, -1, + 2766, 2312, 2791, -1, 2766, 2763, 2311, -1, + 2770, 2313, 2314, -1, 2770, 2315, 2775, -1, + 2770, 2314, 2315, -1, 2770, 2771, 2313, -1, + 2777, 2316, 2317, -1, 2777, 2317, 2318, -1, + 2777, 2318, 2782, -1, 2777, 2778, 2316, -1, + 2319, 2320, 2778, -1, 2319, 2778, 2779, -1, + 2319, 2779, 2321, -1, 2319, 2322, 2320, -1, + 2319, 2323, 2322, -1, 2319, 2324, 2323, -1, + 2319, 2325, 2324, -1, 2319, 2321, 2326, -1, + 2319, 2326, 2325, -1, 2783, 3030, 2327, -1, + 2783, 2328, 2784, -1, 2783, 2329, 2328, -1, + 2783, 2327, 2329, -1, 3068, 2330, 2785, -1, + 3068, 2843, 2330, -1, 3038, 2790, 2792, -1, + 2799, 2331, 2333, -1, 2799, 2332, 2331, -1, + 2799, 2798, 2332, -1, 3039, 2333, 2796, -1, + 3039, 2799, 2333, -1, 2797, 2334, 2798, -1, + 2797, 2335, 2334, -1, 2797, 2336, 2335, -1, + 2797, 3036, 2336, -1, 2337, 2339, 2338, -1, + 2337, 2340, 2339, -1, 2337, 2338, 2341, -1, + 2337, 2341, 2342, -1, 2337, 2342, 2340, -1, + 2343, 2345, 2344, -1, 2343, 2349, 2345, -1, + 2343, 2344, 2348, -1, 2343, 2348, 2349, -1, + 2346, 2348, 2347, -1, 2346, 2349, 2348, -1, + 2346, 2347, 2350, -1, 2346, 2350, 2349, -1, + 2351, 2353, 2352, -1, 2351, 2352, 2354, -1, + 2351, 2354, 2355, -1, 2351, 2356, 2353, -1, + 2351, 2355, 2357, -1, 2351, 2357, 2356, -1, + 3042, 2358, 3047, -1, 3042, 2363, 2358, -1, + 2359, 2361, 2360, -1, 2359, 3043, 2361, -1, + 2359, 2360, 2362, -1, 2359, 3042, 3043, -1, + 2359, 2362, 2363, -1, 2359, 2363, 3042, -1, + 2809, 2364, 3065, -1, 2809, 2804, 2364, -1, + 3063, 2365, 2806, -1, 3063, 2366, 2365, -1, + 3063, 3064, 2366, -1, 3061, 2805, 2367, -1, + 3061, 2367, 2808, -1, 3058, 2369, 2368, -1, + 3058, 2808, 2369, -1, 3058, 2368, 3055, -1, + 3058, 3054, 2808, -1, 2370, 2385, 2384, -1, + 2370, 2372, 2371, -1, 2370, 2371, 2385, -1, + 2370, 2373, 2372, -1, 2370, 2374, 2373, -1, + 2370, 2384, 2374, -1, 2813, 2375, 2382, -1, + 2813, 2382, 2811, -1, 2813, 2815, 2376, -1, + 2813, 2376, 2375, -1, 2814, 2377, 2378, -1, + 2814, 2812, 2377, -1, 2814, 2378, 2379, -1, + 2814, 2379, 2816, -1, 2820, 2380, 2819, -1, + 2820, 2386, 2380, -1, 2820, 2822, 2381, -1, + 2820, 2381, 2386, -1, 2388, 2386, 2381, -1, + 2388, 2382, 2384, -1, 2388, 2381, 2811, -1, + 2388, 2811, 2382, -1, 2383, 2384, 2385, -1, + 2383, 2387, 2386, -1, 2383, 2388, 2384, -1, + 2383, 2386, 2388, -1, 2383, 2385, 2389, -1, + 2383, 2389, 2387, -1, 2390, 2392, 2391, -1, + 2390, 2393, 2398, -1, 2390, 2398, 2392, -1, + 2390, 2394, 2393, -1, 2390, 2395, 2394, -1, + 2390, 2391, 2395, -1, 2396, 2397, 2404, -1, + 2396, 2399, 2398, -1, 2396, 2398, 2397, -1, + 2396, 2400, 2399, -1, 2396, 2401, 2400, -1, + 2396, 2404, 2401, -1, 2402, 2403, 2404, -1, + 2402, 2406, 2405, -1, 2402, 2405, 2407, -1, + 2402, 2407, 2403, -1, 2402, 2408, 2406, -1, + 2402, 2404, 2408, -1, 2409, 2413, 2414, -1, + 2409, 2410, 2421, -1, 2409, 2421, 2422, -1, + 2409, 2422, 2413, -1, 2409, 2411, 2410, -1, + 2409, 2414, 2411, -1, 2412, 2414, 2413, -1, + 2412, 2416, 2415, -1, 2412, 2415, 2414, -1, + 2412, 2417, 2416, -1, 2412, 2418, 2417, -1, + 2412, 2413, 2418, -1, 2419, 2421, 2420, -1, + 2419, 2422, 2421, -1, 2419, 2420, 2423, -1, + 2419, 2424, 2422, -1, 2419, 2423, 2425, -1, + 2419, 2425, 2424, -1, 2426, 2428, 2427, -1, + 2426, 2429, 2428, -1, 2426, 2430, 2429, -1, + 2426, 2431, 2430, -1, 2426, 2432, 2431, -1, + 2426, 2427, 2432, -1, 2828, 2836, 2433, -1, + 2828, 2433, 2833, -1, 2831, 2434, 2824, -1, + 2831, 2832, 2435, -1, 2831, 2435, 2434, -1, + 2438, 2829, 2825, -1, 2438, 2436, 2840, -1, + 2438, 2825, 2437, -1, 2438, 2437, 2436, -1, + 2835, 2836, 2828, -1, 2835, 2828, 2829, -1, + 2835, 2438, 2840, -1, 2835, 2829, 2438, -1, + 2439, 2441, 2440, -1, 2439, 2443, 2442, -1, + 2439, 2442, 2441, -1, 2439, 2444, 2443, -1, + 2439, 2445, 2444, -1, 2439, 2440, 2445, -1, + 3071, 2446, 2841, -1, 3071, 2844, 2446, -1, + 2447, 2448, 2458, -1, 2447, 2458, 2454, -1, + 2447, 2449, 2448, -1, 2447, 2450, 2449, -1, + 2447, 2451, 2450, -1, 2447, 3031, 2451, -1, + 2447, 2452, 3031, -1, 2447, 2454, 2452, -1, + 2459, 2460, 2453, -1, 2459, 2454, 2458, -1, + 2459, 2453, 2455, -1, 2459, 2455, 2454, -1, + 2456, 2458, 2457, -1, 2456, 2459, 2458, -1, + 2456, 2460, 2459, -1, 2456, 2457, 2461, -1, + 2456, 2461, 2462, -1, 2456, 2462, 2463, -1, + 2456, 2463, 2464, -1, 2456, 2464, 2465, -1, + 2456, 2465, 2460, -1, 2849, 2466, 2509, -1, + 2849, 2848, 2467, -1, 2849, 2467, 2466, -1, + 2873, 3110, 2480, -1, 2874, 3094, 2851, -1, + 2874, 2873, 3094, -1, 3090, 3089, 3117, -1, + 3090, 3117, 2909, -1, 3090, 2909, 2855, -1, + 3093, 2851, 3094, -1, 2860, 2861, 2856, -1, + 3099, 3118, 3089, -1, 2468, 2505, 2856, -1, + 2468, 2856, 2861, -1, 2468, 2469, 2505, -1, + 2468, 2861, 2471, -1, 2468, 2471, 2470, -1, + 2468, 2470, 2469, -1, 3096, 2858, 3101, -1, + 3096, 3094, 2873, -1, 3096, 2480, 2858, -1, + 3096, 2873, 2480, -1, 2862, 2471, 2861, -1, + 2862, 2472, 2471, -1, 2862, 2473, 2472, -1, + 2863, 2864, 2473, -1, 2863, 2473, 2862, -1, + 3106, 3105, 2474, -1, 3106, 2474, 2864, -1, + 3184, 2872, 2866, -1, 2870, 2475, 2871, -1, + 2870, 2478, 2475, -1, 2870, 2476, 2478, -1, + 2870, 3113, 2476, -1, 3111, 3079, 3112, -1, + 3111, 3075, 3079, -1, 2512, 2476, 2514, -1, + 2512, 2511, 2477, -1, 2512, 2478, 2476, -1, + 2512, 2477, 2478, -1, 3109, 3108, 2881, -1, + 3109, 2881, 2479, -1, 3109, 2479, 2480, -1, + 3109, 2480, 3110, -1, 2877, 3108, 3182, -1, + 2877, 2867, 2880, -1, 2973, 2855, 2909, -1, + 2973, 2909, 3155, -1, 2481, 2883, 2911, -1, + 2481, 2850, 2852, -1, 2481, 2911, 3078, -1, + 2481, 3078, 2850, -1, 2481, 2852, 2482, -1, + 2481, 2482, 2883, -1, 2484, 3147, 2483, -1, + 2484, 2855, 2973, -1, 2484, 3148, 3147, -1, + 2484, 2973, 3148, -1, 2854, 2483, 2852, -1, + 2854, 2855, 2484, -1, 2854, 2484, 2483, -1, + 2485, 2500, 2486, -1, 2485, 2486, 2487, -1, + 2485, 2487, 2488, -1, 2485, 2488, 2489, -1, + 2485, 2489, 2501, -1, 2485, 2501, 2500, -1, + 2493, 2490, 2491, -1, 2493, 2492, 2970, -1, + 2493, 2971, 2490, -1, 2493, 2970, 2971, -1, + 2496, 2491, 2495, -1, 2496, 2882, 2492, -1, + 2496, 2492, 2493, -1, 2496, 2493, 2491, -1, + 2884, 2494, 2913, -1, 2884, 2495, 2494, -1, + 2884, 2882, 2496, -1, 2884, 2496, 2495, -1, + 2497, 2498, 2499, -1, 2497, 2500, 2501, -1, + 2497, 2499, 2500, -1, 2497, 2501, 2502, -1, + 2497, 2502, 2503, -1, 2497, 2503, 2498, -1, + 2504, 3084, 2505, -1, 2504, 2506, 2507, -1, + 2504, 2505, 2506, -1, 2504, 2507, 2508, -1, + 2504, 2508, 3083, -1, 2504, 3083, 3084, -1, + 2892, 2509, 2891, -1, 2892, 2849, 2509, -1, + 3210, 2891, 2895, -1, 2904, 2905, 2510, -1, + 2904, 2510, 3001, -1, 2904, 3001, 3000, -1, + 2903, 2899, 2906, -1, 3086, 3218, 2897, -1, + 2513, 2915, 2636, -1, 2513, 2636, 2511, -1, + 2513, 2511, 2512, -1, 2513, 2512, 2514, -1, + 3077, 2915, 2513, -1, 3077, 2514, 3079, -1, + 3077, 2513, 2514, -1, 3076, 3078, 2911, -1, + 3076, 2915, 3077, -1, 2515, 2653, 2630, -1, + 2515, 2630, 2633, -1, 2515, 2516, 2653, -1, + 2515, 2633, 2517, -1, 2515, 2518, 2516, -1, + 2515, 2517, 2518, -1, 2519, 2521, 2520, -1, + 2519, 2522, 2521, -1, 2519, 2523, 2522, -1, + 2519, 2520, 2524, -1, 2519, 2525, 2523, -1, + 2519, 2524, 2525, -1, 2530, 2531, 2526, -1, + 2530, 2527, 2535, -1, 2530, 2526, 2528, -1, + 2530, 2528, 2527, -1, 2529, 2535, 2534, -1, + 2529, 2530, 2535, -1, 2529, 2531, 2530, -1, + 2529, 2534, 2532, -1, 2529, 2532, 2533, -1, + 2529, 2533, 2531, -1, 2917, 2534, 2535, -1, + 2917, 2918, 2534, -1, 2917, 2535, 2536, -1, + 2917, 2536, 2922, -1, 2539, 2566, 2565, -1, + 2539, 2565, 2537, -1, 2539, 2538, 2540, -1, + 2539, 2537, 2538, -1, 2543, 2554, 2566, -1, + 2543, 2566, 2539, -1, 2543, 2540, 2544, -1, + 2543, 2539, 2540, -1, 2541, 2542, 2554, -1, + 2541, 2545, 2542, -1, 2541, 2546, 2545, -1, + 2541, 2554, 2543, -1, 2541, 2544, 2546, -1, + 2541, 2543, 2544, -1, 2924, 2545, 2546, -1, + 2924, 2546, 2923, -1, 2924, 2925, 2547, -1, + 2924, 2547, 2545, -1, 2926, 3121, 2548, -1, + 2926, 2549, 2927, -1, 2926, 2548, 2549, -1, + 2555, 2553, 2550, -1, 2555, 2550, 2551, -1, + 2555, 2551, 2552, -1, 2555, 2552, 2568, -1, + 2567, 2554, 2553, -1, 2567, 2566, 2554, -1, + 2567, 2555, 2568, -1, 2567, 2553, 2555, -1, + 2559, 2560, 2556, -1, 2559, 2556, 2557, -1, + 2559, 2557, 2558, -1, 2559, 2558, 2930, -1, + 2929, 2560, 2559, -1, 2929, 2559, 2930, -1, + 2929, 2933, 2561, -1, 2929, 2561, 2560, -1, + 2562, 2563, 2564, -1, 2562, 2564, 2565, -1, + 2562, 2565, 2566, -1, 2562, 2566, 2567, -1, + 2562, 2568, 2563, -1, 2562, 2567, 2568, -1, + 2935, 2940, 2575, -1, 2935, 2936, 2940, -1, + 2939, 2940, 2936, -1, 2939, 2569, 2943, -1, + 2939, 2936, 2569, -1, 3128, 3129, 2570, -1, + 3128, 2570, 2571, -1, 3128, 2571, 2945, -1, + 2572, 2574, 2573, -1, 2572, 2573, 3129, -1, + 2572, 2575, 2574, -1, 2572, 3129, 3131, -1, + 2572, 3131, 2935, -1, 2572, 2935, 2575, -1, + 3132, 2947, 2576, -1, 3132, 2576, 3133, -1, + 2577, 2578, 2579, -1, 2577, 2579, 2585, -1, + 2577, 2580, 2578, -1, 2577, 2585, 2582, -1, + 2577, 2582, 2581, -1, 2577, 2581, 2580, -1, + 2951, 2582, 2585, -1, 2951, 2953, 2583, -1, + 2951, 2583, 2582, -1, 2950, 2584, 2948, -1, + 2950, 2585, 2584, -1, 2950, 2951, 2585, -1, + 2666, 2665, 2590, -1, 2666, 2586, 2667, -1, + 2666, 2588, 2586, -1, 2666, 2590, 2588, -1, + 2587, 2589, 2588, -1, 2587, 2588, 2590, -1, + 2587, 2592, 2591, -1, 2587, 2593, 2592, -1, + 2587, 2590, 2593, -1, 2587, 2594, 2589, -1, + 2587, 2591, 2594, -1, 2595, 2596, 2597, -1, + 2595, 2597, 2598, -1, 2595, 2598, 2599, -1, + 2595, 2599, 2600, -1, 2595, 2600, 2601, -1, + 2595, 2601, 2596, -1, 2602, 2603, 2604, -1, + 2602, 2604, 2605, -1, 2602, 2605, 2606, -1, + 2602, 2606, 2607, -1, 2602, 2607, 2603, -1, + 2958, 2609, 2608, -1, 2958, 2608, 2961, -1, + 2958, 2955, 2609, -1, 2960, 2963, 2610, -1, + 2960, 2610, 2959, -1, 3195, 3144, 2866, -1, + 3195, 2872, 3197, -1, 3195, 2866, 2872, -1, + 2965, 2966, 2611, -1, 2965, 2611, 2612, -1, + 2965, 2612, 2868, -1, 2965, 2868, 3144, -1, + 3199, 2613, 3142, -1, 3199, 3198, 2613, -1, + 2614, 2615, 2616, -1, 2614, 2616, 2617, -1, + 2614, 2619, 2618, -1, 2614, 2620, 2619, -1, + 2614, 2617, 2620, -1, 2614, 2618, 2621, -1, + 2614, 2621, 2615, -1, 2622, 2623, 2624, -1, + 2622, 2626, 2625, -1, 2622, 2627, 2623, -1, + 2622, 2625, 2627, -1, 2622, 2628, 2626, -1, + 2622, 2624, 2628, -1, 2629, 2630, 2631, -1, + 2629, 2631, 2632, -1, 2629, 2632, 2637, -1, + 2629, 2637, 2638, -1, 2629, 2638, 2633, -1, + 2629, 2633, 2630, -1, 2634, 2635, 2636, -1, + 2634, 2637, 2635, -1, 2634, 2638, 2637, -1, + 2634, 2636, 2914, -1, 2634, 2639, 2638, -1, + 2634, 2914, 2639, -1, 2640, 2649, 2641, -1, + 2640, 2642, 2643, -1, 2640, 2641, 2642, -1, + 2640, 2643, 2644, -1, 2640, 2644, 2645, -1, + 2640, 2645, 2649, -1, 2646, 2647, 2648, -1, + 2646, 2648, 2649, -1, 2646, 2650, 2647, -1, + 2646, 2649, 2651, -1, 2646, 2652, 2650, -1, + 2646, 2651, 2652, -1, 2659, 2705, 2704, -1, + 2659, 2656, 2653, -1, 2659, 2653, 2654, -1, + 2659, 2654, 2705, -1, 2655, 2657, 2656, -1, + 2655, 2704, 2658, -1, 2655, 2656, 2659, -1, + 2655, 2659, 2704, -1, 2655, 2660, 2657, -1, + 2655, 2658, 2660, -1, 3139, 3138, 2664, -1, + 3139, 2664, 2661, -1, 3139, 2662, 3140, -1, + 3139, 2661, 2662, -1, 2663, 2664, 2665, -1, + 2663, 2665, 2666, -1, 2663, 2666, 2667, -1, + 2663, 2667, 2668, -1, 2663, 2668, 2669, -1, + 2663, 2669, 2664, -1, 2670, 2671, 2672, -1, + 2670, 2981, 2982, -1, 2670, 2672, 2981, -1, + 2670, 2982, 2673, -1, 2670, 2673, 2674, -1, + 2670, 2674, 2671, -1, 3202, 2970, 2967, -1, + 3154, 2972, 3000, -1, 2974, 2999, 3205, -1, + 2974, 3205, 3149, -1, 2974, 3149, 3152, -1, + 2974, 3158, 2999, -1, 2998, 2678, 2675, -1, + 2998, 2997, 2678, -1, 2975, 3204, 2675, -1, + 2979, 2675, 2678, -1, 2979, 2678, 2980, -1, + 2979, 2975, 2675, -1, 3206, 3205, 2999, -1, + 3206, 2675, 3204, -1, 3206, 2999, 2998, -1, + 3206, 2998, 2675, -1, 2991, 2676, 2985, -1, + 2991, 2677, 2676, -1, 2991, 2992, 2677, -1, + 2986, 2997, 2989, -1, 2986, 2987, 2980, -1, + 2986, 2678, 2997, -1, 2986, 2980, 2678, -1, + 2996, 2990, 2989, -1, 2996, 2679, 2990, -1, + 2996, 3157, 2679, -1, 2996, 2989, 2997, -1, + 3160, 2687, 3161, -1, 3160, 3001, 2686, -1, + 3160, 2686, 2687, -1, 2680, 3161, 2687, -1, + 2680, 2759, 2760, -1, 2680, 2682, 2759, -1, + 2680, 2687, 2682, -1, 3156, 2760, 2679, -1, + 3156, 2680, 2760, -1, 3156, 3161, 2680, -1, + 3156, 2679, 3157, -1, 2681, 2683, 2682, -1, + 2681, 2685, 2684, -1, 2681, 2684, 2683, -1, + 2681, 2686, 2685, -1, 2681, 2687, 2686, -1, + 2681, 2682, 2687, -1, 2688, 2690, 2689, -1, + 2688, 2692, 2691, -1, 2688, 2693, 2692, -1, + 2688, 2689, 2693, -1, 2688, 2691, 2694, -1, + 2688, 2694, 2690, -1, 2976, 2695, 2696, -1, + 2976, 2697, 2977, -1, 2976, 2696, 2697, -1, + 2976, 2983, 2695, -1, 3003, 2698, 2699, -1, + 3003, 2699, 2700, -1, 3003, 2700, 3007, -1, + 3003, 3004, 2698, -1, 2701, 3007, 2702, -1, + 2701, 2702, 2703, -1, 2701, 2703, 2704, -1, + 2701, 2704, 2705, -1, 2701, 2705, 3006, -1, + 2701, 3006, 3007, -1, 2706, 2707, 2708, -1, + 2706, 2708, 3004, -1, 2706, 3004, 3008, -1, + 2706, 3008, 2709, -1, 2706, 2709, 2710, -1, + 2706, 2710, 2707, -1, 3167, 2711, 2712, -1, + 3167, 2712, 3168, -1, 3167, 3170, 2711, -1, + 3021, 3014, 2715, -1, 3021, 2715, 3009, -1, + 3016, 2713, 3017, -1, 3016, 3168, 2713, -1, + 3016, 3009, 3168, -1, 3016, 3021, 3009, -1, + 2714, 3010, 2715, -1, 2714, 2715, 2716, -1, + 2714, 3011, 3010, -1, 2714, 2716, 3011, -1, + 2717, 2718, 2719, -1, 2717, 2719, 2721, -1, + 2717, 2720, 2718, -1, 2717, 2721, 2720, -1, + 2728, 2722, 2721, -1, 2728, 2723, 2722, -1, + 2728, 2729, 2723, -1, 2728, 2721, 2725, -1, + 2724, 2725, 2726, -1, 2724, 2726, 2727, -1, + 2724, 2728, 2725, -1, 2724, 2727, 2729, -1, + 2724, 2729, 2728, -1, 2730, 2732, 2731, -1, + 2730, 2731, 2733, -1, 2730, 2734, 2732, -1, + 2730, 2735, 2734, -1, 2730, 2739, 2735, -1, + 2730, 2733, 2738, -1, 2730, 2738, 2739, -1, + 2736, 2738, 2737, -1, 2736, 2739, 2738, -1, + 2736, 2737, 2740, -1, 2736, 2740, 2739, -1, + 3025, 3024, 2741, -1, 3025, 2741, 2745, -1, + 3025, 2746, 3027, -1, 3025, 2745, 2746, -1, + 2742, 2743, 2744, -1, 2742, 2745, 2743, -1, + 2742, 2746, 2745, -1, 2742, 2744, 2747, -1, + 2742, 2747, 2748, -1, 2742, 2748, 2746, -1, + 2749, 2750, 2751, -1, 2749, 2752, 2753, -1, + 2749, 2753, 2754, -1, 2749, 2754, 2750, -1, + 2749, 2755, 2752, -1, 2749, 2751, 2755, -1, + 2756, 2757, 2758, -1, 2756, 2760, 2759, -1, + 2756, 2759, 2761, -1, 2756, 2761, 2757, -1, + 2756, 2762, 2760, -1, 2756, 2758, 2762, -1, + 2768, 2763, 2766, -1, 2768, 2767, 2764, -1, + 2768, 2765, 2763, -1, 2768, 2764, 2765, -1, + 2793, 2766, 2791, -1, 2793, 2792, 2767, -1, + 2793, 2767, 2768, -1, 2793, 2768, 2766, -1, + 2769, 2771, 2770, -1, 2769, 2772, 2771, -1, + 2769, 2773, 2772, -1, 2769, 2774, 2773, -1, + 2769, 2775, 2774, -1, 2769, 2770, 2775, -1, + 2776, 2778, 2777, -1, 2776, 2780, 2779, -1, + 2776, 2779, 2778, -1, 2776, 2781, 2780, -1, + 2776, 2782, 2781, -1, 2776, 2777, 2782, -1, + 3032, 3030, 2783, -1, 3032, 2783, 2784, -1, + 3032, 2784, 3033, -1, 3072, 3068, 2785, -1, + 3072, 2786, 3070, -1, 3072, 2787, 2786, -1, + 3072, 2785, 2787, -1, 2794, 2795, 2788, -1, + 2794, 2788, 2789, -1, 2794, 2789, 2790, -1, + 2794, 2790, 3038, -1, 3040, 2791, 3036, -1, + 3040, 3038, 2792, -1, 3040, 2793, 2791, -1, + 3040, 2792, 2793, -1, 3037, 2794, 3038, -1, + 3037, 2795, 2794, -1, 3037, 2796, 2795, -1, + 3037, 3039, 2796, -1, 3035, 2797, 2798, -1, + 3035, 2798, 2799, -1, 3035, 2799, 3039, -1, + 3035, 3036, 2797, -1, 3045, 3046, 2800, -1, + 3045, 2802, 2801, -1, 3045, 2801, 3044, -1, + 3045, 2803, 2802, -1, 3045, 2800, 2803, -1, + 3053, 3048, 2804, -1, 3053, 2804, 2809, -1, + 3053, 2809, 3054, -1, 3062, 2805, 3061, -1, + 3062, 2806, 2807, -1, 3062, 2807, 2805, -1, + 3062, 3063, 2806, -1, 3060, 3061, 2808, -1, + 3060, 2808, 3054, -1, 3060, 2809, 3065, -1, + 3060, 3054, 2809, -1, 2810, 2811, 2812, -1, + 2810, 2813, 2811, -1, 2810, 2812, 2814, -1, + 2810, 2815, 2813, -1, 2810, 2816, 2815, -1, + 2810, 2814, 2816, -1, 2817, 2819, 2818, -1, + 2817, 2820, 2819, -1, 2817, 2818, 2821, -1, + 2817, 2822, 2820, -1, 2817, 2821, 2823, -1, + 2817, 2823, 2822, -1, 2830, 2831, 2824, -1, + 2830, 2825, 2829, -1, 2830, 2824, 2826, -1, + 2830, 2826, 2825, -1, 2827, 2829, 2828, -1, + 2827, 2830, 2829, -1, 2827, 2831, 2830, -1, + 2827, 2832, 2831, -1, 2827, 2833, 2832, -1, + 2827, 2828, 2833, -1, 2834, 2836, 2835, -1, + 2834, 2837, 2836, -1, 2834, 2838, 2837, -1, + 2834, 2839, 2838, -1, 2834, 2840, 2839, -1, + 2834, 2835, 2840, -1, 3067, 2841, 2842, -1, + 3067, 3071, 2841, -1, 3067, 2842, 2843, -1, + 3067, 2843, 3068, -1, 3069, 2845, 2844, -1, + 3069, 2844, 3071, -1, 3069, 2846, 2845, -1, + 3069, 3070, 2846, -1, 2847, 2889, 2848, -1, + 2847, 2848, 2849, -1, 2847, 2849, 2892, -1, + 2847, 2887, 2889, -1, 2847, 2893, 2887, -1, + 2847, 2892, 2893, -1, 3074, 2874, 2851, -1, + 3074, 2851, 2850, -1, 3074, 2850, 3078, -1, + 3074, 3075, 2874, -1, 2853, 2850, 2851, -1, + 2853, 2851, 3093, -1, 2853, 2852, 2850, -1, + 2853, 2854, 2852, -1, 3091, 2853, 3093, -1, + 3091, 2854, 2853, -1, 3091, 3090, 2855, -1, + 3091, 2855, 2854, -1, 3081, 3115, 2860, -1, + 3081, 3114, 3115, -1, 3081, 2856, 3084, -1, + 3081, 2860, 2856, -1, 3185, 3082, 2887, -1, + 3185, 2887, 2893, -1, 3214, 3085, 3088, -1, + 3177, 3214, 3088, -1, 3087, 2860, 3115, -1, + 3087, 3176, 3175, -1, 3100, 3099, 3089, -1, + 2857, 3118, 3099, -1, 2857, 3088, 3085, -1, + 2857, 3098, 3088, -1, 2857, 3099, 3098, -1, + 2857, 3191, 3118, -1, 2857, 3085, 3191, -1, + 3103, 3101, 2858, -1, 3103, 2858, 3104, -1, + 2859, 3175, 2863, -1, 2859, 2861, 2860, -1, + 2859, 2862, 2861, -1, 2859, 2863, 2862, -1, + 2859, 3087, 3175, -1, 2859, 2860, 3087, -1, + 3174, 3173, 3106, -1, 3174, 2863, 3175, -1, + 3174, 2864, 2863, -1, 3174, 3106, 2864, -1, + 3183, 2872, 3184, -1, 2865, 3184, 2866, -1, + 2865, 2868, 2867, -1, 2865, 2866, 2868, -1, + 2865, 2867, 2877, -1, 2865, 3182, 3184, -1, + 2865, 2877, 3182, -1, 2869, 2870, 2871, -1, + 2869, 3197, 2872, -1, 2869, 2871, 3197, -1, + 2869, 2872, 3183, -1, 2869, 3113, 2870, -1, + 2869, 3183, 3113, -1, 2875, 3075, 3111, -1, + 2875, 3110, 2873, -1, 2875, 2874, 3075, -1, + 2875, 2873, 2874, -1, 3180, 3110, 2875, -1, + 3180, 2875, 3111, -1, 2876, 3108, 2877, -1, + 2876, 2879, 2878, -1, 2876, 2880, 2879, -1, + 2876, 2877, 2880, -1, 2876, 2878, 2881, -1, + 2876, 2881, 3108, -1, 2912, 2883, 2882, -1, + 2912, 2882, 2884, -1, 2912, 2911, 2883, -1, + 2912, 2884, 2913, -1, 2885, 3082, 2886, -1, + 2885, 2887, 3082, -1, 2885, 2886, 2888, -1, + 2885, 2889, 2887, -1, 2885, 2890, 2889, -1, + 2885, 2888, 2890, -1, 3211, 2891, 3210, -1, + 3211, 2892, 2891, -1, 3211, 2893, 2892, -1, + 3211, 3185, 2893, -1, 2894, 2895, 2898, -1, + 2894, 3210, 2895, -1, 2894, 2898, 2897, -1, + 2894, 3217, 3210, -1, 2894, 2897, 3218, -1, + 2894, 3218, 3217, -1, 2907, 2904, 3000, -1, + 2907, 3000, 2972, -1, 2900, 2903, 2908, -1, + 2900, 3086, 2897, -1, 2900, 2908, 3190, -1, + 2900, 3190, 3086, -1, 2896, 2897, 2898, -1, + 2896, 2899, 2903, -1, 2896, 2900, 2897, -1, + 2896, 2903, 2900, -1, 2896, 2898, 2901, -1, + 2896, 2901, 2899, -1, 2902, 2908, 2903, -1, + 2902, 2907, 2908, -1, 2902, 2904, 2907, -1, + 2902, 2905, 2904, -1, 2902, 2906, 2905, -1, + 2902, 2903, 2906, -1, 3192, 2972, 3188, -1, + 3192, 2907, 2972, -1, 3192, 3190, 2908, -1, + 3192, 2908, 2907, -1, 3189, 3086, 3190, -1, + 3189, 3191, 3085, -1, 3116, 2909, 3117, -1, + 3116, 3155, 2909, -1, 2910, 3076, 2911, -1, + 2910, 2912, 2913, -1, 2910, 2911, 2912, -1, + 2910, 2913, 2914, -1, 2910, 2914, 2915, -1, + 2910, 2915, 3076, -1, 2916, 2918, 2917, -1, + 2916, 2919, 2920, -1, 2916, 2920, 2918, -1, + 2916, 2921, 2919, -1, 2916, 2922, 2921, -1, + 2916, 2917, 2922, -1, 3120, 2923, 3121, -1, + 3120, 2924, 2923, -1, 3120, 3126, 2925, -1, + 3120, 2925, 2924, -1, 3122, 2926, 2927, -1, + 3122, 3121, 2926, -1, 3122, 2927, 3125, -1, + 2928, 2929, 2930, -1, 2928, 2932, 2931, -1, + 2928, 2930, 2932, -1, 2928, 2931, 2933, -1, + 2928, 2933, 2929, -1, 2934, 2936, 2935, -1, + 2934, 2937, 2936, -1, 2934, 3133, 2937, -1, + 2934, 3131, 3133, -1, 2934, 2935, 3131, -1, + 2938, 2940, 2939, -1, 2938, 2941, 2942, -1, + 2938, 2943, 2941, -1, 2938, 2939, 2943, -1, + 2938, 2942, 2944, -1, 2938, 2944, 2940, -1, + 3130, 2945, 2946, -1, 3130, 3128, 2945, -1, + 3130, 2946, 2947, -1, 3130, 2947, 3132, -1, + 3135, 2948, 3136, -1, 3135, 2950, 2948, -1, + 2949, 2951, 2950, -1, 2949, 3140, 2952, -1, + 2949, 3135, 3140, -1, 2949, 2950, 3135, -1, + 2949, 2952, 2953, -1, 2949, 2953, 2951, -1, + 2954, 2955, 2958, -1, 2954, 2958, 2959, -1, + 2954, 2956, 2955, -1, 2954, 2959, 2956, -1, + 2957, 2959, 2958, -1, 2957, 2960, 2959, -1, + 2957, 2961, 2962, -1, 2957, 2958, 2961, -1, + 2957, 2963, 2960, -1, 2957, 2964, 2963, -1, + 2957, 2962, 2964, -1, 3145, 2966, 2965, -1, + 3145, 2965, 3144, -1, 3145, 3141, 2966, -1, + 3201, 3202, 2967, -1, 3201, 2967, 2968, -1, + 3201, 2968, 3147, -1, 2969, 2971, 2970, -1, + 2969, 2970, 3202, -1, 2969, 2977, 2971, -1, + 2969, 3202, 3204, -1, 2969, 2975, 2977, -1, + 2969, 3204, 2975, -1, 3153, 2972, 3154, -1, + 3153, 3188, 2972, -1, 3153, 3155, 3116, -1, + 3153, 3116, 3188, -1, 3151, 3149, 3148, -1, + 3151, 3148, 2973, -1, 3151, 2973, 3155, -1, + 3151, 3152, 3149, -1, 3165, 3158, 2974, -1, + 3165, 3152, 3164, -1, 3165, 2974, 3152, -1, + 2984, 2975, 2979, -1, 2984, 2983, 2976, -1, + 2984, 2977, 2975, -1, 2984, 2976, 2977, -1, + 2978, 2979, 2980, -1, 2978, 2982, 2981, -1, + 2978, 2980, 2982, -1, 2978, 2981, 2983, -1, + 2978, 2983, 2984, -1, 2978, 2984, 2979, -1, + 2993, 2991, 2985, -1, 2993, 2986, 2989, -1, + 2993, 2985, 2987, -1, 2993, 2987, 2986, -1, + 2988, 2989, 2990, -1, 2988, 2992, 2991, -1, + 2988, 2993, 2989, -1, 2988, 2991, 2993, -1, + 2988, 2990, 2994, -1, 2988, 2994, 2992, -1, + 2995, 2996, 2997, -1, 2995, 2997, 2998, -1, + 2995, 3158, 3157, -1, 2995, 3157, 2996, -1, + 2995, 2999, 3158, -1, 2995, 2998, 2999, -1, + 3162, 3000, 3001, -1, 3162, 3001, 3160, -1, + 3162, 3154, 3000, -1, 3162, 3164, 3154, -1, + 3002, 3004, 3003, -1, 3002, 3006, 3005, -1, + 3002, 3007, 3006, -1, 3002, 3003, 3007, -1, + 3002, 3008, 3004, -1, 3002, 3005, 3008, -1, + 3169, 3168, 3009, -1, 3169, 3009, 3010, -1, + 3169, 3010, 3011, -1, 3169, 3011, 3170, -1, + 3020, 3019, 3012, -1, 3020, 3012, 3013, -1, + 3020, 3013, 3014, -1, 3020, 3014, 3021, -1, + 3015, 3016, 3017, -1, 3015, 3018, 3019, -1, + 3015, 3017, 3018, -1, 3015, 3019, 3020, -1, + 3015, 3021, 3016, -1, 3015, 3020, 3021, -1, + 3022, 3023, 3024, -1, 3022, 3024, 3025, -1, + 3022, 3026, 3023, -1, 3022, 3025, 3027, -1, + 3022, 3028, 3026, -1, 3022, 3027, 3028, -1, + 3029, 3031, 3030, -1, 3029, 3030, 3032, -1, + 3029, 3033, 3031, -1, 3029, 3032, 3033, -1, + 3034, 3036, 3035, -1, 3034, 3037, 3038, -1, + 3034, 3039, 3037, -1, 3034, 3035, 3039, -1, + 3034, 3040, 3036, -1, 3034, 3038, 3040, -1, + 3041, 3043, 3042, -1, 3041, 3044, 3043, -1, + 3041, 3045, 3044, -1, 3041, 3046, 3045, -1, + 3041, 3047, 3046, -1, 3041, 3042, 3047, -1, + 3057, 3048, 3053, -1, 3057, 3049, 3048, -1, + 3057, 3050, 3049, -1, 3057, 3056, 3051, -1, + 3057, 3051, 3050, -1, 3052, 3053, 3054, -1, + 3052, 3055, 3056, -1, 3052, 3056, 3057, -1, + 3052, 3057, 3053, -1, 3052, 3058, 3055, -1, + 3052, 3054, 3058, -1, 3059, 3061, 3060, -1, + 3059, 3063, 3062, -1, 3059, 3062, 3061, -1, + 3059, 3064, 3063, -1, 3059, 3065, 3064, -1, + 3059, 3060, 3065, -1, 3066, 3067, 3068, -1, + 3066, 3070, 3069, -1, 3066, 3071, 3067, -1, + 3066, 3069, 3071, -1, 3066, 3072, 3070, -1, + 3066, 3068, 3072, -1, 3073, 3075, 3074, -1, + 3073, 3076, 3077, -1, 3073, 3078, 3076, -1, + 3073, 3074, 3078, -1, 3073, 3079, 3075, -1, + 3073, 3077, 3079, -1, 3080, 3114, 3081, -1, + 3080, 3083, 3082, -1, 3080, 3084, 3083, -1, + 3080, 3081, 3084, -1, 3080, 3082, 3185, -1, + 3080, 3185, 3114, -1, 3216, 3085, 3214, -1, + 3216, 3189, 3085, -1, 3216, 3218, 3086, -1, + 3216, 3086, 3189, -1, 3207, 3087, 3115, -1, + 3207, 3176, 3087, -1, 3172, 3098, 3107, -1, + 3172, 3088, 3098, -1, 3172, 3177, 3088, -1, + 3172, 3107, 3173, -1, 3095, 3100, 3089, -1, + 3095, 3089, 3090, -1, 3095, 3090, 3091, -1, + 3095, 3091, 3093, -1, 3092, 3101, 3100, -1, + 3092, 3093, 3094, -1, 3092, 3095, 3093, -1, + 3092, 3100, 3095, -1, 3092, 3096, 3101, -1, + 3092, 3094, 3096, -1, 3097, 3107, 3098, -1, + 3097, 3098, 3099, -1, 3097, 3099, 3100, -1, + 3097, 3100, 3101, -1, 3097, 3101, 3103, -1, + 3097, 3103, 3107, -1, 3102, 3103, 3104, -1, + 3102, 3104, 3105, -1, 3102, 3105, 3106, -1, + 3102, 3106, 3173, -1, 3102, 3173, 3107, -1, + 3102, 3107, 3103, -1, 3179, 3182, 3108, -1, + 3179, 3108, 3109, -1, 3179, 3109, 3110, -1, + 3179, 3110, 3180, -1, 3181, 3111, 3112, -1, + 3181, 3180, 3111, -1, 3181, 3112, 3113, -1, + 3181, 3113, 3183, -1, 3209, 3114, 3185, -1, + 3209, 3115, 3114, -1, 3209, 3207, 3115, -1, + 3187, 3116, 3117, -1, 3187, 3117, 3118, -1, + 3187, 3118, 3191, -1, 3187, 3188, 3116, -1, + 3119, 3120, 3121, -1, 3119, 3121, 3122, -1, + 3119, 3123, 3124, -1, 3119, 3125, 3123, -1, + 3119, 3122, 3125, -1, 3119, 3124, 3126, -1, + 3119, 3126, 3120, -1, 3127, 3129, 3128, -1, + 3127, 3128, 3130, -1, 3127, 3131, 3129, -1, + 3127, 3130, 3132, -1, 3127, 3133, 3131, -1, + 3127, 3132, 3133, -1, 3134, 3135, 3136, -1, + 3134, 3136, 3137, -1, 3134, 3137, 3138, -1, + 3134, 3138, 3139, -1, 3134, 3139, 3140, -1, + 3134, 3140, 3135, -1, 3146, 3141, 3145, -1, + 3146, 3199, 3142, -1, 3146, 3142, 3143, -1, + 3146, 3143, 3141, -1, 3194, 3144, 3195, -1, + 3194, 3145, 3144, -1, 3194, 3199, 3146, -1, + 3194, 3146, 3145, -1, 3203, 3147, 3148, -1, + 3203, 3201, 3147, -1, 3203, 3148, 3149, -1, + 3203, 3149, 3205, -1, 3150, 3152, 3151, -1, + 3150, 3153, 3154, -1, 3150, 3155, 3153, -1, + 3150, 3151, 3155, -1, 3150, 3164, 3152, -1, + 3150, 3154, 3164, -1, 3163, 3161, 3156, -1, + 3163, 3156, 3157, -1, 3163, 3157, 3158, -1, + 3163, 3158, 3165, -1, 3159, 3160, 3161, -1, + 3159, 3162, 3160, -1, 3159, 3161, 3163, -1, + 3159, 3164, 3162, -1, 3159, 3165, 3164, -1, + 3159, 3163, 3165, -1, 3166, 3167, 3168, -1, + 3166, 3168, 3169, -1, 3166, 3170, 3167, -1, + 3166, 3169, 3170, -1, 3213, 3214, 3177, -1, + 3213, 3177, 3176, -1, 3213, 3176, 3207, -1, + 3171, 3172, 3173, -1, 3171, 3174, 3175, -1, + 3171, 3173, 3174, -1, 3171, 3175, 3176, -1, + 3171, 3176, 3177, -1, 3171, 3177, 3172, -1, + 3178, 3179, 3180, -1, 3178, 3180, 3181, -1, + 3178, 3182, 3179, -1, 3178, 3181, 3183, -1, + 3178, 3184, 3182, -1, 3178, 3183, 3184, -1, + 3208, 3185, 3211, -1, 3208, 3209, 3185, -1, + 3186, 3188, 3187, -1, 3186, 3189, 3190, -1, + 3186, 3191, 3189, -1, 3186, 3187, 3191, -1, + 3186, 3190, 3192, -1, 3186, 3192, 3188, -1, + 3193, 3194, 3195, -1, 3193, 3197, 3196, -1, + 3193, 3195, 3197, -1, 3193, 3196, 3198, -1, + 3193, 3198, 3199, -1, 3193, 3199, 3194, -1, + 3200, 3202, 3201, -1, 3200, 3201, 3203, -1, + 3200, 3204, 3202, -1, 3200, 3203, 3205, -1, + 3200, 3205, 3206, -1, 3200, 3206, 3204, -1, + 3215, 3207, 3209, -1, 3215, 3213, 3207, -1, + 3219, 3209, 3208, -1, 3219, 3215, 3209, -1, + 3219, 3210, 3217, -1, 3219, 3211, 3210, -1, + 3219, 3208, 3211, -1, 3212, 3214, 3213, -1, + 3212, 3213, 3215, -1, 3212, 3216, 3214, -1, + 3212, 3217, 3218, -1, 3212, 3218, 3216, -1, + 3212, 3219, 3217, -1, 3212, 3215, 3219, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link4.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link4.wrl new file mode 100644 index 0000000..328708e --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link4.wrl @@ -0,0 +1,6707 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.00185474 -0.208459 0.0501316, + -0.0340195 -0.208528 -0.0364765, + 0.0576833 -0.045556799 0.052482001, + 0.059316002 -0.208491 0.0092001203, + 0.0562139 -0.208482 0.0211422, + 0.047172099 -0.208469 0.037244201, + 0.0048316298 -0.208451 0.059971102, + 0.038590301 -0.208462 0.0461093, + 0.0431097 -0.208465 0.0418979, + 0.033661801 -0.208459 0.0498337, + 0.058072701 -0.20848601 0.0152511, + 0.059757002 -0.048416398 0.043622501, + 0.0479904 -0.19152699 -0.035860401, + 0.048459399 0.035372298 0.0124718, + 0.027557701 -0.151072 -0.050477099, + 0.0233503 -0.208534 -0.0440467, + 0.0326031 -0.208529 -0.037742302, + -0.0583959 -0.19150899 -0.0136288, + -0.0013432 -0.208451 0.060151, + 0.053759102 -0.20847701 0.026811, + 0.056809202 -0.043281302 0.055130299, + 0.0546159 -0.042392101 0.059636999, + 0.0532961 -0.040258002 0.062245999, + 0.050734501 -0.208473 0.032197401, + 0.051830001 -0.0381625 0.064807601, + 0.0169627 -0.208452 0.057718299, + 0.0424264 -0.032684602 0.075865, + -0.0029901101 0.0599369 0.0124523, + -0.00267513 0.0599587 0.0216667, + -5.5826116e-012 -0.15018301 -0.056540102, + -0.0053973799 -0.150134 -0.056295902, + -0.00268824 -0.150171 -0.0564797, + 0.0469217 -0.208528 -0.037228499, + 0.0599254 -0.171501 -0.00285355, + 0.048784502 -0.191526 -0.034777001, + 0.044560701 0.040182602 0.012468, + 0.0424264 0.042406101 0.0145794, + 0.042958502 0.041878 0.0124667, + 0.042376 0.042488299 0.0124662, + 0.044564299 0.0401491 0.0145568, + 0.044408198 0.040358901 0.0124679, + 0.048147298 0.0358142 0.0124715, + 0.00268824 -0.15017 -0.056480601, + 5.2539887e-012 -0.15231 -0.0571835, + 0.055787299 -0.154062 -0.020771099, + 0.0532961 -0.154737 -0.0262456, + 0.0546159 -0.154402 -0.023527199, + 0.040174201 -0.151912 -0.0423146, + 0.056809202 0.018239601 0.0191583, + 0.033327099 -0.208538 -0.049727, + 0.029552899 -0.19154 -0.052064601, + 0.0307144 -0.191539 -0.051389899, + 0.0302257 -0.15310401 -0.049585301, + 0.038280498 -0.208535 -0.0460358, + 0.0358513 -0.19153699 -0.047958702, + 0.059999999 -0.158079 0.00064591598, + 0.0599402 -0.16491801 -0.00243967, + 0.059999999 -0.171498 8.8971698e-005, + 0.059980098 -0.19149999 -0.00139239, + 0.059999701 -0.19149899 -4.9242495e-005, + 0.059999999 -0.164805 0.00024871199, + 0.059999999 -0.056065701 0.0378001, + -0.059445001 -0.165142 -0.0078606298, + -0.0378174 -0.15225101 -0.044316601, + -0.040174201 -0.154378 -0.042801999, + -0.040174201 -0.151921 -0.042298101, + -0.054342099 -0.19151901 -0.0252824, + -0.059445001 -0.15875 -0.0074576801, + -0.059757002 -0.15852299 -0.00471139, + -0.059999801 -0.171498 0.00027890201, + -0.059316002 -0.191506 -0.0088815596, + -0.059503399 -0.191504 -0.0075514098, + -0.059372 -0.171505 -0.0085220505, + -0.058772299 -0.208508 -0.0119096, + 0.0081421202 -0.0289384 0.090996601, + 0.0053918599 -0.028720301 0.091305502, + 0.0081421202 -0.0243886 0.091779701, + 0.00267513 -0.028592501 0.091486797, + 0.0053918599 -0.0241616 0.092086203, + 0.048467699 -0.038024899 0.069005102, + 0.055787299 -0.037462901 0.058416899, + 0.055787299 -0.041017801 0.0577645, + 0.0546159 -0.038775299 0.060374301, + 0.055787299 -0.0338961 0.058948699, + 0.0532961 -0.0365634 0.062948599, + 0.0546159 -0.035142701 0.0609884, + 0.0137106 -0.029659601 0.089974001, + 0.0109552 -0.208451 0.059157401, + 0.0109179 -0.029250201 0.090554401, + 0.0165099 -0.025669901 0.090050198, + 0.044564299 -0.0343883 0.073676497, + 0.0465803 -0.036171101 0.071386397, + 0.0378174 -0.033744399 0.079148099, + 0.035366699 -0.0323718 0.081001401, + 0.040174201 -0.0310675 0.077942498, + 0.0378174 -0.021077899 0.080970101, + 0.056809202 -0.0363153 0.056395199, + 0.056809202 -0.039804898 0.0558214, + 0.0576833 -0.0421593 0.053212099, + 0.059999999 -0.0240399 0.040246401, + 0.059999999 -0.016562 0.036926299, + 0.0053918599 0.059768301 0.030829201, + 0.0046305298 0.059828501 0.0074523599, + -0.0059254402 0.059718199 0.0124525, + -0.0053918599 0.059768401 0.040021099, + -0.00267513 0.059968699 0.040065501, + -0.0053918599 0.059770498 0.021655301, + -0.00268824 -0.152299 -0.057123099, + 0.0599402 -0.032653801 0.043898098, + 0.059999999 -0.0353976 0.0417387, + 0.059999999 -0.032496799 0.041707098, + 0.059999999 -0.0296189 0.0414479, + 0.059999999 -0.026789701 0.040958401, + 0.059757002 -0.045297898 0.0443042, + 0.0599402 -0.038557801 0.0434414, + 0.059999999 -0.038282599 0.041546799, + 0.0599402 -0.0355982 0.043768499, + 0.059999999 -0.041179799 0.041164599, + 0.0599402 -0.041608799 0.0430113, + 0.0599402 -0.050773598 0.041134302, + 0.0599305 -0.208496 0.00305326, + 0.059445001 -0.039631501 0.047311999, + 0.059757002 -0.039034899 0.045358501, + 0.059757002 -0.042168502 0.0448828, + 0.0599402 -0.158301 -0.00204303, + 0.059706699 -0.17150301 -0.0057888799, + 0.0596609 -0.191503 -0.0062174001, + 0.059909701 -0.208501 -0.00312414, + 0.059757002 -0.165032 -0.0051489202, + 0.059757002 -0.158525 -0.0047528399, + 0.059445001 -0.158751 -0.00749892, + 0.059503399 -0.191504 -0.0075514098, + 0.059445001 -0.16514701 -0.0078944303, + 0.027557701 0.039587598 0.071896903, + 0.0402418 0.044515401 0.0124646, + 0.0498452 0.033409901 0.0124734, + 0.048467699 0.035331499 0.0145085, + 0.046574499 0.0378244 0.0124699, + 0.046333499 0.038132399 0.0124696, + 0.0465803 0.0377874 0.0145331, + 0.047033701 0.037237499 0.0124704, + 0.047047202 0.037244201 0.0074703498, + 0.028020401 -0.20854101 -0.052889202, + 0.054342099 -0.19151901 -0.0252824, + 0.054897901 -0.19151799 -0.0240594, + 0.056809202 -0.159674 -0.0186635, + 0.0576833 -0.15944301 -0.015867701, + 0.048467699 -0.15305001 -0.033618901, + 0.044564299 -0.163947 -0.039763201, + 0.0465803 -0.161204 -0.037177101, + 0.0465803 -0.15860499 -0.036878102, + 0.0465803 -0.156003 -0.036509499, + 0.0465803 -0.153402 -0.036071099, + 0.040174201 -0.15437201 -0.0428215, + 0.0580099 0.0152885 0.0124878, + 0.058021698 0.0152879 0.0074878298, + 0.0599402 -0.0113399 0.036883101, + 0.059999999 -0.0124441 0.033966601, + 0.0465803 -0.1638 -0.037406798, + 0.027557701 -0.153345 -0.051052202, + -0.0546159 -0.0278582 0.061826501, + -0.0532961 -0.025419701 0.0642782, + -0.0599402 -0.050776001 0.0411167, + -0.0424264 -0.154071 -0.040661901, + -0.044564299 -0.15374701 -0.038407501, + -0.048467699 -0.15305699 -0.033595402, + -0.0465803 -0.153409 -0.036048502, + -0.059999999 1.1546101e-005 0.0125, + -0.059999999 -0.00056159502 0.015693599, + -0.059999999 -0.00012932099 0.0141503, + -0.059999999 -7.0921719e-006 0.0133147, + -0.0378174 -0.154667 -0.044820201, + -0.0122731 -0.19154499 -0.0585788, + -0.0248404 -0.153567 -0.052362401, + -0.0248404 -0.15132099 -0.051788699, + -0.027557701 -0.151079 -0.050466899, + -0.0220857 -0.151537 -0.052961901, + -0.0550595 -0.208517 -0.0236762, + -0.0572192 -0.20851301 -0.0178886, + -0.054340299 -0.171519 -0.0252974, + -0.0554916 -0.171517 -0.022681899, + -0.059927799 0.00295392 0.0124977, + -0.0479904 -0.19152699 -0.035860401, + -0.059999999 -0.0560655 0.037785798, + -0.059999999 -0.164801 0.000282819, + -0.059999999 -0.058995701 0.0368293, + -0.059999999 -0.053114899 0.038647801, + 0.028376499 -0.20845599 0.053031601, + 0.035366699 -0.0281146 0.081735499, + 0.0328326 -0.031097701 0.082721598, + 0.019305199 -0.012751 0.0906597, + 0.0220857 0.027677899 0.084147297, + 0.0532961 -0.032853801 0.063524798, + 0.0165099 -0.021143399 0.090690002, + 0.0137106 -0.025139799 0.0907657, + 0.0109179 -0.024713499 0.091341302, + 0.040174201 -0.018529201 0.079399198, + 0.040174201 -0.022719201 0.079060301, + 0.0378174 -0.0295424 0.079901397, + 0.040174201 -0.026900901 0.078574501, + 0.0378174 -0.025317499 0.080510199, + 0.0378174 -0.0231991 0.080758803, + 0.058998398 -0.043613002 0.048692401, + 0.059445001 -0.042834401 0.046781, + 0.058998398 -0.046869598 0.047991902, + 0.059445001 -0.046027601 0.046143901, + 0.058412101 -0.044517301 0.050599001, + 0.050219599 -0.036114998 0.067310601, + 0.051830001 -0.0343915 0.065476298, + 0.050219599 -0.016818499 0.069156498, + 0.050219599 -0.0129718 0.069126397, + 0.051830001 -0.0154481 0.066868097, + 0.051830001 -0.019227199 0.066850103, + 0.056809202 -0.0328178 0.0568511, + 0.058412101 -0.037838198 0.051803902, + 0.0576833 -0.035326201 0.054329298, + 0.0576833 -0.038747601 0.053828198, + 0.058412101 -0.0411832 0.051257301, + 0.058998398 -0.040344201 0.049284499, + 0.0328326 0.0256759 0.077973098, + 0.0248404 0.030391101 0.081188001, + 0.0599402 -0.0135109 0.038426299, + 0.059757002 -0.0104361 0.039937802, + 0.0599402 -0.0184054 0.041047599, + 0.0599402 -0.0158724 0.039824098, + 0.059999999 -0.021400901 0.039323501, + 0.059999999 -0.0189001 0.0382093, + 0.0599402 -0.0296946 0.043795899, + 0.0599402 -0.026761301 0.043457702, + 0.059757002 -0.035915501 0.045736, + 0.059757002 -0.0298885 0.0460742, + 0.059757002 -0.032892901 0.046007399, + 0.0193005 0.0568063 0.0124548, + 0.0107568 0.059035402 0.0074529899, + -8.7673115e-012 0.0600341 0.040079899, + 0.00267513 0.0599626 0.030856799, + 0.00267513 0.059968699 0.040065501, + -0.0137106 0.058408801 0.017022399, + -0.019305199 0.056543101 0.0393079, + -0.0081421202 0.0594269 0.039945599, + -0.0081421202 0.0594499 0.021635899, + -0.0053918599 0.0597675 0.042319801, + -0.0077038999 0.059510902 0.0074526099, + -0.022994 0.055430599 0.0124559, + -0.0220857 0.0557568 0.016961999, + -0.0220857 0.055788402 0.0147124, + -0.033661801 -0.19153801 -0.049515199, + 0.044564299 -0.166486 -0.0399234, + 0.0465803 -0.16638801 -0.037567198, + 0.0463636 -0.171529 -0.0379478, + 0.042409498 -0.17153201 -0.042306699, + 0.042828102 -0.20853201 -0.041854899, + 0.040608101 -0.191534 -0.044017401, + 0.0424264 -0.166581 -0.0421753, + 0.0465803 -0.168965 -0.037658501, + 0.048175599 -0.171527 -0.035628099, + 0.048459999 -0.171527 -0.035224698, + 0.059999999 -0.047155801 0.040107202, + 0.059999999 -0.050141301 0.039434802, + 0.0599402 -0.047729 0.0418601, + 0.0599402 -0.0446718 0.0424858, + 0.059999999 -0.044162702 0.040682301, + 0.059999999 -0.0531126 0.038665399, + 0.059344199 -0.171505 -0.0087099401, + 0.0583959 -0.19150899 -0.0136288, + 0.058689699 -0.191508 -0.012318, + 0.058983799 -0.171507 -0.0107787, + 0.059253901 -0.208506 -0.0092666801, + 0.0302257 0.042257499 0.065842703, + 0.0302257 0.0435187 0.064007796, + 0.027557701 0.043920901 0.0666603, + 0.0302257 0.0409058 0.067621797, + 0.0302257 0.039466999 0.069338702, + 0.0378174 0.046568699 0.0146211, + 0.040174201 0.0445484 0.0146008, + 0.038010798 0.046435501 0.012463, + 0.0328326 0.042849801 0.061297201, + 0.0328326 0.041686598 0.0631449, + 0.0528774 0.028365999 0.0124774, + 0.048467699 0.0148421 0.064279698, + 0.040174201 0.043145798 0.0363455, + 0.040174201 0.044449002 0.016715201, + -1.0845815e-011 -0.15444601 -0.0577568, + 0.00268824 -0.152298 -0.057124101, + 0.0053973799 -0.150133 -0.056297801, + 0.0167691 0.057616498 0.0074541201, + 0.0281986 0.0529682 0.0074578198, + 0.0220857 -0.153754 -0.0535446, + 0.0220857 -0.151531 -0.052970201, + 0.0248404 -0.153561 -0.052372601, + 0.0248404 -0.151315 -0.0517979, + 0.019305199 -0.156131 -0.055070698, + 0.0240272 -0.191542 -0.054826502, + 0.025251999 -0.191542 -0.054274801, + 0.024834501 -0.171542 -0.054465901, + 0.053578701 -0.20852 -0.026839901, + 0.051438902 -0.191523 -0.0307351, + 0.050517999 -0.208524 -0.032205801, + 0.054602101 -0.171518 -0.024697701, + 0.055787299 -0.159905 -0.0214443, + 0.055419099 -0.171517 -0.0228574, + 0.055787299 -0.16573 -0.0218371, + 0.050219599 -0.155388 -0.031522799, + 0.048467699 -0.158352 -0.034426998, + 0.048467699 -0.155701 -0.0340579, + 0.051830001 -0.155066 -0.028914699, + 0.0424264 -0.154064 -0.040682498, + 0.044564299 -0.156293 -0.038867, + 0.044564299 -0.15374 -0.0384291, + 0.044564299 -0.16139901 -0.039533801, + 0.044564299 -0.158847 -0.039235201, + 0.056793701 0.019311599 0.0124846, + 0.057391401 0.017511001 0.0124861, + 0.059431199 0.0081526199 0.0124935, + 0.056809202 0.01551 0.0302344, + 0.059757002 -0.0082509797 0.038274799, + 0.0599402 -0.0093747796 0.0352256, + 0.059999999 -0.00052374101 0.0157081, + 0.059999999 -0.00028193899 0.014956, + 0.059999999 -0.00158166 0.0179656, + 0.0599402 -0.00075967598 0.0222187, + 0.059999999 -0.00108433 0.0169625, + 0.0599402 -0.0026705801 0.026214, + 0.050219599 -0.15809099 -0.0318923, + 0.048467699 -0.161002 -0.034726501, + 0.033319298 -0.171538 -0.049761601, + 0.0378174 -0.16915201 -0.0464199, + 0.038047399 -0.171535 -0.046257298, + 0.019305199 -0.158346 -0.055504501, + 0.019305199 -0.160561 -0.055868998, + 0.0220857 -0.155984 -0.054048698, + 0.0256411 -0.171542 -0.0541085, + -0.0546159 -0.02059 0.062186699, + -0.0532961 -0.0217082 0.0644719, + -0.0546159 -0.024219301 0.062067401, + -0.0546159 -0.042390998 0.0596302, + -0.0521175 -0.20847499 0.0298943, + -0.0532961 -0.040256899 0.062239401, + -0.051830001 -0.0154729 0.066852801, + -0.051830001 -0.0192426 0.066832803, + -0.0532961 -0.018007999 0.064541198, + -0.051830001 -0.0117167 0.066753298, + -0.050219599 -0.0129957 0.069111697, + -0.050219599 -0.016833499 0.069139801, + -0.051830001 -0.00276945 0.065627404, + -0.0570965 -0.20848399 0.018604999, + -0.055787299 -0.0303303 0.059341099, + -0.059999999 -0.0077972198 0.028994599, + -0.059999999 -0.00361019 0.0218096, + -0.059999999 -0.00561126 0.025563501, + -0.0599402 -0.0026701 0.026213801, + -0.059999999 -0.00158619 0.0179605, + -0.0599402 0.0021516799 0.0157545, + -0.0599402 -0.00075900799 0.022215201, + -0.044564299 -0.156297 -0.0388414, + -0.0424264 -0.156574 -0.041095499, + -0.0597114 0.0058894102 0.0124953, + -0.059757002 0.00528024 0.0142046, + -0.0599402 0.0025649699 0.0141774, + -0.059757002 0.00488608 0.015815901, + -0.059757002 0.0053930799 0.01334, + -0.0599402 0.0026825599 0.0133273, + -0.034754898 -0.171537 -0.048750401, + -0.034765299 -0.19153699 -0.048749201, + -0.035366699 -0.166831 -0.0481948, + -0.0378174 -0.159508 -0.0456172, + -0.0378174 -0.157086 -0.045253199, + -0.035366699 -0.159702 -0.047506101, + -0.0378174 -0.161928 -0.045913201, + -0.040174201 -0.1593 -0.043599501, + -0.040174201 -0.156838 -0.043235298, + -0.059351299 0.0088107605 0.012493, + -0.059445001 0.0081399204 0.0133528, + -0.059445001 0.0080318796 0.0142323, + -0.055787299 0.00172404 0.054380801, + -0.0169627 -0.191544 -0.057399798, + -0.0139775 -0.208545 -0.058183201, + -0.0182469 -0.191544 -0.057005599, + -0.019903 -0.208543 -0.056436799, + -0.010915 -0.171545 -0.0588459, + -0.0109552 -0.19154499 -0.0588389, + -0.00616926 -0.19154599 -0.059529498, + -0.0048316298 -0.19154599 -0.0596526, + -0.0053973799 -0.15440699 -0.057512499, + -0.00268824 -0.15443701 -0.057696301, + -0.0053973799 -0.152266 -0.056939401, + -0.0220857 -0.153758 -0.053535599, + -0.058072701 -0.19151001 -0.0149326, + -0.0562139 -0.191515 -0.0208237, + -0.0557741 -0.171516 -0.021943999, + -0.054305699 -0.171519 -0.025375901, + -0.0546159 -0.165841 -0.024560601, + -0.058383498 -0.171509 -0.0136419, + -0.058998398 -0.16525801 -0.010636, + -0.058998398 -0.15898 -0.0102336, + -0.0588759 -0.171508 -0.0114234, + -0.059999701 -0.208498 0.00036775399, + -0.0597024 -0.20850299 -0.0058025299, + -0.0484627 -0.171527 -0.035226699, + -0.049018301 -0.208526 -0.034434699, + -0.051830001 -0.038161501 0.064801201, + -0.048784502 -0.208471 0.035095502, + -0.0220857 -0.0180858 0.089346804, + 0.0081421202 -0.0152134 0.092860699, + 0.0081421202 -0.019810701 0.092401601, + 0.0053918599 -0.019574599 0.092704698, + 0.00267513 -0.024028299 0.092265896, + 3.0512249e-012 -0.028550699 0.091545798, + 0.0053918599 -0.0057322402 0.093577698, + -6.2722032e-012 -0.0101534 0.093681097, + -0.0075038001 -0.208451 0.059694901, + -0.0053918599 -0.028720301 0.091304801, + -0.00267513 -0.028592501 0.091486402, + -0.0137106 -0.0296595 0.089971997, + -0.0135848 -0.208452 0.058607899, + -0.0248404 -0.0190058 0.0882219, + 0.0081421202 -0.0106052 0.093156002, + 0.035366699 -0.021689599 0.082559101, + 0.019305199 -0.026305599 0.089191899, + 0.0220857 -0.0135829 0.089691803, + 0.019305199 -0.0172836 0.090330601, + 0.019305199 -0.0218047 0.089840703, + 0.0302257 -0.0299266 0.084302902, + 0.0328326 -0.0246264 0.0837401, + 0.0328326 -0.026789401 0.0834378, + 0.035366699 -0.025977099 0.082047701, + 0.035366699 -0.023835201 0.082322203, + 0.0328326 -0.022459099 0.084004201, + 0.035366699 0.0081510702 0.0819325, + 0.035366699 0.0101168 0.081600599, + 0.0220857 -0.0090759797 0.089873902, + 0.0220857 -0.0113294 0.089802802, + 0.0248404 -0.0122997 0.088701203, + 0.0109179 -0.0109689 0.0927331, + 0.00267513 0.047027402 0.0760208, + 0.00267513 0.048594501 0.074206203, + 0.0248404 0.0323098 0.0800061, + 0.027557701 0.034550499 0.076460198, + 0.027557701 0.036297999 0.075022601, + 0.027557701 0.037978999 0.073499903, + 9.8068871e-012 0.0128274 0.092656396, + -0.0053918599 0.00347784 0.093335703, + -0.00267513 -0.00096041098 0.093706504, + -0.00267513 0.00364236 0.093501396, + 0.0081421202 0.016792201 0.091507301, + 0.00267513 -0.00096032 0.093707301, + 0.00267513 -0.0055780001 0.093748398, + 5.4775238e-012 -0.00090833602 0.093761899, + 7.9962018e-012 -0.0055275899 0.093803801, + 0.0053918599 -0.0011196299 0.093539499, + 0.0053918599 0.0034785401 0.093337499, + 0.0081421202 0.012302 0.092176698, + 0.0302257 0.0235123 0.081130803, + 0.027557701 0.0230549 0.083112396, + 0.0220857 0.0215433 0.086546503, + 0.0248404 0.022396 0.084920801, + 0.0248404 0.024430299 0.084137298, + 0.050219599 -0.020679399 0.069054097, + 0.048467699 -0.022340599 0.071145304, + 0.0137106 -0.016024601 0.091869399, + 0.0109179 -0.0155641 0.092432, + 0.0109179 -0.0201486 0.091967702, + 0.0137106 -0.020592 0.091398098, + 0.0165099 -0.016597001 0.091169603, + 0.0137106 -0.0114461 0.092177898, + 0.0165099 -0.0120395 0.091487601, + 0.0532961 -0.0179825 0.0645568, + 0.0546159 -0.0314993 0.0614786, + 0.055787299 -0.0111617 0.059209701, + 0.0532961 -0.0124966 0.064434201, + 0.051830001 -0.0117001 0.0667639, + 0.0532961 -0.0143022 0.0645044, + 0.051830001 -0.030606501 0.066015303, + 0.050219599 -0.024545399 0.0688181, + 0.048467699 -0.030206401 0.070346899, + 0.050219599 -0.032269299 0.067946099, + 0.048467699 -0.034124698 0.069743797, + 0.048467699 -0.026276199 0.070814103, + 0.050219599 -0.0284108 0.068448603, + 0.0465803 -0.032199901 0.072096802, + 0.0465803 0.0087608797 0.070446797, + 0.048467699 0.0061808601 0.068578102, + 0.0465803 0.0069218501 0.071088903, + -0.0053918599 0.037868701 0.083675399, + 0.0424264 0.0117258 0.074669302, + 0.044564299 0.00937826 0.072919697, + 0.044564299 0.0112419 0.072244003, + 0.0424264 0.013613 0.073961303, + 0.0424264 0.0154784 0.073162504, + 0.0424264 0.0079063596 0.075816602, + 0.044564299 0.00560755 0.074007697, + 0.0424264 0.0098218601 0.075287499, + 0.044564299 0.0074984799 0.073507302, + 0.0328326 0.0237615 0.0789866, + 0.0328326 0.0118663 0.083048202, + 0.0302257 0.0134744 0.084378898, + 0.059757002 -0.0268708 0.045900799, + 0.059445001 -0.027086301 0.048279598, + 0.059445001 -0.0364266 0.047736999, + 0.058998398 -0.037067398 0.0497673, + 0.058412101 -0.034486901 0.0522383, + 0.0165099 0.057499401 0.039519399, + 0.0165099 0.0575688 0.0305166, + 0.017363001 0.057444301 0.0124543, + 0.019305199 0.056543 0.039308, + 0.019305199 0.056641702 0.030384701, + 0.0229061 0.055466998 0.0124558, + 0.020158799 0.056523599 0.012455, + 0.0226037 0.055586901 0.0074557401, + 0.0255982 0.054276899 0.0124568, + 0.0137106 0.058285002 0.041964799, + 0.0137106 0.0582968 0.039695799, + 0.0137106 0.058341801 0.0306265, + 0.0145255 0.058226701 0.0124536, + -2.699729e-008 0.0600104 0.0124522, + -4.4206461e-012 0.060020201 0.0216705, + 0.00289505 0.059941601 0.0124523, + -4.7589998e-005 0.060011499 0.0124522, + -0.00154487 0.059987601 0.0074522402, + -0.0053973799 -0.163018 -0.0591047, + -0.0165058 0.057679798 0.0124541, + -0.0137813 0.058403399 0.0074534998, + -0.0137106 0.0582969 0.039695699, + -0.0146178 0.0582036 0.0124537, + -0.0137106 0.058389299 0.0215718, + -0.0165099 0.057672098 0.0170056, + -0.019305199 0.056743301 0.021472501, + -0.0202484 0.056491598 0.012455, + -0.0197125 0.056676898 0.0074548698, + -0.0109153 0.058995299 0.012453, + -0.0088465102 0.059355699 0.0124527, + -0.0220857 0.055693999 0.021409299, + -0.0378174 -0.164343 -0.0461425, + -0.036173999 -0.208536 -0.047703002, + 0.044440001 -0.17152999 -0.040175699, + 0.0424264 -0.169063 -0.042266801, + 0.044024602 -0.17153101 -0.040611699, + 0.044564299 -0.16901501 -0.0400148, + 0.044561401 -0.17152999 -0.040035099, + 0.044033099 -0.191531 -0.040603898, + 0.0449345 -0.19153 -0.039607901, + 0.040172402 -0.171534 -0.044425599, + 0.040174201 -0.169109 -0.044404302, + 0.0402769 -0.171534 -0.044335499, + 0.039599199 -0.171534 -0.044919699, + 0.039609101 -0.191534 -0.0449154, + 0.058412101 -0.165379 -0.0134622, + 0.058839001 -0.171508 -0.0116097, + 0.0583813 -0.171509 -0.0136414, + 0.0581921 -0.17151 -0.0144812, + 0.058998398 -0.165263 -0.0106695, + 0.058412101 -0.15921199 -0.0130678, + 0.058998398 -0.15898199 -0.0102746, + 0.0302257 0.0516329 0.021167001, + 0.027557701 0.053137999 0.021257401, + 0.028228801 0.052956201 0.0124578, + 0.027557701 0.045186501 0.064793304, + 0.0302257 0.044685401 0.0621242, + 0.0302257 0.0457545 0.060198799, + 0.0328326 0.0465311 0.0535671, + 0.044564299 0.038342599 0.035283402, + 0.0465803 0.035764098 0.034713101, + 0.0465803 0.037641399 0.016563199, + 0.0424264 0.0408068 0.035828199, + 0.044564299 0.0400194 0.0166163, + 0.040174201 0.0428578 0.040102299, + 0.0424264 0.042291999 0.0166671, + 0.0332799 0.049936 0.0124602, + 0.035366699 0.0484601 0.01464, + 0.0328326 0.0501546 0.016842499, + 0.0307914 0.051507998 0.012459, + 0.0356883 0.048243701 0.0124616, + 0.0328326 0.040430401 0.064944401, + 0.0328326 0.039085001 0.066688903, + 0.035366699 0.038442601 0.063967101, + 0.0378174 0.0271689 0.071898296, + 0.035366699 0.025658 0.075612098, + 0.0302257 0.0379452 0.070986502, + 0.035366699 0.0356814 0.067319699, + 0.0328326 0.0376538 0.068371698, + 0.035366699 0.0371041 0.065673903, + 0.0378174 0.033556301 0.066186398, + 0.0465803 0.0123727 0.068901204, + 0.0465803 0.0105795 0.069717698, + 0.044564299 0.0130845 0.071479201, + 0.0465803 0.015857499 0.067012601, + 0.0465803 0.0141341 0.0679987, + 0.044564299 0.0149007 0.070625201, + 0.040174201 0.0232177 0.071718402, + 0.0378174 0.025417 0.073124602, + 0.053653602 0.0268292 0.0124786, + 0.054204401 0.025738601 0.0124795, + 0.0532961 0.0275055 0.0144301, + 0.0532832 0.0275626 0.0124781, + 0.053669199 0.026833201 0.0074786399, + 0.0532961 0.0221001 0.041064002, + 0.0532961 0.022679299 0.039593399, + 0.048467699 0.035168398 0.016507899, + 0.051423199 0.030925101 0.0124754, + 0.051830001 0.030179201 0.0144569, + 0.051817998 0.030230399 0.0124759, + 0.050219599 0.032791801 0.0144831, + 0.0502089 0.032837301 0.0124739, + 0.050626501 0.0322094 0.0074743498, + 0.0546159 -0.0083198901 0.061387099, + 0.0546159 0.0183565 0.041446399, + 0.0532961 0.021445399 0.042532001, + 0.0532961 0.020713899 0.043992799, + 0.051830001 0.022948699 0.046629898, + 0.0378174 0.045351502 0.036833201, + 0.0378174 0.046483099 0.016760699, + 0.035366699 0.0483873 0.016803101, + 0.0224167 -0.208543 -0.055489101, + 0.0195219 -0.191544 -0.056582801, + -0.00268824 -0.156583 -0.058198702, + 0.019305199 -0.15392201 -0.054566801, + 0.051818501 -0.17152201 -0.0300825, + 0.0521175 -0.191522 -0.029575801, + 0.0532961 -0.165959 -0.027308701, + 0.053283598 -0.17151999 -0.027414801, + 0.0528998 -0.17152099 -0.028176101, + 0.0542247 -0.171519 -0.0255477, + 0.0546159 -0.16584501 -0.024591601, + 0.0532961 -0.160357 -0.026916901, + 0.0546159 -0.16013201 -0.0241994, + 0.057668298 -0.17151099 -0.016369199, + 0.0576833 -0.16549601 -0.016261499, + 0.056809202 0.012748 0.037955798, + 0.055787299 0.0170366 0.036312498, + 0.055787299 0.015899001 0.0390031, + 0.056809202 0.0139128 0.0353918, + 0.055787299 0.0179011 0.0336603, + 0.0546159 0.020131599 0.037224699, + 0.0546159 0.0190208 0.040040601, + 0.0576833 0.0164335 0.014319, + 0.0581805 0.0146752 0.0124883, + 0.0576833 0.0095801102 0.036903001, + 0.0576833 0.0107721 0.0344662, + 0.059757002 -0.00171342 0.030786499, + 0.0599402 -0.00475732 0.0298893, + 0.059999999 -0.0091309603 0.030684801, + 0.059999999 -0.0106851 0.032350399, + 0.059999999 -0.0144051 0.035502199, + 0.059999999 -0.0077777798 0.0289991, + 0.059999999 -0.00011320599 0.014153, + 0.059999902 0.000106517 0.0124999, + 0.059999999 -0.0056117801 0.0255637, + 0.059999999 -0.0066198702 0.0273287, + 0.059999999 -0.0036108301 0.021813, + 0.0599402 -0.00363521 0.028099401, + 0.050219599 -0.166179 -0.032583099, + 0.048467699 -0.163647 -0.034956399, + 0.048467699 -0.16628499 -0.0351169, + 0.050219599 -0.16079199 -0.0321922, + 0.048467699 -0.16891199 -0.035208099, + 0.049871601 -0.171525 -0.0332224, + 0.0514476 -0.171523 -0.0307364, + 0.051830001 -0.16607 -0.0299765, + 0.051830001 -0.160577 -0.029585101, + 0.0328326 -0.152841 -0.047973901, + 0.0378174 -0.157083 -0.045274898, + 0.0353618 -0.171537 -0.048324, + 0.035366699 -0.169192 -0.048306901, + 0.035726301 -0.171537 -0.048067398, + 0.034755301 -0.171537 -0.0487509, + 0.034765299 -0.19153699 -0.048749201, + 0.0220857 -0.15821999 -0.054482799, + 0.0248404 -0.155817 -0.052877001, + 0.027557701 -0.157912 -0.051991802, + 0.027557701 -0.160199 -0.052356999, + 0.0302257 -0.155415 -0.050090399, + 0.027557701 -0.155627 -0.051557001, + 0.0248404 -0.158075 -0.053311501, + 0.0248404 -0.164846 -0.0542005, + 0.027557701 -0.16248301 -0.052653398, + 0.0248404 -0.16259199 -0.053972598, + 0.0220857 -0.160455 -0.054847501, + 0.0248404 -0.160335 -0.053676501, + -0.0532961 -0.0328537 0.063512102, + -0.0532961 -0.036562499 0.0629391, + -0.0532961 -0.0291372 0.063958302, + -0.0546159 -0.031501502 0.061462499, + -0.051830001 -0.0080980901 0.066517301, + -0.0532961 -0.0072720801 0.063860402, + -0.055787299 -0.001326 0.056012299, + -0.055787299 0.00021952201 0.055230498, + -0.055787299 -0.037462801 0.058403499, + -0.055787299 -0.033898398 0.058932401, + -0.0546159 -0.0351425 0.060975298, + -0.0546159 -0.038774598 0.0603646, + -0.056809202 -0.0432803 0.055120099, + -0.056809202 -0.039804801 0.055807799, + -0.0576833 -0.0455558 0.052471701, + -0.054897901 -0.208479 0.024377899, + -0.055787299 -0.041016899 0.057754502, + -0.0576833 -0.0421593 0.0531983, + -0.058412101 -0.0445171 0.050585002, + -0.058412101 -0.041185498 0.051240101, + -0.058998398 -0.0242563 0.0504933, + -0.058998398 -0.021125199 0.050167799, + -0.0576833 -0.0387499 0.0538112, + -0.056809202 -0.032825399 0.0568325, + -0.056809202 -0.036317602 0.056378599, + -0.059999999 -0.032505602 0.0416844, + -0.059999999 -0.0354001 0.041723099, + -0.059999999 -0.050149299 0.039415099, + -0.059445001 -0.0240178 0.0480115, + -0.056809202 -0.00283767 0.0533407, + -0.0599402 -0.00765137 0.033486798, + -0.059999999 -0.0091581997 0.0306914, + -0.0599402 -0.0061114701 0.031703901, + -0.059757002 -0.0045643998 0.034631301, + -0.059999999 -0.0107146 0.032350998, + -0.0599402 -0.00477676 0.0298848, + -0.0599402 -0.00364039 0.028076099, + -0.059757002 0.0044084499 0.017159101, + -0.059757002 0.00395549 0.018293999, + -0.059757002 0.00029395401 0.026869301, + -0.0599402 0.00117393 0.018126599, + -0.059757002 -0.00063247501 0.0288529, + -0.0599402 0.00164945 0.0170501, + -0.059757002 0.00211434 0.022624001, + -0.059445001 0.0024157299 0.029640101, + -0.059445001 0.0032977201 0.0275336, + -0.059445001 0.0050261701 0.0230384, + -0.058412101 0.00760801 0.033535, + -0.058998398 0.0044700601 0.0326101, + -0.058998398 0.0054968102 0.030435801, + -0.059445001 7.0618597e-005 0.033758201, + -0.059757002 -0.0030410099 0.032724101, + -0.059757002 -0.00173278 0.030781999, + -0.059445001 0.00135199 0.0316911, + -0.058998398 0.0032158301 0.034803301, + -0.050219599 -0.15809201 -0.031859599, + -0.050219599 -0.15539201 -0.031493898, + -0.050219599 -0.16079099 -0.032157399, + -0.051830001 -0.15507001 -0.028884999, + -0.048467699 -0.161 -0.034692802, + -0.044564299 -0.16394401 -0.039733201, + -0.027557701 -0.15563001 -0.051543601, + -0.0302257 -0.153111 -0.0495729, + -0.027557701 -0.15335099 -0.051040899, + -0.0328326 -0.15284701 -0.047960401, + -0.035366699 -0.15256 -0.046206299, + -0.0328326 -0.16457 -0.049784102, + -0.0328326 -0.162229 -0.049555201, + -0.035366699 -0.164461 -0.048031099, + -0.035366699 -0.162084 -0.047801901, + -0.044564299 0.039991301 0.016605601, + -0.0465803 0.037774902 0.0145311, + -0.044564299 0.0396626 0.020443499, + -0.0576833 0.0107534 0.034461901, + -0.059445001 0.0076571498 0.0158781, + -0.058998398 0.0108133 0.0142602, + -0.0576833 0.0139003 0.024301, + -0.058848299 0.0117109 0.0124907, + -0.058998398 0.0109163 0.0133658, + -0.058731299 0.0122807 0.00749022, + -0.058412101 0.0137104 0.013379, + -0.058203701 0.0145829 0.0124884, + -0.0546159 0.0047743199 0.056201398, + -0.055787299 0.0031829299 0.053466599, + -0.055787299 0.00459179 0.052491199, + -0.055787299 0.00594613 0.0514584, + -0.048467699 0.035137899 0.0164961, + -0.048467699 0.034726501 0.0201464, + -0.0465803 0.0372428 0.020297799, + -0.0465803 0.037611999 0.016551999, + -0.0227904 -0.191543 -0.055350602, + -0.0256174 -0.208542 -0.054090299, + -0.0302257 -0.16467001 -0.051395599, + -0.0165099 -0.151885 -0.054861199, + -0.019305199 -0.151724 -0.053985499, + -0.0220857 -0.158222 -0.0544701, + -0.0248404 -0.15582 -0.052864999, + -0.0220857 -0.15598699 -0.054037999, + -0.0165099 -0.15626 -0.055936798, + -0.019305199 -0.15613399 -0.055061299, + -0.0165099 -0.15406901 -0.055434398, + -0.0137106 -0.15636501 -0.056666899, + -0.019305199 -0.153926 -0.054558899, + -0.0109179 -0.15861601 -0.057686299, + -0.0081428103 -0.160833 -0.058496799, + -0.0081428103 -0.162991 -0.0587916, + -0.056669399 -0.191514 -0.01956, + -0.053285599 -0.17151999 -0.027415801, + -0.053759102 -0.19152001 -0.026492501, + -0.0532961 -0.160355 -0.026879899, + -0.0532961 -0.16595399 -0.027278399, + -0.0532961 -0.154741 -0.026215, + -0.051830001 -0.15782399 -0.029251, + -0.051830001 -0.160576 -0.0295492, + -0.055787299 -0.15406699 -0.020739101, + -0.055787299 -0.15990201 -0.0214056, + -0.059999999 7.5646785e-006 0.0074999998, + -0.059682 0.0061768098 0.0074950801, + -0.0546159 -0.154406 -0.023495801, + -0.0546159 -0.16013101 -0.024161501, + -0.057670102 -0.17151099 -0.0163697, + -0.0582381 -0.17151 -0.0142969, + -0.058412101 -0.16537499 -0.013429, + -0.058412101 -0.15921 -0.0130273, + -0.059934601 -0.171501 -0.0026638401, + -0.0599402 -0.164913 -0.0024055899, + -0.059980098 -0.19149999 -0.00139239, + -0.0599305 -0.19150101 -0.00273475, + -0.059757002 -0.16502699 -0.00511494, + -0.059725199 -0.17150301 -0.0055998499, + -0.050219599 -0.163486 -0.032388501, + -0.048467699 -0.168909 -0.035191, + -0.051438902 -0.191523 -0.0307351, + -0.051830001 -0.16606601 -0.029947, + -0.0529892 -0.17152099 -0.0280085, + -0.0523162 -0.20852201 -0.029211201, + -0.047982302 -0.171527 -0.035870001, + -0.048288502 -0.171527 -0.035475399, + -0.046578299 -0.171528 -0.037679199, + -0.047172099 -0.19152801 -0.0369257, + -0.059999999 -0.0382808 0.041536901, + -0.059999999 -0.041198801 0.041152202, + -0.059999999 -0.047173601 0.040087301, + -0.059999999 -0.044191401 0.040664699, + -0.035366699 -0.00879726 0.083174199, + -0.0302257 -0.0080175595 0.086253896, + -0.0302257 -0.0102124 0.086233102, + -0.0328326 -0.0094187902 0.084774502, + -0.0328326 -0.0072488398 0.084769703, + -0.027557701 -0.00674188 0.087600797, + -0.027557701 -0.028859099 0.085740499, + -0.025251999 -0.208455 0.054593299, + -0.0307144 -0.20845699 0.0517084, + -0.0449345 -0.20846701 0.039926399, + -0.044564299 -0.0100487 0.0756367, + -0.0465803 -0.0122267 0.073550999, + -0.048467699 -0.0144916 0.071382403, + -0.0358513 -0.20846 0.048277199, + -0.0109179 -0.0292501 0.090552799, + -0.0081421202 -0.028938301 0.090995498, + -0.0053918599 -0.0241614 0.092085801, + -0.00267513 0.019478699 0.091530897, + -0.00267513 0.017273501 0.091925599, + -0.00267513 -0.024028201 0.092265703, + 0.00267513 -0.0102021 0.093624704, + 0.0053918599 -0.0103512 0.093451403, + 0.0053918599 -0.0149682 0.0931601, + -0.0165099 -0.0256691 0.090048999, + -0.019305199 -0.0218042 0.089839198, + -0.0137106 -0.025139101 0.090764798, + -0.0220857 -0.0270478 0.088187002, + -0.0220857 -0.0225772 0.088846102, + -0.019305199 -0.026304699 0.089190602, + -0.0248404 -0.023463201 0.087707601, + -0.0248404 -0.0278995 0.087036602, + -0.0195219 -0.208453 0.056901298, + -0.027557701 -0.0244615 0.086424999, + 0.0081421202 0.059241898 0.0465005, + 0.0109179 0.0588824 0.044235099, + 0.0053918599 0.059355501 0.0487854, + 0.0081421202 0.059378099 0.044362601, + 0.0053918599 0.059590399 0.046596501, + 0.00267513 0.059794798 0.0466525, + 0.0081421202 0.059005301 0.048682101, + 0.0109179 0.058743201 0.0463631, + 0.0109179 0.0585039 0.0485343, + 0.0137106 0.057845701 0.048340399, + 0.0248404 0.042603299 0.071011297, + 0.0248404 0.041065902 0.0727164, + 0.027557701 0.041117501 0.070219003, + 0.027557701 0.042563301 0.068471201, + 0.0248404 0.045418199 0.067396499, + 0.0248404 0.044055399 0.069235697, + 0.0109179 -0.0063713002 0.092870101, + 0.0081421202 -0.0013911 0.0932533, + 0.0081421202 -0.0059951101 0.093286701, + 0.0378174 -0.0168311 0.081280902, + 0.0378174 -0.018954899 0.081144199, + 0.035366699 -0.0152413 0.083042599, + 0.035366699 -0.0195415 0.082758099, + 0.035366699 -0.017391801 0.0829193, + 0.0302257 -0.0124092 0.086180702, + 0.0328326 -0.0137657 0.084677704, + 0.0248404 -0.0145365 0.088582203, + 0.027557701 -0.0133927 0.087460198, + 0.0248404 0.0203477 0.0856058, + 0.0248404 0.0120847 0.087418899, + 0.027557701 0.0129188 0.085972801, + 0.0302257 0.0093684001 0.08506, + 0.0302257 0.0114711 0.0847461, + 0.027557701 0.0107979 0.086301401, + 0.0328326 0.0077980701 0.083696298, + 0.0328326 0.00988096 0.083398603, + 0.027557701 0.0020872201 0.0872593, + 0.027557701 -0.0089567099 0.087598599, + 0.0248404 -0.0100627 0.088780597, + 0.027557701 -0.0111743 0.087548897, + 0.0302257 -0.010212 0.086241201, + 0.0248404 -0.0078266701 0.088820502, + 0.0109179 -0.00177964 0.0928436, + 0.0109179 0.0073538702 0.092302002, + 0.0109179 0.00279809 0.0926539, + 0.0081421202 0.00319868 0.093056403, + 0.0081421202 0.0077661402 0.0926966, + 0.0137106 -0.00686508 0.092323199, + 0.0137106 -0.00228963 0.092305601, + 0.019305199 -0.00368426 0.0908342, + 0.0220857 -0.0068236399 0.089905001, + 0.019305199 -0.00821527 0.090827502, + 0.0220857 -0.0045733401 0.089896098, + 0.0165099 -0.0029237601 0.091636598, + 0.0165099 -0.0074789999 0.091643199, + -0.00267513 0.048593201 0.074205399, + 4.8149076e-012 0.047093902 0.076057397, + 1.1095386e-011 0.048661198 0.074241802, + -0.00267513 0.050070599 0.072317801, + 0.00267513 0.021573501 0.091079101, + 1.5449426e-011 0.019537801 0.0915813, + 1.4496006e-012 0.0173322 0.091976501, + 0.0081421202 0.0231697 0.090127997, + 0.0053918599 0.0234848 0.090382099, + 0.0081421202 0.0335651 0.085877903, + 0.0053918599 0.033896498 0.086110599, + -0.00267513 0.0380673 0.083806999, + -1.1106279e-011 0.0400525 0.082478903, + -2.1458102e-012 0.0381325 0.083850399, + 0.019305199 0.041891702 0.075751498, + 0.0165099 0.042865101 0.076311603, + 0.0220857 0.042378101 0.0734438, + 0.0165099 0.037527598 0.0808663, + 0.0053918599 0.019298101 0.091378398, + 0.0053918599 0.017096199 0.091771297, + 0.0081421202 0.018990099 0.091117397, + 0.0053918599 0.0213906 0.090928003, + 0.0081421202 0.0210789 0.090670303, + 0.00267513 0.0194789 0.091531403, + 0.00267513 0.0172744 0.091926202, + 0.0137106 0.024222299 0.088653803, + 0.0109179 0.0227187 0.0897642, + 0.0109179 0.0206329 0.090301499, + 0.0137106 0.0113221 0.091282703, + 0.0109179 0.0118783 0.091790304, + 0.00267513 0.0082229497 0.093133897, + 0.00267513 0.0127711 0.092605002, + -1.4328556e-012 0.0082777999 0.093186401, + 0.0053918599 0.0080541195 0.092972301, + 0.00267513 0.0036427299 0.093502201, + 0.0053918599 0.0125978 0.0924467, + 5.2488474e-012 0.00369621 0.093555801, + 0.027557701 0.027031099 0.081285402, + 0.027557701 0.0250556 0.082248501, + 0.0302257 0.025473099 0.080189899, + 0.0302257 0.0274032 0.079150803, + 0.027557701 0.028975699 0.080223002, + 0.0248404 0.028433699 0.082271501, + 0.0248404 0.0264448 0.083254501, + 0.027557701 0.021034701 0.083877899, + 0.0302257 0.021526899 0.081973702, + 0.019305199 0.024658499 0.086653799, + 0.0220857 0.0256512 0.085046999, + 0.019305199 0.026716201 0.085840501, + 0.0220857 0.023604499 0.085846402, + 0.0165099 0.0255602 0.087344401, + 0.019305199 0.0307645 0.083909899, + 0.019305199 0.0287534 0.084926099, + 0.0220857 0.0296786 0.083146602, + 0.0220857 0.031647399 0.082044601, + 0.040174201 -0.0164333 0.079513602, + 0.0378174 -0.0147071 0.0813803, + 0.044564299 -0.030348901 0.074359499, + 0.0465803 -0.028211299 0.072668597, + 0.0424264 -0.028580001 0.076521903, + 0.0424264 0.00598722 0.076257199, + 0.040174201 0.0081456397 0.0779998, + 0.0378174 0.0082320496 0.080040999, + 0.044564299 0.00371329 0.074421197, + 0.044564299 0.0018348499 0.074747197, + 0.0532961 -0.029135101 0.063974001, + 0.051830001 -0.0230186 0.0667025, + 0.051830001 -0.0268136 0.066424102, + 0.055787299 -0.030322799 0.059359498, + 0.0546159 -0.0100433 0.061691701, + 0.0532961 -0.0107639 0.064321101, + 0.0546159 -0.016952399 0.062203102, + 0.055787299 -0.019639 0.059870102, + 0.055787299 -0.0145492 0.059675701, + 0.055787299 -0.012855 0.059479099, + 0.056809202 -0.019004701 0.057501201, + 0.055787299 -0.016228201 0.059799001, + 0.0546159 -0.011768 0.061921299, + 0.0546159 -0.0134774 0.062075499, + 0.0546159 0.0168043 0.044231199, + 0.0546159 0.017618001 0.042844899, + 0.055787299 0.0144795 0.0416811, + 0.0532961 0.019904699 0.045441601, + 0.0532961 0.019018 0.0468725, + 0.048467699 -0.0105645 0.071321703, + 0.0465803 -0.0162064 0.073550701, + 0.048467699 -0.0144772 0.071398497, + 0.048467699 -0.0184054 0.071340099, + 0.0465803 -0.0122129 0.073566496, + 0.048467699 0.00253916 0.069707602, + 0.050219599 0.00172608 0.067216299, + 0.048467699 0.0043674698 0.069185004, + 0.0465803 0.0050673098 0.071644597, + 0.0465803 0.0032021201 0.0721149, + 0.050219599 -0.0072878301 0.068848602, + 0.051830001 -0.0098620104 0.066666998, + 0.050219599 -0.0091577796 0.068971798, + 0.048467699 -0.0047854399 0.070969298, + 0.048467699 -0.0066863499 0.071117997, + 0.051830001 -0.00809965 0.066526003, + 0.0532961 -0.00902458 0.064136498, + 0.0532961 -0.00726985 0.063874297, + 0.050219599 -7.5080607e-005 0.067704499, + -0.0465803 0.034241501 0.043227099, + 0.0109179 0.033090599 0.085544698, + 0.00267513 0.0320483 0.087310597, + 0.00267513 0.0257817 0.0898799, + -3.6837612e-013 0.0258427 0.089927502, + 0.00267513 0.0236696 0.0905312, + 0.0053918599 0.025594899 0.089732997, + 7.8338177e-013 0.036163799 0.0851219, + 0.00267513 0.034090899 0.0862469, + -0.00267513 0.029978201 0.088269196, + -3.6708366e-012 0.0300407 0.088316098, + -4.8678639e-012 0.0279493 0.089173198, + -0.00267513 0.036099199 0.085077502, + -3.7589242e-012 0.034154098 0.086290903, + -9.2152197e-012 0.032111 0.087355703, + -1.3087608e-011 0.0419157 0.081010103, + -0.00267513 0.041849501 0.080968902, + -0.0053918599 0.039786302 0.082308203, + -0.00267513 0.0399867 0.082436599, + -0.0053918599 0.048386302 0.074095003, + 0.0328326 0.021817001 0.0799032, + 0.0328326 0.019848499 0.080722898, + 0.0302257 0.032939099 0.075464398, + 0.027557701 0.032742798 0.077807903, + 0.027557701 0.0308821 0.079062998, + 0.0328326 0.0293869 0.075662598, + 0.035366699 0.027475899 0.0744408, + 0.0328326 0.027553501 0.076864302, + 0.0302257 0.0311436 0.076785602, + 0.0302257 0.0292958 0.078015298, + 0.040174201 0.0120273 0.076977096, + 0.040174201 0.0100884 0.077533603, + 0.0378174 0.0101811 0.079643101, + 0.040174201 0.0139541 0.076329999, + 0.035366699 0.0039910199 0.082458198, + 0.035366699 0.0060897302 0.082212701, + 0.035366699 0.00187928 0.082670197, + 0.035366699 -0.013091 0.083127901, + 0.0328326 -0.0115909 0.084750101, + 0.040174201 0.0042966502 0.078666098, + 0.0378174 0.0062873801 0.0803532, + 0.0378174 0.00424923 0.080614403, + 0.040174201 0.00228324 0.078907102, + 0.040174201 0.0062188199 0.078374997, + 0.0424264 0.0021856099 0.076877102, + 0.0424264 0.00408393 0.076608397, + 0.035366699 0.0140725 0.080668502, + 0.035366699 0.0160539 0.080062099, + 0.0328326 0.0138555 0.082609601, + 0.035366699 0.0120866 0.081181601, + 0.0378174 0.0121461 0.079152703, + 0.0378174 0.014107 0.0785705, + 0.0302257 0.017504301 0.083368704, + 0.027557701 0.019000599 0.084546, + 0.0302257 0.0154813 0.0839222, + 0.0302257 0.019522401 0.082719401, + 0.0328326 0.015860699 0.082075499, + 0.0328326 0.0178612 0.0814467, + 0.056809202 -0.022350799 0.0575152, + 0.0576833 -0.0217961 0.0551912, + 0.058998398 -0.033790201 0.0501412, + 0.059445001 -0.030151401 0.048276301, + 0.059445001 -0.033237699 0.0480613, + 0.0220857 0.055391502 0.041269802, + 0.0220857 0.055695701 0.021411199, + 0.0248404 0.054492999 0.021338901, + 0.0248404 0.0541001 0.0409596, + 0.0220857 0.0553177 0.043316599, + 0.019305199 0.056297999 0.0456887, + 0.0165099 0.0574225 0.043859102, + 0.0165099 0.057274301 0.045958001, + 0.019305199 0.056452099 0.043609101, + 0.019305199 0.056518 0.041540399, + 0.0165099 0.057481602 0.041771799, + 0.0137106 0.0582317 0.044067498, + 0.0137106 0.0580885 0.046182599, + 0.0109179 0.058938202 0.039837599, + 0.0109179 0.058963601 0.030714899, + 0.0109179 0.058931202 0.042119902, + 0.0116529 0.058869001 0.0124531, + 0.00875236 0.059369698 0.0124527, + -1.0980297e-011 0.059994102 0.044520099, + 2.9191623e-012 0.059861299 0.0466705, + -0.00267513 0.059927501 0.0445025, + -0.00267513 0.059969399 0.042368598, + 6.9721837e-012 0.0600354 0.042384598, + -0.0109179 0.058160301 0.050719999, + -0.00267513 0.059794199 0.046651699, + -0.0081421202 0.059377398 0.044359401, + -0.0053918599 0.0597241 0.044449501, + -0.0109179 0.058881499 0.0442308, + -0.0053918599 0.0595893 0.046594702, + -0.0109179 0.058931101 0.0421184, + -0.00268824 -0.16303299 -0.0592889, + -0.0165099 0.057499502 0.039519299, + -0.0165099 0.057640899 0.0215267, + -0.017454101 0.0574167 0.0124543, + -0.019305199 0.056812901 0.0147228, + -0.0165099 0.057481401 0.041769501, + -0.0137106 0.058284901 0.041962899, + -0.0109179 0.058991302 0.021608099, + -0.0109179 0.058938298 0.039837599, + -0.0117463 0.058850501 0.0124531, + -0.0109179 0.0590013 0.017036, + -0.0081421202 0.059423398 0.042236999, + -0.0137106 0.058230501 0.044062201, + -0.030873001 0.0514591 0.012459, + -0.0302191 0.051830001 0.0124587, + -0.0378174 -0.166751 -0.046306599, + -0.035366699 -0.16919 -0.048294399, + -0.035878699 -0.171537 -0.047954101, + -0.0424264 -0.161584 -0.0417565, + -0.0424264 -0.164084 -0.041986499, + -0.0424264 -0.15908 -0.04146, + -0.040174201 -0.161761 -0.0438958, + -0.040174201 -0.16421799 -0.0441254, + 0.0248404 0.053220101 0.049168002, + 0.0220857 0.054087199 0.051697601, + 0.027557701 0.052645199 0.040610101, + 0.0248404 0.054017201 0.042981301, + 0.0302257 0.051029101 0.040221799, + 0.027557701 0.052552 0.0426034, + 0.027557701 0.052373402 0.044605501, + 0.027557701 0.052099701 0.046646699, + 0.0328326 0.048258699 0.047612298, + 0.0220857 0.052108899 0.058015302, + 0.027557701 0.046356399 0.062877104, + 0.0248404 0.0466878 0.065500498, + 0.027557701 0.0474273 0.0609187, + 0.0302257 0.046724901 0.058239099, + 0.0302257 0.0475954 0.056252699, + 0.040174201 0.042617999 0.041912101, + 0.0424264 0.040484399 0.039489701, + 0.044564299 0.037983801 0.038844399, + 0.0424264 0.040229499 0.041252501, + 0.0328326 0.043917 0.059408002, + 0.035366699 0.0396934 0.062206101, + 0.0378174 0.037546001 0.061194699, + 0.044564299 0.034298901 0.051061202, + 0.044564299 0.035087701 0.049323101, + 0.0378174 0.044555601 0.0444232, + 0.035366699 0.045794599 0.0489402, + 0.035366699 0.046281401 0.046992399, + 0.0378174 0.036301099 0.062914297, + 0.0378174 0.03497 0.064580403, + 0.040174201 0.032690302 0.063412301, + 0.040174201 0.031286199 0.064975701, + 0.040174201 0.034013402 0.061789699, + 0.0465803 0.0175361 0.065944798, + 0.044564299 0.0201269 0.067546003, + 0.0424264 0.0242662 0.067842796, + 0.0424264 0.0226027 0.069076203, + 0.040174201 0.0266327 0.069255002, + 0.040174201 0.024952799 0.070528701, + 0.0424264 0.027409799 0.065145999, + 0.0424264 0.0258704 0.066531204, + 0.0328326 0.0311691 0.074370503, + 0.035366699 0.029243501 0.0731804, + 0.0328326 0.034552202 0.071527697, + 0.0328326 0.036141101 0.069986403, + 0.035366699 0.034178399 0.068898298, + 0.0328326 0.032892801 0.072990701, + 0.0302257 0.036346 0.072560102, + 0.0302257 0.0346753 0.074054301, + 0.0378174 0.030498 0.069194503, + 0.035366699 0.0326006 0.070404597, + 0.0378174 0.032063801 0.067726098, + 0.0378174 0.0288644 0.070586801, + 0.040174201 0.028252101 0.067901902, + 0.035366699 0.030953599 0.071833603, + 0.040174201 0.0298051 0.066473901, + 0.0424264 0.0191213 0.0712936, + 0.0424264 0.020885499 0.070227399, + 0.044564299 0.018428501 0.0686564, + 0.044564299 0.016684201 0.0696835, + 0.0424264 0.0173166 0.072272703, + 0.035366699 0.023796899 0.076691702, + 0.0378174 0.0236158 0.074262999, + 0.040174201 0.021434501 0.072821803, + 0.0532961 0.0236167 0.0366644, + 0.0532961 0.023184501 0.038124401, + 0.0465803 0.0350799 0.039830402, + 0.044564299 0.037713099 0.040557601, + 0.048467699 0.033082802 0.034120299, + 0.0465803 0.035367299 0.038169, + 0.050219599 0.030310201 0.033507202, + 0.051830001 0.0299807 0.016391801, + 0.048467699 0.032646399 0.037466701, + 0.050219599 0.032611299 0.016450699, + 0.051830001 0.027458001 0.032876398, + 0.050219599 0.029833 0.0367405, + 0.051830001 0.026597699 0.037487701, + 0.0532961 0.0267125 0.0196681, + 0.0532961 0.027288301 0.0163316, + 0.0532961 0.024538999 0.032230999, + 0.051830001 0.0269386 0.035993401, + 0.055787299 0.0210943 0.019330099, + 0.055787299 0.018552 0.030906999, + 0.056809202 0.0189602 0.016145101, + 0.0546159 0.0209595 0.034449801, + 0.056809202 0.019234899 0.0143471, + 0.0546159 0.0247823 0.0144028, + 0.051830001 0.0210997 0.049589999, + 0.051830001 0.022063799 0.048121899, + 0.050219599 0.0250398 0.0493428, + 0.048467699 0.022289401 0.058082901, + 0.0465803 0.032402799 0.048327401, + 0.0378174 0.0448705 0.042534102, + 0.035366699 0.046675801 0.045048099, + 0.0229499 -0.171542 -0.055300798, + 0.0248404 -0.169323 -0.054453202, + 0.0248404 -0.16709 -0.054360501, + 0.0220857 -0.164919 -0.055371098, + 0.0220857 -0.162689 -0.055143502, + 0.0165099 -0.160651 -0.056742501, + 0.0165099 -0.158453 -0.056378301, + 7.4746485e-012 -0.163038 -0.0593496, + 0.033494599 0.049788099 0.0074603599, + 0.0429691 0.041884098 0.0074666501, + 0.019305199 -0.151719 -0.0539927, + 0.038435601 0.046080299 0.0074633099, + 0.0053973799 -0.169433 -0.059590999, + 0.0053966301 -0.171546 -0.0596103, + 0.0053973799 -0.16730499 -0.059496399, + 0.0081428103 -0.167292 -0.059185099, + 0.0061684698 -0.171546 -0.059539001, + 0.00616926 -0.19154599 -0.059529498, + 0.0075038001 -0.19154599 -0.0593764, + 0.0058778701 -0.171546 -0.059574801, + -0.0081428103 -0.167291 -0.059180401, + -0.0081428103 -0.16514499 -0.0590191, + -0.0031320599 -0.171546 -0.0597816, + -0.0026879699 -0.171546 -0.0597945, + 0.0044293702 -0.208546 -0.059670299, + -0.0017465299 -0.208546 -0.059808601, + 0.00294237 -0.171546 -0.0597912, + 0.056669399 -0.191514 -0.01956, + 0.057969999 -0.20851099 -0.0153093, + 0.056071501 -0.208515 -0.021187801, + 0.0424264 -0.159079 -0.041487601, + 0.0424264 -0.156571 -0.0411199, + 0.040174201 -0.156835 -0.043258399, + 0.0378174 -0.161929 -0.045939401, + 0.0378174 -0.15950701 -0.045641799, + 0.040174201 -0.159299 -0.043625701, + 0.040174201 -0.16422001 -0.044152401, + 0.0424264 -0.161586 -0.0417859, + 0.0424264 -0.164087 -0.042015001, + 0.040174201 -0.161762 -0.043923602, + 0.040174201 -0.16666999 -0.0443126, + 0.0378174 -0.164345 -0.046168, + 0.0378174 -0.16675401 -0.046328101, + 0.058829699 0.0118043 0.0124906, + 0.059285302 0.0092409896 0.0074926401, + 0.059337199 0.0089049097 0.0124929, + 0.056809202 0.0148141 0.0328632, + 0.058998398 0.0108291 0.0142628, + 0.058412101 0.013628 0.0142909, + 0.0576833 0.0153695 0.018985599, + 0.0576833 0.016139099 0.016081899, + 0.058998398 0.0096280398 0.018640099, + 0.058998398 0.0044891699 0.032614499, + 0.058412101 0.0076269298 0.033539198, + 0.059445001 0.00137125 0.0316955, + 0.058998398 0.00324262 0.0347968, + 0.058412101 0.0064076101 0.035848599, + 0.058998398 0.00633338 0.028205199, + 0.058412101 0.00860254 0.031259499, + 0.058998398 0.0079687396 0.023460601, + 0.058998398 0.0055018901 0.0304588, + 0.059445001 9.7621392e-005 0.033751599, + 0.059757002 -0.0045350399 0.034630701, + 0.0599402 -0.00608422 0.031697299, + 0.059757002 -0.00301386 0.0327176, + 0.0599402 -0.00762195 0.033486199, + 0.059757002 -0.0062816702 0.0364943, + 0.059445001 -0.00140683 0.035790499, + 0.035366699 -0.166833 -0.048214901, + 0.035366699 -0.164463 -0.0480549, + 0.027557701 -0.164764 -0.052881401, + 0.027557701 -0.167035 -0.053041399, + 0.0302257 -0.169264 -0.051668301, + 0.0328326 -0.169229 -0.050058398, + 0.030832 -0.17153899 -0.051335599, + 0.0282706 -0.17154001 -0.052785799, + 0.0328326 -0.166906 -0.049966201, + 0.0302257 -0.16697399 -0.051576, + 0.027557701 -0.169295 -0.053133901, + 0.0378174 -0.154661 -0.0448386, + 0.0378174 -0.152243 -0.044332098, + 0.035366699 -0.15255199 -0.046220802, + -0.051830001 -0.00633022 0.066300802, + -0.051830001 -0.00454885 0.066003703, + -0.044564299 -0.0060192998 0.0754731, + -0.0532961 -0.0090238899 0.064125501, + -0.0546159 -0.0100456 0.061677501, + -0.0546159 -0.00156349 0.059381001, + -0.055787299 -0.0029072801 0.056724299, + -0.0546159 -0.0032271901 0.0599925, + -0.055787299 -0.0061555901 0.057932701, + -0.0576833 0.0095539102 0.036909301, + -0.058412101 0.0063810698 0.035854999, + -0.0576833 0.0080983099 0.039326102, + -0.0532961 -0.0020506999 0.062600397, + -0.051830001 -0.00099882297 0.065171503, + -0.0599402 -0.032656301 0.0438825, + -0.058412101 -0.024589701 0.052868001, + -0.058412101 -0.021405799 0.0527367, + -0.058412101 -0.034504201 0.052218899, + -0.0576833 -0.035333801 0.054310501, + -0.058412101 -0.037845898 0.051784799, + -0.058412101 -0.027825801 0.052764799, + -0.058412101 -0.031165 0.052543499, + -0.0576833 -0.031917501 0.054695901, + -0.056809202 -0.0258493 0.057390898, + -0.0576833 -0.025095301 0.055135801, + -0.056809202 -0.029334299 0.0571694, + -0.055787299 -0.026764899 0.059629802, + -0.0576833 -0.028505201 0.054968901, + -0.055787299 -0.0232074 0.059799898, + -0.059999999 -0.0144361 0.035493098, + -0.059999999 -0.0124746 0.0339614, + -0.059999999 -0.016592501 0.036912698, + -0.059999999 -0.00662508 0.027305299, + -0.059999999 -0.00108828 0.016942, + -0.059999999 -0.151343 0.00136076, + -0.059999999 -0.0240636 0.040219799, + -0.0599402 -0.0267756 0.0434299, + -0.0599402 -0.023899799 0.042851999, + -0.059757002 -0.0238958 0.045455299, + -0.059757002 -0.026879599 0.045878202, + -0.0599402 -0.0297036 0.0437732, + -0.059999999 -0.0296332 0.041420098, + -0.059999999 -0.026808999 0.040929701, + -0.056809202 0.0075771199 0.0454101, + -0.056809202 0.0053197402 0.0476849, + -0.0576833 0.0021468401 0.046125099, + -0.056809202 0.00281437 0.049787998, + -0.056809202 8.4463885e-005 0.051683001, + -0.058998398 -0.00198701 0.0411015, + -0.059445001 -0.00317744 0.037774999, + -0.059445001 -0.00143604 0.0357912, + -0.056809202 -0.0059164301 0.054735702, + -0.058412101 -0.018214099 0.0523379, + -0.0465803 -0.15860599 -0.036847699, + -0.0465803 -0.161203 -0.037144799, + -0.048467699 -0.158353 -0.0343954, + -0.048467699 -0.155705 -0.034030002, + -0.0465803 -0.15600701 -0.036482699, + -0.044564299 -0.158848 -0.039206099, + -0.044564299 -0.16139799 -0.0395029, + -0.0248404 -0.158077 -0.053297199, + -0.0302257 -0.15542001 -0.050075799, + -0.027557701 -0.157915 -0.051975898, + -0.0328326 -0.157535 -0.0488961, + -0.035366699 -0.15731899 -0.047142401, + -0.035366699 -0.154938 -0.0467095, + -0.0328326 -0.15518899 -0.0484634, + -0.0328326 -0.15988301 -0.049259599, + -0.0302257 -0.15773401 -0.050508201, + -0.0302257 -0.16236199 -0.0511669, + -0.027557701 -0.160199 -0.052339099, + -0.0302257 -0.16004901 -0.050871599, + -0.048460599 0.0353733 0.0124718, + -0.048467699 0.035318501 0.0145064, + -0.048204001 0.035737801 0.0124715, + -0.048901699 0.034772899 0.0074723102, + -0.046393901 0.038058899 0.0124697, + -0.058998398 0.0079693701 0.023457199, + -0.058998398 0.0063338899 0.028205, + -0.059445001 0.0067743598 0.0184636, + -0.0576833 0.0124521 0.029557901, + -0.058412101 0.013277 0.0160043, + -0.058412101 0.0136123 0.0142883, + -0.056496199 0.0202149 0.0124839, + -0.0546159 0.0062527298 0.055233501, + -0.0546159 0.0076791602 0.054202899, + -0.055787299 0.0072418302 0.0503718, + -0.044564299 0.027703799 0.060856801, + -0.055437401 0.0229614 0.0124817, + -0.054245099 0.0256526 0.0124796, + -0.0546159 0.0248453 0.0134314, + -0.054979 0.0240348 0.0074808602, + -0.052922402 0.0282821 0.0124775, + -0.051472198 0.0308435 0.0124754, + -0.0498982 0.033330798 0.0124735, + -0.0522171 0.029560501 0.0074764602, + -0.051830001 0.0301654 0.0144546, + -0.051830001 0.030232901 0.013457, + -0.0532961 0.027563799 0.0134444, + -0.050219599 0.0327783 0.0144809, + -0.050219599 0.032579601 0.0164386, + -0.0576833 0.0153652 0.018980701, + -0.056809202 0.0148091 0.032841101, + -0.055787299 0.022089399 0.0134184, + -0.028376499 -0.19154 -0.0527131, + -0.032825101 -0.171538 -0.050071299, + -0.033477101 -0.171538 -0.049655799, + -0.031060301 -0.20853899 -0.051168699, + -0.029552899 -0.19154 -0.052064601, + -0.0061689499 -0.171546 -0.059542999, + -0.0081428103 -0.16942599 -0.059276499, + -0.0060668602 -0.171546 -0.059555899, + -0.0089870598 -0.171546 -0.0591865, + -0.0079039196 -0.208546 -0.059311099, + -0.0137106 -0.15418801 -0.0561646, + -0.0175901 -0.171544 -0.057227101, + -0.0248404 -0.160335 -0.0536603, + -0.0248404 -0.16259199 -0.053955398, + -0.027557701 -0.16248301 -0.052634299, + -0.019305199 -0.15834799 -0.0554934, + -0.0109179 -0.167272 -0.058733001, + -0.0109179 -0.15644801 -0.057254199, + -0.0053973799 -0.15871 -0.058447, + -0.0081428103 -0.158672 -0.058134001, + -0.0053973799 -0.160864 -0.058809999, + -0.00268824 -0.158733 -0.058630999, + -0.0053973799 -0.15655699 -0.058014899, + -0.0081428103 -0.15651201 -0.057701901, + -0.00268824 -0.16088299 -0.058994099, + -0.056809202 -0.165609 -0.0190244, + -0.056661699 -0.171514 -0.0195734, + -0.056543902 -0.171514 -0.0199329, + -0.057460099 -0.17151199 -0.0171357, + -0.0576833 -0.165492 -0.0162287, + -0.056809202 -0.15967201 -0.018624101, + -0.055787299 -0.16572601 -0.021805299, + -0.0576833 -0.15944199 -0.0158277, + -0.0465803 -0.166384 -0.0375407, + -0.048467699 -0.166281 -0.035089299, + -0.0465803 -0.168962 -0.037642099, + -0.0465803 -0.16379701 -0.037375402, + -0.048467699 -0.163644 -0.034923699, + -0.051434901 -0.171523 -0.0307485, + -0.050734501 -0.191524 -0.0318789, + -0.049977001 -0.171525 -0.033064399, + -0.051545098 -0.171523 -0.0305734, + -0.050219599 -0.16617499 -0.0325545, + -0.0424264 0.0021830699 0.076870397, + -0.035366699 -0.0066547301 0.083145797, + -0.0378174 -0.0083485702 0.081442602, + -0.0424264 -0.0120764 0.0776942, + -0.0248404 -0.0100626 0.088774703, + -0.027557701 -0.0089570703 0.087591201, + -0.027557701 -0.0111742 0.087542303, + -0.0248404 -0.0055935201 0.088813297, + -0.0248404 -0.0145361 0.088577703, + -0.0220857 -0.0135825 0.089687802, + -0.0302257 -0.0299253 0.084300801, + -0.0302257 -0.0255704 0.085000299, + -0.040608101 -0.208463 0.044335902, + -0.0424264 -0.032683499 0.075861797, + -0.0378174 0.027153799 0.071881503, + -0.040174201 0.024936801 0.070510902, + -0.040174201 0.0266157 0.069238402, + -0.0378174 0.025403401 0.0731069, + -0.0378174 0.0236036 0.074244797, + -0.035366699 0.0274632 0.074424297, + -0.0081421202 0.0031976099 0.093053699, + -0.0109179 0.0027966499 0.092650302, + -0.0220857 -0.0090759303 0.089868598, + -0.0220857 -0.0045742001 0.089889601, + -0.019305199 -0.0082152104 0.090822898, + -0.0053918599 -0.019574501 0.092704304, + -0.0109179 -0.024713 0.091340601, + -0.0081421202 -0.0243882 0.091779299, + -0.00267513 0.021573599 0.091078803, + 1.0015389e-011 0.02373 0.090579599, + 1.1452618e-011 0.021633301 0.091128401, + -0.0053918599 0.029787101 0.088126302, + -0.00267513 0.027887501 0.089125402, + -0.019305199 0.0225855 0.087361902, + 2.3823766e-012 -0.0193907 0.092940703, + 0.00267513 -0.0148243 0.0933358, + 0.00267513 -0.0194361 0.092882603, + -2.1082118e-012 -0.0147773 0.093393102, + -6.0866698e-012 -0.023984799 0.092324503, + -0.00267513 -0.019436 0.092882402, + -0.00267513 -0.0148243 0.093335502, + -0.0302257 -0.0124091 0.0861734, + -0.0378174 -0.033742599 0.079145499, + 0.0053918599 0.0597676 0.042320501, + 0.0053918599 0.059724499 0.044451602, + 0.0081421202 0.059423499 0.042238101, + 0.0081421202 0.059426799 0.039945599, + 0.0053918599 0.059768301 0.040021099, + 0.00267513 0.059969399 0.042369001, + 0.0081421202 0.059437301 0.0307822, + 0.00267513 0.059927698 0.044503599, + 0.0058307201 0.059727501 0.0124524, + 0.0081421202 0.058229499 0.053075999, + 0.0081421202 0.058668301 0.050877299, + 0.0081421202 0.0576864 0.055273399, + 0.0109179 0.057723898 0.052907702, + 0.0109179 0.058164701 0.050719202, + 0.0109179 0.057179399 0.055094901, + 0.0165099 0.056681201 0.0502537, + 0.0137106 0.057503499 0.050511599, + 0.0165099 0.057027198 0.048099101, + 0.0137106 0.057060201 0.052686799, + 0.019305199 0.054036301 0.056350999, + 0.0220857 0.052872501 0.055919301, + 0.0220857 0.053531501 0.053811599, + 0.0165099 0.056234699 0.052412, + 0.019305199 0.055244699 0.052082699, + 0.019305199 0.054692499 0.054219998, + 0.0165099 0.054271001 0.058859698, + 0.019305199 0.0532743 0.058470398, + 0.00267513 0.050071999 0.072318599, + 0.019305199 0.045072202 0.072327897, + 0.0165099 0.044501401 0.074620903, + 0.019305199 0.0435226 0.074078299, + 0.0220857 0.043921899 0.071714498, + 0.0220857 0.045379698 0.069914304, + 0.019305199 0.046534698 0.0705062, + 0.0220857 0.046746999 0.068049803, + 0.0302257 -0.014607 0.086081401, + 0.0328326 -0.0159408 0.084566899, + 0.027557701 -0.0156109 0.0873321, + 0.0248404 -0.016772401 0.088423401, + 0.0220857 -0.018086201 0.089349501, + 0.0220857 -0.022577699 0.088847801, + 0.0302257 -0.025571199 0.085002601, + 0.0248404 -0.0279007 0.087038301, + 0.0220857 -0.0270488 0.088188604, + 0.027557701 -0.028860399 0.085742503, + 0.0227904 -0.208454 0.055669099, + 0.0220857 0.0132269 0.088410802, + 0.0220857 0.0088302502 0.089009903, + 0.0248404 0.00771796 0.087995403, + 0.0302257 0.0050724898 0.085582599, + 0.0302257 0.0072271102 0.085338399, + 0.027557701 0.00646473 0.086852401, + 0.027557701 0.0042803399 0.087074503, + 0.0302257 0.00290695 0.085791104, + 0.0328326 0.0035431201 0.084187701, + 0.0328326 0.0056771799 0.083958901, + 0.0165099 0.0061395098 0.091139197, + 0.0165099 0.0106303 0.090651698, + 0.0137106 0.0068126 0.091783702, + 0.019305199 0.0098004397 0.089894801, + 0.0137106 0.0022722499 0.092125498, + 1.1788163e-012 0.050138898 0.072352901, + -0.00267513 0.051454201 0.070364296, + -0.0053918599 0.049862798 0.072211303, + 0.0137106 0.0468762 0.073289998, + 0.0137106 0.045317698 0.075073197, + 0.0165099 0.046055902 0.072852597, + -0.0220857 0.040743802 0.075088203, + -0.0137106 0.046869598 0.073285803, + -0.0137106 0.048339602 0.071430802, + -0.0109179 0.047530401 0.073638402, + -0.0081421202 0.048034199 0.0739071, + 0.0109179 0.0350908 0.084391601, + 0.0081421202 0.0355695 0.084717698, + 0.0137106 0.0364164 0.082718201, + 0.00267513 0.038068201 0.083808199, + 0.0053918599 0.035903901 0.084945403, + 0.00267513 0.036100101 0.085078798, + 0.0109179 0.045974001 0.075437002, + 0.0109179 0.0443292 0.077153899, + 0.0137106 0.0436766 0.076778501, + 0.00267513 0.039987601 0.082437903, + 0.0053918599 0.0378704 0.083678, + 0.0220857 0.039055198 0.076667704, + 0.019305199 0.040185899 0.077342398, + 0.019305199 0.038411401 0.078845903, + 0.0220857 0.0407537 0.0750966, + 0.0248404 0.0377586 0.075894199, + 0.0248404 0.039448999 0.074345797, + 0.0248404 0.034182299 0.078728102, + 0.0220857 0.037288301 0.078152001, + 0.0248404 0.036001001 0.077356599, + 0.019305199 0.036574401 0.0802572, + 0.0220857 0.033577099 0.080843203, + 0.0220857 0.035459898 0.079544798, + 0.0165099 0.0336807 0.083430603, + 0.0165099 0.031693399 0.084562801, + 0.019305199 0.032743301 0.082791701, + 0.019305199 0.034682602 0.081573203, + 0.0165099 0.035628099 0.082197599, + 0.0137106 0.034462299 0.083963297, + 0.0137106 0.032467902 0.085107103, + 0.0165099 0.0213909 0.088692702, + 0.0137106 0.022126799 0.089286603, + 0.0165099 0.023478299 0.088068701, + 0.019305199 0.022586299 0.087366901, + 0.019305199 0.0205085 0.0879803, + 0.0137106 0.017970299 0.090253398, + 0.0137106 0.020047501 0.0898173, + 0.0165099 0.019319501 0.0892151, + 0.0137106 0.0157857 0.090633102, + 0.0109179 0.0185491 0.090743899, + 0.0109179 0.0163571 0.091129303, + 0.044564299 -0.022227 0.075301498, + 0.044564299 -0.0262929 0.074901298, + 0.0465803 -0.0242121 0.073101699, + 0.0465803 -0.020208299 0.073395804, + 0.044564299 -0.0181577 0.075560004, + 0.0424264 -0.0203299 0.077403702, + 0.0424264 -0.0244595 0.077035002, + 0.0465803 -0.0082365898 0.073444702, + 0.044564299 -0.0140918 0.075676598, + 0.0546159 -0.024203099 0.062085599, + 0.055787299 -0.0267483 0.059648301, + 0.0546159 -0.027851 0.061844502, + 0.0546159 -0.0205639 0.0622028, + 0.0532961 -0.021692401 0.064489603, + 0.055787299 -0.023180701 0.059816401, + 0.0532961 -0.025412699 0.064295799, + 0.058412101 0.00493709 0.0381428, + 0.058998398 0.00175509 0.0369629, + 0.058412101 0.0032094701 0.040387701, + 0.056809202 0.0113116 0.0405064, + 0.0576833 0.0081266603 0.039325401, + 0.0599402 -0.0238805 0.0428808, + 0.0599402 -0.021084299 0.042073298, + 0.059757002 -0.023881501 0.045483001, + 0.059757002 -0.020948701 0.0448181, + 0.051830001 -0.0063308901 0.066311501, + 0.051830001 -0.00454664 0.066017203, + 0.050219599 -0.00549642 0.068680197, + -0.044564299 0.038179599 0.037128098, + -0.044564299 0.0373444 0.042298801, + -0.0465803 0.034696098 0.041518301, + -0.0378174 0.038681898 0.059422299, + -0.035366699 0.0418997 0.058543701, + -0.0378174 0.039744802 0.057616599, + -0.040174201 0.0374429 0.056626301, + -0.0424264 0.035969902 0.053831998, + -0.040174201 0.036382601 0.058386501, + -0.0424264 0.025851401 0.066514999, + -0.040174201 0.0297863 0.066460103, + -0.0424264 0.027389999 0.065131404, + -0.040174201 0.0282341 0.067886598, + -0.040174201 0.0312667 0.064963497, + -0.0424264 0.028858401 0.063678898, + -0.0424264 0.0302517 0.062162299, + -0.040174201 0.0326703 0.063401602, + -0.044564299 0.026321299 0.062325701, + -0.044564299 0.0248654 0.0637317, + -0.0378174 0.032046098 0.067713097, + -0.0378174 0.0375266 0.061187599, + -0.0378174 0.033537898 0.066174902, + -0.0328326 0.0416697 0.063138701, + -0.035366699 0.039675198 0.062199399, + -0.035366699 0.040834598 0.060392, + -0.0220857 0.0423677 0.073436201, + -0.0248404 0.041054301 0.072707899, + -0.0302257 0.040890701 0.0676139, + -0.0328326 0.0404137 0.064936899, + -0.0302257 0.042242199 0.065835901, + -0.027557701 0.041104201 0.070210598, + 0.0109179 0.031057499 0.086594, + 0.0053918599 0.0297879 0.088128299, + 0.00267513 0.029978599 0.088270202, + 0.0053918599 0.031855699 0.087171502, + 0.0081421202 0.029462799 0.087886401, + 0.0053918599 0.027698999 0.088982001, + 0.00267513 0.027887801 0.089126296, + 0.0081421202 0.0315274 0.086934, + -0.0081421202 0.031525798 0.086930498, + -0.0053918599 0.033895198 0.086107999, + -0.00267513 0.034090199 0.086245701, + -0.0053918599 0.0359024 0.084942803, + -0.0081421202 0.0335632 0.085874103, + -0.0053918599 0.0318547 0.0871692, + -0.00267513 0.032047801 0.087309398, + -0.00267513 0.045375701 0.077755399, + -0.00267513 0.0436479 0.079406902, + -0.0053918599 0.046820302 0.075905502, + -0.00267513 0.047026198 0.076019801, + 3.2828241e-012 0.045442998 0.077794299, + -1.4764802e-012 0.043714799 0.079447001, + -0.0081421202 0.046470001 0.075711198, + -0.0053918599 0.045171 0.077637501, + -0.0109179 0.045968801 0.075433202, + -0.019305199 0.0401778 0.077334397, + -0.019305199 0.038403701 0.078837298, + -0.0109179 0.040812299 0.080326997, + -0.0081421202 0.0394454 0.082089797, + 0.035366699 0.0180225 0.079362102, + 0.0378174 0.016055301 0.077895999, + 0.040174201 0.015863599 0.0755914, + 0.0328326 0.0013983099 0.0843812, + 0.0302257 0.00073288498 0.0859624, + 0.0302257 -0.00144755 0.086095497, + 0.035366699 -0.0045093298 0.083091699, + 0.0328326 -0.00075479102 0.084537998, + 0.0328326 -0.0029140001 0.084656797, + 0.035366699 -0.0109418 0.083175503, + 0.0378174 8.6688699e-005 0.081035502, + 0.035366699 -0.000242985 0.082847401, + 0.035366699 -0.00237328 0.082988299, + 0.0378174 -0.0041169501 0.081318699, + 0.0378174 -0.00201123 0.0811949, + 0.0576833 -0.031900201 0.054715101, + 0.056809202 -0.0293175 0.057188299, + 0.056809202 -0.025822099 0.057407599, + 0.058412101 -0.0278074 0.052776899, + 0.058412101 -0.0245915 0.052877702, + 0.058998398 -0.0273802 0.050569698, + 0.058998398 -0.0305312 0.050411601, + 0.058412101 -0.031137099 0.052560698, + 0.0576833 -0.0284776 0.054985899, + 0.0576833 -0.025077101 0.055147801, + 0.058998398 -0.024253899 0.0505086, + 0.059445001 -0.024009099 0.048033901, + 0.059445001 -0.020963199 0.047535501, + 0.058412101 -0.0214034 0.052751899, + 0.058998398 -0.0211164 0.050190099, + 0.0220857 0.0548978 0.047471501, + 0.0220857 0.055156399 0.045373701, + 0.019305199 0.056045499 0.047809798, + 0.019305199 0.055695001 0.0499443, + 0.0220857 0.054542001 0.049582701, + 0.0248404 0.053582001 0.047083601, + 0.0248404 0.0538477 0.0450125, + -0.0081421202 0.059002601 0.048681501, + -0.0081421202 0.0592403 0.0464979, + -0.0109179 0.058500402 0.048533499, + -0.0109179 0.058741 0.046359599, + -0.0248404 0.053574 0.047081798, + -0.0248404 0.053210001 0.049169902, + -0.035366699 0.0428693 0.056661699, + -0.0328326 0.044870201 0.057482202, + -0.0424264 0.038929999 0.0466692, + -0.044564299 0.036902498 0.044060901, + -0.0378174 0.0423669 0.0520299, + -0.035366699 0.0437424 0.054753698, + -0.040174201 0.040757399 0.0493301, + -0.040748298 0.044036102 0.0124649, + -0.042443302 0.042420998 0.0124662, + -0.040756401 0.044040602 0.0074649299, + -0.027557701 0.051252499 0.050762199, + -0.019305199 0.055236001 0.0520848, + -0.0220857 0.054533001 0.049584299, + -0.0165099 0.057271 0.045952801, + -0.0137106 0.058085699 0.0461783, + -0.0165099 0.057421099 0.043852702, + -0.0137106 0.0578412 0.0483394, + -0.0165099 0.056674499 0.0502549, + -0.019305199 0.0556872 0.049945801, + -0.0165099 0.0570218 0.048097901, + -0.0137106 0.0574979 0.050512701, + -0.019305199 0.056294002 0.045682501, + -0.019305199 0.0560393 0.047808301, + -0.0220857 0.054890599 0.047469798, + -0.019305199 0.056450501 0.043601599, + -0.019305199 0.056517798 0.041537698, + -0.0220857 0.0554251 0.039060701, + -0.040174201 -0.166667 -0.044289801, + -0.0378174 -0.169149 -0.0464065, + -0.038590301 -0.191535 -0.045790799, + 0.0328326 0.047204301 0.051586799, + 0.0328326 0.0477795 0.049600199, + 0.027557701 0.050035302 0.054866798, + 0.0248404 0.0515384 0.0554244, + 0.0302257 0.048365399 0.054247402, + 0.0302257 0.049034499 0.052230299, + 0.027557701 0.051265001 0.0507592, + 0.0248404 0.052760102 0.051256299, + 0.0248404 0.052200399 0.0533434, + 0.027557701 0.050700601 0.0528161, + 0.027557701 0.0517307 0.048700999, + 0.0302257 0.049604099 0.050206799, + 0.0302257 0.050076202 0.0481821, + 0.0248404 0.047860499 0.063554801, + 0.0248404 0.049904201 0.059543598, + 0.027557701 0.048397999 0.058925599, + 0.0248404 0.0489331 0.061566699, + 0.0220857 0.051240999 0.060092099, + 0.0248404 0.050772998 0.057493601, + 0.027557701 0.049267702 0.056905702, + 0.0220857 0.050269499 0.062141798, + 0.044564299 0.0357867 0.047573, + 0.0328326 0.045758501 0.055535499, + 0.0328326 0.044886898 0.057484999, + 0.0546159 0.0239226 0.0195003, + 0.055787299 0.0217661 0.016208, + 0.0546159 0.0245462 0.0162702, + 0.0546159 0.021565899 0.0315735, + 0.0532961 0.023976499 0.035228699, + 0.056128498 0.021171 0.0124831, + 0.055787299 0.0220215 0.0143751, + 0.056464098 0.020304499 0.0124838, + 0.055400901 0.023049301 0.0124817, + 0.056143001 0.0211727 0.0074831401, + 0.050219599 0.0120562 0.062557802, + 0.048467699 0.0131838 0.065303102, + 0.048467699 0.0114822 0.066246703, + 0.048467699 0.016450999 0.0631788, + 0.048467699 0.0209294 0.059452001, + 0.0465803 0.023689101 0.060924001, + 0.044564299 0.0248864 0.063747004, + 0.051830001 0.0251236 0.042068999, + 0.0465803 0.031610101 0.0500114, + 0.0465803 0.033107799 0.046631299, + 0.048467699 0.0303222 0.0456522, + 0.0465803 0.033726599 0.044928499, + 0.044564299 0.036397099 0.045816202, + 0.048467699 0.031957898 0.0407103, + 0.0465803 0.034711201 0.041521799, + 0.048467699 0.032341801 0.039074302, + 0.0465803 0.0342604 0.043223601, + 0.050219599 0.029510399 0.038292199, + 0.050219599 0.028633701 0.041459799, + 0.048467699 0.0314942 0.042356499, + 0.050219599 0.0291108 0.0398711, + 0.050219599 0.0280778 0.0430509, + 0.051830001 0.025691099 0.040537398, + 0.048467699 0.030949401 0.044005401, + 0.051830001 0.026182 0.039007999, + 0.0378174 0.0450962 0.040679801, + 0.0220857 -0.169348 -0.055624198, + 0.0220857 -0.16713899 -0.055531099, + 0.018242201 -0.171544 -0.057007201, + 0.0202034 -0.171543 -0.0563596, + 0.0182469 -0.191544 -0.057005599, + 0.019305199 -0.16937 -0.056645501, + 0.017408401 -0.171544 -0.0572825, + 0.019305199 -0.162774 -0.0561646, + 0.0165099 -0.162846 -0.057037901, + 0.0137106 -0.16508199 -0.057993598, + 0.0122731 -0.19154499 -0.0585788, + 0.0053973799 -0.163018 -0.059108499, + 0.0053973799 -0.16516501 -0.059335802, + 0.00268824 -0.16303299 -0.0592907, + 0.00268824 -0.165177 -0.059518099, + 0.0109179 -0.162955 -0.058351502, + 0.0109179 -0.16511799 -0.058578901, + 0.0137106 -0.16290601 -0.057766099, + 0.0137106 -0.160726 -0.057470702, + 0.0109179 -0.160787 -0.058056299, + 0.0081428103 -0.162991 -0.058797199, + 0.0081428103 -0.16514499 -0.059024598, + 0.0053973799 -0.152265 -0.056941401, + 0.00268824 -0.15443601 -0.0576974, + 0.0165099 -0.15188099 -0.054867301, + -0.00268824 -0.167312 -0.059677299, + -0.0053973799 -0.16730399 -0.0594933, + -0.0053973799 -0.169432 -0.059589099, + -0.00268824 -0.165176 -0.0595163, + -0.0053973799 -0.16516501 -0.059332199, + -7.1890796e-012 -0.16518 -0.059576999, + 0.0026880901 -0.171546 -0.059797499, + 0.0013432 -0.19154599 -0.059832498, + -5.3542106e-012 -0.19154599 -0.0598475, + -5.2780297e-012 -0.16943701 -0.059833001, + -0.00268824 -0.16943599 -0.0597727, + -0.000344617 -0.171546 -0.059862401, + 1.3787488e-012 -0.16731501 -0.059737802, + -5.7524111e-012 -0.171546 -0.0598634, + 0.00268824 -0.16943599 -0.059773698, + 0.00268824 -0.167312 -0.0596788, + 0.0566587 -0.171514 -0.0195724, + 0.0570965 -0.191513 -0.0182865, + 0.056480099 -0.171514 -0.020111799, + 0.0574052 -0.17151199 -0.0173175, + 0.056809202 -0.16561399 -0.0190567, + 0.058412101 0.0124954 0.018812699, + 0.058998398 0.0104954 0.015955299, + 0.058412101 0.0093888799 0.028880799, + 0.058412101 0.013314 0.016018501, + 0.0576833 0.0117106 0.032061901, + 0.0576833 0.0124516 0.0295581, + 0.059757002 0.0052962699 0.0142073, + 0.0599402 0.0025810599 0.0141799, + 0.059923101 0.0030489999 0.0124976, + 0.059445001 0.0080478098 0.0142349, + 0.059702002 0.0059841401 0.0124952, + 0.0599204 0.0030962699 0.0074975402, + 0.059445001 0.0079036197 0.0150853, + 0.0599402 0.00117841 0.018131699, + 0.059757002 -0.0006273 0.0288761, + 0.0599402 0.0024204601 0.0149987, + 0.059757002 0.0051438198 0.0150417, + 0.059445001 0.00769467 0.0158925, + 0.0328326 -0.16223 -0.049577899, + 0.035366699 -0.162085 -0.047826499, + 0.035366699 -0.159701 -0.047529198, + 0.0328326 -0.164572 -0.049806301, + 0.0302257 -0.16236199 -0.051187899, + 0.0302257 -0.164672 -0.051415998, + 0.0328326 -0.15753201 -0.048914999, + 0.0328326 -0.15988199 -0.049281001, + 0.035366699 -0.157316 -0.0471627, + 0.035366699 -0.15493301 -0.0467267, + 0.0328326 -0.155184 -0.048479401, + 0.0302257 -0.157731 -0.050525598, + 0.0302257 -0.16004799 -0.050891299, + -0.0378174 0.021761701 0.075293101, + -0.048467699 -0.0067017102 0.071107998, + -0.050219599 -0.0091736903 0.0689613, + -0.048467699 -0.0105876 0.071307503, + -0.0465803 -0.0082588801 0.073431, + -0.050219599 -0.0054949098 0.068671897, + -0.0546159 -0.0134757 0.062066499, + -0.0546159 -0.0117673 0.0619101, + -0.0532961 -0.0107623 0.064312197, + -0.0532961 -0.0143192 0.064493299, + -0.0546159 -0.016969699 0.062191699, + -0.0546159 -0.0066124802 0.060986601, + -0.0546159 -0.0049116998 0.0605276, + -0.0532961 -0.0037799799 0.063098103, + -0.0546159 -0.0083252396 0.061369698, + -0.0532961 -0.0055219298 0.063518003, + -0.0465803 0.0069149402 0.071071297, + -0.0465803 0.0087518198 0.070427001, + -0.0532961 -0.00033854501 0.062024198, + -0.050219599 0.0035032299 0.066624202, + -0.048467699 0.00617145 0.068557397, + -0.050219599 0.0017186099 0.0671973, + -0.051830001 0.00075841398 0.064635597, + -0.048467699 0.0043602898 0.069166698, + -0.056809202 -0.0123823 0.056685299, + -0.056809202 -0.0091113402 0.055853799, + -0.0576833 -0.0120829 0.053763699, + -0.0576833 -0.0152961 0.054513201, + -0.055787299 -0.0094839903 0.0588459, + -0.055787299 -0.0128574 0.0594646, + -0.056809202 -0.019003 0.057491701, + -0.0576833 -0.0185485 0.054985501, + -0.056809202 -0.0156953 0.057230901, + -0.0576833 -0.021794399 0.0551816, + -0.056809202 -0.0223688 0.057503399, + -0.055787299 -0.0162265 0.059789699, + -0.055787299 -0.0196566 0.059858501, + -0.0599402 -0.018432301 0.0410248, + -0.0599402 -0.021107901 0.0420467, + -0.059999999 -0.021427801 0.039300699, + -0.059999999 -0.0189292 0.038191002, + -0.059445001 -0.0209774 0.047507901, + -0.059757002 -0.020967901 0.0447894, + -0.059757002 -0.018129401 0.043887999, + -0.058412101 0.00317978 0.040382698, + -0.0576833 0.0043896101 0.043974102, + -0.0576833 0.0063760998 0.041693699, + -0.058412101 0.00119748 0.042536099, + -0.058412101 0.0049084001 0.0381434, + -0.058998398 -8.9189161e-006 0.0390747, + -0.058998398 0.0017261 0.0369635, + -0.056809202 0.0095678195 0.0430029, + -0.056809202 0.0112837 0.040507, + -0.055787299 0.0107478 0.0468385, + -0.055787299 0.0084758298 0.049236398, + -0.058998398 -0.0149936 0.048737399, + -0.058412101 -0.0150587 0.0516707, + -0.058998398 -0.018027401 0.049582802, + -0.059445001 -0.017996799 0.046752799, + -0.059445001 -0.0151108 0.045753799, + -0.058412101 -0.0089890799 0.049538098, + -0.058998398 -0.0120597 0.047639899, + -0.058412101 -0.0119712 0.050734501, + -0.0576833 -0.00591115 0.051440701, + -0.058998398 -0.0092619602 0.046303201, + -0.0576833 -0.0089416504 0.052736599, + -0.044562198 0.040183902 0.012468, + -0.044472098 0.0402884 0.0124679, + -0.044564299 0.040137202 0.0145548, + -0.045056298 0.039610699 0.0124685, + -0.045067899 0.0396166 0.0074684601, + -0.058998398 0.0096236104 0.0186351, + -0.058412101 0.0085974801 0.031236701, + -0.057419099 0.017419901 0.0124861, + -0.057158101 0.0182545 0.0074854698, + -0.0576833 0.016511099 0.0133922, + -0.0576833 0.016418001 0.0143165, + -0.056809202 0.019307701 0.0134053, + -0.0465803 0.0250376 0.059490599, + -0.050219599 0.032124501 0.0199896, + -0.056809202 0.018235199 0.0191535, + -0.056809202 0.0155105 0.030234201, + -0.055787299 0.018552501 0.0309068, + -0.0576833 0.0161027 0.0160679, + -0.056809202 0.0138944 0.035387602, + -0.056809202 0.0127221 0.037962001, + -0.055787299 0.0178963 0.0336386, + -0.051830001 0.0294479 0.0198285, + -0.0532961 0.027491201 0.0144277, + -0.0546159 0.0247676 0.0144004, + -0.051830001 0.029947899 0.016379301, + -0.0240272 -0.191542 -0.054826502, + -0.0109179 -0.152126 -0.056178801, + -0.0109179 -0.154284 -0.056752, + -0.0137106 -0.15201899 -0.055591401, + -0.0308876 0.051446401 0.0074590398, + -0.036012899 0.047997899 0.0074617802, + -0.0254349 0.054349601 0.0074567199, + -0.0081428103 -0.152209 -0.056626402, + -0.0081428103 -0.154357 -0.057199501, + -0.020382199 -0.171543 -0.056295399, + -0.0258127 -0.17154101 -0.054027099, + -0.0248338 -0.171542 -0.0544645, + -0.0240207 -0.171542 -0.054827798, + -0.0231252 -0.171542 -0.055227902, + -0.027557701 -0.167033 -0.0530257, + -0.027557701 -0.16476201 -0.052862801, + -0.0248404 -0.169322 -0.054444499, + -0.0137106 -0.158545 -0.057099, + -0.0165099 -0.158455 -0.056368802, + -0.0109179 -0.160787 -0.058049198, + -0.0137106 -0.169403 -0.058242701, + -0.0137106 -0.167248 -0.058145899, + -0.0147556 -0.171545 -0.0580207, + -0.0137069 -0.171545 -0.058259599, + -0.0122713 -0.171545 -0.058586601, + -0.0118856 -0.171545 -0.058674399, + -0.0109179 -0.169416 -0.058829401, + -0.035366699 0.00186236 0.082659803, + -0.0424264 0.0040851999 0.076601297, + -0.044564299 0.0074941101 0.073493101, + -0.044564299 0.0093716597 0.072902903, + -0.035366699 -0.0045165699 0.0830798, + -0.035366699 -0.00238379 0.082976498, + -0.035366699 -0.00025724599 0.082836099, + -0.0302257 -0.00582546 0.086236298, + -0.0328326 -0.0050824601 0.084726803, + -0.0328326 0.0035274201 0.084178001, + -0.0328326 -0.022458401 0.0840002, + -0.050219599 -0.020686001 0.069037601, + -0.051830001 -0.026815699 0.066408902, + -0.051830001 -0.0230255 0.066685498, + -0.044564299 -0.034387201 0.073673099, + -0.050219599 -0.024547501 0.0688034, + -0.048467699 -0.038023699 0.069001399, + -0.0465803 -0.036169901 0.071382903, + -0.050219599 -0.032268502 0.067937098, + -0.050219599 -0.0284106 0.0684366, + -0.050219599 -0.036114 0.067304499, + -0.051830001 -0.034390699 0.065467, + -0.048467699 -0.0341237 0.069737799, + -0.051830001 -0.030606501 0.066002898, + -0.040174201 -0.0310665 0.077939399, + -0.0302257 0.0329272 0.075451002, + -0.0302257 0.034662601 0.074041799, + -0.035366699 0.023786901 0.076674797, + -0.035366699 0.025646601 0.075595103, + -0.0328326 0.0275429 0.076848499, + -0.0328326 0.029375101 0.075647302, + -0.0109179 -0.00178007 0.092840299, + -0.0137106 0.0022704201 0.092120998, + -0.0165099 -0.021143001 0.090688698, + -0.019305199 -0.017283199 0.090328202, + -0.019305199 -0.0127507 0.090656303, + -0.0081421202 -0.0198105 0.092400998, + -0.0081421202 0.0077637001 0.092693999, + -0.00267513 0.0127698 0.092604302, + -0.0053918599 0.0080525 0.092970498, + -0.00267513 0.0082221497 0.093133099, + -0.0053918599 0.0255946 0.089731596, + -0.0053918599 0.027698399 0.088980302, + -0.0053918599 0.0234848 0.090380996, + -0.00267513 0.0257816 0.0898792, + -0.00267513 0.023669699 0.090530701, + -0.0248404 0.022393599 0.084912904, + -0.0220857 0.025647899 0.085038602, + -0.0220857 0.023602299 0.085839301, + -0.019305199 0.024656599 0.0866476, + -0.019305199 0.028749701 0.084917799, + -0.019305199 0.0267132 0.085833199, + -0.0220857 0.0276735 0.084137902, + -0.0165099 0.029670199 0.085585102, + -0.0165099 0.0276246 0.086512797, + -0.0081421202 0.0252761 0.089480601, + -0.0302257 -0.0168039 0.085937798, + -0.0302257 -0.0211937 0.085546598, + -0.027557701 -0.0156104 0.0873271, + -0.0302257 -0.0146066 0.086075097, + -0.027557701 -0.0200423 0.086954497, + 0.0137106 0.055861399 0.0570282, + 0.0137106 0.0565136 0.054860599, + 0.0109179 0.056528602 0.057275899, + 0.0109179 0.0557702 0.059445299, + 0.0137106 0.055101998 0.059184201, + 0.0165099 0.055031601 0.056720302, + 0.0165099 0.055685598 0.0545693, + 0.0165099 0.053404301 0.060979798, + 0.019305199 0.051435299 0.062643498, + 0.019305199 0.0524069 0.060570501, + 0.0165099 0.052432202 0.063072599, + 0.0053918599 0.049865499 0.0722128, + 0.0053918599 0.048388898 0.074096598, + 0.0053918599 0.052533802 0.068254299, + 0.0053918599 0.051248498 0.070262901, + 0.00267513 0.051455598 0.0703649, + 0.0165099 0.047522798 0.0710124, + 0.019305199 0.049182501 0.066675603, + 0.019305199 0.047906101 0.068619698, + 0.0220857 0.0480203 0.066128097, + 0.0220857 0.049195498 0.064156301, + 0.019305199 0.050359901 0.064681098, + 0.0165099 0.048897501 0.0691071, + 0.0328326 -0.018115301 0.084417701, + 0.0328326 -0.0202884 0.084230199, + 0.0302257 -0.016804401 0.0859432, + 0.027557701 -0.0045274901 0.0875801, + 0.0302257 -0.0036331799 0.086189903, + 0.027557701 -0.0067407801 0.087608904, + 0.0248404 -0.0055925399 0.088820599, + 0.0248404 -0.00113365 0.088702403, + 0.027557701 -0.00011255399 0.087405197, + 0.027557701 -0.0023177599 0.087512203, + 0.0248404 -0.00336118 0.0887812, + 0.0220857 -0.002326 0.089847296, + 0.027557701 -0.0200429 0.086957902, + 0.0248404 -0.019006301 0.088225, + 0.0248404 -0.023463801 0.087709501, + 0.027557701 -0.024462201 0.0864271, + 0.027557701 -0.0178279 0.087164603, + 0.0302257 -0.0190005 0.085766204, + 0.0302257 -0.0211943 0.085550301, + 0.0302257 -0.023384901 0.0852957, + 0.0248404 0.0142218 0.0870772, + 0.027557701 0.0149385 0.085590199, + 0.027557701 0.016961601 0.085117102, + 0.0248404 0.0055165798 0.088229798, + 0.0220857 0.0066138399 0.089255303, + 0.019305199 0.0053322199 0.090366296, + 0.019305199 -0.00142298 0.0907773, + 0.0165099 0.00161838 0.091468297, + -0.0081421202 0.052175101 0.068085797, + -0.0109179 0.052848302 0.065803297, + -0.0053918599 0.052531101 0.068253301, + -0.0053918599 0.051245701 0.070261702, + 0.0081421202 0.057036899 0.0574646, + -0.0053918599 0.059353702 0.048785001, + 0.0053918599 0.0573918 0.057596501, + 0.0053918599 0.0580405 0.0553982, + 0.00267513 0.058789499 0.0532628, + 0.00267513 0.058248099 0.055471402, + 0.0053918599 0.0585826 0.0531937, + 0.0053918599 0.059020098 0.050987799, + -0.0137106 0.054228701 0.061319798, + -0.0137106 0.053256501 0.0634287, + -0.0165099 0.0562272 0.052413799, + 0.00267513 0.057599802 0.057673801, + -0.019305199 0.045062799 0.072322004, + -0.0165099 0.0460479 0.0728475, + -0.019305199 0.0418831 0.0757441, + -0.0165099 0.0411461 0.077912703, + -0.019305199 0.043513499 0.074071601, + -0.0109179 0.050383199 0.069837697, + -0.0109179 0.0490034 0.071770899, + -0.0137106 0.049717199 0.069510303, + -0.0109179 0.0516661 0.067846201, + -0.0081421202 0.0508908 0.070087299, + -0.0081421202 0.049509201 0.072030097, + 0.0053918599 0.046822801 0.075907402, + 0.0081421202 0.046473801 0.075714, + 0.00267513 0.045376901 0.077756397, + 0.019305199 0.0142231 0.089276001, + 0.0165099 0.017250599 0.089643702, + 0.0165099 0.0150753 0.090016, + 0.0465803 -0.0042963298 0.073193401, + 0.0465803 -0.00236549 0.073020197, + 0.044564299 -3.8332295e-005 0.074992299, + 0.0424264 -0.00385872 0.0774372, + 0.044564299 -0.0059980201 0.075486198, + 0.040174201 -0.00182812 0.079289101, + 0.0424264 0.00019842001 0.077096701, + 0.044564299 -0.0019980201 0.0751893, + 0.044564299 -0.0100355 0.075651497, + 0.059445001 -0.0051206201 0.039685, + 0.058998398 2.1084101e-005 0.0390797, + 0.059445001 -0.00314718 0.037780099, + 0.0576833 0.00640547 0.041698601, + 0.059757002 -0.018105701 0.0439144, + 0.048467699 -0.0011403901 0.070502304, + 0.050219599 -0.0018858199 0.068111099, + 0.048467699 0.00070072903 0.070146501, + 0.050219599 -0.0036989099 0.0684366, + 0.048467699 -0.00296582 0.070774503, + 0.0465803 0.00133389 0.072500102, + 0.0465803 -0.00051856402 0.072799601, + -0.0465803 0.035363302 0.038151, + -0.0465803 0.035070401 0.0398155, + -0.048467699 0.032880001 0.0358539, + -0.0465803 0.035581499 0.036503501, + -0.044564299 0.037980001 0.038827099, + -0.044564299 0.037703902 0.0405434, + -0.044564299 0.033397801 0.0527771, + -0.0424264 0.035002101 0.055576202, + -0.048467699 0.030927399 0.044010699, + -0.040174201 0.039287001 0.0530148, + -0.0378174 0.041588102 0.0539129, + -0.040174201 0.0400692 0.051178198, + -0.040174201 0.038411401 0.0548333, + -0.0424264 0.0368471 0.0520625, + -0.0378174 0.040713701 0.055777598, + -0.0424264 0.0242482 0.067825198, + -0.0465803 0.023666499 0.0609098, + -0.035366699 0.0309387 0.071818903, + -0.0378174 0.0304811 0.069180198, + -0.0378174 0.0288484 0.070571199, + -0.035366699 0.032584701 0.070391104, + -0.035366699 0.029229499 0.073164701, + -0.0328326 0.032878902 0.072977103, + -0.0328326 0.0311561 0.0743559, + -0.035366699 0.037086502 0.065664597, + -0.0378174 0.034951098 0.064570397, + -0.0378174 0.036281899 0.062905803, + -0.035366699 0.0384246 0.063959204, + -0.0328326 0.039068598 0.0666802, + -0.0248404 0.044043001 0.069229104, + -0.0220857 0.045368701 0.069908403, + -0.0220857 0.0439112 0.071707897, + -0.0248404 0.042591199 0.071003698, + -0.0248404 0.0454056 0.067390896, + -0.027557701 0.042549599 0.068463899, + -0.027557701 0.043906901 0.066654198, + -0.0302257 0.039452299 0.0693295, + -0.027557701 0.039574601 0.071887501, + -0.0328326 0.036125701 0.069975197, + -0.035366699 0.035664201 0.067309, + -0.035366699 0.034161899 0.068886198, + -0.0328326 0.037637901 0.068361796, + -0.0328326 0.034537401 0.071515203, + -0.0302257 0.037930999 0.070976101, + -0.0302257 0.036332499 0.072548598, + 0.0137106 0.030440601 0.086147502, + 0.0165099 0.027627099 0.0865191, + 0.0165099 0.0296735 0.085592203, + 0.0109179 0.0269165 0.088383101, + 0.0109179 0.028997401 0.0875398, + 0.0081421202 0.027377101 0.088735603, + 0.0081421202 0.0252764 0.089482799, + 0.0109179 0.0248206 0.089124396, + 0.0137106 0.0263119 0.087920099, + 0.0137106 0.0283866 0.087084897, + -0.0081421202 0.037530601 0.083451502, + -0.0081421202 0.035567202 0.084713802, + -0.0109179 0.035087701 0.084386297, + -0.0081421202 0.043098502 0.079078503, + -0.0081421202 0.041303899 0.0806311, + -0.0081421202 0.0448227 0.0774367, + -0.0053918599 0.0434446 0.079285301, + -0.0053918599 0.041647501 0.080843903, + -0.0137106 0.038317502 0.081367902, + -0.0165099 0.037521701 0.080858603, + -0.0137106 0.036412001 0.0827116, + -0.0109179 0.0389576 0.081777602, + -0.0137106 0.040167298 0.079928003, + -0.0165099 0.039365299 0.079432003, + -0.0109179 0.037046801 0.0831315, + 0.0378174 0.0198934 0.076266997, + 0.035366699 0.0199729 0.078567497, + 0.035366699 0.021899501 0.077677503, + 0.0378174 0.017985901 0.0771285, + 0.0378174 0.0217724 0.075311199, + 0.040174201 0.0177506 0.074760303, + 0.040174201 0.0196098 0.073836498, + 0.0328326 -0.00724624 0.08478, + 0.0328326 -0.0050781202 0.084737599, + 0.035366699 -0.0066500199 0.083157398, + 0.035366699 -0.0087944698 0.0831853, + 0.0328326 -0.0094175003 0.084784098, + 0.0302257 -0.0058231 0.086245798, + 0.0302257 -0.00801636 0.0862628, + 0.040174201 -0.014338 0.0795912, + 0.0424264 -0.016198101 0.077628098, + 0.0378174 -0.012584 0.081442401, + 0.0576833 -0.0152876 0.054534901, + 0.058412101 -0.018205401 0.052359901, + 0.0576833 -0.018546101 0.055000499, + 0.056809202 -0.015692901 0.057245702, + -0.0302257 0.0446698 0.062119499, + -0.0302257 0.045738999 0.0601952, + -0.0302257 0.043503199 0.064002201, + -0.0328326 0.0428329 0.061292101, + -0.027557701 0.0451723 0.064788103, + -0.0328326 0.043900199 0.059404202, + -0.0220857 0.053520899 0.0538132, + -0.0220857 0.054077201 0.051700201, + -0.0248404 0.0527489 0.0512591, + -0.0302257 0.047580302 0.056251399, + -0.0302257 0.0467095 0.058236498, + -0.0328326 0.045742001 0.055534098, + -0.035366699 0.044518199 0.052827299, + -0.027557701 0.0492539 0.056904498, + -0.0424264 0.0419752 0.020582801, + -0.0424264 0.0406623 0.037725002, + -0.0424264 0.040480699 0.039473198, + -0.040312301 0.044451501 0.0124646, + -0.0424264 0.042394701 0.0145775, + -0.040171701 0.044572901 0.0124645, + -0.038084399 0.0463751 0.0124631, + -0.0378174 0.043049902 0.0501354, + -0.035764702 0.048187099 0.0124616, + -0.035361301 0.048471499 0.0124614, + -0.033358999 0.049883101 0.0124603, + -0.035366699 0.0481782 0.020956401, + -0.035366699 0.0483649 0.016794501, + -0.027557701 0.0520906 0.046644598, + -0.027557701 0.051719502 0.048703, + -0.0220857 0.055151898 0.0453666, + -0.0424264 -0.166577 -0.042151202, + -0.044564299 -0.166483 -0.039898101, + -0.040169802 -0.171534 -0.044422701, + -0.040174201 -0.16910701 -0.044390101, + -0.038194101 -0.171535 -0.046136599, + -0.039609101 -0.191534 -0.0449154, + 0.0424264 0.035991501 0.053835601, + 0.0424264 0.0368683 0.0520644, + 0.0378174 0.044151202 0.046324499, + 0.040174201 0.042290699 0.043755598, + 0.0424264 0.0302728 0.062173501, + 0.0424264 0.028879 0.063691802, + 0.044564299 0.0263429 0.062339202, + 0.0465803 0.0250609 0.059503, + 0.044564299 0.027726 0.060868502, + 0.044564299 0.033420499 0.0527809, + 0.0424264 0.033966199 0.0572947, + 0.040174201 0.036403298 0.058392599, + 0.0424264 0.035023902 0.055581301, + 0.040174201 0.035252299 0.060114302, + 0.050219599 0.018075701 0.057930101, + 0.050219599 0.0166602 0.0591866, + 0.050219599 0.0151819 0.060379401, + 0.050219599 0.0136455 0.061504599, + 0.0532961 0.0107496 0.055909801, + 0.051830001 0.0137391 0.057567202, + 0.051830001 0.0122773 0.058707699, + 0.050219599 0.0104191 0.063535303, + 0.048467699 0.0097438097 0.067108303, + 0.048467699 0.00797466 0.067886002, + 0.051830001 0.000768503 0.064657703, + 0.050219599 0.00528104 0.065991797, + 0.050219599 0.0035129699 0.066645697, + 0.051830001 0.0025100801 0.064043202, + 0.051830001 0.0107595 0.0597822, + 0.051830001 0.0091903498 0.060786501, + 0.0532961 0.00930476 0.056996901, + 0.0465803 0.020735599 0.063575901, + 0.0465803 0.0222457 0.062283099, + 0.044564299 0.0233612 0.065086998, + 0.044564299 0.021772901 0.066354901, + 0.0465803 0.019164 0.064797997, + 0.048467699 0.0180053 0.062004499, + 0.048467699 0.019499799 0.0607608, + 0.050219599 0.0267237 0.046221301, + 0.051830001 0.0244783 0.043598, + 0.051830001 0.0237536 0.045120001, + 0.050219599 0.0274415 0.044639699, + 0.050219599 0.025923001 0.047791101, + 0.048467699 0.0296109 0.047292002, + 0.048467699 0.0288142 0.048919901, + 0.035366699 0.046978999 0.043116301, + 0.0328326 0.048643801 0.045628201, + 0.0302257 0.050452799 0.046161301, + 0.0165099 -0.167218 -0.0574257, + 0.019305199 -0.16498201 -0.0563922, + 0.019305199 -0.167181 -0.056552298, + 0.0165099 -0.16503599 -0.057265501, + 0.016575299 -0.208544 -0.057498999, + 0.016505901 -0.171544 -0.057532098, + 0.0165099 -0.169388 -0.057519101, + 0.0105583 -0.208545 -0.0588977, + 0.0081428103 -0.152207 -0.056629401, + 0.00268824 -0.16088299 -0.058995798, + 1.0780916e-011 -0.15874 -0.058691598, + 6.7024125e-012 -0.156591 -0.058259301, + 4.4463933e-012 -0.160889 -0.059054799, + 0.0137106 -0.158544 -0.0571068, + 0.0165099 -0.156257 -0.0559448, + 0.0165099 -0.154066 -0.055441201, + 0.059757002 0.0021136701 0.022627501, + 0.0599402 0.00165337 0.0170705, + 0.059757002 0.00029346501 0.026869601, + 0.059445001 0.0024208699 0.0296633, + 0.059757002 0.00441236 0.0171795, + 0.059757002 0.0039599799 0.018299101, + 0.0599402 0.0021895 0.0157691, + 0.059757002 0.00492378 0.015830399, + 0.059445001 0.00329723 0.027533799, + 0.059445001 0.0050254902 0.0230418, + 0.059445001 0.0067788102 0.0184687, + -0.050219599 -0.0036982801 0.068426199, + -0.048467699 -0.0047883401 0.070961498, + -0.0465803 -0.0043111001 0.0731837, + -0.044564299 -0.0020121201 0.075180002, + -0.0532961 0.00623621 0.058949899, + -0.0546159 0.0032484101 0.0571029, + -0.0546159 0.0103579 0.051968601, + -0.0546159 0.0090489602 0.0531133, + -0.051830001 0.0024977301 0.064019203, + -0.058998398 -0.046869401 0.047977801, + -0.059757002 -0.0128502 0.0414332, + -0.059445001 -0.0097580804 0.043082401, + -0.059445001 -0.0123543 0.044523399, + -0.059757002 -0.0154136 0.042762399, + -0.0599402 -0.0159015 0.0398058, + -0.0599402 -0.0135413 0.038412701, + -0.059757002 -0.0082818102 0.038265601, + -0.059445001 -0.0073502902 0.041456301, + -0.059445001 -0.0051513002 0.039675899, + -0.059757002 -0.0104664 0.039924301, + -0.059757002 -0.0063120602 0.0364892, + -0.0599402 -0.0113709 0.036874, + -0.0599402 -0.0094052702 0.0352205, + -0.055787299 0.0127427 0.044305202, + -0.0532961 0.018027199 0.0482735, + -0.0532961 0.0134315 0.053543501, + -0.0546159 0.0116027 0.050773598, + -0.058412101 -0.0034870701 0.046427101, + -0.058998398 -0.0066325502 0.044749402, + -0.058412101 -0.0061499602 0.0480945, + -0.0576833 -0.00033409201 0.048108801, + -0.058412101 -0.00103064 0.044562999, + -0.058998398 -0.0042004902 0.0430048, + -0.0576833 -0.0030304899 0.04989, + -0.058412101 0.0109313 0.0238786, + -0.058412101 0.012491 0.0188077, + -0.058998398 0.0104582 0.0159411, + -0.058412101 0.0093893697 0.0288806, + -0.0576833 0.0117056 0.032039501, + -0.048467699 0.0314744 0.042360101, + -0.055787299 0.017018599 0.0363084, + -0.055787299 0.0217309 0.016194399, + -0.0546159 0.0215664 0.031573299, + -0.055787299 0.0210901 0.019325299, + -0.056809202 0.0189243 0.0161313, + -0.055787299 0.022006501 0.0143726, + -0.056809202 0.0192197 0.0143446, + -0.0532961 0.0272546 0.016318699, + -0.050219599 0.0286132 0.041463502, + -0.0302257 -0.16926301 -0.051657598, + -0.027557701 -0.169294 -0.053124201, + -0.0302257 -0.166972 -0.0515588, + -0.028437899 -0.17154001 -0.052696001, + -0.0302184 -0.17154001 -0.051680598, + -0.030994801 -0.17153899 -0.051237699, + -0.0328326 -0.169227 -0.050046802, + -0.0328326 -0.166904 -0.0499475, + -0.0220857 -0.169347 -0.055616401, + -0.0248404 -0.167089 -0.054346301, + -0.0248404 -0.16484401 -0.054183699, + -0.019305199 -0.162773 -0.0561512, + -0.0220857 -0.162689 -0.055128101, + -0.0220857 -0.160456 -0.054833099, + -0.019305199 -0.160561 -0.055856399, + -0.0165099 -0.16503499 -0.0572544, + -0.0137106 -0.16290601 -0.057756599, + -0.0165099 -0.162846 -0.057026502, + -0.0137106 -0.16508099 -0.0579843, + -0.0137106 -0.160726 -0.057461798, + -0.0109179 -0.162955 -0.058343999, + -0.0165099 -0.160652 -0.056731701, + -0.0109179 -0.165117 -0.058571499, + -0.0378174 0.0042372602 0.080606602, + -0.040174201 0.0042942399 0.078659698, + -0.035366699 0.014071 0.0806593, + -0.035366699 0.0120871 0.081174299, + -0.0424264 0.0059877601 0.076248497, + -0.0424264 0.0079045501 0.0758055, + -0.040174201 0.0120233 0.076964296, + -0.040174201 0.0100867 0.077523202, + -0.0424264 0.0098176897 0.075273901, + -0.0378174 0.0121445 0.079142801, + -0.040174201 -0.0101578 0.079623401, + -0.0378174 -0.0062358198 0.081392802, + -0.0424264 -0.0079672299 0.077629901, + -0.0220857 0.0215423 0.086540699, + -0.0302257 0.0093588103 0.085053697, + -0.0302257 0.0050580399 0.085573703, + -0.0328326 0.0158592 0.082066901, + -0.035366699 -0.028113799 0.081732802, + -0.0328326 -0.0267886 0.083435297, + -0.035366699 -0.032370199 0.080998898, + -0.0328326 -0.0310962 0.082719401, + -0.0378174 -0.0295415 0.079898499, + -0.0465803 -0.032198999 0.072091103, + -0.048467699 -0.0302056 0.070338197, + -0.035366699 -0.0238344 0.082317904, + -0.044564299 -0.0140977 0.075661898, + -0.0424264 -0.016199799 0.077615701, + -0.040174201 -0.0227185 0.079053096, + -0.040174201 -0.0269001 0.078569502, + -0.0424264 -0.0203298 0.077393502, + -0.0378174 -0.0253167 0.080505498, + -0.0220857 0.039045699 0.076658502, + -0.0248404 0.039437901 0.074336298, + -0.027557701 0.037966698 0.073489398, + -0.027557701 0.030873099 0.079049699, + -0.0302257 0.0311327 0.076771498, + -0.027557701 0.0327328 0.077795103, + -0.0302257 0.0292861 0.078000702, + -0.0220857 0.0316412 0.082033999, + -0.0220857 0.029673399 0.083136402, + -0.0248404 0.030384099 0.081176102, + -0.0248404 0.032301798 0.079994202, + -0.019305199 0.030759901 0.083901003, + -0.0081421202 -0.0106051 0.093154497, + -0.0109179 -0.0063712699 0.092867501, + -0.0109179 -0.0109687 0.0927312, + -0.0081421202 -0.0152132 0.0928597, + -0.0053918599 -0.0149681 0.093159497, + -0.0053918599 -0.0057322499 0.093576401, + -0.0081421202 -0.0059951101 0.093284801, + -0.0053918599 -0.0103511 0.093450502, + -0.00267513 -0.0102021 0.093624301, + -0.00267513 -0.0055779698 0.093747698, + -0.0053918599 -0.00111985 0.093537897, + -0.0081421202 -0.00139144 0.093250901, + -0.0165099 -0.00292443 0.091631703, + -0.0137106 -0.0022901699 0.0923016, + -0.0165099 0.00161617 0.091462903, + -0.019305199 0.00083160802 0.090673901, + -0.019305199 -0.0036850199 0.090828501, + -0.0165099 -0.0074789701 0.091639198, + -0.0137106 -0.0068650199 0.092319898, + -0.0137106 -0.016024301 0.0918677, + -0.0109179 -0.0155639 0.092430703, + -0.0137106 -0.0114458 0.092175402, + -0.0165099 -0.0120392 0.091484703, + -0.0165099 -0.016596699 0.091167599, + -0.0137106 -0.0205917 0.091397099, + -0.0109179 -0.0201483 0.091966897, + -0.0081421202 0.021079199 0.090668902, + -0.0081421202 0.0231697 0.090126403, + -0.0053918599 0.021390701 0.090927102, + -0.0053918599 0.019297799 0.091377497, + -0.0081421202 0.0189896 0.091116101, + -0.0053918599 0.0170945 0.091770202, + -0.0053918599 0.0125952 0.092445098, + -0.019305199 0.020508699 0.087976404, + -0.0137106 0.020047899 0.089814998, + -0.0109179 0.0206332 0.090299703, + -0.0165099 0.01932 0.089212298, + -0.0165099 0.021391099 0.088689297, + -0.0109179 0.0185485 0.090742096, + -0.0081421202 0.0167896 0.091505699, + -0.0081421202 0.0122981 0.092174299, + -0.0137106 0.0068085399 0.091779202, + -0.0109179 0.0073506301 0.092298299, + -0.0137106 0.0242217 0.088650197, + -0.0165099 0.025558401 0.087339103, + -0.0165099 0.023477601 0.088064402, + -0.0137106 0.0263106 0.087915704, + -0.0137106 0.022127001 0.089283802, + -0.0109179 0.024820101 0.089121602, + -0.0109179 0.022718901 0.089761898, + -0.0109179 0.028995899 0.087535702, + -0.0109179 0.0269155 0.088379599, + -0.0137106 0.0283846 0.087079696, + -0.0081421202 0.0294616 0.087883301, + -0.0081421202 0.0273763 0.088733003, + -0.035366699 -0.0109432 0.083165102, + -0.0328326 -0.0115914 0.084741302, + -0.0328326 -0.0137656 0.084669799, + -0.0328326 -0.0159404 0.084559999, + -0.0328326 -0.0181148 0.0844118, + -0.035366699 -0.0195409 0.082751803, + 0.0081421202 0.052179299 0.068087302, + 0.0165099 0.051355898 0.065129898, + 0.0165099 0.050176602 0.067143902, + 0.0137106 0.052186299 0.065504096, + 0.0081421202 0.050894901 0.070089102, + 0.0109179 0.051671699 0.067848198, + 0.0137106 0.051005401 0.067534201, + 0.0220857 0.0174262 0.087648697, + 0.0248404 0.016256399 0.0866808, + 0.0220857 0.0153786 0.088057399, + 0.019305199 0.018446701 0.0884929, + 0.0220857 0.019476701 0.087147497, + 0.0248404 0.018293999 0.086192802, + 0.019305199 0.0163876 0.088912398, + 0.0220857 0.0021558199 0.089630499, + 0.0248404 0.00108919 0.0885842, + 0.0248404 0.0033063199 0.088426501, + 0.0220857 0.0043883501 0.089462601, + 0.0220857 -8.263511e-005 0.089758798, + 0.019305199 0.00308623 0.0905433, + 0.019305199 0.00083417603 0.090680301, + 0.0081421202 0.0562791 0.0596442, + 0.00267513 0.052741501 0.0683522, + -4.1584271e-012 0.051522899 0.070397899, + 7.6590357e-012 0.0592933 0.051073998, + 5.955876e-012 0.059627499 0.048865601, + -0.00267513 0.0595599 0.048845802, + 0.00267513 0.059226301 0.051052801, + 0.00267513 0.059560802 0.048845999, + -0.0165099 0.055023499 0.056720499, + -0.0165099 0.054262701 0.058859002, + -0.019305199 0.054026801 0.0563512, + -0.019305199 0.054683302 0.054221399, + -0.0165099 0.055677701 0.0545705, + -0.0137106 0.057054002 0.0526882, + -0.0137106 0.056506999 0.054861601, + -0.0081421202 0.058665 0.050877899, + -0.019305199 0.0478963 0.068615302, + -0.019305199 0.046525098 0.070501097, + -0.0220857 0.046735801 0.068044797, + -0.019305199 0.049172599 0.066671997, + -0.0165099 0.048889101 0.069103301, + -0.0165099 0.047514498 0.071007997, + -0.0137106 0.043670502 0.076773196, + -0.0165099 0.042857699 0.0763053, + -0.0137106 0.041953702 0.0783948, + -0.0109179 0.044324301 0.077149801, + -0.0137106 0.045311201 0.075068504, + -0.0165099 0.044493701 0.074615203, + -0.0109179 0.0426034 0.078782797, + 0.0053918599 0.043446802 0.079287499, + 0.0081421202 0.044826299 0.0774398, + 0.0053918599 0.045173399 0.077639498, + 0.00267513 0.0436491 0.079407997, + 0.00267513 0.0418505 0.080970101, + 0.0137106 0.041959502 0.0784005, + 0.0165099 0.0393718 0.079439402, + 0.0165099 0.041153099 0.077919401, + 0.0109179 0.0389615 0.081782602, + 0.0109179 0.037050299 0.0831367, + 0.0137106 0.0383224 0.081374303, + 0.0137106 0.0401727 0.079934001, + 0.0081421202 0.037533201 0.083455399, + 0.0081421202 0.041307099 0.080634698, + 0.0109179 0.040816601 0.080331802, + 0.0081421202 0.039448299 0.082093596, + 0.0053918599 0.041649699 0.080846302, + 0.0081421202 0.043102 0.0790819, + 0.0109179 0.042608 0.078787401, + 0.0053918599 0.039788298 0.082310699, + 0.0546159 0.0159159 0.0455999, + 0.050219599 0.020700499 0.0552448, + 0.050219599 0.0194236 0.056614298, + 0.0532961 0.0170152 0.049657699, + 0.0532961 0.018054601 0.0482798, + 0.051830001 0.020057 0.051027998, + 0.051830001 0.0189369 0.05243, + 0.051830001 0.0151401 0.056364398, + 0.0532961 0.0121355 0.054761998, + 0.059757002 -0.0153867 0.042785201, + 0.059757002 -0.0128213 0.041451398, + 0.058998398 -0.0180133 0.049610101, + 0.059445001 -0.0179777 0.046781301, + 0.058412101 -0.0150447 0.051697802, + -0.044564299 0.032430701 0.054469999, + -0.044564299 0.0290091 0.059330501, + -0.050219599 0.026698999 0.046222001, + -0.048467699 0.023551701 0.0566478, + -0.0465803 0.026333701 0.058015302, + -0.044564299 0.035765398 0.0475762, + -0.0424264 0.038326401 0.048475999, + -0.044564299 0.036376901 0.045821, + -0.0424264 0.037632599 0.050275002, + -0.0465803 0.033705398 0.044933598, + -0.0465803 0.032379899 0.0483278, + -0.044564299 0.0350658 0.049323499, + -0.0465803 0.033085499 0.046634801, + -0.048467699 0.029587099 0.047292601, + -0.0465803 0.0315868 0.0500095, + -0.044564299 0.034276601 0.051059201, + -0.048467699 0.030299 0.045655701, + -0.0424264 0.032798 0.058960699, + -0.044564299 0.030234201 0.057753298, + -0.0424264 0.031565901 0.060587499, + -0.0424264 0.033944301 0.0572882, + -0.040174201 0.035231698 0.060106799, + -0.044564299 0.031375699 0.056131002, + -0.040174201 0.033992998 0.061780699, + -0.050219599 0.0193986 0.0566011, + -0.051830001 0.0164496 0.055089999, + -0.050219599 0.020675 0.055233601, + -0.048467699 0.0222652 0.05807, + -0.051830001 0.0151149 0.056348599, + -0.0532961 0.0107246 0.055891499, + -0.0532961 0.0121097 0.054745801, + -0.0532961 0.0092808502 0.056976601, + -0.0532961 0.0077831601 0.057997301, + -0.0137106 0.032464601 0.085100703, + -0.0165099 0.031689402 0.084555097, + -0.0137106 0.0304379 0.086141698, + -0.0137106 0.034458499 0.083956704, + -0.0109179 0.033087999 0.085539602, + -0.0109179 0.0310554 0.086589299, + -0.019305199 0.034676298 0.081564002, + -0.0165099 0.0356226 0.082189798, + -0.019305199 0.036567401 0.080248103, + -0.019305199 0.0327379 0.082782403, + -0.0220857 0.033569999 0.080832601, + -0.0165099 0.033675998 0.083422698, + 0.0424264 -0.0120707 0.0777082, + 0.040174201 -0.0122441 0.079632297, + 0.0378174 -0.0104624 0.081467398, + -0.027557701 0.046342202 0.062872902, + -0.0248404 0.046675 0.065495797, + -0.0220857 0.0480089 0.066124, + -0.019305199 0.052397098 0.060568899, + -0.0220857 0.051229801 0.060090199, + -0.019305199 0.053264599 0.058469601, + -0.0165099 0.053395901 0.060978401, + -0.0328326 0.046514999 0.053567398, + -0.0302257 0.04902 0.0522325, + -0.0302257 0.048350599 0.0542477, + -0.0248404 0.0515262 0.055424701, + -0.0248404 0.0507605 0.057492498, + -0.027557701 0.050021801 0.0548671, + -0.0248404 0.0521884 0.0533453, + -0.027557701 0.050687399 0.052818201, + -0.0220857 0.052861702 0.055919498, + -0.0220857 0.052097902 0.0580143, + -0.0424264 0.0402207 0.041239001, + -0.0378174 0.046459101 0.0167515, + -0.040174201 0.044537701 0.0145991, + -0.0378174 0.0462403 0.0208397, + -0.0378174 0.046558499 0.0146194, + -0.035366699 0.045196202 0.050889298, + -0.0328326 0.047188599 0.051589198, + -0.0328326 0.050133899 0.016834499, + -0.035366699 0.0484506 0.0146385, + -0.0328326 0.050206799 0.0146562, + -0.0328326 0.049977101 0.021064799, + -0.0220857 0.0553158 0.043308001, + 0.0378174 0.039764199 0.057621099, + 0.040174201 0.037463602 0.056631099, + 0.0378174 0.0387014 0.0594281, + 0.035366699 0.041917901 0.058547799, + 0.040174201 0.038431801 0.054836702, + 0.035366699 0.040852901 0.060397401, + 0.0378174 0.040732998 0.055780798, + 0.035366699 0.043760099 0.0547552, + 0.035366699 0.0428872 0.056664702, + 0.0424264 0.0394627 0.0448546, + 0.040174201 0.041875701 0.045611098, + 0.0424264 0.039889 0.043047901, + 0.0424264 0.038949199 0.046664599, + 0.044564299 0.0369206 0.0440576, + 0.044564299 0.037358802 0.042302102, + 0.040174201 0.040089 0.0511778, + 0.0424264 0.0383467 0.0484729, + 0.0424264 0.037653401 0.050274499, + 0.040174201 0.039307199 0.053016499, + 0.0378174 0.041607 0.053914499, + 0.0378174 0.043067999 0.050132599, + 0.040174201 0.041371599 0.047469899, + 0.0378174 0.043655999 0.048229299, + 0.040174201 0.040776599 0.049327001, + 0.0378174 0.0423855 0.052029502, + 0.035366699 0.0452132 0.050886799, + 0.035366699 0.0445356 0.0528269, + 0.0465803 0.0307303 0.051677201, + 0.048467699 0.0279327 0.050529599, + 0.044564299 0.0324536 0.054475401, + 0.050219599 0.024074901 0.050870098, + 0.048467699 0.024786901 0.055185299, + 0.0465803 0.026357399 0.0580258, + 0.048467699 0.023576301 0.0566586, + 0.050219599 0.021903399 0.0538272, + 0.050219599 0.023029 0.052367099, + 0.044564299 0.0290318 0.0593406, + 0.0424264 0.0328198 0.0589687, + 0.0424264 0.031587601 0.060597099, + 0.0546159 0.0103851 0.051982999, + 0.0546159 0.0139172 0.0482619, + 0.0546159 0.0149533 0.046945401, + 0.055787299 0.0127711 0.044309799, + 0.056809202 0.0095967203 0.043007798, + 0.0576833 0.0044193701 0.043982901, + 0.056809202 0.0053485902 0.047697701, + 0.055787299 0.0059732101 0.051475398, + 0.0546159 0.0077047399 0.054221701, + 0.0546159 0.00907546 0.0531299, + 0.055787299 0.0072696302 0.0503866, + 0.056809202 0.0028419399 0.049805298, + 0.055787299 0.0046179299 0.052510299, + 0.0546159 0.00479746 0.0562241, + 0.055787299 0.00174767 0.054403901, + 0.0532961 0.00780576 0.0580194, + 0.0546159 0.0062772199 0.055254299, + 0.055787299 0.0032079399 0.0534878, + 0.055787299 -0.0078012398 0.0584502, + 0.055787299 -0.0094757099 0.058867, + 0.056809202 -0.012374 0.056706801, + 0.055787299 0.000241544 0.055255201, + 0.0546159 -0.00321417 0.060017802, + 0.0532961 -0.00032583001 0.062048901, + 0.055787299 -0.0061422898 0.057958499, + 0.0532961 -0.00377209 0.063118197, + 0.0532961 -0.0020403401 0.062623098, + 0.051830001 -0.00099114701 0.065191001, + 0.051830001 -0.0027643801 0.065643899, + 0.0532961 -0.0055167298 0.063534997, + 0.0546159 -0.0066044 0.061007202, + 0.0546159 -0.0049010902 0.060550898, + 0.050219599 0.0087400898 0.064434901, + 0.050219599 0.0070253899 0.065254301, + 0.051830001 0.0042288899 0.063347198, + 0.0532961 0.0046641901 0.059855599, + 0.051830001 0.0075749699 0.061716899, + 0.0532961 0.0062572602 0.058973499, + 0.051830001 0.0059191901 0.062571101, + 0.0546159 0.00326998 0.057127099, + 0.0328326 0.049136501 0.041722301, + 0.0328326 0.048936401 0.043656599, + 0.035366699 0.047191501 0.041220501, + 0.035366699 0.047322601 0.039331201, + 0.0328326 0.0492539 0.039795201, + 0.0302257 0.050924499 0.0421836, + 0.0302257 0.0507356 0.0441534, + 0.0137073 -0.171545 -0.0582611, + 0.0145714 -0.171545 -0.058067098, + 0.0135848 -0.19154499 -0.058289401, + 0.0109179 -0.169416 -0.058833301, + 0.0109154 -0.171545 -0.058847699, + 0.0116994 -0.171545 -0.0587117, + 0.0081428103 -0.16942599 -0.059279401, + 0.0109179 -0.167273 -0.0587392, + 0.0087992204 -0.171546 -0.0592147, + 0.0137106 -0.169404 -0.058247499, + 0.0137106 -0.16724899 -0.0581537, + 0.0081428103 -0.160832 -0.0585021, + 0.0053973799 -0.160864 -0.058813501, + 0.0053973799 -0.154406 -0.057514701, + 0.00268824 -0.156583 -0.058200099, + 0.00268824 -0.158732 -0.058632601, + 0.0109179 -0.152124 -0.056182802, + 0.0137106 -0.152016 -0.055596501, + -0.0424264 0.0117194 0.074653298, + -0.040174201 0.0232033 0.071699701, + -0.0424264 0.022585901 0.069057398, + -0.044564299 0.0201093 0.067526303, + -0.0378174 0.0141033 0.078558497, + -0.040174201 0.0139481 0.076314799, + -0.0378174 0.0198844 0.076249503, + -0.050219599 -0.00188797 0.068098001, + -0.050219599 -8.0006292e-005 0.067688502, + -0.048467699 -0.00296437 0.070766397, + -0.0465803 -0.00236828 0.073012702, + -0.044564299 -4.1022995e-005 0.074985303, + -0.048467699 0.0114666 0.066223398, + -0.0465803 0.015840599 0.0669908, + -0.0465803 0.0141191 0.0679764, + -0.0546159 0.00167987 0.057934601, + -0.0546159 7.4055999e-005 0.0586945, + -0.0532961 0.00135182 0.061369602, + -0.051830001 0.0075562699 0.0616927, + -0.0532961 0.00301491 0.060637899, + -0.0532961 0.0046449401 0.0598308, + -0.050219599 0.0070112399 0.065230198, + -0.051830001 0.0042143101 0.063322298, + -0.050219599 0.0052690599 0.065968499, + -0.048467699 0.00973015 0.067085102, + -0.050219599 0.0087238997 0.064410798, + -0.051830001 0.0059024398 0.062546201, + -0.048467699 0.0079631004 0.067863598, + -0.0599402 -0.0355964 0.043758601, + -0.0599402 -0.044689599 0.042465799, + -0.0599402 -0.047736999 0.041840401, + -0.059445001 -0.049206901 0.045387201, + -0.058689699 -0.208488 0.0126365, + -0.059757002 -0.048418801 0.043605, + -0.0596609 -0.20849299 0.0065359101, + -0.059445001 -0.042842198 0.046761502, + -0.059445001 -0.04603 0.0461265, + -0.058998398 -0.043615501 0.048675101, + -0.059757002 -0.0453059 0.044284601, + -0.058998398 -0.040352002 0.049265102, + -0.059445001 -0.0301496 0.0482664, + -0.059757002 -0.032891098 0.0459975, + -0.059445001 -0.0270888 0.048264101, + -0.059757002 -0.029890999 0.046058699, + -0.058998398 -0.0273785 0.050559901, + -0.058998398 -0.030549901 0.0503993, + -0.0532961 0.0189909 0.046868, + -0.0532961 0.015873499 0.050990202, + -0.0532961 0.0146871 0.052289899, + -0.0546159 0.0127807 0.049533501, + -0.0546159 0.013889 0.0482536, + -0.0532961 0.0169877 0.049649499, + -0.051830001 0.018910199 0.0524204, + -0.051830001 0.0177157 0.053778801, + -0.0546159 0.0239185 0.019495601, + -0.0546159 0.0245116 0.016256999, + -0.0532961 0.0267085 0.0196635, + -0.048467699 0.031942099 0.040706702, + -0.050219599 0.028054999 0.043056399, + -0.050219599 0.0274175 0.044643302, + -0.0546159 0.020954801 0.0344286, + -0.019305199 -0.16718 -0.056541301, + -0.0220857 -0.167138 -0.055518601, + -0.019305199 -0.169369 -0.0566388, + -0.019305199 -0.16497999 -0.056379098, + -0.0165099 -0.167217 -0.057416301, + -0.0220857 -0.16491801 -0.055356201, + -0.0165099 -0.169387 -0.0575133, + -0.035366699 0.0060785199 0.0822054, + -0.0328326 0.0098789698 0.083393402, + -0.0328326 0.0077876798 0.083689399, + -0.0378174 0.00823317 0.080034703, + -0.0378174 0.00628511 0.080347203, + -0.040174201 0.0062200101 0.078368299, + -0.040174201 0.0081461603 0.0779915, + -0.0378174 0.0101815 0.0796353, + -0.035366699 0.0101179 0.081594698, + -0.035366699 0.0081489496 0.081926897, + -0.040174201 -0.00184733 0.079277299, + -0.040174201 -0.00599143 0.079521902, + -0.0424264 -0.00387902 0.077424698, + -0.0424264 0.000184955 0.077087902, + -0.040174201 0.00227051 0.078898802, + -0.0378174 6.8612811e-005 0.081024297, + -0.0378174 -0.00412816 0.0813061, + -0.0248404 0.018294301 0.086187698, + -0.0248404 0.020346699 0.085599303, + -0.0220857 0.019477 0.087142996, + -0.0220857 0.0021513 0.089623101, + -0.0220857 -8.5569896e-005 0.089751497, + -0.027557701 0.016961901 0.085111499, + -0.0302257 0.0134754 0.084373899, + -0.0328326 0.0118672 0.0830428, + -0.0328326 0.0138559 0.082602799, + -0.0302257 0.0154817 0.083916001, + -0.0302257 0.0114693 0.084741302, + -0.044564299 -0.030347999 0.074354, + -0.0424264 -0.0244588 0.077027403, + -0.0424264 -0.0285792 0.076516703, + -0.048467699 -0.0262761 0.070802502, + -0.0465803 -0.0282107 0.072660297, + -0.044564299 -0.026292199 0.074893303, + -0.0378174 -0.016830901 0.081271797, + -0.035366699 -0.0130915 0.083118401, + -0.0378174 -0.0125855 0.081431299, + -0.035366699 -0.0152412 0.083034098, + -0.0378174 -0.021077299 0.080963403, + -0.040174201 -0.0185291 0.079389602, + -0.035366699 -0.0173914 0.082911901, + -0.040174201 -0.0143396 0.079579398, + -0.0248404 0.035991199 0.077345498, + -0.0248404 0.034173299 0.078716502, + -0.027557701 0.034539599 0.076447897, + -0.027557701 0.036286298 0.075011201, + -0.0248404 0.037748098 0.075883903, + -0.0220857 0.037279699 0.078142203, + -0.0220857 0.0354519 0.079534501, + -0.0109179 0.0163536 0.091127098, + -0.0137106 0.0179695 0.0902512, + -0.0109179 0.0118731 0.091787003, + -0.0248404 0.00550659 0.0882219, + -0.0220857 0.0043818201 0.089455202, + -0.027557701 0.0064515499 0.086844198, + -0.027557701 0.0289679 0.080209799, + -0.0248404 0.0284278 0.082259998, + -0.0328326 0.025666701 0.077957302, + -0.0302257 0.027394701 0.079136297, + -0.0328326 0.0237536 0.078971401, + -0.035366699 0.021891 0.077661097, + -0.0328326 0.021810699 0.079889096, + 0.0109179 0.052854002 0.065805003, + 0.0137106 0.0532635 0.063430302, + 0.0137106 0.054235701 0.061321001, + 0.0109179 0.049008802 0.071773797, + 0.0137106 0.049724098 0.069513403, + 0.0137106 0.0483464 0.071434401, + 0.0109179 0.050388701 0.0698402, + 0.0109179 0.047535699 0.073641799, + 0.0081421202 0.049513299 0.072032303, + 0.0081421202 0.048038099 0.073909603, + -0.0081421202 0.058225799 0.053077001, + -0.0109179 0.057718899 0.052908901, + -0.00267513 0.059225202 0.051052999, + -0.0053918599 0.0590179 0.050988201, + 1.3549442e-011 0.058856599 0.053285498, + -0.0109179 0.0539263 0.063716799, + -0.0081421202 0.053358302 0.066032901, + -0.0165099 0.051347401 0.065127298, + -0.019305199 0.050349999 0.064678103, + -0.0165099 0.050168101 0.067140803, + -0.0165099 0.052423701 0.063070603, + -0.0137106 0.052179199 0.065502003, + -0.019305199 0.051425301 0.062641203, + -0.0137106 0.0509983 0.067531697, + 0.0532961 0.0147142 0.052301899, + 0.051830001 0.017742099 0.053790499, + 0.0532961 0.015900901 0.0510002, + 0.0532961 0.0134581 0.053557701, + 0.051830001 0.016475501 0.055103701, + 0.058998398 -0.0149746 0.0487656, + 0.059445001 -0.0150874 0.045780201, + 0.059445001 -0.0123276 0.0445459, + -0.048467699 0.028790001 0.0489178, + -0.0465803 0.030706501 0.051673301, + -0.0465803 0.029740101 0.053312499, + -0.050219599 0.0180513 0.057914801, + -0.048467699 0.020905901 0.059437402, + -0.0465803 0.0207147 0.063558199, + -0.044564299 0.023341199 0.0650701, + -0.0465803 0.022223899 0.062267099, + -0.048467699 0.019477099 0.060744099, + -0.044564299 0.021754 0.066336401, + -0.051830001 0.0122541 0.0586881, + -0.051830001 0.0137148 0.057549398, + -0.050219599 0.016636699 0.0591694, + -0.050219599 0.0120364 0.062535502, + -0.050219599 0.010401 0.063511901, + -0.051830001 0.0091698803 0.060763501, + -0.051830001 0.0107375 0.059760801, + -0.048467699 0.0131663 0.065280497, + -0.048467699 0.0164304 0.063158698, + -0.050219599 0.0136243 0.0614838, + -0.048467699 0.014823 0.064258203, + -0.048467699 0.0179836 0.061985999, + -0.0465803 0.0191443 0.0647787, + -0.050219599 0.0151594 0.060360301, + -0.0465803 0.0175178 0.065924197, + 0.040174201 -0.0080640204 0.079604201, + 0.040174201 -0.0101525 0.079636604, + 0.0424264 -0.0100109 0.077694103, + 0.040174201 -0.00597951 0.079535201, + 0.0424264 -0.0079546496 0.077643998, + 0.0378174 -0.00622808 0.081405498, + 0.0378174 -0.0083435504 0.081455097, + -0.0248404 0.0489203 0.0615637, + -0.0248404 0.047847699 0.063551001, + -0.027557701 0.0474132 0.060915399, + -0.0248404 0.049891599 0.059541501, + -0.027557701 0.048384 0.0589233, + -0.0220857 0.050258201 0.062139101, + -0.0220857 0.049184099 0.064153001, + -0.040174201 0.044170301 0.020715, + -0.0378174 0.045241602 0.038826101, + -0.040174201 0.044423599 0.0167055, + -0.040174201 0.043019101 0.0382917, + -0.0424264 0.042265199 0.016656799, + -0.0424264 0.039875299 0.043044701, + -0.0424264 0.039445501 0.044857699, + -0.040174201 0.041353401 0.047474299, + -0.027557701 0.052367698 0.044596702, + -0.0248404 0.0538426 0.045004498, + -0.0328326 0.049133699 0.041709598, + -0.0302257 0.050921801 0.042171799, + -0.0302257 0.050729401 0.044143699, + -0.0328326 0.049253501 0.039790701, + -0.035366699 0.047188502 0.041206699, + -0.035366699 0.047322199 0.039326299, + -0.0302257 0.050443001 0.046158999, + -0.0328326 0.048929699 0.043646201, + -0.044567399 -0.17152999 -0.040034901, + -0.044564299 -0.169012 -0.039999101, + -0.044033099 -0.191531 -0.040603898, + -0.045200799 -0.20852999 -0.0392914, + -0.0431097 -0.191532 -0.041579399, + -0.0464839 -0.171529 -0.0378008, + -0.042423699 -0.17153201 -0.042287, + -0.0424264 -0.16906101 -0.042251799, + -0.0404175 -0.171534 -0.0442078, + -0.042543601 -0.17153201 -0.042172201, + -0.040904202 -0.208533 -0.043729801, + 0.0465803 0.028712001 0.054927502, + 0.0465803 0.029764 0.053318098, + 0.044564299 0.031398699 0.0561378, + 0.044564299 0.030257201 0.057761699, + 0.0465803 0.027575601 0.056498699, + 0.048467699 0.0259181 0.0536687, + 0.048467699 0.026967101 0.052114598, + 0.055787299 0.0096740602 0.048067398, + 0.055787299 0.0107765 0.0468469, + 0.0546159 0.0128088 0.049543802, + 0.0546159 0.0116304 0.050786, + 0.055787299 0.0085041597 0.049249001, + 0.056809202 0.0076064202 0.045418799, + 0.058998398 -0.0019565499 0.041110501, + 0.058412101 0.00122764 0.042544998, + 0.0576833 0.00217615 0.0461381, + 0.059445001 -0.0097292596 0.043100599, + 0.059445001 -0.0073201 0.0414696, + 0.055787299 -0.0045032199 0.057391699, + 0.0546159 9.1685797e-005 0.0587206, + 0.0546159 0.00169957 0.0579601, + 0.0532961 0.0030321099 0.060663499, + 0.0532961 0.00136683 0.061395202, + 0.0546159 -0.0015481201 0.0594071, + 0.055787299 -0.00288929 0.056751002, + 0.055787299 -0.00130587 0.056038398, + 0.0053973799 -0.156556 -0.0580175, + 0.0081428103 -0.154355 -0.057202902, + 0.0053973799 -0.15871 -0.058450099, + 0.0109179 -0.15644699 -0.0572595, + 0.0137106 -0.156363 -0.056673501, + 0.0137106 -0.154185 -0.056170199, + 0.0109179 -0.154282 -0.0567565, + 0.0109179 -0.15861601 -0.057692599, + 0.0081428103 -0.15651099 -0.057705801, + 0.0081428103 -0.15867101 -0.058138698, + -0.040174201 0.017741101 0.074741699, + -0.040174201 0.0158558 0.075574197, + -0.0424264 0.019107601 0.0712732, + -0.044564299 0.0184124 0.068635702, + -0.044564299 0.016669899 0.069662102, + -0.0424264 0.020870199 0.070207603, + -0.0424264 0.017304599 0.072252303, + -0.040174201 0.0214216 0.072802603, + -0.040174201 0.019598501 0.073817201, + -0.035366699 0.018017299 0.079348803, + -0.0378174 0.0160497 0.077881701, + -0.0378174 0.017978599 0.077112302, + -0.035366699 0.0199659 0.078552298, + -0.035366699 0.0160504 0.080050804, + -0.048467699 0.00253442 0.069692098, + -0.0465803 0.0050627501 0.0716298, + -0.044564299 0.0056056599 0.073996097, + -0.059757002 -0.042186201 0.044863001, + -0.0599402 -0.0385768 0.043428998, + -0.0599402 -0.041637398 0.042993799, + -0.059445001 -0.036455002 0.047719501, + -0.059757002 -0.0359344 0.045723598, + -0.059445001 -0.033256602 0.048048899, + -0.059445001 -0.0396493 0.0472923, + -0.058998398 -0.0370849 0.049747702, + -0.059757002 -0.039063498 0.045340899, + -0.058998398 -0.033818401 0.0501238, + -0.0532961 0.019878 0.045439299, + -0.0546159 0.0158881 0.0455954, + -0.055787299 0.0144521 0.041681699, + -0.055787299 0.0158737 0.039009199, + -0.050219599 0.030086299 0.035182402, + -0.048467699 0.032642201 0.0374479, + -0.048467699 0.032331899 0.039058801, + -0.051830001 0.0261652 0.039004099, + -0.050219599 0.0290945 0.039867401, + -0.027557701 0.0149392 0.085585698, + -0.0248404 0.0162571 0.086676598, + -0.019305199 0.0053264801 0.090359896, + -0.0165099 0.0061345799 0.091133699, + -0.0328326 -0.00292073 0.084645897, + -0.027557701 0.0042692199 0.087065697, + -0.0248404 0.0032989299 0.088418297, + -0.0248404 0.00108408 0.0885759, + -0.027557701 -0.00232143 0.087503202, + -0.0302257 -0.00363718 0.086180001, + -0.027557701 -0.0045296601 0.087571397, + -0.0248404 -0.00113695 0.0886942, + -0.0248404 -0.0033631399 0.0887734, + -0.0465803 -0.0202101 0.073382102, + -0.0465803 -0.0242119 0.073090501, + -0.048467699 -0.022342499 0.071130998, + -0.0465803 -0.016212599 0.073535398, + -0.048467699 -0.0184118 0.071324199, + -0.044564299 -0.0181596 0.075546898, + -0.044564299 -0.0222269 0.075290799, + -0.0137106 0.015781401 0.0906303, + -0.0137106 0.0113155 0.091278702, + -0.027557701 0.025050201 0.0822367, + -0.0302257 0.023506399 0.081117898, + -0.027557701 0.0230508 0.083102003, + -0.027557701 0.027024601 0.081272602, + -0.0248404 0.02644 0.083243802, + -0.0302257 0.025465799 0.080175899, + -0.0248404 0.024426701 0.084127903, + -0.0302257 0.0195194 0.0827097, + -0.0302257 0.021522401 0.081962302, + -0.027557701 0.021032 0.0838691, + -0.027557701 0.0189995 0.084538899, + -0.0302257 0.017503001 0.083360903, + -0.0328326 0.0178579 0.081436202, + -0.0328326 0.019843601 0.0807105, + 0.0081421202 0.054441001 0.063937299, + 0.0109179 0.053931899 0.063718103, + 0.0081421202 0.0533625 0.066034198, + 0.0081421202 0.055413499 0.061804499, + 0.0109179 0.054904401 0.0615955, + 0.0053918599 0.053717598 0.066194199, + -0.00267513 0.058246799 0.055471599, + -0.00267513 0.0587883 0.053263102, + -4.3564713e-012 0.058315501 0.055495501, + -4.4470369e-012 0.057667401 0.0576992, + -0.00267513 0.057598501 0.057673998, + -0.0053918599 0.058037899 0.055398598, + -0.0053918599 0.058580101 0.053194299, + -0.0081421202 0.054436799 0.063936301, + -0.0053918599 0.0573892 0.057596501, + -0.0081421202 0.057682499 0.055273999, + -0.0109179 0.057174101 0.055095699, + -0.0053918599 0.0557664 0.061950099, + -0.0053918599 0.0566318 0.0597829, + -0.0081421202 0.057032902 0.0574647, + 0.0053918599 0.056634501 0.059783202, + 0.058998398 -0.0092355097 0.046325698, + 0.058998398 -0.0120364 0.047666099, + -0.051830001 0.0200302 0.051020201, + -0.051830001 0.021073001 0.0495838, + -0.050219599 0.0218776 0.053817801, + -0.050219599 0.0250143 0.049338501, + -0.048467699 0.027907999 0.050525401, + -0.050219599 0.0258979 0.047788899, + -0.051830001 0.0220374 0.0481176, + -0.051830001 0.0229227 0.0466277, + -0.0378174 0.044135898 0.0463273, + -0.035366699 0.045778502 0.048944101, + -0.0378174 0.043638799 0.048233401, + -0.040174201 0.0418594 0.045614101, + -0.040174201 0.042277601 0.0437527, + -0.0248404 0.0540151 0.0429716, + -0.027557701 0.052549701 0.042592701, + -0.0302257 0.0517601 0.0168713, + -0.0302257 0.051630698 0.021164401, + -0.0302257 0.051028799 0.040217701, + -0.0378174 0.044862699 0.042521998, + -0.035366699 0.046971802 0.043104999, + -0.0378174 0.045092899 0.040665101, + -0.0378174 0.0445433 0.044420298, + -0.040174201 0.0426098 0.041899301, + -0.040174201 0.042854398 0.040086601, + -0.0328326 0.0482453 0.047614701, + -0.0328326 0.048633099 0.045625702, + -0.0302257 0.050063901 0.048184399, + -0.0302257 0.049590301 0.0502101, + -0.0328326 0.047764599 0.049603801, + -0.035366699 0.046266999 0.046994999, + -0.035366699 0.046664398 0.045045499, + -0.0283127 0.0529113 0.0124579, + -0.0275514 0.053295098 0.0124576, + -0.025684301 0.0542362 0.0124568, + -0.0248404 0.054613899 0.0147006, + -0.0248404 0.054573599 0.016935, + 0.058998398 -0.0066039301 0.044767398, + 0.058412101 -0.00100093 0.044576202, + 0.058998398 -0.00417051 0.043017998, + 0.0576833 -0.0030046201 0.049911998, + 0.058412101 -0.0061237598 0.048116699, + 0.058412101 -0.0034587299 0.0464449, + 0.0576833 -0.00030609299 0.0481264, + 0.056809202 0.000109933 0.0517046, + 0.056809202 -0.0028152501 0.053365901, + 0.0576833 -0.0089230398 0.0527642, + 0.0576833 -0.0120691 0.053790402, + 0.058412101 -0.0119524 0.050762601, + 0.058412101 -0.0089660203 0.049564, + 0.0576833 -0.0058884001 0.051466301, + 0.056809202 -0.0058981301 0.054763, + 0.056809202 -0.0090977997 0.0558801, + -0.044564299 0.0130739 0.071458504, + -0.0424264 0.0154682 0.073142797, + -0.044564299 0.0148882 0.070603803, + -0.0465803 0.0105684 0.069696203, + -0.044564299 0.0112333 0.0722249, + -0.0424264 0.0136048 0.073943101, + -0.0465803 0.0123595 0.0688788, + -0.0465803 0.0013345 0.072490498, + -0.048467699 0.000698674 0.070133902, + -0.048467699 -0.00113976 0.070492297, + -0.0465803 0.0032001201 0.0721028, + -0.0465803 -0.00051716599 0.072791897, + -0.044564299 0.00371387 0.0744121, + -0.044564299 0.0018362 0.074739799, + -0.051830001 0.0269341 0.035973199, + -0.050219599 0.0298285 0.036720999, + -0.050219599 0.029500101 0.038276099, + -0.051830001 0.026587 0.037471101, + -0.051830001 0.027212501 0.034491401, + -0.0532961 0.0239718 0.035207901, + -0.0532961 0.0245394 0.032230798, + -0.0532961 0.0226577 0.039597299, + -0.0532961 0.023167299 0.038120601, + -0.0546159 0.0201139 0.037220702, + -0.051830001 0.025669999 0.040541299, + -0.051830001 0.0251 0.042074598, + -0.0532961 0.0214199 0.042536002, + -0.0532961 0.022075901 0.041069798, + -0.0546159 0.018996 0.040046599, + -0.0546159 0.017591201 0.042845398, + -0.0532961 0.020687699 0.043993399, + -0.051830001 0.0244534 0.0436018, + -0.051830001 0.023728199 0.045120601, + -0.027557701 0.0107892 0.086295702, + -0.0248404 0.0142204 0.087073199, + -0.027557701 0.0129171 0.085968398, + -0.0220857 0.00881969 0.089003399, + -0.0220857 0.0066049499 0.0892483, + -0.0248404 0.0077060899 0.087988101, + -0.0248404 0.0120768 0.087413803, + -0.0302257 0.00072390499 0.085952498, + -0.027557701 0.00207904 0.087250099, + -0.0302257 0.0028947601 0.085781403, + -0.0302257 -0.00145372 0.086085401, + -0.0328326 -0.00076456601 0.084527001, + -0.027557701 -0.000118178 0.087396003, + -0.0328326 0.00138506 0.084370703, + -0.019305199 0.0097911898 0.089889102, + -0.0220857 0.0132199 0.088406198, + -0.0165099 0.0106224 0.0906469, + -7.5086786e-012 0.0560451 0.0620641, + -0.00267513 0.055976201 0.0620359, + -0.00267513 0.0568415 0.059864599, + 1.419157e-012 0.056910399 0.059891298, + 0.00267513 0.056842901 0.0598647, + -0.0109179 0.055764701 0.059444901, + -0.0081421202 0.056274999 0.059643898, + -0.0109179 0.056523301 0.0572761, + -0.0137106 0.055095099 0.059183698, + -0.0109179 0.054898798 0.061594501, + -0.0081421202 0.055409402 0.061803799, + -0.0137106 0.0558546 0.057028402, + 0.00267513 0.055004898 0.064180098, + 0.0053918599 0.055769101 0.061950501, + 0.0053918599 0.054796498 0.064090297, + 0.00267513 0.055977602 0.062036101, + 0.00267513 0.053925801 0.066288203, + -4.7359508e-012 0.055072401 0.064209402, + -0.00267513 0.0539244 0.066287801, + -8.1591869e-012 0.053993199 0.066318698, + -0.00267513 0.055003501 0.0641798, + -0.0053918599 0.053714801 0.066193402, + -0.00267513 0.052740101 0.068351701, + -1.0126958e-011 0.052808899 0.068384103, + -0.0053918599 0.054793701 0.064089701, + -0.048467699 0.0258931 0.053661302, + -0.050219599 0.0240491 0.050864201, + -0.048467699 0.026942199 0.052108899, + -0.050219599 0.023003099 0.052359398, + -0.048467699 0.024762001 0.055176198, + -0.0465803 0.0286879 0.054920301, + -0.0465803 0.027551601 0.05649, + -0.027557701 0.053135999 0.0212551, + -0.027557701 0.053240702 0.0169049, + -0.027557701 0.052645002 0.040606301, + -0.0302257 0.051821101 0.0146724, + -0.0248404 0.0541435 0.038777199, + -0.027557701 0.0532909 0.0146873, + -0.0248404 0.054491099 0.021336701, + -0.0248404 0.054099798 0.040956199, + -0.0220857 0.0553913 0.041266799, + -0.019305199 0.016386401 0.088909298, + -0.019305199 0.014217 0.089272, + -0.0220857 0.0153772 0.0880538, + -0.019305199 0.0184473 0.088489696, + -0.0220857 0.017426901 0.087645002, + -0.0165099 0.0172497 0.089640997, + -0.0165099 0.01507 0.090012603 ] + + } + coordIndex [ 178, 1, 401, -1, 7, 18, 4, -1, + 16, 401, 1, -1, 345, 178, 401, -1, + 5, 7, 4, -1, 9, 6, 18, -1, + 9, 18, 7, -1, 769, 16, 1, -1, + 769, 376, 1417, -1, 15, 16, 769, -1, + 0, 4, 18, -1, 0, 16, 4, -1, + 0, 18, 401, -1, 0, 401, 16, -1, + 32, 297, 251, -1, 813, 178, 177, -1, + 813, 1, 178, -1, 813, 769, 1, -1, + 397, 178, 345, -1, 336, 345, 401, -1, + 2863, 2865, 345, -1, 414, 401, 18, -1, + 77, 18, 6, -1, 23, 5, 4, -1, + 1539, 6, 9, -1, 94, 9, 7, -1, + 20, 4, 98, -1, 226, 225, 99, -1, + 226, 99, 643, -1, 226, 643, 100, -1, + 112, 99, 1628, -1, 3, 4, 120, -1, + 127, 4, 267, -1, 127, 120, 4, -1, + 127, 59, 120, -1, 34, 297, 32, -1, + 603, 594, 290, -1, 14, 290, 594, -1, + 655, 297, 34, -1, 3053, 769, 813, -1, + 396, 345, 2865, -1, 396, 397, 345, -1, + 693, 345, 336, -1, 692, 345, 693, -1, + 831, 401, 414, -1, 831, 414, 829, -1, + 853, 829, 414, -1, 8, 7, 5, -1, + 25, 1539, 1537, -1, 187, 1539, 9, -1, + 26, 94, 7, -1, 93, 187, 9, -1, + 93, 189, 187, -1, 2, 98, 4, -1, + 2, 4, 206, -1, 2, 206, 98, -1, + 97, 20, 98, -1, 31, 242, 518, -1, + 1411, 769, 533, -1, 252, 251, 53, -1, + 252, 53, 545, -1, 540, 32, 251, -1, + 540, 251, 539, -1, 10, 206, 4, -1, + 10, 4, 3, -1, 10, 3, 205, -1, + 11, 3, 120, -1, 11, 205, 3, -1, + 126, 127, 267, -1, 58, 59, 127, -1, + 12, 34, 32, -1, 289, 290, 14, -1, + 288, 1232, 141, -1, 288, 141, 603, -1, + 288, 603, 290, -1, 284, 233, 285, -1, + 1247, 1246, 1417, -1, 612, 1417, 1246, -1, + 1250, 267, 4, -1, 1250, 4, 16, -1, + 295, 1251, 1250, -1, 295, 251, 297, -1, + 295, 1250, 251, -1, 146, 1884, 551, -1, + 45, 305, 1884, -1, 52, 594, 1800, -1, + 52, 1800, 659, -1, 1303, 659, 1800, -1, + 155, 1303, 1800, -1, 155, 1266, 306, -1, + 155, 1800, 312, -1, 54, 53, 49, -1, + 1978, 63, 757, -1, 380, 1417, 376, -1, + 378, 376, 769, -1, 786, 813, 177, -1, + 3060, 533, 769, -1, 3060, 769, 3053, -1, + 73, 178, 397, -1, 73, 387, 178, -1, + 75, 6, 74, -1, 75, 77, 6, -1, + 75, 78, 77, -1, 405, 78, 404, -1, + 410, 414, 18, -1, 410, 18, 411, -1, + 412, 411, 18, -1, 19, 21, 23, -1, + 19, 23, 4, -1, 19, 4, 20, -1, + 24, 207, 5, -1, 24, 5, 23, -1, + 79, 8, 5, -1, 79, 5, 207, -1, + 79, 91, 8, -1, 418, 25, 1537, -1, + 87, 6, 1539, -1, 87, 1539, 25, -1, + 87, 74, 6, -1, 87, 88, 74, -1, + 90, 26, 7, -1, 90, 7, 8, -1, + 90, 8, 91, -1, 969, 94, 26, -1, + 92, 9, 94, -1, 92, 93, 9, -1, + 978, 83, 213, -1, 96, 213, 83, -1, + 513, 285, 233, -1, 1093, 233, 102, -1, + 103, 518, 242, -1, 29, 518, 102, -1, + 29, 31, 518, -1, 521, 242, 31, -1, + 111, 99, 112, -1, 204, 10, 205, -1, + 204, 206, 10, -1, 119, 11, 120, -1, + 119, 259, 11, -1, 113, 11, 259, -1, + 113, 205, 11, -1, 33, 56, 58, -1, + 33, 58, 127, -1, 255, 34, 12, -1, + 255, 12, 32, -1, 269, 276, 557, -1, + 39, 564, 139, -1, 39, 566, 564, -1, + 39, 139, 138, -1, 41, 139, 136, -1, + 41, 136, 13, -1, 41, 603, 141, -1, + 41, 13, 603, -1, 135, 602, 603, -1, + 135, 603, 13, -1, 135, 13, 136, -1, + 159, 289, 14, -1, 159, 52, 671, -1, + 159, 14, 594, -1, 159, 594, 52, -1, + 1231, 141, 1232, -1, 1231, 38, 37, -1, + 1231, 134, 38, -1, 1231, 1233, 134, -1, + 1231, 40, 141, -1, 1231, 37, 40, -1, + 379, 380, 2020, -1, 142, 769, 1417, -1, + 142, 1417, 612, -1, 142, 15, 769, -1, + 142, 16, 15, -1, 142, 251, 1250, -1, + 142, 1250, 16, -1, 142, 53, 251, -1, + 142, 49, 53, -1, 265, 267, 1250, -1, + 46, 45, 1884, -1, 46, 1884, 44, -1, + 46, 44, 624, -1, 658, 305, 45, -1, + 617, 295, 297, -1, 308, 306, 1266, -1, + 147, 1266, 304, -1, 1302, 1303, 155, -1, + 153, 155, 306, -1, 154, 155, 312, -1, + 1883, 1884, 1266, -1, 665, 49, 325, -1, + 665, 54, 49, -1, 51, 49, 142, -1, + 663, 54, 665, -1, 60, 58, 56, -1, + 680, 2034, 161, -1, 2035, 161, 2034, -1, + 371, 757, 795, -1, 371, 795, 372, -1, + 163, 164, 757, -1, 166, 757, 164, -1, + 166, 795, 757, -1, 352, 169, 168, -1, + 174, 1399, 1379, -1, 174, 1379, 176, -1, + 174, 176, 386, -1, 65, 757, 63, -1, + 172, 380, 376, -1, 172, 2020, 380, -1, + 388, 177, 178, -1, 390, 785, 786, -1, + 399, 3053, 813, -1, 71, 397, 807, -1, + 71, 807, 72, -1, 17, 799, 387, -1, + 17, 387, 73, -1, 17, 73, 395, -1, + 392, 799, 17, -1, 392, 17, 395, -1, + 393, 395, 72, -1, 393, 67, 394, -1, + 1907, 834, 833, -1, 195, 74, 88, -1, + 195, 88, 194, -1, 407, 18, 77, -1, + 407, 412, 18, -1, 836, 414, 410, -1, + 413, 414, 836, -1, 413, 836, 847, -1, + 447, 442, 448, -1, 81, 19, 20, -1, + 81, 21, 19, -1, 81, 20, 97, -1, + 82, 23, 21, -1, 82, 85, 84, -1, + 82, 21, 81, -1, 22, 24, 23, -1, + 22, 84, 24, -1, 22, 23, 82, -1, + 22, 82, 84, -1, 208, 24, 84, -1, + 208, 207, 24, -1, 89, 25, 418, -1, + 89, 87, 25, -1, 967, 26, 90, -1, + 967, 969, 26, -1, 188, 189, 93, -1, + 217, 98, 206, -1, 215, 213, 96, -1, + 224, 226, 100, -1, 3077, 222, 3078, -1, + 1092, 513, 233, -1, 507, 508, 285, -1, + 510, 1087, 1086, -1, 510, 856, 1087, -1, + 509, 286, 508, -1, 509, 555, 286, -1, + 516, 102, 518, -1, 27, 28, 518, -1, + 27, 518, 103, -1, 27, 103, 106, -1, + 105, 27, 106, -1, 105, 28, 27, -1, + 105, 518, 28, -1, 241, 103, 242, -1, + 43, 107, 31, -1, 43, 31, 29, -1, + 43, 282, 107, -1, 42, 102, 233, -1, + 42, 29, 102, -1, 42, 233, 284, -1, + 42, 43, 29, -1, 30, 385, 528, -1, + 30, 528, 521, -1, 30, 521, 31, -1, + 30, 107, 385, -1, 30, 31, 107, -1, + 1745, 1746, 1974, -1, 1766, 533, 3060, -1, + 253, 1260, 148, -1, 253, 1262, 1260, -1, + 247, 253, 148, -1, 249, 32, 540, -1, + 249, 255, 32, -1, 118, 122, 123, -1, + 115, 109, 116, -1, 115, 117, 109, -1, + 262, 120, 59, -1, 61, 99, 111, -1, + 61, 111, 117, -1, 61, 117, 262, -1, + 61, 262, 59, -1, 203, 205, 113, -1, + 203, 113, 123, -1, 128, 124, 56, -1, + 128, 56, 33, -1, 128, 33, 127, -1, + 552, 551, 1884, -1, 131, 126, 267, -1, + 256, 655, 34, -1, 256, 34, 255, -1, + 133, 866, 1582, -1, 133, 867, 866, -1, + 562, 136, 139, -1, 562, 597, 136, -1, + 562, 139, 564, -1, 274, 38, 134, -1, + 610, 609, 281, -1, 610, 281, 274, -1, + 1161, 279, 1804, -1, 1188, 488, 587, -1, + 35, 40, 39, -1, 35, 39, 138, -1, + 35, 141, 40, -1, 35, 138, 141, -1, + 36, 37, 38, -1, 36, 566, 39, -1, + 36, 40, 37, -1, 36, 39, 40, -1, + 36, 38, 274, -1, 36, 281, 566, -1, + 36, 274, 281, -1, 278, 594, 603, -1, + 140, 139, 41, -1, 140, 41, 141, -1, + 2367, 1246, 2370, -1, 2367, 612, 1246, -1, + 613, 612, 2367, -1, 613, 2367, 1831, -1, + 331, 1297, 142, -1, 1240, 2370, 1246, -1, + 1240, 2821, 2370, -1, 283, 42, 284, -1, + 283, 282, 43, -1, 283, 43, 42, -1, + 144, 1251, 295, -1, 144, 300, 1251, -1, + 299, 44, 1884, -1, 299, 624, 44, -1, + 264, 265, 1250, -1, 264, 1250, 549, -1, + 623, 658, 45, -1, 623, 46, 624, -1, + 623, 45, 46, -1, 623, 657, 658, -1, + 296, 617, 297, -1, 152, 308, 1266, -1, + 152, 1266, 147, -1, 303, 150, 304, -1, + 303, 149, 150, -1, 303, 324, 149, -1, + 47, 153, 1301, -1, 47, 155, 153, -1, + 47, 1301, 1302, -1, 47, 1302, 155, -1, + 1254, 153, 306, -1, 48, 314, 1272, -1, + 48, 1272, 1211, -1, 48, 631, 314, -1, + 48, 1211, 631, -1, 313, 1883, 1266, -1, + 1265, 1266, 155, -1, 634, 154, 312, -1, + 634, 312, 1213, -1, 634, 1211, 1272, -1, + 634, 1213, 1211, -1, 318, 643, 99, -1, + 158, 149, 324, -1, 158, 148, 149, -1, + 158, 248, 247, -1, 158, 247, 148, -1, + 1296, 325, 49, -1, 1296, 49, 51, -1, + 50, 142, 1297, -1, 50, 51, 142, -1, + 50, 1297, 1296, -1, 50, 1296, 51, -1, + 670, 52, 659, -1, 670, 671, 52, -1, + 327, 545, 53, -1, 327, 53, 54, -1, + 327, 54, 663, -1, 55, 645, 644, -1, + 55, 1884, 645, -1, 55, 644, 318, -1, + 55, 124, 1884, -1, 55, 318, 99, -1, + 55, 56, 124, -1, 55, 60, 56, -1, + 55, 99, 61, -1, 55, 61, 60, -1, + 57, 59, 58, -1, 57, 58, 60, -1, + 57, 61, 59, -1, 57, 60, 61, -1, + 1933, 1936, 1939, -1, 736, 795, 734, -1, + 1360, 734, 795, -1, 62, 807, 806, -1, + 62, 72, 807, -1, 62, 393, 72, -1, + 62, 67, 393, -1, 68, 62, 806, -1, + 68, 67, 62, -1, 1395, 742, 1978, -1, + 1395, 740, 742, -1, 1395, 1978, 1387, -1, + 1395, 1399, 741, -1, 1395, 741, 740, -1, + 175, 741, 1399, -1, 175, 1399, 174, -1, + 364, 746, 2446, -1, 532, 364, 1121, -1, + 532, 746, 364, -1, 64, 163, 757, -1, + 64, 757, 65, -1, 64, 370, 163, -1, + 64, 366, 370, -1, 743, 63, 1978, -1, + 743, 1369, 63, -1, 743, 1978, 742, -1, + 171, 63, 1369, -1, 171, 366, 64, -1, + 171, 65, 63, -1, 171, 64, 65, -1, + 1398, 1379, 1399, -1, 2019, 2020, 172, -1, + 2019, 172, 2018, -1, 2021, 379, 2020, -1, + 772, 176, 1379, -1, 772, 1379, 1974, -1, + 180, 177, 388, -1, 784, 388, 178, -1, + 66, 786, 177, -1, 66, 177, 390, -1, + 66, 390, 786, -1, 794, 394, 67, -1, + 794, 67, 68, -1, 794, 167, 361, -1, + 794, 68, 806, -1, 817, 3053, 399, -1, + 185, 184, 396, -1, 69, 804, 396, -1, + 69, 396, 184, -1, 69, 184, 804, -1, + 1338, 1337, 167, -1, 1338, 184, 705, -1, + 1338, 167, 794, -1, 1338, 794, 184, -1, + 70, 71, 72, -1, 70, 72, 395, -1, + 70, 395, 73, -1, 70, 73, 397, -1, + 70, 397, 71, -1, 1908, 833, 832, -1, + 1908, 1907, 833, -1, 3150, 834, 343, -1, + 76, 74, 195, -1, 76, 78, 75, -1, + 76, 75, 74, -1, 76, 404, 78, -1, + 461, 404, 76, -1, 461, 76, 195, -1, + 406, 77, 78, -1, 406, 407, 77, -1, + 406, 78, 405, -1, 2080, 1457, 2081, -1, + 556, 270, 269, -1, 556, 269, 557, -1, + 421, 89, 418, -1, 449, 408, 872, -1, + 2514, 448, 442, -1, 2514, 442, 2515, -1, + 2514, 409, 448, -1, 958, 191, 962, -1, + 964, 436, 1587, -1, 476, 79, 207, -1, + 476, 91, 79, -1, 80, 83, 85, -1, + 80, 81, 97, -1, 80, 82, 81, -1, + 80, 85, 82, -1, 80, 96, 83, -1, + 80, 97, 96, -1, 467, 83, 978, -1, + 467, 85, 83, -1, 192, 208, 84, -1, + 192, 84, 85, -1, 192, 85, 467, -1, + 86, 89, 194, -1, 86, 87, 89, -1, + 86, 194, 88, -1, 86, 88, 87, -1, + 193, 194, 89, -1, 193, 89, 421, -1, + 193, 420, 463, -1, 193, 421, 420, -1, + 479, 90, 91, -1, 479, 967, 90, -1, + 479, 968, 967, -1, 479, 91, 476, -1, + 198, 93, 92, -1, 198, 188, 93, -1, + 198, 92, 94, -1, 198, 425, 188, -1, + 199, 197, 201, -1, 199, 94, 969, -1, + 199, 198, 94, -1, 199, 1613, 197, -1, + 199, 969, 1613, -1, 95, 197, 875, -1, + 95, 201, 197, -1, 95, 875, 877, -1, + 417, 95, 877, -1, 417, 201, 95, -1, + 994, 210, 1006, -1, 216, 215, 96, -1, + 216, 97, 98, -1, 216, 96, 97, -1, + 216, 98, 217, -1, 492, 485, 491, -1, + 1062, 494, 429, -1, 221, 224, 100, -1, + 221, 156, 222, -1, 1629, 1628, 99, -1, + 1629, 99, 225, -1, 642, 100, 643, -1, + 642, 157, 156, -1, 642, 221, 100, -1, + 642, 156, 221, -1, 1090, 1092, 233, -1, + 503, 285, 513, -1, 503, 513, 510, -1, + 1502, 1093, 102, -1, 1502, 102, 101, -1, + 1498, 102, 1499, -1, 1498, 101, 102, -1, + 1498, 1502, 101, -1, 236, 1499, 102, -1, + 236, 102, 516, -1, 236, 516, 235, -1, + 515, 235, 516, -1, 1098, 1499, 236, -1, + 104, 106, 103, -1, 104, 103, 241, -1, + 1097, 241, 1096, -1, 1097, 104, 241, -1, + 1097, 518, 105, -1, 1097, 1098, 518, -1, + 1097, 105, 106, -1, 1097, 106, 104, -1, + 1102, 1096, 241, -1, 1102, 241, 1117, -1, + 384, 385, 107, -1, 384, 107, 282, -1, + 1109, 521, 528, -1, 240, 242, 530, -1, + 240, 241, 242, -1, 1115, 242, 521, -1, + 243, 528, 2001, -1, 1762, 238, 245, -1, + 246, 1411, 533, -1, 246, 1410, 1411, -1, + 354, 1362, 1361, -1, 354, 1361, 166, -1, + 354, 166, 164, -1, 543, 252, 545, -1, + 535, 253, 247, -1, 254, 255, 249, -1, + 254, 248, 652, -1, 538, 249, 540, -1, + 229, 116, 231, -1, 229, 498, 122, -1, + 110, 111, 227, -1, 110, 109, 117, -1, + 110, 117, 111, -1, 108, 116, 109, -1, + 108, 109, 110, -1, 108, 110, 227, -1, + 108, 227, 230, -1, 108, 231, 116, -1, + 108, 230, 231, -1, 228, 227, 111, -1, + 228, 112, 1628, -1, 228, 111, 112, -1, + 228, 1628, 1630, -1, 260, 113, 259, -1, + 260, 123, 113, -1, 260, 118, 123, -1, + 114, 118, 117, -1, 114, 117, 115, -1, + 114, 115, 116, -1, 114, 122, 118, -1, + 114, 116, 229, -1, 114, 229, 122, -1, + 261, 262, 117, -1, 261, 117, 118, -1, + 261, 118, 260, -1, 258, 259, 119, -1, + 258, 119, 120, -1, 258, 120, 262, -1, + 121, 123, 122, -1, 121, 203, 123, -1, + 121, 122, 498, -1, 121, 218, 203, -1, + 121, 498, 499, -1, 121, 499, 218, -1, + 129, 1884, 124, -1, 129, 124, 128, -1, + 129, 128, 132, -1, 125, 127, 126, -1, + 125, 128, 127, -1, 125, 132, 128, -1, + 125, 126, 131, -1, 125, 131, 132, -1, + 130, 552, 1884, -1, 130, 1884, 129, -1, + 130, 129, 132, -1, 548, 264, 549, -1, + 550, 130, 132, -1, 550, 552, 130, -1, + 263, 131, 267, -1, 263, 132, 131, -1, + 263, 550, 132, -1, 2810, 611, 569, -1, + 1148, 557, 276, -1, 558, 557, 1148, -1, + 558, 1148, 1790, -1, 439, 577, 133, -1, + 439, 133, 1582, -1, 272, 271, 867, -1, + 272, 133, 577, -1, 272, 867, 133, -1, + 272, 577, 579, -1, 868, 867, 271, -1, + 868, 270, 870, -1, 560, 562, 564, -1, + 571, 1233, 1230, -1, 275, 134, 1233, -1, + 275, 274, 134, -1, 275, 1233, 571, -1, + 585, 279, 1161, -1, 584, 587, 488, -1, + 1186, 1161, 1162, -1, 1186, 585, 1161, -1, + 591, 592, 1214, -1, 600, 278, 603, -1, + 601, 602, 135, -1, 601, 136, 597, -1, + 601, 135, 136, -1, 1206, 592, 1199, -1, + 1206, 1214, 592, -1, 137, 138, 139, -1, + 137, 139, 140, -1, 137, 141, 138, -1, + 137, 140, 141, -1, 280, 565, 566, -1, + 280, 566, 281, -1, 1220, 1221, 1153, -1, + 1850, 282, 283, -1, 615, 1232, 288, -1, + 328, 291, 330, -1, 328, 1228, 291, -1, + 2815, 2367, 2370, -1, 293, 142, 612, -1, + 293, 331, 142, -1, 1863, 1247, 1245, -1, + 382, 1247, 1417, -1, 1841, 1857, 1840, -1, + 620, 295, 617, -1, 143, 144, 295, -1, + 143, 295, 621, -1, 143, 621, 144, -1, + 298, 300, 144, -1, 298, 144, 621, -1, + 626, 1872, 146, -1, 626, 146, 551, -1, + 145, 1884, 146, -1, 145, 146, 1872, -1, + 145, 299, 1884, -1, 145, 301, 299, -1, + 145, 1872, 301, -1, 151, 147, 304, -1, + 151, 152, 147, -1, 151, 304, 150, -1, + 151, 150, 310, -1, 309, 148, 1260, -1, + 309, 149, 148, -1, 309, 150, 149, -1, + 309, 310, 150, -1, 307, 151, 310, -1, + 307, 308, 152, -1, 307, 152, 151, -1, + 323, 305, 658, -1, 323, 324, 303, -1, + 1252, 307, 310, -1, 660, 1254, 1256, -1, + 660, 1301, 153, -1, 660, 153, 1254, -1, + 1882, 1883, 313, -1, 635, 154, 634, -1, + 635, 155, 154, -1, 635, 1265, 155, -1, + 1627, 1623, 1278, -1, 321, 643, 318, -1, + 321, 319, 648, -1, 321, 318, 317, -1, + 1277, 1278, 1623, -1, 315, 222, 156, -1, + 315, 3078, 222, -1, 1286, 639, 638, -1, + 2385, 317, 318, -1, 641, 157, 642, -1, + 316, 315, 156, -1, 316, 1288, 315, -1, + 316, 156, 157, -1, 316, 157, 641, -1, + 647, 639, 643, -1, 647, 321, 648, -1, + 647, 643, 321, -1, 322, 319, 321, -1, + 651, 158, 324, -1, 651, 652, 248, -1, + 651, 248, 158, -1, 667, 330, 289, -1, + 667, 159, 671, -1, 667, 289, 159, -1, + 1223, 1224, 1293, -1, 1223, 331, 294, -1, + 1223, 294, 1222, -1, 682, 1912, 341, -1, + 1913, 341, 1912, -1, 333, 161, 2035, -1, + 333, 334, 161, -1, 1914, 340, 1913, -1, + 2045, 2034, 680, -1, 679, 400, 2043, -1, + 694, 693, 336, -1, 342, 834, 1907, -1, + 342, 343, 834, -1, 339, 333, 2035, -1, + 339, 340, 333, -1, 1330, 334, 1332, -1, + 160, 346, 681, -1, 160, 1330, 346, -1, + 160, 334, 1330, -1, 160, 161, 334, -1, + 160, 680, 161, -1, 160, 681, 680, -1, + 1940, 1938, 1332, -1, 1940, 1914, 1939, -1, + 344, 2839, 1317, -1, 2847, 684, 1310, -1, + 2399, 2863, 345, -1, 162, 705, 396, -1, + 162, 2861, 705, -1, 162, 396, 2865, -1, + 162, 2865, 2861, -1, 1355, 1312, 1310, -1, + 1355, 1310, 684, -1, 712, 1334, 2412, -1, + 1333, 1334, 347, -1, 351, 350, 1337, -1, + 713, 347, 710, -1, 713, 710, 729, -1, + 711, 729, 710, -1, 711, 1354, 729, -1, + 732, 1954, 1952, -1, 353, 350, 719, -1, + 353, 1337, 350, -1, 720, 168, 1337, -1, + 720, 352, 168, -1, 355, 163, 370, -1, + 355, 370, 369, -1, 355, 164, 163, -1, + 355, 354, 164, -1, 165, 795, 166, -1, + 165, 1360, 795, -1, 165, 166, 1361, -1, + 165, 1361, 1360, -1, 170, 361, 167, -1, + 170, 168, 169, -1, 170, 167, 1337, -1, + 170, 1337, 168, -1, 358, 169, 352, -1, + 358, 170, 169, -1, 358, 361, 170, -1, + 358, 352, 359, -1, 1383, 752, 359, -1, + 360, 373, 372, -1, 1365, 742, 740, -1, + 1368, 367, 366, -1, 1368, 366, 171, -1, + 1368, 171, 1369, -1, 1122, 1121, 364, -1, + 368, 746, 532, -1, 368, 1127, 369, -1, + 368, 532, 1127, -1, 753, 372, 373, -1, + 759, 1978, 757, -1, 1314, 732, 1952, -1, + 2017, 172, 376, -1, 2017, 2018, 172, -1, + 173, 386, 775, -1, 173, 775, 774, -1, + 173, 174, 386, -1, 173, 774, 741, -1, + 173, 741, 175, -1, 173, 175, 174, -1, + 519, 1855, 1856, -1, 2002, 2001, 528, -1, + 2002, 528, 385, -1, 2461, 2459, 1243, -1, + 780, 386, 176, -1, 780, 176, 772, -1, + 780, 772, 778, -1, 179, 390, 177, -1, + 179, 177, 180, -1, 1436, 784, 178, -1, + 1436, 178, 387, -1, 389, 180, 388, -1, + 389, 1439, 180, -1, 391, 390, 179, -1, + 391, 180, 1439, -1, 391, 179, 180, -1, + 789, 736, 790, -1, 789, 795, 736, -1, + 793, 391, 1439, -1, 793, 797, 391, -1, + 801, 394, 794, -1, 801, 794, 1440, -1, + 181, 795, 794, -1, 181, 794, 361, -1, + 181, 360, 795, -1, 181, 361, 360, -1, + 803, 804, 184, -1, 803, 184, 794, -1, + 803, 794, 806, -1, 1447, 399, 813, -1, + 1447, 1448, 399, -1, 791, 808, 811, -1, + 1450, 811, 808, -1, 1450, 809, 1448, -1, + 182, 399, 815, -1, 182, 815, 817, -1, + 182, 817, 399, -1, 1443, 815, 809, -1, + 704, 818, 2859, -1, 3115, 2859, 818, -1, + 820, 705, 2861, -1, 186, 396, 705, -1, + 183, 705, 184, -1, 183, 184, 185, -1, + 183, 186, 705, -1, 183, 185, 396, -1, + 183, 396, 186, -1, 1492, 824, 2561, -1, + 1492, 2081, 1457, -1, 1492, 1457, 824, -1, + 2033, 3150, 343, -1, 2033, 339, 2035, -1, + 2033, 343, 339, -1, 835, 831, 829, -1, + 2056, 402, 846, -1, 460, 404, 461, -1, + 1487, 406, 405, -1, 1487, 405, 844, -1, + 841, 412, 407, -1, 850, 853, 414, -1, + 849, 846, 402, -1, 849, 850, 846, -1, + 415, 849, 402, -1, 2082, 415, 2080, -1, + 1459, 1457, 2080, -1, 1459, 2080, 415, -1, + 1459, 415, 402, -1, 862, 1087, 856, -1, + 861, 863, 862, -1, 869, 870, 270, -1, + 869, 270, 556, -1, 869, 556, 1140, -1, + 873, 872, 408, -1, 2269, 2271, 895, -1, + 190, 906, 465, -1, 190, 420, 419, -1, + 190, 463, 420, -1, 190, 465, 463, -1, + 422, 187, 189, -1, 422, 1539, 187, -1, + 2125, 427, 2124, -1, 424, 188, 425, -1, + 424, 189, 188, -1, 424, 422, 189, -1, + 424, 1535, 422, -1, 894, 432, 882, -1, + 890, 494, 887, -1, 890, 429, 494, -1, + 495, 887, 494, -1, 885, 888, 887, -1, + 885, 495, 2127, -1, 885, 887, 495, -1, + 891, 1546, 2582, -1, 431, 419, 432, -1, + 431, 190, 419, -1, 431, 430, 906, -1, + 431, 906, 190, -1, 905, 906, 430, -1, + 905, 430, 896, -1, 1685, 2163, 434, -1, + 915, 1481, 1479, -1, 1021, 1027, 1015, -1, + 927, 2622, 2626, -1, 927, 1579, 2622, -1, + 1035, 1174, 1176, -1, 1578, 2623, 2622, -1, + 1578, 2622, 1579, -1, 1471, 2547, 1472, -1, + 2060, 440, 840, -1, 2060, 942, 440, -1, + 443, 442, 447, -1, 443, 447, 946, -1, + 930, 444, 1605, -1, 930, 937, 932, -1, + 930, 1605, 937, -1, 446, 408, 449, -1, + 446, 842, 408, -1, 446, 448, 409, -1, + 446, 409, 842, -1, 944, 946, 447, -1, + 2513, 409, 2514, -1, 954, 453, 455, -1, + 953, 952, 191, -1, 957, 191, 958, -1, + 957, 953, 191, -1, 2234, 2241, 960, -1, + 2234, 960, 958, -1, 2234, 958, 962, -1, + 2234, 962, 2235, -1, 963, 962, 191, -1, + 963, 191, 952, -1, 1591, 964, 1587, -1, + 220, 436, 964, -1, 220, 952, 951, -1, + 220, 963, 952, -1, 220, 964, 963, -1, + 1612, 197, 1613, -1, 472, 208, 192, -1, + 975, 192, 467, -1, 975, 977, 472, -1, + 975, 472, 192, -1, 462, 194, 193, -1, + 462, 195, 194, -1, 462, 461, 195, -1, + 462, 193, 463, -1, 196, 875, 197, -1, + 196, 197, 1612, -1, 196, 1612, 965, -1, + 196, 874, 875, -1, 196, 965, 874, -1, + 200, 425, 198, -1, 200, 199, 201, -1, + 200, 198, 199, -1, 426, 417, 427, -1, + 426, 425, 200, -1, 426, 201, 417, -1, + 426, 200, 201, -1, 202, 203, 218, -1, + 202, 204, 205, -1, 202, 205, 203, -1, + 202, 206, 204, -1, 202, 217, 206, -1, + 202, 218, 217, -1, 466, 471, 211, -1, + 466, 211, 212, -1, 466, 212, 1620, -1, + 466, 1620, 1619, -1, 470, 211, 471, -1, + 470, 1006, 210, -1, 470, 210, 211, -1, + 1011, 604, 2795, -1, 980, 1010, 1009, -1, + 996, 210, 994, -1, 1008, 994, 1006, -1, + 475, 476, 207, -1, 475, 207, 208, -1, + 475, 208, 472, -1, 209, 457, 212, -1, + 209, 210, 996, -1, 209, 211, 210, -1, + 209, 212, 211, -1, 209, 997, 457, -1, + 209, 996, 997, -1, 976, 1620, 212, -1, + 976, 212, 457, -1, 976, 473, 977, -1, + 976, 457, 473, -1, 482, 485, 492, -1, + 2338, 2337, 583, -1, 2338, 481, 2340, -1, + 1633, 1011, 2795, -1, 1001, 481, 482, -1, + 2185, 2187, 2168, -1, 1709, 215, 500, -1, + 1709, 213, 215, -1, 1710, 978, 213, -1, + 1710, 213, 1709, -1, 214, 500, 215, -1, + 214, 215, 216, -1, 214, 216, 217, -1, + 214, 499, 500, -1, 214, 218, 499, -1, + 214, 217, 218, -1, 1017, 1024, 1483, -1, + 1023, 1015, 1027, -1, 1030, 1693, 483, -1, + 1030, 921, 1031, -1, 1030, 483, 921, -1, + 487, 584, 488, -1, 1043, 1044, 491, -1, + 2263, 488, 1188, -1, 490, 970, 973, -1, + 490, 973, 1003, -1, 1189, 576, 219, -1, + 1189, 1190, 576, -1, 493, 219, 949, -1, + 493, 949, 452, -1, 493, 452, 1033, -1, + 493, 1189, 219, -1, 1040, 219, 576, -1, + 950, 949, 219, -1, 950, 1042, 951, -1, + 950, 1040, 1042, -1, 950, 219, 1040, -1, + 1037, 951, 1042, -1, 1037, 1036, 436, -1, + 1037, 436, 220, -1, 1037, 220, 951, -1, + 1045, 971, 1044, -1, 1045, 972, 971, -1, + 1045, 429, 972, -1, 1045, 1062, 429, -1, + 1053, 1048, 1054, -1, 2646, 2645, 224, -1, + 2646, 221, 222, -1, 2646, 224, 221, -1, + 2646, 222, 3077, -1, 223, 224, 2645, -1, + 223, 1629, 225, -1, 223, 2180, 1629, -1, + 223, 2645, 2180, -1, 223, 225, 226, -1, + 223, 226, 224, -1, 496, 230, 227, -1, + 496, 497, 230, -1, 496, 227, 228, -1, + 496, 228, 1630, -1, 1714, 497, 1719, -1, + 1075, 229, 231, -1, 1075, 498, 229, -1, + 1074, 231, 230, -1, 1074, 230, 497, -1, + 1074, 1075, 231, -1, 1074, 497, 1714, -1, + 232, 1086, 507, -1, 232, 503, 1086, -1, + 232, 507, 285, -1, 232, 285, 503, -1, + 502, 503, 510, -1, 505, 507, 1086, -1, + 1077, 507, 1085, -1, 860, 2594, 859, -1, + 860, 2591, 2594, -1, 1496, 233, 1093, -1, + 1496, 1090, 233, -1, 517, 518, 515, -1, + 234, 515, 518, -1, 234, 518, 1098, -1, + 234, 235, 515, -1, 234, 236, 235, -1, + 234, 1098, 236, -1, 1100, 1096, 1102, -1, + 1100, 2592, 2591, -1, 1229, 1840, 1857, -1, + 1429, 1430, 614, -1, 237, 1115, 521, -1, + 237, 524, 1105, -1, 237, 1105, 1115, -1, + 523, 237, 521, -1, 523, 524, 237, -1, + 527, 528, 243, -1, 527, 243, 245, -1, + 1112, 523, 525, -1, 526, 245, 238, -1, + 526, 527, 245, -1, 1111, 1752, 1118, -1, + 1111, 1118, 1112, -1, 1111, 526, 238, -1, + 1111, 238, 1762, -1, 1111, 1762, 1752, -1, + 239, 530, 1117, -1, 239, 240, 530, -1, + 239, 1117, 241, -1, 239, 241, 240, -1, + 529, 530, 242, -1, 529, 242, 1115, -1, + 1114, 1105, 1117, -1, 1114, 1115, 1105, -1, + 2299, 2000, 1746, -1, 2299, 2301, 2000, -1, + 3226, 243, 2001, -1, 3226, 2001, 3225, -1, + 3226, 245, 243, -1, 244, 1762, 245, -1, + 244, 531, 1762, -1, 244, 245, 3226, -1, + 244, 3226, 531, -1, 1103, 1118, 1734, -1, + 1103, 1112, 1118, -1, 1103, 1105, 1112, -1, + 363, 533, 1123, -1, 363, 246, 533, -1, + 363, 1410, 246, -1, 544, 545, 327, -1, + 537, 535, 247, -1, 537, 247, 248, -1, + 537, 248, 254, -1, 537, 254, 249, -1, + 537, 249, 538, -1, 250, 535, 536, -1, + 250, 539, 251, -1, 250, 536, 539, -1, + 250, 251, 252, -1, 250, 252, 543, -1, + 250, 543, 535, -1, 542, 535, 543, -1, + 542, 1262, 253, -1, 542, 253, 535, -1, + 542, 544, 327, -1, 654, 255, 254, -1, + 654, 254, 652, -1, 654, 256, 255, -1, + 654, 655, 256, -1, 257, 259, 258, -1, + 257, 260, 259, -1, 257, 261, 260, -1, + 257, 262, 261, -1, 257, 258, 262, -1, + 266, 263, 267, -1, 266, 550, 263, -1, + 547, 265, 264, -1, 547, 264, 548, -1, + 547, 550, 266, -1, 547, 267, 265, -1, + 547, 266, 267, -1, 554, 1079, 1131, -1, + 554, 1078, 1079, -1, 554, 509, 1078, -1, + 554, 555, 509, -1, 570, 1230, 286, -1, + 570, 286, 555, -1, 1133, 2810, 569, -1, + 1789, 559, 1143, -1, 1789, 2753, 559, -1, + 1771, 1143, 559, -1, 1771, 1786, 1143, -1, + 1142, 558, 1790, -1, 1142, 1790, 1789, -1, + 1142, 1789, 1143, -1, 1142, 1141, 558, -1, + 1175, 438, 1176, -1, 1175, 439, 438, -1, + 1175, 577, 439, -1, 277, 2732, 276, -1, + 277, 276, 269, -1, 268, 271, 572, -1, + 268, 269, 270, -1, 268, 277, 269, -1, + 268, 572, 277, -1, 268, 270, 868, -1, + 268, 868, 271, -1, 573, 572, 271, -1, + 573, 271, 272, -1, 573, 272, 579, -1, + 573, 579, 580, -1, 1145, 560, 564, -1, + 568, 569, 611, -1, 273, 610, 274, -1, + 273, 274, 275, -1, 273, 611, 610, -1, + 273, 568, 611, -1, 273, 275, 571, -1, + 273, 571, 568, -1, 2730, 276, 2732, -1, + 2730, 1148, 276, -1, 2752, 559, 2753, -1, + 1149, 2732, 277, -1, 1149, 277, 572, -1, + 575, 1180, 1170, -1, 1159, 1158, 581, -1, + 486, 583, 584, -1, 486, 584, 487, -1, + 1165, 1181, 1180, -1, 1165, 1180, 575, -1, + 1165, 575, 1166, -1, 1185, 1186, 1162, -1, + 1185, 1162, 1164, -1, 593, 278, 592, -1, + 593, 594, 278, -1, 561, 1197, 597, -1, + 561, 597, 562, -1, 599, 278, 600, -1, + 599, 592, 278, -1, 599, 1199, 592, -1, + 1202, 1206, 1199, -1, 1793, 1214, 1206, -1, + 2341, 2340, 481, -1, 2341, 481, 1001, -1, + 1802, 1801, 279, -1, 1802, 279, 585, -1, + 1802, 586, 1803, -1, 1802, 585, 586, -1, + 2332, 1804, 279, -1, 2332, 279, 1801, -1, + 1216, 993, 992, -1, 1823, 1808, 596, -1, + 607, 606, 2355, -1, 607, 992, 990, -1, + 595, 606, 633, -1, 595, 596, 1808, -1, + 2354, 2355, 606, -1, 2354, 595, 1808, -1, + 2354, 606, 595, -1, 1218, 2638, 2637, -1, + 1826, 565, 280, -1, 1826, 1220, 565, -1, + 1826, 281, 609, -1, 1826, 280, 281, -1, + 1834, 1835, 329, -1, 1834, 329, 676, -1, + 2374, 282, 1850, -1, 2374, 384, 282, -1, + 2374, 614, 384, -1, 1849, 283, 284, -1, + 1849, 1850, 283, -1, 1849, 285, 508, -1, + 1849, 284, 285, -1, 2371, 508, 286, -1, + 2371, 1849, 508, -1, 2829, 286, 1230, -1, + 2829, 2371, 286, -1, 287, 330, 291, -1, + 287, 291, 615, -1, 287, 615, 288, -1, + 287, 289, 330, -1, 287, 290, 289, -1, + 287, 288, 290, -1, 1227, 329, 1835, -1, + 1227, 328, 329, -1, 1227, 1228, 328, -1, + 1227, 1835, 1844, -1, 2377, 615, 291, -1, + 2377, 291, 1228, -1, 1837, 2815, 2370, -1, + 292, 612, 1222, -1, 292, 293, 612, -1, + 292, 1222, 294, -1, 292, 294, 331, -1, + 292, 331, 293, -1, 1860, 1247, 1863, -1, + 1244, 1245, 1247, -1, 1244, 1247, 382, -1, + 1244, 382, 1415, -1, 619, 621, 295, -1, + 619, 295, 620, -1, 656, 617, 296, -1, + 656, 297, 655, -1, 656, 296, 297, -1, + 625, 549, 1250, -1, 625, 626, 549, -1, + 622, 298, 621, -1, 622, 300, 298, -1, + 622, 301, 300, -1, 622, 624, 299, -1, + 622, 299, 301, -1, 1870, 1251, 300, -1, + 1870, 1249, 1251, -1, 1870, 300, 301, -1, + 1870, 301, 1872, -1, 302, 303, 304, -1, + 302, 323, 303, -1, 302, 304, 1266, -1, + 302, 1266, 1884, -1, 302, 1884, 305, -1, + 302, 305, 323, -1, 1253, 1254, 306, -1, + 1253, 307, 1252, -1, 1253, 306, 308, -1, + 1253, 308, 307, -1, 1259, 310, 309, -1, + 1259, 1252, 310, -1, 1259, 309, 1260, -1, + 311, 1213, 312, -1, 311, 1798, 1213, -1, + 311, 312, 1800, -1, 311, 1800, 1798, -1, + 1799, 591, 1214, -1, 1799, 1800, 594, -1, + 1799, 594, 591, -1, 1267, 313, 1266, -1, + 1267, 1882, 313, -1, 636, 1627, 1278, -1, + 636, 1626, 1627, -1, 629, 990, 991, -1, + 1268, 1272, 314, -1, 1268, 1271, 1272, -1, + 1268, 314, 631, -1, 1877, 630, 637, -1, + 1877, 1268, 630, -1, 2176, 1288, 2178, -1, + 2176, 315, 1288, -1, 2176, 3078, 315, -1, + 1287, 1288, 316, -1, 1287, 316, 641, -1, + 2380, 317, 2385, -1, 2380, 321, 317, -1, + 2380, 1886, 321, -1, 1888, 318, 644, -1, + 1888, 2385, 318, -1, 1887, 1276, 638, -1, + 649, 639, 647, -1, 649, 322, 1887, -1, + 649, 638, 639, -1, 649, 1887, 638, -1, + 649, 648, 319, -1, 649, 319, 322, -1, + 320, 321, 1886, -1, 320, 322, 321, -1, + 320, 1886, 1887, -1, 320, 1887, 322, -1, + 653, 324, 323, -1, 653, 651, 324, -1, + 653, 323, 658, -1, 1295, 325, 1296, -1, + 1295, 662, 325, -1, 1893, 660, 1256, -1, + 664, 325, 662, -1, 664, 665, 325, -1, + 326, 327, 663, -1, 326, 663, 662, -1, + 326, 662, 1264, -1, 326, 542, 327, -1, + 326, 1262, 542, -1, 326, 1264, 1262, -1, + 666, 329, 328, -1, 666, 676, 329, -1, + 666, 328, 330, -1, 666, 330, 667, -1, + 1300, 331, 1223, -1, 1300, 1223, 1293, -1, + 1300, 1297, 331, -1, 1292, 674, 1895, -1, + 1292, 1293, 1224, -1, 675, 677, 669, -1, + 675, 669, 674, -1, 332, 340, 1914, -1, + 332, 334, 333, -1, 332, 333, 340, -1, + 332, 1332, 334, -1, 332, 1940, 1332, -1, + 332, 1914, 1940, -1, 688, 689, 679, -1, + 337, 679, 689, -1, 337, 336, 401, -1, + 337, 401, 400, -1, 337, 400, 679, -1, + 687, 346, 701, -1, 687, 681, 346, -1, + 687, 688, 681, -1, 335, 694, 336, -1, + 335, 689, 694, -1, 335, 336, 337, -1, + 335, 337, 689, -1, 1906, 682, 341, -1, + 1906, 341, 342, -1, 1906, 342, 1907, -1, + 338, 340, 339, -1, 338, 341, 1913, -1, + 338, 1913, 340, -1, 338, 342, 341, -1, + 338, 343, 342, -1, 338, 339, 343, -1, + 2024, 3112, 3113, -1, 2838, 2839, 344, -1, + 1307, 1304, 683, -1, 1307, 1912, 682, -1, + 1307, 682, 1304, -1, 1305, 344, 1919, -1, + 1305, 1919, 683, -1, 1305, 683, 1304, -1, + 1305, 2838, 344, -1, 1918, 683, 1919, -1, + 1918, 1932, 1933, -1, 1917, 1317, 1316, -1, + 1917, 344, 1317, -1, 1917, 1919, 344, -1, + 2682, 760, 2394, -1, 2395, 2394, 760, -1, + 2395, 374, 685, -1, 2395, 760, 374, -1, + 691, 700, 695, -1, 696, 692, 695, -1, + 696, 345, 692, -1, 696, 2399, 345, -1, + 2876, 1324, 2875, -1, 1320, 1356, 699, -1, + 1329, 701, 346, -1, 1329, 346, 1330, -1, + 1326, 701, 1329, -1, 706, 699, 1945, -1, + 1318, 2874, 1344, -1, 1318, 704, 2859, -1, + 1318, 1344, 703, -1, 1318, 703, 704, -1, + 1339, 1335, 1333, -1, 1339, 1333, 347, -1, + 1342, 1945, 1946, -1, 1342, 706, 1945, -1, + 1350, 1351, 762, -1, 707, 684, 685, -1, + 707, 1355, 684, -1, 707, 374, 1351, -1, + 707, 685, 374, -1, 707, 1967, 1355, -1, + 1961, 1945, 699, -1, 1961, 699, 1356, -1, + 709, 347, 1334, -1, 709, 1334, 712, -1, + 709, 710, 347, -1, 348, 351, 349, -1, + 1336, 347, 713, -1, 1336, 349, 351, -1, + 1336, 1339, 347, -1, 1336, 351, 1337, -1, + 714, 348, 349, -1, 714, 719, 350, -1, + 714, 349, 1336, -1, 714, 1336, 713, -1, + 714, 350, 351, -1, 714, 351, 348, -1, + 715, 359, 352, -1, 715, 352, 720, -1, + 715, 724, 1383, -1, 715, 1383, 359, -1, + 718, 353, 719, -1, 718, 1337, 353, -1, + 718, 720, 1337, -1, 726, 732, 1314, -1, + 731, 722, 719, -1, 731, 732, 726, -1, + 731, 726, 722, -1, 1126, 1362, 354, -1, + 1126, 354, 355, -1, 1126, 369, 1127, -1, + 1126, 355, 369, -1, 735, 791, 790, -1, + 735, 808, 791, -1, 1359, 734, 1360, -1, + 356, 372, 795, -1, 356, 360, 372, -1, + 356, 795, 360, -1, 357, 358, 359, -1, + 357, 373, 360, -1, 357, 361, 358, -1, + 357, 360, 361, -1, 357, 752, 373, -1, + 357, 359, 752, -1, 1371, 367, 1368, -1, + 1371, 745, 367, -1, 362, 1123, 1122, -1, + 362, 1122, 1410, -1, 362, 363, 1123, -1, + 362, 1410, 363, -1, 2445, 364, 2446, -1, + 2445, 1122, 364, -1, 2445, 1410, 1122, -1, + 2445, 1409, 1410, -1, 747, 746, 368, -1, + 747, 367, 745, -1, 365, 366, 367, -1, + 365, 367, 747, -1, 365, 747, 368, -1, + 365, 368, 369, -1, 365, 370, 366, -1, + 365, 369, 370, -1, 1380, 1974, 1379, -1, + 1377, 1398, 1403, -1, 1972, 3036, 2297, -1, + 1972, 1380, 749, -1, 750, 1635, 2294, -1, + 751, 1313, 1989, -1, 751, 1989, 1988, -1, + 756, 371, 372, -1, 756, 372, 753, -1, + 756, 757, 371, -1, 756, 753, 1386, -1, + 2426, 373, 752, -1, 2426, 753, 373, -1, + 758, 759, 757, -1, 758, 756, 1386, -1, + 1980, 758, 1386, -1, 761, 1351, 374, -1, + 761, 762, 1351, -1, 761, 374, 760, -1, + 1404, 1983, 2190, -1, 1404, 2190, 765, -1, + 2888, 1013, 1637, -1, 2888, 1637, 3130, -1, + 1407, 1395, 1387, -1, 375, 2017, 376, -1, + 375, 1419, 2017, -1, 375, 377, 1419, -1, + 375, 376, 378, -1, 375, 378, 377, -1, + 768, 378, 769, -1, 2004, 377, 378, -1, + 2004, 1419, 377, -1, 2004, 378, 768, -1, + 2004, 768, 2008, -1, 783, 1243, 2459, -1, + 783, 1856, 1243, -1, 783, 519, 1856, -1, + 1416, 379, 2021, -1, 1416, 1417, 380, -1, + 1416, 380, 379, -1, 381, 382, 1417, -1, + 381, 1417, 1415, -1, 381, 1415, 382, -1, + 1242, 1424, 2461, -1, 1242, 2461, 1243, -1, + 383, 385, 384, -1, 383, 1430, 2003, -1, + 383, 384, 614, -1, 383, 614, 1430, -1, + 383, 2002, 385, -1, 383, 2003, 2002, -1, + 1998, 1746, 2000, -1, 1425, 781, 779, -1, + 782, 1428, 519, -1, 782, 519, 783, -1, + 777, 775, 386, -1, 777, 386, 780, -1, + 777, 1423, 775, -1, 777, 2013, 1423, -1, + 2012, 779, 781, -1, 798, 387, 799, -1, + 798, 1436, 387, -1, 1438, 793, 1439, -1, + 1438, 1440, 794, -1, 1438, 794, 793, -1, + 1435, 388, 784, -1, 1435, 389, 388, -1, + 1435, 1439, 389, -1, 788, 785, 390, -1, + 788, 390, 391, -1, 788, 391, 797, -1, + 796, 795, 789, -1, 800, 799, 392, -1, + 800, 393, 394, -1, 800, 394, 801, -1, + 800, 392, 395, -1, 800, 395, 393, -1, + 805, 397, 396, -1, 805, 396, 804, -1, + 805, 807, 397, -1, 398, 809, 815, -1, + 398, 1448, 809, -1, 398, 815, 399, -1, + 398, 399, 1448, -1, 1445, 808, 735, -1, + 1445, 735, 737, -1, 1445, 737, 1444, -1, + 810, 1447, 813, -1, 821, 704, 705, -1, + 821, 818, 704, -1, 821, 705, 820, -1, + 1306, 1908, 832, -1, 1306, 832, 2474, -1, + 825, 826, 822, -1, 825, 2561, 824, -1, + 2911, 1306, 2474, -1, 1452, 826, 2030, -1, + 1452, 822, 826, -1, 1456, 824, 1457, -1, + 2029, 2030, 826, -1, 1461, 829, 828, -1, + 1461, 2482, 829, -1, 2042, 400, 401, -1, + 2042, 401, 831, -1, 2042, 2043, 400, -1, + 2560, 822, 2935, -1, 2560, 2561, 825, -1, + 2560, 825, 822, -1, 2487, 832, 833, -1, + 1460, 402, 2056, -1, 1460, 1459, 402, -1, + 2057, 1473, 1460, -1, 2057, 1460, 2056, -1, + 403, 404, 460, -1, 403, 844, 405, -1, + 403, 405, 404, -1, 403, 416, 844, -1, + 403, 433, 416, -1, 403, 460, 433, -1, + 1489, 406, 1487, -1, 1489, 407, 406, -1, + 1489, 841, 407, -1, 843, 844, 416, -1, + 843, 408, 842, -1, 843, 873, 408, -1, + 843, 416, 873, -1, 1488, 842, 409, -1, + 1488, 2513, 1491, -1, 1488, 409, 2513, -1, + 837, 836, 410, -1, 837, 410, 411, -1, + 837, 411, 1478, -1, 838, 841, 1476, -1, + 838, 1478, 411, -1, 838, 411, 412, -1, + 838, 412, 841, -1, 845, 846, 850, -1, + 845, 413, 847, -1, 845, 414, 413, -1, + 845, 850, 414, -1, 852, 854, 828, -1, + 852, 829, 853, -1, 852, 828, 829, -1, + 851, 849, 415, -1, 851, 854, 852, -1, + 851, 2082, 854, -1, 851, 415, 2082, -1, + 2920, 3144, 3145, -1, 2920, 3145, 1474, -1, + 2920, 1474, 2521, -1, 857, 2145, 861, -1, + 857, 859, 2594, -1, 857, 2593, 2145, -1, + 857, 2594, 2593, -1, 1505, 2140, 2138, -1, + 1508, 1512, 1506, -1, 1508, 1505, 2138, -1, + 1508, 1506, 1505, -1, 864, 863, 1507, -1, + 1726, 1081, 1511, -1, 1515, 1514, 1775, -1, + 1774, 1515, 1775, -1, 1528, 869, 1140, -1, + 871, 416, 433, -1, 871, 873, 416, -1, + 871, 433, 902, -1, 871, 902, 903, -1, + 2107, 417, 877, -1, 2107, 427, 417, -1, + 2107, 2124, 427, -1, 880, 876, 1050, -1, + 880, 1530, 876, -1, 880, 1529, 1530, -1, + 881, 432, 419, -1, 881, 419, 1532, -1, + 881, 882, 432, -1, 1534, 418, 1537, -1, + 1534, 421, 418, -1, 1533, 419, 420, -1, + 1533, 1532, 419, -1, 1533, 420, 421, -1, + 1533, 421, 1534, -1, 1538, 1539, 422, -1, + 1538, 422, 1535, -1, 423, 424, 425, -1, + 423, 425, 426, -1, 423, 426, 427, -1, + 423, 427, 2125, -1, 423, 2125, 1535, -1, + 423, 1535, 424, -1, 428, 429, 890, -1, + 428, 1048, 1053, -1, 428, 889, 1048, -1, + 428, 890, 889, -1, 428, 972, 429, -1, + 428, 1053, 972, -1, 2126, 885, 2127, -1, + 883, 954, 455, -1, 883, 1066, 954, -1, + 883, 455, 454, -1, 883, 454, 2577, -1, + 1542, 1545, 888, -1, 1544, 888, 1545, -1, + 2581, 891, 2582, -1, 893, 896, 430, -1, + 893, 431, 432, -1, 893, 430, 431, -1, + 893, 432, 894, -1, 464, 902, 433, -1, + 464, 433, 460, -1, 909, 465, 906, -1, + 909, 464, 465, -1, 909, 902, 464, -1, + 1572, 2968, 2162, -1, 2970, 2162, 2968, -1, + 435, 1521, 912, -1, 435, 434, 2095, -1, + 435, 2095, 2094, -1, 435, 2094, 1521, -1, + 2161, 434, 2163, -1, 2161, 2095, 434, -1, + 2161, 2970, 2095, -1, 2161, 2162, 2970, -1, + 1686, 2163, 1685, -1, 911, 1685, 434, -1, + 911, 435, 912, -1, 911, 434, 435, -1, + 911, 1684, 1685, -1, 1689, 1687, 1564, -1, + 2160, 1032, 1557, -1, 916, 840, 440, -1, + 916, 440, 934, -1, 914, 1481, 915, -1, + 914, 1018, 1481, -1, 914, 918, 1018, -1, + 914, 931, 918, -1, 839, 915, 1479, -1, + 839, 2534, 840, -1, 839, 840, 916, -1, + 839, 916, 915, -1, 917, 931, 932, -1, + 917, 918, 931, -1, 1571, 1021, 1570, -1, + 920, 1570, 1021, -1, 920, 1567, 1570, -1, + 920, 1021, 1015, -1, 2619, 1686, 1028, -1, + 2619, 2163, 1686, -1, 925, 2621, 2623, -1, + 1586, 1579, 927, -1, 1568, 1566, 1594, -1, + 1568, 927, 2626, -1, 1014, 1595, 1594, -1, + 1014, 1594, 1566, -1, 437, 438, 1585, -1, + 437, 1036, 1035, -1, 437, 1176, 438, -1, + 437, 1035, 1176, -1, 1583, 436, 1036, -1, + 1583, 1036, 437, -1, 1583, 437, 1585, -1, + 1583, 1587, 436, -1, 1581, 1585, 438, -1, + 1581, 439, 1582, -1, 1581, 438, 439, -1, + 941, 934, 440, -1, 941, 440, 942, -1, + 929, 945, 444, -1, 929, 444, 930, -1, + 929, 934, 941, -1, 929, 941, 945, -1, + 2059, 2547, 1471, -1, 441, 443, 2061, -1, + 441, 2061, 2059, -1, 441, 2059, 1471, -1, + 441, 1471, 2515, -1, 441, 2515, 442, -1, + 441, 442, 443, -1, 2062, 2061, 443, -1, + 2062, 942, 2060, -1, 2062, 946, 942, -1, + 2062, 443, 946, -1, 935, 2241, 2240, -1, + 935, 960, 2241, -1, 935, 1598, 960, -1, + 1602, 937, 1605, -1, 1600, 454, 1599, -1, + 1600, 2577, 454, -1, 451, 444, 945, -1, + 451, 901, 939, -1, 1606, 1605, 444, -1, + 1606, 444, 451, -1, 1606, 451, 939, -1, + 445, 446, 449, -1, 445, 944, 447, -1, + 445, 447, 448, -1, 445, 448, 446, -1, + 445, 449, 450, -1, 445, 450, 944, -1, + 900, 449, 872, -1, 900, 450, 449, -1, + 900, 872, 899, -1, 900, 901, 450, -1, + 943, 450, 901, -1, 943, 901, 451, -1, + 943, 451, 945, -1, 943, 944, 450, -1, + 948, 452, 949, -1, 948, 453, 452, -1, + 955, 453, 954, -1, 955, 452, 453, -1, + 955, 1033, 452, -1, 456, 953, 957, -1, + 456, 455, 453, -1, 456, 453, 948, -1, + 456, 948, 953, -1, 959, 454, 455, -1, + 959, 455, 456, -1, 959, 456, 957, -1, + 959, 1599, 454, -1, 1590, 1595, 2233, -1, + 1590, 2233, 2235, -1, 2273, 965, 1612, -1, + 458, 997, 1610, -1, 458, 477, 473, -1, + 458, 457, 997, -1, 458, 473, 457, -1, + 1609, 968, 477, -1, 1609, 477, 458, -1, + 1609, 458, 1610, -1, 1611, 1615, 2273, -1, + 1611, 2273, 1612, -1, 1058, 973, 970, -1, + 2169, 2168, 2187, -1, 459, 460, 461, -1, + 459, 461, 462, -1, 459, 462, 463, -1, + 459, 464, 460, -1, 459, 463, 465, -1, + 459, 465, 464, -1, 966, 874, 965, -1, + 966, 2274, 1050, -1, 966, 1050, 876, -1, + 966, 876, 874, -1, 981, 988, 471, -1, + 981, 471, 466, -1, 981, 466, 1619, -1, + 1618, 975, 467, -1, 1618, 467, 978, -1, + 979, 1011, 1010, -1, 979, 604, 1011, -1, + 468, 2278, 2786, -1, 468, 984, 2278, -1, + 468, 2786, 2785, -1, 468, 2785, 604, -1, + 468, 604, 979, -1, 468, 979, 984, -1, + 986, 988, 981, -1, 2179, 1623, 1627, -1, + 1005, 980, 1009, -1, 1005, 1006, 470, -1, + 469, 470, 471, -1, 469, 471, 988, -1, + 469, 988, 980, -1, 469, 1005, 470, -1, + 469, 980, 1005, -1, 998, 996, 994, -1, + 998, 2175, 1615, -1, 478, 472, 977, -1, + 478, 977, 473, -1, 478, 475, 472, -1, + 478, 473, 477, -1, 474, 476, 475, -1, + 474, 477, 968, -1, 474, 478, 477, -1, + 474, 475, 478, -1, 474, 968, 479, -1, + 474, 479, 476, -1, 480, 482, 481, -1, + 480, 2338, 583, -1, 480, 481, 2338, -1, + 480, 583, 486, -1, 480, 485, 482, -1, + 480, 486, 485, -1, 1002, 1001, 482, -1, + 1002, 482, 492, -1, 1002, 490, 1003, -1, + 1002, 492, 490, -1, 2186, 1003, 973, -1, + 2183, 1003, 2186, -1, 1007, 2185, 2168, -1, + 1007, 2168, 2167, -1, 1007, 2167, 1008, -1, + 1634, 2185, 1007, -1, 1740, 1637, 1013, -1, + 1740, 1013, 2657, -1, 1649, 1391, 1652, -1, + 1982, 1652, 1391, -1, 1656, 1654, 2228, -1, + 1669, 920, 1015, -1, 1670, 1671, 2238, -1, + 1019, 1018, 918, -1, 1019, 2238, 1671, -1, + 1672, 1024, 1017, -1, 1480, 1481, 1018, -1, + 1025, 1020, 921, -1, 1025, 483, 1677, -1, + 1025, 921, 483, -1, 2243, 483, 1693, -1, + 2243, 1677, 483, -1, 1680, 1023, 1027, -1, + 1029, 922, 1028, -1, 1029, 1031, 922, -1, + 2247, 1693, 1030, -1, 484, 487, 1046, -1, + 484, 1043, 491, -1, 484, 1046, 1043, -1, + 484, 491, 485, -1, 484, 485, 486, -1, + 484, 486, 487, -1, 1696, 487, 488, -1, + 1696, 488, 2263, -1, 1696, 1046, 487, -1, + 1034, 1070, 1694, -1, 1034, 1033, 955, -1, + 489, 970, 490, -1, 489, 491, 1044, -1, + 489, 492, 491, -1, 489, 490, 492, -1, + 489, 1044, 971, -1, 489, 971, 970, -1, + 2260, 493, 1033, -1, 2260, 1189, 493, -1, + 1039, 1040, 576, -1, 1039, 575, 1170, -1, + 1169, 1174, 1035, -1, 1064, 1043, 1046, -1, + 1549, 1048, 889, -1, 1549, 889, 1544, -1, + 1049, 1705, 1704, -1, 1049, 1548, 1697, -1, + 1049, 1697, 1705, -1, 1055, 1054, 1704, -1, + 1061, 494, 1062, -1, 1061, 495, 494, -1, + 1060, 1694, 1070, -1, 1060, 1070, 1069, -1, + 1067, 2128, 2127, -1, 1067, 2127, 495, -1, + 1067, 495, 1061, -1, 1067, 1061, 1069, -1, + 1720, 496, 1630, -1, 1720, 497, 496, -1, + 1720, 1719, 497, -1, 1716, 1709, 500, -1, + 1711, 1071, 1621, -1, 1722, 2277, 1072, -1, + 1073, 499, 498, -1, 1073, 498, 1075, -1, + 1073, 500, 499, -1, 1073, 1716, 500, -1, + 511, 510, 513, -1, 511, 513, 512, -1, + 501, 510, 1086, -1, 501, 502, 510, -1, + 501, 1086, 503, -1, 501, 503, 502, -1, + 504, 1085, 507, -1, 504, 507, 505, -1, + 504, 1086, 1085, -1, 504, 505, 1086, -1, + 1080, 1084, 1081, -1, 1083, 1511, 1081, -1, + 1083, 1081, 1084, -1, 1083, 864, 1511, -1, + 506, 508, 507, -1, 506, 507, 1077, -1, + 506, 509, 508, -1, 506, 1078, 509, -1, + 506, 1077, 1078, -1, 1091, 856, 510, -1, + 1091, 858, 856, -1, 1091, 1496, 858, -1, + 1091, 510, 511, -1, 1091, 511, 512, -1, + 1091, 513, 1092, -1, 1091, 512, 513, -1, + 1500, 1093, 1502, -1, 514, 515, 516, -1, + 514, 517, 515, -1, 514, 516, 518, -1, + 514, 518, 517, -1, 1095, 2591, 860, -1, + 1095, 1100, 2591, -1, 1095, 1096, 1100, -1, + 1095, 860, 1501, -1, 1732, 1103, 1734, -1, + 1106, 1857, 1855, -1, 1106, 1229, 1857, -1, + 1106, 1855, 519, -1, 1106, 519, 1428, -1, + 520, 1109, 525, -1, 520, 525, 523, -1, + 520, 521, 1109, -1, 520, 523, 521, -1, + 522, 524, 523, -1, 522, 523, 1112, -1, + 522, 1105, 524, -1, 522, 1112, 1105, -1, + 1108, 525, 1109, -1, 1108, 1112, 525, -1, + 1110, 526, 1111, -1, 1110, 527, 526, -1, + 1110, 1109, 528, -1, 1110, 528, 527, -1, + 1116, 529, 1115, -1, 1116, 1117, 530, -1, + 1116, 530, 529, -1, 2223, 1664, 2222, -1, + 2223, 2221, 2283, -1, 2281, 1664, 2223, -1, + 2281, 2223, 2283, -1, 2284, 1639, 2282, -1, + 2284, 1737, 1639, -1, 2202, 1639, 1737, -1, + 2295, 2294, 1635, -1, 3039, 1743, 2300, -1, + 1099, 1757, 2972, -1, 1099, 2972, 2971, -1, + 2600, 2972, 1757, -1, 1753, 1099, 1733, -1, + 1753, 1757, 1099, -1, 1761, 1752, 1762, -1, + 2303, 1999, 2000, -1, 1763, 1762, 531, -1, + 1763, 531, 3226, -1, 1760, 1749, 1755, -1, + 1128, 1764, 1125, -1, 1128, 1127, 532, -1, + 1128, 532, 1121, -1, 1128, 1121, 1764, -1, + 2313, 1123, 533, -1, 2313, 533, 1766, -1, + 2309, 1125, 1764, -1, 2309, 738, 1125, -1, + 2310, 1444, 738, -1, 2310, 738, 2309, -1, + 1363, 1125, 738, -1, 534, 536, 535, -1, + 534, 535, 537, -1, 534, 537, 538, -1, + 534, 539, 536, -1, 534, 540, 539, -1, + 534, 538, 540, -1, 541, 542, 543, -1, + 541, 544, 542, -1, 541, 543, 545, -1, + 541, 545, 544, -1, 546, 547, 548, -1, + 546, 548, 549, -1, 546, 550, 547, -1, + 546, 626, 551, -1, 546, 549, 626, -1, + 546, 551, 552, -1, 546, 552, 550, -1, + 1132, 1131, 1079, -1, 1132, 1079, 1080, -1, + 1135, 1729, 1136, -1, 1135, 1730, 1729, -1, + 553, 554, 1131, -1, 553, 569, 570, -1, + 553, 555, 554, -1, 553, 570, 555, -1, + 553, 1131, 1133, -1, 553, 1133, 569, -1, + 2812, 1135, 1136, -1, 1770, 1775, 1514, -1, + 1784, 2091, 1787, -1, 1784, 2092, 2091, -1, + 1139, 1140, 556, -1, 1139, 556, 557, -1, + 1139, 557, 558, -1, 1139, 558, 1141, -1, + 1767, 1771, 559, -1, 1767, 559, 2752, -1, + 1778, 1768, 1137, -1, 1778, 1137, 1779, -1, + 1144, 1145, 565, -1, 1144, 565, 1220, -1, + 1144, 1220, 1153, -1, 1144, 1153, 2318, -1, + 1146, 560, 1145, -1, 1146, 1197, 561, -1, + 1146, 562, 560, -1, 1146, 561, 562, -1, + 563, 1145, 564, -1, 563, 565, 1145, -1, + 563, 564, 566, -1, 563, 566, 565, -1, + 567, 569, 568, -1, 567, 1230, 570, -1, + 567, 570, 569, -1, 567, 571, 1230, -1, + 567, 568, 571, -1, 2315, 2327, 2324, -1, + 2315, 2324, 1151, -1, 1155, 1221, 1137, -1, + 1155, 1137, 1768, -1, 1155, 1153, 1221, -1, + 2349, 1164, 1162, -1, 1168, 1181, 1165, -1, + 1157, 581, 1158, -1, 1157, 1156, 580, -1, + 574, 580, 1156, -1, 574, 1149, 572, -1, + 574, 573, 580, -1, 574, 572, 573, -1, + 1150, 1156, 2328, -1, 1150, 1149, 574, -1, + 1150, 574, 1156, -1, 589, 1166, 575, -1, + 589, 575, 1039, -1, 589, 576, 1190, -1, + 589, 1039, 576, -1, 1183, 2320, 1159, -1, + 1172, 579, 577, -1, 1172, 577, 1175, -1, + 1179, 581, 1173, -1, 1179, 1159, 581, -1, + 1179, 1183, 1159, -1, 578, 580, 579, -1, + 578, 1173, 581, -1, 578, 579, 1172, -1, + 578, 1172, 1173, -1, 578, 1157, 580, -1, + 578, 581, 1157, -1, 1178, 1179, 1173, -1, + 582, 2337, 1803, -1, 582, 1803, 586, -1, + 582, 583, 2337, -1, 582, 586, 587, -1, + 582, 584, 583, -1, 582, 587, 584, -1, + 1187, 585, 1186, -1, 1187, 586, 585, -1, + 1187, 587, 586, -1, 1187, 1188, 587, -1, + 2264, 2263, 1188, -1, 588, 1191, 1185, -1, + 588, 1166, 589, -1, 588, 1164, 1166, -1, + 588, 1185, 1164, -1, 588, 1190, 1191, -1, + 588, 589, 1190, -1, 590, 592, 591, -1, + 590, 593, 592, -1, 590, 591, 594, -1, + 590, 594, 593, -1, 1193, 1825, 1823, -1, + 1193, 1823, 596, -1, 632, 596, 595, -1, + 632, 595, 633, -1, 632, 1193, 596, -1, + 632, 1212, 1193, -1, 632, 631, 1212, -1, + 1210, 631, 1211, -1, 1210, 1212, 631, -1, + 1201, 1199, 599, -1, 1201, 599, 601, -1, + 1201, 601, 597, -1, 1201, 597, 1197, -1, + 598, 599, 600, -1, 598, 601, 599, -1, + 598, 602, 601, -1, 598, 603, 602, -1, + 598, 600, 603, -1, 1203, 1202, 1199, -1, + 1203, 1200, 1816, -1, 1204, 1821, 1825, -1, + 1207, 1795, 1793, -1, 1792, 1211, 1213, -1, + 2796, 604, 2785, -1, 2796, 2795, 604, -1, + 2331, 1804, 2332, -1, 2331, 2334, 2330, -1, + 608, 1216, 992, -1, 608, 992, 607, -1, + 608, 607, 2355, -1, 608, 2355, 2357, -1, + 1215, 993, 1216, -1, 1215, 2762, 2641, -1, + 605, 633, 606, -1, 605, 629, 633, -1, + 605, 990, 629, -1, 605, 606, 607, -1, + 605, 607, 990, -1, 1217, 1216, 608, -1, + 1217, 608, 2357, -1, 1217, 2357, 2755, -1, + 1217, 2755, 3067, -1, 1805, 2329, 2638, -1, + 1805, 2638, 1218, -1, 1805, 1218, 1806, -1, + 2760, 1218, 2637, -1, 1809, 1219, 1151, -1, + 1809, 1151, 2324, -1, 1809, 2324, 2754, -1, + 2809, 1826, 609, -1, 2809, 609, 610, -1, + 2809, 610, 611, -1, 2809, 611, 2810, -1, + 1830, 1222, 612, -1, 1830, 612, 613, -1, + 1830, 613, 1831, -1, 2365, 1225, 1828, -1, + 2373, 1429, 614, -1, 2373, 614, 2374, -1, + 2373, 2375, 1429, -1, 2376, 2377, 1228, -1, + 1846, 3094, 2376, -1, 2378, 1232, 615, -1, + 2378, 615, 2377, -1, 1241, 1246, 1235, -1, + 1854, 1244, 1415, -1, 1867, 1236, 1866, -1, + 1248, 1235, 1246, -1, 616, 620, 617, -1, + 616, 617, 656, -1, 616, 657, 620, -1, + 616, 656, 657, -1, 618, 619, 620, -1, + 618, 621, 619, -1, 618, 622, 621, -1, + 618, 657, 623, -1, 618, 620, 657, -1, + 618, 623, 624, -1, 618, 624, 622, -1, + 1871, 625, 1250, -1, 1871, 1872, 626, -1, + 1871, 626, 625, -1, 1261, 1252, 1259, -1, + 627, 637, 630, -1, 627, 636, 637, -1, + 627, 1626, 636, -1, 627, 630, 629, -1, + 627, 991, 1626, -1, 627, 629, 991, -1, + 628, 629, 630, -1, 628, 1268, 631, -1, + 628, 630, 1268, -1, 628, 631, 632, -1, + 628, 633, 629, -1, 628, 632, 633, -1, + 1270, 634, 1272, -1, 1270, 635, 634, -1, + 1270, 1265, 635, -1, 1273, 1874, 1875, -1, + 1624, 1277, 1623, -1, 1275, 636, 1278, -1, + 1275, 637, 636, -1, 1280, 1273, 1875, -1, + 1280, 1281, 1273, -1, 1280, 1275, 1282, -1, + 1280, 1875, 1877, -1, 1280, 1877, 637, -1, + 1280, 637, 1275, -1, 2388, 2389, 1282, -1, + 2388, 1282, 2387, -1, 1283, 1286, 638, -1, + 1283, 638, 1276, -1, 1283, 1276, 1277, -1, + 1283, 1277, 1624, -1, 1285, 639, 1286, -1, + 1285, 643, 639, -1, 640, 1287, 641, -1, + 640, 642, 643, -1, 640, 641, 642, -1, + 640, 643, 1285, -1, 640, 1285, 1287, -1, + 1880, 644, 645, -1, 1880, 1888, 644, -1, + 1880, 645, 1884, -1, 1889, 1888, 1880, -1, + 2382, 1276, 1887, -1, 2382, 2387, 1282, -1, + 646, 647, 648, -1, 646, 648, 649, -1, + 646, 649, 647, -1, 650, 652, 651, -1, + 650, 651, 653, -1, 650, 655, 654, -1, + 650, 654, 652, -1, 650, 656, 655, -1, + 650, 657, 656, -1, 650, 658, 657, -1, + 650, 653, 658, -1, 1299, 1300, 1293, -1, + 1290, 662, 1295, -1, 1290, 1264, 662, -1, + 1290, 1291, 1263, -1, 1290, 1263, 1264, -1, + 1903, 669, 1902, -1, 1903, 1895, 674, -1, + 1903, 674, 669, -1, 1901, 670, 659, -1, + 1901, 1902, 670, -1, 1901, 659, 1303, -1, + 1899, 1301, 660, -1, 1899, 660, 1893, -1, + 1892, 1291, 1894, -1, 1892, 1893, 1256, -1, + 661, 662, 663, -1, 661, 664, 662, -1, + 661, 663, 665, -1, 661, 665, 664, -1, + 672, 677, 676, -1, 672, 676, 666, -1, + 672, 666, 667, -1, 672, 667, 671, -1, + 668, 1902, 669, -1, 668, 671, 670, -1, + 668, 670, 1902, -1, 668, 672, 671, -1, + 668, 669, 677, -1, 668, 677, 672, -1, + 673, 674, 1292, -1, 673, 675, 674, -1, + 673, 1292, 1224, -1, 673, 1225, 675, -1, + 673, 1224, 1828, -1, 673, 1828, 1225, -1, + 1226, 675, 1225, -1, 1226, 1834, 676, -1, + 1226, 676, 677, -1, 1226, 677, 675, -1, + 678, 688, 679, -1, 678, 2045, 680, -1, + 678, 680, 681, -1, 678, 681, 688, -1, + 678, 2043, 2045, -1, 678, 679, 2043, -1, + 1909, 1304, 682, -1, 1909, 682, 1906, -1, + 1308, 1307, 683, -1, 1308, 683, 1918, -1, + 1308, 1918, 1933, -1, 1311, 1316, 1922, -1, + 2883, 2884, 2676, -1, 1956, 1989, 1313, -1, + 2846, 684, 2847, -1, 2846, 685, 684, -1, + 2846, 2395, 685, -1, 702, 700, 691, -1, + 702, 687, 701, -1, 686, 691, 694, -1, + 686, 688, 687, -1, 686, 687, 702, -1, + 686, 702, 691, -1, 686, 694, 689, -1, + 686, 689, 688, -1, 690, 691, 695, -1, + 690, 695, 692, -1, 690, 692, 693, -1, + 690, 693, 694, -1, 690, 694, 691, -1, + 3121, 2870, 1323, -1, 2864, 2861, 2865, -1, + 697, 1323, 2870, -1, 697, 696, 695, -1, + 697, 695, 700, -1, 697, 700, 1323, -1, + 2868, 2399, 696, -1, 2868, 697, 2870, -1, + 2868, 696, 697, -1, 1319, 2875, 1324, -1, + 698, 1320, 699, -1, 698, 2873, 2875, -1, + 698, 2875, 1319, -1, 698, 1319, 1320, -1, + 698, 706, 2873, -1, 698, 699, 706, -1, + 1935, 1356, 1320, -1, 1322, 1323, 700, -1, + 1322, 701, 1326, -1, 1322, 702, 701, -1, + 1322, 700, 702, -1, 1325, 2876, 3123, -1, + 1325, 1324, 2876, -1, 1328, 1319, 1324, -1, + 1345, 703, 1344, -1, 1345, 704, 703, -1, + 1345, 705, 704, -1, 1345, 1338, 705, -1, + 2405, 1333, 1335, -1, 2405, 1335, 2404, -1, + 1341, 1342, 1946, -1, 1343, 1344, 2874, -1, + 1343, 706, 1342, -1, 1343, 2874, 2873, -1, + 1343, 2873, 706, -1, 1353, 2410, 2408, -1, + 1353, 711, 2410, -1, 1353, 1354, 711, -1, + 763, 1390, 1350, -1, 763, 1350, 762, -1, + 763, 762, 1389, -1, 1949, 1347, 1950, -1, + 1348, 1349, 1350, -1, 1348, 1949, 1349, -1, + 1348, 1347, 1949, -1, 1348, 1350, 1390, -1, + 2423, 707, 1351, -1, 2423, 1967, 707, -1, + 1352, 2422, 2421, -1, 1352, 2408, 2422, -1, + 1352, 1353, 2408, -1, 1929, 1312, 1355, -1, + 1929, 1932, 1312, -1, 708, 710, 709, -1, + 708, 711, 710, -1, 708, 712, 2412, -1, + 708, 709, 712, -1, 708, 2412, 2410, -1, + 708, 2410, 711, -1, 730, 713, 729, -1, + 730, 714, 713, -1, 730, 719, 714, -1, + 730, 731, 719, -1, 716, 720, 721, -1, + 716, 715, 720, -1, 716, 721, 722, -1, + 723, 724, 715, -1, 723, 716, 722, -1, + 723, 715, 716, -1, 717, 718, 719, -1, + 717, 720, 718, -1, 717, 721, 720, -1, + 717, 722, 721, -1, 717, 719, 722, -1, + 727, 722, 726, -1, 727, 723, 722, -1, + 727, 1976, 1382, -1, 727, 724, 723, -1, + 727, 1383, 724, -1, 727, 1382, 1383, -1, + 725, 726, 1314, -1, 725, 751, 1976, -1, + 725, 1976, 727, -1, 725, 727, 726, -1, + 725, 1314, 1313, -1, 725, 1313, 751, -1, + 728, 729, 1354, -1, 728, 730, 729, -1, + 728, 731, 730, -1, 728, 732, 731, -1, + 728, 1354, 1954, -1, 728, 1954, 732, -1, + 733, 734, 1359, -1, 733, 735, 790, -1, + 733, 737, 735, -1, 733, 1359, 737, -1, + 733, 790, 736, -1, 733, 736, 734, -1, + 1358, 1444, 737, -1, 1358, 737, 1359, -1, + 1358, 738, 1444, -1, 1358, 1363, 738, -1, + 739, 1366, 1365, -1, 739, 740, 741, -1, + 739, 1365, 740, -1, 739, 741, 774, -1, + 739, 774, 1364, -1, 739, 1364, 1366, -1, + 1370, 742, 1365, -1, 1370, 743, 742, -1, + 1370, 1369, 743, -1, 1373, 2010, 770, -1, + 1373, 770, 745, -1, 1373, 1371, 1375, -1, + 1373, 745, 1371, -1, 744, 745, 770, -1, + 744, 2446, 746, -1, 744, 2441, 2446, -1, + 744, 770, 2441, -1, 744, 746, 747, -1, + 744, 747, 745, -1, 1378, 1380, 1379, -1, + 1378, 749, 1380, -1, 1378, 1377, 749, -1, + 767, 749, 1377, -1, 767, 1635, 750, -1, + 766, 1635, 767, -1, 1971, 1745, 1974, -1, + 1971, 2297, 1745, -1, 1971, 1972, 2297, -1, + 748, 1972, 749, -1, 748, 749, 767, -1, + 748, 767, 750, -1, 748, 750, 2294, -1, + 748, 2294, 2293, -1, 748, 3036, 1972, -1, + 748, 2293, 3036, -1, 2191, 765, 2190, -1, + 2191, 1635, 766, -1, 754, 1384, 1406, -1, + 754, 1406, 1405, -1, 2428, 1976, 751, -1, + 2428, 1406, 1384, -1, 2428, 1988, 1406, -1, + 2428, 751, 1988, -1, 1975, 2426, 752, -1, + 1975, 752, 1383, -1, 1385, 1386, 753, -1, + 1385, 753, 2426, -1, 1385, 1384, 754, -1, + 1385, 754, 1405, -1, 755, 757, 756, -1, + 755, 758, 757, -1, 755, 756, 758, -1, + 1979, 759, 758, -1, 1979, 758, 1980, -1, + 1979, 1978, 759, -1, 1388, 760, 2682, -1, + 1388, 761, 760, -1, 1388, 762, 761, -1, + 1388, 1389, 762, -1, 2397, 1389, 2679, -1, + 2397, 1390, 763, -1, 2397, 763, 1389, -1, + 764, 1404, 765, -1, 764, 765, 2191, -1, + 764, 1377, 1403, -1, 764, 1403, 1404, -1, + 764, 2191, 766, -1, 764, 767, 1377, -1, + 764, 766, 767, -1, 3194, 2883, 2676, -1, + 2429, 1013, 2888, -1, 1394, 1407, 1993, -1, + 1992, 1394, 1993, -1, 1992, 1402, 1394, -1, + 3276, 2652, 3275, -1, 2438, 2196, 2429, -1, + 1995, 768, 769, -1, 1995, 2008, 768, -1, + 1995, 769, 2005, -1, 1408, 2005, 769, -1, + 1408, 769, 1411, -1, 1408, 1411, 1412, -1, + 2009, 770, 2010, -1, 2009, 2441, 770, -1, + 1414, 1416, 2021, -1, 1414, 2021, 1424, -1, + 1414, 1424, 1242, -1, 1414, 1242, 1854, -1, + 1414, 1854, 1415, -1, 1418, 779, 778, -1, + 1418, 1425, 779, -1, 771, 1746, 1998, -1, + 771, 778, 772, -1, 771, 1418, 778, -1, + 771, 1998, 1418, -1, 771, 1974, 1746, -1, + 771, 772, 1974, -1, 773, 2452, 1364, -1, + 773, 774, 775, -1, 773, 1364, 774, -1, + 773, 775, 1423, -1, 773, 1423, 2453, -1, + 773, 2453, 2452, -1, 2898, 2017, 1419, -1, + 2457, 2461, 1424, -1, 1427, 781, 1425, -1, + 1427, 782, 781, -1, 1427, 1428, 782, -1, + 776, 2013, 777, -1, 776, 778, 779, -1, + 776, 780, 778, -1, 776, 777, 780, -1, + 776, 779, 2012, -1, 776, 2012, 2013, -1, + 2014, 2012, 781, -1, 2014, 781, 782, -1, + 2014, 783, 2459, -1, 2014, 782, 783, -1, + 1434, 784, 1436, -1, 1434, 1435, 784, -1, + 812, 785, 788, -1, 812, 788, 811, -1, + 812, 813, 786, -1, 812, 786, 785, -1, + 787, 788, 797, -1, 787, 797, 796, -1, + 787, 796, 789, -1, 787, 789, 790, -1, + 787, 790, 791, -1, 787, 791, 811, -1, + 787, 811, 788, -1, 792, 793, 794, -1, + 792, 794, 795, -1, 792, 795, 796, -1, + 792, 797, 793, -1, 792, 796, 797, -1, + 1437, 1436, 798, -1, 1437, 798, 799, -1, + 1437, 799, 800, -1, 1437, 801, 1440, -1, + 1437, 800, 801, -1, 802, 804, 803, -1, + 802, 805, 804, -1, 802, 803, 806, -1, + 802, 806, 807, -1, 802, 807, 805, -1, + 1442, 1450, 808, -1, 1442, 808, 1445, -1, + 1442, 809, 1450, -1, 1442, 1443, 809, -1, + 1449, 1447, 810, -1, 1449, 811, 1450, -1, + 1449, 812, 811, -1, 1449, 810, 813, -1, + 1449, 813, 812, -1, 814, 815, 1443, -1, + 814, 1443, 816, -1, 814, 817, 815, -1, + 814, 816, 817, -1, 3055, 1443, 3051, -1, + 3055, 816, 1443, -1, 3055, 3053, 817, -1, + 3055, 817, 816, -1, 819, 3115, 818, -1, + 819, 818, 821, -1, 3116, 3115, 819, -1, + 3116, 819, 821, -1, 2860, 820, 2861, -1, + 2860, 821, 820, -1, 2860, 3116, 821, -1, + 2393, 1306, 2911, -1, 2912, 2842, 2393, -1, + 2912, 2393, 2911, -1, 2026, 1452, 2030, -1, + 1453, 2935, 822, -1, 1453, 822, 1452, -1, + 3137, 2026, 2030, -1, 3137, 2027, 2026, -1, + 1458, 827, 1456, -1, 1458, 1474, 3145, -1, + 1458, 1473, 1474, -1, 823, 827, 2029, -1, + 823, 824, 1456, -1, 823, 1456, 827, -1, + 823, 825, 824, -1, 823, 826, 825, -1, + 823, 2029, 826, -1, 3143, 2029, 827, -1, + 3143, 1458, 3145, -1, 3143, 827, 1458, -1, + 1462, 828, 854, -1, 1462, 1461, 828, -1, + 830, 835, 829, -1, 830, 829, 2482, -1, + 830, 2482, 2481, -1, 1493, 2046, 835, -1, + 1493, 835, 830, -1, 1493, 830, 2481, -1, + 2038, 831, 2039, -1, 2038, 2042, 831, -1, + 2041, 2034, 2045, -1, 1463, 831, 835, -1, + 1463, 2039, 831, -1, 1454, 2487, 2488, -1, + 1454, 2488, 2940, -1, 1454, 2474, 832, -1, + 1454, 832, 2487, -1, 3149, 2487, 833, -1, + 3149, 833, 834, -1, 3149, 834, 3150, -1, + 1464, 835, 2046, -1, 1464, 1463, 835, -1, + 2203, 2833, 1466, -1, 2832, 1466, 2833, -1, + 2832, 1468, 1466, -1, 2053, 1472, 2054, -1, + 2512, 1491, 2513, -1, 2512, 2509, 1491, -1, + 1477, 2529, 847, -1, 1477, 847, 836, -1, + 1477, 836, 837, -1, 1477, 837, 1478, -1, + 2058, 838, 1476, -1, 2058, 1478, 838, -1, + 2546, 2054, 1472, -1, 2546, 1472, 2547, -1, + 2066, 1017, 1483, -1, 2066, 1480, 1017, -1, + 2533, 2065, 2532, -1, 2533, 1479, 2065, -1, + 2533, 839, 1479, -1, 2533, 2534, 839, -1, + 2536, 2060, 840, -1, 2536, 840, 2534, -1, + 1482, 1679, 1674, -1, 2077, 2532, 2065, -1, + 2558, 1674, 2688, -1, 2558, 1482, 1674, -1, + 2557, 2685, 2075, -1, 2557, 2075, 2076, -1, + 1490, 841, 1489, -1, 1490, 1476, 841, -1, + 1490, 1491, 2509, -1, 1490, 2509, 1476, -1, + 1486, 842, 1488, -1, 1486, 844, 843, -1, + 1486, 843, 842, -1, 1486, 1487, 844, -1, + 2055, 846, 845, -1, 2055, 2056, 846, -1, + 2055, 847, 2529, -1, 2055, 845, 847, -1, + 848, 850, 849, -1, 848, 849, 851, -1, + 848, 851, 852, -1, 848, 853, 850, -1, + 848, 852, 853, -1, 2079, 2032, 1462, -1, + 2079, 854, 2082, -1, 2079, 1462, 854, -1, + 855, 861, 862, -1, 855, 862, 856, -1, + 855, 856, 858, -1, 855, 858, 859, -1, + 855, 859, 857, -1, 855, 857, 861, -1, + 1495, 858, 1496, -1, 1495, 859, 858, -1, + 1495, 860, 859, -1, 1495, 1501, 860, -1, + 1504, 861, 2145, -1, 1504, 2145, 2144, -1, + 1504, 863, 861, -1, 1504, 1507, 863, -1, + 2141, 2140, 1505, -1, 2085, 1508, 2138, -1, + 2085, 2138, 2587, -1, 1088, 862, 863, -1, + 1088, 863, 864, -1, 1088, 1087, 862, -1, + 1088, 864, 1083, -1, 1510, 864, 1507, -1, + 1510, 1506, 1512, -1, 1510, 1507, 1506, -1, + 1510, 1511, 864, -1, 1727, 1516, 1517, -1, + 1727, 1517, 1728, -1, 1130, 1515, 1774, -1, + 1130, 1728, 1517, -1, 1130, 1517, 1518, -1, + 1130, 1518, 1515, -1, 2963, 2087, 3173, -1, + 1580, 1582, 866, -1, 1580, 866, 926, -1, + 865, 926, 866, -1, 865, 1525, 926, -1, + 865, 870, 1525, -1, 865, 866, 867, -1, + 865, 867, 868, -1, 865, 868, 870, -1, + 1524, 926, 1525, -1, 1524, 1523, 925, -1, + 2102, 1528, 1140, -1, 1526, 870, 869, -1, + 1526, 869, 1528, -1, 1526, 1525, 870, -1, + 1526, 1528, 1527, -1, 897, 871, 903, -1, + 897, 899, 872, -1, 897, 872, 873, -1, + 897, 873, 871, -1, 878, 875, 874, -1, + 878, 874, 876, -1, 878, 877, 875, -1, + 878, 876, 1530, -1, 2106, 2107, 877, -1, + 2106, 877, 878, -1, 2106, 878, 1530, -1, + 1051, 880, 1050, -1, 1051, 2269, 895, -1, + 879, 1529, 880, -1, 879, 895, 894, -1, + 879, 1051, 895, -1, 879, 880, 1051, -1, + 879, 894, 882, -1, 879, 882, 1529, -1, + 2270, 2111, 2271, -1, 2114, 1698, 891, -1, + 2114, 891, 2581, -1, 1531, 881, 1532, -1, + 1531, 1532, 2122, -1, 1531, 882, 881, -1, + 1531, 1529, 882, -1, 2120, 1534, 1537, -1, + 1540, 2164, 1553, -1, 1540, 1553, 1541, -1, + 2578, 883, 2577, -1, 2578, 2128, 1066, -1, + 2578, 1066, 883, -1, 884, 1542, 888, -1, + 884, 888, 885, -1, 884, 885, 2126, -1, + 884, 2126, 1540, -1, 884, 1541, 1542, -1, + 884, 1540, 1541, -1, 2129, 1546, 1545, -1, + 2129, 1545, 1542, -1, 2129, 2582, 1546, -1, + 886, 887, 888, -1, 886, 888, 1544, -1, + 886, 1544, 889, -1, 886, 889, 890, -1, + 886, 890, 887, -1, 1547, 1698, 1697, -1, + 1547, 1697, 1548, -1, 1547, 891, 1698, -1, + 1547, 1546, 891, -1, 892, 2111, 896, -1, + 892, 893, 894, -1, 892, 896, 893, -1, + 892, 894, 895, -1, 892, 895, 2271, -1, + 892, 2271, 2111, -1, 2112, 896, 2111, -1, + 2112, 2116, 907, -1, 2112, 907, 905, -1, + 2112, 905, 896, -1, 1554, 1552, 899, -1, + 1554, 903, 2133, -1, 1554, 897, 903, -1, + 1554, 899, 897, -1, 1551, 938, 1552, -1, + 1551, 2166, 938, -1, 1551, 1553, 2164, -1, + 1551, 2164, 2166, -1, 898, 899, 1552, -1, + 898, 901, 900, -1, 898, 900, 899, -1, + 898, 939, 901, -1, 898, 938, 939, -1, + 898, 1552, 938, -1, 908, 903, 902, -1, + 908, 902, 909, -1, 908, 2133, 903, -1, + 908, 2132, 2133, -1, 2117, 2584, 2132, -1, + 2117, 907, 2116, -1, 904, 906, 905, -1, + 904, 905, 907, -1, 904, 2132, 908, -1, + 904, 907, 2117, -1, 904, 2117, 2132, -1, + 904, 909, 906, -1, 904, 908, 909, -1, + 910, 1557, 1032, -1, 910, 913, 1557, -1, + 910, 1032, 1684, -1, 910, 912, 913, -1, + 910, 1684, 911, -1, 910, 911, 912, -1, + 1555, 1556, 913, -1, 1555, 1521, 2098, -1, + 1555, 912, 1521, -1, 1555, 913, 912, -1, + 2137, 1556, 2136, -1, 2137, 1557, 913, -1, + 2137, 913, 1556, -1, 3316, 2136, 1556, -1, + 1574, 925, 1523, -1, 1574, 2621, 925, -1, + 1559, 1523, 1560, -1, 1559, 1574, 1523, -1, + 1559, 1572, 1573, -1, 1559, 1573, 1574, -1, + 2219, 1660, 2154, -1, 2219, 2154, 2150, -1, + 2981, 2147, 2704, -1, 2981, 2982, 2147, -1, + 2984, 2158, 2982, -1, 1563, 2607, 2608, -1, + 1563, 2157, 2607, -1, 1565, 1564, 1687, -1, + 1565, 1032, 2160, -1, 933, 914, 915, -1, + 933, 916, 934, -1, 933, 915, 916, -1, + 933, 931, 914, -1, 936, 2240, 917, -1, + 936, 935, 2240, -1, 936, 932, 937, -1, + 936, 917, 932, -1, 2239, 917, 2240, -1, + 2239, 2238, 1019, -1, 2239, 918, 917, -1, + 2239, 1019, 918, -1, 919, 1567, 920, -1, + 919, 1673, 1014, -1, 919, 1669, 1673, -1, + 919, 920, 1669, -1, 919, 1566, 1567, -1, + 919, 1014, 1566, -1, 923, 1031, 921, -1, + 923, 922, 1031, -1, 923, 921, 1020, -1, + 923, 1575, 922, -1, 2620, 2619, 1028, -1, + 2620, 1028, 922, -1, 2620, 922, 1575, -1, + 2628, 1570, 1567, -1, 1569, 2635, 1575, -1, + 1569, 1575, 923, -1, 1569, 1020, 1571, -1, + 1569, 923, 1020, -1, 924, 2623, 1578, -1, + 924, 925, 2623, -1, 924, 1524, 925, -1, + 924, 1578, 1580, -1, 924, 1580, 926, -1, + 924, 926, 1524, -1, 1584, 1579, 1586, -1, + 1584, 1585, 1581, -1, 1593, 1586, 927, -1, + 1593, 927, 1568, -1, 1593, 1568, 1594, -1, + 928, 929, 930, -1, 928, 932, 931, -1, + 928, 930, 932, -1, 928, 931, 933, -1, + 928, 934, 929, -1, 928, 933, 934, -1, + 1597, 1598, 935, -1, 1597, 935, 936, -1, + 1597, 937, 1602, -1, 1597, 936, 937, -1, + 1604, 938, 2166, -1, 1604, 939, 938, -1, + 1604, 1606, 939, -1, 1604, 2166, 2165, -1, + 940, 941, 942, -1, 940, 944, 943, -1, + 940, 945, 941, -1, 940, 943, 945, -1, + 940, 942, 946, -1, 940, 946, 944, -1, + 947, 948, 949, -1, 947, 949, 950, -1, + 947, 950, 951, -1, 947, 951, 952, -1, + 947, 952, 953, -1, 947, 953, 948, -1, + 1068, 954, 1066, -1, 1068, 955, 954, -1, + 1068, 1070, 1034, -1, 1068, 1034, 955, -1, + 956, 957, 958, -1, 956, 959, 957, -1, + 956, 1599, 959, -1, 956, 958, 960, -1, + 956, 1598, 1599, -1, 956, 960, 1598, -1, + 961, 2235, 962, -1, 961, 1590, 2235, -1, + 961, 1591, 1590, -1, 961, 962, 963, -1, + 961, 963, 964, -1, 961, 964, 1591, -1, + 2272, 965, 2273, -1, 2272, 2274, 966, -1, + 2272, 966, 965, -1, 1608, 967, 968, -1, + 1608, 968, 1609, -1, 1608, 1613, 969, -1, + 1608, 969, 967, -1, 1056, 970, 971, -1, + 1056, 1058, 970, -1, 1056, 971, 972, -1, + 1056, 972, 1053, -1, 974, 2169, 2187, -1, + 974, 2186, 973, -1, 974, 2187, 2186, -1, + 974, 973, 1058, -1, 1057, 2173, 2169, -1, + 1057, 1055, 2173, -1, 1057, 974, 1058, -1, + 1057, 2169, 974, -1, 1622, 975, 1618, -1, + 1622, 1620, 976, -1, 1622, 977, 975, -1, + 1622, 976, 977, -1, 1617, 1618, 978, -1, + 1617, 978, 1710, -1, 1617, 1711, 1621, -1, + 1617, 1710, 1711, -1, 987, 984, 979, -1, + 987, 979, 1010, -1, 987, 980, 988, -1, + 987, 1010, 980, -1, 982, 1621, 1071, -1, + 982, 986, 981, -1, 982, 1619, 1621, -1, + 982, 981, 1619, -1, 985, 1071, 1072, -1, + 985, 982, 1071, -1, 985, 986, 982, -1, + 985, 2277, 2278, -1, 985, 1072, 2277, -1, + 983, 2278, 984, -1, 983, 985, 2278, -1, + 983, 986, 985, -1, 983, 984, 987, -1, + 983, 988, 986, -1, 983, 987, 988, -1, + 2769, 991, 2636, -1, 2769, 1626, 991, -1, + 989, 991, 990, -1, 989, 2636, 991, -1, + 989, 990, 992, -1, 989, 992, 993, -1, + 989, 993, 2636, -1, 2640, 2636, 993, -1, + 2640, 1215, 2641, -1, 2640, 993, 1215, -1, + 1614, 998, 994, -1, 1614, 1008, 2167, -1, + 1614, 994, 1008, -1, 1614, 2175, 998, -1, + 995, 997, 996, -1, 995, 996, 998, -1, + 995, 1610, 997, -1, 995, 998, 1615, -1, + 995, 1615, 1611, -1, 995, 1611, 1610, -1, + 2794, 2793, 1012, -1, 2794, 1633, 2795, -1, + 1000, 2339, 2341, -1, 1000, 2793, 2339, -1, + 1000, 1012, 2793, -1, 1000, 2341, 1001, -1, + 999, 2183, 1012, -1, 999, 1012, 1000, -1, + 999, 1000, 1001, -1, 999, 1001, 1002, -1, + 999, 1002, 1003, -1, 999, 1003, 2183, -1, + 1004, 1005, 1009, -1, 1004, 1009, 1634, -1, + 1004, 1006, 1005, -1, 1004, 1634, 1007, -1, + 1004, 1008, 1006, -1, 1004, 1007, 1008, -1, + 1632, 1634, 1009, -1, 1632, 1009, 1010, -1, + 1632, 1010, 1011, -1, 1632, 1011, 1633, -1, + 2182, 2794, 1012, -1, 2182, 1633, 2794, -1, + 2182, 1012, 2183, -1, 2659, 2657, 1013, -1, + 2659, 1013, 2429, -1, 2659, 2429, 2196, -1, + 1655, 2671, 2214, -1, 1655, 1658, 1638, -1, + 2999, 2203, 1644, -1, 1648, 1656, 1651, -1, + 1648, 1654, 1656, -1, 1646, 1644, 1647, -1, + 1646, 1649, 1652, -1, 1650, 1391, 1649, -1, + 1650, 1648, 1651, -1, 1650, 1649, 1648, -1, + 2651, 1391, 1650, -1, 2206, 1647, 2207, -1, + 1467, 2207, 1647, -1, 1467, 2203, 1466, -1, + 1467, 1647, 1644, -1, 1467, 1644, 2203, -1, + 2213, 1651, 1656, -1, 1659, 2282, 1639, -1, + 1659, 1638, 1658, -1, 1661, 1561, 1660, -1, + 1661, 2494, 1561, -1, 1661, 2225, 2494, -1, + 1661, 1665, 2225, -1, 2224, 2225, 1665, -1, + 1666, 1673, 1670, -1, 1666, 1014, 1673, -1, + 1666, 2233, 1595, -1, 1666, 1595, 1014, -1, + 1668, 1023, 1024, -1, 1668, 1024, 1672, -1, + 1668, 1015, 1023, -1, 1668, 1669, 1015, -1, + 1016, 1672, 1017, -1, 1016, 1480, 1018, -1, + 1016, 1017, 1480, -1, 1016, 1018, 1019, -1, + 1016, 1019, 1671, -1, 1016, 1671, 1672, -1, + 1026, 1020, 1025, -1, 1026, 1027, 1021, -1, + 1026, 1571, 1020, -1, 1026, 1021, 1571, -1, + 2244, 1677, 2243, -1, 1022, 1023, 1680, -1, + 1022, 1483, 1024, -1, 1022, 1024, 1023, -1, + 1022, 1482, 1483, -1, 1022, 1680, 1679, -1, + 1022, 1679, 1482, -1, 1676, 1025, 1677, -1, + 1676, 1026, 1025, -1, 1676, 1680, 1027, -1, + 1676, 1027, 1026, -1, 1682, 1028, 1686, -1, + 1682, 1029, 1028, -1, 1682, 2249, 1029, -1, + 1682, 1688, 2249, -1, 2250, 1029, 2249, -1, + 2250, 2247, 1030, -1, 2250, 1030, 1031, -1, + 2250, 1031, 1029, -1, 1683, 1687, 1688, -1, + 1683, 1565, 1687, -1, 1683, 1032, 1565, -1, + 1683, 1684, 1032, -1, 2493, 1561, 2494, -1, + 2493, 1690, 1561, -1, 2256, 2153, 1690, -1, + 2256, 2255, 2153, -1, 2254, 2243, 1693, -1, + 2259, 2260, 1033, -1, 2259, 1033, 1034, -1, + 2259, 1034, 1694, -1, 1041, 1169, 1035, -1, + 1041, 1035, 1036, -1, 1041, 1036, 1037, -1, + 1041, 1037, 1042, -1, 1038, 1039, 1170, -1, + 1038, 1170, 1169, -1, 1038, 1040, 1039, -1, + 1038, 1169, 1041, -1, 1038, 1042, 1040, -1, + 1038, 1041, 1042, -1, 1063, 1044, 1043, -1, + 1063, 1043, 1064, -1, 1063, 1045, 1044, -1, + 1063, 1062, 1045, -1, 1695, 1046, 1696, -1, + 1695, 1064, 1046, -1, 1695, 1694, 1060, -1, + 1695, 1060, 1064, -1, 1047, 1048, 1549, -1, + 1047, 1054, 1048, -1, 1047, 1549, 1548, -1, + 1047, 1548, 1049, -1, 1047, 1704, 1054, -1, + 1047, 1049, 1704, -1, 1700, 3023, 1707, -1, + 1700, 2267, 3023, -1, 1703, 1050, 2274, -1, + 1703, 2274, 2697, -1, 1703, 1051, 1050, -1, + 1703, 2269, 1051, -1, 2172, 1055, 1704, -1, + 2172, 2173, 1055, -1, 1052, 1053, 1054, -1, + 1052, 1054, 1055, -1, 1052, 1056, 1053, -1, + 1052, 1055, 1057, -1, 1052, 1058, 1056, -1, + 1052, 1057, 1058, -1, 1059, 1060, 1069, -1, + 1059, 1061, 1062, -1, 1059, 1069, 1061, -1, + 1059, 1062, 1063, -1, 1059, 1064, 1060, -1, + 1059, 1063, 1064, -1, 1065, 1066, 2128, -1, + 1065, 2128, 1067, -1, 1065, 1068, 1066, -1, + 1065, 1067, 1069, -1, 1065, 1069, 1070, -1, + 1065, 1070, 1068, -1, 1718, 1072, 1071, -1, + 1718, 1071, 1711, -1, 1713, 1714, 1719, -1, + 1713, 1719, 1722, -1, 1713, 1722, 1072, -1, + 1713, 1072, 1718, -1, 1715, 1716, 1073, -1, + 1715, 1074, 1714, -1, 1715, 1075, 1074, -1, + 1715, 1073, 1075, -1, 1076, 1077, 1085, -1, + 1076, 1085, 1084, -1, 1076, 1084, 1080, -1, + 1076, 1078, 1077, -1, 1076, 1079, 1078, -1, + 1076, 1080, 1079, -1, 1725, 1730, 1132, -1, + 1725, 1132, 1080, -1, 1725, 1081, 1726, -1, + 1725, 1080, 1081, -1, 1082, 1083, 1084, -1, + 1082, 1085, 1086, -1, 1082, 1084, 1085, -1, + 1082, 1086, 1087, -1, 1082, 1087, 1088, -1, + 1082, 1088, 1083, -1, 1089, 1090, 1496, -1, + 1089, 1496, 1091, -1, 1089, 1092, 1090, -1, + 1089, 1091, 1092, -1, 1497, 1496, 1093, -1, + 1497, 1093, 1500, -1, 1094, 1096, 1095, -1, + 1094, 1097, 1096, -1, 1094, 1098, 1097, -1, + 1094, 1095, 1501, -1, 1094, 1499, 1098, -1, + 1094, 1501, 1499, -1, 2602, 1733, 1099, -1, + 2602, 1099, 2971, -1, 1104, 1732, 2139, -1, + 1104, 1100, 1102, -1, 1104, 2592, 1100, -1, + 1104, 2139, 2592, -1, 1101, 1102, 1117, -1, + 1101, 1103, 1732, -1, 1101, 1104, 1102, -1, + 1101, 1732, 1104, -1, 1101, 1117, 1105, -1, + 1101, 1105, 1103, -1, 1432, 1429, 2375, -1, + 1432, 2375, 1229, -1, 1432, 1229, 1106, -1, + 1432, 1106, 1428, -1, 1107, 1108, 1109, -1, + 1107, 1109, 1110, -1, 1107, 1110, 1111, -1, + 1107, 1111, 1112, -1, 1107, 1112, 1108, -1, + 1113, 1115, 1114, -1, 1113, 1116, 1115, -1, + 1113, 1114, 1117, -1, 1113, 1117, 1116, -1, + 2699, 2283, 2221, -1, 2699, 2221, 2605, -1, + 1735, 3041, 3040, -1, 1735, 1760, 3041, -1, + 1735, 1736, 1749, -1, 1735, 1749, 1760, -1, + 2307, 2287, 1736, -1, 2291, 1742, 2290, -1, + 2292, 3029, 3028, -1, 2706, 2712, 3219, -1, + 2706, 3219, 3220, -1, 2656, 2199, 1743, -1, + 2656, 2658, 2199, -1, 2198, 1737, 1742, -1, + 2198, 2202, 1737, -1, 2719, 2301, 2299, -1, + 1751, 1734, 1118, -1, 1751, 1118, 1752, -1, + 1751, 1733, 1734, -1, 1751, 1753, 1733, -1, + 1756, 1757, 1753, -1, 2726, 1758, 1761, -1, + 2302, 2000, 2301, -1, 2302, 2303, 2000, -1, + 1119, 2724, 3329, -1, 1119, 1999, 2303, -1, + 1119, 2303, 2724, -1, 1119, 1120, 1999, -1, + 1119, 3329, 1120, -1, 3223, 1120, 3329, -1, + 3223, 2001, 1999, -1, 3223, 1999, 1120, -1, + 1759, 1760, 1755, -1, 1759, 1756, 1758, -1, + 1765, 1764, 1121, -1, 1765, 1121, 1122, -1, + 1765, 1122, 1123, -1, 1765, 1123, 2313, -1, + 1124, 1125, 1363, -1, 1124, 1126, 1127, -1, + 1124, 1362, 1126, -1, 1124, 1363, 1362, -1, + 1124, 1127, 1128, -1, 1124, 1128, 1125, -1, + 1129, 1777, 1136, -1, 1129, 1136, 1729, -1, + 1129, 1774, 1777, -1, 1129, 1729, 1728, -1, + 1129, 1728, 1130, -1, 1129, 1130, 1774, -1, + 1134, 1133, 1131, -1, 1134, 1131, 1132, -1, + 1134, 1132, 1730, -1, 1134, 1730, 1135, -1, + 2811, 2810, 1133, -1, 2811, 1133, 1134, -1, + 2811, 1135, 2812, -1, 2811, 1134, 1135, -1, + 2362, 2812, 1136, -1, 2362, 1136, 1777, -1, + 2362, 1777, 1779, -1, 2361, 1137, 1221, -1, + 2361, 1779, 1137, -1, 2361, 2362, 1779, -1, + 1776, 1775, 1770, -1, 1138, 1784, 1785, -1, + 1138, 1770, 1514, -1, 1138, 1785, 1770, -1, + 1138, 1514, 1520, -1, 1138, 2092, 1784, -1, + 1138, 1520, 2092, -1, 1780, 1139, 1141, -1, + 1780, 1141, 1783, -1, 1780, 1140, 1139, -1, + 1780, 2102, 1140, -1, 1782, 1783, 1141, -1, + 1782, 1141, 1142, -1, 1782, 1143, 1786, -1, + 1782, 1142, 1143, -1, 1147, 1145, 1144, -1, + 1147, 1146, 1145, -1, 1147, 2318, 2738, -1, + 1147, 1144, 2318, -1, 1195, 1197, 1146, -1, + 1195, 1146, 1147, -1, 1195, 2738, 2741, -1, + 1195, 1147, 2738, -1, 2316, 2315, 1151, -1, + 2735, 2730, 2733, -1, 2735, 1790, 1148, -1, + 2735, 1148, 2730, -1, 2729, 2732, 1149, -1, + 2729, 1149, 1150, -1, 2326, 1150, 2328, -1, + 2326, 2729, 1150, -1, 1152, 1788, 2744, -1, + 1152, 2316, 1151, -1, 1152, 2744, 2316, -1, + 1152, 1151, 1219, -1, 1810, 1812, 1788, -1, + 1810, 1219, 1811, -1, 1810, 1152, 1219, -1, + 1810, 1788, 1152, -1, 1813, 1788, 1812, -1, + 1813, 2740, 2739, -1, 2317, 2318, 1153, -1, + 2317, 1153, 1155, -1, 1154, 2752, 2749, -1, + 1154, 1155, 1768, -1, 1154, 2317, 1155, -1, + 1154, 2749, 2317, -1, 1154, 1768, 1767, -1, + 1154, 1767, 2752, -1, 1160, 1158, 2765, -1, + 1160, 2328, 1156, -1, 1160, 1157, 1158, -1, + 1160, 1156, 1157, -1, 2319, 2765, 1158, -1, + 2319, 1158, 1159, -1, 2319, 1159, 2320, -1, + 2764, 2328, 1160, -1, 2764, 1160, 2765, -1, + 2350, 1161, 1804, -1, 2350, 1162, 1161, -1, + 2350, 2349, 1162, -1, 1807, 1806, 2321, -1, + 1807, 1168, 2348, -1, 1163, 2349, 2348, -1, + 1163, 2348, 1168, -1, 1163, 1164, 2349, -1, + 1163, 1168, 1165, -1, 1163, 1166, 1164, -1, + 1163, 1165, 1166, -1, 1167, 2320, 1183, -1, + 1167, 1168, 1807, -1, 1167, 1181, 1168, -1, + 1167, 1183, 1181, -1, 1167, 2321, 2320, -1, + 1167, 1807, 2321, -1, 1182, 1178, 1174, -1, + 1182, 1174, 1169, -1, 1182, 1169, 1170, -1, + 1182, 1170, 1180, -1, 1171, 1173, 1172, -1, + 1171, 1178, 1173, -1, 1171, 1174, 1178, -1, + 1171, 1172, 1175, -1, 1171, 1176, 1174, -1, + 1171, 1175, 1176, -1, 1177, 1179, 1178, -1, + 1177, 1180, 1181, -1, 1177, 1182, 1180, -1, + 1177, 1178, 1182, -1, 1177, 1181, 1183, -1, + 1177, 1183, 1179, -1, 1184, 1186, 1185, -1, + 1184, 1187, 1186, -1, 1184, 1188, 1187, -1, + 1184, 1185, 1191, -1, 1184, 2264, 1188, -1, + 1184, 1191, 2264, -1, 2262, 1190, 1189, -1, + 2262, 1189, 2260, -1, 2262, 1191, 1190, -1, + 2262, 2264, 1191, -1, 1192, 1212, 1795, -1, + 1192, 1193, 1212, -1, 1192, 1825, 1193, -1, + 1192, 1204, 1825, -1, 1192, 1795, 1204, -1, + 1815, 2741, 2740, -1, 1194, 1200, 1197, -1, + 1194, 1816, 1200, -1, 1194, 1815, 1816, -1, + 1194, 1197, 1195, -1, 1194, 1195, 2741, -1, + 1194, 2741, 1815, -1, 1196, 1197, 1200, -1, + 1196, 1201, 1197, -1, 1196, 1200, 1201, -1, + 1198, 1203, 1199, -1, 1198, 1200, 1203, -1, + 1198, 1199, 1201, -1, 1198, 1201, 1200, -1, + 1818, 1821, 1204, -1, 1818, 1203, 1816, -1, + 1208, 1206, 1202, -1, 1208, 1202, 1203, -1, + 1208, 1204, 1795, -1, 1208, 1795, 1207, -1, + 1208, 1203, 1818, -1, 1208, 1818, 1204, -1, + 1205, 1793, 1206, -1, 1205, 1207, 1793, -1, + 1205, 1206, 1208, -1, 1205, 1208, 1207, -1, + 1209, 1212, 1210, -1, 1209, 1792, 1212, -1, + 1209, 1210, 1211, -1, 1209, 1211, 1792, -1, + 1794, 1795, 1212, -1, 1794, 1212, 1792, -1, + 1797, 1213, 1798, -1, 1797, 1792, 1213, -1, + 1797, 1799, 1214, -1, 1797, 1214, 1793, -1, + 1797, 1793, 1792, -1, 2989, 2638, 2329, -1, + 2798, 1803, 2337, -1, 2757, 1215, 1216, -1, + 2757, 1216, 1217, -1, 2757, 2762, 1215, -1, + 2757, 1217, 3067, -1, 2352, 2330, 2329, -1, + 2352, 2329, 1805, -1, 2761, 2760, 2637, -1, + 2761, 2637, 2642, -1, 2761, 2642, 2641, -1, + 2761, 2641, 2762, -1, 2322, 2321, 1806, -1, + 2322, 1806, 1218, -1, 2322, 1218, 2760, -1, + 1822, 1808, 1823, -1, 2358, 1219, 1809, -1, + 2358, 1811, 1219, -1, 2360, 1221, 1220, -1, + 2360, 1220, 1826, -1, 2360, 2361, 1221, -1, + 1827, 1222, 1830, -1, 1827, 1223, 1222, -1, + 1827, 1828, 1224, -1, 1827, 1224, 1223, -1, + 1833, 1831, 2367, -1, 2364, 1225, 2365, -1, + 2364, 1834, 1226, -1, 2364, 1226, 1225, -1, + 1836, 1844, 1835, -1, 1836, 2823, 2820, -1, + 1237, 2820, 2819, -1, 1237, 1236, 1848, -1, + 1839, 1848, 1236, -1, 1839, 1236, 1867, -1, + 1839, 1867, 1841, -1, 1839, 1847, 1848, -1, + 1845, 1846, 2376, -1, 1845, 1227, 1844, -1, + 1845, 1228, 1227, -1, 1845, 2376, 1228, -1, + 1843, 2820, 1237, -1, 1843, 1237, 1848, -1, + 1843, 1836, 2820, -1, 1843, 1844, 1836, -1, + 2827, 2374, 1850, -1, 2372, 2825, 1840, -1, + 2372, 1840, 1229, -1, 2372, 1229, 2375, -1, + 2824, 1846, 1847, -1, 2824, 3094, 1846, -1, + 2830, 1230, 1233, -1, 2830, 2829, 1230, -1, + 1851, 1231, 1232, -1, 1851, 1232, 2378, -1, + 1851, 1233, 1231, -1, 1851, 2830, 1233, -1, + 1234, 1241, 1235, -1, 1234, 1235, 1248, -1, + 1234, 1248, 1866, -1, 1234, 1866, 1236, -1, + 1234, 2819, 1241, -1, 1234, 1236, 1237, -1, + 1234, 1237, 2819, -1, 1238, 2819, 2821, -1, + 1238, 1241, 2819, -1, 1238, 2821, 1240, -1, + 1238, 1240, 1241, -1, 1239, 1240, 1246, -1, + 1239, 1246, 1241, -1, 1239, 1241, 1240, -1, + 1853, 1854, 1242, -1, 1853, 1243, 1856, -1, + 1853, 1242, 1243, -1, 1862, 1244, 1854, -1, + 1862, 1245, 1244, -1, 1862, 1863, 1245, -1, + 1864, 1857, 1841, -1, 1864, 1841, 1867, -1, + 1859, 1248, 1246, -1, 1859, 1246, 1247, -1, + 1859, 1247, 1860, -1, 1858, 1866, 1248, -1, + 1858, 1248, 1859, -1, 1869, 1249, 1870, -1, + 1869, 1871, 1250, -1, 1869, 1250, 1251, -1, + 1869, 1251, 1249, -1, 1257, 1252, 1261, -1, + 1257, 1254, 1253, -1, 1257, 1253, 1252, -1, + 1257, 1256, 1254, -1, 1255, 1261, 1263, -1, + 1255, 1892, 1256, -1, 1255, 1256, 1257, -1, + 1255, 1257, 1261, -1, 1255, 1263, 1291, -1, + 1255, 1291, 1892, -1, 1258, 1259, 1260, -1, + 1258, 1261, 1259, -1, 1258, 1260, 1262, -1, + 1258, 1263, 1261, -1, 1258, 1264, 1263, -1, + 1258, 1262, 1264, -1, 1269, 1265, 1270, -1, + 1269, 1266, 1265, -1, 1269, 1267, 1266, -1, + 1269, 1882, 1267, -1, 1269, 1885, 1882, -1, + 1269, 1874, 1885, -1, 1878, 1271, 1268, -1, + 1878, 1268, 1877, -1, 1876, 1874, 1269, -1, + 1876, 1269, 1270, -1, 1876, 1271, 1878, -1, + 1876, 1272, 1271, -1, 1876, 1270, 1272, -1, + 1890, 1874, 1273, -1, 1890, 1885, 1874, -1, + 1890, 1273, 1281, -1, 1890, 1889, 1885, -1, + 1274, 1282, 1275, -1, 1274, 1277, 1276, -1, + 1274, 1278, 1277, -1, 1274, 1275, 1278, -1, + 1274, 2382, 1282, -1, 1274, 1276, 2382, -1, + 1279, 1281, 1280, -1, 1279, 1280, 1282, -1, + 1279, 1890, 1281, -1, 1279, 1282, 2389, -1, + 1279, 2389, 1890, -1, 1289, 1286, 1283, -1, + 1289, 1283, 1624, -1, 1289, 2177, 2178, -1, + 1289, 1624, 2177, -1, 1284, 1285, 1286, -1, + 1284, 1287, 1285, -1, 1284, 1288, 1287, -1, + 1284, 1286, 1289, -1, 1284, 2178, 1288, -1, + 1284, 1289, 2178, -1, 1881, 1880, 1884, -1, + 2384, 2380, 2385, -1, 2384, 2387, 2382, -1, + 1298, 1299, 1894, -1, 1298, 1290, 1295, -1, + 1298, 1894, 1291, -1, 1298, 1291, 1290, -1, + 1896, 1894, 1299, -1, 1896, 1292, 1895, -1, + 1896, 1293, 1292, -1, 1896, 1299, 1293, -1, + 1294, 1295, 1296, -1, 1294, 1296, 1297, -1, + 1294, 1298, 1295, -1, 1294, 1299, 1298, -1, + 1294, 1297, 1300, -1, 1294, 1300, 1299, -1, + 1898, 1895, 1903, -1, 1898, 1899, 1893, -1, + 1900, 1301, 1899, -1, 1900, 1302, 1301, -1, + 1900, 1303, 1302, -1, 1900, 1901, 1303, -1, + 2837, 1904, 3105, -1, 2390, 1304, 1909, -1, + 2390, 1305, 1304, -1, 2390, 2838, 1305, -1, + 2392, 1908, 1306, -1, 2392, 1306, 2393, -1, + 2391, 1909, 1906, -1, 1911, 1912, 1307, -1, + 1911, 1307, 1308, -1, 1911, 1933, 1939, -1, + 1911, 1308, 1933, -1, 1309, 1922, 2848, -1, + 1309, 1311, 1922, -1, 1309, 2848, 2847, -1, + 1309, 2847, 1310, -1, 1309, 1310, 1312, -1, + 1309, 1312, 1311, -1, 1916, 1917, 1316, -1, + 1916, 1316, 1311, -1, 1916, 1312, 1932, -1, + 1916, 1311, 1312, -1, 3008, 2682, 2394, -1, + 3192, 2882, 2883, -1, 3192, 2883, 3194, -1, + 3192, 3193, 2414, -1, 3192, 2414, 2882, -1, + 1315, 1956, 1313, -1, 1315, 1952, 1950, -1, + 1315, 1314, 1952, -1, 1315, 1313, 1314, -1, + 1955, 1950, 1347, -1, 1955, 1315, 1950, -1, + 1955, 1956, 1315, -1, 1955, 1347, 1957, -1, + 3111, 3112, 1927, -1, 1920, 1927, 3112, -1, + 1920, 3112, 2024, -1, 1926, 1316, 1317, -1, + 1926, 1922, 1316, -1, 1925, 2839, 3111, -1, + 1925, 3111, 1927, -1, 1925, 1317, 2839, -1, + 1925, 1926, 1317, -1, 1924, 2858, 2854, -1, + 1924, 1921, 2858, -1, 1924, 1927, 1920, -1, + 1924, 1920, 1921, -1, 2872, 1318, 2859, -1, + 2872, 2874, 1318, -1, 1931, 1356, 1935, -1, + 1931, 1935, 1936, -1, 1937, 1320, 1319, -1, + 1937, 1935, 1320, -1, 1937, 1319, 1328, -1, + 1937, 1328, 1938, -1, 1321, 1322, 1326, -1, + 1321, 1326, 1325, -1, 1321, 1323, 1322, -1, + 1321, 1325, 3123, -1, 1321, 3123, 3121, -1, + 1321, 3121, 1323, -1, 1331, 1328, 1324, -1, + 1331, 1324, 1325, -1, 1331, 1325, 1326, -1, + 1331, 1326, 1329, -1, 1327, 1938, 1328, -1, + 1327, 1329, 1330, -1, 1327, 1331, 1329, -1, + 1327, 1328, 1331, -1, 1327, 1332, 1938, -1, + 1327, 1330, 1332, -1, 2411, 1333, 2405, -1, + 2411, 2412, 1334, -1, 2411, 1334, 1333, -1, + 1944, 1335, 1339, -1, 1944, 1339, 1943, -1, + 1944, 2404, 1335, -1, 1346, 1341, 1339, -1, + 1346, 1339, 1336, -1, 1346, 1336, 1337, -1, + 1346, 1337, 1338, -1, 1346, 1338, 1345, -1, + 1942, 1943, 1339, -1, 1942, 1339, 1341, -1, + 1942, 1341, 1946, -1, 1340, 1342, 1341, -1, + 1340, 1344, 1343, -1, 1340, 1343, 1342, -1, + 1340, 1345, 1344, -1, 1340, 1346, 1345, -1, + 1340, 1341, 1346, -1, 2407, 2422, 2408, -1, + 1947, 1942, 1946, -1, 2403, 1947, 1963, -1, + 1951, 2421, 1349, -1, 1951, 1349, 1949, -1, + 1951, 1352, 2421, -1, 1958, 1957, 1347, -1, + 1958, 1348, 1390, -1, 1958, 1347, 1348, -1, + 3126, 1989, 1956, -1, 2881, 2882, 2414, -1, + 2420, 1349, 2421, -1, 2420, 1350, 1349, -1, + 2420, 1351, 1350, -1, 2420, 2423, 1351, -1, + 2419, 1967, 2423, -1, 1953, 1353, 1352, -1, + 1953, 1954, 1354, -1, 1953, 1354, 1353, -1, + 1953, 1352, 1951, -1, 1969, 1966, 1930, -1, + 1969, 1355, 1967, -1, 1969, 1929, 1355, -1, + 1969, 1930, 1929, -1, 1960, 1961, 1356, -1, + 1960, 1930, 1966, -1, 1960, 1356, 1931, -1, + 1960, 1931, 1930, -1, 1357, 1358, 1359, -1, + 1357, 1360, 1361, -1, 1357, 1359, 1360, -1, + 1357, 1361, 1362, -1, 1357, 1362, 1363, -1, + 1357, 1363, 1358, -1, 1420, 1421, 1374, -1, + 1420, 1364, 2452, -1, 1420, 1366, 1364, -1, + 1420, 1374, 1366, -1, 1372, 1370, 1365, -1, + 1372, 1365, 1366, -1, 1372, 1374, 1375, -1, + 1372, 1366, 1374, -1, 1367, 1368, 1369, -1, + 1367, 1369, 1370, -1, 1367, 1371, 1368, -1, + 1367, 1370, 1372, -1, 1367, 1375, 1371, -1, + 1367, 1372, 1375, -1, 1422, 2010, 1373, -1, + 1422, 1374, 1421, -1, 1422, 1375, 1374, -1, + 1422, 1373, 1375, -1, 1376, 1398, 1377, -1, + 1376, 1377, 1378, -1, 1376, 1379, 1398, -1, + 1376, 1378, 1379, -1, 1973, 1380, 1972, -1, + 1973, 1974, 1380, -1, 1381, 1382, 1976, -1, + 1381, 1976, 1975, -1, 1381, 1383, 1382, -1, + 1381, 1975, 1383, -1, 2425, 1385, 2426, -1, + 2425, 2428, 1384, -1, 2425, 1384, 1385, -1, + 1987, 1385, 1405, -1, 1987, 2434, 1980, -1, + 1987, 1980, 1386, -1, 1987, 1386, 1385, -1, + 1981, 1387, 1978, -1, 1981, 1407, 1387, -1, + 2681, 1388, 2682, -1, 2681, 2679, 1389, -1, + 2681, 1389, 1388, -1, 2396, 1390, 2397, -1, + 2396, 1958, 1390, -1, 2396, 2416, 1958, -1, + 2654, 1982, 1391, -1, 2654, 1391, 2651, -1, + 1392, 1395, 1407, -1, 1392, 1394, 1395, -1, + 1392, 1407, 1394, -1, 1393, 1395, 1394, -1, + 1393, 1394, 1402, -1, 1393, 1399, 1395, -1, + 1393, 1402, 1399, -1, 1396, 1399, 1402, -1, + 1396, 1401, 1399, -1, 1396, 1402, 1401, -1, + 1397, 1398, 1399, -1, 1397, 1399, 1401, -1, + 1397, 1403, 1398, -1, 1397, 1401, 1403, -1, + 1994, 1983, 1404, -1, 1400, 1401, 1402, -1, + 1400, 1402, 1992, -1, 1400, 1992, 1994, -1, + 1400, 1403, 1401, -1, 1400, 1404, 1403, -1, + 1400, 1994, 1404, -1, 1985, 1406, 1990, -1, + 1985, 1405, 1406, -1, 1985, 1987, 1405, -1, + 2430, 1406, 1988, -1, 2430, 1990, 1406, -1, + 1986, 1990, 2891, -1, 1986, 2891, 2433, -1, + 1986, 2433, 2434, -1, 2435, 1993, 1407, -1, + 2435, 1407, 1981, -1, 2886, 1993, 2435, -1, + 2890, 2652, 2663, -1, 2890, 3275, 2652, -1, + 2006, 1995, 2005, -1, 2442, 2005, 1408, -1, + 2442, 1408, 1412, -1, 2442, 1412, 2443, -1, + 2444, 1409, 2445, -1, 2444, 1411, 1410, -1, + 2444, 1410, 1409, -1, 2444, 1412, 1411, -1, + 2444, 2443, 1412, -1, 1413, 1414, 1415, -1, + 1413, 1416, 1414, -1, 1413, 1415, 1417, -1, + 1413, 1417, 1416, -1, 1997, 1425, 1418, -1, + 1997, 1418, 1998, -1, 2894, 1419, 2004, -1, + 2894, 2898, 1419, -1, 2451, 2897, 1421, -1, + 2451, 1420, 2452, -1, 2451, 1421, 1420, -1, + 2449, 1421, 2897, -1, 2449, 2010, 1422, -1, + 2449, 1422, 1421, -1, 2460, 2453, 1423, -1, + 2460, 1423, 2013, -1, 2016, 1424, 2021, -1, + 2016, 2457, 1424, -1, 2016, 2896, 2454, -1, + 2016, 2454, 2457, -1, 1431, 1427, 1425, -1, + 1431, 1997, 2003, -1, 1431, 1425, 1997, -1, + 1431, 2003, 1430, -1, 1426, 1428, 1427, -1, + 1426, 1430, 1429, -1, 1426, 1431, 1430, -1, + 1426, 1427, 1431, -1, 1426, 1432, 1428, -1, + 1426, 1429, 1432, -1, 1433, 1435, 1434, -1, + 1433, 1434, 1436, -1, 1433, 1436, 1437, -1, + 1433, 1438, 1439, -1, 1433, 1439, 1435, -1, + 1433, 1440, 1438, -1, 1433, 1437, 1440, -1, + 1441, 1443, 1442, -1, 1441, 1444, 2310, -1, + 1441, 1445, 1444, -1, 1441, 1442, 1445, -1, + 1441, 3051, 1443, -1, 1441, 2310, 3051, -1, + 1446, 1448, 1447, -1, 1446, 1447, 1449, -1, + 1446, 1450, 1448, -1, 1446, 1449, 1450, -1, + 3257, 2023, 3256, -1, 2463, 2904, 2023, -1, + 2467, 2024, 3113, -1, 1451, 2842, 2912, -1, + 1451, 3257, 2842, -1, 1451, 2023, 3257, -1, + 1451, 2463, 2023, -1, 1451, 2912, 2913, -1, + 1451, 2913, 2463, -1, 2473, 1452, 2026, -1, + 2473, 1453, 1452, -1, 2472, 2940, 2935, -1, + 2472, 2935, 1453, -1, 2472, 1454, 2940, -1, + 2472, 2474, 1454, -1, 2472, 1453, 2473, -1, + 3288, 2027, 3137, -1, 2923, 2907, 2900, -1, + 2028, 2022, 2914, -1, 2028, 3290, 2022, -1, + 2028, 2027, 3288, -1, 2028, 3288, 3290, -1, + 2031, 2022, 3290, -1, 2031, 2477, 2901, -1, + 2031, 2901, 2899, -1, 2031, 2899, 2022, -1, + 1455, 1456, 1457, -1, 1455, 1458, 1456, -1, + 1455, 1473, 1458, -1, 1455, 1457, 1459, -1, + 1455, 1460, 1473, -1, 1455, 1459, 1460, -1, + 2480, 2482, 1461, -1, 2480, 1461, 1462, -1, + 2480, 1462, 2032, -1, 3148, 3150, 2033, -1, + 2036, 1464, 2927, -1, 2036, 1463, 1464, -1, + 2036, 2039, 1463, -1, 2929, 2927, 1464, -1, + 2929, 1464, 2046, -1, 1470, 2052, 2209, -1, + 1470, 1468, 2050, -1, 2211, 2209, 2052, -1, + 2211, 2047, 2210, -1, 1465, 1466, 1468, -1, + 1465, 1467, 1466, -1, 1465, 2207, 1467, -1, + 1465, 2209, 2207, -1, 1465, 1470, 2209, -1, + 1465, 1468, 1470, -1, 1469, 2050, 1468, -1, + 1469, 2049, 2050, -1, 1469, 1904, 2049, -1, + 1469, 1468, 2832, -1, 3104, 1469, 2832, -1, + 3104, 3105, 1904, -1, 3104, 1904, 1469, -1, + 2048, 2944, 2232, -1, 2048, 2210, 2047, -1, + 2048, 2232, 2230, -1, 2048, 2230, 2210, -1, + 2495, 2232, 2944, -1, 2495, 2494, 2225, -1, + 2051, 1470, 2050, -1, 2051, 2052, 1470, -1, + 2497, 2047, 2211, -1, 2497, 2211, 2052, -1, + 2497, 2498, 2047, -1, 2955, 2502, 2954, -1, + 2955, 3159, 2074, -1, 2516, 1471, 1472, -1, + 2516, 1472, 2053, -1, 2516, 2515, 1471, -1, + 2523, 2522, 2526, -1, 2523, 2507, 2506, -1, + 2523, 2526, 2507, -1, 1475, 1473, 2057, -1, + 1475, 2522, 2521, -1, 1475, 2521, 1474, -1, + 1475, 1474, 1473, -1, 2527, 2526, 2522, -1, + 2527, 1475, 2057, -1, 2527, 2522, 1475, -1, + 2508, 1476, 2509, -1, 2508, 2058, 1476, -1, + 2530, 2529, 1477, -1, 2530, 1477, 1478, -1, + 2530, 1478, 2058, -1, 2520, 2519, 3135, -1, + 2520, 2920, 2521, -1, 3136, 3135, 2519, -1, + 3136, 2519, 2054, -1, 3136, 2054, 2546, -1, + 2067, 2065, 1479, -1, 2067, 1480, 2066, -1, + 2067, 1479, 1481, -1, 2067, 1481, 1480, -1, + 2545, 2059, 2061, -1, 2064, 1483, 1482, -1, + 2064, 2066, 1483, -1, 2064, 2558, 2559, -1, + 2064, 1482, 2558, -1, 2542, 2552, 2550, -1, + 1484, 2550, 2071, -1, 1484, 2475, 2538, -1, + 1484, 2538, 2542, -1, 1484, 2542, 2550, -1, + 1484, 2071, 2070, -1, 1484, 2070, 2475, -1, + 2549, 2071, 2550, -1, 3164, 3165, 2917, -1, + 2073, 2071, 2549, -1, 2073, 2549, 2076, -1, + 2553, 2532, 2077, -1, 1485, 1487, 1486, -1, + 1485, 1486, 1488, -1, 1485, 1489, 1487, -1, + 1485, 1490, 1489, -1, 1485, 1488, 1491, -1, + 1485, 1491, 1490, -1, 2562, 1492, 2561, -1, + 2562, 2081, 1492, -1, 2562, 2563, 2081, -1, + 2564, 2032, 2079, -1, 2565, 2032, 2564, -1, + 2483, 1493, 2481, -1, 2483, 2046, 1493, -1, + 1494, 1495, 1496, -1, 1494, 1496, 1497, -1, + 1494, 1498, 1499, -1, 1494, 1497, 1500, -1, + 1494, 1499, 1501, -1, 1494, 1501, 1495, -1, + 1494, 1502, 1498, -1, 1494, 1500, 1502, -1, + 1503, 1504, 2144, -1, 1503, 2144, 2141, -1, + 1503, 2141, 1505, -1, 1503, 1505, 1506, -1, + 1503, 1506, 1507, -1, 1503, 1507, 1504, -1, + 2084, 1508, 2085, -1, 2084, 1512, 1508, -1, + 2084, 1516, 1512, -1, 2086, 2085, 2587, -1, + 2086, 2587, 3172, -1, 2086, 3172, 3173, -1, + 2086, 3173, 2087, -1, 1509, 1516, 1727, -1, + 1509, 1511, 1510, -1, 1509, 1726, 1511, -1, + 1509, 1727, 1726, -1, 1509, 1512, 1516, -1, + 1509, 1510, 1512, -1, 1519, 2088, 2087, -1, + 1519, 2087, 2963, -1, 1513, 1518, 2088, -1, + 1513, 2088, 1519, -1, 1513, 1519, 1520, -1, + 1513, 1520, 1514, -1, 1513, 1514, 1515, -1, + 1513, 1515, 1518, -1, 2089, 1517, 1516, -1, + 2089, 1518, 1517, -1, 2089, 2088, 1518, -1, + 2089, 1516, 2084, -1, 2090, 2963, 2962, -1, + 2090, 1519, 2963, -1, 2090, 2092, 1520, -1, + 2090, 1520, 1519, -1, 2099, 1560, 1527, -1, + 2570, 2571, 2566, -1, 2097, 2570, 2566, -1, + 2097, 2094, 2570, -1, 2097, 2098, 1521, -1, + 2097, 1521, 2094, -1, 1522, 1560, 1523, -1, + 1522, 1523, 1524, -1, 1522, 1527, 1560, -1, + 1522, 1524, 1525, -1, 1522, 1526, 1527, -1, + 1522, 1525, 1526, -1, 2104, 1787, 2091, -1, + 2104, 2091, 2567, -1, 2104, 2567, 2568, -1, + 2101, 2099, 1527, -1, 2101, 1527, 1528, -1, + 2101, 1528, 2102, -1, 2108, 1530, 1529, -1, + 2108, 2106, 1530, -1, 2108, 1529, 1531, -1, + 2108, 1531, 2122, -1, 1699, 1698, 2114, -1, + 1699, 2110, 1702, -1, 2115, 2110, 1699, -1, + 2115, 1699, 2114, -1, 2119, 2122, 1532, -1, + 2119, 1532, 1533, -1, 2119, 1533, 1534, -1, + 2119, 1534, 2120, -1, 2121, 1535, 2125, -1, + 2121, 1538, 1535, -1, 1536, 2120, 1537, -1, + 1536, 1538, 2121, -1, 1536, 2121, 2120, -1, + 1536, 1537, 1539, -1, 1536, 1539, 1538, -1, + 2575, 2164, 1540, -1, 2575, 1540, 2126, -1, + 2130, 1541, 1553, -1, 2130, 1553, 2131, -1, + 2130, 1542, 1541, -1, 2130, 2129, 1542, -1, + 1543, 1544, 1545, -1, 1543, 1545, 1546, -1, + 1543, 1546, 1547, -1, 1543, 1547, 1548, -1, + 1543, 1548, 1549, -1, 1543, 1549, 1544, -1, + 1550, 1551, 1552, -1, 1550, 2131, 1553, -1, + 1550, 1553, 1551, -1, 1550, 1554, 2133, -1, + 1550, 1552, 1554, -1, 1550, 2133, 2585, -1, + 1550, 2585, 2131, -1, 2589, 1555, 2098, -1, + 2589, 1556, 1555, -1, 2589, 3316, 1556, -1, + 2589, 2098, 2588, -1, 2159, 2160, 1557, -1, + 2159, 1557, 2137, -1, 2143, 2141, 2144, -1, + 1558, 1559, 1560, -1, 1558, 1560, 2099, -1, + 1558, 2099, 2966, -1, 1558, 2966, 2968, -1, + 1558, 2968, 1572, -1, 1558, 1572, 1559, -1, + 2135, 2977, 2976, -1, 2135, 2982, 2158, -1, + 2135, 2976, 2147, -1, 2135, 2147, 2982, -1, + 3315, 2136, 3316, -1, 3315, 2977, 2136, -1, + 2152, 1561, 1690, -1, 2152, 1690, 2153, -1, + 2152, 1660, 1561, -1, 2152, 2154, 1660, -1, + 2218, 2605, 2221, -1, 2218, 2219, 2150, -1, + 2614, 2150, 2154, -1, 2614, 2151, 2150, -1, + 2614, 2613, 2151, -1, 2980, 2607, 2157, -1, + 2980, 2157, 2984, -1, 2980, 2606, 2607, -1, + 1562, 2608, 2151, -1, 1562, 1563, 2608, -1, + 1562, 2151, 2613, -1, 1562, 1564, 1563, -1, + 1562, 2613, 1689, -1, 1562, 1689, 1564, -1, + 2156, 2157, 1563, -1, 2156, 1563, 1564, -1, + 2156, 1564, 1565, -1, 2156, 1565, 2160, -1, + 2625, 1567, 1566, -1, 2625, 2628, 1567, -1, + 2625, 1566, 1568, -1, 2625, 1568, 2626, -1, + 1576, 2635, 1569, -1, 1576, 1570, 2628, -1, + 1576, 1571, 1570, -1, 1576, 1569, 1571, -1, + 2617, 2633, 1573, -1, 2617, 1573, 1572, -1, + 2617, 1572, 2162, -1, 2634, 1573, 2633, -1, + 2634, 1574, 1573, -1, 2634, 2621, 1574, -1, + 2632, 1575, 2635, -1, 2632, 2620, 1575, -1, + 2631, 2635, 1576, -1, 2631, 1576, 2628, -1, + 1577, 1578, 1579, -1, 1577, 1579, 1584, -1, + 1577, 1580, 1578, -1, 1577, 1584, 1581, -1, + 1577, 1581, 1582, -1, 1577, 1582, 1580, -1, + 1588, 1587, 1583, -1, 1588, 1584, 1586, -1, + 1588, 1583, 1585, -1, 1588, 1585, 1584, -1, + 1592, 1586, 1593, -1, 1592, 1591, 1587, -1, + 1592, 1587, 1588, -1, 1592, 1588, 1586, -1, + 1589, 1590, 1591, -1, 1589, 1591, 1592, -1, + 1589, 1592, 1593, -1, 1589, 1593, 1594, -1, + 1589, 1594, 1595, -1, 1589, 1595, 1590, -1, + 1596, 1598, 1597, -1, 1596, 1603, 1600, -1, + 1596, 1602, 1603, -1, 1596, 1597, 1602, -1, + 1596, 1599, 1598, -1, 1596, 1600, 1599, -1, + 2576, 1600, 1603, -1, 2576, 1603, 2165, -1, + 2576, 2577, 1600, -1, 1601, 1603, 1602, -1, + 1601, 2165, 1603, -1, 1601, 1604, 2165, -1, + 1601, 1602, 1605, -1, 1601, 1605, 1606, -1, + 1601, 1606, 1604, -1, 3024, 3023, 2267, -1, + 1607, 1608, 1609, -1, 1607, 1609, 1610, -1, + 1607, 1610, 1611, -1, 1607, 1611, 1612, -1, + 1607, 1612, 1613, -1, 1607, 1613, 1608, -1, + 2171, 3022, 2175, -1, 2171, 1614, 2167, -1, + 2171, 2175, 1614, -1, 2695, 1615, 2175, -1, + 2695, 2273, 1615, -1, 1616, 1618, 1617, -1, + 1616, 1619, 1620, -1, 1616, 1621, 1619, -1, + 1616, 1617, 1621, -1, 1616, 1620, 1622, -1, + 1616, 1622, 1618, -1, 1625, 1623, 2179, -1, + 1625, 3075, 2177, -1, 1625, 1624, 1623, -1, + 1625, 2177, 1624, -1, 2771, 1625, 2179, -1, + 2771, 3075, 1625, -1, 3230, 3078, 2176, -1, + 2770, 1626, 2769, -1, 2770, 1627, 1626, -1, + 2770, 2179, 1627, -1, 3238, 2649, 3239, -1, + 1631, 2180, 2648, -1, 1631, 1630, 1628, -1, + 1631, 1628, 1629, -1, 1631, 1629, 2180, -1, + 1721, 1720, 1630, -1, 1721, 1630, 1631, -1, + 1721, 1631, 2648, -1, 1721, 2648, 2647, -1, + 2184, 1632, 1633, -1, 2184, 1633, 2182, -1, + 2184, 1634, 1632, -1, 2184, 2185, 1634, -1, + 3037, 2715, 2193, -1, 2192, 2715, 2295, -1, + 2192, 2193, 2715, -1, 2192, 2295, 1635, -1, + 2192, 1635, 2191, -1, 1636, 1637, 1740, -1, + 1636, 3037, 2193, -1, 1636, 1740, 3038, -1, + 1636, 3038, 3037, -1, 2189, 1637, 1636, -1, + 2189, 1636, 2193, -1, 2189, 3129, 3130, -1, + 2189, 3130, 1637, -1, 2994, 2194, 2664, -1, + 2665, 2664, 2194, -1, 2665, 2194, 1642, -1, + 2665, 1642, 2201, -1, 1643, 1638, 1641, -1, + 1643, 1655, 1638, -1, 1643, 2671, 1655, -1, + 1643, 2670, 2671, -1, 1640, 1641, 1638, -1, + 1640, 1639, 2202, -1, 1640, 1659, 1639, -1, + 1640, 1638, 1659, -1, 2200, 1640, 2202, -1, + 2200, 1641, 1640, -1, 2200, 1642, 1641, -1, + 2200, 2201, 1642, -1, 2195, 1641, 1642, -1, + 2195, 1642, 2194, -1, 2195, 1643, 1641, -1, + 2195, 2670, 1643, -1, 1653, 3000, 2999, -1, + 1653, 1646, 1652, -1, 1653, 2999, 1644, -1, + 1653, 1644, 1646, -1, 1645, 1646, 1647, -1, + 1645, 1654, 1648, -1, 1645, 1648, 1649, -1, + 1645, 1649, 1646, -1, 1645, 1647, 2206, -1, + 1645, 2206, 1654, -1, 2673, 2214, 2671, -1, + 2673, 2213, 2214, -1, 2673, 1651, 2213, -1, + 2669, 2651, 1650, -1, 2669, 1650, 1651, -1, + 2669, 1651, 2673, -1, 2204, 1982, 2677, -1, + 2204, 1652, 1982, -1, 2204, 3000, 1653, -1, + 2204, 1653, 1652, -1, 2208, 2228, 1654, -1, + 2208, 1654, 2206, -1, 2208, 2210, 2230, -1, + 2208, 2230, 2228, -1, 2215, 1655, 2214, -1, + 2215, 1658, 1655, -1, 2215, 2216, 1663, -1, + 2215, 1663, 1658, -1, 2227, 1656, 2228, -1, + 2227, 2213, 1656, -1, 1657, 1658, 1663, -1, + 1657, 2282, 1659, -1, 1657, 1659, 1658, -1, + 1657, 2281, 2282, -1, 1657, 1664, 2281, -1, + 1657, 1663, 1664, -1, 2220, 1660, 2219, -1, + 2220, 1661, 1660, -1, 2220, 2222, 1665, -1, + 2220, 1665, 1661, -1, 2229, 2224, 2216, -1, + 1662, 2216, 2224, -1, 1662, 1664, 1663, -1, + 1662, 1663, 2216, -1, 1662, 2222, 1664, -1, + 1662, 1665, 2222, -1, 1662, 2224, 1665, -1, + 2237, 1666, 1670, -1, 2237, 1670, 2238, -1, + 2237, 2233, 1666, -1, 1667, 1669, 1668, -1, + 1667, 1671, 1670, -1, 1667, 1672, 1671, -1, + 1667, 1668, 1672, -1, 1667, 1673, 1669, -1, + 1667, 1670, 1673, -1, 1678, 1674, 1679, -1, + 2687, 2688, 1674, -1, 2687, 1674, 1678, -1, + 2245, 1678, 2244, -1, 2245, 2687, 1678, -1, + 1675, 1676, 1677, -1, 1675, 1678, 1679, -1, + 1675, 1679, 1680, -1, 1675, 1680, 1676, -1, + 1675, 1677, 2244, -1, 1675, 2244, 1678, -1, + 1681, 1688, 1682, -1, 1681, 1684, 1683, -1, + 1681, 1683, 1688, -1, 1681, 1685, 1684, -1, + 1681, 1686, 1685, -1, 1681, 1682, 1686, -1, + 2248, 1687, 1689, -1, 2248, 1688, 1687, -1, + 2248, 2249, 1688, -1, 2612, 1689, 2613, -1, + 2612, 2248, 1689, -1, 2611, 2153, 2255, -1, + 1691, 2256, 1690, -1, 1691, 2946, 2691, -1, + 1691, 2493, 2946, -1, 1691, 1690, 2493, -1, + 2252, 1691, 2691, -1, 2252, 2256, 1691, -1, + 2684, 2504, 2075, -1, 2684, 2075, 2685, -1, + 1692, 2247, 2615, -1, 1692, 1693, 2247, -1, + 1692, 2254, 1693, -1, 1692, 2255, 2254, -1, + 1692, 2611, 2255, -1, 1692, 2615, 2611, -1, + 2261, 2259, 1694, -1, 2261, 1694, 1695, -1, + 2261, 1696, 2263, -1, 2261, 1695, 1696, -1, + 1701, 1705, 1697, -1, 1701, 1697, 1698, -1, + 1701, 1698, 1699, -1, 1701, 1699, 1702, -1, + 2266, 2267, 1700, -1, 2266, 1700, 1702, -1, + 2266, 2110, 2270, -1, 2266, 1702, 2110, -1, + 1706, 1700, 1707, -1, 1706, 1705, 1701, -1, + 1706, 1702, 1700, -1, 1706, 1701, 1702, -1, + 2268, 1703, 2697, -1, 2268, 2697, 3024, -1, + 2268, 3024, 2267, -1, 2268, 2269, 1703, -1, + 1708, 2172, 1704, -1, 1708, 1704, 1705, -1, + 1708, 1705, 1706, -1, 1708, 1706, 1707, -1, + 3021, 1707, 3023, -1, 3021, 1708, 1707, -1, + 3021, 2172, 1708, -1, 1717, 1709, 1716, -1, + 1717, 1710, 1709, -1, 1717, 1711, 1710, -1, + 1717, 1718, 1711, -1, 1712, 1714, 1713, -1, + 1712, 1715, 1714, -1, 1712, 1716, 1715, -1, + 1712, 1717, 1716, -1, 1712, 1713, 1718, -1, + 1712, 1718, 1717, -1, 1723, 1722, 1719, -1, + 1723, 1719, 1720, -1, 1723, 1720, 1721, -1, + 1723, 1721, 2647, -1, 2276, 2277, 1722, -1, + 2276, 1722, 1723, -1, 2276, 2647, 2649, -1, + 2276, 1723, 2647, -1, 1724, 1725, 1726, -1, + 1724, 1727, 1728, -1, 1724, 1726, 1727, -1, + 1724, 1728, 1729, -1, 1724, 1729, 1730, -1, + 1724, 1730, 1725, -1, 1731, 2139, 1732, -1, + 1731, 2974, 2139, -1, 1731, 2602, 2974, -1, + 1731, 1733, 2602, -1, 1731, 1734, 1733, -1, + 1731, 1732, 1734, -1, 2700, 2699, 2605, -1, + 2700, 2606, 3031, -1, 2698, 2283, 2699, -1, + 2286, 1749, 1736, -1, 2286, 1736, 2287, -1, + 2597, 2713, 2703, -1, 2714, 2703, 2713, -1, + 2306, 1736, 1735, -1, 2306, 2307, 1736, -1, + 2306, 1735, 3040, -1, 1747, 2287, 2307, -1, + 1747, 2712, 2711, -1, 1747, 2711, 2287, -1, + 1747, 3219, 2712, -1, 1738, 2284, 2280, -1, + 1738, 1737, 2284, -1, 1738, 2290, 1742, -1, + 1738, 1742, 1737, -1, 2289, 2290, 1738, -1, + 2289, 1738, 2280, -1, 2705, 2291, 2290, -1, + 2710, 2707, 2292, -1, 2710, 2712, 2706, -1, + 2710, 2706, 2707, -1, 1739, 2657, 2656, -1, + 1739, 3038, 1740, -1, 1739, 1740, 2657, -1, + 1739, 3039, 3038, -1, 1739, 1743, 3039, -1, + 1739, 2656, 1743, -1, 1741, 2291, 2300, -1, + 1741, 2199, 2198, -1, 1741, 1742, 2291, -1, + 1741, 2198, 1742, -1, 1741, 2300, 1743, -1, + 1741, 1743, 2199, -1, 1744, 1745, 2297, -1, + 1744, 2297, 2296, -1, 1744, 1746, 1745, -1, + 1744, 2296, 1746, -1, 3215, 2294, 2295, -1, + 3034, 2297, 3036, -1, 2298, 2299, 1746, -1, + 2298, 1746, 2296, -1, 3218, 3219, 1747, -1, + 3218, 1747, 2307, -1, 1748, 2148, 1755, -1, + 1748, 2286, 2598, -1, 1748, 2598, 2599, -1, + 1748, 2599, 2148, -1, 1748, 1755, 1749, -1, + 1748, 1749, 2286, -1, 1750, 1751, 1752, -1, + 1750, 1758, 1756, -1, 1750, 1753, 1751, -1, + 1750, 1756, 1753, -1, 1750, 1752, 1761, -1, + 1750, 1761, 1758, -1, 1754, 1755, 2148, -1, + 1754, 1759, 1755, -1, 1754, 1756, 1759, -1, + 1754, 1757, 1756, -1, 1754, 2600, 1757, -1, + 1754, 2148, 2600, -1, 2308, 1758, 2726, -1, + 2308, 1759, 1758, -1, 2308, 1760, 1759, -1, + 2308, 3041, 1760, -1, 3334, 1761, 1762, -1, + 3334, 2726, 1761, -1, 3334, 1762, 1763, -1, + 3334, 3226, 3227, -1, 3334, 1763, 3226, -1, + 3207, 3329, 2724, -1, 3207, 2724, 3208, -1, + 3044, 2306, 3040, -1, 3224, 3225, 2001, -1, + 3224, 2001, 3223, -1, 2312, 2309, 1764, -1, + 2312, 1764, 1765, -1, 2312, 1765, 2313, -1, + 2314, 2313, 1766, -1, 2314, 1766, 3060, -1, + 2314, 3060, 3058, -1, 3054, 3060, 3053, -1, + 3054, 3053, 3052, -1, 1772, 1778, 1776, -1, + 1772, 1771, 1767, -1, 1772, 1767, 1768, -1, + 1772, 1768, 1778, -1, 1769, 1776, 1770, -1, + 1769, 1785, 1786, -1, 1769, 1770, 1785, -1, + 1769, 1786, 1771, -1, 1769, 1771, 1772, -1, + 1769, 1772, 1776, -1, 1773, 1774, 1775, -1, + 1773, 1775, 1776, -1, 1773, 1777, 1774, -1, + 1773, 1776, 1778, -1, 1773, 1779, 1777, -1, + 1773, 1778, 1779, -1, 2103, 2102, 1780, -1, + 2103, 1787, 2104, -1, 2103, 1783, 1787, -1, + 2103, 1780, 1783, -1, 1781, 1783, 1782, -1, + 1781, 1785, 1784, -1, 1781, 1786, 1785, -1, + 1781, 1782, 1786, -1, 1781, 1784, 1787, -1, + 1781, 1787, 1783, -1, 2731, 2315, 2316, -1, + 2743, 2744, 1788, -1, 2743, 1788, 1813, -1, + 2743, 1813, 2739, -1, 2734, 2751, 2753, -1, + 2734, 2753, 1789, -1, 2734, 1789, 1790, -1, + 2734, 1790, 2735, -1, 2763, 2765, 2319, -1, + 1791, 1792, 1793, -1, 1791, 1794, 1792, -1, + 1791, 1793, 1795, -1, 1791, 1795, 1794, -1, + 1796, 1797, 1798, -1, 1796, 1799, 1797, -1, + 1796, 1798, 1800, -1, 1796, 1800, 1799, -1, + 2343, 2332, 1801, -1, 2343, 1801, 2344, -1, + 2780, 3236, 3235, -1, 2336, 2344, 1801, -1, + 2336, 1801, 1802, -1, 2336, 1802, 1803, -1, + 2336, 1803, 2798, -1, 2351, 2331, 2330, -1, + 2351, 2330, 2352, -1, 2351, 1804, 2331, -1, + 2351, 2350, 1804, -1, 2347, 1805, 1806, -1, + 2347, 2352, 1805, -1, 2347, 1807, 2348, -1, + 2347, 1806, 1807, -1, 2356, 2354, 1808, -1, + 2356, 1808, 1822, -1, 2356, 1822, 1811, -1, + 2356, 1811, 2358, -1, 2359, 2358, 1809, -1, + 2359, 2754, 2755, -1, 2359, 1809, 2754, -1, + 2359, 2755, 2357, -1, 1824, 1820, 1812, -1, + 1824, 1812, 1810, -1, 1824, 1810, 1811, -1, + 1824, 1811, 1822, -1, 1817, 1812, 1820, -1, + 1817, 1815, 2740, -1, 1817, 1813, 1812, -1, + 1817, 2740, 1813, -1, 1814, 1816, 1815, -1, + 1814, 1820, 1821, -1, 1814, 1815, 1817, -1, + 1814, 1817, 1820, -1, 1814, 1821, 1818, -1, + 1814, 1818, 1816, -1, 1819, 1821, 1820, -1, + 1819, 1822, 1823, -1, 1819, 1824, 1822, -1, + 1819, 1820, 1824, -1, 1819, 1825, 1821, -1, + 1819, 1823, 1825, -1, 2808, 1826, 2809, -1, + 2808, 2360, 1826, -1, 1832, 1827, 1830, -1, + 1832, 2365, 1828, -1, 1832, 1828, 1827, -1, + 1832, 2369, 2365, -1, 1832, 1833, 2369, -1, + 1829, 1830, 1831, -1, 1829, 1831, 1833, -1, + 1829, 1832, 1830, -1, 1829, 1833, 1832, -1, + 2368, 1833, 2367, -1, 2368, 2369, 1833, -1, + 2366, 1835, 1834, -1, 2366, 1834, 2364, -1, + 2366, 1836, 1835, -1, 2366, 2823, 1836, -1, + 2818, 2815, 1837, -1, 2818, 1837, 2370, -1, + 1838, 1847, 1839, -1, 1838, 2824, 1847, -1, + 1838, 2825, 2824, -1, 1838, 1840, 2825, -1, + 1838, 1841, 1840, -1, 1838, 1839, 1841, -1, + 1842, 1844, 1843, -1, 1842, 1845, 1844, -1, + 1842, 1846, 1845, -1, 1842, 1847, 1846, -1, + 1842, 1848, 1847, -1, 1842, 1843, 1848, -1, + 2826, 1850, 1849, -1, 2826, 2827, 1850, -1, + 2826, 1849, 2371, -1, 3089, 2825, 2372, -1, + 3092, 1851, 2378, -1, 3092, 2830, 1851, -1, + 1852, 1854, 1853, -1, 1852, 1862, 1854, -1, + 1852, 1856, 1855, -1, 1852, 1853, 1856, -1, + 1852, 1864, 1862, -1, 1852, 1855, 1857, -1, + 1852, 1857, 1864, -1, 1865, 1866, 1858, -1, + 1865, 1858, 1859, -1, 1865, 1860, 1863, -1, + 1865, 1859, 1860, -1, 1861, 1863, 1862, -1, + 1861, 1862, 1864, -1, 1861, 1865, 1863, -1, + 1861, 1866, 1865, -1, 1861, 1867, 1866, -1, + 1861, 1864, 1867, -1, 1868, 1869, 1870, -1, + 1868, 1871, 1869, -1, 1868, 1870, 1872, -1, + 1868, 1872, 1871, -1, 1873, 1875, 1874, -1, + 1873, 1874, 1876, -1, 1873, 1877, 1875, -1, + 1873, 1878, 1877, -1, 1873, 1876, 1878, -1, + 1879, 1889, 1880, -1, 1879, 1880, 1881, -1, + 1879, 1883, 1882, -1, 1879, 1884, 1883, -1, + 1879, 1881, 1884, -1, 1879, 1882, 1885, -1, + 1879, 1885, 1889, -1, 2381, 1886, 2380, -1, + 2381, 1887, 1886, -1, 2381, 2382, 1887, -1, + 2386, 2385, 1888, -1, 2386, 1888, 1889, -1, + 2386, 1890, 2389, -1, 2386, 1889, 1890, -1, + 1891, 1893, 1892, -1, 1891, 1898, 1893, -1, + 1891, 1892, 1894, -1, 1891, 1895, 1898, -1, + 1891, 1896, 1895, -1, 1891, 1894, 1896, -1, + 1897, 1899, 1898, -1, 1897, 1901, 1900, -1, + 1897, 1900, 1899, -1, 1897, 1902, 1901, -1, + 1897, 1903, 1902, -1, 1897, 1898, 1903, -1, + 3097, 2837, 3105, -1, 2464, 3110, 2835, -1, + 2959, 2958, 2049, -1, 2959, 1904, 2837, -1, + 2959, 2049, 1904, -1, 1905, 1906, 1907, -1, + 1905, 2391, 1906, -1, 1905, 1907, 1908, -1, + 1905, 1908, 2392, -1, 1905, 2392, 2391, -1, + 2840, 2390, 1909, -1, 2840, 1909, 2391, -1, + 1910, 1912, 1911, -1, 1910, 1913, 1912, -1, + 1910, 1914, 1913, -1, 1910, 1939, 1914, -1, + 1910, 1911, 1939, -1, 1915, 1917, 1916, -1, + 1915, 1918, 1919, -1, 1915, 1919, 1917, -1, + 1915, 1932, 1918, -1, 1915, 1916, 1932, -1, + 2849, 3008, 2394, -1, 2849, 3007, 3008, -1, + 2415, 2416, 2396, -1, 2415, 2678, 2675, -1, + 2025, 2831, 3248, -1, 2025, 1920, 2024, -1, + 2025, 1921, 1920, -1, 2025, 3248, 1921, -1, + 3247, 2858, 1921, -1, 3247, 1921, 3248, -1, + 2398, 2848, 1922, -1, 2398, 1922, 1926, -1, + 1923, 1924, 2854, -1, 1923, 1926, 1925, -1, + 1923, 1925, 1927, -1, 1923, 1927, 1924, -1, + 1923, 2854, 2398, -1, 1923, 2398, 1926, -1, + 3120, 2870, 3121, -1, 1928, 1929, 1930, -1, + 1928, 1930, 1931, -1, 1928, 1931, 1936, -1, + 1928, 1932, 1929, -1, 1928, 1936, 1933, -1, + 1928, 1933, 1932, -1, 1934, 1936, 1935, -1, + 1934, 1935, 1937, -1, 1934, 1937, 1938, -1, + 1934, 1939, 1936, -1, 1934, 1940, 1939, -1, + 1934, 1938, 1940, -1, 1941, 1943, 1942, -1, + 1941, 2404, 1944, -1, 1941, 1944, 1943, -1, + 1941, 2403, 2404, -1, 1941, 1942, 1947, -1, + 1941, 1947, 2403, -1, 2402, 1968, 2401, -1, + 2402, 1965, 1968, -1, 2402, 1963, 1965, -1, + 2402, 2403, 1963, -1, 1962, 1945, 1961, -1, + 1962, 1946, 1945, -1, 1962, 1947, 1946, -1, + 1962, 1963, 1947, -1, 2409, 2401, 2407, -1, + 2409, 2411, 2405, -1, 1948, 1949, 1950, -1, + 1948, 1951, 1949, -1, 1948, 1950, 1952, -1, + 1948, 1953, 1951, -1, 1948, 1952, 1954, -1, + 1948, 1954, 1953, -1, 2413, 1955, 1957, -1, + 2413, 1957, 2881, -1, 2413, 1956, 1955, -1, + 2413, 3126, 1956, -1, 3274, 3199, 3276, -1, + 2880, 2881, 1957, -1, 2880, 1958, 2416, -1, + 2880, 1957, 1958, -1, 2418, 1968, 2419, -1, + 2418, 2401, 1968, -1, 2418, 2422, 2407, -1, + 2418, 2407, 2401, -1, 1959, 1966, 1965, -1, + 1959, 1961, 1960, -1, 1959, 1960, 1966, -1, + 1959, 1962, 1961, -1, 1959, 1965, 1963, -1, + 1959, 1963, 1962, -1, 1964, 1965, 1966, -1, + 1964, 1967, 2419, -1, 1964, 2419, 1968, -1, + 1964, 1968, 1965, -1, 1964, 1969, 1967, -1, + 1964, 1966, 1969, -1, 1970, 1972, 1971, -1, + 1970, 1973, 1972, -1, 1970, 1971, 1974, -1, + 1970, 1974, 1973, -1, 2427, 2426, 1975, -1, + 2427, 1975, 1976, -1, 2427, 1976, 2428, -1, + 1977, 1978, 1979, -1, 1977, 1981, 1978, -1, + 1977, 1979, 1981, -1, 2436, 1979, 1980, -1, + 2436, 1981, 1979, -1, 2436, 1980, 2434, -1, + 2436, 2435, 1981, -1, 2653, 3194, 2676, -1, + 2653, 2676, 2677, -1, 2653, 2677, 1982, -1, + 2653, 1982, 2654, -1, 3128, 1991, 3262, -1, + 3128, 3129, 2190, -1, 3128, 1994, 1991, -1, + 3128, 2190, 1983, -1, 3128, 1983, 1994, -1, + 1984, 1985, 1990, -1, 1984, 1986, 2434, -1, + 1984, 1990, 1986, -1, 1984, 2434, 1987, -1, + 1984, 1987, 1985, -1, 3127, 1988, 1989, -1, + 3127, 2430, 1988, -1, 3127, 1989, 3126, -1, + 3267, 2891, 1990, -1, 3267, 1990, 2430, -1, + 2432, 2433, 2891, -1, 2437, 3262, 1991, -1, + 2437, 1992, 1993, -1, 2437, 1993, 2886, -1, + 2437, 1991, 1994, -1, 2437, 1994, 1992, -1, + 2889, 2196, 2438, -1, 2666, 2890, 2663, -1, + 2666, 2196, 2889, -1, 2666, 2889, 2890, -1, + 2007, 2008, 1995, -1, 2007, 1995, 2006, -1, + 2440, 2005, 2442, -1, 2440, 2441, 2009, -1, + 1996, 1997, 1998, -1, 1996, 2000, 1999, -1, + 1996, 1998, 2000, -1, 1996, 1999, 2001, -1, + 1996, 2001, 2002, -1, 1996, 2002, 2003, -1, + 1996, 2003, 1997, -1, 2447, 2004, 2008, -1, + 2447, 2894, 2004, -1, 2895, 2897, 2451, -1, + 2895, 2454, 2896, -1, 2011, 2005, 2440, -1, + 2011, 2440, 2009, -1, 2011, 2006, 2005, -1, + 2011, 2007, 2006, -1, 2011, 2008, 2007, -1, + 2011, 2447, 2008, -1, 2448, 2009, 2010, -1, + 2448, 2010, 2449, -1, 2448, 2011, 2009, -1, + 2448, 2447, 2011, -1, 2458, 2013, 2012, -1, + 2458, 2460, 2013, -1, 2458, 2014, 2459, -1, + 2458, 2012, 2014, -1, 2456, 2457, 2454, -1, + 2456, 2453, 2460, -1, 2015, 2898, 2896, -1, + 2015, 2896, 2016, -1, 2015, 2017, 2898, -1, + 2015, 2018, 2017, -1, 2015, 2019, 2018, -1, + 2015, 2020, 2019, -1, 2015, 2021, 2020, -1, + 2015, 2016, 2021, -1, 2462, 2022, 2899, -1, + 2462, 2914, 2022, -1, 2462, 2913, 2914, -1, + 2462, 2463, 2913, -1, 2466, 2023, 2904, -1, + 2466, 3256, 2023, -1, 2466, 3113, 3256, -1, + 2466, 2467, 3113, -1, 2470, 2024, 2467, -1, + 2470, 2831, 2025, -1, 2470, 2025, 2024, -1, + 2469, 2470, 2467, -1, 2915, 2026, 2027, -1, + 2915, 2473, 2026, -1, 2915, 2027, 2028, -1, + 2915, 2028, 2914, -1, 3142, 2030, 2029, -1, + 3142, 3137, 2030, -1, 3142, 2029, 3143, -1, + 2921, 3165, 3166, -1, 2919, 2520, 3135, -1, + 2919, 2920, 2520, -1, 2952, 2919, 3135, -1, + 2952, 3139, 2919, -1, 3286, 2031, 3290, -1, + 3286, 2477, 2031, -1, 2926, 2923, 2900, -1, + 2486, 2480, 2032, -1, 2486, 2032, 2565, -1, + 2037, 3148, 2033, -1, 2037, 2034, 2041, -1, + 2037, 2035, 2034, -1, 2037, 2033, 2035, -1, + 2484, 2039, 2036, -1, 2484, 2036, 2927, -1, + 2930, 2041, 2485, -1, 2930, 2037, 2041, -1, + 2930, 3148, 2037, -1, 2044, 2042, 2038, -1, + 2044, 2484, 2485, -1, 2044, 2038, 2039, -1, + 2044, 2039, 2484, -1, 2040, 2485, 2041, -1, + 2040, 2043, 2042, -1, 2040, 2042, 2044, -1, + 2040, 2044, 2485, -1, 2040, 2045, 2043, -1, + 2040, 2041, 2045, -1, 2938, 2940, 2488, -1, + 2938, 2488, 2491, -1, 3152, 2928, 2491, -1, + 2490, 2928, 2929, -1, 2490, 2929, 2046, -1, + 2490, 2046, 2483, -1, 2490, 2483, 2492, -1, + 2943, 2047, 2498, -1, 2943, 2048, 2047, -1, + 2943, 2944, 2048, -1, 2956, 2050, 2049, -1, + 2956, 2051, 2050, -1, 2956, 2049, 2958, -1, + 2956, 2957, 2051, -1, 2499, 2052, 2051, -1, + 2499, 2497, 2052, -1, 2499, 2051, 2957, -1, + 2499, 2957, 2954, -1, 2501, 2502, 2955, -1, + 2501, 2955, 2074, -1, 2692, 2504, 2684, -1, + 2692, 2684, 2694, -1, 2947, 2691, 2946, -1, + 2511, 2053, 2506, -1, 2511, 2516, 2053, -1, + 2518, 2053, 2054, -1, 2518, 2054, 2519, -1, + 2518, 2506, 2053, -1, 2518, 2523, 2506, -1, + 2528, 2055, 2529, -1, 2528, 2056, 2055, -1, + 2528, 2057, 2056, -1, 2528, 2527, 2057, -1, + 2525, 2058, 2508, -1, 2525, 2530, 2058, -1, + 2525, 2508, 2507, -1, 2525, 2507, 2526, -1, + 2535, 2540, 2543, -1, 2535, 2536, 2534, -1, + 2950, 2547, 2059, -1, 2950, 2059, 2545, -1, + 2537, 2060, 2536, -1, 2537, 2545, 2061, -1, + 2537, 2061, 2062, -1, 2537, 2062, 2060, -1, + 3293, 3136, 2546, -1, 2063, 2559, 2077, -1, + 2063, 2064, 2559, -1, 2063, 2077, 2065, -1, + 2063, 2066, 2064, -1, 2063, 2065, 2067, -1, + 2063, 2067, 2066, -1, 2551, 2557, 2076, -1, + 2551, 2076, 2549, -1, 2068, 3164, 2917, -1, + 2068, 2070, 3161, -1, 2068, 2917, 2475, -1, + 2068, 2475, 2070, -1, 3157, 2068, 3161, -1, + 3157, 3164, 2068, -1, 2069, 2070, 2071, -1, + 2069, 2071, 2073, -1, 2069, 2073, 2074, -1, + 2069, 3161, 2070, -1, 2069, 3159, 3161, -1, + 2069, 2074, 3159, -1, 2072, 2074, 2073, -1, + 2072, 2504, 2501, -1, 2072, 2501, 2074, -1, + 2072, 2075, 2504, -1, 2072, 2076, 2075, -1, + 2072, 2073, 2076, -1, 2556, 2077, 2559, -1, + 2556, 2553, 2077, -1, 2556, 2551, 2553, -1, + 2556, 2557, 2551, -1, 2554, 2532, 2553, -1, + 2554, 2552, 2540, -1, 2078, 2564, 2079, -1, + 2078, 2080, 2081, -1, 2078, 2081, 2563, -1, + 2078, 2563, 2564, -1, 2078, 2082, 2080, -1, + 2078, 2079, 2082, -1, 2936, 2563, 2562, -1, + 2083, 2084, 2085, -1, 2083, 2086, 2087, -1, + 2083, 2085, 2086, -1, 2083, 2087, 2088, -1, + 2083, 2088, 2089, -1, 2083, 2089, 2084, -1, + 2093, 2090, 2962, -1, 2093, 2567, 2091, -1, + 2093, 2091, 2092, -1, 2093, 2092, 2090, -1, + 2569, 2093, 2962, -1, 2569, 2567, 2093, -1, + 2969, 2570, 2094, -1, 2969, 2094, 2095, -1, + 2969, 2095, 2970, -1, 2096, 2097, 2566, -1, + 2096, 2566, 3171, -1, 2096, 3171, 3174, -1, + 2096, 3174, 2588, -1, 2096, 2588, 2098, -1, + 2096, 2098, 2097, -1, 2105, 2099, 2101, -1, + 2105, 2568, 2965, -1, 2105, 2966, 2099, -1, + 2105, 2965, 2966, -1, 2100, 2101, 2102, -1, + 2100, 2102, 2103, -1, 2100, 2103, 2104, -1, + 2100, 2104, 2568, -1, 2100, 2568, 2105, -1, + 2100, 2105, 2101, -1, 2123, 2107, 2106, -1, + 2123, 2106, 2108, -1, 2123, 2124, 2107, -1, + 2123, 2108, 2122, -1, 2109, 2270, 2110, -1, + 2109, 2110, 2115, -1, 2109, 2111, 2270, -1, + 2109, 2115, 2116, -1, 2109, 2116, 2112, -1, + 2109, 2112, 2111, -1, 2113, 2114, 2581, -1, + 2113, 2115, 2114, -1, 2113, 2116, 2115, -1, + 2113, 2581, 2584, -1, 2113, 2117, 2116, -1, + 2113, 2584, 2117, -1, 2118, 2119, 2120, -1, + 2118, 2120, 2121, -1, 2118, 2122, 2119, -1, + 2118, 2124, 2123, -1, 2118, 2123, 2122, -1, + 2118, 2125, 2124, -1, 2118, 2121, 2125, -1, + 2574, 2575, 2126, -1, 2574, 2126, 2127, -1, + 2574, 2127, 2128, -1, 2574, 2128, 2578, -1, + 2583, 2582, 2129, -1, 2583, 2129, 2130, -1, + 2583, 2130, 2131, -1, 2583, 2131, 2585, -1, + 2586, 2132, 2584, -1, 2586, 2133, 2132, -1, + 2586, 2585, 2133, -1, 2134, 2158, 2159, -1, + 2134, 2135, 2158, -1, 2134, 2977, 2135, -1, + 2134, 2136, 2977, -1, 2134, 2137, 2136, -1, + 2134, 2159, 2137, -1, 3189, 2140, 3298, -1, + 3189, 2587, 2138, -1, 3189, 2138, 2140, -1, + 3310, 3174, 3308, -1, 3310, 2588, 3174, -1, + 2973, 2592, 2139, -1, 2973, 2139, 2974, -1, + 2149, 2143, 3178, -1, 2149, 3298, 2140, -1, + 2149, 2140, 2141, -1, 2149, 2141, 2143, -1, + 3177, 3178, 2143, -1, 2142, 2593, 2975, -1, + 2142, 2143, 2144, -1, 2142, 2975, 3177, -1, + 2142, 3177, 2143, -1, 2142, 2145, 2593, -1, + 2142, 2144, 2145, -1, 2596, 2703, 2704, -1, + 2596, 2597, 2703, -1, 2146, 2704, 2147, -1, + 2146, 2596, 2704, -1, 2146, 3302, 2596, -1, + 2146, 3303, 3302, -1, 2146, 2147, 2976, -1, + 2146, 2976, 3303, -1, 2601, 2148, 2599, -1, + 2601, 2600, 2148, -1, 3297, 2149, 3178, -1, + 3297, 3298, 2149, -1, 2604, 2218, 2150, -1, + 2604, 2150, 2151, -1, 2604, 2151, 2608, -1, + 2604, 2605, 2218, -1, 2610, 2152, 2153, -1, + 2610, 2153, 2611, -1, 2610, 2154, 2152, -1, + 2610, 2614, 2154, -1, 2155, 2157, 2156, -1, + 2155, 2158, 2984, -1, 2155, 2984, 2157, -1, + 2155, 2159, 2158, -1, 2155, 2160, 2159, -1, + 2155, 2156, 2160, -1, 2618, 2162, 2161, -1, + 2618, 2617, 2162, -1, 2618, 2161, 2163, -1, + 2618, 2163, 2619, -1, 2630, 2621, 2634, -1, + 2579, 2164, 2575, -1, 2579, 2576, 2165, -1, + 2579, 2166, 2164, -1, 2579, 2165, 2166, -1, + 2174, 2171, 2167, -1, 2174, 2167, 2168, -1, + 2174, 2168, 2169, -1, 2174, 2169, 2173, -1, + 2170, 3022, 2171, -1, 2170, 2173, 2172, -1, + 2170, 2174, 2173, -1, 2170, 2171, 2174, -1, + 2170, 3021, 3022, -1, 2170, 2172, 3021, -1, + 3020, 2175, 3022, -1, 3020, 2695, 2175, -1, + 3074, 3230, 2176, -1, 3074, 2178, 2177, -1, + 3074, 2176, 2178, -1, 3074, 2177, 3075, -1, + 2987, 3070, 2767, -1, 3073, 2771, 2179, -1, + 3073, 2179, 2770, -1, 3073, 2772, 2771, -1, + 2991, 2180, 2645, -1, 2991, 2648, 2180, -1, + 2181, 2182, 2183, -1, 2181, 2184, 2182, -1, + 2181, 2185, 2184, -1, 2181, 2183, 2186, -1, + 2181, 2187, 2185, -1, 2181, 2186, 2187, -1, + 2188, 3129, 2189, -1, 2188, 2190, 3129, -1, + 2188, 2191, 2190, -1, 2188, 2192, 2191, -1, + 2188, 2193, 2192, -1, 2188, 2189, 2193, -1, + 2650, 2194, 2994, -1, 2650, 2195, 2194, -1, + 2650, 2672, 2670, -1, 2650, 2670, 2195, -1, + 2662, 2659, 2196, -1, 2662, 2196, 2666, -1, + 2661, 2201, 2658, -1, 2661, 2665, 2201, -1, + 2197, 2198, 2199, -1, 2197, 2201, 2200, -1, + 2197, 2202, 2198, -1, 2197, 2200, 2202, -1, + 2197, 2199, 2658, -1, 2197, 2658, 2201, -1, + 3002, 2203, 2999, -1, 3002, 2833, 2203, -1, + 3002, 2834, 2833, -1, 3002, 3015, 2834, -1, + 2668, 2651, 2669, -1, 2668, 2672, 3324, -1, + 2997, 3000, 2204, -1, 2997, 2204, 2677, -1, + 2996, 2675, 2678, -1, 2996, 2678, 3005, -1, + 3003, 2679, 2681, -1, 2205, 2206, 2207, -1, + 2205, 2208, 2206, -1, 2205, 2207, 2209, -1, + 2205, 2210, 2208, -1, 2205, 2209, 2211, -1, + 2205, 2211, 2210, -1, 2212, 2213, 2227, -1, + 2212, 2214, 2213, -1, 2212, 2215, 2214, -1, + 2212, 2216, 2215, -1, 2212, 2229, 2216, -1, + 2212, 2227, 2229, -1, 2217, 2219, 2218, -1, + 2217, 2220, 2219, -1, 2217, 2218, 2221, -1, + 2217, 2222, 2220, -1, 2217, 2221, 2223, -1, + 2217, 2223, 2222, -1, 2231, 2224, 2229, -1, + 2231, 2225, 2224, -1, 2231, 2495, 2225, -1, + 2231, 2232, 2495, -1, 2226, 2227, 2228, -1, + 2226, 2229, 2227, -1, 2226, 2228, 2230, -1, + 2226, 2231, 2229, -1, 2226, 2230, 2232, -1, + 2226, 2232, 2231, -1, 2242, 2233, 2237, -1, + 2242, 2241, 2234, -1, 2242, 2234, 2235, -1, + 2242, 2235, 2233, -1, 2236, 2237, 2238, -1, + 2236, 2238, 2239, -1, 2236, 2239, 2240, -1, + 2236, 2240, 2241, -1, 2236, 2241, 2242, -1, + 2236, 2242, 2237, -1, 2257, 2253, 2245, -1, + 2257, 2243, 2254, -1, 2257, 2244, 2243, -1, + 2257, 2245, 2244, -1, 2686, 2687, 2245, -1, + 2686, 2245, 2253, -1, 2246, 2615, 2247, -1, + 2246, 2249, 2248, -1, 2246, 2612, 2615, -1, + 2246, 2248, 2612, -1, 2246, 2250, 2249, -1, + 2246, 2247, 2250, -1, 2690, 2252, 2691, -1, + 2690, 2253, 2252, -1, 2690, 2686, 2253, -1, + 2690, 2694, 2686, -1, 2251, 2252, 2253, -1, + 2251, 2254, 2255, -1, 2251, 2255, 2256, -1, + 2251, 2256, 2252, -1, 2251, 2253, 2257, -1, + 2251, 2257, 2254, -1, 2258, 2260, 2259, -1, + 2258, 2259, 2261, -1, 2258, 2262, 2260, -1, + 2258, 2261, 2263, -1, 2258, 2263, 2264, -1, + 2258, 2264, 2262, -1, 2265, 2267, 2266, -1, + 2265, 2268, 2267, -1, 2265, 2269, 2268, -1, + 2265, 2266, 2270, -1, 2265, 2271, 2269, -1, + 2265, 2270, 2271, -1, 2696, 2272, 2273, -1, + 2696, 2273, 2695, -1, 2696, 2697, 2274, -1, + 2696, 2274, 2272, -1, 2275, 2277, 2276, -1, + 2275, 3238, 2786, -1, 2275, 2649, 3238, -1, + 2275, 2276, 2649, -1, 2275, 2786, 2278, -1, + 2275, 2278, 2277, -1, 3027, 2280, 2698, -1, + 3027, 3029, 2289, -1, 3027, 2289, 2280, -1, + 2279, 2698, 2280, -1, 2279, 2282, 2281, -1, + 2279, 2281, 2283, -1, 2279, 2283, 2698, -1, + 2279, 2284, 2282, -1, 2279, 2280, 2284, -1, + 2702, 3028, 3030, -1, 2702, 3030, 2983, -1, + 2285, 2286, 2287, -1, 2285, 2287, 2711, -1, + 2285, 2711, 2713, -1, 2285, 2598, 2286, -1, + 2285, 2713, 2597, -1, 2285, 2597, 2598, -1, + 2288, 2290, 2289, -1, 2288, 2705, 2290, -1, + 2288, 2707, 2705, -1, 2288, 2292, 2707, -1, + 2288, 3029, 2292, -1, 2288, 2289, 3029, -1, + 2720, 2291, 2705, -1, 2720, 2300, 2291, -1, + 2709, 3028, 2702, -1, 2709, 2702, 2714, -1, + 2709, 2292, 3028, -1, 2709, 2710, 2292, -1, + 3035, 2293, 2294, -1, 3035, 2294, 3215, -1, + 3035, 3036, 2293, -1, 3035, 3215, 3212, -1, + 3214, 2295, 2715, -1, 3214, 3215, 2295, -1, + 2717, 2296, 2297, -1, 2717, 2297, 3034, -1, + 2717, 2298, 2296, -1, 2717, 3034, 2718, -1, + 2717, 2719, 2299, -1, 2717, 2299, 2298, -1, + 3202, 3039, 2300, -1, 3202, 2300, 2720, -1, + 3209, 2725, 3045, -1, 3209, 3208, 2724, -1, + 2723, 2301, 2719, -1, 2723, 2719, 2305, -1, + 2723, 2302, 2301, -1, 2723, 2724, 2303, -1, + 2723, 2303, 2302, -1, 2723, 3045, 2725, -1, + 2723, 2305, 3045, -1, 2304, 3045, 2305, -1, + 2304, 3047, 3045, -1, 2304, 2305, 2719, -1, + 2304, 2719, 3047, -1, 3048, 2306, 3044, -1, + 3048, 2307, 2306, -1, 3048, 3218, 2307, -1, + 3205, 3041, 2308, -1, 3205, 2308, 2726, -1, + 3057, 2309, 2312, -1, 3057, 2312, 3058, -1, + 3057, 3051, 2310, -1, 3057, 2310, 2309, -1, + 2311, 2312, 2313, -1, 2311, 3058, 2312, -1, + 2311, 2313, 2314, -1, 2311, 2314, 3058, -1, + 2728, 2327, 2315, -1, 2728, 2315, 2731, -1, + 2728, 2326, 2327, -1, 2728, 2729, 2326, -1, + 2745, 2316, 2744, -1, 2745, 2731, 2316, -1, + 2745, 2733, 2731, -1, 2737, 2317, 2749, -1, + 2737, 2749, 2748, -1, 2737, 2318, 2317, -1, + 2737, 2738, 2318, -1, 2750, 2743, 2739, -1, + 2750, 2739, 2748, -1, 2323, 2763, 2319, -1, + 2323, 2320, 2321, -1, 2323, 2319, 2320, -1, + 2323, 2321, 2322, -1, 2759, 2322, 2760, -1, + 2759, 2323, 2322, -1, 2759, 2763, 2323, -1, + 2756, 2324, 2327, -1, 2756, 2754, 2324, -1, + 2325, 2764, 3063, -1, 2325, 2327, 2326, -1, + 2325, 2756, 2327, -1, 2325, 3063, 2756, -1, + 2325, 2326, 2328, -1, 2325, 2328, 2764, -1, + 3065, 2763, 2759, -1, 2643, 2334, 2644, -1, + 2643, 2989, 2329, -1, 2643, 2330, 2334, -1, + 2643, 2329, 2330, -1, 2335, 2343, 2345, -1, + 2335, 2334, 2331, -1, 2335, 2331, 2332, -1, + 2335, 2332, 2343, -1, 3072, 2766, 2776, -1, + 3072, 2776, 2772, -1, 3072, 2772, 3073, -1, + 2787, 2780, 2805, -1, 2787, 3236, 2780, -1, + 2775, 2766, 2644, -1, 2775, 2776, 2766, -1, + 2333, 2345, 2774, -1, 2333, 2644, 2334, -1, + 2333, 2775, 2644, -1, 2333, 2774, 2775, -1, + 2333, 2334, 2335, -1, 2333, 2335, 2345, -1, + 2782, 2778, 2774, -1, 2782, 2774, 2345, -1, + 2792, 2339, 2793, -1, 2792, 2789, 2339, -1, + 2802, 2344, 2336, -1, 2802, 2336, 2798, -1, + 2802, 2803, 2344, -1, 2799, 2340, 2800, -1, + 2799, 2798, 2337, -1, 2799, 2338, 2340, -1, + 2799, 2337, 2338, -1, 2342, 2339, 2789, -1, + 2342, 2800, 2340, -1, 2342, 2340, 2341, -1, + 2342, 2341, 2339, -1, 3083, 3082, 2800, -1, + 3083, 2789, 3084, -1, 3083, 2342, 2789, -1, + 3083, 2800, 2342, -1, 2781, 2343, 2344, -1, + 2781, 2344, 2803, -1, 2781, 2345, 2343, -1, + 2781, 2782, 2345, -1, 2346, 2347, 2348, -1, + 2346, 2348, 2349, -1, 2346, 2349, 2350, -1, + 2346, 2350, 2351, -1, 2346, 2351, 2352, -1, + 2346, 2352, 2347, -1, 2353, 2355, 2354, -1, + 2353, 2354, 2356, -1, 2353, 2357, 2355, -1, + 2353, 2356, 2358, -1, 2353, 2359, 2357, -1, + 2353, 2358, 2359, -1, 2807, 2361, 2360, -1, + 2807, 2360, 2808, -1, 2807, 2812, 2362, -1, + 2807, 2362, 2361, -1, 2363, 2364, 2365, -1, + 2363, 2366, 2364, -1, 2363, 2365, 2369, -1, + 2363, 2823, 2366, -1, 2363, 2369, 2822, -1, + 2363, 2822, 2823, -1, 2814, 2367, 2815, -1, + 2814, 2368, 2367, -1, 2814, 2822, 2369, -1, + 2814, 2369, 2368, -1, 2817, 2370, 2821, -1, + 2817, 2818, 2370, -1, 3088, 2826, 2371, -1, + 3088, 2371, 2829, -1, 2828, 3089, 2372, -1, + 2828, 2373, 2374, -1, 2828, 2374, 2827, -1, + 2828, 2375, 2373, -1, 2828, 2372, 2375, -1, + 3091, 2377, 2376, -1, 3091, 2378, 2377, -1, + 3091, 3092, 2378, -1, 3091, 2376, 3094, -1, + 2379, 2380, 2384, -1, 2379, 2381, 2380, -1, + 2379, 2384, 2382, -1, 2379, 2382, 2381, -1, + 2383, 2384, 2385, -1, 2383, 2385, 2386, -1, + 2383, 2387, 2384, -1, 2383, 2388, 2387, -1, + 2383, 2389, 2388, -1, 2383, 2386, 2389, -1, + 3103, 3097, 3105, -1, 3108, 2837, 3097, -1, + 3108, 3097, 3098, -1, 2465, 2924, 2464, -1, + 2465, 2923, 2924, -1, 2465, 2907, 2923, -1, + 2465, 2906, 2907, -1, 2478, 3166, 3167, -1, + 2478, 2464, 2924, -1, 2478, 3110, 2464, -1, + 2478, 3167, 3110, -1, 3253, 2838, 2390, -1, + 3253, 2390, 2840, -1, 2841, 2391, 2392, -1, + 2841, 2840, 2391, -1, 2841, 2393, 2842, -1, + 2841, 2392, 2393, -1, 2851, 2849, 2394, -1, + 2851, 2394, 2395, -1, 2851, 2395, 2846, -1, + 2856, 3007, 2849, -1, 2856, 2843, 3007, -1, + 2680, 2396, 2397, -1, 2680, 2415, 2396, -1, + 2680, 2397, 2679, -1, 2680, 2678, 2415, -1, + 3017, 3013, 2844, -1, 3017, 2834, 3015, -1, + 2845, 3101, 2844, -1, 2845, 2843, 3250, -1, + 3100, 2844, 3101, -1, 3100, 2834, 3017, -1, + 3100, 3017, 2844, -1, 2853, 2848, 2398, -1, + 2853, 2398, 2854, -1, 3114, 3116, 2860, -1, + 2867, 2863, 2399, -1, 2867, 2399, 2868, -1, + 3119, 3123, 2876, -1, 2400, 2401, 2409, -1, + 2400, 2402, 2401, -1, 2400, 2403, 2402, -1, + 2400, 2404, 2403, -1, 2400, 2405, 2404, -1, + 2400, 2409, 2405, -1, 2406, 2407, 2408, -1, + 2406, 2409, 2407, -1, 2406, 2408, 2410, -1, + 2406, 2411, 2409, -1, 2406, 2410, 2412, -1, + 2406, 2412, 2411, -1, 3125, 3126, 2413, -1, + 3125, 2413, 2881, -1, 3125, 2881, 2414, -1, + 2877, 2414, 3193, -1, 2877, 3193, 3198, -1, + 2877, 3125, 2414, -1, 2879, 2416, 2415, -1, + 2879, 2880, 2416, -1, 2879, 2675, 2884, -1, + 2879, 2415, 2675, -1, 2417, 2418, 2419, -1, + 2417, 2420, 2421, -1, 2417, 2421, 2422, -1, + 2417, 2422, 2418, -1, 2417, 2423, 2420, -1, + 2417, 2419, 2423, -1, 2424, 2425, 2426, -1, + 2424, 2426, 2427, -1, 2424, 2428, 2425, -1, + 2424, 2427, 2428, -1, 3263, 2432, 2891, -1, + 3263, 2885, 2432, -1, 3132, 3131, 2438, -1, + 3132, 2429, 2888, -1, 3132, 2438, 2429, -1, + 3272, 2430, 3127, -1, 3272, 3267, 2430, -1, + 2431, 2433, 2432, -1, 2431, 2432, 2885, -1, + 2431, 2434, 2433, -1, 2431, 2886, 2435, -1, + 2431, 2885, 2886, -1, 2431, 2436, 2434, -1, + 2431, 2435, 2436, -1, 2887, 3262, 2437, -1, + 2887, 2437, 2886, -1, 3268, 2438, 3131, -1, + 3268, 2889, 2438, -1, 2439, 2441, 2440, -1, + 2439, 2440, 2442, -1, 2439, 2442, 2443, -1, + 2439, 2443, 2444, -1, 2439, 2444, 2445, -1, + 2439, 2446, 2441, -1, 2439, 2445, 2446, -1, + 2893, 2894, 2447, -1, 2893, 2447, 2448, -1, + 2893, 2449, 2897, -1, 2893, 2448, 2449, -1, + 2450, 2895, 2451, -1, 2450, 2452, 2453, -1, + 2450, 2451, 2452, -1, 2450, 2453, 2456, -1, + 2450, 2454, 2895, -1, 2450, 2456, 2454, -1, + 2455, 2457, 2456, -1, 2455, 2458, 2459, -1, + 2455, 2460, 2458, -1, 2455, 2456, 2460, -1, + 2455, 2459, 2461, -1, 2455, 2461, 2457, -1, + 2903, 2462, 2899, -1, 2903, 2904, 2463, -1, + 2903, 2463, 2462, -1, 2471, 2469, 2906, -1, + 2471, 2464, 2835, -1, 2471, 2906, 2465, -1, + 2471, 2465, 2464, -1, 2905, 2467, 2466, -1, + 2905, 2469, 2467, -1, 2905, 2466, 2904, -1, + 2905, 2906, 2469, -1, 2468, 2835, 2836, -1, + 2468, 2470, 2469, -1, 2468, 2471, 2835, -1, + 2468, 2469, 2471, -1, 2468, 2836, 2831, -1, + 2468, 2831, 2470, -1, 2910, 2472, 2473, -1, + 2910, 2473, 2915, -1, 2910, 2474, 2472, -1, + 2910, 2911, 2474, -1, 2918, 2475, 2917, -1, + 2918, 2538, 2475, -1, 3338, 2538, 2918, -1, + 3338, 2918, 3339, -1, 3138, 2953, 2477, -1, + 3138, 2477, 3286, -1, 3277, 3279, 2926, -1, + 3277, 2953, 3282, -1, 2476, 2901, 2477, -1, + 2476, 2900, 2901, -1, 2476, 2926, 2900, -1, + 2476, 3277, 2926, -1, 2476, 2477, 2953, -1, + 2476, 2953, 3277, -1, 2925, 2921, 3166, -1, + 2925, 3166, 2478, -1, 2925, 2478, 2924, -1, + 2479, 2480, 2486, -1, 2479, 2481, 2482, -1, + 2479, 2482, 2480, -1, 2479, 2483, 2481, -1, + 2479, 2492, 2483, -1, 2479, 2486, 2492, -1, + 2931, 2485, 2484, -1, 2931, 2930, 2485, -1, + 2931, 2484, 2927, -1, 2937, 2492, 2486, -1, + 2937, 2486, 2565, -1, 3151, 2487, 3149, -1, + 3151, 2488, 2487, -1, 3151, 2491, 2488, -1, + 3151, 3152, 2491, -1, 2489, 2928, 2490, -1, + 2489, 2491, 2928, -1, 2489, 2938, 2491, -1, + 2489, 2937, 2938, -1, 2489, 2490, 2492, -1, + 2489, 2492, 2937, -1, 2945, 2946, 2493, -1, + 2945, 2493, 2494, -1, 2945, 2494, 2495, -1, + 2945, 2495, 2944, -1, 2942, 2943, 2498, -1, + 2942, 2498, 2503, -1, 2942, 2503, 2693, -1, + 2942, 2693, 2947, -1, 2496, 2498, 2497, -1, + 2496, 2497, 2499, -1, 2496, 2499, 2954, -1, + 2496, 2503, 2498, -1, 2496, 2954, 2502, -1, + 2496, 2502, 2503, -1, 2500, 2502, 2501, -1, + 2500, 2503, 2502, -1, 2500, 2693, 2503, -1, + 2500, 2692, 2693, -1, 2500, 2501, 2504, -1, + 2500, 2504, 2692, -1, 2505, 2506, 2507, -1, + 2505, 2511, 2506, -1, 2505, 2512, 2511, -1, + 2505, 2507, 2508, -1, 2505, 2509, 2512, -1, + 2505, 2508, 2509, -1, 2510, 2511, 2512, -1, + 2510, 2513, 2514, -1, 2510, 2512, 2513, -1, + 2510, 2514, 2515, -1, 2510, 2515, 2516, -1, + 2510, 2516, 2511, -1, 2517, 2518, 2519, -1, + 2517, 2520, 2521, -1, 2517, 2519, 2520, -1, + 2517, 2521, 2522, -1, 2517, 2522, 2523, -1, + 2517, 2523, 2518, -1, 2524, 2525, 2526, -1, + 2524, 2526, 2527, -1, 2524, 2527, 2528, -1, + 2524, 2528, 2529, -1, 2524, 2529, 2530, -1, + 2524, 2530, 2525, -1, 2531, 2540, 2535, -1, + 2531, 2532, 2554, -1, 2531, 2554, 2540, -1, + 2531, 2533, 2532, -1, 2531, 2534, 2533, -1, + 2531, 2535, 2534, -1, 2544, 2536, 2535, -1, + 2544, 2537, 2536, -1, 2544, 2545, 2537, -1, + 2544, 2535, 2543, -1, 2541, 3340, 2949, -1, + 2541, 3338, 3340, -1, 2541, 2542, 2538, -1, + 2541, 2538, 3338, -1, 2539, 2543, 2540, -1, + 2539, 2949, 2543, -1, 2539, 2540, 2552, -1, + 2539, 2541, 2949, -1, 2539, 2552, 2542, -1, + 2539, 2542, 2541, -1, 2948, 2543, 2949, -1, + 2948, 2544, 2543, -1, 2948, 2950, 2545, -1, + 2948, 2545, 2544, -1, 3154, 3293, 2546, -1, + 3154, 2546, 2547, -1, 3154, 2547, 2950, -1, + 3281, 2952, 3135, -1, 2548, 2549, 2550, -1, + 2548, 2551, 2549, -1, 2548, 2550, 2552, -1, + 2548, 2553, 2551, -1, 2548, 2552, 2554, -1, + 2548, 2554, 2553, -1, 2555, 2557, 2556, -1, + 2555, 2688, 2685, -1, 2555, 2685, 2557, -1, + 2555, 2558, 2688, -1, 2555, 2559, 2558, -1, + 2555, 2556, 2559, -1, 2934, 2560, 2935, -1, + 2934, 2561, 2560, -1, 2934, 2562, 2561, -1, + 2934, 2936, 2562, -1, 2939, 2563, 2936, -1, + 2939, 2564, 2563, -1, 2939, 2565, 2564, -1, + 2939, 2937, 2565, -1, 2961, 2566, 2571, -1, + 2961, 3171, 2566, -1, 2961, 2571, 2569, -1, + 2961, 2569, 2962, -1, 2572, 2568, 2567, -1, + 2572, 2567, 2569, -1, 2572, 2965, 2568, -1, + 2572, 2569, 2571, -1, 2967, 2571, 2570, -1, + 2967, 2572, 2571, -1, 2967, 2965, 2572, -1, + 2967, 2570, 2969, -1, 2573, 2575, 2574, -1, + 2573, 2577, 2576, -1, 2573, 2578, 2577, -1, + 2573, 2574, 2578, -1, 2573, 2579, 2575, -1, + 2573, 2576, 2579, -1, 2580, 2581, 2582, -1, + 2580, 2582, 2583, -1, 2580, 2584, 2581, -1, + 2580, 2583, 2585, -1, 2580, 2586, 2584, -1, + 2580, 2585, 2586, -1, 3307, 3172, 2587, -1, + 3307, 2587, 3189, -1, 3307, 3308, 3172, -1, + 3317, 2588, 3310, -1, 3317, 2589, 2588, -1, + 3317, 3316, 2589, -1, 2590, 2591, 2592, -1, + 2590, 2592, 2973, -1, 2590, 2973, 2975, -1, + 2590, 2975, 2593, -1, 2590, 2593, 2594, -1, + 2590, 2594, 2591, -1, 3305, 2601, 2599, -1, + 3305, 3301, 2601, -1, 2595, 2597, 2596, -1, + 2595, 2599, 2598, -1, 2595, 2598, 2597, -1, + 2595, 3305, 2599, -1, 2595, 2596, 3302, -1, + 2595, 3302, 3305, -1, 3185, 2972, 2600, -1, + 3185, 2600, 2601, -1, 3185, 2601, 3301, -1, + 3181, 2971, 3180, -1, 3181, 2602, 2971, -1, + 3181, 2974, 2602, -1, 3179, 3180, 3183, -1, + 3179, 3297, 3178, -1, 2979, 2606, 2980, -1, + 2979, 3031, 2606, -1, 2979, 3030, 3031, -1, + 2979, 2983, 3030, -1, 2603, 2605, 2604, -1, + 2603, 2700, 2605, -1, 2603, 2606, 2700, -1, + 2603, 2607, 2606, -1, 2603, 2608, 2607, -1, + 2603, 2604, 2608, -1, 2609, 2610, 2611, -1, + 2609, 2612, 2613, -1, 2609, 2613, 2614, -1, + 2609, 2614, 2610, -1, 2609, 2615, 2612, -1, + 2609, 2611, 2615, -1, 2616, 2632, 2633, -1, + 2616, 2633, 2617, -1, 2616, 2617, 2618, -1, + 2616, 2618, 2619, -1, 2616, 2619, 2620, -1, + 2616, 2620, 2632, -1, 2627, 2621, 2630, -1, + 2627, 2626, 2622, -1, 2627, 2622, 2623, -1, + 2627, 2623, 2621, -1, 2624, 2625, 2626, -1, + 2624, 2626, 2627, -1, 2624, 2627, 2630, -1, + 2624, 2630, 2631, -1, 2624, 2628, 2625, -1, + 2624, 2631, 2628, -1, 2629, 2631, 2630, -1, + 2629, 2633, 2632, -1, 2629, 2634, 2633, -1, + 2629, 2630, 2634, -1, 2629, 2632, 2635, -1, + 2629, 2635, 2631, -1, 2768, 2769, 2636, -1, + 2768, 2636, 2640, -1, 2986, 2987, 2642, -1, + 2986, 2642, 2637, -1, 2986, 2637, 2638, -1, + 2986, 2638, 2989, -1, 2639, 2987, 2767, -1, + 2639, 2768, 2640, -1, 2639, 2767, 2768, -1, + 2639, 2640, 2641, -1, 2639, 2641, 2642, -1, + 2639, 2642, 2987, -1, 2988, 2989, 2643, -1, + 2988, 2643, 2644, -1, 2988, 2644, 2766, -1, + 3243, 2786, 3238, -1, 3243, 3079, 2790, -1, + 3243, 3242, 3079, -1, 2992, 3077, 3190, -1, + 2992, 2991, 2645, -1, 2992, 2646, 3077, -1, + 2992, 2645, 2646, -1, 2990, 2647, 2648, -1, + 2990, 2648, 2991, -1, 2990, 3239, 2649, -1, + 2990, 2649, 2647, -1, 2995, 2672, 2650, -1, + 2995, 3324, 2672, -1, 2995, 2650, 2994, -1, + 2995, 3321, 3324, -1, 3325, 2668, 3324, -1, + 3325, 2654, 2651, -1, 3325, 2651, 2668, -1, + 3197, 3276, 3199, -1, 3197, 2652, 3276, -1, + 2993, 2664, 2663, -1, 2993, 2994, 2664, -1, + 2993, 2663, 2652, -1, 2993, 2652, 3197, -1, + 3323, 3194, 2653, -1, 3323, 2653, 2654, -1, + 3323, 2654, 3325, -1, 2655, 2656, 2657, -1, + 2655, 2662, 2661, -1, 2655, 2658, 2656, -1, + 2655, 2661, 2658, -1, 2655, 2657, 2659, -1, + 2655, 2659, 2662, -1, 2660, 2661, 2662, -1, + 2660, 2663, 2664, -1, 2660, 2664, 2665, -1, + 2660, 2665, 2661, -1, 2660, 2666, 2663, -1, + 2660, 2662, 2666, -1, 2667, 2668, 2669, -1, + 2667, 2671, 2670, -1, 2667, 2670, 2672, -1, + 2667, 2672, 2668, -1, 2667, 2673, 2671, -1, + 2667, 2669, 2673, -1, 2674, 2675, 2996, -1, + 2674, 2676, 2884, -1, 2674, 2884, 2675, -1, + 2674, 2677, 2676, -1, 2674, 2997, 2677, -1, + 2674, 2996, 2997, -1, 3004, 3005, 2678, -1, + 3004, 2679, 3003, -1, 3004, 2680, 2679, -1, + 3004, 2678, 2680, -1, 3009, 2681, 2682, -1, + 3009, 3003, 2681, -1, 3009, 2682, 3008, -1, + 3009, 3012, 3003, -1, 2683, 2684, 2685, -1, + 2683, 2687, 2686, -1, 2683, 2694, 2684, -1, + 2683, 2686, 2694, -1, 2683, 2685, 2688, -1, + 2683, 2688, 2687, -1, 2689, 2690, 2691, -1, + 2689, 2693, 2692, -1, 2689, 2692, 2694, -1, + 2689, 2694, 2690, -1, 2689, 2691, 2947, -1, + 2689, 2947, 2693, -1, 3019, 2695, 3020, -1, + 3019, 2696, 2695, -1, 3019, 3024, 2697, -1, + 3019, 2697, 2696, -1, 3026, 2698, 2699, -1, + 3026, 3027, 2698, -1, 3026, 2700, 3031, -1, + 3026, 2699, 2700, -1, 2701, 2702, 2983, -1, + 2701, 2704, 2703, -1, 2701, 2703, 2714, -1, + 2701, 2714, 2702, -1, 2701, 2981, 2704, -1, + 2701, 2983, 2981, -1, 2721, 2720, 2705, -1, + 2721, 2706, 3220, -1, 2721, 2707, 2706, -1, + 2721, 2705, 2707, -1, 2708, 2710, 2709, -1, + 2708, 2711, 2712, -1, 2708, 2712, 2710, -1, + 2708, 2713, 2711, -1, 2708, 2714, 2713, -1, + 2708, 2709, 2714, -1, 3033, 3035, 3212, -1, + 3033, 3212, 3046, -1, 3033, 3046, 3047, -1, + 3033, 2718, 3034, -1, 3033, 3047, 2718, -1, + 3204, 2715, 3037, -1, 3204, 3214, 2715, -1, + 2716, 2717, 2718, -1, 2716, 2719, 2717, -1, + 2716, 2718, 3047, -1, 2716, 3047, 2719, -1, + 3201, 3202, 2720, -1, 3201, 3220, 3221, -1, + 3201, 2721, 3220, -1, 3201, 2720, 2721, -1, + 3043, 3209, 3045, -1, 3043, 3044, 3040, -1, + 2722, 2724, 2723, -1, 2722, 2723, 2725, -1, + 2722, 3209, 2724, -1, 2722, 2725, 3209, -1, + 3049, 3048, 3044, -1, 3332, 3334, 3227, -1, + 3333, 2726, 3334, -1, 3333, 3205, 2726, -1, + 3059, 3051, 3057, -1, 3059, 3060, 3054, -1, + 2727, 2729, 2728, -1, 2727, 2733, 2730, -1, + 2727, 2731, 2733, -1, 2727, 2728, 2731, -1, + 2727, 2730, 2732, -1, 2727, 2732, 2729, -1, + 2746, 2733, 2745, -1, 2746, 2751, 2734, -1, + 2746, 2735, 2733, -1, 2746, 2734, 2735, -1, + 2736, 2738, 2737, -1, 2736, 2739, 2740, -1, + 2736, 2748, 2739, -1, 2736, 2737, 2748, -1, + 2736, 2741, 2738, -1, 2736, 2740, 2741, -1, + 2742, 2744, 2743, -1, 2742, 2743, 2750, -1, + 2742, 2745, 2744, -1, 2742, 2750, 2751, -1, + 2742, 2751, 2746, -1, 2742, 2746, 2745, -1, + 2747, 2748, 2749, -1, 2747, 2750, 2748, -1, + 2747, 2751, 2750, -1, 2747, 2749, 2752, -1, + 2747, 2752, 2753, -1, 2747, 2753, 2751, -1, + 3062, 2755, 2754, -1, 3062, 3067, 2755, -1, + 3062, 2754, 2756, -1, 3062, 2756, 3063, -1, + 3066, 2762, 2757, -1, 3066, 2757, 3067, -1, + 2758, 2759, 2760, -1, 2758, 3065, 2759, -1, + 2758, 3066, 3065, -1, 2758, 2760, 2761, -1, + 2758, 2761, 2762, -1, 2758, 2762, 3066, -1, + 3064, 2763, 3065, -1, 3064, 3063, 2764, -1, + 3064, 2764, 2765, -1, 3064, 2765, 2763, -1, + 3071, 2766, 3072, -1, 3071, 2988, 2766, -1, + 3069, 2767, 3070, -1, 3069, 2769, 2768, -1, + 3069, 2768, 2767, -1, 3069, 2770, 2769, -1, + 3069, 3073, 2770, -1, 3076, 3075, 2771, -1, + 3076, 2771, 2772, -1, 2777, 3235, 3234, -1, + 2777, 2778, 3235, -1, 2777, 3076, 2772, -1, + 2777, 3234, 3076, -1, 2777, 2772, 2776, -1, + 3086, 3242, 3236, -1, 3086, 3236, 2787, -1, + 2773, 2774, 2778, -1, 2773, 2775, 2774, -1, + 2773, 2776, 2775, -1, 2773, 2778, 2777, -1, + 2773, 2777, 2776, -1, 2783, 2778, 2782, -1, + 2783, 3235, 2778, -1, 2783, 2780, 3235, -1, + 2779, 2805, 2780, -1, 2779, 2782, 2781, -1, + 2779, 2780, 2783, -1, 2779, 2783, 2782, -1, + 2779, 2803, 2805, -1, 2779, 2781, 2803, -1, + 2784, 2790, 2797, -1, 2784, 3243, 2790, -1, + 2784, 2796, 2785, -1, 2784, 2797, 2796, -1, + 2784, 2785, 2786, -1, 2784, 2786, 3243, -1, + 3081, 2787, 2805, -1, 3081, 3086, 2787, -1, + 2788, 3084, 2789, -1, 2788, 2789, 2792, -1, + 2788, 2792, 2797, -1, 2788, 2797, 2790, -1, + 2788, 2790, 3079, -1, 2788, 3079, 3084, -1, + 2791, 2792, 2793, -1, 2791, 2794, 2795, -1, + 2791, 2793, 2794, -1, 2791, 2795, 2796, -1, + 2791, 2796, 2797, -1, 2791, 2797, 2792, -1, + 2804, 2802, 2798, -1, 2804, 2798, 2799, -1, + 2804, 2799, 2800, -1, 2804, 2800, 3082, -1, + 2801, 2803, 2802, -1, 2801, 3082, 3081, -1, + 2801, 2804, 3082, -1, 2801, 2802, 2804, -1, + 2801, 2805, 2803, -1, 2801, 3081, 2805, -1, + 2806, 2807, 2808, -1, 2806, 2809, 2810, -1, + 2806, 2808, 2809, -1, 2806, 2810, 2811, -1, + 2806, 2811, 2812, -1, 2806, 2812, 2807, -1, + 2813, 2818, 2822, -1, 2813, 2822, 2814, -1, + 2813, 2815, 2818, -1, 2813, 2814, 2815, -1, + 2816, 2818, 2817, -1, 2816, 2819, 2820, -1, + 2816, 2821, 2819, -1, 2816, 2817, 2821, -1, + 2816, 2822, 2818, -1, 2816, 2820, 2823, -1, + 2816, 2823, 2822, -1, 3096, 3094, 2824, -1, + 3096, 2824, 2825, -1, 3096, 2825, 3089, -1, + 3087, 2826, 3088, -1, 3087, 2827, 2826, -1, + 3087, 2828, 2827, -1, 3087, 3089, 2828, -1, + 3093, 3088, 2829, -1, 3093, 2829, 2830, -1, + 3093, 2830, 3092, -1, 3249, 3248, 2831, -1, + 3249, 2831, 2836, -1, 3249, 2836, 3098, -1, + 3246, 3103, 3101, -1, 3246, 2845, 3250, -1, + 3246, 3101, 2845, -1, 3102, 2832, 2833, -1, + 3102, 3104, 2832, -1, 3102, 2833, 2834, -1, + 3102, 2834, 3100, -1, 3107, 2835, 3110, -1, + 3107, 2836, 2835, -1, 3107, 3098, 2836, -1, + 3107, 3108, 3098, -1, 3109, 2959, 2837, -1, + 3109, 2837, 3108, -1, 3252, 2838, 3253, -1, + 3252, 2839, 2838, -1, 3252, 3111, 2839, -1, + 3255, 3253, 2840, -1, 3255, 2840, 2841, -1, + 3255, 2842, 3257, -1, 3255, 2841, 2842, -1, + 2855, 3250, 2843, -1, 2855, 2858, 3247, -1, + 2855, 3247, 3250, -1, 2855, 2843, 2856, -1, + 3010, 3007, 2843, -1, 3010, 2844, 3013, -1, + 3010, 2845, 2844, -1, 3010, 2843, 2845, -1, + 2850, 2846, 2847, -1, 2850, 2851, 2846, -1, + 2850, 2847, 2848, -1, 2850, 2848, 2853, -1, + 2857, 2856, 2849, -1, 2857, 2850, 2853, -1, + 2857, 2849, 2851, -1, 2857, 2851, 2850, -1, + 2852, 2853, 2854, -1, 2852, 2855, 2856, -1, + 2852, 2856, 2857, -1, 2852, 2857, 2853, -1, + 2852, 2854, 2858, -1, 2852, 2858, 2855, -1, + 3118, 3119, 2872, -1, 3118, 2859, 3115, -1, + 3118, 2872, 2859, -1, 2869, 3114, 2860, -1, + 2869, 2861, 2864, -1, 2869, 2860, 2861, -1, + 2869, 2864, 2867, -1, 2862, 2863, 2867, -1, + 2862, 2867, 2864, -1, 2862, 2865, 2863, -1, + 2862, 2864, 2865, -1, 2866, 3120, 3114, -1, + 2866, 2867, 2868, -1, 2866, 3114, 2869, -1, + 2866, 2869, 2867, -1, 2866, 2868, 2870, -1, + 2866, 2870, 3120, -1, 2871, 2872, 3119, -1, + 2871, 2873, 2874, -1, 2871, 2874, 2872, -1, + 2871, 2875, 2873, -1, 2871, 2876, 2875, -1, + 2871, 3119, 2876, -1, 3124, 3125, 2877, -1, + 3124, 3199, 3274, -1, 3124, 3198, 3199, -1, + 3124, 2877, 3198, -1, 2878, 2880, 2879, -1, + 2878, 2882, 2881, -1, 2878, 2881, 2880, -1, + 2878, 2883, 2882, -1, 2878, 2884, 2883, -1, + 2878, 2879, 2884, -1, 3264, 2886, 2885, -1, + 3264, 2885, 3263, -1, 3264, 3262, 2887, -1, + 3264, 2887, 2886, -1, 3260, 2888, 3130, -1, + 3260, 3132, 2888, -1, 3269, 2889, 3268, -1, + 3269, 3275, 2890, -1, 3269, 2890, 2889, -1, + 3266, 2891, 3267, -1, 3266, 3263, 2891, -1, + 3266, 3131, 3263, -1, 3266, 3268, 3131, -1, + 2892, 2894, 2893, -1, 2892, 2895, 2896, -1, + 2892, 2897, 2895, -1, 2892, 2893, 2897, -1, + 2892, 2896, 2898, -1, 2892, 2898, 2894, -1, + 2908, 2903, 2899, -1, 2908, 2900, 2907, -1, + 2908, 2901, 2900, -1, 2908, 2899, 2901, -1, + 2902, 2904, 2903, -1, 2902, 2906, 2905, -1, + 2902, 2905, 2904, -1, 2902, 2907, 2906, -1, + 2902, 2908, 2907, -1, 2902, 2903, 2908, -1, + 2909, 2911, 2910, -1, 2909, 2913, 2912, -1, + 2909, 2912, 2911, -1, 2909, 2914, 2913, -1, + 2909, 2915, 2914, -1, 2909, 2910, 2915, -1, + 2916, 2921, 3134, -1, 2916, 2917, 3165, -1, + 2916, 3165, 2921, -1, 2916, 2918, 2917, -1, + 2916, 3339, 2918, -1, 2916, 3134, 3339, -1, + 3140, 2919, 3139, -1, 3140, 3144, 2920, -1, + 3140, 2920, 2919, -1, 3289, 3144, 3140, -1, + 3133, 2921, 2925, -1, 3133, 3134, 2921, -1, + 2922, 2924, 2923, -1, 2922, 2925, 2924, -1, + 2922, 2923, 2926, -1, 2922, 3133, 2925, -1, + 2922, 2926, 3279, -1, 2922, 3279, 3133, -1, + 2932, 2931, 2927, -1, 2932, 2928, 3152, -1, + 2932, 2927, 2929, -1, 2932, 2929, 2928, -1, + 3147, 3148, 2930, -1, 3147, 2930, 2931, -1, + 3147, 2932, 3152, -1, 3147, 2931, 2932, -1, + 2933, 2934, 2935, -1, 2933, 2936, 2934, -1, + 2933, 2938, 2937, -1, 2933, 2939, 2936, -1, + 2933, 2937, 2939, -1, 2933, 2935, 2940, -1, + 2933, 2940, 2938, -1, 2941, 2943, 2942, -1, + 2941, 2944, 2943, -1, 2941, 2945, 2944, -1, + 2941, 2946, 2945, -1, 2941, 2947, 2946, -1, + 2941, 2942, 2947, -1, 3153, 2948, 2949, -1, + 3153, 2949, 3340, -1, 3153, 2950, 2948, -1, + 3153, 3154, 2950, -1, 2951, 3281, 3282, -1, + 2951, 3138, 3139, -1, 2951, 3139, 2952, -1, + 2951, 2952, 3281, -1, 2951, 3282, 2953, -1, + 2951, 2953, 3138, -1, 3158, 2954, 2957, -1, + 3158, 3159, 2955, -1, 3158, 2955, 2954, -1, + 3160, 2958, 3156, -1, 3160, 2956, 2958, -1, + 3160, 2957, 2956, -1, 3160, 3158, 2957, -1, + 2960, 3156, 2958, -1, 2960, 3109, 3168, -1, + 2960, 2958, 2959, -1, 2960, 2959, 3109, -1, + 3163, 3164, 3157, -1, 3163, 3157, 3156, -1, + 3163, 2960, 3168, -1, 3163, 3156, 2960, -1, + 3170, 2961, 2962, -1, 3170, 2963, 3173, -1, + 3170, 2962, 2963, -1, 3170, 3171, 2961, -1, + 2964, 2966, 2965, -1, 2964, 2965, 2967, -1, + 2964, 2968, 2966, -1, 2964, 2967, 2969, -1, + 2964, 2970, 2968, -1, 2964, 2969, 2970, -1, + 3184, 3183, 3180, -1, 3184, 3180, 2971, -1, + 3184, 2971, 2972, -1, 3184, 2972, 3185, -1, + 3176, 2973, 2974, -1, 3176, 2974, 3181, -1, + 3176, 2975, 2973, -1, 3176, 3177, 2975, -1, + 3296, 3297, 3179, -1, 3296, 3179, 3183, -1, + 3182, 3303, 2976, -1, 3182, 3304, 3303, -1, + 3182, 2976, 2977, -1, 3182, 2977, 3315, -1, + 3187, 3296, 3183, -1, 2978, 2979, 2980, -1, + 2978, 2982, 2981, -1, 2978, 2981, 2983, -1, + 2978, 2983, 2979, -1, 2978, 2984, 2982, -1, + 2978, 2980, 2984, -1, 2985, 2987, 2986, -1, + 2985, 2988, 3071, -1, 2985, 2986, 2989, -1, + 2985, 2989, 2988, -1, 2985, 3070, 2987, -1, + 2985, 3071, 3070, -1, 3191, 2990, 2991, -1, + 3191, 2992, 3190, -1, 3191, 2991, 2992, -1, + 3191, 3239, 2990, -1, 3320, 3198, 3193, -1, + 3196, 2993, 3197, -1, 3196, 2994, 2993, -1, + 3196, 2995, 2994, -1, 3196, 3321, 2995, -1, + 3001, 3005, 3014, -1, 3001, 2996, 3005, -1, + 3001, 2997, 2996, -1, 3001, 3000, 2997, -1, + 2998, 3014, 3015, -1, 2998, 2999, 3000, -1, + 2998, 3000, 3001, -1, 2998, 3001, 3014, -1, + 2998, 3015, 3002, -1, 2998, 3002, 2999, -1, + 3016, 3003, 3012, -1, 3016, 3005, 3004, -1, + 3016, 3004, 3003, -1, 3016, 3014, 3005, -1, + 3006, 3008, 3007, -1, 3006, 3009, 3008, -1, + 3006, 3012, 3009, -1, 3006, 3013, 3012, -1, + 3006, 3010, 3013, -1, 3006, 3007, 3010, -1, + 3011, 3012, 3013, -1, 3011, 3015, 3014, -1, + 3011, 3014, 3016, -1, 3011, 3016, 3012, -1, + 3011, 3013, 3017, -1, 3011, 3017, 3015, -1, + 3018, 3019, 3020, -1, 3018, 3022, 3021, -1, + 3018, 3020, 3022, -1, 3018, 3021, 3023, -1, + 3018, 3023, 3024, -1, 3018, 3024, 3019, -1, + 3025, 3027, 3026, -1, 3025, 3028, 3029, -1, + 3025, 3029, 3027, -1, 3025, 3030, 3028, -1, + 3025, 3031, 3030, -1, 3025, 3026, 3031, -1, + 3032, 3033, 3034, -1, 3032, 3035, 3033, -1, + 3032, 3034, 3036, -1, 3032, 3036, 3035, -1, + 3203, 3037, 3038, -1, 3203, 3204, 3037, -1, + 3203, 3038, 3039, -1, 3203, 3039, 3202, -1, + 3213, 3214, 3204, -1, 3206, 3043, 3040, -1, + 3206, 3209, 3043, -1, 3206, 3040, 3041, -1, + 3206, 3041, 3205, -1, 3211, 3049, 3046, -1, + 3211, 3046, 3212, -1, 3042, 3044, 3043, -1, + 3042, 3049, 3044, -1, 3042, 3043, 3045, -1, + 3042, 3046, 3049, -1, 3042, 3045, 3047, -1, + 3042, 3047, 3046, -1, 3222, 3213, 3221, -1, + 3217, 3218, 3048, -1, 3217, 3048, 3049, -1, + 3217, 3049, 3211, -1, 3217, 3211, 3222, -1, + 3050, 3051, 3059, -1, 3050, 3052, 3053, -1, + 3050, 3054, 3052, -1, 3050, 3059, 3054, -1, + 3050, 3053, 3055, -1, 3050, 3055, 3051, -1, + 3056, 3057, 3058, -1, 3056, 3059, 3057, -1, + 3056, 3058, 3060, -1, 3056, 3060, 3059, -1, + 3061, 3062, 3063, -1, 3061, 3063, 3064, -1, + 3061, 3064, 3065, -1, 3061, 3065, 3066, -1, + 3061, 3067, 3062, -1, 3061, 3066, 3067, -1, + 3068, 3069, 3070, -1, 3068, 3070, 3071, -1, + 3068, 3071, 3072, -1, 3068, 3072, 3073, -1, + 3068, 3073, 3069, -1, 3229, 3074, 3075, -1, + 3229, 3230, 3074, -1, 3229, 3075, 3076, -1, + 3229, 3076, 3234, -1, 3228, 3232, 3190, -1, + 3228, 3190, 3077, -1, 3228, 3077, 3078, -1, + 3228, 3078, 3230, -1, 3241, 3236, 3242, -1, + 3085, 3079, 3242, -1, 3085, 3242, 3086, -1, + 3085, 3084, 3079, -1, 3080, 3081, 3082, -1, + 3080, 3082, 3083, -1, 3080, 3083, 3084, -1, + 3080, 3084, 3085, -1, 3080, 3086, 3081, -1, + 3080, 3085, 3086, -1, 3095, 3087, 3088, -1, + 3095, 3088, 3093, -1, 3095, 3096, 3089, -1, + 3095, 3089, 3087, -1, 3090, 3092, 3091, -1, + 3090, 3093, 3092, -1, 3090, 3091, 3094, -1, + 3090, 3095, 3093, -1, 3090, 3094, 3096, -1, + 3090, 3096, 3095, -1, 3245, 3103, 3246, -1, + 3245, 3097, 3103, -1, 3245, 3098, 3097, -1, + 3245, 3249, 3098, -1, 3099, 3100, 3101, -1, + 3099, 3102, 3100, -1, 3099, 3101, 3103, -1, + 3099, 3104, 3102, -1, 3099, 3105, 3104, -1, + 3099, 3103, 3105, -1, 3106, 3108, 3107, -1, + 3106, 3109, 3108, -1, 3106, 3107, 3110, -1, + 3106, 3168, 3109, -1, 3106, 3110, 3167, -1, + 3106, 3167, 3168, -1, 3254, 3112, 3111, -1, + 3254, 3111, 3252, -1, 3254, 3113, 3112, -1, + 3254, 3256, 3113, -1, 3122, 3114, 3120, -1, + 3122, 3118, 3115, -1, 3122, 3115, 3116, -1, + 3122, 3116, 3114, -1, 3117, 3119, 3118, -1, + 3117, 3120, 3121, -1, 3117, 3122, 3120, -1, + 3117, 3118, 3122, -1, 3117, 3121, 3123, -1, + 3117, 3123, 3119, -1, 3273, 3125, 3124, -1, + 3273, 3126, 3125, -1, 3273, 3124, 3274, -1, + 3273, 3127, 3126, -1, 3273, 3272, 3127, -1, + 3259, 3128, 3262, -1, 3259, 3129, 3128, -1, + 3259, 3130, 3129, -1, 3259, 3260, 3130, -1, + 3261, 3263, 3131, -1, 3261, 3131, 3132, -1, + 3261, 3132, 3260, -1, 3271, 3267, 3272, -1, + 3271, 3275, 3269, -1, 3337, 3339, 3134, -1, + 3278, 3133, 3279, -1, 3278, 3134, 3133, -1, + 3278, 3337, 3134, -1, 3278, 3292, 3337, -1, + 3291, 3281, 3135, -1, 3291, 3135, 3136, -1, + 3291, 3136, 3293, -1, 3287, 3288, 3137, -1, + 3287, 3137, 3142, -1, 3285, 3138, 3286, -1, + 3285, 3139, 3138, -1, 3285, 3140, 3139, -1, + 3285, 3289, 3140, -1, 3141, 3142, 3143, -1, + 3141, 3144, 3289, -1, 3141, 3287, 3142, -1, + 3141, 3289, 3287, -1, 3141, 3145, 3144, -1, + 3141, 3143, 3145, -1, 3146, 3148, 3147, -1, + 3146, 3149, 3150, -1, 3146, 3150, 3148, -1, + 3146, 3151, 3149, -1, 3146, 3152, 3151, -1, + 3146, 3147, 3152, -1, 3341, 3153, 3340, -1, + 3341, 3293, 3154, -1, 3341, 3154, 3153, -1, + 3155, 3156, 3157, -1, 3155, 3159, 3158, -1, + 3155, 3160, 3156, -1, 3155, 3158, 3160, -1, + 3155, 3161, 3159, -1, 3155, 3157, 3161, -1, + 3162, 3164, 3163, -1, 3162, 3166, 3165, -1, + 3162, 3165, 3164, -1, 3162, 3167, 3166, -1, + 3162, 3168, 3167, -1, 3162, 3163, 3168, -1, + 3169, 3171, 3170, -1, 3169, 3172, 3308, -1, + 3169, 3173, 3172, -1, 3169, 3170, 3173, -1, + 3169, 3308, 3174, -1, 3169, 3174, 3171, -1, + 3175, 3177, 3176, -1, 3175, 3178, 3177, -1, + 3175, 3179, 3178, -1, 3175, 3180, 3179, -1, + 3175, 3181, 3180, -1, 3175, 3176, 3181, -1, + 3295, 3186, 3314, -1, 3295, 3187, 3186, -1, + 3295, 3296, 3187, -1, 3295, 3314, 3311, -1, + 3318, 3182, 3315, -1, 3318, 3314, 3186, -1, + 3318, 3186, 3304, -1, 3318, 3304, 3182, -1, + 3188, 3187, 3183, -1, 3188, 3183, 3184, -1, + 3188, 3185, 3301, -1, 3188, 3184, 3185, -1, + 3300, 3304, 3186, -1, 3300, 3186, 3187, -1, + 3300, 3187, 3188, -1, 3300, 3188, 3301, -1, + 3309, 3189, 3298, -1, 3309, 3307, 3189, -1, + 3313, 3317, 3310, -1, 3313, 3311, 3314, -1, + 3240, 3190, 3232, -1, 3240, 3191, 3190, -1, + 3240, 3239, 3191, -1, 3240, 3232, 3241, -1, + 3322, 3193, 3192, -1, 3322, 3320, 3193, -1, + 3322, 3192, 3194, -1, 3322, 3194, 3323, -1, + 3195, 3196, 3197, -1, 3195, 3198, 3320, -1, + 3195, 3320, 3321, -1, 3195, 3321, 3196, -1, + 3195, 3199, 3198, -1, 3195, 3197, 3199, -1, + 3200, 3221, 3213, -1, 3200, 3201, 3221, -1, + 3200, 3202, 3201, -1, 3200, 3203, 3202, -1, + 3200, 3204, 3203, -1, 3200, 3213, 3204, -1, + 3328, 3205, 3333, -1, 3328, 3206, 3205, -1, + 3328, 3329, 3207, -1, 3328, 3207, 3208, -1, + 3328, 3208, 3209, -1, 3328, 3209, 3206, -1, + 3210, 3211, 3212, -1, 3210, 3214, 3213, -1, + 3210, 3213, 3222, -1, 3210, 3222, 3211, -1, + 3210, 3212, 3215, -1, 3210, 3215, 3214, -1, + 3216, 3218, 3217, -1, 3216, 3220, 3219, -1, + 3216, 3219, 3218, -1, 3216, 3221, 3220, -1, + 3216, 3222, 3221, -1, 3216, 3217, 3222, -1, + 3331, 3223, 3329, -1, 3331, 3329, 3327, -1, + 3331, 3224, 3223, -1, 3331, 3225, 3224, -1, + 3331, 3226, 3225, -1, 3331, 3227, 3226, -1, + 3331, 3332, 3227, -1, 3331, 3327, 3333, -1, + 3233, 3232, 3228, -1, 3233, 3229, 3234, -1, + 3233, 3230, 3229, -1, 3233, 3228, 3230, -1, + 3231, 3241, 3232, -1, 3231, 3233, 3234, -1, + 3231, 3232, 3233, -1, 3231, 3234, 3235, -1, + 3231, 3235, 3236, -1, 3231, 3236, 3241, -1, + 3237, 3238, 3239, -1, 3237, 3239, 3240, -1, + 3237, 3240, 3241, -1, 3237, 3241, 3242, -1, + 3237, 3243, 3238, -1, 3237, 3242, 3243, -1, + 3244, 3245, 3246, -1, 3244, 3247, 3248, -1, + 3244, 3248, 3249, -1, 3244, 3249, 3245, -1, + 3244, 3250, 3247, -1, 3244, 3246, 3250, -1, + 3251, 3252, 3253, -1, 3251, 3254, 3252, -1, + 3251, 3253, 3255, -1, 3251, 3256, 3254, -1, + 3251, 3257, 3256, -1, 3251, 3255, 3257, -1, + 3258, 3260, 3259, -1, 3258, 3261, 3260, -1, + 3258, 3259, 3262, -1, 3258, 3263, 3261, -1, + 3258, 3262, 3264, -1, 3258, 3264, 3263, -1, + 3265, 3266, 3267, -1, 3265, 3267, 3271, -1, + 3265, 3268, 3266, -1, 3265, 3269, 3268, -1, + 3265, 3271, 3269, -1, 3270, 3271, 3272, -1, + 3270, 3273, 3274, -1, 3270, 3272, 3273, -1, + 3270, 3275, 3271, -1, 3270, 3276, 3275, -1, + 3270, 3274, 3276, -1, 3283, 3277, 3282, -1, + 3283, 3292, 3278, -1, 3283, 3279, 3277, -1, + 3283, 3278, 3279, -1, 3280, 3281, 3291, -1, + 3280, 3291, 3292, -1, 3280, 3282, 3281, -1, + 3280, 3283, 3282, -1, 3280, 3292, 3283, -1, + 3284, 3285, 3286, -1, 3284, 3288, 3287, -1, + 3284, 3287, 3289, -1, 3284, 3289, 3285, -1, + 3284, 3290, 3288, -1, 3284, 3286, 3290, -1, + 3336, 3292, 3291, -1, 3336, 3337, 3292, -1, + 3336, 3291, 3293, -1, 3336, 3293, 3341, -1, + 3294, 3295, 3311, -1, 3294, 3311, 3309, -1, + 3294, 3297, 3296, -1, 3294, 3296, 3295, -1, + 3294, 3298, 3297, -1, 3294, 3309, 3298, -1, + 3299, 3300, 3301, -1, 3299, 3302, 3303, -1, + 3299, 3303, 3304, -1, 3299, 3304, 3300, -1, + 3299, 3305, 3302, -1, 3299, 3301, 3305, -1, + 3306, 3308, 3307, -1, 3306, 3307, 3309, -1, + 3306, 3310, 3308, -1, 3306, 3309, 3311, -1, + 3306, 3313, 3310, -1, 3306, 3311, 3313, -1, + 3312, 3313, 3314, -1, 3312, 3315, 3316, -1, + 3312, 3316, 3317, -1, 3312, 3317, 3313, -1, + 3312, 3318, 3315, -1, 3312, 3314, 3318, -1, + 3319, 3321, 3320, -1, 3319, 3320, 3322, -1, + 3319, 3322, 3323, -1, 3319, 3324, 3321, -1, + 3319, 3325, 3324, -1, 3319, 3323, 3325, -1, + 3326, 3333, 3327, -1, 3326, 3328, 3333, -1, + 3326, 3327, 3329, -1, 3326, 3329, 3328, -1, + 3330, 3332, 3331, -1, 3330, 3331, 3333, -1, + 3330, 3334, 3332, -1, 3330, 3333, 3334, -1, + 3335, 3337, 3336, -1, 3335, 3338, 3339, -1, + 3335, 3339, 3337, -1, 3335, 3340, 3338, -1, + 3335, 3341, 3340, -1, 3335, 3336, 3341, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link5.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link5.wrl new file mode 100644 index 0000000..58e199d --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link5.wrl @@ -0,0 +1,7163 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -6.2182173e-012 -0.050000001 -0.19850001, + -0.0216942 0.045048401 -0.19850001, + -0.0266016 0.042336199 -0.19850001, + -0.016514 0.047194201 -0.19850001, + 0.0248404 -0.0482627 -0.13134401, + 0.027557701 -0.0458428 -0.128694, + 0.0248404 -0.049305499 -0.133827, + 0.0220857 -0.0530218 -0.141497, + -0.059999999 0.053754799 -0.0011990099, + -0.0311745 -0.039091598 -0.19850001, + -0.0353553 -0.0353553 -0.19850001, + -0.039091598 -0.0311745 -0.19850001, + -0.0487464 -0.011126 -0.19850001, + -0.0216942 -0.045048401 -0.19850001, + -0.016514 -0.047194201 -0.19850001, + -0.0266016 -0.042336199 -0.19850001, + -0.011126 0.0487464 -0.19850001, + -0.011126 -0.0487464 -0.19850001, + -0.0058307201 0.050999999 0.059716001, + -0.0081406701 0.050999999 0.059432998, + -0.0046292599 0.050999999 0.059804, + 0.0248404 -0.047124699 -0.12889101, + 0.035366699 -0.0399523 -0.125479, + 0.0248404 -0.0502529 -0.13633101, + 0.027557701 -0.046974801 -0.131163, + 0.0302257 -0.044419002 -0.128475, + 0.0328326 -0.042854901 -0.128234, + 0.00559822 -0.049685601 -0.19850001, + 0.0220857 -0.052261502 -0.13897499, + 0.050219599 -0.0248471 -0.122956, + 0.0424264 -0.034115601 -0.124505, + -0.0353553 0.0353553 -0.19850001, + -0.042336199 0.0266016 -0.19850001, + -0.039091598 0.0311745 -0.19850001, + -0.0302257 0.087379597 -0.0084739998, + -0.045048401 0.0216942 -0.19850001, + -0.045048401 -0.0216942 -0.19850001, + -0.049685601 -0.00559822 -0.19850001, + -0.047194201 -0.016514 -0.19850001, + -0.042336199 -0.0266016 -0.19850001, + -0.0182469 -0.057158101 -0.1815, + -0.018242201 -0.0571438 -0.16150001, + -0.0046305298 0.046 0.059820998, + 0.0081428103 -0.051816199 -0.129611, + -1.7080558e-012 -0.059999999 -0.1815, + 4.980898e-013 0.050000001 -0.19850001, + -0.00559822 0.049685601 -0.19850001, + 0.00559822 0.049685601 -0.19850001, + 0.049685601 -0.00559822 -0.19850001, + 0.042336199 0.0266016 -0.19850001, + 0.0353553 0.0353553 -0.19850001, + 0.039091598 0.0311745 -0.19850001, + 0.0497806 0.033494599 -0.1815, + 0.016514 0.047194201 -0.19850001, + 0.011126 0.0487464 -0.19850001, + -0.016505901 -0.057668701 -0.16150001, + -0.017408401 -0.057419099 -0.16150001, + -0.00268824 -0.059264898 -0.151794, + -0.0109179 -0.0583263 -0.15175, + -0.0109179 -0.057936601 -0.149268, + -0.0053973799 -0.059082501 -0.151785, + -0.0081428103 -0.058771499 -0.15177099, + -0.00289505 0.050999999 0.05993, + 5.3424166e-012 0.072679996 0.049635999, + -0.00267513 0.071111001 0.050751001, + 0.0302257 -0.046575401 -0.13347501, + 0.0302257 -0.0455442 -0.130961, + 0.027557701 -0.0480121 -0.13366, + 0.0328326 -0.044997301 -0.13327201, + 0.0328326 -0.043972801 -0.13074, + 0.0487464 -0.011126 -0.19850001, + 0.0220857 -0.051405501 -0.136466, + 0.035366699 -0.046976302 -0.146046, + 0.0328326 -0.049186099 -0.14875799, + 0.035366699 -0.046421401 -0.143434, + 0.027557701 -0.048954502 -0.13618, + 0.0248404 -0.051105 -0.138854, + 0.0302257 -0.0475123 -0.136012, + 0.0532961 -0.019751299 -0.122104, + 0.051830001 -0.022328701 -0.122535, + 0.048467699 -0.0272952 -0.123365, + 0.0424264 -0.035286799 -0.12706999, + 0.044564299 -0.0319396 -0.124141, + 0.0465803 -0.029662799 -0.123761, + 0.0546159 -0.017126299 -0.121666, + 0.059999999 0.0079012001 -0.114605, + -0.0311745 0.039091598 -0.19850001, + -0.059445001 0.055418901 0.0053229998, + -0.0599402 0.0537914 0.00149899, + -0.059999999 0.053200498 -0.00078300497, + -0.059999999 0.052538998 -0.000429001, + -0.059999902 0.050999999 9.5001204e-005, + -0.059999999 0.051782701 -0.00016799899, + -0.059999999 0.0089843599 -0.111571, + -0.0465803 0.052742701 0.037354, + -0.048147298 0.050999999 0.035803001, + -0.048459399 0.050999999 0.035360999, + -0.055787299 0.059585098 0.016222, + -0.0081421202 0.087558202 0.030695001, + -3.9482597e-012 0.087818302 0.031213, + -0.00267513 0.087790601 0.031157, + -0.0053918599 0.0877048 0.030986, + -0.0220857 0.0873871 0.023700999, + -0.0165099 0.082723603 0.035884, + -0.051830001 0.070438102 0.012055, + -0.0532961 0.068095498 0.012038, + -0.00267513 0.0726659 0.049575999, + 0.059999999 0.059028801 -0.028603001, + 0.0599402 0.059978999 -0.028720001, + 0.059999999 0.057812098 -0.033573002, + 0.059999999 0.058500301 -0.031094, + 0.0599402 0.059365701 -0.031259, + 0.021165101 0.056143001 -0.1815, + -0.027557701 0.089155003 0.0086120004, + -0.027557701 0.088397399 -0.0074040098, + -0.027557701 0.088711999 -0.00571201, + -0.021165101 0.056143001 -0.1815, + -0.035366699 0.085399598 -0.0092949998, + -0.0081421202 0.092347898 -0.00464101, + -0.0109179 0.092034496 -0.0049620098, + -0.033491299 0.050999999 0.049775999, + -0.033494599 0.046 0.049780998, + -0.059503399 -0.0077038999 -0.1815, + -0.059706699 -0.0059254402 -0.16150001, + -0.049685601 0.00559822 -0.19850001, + -0.050000001 -7.1617074e-012 -0.19850001, + -0.057608999 0.0167691 -0.1815, + -0.047194201 0.016514 -0.19850001, + -0.0487464 0.011126 -0.19850001, + -0.0240272 -0.054979 -0.1815, + -0.035726301 -0.048204001 -0.16150001, + -0.0220857 -0.048270099 -0.129062, + -0.0081428103 -0.051819 -0.12961, + 0.0220857 -0.048262499 -0.12906601, + 0.0109179 -0.051382098 -0.129545, + 0.0081428103 -0.0529764 -0.132008, + 0.019305199 -0.0532704 -0.139081, + 0.0165099 -0.055568799 -0.144178, + 0.0165099 -0.054899301 -0.141671, + 0.019305199 -0.0540336 -0.141591, + 4.6336378e-013 -0.0523565 -0.129694, + 0.0053973799 -0.0532813 -0.13205101, + 0.00268824 -0.052297901 -0.129685, + 0.0053973799 -0.052119698 -0.129658, + 0.00616926 -0.059682 -0.1815, + 0.010915 -0.058982499 -0.16150001, + 0.0061689499 -0.059679601 -0.16150001, + 0.0089870598 -0.059323099 -0.16150001, + 0.0109179 -0.058956102 -0.159097, + 0.0026879699 -0.059931099 -0.16150001, + 0.0353553 -0.0353553 -0.19850001, + 0.0311745 -0.039091598 -0.19850001, + 0.039091598 -0.0311745 -0.19850001, + 0.0216942 0.045048401 -0.19850001, + 0.041876599 0.0429691 -0.1815, + 0.056809202 0.067349002 -0.025526, + 0.0460728 0.038435601 -0.1815, + -0.019305199 -0.056648899 -0.156617, + -0.0061684698 -0.0596756 -0.16150001, + -0.0165099 -0.057645001 -0.159082, + -0.0165099 -0.056627098 -0.14919101, + -0.019305199 -0.055278499 -0.146625, + -0.0137106 -0.057352901 -0.149234, + -0.0137106 -0.057741798 -0.151722, + -0.0081428103 -0.057898201 -0.146809, + -0.0053973799 -0.0586918 -0.149312, + -0.0081428103 -0.0583812 -0.149294, + 2.6250063e-012 -0.059623901 -0.154254, + -0.0053966301 -0.059746899 -0.16150001, + -0.00294237 -0.059927799 -0.16150001, + -0.0058778701 -0.0597114 -0.16150001, + -0.00616926 -0.059682 -0.1815, + -0.0053973799 -0.059716899 -0.159107, + -0.0081428103 -0.059070799 -0.15423401, + -0.0053918599 0.054553501 0.05878, + -0.0081421202 0.069429301 0.051359002, + -0.0081421202 0.071003199 0.050248999, + -0.0053918599 0.0710712 0.050565999, + -0.0109179 0.072440803 0.048624001, + -0.0137106 0.072300501 0.048030999, + -0.0109179 0.0709057 0.049796, + 0.00154487 0.046 0.059980001, + 0.00154442 0.050999999 0.059962001, + 0.0137106 -0.050812501 -0.129457, + 0.0220857 0.062509999 0.051424, + 0.0308876 0.046 0.051438998, + 0.0118856 -0.058811001 -0.16150001, + 0.044033099 -0.040756401 -0.1815, + 0.059821099 0.0046305298 -0.1815, + 0.049685601 0.00559822 -0.19850001, + 0.050000001 -3.9929136e-012 -0.19850001, + 0.0599402 0.058588699 -0.033771001, + 0.045048401 0.0216942 -0.19850001, + 0.052960701 0.0281986 -0.1815, + 0.058998398 0.062815703 -0.029541999, + 0.057608999 0.0167691 -0.1815, + 0.047194201 0.016514 -0.19850001, + 0.0487464 0.011126 -0.19850001, + 0.059027899 0.0107568 -0.1815, + 0.055579402 0.0226037 -0.1815, + 0.059757002 0.0593528 -0.034035001, + 0.059757002 0.060224 -0.031502001, + 0.059445001 0.061074901 -0.031800002, + 0.059999801 0.000142344 -0.16150001, + 0.042336199 -0.0266016 -0.19850001, + 0.045048401 -0.0216942 -0.19850001, + 0.0479904 -0.036012899 -0.1815, + 0.048467699 -0.032106001 -0.136866, + 0.0378174 -0.044548199 -0.143282, + 0.0328326 -0.047509301 -0.140985, + 0.035366699 -0.045775 -0.14082301, + 0.027557701 -0.050555199 -0.141268, + 0.027557701 -0.049802199 -0.13871799, + 0.0248404 -0.051861901 -0.141389, + 0.0248404 -0.052523799 -0.143931, + 0.027557701 -0.051213801 -0.143824, + 0.0302257 -0.0491037 -0.141133, + 0.0302257 -0.048354998 -0.138567, + 0.0302257 -0.050320599 -0.14628001, + 0.0302257 -0.049758598 -0.14370599, + 0.0302257 -0.050790701 -0.14885101, + 0.0328326 -0.048718799 -0.14616799, + 0.0328326 -0.048160199 -0.143576, + 0.0546159 -0.0201304 -0.130073, + 0.040174201 -0.0394556 -0.13256, + 0.040174201 -0.038454801 -0.129961, + 0.0378174 -0.039320599 -0.127691, + 0.035366699 -0.0422634 -0.13049901, + 0.035366699 -0.041153599 -0.12797301, + 0.0378174 -0.040421899 -0.13023899, + 0.0378174 -0.038128801 -0.125175, + 0.040174201 -0.037362799 -0.12739, + 0.040174201 -0.036180999 -0.12485, + 0.050219599 -0.025970601 -0.12563699, + 0.048467699 -0.028431401 -0.12601499, + 0.055787299 -0.0144652 -0.121221, + 0.0546159 -0.019211899 -0.12724601, + 0.0546159 -0.018210201 -0.124442, + -0.059445001 0.054790098 0.0061050002, + -0.058998398 0.056847099 0.0065540001, + -0.058998398 0.055553298 0.0081359996, + -0.058998398 0.060394 0.000996002, + -0.059445001 0.057723101 0.0020079999, + -0.058998398 0.058093701 0.0048370101, + -0.058998398 0.059280999 0.0029839899, + -0.058998398 0.062839203 -0.029547, + -0.052960701 0.0281986 -0.1815, + -0.055579402 0.0226037 -0.1815, + -0.059445001 0.061098602 -0.031805001, + -0.059445001 0.061905701 -0.029205, + -0.058998398 0.063580699 -0.026881, + -0.059999999 0.056990501 -0.036024999, + -0.059821099 0.0046305298 -0.1815, + -0.059027899 0.0107568 -0.1815, + -0.059757002 0.059376601 -0.03404, + -0.059999999 0.055991098 -0.038431998, + -0.059445001 0.0565948 0.00373, + -0.059757002 0.058308098 -0.0026390101, + -0.059757002 0.059186701 -0.0046069901, + -0.059445001 0.059787098 -0.00182001, + -0.059445001 0.058791898 0.00015699799, + -0.059757002 0.055285901 0.00253999, + -0.059757002 0.054712899 0.003332, + -0.0599402 0.054263402 0.001052, + -0.059999999 0.054209799 -0.00165601, + -0.0599402 0.055154599 -0.00020700099, + -0.059757002 0.056345101 0.00093600497, + -0.059757002 0.057356399 -0.00079100003, + -0.0599402 0.0560988 -0.00182201, + -0.0599402 0.054636799 0.00059500098, + -0.059999999 0.054561201 -0.0021210001, + -0.059999999 0.057356801 -0.0081359996, + -0.058998398 -0.0107903 -0.155527, + -0.059344199 -0.0088465102 -0.16150001, + -0.059445001 -0.0080169002 -0.155461, + -0.059445001 -0.0075966101 -0.14936399, + -0.058998398 -0.010365 -0.14949401, + -0.058983799 -0.0109153 -0.16150001, + -0.058839001 -0.0117463 -0.16150001, + -0.0378174 0.0668905 0.038277999, + -0.044560701 0.050999999 0.040171001, + -0.046333499 0.050999999 0.038121, + -0.0532961 0.0541282 0.026464, + -0.054204401 0.050999999 0.025727, + -0.0502089 0.050999999 0.032825999, + -0.0498452 0.050999999 0.033397999, + -0.051830001 0.054164201 0.029142, + -0.051817998 0.050999999 0.030219, + -0.051830001 0.052701999 0.02977, + -0.051423199 0.050999999 0.030913999, + -0.0532832 0.050999999 0.027550999, + -0.0532961 0.052687701 0.027105, + -0.053653602 0.050999999 0.026818, + -0.0528774 0.050999999 0.028354, + -0.055787299 0.061248999 0.014359, + -0.0546159 0.062597603 0.016167, + -0.0532961 0.069473401 0.0094309999, + -0.0532961 0.068804502 0.010752, + 0.00267513 0.0868444 0.032940999, + -0.0081421202 0.088427901 0.028884999, + -0.0109179 0.088210396 0.028472001, + -6.6904932e-012 0.088697299 0.029398, + -0.0081421202 0.089229301 0.027047999, + 0.00267513 0.0908852 0.023751, + -0.00267513 0.0886686 0.029343, + -0.0053918599 0.089386098 0.027333001, + -0.0053918599 0.088579699 0.029173, + -0.0248404 0.086796701 0.022629, + -0.0109179 0.089729302 0.024784001, + -0.0109179 0.089004502 0.026639, + -0.0137106 0.088709399 0.026102999, + -0.019305199 0.087143302 0.026447, + -0.0220857 0.086645 0.025502, + -0.0165099 0.083817698 0.034232002, + -0.0220857 0.085836403 0.027276, + -0.027557701 0.0799018 0.033208001, + -0.0165099 0.077794202 0.042022001, + -0.0165099 0.0764383 0.043426, + -0.0137106 0.079352699 0.041283999, + -0.019305199 0.076174803 0.042552002, + -0.0220857 0.074506499 0.042869002, + -0.027557701 0.086766697 0.019625001, + -0.0302257 0.086004697 0.018298, + -0.027557701 0.087334298 0.017811, + -0.0378174 0.068191901 0.037193999, + -0.0532961 0.066566698 0.014498, + -0.0546159 0.065802298 0.011767, + -0.0532961 0.067348897 0.013288, + -0.051830001 0.068154097 0.015957, + -0.0328326 0.084580898 0.018606, + -0.050219599 0.0721092 0.013228, + -0.051830001 0.071116298 0.010682, + -0.0081421202 0.086621404 0.032474, + -0.0053918599 0.086762697 0.032768, + -6.1389435e-012 0.086872101 0.032997001, + -0.00267513 0.086845398 0.032940999, + -0.00267513 0.085834399 0.03469, + -0.0137106 0.078028597 0.042746998, + -0.0165099 0.081571497 0.037491001, + -0.0137106 0.073790498 0.046799, + -0.0165099 0.075039402 0.044774, + -0.019305199 0.074793696 0.043896001, + -0.0220857 0.073107101 0.044151001, + -0.0137106 0.081848703 0.038203001, + -0.0137106 0.080627099 0.039767999, + -0.056809202 0.068842404 -0.018409001, + -0.0576833 0.067377202 -0.019362001, + 0.058998398 0.064568803 -0.013344, + 0.058998398 0.064727299 -0.016016001, + 0.059757002 0.060931299 -0.028927, + 0.059445001 0.0618813 -0.029201999, + 0.058998398 0.0635565 -0.026877999, + 0.040174201 0.082714297 -0.012186, + 0.0378174 0.084097899 -0.01069, + -0.048467699 0.077976003 0.000147003, + -0.0424264 0.082513101 -0.00559399, + -0.0328326 0.086601503 -0.0079950001, + -0.0302257 0.087706298 -0.0068000001, + -0.040174201 0.083577797 -0.0072640101, + -0.040174201 0.083755799 -0.0055800001, + -0.0248404 0.0901298 0.0078619998, + -0.027557701 0.088926002 0.010457, + -0.0248404 0.089951098 0.009718, + -0.0248404 0.089313596 -0.0064400001, + -0.0152803 0.058021698 -0.1815, + -0.00923343 0.059285302 -0.1815, + 0.0328326 0.0865179 0.011462, + -4.924379e-012 0.0915161 0.021903999, + 0.00267513 0.091482699 0.021850999, + 2.6016008e-012 0.092043102 0.019991999, + -0.0081421202 0.093137302 0.00064700301, + 0.0165099 0.092105903 0.001121, + -0.0332799 0.050999999 0.049924001, + -0.0328269 0.050999999 0.050211001, + -0.0248404 0.071391299 0.044188999, + -0.059757002 -0.0052730702 -0.155396, + -0.0599254 -0.0029901101 -0.16150001, + -0.0583813 -0.013778 -0.16150001, + -0.058412101 -0.0135813 -0.15559299, + -0.0378174 -0.0465465 -0.15895, + -0.051818501 -0.0302191 -0.16150001, + -0.0514476 -0.030873001 -0.16150001, + -0.051438902 -0.0308876 -0.1815, + -0.0328326 -0.047521502 -0.140982, + -0.0081428103 -0.0573208 -0.14432, + -0.0109179 -0.051385801 -0.12954301, + -0.0137106 -0.050817199 -0.129455, + -0.0248404 -0.0471332 -0.128887, + -0.027557701 -0.0458523 -0.12868901, + -0.0081428103 -0.052979302 -0.132007, + -0.0053973799 -0.055314701 -0.13691901, + 0.019305199 -0.049255099 -0.129218, + 0.0165099 -0.050104301 -0.12934899, + 0.0109179 -0.052540202 -0.131947, + 0.0053973799 -0.0553126 -0.13692001, + 0.0053973799 -0.054345701 -0.13447399, + 0.0081428103 -0.054039501 -0.134434, + 0.00268824 -0.053460501 -0.132076, + 1.7774005e-012 -0.053519301 -0.132084, + -0.00268824 -0.0522989 -0.129685, + -0.0053973799 -0.052121501 -0.129657, + 0.0109179 -0.058831599 -0.15666801, + 0.0053973799 -0.059715401 -0.159106, + 0.0081428103 -0.059402999 -0.15910301, + 0.0060668602 -0.059692498 -0.16150001, + 0.0053963801 -0.059744101 -0.16150001, + 0.0031320599 -0.059918199 -0.16150001, + 0.0220857 -0.054256901 -0.14655501, + 0.0220857 -0.0536866 -0.144025, + 0.019305199 -0.054701 -0.144108, + 0.019305199 -0.0557523 -0.149141, + 0.0165099 -0.056143101 -0.146687, + 0.019305199 -0.055273499 -0.146626, + 0.027557701 -0.051778901 -0.146382, + 0.0248404 -0.053091601 -0.146474, + 0.027557701 -0.0522516 -0.148937, + 0.0216942 -0.045048401 -0.19850001, + 0.0266016 -0.042336199 -0.19850001, + 0.016514 -0.047194201 -0.19850001, + -0.00559822 -0.049685601 -0.19850001, + 0.011126 -0.0487464 -0.19850001, + 0.047194201 -0.016514 -0.19850001, + -0.0030887299 0.0599204 -0.1815, + -0.0053918599 0.0925669 -0.0044170101, + 0.0311745 0.039091598 -0.19850001, + 0.0266016 0.042336199 -0.19850001, + 0.026825599 0.053669199 -0.1815, + 0.055787299 0.069153301 -0.023329999, + -0.019305199 -0.054707199 -0.144106, + -0.0165099 -0.0561474 -0.146686, + -0.019305199 -0.056143198 -0.151647, + -0.019305199 -0.0564401 -0.15414099, + -0.019305199 -0.055756599 -0.14914, + -0.0165099 -0.057014901 -0.15168799, + -0.024834501 -0.0546025 -0.16150001, + -0.0256411 -0.054245099 -0.16150001, + -0.027557701 -0.053259999 -0.15903001, + -0.0328326 -0.048170701 -0.143573, + -0.0137073 -0.058397699 -0.16150001, + -0.0145714 -0.058203701 -0.16150001, + -0.0122731 -0.058731299 -0.1815, + -0.0165099 -0.057522099 -0.156638, + -0.0165099 -0.057312701 -0.154172, + -0.0137106 -0.058373399 -0.159091, + -0.0116994 -0.058848299 -0.16150001, + -0.0109154 -0.058984298 -0.16150001, + -0.0087992204 -0.059351299 -0.16150001, + -0.0109179 -0.0574544 -0.146777, + -0.0137106 -0.056871802 -0.146736, + -0.0109179 -0.056878101 -0.144283, + -0.00268824 -0.058389898 -0.146843, + 7.1405924e-013 -0.058449101 -0.14684699, + -0.0053973799 -0.058208201 -0.14683001, + -0.00268824 -0.058873899 -0.149323, + -0.0053973799 -0.057629999 -0.144345, + -0.00268824 -0.059564602 -0.15425199, + -0.0053973799 -0.059592701 -0.15668701, + -0.0053973799 -0.0593821 -0.154245, + -6.656248e-012 -0.059959099 -0.159109, + -0.00268824 -0.059899699 -0.159109, + 1.4334941e-012 -0.059999999 -0.16150001, + 0.000344617 -0.059999 -0.16150001, + -0.00268824 -0.0597753 -0.156691, + 4.7086172e-012 -0.059834599 -0.156693, + 0.00268824 -0.059898902 -0.159109, + -4.4470434e-012 0.0695384 0.051922999, + -6.7332199e-012 0.071123898 0.050811999, + 0.019305199 0.0610191 0.053256001, + 0.0029901101 0.050999999 0.059925001, + 0.019709 0.050999999 0.056659002, + 0.017454101 0.050999999 0.057404999, + 0.019305199 0.052840199 0.056306001, + 0.0202484 0.050999999 0.056480002, + 0.0197125 0.046 0.056669001, + 0.0254349 0.046 0.054342002, + 0.0302257 0.087016001 0.014687, + 0.0302257 0.087427102 0.012867, + 0.0328326 0.086129703 0.013265, + 0.0328326 0.085675299 0.015058, + 0.0137106 0.081844702 0.038199998, + 0.0248404 0.0792486 0.036031, + 0.0248404 0.078048997 0.037521999, + 0.045067899 0.046 0.039609, + 0.044564299 0.054273002 0.039111, + 0.042443302 0.050999999 0.042410001, + 0.044472098 0.050999999 0.040277001, + 0.048901699 0.046 0.034765001, + 0.022994 0.050999999 0.055419002, + 0.0220857 0.052834399 0.055282999, + 0.0220857 0.0544919 0.054788999, + 0.0254324 0.050999999 0.054336999, + 0.0424264 0.0527605 0.041924998, + 0.040174201 0.0557913 0.042897001, + 0.0424264 0.0557306 0.040736999, + 0.0424264 0.054304302 0.041373, + 0.0137106 0.073787801 0.046794999, + 0.0220857 0.064082399 0.050570998, + 0.019305199 0.064218998 0.051612999, + 0.019305199 0.062624797 0.052466001, + 0.0220857 0.060926199 0.052214999, + 0.0220857 0.0593323 0.052946001, + 0.0302257 0.063553497 0.046535999, + 0.0328326 0.063338198 0.044893999, + 0.0248404 0.062378399 0.05023, + 0.027557701 0.0622302 0.048884999, + 0.0302257 0.062065601 0.047391001, + 0.034754898 -0.048886999 -0.16150001, + 0.0424264 -0.042066701 -0.153631, + 0.0137069 -0.058396202 -0.16150001, + 0.0122731 -0.058731299 -0.1815, + 0.0122713 -0.0587232 -0.16150001, + 0.042423699 -0.042423598 -0.16150001, + 0.039609101 -0.045067899 -0.1815, + 0.044567399 -0.0401715 -0.16150001, + 0.042543601 -0.0423088 -0.16150001, + 0.059999999 0.054822501 -0.040773001, + 0.059999999 0.056965999 -0.036022, + 0.059999999 0.0559671 -0.038426999, + 0.059999999 0.00014212901 -0.15526401, + 0.051434901 -0.0308851 -0.16150001, + 0.051438902 -0.0308876 -0.1815, + 0.051545098 -0.030710001 -0.16150001, + 0.035366699 -0.047440499 -0.148656, + 0.0465803 -0.034524601 -0.137119, + 0.0378174 -0.045099098 -0.145915, + 0.0220857 -0.0551189 -0.1516, + 0.019305199 -0.056138702 -0.151647, + 0.0220857 -0.054733999 -0.14908201, + 0.0248404 -0.053566601 -0.149014, + 0.0248404 -0.0539499 -0.151545, + 0.027557701 -0.052632902 -0.151483, + 0.028437899 -0.0528326 -0.16150001, + 0.0302257 -0.051169999 -0.15141401, + 0.035366699 -0.044204701 -0.135627, + 0.0328326 -0.045928098 -0.135828, + 0.0328326 -0.046765398 -0.1384, + 0.035366699 -0.0450362 -0.138219, + 0.035366699 -0.043280501 -0.13305201, + 0.0378174 -0.042348199 -0.13541099, + 0.0378174 -0.041431099 -0.13281401, + 0.0546159 -0.021717699 -0.13577899, + 0.0546159 -0.0209656 -0.132919, + 0.048467699 -0.029481299 -0.128695, + 0.0465803 -0.032844901 -0.13170899, + 0.0465803 -0.033728901 -0.134406, + 0.044564299 -0.0341716 -0.129357, + 0.0465803 -0.031872202 -0.129033, + 0.044564299 -0.0330997 -0.126734, + 0.0424264 -0.036369 -0.129667, + 0.0465803 -0.030811099 -0.12638199, + 0.0599402 0.060427099 -0.026171001, + 0.059445001 0.063372597 -0.018583, + 0.058984298 0.050999999 0.010915, + 0.0465803 0.067357302 0.027172999, + 0.048467699 0.066769503 0.024691001, + 0.044564299 0.069030799 0.028387001, + 0.044564299 0.059506599 0.036322001, + 0.0465803 0.066268697 0.028287999, + 0.050219599 0.067116603 0.020978, + -0.058998398 0.0539032 0.0097610001, + -0.058412101 0.053941101 0.012564, + -0.058998398 0.054868001 0.0089079998, + -0.058412101 0.055688601 0.010967, + -0.0546159 0.066528797 0.010569, + -0.059445001 0.0625422 -0.026564, + -0.059999999 0.052144401 -0.045254, + -0.059999999 0.054844301 -0.040778998, + -0.059999999 0.0578366 -0.033573002, + -0.0599402 0.0586132 -0.033773001, + -0.059757002 0.060248502 -0.031504001, + -0.0599402 0.058594201 -0.0073569901, + -0.059999999 0.058006302 -0.010086, + -0.059999999 0.059689298 -0.021211, + -0.0599402 0.060851902 -0.021104001, + -0.059757002 0.062054802 -0.021116, + -0.059999999 0.055854399 -0.0045579998, + -0.0599402 0.056994598 -0.00355299, + -0.0599402 0.057830598 -0.0053979899, + -0.058412101 -0.0131511 -0.149625, + -0.0576833 -0.015943799 -0.149756, + -0.058998398 -0.0036967101 -0.119407, + -0.058412101 -0.0063942298 -0.119858, + -0.059445001 -0.00201777 -0.121937, + -0.059445001 -0.00101622 -0.118959, + -0.059757002 0.00163568 -0.118515, + -0.058998398 -0.0072961301 -0.13131499, + -0.058998398 -0.0065124398 -0.12830999, + -0.058412101 -0.0100424 -0.13163599, + -0.058412101 -0.0107572 -0.13462301, + -0.0599204 0.046 0.003089, + -0.059919201 0.050999999 0.003089, + -0.0592779 0.050999999 0.0092319902, + -0.058829699 0.050999999 0.011793, + -0.059285302 0.046 0.0092329998, + -0.055400901 0.050999999 0.023038, + -0.0546159 0.052673101 0.024390001, + -0.056128498 0.050999999 0.021159999, + -0.055787299 0.051840201 0.02189, + -0.051830001 0.0673173 0.01718, + -0.051830001 0.061686099 0.023607999, + -0.050219599 0.063142702 0.025304001, + -0.0378174 0.054382998 0.045558002, + -0.0378174 0.055865899 0.044934999, + -0.0378174 0.0572812 0.044287, + -0.0378174 0.064218797 0.040277001, + -0.0378174 0.065564901 0.039306, + -0.035366699 0.065897398 0.041228, + -0.0378174 0.058688499 0.043598, + -0.0424264 0.055750102 0.040738001, + -0.044564299 0.054297701 0.039128002, + -0.040174201 0.057183601 0.042243998, + -0.040174201 0.055809699 0.042897999, + -0.0424264 0.052767299 0.041958001, + -0.0424264 0.0543277 0.041389, + -0.044564299 0.0527553 0.039708, + -0.042376 0.050999999 0.042477001, + -0.044408198 0.050999999 0.040346999, + -0.0402418 0.050999999 0.044504002, + -0.040174201 0.052778699 0.044093002, + -0.040174201 0.054356199 0.043533999, + -0.050219599 0.061020199 0.027177, + -0.051830001 0.059644099 0.025385, + -0.051830001 0.060672101 0.02452, + -0.050219599 0.062089801 0.026265001, + -0.044564299 0.055687301 0.038463, + -0.051830001 0.058602501 0.026206, + -0.0546159 0.055258401 0.022972999, + -0.0532961 0.055334501 0.025718, + -0.0532961 0.0563596 0.025003999, + -0.0532961 0.057362799 0.024271, + -0.0546159 0.054091599 0.023736, + -0.055787299 0.054054402 0.020971, + -0.0546159 0.058112901 0.020725001, + -0.0532961 0.059344701 0.022667, + -0.0532961 0.058359899 0.023490001, + -0.0546159 0.0562279 0.022249, + -0.0532961 0.060315799 0.0218, + -0.055787299 0.057862401 0.017921001, + -0.055787299 0.0526582 0.021638, + -0.056809202 0.066956699 1.89972e-005, + -0.0546159 0.064254701 0.014048, + -0.0546159 0.065043502 0.012927, + -0.0532961 0.065751597 0.015668999, + -0.0546159 0.063438602 0.015129, + -0.056809202 0.055103298 0.017380999, + -0.055787299 0.055181298 0.020190001, + -0.056809202 0.055959702 0.016638, + -0.055787299 0.056094401 0.019456999, + 0.0053918599 0.087702803 0.030985, + 0.0053918599 0.086760797 0.032767002, + 0.00267513 0.087789603 0.031157, + 0.0081421202 0.086618498 0.032473002, + 0.0081421202 0.085616402 0.034217, + 0.0109179 0.083245203 0.037156001, + 0.00267513 0.088667601 0.029341999, + -0.0053918599 0.090788797 0.023587, + -0.0081421202 0.090622202 0.023308, + -0.0053918599 0.091383502 0.02169, + -0.0053918599 0.090122901 0.02547, + -0.00267513 0.090886302 0.023751, + -0.0081421202 0.089961097 0.025188001, + -0.00267513 0.091483697 0.021850999, + -5.4828525e-012 0.090248197 0.025690001, + -4.3658284e-012 0.090917803 0.023805, + -0.00267513 0.090217598 0.025636001, + -0.00267513 0.089478001 0.027501, + -7.9226157e-012 0.089507602 0.027555, + 0.00267513 0.090216503 0.025635, + 0.00267513 0.089477003 0.0275, + -0.0220857 0.090976797 0.00696899, + -0.0081421202 0.092556201 0.015678, + -0.0109179 0.090383701 0.022909001, + -0.0302257 0.080385096 0.030213, + -0.0302257 0.079343602 0.031776998, + -0.0302257 0.081370898 0.028607, + -0.0328326 0.0797415 0.028651999, + -0.0165099 0.087569498 0.027255001, + -0.0137106 0.087924697 0.027929001, + -0.0137106 0.085169204 0.033234999, + -0.0109179 0.086419098 0.032051999, + -0.0109179 0.087348104 0.030277001, + -0.027557701 0.080970898 0.031633001, + -0.0248404 0.072802 0.042969, + -0.0248404 0.074177198 0.041692, + -0.0220857 0.075866699 0.041529998, + -0.040174201 0.068982601 0.034015, + -0.044564299 0.069039501 0.028399, + -0.0424264 0.069626398 0.030672001, + -0.040174201 0.066492401 0.036228001, + -0.040174201 0.067751199 0.035147998, + -0.040174201 0.063906603 0.038222, + -0.040174201 0.065209702 0.037253, + -0.0465803 0.069452897 0.024809999, + -0.048467699 0.067786701 0.023549, + -0.0465803 0.068425402 0.026021, + -0.051830001 0.068954699 0.014694, + -0.051830001 0.069716796 0.013393, + -0.0328326 0.080697499 0.02706, + -0.035366699 0.079041302 0.026954999, + -0.035366699 0.079964899 0.025376, + -0.035366699 0.083074503 0.01873, + -0.0302257 0.0847148 0.021841001, + -0.0328326 0.083929203 0.020351, + -0.0302257 0.085392602 0.02008, + -0.027557701 0.086131603 0.021421, + -0.027557701 0.085430004 0.023197001, + -0.0248404 0.085284702 0.026182, + -0.0248404 0.086073697 0.024418, + -0.0302257 0.0822988 0.026963999, + -0.027557701 0.0838321 0.026671, + -0.027557701 0.084663101 0.024948001, + -0.048467699 0.068763502 0.022346999, + -0.050219599 0.068050601 0.0198, + -0.050219599 0.068940803 0.018564999, + -0.050219599 0.071380801 0.014618, + -0.0081421202 0.075534202 0.046544001, + -0.0109179 0.073942997 0.047389999, + -0.0081421202 0.074059203 0.047839999, + -0.0081421202 0.0725476 0.049075998, + -0.0053918599 0.072622202 0.049391001, + -0.0109179 0.085424699 0.033792999, + -0.0137106 0.084122203 0.034933001, + -0.0137106 0.0830146 0.036589999, + -0.0109179 0.079552799 0.041864, + -0.019305199 0.078805096 0.039698001, + -0.019305199 0.077513002 0.041152, + -0.0165099 0.079103701 0.040562999, + -0.0165099 0.080363899 0.039051998, + -0.0109179 0.076834597 0.044741001, + -0.0137106 0.075244203 0.045506001, + -0.0137106 0.076658003 0.044155002, + -0.0109179 0.075408801 0.046094999, + -0.0109179 0.078217 0.043329999, + -0.019305199 0.071916699 0.046409, + -0.0165099 0.073600799 0.046062998, + -0.0165099 0.072126001 0.047293, + -0.019305199 0.073373199 0.045182001, + -0.0220857 0.071671903 0.045375001, + -0.0576833 0.067190498 -0.020783, + -0.058412101 0.065266304 -0.024542, + -0.058998398 0.061414801 -0.001121, + -0.059445001 0.060691401 -0.0039210101, + -0.048467699 0.078272797 -0.0031300001, + -0.048467699 0.078153603 -0.0014909999, + -0.050219599 0.076808602 -0.0053119999, + -0.0465803 0.079535998 0.00064700301, + -0.0465803 0.079323597 0.0023119999, + -0.050219599 0.076724097 -0.003701, + 0.058412101 0.063156098 -0.000582001, + 0.058412101 0.064053401 -0.002965, + 0.058412101 0.065406598 -0.0080429995, + 0.0576833 0.066578001 -0.00535201, + 0.058412101 0.064808197 -0.0054569999, + 0.058998398 0.063744202 -0.0081840102, + 0.058998398 0.064237997 -0.010728, + 0.040174201 0.083870403 0.00130099, + -0.040174201 0.083058797 -0.010573, + -0.040174201 0.083344802 -0.0089290002, + -0.040174201 0.082721598 -0.012191, + -0.0378174 0.084424503 -0.00905299, + -0.0378174 0.084104799 -0.010695, + -0.026825599 0.053669199 -0.1815, + -0.040174201 0.083940603 -0.0021649899, + -0.040174201 0.083877303 -0.00388, + -0.0378174 0.085063502 -0.0039880099, + -0.0424264 0.082135797 0.0046660001, + -0.0424264 0.082351297 0.0029460001, + -0.044564299 0.080865398 0.0027020001, + -0.044564299 0.080619603 0.0043930099, + -0.035366699 0.083697699 0.017003, + -0.040174201 0.083033502 0.0082710003, + -0.0424264 0.081858002 0.0063820002, + -0.040174201 0.083341599 0.0065310099, + -0.0302257 0.088060103 0.0092120096, + -0.0302257 0.087783203 0.01104, + -0.0378174 0.085184902 0.00122701, + -0.0220857 0.091037497 0.0051199999, + -0.0220857 0.091034397 0.0032850001, + -0.027557701 0.088629998 0.012302, + -0.0248404 0.089705497 0.011577, + 0.019305199 0.0916899 0.0040939902, + 0.0165099 0.0922122 0.00294299, + -0.0220857 0.090126798 -0.0055850102, + -0.0248404 0.089617401 -0.004733, + 0.040174201 0.083751403 0.0030420099, + 0.0378174 0.084943399 0.0047539999, + 0.035366699 0.085826799 0.0081460001, + 0.035366699 0.086059399 0.00635699, + 0.035366699 0.085528798 0.00993401, + 0.0137106 0.088704102 0.026101001, + 0.0137106 0.089419603 0.024251999, + 0.0248404 0.087442897 0.020817, + 0.0081421202 0.0899579 0.025187001, + 0.0053918599 0.0901208 0.025469, + 0.0053918599 0.090786599 0.023587, + 0.0081421202 0.090618998 0.023308, + 0.0109179 0.0897251 0.024783, + 0.0109179 0.0890003 0.026637999, + 0.0081421202 0.088424802 0.028883999, + 0.0081421202 0.089226097 0.027047001, + 0.0109179 0.088206299 0.02847, + 0.0081421202 0.0875552 0.030694, + 0.0053918599 0.088577703 0.029173, + 0.0053918599 0.089384101 0.027333001, + 0.0165099 0.092240296 0.0066419998, + 0.019305199 0.091681801 0.0059409901, + 0.0165099 0.092257597 0.0047849999, + 0.0137106 0.092730999 0.0053599998, + 0.0109179 0.0919175 0.017211, + 0.0109179 0.092288397 0.015299, + 0.0137106 0.091578104 0.016705999, + 0.0165099 0.092158303 0.0085140103, + 0.019305199 0.0916095 0.0078019998, + 0.0165099 0.092009999 0.010396, + 0.0220857 0.090841502 0.0088309897, + 0.019305199 0.0914713 0.0096749999, + 0.0109179 0.090962902 0.021019001, + 0.0109179 0.090379402 0.022909001, + 0.0109179 0.091475703 0.019119, + 0.0137106 0.090065002 0.022383999, + 0.0081421202 0.0925529 0.015679, + 0.0081421202 0.092176102 0.017595001, + 0.0053918599 0.091381401 0.021689, + 0.0081421202 0.091728203 0.019508, + 0.0081421202 0.091209203 0.021414001, + 0.00267513 0.092463396 0.018021001, + 0.0053918599 0.092357002 0.017864, + 0.0053918599 0.091904901 0.019780001, + 0.00267513 0.092008799 0.01994, + 0.027557701 0.088618703 0.012302, + -0.0081421202 0.092929497 -0.001149, + -0.0081421202 0.092665702 -0.0029129901, + -0.0109179 0.0930833 0.0039650002, + -0.0081421202 0.093377002 0.0043119998, + -0.0109179 0.092988998 0.0021269999, + -0.0081421202 0.093287103 0.0024689899, + 0.0302257 0.087973297 -0.0050909999, + 0.0302257 0.087375604 -0.0084699998, + 0.0302257 0.087700799 -0.0067960098, + 0.027557701 0.088966899 -0.0039859898, + 0.019305199 0.091635801 0.00226401, + 0.019305199 0.091348201 -0.001339, + 0.0220857 0.090837799 -0.00033099399, + 0.019305199 0.091521204 0.00045199599, + 0.0165099 0.091940701 -0.00067999301, + 0.0220857 0.090962 0.00146899, + 0.0248404 0.090189703 0.00055799901, + 0.0248404 0.090054303 -0.001228, + 0.027557701 0.0891717 -0.0022380101, + 0.0053918599 0.078459397 0.044082999, + 0.0081421202 0.075532503 0.046542, + 0.0081421202 0.074057601 0.047837999, + 0.0081421202 0.076967299 0.045186002, + 0.0109179 0.075406499 0.046092, + 0.0109179 0.073940903 0.047387, + 0.00267513 0.0798731 0.042794, + 0.00267513 0.082428403 0.039693002, + 0.00267513 0.081177399 0.041269001, + 4.999222e-012 0.082451597 0.039751999, + 0.0081421202 0.079703003 0.042303, + 0.0081421202 0.078358501 0.043772001, + 0.0053918599 0.079810098 0.042613, + 0.0053918599 0.081110798 0.041088998, + 2.1903041e-012 0.079893902 0.042854, + -4.2478805e-013 0.0811994 0.041328002, + -0.00267513 0.074187703 0.048339002, + -0.0053918599 0.074140303 0.048154999, + 0.0053918599 0.0741392 0.048153002, + 0.0109179 0.080835603 0.040341999, + 0.0109179 0.082068399 0.038773, + 0.0137106 0.080623202 0.039765, + 0.0137106 0.079348996 0.041281, + 0.0109179 0.079549901 0.041861001, + 0.0081421202 0.080997497 0.040780999, + 0.0137106 0.083010301 0.036587, + 0.0109179 0.084363498 0.035494, + 0.0109179 0.085420899 0.033790998, + 0.0165099 0.081566602 0.037487999, + 0.0220857 0.079672702 0.037183002, + 0.0109179 0.086415201 0.032051001, + 0.0109179 0.087344103 0.030276, + -0.037814599 0.050999999 0.046576999, + -0.0378174 0.052789401 0.046107002, + -0.038010798 0.050999999 0.046424001, + -0.0356883 0.050999999 0.048232, + -0.038435601 0.046 0.046073001, + -0.0220857 0.070204303 0.046537999, + -0.0081421202 0.064572498 0.054303002, + -0.027557701 0.068216197 0.045108002, + -0.0248404 0.069948301 0.045348998, + -0.0599402 0.0042525502 -0.118078, + -0.059999999 0.0068492498 -0.117644, + -0.059999999 0.0034404199 -0.130063, + -0.059999999 0.00499911 -0.123817, + -0.0599402 0.00079678802 -0.130372, + -0.059999999 0.000121237 -0.155267, + -0.059999999 0.00052689301 -0.148982, + -0.059999999 -4.7590009e-005 -0.16150001, + -0.0599402 -0.0025654801 -0.155331, + -0.059980098 -0.00154487 -0.1815, + -0.035366699 -0.039964098 -0.12547299, + -0.047047202 0.046 0.037237, + -0.0328326 -0.041655999 -0.125756, + -0.0429691 0.046 0.041877002, + -0.0302257 -0.044429298 -0.12847, + -0.0328326 -0.0428662 -0.12822901, + -0.058412101 -0.0113924 -0.137619, + -0.058412101 -0.0124248 -0.14362501, + -0.0576833 -0.0152085 -0.14382, + -0.038047399 -0.046393901 -0.16150001, + -0.055787299 -0.0220578 -0.158657, + -0.055419099 -0.022994 -0.16150001, + -0.054342099 -0.0254349 -0.1815, + -0.0532961 -0.027528601 -0.158722, + -0.0528998 -0.0283127 -0.16150001, + -0.051830001 -0.0301961 -0.15875401, + -0.053283598 -0.0275514 -0.16150001, + -0.0542247 -0.025684301 -0.16150001, + -0.0546159 -0.024811899 -0.15869001, + -0.0532961 -0.026964899 -0.15027501, + -0.0532961 -0.0274198 -0.15592299, + -0.040174201 -0.043560401 -0.148426, + -0.0378174 -0.045940802 -0.15116701, + -0.040174201 -0.0431045 -0.145772, + -0.0378174 -0.0455685 -0.148543, + -0.035366699 -0.047448501 -0.148653, + -0.035366699 -0.045049999 -0.138216, + -0.0328326 -0.046778198 -0.13839699, + -0.035366699 -0.045788001 -0.14082, + -0.035366699 -0.048315 -0.15641899, + -0.034755301 -0.048887499 -0.16150001, + -0.0353618 -0.048460599 -0.16150001, + -0.035366699 -0.0484333 -0.158972, + -0.034765299 -0.048901699 -0.1815, + -0.0109179 -0.055436499 -0.139305, + -0.0081428103 -0.055876698 -0.13935199, + -0.0081428103 -0.056647401 -0.14183199, + -0.0109179 -0.056205899 -0.141791, + -0.0137106 -0.054858599 -0.139245, + -0.0137106 -0.053993799 -0.136765, + -0.0109179 -0.053605501 -0.134377, + -0.0109179 -0.052544098 -0.131945, + -0.0081428103 -0.0540425 -0.134433, + -0.0081428103 -0.0550084 -0.13688301, + -0.0109179 -0.054569699 -0.136832, + -0.0165099 -0.0512623 -0.13176399, + -0.0165099 -0.052318301 -0.134211, + -0.019305199 -0.050410099 -0.131643, + -0.0165099 -0.050110001 -0.129346, + -0.019305199 -0.049261801 -0.129215, + -0.0137106 -0.051972799 -0.131864, + -0.0137106 -0.053031798 -0.134303, + -0.0220857 -0.0494138 -0.131502, + -0.0248404 -0.0482715 -0.131341, + -0.0302257 -0.045554999 -0.13095701, + -0.027557701 -0.046984602 -0.13115899, + -0.0248404 -0.049314801 -0.13382301, + 0.00268824 -0.056363199 -0.139403, + -0.00268824 -0.057136599 -0.14187799, + -0.00268824 -0.056364302 -0.139403, + -7.5258385e-012 -0.057195202 -0.141884, + 8.1676358e-012 -0.057870299 -0.144365, + -0.00268824 -0.057811301 -0.14436001, + -0.0053973799 -0.056955799 -0.14186101, + -0.0053973799 -0.056184102 -0.139384, + 0.0081428103 -0.0550052 -0.136884, + 0.0137106 -0.058036 -0.15419701, + 0.0165099 -0.057011001 -0.15168899, + 0.0165099 -0.056623399 -0.14919201, + -0.0053973799 -0.054347798 -0.134473, + -0.0053973799 -0.0532832 -0.13204999, + -0.00268824 -0.053461399 -0.132076, + 0.0053973799 -0.059081201 -0.151786, + 0.00268824 -0.059563801 -0.15425099, + 0.00268824 -0.059774399 -0.156691, + 0.0081428103 -0.059278499 -0.156679, + 0.0053973799 -0.059380401 -0.154245, + 0.0053973799 -0.059590898 -0.15668701, + -0.0053918599 0.093348399 0.00088200398, + -0.0053918599 0.093143404 -0.00091700698, + -0.00267513 0.0926954 -0.0042849998, + -0.0053918599 0.092882201 -0.002685, + -0.019305199 0.090836197 -0.0048389998, + -0.0220857 0.090420902 -0.0038640001, + -0.0220857 0.090660699 -0.00211099, + -0.019305199 0.091526903 0.00044999699, + 0.037236601 0.047047202 -0.1815, + 0.058412101 0.065735802 -0.021771001, + 0.058998398 0.064707696 -0.018724, + 0.0576833 0.067582302 -0.016511001, + 0.056809202 0.069069698 -0.0155, + 0.058412101 0.066042297 -0.018983999, + 0.056809202 0.068969302 -0.016956, + 0.058412101 0.066160403 -0.016197, + 0.055787299 0.069510698 -0.021899, + 0.055787299 0.069821499 -0.020454001, + 0.056809202 0.068619803 -0.019854, + 0.056809202 0.068372197 -0.021291001, + 0.0576833 0.066932298 -0.022195, + 0.0576833 0.067353703 -0.019362001, + 0.056809202 0.068819098 -0.018408, + 0.055787299 0.0700844 -0.018995, + 0.055787299 0.070298404 -0.017525, + 0.0576833 0.066323698 -0.024991, + 0.056809202 0.067735702 -0.024129, + 0.0576833 0.065951303 -0.02637, + 0.058412101 0.064567603 -0.027269, + 0.056809202 0.068077199 -0.022717001, + 0.0576833 0.066651002 -0.023599001, + 0.058412101 0.065242402 -0.024538999, + -0.0165099 -0.0549054 -0.14167, + -0.0137106 -0.055626199 -0.141737, + -0.0137106 -0.0562969 -0.144236, + -0.0165099 -0.0555741 -0.144177, + -0.019305199 -0.054040801 -0.141589, + -0.0220857 -0.0551241 -0.151599, + -0.0220857 -0.055750102 -0.15906, + -0.0248404 -0.054579198 -0.15904599, + -0.0229499 -0.055437401 -0.16150001, + -0.0202034 -0.056496199 -0.16150001, + -0.019305199 -0.056771401 -0.159072, + -0.0302257 -0.049114801 -0.14113, + -0.0220857 -0.054738902 -0.14907999, + -0.027557701 -0.051786099 -0.14638001, + -0.0302257 -0.049768198 -0.143703, + -0.0248404 -0.0535722 -0.149012, + -0.027557701 -0.053139299 -0.156534, + -0.0302257 -0.0507975 -0.148849, + -0.0302257 -0.0511772 -0.15141299, + -0.0328326 -0.049193501 -0.148756, + -0.0328326 -0.048727401 -0.146166, + -0.0302257 -0.050328501 -0.14627799, + -0.027557701 -0.052257799 -0.14893501, + -0.0109179 -0.058835398 -0.15666901, + -0.0109179 -0.0589591 -0.159098, + -0.0137106 -0.058249999 -0.156655, + -0.0109179 -0.058625199 -0.154218, + -0.0137106 -0.058040202 -0.15419801, + -0.0081428103 -0.059281301 -0.15668, + -0.0081428103 -0.059405301 -0.15910301, + 0.00268824 -0.0588733 -0.149323, + 3.1337682e-012 -0.058933198 -0.149327, + -3.5225425e-013 -0.059324302 -0.151797, + 0.00268824 -0.059264299 -0.151794, + 0.0053973799 -0.0586906 -0.149312, + 8.2415212e-012 0.054555301 0.059023, + -0.00267513 0.054555301 0.058963001, + 2.6992916e-008 0.050999999 0.059999, + 4.7589994e-005 0.050999999 0.059999999, + 0.00267513 0.054553799 0.058961999, + -0.0053918599 0.067884997 0.052723002, + -0.00267513 0.067917101 0.052909002, + -0.0053918599 0.066258103 0.053704999, + -0.0053918599 0.069490798 0.051676001, + -0.00267513 0.069526799 0.051862001, + -4.1944664e-012 0.056234501 0.058490999, + 0.0053918599 0.067884304 0.052722, + 0.00267513 0.069526397 0.051862001, + 0.0053918599 0.066257402 0.053702999, + 0.00267513 0.067916803 0.052908, + 0.0053918599 0.069490001 0.051674999, + 0.00267513 0.071110599 0.050749999, + 0.00267513 0.072665401 0.049575999, + 0.0109179 0.059555501 0.05621, + 0.0081421202 0.0612588 0.055939998, + 0.0109153 0.050999999 0.058984, + 0.0137813 0.046 0.058396, + 0.0077038999 0.046 0.059503, + 0.0088465102 0.050999999 0.059344001, + 0.0081404904 0.050999999 0.059432, + 0.0059254402 0.050999999 0.059707001, + 0.0109179 0.057882901 0.056875002, + 0.0053918599 0.056226399 0.058244999, + 0.0053918599 0.054550499 0.058777999, + 0.00267513 0.056232199 0.058430001, + 0.00267513 0.057928499 0.057829998, + 0.0053918599 0.059608102 0.056981001, + 0.0081421202 0.059586499 0.056664001, + 0.00267513 0.059620801 0.057167999, + 0.0053918599 0.0579197 0.057643998, + 0.0081421202 0.057904501 0.057328001, + 0.044564299 0.067922503 0.029558999, + 0.044564299 0.066784203 0.030680001, + 0.044564299 0.072146997 0.024584999, + 0.0465803 0.071387701 0.022239, + 0.048467699 0.0696944 0.021088, + 0.027557701 0.086755902 0.019622, + 0.027557701 0.087323301 0.017809, + 0.0302257 0.086537898 0.016497999, + 0.035366699 0.081627898 0.022107, + 0.0328326 0.082424097 0.023761, + 0.019305199 0.0788 0.039693002, + 0.0220857 0.078450099 0.038681999, + 0.019305199 0.080042697 0.038187999, + 0.0165099 0.079099298 0.040559001, + 0.0220857 0.077178702 0.040130001, + 0.0165099 0.080359198 0.039048001, + 0.0137106 0.076654904 0.044151999, + 0.0109179 0.076832101 0.044739, + 0.0109179 0.078214303 0.043327998, + 0.0137106 0.078025199 0.042744, + 0.0137106 0.075241297 0.045503002, + 0.0302257 0.080375597 0.030206, + 0.0328326 0.079731204 0.028646, + 0.0302257 0.065027997 0.045620002, + 0.0302257 0.066485599 0.044643998, + 0.027557701 0.0696555 0.044002999, + 0.027557701 0.071070202 0.042846002, + 0.027557701 0.075108901 0.039030999, + 0.027557701 0.076375604 0.037648998, + 0.0248404 0.076801002 0.038963001, + 0.0248404 0.074171901 0.041685, + 0.0248404 0.075507604 0.040352002, + 0.027557701 0.073800303 0.040359002, + 0.027557701 0.072452903 0.041630998, + 0.044564299 0.051886 0.039942, + 0.046393901 0.050999999 0.038047001, + 0.0465759 0.050999999 0.037813999, + 0.044564299 0.052748099 0.039673001, + 0.044564299 0.056970801 0.037792001, + 0.044564299 0.0582457 0.037078999, + 0.0465803 0.056856599 0.035402998, + 0.044564299 0.055666801 0.038462002, + 0.050209999 0.050999999 0.032827001, + 0.0248404 0.052827898 0.054111999, + 0.0248404 0.054475199 0.053613, + 0.025684301 0.050999999 0.054225001, + 0.0275514 0.050999999 0.053284001, + 0.035366699 0.061687998 0.043965001, + 0.0328326 0.061884701 0.04575, + 0.0109179 0.072438903 0.048620999, + 0.0165099 0.0659355 0.051587999, + 0.0081421202 0.072546199 0.049073, + 0.0053918599 0.071070299 0.050563999, + 0.0053918599 0.072621301 0.049389999, + 0.0248404 0.068473101 0.046443, + 0.0248404 0.0699443 0.045343, + 0.0220857 0.070200801 0.046532001, + 0.0220857 0.068704702 0.047635, + 0.027557701 0.068212204 0.0451, + 0.027557701 0.066744097 0.046138, + 0.0248404 0.0654599 0.048459999, + 0.0248404 0.066976897 0.047481999, + 0.0248404 0.063925803 0.049377002, + 0.027557701 0.065255202 0.047115002, + 0.027557701 0.063749403 0.048030999, + 0.0109179 0.070904002 0.049793001, + 0.0137106 0.069223702 0.050306, + 0.0081421202 0.071001798 0.050246999, + 0.027557701 0.060699701 0.049679, + 0.0248404 0.059250802 0.051755, + 0.0248404 0.0608197 0.051022999, + 0.027557701 0.059158999 0.050414, + 0.0248404 0.056077398 0.053050999, + 0.0248404 0.057670601 0.052432001, + 0.027557701 0.0576066 0.051093999, + 0.036012899 0.046 0.047990002, + 0.030873001 0.050999999 0.051447999, + 0.033358999 0.050999999 0.049872, + 0.0328326 0.052803401 0.049716, + 0.027557701 0.056039698 0.051718, + 0.031537499 0.052808002 0.050539002, + 0.050219599 0.055459101 0.031044999, + 0.051830001 0.054135501 0.029123001, + 0.0546159 0.0552334 0.022971001, + 0.048467699 0.065732501 0.025800001, + 0.048467699 0.0635828 0.027873, + 0.048467699 0.064669199 0.026861001, + 0.0465803 0.065153398 0.029354, + 0.035878699 -0.0480907 -0.16150001, + 0.0424264 -0.0417872 -0.15097301, + 0.0529892 -0.028145101 -0.16150001, + 0.053285599 -0.0275524 -0.16150001, + 0.0484627 -0.035363302 -0.16150001, + 0.050219599 -0.0327884 -0.15878201, + 0.049977001 -0.033201002 -0.16150001, + 0.059999999 0.00054109597 -0.148984, + 0.0465803 -0.035232101 -0.139843, + 0.048467699 -0.033419602 -0.14237601, + 0.048467699 -0.032806199 -0.13961799, + 0.044564299 -0.038727701 -0.14546999, + 0.044564299 -0.038190499 -0.142764, + 0.0465803 -0.035851698 -0.142574, + 0.0465803 -0.0363838 -0.14530601, + 0.044564299 -0.039177299 -0.148173, + 0.044564299 -0.03954 -0.150868, + 0.0424264 -0.039794501 -0.140268, + 0.044564299 -0.037565 -0.14005999, + 0.044564299 -0.036850501 -0.137363, + 0.0424264 -0.040425699 -0.142946, + 0.040174201 -0.042547401 -0.14311901, + 0.040174201 -0.041910801 -0.14046399, + 0.0378174 -0.043173298 -0.138024, + 0.0378174 -0.043906499 -0.14065, + 0.0424264 -0.0382623 -0.13493501, + 0.0424264 -0.0390734 -0.137595, + 0.044564299 -0.036047 -0.13467599, + 0.044564299 -0.035154 -0.132006, + 0.0424264 -0.037360799 -0.13229001, + 0.040174201 -0.0403651 -0.13518, + 0.040174201 -0.041183401 -0.137816, + 0.0240272 -0.054979 -0.1815, + 0.0220857 -0.055413298 -0.15410399, + 0.0258127 -0.054163702 -0.16150001, + 0.0248338 -0.054601099 -0.16150001, + 0.0240207 -0.054964401 -0.16150001, + 0.0231252 -0.055364501 -0.16150001, + 0.0302184 -0.051817201 -0.16150001, + 0.029552899 -0.0522171 -0.1815, + 0.034765299 -0.048901699 -0.1815, + 0.051830001 -0.027032301 -0.136335, + 0.0532961 -0.024399299 -0.136059, + 0.0532961 -0.023638001 -0.13323, + 0.050219599 -0.029604999 -0.136604, + 0.050219599 -0.030297801 -0.139384, + 0.051830001 -0.023439299 -0.125247, + 0.0532961 -0.0208486 -0.124848, + 0.059999999 0.058557302 -0.012154, + 0.059757002 0.062032402 -0.021122999, + 0.059999999 0.0596097 -0.023651, + 0.0599402 0.060709901 -0.023630001, + 0.059999999 0.059397601 -0.026117001, + 0.059999999 0.059669599 -0.021222999, + 0.0599402 0.060830701 -0.021113001, + 0.059445001 0.062979497 -0.023902001, + 0.059757002 0.061836202 -0.02372, + 0.059445001 0.063264199 -0.021235, + 0.058998398 0.064506002 -0.021451, + 0.059445001 0.062518001 -0.026564, + 0.059757002 0.061469201 -0.026327001, + 0.058998398 0.064121798 -0.024174999, + 0.059757002 0.061928 -0.016034, + 0.0599402 0.060794398 -0.018639, + 0.059757002 0.062061299 -0.018556001, + 0.059445001 0.063308299 -0.015964, + 0.059445001 0.063076802 -0.013395, + 0.0576833 0.067457199 -0.010842, + 0.0576833 0.0676165 -0.013664, + 0.058412101 0.066090599 -0.013432, + 0.0576833 0.067108899 -0.0080650002, + 0.058412101 0.065837301 -0.010708, + 0.059999999 0.053174399 -0.000822998, + 0.0599402 0.053758301 0.00147701, + 0.059445001 0.0518023 0.0079490095, + 0.059351299 0.050999999 0.0087989997, + 0.0599402 0.0578226 -0.0054139998, + 0.0599402 0.056098301 -0.001834, + 0.059999999 0.0558539 -0.0045700101, + 0.0599402 0.0569885 -0.0035659899, + 0.059999999 0.057348799 -0.0081519904, + 0.059999999 0.057996601 -0.010102, + 0.059999999 0.056629401 -0.0063060001, + 0.056809202 -0.0117792 -0.120772, + 0.055787299 -0.0155354 -0.124031, + 0.059445001 7.9036006e-005 -0.11602, + 0.059757002 0.0027163799 -0.115543, + 0.058998398 0.052588601 0.010434, + 0.057668701 0.050999999 0.016505999, + 0.0576833 0.0518241 0.016306, + 0.058412101 0.0526038 0.013224, + 0.058848299 0.050999999 0.011699, + 0.058998398 0.051809501 0.01072, + 0.055787299 -0.0196603 -0.138395, + 0.0546159 -0.022386899 -0.138649, + 0.0546159 -0.022973601 -0.141525, + 0.056809202 -0.016908299 -0.13813899, + 0.050219599 0.073408902 0.010339, + 0.051830001 0.071732901 0.0092669996, + 0.051830001 0.074751601 -0.001254, + 0.050219599 0.0761078 0.001105, + 0.0532961 0.073133998 -0.002138, + 0.048467699 0.075098701 0.01127, + 0.044564299 0.079927497 0.0077489899, + 0.0424264 0.061009798 0.037808001, + 0.051830001 0.072317801 0.00783299, + 0.0546159 0.071524203 -0.0031349901, + -0.0576833 0.058840498 0.010538, + -0.058412101 0.057101 0.0093970001, + -0.058412101 0.058466598 0.0076840101, + -0.056809202 0.059213798 0.013387, + -0.0576833 0.055824298 0.013805, + -0.058412101 0.0549464 0.01173, + -0.0576833 0.0550249 0.014558, + -0.0576833 0.057355501 0.012246, + -0.056809202 0.057609599 0.015091, + -0.058412101 0.0621427 0.00169701, + -0.0576833 0.064014502 0.00223399, + -0.055787299 0.066333398 0.0065919999, + -0.056809202 0.064858198 0.0050310101, + -0.055787299 0.065697402 0.0078130001, + -0.0546159 0.067875199 0.0080629997, + -0.0546159 0.067220502 0.0093339998, + -0.056809202 0.060759101 0.011527, + -0.055787299 0.064325497 0.010148, + -0.055787299 0.0628362 0.012332, + -0.0322018 0.050626501 -0.1815, + -0.0465803 0.078488298 -0.015659001, + -0.058998398 0.064529702 -0.021447999, + -0.059445001 0.063287497 -0.021229999, + -0.059445001 0.063003302 -0.023899, + -0.058998398 0.064145803 -0.024174999, + -0.058412101 0.066065699 -0.018981, + -0.058412101 0.065759599 -0.021771001, + -0.059999999 0.059630901 -0.023642, + -0.059999999 0.0585244 -0.031091999, + -0.0599402 0.059390102 -0.031259, + -0.059757002 0.0609557 -0.028927, + -0.059757002 0.060660299 -0.0088849897, + -0.0599402 0.0592697 -0.0094250003, + -0.059757002 0.059975799 -0.0066920002, + -0.059445001 0.062164601 -0.00846201, + -0.059445001 0.061489001 -0.0061380002, + -0.0599402 0.060814101 -0.018626999, + -0.059757002 0.062082399 -0.018546, + -0.059999999 0.059031099 -0.014285, + -0.059999999 0.059379499 -0.016519999, + -0.059999999 0.0596026 -0.018833, + -0.0599402 0.059842501 -0.011595, + -0.059999999 0.058568899 -0.012138, + -0.059999999 0.056635499 -0.0062930002, + -0.059999999 0.0550243 -0.00293201, + -0.059445001 -0.0058820401 -0.137106, + -0.059445001 -0.0068882201 -0.14323699, + -0.059757002 -0.00316488 -0.13685399, + -0.058998398 -0.0096477596 -0.14342999, + -0.058998398 -0.0086284801 -0.137362, + -0.058998398 -0.0080016097 -0.134334, + -0.058412101 -0.0083750403 -0.125705, + -0.058998398 -0.0056509101 -0.12532, + -0.058412101 -0.0092482101 -0.12866201, + -0.058412101 -0.0074233902 -0.122769, + -0.058998398 -0.00471202 -0.122352, + -0.0576833 -0.0119905 -0.129015, + -0.059923101 0.050999999 0.0030370001, + -0.0599402 0.051789701 0.0025170001, + -0.059431199 0.050999999 0.0081410101, + -0.059337199 0.050999999 0.0088930102, + -0.058998398 0.0518112 0.010736, + -0.0532961 -0.019769 -0.122094, + -0.056793701 0.050999999 0.019300001, + -0.056464098 0.050999999 0.020292999, + -0.048467699 0.065740302 0.025813, + -0.0465803 0.067365497 0.027185, + -0.048467699 0.066778101 0.024704, + -0.050219599 0.064175896 0.024296001, + -0.050219599 0.065186203 0.023241, + -0.051830001 0.0655457 0.0195, + -0.051830001 0.066446997 0.018361, + -0.050219599 0.067126296 0.020992, + -0.050219599 0.066170603 0.022139, + -0.051830001 0.064616203 0.020594999, + -0.0532961 0.0640328 0.017887, + -0.0532961 0.064906098 0.016798999, + -0.0532961 0.062213302 0.019932, + -0.051830001 0.063661098 0.021645, + -0.0532961 0.063134201 0.018931, + -0.0546159 0.061734501 0.017163999, + -0.051830001 0.062683403 0.022648999, + -0.0532961 0.0612728 0.020888001, + -0.0546159 0.059953 0.019029999, + -0.0328326 0.076553002 0.033178002, + -0.0302257 0.077103503 0.034772001, + -0.0302257 0.078248799 0.033296999, + -0.040174201 0.070183396 0.032827999, + -0.0302257 0.067926802 0.043616999, + -0.027557701 0.069659904 0.044009998, + -0.035366699 0.0527994 0.047991998, + -0.035366699 0.0544081 0.047451999, + -0.0328326 0.064782202 0.043986, + -0.0302257 0.0664896 0.044652, + -0.0328326 0.066206001 0.043012001, + -0.035366699 0.064511001 0.042201001, + -0.040174201 0.058548 0.041549999, + -0.0424264 0.057080001 0.040077001, + -0.044564299 0.056970902 0.037792999, + -0.0378174 0.061478999 0.042048, + -0.0378174 0.062855802 0.041191, + -0.035366699 0.061690699 0.043970998, + -0.0378174 0.060089398 0.042849999, + -0.035366699 0.063107699 0.043115001, + -0.051830001 0.0554092 0.028413, + -0.051830001 0.056488801 0.027708, + -0.051830001 0.057548702 0.026982, + -0.048467699 0.060220901 0.030623, + -0.050219599 0.0588395 0.028859001, + -0.050219599 0.059936602 0.028041, + -0.048467699 0.061358601 0.029759999, + -0.0465803 0.060495902 0.033119999, + -0.048467699 0.062482301 0.028848, + -0.044564299 0.063226797 0.033748001, + -0.0424264 0.064833097 0.035075001, + -0.0424264 0.063575603 0.036042999, + -0.044564299 0.062000498 0.034660999, + -0.0465803 0.061685801 0.032258999, + -0.0465803 0.0628618 0.031346001, + -0.058021698 0.046 0.01528, + -0.048467699 0.0579069 0.032205001, + -0.0465803 0.0592927 0.033932, + -0.048467699 0.059069902 0.031438001, + -0.0465803 0.0580777 0.034694999, + -0.050219599 0.057730298 0.02963, + -0.050219599 0.056615099 0.030351, + -0.050219599 0.055482101 0.031047, + -0.048467699 0.0567379 0.032919999, + -0.0465803 0.056856699 0.035404, + -0.055787299 0.067494698 0.0040509901, + -0.056809202 0.065982297 0.0025850099, + -0.055787299 0.0669332 0.0053370101, + -0.0546159 0.068490803 0.006759, + 0.0081421202 0.084550798 0.035923, + 0.0053918599 0.085753098 0.034515001, + 0.00267513 0.085833497 0.034689002, + -0.0220857 0.088666901 0.020037999, + -0.0248404 0.0880403 0.018990999, + -0.0220857 0.0880614 0.021879001, + -0.0248404 0.087452598 0.020819001, + -0.0109179 0.093115903 0.0058220099, + -0.019305199 0.091689199 0.0059389998, + -0.0137106 0.092735998 0.0053589898, + -0.0081421202 0.091212399 0.021414001, + -0.0137106 0.089424998 0.024253, + -0.0165099 0.088342302 0.025436001, + -0.019305199 0.087901898 0.024636, + -0.035366699 0.074828297 0.032850999, + -0.0378174 0.071917601 0.033617001, + -0.0378174 0.0707087 0.034862999, + -0.0378174 0.069465801 0.036056001, + -0.035366699 0.077033497 0.029991999, + -0.035366699 0.078063503 0.028494, + -0.035366699 0.075954102 0.031445, + -0.0328326 0.077666797 0.031714, + -0.0378174 0.075308897 0.029577, + -0.0328326 0.078730501 0.030205, + -0.0378174 0.076351203 0.028136, + -0.0378174 0.077344798 0.026651001, + -0.040174201 0.071350597 0.031590998, + -0.0378174 0.073089197 0.03232, + -0.0378174 0.074220598 0.030972, + -0.019305199 0.086317703 0.028231001, + -0.0248404 0.083513997 0.029618001, + -0.0248404 0.082535602 0.031284999, + -0.0220857 0.084024802 0.030734001, + -0.0220857 0.084962599 0.029022001, + -0.0248404 0.084431 0.027915999, + -0.027557701 0.082938299 0.028361, + -0.027557701 0.081983902 0.030015999, + -0.0220857 0.081966303 0.034047, + -0.019305199 0.082374498 0.035037, + -0.019305199 0.083452404 0.033392001, + -0.0220857 0.083025299 0.03241, + -0.0248404 0.081498303 0.032912001, + -0.0248404 0.080404103 0.034497, + -0.027557701 0.078778699 0.034738999, + -0.0248404 0.0755134 0.040358, + -0.0220857 0.0771842 0.040135, + -0.0424264 0.068470202 0.031851001, + -0.044564299 0.0679304 0.029571, + -0.0465803 0.075510502 0.015139, + -0.048467699 0.0730744 0.015702, + -0.048467699 0.073804498 0.014259, + -0.044564299 0.076496199 0.017405, + -0.0465803 0.074784197 0.016634, + -0.040174201 0.077481203 0.023172, + -0.0378174 0.078286998 0.025126001, + -0.040174201 0.08117 0.015119, + -0.040174201 0.080549203 0.016786, + -0.0378174 0.0821537 0.016984001, + -0.0378174 0.0827462 0.015276, + -0.035366699 0.082388401 0.020435, + -0.0378174 0.0814991 0.018671, + -0.0328326 0.082435697 0.023766, + -0.0302257 0.083166704 0.025287, + -0.0328326 0.081596203 0.025429999, + -0.0328326 0.083213799 0.022072, + -0.0302257 0.083972499 0.023577999, + -0.044564299 0.0778751 0.014284, + -0.044564299 0.077213198 0.015859, + -0.0424264 0.0788977 0.016410001, + -0.0424264 0.079541802 0.014788, + -0.044564299 0.080312803 0.0060780002, + -0.0424264 0.081518099 0.0080920001, + -0.040174201 0.082227498 0.011724, + -0.0424264 0.081115998 0.0097899903, + -0.040174201 0.082662098 0.010003, + -0.0378174 0.083275601 0.013548, + -0.040174201 0.0817298 0.013431, + -0.0378174 0.083741002 0.011806, + -0.050219599 0.072791398 0.011804, + -0.044564299 0.079027802 0.011058, + -0.044564299 0.0784804 0.012682, + -0.0424264 0.080126897 0.013141, + -0.0424264 0.080651902 0.011474, + -0.0081421202 0.084553503 0.035925001, + -0.0109179 0.084367 0.035496, + -0.0081421202 0.085619099 0.034219, + -0.0053918599 0.084683597 0.036224999, + -0.0109179 0.0832486 0.037158001, + -0.0053918599 0.085754901 0.034515999, + -3.3821877e-013 0.084784403 0.036458001, + -3.2397958e-012 0.0836474 0.038127001, + 6.1328681e-012 0.085859999 0.034747001, + -0.00267513 0.084759802 0.036401, + -0.00267513 0.083623901 0.038070001, + -0.0081421202 0.082241401 0.039211001, + -0.0109179 0.082071699 0.038775001, + -0.0081421202 0.083426803 0.037590001, + -0.0109179 0.080838703 0.040344, + -0.0053918599 0.083551101 0.037891999, + -0.0053918599 0.078460701 0.044085, + -0.0081421202 0.078360498 0.043774001, + -0.00267513 0.0798738 0.042794999, + -0.0081421202 0.076969102 0.045187999, + -0.0053918599 0.081112303 0.04109, + -0.0053918599 0.079811603 0.042614002, + -0.00267513 0.081178203 0.041269999, + -0.00267513 0.0824292 0.039694, + -0.0053918599 0.082359903 0.039515, + -0.0081421202 0.080999799 0.040782999, + -0.0081421202 0.079705201 0.042305, + -0.0576833 0.065973498 -0.026374999, + -0.0497806 0.033494599 -0.1815, + -0.058412101 0.064590901 -0.027274, + -0.0576833 0.066346698 -0.024995999, + -0.056809202 0.068395302 -0.021295, + -0.056809202 0.068099901 -0.022721, + -0.056809202 0.068643101 -0.019856, + -0.0576833 0.066955902 -0.022198001, + -0.0576833 0.066674396 -0.023603, + -0.055787299 0.069173597 -0.023335001, + -0.056809202 0.067757599 -0.024134001, + -0.0460728 0.038435601 -0.1815, + -0.041876599 0.0429691 -0.1815, + -0.0546159 0.071290299 -0.019695999, + -0.055787299 0.069843702 -0.020458, + -0.055787299 0.069532201 -0.021904999, + -0.0546159 0.070960797 -0.021159001, + -0.044564299 0.080084898 -0.013882, + -0.0424264 0.081916101 -0.010566, + -0.0424264 0.081610598 -0.012184, + -0.058412101 0.064068899 -0.0029509999, + -0.058998398 0.062326599 -0.00336099, + -0.058412101 0.063169599 -0.000567001, + -0.0576833 0.065892003 -0.0027109999, + -0.058412101 0.064825602 -0.005444, + -0.058998398 0.063113801 -0.005715, + -0.0576833 0.065026298 -0.000181, + -0.058998398 0.064730801 -0.018719001, + -0.059445001 0.063394897 -0.018576, + -0.058998398 0.063761801 -0.0081710098, + -0.058412101 0.065425701 -0.0080319997, + -0.056809202 0.068992503 -0.016956, + -0.051830001 0.0753024 -0.0075559998, + -0.055787299 0.070485502 -0.016047999, + -0.044564299 0.081050202 0.001008, + -0.0465803 0.079688698 -0.001021, + -0.048467699 0.078336596 -0.0064040101, + -0.050219599 0.076836102 -0.0069220001, + -0.048467699 0.078333497 -0.0047690002, + -0.051830001 0.075295702 -0.0091349902, + -0.050219599 0.076582402 -0.0020910001, + -0.050219599 0.076383501 -0.00048700001, + 0.059757002 0.061209701 -0.011193, + 0.059445001 0.062686898 -0.010894, + 0.059757002 0.0616409 -0.013575, + 0.0599402 0.059828699 -0.011611, + 0.0599402 0.058584601 -0.007373, + 0.059757002 0.059177101 -0.004623, + 0.0599402 0.059257999 -0.0094409902, + 0.058412101 0.062131301 0.00168201, + 0.058998398 0.061403301 -0.00113699, + 0.059445001 0.061475299 -0.0061530001, + 0.058998398 0.063098103 -0.0057290001, + 0.059445001 0.062148798 -0.0084760003, + 0.059757002 0.059964199 -0.0067070001, + 0.059445001 0.060679901 -0.0039369999, + 0.058998398 0.062313002 -0.0033760101, + 0.059757002 0.0606465 -0.0088999895, + 0.051830001 0.075232498 -0.0059750099, + 0.0532961 0.073660098 -0.0067530102, + 0.0532961 0.073726803 -0.0083020004, + 0.055787299 0.0705764 -0.014562, + 0.0546159 0.0719615 -0.015218, + 0.055787299 0.070462704 -0.016047001, + 0.0532961 0.073697299 -0.0114, + 0.0532961 0.073739201 -0.0098520098, + 0.0546159 0.072168604 -0.012191, + 0.0546159 0.072090998 -0.013707, + 0.0424264 0.081600502 -0.012179, + 0.035366699 0.085393198 -0.0092899902, + 0.0328326 0.086881898 -0.00630499, + 0.0328326 0.086595602 -0.0079900101, + 0.0328326 0.087291799 -0.0028609899, + 0.035366699 0.086136997 -0.004224, + 0.0328326 0.087114498 -0.0045939898, + 0.035366699 0.086274698 -0.0024929999, + 0.0302257 0.088191301 -0.00336099, + 0.0424264 0.082334101 0.0029460001, + 0.0424264 0.082487397 0.00122701, + 0.035366699 0.086332098 0.00278799, + 0.035366699 0.086227603 0.0045700101, + 0.0378174 0.085169502 0.0012300001, + 0.0378174 0.085087799 0.0029889999, + 0.0378174 0.085149102 -0.00225999, + 0.0378174 0.085189603 -0.00052099599, + -0.035366699 0.085703 -0.0076299999, + -0.0378174 0.084692098 -0.0073849899, + -0.0378174 0.084905699 -0.0056950101, + -0.0328326 0.087108798 0.0078439899, + -0.0302257 0.088270597 0.0073839999, + -0.035366699 0.0855432 0.009935, + -0.035366699 0.085841201 0.0081460001, + -0.0378174 0.084478699 0.008289, + -0.0378174 0.084141999 0.010052, + -0.035366699 0.085179701 0.011719, + -0.0328326 0.0865312 0.011463, + -0.0328326 0.086853102 0.0096540097, + -0.040174201 0.083767898 0.0030410001, + -0.040174201 0.083586402 0.0047860001, + -0.0378174 0.084751002 0.0065219998, + -0.035366699 0.086242102 0.0045679901, + -0.0378174 0.085103303 0.0029869999, + -0.035366699 0.0863465 0.002786, + -0.0328326 0.087298997 0.0060350001, + -0.035366699 0.086073898 0.006356, + -0.0378174 0.084958903 0.0047530099, + -0.0328326 0.087424599 0.0042319898, + -0.027557701 0.0894152 0.0049419999, + -0.027557701 0.0894484 0.00312199, + -0.0302257 0.088496096 0.0037479999, + -0.0302257 0.0884156 0.005562, + -0.027557701 0.089317799 0.0067729899, + -0.0248404 0.090242498 0.00601601, + -0.0248404 0.090290301 0.0041809999, + -0.0248404 0.0902749 0.00236, + -0.0220857 0.090969399 0.001467, + -0.0220857 0.090844199 -0.00033299299, + -0.027557701 0.0889735 -0.0039900099, + -0.0248404 0.089867398 -0.002995, + -0.0328326 0.086889699 -0.0063090101, + -0.0302257 0.087980501 -0.0050949999, + -0.035366699 0.0859534 -0.0059389998, + -0.0165099 0.092217699 0.0029420001, + -0.019305199 0.091697 0.004092, + -0.019305199 0.091642201 0.00226199, + -0.0165099 0.092263602 0.0047829999, + -0.0137106 0.092697501 0.0035089999, + -0.0220857 0.090850502 0.0088299997, + -0.0053918599 0.093495302 0.0027079899, + -0.0081421202 0.093405098 0.0061750002, + 0.0424264 0.081501201 0.0080890004, + 0.040174201 0.083325401 0.0065299999, + 0.0378174 0.084735602 0.0065219998, + 0.0378174 0.084463403 0.0082879895, + 0.040174201 0.083570004 0.0047860001, + 0.040174201 0.083017401 0.0082689999, + 0.0424264 0.082118601 0.0046649901, + 0.0424264 0.081840999 0.0063809999, + 0.0378174 0.083725996 0.011803, + 0.0378174 0.0841268 0.01005, + 0.040174201 0.082646199 0.010001, + 0.035366699 0.084736899 0.013491, + 0.035366699 0.085165501 0.011717, + -0.00267513 0.092464499 0.018021001, + -0.0053918599 0.0923592 0.017864, + -0.0053918599 0.091907099 0.019780001, + -0.00267513 0.092009798 0.01994, + -4.015004e-012 0.092498504 0.018073, + 6.7380394e-012 0.092882603 0.01615, + 0.0302257 0.083155997 0.025281999, + 0.0137106 0.087067299 0.029727999, + 0.0137106 0.0879196 0.027928, + 0.0137106 0.0861485 0.031497002, + 0.027557701 0.086121 0.021419, + 0.0302257 0.083961397 0.023573, + 0.0248404 0.089000002 0.015296, + 0.027557701 0.088254802 0.014145, + 0.027557701 0.087823004 0.015982, + 0.0220857 0.090388298 0.012573, + 0.0220857 0.090648599 0.0107, + 0.0248404 0.089695297 0.011578, + 0.0248404 0.089382 0.013438, + 0.0220857 0.090059496 0.014447, + 0.019305199 0.091265999 0.011556, + 0.0302257 0.087770902 0.01104, + 0.0328326 0.086839698 0.0096540097, + -0.0109179 0.092355803 -0.00324001, + 0.0109179 0.092621297 -0.001479, + 0.0137106 0.092434898 -0.00013000501, + 0.0137106 0.091947101 -0.003666, + 0.0165099 0.091718398 -0.00245399, + 0.0165099 0.091440797 -0.0041979998, + 0.0137106 0.092218801 -0.001914, + 0.00923343 0.059285302 -0.1815, + 0.0109179 0.092354402 -0.00323801, + 0.0109179 0.092033401 -0.0049609998, + 0.0220857 0.090416901 -0.0038609901, + 0.0248404 0.0898614 -0.002991, + 0.0220857 0.090655498 -0.00210899, + 0.019305199 0.091118403 -0.0031030001, + 0.019305199 0.090833701 -0.004836, + 0.0248404 0.0893104 -0.0064369999, + 0.027557701 0.0883938 -0.0073999902, + 0.027557701 0.088707 -0.0057079899, + 0.0248404 0.089612901 -0.0047289999, + 0.0152803 0.058021698 -0.1815, + 0.0220857 0.090124004 -0.0055820001, + 0.0248404 0.090265803 0.0023620001, + 0.0220857 0.091026403 0.0032870001, + 0.035366699 0.0863543 -0.00074600201, + 0.035366699 0.086374 0.001015, + 0.0302257 0.088484101 0.0037510099, + 0.027557701 0.089437798 0.003125, + 0.0328326 0.0874734 0.00244, + 0.0328326 0.087411299 0.0042339899, + 0.0302257 0.088457301 0.00016200299, + 0.0328326 0.087411903 -0.00111, + 0.0302257 0.088353299 -0.00160899, + 0.0302257 0.088501498 0.00194901, + 0.027557701 0.089409001 0.0013200101, + 0.0328326 0.087473102 0.00065800501, + 0.027557701 0.089319699 -0.00046800199, + 0.027557701 0.088914797 0.010457, + 0.0248404 0.089940898 0.00971899, + -0.00267513 0.077118002 0.045683, + -0.00267513 0.078519396 0.044266999, + -0.0053918599 0.077063002 0.045499999, + -0.0053918599 0.075621702 0.046856999, + 0.00267513 0.077117398 0.045682002, + 0.0053918599 0.077061802 0.045499001, + 0.00267513 0.078518704 0.044266, + 0.0053918599 0.075620599 0.046856001, + 6.5636815e-012 0.078538299 0.044326, + -0.0328326 0.052808698 0.049741998, + -0.0307914 0.050999999 0.051497001, + -0.035366699 0.0573727 0.046201002, + -0.035366699 0.055918399 0.046840999, + -0.0328326 0.0544312 0.049210001, + -0.019305199 0.070427597 0.047575001, + -0.0109179 0.069341302 0.050905, + -0.0081421202 0.066209897 0.053387001, + -0.0081421202 0.067830198 0.052405, + -0.0599402 -0.00146406 -0.142858, + -0.059999999 0.00120921 -0.142671, + -0.059999999 0.00217697 -0.13635699, + -0.0599402 -0.000483624 -0.136604, + -0.0599402 -0.0021549801 -0.14910799, + -0.059757002 -0.0041581001 -0.14304601, + -0.059757002 -0.0048576999 -0.149235, + -0.059757002 -0.000265904 -0.12456, + -0.0599402 0.0023767899 -0.124187, + -0.059757002 0.00064776099 -0.121526, + -0.059757002 -0.00186738 -0.13068201, + -0.059445001 -0.00294398 -0.124938, + -0.059445001 -0.0045672101 -0.130997, + -0.0328326 -0.045940898 -0.13582399, + -0.0328326 -0.043984499 -0.130735, + -0.0328326 -0.045009602 -0.133268, + -0.056143001 0.046 0.021165, + -0.0546159 -0.0182289 -0.124433, + -0.0546159 -0.017144499 -0.121656, + -0.0532961 -0.020866901 -0.124839, + -0.055787299 -0.0144838 -0.121211, + -0.051830001 -0.0270526 -0.13632999, + -0.057668298 -0.0165058 -0.16150001, + -0.0581921 -0.0146178 -0.16150001, + -0.0583959 -0.0137813 -0.1815, + -0.0576833 -0.016379001 -0.15566, + -0.0566587 -0.019709 -0.16150001, + -0.0574052 -0.017454101 -0.16150001, + -0.056809202 -0.0191726 -0.155726, + -0.056480099 -0.0202484 -0.16150001, + -0.056669399 -0.0197125 -0.1815, + -0.056809202 -0.0162776 -0.13520101, + -0.0576833 -0.0135194 -0.134912, + -0.0576833 -0.0127952 -0.13195699, + -0.056809202 -0.0155439 -0.132277, + -0.0576833 -0.0147254 -0.140847, + -0.0576833 -0.0141628 -0.137877, + -0.055787299 -0.021506101 -0.15001801, + -0.0546159 -0.024254199 -0.15014701, + -0.056809202 -0.0187323 -0.149887, + -0.055787299 -0.021951299 -0.155792, + -0.0546159 -0.0247043 -0.155858, + -0.056809202 -0.017988199 -0.144014, + -0.040172402 -0.044562198 -0.16150001, + -0.040174201 -0.044531099 -0.158926, + -0.0402769 -0.044472098 -0.16150001, + -0.039599199 -0.045056298 -0.16150001, + -0.039609101 -0.045067899 -0.1815, + -0.0479904 -0.036012899 -0.1815, + -0.048459999 -0.035361301 -0.16150001, + -0.048175599 -0.035764702 -0.16150001, + -0.049871601 -0.033358999 -0.16150001, + -0.0532961 -0.0266195 -0.147434, + -0.051830001 -0.029626399 -0.1504, + -0.0424264 -0.039810099 -0.140264, + -0.0424264 -0.0404392 -0.14294299, + -0.051830001 -0.0292773 -0.14759, + -0.050219599 -0.032226998 -0.15052199, + -0.050219599 -0.031874198 -0.147742, + -0.0378174 -0.044560298 -0.143279, + -0.0378174 -0.043920498 -0.140646, + -0.035366699 -0.0464327 -0.14343099, + -0.035366699 -0.0469856 -0.146044, + -0.0378174 -0.045109 -0.14591201, + -0.040174201 -0.042560201 -0.143116, + -0.040174201 -0.041925602 -0.140461, + -0.030832 -0.051472198 -0.16150001, + -0.0328326 -0.0501846 -0.15899301, + -0.033319298 -0.0498982 -0.16150001, + -0.029552899 -0.0522171 -0.1815, + -0.0302257 -0.051794499 -0.159012, + -0.0282706 -0.052922402 -0.16150001, + -0.0220857 -0.0522701 -0.138973, + -0.0220857 -0.053029899 -0.141495, + -0.019305199 -0.0524185 -0.136581, + -0.019305199 -0.053277899 -0.139079, + -0.0220857 -0.051414099 -0.136463, + -0.0220857 -0.050461899 -0.13397101, + -0.019305199 -0.051462501 -0.13410001, + -0.0165099 -0.0532775 -0.13668101, + -0.0165099 -0.054139901 -0.13916899, + -0.027557701 -0.048022401 -0.13365699, + -0.0248404 -0.0502626 -0.136329, + -0.0302257 -0.0465867 -0.133471, + 7.667398e-012 -0.055552602 -0.136948, + -3.1285113e-012 -0.0564228 -0.13941, + 0.00268824 -0.055493299 -0.136941, + 0.00268824 -0.054525699 -0.134496, + -7.8334431e-012 -0.054584801 -0.13450401, + -0.00268824 -0.055494301 -0.136941, + -0.00268824 -0.054526702 -0.134496, + 0.019305199 -0.0504032 -0.13164601, + 0.0220857 -0.0504536 -0.133974, + 0.0220857 -0.049405899 -0.131506, + 0.0165099 -0.054133501 -0.139171, + 0.019305199 -0.052410901 -0.136583, + 0.019305199 -0.0514552 -0.134103, + 0.0137106 -0.057738502 -0.151723, + 0.0109179 -0.058621898 -0.154218, + 0.0081428103 -0.0590683 -0.15423401, + 0.0147556 -0.058157299 -0.16150001, + 0.0081421202 0.0923471 -0.0046399999, + 0.0109179 0.092832401 0.00031100499, + 0.0137106 0.092593603 0.001679, + 0.0137106 0.092692897 0.0035099899, + -0.0165099 0.091721401 -0.0024570001, + -0.019305199 0.091121897 -0.0031049999, + -0.019305199 0.091352798 -0.001341, + -0.0165099 0.091443002 -0.0041999999, + -0.0137106 0.091948897 -0.003668, + -0.0248404 -0.054250501 -0.154063, + -0.0248404 -0.053955801 -0.151544, + -0.0220857 -0.05542 -0.15410499, + -0.0220857 -0.055628099 -0.15659299, + -0.0248404 -0.054457799 -0.156565, + -0.027557701 -0.052932899 -0.154016, + -0.027557701 -0.052639499 -0.151482, + -0.0248404 -0.052531701 -0.143929, + -0.0248404 -0.053098101 -0.14647201, + -0.027557701 -0.051222499 -0.143822, + -0.0220857 -0.0536936 -0.144023, + -0.0220857 -0.054262701 -0.14655299, + -0.0328326 -0.0498612 -0.153908, + -0.0302257 -0.051469099 -0.153965, + -0.0328326 -0.049570899 -0.151338, + -0.035366699 -0.048111901 -0.153846, + -0.0328326 -0.050065499 -0.156461, + -0.0302257 -0.0516745 -0.156499, + -0.035366699 -0.047823399 -0.151255, + -0.00267513 0.057928499 0.057829998, + -6.2330436e-012 0.057931401 0.057891, + -0.00267513 0.056233399 0.058430001, + -0.0053918599 0.0579197 0.057643998, + -0.0053918599 0.056228898 0.058244999, + 0.0053918599 0.061287198 0.056258, + -5.8062448e-012 0.067927502 0.05297, + 0.0081421202 0.066208899 0.053385001, + 0.0137106 0.059514798 0.055613998, + 0.019305199 0.057776801 0.054655999, + 0.0220857 0.0577273 0.053619999, + 0.019305199 0.059403401 0.053984001, + 0.0165099 0.059464101 0.054873001, + 0.0220857 0.056111 0.054235, + 0.0165099 0.056165598 0.056150001, + 0.0137106 0.0578545 0.056281, + 0.0137106 0.056186698 0.056885999, + 0.0165099 0.057819199 0.055542, + 0.0165099 0.054519199 0.056694001, + 0.019305199 0.0561404 0.055266999, + 0.019305199 0.0545066 0.055815998, + 0.0117463 0.050999999 0.058839001, + 0.0146178 0.050999999 0.058192, + 0.0165099 0.052845102 0.057179999, + 0.0109179 0.054538701 0.058015, + 0.0109179 0.056203801 0.057479002, + 0.0137106 0.054529902 0.057425998, + 0.0137106 0.0528493 0.057909001, + 0.0109179 0.052852701 0.058495998, + 0.0081421202 0.054545499 0.058463998, + 0.0081421202 0.056217 0.05793, + 0.0328326 0.074179597 0.035952002, + 0.0302257 0.073387504 0.038885001, + 0.0302257 0.074666098 0.037563998, + 0.0302257 0.070718497 0.041361, + 0.0302257 0.072070502 0.040151, + 0.0424264 0.069618098 0.03066, + 0.040174201 0.074608997 0.027572, + 0.0424264 0.072872698 0.026827, + 0.0424264 0.073877402 0.025456, + 0.0378174 0.075298898 0.029568, + 0.035366699 0.074819498 0.032841999, + 0.044564299 0.074022703 0.021826999, + 0.0465803 0.072300397 0.020894, + 0.044564299 0.073106803 0.023227001, + 0.0424264 0.074837498 0.024041999, + 0.0424264 0.075750299 0.022585999, + 0.0465803 0.069442898 0.024798, + 0.0465803 0.070434302 0.023541, + 0.044564299 0.071145996 0.025899, + 0.044564299 0.070106298 0.027167, + 0.0465803 0.068416297 0.026009001, + 0.048467699 0.067777298 0.023536, + 0.048467699 0.068753198 0.022334, + 0.0378174 0.079995602 0.021956, + 0.040174201 0.078319199 0.021616001, + 0.0378174 0.083260797 0.013545, + 0.035366699 0.084243 0.015253, + 0.0302257 0.084703498 0.021837, + 0.0328326 0.083201803 0.022067999, + 0.0248404 0.072797202 0.042962998, + 0.0248404 0.071386904 0.044181999, + 0.019305199 0.071913198 0.046404, + 0.0165099 0.073597603 0.046059001, + 0.0220857 0.071667999 0.045368999, + 0.035366699 0.077023499 0.029983999, + 0.0328326 0.078720704 0.030198, + 0.035366699 0.075944699 0.031436, + 0.0328326 0.075383998 0.034586001, + 0.0302257 0.075903103 0.036189999, + 0.027557701 0.077597298 0.036215998, + 0.0302257 0.069334596 0.042514, + 0.0302257 0.067922398 0.043609001, + 0.048467699 0.051873401 0.03514, + 0.0465803 0.051879801 0.037588, + 0.048204001 0.050999999 0.035726, + 0.048460599 0.050999999 0.035362002, + 0.0465803 0.052735198 0.037317999, + 0.0498982 0.050999999 0.033319, + 0.048467699 0.054206502 0.034283999, + 0.048467699 0.052721798 0.034867998, + 0.0465803 0.054240402 0.036745001, + 0.0465803 0.055600099 0.036081001, + 0.048467699 0.055530801 0.033604998, + 0.050219599 0.054171499 0.031739999, + 0.0378174 0.0614761 0.042041, + 0.040174201 0.0612498 0.039987002, + 0.0424264 0.0597113 0.038615, + 0.0288986 0.052816499 0.052076999, + 0.027557701 0.0528205 0.052792002, + 0.027557701 0.054456402 0.052287001, + 0.0302257 0.0544357 0.050815001, + 0.0302257 0.052812401 0.051325999, + 0.0283127 0.050999999 0.052900001, + 0.035366699 0.060260698 0.044764001, + 0.0328326 0.055952001 0.048610002, + 0.0328326 0.054413099 0.049198002, + 0.0302257 0.0559978 0.050237, + 0.0302257 0.0575356 0.049608, + 0.040312301 0.050999999 0.044440001, + 0.0424264 0.0518918 0.042192001, + 0.040748298 0.050999999 0.044025, + 0.040756401 0.046 0.044032998, + 0.040174201 0.052772202 0.044062, + 0.040174201 0.051897399 0.044326998, + 0.038084399 0.050999999 0.046363998, + 0.0165099 0.070615903 0.048457999, + 0.0137106 0.070775501 0.049198002, + 0.0165099 0.072123103 0.047288999, + 0.019305199 0.070424497 0.047570001, + 0.0137106 0.072298102 0.048027001, + 0.019305199 0.067363903 0.049717002, + 0.0165099 0.0675181 0.050608002, + 0.019305199 0.065799899 0.050696999, + 0.0220857 0.067183599 0.048675999, + 0.019305199 0.068906702 0.048675001, + 0.0165099 0.0690796 0.049564, + 0.0220857 0.0656415 0.049655002, + 0.0109179 0.067750201 0.051948, + 0.0109179 0.0693397 0.050903, + 0.0137106 0.067646697 0.051351, + 0.0081421202 0.067829102 0.052402999, + 0.0081421202 0.069428198 0.051357001, + 0.035366699 0.052793801 0.047963999, + 0.035764702 0.050999999 0.048176002, + 0.034109399 0.0527987 0.048857, + 0.048467699 0.0567379 0.032919001, + 0.0465803 0.058081601 0.034683999, + 0.051830001 0.0553854 0.028411999, + 0.0532961 0.0553101 0.025715999, + 0.0532961 0.0563595 0.025002001, + 0.0532961 0.0540988 0.026443999, + 0.0465803 0.0640148 0.030369001, + 0.044564299 0.063221499 0.033737, + 0.040174201 -0.044519901 -0.158923, + 0.040169802 -0.0445593 -0.16150001, + 0.0404175 -0.044344399 -0.16150001, + 0.0378174 -0.046535999 -0.15894701, + 0.040174201 -0.044400599 -0.156324, + 0.038194101 -0.046273202 -0.16150001, + 0.0424264 -0.042381998 -0.158897, + 0.0424264 -0.0422635 -0.15627301, + 0.0424264 -0.041421302 -0.148304, + 0.0424264 -0.040967699 -0.14562599, + 0.040174201 -0.043094002 -0.14577501, + 0.0378174 -0.046415899 -0.156372, + 0.040174201 -0.0442021 -0.153707, + 0.055787299 -0.020738401 -0.14421199, + 0.055787299 -0.02024 -0.141302, + 0.051830001 -0.028317699 -0.14196, + 0.050219599 -0.030904699 -0.142171, + 0.051830001 -0.0277174 -0.139145, + 0.0532961 -0.0256701 -0.141745, + 0.0532961 -0.025076499 -0.138899, + 0.048467699 -0.033946499 -0.145135, + 0.0465803 -0.0368293 -0.148035, + 0.0546159 -0.023477901 -0.144403, + 0.0465803 -0.037773099 -0.158842, + 0.044564299 -0.040129799 -0.15887, + 0.0464839 -0.037937399 -0.16150001, + 0.046578299 -0.037815802 -0.16150001, + 0.048467699 -0.035322402 -0.158812, + 0.047982302 -0.0360066 -0.16150001, + 0.048288502 -0.035611998 -0.16150001, + 0.0465803 -0.037462998 -0.153468, + 0.0465803 -0.0376564 -0.15616401, + 0.0465803 -0.037188601 -0.150757, + 0.044564299 -0.039817002 -0.153551, + 0.044564299 -0.040012199 -0.15622, + 0.059934601 -0.0028003999 -0.16150001, + 0.0599402 -0.0025446101 -0.15532801, + 0.059980098 -0.00154487 -0.1815, + 0.054340299 -0.025434 -0.16150001, + 0.054305699 -0.0255125 -0.16150001, + 0.054342099 -0.0254349 -0.1815, + 0.059372 -0.0086586103 -0.16150001, + 0.059503399 -0.0077038999 -0.1815, + 0.059725199 -0.0057364102 -0.16150001, + 0.0182469 -0.057158101 -0.1815, + 0.019305199 -0.056766 -0.15907, + 0.020382199 -0.056432001 -0.16150001, + 0.018242801 -0.057145901 -0.16150001, + 0.0175901 -0.0573637 -0.16150001, + 0.0248404 -0.054449201 -0.156564, + 0.0220857 -0.055620398 -0.156592, + 0.0248404 -0.054242998 -0.154063, + 0.0248404 -0.054572199 -0.159044, + 0.0220857 -0.055743899 -0.159058, + 0.027557701 -0.052924499 -0.154016, + 0.050219599 -0.0270089 -0.128346, + 0.048467699 -0.0304437 -0.1314, + 0.048467699 -0.031318501 -0.13412499, + 0.051830001 -0.025406601 -0.130752, + 0.051830001 -0.026262101 -0.133536, + 0.0532961 -0.0227926 -0.13041601, + 0.0532961 -0.021862799 -0.12762, + 0.051830001 -0.024465701 -0.127988, + 0.050219599 -0.0279608 -0.131081, + 0.050219599 -0.028826101 -0.133835, + 0.059999999 0.0593636 -0.016535001, + 0.059999999 0.0595847 -0.018846, + 0.059999999 0.0590172 -0.0143, + 0.0599402 0.060608801 -0.016221, + 0.0599402 0.060283098 -0.013874, + 0.056809202 0.0690706 -0.011135, + 0.055787299 0.070179299 -0.0056830002, + 0.056809202 0.0688219 -0.0082559995, + 0.056809202 0.068970896 -0.0096909897, + 0.0571438 0.050999999 0.018242, + 0.057419099 0.050999999 0.017408, + 0.057158101 0.046 0.018247001, + 0.059757002 0.0573503 -0.000804001, + 0.059757002 0.0583001 -0.00265401, + 0.059445001 0.059777599 -0.001836, + 0.0546159 0.0562279 0.022248, + 0.055787299 0.059579398 0.016209999, + 0.0576833 0.052618999 0.016022, + 0.0599402 0.051788099 0.00250101, + 0.059999999 0.051781099 -0.000184006, + 0.059999999 0.050999999 9.4292955e-013, + 0.059999999 0.046 8.1265142e-012, + 0.0599402 0.053198401 0.001869, + 0.0599402 0.052544001 0.0022100101, + 0.059445001 0.052573498 0.0076609999, + 0.059757002 0.052558601 0.0049170102, + 0.059999999 0.0537217 -0.001222, + 0.059999999 0.0550243 -0.00293401, + 0.059999999 0.052529398 -0.00047599801, + 0.059757002 0.056344599 0.00092399598, + 0.0599402 0.054609299 0.00059300201, + 0.0599402 0.055154599 -0.000207993, + 0.059999999 0.054533701 -0.0021230001, + 0.0599402 0.0542331 0.001039, + 0.059999999 0.054179501 -0.001668, + 0.059746899 0.050999999 0.0053969999, + 0.059757002 0.0517952 0.0052069998, + 0.059927799 0.050999999 0.0029420001, + 0.0597114 0.050999999 0.0058780098, + 0.055787299 -0.016524499 -0.126867, + 0.055787299 -0.017431499 -0.12972599, + 0.056809202 -0.0128356 -0.123615, + 0.056809202 -0.013812 -0.12648401, + 0.058412101 -0.0063747601 -0.119869, + 0.0576833 -0.0090789404 -0.120321, + 0.059682 0.046 0.00616901, + 0.0576833 -0.0101215 -0.123197, + 0.059999999 0.0068692402 -0.117655, + 0.058397699 0.050999999 0.013707, + 0.058412101 0.051816799 0.01351, + 0.058203701 0.050999999 0.014571, + 0.058720101 0.050999999 0.012271, + 0.058731299 0.046 0.012273, + 0.056809202 -0.0162553 -0.135207, + 0.055787299 -0.018256299 -0.132603, + 0.055787299 -0.0189992 -0.13549399, + 0.056809202 -0.0147075 -0.129375, + 0.0576833 -0.0110851 -0.12609901, + 0.056809202 -0.0155218 -0.132284, + 0.056809202 -0.0174808 -0.141078, + 0.048467699 0.070598103 0.019799, + 0.050219599 0.0739922 0.0088550001, + 0.048467699 0.075675197 0.0097380104, + 0.051830001 0.074479997 0.00030400101, + 0.0532961 0.072850898 -0.00062100199, + 0.0465803 0.073169999 0.019509001, + 0.048467699 0.071461998 0.018469, + 0.044564299 0.075712301 0.018909, + 0.044564299 0.074891999 0.020386999, + 0.0424264 0.0766133 0.021091999, + 0.051830001 0.0752813 -0.0075559998, + 0.0465803 0.077860303 0.0088719903, + 0.048467699 0.0761972 0.0081820097, + 0.0465803 0.078310199 0.0072519998, + 0.050219599 0.064168498 0.024282999, + 0.050219599 0.063135996 0.025292, + 0.0532961 0.058359399 0.02348, + 0.0546159 0.058112402 0.020714, + 0.056809202 0.063589796 0.0073270001, + 0.055787299 0.065684497 0.007799, + 0.055787299 0.064314701 0.010133, + 0.0576833 0.0628611 0.0045059999, + 0.056809202 0.059207998 0.013375, + 0.055787299 0.062827297 0.012317, + 0.055787299 0.061241601 0.014344, + 0.0532961 0.071201302 0.0052680098, + 0.056809202 0.068378702 -0.0054259901, + 0.055787299 0.069935098 -0.0042339899, + 0.0546159 0.071233898 -0.0016589999, + 0.056809202 0.0648451 0.0050160098, + 0.0576833 0.064001203 0.0022189899, + 0.0546159 0.069578998 0.0040469998, + 0.0532961 0.070665799 0.0066809999, + 0.0532961 0.070084199 0.0080659902, + -0.0576833 0.061616901 0.0066729998, + -0.0576833 0.062872298 0.004522, + -0.056809202 0.063600801 0.007342, + -0.056809202 0.062228199 0.00950999, + -0.0576833 0.060266498 0.0086799897, + -0.058412101 0.059773099 0.0058280001, + -0.058412101 0.061004698 0.0038309901, + -0.0599402 0.060450502 -0.026165999, + -0.059999999 0.059420101 -0.026109001, + -0.059999999 0.0590523 -0.028597999, + -0.0599402 0.060003102 -0.028717, + -0.0599402 0.060732398 -0.023622001, + -0.059757002 0.061493199 -0.026324, + -0.059757002 0.0618596 -0.023715001, + -0.059445001 0.063329302 -0.015954001, + -0.058998398 0.064257301 -0.010717, + -0.059757002 0.053248599 0.0046199998, + -0.0599402 0.0532244 0.001908, + -0.0599402 0.052553602 0.002257, + -0.059757002 0.053828198 0.00421899, + -0.059445001 0.0538655 0.00697501, + -0.059445001 0.052583098 0.0077069998, + -0.059445001 0.051803902 0.0079650003, + -0.058998398 0.052598 0.01048, + -0.059445001 0.053273 0.0073680002, + -0.058998398 0.053297698 0.010146, + -0.059757002 0.052568201 0.0049640001, + -0.059757002 0.051796801 0.0052230102, + -0.059702002 0.050999999 0.0059730099, + -0.0532961 -0.022812599 -0.130409, + -0.0546159 -0.020150799 -0.13006601, + -0.0546159 -0.019231301 -0.12723801, + -0.0532961 -0.0218818 -0.12761199, + -0.0532961 -0.023658801 -0.133224, + -0.051830001 -0.026282299 -0.13353001, + -0.048467699 -0.0273114 -0.123356, + -0.050219599 -0.0259878 -0.12562799, + -0.051830001 -0.023457 -0.125238, + -0.051830001 -0.022345901 -0.122526, + -0.050219599 -0.0248638 -0.122947, + -0.048467699 -0.028448001 -0.12600701, + -0.035366699 0.068604499 0.039110001, + -0.035366699 0.067263097 0.040197, + -0.0328326 0.067608997 0.041979, + -0.027557701 0.071075097 0.042853002, + -0.0302257 0.069339499 0.042521998, + -0.0328326 0.068987504 0.040888, + -0.035366699 0.060261 0.044771001, + -0.035366699 0.058820099 0.045515001, + -0.0302257 0.065031603 0.045627002, + -0.0328326 0.063341603 0.044900998, + -0.040174201 0.059906099 0.040798999, + -0.0424264 0.058398899 0.039377999, + -0.044564299 0.058242001 0.037089001, + -0.0576833 0.053347301 0.015744001, + -0.056809202 0.053371999 0.018541999, + -0.0576833 0.053978998 0.015374, + -0.056809202 0.054016799 0.01818, + -0.058412101 0.053322401 0.012942, + -0.058412101 0.052613098 0.01327, + -0.0576833 0.051825698 0.016321, + -0.056809202 0.052643299 0.018859999, + -0.056809202 0.051833 0.019113, + -0.0576833 0.052628201 0.016067, + -0.057391401 0.050999999 0.017499, + -0.0576679 0.050999999 0.016505999, + -0.0581805 0.050999999 0.014664, + -0.058412101 0.051818401 0.013525, + -0.048467699 0.054233301 0.034302998, + -0.048467699 0.055553 0.033606999, + -0.050219599 0.0541992 0.031759001, + -0.048467699 0.052729499 0.034906, + -0.050219599 0.052715998 0.032375, + -0.0465803 0.054266099 0.036763001, + -0.0465803 0.055621501 0.036082, + 0.0053918599 0.083549403 0.037891001, + 0.0053918599 0.084681801 0.036224, + 0.0081421202 0.083424203 0.037588999, + 0.0081421202 0.082239002 0.039209001, + 0.0053918599 0.082358301 0.039514001, + 0.00267513 0.083623096 0.038068999, + 0.00267513 0.0847589 0.036400001, + -0.0109179 0.093084998 0.0076950099, + -0.00267513 0.092847802 0.016099, + -0.0053918599 0.092740104 0.015944, + -0.0081421202 0.093369499 0.0080529898, + -0.0081421202 0.093268298 0.0099459998, + -0.0109179 0.091480099 0.019119, + -0.0081421202 0.092179403 0.017595001, + -0.0109179 0.091921903 0.017211, + -0.0081421202 0.091731504 0.019508, + -0.0109179 0.090967298 0.021020001, + -0.0137106 0.0919469 0.014801, + -0.0137106 0.091583699 0.016705999, + -0.0109179 0.092292801 0.015299, + -0.0109179 0.0925937 0.013388, + -0.0165099 0.091516703 0.014182, + -0.0165099 0.091163099 0.016078999, + -0.0165099 0.090739198 0.017972, + -0.0137106 0.091149896 0.018608, + -0.019305199 0.089764804 0.019086, + -0.0328326 0.074187197 0.03596, + -0.035366699 0.073658697 0.034208, + -0.0328326 0.075392202 0.034593999, + -0.035366699 0.072448403 0.035514001, + -0.0302257 0.075910598 0.036196999, + -0.035366699 0.069918104 0.037966002, + -0.035366699 0.071200401 0.036766998, + -0.048467699 0.072297104 0.017109999, + -0.050219599 0.0697942 0.017289, + -0.050219599 0.070608303 0.015973, + -0.048467699 0.071474798 0.018479999, + -0.0165099 0.085822701 0.030811001, + -0.019305199 0.085426196 0.029986, + -0.0165099 0.086729199 0.029048, + -0.0137106 0.086153299 0.031498998, + -0.0165099 0.084851503 0.032540999, + -0.019305199 0.084470399 0.031707998, + -0.0137106 0.087072298 0.02973, + -0.0220857 0.080849998 0.035641, + -0.019305199 0.080048099 0.038192999, + -0.019305199 0.081238903 0.036637999, + -0.0248404 0.078055598 0.037528001, + -0.0248404 0.079255603 0.036036, + -0.027557701 0.077604599 0.036222, + -0.027557701 0.076382503 0.037656002, + -0.0248404 0.076807201 0.038968999, + -0.0220857 0.078455999 0.038686998, + -0.0220857 0.079678901 0.037188001, + -0.0424264 0.067283802 0.032977998, + -0.0424264 0.066070303 0.034053002, + -0.044564299 0.064436302 0.032781001, + -0.0465803 0.065160297 0.029366, + -0.044564299 0.0667914 0.030692, + -0.0465803 0.066276103 0.0283, + -0.0465803 0.064020999 0.030381, + -0.048467699 0.063589297 0.027884999, + -0.044564299 0.065625601 0.031762999, + -0.048467699 0.0646763 0.026874, + -0.044564299 0.074905299 0.020396, + -0.0424264 0.076626599 0.0211, + -0.044564299 0.0757263 0.018918, + -0.0465803 0.073183201 0.01952, + -0.0465803 0.074007697 0.018095, + -0.035366699 0.0816404 0.022112999, + -0.035366699 0.0808319 0.023761, + -0.0378174 0.079175599 0.023561999, + -0.051830001 0.074499898 0.00030900599, + -0.048467699 0.075115301 0.011278, + -0.050219599 0.0734253 0.010348, + -0.048467699 0.074485399 0.012784, + -0.0465803 0.0768051 0.012059, + -0.050219599 0.074009299 0.0088640004, + -0.0465803 0.076184697 0.013613, + -0.044564299 0.079516403 0.00941299, + -0.044564299 0.079944901 0.0077519999, + -0.0465803 0.078327999 0.0072570001, + -0.050219599 0.075445198 0.0042660101, + -0.048467699 0.076214902 0.0081890002, + -0.048467699 0.076681897 0.00661, + -0.0465803 0.077877797 0.0088780103, + -0.0465803 0.077369802 0.01048, + -0.048467699 0.075692303 0.0097460002, + -0.050219599 0.076807298 -0.0085269902, + -0.048467699 0.078282803 -0.0080319997, + -0.050219599 0.076722898 -0.010125, + -0.050219599 0.076583698 -0.011713, + -0.058412101 0.066112503 -0.013425, + -0.058998398 0.064749397 -0.016008999, + -0.058998398 0.064589597 -0.013335, + -0.058412101 0.065857902 -0.010698, + -0.058412101 0.066183202 -0.016193001, + -0.0546159 0.072190799 -0.012191, + -0.055787299 0.070599101 -0.014562, + -0.0532961 0.073760897 -0.0098520098, + -0.0546159 0.072215401 -0.010671, + -0.056809202 0.069142804 -0.01404, + -0.056809202 0.069092698 -0.015498, + -0.0576833 0.067605399 -0.016509, + -0.055787299 0.070661299 -0.013073, + -0.051830001 0.074173003 0.001854, + -0.0546159 0.071253799 -0.001651, + -0.0532961 0.072870903 -0.00061399798, + -0.055787299 0.068929598 1.8005403e-005, + -0.055787299 0.068015799 0.0027339901, + -0.055787299 0.0684947 0.00138901, + -0.051830001 0.075253502 -0.0059739999, + -0.0532961 0.073748402 -0.0083009899, + -0.055787299 0.070321202 -0.017527999, + -0.055787299 0.070107102 -0.018998999, + -0.0546159 0.072113402 -0.013709, + -0.0532961 0.073719099 -0.011401, + -0.051830001 0.075234003 -0.01071, + -0.0424264 0.082504801 0.001226, + -0.040174201 0.083886802 0.001299, + -0.040174201 0.083944097 -0.000438004, + -0.0465803 0.079781599 -0.002688, + -0.044564299 0.081174098 -0.00068699598, + -0.0424264 0.082596801 -0.00049200398, + 0.058998398 0.059273101 0.00296899, + 0.059445001 0.057716999 0.0019950001, + 0.058998398 0.058087699 0.0048240102, + 0.058998398 0.060384501 0.00098100305, + 0.058412101 0.060995299 0.0038159899, + 0.059445001 0.058784001 0.000141998, + 0.050219599 0.076562203 -0.0020939901, + 0.051830001 0.074967697 -0.0028210001, + 0.051830001 0.075127997 -0.0043959999, + 0.050219599 0.076703802 -0.003702, + 0.050219599 0.076363601 -0.00049000501, + 0.035366699 0.085943103 -0.0059349998, + 0.035366699 0.085694604 -0.0076250001, + 0.040174201 0.083333097 -0.008924, + 0.0424264 0.081903704 -0.010561, + 0.040174201 0.0830492 -0.010568, + 0.0378174 0.084681101 -0.0073799998, + 0.0378174 0.084415503 -0.009048, + 0.0378174 0.085049704 -0.0039839898, + 0.0378174 0.0848931 -0.005692, + 0.040174201 0.083564296 -0.0072599901, + 0.0465803 0.079033002 0.0039670002, + 0.044564299 0.0806017 0.0043910099, + 0.044564299 0.080295101 0.0060749999, + 0.0465803 0.078701302 0.0056159999, + 0.048467699 0.077426299 0.00339799, + 0.048467699 0.077720597 0.001776, + 0.044564299 0.080847397 0.0027010001, + 0.0465803 0.079304896 0.0023099999, + 0.048467699 0.077956498 0.000145004, + 0.0424264 0.082579397 -0.00049000501, + 0.040174201 0.083927803 -0.00043499799, + 0.040174201 0.083924599 -0.0021619999, + 0.040174201 0.083861798 -0.00387601, + 0.040174201 0.083741099 -0.0055760001, + 0.050219599 0.075489603 -0.017907999, + 0.0532961 0.073601998 -0.012942, + 0.0465803 0.078477196 -0.015652999, + 0.0322018 0.050626501 -0.1815, + 0.044564299 0.080074199 -0.013876, + 0.044564299 0.080397896 -0.012286, + -0.0328326 0.087486498 0.0024379999, + -0.0302257 0.088513099 0.0019470101, + -0.035366699 0.084750898 0.013494, + -0.0328326 0.085167602 0.016841, + -0.035366699 0.084256798 0.015256, + -0.0302257 0.087028198 0.014688, + -0.0328326 0.086142898 0.013266, + -0.0302257 0.087439299 0.012867, + -0.0302257 0.0865499 0.0165, + -0.027557701 0.087834097 0.015983, + -0.0328326 0.0856883 0.01506, + -0.027557701 0.088266 0.014146, + -0.027557701 0.0893289 -0.00047099299, + -0.0248404 0.090198003 0.00055499299, + -0.0248404 0.090061598 -0.0012300001, + -0.027557701 0.089179799 -0.0022410001, + -0.027557701 0.089419097 0.001317, + -0.0302257 0.088468298 0.00015899701, + -0.0328326 0.0873027 -0.0028650099, + -0.0302257 0.088200197 -0.003364, + -0.0302257 0.088363402 -0.0016120001, + -0.0328326 0.087124102 -0.0045969998, + -0.035366699 0.086148903 -0.0042270101, + -0.0220857 0.090657599 0.010699, + -0.019305199 0.091273896 0.011555, + -0.0220857 0.089203298 0.018183, + -0.0248404 0.088559501 0.017148999, + -0.019305199 0.090246499 0.017209999, + -0.0053918599 0.093582198 0.0045549902, + 0.00267513 0.092846699 0.016099, + 0.0053918599 0.093048297 0.014024, + 0.0053918599 0.092737898 0.015944, + 0.0302257 0.082288504 0.026959, + 0.0302257 0.081361003 0.028602, + 0.0137106 0.084117703 0.034929998, + 0.0137106 0.085164599 0.033232, + 0.019305199 0.088584803 0.022802001, + 0.0220857 0.088052697 0.021877, + 0.0165099 0.089039899 0.023592999, + 0.019305199 0.087136097 0.026443999, + 0.019305199 0.087894499 0.024634, + 0.0165099 0.087563299 0.027253, + 0.0165099 0.088335998 0.025434, + 0.0248404 0.086064398 0.024414999, + 0.027557701 0.0854197 0.023194, + 0.0248404 0.086787201 0.022627, + 0.0220857 0.0866367 0.025498999, + 0.027557701 0.084652998 0.024944, + 0.0220857 0.087378599 0.023699, + 0.0220857 0.088658102 0.020036999, + 0.0248404 0.088549502 0.017147999, + 0.0248404 0.088030398 0.018989, + 0.0165099 0.0902384 0.019857001, + 0.0137106 0.090639897 0.020501001, + 0.0165099 0.089674197 0.021732001, + 0.019305199 0.089205697 0.020950999, + 0.0137106 0.091144301 0.018607, + 0.019305199 0.090238698 0.017209001, + 0.0220857 0.089661598 0.016318001, + 0.019305199 0.0897571 0.019084999, + 0.0165099 0.0907325 0.017971, + 0.0220857 0.089194402 0.018183, + 0.0165099 0.091509998 0.014183, + 0.019305199 0.090992801 0.013441, + 0.0165099 0.0917942 0.012287, + 0.0165099 0.091156296 0.016078999, + 0.0137106 0.091941297 0.014802, + 0.019305199 0.090650603 0.015326, + 0.0137106 0.092234798 0.012898, + -0.0137106 0.092438199 -0.000132004, + -0.0137106 0.092221297 -0.001916, + -0.0165099 0.091944702 -0.000682007, + -0.0137106 0.092597596 0.001677, + -0.0165099 0.092110701 0.001119, + -0.0109179 0.092835002 0.00030999799, + -0.0109179 0.092623301 -0.001481, + 0.0248404 0.090232603 0.00601801, + 0.0248404 0.090280697 0.004183, + 0.027557701 0.089404203 0.0049439999, + 0.0248404 0.090119697 0.0078640003, + 0.0220857 0.090967901 0.00697099, + 0.0220857 0.091029003 0.0051219901, + 0.0302257 0.088258199 0.0073859999, + 0.027557701 0.089143701 0.0086130099, + 0.0302257 0.088047698 0.0092120096, + 0.0328326 0.087285601 0.0060370001, + 0.0302257 0.088403396 0.005564, + 0.027557701 0.0893066 0.0067739999, + 0.0328326 0.087095402 0.0078450004, + -5.1874828e-012 0.075689502 0.0471, + 6.9470883e-012 0.077135697 0.045742001, + 0.00267513 0.075672403 0.047040001, + 0.00267513 0.074187197 0.048338, + -2.9744599e-013 0.074203096 0.048399001, + -0.00267513 0.075672999 0.047040999, + -0.0328326 0.0574576 0.047977, + -0.0328326 0.055966999 0.048611, + -0.027557701 0.0667478 0.046145, + -0.0248404 0.068476699 0.04645, + -0.0220857 0.068707898 0.047641002, + -0.0302257 0.056011699 0.050237998, + -0.0302257 0.054452401 0.050827, + -0.0165099 0.069081999 0.049568001, + -0.019305199 0.068909504 0.04868, + -0.0165099 0.070618503 0.048462, + -0.0137106 0.069225803 0.050310001, + -0.0137106 0.070777699 0.049201999, + -0.0465803 -0.031888802 -0.129026, + -0.0465803 -0.0296783 -0.123752, + -0.0465803 -0.030827099 -0.12637401, + -0.055787299 -0.0155545 -0.124021, + -0.056809202 -0.0117981 -0.120762, + -0.0576833 -0.0090981601 -0.12031, + -0.051830001 -0.0283342 -0.141956, + -0.051830001 -0.0277365 -0.13913999, + -0.051830001 -0.028847201 -0.144774, + -0.048467699 -0.033959199 -0.14513201, + -0.050219599 -0.031439401 -0.14495499, + -0.050219599 -0.030920699 -0.142167, + -0.051830001 -0.025426 -0.13074499, + -0.051830001 -0.0244841 -0.12797999, + -0.0532961 -0.0256871 -0.14173999, + -0.0532961 -0.0261942 -0.14458799, + -0.0546159 -0.021739099 -0.135773, + -0.0546159 -0.0224071 -0.13864399, + -0.055787299 -0.019021001 -0.135488, + -0.055787299 -0.0182781 -0.132596, + -0.0546159 -0.0209869 -0.132912, + -0.0532961 -0.024420099 -0.13605399, + -0.0532961 -0.0250962 -0.13889401, + -0.055787299 -0.020257801 -0.141298, + -0.056809202 -0.0169292 -0.138134, + -0.055787299 -0.0196809 -0.13839, + -0.056809202 -0.017499 -0.141073, + -0.055787299 -0.020753 -0.144208, + -0.0546159 -0.022991 -0.14152101, + -0.0546159 -0.0234922 -0.144399, + -0.048467699 -0.035029899 -0.153382, + -0.0465803 -0.0377861 -0.15884501, + -0.042409498 -0.042443302 -0.16150001, + -0.044024602 -0.040748298 -0.16150001, + -0.044564299 -0.039187402 -0.14816999, + -0.0424264 -0.040978801 -0.145623, + -0.0424264 -0.041430801 -0.14830101, + -0.0465803 -0.037199602 -0.150756, + -0.0465803 -0.036839802 -0.14803199, + -0.048467699 -0.0343986 -0.147889, + -0.048467699 -0.034754898 -0.15064099, + -0.044564299 -0.039550502 -0.150866, + -0.040174201 -0.044214301 -0.153708, + -0.0424264 -0.041797198 -0.15097199, + -0.040174201 -0.0439297 -0.151072, + -0.0424264 -0.042079501 -0.153632, + -0.040174201 -0.044414598 -0.15632699, + -0.0378174 -0.046227299 -0.153779, + -0.0378174 -0.046429101 -0.15637501, + -0.027557701 -0.049812999 -0.138715, + -0.027557701 -0.048965301 -0.136177, + -0.0248404 -0.051114701 -0.138852, + -0.027557701 -0.050565299 -0.141265, + -0.0248404 -0.051871002 -0.141387, + -0.0302257 -0.0483668 -0.13856401, + -0.0302257 -0.047524001 -0.13600899, + 0.0081428103 -0.057895999 -0.146809, + 0.0137106 -0.0562925 -0.144237, + 0.0053973799 -0.0582068 -0.14683101, + 0.00268824 -0.058389202 -0.146843, + 0.0165099 -0.0532711 -0.136683, + 0.0109179 -0.057934102 -0.149268, + 0.0109179 -0.0583237 -0.15175, + 0.0137106 -0.057349801 -0.149234, + 0.0137106 -0.056868199 -0.14673699, + 0.0109179 -0.057451598 -0.146778, + 0.0081428103 -0.058379401 -0.149294, + 0.0081428103 -0.058769599 -0.15177099, + 0.0165099 -0.057516299 -0.156637, + 0.0165099 -0.0576404 -0.159081, + 0.019305199 -0.056642201 -0.156616, + 0.019305199 -0.0564343 -0.15414099, + 0.0165099 -0.057307702 -0.154172, + 0.0137106 -0.058245301 -0.156654, + 0.0137106 -0.058369599 -0.15909, + 0.0030887299 0.0599204 -0.1815, + 0.0081421202 0.092664599 -0.0029120001, + 0.0053918599 0.092566401 -0.0044160001, + 0.0109179 0.092985801 0.0021280099, + 0.0532961 0.072356798 -0.020486999, + 0.0546159 0.071269199 -0.019691, + 0.0546159 0.070940897 -0.021153999, + 0.0546159 0.071780697 -0.016720001, + 0.0546159 0.071549602 -0.018212, + -0.00267513 0.064638302 0.054807, + -0.0053918599 0.064613998 0.054621, + -0.00267513 0.066286303 0.053890999, + -0.0053918599 0.062956497 0.055472001, + -0.0053918599 0.061287299 0.056258999, + -0.00267513 0.0596206 0.057167999, + -0.0053918599 0.0596077 0.056983002, + -3.4969647e-012 0.059624799 0.057229001, + 4.9928811e-012 0.062983602 0.055718999, + 0.00267513 0.061303899 0.056444, + 1.7659668e-012 0.0613093 0.056504998, + -0.00267513 0.062977001 0.055658001, + -0.00267513 0.061303899 0.056444999, + 0.00267513 0.064638101 0.054807, + 0.00267513 0.0629768 0.055658001, + -6.6386377e-014 0.064646199 0.054868001, + -2.0387088e-012 0.0662954 0.053952001, + 0.00267513 0.066285998 0.053890001, + 0.0053918599 0.064613499 0.054620001, + 0.0053918599 0.062956102 0.055470999, + 0.0109179 0.061218198 0.055484999, + 0.0081421202 0.062921003 0.055153001, + 0.0081421202 0.064571701 0.054301001, + 0.0109179 0.066139601 0.052928999, + 0.0137106 0.0660486 0.052331001, + 0.0165099 0.064335898 0.052505001, + 0.0424264 0.063570499 0.036033001, + 0.0424264 0.062296901 0.036947999, + 0.035366699 0.063104101 0.043108001, + 0.0328326 0.064778298 0.043977998, + 0.0328326 0.066201597 0.043003999, + 0.040174201 0.072471701 0.030292001, + 0.0424264 0.0718261 0.028153, + 0.040174201 0.073561601 0.028956, + 0.0424264 0.070740201 0.029431, + 0.0378174 0.074211203 0.030963, + 0.040174201 0.077468596 0.023164, + 0.035366699 0.079953298 0.025369, + 0.0378174 0.079163201 0.023554999, + 0.035366699 0.080819897 0.023755001, + 0.0328326 0.080686703 0.027053, + 0.0328326 0.081585102 0.025424, + 0.035366699 0.082375497 0.02043, + 0.0378174 0.080770202 0.020324999, + 0.0378174 0.081485301 0.018665001, + 0.040174201 0.081154898 0.015114, + 0.0378174 0.082139499 0.01698, + 0.0378174 0.082731701 0.015272, + 0.0424264 0.080635697 0.01147, + 0.040174201 0.081714399 0.013427, + 0.044564299 0.0794992 0.0094090002, + 0.0424264 0.081099398 0.0097859995, + 0.040174201 0.0822118 0.011721, + 0.0328326 0.084568299 0.018603001, + 0.035366699 0.083684199 0.016999001, + 0.035366699 0.0830613 0.018726001, + 0.0328326 0.083916903 0.020346999, + 0.0328326 0.085154697 0.016838999, + 0.0302257 0.085381001 0.020076999, + 0.0302257 0.085992798 0.018296, + 0.0165099 0.0750359 0.044769999, + 0.019305199 0.073369399 0.045177002, + 0.0220857 0.073102802 0.044144999, + 0.0302257 0.078240298 0.033291001, + 0.0328326 0.077657498 0.031707, + 0.0328326 0.0765443 0.03317, + 0.0302257 0.077095501 0.034763999, + 0.0302257 0.079334602 0.031771, + 0.027557701 0.078770898 0.034733001, + 0.027557701 0.0798935 0.033202, + 0.040174201 0.0585513 0.041540001, + 0.0424264 0.057080001 0.040075, + 0.0424264 0.058402501 0.039368, + 0.040174201 0.0599057 0.040791001, + 0.040174201 0.0571835 0.042242002, + 0.0378174 0.058691598 0.043589, + 0.0378174 0.060089 0.042842999, + 0.0378174 0.0572812 0.044286001, + 0.0328326 0.0589449 0.047286998, + 0.035366699 0.058823001 0.045506999, + 0.0328326 0.060419898 0.046546999, + 0.0328326 0.0574576 0.047975, + 0.0302257 0.059057001 0.048923999, + 0.035366699 0.0573727 0.0462, + 0.0302257 0.060566399 0.048186999, + 0.0378174 0.0543621 0.045543998, + 0.040174201 0.054334 0.043519001, + 0.0378174 0.055848502 0.044932999, + 0.0390082 0.052777901 0.045085002, + 0.0378174 0.052783299 0.046077002, + 0.035366699 0.055902101 0.046840001, + 0.035366699 0.054388501 0.047439002, + 0.036603201 0.0527886 0.047037002, + 0.044564299 0.061995901 0.034651998, + 0.044564299 0.060756899 0.035512999, + 0.051830001 0.058602002 0.026195001, + 0.051830001 0.059640199 0.025374999, + 0.051830001 0.0606668 0.024509, + 0.050219599 0.062083799 0.026253, + 0.0522171 0.046 0.029553, + 0.055787299 0.052649301 0.021593999, + 0.0546159 0.054061402 0.023716001, + 0.055787299 0.054023601 0.020950001, + 0.056809202 0.052634198 0.018815, + 0.056809202 0.051831398 0.019098001, + 0.0378174 -0.045931801 -0.151168, + 0.0378174 -0.046215899 -0.153778, + 0.040174201 -0.0439202 -0.15107401, + 0.040174201 -0.0435513 -0.14842799, + 0.0378174 -0.045559999 -0.148546, + 0.027557701 -0.053129699 -0.156532, + 0.027557701 -0.053252298 -0.15902799, + 0.0328326 -0.049851201 -0.153907, + 0.0302257 -0.051459901 -0.153964, + 0.0328326 -0.049563099 -0.15133899, + 0.035366699 -0.048101202 -0.153845, + 0.0302257 -0.051663999 -0.156497, + 0.035366699 -0.047814999 -0.15125699, + 0.0328326 -0.050175499 -0.15899099, + 0.030994801 -0.051374301 -0.16150001, + 0.0302257 -0.051786002 -0.15900999, + 0.0328326 -0.050053999 -0.156459, + 0.033477101 -0.049792401 -0.16150001, + 0.035366699 -0.048423499 -0.15897, + 0.035366699 -0.048302699 -0.156417, + 0.0532961 -0.0274012 -0.155919, + 0.0546159 -0.0246852 -0.155855, + 0.050219599 -0.031426199 -0.144959, + 0.048467699 -0.0343876 -0.147892, + 0.051830001 -0.0288336 -0.144778, + 0.0532961 -0.026180301 -0.144592, + 0.0557741 -0.0220806 -0.16150001, + 0.0554916 -0.0228185 -0.16150001, + 0.059445001 -0.0079961997 -0.155458, + 0.059757002 -0.0052522598 -0.15539201, + 0.055787299 0.070649698 -0.011586, + 0.055787299 0.0706091 -0.0101, + 0.056809202 0.069120303 -0.012587, + 0.055787299 0.070638701 -0.013075, + 0.056809202 0.069119997 -0.014042, + 0.0546159 0.072193302 -0.010672, + 0.0546159 0.072165102 -0.0091530001, + 0.0546159 0.071950004 -0.0061269999, + 0.055787299 0.070373498 -0.0071459999, + 0.0546159 0.071763203 -0.0046250001, + 0.0546159 0.072084099 -0.0076369899, + 0.0532961 0.073538996 -0.0052069998, + 0.055787299 0.070517004 -0.0086190002, + 0.0532961 0.073363602 -0.003668, + 0.0576833 0.060258798 0.0086649898, + 0.058412101 0.058460701 0.0076710102, + 0.0576833 0.058834601 0.010525, + 0.056809202 0.062219098 0.0094950004, + 0.0576833 0.0616077 0.0066570002, + 0.058412101 0.059765302 0.0058129998, + 0.056809202 0.060751501 0.011512, + 0.058412101 0.053297099 0.012904, + 0.058998398 0.053272098 0.010108, + 0.058412101 0.053908799 0.012542, + 0.058412101 0.055688601 0.010965, + 0.058412101 0.0549196 0.011728, + 0.058412101 0.0571004 0.0093849897, + 0.0576833 0.057354901 0.012235, + 0.0532961 0.060310401 0.021787999, + 0.051830001 0.0616799 0.023595, + 0.059757002 0.0532226 0.0045809899, + 0.059445001 0.053247198 0.0073289899, + 0.058998398 0.0538706 0.0097380104, + 0.0576833 -0.0119689 -0.129022, + 0.0576833 -0.0127727 -0.131963, + 0.0576833 -0.0134969 -0.134918, + 0.059757002 0.00066821702 -0.121536, + 0.059757002 0.0016556 -0.118526, + 0.0599402 0.0042725299 -0.118089, + 0.050219599 0.074523903 0.0073459898, + 0.051830001 0.072853997 0.0063709999, + 0.0532961 0.071689099 0.003828, + 0.050219599 0.075795203 0.00269, + 0.048467699 0.077073701 0.0050090002, + 0.048467699 0.076663703 0.006604, + 0.048467699 0.072283402 0.017099001, + 0.0465803 0.073993899 0.018084999, + 0.050219599 0.076786697 -0.0085239997, + 0.051830001 0.075274497 -0.0091340002, + 0.051830001 0.075212799 -0.010708, + 0.048467699 0.078313701 -0.0047680102, + 0.050219599 0.076788202 -0.0053119999, + 0.050219599 0.076815598 -0.0069200001, + 0.0546159 0.066516198 0.010555, + 0.050219599 0.068039902 0.019787, + 0.0546159 0.065790698 0.011753, + 0.0546159 0.070064098 0.00265601, + 0.055787299 0.067478903 0.0040379898, + 0.055787299 0.066918299 0.0053240098, + 0.0546159 0.0690488 0.0054120002, + 0.0546159 0.068475403 0.0067469901, + 0.056809202 0.066939801 5.9967001e-006, + 0.0576833 0.065010898 -0.000195007, + 0.0576833 0.0658748 -0.00272301, + 0.056809202 0.065967202 0.00257201, + 0.055787299 0.068477198 0.00137801, + 0.055787299 0.067999199 0.002722, + -0.048467699 0.077197999 -0.015973, + -0.059757002 0.0616588 -0.013562, + -0.059445001 0.0630963 -0.013384, + -0.059757002 0.061947599 -0.016023001, + -0.0599402 0.060299002 -0.01386, + -0.059757002 0.061225601 -0.011179, + -0.059445001 0.0627046 -0.010881, + -0.0599402 0.060626701 -0.016208, + -0.027557701 0.075115301 0.039037999, + -0.0302257 0.074672997 0.037571002, + -0.0328326 0.072940998 0.037273999, + -0.0328326 0.061887201 0.045756001, + -0.0424264 0.061012901 0.037815999, + -0.0424264 0.059711698 0.038623001, + -0.040174201 0.061252799 0.039995, + -0.040174201 0.062586598 0.039136, + -0.0424264 0.0623012 0.036956999, + -0.044564299 0.059507001 0.036331002, + -0.044564299 0.060760301 0.035521001, + -0.00267513 0.093160503 0.014177, + -5.7460725e-012 0.093195997 0.014227, + 0.00267513 0.0931594 0.014177, + -0.0053918599 0.093291298 0.012108, + -0.0053918599 0.093463503 0.0102, + -0.0081421202 0.093099698 0.01185, + -0.0081421202 0.092862703 0.013762, + -0.0053918599 0.093050502 0.014024, + -0.0165099 0.089680798 0.021733001, + -0.0165099 0.090245098 0.019858001, + -0.019305199 0.089213401 0.020951999, + -0.019305199 0.088592298 0.022802999, + -0.0165099 0.089046396 0.023593999, + -0.0137106 0.090070397 0.022384999, + -0.0137106 0.090645403 0.020501999, + -0.0302257 0.072076403 0.040158998, + -0.0302257 0.070723802 0.041368999, + -0.0328326 0.070337899 0.039739002, + -0.0328326 0.071656801 0.038534001, + -0.0302257 0.073393904 0.038892001, + -0.027557701 0.072458297 0.041638002, + -0.027557701 0.0738061 0.040366001, + -0.0465803 0.071399301 0.02225, + -0.048467699 0.069705598 0.021101, + -0.0465803 0.070445098 0.023553001, + -0.0465803 0.072312802 0.020905999, + -0.048467699 0.070610203 0.019811001, + -0.044564299 0.072158098 0.024596, + -0.040174201 0.074619703 0.027581999, + -0.0424264 0.071835898 0.028163999, + -0.040174201 0.072480999 0.030303, + -0.040174201 0.0735716 0.028966, + -0.0424264 0.0728833 0.026838001, + -0.0424264 0.070749298 0.029441999, + -0.044564299 0.071156301 0.025911, + -0.044564299 0.070115797 0.027179001, + -0.040174201 0.079128802 0.020042, + -0.0378174 0.080783598 0.020331001, + -0.040174201 0.079868302 0.018428, + -0.0378174 0.080008402 0.021963, + -0.040174201 0.078332402 0.021624001, + -0.0424264 0.0781959 0.018005, + -0.0424264 0.077438198 0.019569, + -0.048467699 0.077445202 0.00340199, + -0.0465803 0.079051502 0.00397, + -0.048467699 0.077739902 0.0017790101, + -0.048467699 0.077092297 0.0050140098, + -0.050219599 0.0758145 0.00269501, + -0.0465803 0.078719497 0.00562, + -0.050219599 0.076127499 0.0011089901, + -0.0424264 0.082369097 -0.0072690002, + -0.0424264 0.082169503 -0.0089269998, + -0.0465803 0.079572 -0.0092899902, + -0.048467699 0.0780081 -0.011255, + -0.048467699 0.078172997 -0.0096499901, + -0.0465803 0.079709798 -0.0076560099, + -0.044564299 0.081075899 -0.0073999902, + -0.044564299 0.080908097 -0.009048, + -0.050219599 0.076145597 -0.014847, + -0.050219599 0.0763909 -0.013287, + -0.051830001 0.074132197 -0.018417001, + -0.050219599 0.0758496 -0.016388999, + -0.050219599 0.075504303 -0.017913001, + -0.051830001 0.074454501 -0.016906001, + -0.037236601 0.047047202 -0.1815, + -0.0532961 0.072723597 -0.019013001, + -0.0532961 0.072374597 -0.020492001, + -0.0576833 0.067129299 -0.0080559999, + -0.0576833 0.067639098 -0.01366, + -0.0576833 0.067478903 -0.010835, + -0.056809202 0.0681054 -0.0040259999, + -0.0576833 0.066596903 -0.0053409999, + -0.056809202 0.067766301 -0.002655, + -0.056809202 0.068398699 -0.0054170098, + -0.055787299 0.069661401 -0.0027920101, + -0.055787299 0.069319002 -0.00137601, + -0.050219599 0.075020596 0.0058200099, + -0.050219599 0.074541599 0.0073540001, + -0.0546159 0.069065101 0.0054239999, + -0.0532961 0.070100099 0.0080770003, + -0.051830001 0.071749099 0.0092769898, + -0.051830001 0.075148799 -0.0043939999, + -0.0532961 0.073681504 -0.0067510102, + -0.0546159 0.071571402 -0.018216999, + -0.0532961 0.073024496 -0.017517, + -0.051830001 0.0747272 -0.015377, + -0.044564299 0.081242003 -0.004063, + -0.0465803 0.0797913 -0.0060089999, + -0.0465803 0.079815499 -0.0043520099, + -0.044564299 0.081237704 -0.00237801, + -0.044564299 0.081187703 -0.0057380102, + -0.0424264 0.082628302 -0.002203, + -0.0424264 0.082599998 -0.0039049999, + 0.0465803 0.079669699 -0.001021, + 0.0465803 0.079517201 0.00064599601, + 0.048467699 0.078134 -0.001492, + 0.048467699 0.078253001 -0.0031300001, + 0.0465803 0.079762504 -0.002687, + 0.044564299 0.081032 0.001008, + 0.044564299 0.081155799 -0.00068600499, + 0.050219599 0.076702498 -0.010121, + 0.044564299 0.080670998 -0.010674, + 0.0424264 0.082155302 -0.0089220004, + 0.048467699 0.077502802 -0.014413, + 0.0465803 0.0788223 -0.014091, + 0.048467699 0.077183798 -0.015967, + 0.0465803 0.079117902 -0.012507, + 0.044564299 0.081219502 -0.0023760099, + 0.0424264 0.082611002 -0.0022, + 0.0424264 0.0825831 -0.0039009999, + -0.035366699 0.086368002 -0.00075000001, + -0.0328326 0.087485701 0.00065499899, + -0.035366699 0.086388104 0.00101199, + -0.035366699 0.086287603 -0.0024969899, + -0.0378174 0.085163698 -0.002263, + -0.0328326 0.087423898 -0.00111301, + -0.0378174 0.085204698 -0.00052400201, + -0.0165099 0.092164896 0.0085119903, + -0.019305199 0.0914791 0.0096739996, + -0.019305199 0.091617197 0.0078009898, + -0.0165099 0.092246599 0.0066410098, + -0.0137106 0.0927113 0.0072250101, + -0.0137106 0.092464902 0.010997, + -0.0165099 0.092016697 0.010395, + -0.0137106 0.092621602 0.0091049997, + -0.0109179 0.092825301 0.011481, + -0.0137106 0.092240401 0.012897, + -0.0165099 0.091801003 0.012287, + -0.0109179 0.0929887 0.0095829898, + -0.0220857 0.090068497 0.014447, + -0.0248404 0.089010097 0.015297, + -0.0248404 0.089392103 0.013438, + -0.0220857 0.089670502 0.016318001, + -0.0220857 0.090397298 0.012572, + -0.019305199 0.090658501 0.015326, + -0.019305199 0.091000699 0.01344, + 0.0081421202 0.092859298 0.013763, + 0.0109179 0.0925892 0.013389, + 0.0053918599 0.0932891 0.012109, + 0.0081421202 0.093096398 0.011851, + 0.027557701 0.083822303 0.026666, + 0.0248404 0.085275702 0.026178, + 0.019305199 0.081233099 0.036633998, + 0.0165099 0.082718402 0.035879999, + 0.0165099 0.085816897 0.030809, + 0.0165099 0.086723201 0.029046001, + -0.0145255 0.050999999 0.058215, + -0.0167691 0.046 0.057608999, + -0.0107568 0.046 0.059028, + -0.027557701 0.054471701 0.052297998, + -0.027557701 0.056052301 0.051718999, + -0.0302257 0.052817199 0.051350001, + -0.030219801 0.050999999 0.051819999, + -0.019305199 0.067366399 0.049722001, + -0.0165099 0.067520298 0.050611999, + -0.0137106 0.067648597 0.051353998, + -0.0109179 0.067751698 0.051950999, + -0.0081421202 0.05455 0.058467001, + -0.0107542 0.050999999 0.059013002, + -0.0116529 0.050999999 0.058858, + -0.0137106 0.052851502 0.057920001, + -0.00875236 0.050999999 0.059358001, + -0.035366699 -0.044218499 -0.13562299, + -0.040174201 -0.041199099 -0.137812, + -0.0378174 -0.042362899 -0.135406, + -0.0378174 -0.043188099 -0.13802101, + -0.044564299 -0.036064301 -0.134671, + -0.0424264 -0.03909 -0.137591, + -0.044564299 -0.031954501 -0.124133, + -0.044564299 -0.033114899 -0.126726, + -0.056809202 -0.0138323 -0.126476, + -0.056809202 -0.0128551 -0.123605, + -0.055787299 -0.0165444 -0.126858, + -0.056809202 -0.0147287 -0.12936699, + -0.055787299 -0.0174524 -0.12971801, + -0.0576833 -0.0111057 -0.12609001, + -0.0576833 -0.0101412 -0.123188, + -0.048467699 -0.030461799 -0.131394, + -0.050219599 -0.027979599 -0.131074, + -0.048467699 -0.029498501 -0.12868799, + -0.0465803 -0.032862298 -0.131703, + -0.050219599 -0.0270268 -0.12833899, + -0.050219599 -0.032691199 -0.156048, + -0.048467699 -0.0352236 -0.15610801, + -0.050219599 -0.032499298 -0.153292, + -0.050219599 -0.032802399 -0.158785, + -0.051830001 -0.030086 -0.155986, + -0.048467699 -0.035335999 -0.15881599, + -0.051830001 -0.029896 -0.1532, + -0.044561401 -0.040171701 -0.16150001, + -0.0463636 -0.038084399 -0.16150001, + -0.044440001 -0.040312301 -0.16150001, + -0.044033099 -0.040756401 -0.1815, + -0.044564299 -0.0400277 -0.156222, + -0.044564299 -0.040142201 -0.15887301, + -0.0465803 -0.037672602 -0.156166, + -0.0465803 -0.037477098 -0.153469, + -0.044564299 -0.039830498 -0.153552, + -0.0424264 -0.042278301 -0.156276, + -0.0424264 -0.0423938 -0.15889999, + -0.0465803 -0.033747099 -0.13440099, + -0.044564299 -0.036867999 -0.13735799, + -0.044564299 -0.037581399 -0.140056, + -0.050219599 -0.030316301 -0.13937999, + -0.0465803 -0.035866499 -0.14257, + -0.044564299 -0.0382047 -0.14275999, + -0.044564299 -0.038739402 -0.145466, + -0.0465803 -0.036396001 -0.145302, + -0.048467699 -0.033435099 -0.142372, + 0.0109179 -0.056201901 -0.141792, + 0.0109179 -0.056874599 -0.144284, + 0.0137106 -0.055621199 -0.141738, + 0.0137106 -0.054853201 -0.139246, + 0.0109179 -0.055432301 -0.13930701, + 0.0081428103 -0.057318199 -0.14432, + 0.0053973799 -0.056953799 -0.141862, + 0.0053973799 -0.0576283 -0.144345, + 0.0081428103 -0.056644399 -0.14183301, + 0.0081428103 -0.055873498 -0.13935301, + 0.0053973799 -0.056182001 -0.139385, + 0.00268824 -0.057135601 -0.14187799, + 0.00268824 -0.0578105 -0.14436001, + 0.0137106 -0.053026602 -0.134305, + 0.0137106 -0.053988401 -0.136766, + 0.0165099 -0.052312098 -0.134213, + 0.0165099 -0.0512564 -0.13176601, + 0.0137106 -0.0519679 -0.13186599, + 0.0109179 -0.0536015 -0.134378, + 0.0109179 -0.0545654 -0.136833, + 0.00267513 0.092695102 -0.0042849998, + 0.0053918599 0.093142398 -0.00091700698, + 0.0053918599 0.092881501 -0.002685, + 0.0081421202 0.092928 -0.00114799, + 0.0081421202 0.093135297 0.00064799498, + 0.0053918599 0.093347102 0.00088299601, + 0.0081421202 0.093374297 0.004313, + 0.0081421202 0.093284696 0.0024699999, + 0.0109179 0.093079597 0.0039659999, + 0.0053918599 0.093493797 0.0027079899, + 0.051830001 0.074435599 -0.016900999, + 0.050219599 0.075832799 -0.016384, + 0.051830001 0.074114896 -0.018412, + 0.0532961 0.073003903 -0.017511999, + 0.0532961 0.072704203 -0.019007999, + 0.0532961 0.073254399 -0.016000999, + 0.0532961 0.073454 -0.014477, + 0.051830001 0.075097002 -0.012274, + 0.0137106 0.0628049 0.054099999, + 0.0109179 0.0628708 0.054696999, + 0.0109179 0.064511903 0.053846002, + 0.0137106 0.064433403 0.053247999, + 0.0137106 0.061164901 0.054887999, + 0.0165099 0.062723003 0.053357001, + 0.0165099 0.061098602 0.054145999, + 0.0424264 0.064827397 0.035064001, + 0.044564299 0.064430296 0.03277, + 0.044564299 0.065619104 0.031750999, + 0.0424264 0.066064097 0.034042001, + 0.040174201 0.0664865 0.036217, + 0.0328326 0.067604102 0.04197, + 0.040174201 0.0625825 0.039128002, + 0.0378174 0.062851898 0.041182999, + 0.035366699 0.064506799 0.042192001, + 0.0328326 0.071650498 0.038525999, + 0.0328326 0.072934099 0.037266001, + 0.0378174 0.071909502 0.033606999, + 0.035366699 0.072440803 0.035503998, + 0.035366699 0.073650502 0.034198999, + 0.0378174 0.073080502 0.032310002, + 0.040174201 0.071341999 0.031580001, + 0.0378174 0.077333502 0.026643001, + 0.0378174 0.078275099 0.025118001, + 0.040174201 0.076565102 0.024674, + 0.0378174 0.076340497 0.028127, + 0.040174201 0.0756111 0.026145, + 0.035366699 0.078052901 0.028487001, + 0.035366699 0.079030298 0.026946999, + 0.040174201 0.080534503 0.016781, + 0.0465803 0.077352799 0.010473, + 0.044564299 0.079011098 0.011052, + 0.0424264 0.0801109 0.013136, + 0.019305199 0.076170303 0.042546999, + 0.019305199 0.074789599 0.043891001, + 0.0165099 0.076434501 0.043421999, + 0.0165099 0.077790096 0.042018, + 0.019305199 0.077508204 0.041147001, + 0.0220857 0.075861499 0.041524, + 0.0220857 0.074501798 0.042863, + 0.051830001 0.056488801 0.027706999, + 0.051830001 0.057553001 0.026969999, + 0.050219599 0.056615099 0.03035, + 0.051830001 0.0518599 0.030005001, + 0.051830001 0.052693699 0.029728999, + 0.052922402 0.050999999 0.028271001, + 0.051472198 0.050999999 0.030832, + 0.050219599 0.0518668 0.032609001, + 0.050219599 0.052707899 0.032334998, + 0.056496199 0.050999999 0.020203, + 0.054979 0.046 0.024026999, + 0.051830001 -0.030068001 -0.155983, + 0.0532961 -0.0269523 -0.15027601, + 0.0532961 -0.0266075 -0.147438, + 0.0532961 -0.0272156 -0.15310401, + 0.0546159 -0.0242412 -0.150149, + 0.0546159 -0.023900401 -0.14727899, + 0.051830001 -0.029265599 -0.14759301, + 0.050219599 -0.031862799 -0.147745, + 0.048467699 -0.034743499 -0.15064199, + 0.056809202 -0.0179733 -0.14401799, + 0.055787299 -0.021155899 -0.147119, + 0.055787299 -0.0214929 -0.15002, + 0.058412101 -0.0131373 -0.149627, + 0.058998398 -0.0107698 -0.155523, + 0.0588759 -0.01156 -0.16150001, + 0.056669399 -0.0197125 -0.1815, + 0.058412101 -0.0092263399 -0.12866899, + 0.059445001 -0.0029228199 -0.124947, + 0.0599402 -0.00144835 -0.14286201, + 0.059757002 -0.00484356 -0.14923701, + 0.0599402 -0.0021408 -0.14911, + 0.059999999 0.0012249399 -0.142675, + 0.059445001 0.0565942 0.0037179999, + 0.058998398 0.056846499 0.0065430002, + 0.059757002 0.0552858 0.00253799, + 0.056809202 0.0576091 0.01508, + 0.0576833 0.055824202 0.013803, + 0.055787299 0.057861902 0.01791, + 0.050219599 0.0661617 0.022125, + 0.050219599 0.065178096 0.023227001, + 0.0532961 0.064024203 0.017872, + 0.051830001 0.065536499 0.019486001, + 0.051830001 0.064607903 0.020581, + 0.0546159 0.063429803 0.015114, + 0.0532961 0.062206201 0.019918, + 0.0532961 0.0631264 0.018917, + 0.051830001 0.063653499 0.021631001, + 0.051830001 0.062676497 0.022636, + 0.0532961 0.061266501 0.020876, + 0.0546159 0.0617272 0.01715, + 0.0546159 0.059947401 0.019018, + 0.058998398 -0.0072731501 -0.131322, + 0.058412101 -0.0100196 -0.131642, + 0.058998398 -0.0064903498 -0.128317, + 0.059445001 -0.00454405 -0.13100401, + 0.059445001 -0.00687264 -0.143242, + 0.059445001 -0.0058601 -0.13711201, + 0.058998398 -0.0096322997 -0.143435, + 0.059757002 -0.0041424399 -0.143051, + 0.059445001 -0.0075825402 -0.14936601, + 0.058998398 -0.0103511 -0.149496, + 0.059757002 -0.00314283 -0.136859, + 0.058998398 -0.0091579203 -0.14040001, + 0.058412101 -0.0124095 -0.143629, + 0.0576833 -0.0151934 -0.143824, + 0.058412101 -0.0113708 -0.137624, + 0.058412101 -0.0107344 -0.134629, + 0.058998398 -0.0079785204 -0.13434, + 0.058998398 -0.0086067002 -0.137367, + 0.058412101 -0.0119291 -0.140626, + 0.0576833 -0.0141415 -0.13788199, + 0.0576833 -0.014707 -0.140852, + 0.051830001 0.073773101 0.0033760101, + 0.050219599 0.0754264 0.0042599901, + 0.051830001 0.074153498 0.00184801, + 0.051830001 0.073339596 0.0048839999, + 0.0532961 0.072127499 0.0023650101, + 0.050219599 0.075002298 0.0058129998, + 0.0532961 0.0725151 0.00088099699, + 0.048467699 0.073789299 0.01425, + 0.048467699 0.073059998 0.015691999, + 0.050219599 0.072775602 0.011793, + 0.048467699 0.074469499 0.012775, + 0.0465803 0.075495198 0.01513, + 0.0465803 0.074769601 0.016625, + 0.0546159 0.067206897 0.0093200104, + 0.0546159 0.0678607 0.0080500003, + 0.0532961 0.065741301 0.015655, + 0.0546159 0.064245097 0.014033, + 0.0546159 0.065032899 0.012913, + 0.0532961 0.064896703 0.016785, + 0.051830001 0.066436902 0.018347001, + 0.055787299 0.069300003 -0.001386, + 0.055787299 0.069641702 -0.0028009899, + 0.0546159 0.070893101 -0.000199997, + 0.0546159 0.070502698 0.001239, + 0.055787299 0.068911299 7.9956062e-006, + 0.056809202 0.067747697 -0.00266499, + -0.0328326 0.0604202 0.046553999, + -0.0328326 0.058942199 0.047295, + -0.0053918599 0.093568198 0.0083039999, + -0.0053918599 0.093607098 0.00642101, + -6.1682356e-012 0.093614802 0.010398, + 0.00267513 0.093402401 0.01226, + 7.3941634e-012 0.093439803 0.012309, + -0.00267513 0.093577802 0.010349, + -0.00267513 0.093403503 0.012259, + -0.0424264 0.074849501 0.024052, + -0.044564299 0.074035197 0.021837, + -0.044564299 0.073118597 0.023238, + -0.0424264 0.073888697 0.025466001, + -0.0424264 0.075763002 0.022595, + -0.040174201 0.075622402 0.026154, + -0.040174201 0.076577097 0.024683001, + -0.0465803 0.079133399 -0.012512, + -0.048467699 0.077789597 -0.012845, + -0.0465803 0.079379298 -0.010909, + -0.044564299 0.080685899 -0.010679, + -0.048467699 0.077519 -0.014418, + -0.0465803 0.078835897 -0.014096, + -0.044564299 0.080410898 -0.012291, + -0.056809202 0.068992697 -0.0096850004, + -0.055787299 0.070200197 -0.0056770002, + -0.055787299 0.070395 -0.0071399999, + -0.0546159 0.071544699 -0.0031280101, + -0.055787299 0.069955498 -0.004226, + -0.056809202 0.068644904 -0.006825, + -0.056809202 0.068843201 -0.0082489904, + -0.0532961 0.072146297 0.0023739899, + -0.0546159 0.070521303 0.00124899, + -0.0532961 0.072534502 0.00088900799, + -0.0546159 0.070912398 -0.000190994, + -0.051830001 0.073792003 0.0033829999, + -0.051830001 0.073357902 0.004892, + -0.0532961 0.071218699 0.0052780001, + -0.0532961 0.070682503 0.0066920002, + -0.0546159 0.069596097 0.0040580002, + -0.0546159 0.070082001 0.002666, + -0.0532961 0.071707197 0.0038379999, + -0.051830001 0.072871603 0.0063800002, + -0.051830001 0.072334804 0.0078419996, + -0.0532961 0.073384501 -0.0036629899, + -0.0532961 0.073560201 -0.0052039898, + -0.051830001 0.074988201 -0.00281799, + -0.051830001 0.074771903 -0.00124899, + -0.0532961 0.073154502 -0.0021329999, + -0.0546159 0.071784198 -0.004619, + -0.0546159 0.071971402 -0.0061219898, + -0.0532961 0.073475704 -0.01448, + -0.0546159 0.071802899 -0.016724, + -0.0546159 0.071983799 -0.015221, + -0.0532961 0.073275603 -0.016005, + -0.0532961 0.073623799 -0.012945, + -0.051830001 0.074948899 -0.013834, + -0.051830001 0.075118102 -0.012277, + 0.0465803 0.079772398 -0.0060060001, + 0.048467699 0.078263097 -0.0080290101, + 0.048467699 0.0783168 -0.0064019901, + 0.0465803 0.079796501 -0.0043500098, + 0.044564299 0.081223898 -0.0040600002, + 0.048467699 0.0781537 -0.0096460003, + 0.0465803 0.0793624 -0.010905, + 0.0053918599 0.093461297 0.010201, + 0.00267513 0.093576796 0.01035, + 0.0053918599 0.093605198 0.006422, + 0.0053918599 0.093566097 0.0083039999, + 0.0053918599 0.093580402 0.0045560002, + 0.00267513 0.093616597 0.002849, + -0.00267513 0.093617402 0.00284801, + 0.0081421202 0.093402199 0.0061759902, + 0.0109179 0.093111902 0.0058229999, + 0.0137106 0.092706099 0.0072260001, + 0.027557701 0.0809623 0.031628001, + 0.0165099 0.083812296 0.034228999, + 0.0165099 0.084845901 0.032538, + 0.019305199 0.086310603 0.028229, + 0.0220857 0.085828401 0.027272999, + -0.0248404 0.057670601 0.052432999, + -0.0248404 0.066980198 0.047488999, + -0.0220857 0.067186497 0.048682, + -0.019305199 0.052843299 0.056320999, + -0.020158799 0.050999999 0.056511998, + -0.019305199 0.054517198 0.055822998, + -0.0193005 0.050999999 0.056795001, + -0.017363001 0.050999999 0.057433002, + -0.0165099 0.052847799 0.057193, + -0.0165099 0.0545284 0.056699999, + -0.0229061 0.050999999 0.055454999, + -0.0226011 0.050999999 0.055573002, + -0.0220857 0.052838001 0.055300999, + -0.0248404 0.052831899 0.054131001, + -0.0248347 0.050999999 0.054602999, + -0.0226037 0.046 0.055578999, + -0.0220857 0.0561211 0.054235, + -0.0220857 0.0545041 0.054798, + -0.0220857 0.0577273 0.053619999, + -0.0248404 0.056088801 0.053052001, + -0.0248404 0.054488901 0.053622, + -0.0275518 0.050999999 0.053284999, + -0.027557701 0.0528249 0.052813999, + -0.0255982 0.050999999 0.054265, + -0.028228801 0.050999999 0.052944999, + -0.0281986 0.046 0.052960999, + -0.019305199 0.065802202 0.050701, + -0.0220857 0.062511601 0.051429, + -0.0137106 0.054537501 0.057431001, + -0.0109179 0.054544698 0.058019001, + -0.0081421202 0.0562208 0.05793, + -0.035366699 -0.0432938 -0.133047, + -0.0424264 -0.034129702 -0.124497, + -0.053669199 0.046 0.026826, + -0.0424264 -0.037376702 -0.132285, + -0.040174201 -0.040380798 -0.135175, + -0.0424264 -0.0382788 -0.13493, + -0.044564299 -0.0351707 -0.132, + -0.044564299 -0.034187399 -0.12935001, + -0.040174201 -0.038469099 -0.12995499, + -0.0424264 -0.035301302 -0.12706301, + -0.0424264 -0.036384098 -0.12966099, + -0.040174201 -0.039470699 -0.13255399, + -0.0378174 -0.041445199 -0.132809, + -0.048467699 -0.032124899 -0.136861, + -0.0465803 -0.034542799 -0.137115, + -0.0465803 -0.0352493 -0.13983899, + -0.048467699 -0.032824099 -0.139613, + -0.048467699 -0.031337399 -0.13412, + -0.050219599 -0.0296246 -0.136599, + -0.050219599 -0.028845601 -0.133829, + 2.3806593e-012 0.093309604 -0.00073700002, + -0.00267513 0.093268797 -0.00078100601, + 3.8710224e-012 0.092737198 -0.0042420002, + 0.00267513 0.093268298 -0.00078100601, + -0.00267513 0.093472198 0.00102, + 0.00267513 0.093471497 0.001021, + 0.050219599 0.076371498 -0.013282, + 0.051830001 0.074928202 -0.01383, + 0.050219599 0.076563701 -0.011708, + 0.048467699 0.077771902 -0.01284, + 0.050219599 0.076127298 -0.014842, + 0.051830001 0.074707203 -0.015373, + 0.048467699 0.077989399 -0.011251, + 0.035366699 0.071193598 0.036757, + 0.035366699 0.068598904 0.039099999, + 0.0378174 0.068185903 0.037184, + 0.035366699 0.0699118 0.037955999, + 0.0328326 0.068982199 0.040879, + 0.0328326 0.070332102 0.039730001, + 0.0378174 0.065559797 0.039296001, + 0.040174201 0.063901797 0.038213, + 0.040174201 0.065204397 0.037241999, + 0.0378174 0.064214297 0.040268, + 0.0378174 0.066884898 0.038268, + 0.035366699 0.0658926 0.041219, + 0.035366699 0.067257904 0.040188, + 0.0424264 0.078181498 0.017997, + 0.040174201 0.079854101 0.018422, + 0.040174201 0.0791151 0.020035001, + 0.0424264 0.0774244 0.019561, + 0.044564299 0.076481603 0.017395999, + 0.044564299 0.077859402 0.014277, + 0.044564299 0.078464203 0.012676, + 0.0465803 0.076788597 0.012052, + 0.0465803 0.076168798 0.013605, + 0.044564299 0.077197999 0.015851, + 0.0424264 0.078882702 0.016403001, + 0.0424264 0.079526298 0.014782, + 0.048467699 0.061353698 0.029750001, + 0.050219599 0.059932798 0.028031999, + 0.050219599 0.061015099 0.027167, + 0.048467699 0.062476501 0.028836001, + 0.0465803 0.062856302 0.031335, + 0.0465803 0.061681099 0.032249, + 0.048467699 0.059069499 0.031428002, + 0.050219599 0.057734501 0.029619001, + 0.050219599 0.058839001 0.028849, + 0.048467699 0.060217299 0.030614, + 0.048467699 0.057910901 0.032194, + 0.0465803 0.0604924 0.033112001, + 0.0465803 0.059292302 0.033923, + 0.0546159 0.051845901 0.024626, + 0.055787299 0.0518387 0.021875, + 0.0546159 0.052664299 0.024347, + 0.055437401 0.050999999 0.022949999, + 0.054245099 0.050999999 0.025641, + 0.0532961 0.051853001 0.02734, + 0.0532961 0.052679099 0.027062999, + 0.050219599 -0.032484099 -0.153291, + 0.051830001 -0.0298803 -0.153199, + 0.050219599 -0.032673702 -0.156045, + 0.050219599 -0.0322151 -0.15052301, + 0.048467699 -0.035015199 -0.153381, + 0.051830001 -0.0296141 -0.150401, + 0.048467699 -0.035206798 -0.156105, + 0.056809202 -0.0191528 -0.15572301, + 0.0576833 -0.015930099 -0.149758, + 0.056809202 -0.0187189 -0.14988901, + 0.056661699 -0.019710001 -0.16150001, + 0.056543902 -0.0200695 -0.16150001, + 0.055787299 -0.0219319 -0.155789, + 0.057460099 -0.017272299 -0.16150001, + 0.0582381 -0.0144335 -0.16150001, + 0.058412101 -0.013561 -0.15559, + 0.0576833 -0.016358901 -0.155656, + 0.058383498 -0.0137785 -0.16150001, + 0.057670102 -0.016506299 -0.16150001, + 0.0583959 -0.0137813 -0.1815, + 0.058998398 -0.0046918201 -0.122362, + 0.058998398 -0.0056299102 -0.125329, + 0.059445001 -0.0019974201 -0.121947, + 0.058998398 -0.0036770499 -0.119418, + 0.059445001 -0.00099641294 -0.11897, + 0.058412101 -0.0074033998 -0.122779, + 0.058412101 -0.0083542503 -0.125714, + 0.0599402 0.00329859 -0.121131, + 0.059757002 -0.000244636 -0.124569, + 0.059757002 -0.0018440899 -0.130689, + 0.0599402 -0.00046149699 -0.136609, + 0.059445001 0.054762799 0.0061030001, + 0.058998398 0.055553298 0.008134, + 0.058998398 0.0548409 0.0089069996, + 0.059445001 0.055418801 0.0053209998, + 0.059445001 0.053832699 0.0069519999, + 0.059757002 0.0546855 0.00333, + 0.059757002 0.0537952 0.0041959998, + 0.056809202 0.055077199 0.017379999, + 0.056809202 0.055959702 0.016636999, + 0.0576833 0.054998402 0.014556, + 0.056809202 0.053985398 0.018159, + 0.0576833 0.053947099 0.015352, + 0.055787299 0.055155698 0.020189, + 0.055787299 0.056094401 0.019455001, + 0.0532961 0.068082303 0.012025, + 0.050219599 0.070594899 0.015961001, + 0.051830001 0.068142101 0.015944, + 0.051830001 0.068941802 0.014681, + 0.050219599 0.069781698 0.017276, + 0.050219599 0.068929203 0.018553, + 0.051830001 0.067306302 0.017166, + 0.0532961 0.066555403 0.014484, + 0.0532961 0.067336597 0.013274, + -0.0302257 0.060566701 0.048193, + -0.00267513 0.093684599 0.0084509999, + -1.1871733e-012 0.093722202 0.00849899, + 0.00267513 0.093683504 0.0084509999, + -0.055787299 0.070631199 -0.010097, + -0.055787299 0.070538796 -0.0086150104, + -0.056809202 0.069092803 -0.01113, + -0.055787299 0.070672102 -0.011584, + -0.056809202 0.0691429 -0.012583, + -0.0546159 0.072187103 -0.0091509996, + -0.0546159 0.072105698 -0.0076330001, + 0.044564299 0.081058703 -0.007396, + 0.0465803 0.079554103 -0.0092860004, + 0.044564299 0.0808919 -0.0090429997, + 0.0424264 0.0824968 -0.0055900002, + 0.044564299 0.081169903 -0.0057339901, + 0.0465803 0.079691298 -0.0076519898, + 0.0424264 0.082353599 -0.0072650001, + 0.0109179 0.092984401 0.0095829898, + 0.0109179 0.093080796 0.0076959999, + 0.0137106 0.092616104 0.0091069899, + 0.0137106 0.092459403 0.010998, + 0.0109179 0.092820898 0.011482, + 0.0081421202 0.093264997 0.0099470103, + 0.0081421202 0.093366399 0.0080540003, + 0.0248404 0.084422201 0.027912, + 0.027557701 0.082928903 0.028356001, + 0.027557701 0.081974797 0.030011, + -0.0248404 0.062380299 0.050235, + -0.0220857 0.064084701 0.050576001, + -0.0220857 0.0656441 0.049660001, + -0.0165099 0.056173101 0.056150999, + -0.019305199 0.057776801 0.054655999, + -0.019305199 0.0561492 0.055268001, + -0.0081421202 0.061258901 0.055941001, + -0.0081421202 0.062921599 0.055153999, + -0.0109179 0.062871598 0.054699, + -0.0109179 0.064512998 0.053847998, + -0.0109179 0.066140898 0.052932002, + -0.019305199 0.059401799 0.053989001, + -0.0220857 0.0609264 0.052220002, + -0.0220857 0.059330501 0.052951001, + -0.019305199 0.064221002 0.051617, + -0.0165099 0.065937497 0.051592, + -0.0137106 0.066050202 0.052335002, + -0.0109179 0.057882901 0.056875002, + -0.0109179 0.056208801 0.057479002, + -0.0081421202 0.057904501 0.057328001, + -0.0137106 0.056193002 0.056887001, + -0.0081421202 0.059585799 0.056666002, + -0.0378174 -0.039333601 -0.127684, + -0.0378174 -0.040435299 -0.130233, + -0.040174201 -0.037376601 -0.12738299, + -0.040174201 -0.036194399 -0.124842, + -0.0378174 -0.0381414 -0.125168, + -0.035366699 -0.041165698 -0.127967, + -0.050626501 0.046 0.032202002, + -0.035366699 -0.042275999 -0.130493, + 0.040174201 0.068975501 0.034003999, + 0.0378174 0.069459103 0.036045, + 0.040174201 0.067744799 0.035137001, + 0.040174201 0.070175603 0.032818001, + 0.0424264 0.0684627 0.031838998, + 0.0378174 0.070701301 0.034853, + 0.0424264 0.067276999 0.032967001, + 0.059999999 0.0050204601 -0.123826, + 0.0599402 0.00239812 -0.124196, + 0.0599402 0.00082014297 -0.13037799, + 0.059999999 0.0034638001 -0.13007, + 0.059999999 0.0059086499 -0.120729, + 0.059999999 0.0021991199 -0.136362, + 0.051830001 0.070423499 0.012043, + 0.051830001 0.069703102 0.01338, + 0.0532961 0.068790302 0.01074, + 0.0532961 0.069458403 0.00941901, + 0.051830001 0.071100898 0.010671, + 0.050219599 0.072094299 0.013217, + 0.050219599 0.071366601 0.014607, + -0.027557701 0.059156701 0.050420001, + -0.0248404 0.059248801 0.051761001, + -0.0248404 0.060819902 0.051027998, + -0.027557701 0.060699899 0.049685001, + -0.027557701 0.0576066 0.051095001, + -0.0302257 0.059054501 0.048930999, + -0.0302257 0.0575356 0.049609002, + -2.7206579e-012 0.093741402 0.004745, + 1.2017232e-012 0.093656898 0.0028939999, + -0.00267513 0.093702398 0.0046979999, + -0.00267513 0.093725502 0.0065659899, + -9.3207983e-013 0.093763798 0.0066140001, + 0.00267513 0.093701497 0.0046979999, + 0.00267513 0.093724497 0.0065659899, + 0.0220857 0.081959397 0.034042001, + 0.019305199 0.0834461 0.033388998, + 0.019305199 0.082368404 0.035032999, + 0.0220857 0.080843396 0.035636, + 0.0248404 0.081490502 0.032907002, + 0.0248404 0.080396697 0.034490999, + 0.0220857 0.084017299 0.03073, + 0.0248404 0.083505496 0.029614, + 0.0220857 0.084954798 0.029018, + 0.0220857 0.083018102 0.032405999, + 0.019305199 0.084463902 0.031704001, + 0.0248404 0.082527503 0.03128, + 0.019305199 0.085419402 0.029983001, + -0.027557701 0.063752197 0.048037, + -0.0248404 0.063928299 0.049382001, + -0.027557701 0.062232301 0.048891, + -0.0302257 0.0635565 0.046542, + -0.027557701 0.065258503 0.047121, + -0.0248404 0.065462798 0.048466001, + -0.0302257 0.062067799 0.047396999, + -0.0137106 0.059513699 0.055617001, + -0.0137106 0.061165001 0.054891001, + -0.0165099 0.059462801 0.054877002, + -0.0165099 0.057819199 0.055542, + -0.0137106 0.0578545 0.056281, + -0.0109179 0.059554599 0.056212001, + -0.0109179 0.061218299 0.055486999, + -0.0165099 0.062724203 0.05336, + -0.0165099 0.064337596 0.052508, + -0.019305199 0.062626198 0.052469, + -0.019305199 0.061019301 0.053259999, + -0.0165099 0.061098799 0.054149002, + -0.0137106 0.062805898 0.054102, + -0.0137106 0.064434797 0.053250998 ] + + } + coordIndex [ 482, 1972, 25, -1, 903, 616, 901, -1, + 419, 420, 27, -1, 5, 25, 1972, -1, + 3, 364, 16, -1, 3, 116, 364, -1, + 2, 1295, 761, -1, 2, 86, 1295, -1, + 12, 38, 1765, -1, 1771, 1765, 38, -1, + 1771, 38, 912, -1, 39, 11, 1789, -1, + 0, 419, 27, -1, 0, 144, 44, -1, + 0, 27, 144, -1, 0, 44, 171, -1, + 0, 171, 419, -1, 14, 35, 16, -1, + 14, 39, 35, -1, 14, 419, 17, -1, + 14, 17, 40, -1, 1810, 933, 15, -1, + 949, 3306, 121, -1, 385, 2962, 3296, -1, + 385, 3296, 386, -1, 48, 14, 16, -1, + 169, 171, 44, -1, 2972, 1874, 3311, -1, + 21, 5, 1972, -1, 21, 133, 1834, -1, + 24, 25, 5, -1, 23, 6, 71, -1, + 23, 71, 28, -1, 214, 213, 408, -1, + 80, 2080, 3113, -1, 30, 3113, 2693, -1, + 246, 32, 35, -1, 264, 1320, 92, -1, + 615, 616, 903, -1, 1733, 121, 3306, -1, + 31, 86, 33, -1, 1, 2, 761, -1, + 1, 761, 116, -1, 1, 116, 3, -1, + 1, 86, 2, -1, 1, 33, 86, -1, + 1, 16, 35, -1, 1, 3, 16, -1, + 1, 35, 32, -1, 1, 32, 33, -1, + 10, 11, 39, -1, 382, 39, 1789, -1, + 122, 12, 1765, -1, 129, 14, 40, -1, + 948, 3306, 949, -1, 948, 386, 3296, -1, + 948, 3296, 3306, -1, 131, 949, 121, -1, + 131, 121, 885, -1, 42, 2963, 400, -1, + 42, 2976, 2963, -1, 132, 2962, 385, -1, + 132, 2963, 2962, -1, 132, 400, 2963, -1, + 142, 1067, 181, -1, 421, 419, 14, -1, + 421, 14, 48, -1, 422, 118, 423, -1, + 153, 48, 16, -1, 460, 169, 44, -1, + 62, 20, 42, -1, 62, 42, 181, -1, + 19, 2972, 2976, -1, 19, 2976, 42, -1, + 174, 1874, 2972, -1, 174, 20, 62, -1, + 719, 176, 177, -1, 470, 1892, 1066, -1, + 232, 231, 30, -1, 232, 30, 2693, -1, + 486, 230, 2693, -1, 228, 486, 22, -1, + 228, 230, 486, -1, 1116, 482, 486, -1, + 1833, 71, 6, -1, 4, 21, 1834, -1, + 4, 1833, 6, -1, 4, 1834, 1833, -1, + 4, 6, 24, -1, 4, 5, 21, -1, + 4, 24, 5, -1, 67, 24, 6, -1, + 67, 6, 23, -1, 7, 408, 213, -1, + 7, 28, 139, -1, 7, 409, 408, -1, + 7, 139, 409, -1, 76, 23, 28, -1, + 76, 7, 213, -1, 76, 28, 7, -1, + 215, 214, 414, -1, 29, 2080, 80, -1, + 29, 79, 2080, -1, 29, 233, 79, -1, + 81, 30, 231, -1, 1530, 31, 33, -1, + 270, 1320, 264, -1, 8, 264, 89, -1, + 8, 263, 264, -1, 88, 8, 89, -1, + 88, 263, 8, -1, 90, 92, 2181, -1, + 90, 89, 264, -1, 90, 264, 92, -1, + 95, 3500, 901, -1, 288, 289, 2235, -1, + 99, 100, 335, -1, 333, 335, 100, -1, + 334, 298, 99, -1, 334, 99, 335, -1, + 714, 330, 104, -1, 339, 179, 716, -1, + 735, 179, 339, -1, 516, 1221, 3513, -1, + 617, 903, 885, -1, 617, 615, 903, -1, + 617, 885, 883, -1, 2967, 1733, 3306, -1, + 278, 122, 1765, -1, 9, 10, 39, -1, + 9, 14, 15, -1, 9, 39, 14, -1, + 9, 1788, 10, -1, 9, 15, 933, -1, + 9, 933, 1788, -1, 3007, 10, 1788, -1, + 3007, 1789, 11, -1, 3007, 11, 10, -1, + 1792, 382, 1789, -1, 128, 35, 39, -1, + 128, 39, 124, -1, 37, 124, 39, -1, + 37, 38, 12, -1, 37, 125, 124, -1, + 37, 12, 122, -1, 37, 899, 125, -1, + 37, 122, 899, -1, 891, 1320, 565, -1, + 891, 565, 897, -1, 891, 92, 1320, -1, + 13, 15, 14, -1, 13, 14, 129, -1, + 13, 1810, 15, -1, 13, 129, 1810, -1, + 909, 1788, 933, -1, 435, 1810, 129, -1, + 388, 903, 904, -1, 388, 885, 903, -1, + 387, 131, 885, -1, 387, 885, 388, -1, + 140, 181, 42, -1, 140, 142, 181, -1, + 135, 395, 396, -1, 143, 1066, 1067, -1, + 143, 1067, 142, -1, 973, 972, 1043, -1, + 418, 2048, 420, -1, 1705, 1704, 1692, -1, + 2585, 1692, 47, -1, 365, 16, 364, -1, + 46, 16, 365, -1, 46, 365, 422, -1, + 51, 49, 50, -1, 112, 426, 153, -1, + 112, 353, 426, -1, 112, 1704, 837, -1, + 54, 47, 1692, -1, 54, 1692, 1704, -1, + 54, 46, 47, -1, 54, 153, 16, -1, + 54, 16, 46, -1, 440, 439, 40, -1, + 440, 40, 17, -1, 440, 17, 419, -1, + 440, 419, 171, -1, 461, 44, 149, -1, + 461, 460, 44, -1, 55, 40, 439, -1, + 55, 56, 40, -1, 459, 169, 460, -1, + 1047, 181, 1048, -1, 1047, 62, 181, -1, + 18, 2972, 19, -1, 18, 174, 2972, -1, + 18, 20, 174, -1, 18, 42, 20, -1, + 18, 19, 42, -1, 1873, 3311, 1874, -1, + 64, 177, 1053, -1, 718, 176, 719, -1, + 106, 63, 2496, -1, 106, 719, 177, -1, + 106, 177, 64, -1, 1890, 471, 488, -1, + 1070, 181, 1067, -1, 1156, 1972, 1975, -1, + 1156, 185, 133, -1, 1156, 21, 1972, -1, + 1156, 133, 21, -1, 227, 228, 69, -1, + 227, 68, 537, -1, 227, 69, 68, -1, + 26, 69, 228, -1, 26, 228, 22, -1, + 26, 482, 25, -1, 26, 22, 486, -1, + 26, 486, 482, -1, 1117, 486, 1945, -1, + 1117, 1116, 486, -1, 75, 67, 23, -1, + 75, 23, 76, -1, 66, 24, 67, -1, + 66, 25, 24, -1, 66, 26, 25, -1, + 66, 69, 26, -1, 509, 420, 2048, -1, + 509, 27, 420, -1, 509, 144, 27, -1, + 509, 147, 144, -1, 2041, 2046, 48, -1, + 2041, 516, 517, -1, 70, 421, 48, -1, + 70, 48, 2046, -1, 208, 1193, 74, -1, + 136, 28, 71, -1, 136, 139, 28, -1, + 221, 220, 73, -1, 221, 74, 222, -1, + 2708, 522, 73, -1, 209, 535, 216, -1, + 217, 216, 535, -1, 413, 215, 414, -1, + 1216, 84, 78, -1, 1192, 1199, 538, -1, + 225, 81, 231, -1, 225, 548, 81, -1, + 234, 233, 29, -1, 234, 29, 80, -1, + 1197, 1196, 543, -1, 83, 80, 3113, -1, + 82, 3113, 30, -1, 82, 30, 81, -1, + 82, 83, 3113, -1, 2121, 1252, 2114, -1, + 2121, 78, 84, -1, 2121, 2080, 79, -1, + 2121, 79, 78, -1, 237, 84, 1216, -1, + 1531, 86, 31, -1, 1531, 31, 1530, -1, + 1520, 246, 1521, -1, 1520, 32, 246, -1, + 1520, 33, 32, -1, 1520, 1530, 33, -1, + 266, 242, 267, -1, 2182, 262, 263, -1, + 2182, 263, 88, -1, 1334, 2181, 92, -1, + 281, 95, 901, -1, 96, 95, 2234, -1, + 96, 3500, 95, -1, 291, 282, 595, -1, + 291, 286, 282, -1, 291, 288, 286, -1, + 1284, 97, 1279, -1, 1356, 97, 1359, -1, + 636, 1358, 1359, -1, 650, 99, 298, -1, + 1411, 298, 334, -1, 707, 312, 102, -1, + 332, 98, 679, -1, 332, 679, 720, -1, + 680, 300, 2281, -1, 680, 679, 98, -1, + 677, 2281, 300, -1, 677, 300, 309, -1, + 677, 309, 310, -1, 1422, 2826, 102, -1, + 1422, 102, 312, -1, 331, 2894, 296, -1, + 331, 2895, 2894, -1, 331, 296, 104, -1, + 331, 104, 330, -1, 734, 735, 339, -1, + 338, 103, 2284, -1, 722, 721, 103, -1, + 722, 103, 338, -1, 722, 338, 343, -1, + 550, 108, 1229, -1, 201, 191, 200, -1, + 110, 1221, 516, -1, 194, 193, 1006, -1, + 1587, 2401, 426, -1, 1590, 112, 837, -1, + 757, 2866, 358, -1, 757, 358, 1605, -1, + 775, 2358, 2357, -1, 360, 362, 1646, -1, + 360, 113, 362, -1, 360, 1630, 113, -1, + 759, 757, 1605, -1, 115, 114, 357, -1, + 115, 1636, 783, -1, 356, 116, 117, -1, + 34, 114, 364, -1, 34, 357, 114, -1, + 34, 364, 116, -1, 34, 116, 356, -1, + 34, 356, 357, -1, 1087, 2453, 2454, -1, + 1685, 118, 422, -1, 1685, 422, 365, -1, + 860, 861, 849, -1, 1062, 2496, 63, -1, + 855, 849, 861, -1, 876, 651, 652, -1, + 884, 121, 120, -1, 884, 885, 121, -1, + 372, 120, 121, -1, 273, 274, 122, -1, + 123, 899, 122, -1, 123, 122, 274, -1, + 123, 274, 375, -1, 2542, 3007, 1788, -1, + 127, 35, 128, -1, 247, 246, 35, -1, + 247, 35, 127, -1, 253, 128, 124, -1, + 36, 38, 37, -1, 36, 37, 39, -1, + 36, 912, 38, -1, 36, 382, 912, -1, + 36, 39, 382, -1, 93, 92, 891, -1, + 93, 891, 589, -1, 890, 589, 891, -1, + 890, 584, 589, -1, 890, 1750, 584, -1, + 41, 40, 56, -1, 41, 56, 1020, -1, + 1019, 129, 40, -1, 1019, 40, 41, -1, + 1019, 41, 1020, -1, 1812, 1810, 435, -1, + 1018, 129, 1019, -1, 952, 131, 387, -1, + 389, 132, 385, -1, 391, 133, 185, -1, + 391, 185, 392, -1, 3041, 392, 183, -1, + 138, 139, 136, -1, 399, 42, 400, -1, + 399, 140, 42, -1, 43, 134, 1066, -1, + 43, 1066, 143, -1, 43, 135, 134, -1, + 141, 395, 135, -1, 141, 1828, 395, -1, + 141, 135, 43, -1, 141, 43, 143, -1, + 406, 149, 44, -1, 406, 44, 144, -1, + 146, 144, 147, -1, 146, 404, 144, -1, + 148, 186, 2584, -1, 407, 527, 414, -1, + 407, 414, 214, -1, 407, 214, 408, -1, + 1201, 2048, 418, -1, 151, 512, 1209, -1, + 1699, 1692, 1690, -1, 1699, 1705, 1692, -1, + 45, 422, 2585, -1, 45, 46, 422, -1, + 45, 2585, 47, -1, 45, 47, 46, -1, + 424, 50, 49, -1, 424, 154, 50, -1, + 424, 986, 154, -1, 424, 48, 153, -1, + 2589, 154, 986, -1, 192, 49, 193, -1, + 192, 196, 49, -1, 190, 49, 196, -1, + 190, 197, 189, -1, 190, 196, 197, -1, + 190, 2041, 48, -1, 190, 48, 424, -1, + 190, 424, 49, -1, 52, 193, 49, -1, + 52, 49, 51, -1, 52, 1006, 193, -1, + 52, 1005, 1006, -1, 156, 50, 154, -1, + 156, 51, 50, -1, 156, 52, 51, -1, + 156, 154, 427, -1, 156, 427, 1004, -1, + 156, 1005, 52, -1, 53, 112, 153, -1, + 53, 153, 54, -1, 53, 1704, 112, -1, + 53, 54, 1704, -1, 963, 936, 454, -1, + 963, 454, 962, -1, 429, 162, 448, -1, + 444, 440, 445, -1, 159, 55, 439, -1, + 159, 56, 55, -1, 159, 1020, 56, -1, + 157, 441, 431, -1, 157, 431, 1853, -1, + 157, 1020, 159, -1, 157, 159, 441, -1, + 442, 1037, 433, -1, 442, 431, 441, -1, + 384, 454, 936, -1, 384, 452, 454, -1, + 163, 58, 162, -1, 163, 433, 1037, -1, + 59, 166, 447, -1, 59, 162, 58, -1, + 59, 448, 162, -1, 59, 447, 448, -1, + 57, 1042, 453, -1, 57, 60, 455, -1, + 1041, 453, 1042, -1, 167, 57, 455, -1, + 167, 1042, 57, -1, 167, 973, 1043, -1, + 167, 1043, 1042, -1, 172, 169, 459, -1, + 172, 1039, 170, -1, 172, 1038, 1039, -1, + 1036, 173, 58, -1, 1036, 163, 1037, -1, + 1036, 58, 163, -1, 1036, 1038, 173, -1, + 165, 166, 60, -1, 165, 453, 452, -1, + 165, 57, 453, -1, 165, 60, 57, -1, + 61, 60, 166, -1, 61, 58, 173, -1, + 61, 166, 59, -1, 61, 59, 58, -1, + 457, 455, 60, -1, 457, 61, 173, -1, + 457, 60, 61, -1, 1046, 174, 62, -1, + 1046, 62, 1047, -1, 2599, 2600, 1873, -1, + 466, 1062, 63, -1, 466, 63, 106, -1, + 466, 106, 64, -1, 1054, 64, 1053, -1, + 1054, 466, 64, -1, 180, 2508, 1738, -1, + 180, 2509, 2508, -1, 180, 1738, 176, -1, + 180, 176, 718, -1, 468, 181, 1070, -1, + 473, 470, 1066, -1, 473, 1066, 134, -1, + 473, 134, 183, -1, 494, 491, 1118, -1, + 484, 1972, 482, -1, 1996, 1121, 1953, -1, + 1158, 185, 1156, -1, 1978, 1979, 1932, -1, + 1978, 1932, 1933, -1, 1149, 503, 1151, -1, + 1143, 496, 503, -1, 1137, 1932, 1979, -1, + 1137, 1934, 1932, -1, 184, 1151, 503, -1, + 184, 499, 1151, -1, 184, 503, 496, -1, + 184, 498, 499, -1, 534, 537, 68, -1, + 534, 68, 77, -1, 534, 77, 217, -1, + 534, 217, 535, -1, 65, 66, 67, -1, + 65, 75, 77, -1, 65, 67, 75, -1, + 65, 77, 68, -1, 65, 68, 69, -1, + 65, 69, 66, -1, 1841, 509, 2048, -1, + 2724, 1264, 2022, -1, 514, 512, 187, -1, + 198, 189, 197, -1, 198, 200, 191, -1, + 203, 2041, 517, -1, 3409, 421, 70, -1, + 3409, 70, 2046, -1, 206, 187, 152, -1, + 206, 152, 204, -1, 206, 1175, 1173, -1, + 206, 1173, 2033, -1, 206, 2029, 187, -1, + 206, 2030, 2029, -1, 205, 204, 421, -1, + 205, 421, 2044, -1, 1172, 1171, 2044, -1, + 1172, 2044, 2043, -1, 2703, 524, 522, -1, + 1191, 1193, 208, -1, 1836, 71, 1833, -1, + 1836, 136, 71, -1, 72, 73, 522, -1, + 72, 221, 73, -1, 72, 74, 221, -1, + 72, 522, 524, -1, 72, 208, 74, -1, + 72, 524, 208, -1, 532, 73, 220, -1, + 532, 2708, 73, -1, 532, 220, 530, -1, + 210, 222, 74, -1, 210, 209, 222, -1, + 210, 74, 1193, -1, 210, 1193, 1192, -1, + 212, 75, 76, -1, 212, 76, 213, -1, + 212, 77, 75, -1, 212, 217, 77, -1, + 219, 216, 215, -1, 219, 215, 413, -1, + 219, 222, 209, -1, 219, 209, 216, -1, + 1215, 78, 79, -1, 1215, 1216, 78, -1, + 1215, 79, 233, -1, 224, 538, 1199, -1, + 224, 548, 225, -1, 229, 227, 537, -1, + 229, 225, 231, -1, 1179, 1178, 1214, -1, + 2061, 523, 207, -1, 2061, 207, 2068, -1, + 1213, 2068, 207, -1, 1213, 1179, 1214, -1, + 1213, 207, 1179, -1, 1198, 548, 224, -1, + 1198, 224, 1199, -1, 549, 234, 80, -1, + 549, 80, 83, -1, 547, 81, 548, -1, + 547, 82, 81, -1, 547, 83, 82, -1, + 547, 549, 83, -1, 1574, 2083, 1566, -1, + 3112, 3113, 2080, -1, 2106, 2114, 2090, -1, + 1244, 2121, 2114, -1, 2119, 2080, 2121, -1, + 235, 2121, 84, -1, 235, 1252, 2121, -1, + 235, 84, 237, -1, 236, 223, 2108, -1, + 236, 2064, 223, -1, 85, 3513, 2090, -1, + 85, 2090, 2116, -1, 85, 2116, 3513, -1, + 2109, 2108, 223, -1, 2109, 223, 541, -1, + 1263, 540, 2023, -1, 1263, 2022, 1264, -1, + 1263, 2023, 2022, -1, 2124, 540, 1263, -1, + 1649, 2385, 1656, -1, 1649, 1272, 2385, -1, + 1923, 2783, 1085, -1, 241, 740, 259, -1, + 241, 1285, 740, -1, 239, 1278, 243, -1, + 294, 1279, 97, -1, 294, 1356, 295, -1, + 294, 97, 1356, -1, 2169, 1285, 241, -1, + 1292, 294, 1294, -1, 1292, 1279, 294, -1, + 2879, 1295, 86, -1, 2879, 86, 1531, -1, + 250, 739, 1521, -1, 569, 249, 248, -1, + 569, 1306, 249, -1, 255, 899, 897, -1, + 255, 251, 899, -1, 255, 567, 251, -1, + 238, 87, 262, -1, 238, 2182, 2183, -1, + 238, 262, 2182, -1, 238, 240, 239, -1, + 238, 239, 87, -1, 256, 262, 87, -1, + 256, 242, 266, -1, 256, 243, 242, -1, + 256, 239, 243, -1, 256, 87, 239, -1, + 741, 1311, 1309, -1, 741, 259, 740, -1, + 258, 259, 741, -1, 258, 741, 1309, -1, + 258, 1309, 570, -1, 268, 267, 576, -1, + 268, 1320, 270, -1, 268, 576, 1320, -1, + 577, 570, 271, -1, 577, 258, 570, -1, + 2180, 2182, 88, -1, 2180, 88, 89, -1, + 2180, 89, 90, -1, 2180, 90, 2181, -1, + 1747, 375, 274, -1, 1747, 1745, 375, -1, + 276, 378, 578, -1, 581, 593, 589, -1, + 588, 1326, 906, -1, 91, 1334, 92, -1, + 91, 589, 1334, -1, 91, 92, 93, -1, + 91, 93, 589, -1, 2191, 589, 593, -1, + 279, 605, 2205, -1, 279, 324, 688, -1, + 279, 691, 605, -1, 279, 688, 691, -1, + 2269, 1426, 324, -1, 625, 621, 634, -1, + 1399, 2216, 2813, -1, 1388, 2299, 623, -1, + 630, 595, 282, -1, 630, 631, 638, -1, + 630, 638, 595, -1, 283, 595, 594, -1, + 283, 292, 291, -1, 283, 291, 595, -1, + 94, 2236, 2234, -1, 94, 281, 614, -1, + 94, 95, 281, -1, 94, 2234, 95, -1, + 94, 609, 2236, -1, 94, 614, 609, -1, + 285, 3500, 96, -1, 285, 2234, 2235, -1, + 285, 96, 2234, -1, 1380, 282, 286, -1, + 2233, 288, 2235, -1, 2233, 286, 288, -1, + 293, 288, 291, -1, 641, 1293, 1294, -1, + 641, 326, 1293, -1, 1408, 296, 2894, -1, + 1408, 2894, 2893, -1, 297, 1291, 105, -1, + 297, 104, 296, -1, 563, 105, 1291, -1, + 563, 1293, 326, -1, 592, 2229, 2230, -1, + 592, 2230, 1337, -1, 637, 1359, 97, -1, + 637, 97, 1284, -1, 633, 622, 636, -1, + 633, 634, 621, -1, 633, 621, 622, -1, + 1410, 298, 1411, -1, 101, 333, 100, -1, + 101, 306, 98, -1, 101, 98, 332, -1, + 101, 332, 333, -1, 299, 98, 306, -1, + 299, 680, 98, -1, 299, 300, 680, -1, + 299, 306, 305, -1, 301, 100, 99, -1, + 301, 99, 650, -1, 304, 301, 666, -1, + 304, 100, 301, -1, 304, 101, 100, -1, + 304, 306, 101, -1, 1414, 102, 2826, -1, + 307, 707, 102, -1, 307, 1414, 1415, -1, + 307, 102, 1414, -1, 307, 705, 707, -1, + 656, 1419, 671, -1, 656, 657, 1419, -1, + 676, 677, 310, -1, 706, 1443, 314, -1, + 706, 709, 1443, -1, 706, 312, 707, -1, + 706, 314, 312, -1, 1444, 674, 1445, -1, + 1444, 1443, 709, -1, 1428, 675, 698, -1, + 1435, 687, 1363, -1, 1435, 2848, 687, -1, + 1447, 2284, 103, -1, 313, 103, 721, -1, + 313, 1447, 103, -1, 313, 1448, 1447, -1, + 317, 340, 730, -1, 317, 730, 337, -1, + 737, 374, 889, -1, 737, 342, 374, -1, + 319, 725, 684, -1, 2507, 2509, 179, -1, + 2507, 179, 735, -1, 322, 703, 321, -1, + 322, 329, 703, -1, 1413, 321, 1415, -1, + 2406, 2407, 769, -1, 2406, 769, 329, -1, + 2406, 329, 322, -1, 686, 2848, 2850, -1, + 686, 687, 2848, -1, 686, 2850, 694, -1, + 686, 694, 1342, -1, 1343, 1342, 694, -1, + 696, 714, 104, -1, 696, 105, 695, -1, + 696, 104, 297, -1, 696, 297, 105, -1, + 327, 695, 105, -1, 327, 563, 326, -1, + 327, 105, 563, -1, 700, 329, 769, -1, + 697, 675, 674, -1, 697, 698, 675, -1, + 708, 697, 674, -1, 708, 1444, 709, -1, + 708, 674, 1444, -1, 2315, 3243, 3244, -1, + 865, 106, 2496, -1, 865, 719, 106, -1, + 1497, 335, 333, -1, 1500, 2244, 1411, -1, + 1500, 1411, 334, -1, 723, 1506, 318, -1, + 723, 318, 337, -1, 727, 343, 338, -1, + 344, 318, 1506, -1, 344, 343, 727, -1, + 344, 726, 318, -1, 344, 727, 726, -1, + 729, 730, 340, -1, 729, 340, 734, -1, + 729, 734, 339, -1, 341, 340, 317, -1, + 341, 317, 319, -1, 1496, 722, 343, -1, + 346, 1302, 1301, -1, 346, 738, 1302, -1, + 1536, 761, 1295, -1, 743, 745, 1554, -1, + 349, 1229, 108, -1, 111, 191, 201, -1, + 111, 108, 110, -1, 111, 349, 108, -1, + 111, 201, 349, -1, 107, 1221, 110, -1, + 107, 110, 108, -1, 107, 550, 1221, -1, + 107, 108, 550, -1, 109, 516, 191, -1, + 109, 110, 516, -1, 109, 191, 111, -1, + 109, 111, 110, -1, 350, 202, 194, -1, + 350, 201, 202, -1, 350, 349, 201, -1, + 351, 1009, 1230, -1, 351, 350, 194, -1, + 351, 194, 1006, -1, 351, 1006, 1009, -1, + 987, 1230, 1009, -1, 352, 426, 353, -1, + 352, 1587, 426, -1, 1588, 353, 112, -1, + 1588, 112, 1590, -1, 2865, 358, 2866, -1, + 2865, 2871, 355, -1, 1537, 2866, 757, -1, + 2931, 2358, 775, -1, 768, 1479, 771, -1, + 768, 2859, 1479, -1, 1639, 1636, 115, -1, + 1639, 115, 357, -1, 764, 2929, 2928, -1, + 764, 763, 2929, -1, 2414, 778, 2410, -1, + 1480, 771, 1479, -1, 774, 2410, 778, -1, + 361, 113, 773, -1, 361, 773, 774, -1, + 361, 774, 778, -1, 361, 362, 113, -1, + 1608, 1630, 1629, -1, 1608, 113, 1630, -1, + 1608, 773, 113, -1, 1631, 1630, 360, -1, + 1845, 807, 806, -1, 1845, 806, 781, -1, + 1637, 783, 1636, -1, 363, 364, 114, -1, + 363, 114, 115, -1, 363, 115, 783, -1, + 760, 116, 761, -1, 760, 117, 116, -1, + 760, 759, 117, -1, 1604, 356, 117, -1, + 1604, 759, 1605, -1, 1604, 117, 759, -1, + 829, 1675, 476, -1, 477, 478, 1660, -1, + 477, 1660, 1661, -1, 1676, 2453, 1087, -1, + 793, 667, 803, -1, 793, 794, 303, -1, + 793, 303, 667, -1, 661, 659, 367, -1, + 1086, 1087, 2454, -1, 1086, 2454, 791, -1, + 1086, 791, 1672, -1, 2452, 791, 2454, -1, + 797, 789, 796, -1, 790, 796, 789, -1, + 790, 819, 817, -1, 790, 817, 796, -1, + 790, 789, 2445, -1, 3465, 813, 3464, -1, + 2471, 3466, 2952, -1, 2471, 3465, 3466, -1, + 2456, 819, 2457, -1, 795, 817, 824, -1, + 795, 822, 794, -1, 795, 824, 822, -1, + 795, 796, 817, -1, 808, 820, 821, -1, + 368, 367, 303, -1, 368, 303, 794, -1, + 368, 794, 822, -1, 2483, 812, 814, -1, + 2482, 2483, 814, -1, 978, 835, 1647, -1, + 978, 370, 835, -1, 978, 1647, 3336, -1, + 831, 118, 1685, -1, 831, 830, 981, -1, + 831, 981, 423, -1, 831, 423, 118, -1, + 119, 365, 1850, -1, 119, 1850, 1685, -1, + 119, 1685, 365, -1, 1643, 1634, 777, -1, + 871, 1094, 870, -1, 1670, 800, 1669, -1, + 1670, 797, 800, -1, 1670, 789, 797, -1, + 479, 874, 653, -1, 479, 877, 874, -1, + 875, 653, 874, -1, 875, 876, 652, -1, + 880, 1669, 800, -1, 1366, 884, 120, -1, + 1366, 120, 372, -1, 373, 121, 1733, -1, + 373, 372, 121, -1, 2973, 2963, 2976, -1, + 2973, 2974, 2963, -1, 3491, 3311, 1873, -1, + 3491, 1873, 2600, -1, 377, 278, 1765, -1, + 377, 378, 278, -1, 277, 122, 278, -1, + 277, 273, 122, -1, 376, 899, 123, -1, + 376, 123, 375, -1, 3499, 901, 3500, -1, + 1766, 578, 378, -1, 1786, 2542, 1788, -1, + 911, 1771, 912, -1, 381, 382, 1792, -1, + 914, 912, 382, -1, 914, 916, 912, -1, + 252, 253, 124, -1, 252, 125, 899, -1, + 252, 124, 125, -1, 252, 899, 251, -1, + 126, 127, 128, -1, 126, 128, 253, -1, + 126, 247, 127, -1, 126, 253, 254, -1, + 126, 254, 569, -1, 126, 248, 247, -1, + 126, 569, 248, -1, 436, 1812, 435, -1, + 436, 1026, 1868, -1, 434, 435, 129, -1, + 434, 129, 1018, -1, 2558, 379, 932, -1, + 2558, 2556, 379, -1, 130, 932, 379, -1, + 130, 931, 932, -1, 130, 379, 909, -1, + 130, 933, 931, -1, 130, 909, 933, -1, + 1866, 922, 2557, -1, 1866, 1869, 922, -1, + 1811, 1868, 1867, -1, 1811, 436, 1868, -1, + 1811, 1812, 436, -1, 950, 386, 948, -1, + 947, 949, 131, -1, 947, 131, 952, -1, + 3026, 2567, 138, -1, 1044, 1043, 972, -1, + 1044, 2566, 2568, -1, 970, 400, 132, -1, + 970, 132, 389, -1, 935, 964, 943, -1, + 935, 963, 964, -1, 935, 936, 963, -1, + 935, 943, 944, -1, 390, 942, 943, -1, + 390, 943, 964, -1, 1832, 1834, 133, -1, + 1832, 133, 391, -1, 393, 183, 134, -1, + 393, 3041, 183, -1, 393, 134, 135, -1, + 393, 135, 396, -1, 2574, 2567, 2575, -1, + 1835, 138, 136, -1, 1835, 136, 1836, -1, + 1835, 3027, 3026, -1, 1835, 3026, 138, -1, + 137, 138, 2567, -1, 137, 2567, 2574, -1, + 137, 2574, 411, -1, 137, 411, 409, -1, + 137, 409, 139, -1, 137, 139, 138, -1, + 1827, 395, 1828, -1, 398, 142, 140, -1, + 398, 140, 399, -1, 397, 1828, 141, -1, + 397, 142, 398, -1, 397, 143, 142, -1, + 397, 141, 143, -1, 405, 144, 404, -1, + 405, 406, 144, -1, 145, 148, 147, -1, + 145, 186, 148, -1, 145, 147, 509, -1, + 145, 509, 186, -1, 2582, 967, 966, -1, + 2582, 526, 967, -1, 2583, 966, 401, -1, + 2583, 148, 2584, -1, 2583, 401, 148, -1, + 2583, 2582, 966, -1, 403, 404, 146, -1, + 403, 146, 147, -1, 403, 147, 148, -1, + 403, 148, 401, -1, 464, 149, 406, -1, + 464, 461, 149, -1, 410, 527, 407, -1, + 410, 526, 527, -1, 410, 967, 526, -1, + 415, 530, 220, -1, 1203, 1201, 1208, -1, + 417, 1209, 1208, -1, 417, 151, 1209, -1, + 417, 421, 204, -1, 150, 187, 512, -1, + 150, 512, 151, -1, 150, 152, 187, -1, + 150, 204, 152, -1, 150, 417, 204, -1, + 150, 151, 417, -1, 1693, 2585, 1842, -1, + 3334, 2585, 422, -1, 1849, 1850, 365, -1, + 1849, 365, 982, -1, 425, 153, 426, -1, + 425, 424, 153, -1, 2591, 154, 2589, -1, + 2591, 427, 154, -1, 995, 2590, 2593, -1, + 998, 987, 1009, -1, 155, 1004, 1005, -1, + 155, 1005, 156, -1, 155, 156, 1004, -1, + 428, 161, 429, -1, 428, 1861, 161, -1, + 1862, 161, 1861, -1, 1862, 1022, 432, -1, + 1862, 432, 161, -1, 1015, 1853, 431, -1, + 1854, 1020, 157, -1, 1854, 157, 1853, -1, + 1024, 437, 1031, -1, 158, 171, 170, -1, + 158, 170, 1039, -1, 446, 440, 171, -1, + 446, 445, 440, -1, 446, 171, 158, -1, + 446, 158, 1039, -1, 443, 159, 439, -1, + 443, 441, 159, -1, 160, 429, 161, -1, + 160, 161, 432, -1, 160, 432, 433, -1, + 160, 162, 429, -1, 160, 163, 162, -1, + 160, 433, 163, -1, 164, 452, 384, -1, + 164, 166, 165, -1, 164, 165, 452, -1, + 164, 447, 166, -1, 164, 449, 447, -1, + 164, 384, 449, -1, 463, 167, 455, -1, + 463, 973, 167, -1, 168, 169, 172, -1, + 168, 172, 170, -1, 168, 171, 169, -1, + 168, 170, 171, -1, 456, 1038, 172, -1, + 456, 173, 1038, -1, 456, 457, 173, -1, + 456, 172, 459, -1, 1872, 1874, 174, -1, + 1872, 174, 1046, -1, 175, 1740, 1053, -1, + 175, 177, 176, -1, 175, 1053, 177, -1, + 175, 176, 1738, -1, 175, 1738, 2971, -1, + 175, 2971, 1740, -1, 1052, 1739, 887, -1, + 465, 466, 1054, -1, 465, 1876, 1057, -1, + 465, 1057, 466, -1, 178, 179, 2509, -1, + 178, 2509, 180, -1, 178, 716, 179, -1, + 178, 180, 718, -1, 178, 717, 716, -1, + 178, 718, 717, -1, 1888, 471, 1890, -1, + 182, 1048, 181, -1, 182, 181, 468, -1, + 1049, 182, 468, -1, 1049, 1048, 182, -1, + 1077, 1064, 1875, -1, 472, 473, 487, -1, + 472, 488, 471, -1, 472, 487, 488, -1, + 474, 490, 487, -1, 474, 487, 473, -1, + 474, 1126, 490, -1, 474, 392, 185, -1, + 474, 185, 1963, -1, 474, 183, 392, -1, + 474, 473, 183, -1, 3069, 2620, 2003, -1, + 1668, 1090, 1673, -1, 1929, 1673, 1090, -1, + 1088, 2651, 478, -1, 1088, 1676, 1087, -1, + 3099, 3100, 1094, -1, 3099, 1094, 871, -1, + 2654, 1101, 1933, -1, 3539, 878, 480, -1, + 3276, 3540, 2663, -1, 1940, 2662, 480, -1, + 3541, 2662, 2663, -1, 3541, 480, 2662, -1, + 3541, 2663, 3540, -1, 3541, 3539, 480, -1, + 1113, 1114, 1905, -1, 1115, 1118, 491, -1, + 483, 494, 1118, -1, 483, 1951, 1122, -1, + 1971, 1972, 484, -1, 1997, 3382, 556, -1, + 1997, 1121, 1996, -1, 1120, 1997, 556, -1, + 1120, 1121, 1997, -1, 1948, 486, 2693, -1, + 3107, 1163, 1954, -1, 1162, 1953, 1954, -1, + 1162, 1996, 1953, -1, 1162, 1954, 1163, -1, + 493, 483, 1122, -1, 493, 494, 483, -1, + 1125, 1153, 1883, -1, 2680, 491, 494, -1, + 495, 1933, 1101, -1, 495, 1978, 1933, -1, + 495, 1101, 853, -1, 1129, 505, 2674, -1, + 1128, 502, 1129, -1, 497, 496, 1983, -1, + 497, 184, 496, -1, 497, 498, 184, -1, + 497, 1983, 1131, -1, 467, 499, 498, -1, + 467, 498, 3067, -1, 500, 499, 467, -1, + 500, 467, 1881, -1, 1157, 1963, 185, -1, + 1157, 185, 1158, -1, 2758, 2144, 2692, -1, + 2009, 1209, 512, -1, 531, 1203, 1208, -1, + 531, 2705, 1203, -1, 2716, 1209, 506, -1, + 2716, 506, 2717, -1, 510, 186, 509, -1, + 510, 2584, 186, -1, 2052, 1841, 2048, -1, + 2026, 1264, 2724, -1, 2011, 2010, 2038, -1, + 2011, 507, 2008, -1, 513, 187, 2029, -1, + 513, 514, 187, -1, 188, 189, 198, -1, + 188, 190, 189, -1, 188, 2041, 190, -1, + 188, 516, 2041, -1, 188, 198, 191, -1, + 188, 191, 516, -1, 199, 192, 193, -1, + 199, 196, 192, -1, 199, 193, 194, -1, + 199, 194, 202, -1, 195, 197, 196, -1, + 195, 198, 197, -1, 195, 196, 199, -1, + 195, 200, 198, -1, 195, 201, 200, -1, + 195, 202, 201, -1, 195, 199, 202, -1, + 518, 203, 517, -1, 518, 2041, 203, -1, + 3129, 2044, 421, -1, 3129, 421, 3409, -1, + 520, 206, 204, -1, 520, 204, 205, -1, + 520, 205, 2044, -1, 520, 2044, 1171, -1, + 520, 1171, 521, -1, 520, 1175, 206, -1, + 2032, 206, 2033, -1, 2032, 2030, 206, -1, + 2037, 507, 2011, -1, 2037, 2011, 2038, -1, + 1177, 207, 523, -1, 1177, 1179, 207, -1, + 1185, 2037, 2036, -1, 1185, 1170, 507, -1, + 1185, 507, 2037, -1, 2013, 1181, 1189, -1, + 1190, 208, 524, -1, 1190, 1191, 208, -1, + 529, 530, 415, -1, 2058, 532, 530, -1, + 2714, 2705, 531, -1, 536, 535, 209, -1, + 536, 209, 210, -1, 536, 1192, 538, -1, + 536, 210, 1192, -1, 211, 212, 213, -1, + 211, 213, 214, -1, 211, 214, 215, -1, + 211, 215, 216, -1, 211, 216, 217, -1, + 211, 217, 212, -1, 218, 219, 413, -1, + 218, 415, 220, -1, 218, 413, 415, -1, + 218, 220, 221, -1, 218, 221, 222, -1, + 218, 222, 219, -1, 1212, 223, 2064, -1, + 1212, 541, 223, -1, 2059, 1215, 233, -1, + 539, 224, 225, -1, 539, 225, 229, -1, + 539, 538, 224, -1, 539, 229, 537, -1, + 226, 228, 227, -1, 226, 227, 229, -1, + 226, 230, 228, -1, 226, 229, 231, -1, + 226, 231, 232, -1, 226, 2693, 230, -1, + 226, 232, 2693, -1, 544, 523, 2061, -1, + 544, 543, 1196, -1, 544, 1188, 523, -1, + 544, 1196, 1188, -1, 542, 233, 234, -1, + 542, 2059, 233, -1, 546, 1197, 543, -1, + 546, 543, 542, -1, 546, 234, 549, -1, + 546, 542, 234, -1, 1218, 1226, 551, -1, + 2097, 2090, 3513, -1, 2097, 3513, 1221, -1, + 2097, 1221, 2071, -1, 2100, 2081, 2098, -1, + 3414, 2090, 2114, -1, 1253, 1252, 235, -1, + 1253, 235, 237, -1, 1253, 236, 2108, -1, + 1253, 237, 236, -1, 2065, 2064, 236, -1, + 2065, 237, 1216, -1, 2065, 236, 237, -1, + 3514, 3135, 1176, -1, 3514, 1176, 518, -1, + 3514, 516, 3513, -1, 3514, 518, 516, -1, + 2123, 2109, 541, -1, 2123, 541, 540, -1, + 2123, 540, 2124, -1, 3125, 3118, 2720, -1, + 2018, 1264, 2026, -1, 3186, 1266, 1271, -1, + 2130, 1271, 1266, -1, 2386, 2385, 1272, -1, + 1920, 555, 1921, -1, 1920, 2628, 555, -1, + 2687, 2003, 2620, -1, 554, 1922, 1921, -1, + 554, 3142, 1922, -1, 558, 1922, 3142, -1, + 558, 1923, 1922, -1, 558, 2783, 1923, -1, + 558, 3195, 2783, -1, 3440, 2129, 1085, -1, + 3440, 1085, 2783, -1, 1316, 572, 1303, -1, + 1316, 1315, 2803, -1, 571, 271, 570, -1, + 2186, 2221, 2188, -1, 560, 1282, 1281, -1, + 560, 2188, 2221, -1, 561, 238, 2183, -1, + 561, 240, 238, -1, 1277, 1278, 239, -1, + 1277, 239, 240, -1, 1277, 240, 561, -1, + 244, 242, 243, -1, 244, 2169, 241, -1, + 260, 241, 259, -1, 260, 267, 242, -1, + 260, 242, 244, -1, 260, 244, 241, -1, + 2168, 1278, 2167, -1, 2168, 243, 1278, -1, + 2168, 244, 243, -1, 2168, 2169, 244, -1, + 245, 1521, 246, -1, 245, 250, 1521, -1, + 245, 246, 247, -1, 245, 247, 248, -1, + 245, 248, 249, -1, 245, 249, 250, -1, + 1300, 739, 250, -1, 1300, 1302, 739, -1, + 2176, 1298, 1299, -1, 564, 249, 1306, -1, + 564, 1299, 1300, -1, 564, 250, 249, -1, + 564, 1300, 250, -1, 568, 251, 567, -1, + 568, 252, 251, -1, 568, 253, 252, -1, + 568, 254, 253, -1, 568, 569, 254, -1, + 566, 255, 897, -1, 566, 567, 255, -1, + 566, 897, 565, -1, 261, 262, 256, -1, + 261, 256, 266, -1, 257, 259, 258, -1, + 257, 267, 260, -1, 257, 260, 259, -1, + 257, 576, 267, -1, 257, 577, 576, -1, + 257, 258, 577, -1, 573, 2174, 1303, -1, + 573, 1303, 572, -1, 269, 261, 266, -1, + 269, 263, 262, -1, 269, 262, 261, -1, + 269, 264, 263, -1, 269, 270, 264, -1, + 265, 266, 267, -1, 265, 267, 268, -1, + 265, 269, 266, -1, 265, 268, 270, -1, + 265, 270, 269, -1, 1319, 577, 271, -1, + 1319, 271, 571, -1, 1319, 571, 1318, -1, + 1746, 1322, 1323, -1, 275, 276, 1322, -1, + 275, 1747, 274, -1, 275, 1322, 1746, -1, + 275, 1746, 1747, -1, 1324, 1322, 276, -1, + 1324, 276, 578, -1, 272, 274, 273, -1, + 272, 275, 274, -1, 272, 276, 275, -1, + 272, 273, 277, -1, 272, 277, 278, -1, + 272, 278, 378, -1, 272, 378, 276, -1, + 580, 581, 589, -1, 2515, 593, 581, -1, + 583, 1331, 580, -1, 583, 580, 589, -1, + 583, 589, 584, -1, 1753, 586, 1752, -1, + 1333, 1334, 589, -1, 1395, 2229, 592, -1, + 1395, 592, 593, -1, 1395, 1757, 2227, -1, + 596, 1757, 594, -1, 600, 623, 2299, -1, + 1355, 1350, 1351, -1, 1355, 1351, 295, -1, + 1355, 295, 1356, -1, 1357, 600, 1344, -1, + 2204, 2269, 324, -1, 2204, 324, 279, -1, + 2204, 279, 2205, -1, 607, 610, 603, -1, + 607, 603, 2211, -1, 602, 619, 601, -1, + 602, 601, 1735, -1, 606, 2205, 605, -1, + 690, 605, 691, -1, 690, 2812, 2811, -1, + 280, 616, 614, -1, 280, 614, 281, -1, + 280, 901, 616, -1, 280, 281, 901, -1, + 618, 601, 619, -1, 618, 617, 883, -1, + 613, 609, 614, -1, 624, 2236, 609, -1, + 1385, 621, 625, -1, 2237, 2236, 624, -1, + 1397, 1387, 1398, -1, 1397, 2814, 1387, -1, + 1397, 2813, 2814, -1, 1397, 1399, 2813, -1, + 627, 630, 282, -1, 627, 282, 1380, -1, + 627, 1382, 628, -1, 645, 2220, 631, -1, + 635, 647, 645, -1, 3314, 594, 1757, -1, + 3314, 283, 594, -1, 3314, 292, 283, -1, + 3314, 3500, 293, -1, 2219, 1282, 560, -1, + 2219, 560, 2221, -1, 2218, 638, 631, -1, + 2218, 631, 2220, -1, 284, 2235, 289, -1, + 284, 285, 2235, -1, 284, 289, 3500, -1, + 284, 3500, 285, -1, 1402, 286, 2233, -1, + 1402, 1401, 1380, -1, 1402, 1380, 286, -1, + 287, 289, 288, -1, 287, 288, 293, -1, + 287, 3500, 289, -1, 287, 293, 3500, -1, + 290, 291, 292, -1, 290, 293, 291, -1, + 290, 292, 3314, -1, 290, 3314, 293, -1, + 643, 1294, 294, -1, 643, 294, 295, -1, + 643, 295, 1351, -1, 643, 1351, 1352, -1, + 1290, 1408, 1407, -1, 1290, 296, 1408, -1, + 1290, 297, 296, -1, 1290, 1291, 297, -1, + 646, 637, 1284, -1, 646, 647, 637, -1, + 646, 1284, 1282, -1, 649, 298, 1410, -1, + 649, 650, 298, -1, 649, 652, 651, -1, + 649, 1410, 652, -1, 302, 299, 305, -1, + 302, 660, 309, -1, 302, 309, 300, -1, + 302, 300, 299, -1, 654, 301, 650, -1, + 654, 666, 301, -1, 658, 305, 664, -1, + 658, 302, 305, -1, 658, 660, 302, -1, + 658, 664, 659, -1, 663, 667, 303, -1, + 663, 659, 664, -1, 663, 367, 659, -1, + 663, 303, 367, -1, 665, 304, 666, -1, + 665, 664, 305, -1, 665, 305, 306, -1, + 665, 306, 304, -1, 704, 321, 703, -1, + 704, 705, 307, -1, 704, 1415, 321, -1, + 704, 307, 1415, -1, 308, 671, 1420, -1, + 308, 309, 660, -1, 308, 310, 309, -1, + 308, 1420, 310, -1, 308, 660, 656, -1, + 308, 656, 671, -1, 2254, 671, 1419, -1, + 1421, 676, 310, -1, 1421, 310, 1420, -1, + 311, 1438, 676, -1, 311, 1422, 312, -1, + 311, 1421, 1422, -1, 311, 676, 1421, -1, + 311, 314, 1438, -1, 311, 312, 314, -1, + 673, 1430, 1362, -1, 673, 315, 681, -1, + 673, 1362, 315, -1, 1432, 675, 1428, -1, + 1432, 1430, 673, -1, 1434, 1428, 698, -1, + 2282, 2284, 1447, -1, 678, 313, 721, -1, + 678, 720, 679, -1, 678, 721, 720, -1, + 2279, 1448, 313, -1, 2279, 313, 678, -1, + 1442, 1438, 314, -1, 1442, 314, 1443, -1, + 1450, 315, 1451, -1, 1450, 681, 315, -1, + 2804, 2288, 2805, -1, 1452, 315, 1362, -1, + 1452, 1362, 1361, -1, 1452, 1451, 315, -1, + 316, 726, 725, -1, 316, 317, 337, -1, + 316, 725, 319, -1, 316, 319, 317, -1, + 316, 318, 726, -1, 316, 337, 318, -1, + 320, 684, 683, -1, 320, 342, 341, -1, + 320, 319, 684, -1, 320, 341, 319, -1, + 682, 374, 342, -1, 682, 342, 320, -1, + 682, 320, 683, -1, 682, 2207, 374, -1, + 1454, 684, 725, -1, 886, 889, 2501, -1, + 886, 737, 889, -1, 323, 322, 321, -1, + 323, 321, 1413, -1, 323, 2429, 2412, -1, + 323, 1413, 2429, -1, 2411, 2406, 322, -1, + 2411, 323, 2412, -1, 2411, 322, 323, -1, + 689, 324, 1426, -1, 689, 688, 324, -1, + 1455, 1363, 687, -1, 1392, 2814, 2812, -1, + 1392, 1387, 2814, -1, 1392, 1393, 1387, -1, + 1390, 691, 688, -1, 693, 1343, 694, -1, + 693, 711, 1348, -1, 1458, 330, 714, -1, + 1458, 1459, 330, -1, 328, 695, 327, -1, + 328, 2272, 695, -1, 328, 598, 713, -1, + 328, 713, 2272, -1, 325, 326, 641, -1, + 325, 327, 326, -1, 325, 641, 642, -1, + 325, 328, 327, -1, 325, 642, 598, -1, + 325, 598, 328, -1, 1466, 700, 769, -1, + 702, 703, 329, -1, 702, 329, 700, -1, + 1468, 702, 700, -1, 1468, 1473, 702, -1, + 1472, 697, 708, -1, 1477, 2856, 2853, -1, + 1477, 1476, 2856, -1, 2841, 2272, 713, -1, + 1487, 330, 1459, -1, 1487, 331, 330, -1, + 1487, 2895, 331, -1, 1494, 333, 332, -1, + 1494, 1497, 333, -1, 1494, 332, 720, -1, + 336, 334, 335, -1, 336, 1500, 334, -1, + 336, 1501, 1500, -1, 336, 335, 1497, -1, + 1495, 1501, 336, -1, 1495, 336, 1497, -1, + 732, 337, 730, -1, 732, 723, 337, -1, + 732, 1518, 723, -1, 2283, 338, 2284, -1, + 2283, 727, 338, -1, 731, 339, 716, -1, + 731, 729, 339, -1, 736, 734, 340, -1, + 736, 340, 341, -1, 736, 342, 737, -1, + 736, 341, 342, -1, 1504, 1496, 343, -1, + 1504, 344, 1506, -1, 1504, 343, 344, -1, + 1504, 1505, 1496, -1, 1552, 1550, 2336, -1, + 345, 2351, 1525, -1, 345, 1552, 2351, -1, + 345, 1550, 1552, -1, 345, 346, 1550, -1, + 345, 738, 346, -1, 345, 1525, 738, -1, + 3223, 1295, 1296, -1, 3223, 1536, 1295, -1, + 1544, 1310, 1311, -1, 1542, 2886, 1543, -1, + 1542, 1545, 639, -1, 1542, 2887, 2886, -1, + 1542, 639, 2887, -1, 1541, 740, 1285, -1, + 1549, 1543, 2886, -1, 2341, 346, 1301, -1, + 2341, 1301, 2334, -1, 2341, 1550, 346, -1, + 2349, 747, 744, -1, 2349, 744, 1551, -1, + 1553, 1554, 745, -1, 354, 1560, 2860, -1, + 354, 745, 743, -1, 1559, 743, 747, -1, + 1559, 354, 743, -1, 1559, 1560, 354, -1, + 754, 1235, 347, -1, 754, 347, 1240, -1, + 751, 2792, 752, -1, 1238, 1240, 347, -1, + 1238, 347, 348, -1, 1238, 348, 993, -1, + 1238, 993, 1237, -1, 1234, 347, 1235, -1, + 1234, 348, 347, -1, 1234, 551, 348, -1, + 1578, 2370, 2740, -1, 2732, 2733, 990, -1, + 1585, 1584, 2734, -1, 1585, 2734, 2732, -1, + 988, 348, 551, -1, 988, 551, 1226, -1, + 988, 993, 348, -1, 1228, 1229, 349, -1, + 1228, 349, 350, -1, 1228, 351, 1230, -1, + 1228, 350, 351, -1, 2377, 352, 353, -1, + 2377, 1587, 352, -1, 2379, 353, 1588, -1, + 2379, 2377, 353, -1, 1599, 2488, 787, -1, + 1599, 785, 1601, -1, 1599, 787, 785, -1, + 784, 1601, 785, -1, 359, 2865, 355, -1, + 359, 355, 763, -1, 359, 358, 2865, -1, + 359, 763, 764, -1, 1538, 761, 1536, -1, + 1538, 758, 761, -1, 2927, 2931, 775, -1, + 746, 2859, 768, -1, 746, 2860, 2859, -1, + 746, 354, 2860, -1, 746, 745, 354, -1, + 2902, 2870, 2327, -1, 2905, 355, 2871, -1, + 2905, 2871, 2870, -1, 2905, 2870, 2902, -1, + 2907, 763, 355, -1, 2907, 355, 2905, -1, + 1638, 357, 356, -1, 1638, 1639, 357, -1, + 1638, 356, 1604, -1, 1606, 1605, 358, -1, + 1606, 358, 359, -1, 1606, 359, 764, -1, + 1615, 774, 773, -1, 1616, 766, 1617, -1, + 1618, 772, 1611, -1, 1618, 1617, 772, -1, + 1633, 777, 1634, -1, 1628, 1625, 1629, -1, + 1642, 777, 776, -1, 1642, 776, 1417, -1, + 1642, 1643, 777, -1, 669, 360, 1646, -1, + 669, 1631, 360, -1, 669, 776, 1631, -1, + 669, 1417, 776, -1, 2426, 1646, 362, -1, + 779, 362, 361, -1, 779, 361, 778, -1, + 779, 2426, 362, -1, 779, 2948, 2426, -1, + 805, 2483, 2484, -1, 805, 812, 2483, -1, + 833, 1647, 835, -1, 833, 1416, 1648, -1, + 1844, 1845, 781, -1, 782, 363, 783, -1, + 782, 364, 363, -1, 782, 365, 364, -1, + 782, 982, 365, -1, 2491, 787, 2488, -1, + 1683, 829, 476, -1, 1927, 478, 2651, -1, + 1927, 1660, 478, -1, 1927, 1926, 1660, -1, + 366, 477, 1661, -1, 366, 476, 477, -1, + 366, 1684, 1683, -1, 366, 1683, 476, -1, + 1651, 785, 787, -1, 788, 1684, 366, -1, + 788, 366, 1661, -1, 2247, 2822, 670, -1, + 1665, 657, 661, -1, 1664, 1419, 657, -1, + 1664, 657, 1665, -1, 799, 793, 803, -1, + 799, 800, 797, -1, 811, 3464, 813, -1, + 2469, 2471, 2952, -1, 2951, 2433, 820, -1, + 809, 820, 808, -1, 809, 2952, 2951, -1, + 809, 2951, 820, -1, 809, 2469, 2952, -1, + 818, 2459, 808, -1, 818, 2456, 2459, -1, + 818, 808, 821, -1, 369, 367, 368, -1, + 369, 1666, 1665, -1, 369, 661, 367, -1, + 369, 1665, 661, -1, 828, 368, 822, -1, + 828, 369, 368, -1, 828, 1666, 369, -1, + 1722, 2482, 814, -1, 979, 830, 370, -1, + 979, 370, 978, -1, 979, 981, 830, -1, + 2477, 370, 830, -1, 834, 2477, 2475, -1, + 834, 835, 370, -1, 834, 370, 2477, -1, + 836, 1702, 839, -1, 371, 843, 844, -1, + 371, 781, 840, -1, 371, 840, 843, -1, + 371, 1844, 781, -1, 371, 844, 1687, -1, + 371, 1687, 1844, -1, 1696, 1697, 847, -1, + 1696, 847, 848, -1, 1696, 848, 839, -1, + 842, 846, 847, -1, 842, 847, 1697, -1, + 1698, 1699, 1690, -1, 1698, 1690, 1689, -1, + 1098, 853, 1101, -1, 1098, 1099, 860, -1, + 2495, 1062, 1134, -1, 2495, 2496, 1062, -1, + 852, 860, 849, -1, 852, 1098, 860, -1, + 852, 853, 1098, -1, 857, 855, 861, -1, + 857, 861, 862, -1, 873, 2241, 2242, -1, + 873, 2242, 862, -1, 1724, 1731, 863, -1, + 1729, 849, 855, -1, 1729, 855, 863, -1, + 1729, 863, 1731, -1, 869, 479, 653, -1, + 869, 653, 2240, -1, 869, 2240, 2241, -1, + 869, 870, 479, -1, 2958, 874, 877, -1, + 879, 801, 651, -1, 879, 880, 801, -1, + 879, 651, 876, -1, 879, 876, 2438, -1, + 882, 618, 883, -1, 882, 601, 618, -1, + 882, 884, 1366, -1, 1732, 1366, 372, -1, + 1732, 372, 373, -1, 1732, 373, 1733, -1, + 3285, 3296, 2962, -1, 3480, 3479, 887, -1, + 1369, 2212, 2500, -1, 1369, 1364, 1370, -1, + 1365, 374, 2207, -1, 1365, 889, 374, -1, + 893, 891, 897, -1, 896, 893, 897, -1, + 896, 1743, 893, -1, 894, 1323, 1751, -1, + 898, 375, 1745, -1, 898, 376, 375, -1, + 898, 899, 376, -1, 898, 1745, 896, -1, + 905, 903, 901, -1, 905, 954, 904, -1, + 1777, 1773, 588, -1, 1777, 588, 906, -1, + 579, 1780, 908, -1, 579, 578, 1766, -1, + 1764, 378, 377, -1, 1764, 1766, 378, -1, + 1764, 377, 1765, -1, 1769, 1781, 1780, -1, + 1769, 1780, 579, -1, 1769, 579, 1766, -1, + 1783, 908, 1780, -1, 2539, 1793, 2525, -1, + 1785, 379, 2556, -1, 1785, 909, 379, -1, + 3013, 1785, 2556, -1, 918, 1782, 1781, -1, + 918, 911, 912, -1, 3000, 381, 1792, -1, + 3000, 915, 381, -1, 3000, 3001, 915, -1, + 380, 382, 381, -1, 380, 914, 382, -1, + 380, 381, 915, -1, 380, 915, 914, -1, + 920, 915, 3001, -1, 920, 3001, 3003, -1, + 923, 1805, 1796, -1, 2554, 921, 2546, -1, + 2554, 2557, 922, -1, 2554, 922, 921, -1, + 1802, 437, 928, -1, 383, 928, 437, -1, + 383, 1021, 927, -1, 383, 437, 1024, -1, + 383, 1024, 1021, -1, 926, 383, 927, -1, + 926, 928, 383, -1, 2980, 926, 2979, -1, + 2980, 928, 926, -1, 929, 1867, 1866, -1, + 929, 2558, 932, -1, 929, 2557, 2558, -1, + 929, 1866, 2557, -1, 1809, 933, 1810, -1, + 939, 944, 951, -1, 939, 1820, 938, -1, + 937, 938, 1011, -1, 937, 1011, 449, -1, + 937, 384, 936, -1, 937, 449, 384, -1, + 1821, 938, 1820, -1, 1821, 1011, 938, -1, + 941, 389, 385, -1, 941, 385, 386, -1, + 941, 386, 950, -1, 941, 942, 389, -1, + 946, 1820, 939, -1, 946, 939, 951, -1, + 1814, 2563, 1861, -1, 1814, 428, 1014, -1, + 1814, 1861, 428, -1, 1819, 947, 952, -1, + 1819, 946, 947, -1, 1819, 1820, 946, -1, + 955, 388, 904, -1, 955, 904, 954, -1, + 953, 952, 387, -1, 953, 955, 956, -1, + 953, 387, 388, -1, 953, 388, 955, -1, + 1823, 1817, 956, -1, 3035, 3034, 957, -1, + 3035, 957, 960, -1, 959, 1830, 390, -1, + 959, 390, 964, -1, 969, 389, 942, -1, + 969, 970, 389, -1, 969, 942, 390, -1, + 969, 390, 1830, -1, 3040, 391, 392, -1, + 3040, 1832, 391, -1, 3040, 392, 3041, -1, + 3042, 3041, 393, -1, 3042, 393, 396, -1, + 3042, 396, 965, -1, 3042, 965, 3043, -1, + 2573, 411, 2574, -1, 394, 957, 3034, -1, + 394, 1827, 957, -1, 394, 395, 1827, -1, + 394, 3034, 965, -1, 394, 396, 395, -1, + 394, 965, 396, -1, 1829, 1828, 397, -1, + 1829, 397, 398, -1, 971, 398, 399, -1, + 971, 399, 400, -1, 971, 400, 970, -1, + 971, 1829, 398, -1, 2581, 526, 2582, -1, + 2576, 2575, 2566, -1, 2576, 2566, 1044, -1, + 2576, 1044, 972, -1, 2576, 972, 2577, -1, + 1839, 401, 966, -1, 975, 403, 401, -1, + 975, 401, 1839, -1, 974, 464, 977, -1, + 974, 973, 463, -1, 402, 977, 464, -1, + 402, 404, 403, -1, 402, 405, 404, -1, + 402, 975, 977, -1, 402, 403, 975, -1, + 402, 406, 405, -1, 402, 464, 406, -1, + 412, 410, 407, -1, 412, 408, 409, -1, + 412, 407, 408, -1, 412, 409, 411, -1, + 968, 967, 410, -1, 968, 411, 2573, -1, + 968, 412, 411, -1, 968, 410, 412, -1, + 528, 413, 414, -1, 528, 415, 413, -1, + 528, 529, 415, -1, 528, 414, 527, -1, + 1205, 1206, 1201, -1, 416, 1208, 1201, -1, + 416, 417, 1208, -1, 416, 1201, 418, -1, + 416, 420, 419, -1, 416, 418, 420, -1, + 416, 419, 421, -1, 416, 421, 417, -1, + 1843, 1844, 1687, -1, 980, 422, 423, -1, + 980, 3334, 422, -1, 980, 423, 981, -1, + 1848, 984, 1635, -1, 2400, 986, 424, -1, + 2400, 424, 425, -1, 2400, 425, 426, -1, + 2400, 2920, 986, -1, 2400, 426, 2401, -1, + 2397, 986, 2920, -1, 994, 1004, 427, -1, + 994, 427, 2591, -1, 994, 2591, 2590, -1, + 994, 2590, 995, -1, 1002, 1581, 1582, -1, + 1002, 1582, 1000, -1, 999, 987, 998, -1, + 1008, 998, 1009, -1, 1008, 997, 998, -1, + 1013, 428, 429, -1, 1013, 429, 448, -1, + 1013, 1014, 428, -1, 1025, 1015, 1022, -1, + 430, 1015, 431, -1, 430, 433, 432, -1, + 430, 432, 1022, -1, 430, 1022, 1015, -1, + 430, 431, 442, -1, 430, 442, 433, -1, + 1017, 434, 1018, -1, 1017, 435, 434, -1, + 1017, 436, 435, -1, 1017, 1026, 436, -1, + 1855, 1856, 1026, -1, 1855, 1026, 1017, -1, + 1860, 1021, 1024, -1, 1030, 1031, 437, -1, + 1030, 1803, 1029, -1, 1030, 437, 1802, -1, + 1030, 1802, 1803, -1, 925, 1029, 1803, -1, + 1865, 925, 1869, -1, 1865, 1029, 925, -1, + 1865, 1028, 1029, -1, 438, 443, 439, -1, + 438, 444, 443, -1, 438, 439, 440, -1, + 438, 440, 444, -1, 1035, 441, 443, -1, + 1035, 1037, 442, -1, 1035, 442, 441, -1, + 1034, 443, 444, -1, 1034, 444, 445, -1, + 1034, 1035, 443, -1, 1034, 445, 446, -1, + 1034, 446, 1039, -1, 1012, 448, 447, -1, + 1012, 447, 449, -1, 1012, 449, 1011, -1, + 1012, 1013, 448, -1, 961, 962, 451, -1, + 961, 451, 3036, -1, 961, 3036, 3035, -1, + 961, 3035, 960, -1, 2569, 3036, 451, -1, + 2569, 451, 1041, -1, 450, 451, 962, -1, + 450, 452, 453, -1, 450, 453, 1041, -1, + 450, 1041, 451, -1, 450, 454, 452, -1, + 450, 962, 454, -1, 462, 463, 455, -1, + 462, 456, 459, -1, 462, 455, 457, -1, + 462, 457, 456, -1, 458, 459, 460, -1, + 458, 460, 461, -1, 458, 462, 459, -1, + 458, 463, 462, -1, 458, 461, 464, -1, + 458, 464, 974, -1, 458, 974, 463, -1, + 1055, 1872, 1046, -1, 1055, 1049, 1074, -1, + 1058, 2612, 2616, -1, 1051, 1052, 2596, -1, + 1051, 2596, 1876, -1, 1051, 1876, 465, -1, + 1051, 465, 1054, -1, 2595, 887, 3479, -1, + 2595, 1052, 887, -1, 2595, 2596, 1052, -1, + 1061, 1062, 466, -1, 1061, 466, 1057, -1, + 1060, 1057, 1056, -1, 1060, 1056, 1991, -1, + 1060, 1991, 1992, -1, 1060, 1061, 1057, -1, + 1893, 1892, 470, -1, 1893, 470, 471, -1, + 1893, 471, 1888, -1, 1885, 1071, 1886, -1, + 3068, 467, 3067, -1, 3068, 1881, 467, -1, + 1073, 468, 1070, -1, 1073, 1049, 468, -1, + 1073, 1074, 1049, -1, 1068, 1065, 1898, -1, + 1068, 1067, 1065, -1, 1896, 1888, 1886, -1, + 1896, 1893, 1888, -1, 469, 471, 470, -1, + 469, 472, 471, -1, 469, 470, 473, -1, + 469, 473, 472, -1, 1127, 474, 1963, -1, + 1127, 1126, 474, -1, 1906, 2628, 3084, -1, + 1906, 555, 2628, -1, 1906, 1081, 555, -1, + 3081, 3082, 1901, -1, 1908, 1919, 1083, -1, + 1084, 1914, 1083, -1, 1084, 1085, 2129, -1, + 2645, 1272, 1649, -1, 2645, 1649, 1659, -1, + 2435, 2436, 2634, -1, 2641, 1926, 1927, -1, + 2652, 1086, 1672, -1, 475, 1676, 1088, -1, + 475, 476, 1675, -1, 475, 1675, 1676, -1, + 475, 477, 476, -1, 475, 478, 477, -1, + 475, 1088, 478, -1, 1096, 1093, 877, -1, + 1096, 870, 1094, -1, 1096, 479, 870, -1, + 1096, 877, 479, -1, 1092, 1095, 1110, -1, + 1092, 878, 1093, -1, 3101, 1095, 3100, -1, + 1100, 3099, 871, -1, 1100, 871, 872, -1, + 1100, 872, 1099, -1, 3098, 3099, 1100, -1, + 2661, 3276, 2663, -1, 481, 1940, 480, -1, + 481, 1092, 1110, -1, 481, 480, 878, -1, + 481, 878, 1092, -1, 1902, 1113, 1905, -1, + 1938, 3082, 1911, -1, 1938, 1901, 3082, -1, + 1107, 1114, 1930, -1, 1136, 1934, 1137, -1, + 1136, 1139, 1106, -1, 1941, 1107, 1106, -1, + 1109, 481, 1110, -1, 1109, 1940, 481, -1, + 1112, 1110, 1095, -1, 1112, 1095, 3101, -1, + 485, 1116, 1115, -1, 485, 482, 1116, -1, + 485, 484, 482, -1, 1947, 483, 1118, -1, + 1947, 1951, 483, -1, 1952, 1953, 1121, -1, + 1952, 1122, 1951, -1, 1970, 1971, 484, -1, + 1970, 1115, 491, -1, 1970, 484, 485, -1, + 1970, 485, 1115, -1, 1946, 1945, 486, -1, + 1946, 486, 1948, -1, 1123, 2693, 3109, -1, + 1123, 1948, 2693, -1, 3111, 3107, 1954, -1, + 2665, 493, 1122, -1, 2665, 2668, 493, -1, + 1957, 1120, 556, -1, 1957, 556, 1273, -1, + 1957, 2666, 1120, -1, 489, 1125, 1883, -1, + 489, 1890, 488, -1, 489, 1889, 1890, -1, + 489, 1883, 1889, -1, 1124, 488, 487, -1, + 1124, 489, 488, -1, 1124, 1125, 489, -1, + 1124, 487, 490, -1, 1124, 490, 1126, -1, + 1960, 1153, 1125, -1, 2669, 2671, 2668, -1, + 1973, 491, 2680, -1, 1973, 1970, 491, -1, + 492, 494, 493, -1, 492, 2680, 494, -1, + 492, 493, 2668, -1, 492, 2681, 2680, -1, + 492, 2668, 2671, -1, 492, 2671, 2681, -1, + 854, 851, 1130, -1, 854, 495, 853, -1, + 1132, 1130, 851, -1, 1980, 1978, 495, -1, + 1980, 854, 1130, -1, 1980, 495, 854, -1, + 1146, 1130, 1132, -1, 1138, 1985, 1984, -1, + 1138, 1979, 1985, -1, 1138, 1137, 1979, -1, + 1138, 1984, 1142, -1, 1987, 1983, 496, -1, + 1987, 496, 1143, -1, 2619, 1131, 2618, -1, + 2619, 497, 1131, -1, 2619, 3067, 498, -1, + 2619, 498, 497, -1, 1990, 2618, 1131, -1, + 1955, 1128, 2670, -1, 1150, 500, 1154, -1, + 1150, 1151, 499, -1, 1150, 499, 500, -1, + 1155, 1150, 1154, -1, 1880, 1883, 1153, -1, + 1880, 1153, 1154, -1, 1880, 1154, 500, -1, + 1880, 500, 1881, -1, 2622, 1955, 3076, -1, + 2622, 1128, 1955, -1, 2622, 502, 1128, -1, + 2623, 1104, 502, -1, 2623, 502, 2622, -1, + 2623, 2624, 1105, -1, 2623, 1105, 1104, -1, + 501, 1104, 1144, -1, 501, 1144, 1145, -1, + 501, 1145, 505, -1, 501, 502, 1104, -1, + 501, 505, 1129, -1, 501, 1129, 502, -1, + 504, 1143, 503, -1, 504, 1145, 1143, -1, + 504, 503, 1149, -1, 504, 505, 1145, -1, + 1995, 2685, 1966, -1, 1995, 1966, 1159, -1, + 1995, 1159, 1158, -1, 1962, 1963, 1157, -1, + 2678, 1149, 2676, -1, 2678, 505, 504, -1, + 2678, 504, 1149, -1, 2678, 2674, 505, -1, + 3143, 3142, 554, -1, 3143, 554, 1165, -1, + 2002, 1168, 3071, -1, 1167, 557, 1168, -1, + 1167, 1165, 557, -1, 1169, 1209, 2009, -1, + 1169, 506, 1209, -1, 1169, 2717, 506, -1, + 2016, 507, 1170, -1, 2016, 2008, 507, -1, + 2015, 2008, 2016, -1, 508, 509, 1841, -1, + 508, 510, 509, -1, 508, 1841, 2584, -1, + 508, 2584, 510, -1, 1184, 2012, 1170, -1, + 1184, 1170, 1185, -1, 2020, 1214, 1178, -1, + 2020, 1178, 2024, -1, 2020, 2021, 1214, -1, + 3114, 521, 1171, -1, 3114, 1174, 521, -1, + 3114, 3392, 1174, -1, 511, 512, 514, -1, + 511, 2006, 512, -1, 511, 514, 2010, -1, + 511, 2010, 2006, -1, 2005, 2009, 512, -1, + 2005, 512, 2006, -1, 2028, 513, 2029, -1, + 2028, 2038, 2010, -1, 2028, 2010, 514, -1, + 2028, 514, 513, -1, 515, 517, 516, -1, + 515, 518, 517, -1, 515, 516, 518, -1, + 2040, 2041, 518, -1, 2040, 518, 1176, -1, + 2726, 2044, 3129, -1, 3164, 3127, 3163, -1, + 2727, 3163, 3127, -1, 519, 1175, 520, -1, + 519, 520, 521, -1, 519, 1174, 1175, -1, + 519, 521, 1174, -1, 2711, 2703, 522, -1, + 2711, 522, 2708, -1, 1183, 2024, 1178, -1, + 1187, 1189, 1181, -1, 1187, 1181, 1177, -1, + 1187, 1177, 523, -1, 1187, 523, 1188, -1, + 1195, 1188, 1196, -1, 2014, 524, 2703, -1, + 2014, 1190, 524, -1, 2014, 2013, 1189, -1, + 2014, 1189, 1190, -1, 525, 1202, 529, -1, + 525, 527, 526, -1, 525, 528, 527, -1, + 525, 529, 528, -1, 525, 2581, 1202, -1, + 525, 526, 2581, -1, 2055, 529, 1202, -1, + 2055, 530, 529, -1, 2055, 2058, 530, -1, + 1207, 2714, 531, -1, 1207, 531, 1208, -1, + 2707, 532, 2058, -1, 2707, 2708, 532, -1, + 533, 534, 535, -1, 533, 535, 536, -1, + 533, 537, 534, -1, 533, 536, 538, -1, + 533, 539, 537, -1, 533, 538, 539, -1, + 1211, 2021, 2023, -1, 1211, 2023, 540, -1, + 1211, 540, 541, -1, 1211, 541, 1212, -1, + 2063, 2068, 1213, -1, 2063, 1212, 2064, -1, + 2060, 2059, 542, -1, 2060, 542, 543, -1, + 2060, 543, 544, -1, 2060, 544, 2061, -1, + 545, 1197, 546, -1, 545, 547, 548, -1, + 545, 549, 547, -1, 545, 546, 549, -1, + 545, 548, 1198, -1, 545, 1198, 1197, -1, + 1217, 1250, 2071, -1, 1217, 2071, 1564, -1, + 1220, 1221, 550, -1, 1225, 1226, 1218, -1, + 1225, 1218, 1220, -1, 1225, 550, 1229, -1, + 1225, 1220, 550, -1, 1233, 1218, 551, -1, + 1233, 551, 1234, -1, 2739, 1578, 2740, -1, + 1239, 2155, 751, -1, 3433, 1164, 2696, -1, + 3433, 3434, 2084, -1, 3433, 2084, 1164, -1, + 1568, 748, 2159, -1, 1259, 2750, 2086, -1, + 2089, 2090, 2097, -1, 2107, 1244, 2114, -1, + 2095, 1242, 1241, -1, 2095, 1241, 2097, -1, + 2082, 2081, 1248, -1, 2082, 1566, 2083, -1, + 1246, 1248, 2081, -1, 1246, 2081, 2100, -1, + 2125, 2109, 2123, -1, 2113, 2114, 1252, -1, + 552, 1261, 1260, -1, 552, 1244, 1261, -1, + 552, 1260, 2121, -1, 552, 2121, 1244, -1, + 1256, 2750, 1259, -1, 1256, 1259, 1261, -1, + 1258, 2086, 2697, -1, 2047, 2728, 2727, -1, + 2047, 2046, 2041, -1, 2764, 2122, 1265, -1, + 2142, 2773, 2772, -1, 2142, 2772, 2386, -1, + 2142, 2386, 1272, -1, 553, 557, 1165, -1, + 553, 554, 1921, -1, 553, 1165, 554, -1, + 553, 1921, 555, -1, 553, 555, 1081, -1, + 553, 1081, 557, -1, 2688, 556, 3382, -1, + 2688, 1273, 556, -1, 1082, 3071, 1168, -1, + 1082, 1168, 557, -1, 1082, 557, 1081, -1, + 1082, 3508, 3071, -1, 3145, 558, 3142, -1, + 3145, 3195, 558, -1, 2157, 1275, 2133, -1, + 2157, 2133, 3182, -1, 3201, 751, 2155, -1, + 3201, 2792, 751, -1, 2787, 3190, 2148, -1, + 2787, 2148, 2158, -1, 2791, 2159, 748, -1, + 559, 560, 1281, -1, 559, 1281, 561, -1, + 559, 2188, 560, -1, 559, 561, 2183, -1, + 559, 2183, 2187, -1, 559, 2187, 2188, -1, + 562, 561, 1281, -1, 562, 1277, 561, -1, + 1283, 1277, 562, -1, 1283, 1284, 1279, -1, + 1283, 562, 1281, -1, 1286, 1541, 1285, -1, + 1286, 1545, 1541, -1, 1289, 563, 1291, -1, + 1289, 1293, 563, -1, 2165, 1293, 1289, -1, + 2165, 1289, 1288, -1, 2881, 1531, 1535, -1, + 2881, 2879, 1531, -1, 1546, 2334, 1301, -1, + 2175, 564, 1306, -1, 2175, 2176, 1299, -1, + 2175, 1299, 564, -1, 2172, 1304, 567, -1, + 2172, 1316, 1303, -1, 2172, 1320, 1316, -1, + 2172, 565, 1320, -1, 2172, 566, 565, -1, + 2172, 567, 566, -1, 1305, 567, 1304, -1, + 1305, 568, 567, -1, 1305, 1306, 569, -1, + 1305, 569, 568, -1, 1308, 570, 1309, -1, + 1308, 571, 570, -1, 1308, 1318, 571, -1, + 1308, 1317, 1318, -1, 2801, 1310, 2802, -1, + 2800, 2803, 1315, -1, 2800, 1317, 2801, -1, + 1312, 1316, 2803, -1, 1312, 1313, 573, -1, + 1312, 572, 1316, -1, 1312, 573, 572, -1, + 574, 573, 1313, -1, 574, 2176, 2174, -1, + 574, 2174, 573, -1, 574, 1298, 2176, -1, + 1547, 1313, 2177, -1, 1547, 1546, 1298, -1, + 1547, 1298, 574, -1, 1547, 574, 1313, -1, + 575, 1320, 576, -1, 575, 1319, 1320, -1, + 575, 576, 577, -1, 575, 577, 1319, -1, + 1325, 906, 1326, -1, 907, 1324, 578, -1, + 907, 906, 1325, -1, 907, 1325, 1324, -1, + 907, 578, 579, -1, 907, 579, 908, -1, + 2991, 2515, 581, -1, 2514, 1761, 593, -1, + 2514, 593, 2515, -1, 1330, 580, 1331, -1, + 1330, 581, 580, -1, 1330, 2990, 2991, -1, + 1330, 2991, 581, -1, 1332, 1329, 1774, -1, + 1332, 1774, 1775, -1, 1328, 1752, 586, -1, + 1328, 586, 1329, -1, 587, 1329, 586, -1, + 587, 1774, 1329, -1, 587, 1773, 1774, -1, + 587, 588, 1773, -1, 582, 1331, 583, -1, + 582, 1328, 1331, -1, 582, 1752, 1328, -1, + 582, 1750, 1752, -1, 582, 584, 1750, -1, + 582, 583, 584, -1, 585, 1753, 1326, -1, + 585, 586, 1753, -1, 585, 587, 586, -1, + 585, 1326, 588, -1, 585, 588, 587, -1, + 590, 589, 2191, -1, 590, 1333, 589, -1, + 2190, 1333, 590, -1, 2190, 590, 2191, -1, + 1335, 2191, 593, -1, 1335, 593, 1336, -1, + 591, 593, 592, -1, 591, 1336, 593, -1, + 591, 592, 1337, -1, 591, 1337, 1336, -1, + 1759, 593, 1761, -1, 1759, 1395, 593, -1, + 597, 638, 2225, -1, 597, 596, 594, -1, + 597, 594, 595, -1, 597, 595, 638, -1, + 1340, 1757, 596, -1, 1340, 597, 2225, -1, + 1340, 596, 597, -1, 2529, 2530, 2989, -1, + 2301, 600, 2299, -1, 2301, 1344, 600, -1, + 1349, 1350, 1345, -1, 1349, 693, 1348, -1, + 1349, 1345, 1343, -1, 1349, 1343, 693, -1, + 712, 713, 598, -1, 712, 1348, 711, -1, + 1347, 712, 598, -1, 1347, 1348, 712, -1, + 1347, 598, 642, -1, 1347, 642, 1352, -1, + 599, 1358, 636, -1, 599, 1357, 1358, -1, + 599, 636, 622, -1, 599, 600, 1357, -1, + 599, 622, 623, -1, 599, 623, 600, -1, + 1354, 1350, 1355, -1, 1354, 1345, 1350, -1, + 1354, 1344, 1345, -1, 1354, 1357, 1344, -1, + 2206, 606, 1370, -1, 2206, 2205, 606, -1, + 2206, 1370, 1364, -1, 1367, 1735, 601, -1, + 1367, 601, 882, -1, 1367, 882, 1366, -1, + 1367, 2499, 1735, -1, 1734, 3203, 2211, -1, + 1734, 602, 1735, -1, 1734, 2211, 603, -1, + 1734, 603, 602, -1, 611, 619, 602, -1, + 611, 613, 619, -1, 611, 603, 610, -1, + 611, 602, 603, -1, 2210, 1377, 1378, -1, + 2210, 1378, 607, -1, 2210, 607, 2211, -1, + 2213, 1379, 1377, -1, 1371, 1376, 1379, -1, + 1371, 1370, 606, -1, 604, 690, 2811, -1, + 604, 2811, 1376, -1, 604, 605, 690, -1, + 604, 1376, 1371, -1, 604, 606, 605, -1, + 604, 1371, 606, -1, 1372, 610, 607, -1, + 1372, 1373, 610, -1, 1372, 607, 1378, -1, + 1372, 1378, 2214, -1, 2810, 1376, 2811, -1, + 608, 609, 613, -1, 608, 624, 609, -1, + 608, 1373, 624, -1, 608, 610, 1373, -1, + 608, 611, 610, -1, 608, 613, 611, -1, + 612, 613, 614, -1, 612, 616, 615, -1, + 612, 614, 616, -1, 612, 615, 617, -1, + 612, 617, 618, -1, 612, 618, 619, -1, + 612, 619, 613, -1, 1384, 625, 1382, -1, + 1384, 1385, 625, -1, 1386, 1394, 1388, -1, + 1386, 1393, 1394, -1, 620, 621, 1385, -1, + 620, 622, 621, -1, 620, 623, 622, -1, + 620, 1388, 623, -1, 620, 1386, 1388, -1, + 620, 1385, 1386, -1, 1404, 2216, 1399, -1, + 1374, 2237, 624, -1, 1374, 624, 1373, -1, + 1374, 2216, 1404, -1, 1374, 1404, 2237, -1, + 1381, 1382, 627, -1, 1381, 627, 1380, -1, + 629, 634, 635, -1, 629, 625, 634, -1, + 629, 628, 1382, -1, 629, 1382, 625, -1, + 626, 627, 628, -1, 626, 628, 629, -1, + 626, 629, 635, -1, 626, 630, 627, -1, + 626, 635, 645, -1, 626, 631, 630, -1, + 626, 645, 631, -1, 632, 634, 633, -1, + 632, 635, 634, -1, 632, 636, 1359, -1, + 632, 633, 636, -1, 632, 647, 635, -1, + 632, 1359, 637, -1, 632, 637, 647, -1, + 2222, 2221, 2186, -1, 2222, 1337, 2230, -1, + 2222, 2186, 1337, -1, 2224, 2225, 638, -1, + 2224, 638, 2218, -1, 1403, 1404, 1399, -1, + 2347, 2348, 639, -1, 1406, 1288, 1407, -1, + 1406, 2347, 639, -1, 1406, 639, 1545, -1, + 1406, 1545, 1286, -1, 1406, 1286, 1288, -1, + 2346, 2890, 2887, -1, 2346, 2887, 639, -1, + 2346, 639, 2348, -1, 640, 642, 641, -1, + 640, 1352, 642, -1, 640, 643, 1352, -1, + 640, 641, 1294, -1, 640, 1294, 643, -1, + 644, 2220, 645, -1, 644, 646, 1282, -1, + 644, 645, 647, -1, 644, 647, 646, -1, + 644, 1282, 2219, -1, 644, 2219, 2220, -1, + 648, 801, 802, -1, 648, 650, 649, -1, + 648, 651, 801, -1, 648, 649, 651, -1, + 648, 802, 654, -1, 648, 654, 650, -1, + 1409, 652, 1410, -1, 1409, 875, 652, -1, + 1409, 653, 875, -1, 1409, 2240, 653, -1, + 668, 666, 654, -1, 668, 803, 667, -1, + 668, 802, 803, -1, 668, 654, 802, -1, + 655, 657, 656, -1, 655, 658, 659, -1, + 655, 656, 660, -1, 655, 660, 658, -1, + 655, 659, 661, -1, 655, 661, 657, -1, + 662, 663, 664, -1, 662, 665, 666, -1, + 662, 664, 665, -1, 662, 667, 663, -1, + 662, 668, 667, -1, 662, 666, 668, -1, + 2428, 2429, 1413, -1, 2825, 1414, 2826, -1, + 2936, 1416, 1418, -1, 2934, 669, 1646, -1, + 2934, 1417, 669, -1, 2940, 2941, 2258, -1, + 2821, 670, 2822, -1, 2251, 670, 2252, -1, + 2251, 2247, 670, -1, 2251, 1663, 2247, -1, + 2257, 2252, 670, -1, 2257, 670, 2821, -1, + 2257, 2821, 2258, -1, 2828, 1420, 671, -1, + 2828, 671, 2254, -1, 672, 673, 681, -1, + 672, 1445, 674, -1, 672, 681, 1445, -1, + 672, 674, 675, -1, 672, 675, 1432, -1, + 672, 1432, 673, -1, 1433, 1428, 1434, -1, + 1433, 2843, 1431, -1, 2846, 1431, 2843, -1, + 2280, 1448, 2279, -1, 2277, 676, 1438, -1, + 2277, 2281, 677, -1, 2277, 677, 676, -1, + 2278, 2279, 678, -1, 2278, 678, 679, -1, + 2278, 680, 2281, -1, 2278, 679, 680, -1, + 1440, 1445, 681, -1, 1440, 681, 1450, -1, + 1449, 1448, 2280, -1, 1449, 2280, 1441, -1, + 1449, 1441, 1440, -1, 1449, 1440, 1450, -1, + 2287, 1452, 1361, -1, 2835, 2207, 682, -1, + 2835, 683, 2836, -1, 2835, 682, 683, -1, + 1453, 2836, 683, -1, 1453, 2804, 2836, -1, + 1453, 683, 684, -1, 1453, 684, 1454, -1, + 1737, 2507, 735, -1, 685, 1363, 1455, -1, + 685, 689, 1426, -1, 685, 2292, 689, -1, + 685, 1455, 2292, -1, 685, 1426, 1425, -1, + 685, 1425, 1363, -1, 1456, 687, 686, -1, + 1456, 1455, 687, -1, 1456, 686, 1342, -1, + 1456, 1342, 2297, -1, 2293, 1390, 688, -1, + 2293, 688, 689, -1, 2293, 689, 2292, -1, + 2293, 2294, 1390, -1, 1391, 690, 691, -1, + 1391, 691, 1390, -1, 1391, 2812, 690, -1, + 1391, 1392, 2812, -1, 692, 693, 694, -1, + 692, 2849, 2839, -1, 692, 2839, 711, -1, + 692, 711, 693, -1, 692, 694, 2850, -1, + 692, 2850, 2849, -1, 2273, 695, 2272, -1, + 2273, 714, 696, -1, 2273, 696, 695, -1, + 1460, 2856, 1476, -1, 1460, 2857, 2856, -1, + 1460, 1476, 1457, -1, 2855, 2857, 2303, -1, + 699, 2308, 2309, -1, 699, 698, 697, -1, + 699, 1472, 2308, -1, 699, 697, 1472, -1, + 1463, 1434, 698, -1, 1463, 698, 699, -1, + 1463, 699, 2309, -1, 1463, 3217, 1434, -1, + 1465, 1477, 2853, -1, 1465, 1478, 1477, -1, + 2307, 1473, 1468, -1, 1469, 700, 1466, -1, + 1469, 1468, 700, -1, 1469, 1465, 2853, -1, + 1469, 1466, 1465, -1, 701, 702, 1473, -1, + 701, 1473, 1474, -1, 701, 703, 702, -1, + 701, 1474, 705, -1, 701, 704, 703, -1, + 701, 705, 704, -1, 710, 705, 1474, -1, + 710, 709, 706, -1, 710, 707, 705, -1, + 710, 706, 707, -1, 1471, 708, 709, -1, + 1471, 709, 710, -1, 1471, 710, 1474, -1, + 1471, 1472, 708, -1, 2862, 2343, 2320, -1, + 3236, 2320, 2343, -1, 1489, 1478, 1490, -1, + 2863, 1479, 2859, -1, 1482, 1483, 1480, -1, + 2838, 711, 2839, -1, 2838, 712, 711, -1, + 2838, 2841, 713, -1, 2838, 713, 712, -1, + 2271, 2306, 1458, -1, 2271, 1458, 714, -1, + 2271, 714, 2273, -1, 2316, 1457, 1476, -1, + 2892, 2315, 2325, -1, 2892, 3243, 2315, -1, + 2313, 1487, 1459, -1, 2313, 1459, 1457, -1, + 2313, 1457, 2316, -1, 715, 1725, 1511, -1, + 715, 1726, 1725, -1, 715, 717, 1726, -1, + 715, 1511, 731, -1, 715, 716, 717, -1, + 715, 731, 716, -1, 866, 1726, 717, -1, + 866, 718, 719, -1, 866, 717, 718, -1, + 866, 719, 865, -1, 1493, 1494, 720, -1, + 1493, 720, 721, -1, 1493, 721, 722, -1, + 1493, 722, 1496, -1, 1515, 1502, 1516, -1, + 1515, 1514, 858, -1, 1515, 858, 1499, -1, + 1515, 1499, 1502, -1, 1517, 1506, 723, -1, + 1517, 723, 1518, -1, 1509, 1518, 732, -1, + 1509, 1513, 1518, -1, 724, 2283, 2290, -1, + 724, 1454, 725, -1, 724, 2290, 1454, -1, + 724, 725, 726, -1, 724, 726, 727, -1, + 724, 727, 2283, -1, 728, 730, 729, -1, + 728, 729, 731, -1, 728, 732, 730, -1, + 728, 731, 1511, -1, 728, 1511, 1509, -1, + 728, 1509, 732, -1, 733, 735, 734, -1, + 733, 734, 736, -1, 733, 1737, 735, -1, + 733, 736, 737, -1, 733, 737, 886, -1, + 733, 886, 1737, -1, 1507, 1495, 1505, -1, + 1507, 1516, 1502, -1, 1507, 1501, 1495, -1, + 1507, 1502, 1501, -1, 1526, 1527, 739, -1, + 1526, 739, 1302, -1, 1526, 1302, 738, -1, + 1526, 738, 1525, -1, 1522, 1521, 739, -1, + 1522, 739, 1527, -1, 1524, 1529, 1522, -1, + 1524, 1522, 1527, -1, 1534, 1529, 1524, -1, + 1534, 1524, 1533, -1, 2352, 1525, 2351, -1, + 2898, 1533, 2352, -1, 3221, 2866, 1537, -1, + 1548, 2802, 1310, -1, 1548, 1310, 1544, -1, + 1548, 1544, 1543, -1, 1548, 1543, 1549, -1, + 1540, 740, 1541, -1, 1540, 741, 740, -1, + 1540, 1311, 741, -1, 1540, 1544, 1311, -1, + 3235, 2889, 2890, -1, 2353, 1552, 2336, -1, + 2359, 2903, 1557, -1, 742, 747, 743, -1, + 742, 744, 747, -1, 742, 1557, 744, -1, + 742, 2359, 1557, -1, 742, 743, 1554, -1, + 742, 1554, 2359, -1, 1556, 1551, 744, -1, + 1556, 744, 1557, -1, 1558, 1551, 1556, -1, + 1558, 1556, 2326, -1, 1558, 2337, 1551, -1, + 1558, 2354, 2337, -1, 767, 1553, 745, -1, + 767, 745, 746, -1, 767, 746, 768, -1, + 767, 766, 1553, -1, 2356, 1553, 766, -1, + 2356, 1616, 2357, -1, 2356, 766, 1616, -1, + 2896, 747, 2349, -1, 2896, 1559, 747, -1, + 1562, 1563, 1235, -1, 1562, 1235, 754, -1, + 1562, 754, 753, -1, 1562, 753, 1572, -1, + 1569, 2083, 1574, -1, 1569, 1574, 1575, -1, + 1569, 1575, 748, -1, 1569, 748, 1568, -1, + 749, 748, 1575, -1, 749, 752, 2792, -1, + 749, 2791, 748, -1, 749, 2792, 2791, -1, + 1571, 1572, 753, -1, 1571, 753, 752, -1, + 1571, 752, 749, -1, 1571, 749, 1575, -1, + 750, 751, 752, -1, 750, 752, 753, -1, + 750, 1240, 1239, -1, 750, 1239, 751, -1, + 750, 753, 754, -1, 750, 754, 1240, -1, + 2372, 1269, 1268, -1, 2372, 2388, 1269, -1, + 1577, 2370, 1578, -1, 1577, 2139, 2780, -1, + 1579, 1584, 2139, -1, 1579, 2139, 1577, -1, + 1579, 1577, 1578, -1, 1579, 2734, 1584, -1, + 1580, 2732, 990, -1, 1580, 1585, 2732, -1, + 2398, 1581, 3060, -1, 1227, 1230, 987, -1, + 1227, 988, 1226, -1, 1713, 2489, 2488, -1, + 1713, 2488, 1599, -1, 2373, 1592, 2381, -1, + 2373, 1593, 1592, -1, 1596, 1597, 784, -1, + 2384, 1656, 2385, -1, 2913, 1597, 1596, -1, + 2913, 1596, 2389, -1, 1594, 1708, 1602, -1, + 1594, 1715, 1708, -1, 2380, 1594, 1602, -1, + 2380, 2381, 1592, -1, 2380, 1592, 1594, -1, + 2395, 2380, 1602, -1, 1603, 1600, 2393, -1, + 1603, 1709, 1600, -1, 1603, 1602, 1708, -1, + 1603, 1708, 1709, -1, 755, 2392, 2393, -1, + 755, 1601, 784, -1, 755, 784, 1597, -1, + 755, 1597, 2392, -1, 755, 1600, 1601, -1, + 755, 2393, 1600, -1, 2402, 2401, 1587, -1, + 756, 1537, 757, -1, 756, 1538, 1537, -1, + 756, 758, 1538, -1, 756, 757, 759, -1, + 756, 759, 760, -1, 756, 761, 758, -1, + 756, 760, 761, -1, 1621, 2927, 775, -1, + 762, 763, 2907, -1, 762, 2358, 2931, -1, + 762, 2906, 2358, -1, 762, 2907, 2906, -1, + 762, 2929, 763, -1, 762, 2931, 2929, -1, + 2425, 764, 2928, -1, 2425, 1606, 764, -1, + 765, 1617, 766, -1, 765, 772, 1617, -1, + 765, 771, 772, -1, 765, 766, 767, -1, + 765, 768, 771, -1, 765, 767, 768, -1, + 1467, 1484, 1485, -1, 1467, 1466, 769, -1, + 1467, 769, 2407, -1, 1467, 2407, 1484, -1, + 2405, 1613, 1486, -1, 2405, 1484, 2407, -1, + 2405, 1486, 1484, -1, 1612, 1486, 1613, -1, + 1612, 1483, 1486, -1, 770, 771, 1480, -1, + 770, 1480, 1483, -1, 770, 772, 771, -1, + 770, 1483, 1612, -1, 770, 1611, 772, -1, + 770, 1612, 1611, -1, 1607, 773, 1608, -1, + 1607, 1615, 773, -1, 1614, 2410, 774, -1, + 1614, 774, 1615, -1, 1610, 1618, 1611, -1, + 1610, 1623, 1618, -1, 1610, 1607, 1623, -1, + 1610, 1615, 1607, -1, 1620, 775, 2357, -1, + 1620, 2357, 1616, -1, 1620, 1621, 775, -1, + 1627, 1633, 2419, -1, 2417, 984, 1637, -1, + 2417, 1635, 984, -1, 1632, 776, 777, -1, + 1632, 777, 1633, -1, 1632, 1631, 776, -1, + 1632, 1633, 1627, -1, 2403, 1625, 1628, -1, + 2403, 1621, 1625, -1, 2403, 2927, 1621, -1, + 2422, 1636, 1639, -1, 2404, 1627, 2419, -1, + 2404, 1628, 1627, -1, 2404, 2403, 1628, -1, + 1644, 1642, 1417, -1, 2946, 778, 2414, -1, + 2946, 779, 778, -1, 2946, 2948, 779, -1, + 780, 806, 805, -1, 780, 781, 806, -1, + 780, 840, 781, -1, 780, 1707, 840, -1, + 780, 805, 2484, -1, 780, 2484, 1707, -1, + 2431, 1647, 833, -1, 2431, 833, 1648, -1, + 2953, 2433, 2951, -1, 2816, 1667, 2432, -1, + 3275, 807, 3274, -1, 3275, 3464, 811, -1, + 3052, 807, 1845, -1, 3052, 3274, 807, -1, + 983, 782, 783, -1, 983, 1637, 984, -1, + 983, 783, 1637, -1, 983, 982, 782, -1, + 1653, 784, 785, -1, 1653, 785, 1651, -1, + 1653, 1596, 784, -1, 786, 1652, 1651, -1, + 786, 788, 1652, -1, 786, 1651, 787, -1, + 786, 1684, 788, -1, 786, 2491, 1684, -1, + 786, 787, 2491, -1, 1658, 788, 1661, -1, + 1658, 1652, 788, -1, 2246, 2247, 1663, -1, + 2246, 1667, 2816, -1, 2450, 1668, 1673, -1, + 2444, 2445, 789, -1, 2444, 789, 1670, -1, + 2441, 790, 2445, -1, 2441, 2457, 819, -1, + 2441, 819, 790, -1, 2440, 791, 2452, -1, + 2440, 2452, 2458, -1, 2449, 3280, 2956, -1, + 2448, 1672, 791, -1, 2448, 791, 2440, -1, + 2448, 2440, 2451, -1, 792, 793, 799, -1, + 792, 794, 793, -1, 792, 795, 794, -1, + 792, 796, 795, -1, 792, 797, 796, -1, + 792, 799, 797, -1, 798, 800, 799, -1, + 798, 880, 800, -1, 798, 801, 880, -1, + 798, 802, 801, -1, 798, 803, 802, -1, + 798, 799, 803, -1, 804, 812, 805, -1, + 804, 811, 812, -1, 804, 805, 806, -1, + 804, 3275, 811, -1, 804, 806, 807, -1, + 804, 807, 3275, -1, 1680, 1675, 829, -1, + 1680, 829, 1679, -1, 2461, 1681, 2470, -1, + 810, 808, 2459, -1, 810, 2468, 2469, -1, + 810, 809, 808, -1, 810, 2469, 809, -1, + 2463, 810, 2459, -1, 2463, 2468, 810, -1, + 815, 813, 1682, -1, 815, 811, 813, -1, + 815, 812, 811, -1, 815, 814, 812, -1, + 2467, 1682, 813, -1, 2467, 813, 3465, -1, + 2467, 3465, 2471, -1, 1678, 1679, 1722, -1, + 1678, 1722, 814, -1, 1678, 814, 815, -1, + 1678, 815, 1682, -1, 823, 818, 821, -1, + 823, 821, 826, -1, 816, 824, 817, -1, + 816, 823, 824, -1, 816, 818, 823, -1, + 816, 2456, 818, -1, 816, 817, 819, -1, + 816, 819, 2456, -1, 2434, 2432, 826, -1, + 2434, 820, 2433, -1, 2434, 821, 820, -1, + 2434, 826, 821, -1, 827, 828, 822, -1, + 827, 823, 826, -1, 827, 822, 824, -1, + 827, 824, 823, -1, 825, 826, 2432, -1, + 825, 827, 826, -1, 825, 828, 827, -1, + 825, 1666, 828, -1, 825, 1667, 1666, -1, + 825, 2432, 1667, -1, 1721, 1679, 829, -1, + 1721, 1722, 1679, -1, 1721, 829, 1683, -1, + 2478, 2477, 830, -1, 2478, 830, 831, -1, + 2478, 831, 1685, -1, 1645, 834, 2475, -1, + 1645, 1644, 1418, -1, 832, 1416, 833, -1, + 832, 834, 1645, -1, 832, 833, 835, -1, + 832, 835, 834, -1, 832, 1418, 1416, -1, + 832, 1645, 1418, -1, 1589, 836, 1593, -1, + 1589, 1593, 2373, -1, 1595, 839, 848, -1, + 1595, 836, 839, -1, 1595, 848, 1716, -1, + 1595, 1593, 836, -1, 838, 1702, 836, -1, + 838, 1590, 837, -1, 838, 1589, 1590, -1, + 838, 836, 1589, -1, 1701, 837, 1704, -1, + 1701, 838, 837, -1, 1701, 1702, 838, -1, + 1691, 1687, 844, -1, 1691, 844, 1689, -1, + 1703, 839, 1702, -1, 1703, 1696, 839, -1, + 845, 843, 840, -1, 845, 842, 843, -1, + 845, 840, 1707, -1, 845, 846, 842, -1, + 841, 1697, 1698, -1, 841, 843, 842, -1, + 841, 842, 1697, -1, 841, 844, 843, -1, + 841, 1689, 844, -1, 841, 1698, 1689, -1, + 1706, 1718, 846, -1, 1706, 1711, 1718, -1, + 1706, 846, 845, -1, 1706, 845, 1707, -1, + 1720, 846, 1718, -1, 1720, 847, 846, -1, + 1720, 848, 847, -1, 1720, 1716, 848, -1, + 1717, 1718, 1711, -1, 2490, 2489, 2481, -1, + 867, 2495, 1134, -1, 867, 851, 1730, -1, + 867, 1134, 1132, -1, 867, 1132, 851, -1, + 1728, 852, 849, -1, 1728, 849, 1729, -1, + 850, 1730, 851, -1, 850, 853, 852, -1, + 850, 1728, 1730, -1, 850, 852, 1728, -1, + 850, 854, 853, -1, 850, 851, 854, -1, + 864, 863, 855, -1, 864, 855, 857, -1, + 864, 857, 858, -1, 864, 858, 1514, -1, + 856, 858, 857, -1, 856, 1499, 858, -1, + 856, 2243, 1499, -1, 856, 2242, 2243, -1, + 856, 862, 2242, -1, 856, 857, 862, -1, + 859, 872, 873, -1, 859, 1099, 872, -1, + 859, 860, 1099, -1, 859, 861, 860, -1, + 859, 862, 861, -1, 859, 873, 862, -1, + 1510, 1724, 863, -1, 1510, 864, 1514, -1, + 1510, 863, 864, -1, 1510, 1514, 1513, -1, + 2497, 865, 2496, -1, 2497, 866, 865, -1, + 2497, 1726, 866, -1, 2494, 867, 1730, -1, + 2494, 2495, 867, -1, 868, 870, 869, -1, + 868, 872, 871, -1, 868, 871, 870, -1, + 868, 873, 872, -1, 868, 2241, 873, -1, + 868, 869, 2241, -1, 2437, 874, 2958, -1, + 2437, 875, 874, -1, 2437, 876, 875, -1, + 2437, 2438, 876, -1, 2957, 877, 1093, -1, + 2957, 2958, 877, -1, 2957, 1093, 878, -1, + 2957, 878, 3539, -1, 1671, 879, 2438, -1, + 1671, 2959, 1669, -1, 1671, 1669, 880, -1, + 1671, 880, 879, -1, 881, 882, 883, -1, + 881, 884, 882, -1, 881, 883, 885, -1, + 881, 885, 884, -1, 2502, 886, 2501, -1, + 2502, 1737, 886, -1, 3493, 3491, 2600, -1, + 3481, 887, 1739, -1, 3481, 3480, 887, -1, + 888, 1365, 1364, -1, 888, 1369, 2500, -1, + 888, 1364, 1369, -1, 888, 2500, 2501, -1, + 888, 2501, 889, -1, 888, 889, 1365, -1, + 1742, 896, 1745, -1, 1742, 1743, 896, -1, + 1744, 1746, 1323, -1, 1744, 1323, 894, -1, + 1749, 893, 894, -1, 1749, 890, 891, -1, + 1749, 891, 893, -1, 1749, 1750, 890, -1, + 1749, 894, 1751, -1, 892, 893, 1743, -1, + 892, 894, 893, -1, 892, 1743, 1744, -1, + 892, 1744, 894, -1, 895, 896, 897, -1, + 895, 898, 896, -1, 895, 897, 899, -1, + 895, 899, 898, -1, 2564, 927, 1021, -1, + 900, 901, 3499, -1, 900, 905, 901, -1, + 900, 3499, 905, -1, 902, 904, 903, -1, + 902, 905, 904, -1, 902, 903, 905, -1, + 1755, 1824, 954, -1, 1755, 954, 905, -1, + 1755, 905, 3499, -1, 1754, 927, 2564, -1, + 1754, 2564, 2565, -1, 3317, 2982, 2978, -1, + 1795, 1796, 1805, -1, 1795, 2982, 3016, -1, + 3498, 3499, 3500, -1, 2511, 1757, 2198, -1, + 2511, 2198, 2512, -1, 2193, 2989, 2530, -1, + 2193, 2530, 2196, -1, 2513, 1761, 2514, -1, + 2531, 2532, 2517, -1, 2531, 2196, 2530, -1, + 3331, 2197, 3330, -1, 2522, 2197, 3331, -1, + 2510, 2994, 2995, -1, 1776, 1777, 906, -1, + 1776, 906, 907, -1, 1776, 907, 908, -1, + 1776, 908, 1783, -1, 1768, 1765, 1771, -1, + 1768, 1769, 1766, -1, 2534, 1773, 1777, -1, + 2524, 2525, 2518, -1, 1779, 2539, 2537, -1, + 1779, 1793, 2539, -1, 1779, 1782, 920, -1, + 1787, 909, 1785, -1, 1787, 1788, 909, -1, + 3005, 1789, 3007, -1, 3005, 1791, 1789, -1, + 3005, 2541, 1791, -1, 3010, 3011, 2540, -1, + 3014, 1785, 3013, -1, 3014, 2542, 1786, -1, + 3014, 1786, 1785, -1, 910, 918, 1781, -1, + 910, 911, 918, -1, 910, 1781, 1769, -1, + 910, 1769, 1770, -1, 910, 1771, 911, -1, + 910, 1770, 1771, -1, 917, 912, 916, -1, + 917, 918, 912, -1, 913, 914, 915, -1, + 913, 915, 920, -1, 913, 916, 914, -1, + 913, 917, 916, -1, 913, 918, 917, -1, + 913, 1782, 918, -1, 913, 920, 1782, -1, + 919, 920, 3003, -1, 919, 1794, 1793, -1, + 919, 3003, 1794, -1, 919, 1793, 1779, -1, + 919, 1779, 920, -1, 2545, 2546, 921, -1, + 2545, 921, 923, -1, 2545, 923, 1796, -1, + 2545, 1796, 3020, -1, 924, 921, 922, -1, + 924, 923, 921, -1, 924, 922, 1869, -1, + 924, 1869, 925, -1, 2553, 2554, 2546, -1, + 1804, 1805, 923, -1, 1804, 923, 924, -1, + 1804, 925, 1803, -1, 1804, 924, 925, -1, + 2977, 2979, 926, -1, 2977, 1754, 3312, -1, + 2977, 926, 927, -1, 2977, 927, 1754, -1, + 1806, 1795, 1805, -1, 1806, 2978, 2982, -1, + 1806, 2982, 1795, -1, 1801, 1802, 928, -1, + 1801, 928, 2980, -1, 1801, 2980, 2978, -1, + 1801, 2978, 1806, -1, 1808, 932, 1809, -1, + 1808, 929, 932, -1, 1808, 1867, 929, -1, + 1808, 1811, 1867, -1, 930, 932, 931, -1, + 930, 1809, 932, -1, 930, 931, 933, -1, + 930, 933, 1809, -1, 934, 936, 935, -1, + 934, 937, 936, -1, 934, 935, 944, -1, + 934, 938, 937, -1, 934, 944, 939, -1, + 934, 939, 938, -1, 1813, 1814, 1014, -1, + 1813, 1817, 1823, -1, 1816, 1817, 1813, -1, + 1816, 1813, 1014, -1, 940, 942, 941, -1, + 940, 944, 943, -1, 940, 943, 942, -1, + 940, 951, 944, -1, 940, 950, 951, -1, + 940, 941, 950, -1, 945, 947, 946, -1, + 945, 948, 949, -1, 945, 949, 947, -1, + 945, 950, 948, -1, 945, 951, 950, -1, + 945, 946, 951, -1, 1818, 1819, 952, -1, + 1818, 956, 1817, -1, 1818, 952, 953, -1, + 1818, 953, 956, -1, 1822, 954, 1824, -1, + 1822, 955, 954, -1, 1822, 956, 955, -1, + 1822, 1823, 956, -1, 1826, 957, 1827, -1, + 1826, 960, 957, -1, 1826, 959, 960, -1, + 1826, 1830, 959, -1, 958, 960, 959, -1, + 958, 962, 961, -1, 958, 961, 960, -1, + 958, 963, 962, -1, 958, 964, 963, -1, + 958, 959, 964, -1, 3039, 1832, 3040, -1, + 3033, 3028, 3043, -1, 3033, 3043, 965, -1, + 3033, 3032, 3028, -1, 3033, 965, 3034, -1, + 1838, 966, 967, -1, 1838, 967, 968, -1, + 1838, 968, 2573, -1, 1838, 1839, 966, -1, + 1831, 970, 969, -1, 1831, 971, 970, -1, + 1831, 969, 1830, -1, 1831, 1829, 971, -1, + 2580, 1202, 2581, -1, 976, 2577, 972, -1, + 976, 972, 973, -1, 976, 973, 974, -1, + 976, 974, 977, -1, 1840, 975, 1839, -1, + 1840, 2577, 976, -1, 1840, 977, 975, -1, + 1840, 976, 977, -1, 1204, 1201, 1203, -1, + 1204, 1205, 1201, -1, 1694, 1692, 2585, -1, + 1694, 2585, 1693, -1, 2586, 1693, 1842, -1, + 3048, 1843, 3047, -1, 3333, 978, 3336, -1, + 3333, 979, 978, -1, 3333, 3334, 980, -1, + 3333, 981, 979, -1, 3333, 980, 981, -1, + 1847, 1849, 982, -1, 1847, 982, 983, -1, + 1847, 984, 1848, -1, 1847, 983, 984, -1, + 985, 1848, 1635, -1, 985, 1634, 1643, -1, + 985, 1635, 1634, -1, 985, 1643, 2476, -1, + 985, 2476, 2474, -1, 985, 2474, 1848, -1, + 2399, 2920, 2400, -1, 3056, 2589, 986, -1, + 3056, 986, 2397, -1, 1001, 995, 2593, -1, + 1001, 997, 995, -1, 2592, 1581, 1002, -1, + 2592, 3060, 1581, -1, 2592, 1001, 2593, -1, + 2592, 1002, 1001, -1, 992, 999, 1000, -1, + 992, 1000, 1582, -1, 992, 1582, 1580, -1, + 992, 1580, 990, -1, 991, 987, 999, -1, + 991, 1227, 987, -1, 991, 993, 988, -1, + 991, 988, 1227, -1, 989, 2733, 1237, -1, + 989, 990, 2733, -1, 989, 991, 999, -1, + 989, 992, 990, -1, 989, 999, 992, -1, + 989, 1237, 993, -1, 989, 993, 991, -1, + 1007, 994, 995, -1, 1007, 995, 997, -1, + 1007, 1004, 994, -1, 1007, 997, 1008, -1, + 996, 998, 997, -1, 996, 1000, 999, -1, + 996, 999, 998, -1, 996, 997, 1001, -1, + 996, 1002, 1000, -1, 996, 1001, 1002, -1, + 1003, 1005, 1004, -1, 1003, 1006, 1005, -1, + 1003, 1004, 1007, -1, 1003, 1007, 1008, -1, + 1003, 1009, 1006, -1, 1003, 1008, 1009, -1, + 1010, 1011, 1821, -1, 1010, 1012, 1011, -1, + 1010, 1013, 1012, -1, 1010, 1014, 1013, -1, + 1010, 1816, 1014, -1, 1010, 1821, 1816, -1, + 1852, 1853, 1015, -1, 1852, 1015, 1025, -1, + 1852, 1025, 1032, -1, 1016, 1017, 1018, -1, + 1016, 1018, 1019, -1, 1016, 1854, 1855, -1, + 1016, 1855, 1017, -1, 1016, 1019, 1020, -1, + 1016, 1020, 1854, -1, 2562, 1021, 1860, -1, + 2562, 2564, 1021, -1, 1859, 1022, 1862, -1, + 1859, 1025, 1022, -1, 1023, 1024, 1031, -1, + 1023, 1860, 1024, -1, 1023, 1031, 1032, -1, + 1023, 1859, 1860, -1, 1023, 1032, 1025, -1, + 1023, 1025, 1859, -1, 1864, 1856, 1028, -1, + 1864, 1868, 1026, -1, 1864, 1026, 1856, -1, + 1864, 1028, 1865, -1, 1857, 1028, 1856, -1, + 1857, 1852, 1032, -1, 1027, 1029, 1028, -1, + 1027, 1031, 1030, -1, 1027, 1030, 1029, -1, + 1027, 1032, 1031, -1, 1027, 1857, 1032, -1, + 1027, 1028, 1857, -1, 1033, 1035, 1034, -1, + 1033, 1036, 1037, -1, 1033, 1037, 1035, -1, + 1033, 1038, 1036, -1, 1033, 1039, 1038, -1, + 1033, 1034, 1039, -1, 1040, 2569, 1041, -1, + 1040, 1042, 1043, -1, 1040, 1041, 1042, -1, + 1040, 1043, 1044, -1, 1040, 1044, 2568, -1, + 1040, 2568, 2569, -1, 1045, 1055, 1046, -1, + 1045, 1047, 1048, -1, 1045, 1046, 1047, -1, + 1045, 1048, 1049, -1, 1045, 1049, 1055, -1, + 1877, 1991, 1056, -1, 1877, 1056, 1058, -1, + 1877, 1058, 2616, -1, 1877, 2617, 1991, -1, + 1050, 1052, 1051, -1, 1050, 1053, 1740, -1, + 1050, 1054, 1053, -1, 1050, 1051, 1054, -1, + 1050, 1740, 1739, -1, 1050, 1739, 1052, -1, + 2598, 3493, 2600, -1, 2598, 3478, 3493, -1, + 1871, 1872, 1055, -1, 1871, 1075, 2601, -1, + 1871, 1074, 1075, -1, 1871, 1055, 1074, -1, + 2613, 1875, 1064, -1, 1078, 2604, 2601, -1, + 1078, 2603, 2604, -1, 1078, 2601, 1075, -1, + 1078, 1075, 1079, -1, 1059, 1058, 1056, -1, + 1059, 1057, 1876, -1, 1059, 1056, 1057, -1, + 2611, 2612, 1058, -1, 2611, 1058, 1059, -1, + 2611, 1059, 1876, -1, 1133, 1060, 1992, -1, + 1133, 1061, 1060, -1, 1133, 1134, 1062, -1, + 1133, 1062, 1061, -1, 1063, 1878, 2614, -1, + 1063, 1071, 1885, -1, 1063, 1885, 1878, -1, + 1063, 1077, 1071, -1, 1063, 1064, 1077, -1, + 1063, 2614, 1064, -1, 2615, 1064, 2614, -1, + 2615, 2613, 1064, -1, 2615, 2616, 2612, -1, + 2615, 2612, 2613, -1, 3066, 2614, 1878, -1, + 1887, 1878, 1885, -1, 1891, 1898, 1065, -1, + 1891, 1066, 1892, -1, 1891, 1067, 1066, -1, + 1891, 1065, 1067, -1, 1069, 1070, 1067, -1, + 1069, 1067, 1068, -1, 1899, 1068, 1898, -1, + 1899, 1069, 1068, -1, 1899, 1073, 1070, -1, + 1899, 1070, 1069, -1, 1895, 1886, 1071, -1, + 1895, 1896, 1886, -1, 1080, 1079, 1900, -1, + 1080, 1071, 1077, -1, 1080, 1895, 1071, -1, + 1080, 1900, 1895, -1, 1072, 1900, 1079, -1, + 1072, 1899, 1900, -1, 1072, 1073, 1899, -1, + 1072, 1074, 1073, -1, 1072, 1075, 1074, -1, + 1072, 1079, 1075, -1, 1076, 1077, 1875, -1, + 1076, 1078, 1079, -1, 1076, 1080, 1077, -1, + 1076, 1079, 1080, -1, 1076, 1875, 2603, -1, + 1076, 2603, 1078, -1, 3506, 1081, 1906, -1, + 3506, 3508, 1082, -1, 3506, 1082, 1081, -1, + 3078, 1902, 1905, -1, 1909, 1083, 1914, -1, + 1909, 1908, 1083, -1, 3087, 1916, 2630, -1, + 3083, 1911, 3082, -1, 3083, 2629, 1911, -1, + 1910, 3088, 1935, -1, 1910, 2629, 2627, -1, + 1913, 1914, 1084, -1, 1913, 1084, 2129, -1, + 1913, 2129, 2135, -1, 1913, 2135, 2134, -1, + 1918, 1083, 1919, -1, 1918, 1084, 1083, -1, + 1918, 1923, 1085, -1, 1918, 1085, 1084, -1, + 3090, 1935, 3088, -1, 3090, 1936, 1935, -1, + 1103, 3091, 2634, -1, 1103, 2634, 2436, -1, + 1103, 1936, 3090, -1, 1103, 3090, 3091, -1, + 2635, 2435, 2634, -1, 2635, 2633, 1090, -1, + 2635, 1090, 1668, -1, 2635, 1668, 2435, -1, + 2646, 2645, 1659, -1, 1928, 1673, 1929, -1, + 1928, 2652, 1672, -1, 2653, 1086, 2652, -1, + 2653, 1087, 1086, -1, 2653, 1088, 1087, -1, + 2653, 2651, 1088, -1, 1089, 2637, 2636, -1, + 1089, 2633, 1924, -1, 1089, 1924, 2637, -1, + 1089, 1090, 2633, -1, 1089, 1929, 1090, -1, + 1089, 2636, 1929, -1, 1091, 1092, 1093, -1, + 1091, 1094, 3100, -1, 1091, 3100, 1095, -1, + 1091, 1095, 1092, -1, 1091, 1096, 1094, -1, + 1091, 1093, 1096, -1, 1097, 1099, 1098, -1, + 1097, 1100, 1099, -1, 1097, 1098, 1101, -1, + 1097, 3098, 1100, -1, 1097, 1101, 2654, -1, + 1097, 2654, 3098, -1, 1102, 3276, 2661, -1, + 1102, 2436, 3471, -1, 1102, 3471, 3276, -1, + 1102, 1103, 2436, -1, 1102, 2661, 1936, -1, + 1102, 1936, 1103, -1, 2659, 1938, 1911, -1, + 1939, 1903, 1901, -1, 1939, 1901, 1938, -1, + 1939, 1109, 1903, -1, 1939, 1940, 1109, -1, + 1140, 1142, 1144, -1, 1140, 1105, 1139, -1, + 1140, 1104, 1105, -1, 1140, 1144, 1104, -1, + 1931, 1106, 1107, -1, 1931, 1136, 1106, -1, + 1931, 1107, 1930, -1, 1931, 1934, 1136, -1, + 1942, 1105, 2624, -1, 1942, 1139, 1105, -1, + 1942, 1106, 1139, -1, 1942, 1941, 1106, -1, + 1904, 1941, 3349, -1, 1904, 1107, 1941, -1, + 1904, 1905, 1114, -1, 1904, 1114, 1107, -1, + 1108, 1903, 1109, -1, 1108, 1902, 1903, -1, + 1108, 1113, 1902, -1, 1108, 1112, 1113, -1, + 1108, 1109, 1110, -1, 1108, 1110, 1112, -1, + 1111, 1113, 1112, -1, 1111, 1930, 1114, -1, + 1111, 1114, 1113, -1, 1111, 3102, 1930, -1, + 1111, 1112, 3101, -1, 1111, 3101, 3102, -1, + 1944, 1115, 1116, -1, 1944, 1116, 1117, -1, + 1944, 1118, 1115, -1, 1944, 1947, 1118, -1, + 1944, 1117, 1945, -1, 1119, 1121, 1120, -1, + 1119, 1952, 1121, -1, 1119, 1122, 1952, -1, + 1119, 1120, 2666, -1, 1119, 2665, 1122, -1, + 1119, 2666, 2665, -1, 3110, 1123, 3109, -1, + 3110, 1948, 1123, -1, 1950, 3110, 3111, -1, + 1950, 1951, 1947, -1, 1956, 1273, 3075, -1, + 1956, 1957, 1273, -1, 1956, 3075, 3076, -1, + 1956, 3076, 1955, -1, 1959, 1125, 1124, -1, + 1959, 1960, 1125, -1, 1959, 1124, 1126, -1, + 1959, 1126, 1127, -1, 1959, 1127, 1963, -1, + 1964, 2670, 1128, -1, 1964, 2669, 2670, -1, + 1964, 1129, 2674, -1, 1964, 1128, 1129, -1, + 1974, 1970, 1973, -1, 2683, 2686, 1975, -1, + 1977, 1147, 1986, -1, 1977, 1146, 1147, -1, + 1977, 1980, 1130, -1, 1977, 1130, 1146, -1, + 1982, 1131, 1983, -1, 1982, 1990, 1131, -1, + 1982, 1986, 1147, -1, 1982, 1147, 1990, -1, + 1148, 1146, 1132, -1, 1148, 1133, 1992, -1, + 1148, 1132, 1134, -1, 1148, 1134, 1133, -1, + 1135, 1136, 1137, -1, 1135, 1137, 1138, -1, + 1135, 1138, 1142, -1, 1135, 1139, 1136, -1, + 1135, 1142, 1140, -1, 1135, 1140, 1139, -1, + 1141, 1142, 1984, -1, 1141, 1984, 1987, -1, + 1141, 1987, 1143, -1, 1141, 1144, 1142, -1, + 1141, 1143, 1145, -1, 1141, 1145, 1144, -1, + 1989, 1147, 1146, -1, 1989, 1990, 1147, -1, + 1989, 1148, 1992, -1, 1989, 1146, 1148, -1, + 1152, 2676, 1149, -1, 1152, 1150, 1155, -1, + 1152, 1149, 1151, -1, 1152, 1151, 1150, -1, + 1968, 1155, 1967, -1, 1968, 2675, 2676, -1, + 1968, 2676, 1152, -1, 1968, 1152, 1155, -1, + 1160, 1153, 1960, -1, 1160, 1154, 1153, -1, + 1160, 1155, 1154, -1, 1160, 1967, 1155, -1, + 1994, 1995, 1158, -1, 1994, 1158, 1156, -1, + 1994, 1156, 1975, -1, 1994, 1975, 2686, -1, + 1161, 1962, 1157, -1, 1161, 1157, 1158, -1, + 1161, 1158, 1159, -1, 1161, 1159, 1966, -1, + 1961, 1967, 1160, -1, 1961, 1160, 1960, -1, + 1961, 1962, 1161, -1, 1961, 1966, 1967, -1, + 1961, 1161, 1966, -1, 3105, 1996, 1162, -1, + 1998, 1163, 2001, -1, 1998, 2001, 1999, -1, + 1998, 1162, 1163, -1, 1998, 3105, 1162, -1, + 2000, 2084, 2145, -1, 2000, 1164, 2084, -1, + 2000, 1999, 1164, -1, 3389, 1163, 3107, -1, + 3389, 2001, 1163, -1, 2695, 1164, 1999, -1, + 2695, 1999, 2001, -1, 2695, 2696, 1164, -1, + 2143, 3143, 1165, -1, 2143, 1167, 2144, -1, + 2143, 1165, 1167, -1, 3375, 2003, 2687, -1, + 3070, 2002, 3071, -1, 3070, 3069, 2003, -1, + 1166, 1167, 1168, -1, 1166, 1168, 2002, -1, + 1166, 2002, 3373, -1, 1166, 3373, 2692, -1, + 1166, 2692, 2144, -1, 1166, 2144, 1167, -1, + 2007, 2717, 1169, -1, 2007, 1169, 2009, -1, + 2007, 2015, 2717, -1, 2007, 2008, 2015, -1, + 2701, 1170, 2012, -1, 2701, 2016, 1170, -1, + 2718, 2717, 2015, -1, 3124, 3118, 3125, -1, + 3124, 3119, 3118, -1, 2723, 2724, 2022, -1, + 2721, 2020, 2024, -1, 2719, 3114, 1171, -1, + 2719, 1171, 1172, -1, 2719, 2043, 2720, -1, + 2719, 1172, 2043, -1, 2031, 2033, 1173, -1, + 2031, 1174, 3392, -1, 2031, 3392, 3396, -1, + 2031, 1173, 1175, -1, 2031, 1175, 1174, -1, + 2035, 2038, 2028, -1, 2035, 3396, 3394, -1, + 3134, 1176, 3135, -1, 3134, 2040, 1176, -1, + 3134, 2728, 2040, -1, 3402, 3125, 2720, -1, + 3402, 2720, 2726, -1, 1182, 1177, 1181, -1, + 1182, 1183, 1178, -1, 1182, 1178, 1179, -1, + 1182, 1179, 1177, -1, 1180, 1184, 1183, -1, + 1180, 1181, 2013, -1, 1180, 1182, 1181, -1, + 1180, 1183, 1182, -1, 1180, 2013, 2012, -1, + 1180, 2012, 1184, -1, 2025, 1183, 1184, -1, + 2025, 1185, 2036, -1, 2025, 1184, 1185, -1, + 2025, 2024, 1183, -1, 1186, 1187, 1188, -1, + 1186, 1188, 1195, -1, 1186, 1189, 1187, -1, + 1186, 1195, 1191, -1, 1186, 1190, 1189, -1, + 1186, 1191, 1190, -1, 1200, 1191, 1195, -1, + 1200, 1199, 1192, -1, 1200, 1192, 1193, -1, + 1200, 1193, 1191, -1, 1194, 1195, 1196, -1, + 1194, 1196, 1197, -1, 1194, 1197, 1198, -1, + 1194, 1198, 1199, -1, 1194, 1199, 1200, -1, + 1194, 1200, 1195, -1, 2050, 2048, 1201, -1, + 2050, 1201, 1206, -1, 2050, 1206, 2057, -1, + 2054, 2055, 1202, -1, 2054, 1202, 2580, -1, + 2056, 1203, 2705, -1, 2056, 1204, 1203, -1, + 2056, 1205, 1204, -1, 2056, 2057, 1206, -1, + 2056, 1206, 1205, -1, 2713, 2714, 1207, -1, + 2713, 1207, 1208, -1, 2713, 1208, 1209, -1, + 2713, 1209, 2716, -1, 2704, 2707, 2058, -1, + 2704, 2056, 2705, -1, 1210, 1211, 1212, -1, + 1210, 1212, 2063, -1, 1210, 2021, 1211, -1, + 1210, 2063, 1213, -1, 1210, 1214, 2021, -1, + 1210, 1213, 1214, -1, 2066, 1215, 2059, -1, + 2066, 1216, 1215, -1, 2066, 2065, 1216, -1, + 2073, 1564, 2071, -1, 2073, 2072, 1563, -1, + 2070, 1222, 1232, -1, 2070, 1232, 2072, -1, + 2070, 2071, 1222, -1, 1567, 1565, 1250, -1, + 1567, 1250, 1217, -1, 1567, 1217, 1564, -1, + 1567, 1564, 1576, -1, 1245, 1565, 1566, -1, + 1245, 1566, 2082, -1, 1245, 2082, 1248, -1, + 1245, 1247, 1251, -1, 1245, 1248, 1247, -1, + 1223, 1232, 1222, -1, 1223, 1220, 1218, -1, + 1223, 1233, 1232, -1, 1223, 1218, 1233, -1, + 1219, 1221, 1220, -1, 1219, 2071, 1221, -1, + 1219, 1222, 2071, -1, 1219, 1223, 1222, -1, + 1219, 1220, 1223, -1, 1224, 1226, 1225, -1, + 1224, 1227, 1226, -1, 1224, 1229, 1228, -1, + 1224, 1225, 1229, -1, 1224, 1228, 1230, -1, + 1224, 1230, 1227, -1, 1231, 2072, 1232, -1, + 1231, 1232, 1233, -1, 1231, 1563, 2072, -1, + 1231, 1233, 1234, -1, 1231, 1235, 1563, -1, + 1231, 1234, 1235, -1, 1270, 2133, 1275, -1, + 1270, 2742, 1268, -1, 2369, 1268, 2742, -1, + 2369, 2372, 1268, -1, 2369, 2740, 2370, -1, + 2369, 2742, 2740, -1, 2738, 1270, 1275, -1, + 2738, 2742, 1270, -1, 2738, 1275, 2075, -1, + 2731, 1237, 2733, -1, 2731, 2074, 1237, -1, + 2741, 2077, 2074, -1, 2076, 2155, 1239, -1, + 2076, 2075, 2155, -1, 1236, 1237, 2074, -1, + 1236, 2074, 2077, -1, 1236, 1238, 1237, -1, + 1236, 2077, 2076, -1, 1236, 2076, 1239, -1, + 1236, 1240, 1238, -1, 1236, 1239, 1240, -1, + 2698, 2079, 1258, -1, 2698, 1258, 2697, -1, + 2150, 2747, 2366, -1, 2150, 1568, 2159, -1, + 2150, 2366, 1568, -1, 2150, 2159, 2158, -1, + 2748, 2366, 2747, -1, 2363, 2098, 2081, -1, + 2120, 2121, 1260, -1, 2085, 3154, 3141, -1, + 2085, 3153, 3154, -1, 3432, 2086, 2750, -1, + 3139, 2085, 3141, -1, 3139, 2151, 2085, -1, + 2091, 1241, 1242, -1, 2091, 2097, 1241, -1, + 2091, 2092, 2097, -1, 2088, 2089, 2097, -1, + 2088, 2097, 2092, -1, 3427, 2091, 1242, -1, + 2102, 3427, 1242, -1, 2102, 3426, 3427, -1, + 2102, 1242, 2095, -1, 3138, 2100, 2098, -1, + 2105, 2094, 2093, -1, 1243, 1244, 2107, -1, + 1243, 1261, 1244, -1, 1243, 2105, 2093, -1, + 1243, 2107, 2105, -1, 1243, 2093, 1256, -1, + 1243, 1256, 1261, -1, 1249, 1250, 1565, -1, + 1249, 1245, 1251, -1, 1249, 1565, 1245, -1, + 2096, 2100, 2101, -1, 2096, 1246, 2100, -1, + 2096, 1247, 1248, -1, 2096, 1248, 1246, -1, + 2096, 1250, 1249, -1, 2096, 1251, 1247, -1, + 2096, 1249, 1251, -1, 2096, 2071, 1250, -1, + 2096, 2097, 2071, -1, 2110, 2113, 1252, -1, + 2110, 1252, 1253, -1, 2110, 1253, 2108, -1, + 3415, 2126, 3416, -1, 1254, 3414, 2114, -1, + 1254, 2114, 3413, -1, 1254, 3413, 3414, -1, + 2767, 2090, 2766, -1, 2767, 2116, 2090, -1, + 1255, 2090, 3414, -1, 1255, 2766, 2090, -1, + 1255, 3414, 2766, -1, 2751, 2750, 1256, -1, + 2751, 1256, 2093, -1, 1257, 2119, 1258, -1, + 1257, 1258, 2079, -1, 1257, 2080, 2119, -1, + 1257, 2079, 2080, -1, 2118, 1258, 2119, -1, + 2118, 1259, 2086, -1, 2118, 2086, 1258, -1, + 2118, 2120, 1260, -1, 2118, 1260, 1261, -1, + 2118, 1261, 1259, -1, 2128, 1265, 2018, -1, + 1262, 2018, 1265, -1, 1262, 2124, 1263, -1, + 1262, 2122, 2124, -1, 1262, 1265, 2122, -1, + 1262, 1263, 1264, -1, 1262, 1264, 2018, -1, + 2763, 2122, 2764, -1, 3174, 2764, 1265, -1, + 3174, 1265, 2128, -1, 3128, 3409, 2046, -1, + 3185, 1266, 3186, -1, 3185, 3520, 3519, -1, + 3185, 1267, 1266, -1, 3185, 3519, 1267, -1, + 2162, 3519, 3518, -1, 2162, 1267, 3519, -1, + 2162, 2161, 1267, -1, 1274, 2130, 1266, -1, + 1274, 1266, 1267, -1, 1274, 2769, 2130, -1, + 1274, 1267, 2161, -1, 3181, 2773, 2141, -1, + 2387, 2772, 2771, -1, 2387, 2386, 2772, -1, + 2387, 1269, 2388, -1, 2387, 2771, 1269, -1, + 2132, 1268, 1269, -1, 2132, 1269, 2771, -1, + 2132, 2133, 1270, -1, 2132, 1270, 1268, -1, + 2138, 1916, 2137, -1, 2138, 2630, 1916, -1, + 2138, 1925, 2630, -1, 2138, 3361, 1925, -1, + 3366, 3186, 1271, -1, 3366, 1271, 3365, -1, + 2775, 2137, 2134, -1, 2131, 1271, 2130, -1, + 2131, 3365, 1271, -1, 2644, 2142, 1272, -1, + 2644, 1272, 2645, -1, 3093, 3365, 2131, -1, + 3093, 2131, 2141, -1, 2621, 1273, 2688, -1, + 2621, 3075, 1273, -1, 2621, 2687, 2620, -1, + 2621, 2688, 2687, -1, 3150, 3143, 2143, -1, + 3189, 2148, 3190, -1, 3189, 2782, 2148, -1, + 2154, 2161, 2160, -1, 2154, 2770, 2769, -1, + 2154, 1274, 2161, -1, 2154, 2769, 1274, -1, + 3199, 3180, 2770, -1, 2156, 2075, 1275, -1, + 2156, 1275, 2157, -1, 2156, 2155, 2075, -1, + 2789, 3190, 2787, -1, 2789, 3518, 3190, -1, + 2789, 2162, 3518, -1, 2795, 2794, 2160, -1, + 1276, 1277, 1283, -1, 1276, 2167, 1278, -1, + 1276, 1278, 1277, -1, 1276, 1292, 2167, -1, + 1276, 1279, 1292, -1, 1276, 1283, 1279, -1, + 1280, 1281, 1282, -1, 1280, 1283, 1281, -1, + 1280, 1282, 1284, -1, 1280, 1284, 1283, -1, + 2164, 1285, 2169, -1, 2164, 1286, 1285, -1, + 2164, 1288, 1286, -1, 2164, 2165, 1288, -1, + 1287, 1407, 1288, -1, 1287, 1288, 1289, -1, + 1287, 1290, 1407, -1, 1287, 1291, 1290, -1, + 1287, 1289, 1291, -1, 2166, 2167, 1292, -1, + 2166, 1293, 2165, -1, 2166, 1294, 1293, -1, + 2166, 1292, 1294, -1, 2796, 1295, 2879, -1, + 2796, 2879, 2877, -1, 2796, 1296, 1295, -1, + 2796, 3223, 1296, -1, 2880, 2881, 1535, -1, + 1297, 1299, 1298, -1, 1297, 1298, 1546, -1, + 1297, 1300, 1299, -1, 1297, 1546, 1301, -1, + 1297, 1301, 1302, -1, 1297, 1302, 1300, -1, + 2171, 1303, 2174, -1, 2171, 2172, 1303, -1, + 2173, 1304, 2172, -1, 2173, 1305, 1304, -1, + 2173, 2175, 1306, -1, 2173, 1306, 1305, -1, + 1307, 1317, 1308, -1, 1307, 2801, 1317, -1, + 1307, 1308, 1309, -1, 1307, 1310, 2801, -1, + 1307, 1311, 1310, -1, 1307, 1309, 1311, -1, + 2799, 1312, 2803, -1, 2799, 1313, 1312, -1, + 2799, 2177, 1313, -1, 1314, 2800, 1315, -1, + 1314, 1315, 1316, -1, 1314, 1318, 1317, -1, + 1314, 1317, 2800, -1, 1314, 1319, 1318, -1, + 1314, 1316, 1320, -1, 1314, 1320, 1319, -1, + 1321, 1323, 1322, -1, 1321, 1322, 1324, -1, + 1321, 1324, 1325, -1, 1321, 1326, 1753, -1, + 1321, 1325, 1326, -1, 1321, 1751, 1323, -1, + 1321, 1753, 1751, -1, 2988, 1775, 2529, -1, + 2988, 2529, 2989, -1, 2988, 2990, 1332, -1, + 2988, 1332, 1775, -1, 1327, 1328, 1329, -1, + 1327, 2990, 1330, -1, 1327, 1330, 1331, -1, + 1327, 1331, 1328, -1, 1327, 1332, 2990, -1, + 1327, 1329, 1332, -1, 2189, 1334, 1333, -1, + 2189, 1333, 2190, -1, 2189, 2181, 1334, -1, + 2185, 1335, 1336, -1, 2185, 2191, 1335, -1, + 2185, 1337, 2186, -1, 2185, 1336, 1337, -1, + 2195, 2523, 1760, -1, 2195, 2522, 2523, -1, + 1338, 1395, 1759, -1, 1338, 1759, 1760, -1, + 1338, 2201, 1395, -1, 2200, 1760, 2523, -1, + 2200, 1338, 1760, -1, 2200, 2201, 1338, -1, + 2202, 1395, 2201, -1, 2202, 2198, 1757, -1, + 2202, 1757, 1395, -1, 1339, 2227, 1757, -1, + 1339, 1757, 1340, -1, 1339, 2225, 2227, -1, + 1339, 1340, 2225, -1, 1341, 2297, 1342, -1, + 1341, 2301, 2297, -1, 1341, 1342, 1343, -1, + 1341, 1344, 2301, -1, 1341, 1345, 1344, -1, + 1341, 1343, 1345, -1, 1346, 1348, 1347, -1, + 1346, 1350, 1349, -1, 1346, 1349, 1348, -1, + 1346, 1351, 1350, -1, 1346, 1352, 1351, -1, + 1346, 1347, 1352, -1, 1353, 1354, 1355, -1, + 1353, 1355, 1356, -1, 1353, 1358, 1357, -1, + 1353, 1357, 1354, -1, 1353, 1359, 1358, -1, + 1353, 1356, 1359, -1, 2268, 1361, 2266, -1, + 2268, 2805, 2288, -1, 2268, 2287, 1361, -1, + 2268, 2288, 2287, -1, 1360, 1429, 1423, -1, + 1360, 1423, 2266, -1, 1360, 1430, 1429, -1, + 1360, 2266, 1361, -1, 1360, 1362, 1430, -1, + 1360, 1361, 1362, -1, 1437, 1436, 1423, -1, + 1437, 1429, 1431, -1, 1437, 1423, 1429, -1, + 1437, 1431, 2846, -1, 1424, 1436, 1435, -1, + 1424, 1435, 1363, -1, 1424, 1363, 1425, -1, + 1424, 1425, 2267, -1, 2208, 2206, 1364, -1, + 2208, 1365, 2207, -1, 2208, 1364, 1365, -1, + 2832, 2269, 2204, -1, 1736, 1366, 1732, -1, + 1736, 1367, 1366, -1, 1736, 2499, 1367, -1, + 1736, 1732, 2504, -1, 2807, 1377, 2210, -1, + 2807, 2213, 1377, -1, 1368, 2213, 2212, -1, + 1368, 1369, 1370, -1, 1368, 2212, 1369, -1, + 1368, 1370, 1371, -1, 1368, 1379, 2213, -1, + 1368, 1371, 1379, -1, 2215, 1373, 1372, -1, + 2215, 1372, 2214, -1, 2215, 2216, 1374, -1, + 2215, 1374, 1373, -1, 1375, 1376, 2810, -1, + 1375, 1378, 1377, -1, 1375, 2214, 1378, -1, + 1375, 2810, 2214, -1, 1375, 1377, 1379, -1, + 1375, 1379, 1376, -1, 1400, 1398, 1384, -1, + 1400, 1380, 1401, -1, 1400, 1381, 1380, -1, + 1400, 1384, 1382, -1, 1400, 1382, 1381, -1, + 1383, 1385, 1384, -1, 1383, 1386, 1385, -1, + 1383, 1384, 1398, -1, 1383, 1393, 1386, -1, + 1383, 1398, 1387, -1, 1383, 1387, 1393, -1, + 2298, 1394, 2294, -1, 2298, 2299, 1388, -1, + 2298, 1388, 1394, -1, 1389, 1390, 2294, -1, + 1389, 1392, 1391, -1, 1389, 1391, 1390, -1, + 1389, 1393, 1392, -1, 1389, 1394, 1393, -1, + 1389, 2294, 1394, -1, 2228, 2229, 1395, -1, + 2228, 1395, 2227, -1, 2226, 2224, 2218, -1, + 2226, 2222, 2230, -1, 1396, 1397, 1398, -1, + 1396, 1399, 1397, -1, 1396, 1403, 1399, -1, + 1396, 1400, 1401, -1, 1396, 1398, 1400, -1, + 1396, 1401, 1402, -1, 1396, 1402, 1403, -1, + 2232, 1402, 2233, -1, 2232, 1403, 1402, -1, + 2232, 2237, 1404, -1, 2232, 1404, 1403, -1, + 1405, 1406, 1407, -1, 1405, 2347, 1406, -1, + 1405, 2893, 2347, -1, 1405, 1407, 1408, -1, + 1405, 1408, 2893, -1, 2239, 1409, 1410, -1, + 2239, 1411, 2244, -1, 2239, 1410, 1411, -1, + 2239, 2240, 1409, -1, 2430, 2428, 2263, -1, + 2430, 2263, 2261, -1, 2430, 2260, 2949, -1, + 2430, 2261, 2260, -1, 1412, 2428, 1413, -1, + 1412, 1415, 1414, -1, 1412, 1413, 1415, -1, + 1412, 1414, 2825, -1, 1412, 2263, 2428, -1, + 1412, 2825, 2263, -1, 2245, 1416, 2936, -1, + 2245, 2248, 1648, -1, 2245, 1648, 1416, -1, + 2245, 2936, 2939, -1, 2935, 1417, 2934, -1, + 2935, 1644, 1417, -1, 2935, 2936, 1418, -1, + 2935, 1418, 1644, -1, 2820, 2940, 2258, -1, + 2820, 2258, 2821, -1, 2820, 2249, 2940, -1, + 2253, 1419, 1664, -1, 2253, 2254, 1419, -1, + 2253, 1664, 1663, -1, 2253, 1663, 2251, -1, + 2256, 2252, 2257, -1, 2256, 2262, 2252, -1, + 2256, 2261, 2262, -1, 2256, 2260, 2261, -1, + 2829, 2828, 2254, -1, 2827, 1420, 2828, -1, + 2827, 1421, 1420, -1, 2827, 2826, 1422, -1, + 2827, 1422, 1421, -1, 2265, 2266, 1423, -1, + 2265, 1423, 1436, -1, 2265, 1436, 1424, -1, + 2265, 1424, 2267, -1, 2270, 2806, 2267, -1, + 2270, 2267, 1425, -1, 2270, 1426, 2269, -1, + 2270, 1425, 1426, -1, 1427, 1428, 1433, -1, + 1427, 1429, 1430, -1, 1427, 1431, 1429, -1, + 1427, 1433, 1431, -1, 1427, 1430, 1432, -1, + 1427, 1432, 1428, -1, 3216, 2843, 1433, -1, + 3216, 1434, 3217, -1, 3216, 1433, 1434, -1, + 2305, 2306, 2271, -1, 2842, 2839, 2849, -1, + 2845, 2848, 1435, -1, 2845, 1435, 1436, -1, + 2845, 1436, 1437, -1, 2845, 1437, 2846, -1, + 2276, 1442, 1441, -1, 2276, 1441, 2280, -1, + 2276, 1438, 1442, -1, 2276, 2277, 1438, -1, + 1439, 1440, 1441, -1, 1439, 1442, 1443, -1, + 1439, 1441, 1442, -1, 1439, 1443, 1444, -1, + 1439, 1444, 1445, -1, 1439, 1445, 1440, -1, + 1446, 1447, 1448, -1, 1446, 1448, 1449, -1, + 1446, 2282, 1447, -1, 1446, 1449, 1450, -1, + 1446, 1451, 2282, -1, 1446, 1450, 1451, -1, + 2286, 2282, 1451, -1, 2286, 1451, 1452, -1, + 2286, 1452, 2287, -1, 2289, 2288, 2804, -1, + 2289, 2804, 1453, -1, 2289, 1454, 2290, -1, + 2289, 1453, 1454, -1, 2296, 2292, 1455, -1, + 2296, 1455, 1456, -1, 2296, 1456, 2297, -1, + 1461, 1460, 1457, -1, 1461, 1458, 2306, -1, + 1461, 1459, 1458, -1, 1461, 1457, 1459, -1, + 2304, 2303, 2857, -1, 2304, 2857, 1460, -1, + 2304, 1461, 2306, -1, 2304, 1460, 1461, -1, + 1462, 2855, 2303, -1, 1462, 3215, 3217, -1, + 1462, 2303, 3215, -1, 1462, 3217, 1463, -1, + 1462, 2309, 2855, -1, 1462, 1463, 2309, -1, + 1464, 1490, 1478, -1, 1464, 1478, 1465, -1, + 1464, 1485, 1490, -1, 1464, 1465, 1466, -1, + 1464, 1467, 1485, -1, 1464, 1466, 1467, -1, + 2852, 2307, 1468, -1, 2852, 1468, 1469, -1, + 2852, 1469, 2853, -1, 1470, 1472, 1471, -1, + 1470, 1473, 2307, -1, 1470, 1474, 1473, -1, + 1470, 1471, 1474, -1, 1470, 2308, 1472, -1, + 1470, 2307, 2308, -1, 2864, 1560, 3248, -1, + 2864, 2860, 1560, -1, 1475, 1489, 2314, -1, + 1475, 2314, 2316, -1, 1475, 2316, 1476, -1, + 1475, 1476, 1477, -1, 1475, 1477, 1478, -1, + 1475, 1478, 1489, -1, 2318, 1479, 2863, -1, + 2318, 2317, 1482, -1, 2318, 1480, 1479, -1, + 2318, 1482, 1480, -1, 1491, 1482, 2317, -1, + 1491, 1490, 1485, -1, 1481, 1483, 1482, -1, + 1481, 1485, 1484, -1, 1481, 1491, 1485, -1, + 1481, 1482, 1491, -1, 1481, 1484, 1486, -1, + 1481, 1486, 1483, -1, 2891, 2320, 3236, -1, + 2312, 1487, 2313, -1, 2312, 2895, 1487, -1, + 2312, 3244, 2895, -1, 2312, 2315, 3244, -1, + 2324, 2314, 1489, -1, 2324, 2325, 2314, -1, + 1488, 2317, 2323, -1, 1488, 1489, 1490, -1, + 1488, 2324, 1489, -1, 1488, 2323, 2324, -1, + 1488, 1490, 1491, -1, 1488, 1491, 2317, -1, + 2322, 2320, 2891, -1, 1492, 1494, 1493, -1, + 1492, 1505, 1495, -1, 1492, 1496, 1505, -1, + 1492, 1493, 1496, -1, 1492, 1497, 1494, -1, + 1492, 1495, 1497, -1, 1498, 2243, 2244, -1, + 1498, 1499, 2243, -1, 1498, 2244, 1500, -1, + 1498, 1500, 1501, -1, 1498, 1501, 1502, -1, + 1498, 1502, 1499, -1, 1503, 1505, 1504, -1, + 1503, 1517, 1516, -1, 1503, 1504, 1506, -1, + 1503, 1506, 1517, -1, 1503, 1516, 1507, -1, + 1503, 1507, 1505, -1, 1508, 1725, 1724, -1, + 1508, 1513, 1509, -1, 1508, 1724, 1510, -1, + 1508, 1510, 1513, -1, 1508, 1511, 1725, -1, + 1508, 1509, 1511, -1, 1512, 1513, 1514, -1, + 1512, 1514, 1515, -1, 1512, 1515, 1516, -1, + 1512, 1516, 1517, -1, 1512, 1517, 1518, -1, + 1512, 1518, 1513, -1, 1519, 1520, 1521, -1, + 1519, 1521, 1522, -1, 1519, 1522, 1529, -1, + 1519, 1530, 1520, -1, 1519, 1529, 1530, -1, + 1523, 1533, 1524, -1, 1523, 1525, 2352, -1, + 1523, 2352, 1533, -1, 1523, 1526, 1525, -1, + 1523, 1527, 1526, -1, 1523, 1524, 1527, -1, + 1528, 1530, 1529, -1, 1528, 1529, 1534, -1, + 1528, 1531, 1530, -1, 1528, 1535, 1531, -1, + 1528, 1534, 1535, -1, 1532, 1533, 2898, -1, + 1532, 1535, 1534, -1, 1532, 1534, 1533, -1, + 1532, 2880, 1535, -1, 1532, 2898, 2899, -1, + 1532, 2899, 2880, -1, 2868, 2874, 2329, -1, + 2878, 2880, 2899, -1, 3224, 1536, 3223, -1, + 3224, 3221, 1537, -1, 3224, 1538, 1536, -1, + 3224, 1537, 1538, -1, 1539, 1540, 1541, -1, + 1539, 1542, 1543, -1, 1539, 1543, 1544, -1, + 1539, 1544, 1540, -1, 1539, 1545, 1542, -1, + 1539, 1541, 1545, -1, 2882, 1549, 2886, -1, + 2883, 2341, 2334, -1, 2331, 2334, 1546, -1, + 2331, 2177, 2332, -1, 2331, 1547, 2177, -1, + 2331, 1546, 1547, -1, 2333, 1549, 2882, -1, + 2333, 2882, 2884, -1, 2178, 2802, 1548, -1, + 2178, 2333, 2332, -1, 2178, 1548, 1549, -1, + 2178, 1549, 2333, -1, 2340, 1550, 2341, -1, + 2340, 2336, 1550, -1, 2340, 2342, 2336, -1, + 3228, 3249, 3250, -1, 3228, 2345, 3249, -1, + 3241, 2346, 2348, -1, 2350, 2349, 1551, -1, + 2350, 1551, 2337, -1, 2350, 2338, 3453, -1, + 2350, 2337, 2338, -1, 3254, 2351, 1552, -1, + 3254, 1552, 2353, -1, 2360, 1554, 1553, -1, + 2360, 2359, 1554, -1, 2360, 1553, 2356, -1, + 1555, 2327, 2326, -1, 1555, 2326, 1556, -1, + 1555, 1556, 1557, -1, 1555, 2902, 2327, -1, + 1555, 1557, 2903, -1, 1555, 2903, 2902, -1, + 2355, 1558, 2326, -1, 2355, 2354, 1558, -1, + 3247, 1559, 2896, -1, 3247, 1560, 1559, -1, + 3247, 3248, 1560, -1, 1561, 1562, 1572, -1, + 1561, 1572, 1576, -1, 1561, 1563, 1562, -1, + 1561, 1576, 1564, -1, 1561, 2073, 1563, -1, + 1561, 1564, 2073, -1, 1573, 1566, 1565, -1, + 1573, 1574, 1566, -1, 1573, 1565, 1567, -1, + 1573, 1567, 1576, -1, 2365, 1568, 2366, -1, + 2365, 1569, 1568, -1, 2365, 2083, 1569, -1, + 1570, 1572, 1571, -1, 1570, 1574, 1573, -1, + 1570, 1575, 1574, -1, 1570, 1571, 1575, -1, + 1570, 1576, 1572, -1, 1570, 1573, 1576, -1, + 2371, 2370, 1577, -1, 2371, 1577, 2780, -1, + 2777, 2139, 1584, -1, 2735, 1578, 2739, -1, + 2735, 1579, 1578, -1, 2735, 2734, 1579, -1, + 1586, 1585, 1580, -1, 1586, 1581, 2398, -1, + 1586, 1582, 1581, -1, 1586, 1580, 1582, -1, + 1583, 2398, 2778, -1, 1583, 2777, 1584, -1, + 1583, 2778, 2777, -1, 1583, 1584, 1585, -1, + 1583, 1585, 1586, -1, 1583, 1586, 2398, -1, + 2376, 1587, 2377, -1, 2376, 2402, 1587, -1, + 2376, 2917, 2916, -1, 2376, 2916, 2402, -1, + 2382, 3461, 2917, -1, 2374, 2379, 1588, -1, + 2374, 1589, 2373, -1, 2374, 1588, 1590, -1, + 2374, 1590, 1589, -1, 1591, 1592, 1593, -1, + 1591, 1716, 1715, -1, 1591, 1594, 1592, -1, + 1591, 1715, 1594, -1, 1591, 1595, 1716, -1, + 1591, 1593, 1595, -1, 1655, 2389, 1596, -1, + 1655, 1656, 2384, -1, 1655, 2384, 2389, -1, + 1655, 1596, 1653, -1, 2390, 2389, 2384, -1, + 2914, 1597, 2913, -1, 2914, 2922, 2392, -1, + 2914, 2392, 1597, -1, 2914, 2912, 2922, -1, + 1598, 1712, 1713, -1, 1598, 1709, 1712, -1, + 1598, 1713, 1599, -1, 1598, 1600, 1709, -1, + 1598, 1599, 1601, -1, 1598, 1601, 1600, -1, + 2394, 2395, 1602, -1, 2394, 1602, 1603, -1, + 2394, 1603, 2393, -1, 2394, 2924, 2395, -1, + 2921, 2402, 2916, -1, 1640, 1638, 1604, -1, + 1640, 1604, 1605, -1, 1640, 1605, 1606, -1, + 1640, 1606, 2425, -1, 1622, 1623, 1607, -1, + 1622, 1607, 1608, -1, 1622, 1629, 1625, -1, + 1622, 1608, 1629, -1, 2409, 1613, 2405, -1, + 2409, 1614, 1613, -1, 2409, 2410, 1614, -1, + 1609, 1610, 1611, -1, 1609, 1611, 1612, -1, + 1609, 1612, 1613, -1, 1609, 1613, 1614, -1, + 1609, 1614, 1615, -1, 1609, 1615, 1610, -1, + 1624, 1620, 1616, -1, 1624, 1616, 1617, -1, + 1624, 1617, 1618, -1, 1624, 1618, 1623, -1, + 1619, 1621, 1620, -1, 1619, 1623, 1622, -1, + 1619, 1624, 1623, -1, 1619, 1620, 1624, -1, + 1619, 1625, 1621, -1, 1619, 1622, 1625, -1, + 1626, 1627, 1628, -1, 1626, 1629, 1630, -1, + 1626, 1628, 1629, -1, 1626, 1630, 1631, -1, + 1626, 1631, 1632, -1, 1626, 1632, 1627, -1, + 2416, 2419, 1633, -1, 2416, 1633, 1634, -1, + 2416, 1634, 1635, -1, 2416, 1635, 2417, -1, + 2418, 1636, 2422, -1, 2418, 2422, 2423, -1, + 2418, 1637, 1636, -1, 2418, 2417, 1637, -1, + 2424, 1639, 1638, -1, 2424, 2422, 1639, -1, + 2424, 1638, 1640, -1, 2424, 1640, 2425, -1, + 2420, 2404, 2419, -1, 2420, 2423, 2930, -1, + 1641, 1643, 1642, -1, 1641, 1642, 1644, -1, + 1641, 2476, 1643, -1, 1641, 1644, 1645, -1, + 1641, 2475, 2476, -1, 1641, 1645, 2475, -1, + 2259, 2949, 2260, -1, 2259, 2941, 2942, -1, + 2950, 2259, 2942, -1, 2950, 2949, 2259, -1, + 2933, 1646, 2426, -1, 2933, 2934, 1646, -1, + 2945, 2946, 2414, -1, 2945, 2412, 2429, -1, + 2945, 2414, 2412, -1, 3272, 3336, 1647, -1, + 3272, 1647, 2431, -1, 3205, 1648, 2248, -1, + 3205, 2431, 1648, -1, 3207, 2433, 2953, -1, + 1654, 1649, 1656, -1, 1654, 1659, 1649, -1, + 1654, 1652, 1658, -1, 1654, 1658, 1659, -1, + 1650, 1651, 1652, -1, 1650, 1653, 1651, -1, + 1650, 1652, 1654, -1, 1650, 1655, 1653, -1, + 1650, 1656, 1655, -1, 1650, 1654, 1656, -1, + 1657, 1659, 1658, -1, 1657, 1926, 2646, -1, + 1657, 2646, 1659, -1, 1657, 1660, 1926, -1, + 1657, 1661, 1660, -1, 1657, 1658, 1661, -1, + 1662, 2246, 1663, -1, 1662, 1663, 1664, -1, + 1662, 1664, 1665, -1, 1662, 1665, 1666, -1, + 1662, 1666, 1667, -1, 1662, 1667, 2246, -1, + 2955, 2435, 1668, -1, 2955, 1668, 2450, -1, + 2955, 2450, 2956, -1, 2960, 3279, 2444, -1, + 2960, 1669, 2959, -1, 2960, 1670, 1669, -1, + 2960, 2444, 1670, -1, 3278, 1671, 2438, -1, + 3278, 2959, 1671, -1, 2443, 2441, 2445, -1, + 2443, 2449, 2451, -1, 2447, 1672, 2448, -1, + 2447, 1928, 1672, -1, 2447, 2450, 1673, -1, + 2447, 1673, 1928, -1, 1674, 1675, 1680, -1, + 1674, 1676, 1675, -1, 1674, 2453, 1676, -1, + 1674, 2461, 2453, -1, 1674, 1680, 1681, -1, + 1674, 1681, 2461, -1, 2462, 2458, 2452, -1, + 2466, 1682, 2467, -1, 2466, 2470, 1681, -1, + 1677, 1679, 1678, -1, 1677, 1680, 1679, -1, + 1677, 1681, 1680, -1, 1677, 2466, 1681, -1, + 1677, 1678, 1682, -1, 1677, 1682, 2466, -1, + 2487, 1721, 1683, -1, 2487, 1684, 2491, -1, + 2487, 1683, 1684, -1, 2473, 1685, 1850, -1, + 2473, 2478, 1685, -1, 1686, 1843, 1687, -1, + 1686, 1687, 1691, -1, 1686, 1691, 1693, -1, + 1686, 3047, 1843, -1, 1686, 1693, 2586, -1, + 1686, 2586, 3047, -1, 1688, 1689, 1690, -1, + 1688, 1691, 1689, -1, 1688, 1690, 1692, -1, + 1688, 1693, 1691, -1, 1688, 1692, 1694, -1, + 1688, 1694, 1693, -1, 1695, 1697, 1696, -1, + 1695, 1696, 1703, -1, 1695, 1703, 1705, -1, + 1695, 1698, 1697, -1, 1695, 1705, 1699, -1, + 1695, 1699, 1698, -1, 1700, 1702, 1701, -1, + 1700, 1703, 1702, -1, 1700, 1701, 1704, -1, + 1700, 1704, 1705, -1, 1700, 1705, 1703, -1, + 2480, 2481, 1711, -1, 2480, 1711, 1706, -1, + 2480, 1707, 2484, -1, 2480, 1706, 1707, -1, + 1719, 1717, 1712, -1, 1719, 1708, 1715, -1, + 1719, 1709, 1708, -1, 1719, 1712, 1709, -1, + 1710, 1711, 2481, -1, 1710, 1717, 1711, -1, + 1710, 2481, 2489, -1, 1710, 1712, 1717, -1, + 1710, 2489, 1713, -1, 1710, 1713, 1712, -1, + 1714, 1715, 1716, -1, 1714, 1718, 1717, -1, + 1714, 1719, 1715, -1, 1714, 1717, 1719, -1, + 1714, 1716, 1720, -1, 1714, 1720, 1718, -1, + 2486, 1722, 1721, -1, 2486, 2482, 1722, -1, + 2486, 2490, 2482, -1, 2486, 1721, 2487, -1, + 1723, 1724, 1725, -1, 1723, 1725, 1726, -1, + 1723, 1726, 2497, -1, 1723, 2497, 2493, -1, + 1723, 1731, 1724, -1, 1723, 2493, 1731, -1, + 1727, 1728, 1729, -1, 1727, 2493, 2494, -1, + 1727, 1730, 1728, -1, 1727, 2494, 1730, -1, + 1727, 1729, 1731, -1, 1727, 1731, 2493, -1, + 2966, 1732, 1733, -1, 2966, 2504, 1732, -1, + 2966, 1733, 2967, -1, 2498, 3527, 3203, -1, + 2498, 3203, 1734, -1, 2498, 1735, 2499, -1, + 2498, 1734, 1735, -1, 2503, 2499, 1736, -1, + 2503, 1736, 2504, -1, 3553, 2500, 2212, -1, + 2964, 2504, 2966, -1, 3304, 3306, 3296, -1, + 2506, 2502, 3283, -1, 2506, 1737, 2502, -1, + 2506, 2507, 1737, -1, 2970, 2508, 2969, -1, + 2970, 1738, 2508, -1, 2970, 2971, 1738, -1, + 3561, 3493, 3478, -1, 3482, 3481, 1739, -1, + 3482, 1739, 1740, -1, 3482, 1740, 2971, -1, + 1741, 1743, 1742, -1, 1741, 1744, 1743, -1, + 1741, 1742, 1745, -1, 1741, 1746, 1744, -1, + 1741, 1745, 1747, -1, 1741, 1747, 1746, -1, + 1748, 1750, 1749, -1, 1748, 1749, 1751, -1, + 1748, 1752, 1750, -1, 1748, 1753, 1752, -1, + 1748, 1751, 1753, -1, 1756, 3312, 1754, -1, + 1756, 1824, 1755, -1, 1756, 2565, 1824, -1, + 1756, 1754, 2565, -1, 3319, 2512, 2510, -1, + 3501, 1755, 3499, -1, 3501, 3312, 1756, -1, + 3501, 1756, 1755, -1, 2983, 3314, 1757, -1, + 2983, 1757, 2511, -1, 2987, 2194, 2513, -1, + 2987, 2989, 2193, -1, 2987, 2193, 2194, -1, + 1758, 2513, 2194, -1, 1758, 1760, 1759, -1, + 1758, 1759, 1761, -1, 1758, 1761, 2513, -1, + 1758, 2194, 2195, -1, 1758, 2195, 1760, -1, + 1762, 2531, 2517, -1, 1762, 3330, 2197, -1, + 1762, 2197, 2196, -1, 1762, 2196, 2531, -1, + 1762, 3018, 3330, -1, 1762, 2517, 3018, -1, + 2521, 3018, 2517, -1, 3023, 3018, 2521, -1, + 2996, 2200, 2523, -1, 1763, 1764, 1765, -1, + 1763, 1765, 1768, -1, 1763, 1766, 1764, -1, + 1763, 1768, 1766, -1, 1767, 1769, 1768, -1, + 1767, 1770, 1769, -1, 1767, 1768, 1771, -1, + 1767, 1771, 1770, -1, 2528, 2529, 1775, -1, + 2527, 2528, 2535, -1, 2527, 2524, 2532, -1, + 1772, 1773, 2534, -1, 1772, 1774, 1773, -1, + 1772, 1775, 1774, -1, 1772, 2528, 1775, -1, + 1772, 2534, 2535, -1, 1772, 2535, 2528, -1, + 2536, 1776, 1783, -1, 2536, 1783, 2537, -1, + 2536, 1777, 1776, -1, 2536, 2534, 1777, -1, + 1778, 1779, 2537, -1, 1778, 1780, 1781, -1, + 1778, 1781, 1782, -1, 1778, 1782, 1779, -1, + 1778, 1783, 1780, -1, 1778, 2537, 1783, -1, + 1784, 1785, 1786, -1, 1784, 1787, 1785, -1, + 1784, 1786, 1788, -1, 1784, 1788, 1787, -1, + 1790, 1792, 1789, -1, 1790, 1789, 1791, -1, + 3002, 1790, 1791, -1, 3002, 1791, 2541, -1, + 3002, 3000, 1792, -1, 3002, 1792, 1790, -1, + 3009, 2541, 3005, -1, 3009, 3010, 2541, -1, + 1797, 1794, 1798, -1, 1797, 1793, 1794, -1, + 1797, 2525, 1793, -1, 1797, 2518, 2525, -1, + 2999, 1794, 3003, -1, 2999, 1798, 1794, -1, + 2999, 2540, 1798, -1, 3017, 1795, 3016, -1, + 3017, 1796, 1795, -1, 3017, 3020, 1796, -1, + 2544, 2553, 2546, -1, 2544, 2551, 2553, -1, + 2544, 3022, 2548, -1, 2544, 2548, 2551, -1, + 1799, 2549, 2520, -1, 1799, 1797, 1798, -1, + 1799, 2520, 2518, -1, 1799, 2518, 1797, -1, + 2550, 1798, 2540, -1, 2550, 2540, 3011, -1, + 2550, 1799, 1798, -1, 2550, 2549, 1799, -1, + 2555, 2553, 2551, -1, 2555, 3013, 2556, -1, + 1800, 1802, 1801, -1, 1800, 1803, 1802, -1, + 1800, 1804, 1803, -1, 1800, 1805, 1804, -1, + 1800, 1806, 1805, -1, 1800, 1801, 1806, -1, + 1807, 1808, 1809, -1, 1807, 1809, 1810, -1, + 1807, 1811, 1808, -1, 1807, 1810, 1812, -1, + 1807, 1812, 1811, -1, 2561, 1813, 1823, -1, + 2561, 2563, 1814, -1, 2561, 1814, 1813, -1, + 1815, 1817, 1816, -1, 1815, 1818, 1817, -1, + 1815, 1819, 1818, -1, 1815, 1820, 1819, -1, + 1815, 1821, 1820, -1, 1815, 1816, 1821, -1, + 2560, 1823, 1822, -1, 2560, 2561, 1823, -1, + 2560, 1824, 2565, -1, 2560, 1822, 1824, -1, + 3029, 2568, 2566, -1, 1825, 1826, 1827, -1, + 1825, 1827, 1828, -1, 1825, 1828, 1829, -1, + 1825, 1830, 1826, -1, 1825, 1831, 1830, -1, + 1825, 1829, 1831, -1, 1837, 1832, 3039, -1, + 1837, 1836, 1833, -1, 1837, 1833, 1834, -1, + 1837, 1834, 1832, -1, 2570, 1835, 1836, -1, + 2570, 1836, 1837, -1, 2570, 1837, 3039, -1, + 2570, 3027, 1835, -1, 2572, 1839, 1838, -1, + 2572, 2577, 1840, -1, 2572, 1840, 1839, -1, + 2572, 1838, 2573, -1, 2579, 2584, 1841, -1, + 2579, 1841, 2052, -1, 2587, 2586, 1842, -1, + 2587, 1842, 2585, -1, 2588, 1843, 3048, -1, + 2588, 1844, 1843, -1, 2588, 1845, 1844, -1, + 2588, 3052, 1845, -1, 1846, 1847, 1848, -1, + 1846, 1848, 2474, -1, 1846, 1849, 1847, -1, + 1846, 2474, 2473, -1, 1846, 1850, 1849, -1, + 1846, 2473, 1850, -1, 3057, 2593, 2590, -1, + 1851, 1853, 1852, -1, 1851, 1854, 1853, -1, + 1851, 1855, 1854, -1, 1851, 1856, 1855, -1, + 1851, 1857, 1856, -1, 1851, 1852, 1857, -1, + 1858, 1860, 1859, -1, 1858, 2563, 2562, -1, + 1858, 2562, 1860, -1, 1858, 1861, 2563, -1, + 1858, 1862, 1861, -1, 1858, 1859, 1862, -1, + 1863, 1864, 1865, -1, 1863, 1866, 1867, -1, + 1863, 1867, 1868, -1, 1863, 1868, 1864, -1, + 1863, 1869, 1866, -1, 1863, 1865, 1869, -1, + 1870, 1872, 1871, -1, 1870, 2599, 1873, -1, + 1870, 2601, 2599, -1, 1870, 1871, 2601, -1, + 1870, 1873, 1874, -1, 1870, 1874, 1872, -1, + 2608, 2603, 1875, -1, 2608, 1875, 2613, -1, + 2610, 2611, 1876, -1, 2610, 1876, 2596, -1, + 3064, 1877, 2616, -1, 3064, 2617, 1877, -1, + 1882, 1878, 1887, -1, 1882, 3066, 1878, -1, + 1882, 3068, 3066, -1, 1882, 1881, 3068, -1, + 1879, 1887, 1889, -1, 1879, 1880, 1881, -1, + 1879, 1881, 1882, -1, 1879, 1882, 1887, -1, + 1879, 1889, 1883, -1, 1879, 1883, 1880, -1, + 1884, 1885, 1886, -1, 1884, 1887, 1885, -1, + 1884, 1886, 1888, -1, 1884, 1889, 1887, -1, + 1884, 1890, 1889, -1, 1884, 1888, 1890, -1, + 1897, 1898, 1891, -1, 1897, 1891, 1892, -1, + 1897, 1892, 1893, -1, 1897, 1893, 1896, -1, + 1894, 1896, 1895, -1, 1894, 1898, 1897, -1, + 1894, 1897, 1896, -1, 1894, 1899, 1898, -1, + 1894, 1900, 1899, -1, 1894, 1895, 1900, -1, + 3079, 3081, 1901, -1, 3079, 1902, 3078, -1, + 3079, 1901, 1903, -1, 3079, 1903, 1902, -1, + 3353, 2620, 3069, -1, 3350, 1904, 3349, -1, + 3350, 3078, 1905, -1, 3350, 1905, 1904, -1, + 3348, 3078, 3350, -1, 3505, 1906, 3084, -1, + 3505, 3506, 1906, -1, 2626, 1908, 2627, -1, + 2626, 1919, 1908, -1, 2626, 2628, 1920, -1, + 2626, 1920, 1919, -1, 1915, 3089, 1909, -1, + 1915, 3087, 3089, -1, 1915, 1916, 3087, -1, + 1915, 1909, 1914, -1, 1907, 2627, 1908, -1, + 1907, 1908, 1909, -1, 1907, 1909, 3089, -1, + 1907, 1910, 2627, -1, 1907, 3089, 3088, -1, + 1907, 3088, 1910, -1, 2632, 2630, 1925, -1, + 2632, 1925, 1924, -1, 2632, 1924, 2633, -1, + 1937, 1910, 1935, -1, 1937, 2659, 1911, -1, + 1937, 1911, 2629, -1, 1937, 2629, 1910, -1, + 1912, 2134, 2137, -1, 1912, 1913, 2134, -1, + 1912, 1914, 1913, -1, 1912, 1915, 1914, -1, + 1912, 2137, 1916, -1, 1912, 1916, 1915, -1, + 1917, 1918, 1919, -1, 1917, 1920, 1921, -1, + 1917, 1919, 1920, -1, 1917, 1921, 1922, -1, + 1917, 1922, 1923, -1, 1917, 1923, 1918, -1, + 3360, 1924, 1925, -1, 3360, 2637, 1924, -1, + 3360, 1925, 3361, -1, 2643, 1926, 2641, -1, + 2643, 2646, 1926, -1, 2648, 2641, 1927, -1, + 2648, 1927, 2651, -1, 2648, 2640, 2641, -1, + 2648, 2649, 2640, -1, 2650, 1928, 1929, -1, + 2650, 2652, 1928, -1, 2650, 1929, 2636, -1, + 2650, 2636, 2649, -1, 2656, 1930, 3102, -1, + 2656, 1934, 1931, -1, 2656, 1931, 1930, -1, + 2655, 1933, 1932, -1, 2655, 2654, 1933, -1, + 2655, 1932, 1934, -1, 2655, 1934, 2656, -1, + 2658, 1935, 1936, -1, 2658, 1936, 2661, -1, + 2658, 1937, 1935, -1, 2658, 2659, 1937, -1, + 2660, 1938, 2659, -1, 2660, 1939, 1938, -1, + 2660, 2662, 1940, -1, 2660, 1940, 1939, -1, + 3074, 3349, 1941, -1, 3074, 1941, 1942, -1, + 3074, 1942, 2624, -1, 3074, 2624, 3356, -1, + 1943, 1944, 1945, -1, 1943, 1945, 1946, -1, + 1943, 1947, 1944, -1, 1943, 1950, 1947, -1, + 1943, 1946, 1948, -1, 1943, 1948, 3110, -1, + 1943, 3110, 1950, -1, 1949, 1951, 1950, -1, + 1949, 1953, 1952, -1, 1949, 1952, 1951, -1, + 1949, 1954, 1953, -1, 1949, 3111, 1954, -1, + 1949, 1950, 3111, -1, 2667, 1955, 2670, -1, + 2667, 1956, 1955, -1, 2667, 2666, 1957, -1, + 2667, 1957, 1956, -1, 1958, 1960, 1959, -1, + 1958, 1961, 1960, -1, 1958, 1962, 1961, -1, + 1958, 1963, 1962, -1, 1958, 1959, 1963, -1, + 2673, 2671, 2669, -1, 2673, 2669, 1964, -1, + 2673, 1964, 2674, -1, 1965, 1967, 1966, -1, + 1965, 1968, 1967, -1, 1965, 2675, 1968, -1, + 1965, 2684, 2675, -1, 1965, 2685, 2684, -1, + 1965, 1966, 2685, -1, 1969, 1971, 1970, -1, + 1969, 1970, 1974, -1, 1969, 1974, 1975, -1, + 1969, 1975, 1972, -1, 1969, 1972, 1971, -1, + 2682, 1973, 2680, -1, 2682, 1974, 1973, -1, + 2682, 1975, 1974, -1, 2682, 2683, 1975, -1, + 1976, 1977, 1986, -1, 1976, 1979, 1978, -1, + 1976, 1978, 1980, -1, 1976, 1980, 1977, -1, + 1976, 1985, 1979, -1, 1976, 1986, 1985, -1, + 1981, 1982, 1983, -1, 1981, 1984, 1985, -1, + 1981, 1985, 1986, -1, 1981, 1986, 1982, -1, + 1981, 1983, 1987, -1, 1981, 1987, 1984, -1, + 1988, 1990, 1989, -1, 1988, 2618, 1990, -1, + 1988, 2617, 2618, -1, 1988, 1991, 2617, -1, + 1988, 1992, 1991, -1, 1988, 1989, 1992, -1, + 1993, 1994, 2686, -1, 1993, 1995, 1994, -1, + 1993, 2686, 2685, -1, 1993, 2685, 1995, -1, + 3380, 1996, 3105, -1, 3380, 3382, 1997, -1, + 3380, 1997, 1996, -1, 3103, 1998, 1999, -1, + 3103, 1999, 2000, -1, 3103, 2000, 3104, -1, + 3103, 3105, 1998, -1, 2691, 2690, 2145, -1, + 2691, 2758, 2692, -1, 2689, 2145, 2690, -1, + 2689, 2000, 2145, -1, 2689, 3104, 2000, -1, + 2689, 2690, 3371, -1, 3108, 3109, 2693, -1, + 3385, 2001, 3389, -1, 3385, 2695, 2001, -1, + 3374, 3373, 2002, -1, 3374, 2002, 3070, -1, + 3374, 2003, 3375, -1, 3374, 3070, 2003, -1, + 2004, 2005, 2006, -1, 2004, 2008, 2007, -1, + 2004, 2009, 2005, -1, 2004, 2007, 2009, -1, + 2004, 2006, 2010, -1, 2004, 2010, 2011, -1, + 2004, 2011, 2008, -1, 2702, 2701, 2012, -1, + 2702, 2012, 2013, -1, 2702, 2013, 2014, -1, + 2702, 2014, 2703, -1, 2700, 2015, 2016, -1, + 2700, 2016, 2701, -1, 2700, 2709, 2718, -1, + 2700, 2718, 2015, -1, 2715, 2718, 2709, -1, + 2017, 2026, 3119, -1, 2017, 3119, 3124, -1, + 2017, 2018, 2026, -1, 2017, 3124, 3123, -1, + 2017, 3123, 2128, -1, 2017, 2128, 2018, -1, + 2019, 2021, 2020, -1, 2019, 2723, 2022, -1, + 2019, 2020, 2721, -1, 2019, 2721, 2723, -1, + 2019, 2023, 2021, -1, 2019, 2022, 2023, -1, + 2722, 2721, 2024, -1, 2722, 2024, 2025, -1, + 2722, 2036, 3122, -1, 2722, 2025, 2036, -1, + 3116, 2026, 2724, -1, 3116, 3119, 2026, -1, + 2027, 2028, 2029, -1, 2027, 2035, 2028, -1, + 2027, 2029, 2030, -1, 2027, 2031, 3396, -1, + 2027, 3396, 2035, -1, 2027, 2030, 2032, -1, + 2027, 2032, 2033, -1, 2027, 2033, 2031, -1, + 2034, 2035, 3394, -1, 2034, 3122, 2036, -1, + 2034, 3394, 3122, -1, 2034, 2036, 2037, -1, + 2034, 2037, 2038, -1, 2034, 2038, 2035, -1, + 2039, 2040, 2728, -1, 2039, 2041, 2040, -1, + 2039, 2728, 2047, -1, 2039, 2047, 2041, -1, + 2042, 2726, 2720, -1, 2042, 2720, 2043, -1, + 2042, 2044, 2726, -1, 2042, 2043, 2044, -1, + 2045, 3127, 3128, -1, 2045, 2727, 3127, -1, + 2045, 3128, 2046, -1, 2045, 2047, 2727, -1, + 2045, 2046, 2047, -1, 2051, 2052, 2048, -1, + 2051, 2048, 2050, -1, 2049, 2050, 2057, -1, + 2049, 2057, 2054, -1, 2049, 2054, 2580, -1, + 2049, 2051, 2050, -1, 2049, 2052, 2051, -1, + 2049, 2579, 2052, -1, 2049, 2580, 2579, -1, + 2053, 2055, 2054, -1, 2053, 2056, 2704, -1, + 2053, 2054, 2057, -1, 2053, 2057, 2056, -1, + 2053, 2058, 2055, -1, 2053, 2704, 2058, -1, + 2067, 2066, 2059, -1, 2067, 2059, 2060, -1, + 2067, 2061, 2068, -1, 2067, 2060, 2061, -1, + 2062, 2063, 2064, -1, 2062, 2064, 2065, -1, + 2062, 2065, 2066, -1, 2062, 2066, 2067, -1, + 2062, 2068, 2063, -1, 2062, 2067, 2068, -1, + 2069, 2071, 2070, -1, 2069, 2070, 2072, -1, + 2069, 2073, 2071, -1, 2069, 2072, 2073, -1, + 2730, 2074, 2731, -1, 2730, 2741, 2074, -1, + 2730, 2739, 2741, -1, 2730, 2735, 2739, -1, + 2737, 2738, 2075, -1, 2737, 2075, 2076, -1, + 2737, 2077, 2741, -1, 2737, 2076, 2077, -1, + 2078, 2698, 3112, -1, 2078, 2079, 2698, -1, + 2078, 3112, 2080, -1, 2078, 2080, 2079, -1, + 2756, 2755, 2745, -1, 2756, 2745, 2151, -1, + 2756, 2151, 3139, -1, 2756, 3139, 3140, -1, + 2744, 2745, 2755, -1, 2744, 2364, 2748, -1, + 2367, 2363, 2081, -1, 2367, 2082, 2083, -1, + 2367, 2081, 2082, -1, 2367, 2083, 2365, -1, + 3137, 2744, 2755, -1, 3137, 2364, 2744, -1, + 2754, 2761, 3423, -1, 3192, 2152, 3193, -1, + 3192, 3147, 2152, -1, 3194, 3195, 3145, -1, + 3194, 3147, 3192, -1, 2146, 2145, 2084, -1, + 2146, 2084, 3434, -1, 2146, 3434, 3141, -1, + 2146, 3141, 3154, -1, 2153, 2085, 2151, -1, + 2153, 2152, 3147, -1, 2153, 3147, 3153, -1, + 2153, 3153, 2085, -1, 3431, 2697, 2086, -1, + 3431, 2086, 3432, -1, 3431, 2696, 2697, -1, + 3431, 3433, 2696, -1, 2087, 2089, 2088, -1, + 2087, 2088, 2092, -1, 2087, 2106, 2090, -1, + 2087, 2090, 2089, -1, 2087, 2105, 2106, -1, + 2087, 2092, 2094, -1, 2087, 2094, 2105, -1, + 2759, 2091, 3427, -1, 2759, 2094, 2092, -1, + 2759, 2092, 2091, -1, 2760, 2751, 2093, -1, + 2760, 2761, 2751, -1, 2760, 2093, 2094, -1, + 2760, 2094, 2759, -1, 2103, 2102, 2095, -1, + 2103, 2096, 2101, -1, 2103, 2095, 2097, -1, + 2103, 2097, 2096, -1, 3136, 2098, 2363, -1, + 3136, 3138, 2098, -1, 3136, 2363, 2364, -1, + 3136, 2364, 3137, -1, 2099, 2100, 3138, -1, + 2099, 2101, 2100, -1, 2099, 3426, 2102, -1, + 2099, 3138, 3426, -1, 2099, 2103, 2101, -1, + 2099, 2102, 2103, -1, 2104, 2106, 2105, -1, + 2104, 2105, 2107, -1, 2104, 2114, 2106, -1, + 2104, 2107, 2114, -1, 2111, 2125, 2126, -1, + 2111, 2110, 2108, -1, 2111, 2108, 2109, -1, + 2111, 2109, 2125, -1, 2115, 2113, 2110, -1, + 2115, 2126, 3415, -1, 2115, 2111, 2126, -1, + 2115, 2110, 2111, -1, 2112, 2114, 2113, -1, + 2112, 2113, 2115, -1, 2112, 2115, 3415, -1, + 2112, 3415, 3413, -1, 2112, 3413, 2114, -1, + 3170, 2764, 3174, -1, 3417, 3513, 2116, -1, + 3417, 2116, 2767, -1, 2117, 2118, 2119, -1, + 2117, 2120, 2118, -1, 2117, 2119, 2121, -1, + 2117, 2121, 2120, -1, 2127, 2122, 2763, -1, + 2127, 2125, 2123, -1, 2127, 2124, 2122, -1, + 2127, 2123, 2124, -1, 2762, 2126, 2125, -1, + 2762, 3416, 2126, -1, 2762, 2125, 2127, -1, + 2762, 2127, 2763, -1, 3175, 3174, 2128, -1, + 3175, 3123, 3168, -1, 3175, 2128, 3123, -1, + 3439, 3436, 2135, -1, 3439, 2135, 2129, -1, + 3439, 2129, 3440, -1, 2768, 2130, 2769, -1, + 2768, 3181, 2141, -1, 2768, 2131, 2130, -1, + 2768, 2141, 2131, -1, 3178, 2132, 2771, -1, + 3178, 3182, 2133, -1, 3178, 2133, 2132, -1, + 3187, 3186, 3366, -1, 3187, 3362, 3188, -1, + 2774, 2134, 2135, -1, 2774, 2775, 2134, -1, + 2774, 3436, 3521, -1, 2774, 2135, 3436, -1, + 2136, 2137, 2775, -1, 2136, 2138, 2137, -1, + 2136, 3188, 3362, -1, 2136, 2775, 3188, -1, + 2136, 3362, 3361, -1, 2136, 3361, 2138, -1, + 2391, 2388, 2372, -1, 2391, 2390, 2388, -1, + 2781, 2780, 2139, -1, 2781, 2139, 2777, -1, + 2911, 2371, 2780, -1, 2911, 2910, 2371, -1, + 2140, 3093, 2141, -1, 2140, 2141, 2773, -1, + 2140, 2773, 2142, -1, 2140, 3094, 3093, -1, + 2140, 2644, 3094, -1, 2140, 2142, 2644, -1, + 3151, 3150, 2143, -1, 3151, 2144, 2758, -1, + 3151, 2143, 2144, -1, 2757, 2691, 2145, -1, + 2757, 2758, 2691, -1, 2757, 2145, 2146, -1, + 2757, 2146, 3154, -1, 2149, 2152, 2746, -1, + 2149, 2148, 2782, -1, 2149, 2782, 2784, -1, + 2149, 3193, 2152, -1, 2149, 2784, 3193, -1, + 3443, 2784, 2782, -1, 2147, 2158, 2148, -1, + 2147, 2746, 2747, -1, 2147, 2148, 2149, -1, + 2147, 2149, 2746, -1, 2147, 2150, 2158, -1, + 2147, 2747, 2150, -1, 2749, 2151, 2745, -1, + 2749, 2746, 2152, -1, 2749, 2153, 2151, -1, + 2749, 2152, 2153, -1, 3198, 3182, 3180, -1, + 3198, 3180, 3199, -1, 3198, 2157, 3182, -1, + 2785, 2160, 2794, -1, 2785, 3199, 2770, -1, + 2785, 2770, 2154, -1, 2785, 2154, 2160, -1, + 3197, 3201, 2155, -1, 3197, 2155, 2156, -1, + 3197, 2156, 2157, -1, 3197, 2157, 3198, -1, + 2793, 2787, 2158, -1, 2793, 2158, 2159, -1, + 2793, 2159, 2791, -1, 2788, 2795, 2160, -1, + 2788, 2160, 2161, -1, 2788, 2161, 2162, -1, + 2788, 2162, 2789, -1, 2163, 2165, 2164, -1, + 2163, 2167, 2166, -1, 2163, 2166, 2165, -1, + 2163, 2168, 2167, -1, 2163, 2169, 2168, -1, + 2163, 2164, 2169, -1, 2170, 2172, 2171, -1, + 2170, 2173, 2172, -1, 2170, 2171, 2174, -1, + 2170, 2175, 2173, -1, 2170, 2174, 2176, -1, + 2170, 2176, 2175, -1, 2798, 2177, 2799, -1, + 2798, 2332, 2177, -1, 2798, 2802, 2178, -1, + 2798, 2178, 2332, -1, 2179, 2180, 2181, -1, + 2179, 2181, 2189, -1, 2179, 2182, 2180, -1, + 2179, 2189, 2187, -1, 2179, 2183, 2182, -1, + 2179, 2187, 2183, -1, 2184, 2185, 2186, -1, + 2184, 2188, 2187, -1, 2184, 2186, 2188, -1, + 2184, 2187, 2189, -1, 2184, 2189, 2190, -1, + 2184, 2190, 2191, -1, 2184, 2191, 2185, -1, + 2192, 2194, 2193, -1, 2192, 2195, 2194, -1, + 2192, 2193, 2196, -1, 2192, 2522, 2195, -1, + 2192, 2196, 2197, -1, 2192, 2197, 2522, -1, + 2203, 2198, 2202, -1, 2203, 2512, 2198, -1, + 2203, 2510, 2512, -1, 2203, 2994, 2510, -1, + 2199, 2201, 2200, -1, 2199, 2202, 2201, -1, + 2199, 2200, 2996, -1, 2199, 2203, 2202, -1, + 2199, 2996, 2994, -1, 2199, 2994, 2203, -1, + 2209, 2832, 2204, -1, 2209, 2204, 2205, -1, + 2209, 2205, 2206, -1, 2209, 2206, 2208, -1, + 2831, 2207, 2835, -1, 2831, 2208, 2207, -1, + 2831, 2209, 2208, -1, 2831, 2832, 2209, -1, + 3202, 2807, 2210, -1, 3202, 2211, 3203, -1, + 3202, 2210, 2211, -1, 3552, 3553, 2212, -1, + 3552, 2212, 2213, -1, 3552, 2213, 2807, -1, + 2809, 2214, 2810, -1, 2809, 2215, 2214, -1, + 2809, 2813, 2216, -1, 2809, 2216, 2215, -1, + 2217, 2226, 2218, -1, 2217, 2220, 2219, -1, + 2217, 2218, 2220, -1, 2217, 2219, 2221, -1, + 2217, 2221, 2222, -1, 2217, 2222, 2226, -1, + 2223, 2225, 2224, -1, 2223, 2224, 2226, -1, + 2223, 2227, 2225, -1, 2223, 2228, 2227, -1, + 2223, 2229, 2228, -1, 2223, 2230, 2229, -1, + 2223, 2226, 2230, -1, 2231, 2232, 2233, -1, + 2231, 2235, 2234, -1, 2231, 2233, 2235, -1, + 2231, 2234, 2236, -1, 2231, 2236, 2237, -1, + 2231, 2237, 2232, -1, 2238, 2240, 2239, -1, + 2238, 2242, 2241, -1, 2238, 2241, 2240, -1, + 2238, 2243, 2242, -1, 2238, 2244, 2243, -1, + 2238, 2239, 2244, -1, 2943, 2940, 2249, -1, + 2943, 2249, 2248, -1, 2943, 2248, 2245, -1, + 2943, 2245, 2939, -1, 2815, 2246, 2816, -1, + 2815, 2822, 2247, -1, 2815, 2247, 2246, -1, + 3204, 2248, 2249, -1, 3204, 3205, 2248, -1, + 3210, 2822, 2815, -1, 2819, 2249, 2820, -1, + 2819, 3204, 2249, -1, 2250, 2251, 2252, -1, + 2250, 2253, 2251, -1, 2250, 2254, 2253, -1, + 2250, 2252, 2262, -1, 2250, 2262, 2829, -1, + 2250, 2829, 2254, -1, 2255, 2256, 2257, -1, + 2255, 2258, 2941, -1, 2255, 2257, 2258, -1, + 2255, 2941, 2259, -1, 2255, 2260, 2256, -1, + 2255, 2259, 2260, -1, 2824, 2262, 2261, -1, + 2824, 2829, 2262, -1, 2824, 2261, 2263, -1, + 2824, 2263, 2825, -1, 2264, 2266, 2265, -1, + 2264, 2806, 2805, -1, 2264, 2267, 2806, -1, + 2264, 2265, 2267, -1, 2264, 2805, 2268, -1, + 2264, 2268, 2266, -1, 2833, 2269, 2832, -1, + 2833, 2270, 2269, -1, 2833, 2806, 2270, -1, + 2274, 2305, 2271, -1, 2274, 2272, 2841, -1, + 2274, 2273, 2272, -1, 2274, 2271, 2273, -1, + 2840, 2274, 2841, -1, 2840, 2305, 2274, -1, + 2840, 3213, 3212, -1, 2840, 3212, 2305, -1, + 2847, 2846, 2843, -1, 2847, 2842, 2849, -1, + 2275, 2277, 2276, -1, 2275, 2279, 2278, -1, + 2275, 2280, 2279, -1, 2275, 2276, 2280, -1, + 2275, 2281, 2277, -1, 2275, 2278, 2281, -1, + 2291, 2282, 2286, -1, 2291, 2290, 2283, -1, + 2291, 2284, 2282, -1, 2291, 2283, 2284, -1, + 2285, 2286, 2287, -1, 2285, 2287, 2288, -1, + 2285, 2288, 2289, -1, 2285, 2289, 2290, -1, + 2285, 2290, 2291, -1, 2285, 2291, 2286, -1, + 2300, 2292, 2296, -1, 2300, 2293, 2292, -1, + 2300, 2294, 2293, -1, 2300, 2298, 2294, -1, + 2295, 2296, 2297, -1, 2295, 2299, 2298, -1, + 2295, 2298, 2300, -1, 2295, 2300, 2296, -1, + 2295, 2301, 2299, -1, 2295, 2297, 2301, -1, + 2302, 3215, 2303, -1, 2302, 2303, 2304, -1, + 2302, 3212, 3215, -1, 2302, 2305, 3212, -1, + 2302, 2306, 2305, -1, 2302, 2304, 2306, -1, + 2854, 2308, 2307, -1, 2854, 2307, 2852, -1, + 2854, 2309, 2308, -1, 2854, 2855, 2309, -1, + 2310, 2864, 3248, -1, 2310, 2345, 2343, -1, + 2310, 2343, 2862, -1, 2310, 2862, 2864, -1, + 2310, 3248, 3249, -1, 2310, 3249, 2345, -1, + 2311, 2312, 2313, -1, 2311, 2314, 2325, -1, + 2311, 2325, 2315, -1, 2311, 2315, 2312, -1, + 2311, 2316, 2314, -1, 2311, 2313, 2316, -1, + 2319, 2322, 2323, -1, 2319, 2323, 2317, -1, + 2319, 2317, 2318, -1, 2319, 2318, 2863, -1, + 2861, 2319, 2863, -1, 2861, 2322, 2319, -1, + 2861, 2862, 2320, -1, 2861, 2320, 2322, -1, + 2321, 2323, 2322, -1, 2321, 2325, 2324, -1, + 2321, 2324, 2323, -1, 2321, 2892, 2325, -1, + 2321, 2891, 2892, -1, 2321, 2322, 2891, -1, + 2328, 2326, 2327, -1, 2328, 2355, 2326, -1, + 2328, 2329, 3258, -1, 2328, 3258, 2355, -1, + 3222, 3223, 2796, -1, 2869, 2327, 2870, -1, + 2869, 2328, 2327, -1, 2869, 2868, 2329, -1, + 2869, 2329, 2328, -1, 3257, 3258, 2329, -1, + 3257, 2329, 2874, -1, 2330, 2331, 2332, -1, + 2330, 2332, 2333, -1, 2330, 2334, 2331, -1, + 2330, 2333, 2884, -1, 2330, 2883, 2334, -1, + 2330, 2884, 2883, -1, 2335, 2342, 2338, -1, + 2335, 2354, 2353, -1, 2335, 2353, 2336, -1, + 2335, 2336, 2342, -1, 2335, 2337, 2354, -1, + 2335, 2338, 2337, -1, 3451, 3453, 2338, -1, + 3451, 2338, 2342, -1, 2339, 2340, 2341, -1, + 2339, 2341, 2883, -1, 2339, 2883, 3452, -1, + 2339, 2342, 2340, -1, 2339, 3452, 3451, -1, + 2339, 3451, 2342, -1, 2888, 2882, 2886, -1, + 2888, 3230, 2882, -1, 2888, 2889, 3229, -1, + 2888, 3229, 3230, -1, 3234, 3236, 2343, -1, + 3234, 2343, 2345, -1, 2344, 2889, 3235, -1, + 2344, 3229, 2889, -1, 2344, 3228, 3229, -1, + 2344, 2345, 3228, -1, 2344, 3235, 3234, -1, + 2344, 3234, 2345, -1, 3233, 2346, 3241, -1, + 3233, 2890, 2346, -1, 3233, 3235, 2890, -1, + 3240, 2348, 2347, -1, 3240, 3241, 2348, -1, + 3240, 2347, 2893, -1, 2897, 2896, 2349, -1, + 2897, 2349, 2350, -1, 2897, 3453, 3454, -1, + 2897, 2350, 3453, -1, 3253, 2351, 3254, -1, + 3253, 2352, 2351, -1, 3253, 2898, 2352, -1, + 3256, 2353, 2354, -1, 3256, 3254, 2353, -1, + 3256, 2355, 3258, -1, 3256, 2354, 2355, -1, + 2361, 2360, 2356, -1, 2361, 2356, 2357, -1, + 2361, 2357, 2358, -1, 2361, 2358, 2906, -1, + 2904, 2903, 2359, -1, 2904, 2359, 2360, -1, + 2904, 2361, 2906, -1, 2904, 2360, 2361, -1, + 2362, 2364, 2363, -1, 2362, 2365, 2366, -1, + 2362, 2363, 2367, -1, 2362, 2367, 2365, -1, + 2362, 2366, 2748, -1, 2362, 2748, 2364, -1, + 2368, 2369, 2370, -1, 2368, 2370, 2371, -1, + 2368, 2372, 2369, -1, 2368, 2371, 2910, -1, + 2368, 2391, 2372, -1, 2368, 2910, 2391, -1, + 2378, 2381, 2382, -1, 2378, 2373, 2381, -1, + 2378, 2379, 2374, -1, 2378, 2374, 2373, -1, + 2375, 2917, 2376, -1, 2375, 2382, 2917, -1, + 2375, 2376, 2377, -1, 2375, 2378, 2382, -1, + 2375, 2377, 2379, -1, 2375, 2379, 2378, -1, + 2396, 2381, 2380, -1, 2396, 2382, 2381, -1, + 2396, 2380, 2395, -1, 2396, 3461, 2382, -1, + 2383, 2384, 2385, -1, 2383, 2390, 2384, -1, + 2383, 2385, 2386, -1, 2383, 2386, 2387, -1, + 2383, 2387, 2388, -1, 2383, 2388, 2390, -1, + 2909, 2913, 2389, -1, 2909, 2389, 2390, -1, + 2909, 2391, 2910, -1, 2909, 2390, 2391, -1, + 2923, 2392, 2922, -1, 2923, 2393, 2392, -1, + 2923, 2394, 2393, -1, 2923, 2924, 2394, -1, + 3458, 2395, 2924, -1, 3458, 3461, 2396, -1, + 3458, 2396, 2395, -1, 3458, 2924, 3459, -1, + 3055, 2397, 2920, -1, 3055, 3056, 2397, -1, + 3061, 2398, 3060, -1, 3061, 2778, 2398, -1, + 3061, 2915, 2778, -1, 3265, 2921, 2916, -1, + 3341, 3265, 3344, -1, 3341, 2921, 3265, -1, + 2919, 2920, 2399, -1, 2919, 2400, 2401, -1, + 2919, 2399, 2400, -1, 2919, 2401, 2402, -1, + 2919, 2402, 2921, -1, 3262, 2922, 2912, -1, + 2926, 2927, 2403, -1, 2926, 2403, 2404, -1, + 2926, 2404, 2420, -1, 2926, 2420, 2930, -1, + 2413, 2409, 2405, -1, 2413, 2407, 2406, -1, + 2413, 2405, 2407, -1, 2413, 2406, 2411, -1, + 2408, 2410, 2409, -1, 2408, 2411, 2412, -1, + 2408, 2413, 2411, -1, 2408, 2409, 2413, -1, + 2408, 2412, 2414, -1, 2408, 2414, 2410, -1, + 2415, 2416, 2417, -1, 2415, 2417, 2418, -1, + 2415, 2419, 2416, -1, 2415, 2418, 2423, -1, + 2415, 2420, 2419, -1, 2415, 2423, 2420, -1, + 2421, 2423, 2422, -1, 2421, 2422, 2424, -1, + 2421, 2930, 2423, -1, 2421, 2424, 2425, -1, + 2421, 2425, 2928, -1, 2421, 2928, 2930, -1, + 2427, 2933, 2426, -1, 2427, 2426, 2948, -1, + 2427, 2948, 2950, -1, 2427, 2950, 2942, -1, + 2938, 2427, 2942, -1, 2938, 2933, 2427, -1, + 2947, 2429, 2428, -1, 2947, 2945, 2429, -1, + 2947, 2430, 2949, -1, 2947, 2428, 2430, -1, + 3531, 3272, 2431, -1, 3531, 2431, 3205, -1, + 3267, 3207, 2953, -1, 2817, 2816, 2432, -1, + 2817, 2433, 3207, -1, 2817, 2434, 2433, -1, + 2817, 2432, 2434, -1, 3470, 2435, 2955, -1, + 3470, 3471, 2436, -1, 3470, 2436, 2435, -1, + 3277, 2438, 2437, -1, 3277, 3278, 2438, -1, + 3277, 2437, 2958, -1, 3546, 2959, 3278, -1, + 2439, 2451, 2440, -1, 2439, 2443, 2451, -1, + 2439, 2440, 2458, -1, 2439, 2441, 2443, -1, + 2439, 2458, 2457, -1, 2439, 2457, 2441, -1, + 2442, 2449, 2443, -1, 2442, 3279, 3280, -1, + 2442, 3280, 2449, -1, 2442, 2444, 3279, -1, + 2442, 2445, 2444, -1, 2442, 2443, 2445, -1, + 2446, 2447, 2448, -1, 2446, 2449, 2956, -1, + 2446, 2956, 2450, -1, 2446, 2450, 2447, -1, + 2446, 2451, 2449, -1, 2446, 2448, 2451, -1, + 2464, 2462, 2452, -1, 2464, 2453, 2461, -1, + 2464, 2454, 2453, -1, 2464, 2452, 2454, -1, + 2455, 2462, 2463, -1, 2455, 2456, 2457, -1, + 2455, 2457, 2458, -1, 2455, 2458, 2462, -1, + 2455, 2459, 2456, -1, 2455, 2463, 2459, -1, + 2460, 2461, 2470, -1, 2460, 2463, 2462, -1, + 2460, 2464, 2461, -1, 2460, 2462, 2464, -1, + 2460, 2470, 2468, -1, 2460, 2468, 2463, -1, + 2465, 2466, 2467, -1, 2465, 2469, 2468, -1, + 2465, 2468, 2470, -1, 2465, 2470, 2466, -1, + 2465, 2471, 2469, -1, 2465, 2467, 2471, -1, + 2472, 2473, 2474, -1, 2472, 2476, 2475, -1, + 2472, 2474, 2476, -1, 2472, 2475, 2477, -1, + 2472, 2477, 2478, -1, 2472, 2478, 2473, -1, + 2479, 2481, 2480, -1, 2479, 2482, 2490, -1, + 2479, 2490, 2481, -1, 2479, 2483, 2482, -1, + 2479, 2484, 2483, -1, 2479, 2480, 2484, -1, + 2485, 2486, 2487, -1, 2485, 2488, 2489, -1, + 2485, 2489, 2490, -1, 2485, 2490, 2486, -1, + 2485, 2491, 2488, -1, 2485, 2487, 2491, -1, + 2492, 2494, 2493, -1, 2492, 2496, 2495, -1, + 2492, 2495, 2494, -1, 2492, 2497, 2496, -1, + 2492, 2493, 2497, -1, 2975, 3309, 3289, -1, + 3528, 2503, 3526, -1, 3528, 3527, 2498, -1, + 3528, 2498, 2499, -1, 3528, 2499, 2503, -1, + 3282, 2501, 2500, -1, 3282, 2500, 3553, -1, + 3282, 2502, 2501, -1, 3282, 3283, 2502, -1, + 3299, 3485, 3281, -1, 3290, 3289, 3309, -1, + 2965, 3526, 2503, -1, 2965, 3281, 3526, -1, + 2965, 2503, 2504, -1, 2965, 2504, 2964, -1, + 3303, 2964, 2966, -1, 3303, 3301, 2964, -1, + 3483, 3485, 3299, -1, 2968, 2506, 3283, -1, + 2505, 2507, 2506, -1, 2505, 2969, 2508, -1, + 2505, 2968, 2969, -1, 2505, 2506, 2968, -1, + 2505, 2508, 2509, -1, 2505, 2509, 2507, -1, + 3487, 2970, 2969, -1, 3492, 3475, 3290, -1, + 3492, 3290, 3309, -1, 3318, 2510, 2995, -1, + 3318, 3319, 2510, -1, 2984, 2511, 2512, -1, + 2984, 2983, 2511, -1, 2984, 2512, 3319, -1, + 2984, 3321, 2983, -1, 2986, 2513, 2514, -1, + 2986, 2987, 2513, -1, 2986, 2515, 2991, -1, + 2986, 2514, 2515, -1, 2516, 2521, 2517, -1, + 2516, 2524, 2518, -1, 2516, 2518, 2520, -1, + 2516, 2520, 2521, -1, 2516, 2517, 2532, -1, + 2516, 2532, 2524, -1, 2519, 3022, 3023, -1, + 2519, 2548, 3022, -1, 2519, 2549, 2548, -1, + 2519, 2520, 2549, -1, 2519, 2521, 2520, -1, + 2519, 3023, 2521, -1, 2993, 3331, 3329, -1, + 2993, 2522, 3331, -1, 2993, 2523, 2522, -1, + 2993, 2996, 2523, -1, 2538, 2527, 2535, -1, + 2538, 2524, 2527, -1, 2538, 2539, 2525, -1, + 2538, 2525, 2524, -1, 2526, 2528, 2527, -1, + 2526, 2530, 2529, -1, 2526, 2529, 2528, -1, + 2526, 2531, 2530, -1, 2526, 2532, 2531, -1, + 2526, 2527, 2532, -1, 2533, 2535, 2534, -1, + 2533, 2534, 2536, -1, 2533, 2536, 2537, -1, + 2533, 2538, 2535, -1, 2533, 2537, 2539, -1, + 2533, 2539, 2538, -1, 2998, 3010, 2540, -1, + 2998, 2540, 2999, -1, 2998, 2541, 3010, -1, + 2998, 3002, 2541, -1, 2543, 3007, 2542, -1, + 2543, 2542, 3014, -1, 3006, 3007, 2543, -1, + 3006, 3014, 3009, -1, 3006, 2543, 3014, -1, + 3012, 3013, 2555, -1, 3012, 2555, 2551, -1, + 3327, 3020, 3017, -1, 3021, 3022, 2544, -1, + 3021, 2545, 3020, -1, 3021, 2546, 2545, -1, + 3021, 2544, 2546, -1, 2547, 2548, 2549, -1, + 2547, 2549, 2550, -1, 2547, 2550, 3011, -1, + 2547, 2551, 2548, -1, 2547, 3011, 3012, -1, + 2547, 3012, 2551, -1, 2552, 2554, 2553, -1, + 2552, 2553, 2555, -1, 2552, 2555, 2556, -1, + 2552, 2557, 2554, -1, 2552, 2558, 2557, -1, + 2552, 2556, 2558, -1, 2559, 2561, 2560, -1, + 2559, 2562, 2563, -1, 2559, 2563, 2561, -1, + 2559, 2564, 2562, -1, 2559, 2565, 2564, -1, + 2559, 2560, 2565, -1, 3025, 2566, 2575, -1, + 3025, 3029, 2566, -1, 3025, 2575, 2567, -1, + 3025, 2567, 3026, -1, 3031, 2568, 3029, -1, + 3031, 3036, 2569, -1, 3031, 2569, 2568, -1, + 3031, 3029, 3032, -1, 3038, 3027, 2570, -1, + 3038, 3028, 3027, -1, 3038, 3043, 3028, -1, + 3038, 2570, 3039, -1, 2571, 2572, 2573, -1, + 2571, 2574, 2575, -1, 2571, 2573, 2574, -1, + 2571, 2575, 2576, -1, 2571, 2576, 2577, -1, + 2571, 2577, 2572, -1, 2578, 2579, 2580, -1, + 2578, 2581, 2582, -1, 2578, 2580, 2581, -1, + 2578, 2582, 2583, -1, 2578, 2583, 2584, -1, + 2578, 2584, 2579, -1, 3044, 2585, 3334, -1, + 3044, 2587, 2585, -1, 3046, 3047, 2586, -1, + 3046, 2586, 2587, -1, 3046, 2587, 3044, -1, + 3051, 2588, 3048, -1, 3051, 3048, 3049, -1, + 3051, 3052, 2588, -1, 3058, 2589, 3056, -1, + 3058, 3057, 2590, -1, 3058, 2591, 2589, -1, + 3058, 2590, 2591, -1, 3059, 2592, 2593, -1, + 3059, 2593, 3057, -1, 3059, 3060, 2592, -1, + 3343, 3059, 3057, -1, 2597, 2598, 2605, -1, + 2597, 2595, 3479, -1, 2597, 3479, 3478, -1, + 2597, 3478, 2598, -1, 2594, 2596, 2595, -1, + 2594, 2605, 2609, -1, 2594, 2595, 2597, -1, + 2594, 2597, 2605, -1, 2594, 2610, 2596, -1, + 2594, 2609, 2610, -1, 2606, 2605, 2598, -1, + 2606, 2600, 2599, -1, 2606, 2598, 2600, -1, + 2606, 2599, 2601, -1, 2606, 2601, 2604, -1, + 2602, 2604, 2603, -1, 2602, 2603, 2608, -1, + 2602, 2608, 2609, -1, 2602, 2609, 2605, -1, + 2602, 2606, 2604, -1, 2602, 2605, 2606, -1, + 2607, 2609, 2608, -1, 2607, 2610, 2609, -1, + 2607, 2611, 2610, -1, 2607, 2612, 2611, -1, + 2607, 2613, 2612, -1, 2607, 2608, 2613, -1, + 3063, 2614, 3066, -1, 3063, 2615, 2614, -1, + 3063, 2616, 2615, -1, 3063, 3064, 2616, -1, + 3065, 2618, 2617, -1, 3065, 2617, 3064, -1, + 3065, 3067, 2619, -1, 3065, 2619, 2618, -1, + 3352, 2620, 3353, -1, 3352, 2621, 2620, -1, + 3352, 3075, 2621, -1, 3073, 3353, 3069, -1, + 3077, 2622, 3076, -1, 3077, 2623, 2622, -1, + 3077, 2624, 2623, -1, 3077, 3356, 2624, -1, + 3355, 3073, 3347, -1, 3355, 3353, 3073, -1, + 2625, 2626, 2627, -1, 2625, 3083, 3084, -1, + 2625, 3084, 2628, -1, 2625, 2628, 2626, -1, + 2625, 2627, 2629, -1, 2625, 2629, 3083, -1, + 3086, 3087, 2630, -1, 3086, 2630, 2632, -1, + 2631, 2632, 2633, -1, 2631, 2634, 3091, -1, + 2631, 3091, 3086, -1, 2631, 3086, 2632, -1, + 2631, 2633, 2635, -1, 2631, 2635, 2634, -1, + 2638, 3092, 2640, -1, 2638, 2636, 2637, -1, + 2638, 2649, 2636, -1, 2638, 2640, 2649, -1, + 3359, 2637, 3360, -1, 3359, 2638, 2637, -1, + 3359, 3092, 2638, -1, 3367, 3362, 3187, -1, + 3367, 3187, 3366, -1, 2639, 2641, 2640, -1, + 2639, 2643, 2641, -1, 2639, 2640, 3092, -1, + 2639, 3095, 2643, -1, 2639, 3092, 3369, -1, + 2639, 3369, 3095, -1, 2642, 2643, 3095, -1, + 2642, 2644, 2645, -1, 2642, 2645, 2646, -1, + 2642, 2646, 2643, -1, 2642, 3094, 2644, -1, + 2642, 3095, 3094, -1, 2647, 2649, 2648, -1, + 2647, 2650, 2649, -1, 2647, 2648, 2651, -1, + 2647, 2652, 2650, -1, 2647, 2651, 2653, -1, + 2647, 2653, 2652, -1, 3097, 3098, 2654, -1, + 3097, 2654, 2655, -1, 3097, 2656, 3102, -1, + 3097, 2655, 2656, -1, 2657, 2659, 2658, -1, + 2657, 2660, 2659, -1, 2657, 2658, 2661, -1, + 2657, 2662, 2660, -1, 2657, 2663, 2662, -1, + 2657, 2661, 2663, -1, 2664, 2665, 2666, -1, + 2664, 2666, 2667, -1, 2664, 2668, 2665, -1, + 2664, 2669, 2668, -1, 2664, 2670, 2669, -1, + 2664, 2667, 2670, -1, 2677, 2671, 2673, -1, + 2677, 2681, 2671, -1, 2677, 2684, 2681, -1, + 2677, 2675, 2684, -1, 2672, 2673, 2674, -1, + 2672, 2676, 2675, -1, 2672, 2675, 2677, -1, + 2672, 2677, 2673, -1, 2672, 2674, 2678, -1, + 2672, 2678, 2676, -1, 2679, 2680, 2681, -1, + 2679, 2682, 2680, -1, 2679, 2683, 2682, -1, + 2679, 2684, 2685, -1, 2679, 2681, 2684, -1, + 2679, 2685, 2686, -1, 2679, 2686, 2683, -1, + 3381, 3375, 2687, -1, 3381, 2688, 3382, -1, + 3381, 2687, 2688, -1, 3378, 3104, 2689, -1, + 3378, 2689, 3371, -1, 3372, 3371, 2690, -1, + 3372, 2691, 2692, -1, 3372, 2690, 2691, -1, + 3372, 2692, 3373, -1, 3388, 3389, 3107, -1, + 3387, 2693, 3113, -1, 3387, 3108, 2693, -1, + 3387, 3388, 3108, -1, 3384, 3112, 2698, -1, + 2694, 2696, 2695, -1, 2694, 2695, 3385, -1, + 2694, 3385, 3384, -1, 2694, 2697, 2696, -1, + 2694, 2698, 2697, -1, 2694, 3384, 2698, -1, + 2699, 2700, 2701, -1, 2699, 2702, 2703, -1, + 2699, 2701, 2702, -1, 2699, 2703, 2711, -1, + 2699, 2711, 2709, -1, 2699, 2709, 2700, -1, + 2710, 2714, 2715, -1, 2710, 2707, 2704, -1, + 2710, 2705, 2714, -1, 2710, 2704, 2705, -1, + 2706, 2708, 2707, -1, 2706, 2715, 2709, -1, + 2706, 2707, 2710, -1, 2706, 2710, 2715, -1, + 2706, 2711, 2708, -1, 2706, 2709, 2711, -1, + 2712, 2714, 2713, -1, 2712, 2715, 2714, -1, + 2712, 2713, 2716, -1, 2712, 2716, 2717, -1, + 2712, 2717, 2718, -1, 2712, 2718, 2715, -1, + 3117, 3114, 2719, -1, 3117, 2720, 3118, -1, + 3117, 2719, 2720, -1, 3121, 2723, 2721, -1, + 3121, 2722, 3122, -1, 3121, 2721, 2722, -1, + 3120, 3395, 3116, -1, 3120, 2723, 3121, -1, + 3120, 2724, 2723, -1, 3120, 3116, 2724, -1, + 3398, 3406, 3126, -1, 3398, 3167, 3168, -1, + 3398, 3126, 3167, -1, 3407, 3409, 3128, -1, + 2725, 3402, 2726, -1, 2725, 3401, 3402, -1, + 2725, 2726, 3129, -1, 2725, 3129, 3401, -1, + 3403, 3129, 3409, -1, 3412, 2766, 3414, -1, + 3133, 3162, 3163, -1, 3133, 3163, 2727, -1, + 3133, 2727, 2728, -1, 3133, 2728, 3134, -1, + 2729, 2730, 2731, -1, 2729, 2733, 2732, -1, + 2729, 2731, 2733, -1, 2729, 2732, 2734, -1, + 2729, 2734, 2735, -1, 2729, 2735, 2730, -1, + 2736, 2738, 2737, -1, 2736, 2739, 2740, -1, + 2736, 2741, 2739, -1, 2736, 2737, 2741, -1, + 2736, 2740, 2742, -1, 2736, 2742, 2738, -1, + 2743, 2745, 2744, -1, 2743, 2747, 2746, -1, + 2743, 2748, 2747, -1, 2743, 2744, 2748, -1, + 2743, 2749, 2745, -1, 2743, 2746, 2749, -1, + 3422, 3137, 2755, -1, 2752, 3432, 2750, -1, + 2752, 2761, 2754, -1, 2752, 2750, 2751, -1, + 2752, 2751, 2761, -1, 3430, 2754, 3140, -1, + 3430, 3432, 2752, -1, 3430, 2752, 2754, -1, + 2753, 2754, 3423, -1, 2753, 3422, 2755, -1, + 2753, 3423, 3422, -1, 2753, 2755, 2756, -1, + 2753, 2756, 3140, -1, 2753, 3140, 2754, -1, + 3152, 2757, 3154, -1, 3152, 3151, 2758, -1, + 3152, 2758, 2757, -1, 3425, 2759, 3427, -1, + 3425, 2760, 2759, -1, 3425, 3423, 2761, -1, + 3425, 2761, 2760, -1, 3130, 3416, 2762, -1, + 3130, 2762, 2763, -1, 3156, 2763, 2764, -1, + 3156, 2764, 3170, -1, 3156, 3130, 2763, -1, + 3156, 3157, 3130, -1, 3161, 3166, 3167, -1, + 3161, 3167, 3126, -1, 3161, 3126, 3164, -1, + 3172, 3160, 3171, -1, 3172, 3166, 3160, -1, + 2765, 3418, 3417, -1, 2765, 2766, 3412, -1, + 2765, 2767, 2766, -1, 2765, 3417, 2767, -1, + 2765, 3131, 3418, -1, 2765, 3412, 3131, -1, + 3179, 2768, 2769, -1, 3179, 3181, 2768, -1, + 3179, 2770, 3180, -1, 3179, 2769, 2770, -1, + 3177, 3178, 2771, -1, 3177, 2771, 2772, -1, + 3177, 2772, 2773, -1, 3177, 2773, 3181, -1, + 3184, 3521, 3520, -1, 3184, 2774, 3521, -1, + 3184, 3188, 2775, -1, 3184, 2775, 2774, -1, + 2776, 2781, 2777, -1, 2776, 2778, 2915, -1, + 2776, 2777, 2778, -1, 2776, 2915, 3260, -1, + 2776, 3261, 2781, -1, 2776, 3260, 3261, -1, + 3264, 3260, 2915, -1, 2779, 2911, 2780, -1, + 2779, 2780, 2781, -1, 2779, 2781, 3261, -1, + 2779, 3261, 3262, -1, 2779, 2912, 2911, -1, + 2779, 3262, 2912, -1, 3435, 2782, 3189, -1, + 3435, 3443, 2782, -1, 3441, 2783, 3195, -1, + 3441, 3440, 2783, -1, 3442, 3193, 2784, -1, + 3442, 2784, 3443, -1, 3200, 2785, 2794, -1, + 3200, 3199, 2785, -1, 2786, 2787, 2793, -1, + 2786, 2793, 2795, -1, 2786, 2795, 2788, -1, + 2786, 2789, 2787, -1, 2786, 2788, 2789, -1, + 2790, 2791, 2792, -1, 2790, 2793, 2791, -1, + 2790, 2792, 3201, -1, 2790, 3200, 2794, -1, + 2790, 3201, 3200, -1, 2790, 2794, 2795, -1, + 2790, 2795, 2793, -1, 2876, 2796, 2877, -1, + 2876, 2878, 2873, -1, 2876, 3222, 2796, -1, + 2876, 2873, 3222, -1, 2797, 2798, 2799, -1, + 2797, 2800, 2801, -1, 2797, 2801, 2802, -1, + 2797, 2802, 2798, -1, 2797, 2803, 2800, -1, + 2797, 2799, 2803, -1, 2834, 2804, 2805, -1, + 2834, 2836, 2804, -1, 2834, 2805, 2806, -1, + 2834, 2806, 2833, -1, 3555, 2807, 3202, -1, + 3555, 3552, 2807, -1, 2808, 2809, 2810, -1, + 2808, 2811, 2812, -1, 2808, 2810, 2811, -1, + 2808, 2813, 2809, -1, 2808, 2812, 2814, -1, + 2808, 2814, 2813, -1, 3445, 3209, 3446, -1, + 3445, 2819, 3209, -1, 3445, 3204, 2819, -1, + 3208, 2815, 2816, -1, 3208, 3210, 2815, -1, + 3208, 2816, 2817, -1, 3208, 2817, 3207, -1, + 2818, 2819, 2820, -1, 2818, 2821, 2822, -1, + 2818, 2820, 2821, -1, 2818, 2822, 3210, -1, + 2818, 3210, 3209, -1, 2818, 3209, 2819, -1, + 2823, 2824, 2825, -1, 2823, 2825, 2826, -1, + 2823, 2826, 2827, -1, 2823, 2827, 2828, -1, + 2823, 2828, 2829, -1, 2823, 2829, 2824, -1, + 2830, 2832, 2831, -1, 2830, 2833, 2832, -1, + 2830, 2834, 2833, -1, 2830, 2831, 2835, -1, + 2830, 2835, 2836, -1, 2830, 2836, 2834, -1, + 2837, 2838, 2839, -1, 2837, 3213, 2840, -1, + 2837, 2841, 2838, -1, 2837, 2840, 2841, -1, + 2837, 2839, 2842, -1, 2837, 2842, 3213, -1, + 3214, 3213, 2842, -1, 3214, 2842, 2847, -1, + 3214, 2843, 3216, -1, 3214, 2847, 2843, -1, + 2844, 2845, 2846, -1, 2844, 2846, 2847, -1, + 2844, 2848, 2845, -1, 2844, 2847, 2849, -1, + 2844, 2850, 2848, -1, 2844, 2849, 2850, -1, + 2851, 2852, 2853, -1, 2851, 2854, 2852, -1, + 2851, 2855, 2854, -1, 2851, 2853, 2856, -1, + 2851, 2856, 2857, -1, 2851, 2857, 2855, -1, + 2858, 2859, 2860, -1, 2858, 2862, 2861, -1, + 2858, 2863, 2859, -1, 2858, 2861, 2863, -1, + 2858, 2860, 2864, -1, 2858, 2864, 2862, -1, + 2872, 3221, 3220, -1, 2872, 2871, 2865, -1, + 2872, 2865, 2866, -1, 2872, 2866, 3221, -1, + 3219, 2868, 3220, -1, 3219, 2874, 2868, -1, + 3219, 2873, 2874, -1, 3219, 3222, 2873, -1, + 2867, 3220, 2868, -1, 2867, 2868, 2869, -1, + 2867, 2869, 2870, -1, 2867, 2870, 2871, -1, + 2867, 2871, 2872, -1, 2867, 2872, 3220, -1, + 2900, 2878, 2899, -1, 2900, 2873, 2878, -1, + 2900, 2874, 2873, -1, 2900, 3257, 2874, -1, + 2875, 2876, 2877, -1, 2875, 2878, 2876, -1, + 2875, 2877, 2879, -1, 2875, 2880, 2878, -1, + 2875, 2879, 2881, -1, 2875, 2881, 2880, -1, + 3231, 3225, 2884, -1, 3231, 2884, 2882, -1, + 3231, 2882, 3230, -1, 3450, 2883, 2884, -1, + 3450, 2884, 3225, -1, 3450, 3452, 2883, -1, + 3227, 3225, 3231, -1, 3227, 3250, 3251, -1, + 2885, 2886, 2887, -1, 2885, 2888, 2886, -1, + 2885, 2889, 2888, -1, 2885, 2887, 2890, -1, + 2885, 2890, 2889, -1, 3237, 2891, 3236, -1, + 3237, 3243, 2892, -1, 3237, 2892, 2891, -1, + 3242, 3233, 3241, -1, 3242, 3243, 3237, -1, + 3239, 2893, 2894, -1, 3239, 3240, 2893, -1, + 3239, 2894, 2895, -1, 3239, 2895, 3244, -1, + 3246, 3247, 2896, -1, 3246, 2896, 2897, -1, + 3246, 3454, 3251, -1, 3246, 2897, 3454, -1, + 3255, 2899, 2898, -1, 3255, 2898, 3253, -1, + 3255, 2900, 2899, -1, 3255, 3257, 2900, -1, + 2901, 2902, 2903, -1, 2901, 2903, 2904, -1, + 2901, 2905, 2902, -1, 2901, 2904, 2906, -1, + 2901, 2906, 2907, -1, 2901, 2907, 2905, -1, + 2908, 2909, 2910, -1, 2908, 2911, 2912, -1, + 2908, 2910, 2911, -1, 2908, 2913, 2909, -1, + 2908, 2912, 2914, -1, 2908, 2914, 2913, -1, + 3340, 2915, 3061, -1, 3340, 3264, 2915, -1, + 3340, 3344, 3264, -1, 3457, 3265, 2916, -1, + 3457, 2917, 3461, -1, 3457, 2916, 2917, -1, + 2918, 2920, 2919, -1, 2918, 3341, 3342, -1, + 2918, 2921, 3341, -1, 2918, 2919, 2921, -1, + 2918, 3055, 2920, -1, 2918, 3342, 3055, -1, + 3263, 2922, 3262, -1, 3263, 2923, 2922, -1, + 3263, 3459, 2924, -1, 3263, 2924, 2923, -1, + 3460, 3260, 3264, -1, 2925, 2927, 2926, -1, + 2925, 2928, 2929, -1, 2925, 2930, 2928, -1, + 2925, 2926, 2930, -1, 2925, 2929, 2931, -1, + 2925, 2931, 2927, -1, 2932, 2934, 2933, -1, + 2932, 2933, 2938, -1, 2932, 2935, 2934, -1, + 2932, 2938, 2939, -1, 2932, 2939, 2936, -1, + 2932, 2936, 2935, -1, 2937, 2939, 2938, -1, + 2937, 2941, 2940, -1, 2937, 2942, 2941, -1, + 2937, 2938, 2942, -1, 2937, 2943, 2939, -1, + 2937, 2940, 2943, -1, 2944, 2946, 2945, -1, + 2944, 2945, 2947, -1, 2944, 2948, 2946, -1, + 2944, 2947, 2949, -1, 2944, 2949, 2950, -1, + 2944, 2950, 2948, -1, 3271, 3534, 3270, -1, + 2954, 2953, 2951, -1, 2954, 3466, 3467, -1, + 2954, 2952, 3466, -1, 2954, 2951, 2952, -1, + 3468, 3269, 3467, -1, 3266, 3267, 2953, -1, + 3266, 3467, 3269, -1, 3266, 2953, 2954, -1, + 3266, 2954, 3467, -1, 3469, 2955, 2956, -1, + 3469, 3470, 2955, -1, 3469, 2956, 3280, -1, + 3538, 2958, 2957, -1, 3538, 3277, 2958, -1, + 3538, 2957, 3539, -1, 3548, 2959, 3546, -1, + 3548, 3279, 2960, -1, 3548, 2960, 2959, -1, + 3287, 3285, 2962, -1, 3287, 2962, 3288, -1, + 2961, 3289, 3288, -1, 2961, 2975, 3289, -1, + 2961, 2974, 2975, -1, 2961, 3288, 2962, -1, + 2961, 2962, 2963, -1, 2961, 2963, 2974, -1, + 3308, 3473, 3472, -1, 3308, 3484, 3565, -1, + 3308, 3524, 3484, -1, 3308, 3472, 3524, -1, + 3474, 2968, 3283, -1, 3286, 3475, 3477, -1, + 3286, 3290, 3475, -1, 3292, 3285, 3293, -1, + 3292, 3296, 3285, -1, 3294, 3301, 3303, -1, + 3294, 3303, 3304, -1, 3298, 3286, 3477, -1, + 3298, 3293, 3286, -1, 3298, 3301, 3294, -1, + 3298, 3294, 3293, -1, 3300, 2964, 3301, -1, + 3300, 2965, 2964, -1, 3300, 3281, 2965, -1, + 3300, 3299, 3281, -1, 3305, 2966, 2967, -1, + 3305, 3303, 2966, -1, 3305, 2967, 3306, -1, + 3476, 3483, 3299, -1, 3558, 3483, 3476, -1, + 3307, 3474, 3473, -1, 3307, 2968, 3474, -1, + 3307, 2969, 2968, -1, 3307, 3487, 2969, -1, + 3488, 2970, 3487, -1, 3488, 2971, 2970, -1, + 3488, 3482, 2971, -1, 3310, 2972, 3311, -1, + 3310, 2974, 2973, -1, 3310, 2975, 2974, -1, + 3310, 3309, 2975, -1, 3310, 2976, 2972, -1, + 3310, 2973, 2976, -1, 3324, 3323, 2979, -1, + 3324, 2979, 2977, -1, 3324, 2977, 3312, -1, + 3316, 3317, 2978, -1, 3316, 2979, 3323, -1, + 3316, 2980, 2979, -1, 3316, 2978, 2980, -1, + 2981, 2995, 3015, -1, 2981, 3318, 2995, -1, + 2981, 3015, 3016, -1, 2981, 3317, 3318, -1, + 2981, 3016, 2982, -1, 2981, 2982, 3317, -1, + 3313, 3314, 2983, -1, 3313, 2983, 3321, -1, + 3496, 3313, 3321, -1, 3322, 2984, 3319, -1, + 3322, 3321, 2984, -1, 2985, 2987, 2986, -1, + 2985, 2988, 2989, -1, 2985, 2989, 2987, -1, + 2985, 2990, 2988, -1, 2985, 2991, 2990, -1, + 2985, 2986, 2991, -1, 2992, 2993, 3329, -1, + 2992, 2995, 2994, -1, 2992, 2994, 2996, -1, + 2992, 2996, 2993, -1, 2992, 3015, 2995, -1, + 2992, 3329, 3015, -1, 2997, 2998, 2999, -1, + 2997, 3001, 3000, -1, 2997, 3000, 3002, -1, + 2997, 3002, 2998, -1, 2997, 3003, 3001, -1, + 2997, 2999, 3003, -1, 3004, 3009, 3005, -1, + 3004, 3006, 3009, -1, 3004, 3005, 3007, -1, + 3004, 3007, 3006, -1, 3008, 3010, 3009, -1, + 3008, 3011, 3010, -1, 3008, 3012, 3011, -1, + 3008, 3013, 3012, -1, 3008, 3014, 3013, -1, + 3008, 3009, 3014, -1, 3326, 3015, 3329, -1, + 3326, 3016, 3015, -1, 3326, 3017, 3016, -1, + 3326, 3327, 3017, -1, 3328, 3330, 3018, -1, + 3328, 3018, 3023, -1, 3019, 3020, 3327, -1, + 3019, 3022, 3021, -1, 3019, 3021, 3020, -1, + 3019, 3023, 3022, -1, 3019, 3328, 3023, -1, + 3019, 3327, 3328, -1, 3024, 3025, 3026, -1, + 3024, 3026, 3027, -1, 3024, 3027, 3028, -1, + 3024, 3028, 3032, -1, 3024, 3032, 3029, -1, + 3024, 3029, 3025, -1, 3030, 3031, 3032, -1, + 3030, 3033, 3034, -1, 3030, 3032, 3033, -1, + 3030, 3034, 3035, -1, 3030, 3035, 3036, -1, + 3030, 3036, 3031, -1, 3037, 3038, 3039, -1, + 3037, 3040, 3041, -1, 3037, 3039, 3040, -1, + 3037, 3041, 3042, -1, 3037, 3042, 3043, -1, + 3037, 3043, 3038, -1, 3335, 3044, 3334, -1, + 3335, 3046, 3044, -1, 3335, 3337, 3049, -1, + 3045, 3047, 3046, -1, 3045, 3049, 3048, -1, + 3045, 3048, 3047, -1, 3045, 3335, 3049, -1, + 3045, 3046, 3335, -1, 3053, 3051, 3049, -1, + 3053, 3271, 3270, -1, 3053, 3049, 3337, -1, + 3053, 3337, 3271, -1, 3050, 3052, 3051, -1, + 3050, 3274, 3052, -1, 3050, 3273, 3274, -1, + 3050, 3270, 3273, -1, 3050, 3053, 3270, -1, + 3050, 3051, 3053, -1, 3054, 3055, 3342, -1, + 3054, 3342, 3343, -1, 3054, 3056, 3055, -1, + 3054, 3343, 3057, -1, 3054, 3058, 3056, -1, + 3054, 3057, 3058, -1, 3339, 3060, 3059, -1, + 3339, 3059, 3343, -1, 3339, 3061, 3060, -1, + 3339, 3340, 3061, -1, 3062, 3064, 3063, -1, + 3062, 3065, 3064, -1, 3062, 3063, 3066, -1, + 3062, 3067, 3065, -1, 3062, 3068, 3067, -1, + 3062, 3066, 3068, -1, 3072, 3073, 3069, -1, + 3072, 3069, 3070, -1, 3072, 3071, 3508, -1, + 3072, 3070, 3071, -1, 3504, 3072, 3508, -1, + 3504, 3073, 3072, -1, 3504, 3347, 3073, -1, + 3357, 3349, 3074, -1, 3357, 3074, 3356, -1, + 3354, 3076, 3075, -1, 3354, 3075, 3352, -1, + 3354, 3077, 3076, -1, 3354, 3356, 3077, -1, + 3345, 3507, 3081, -1, 3345, 3078, 3348, -1, + 3345, 3081, 3079, -1, 3345, 3079, 3078, -1, + 3080, 3081, 3507, -1, 3080, 3082, 3081, -1, + 3080, 3083, 3082, -1, 3080, 3084, 3083, -1, + 3080, 3505, 3084, -1, 3080, 3507, 3505, -1, + 3085, 3087, 3086, -1, 3085, 3088, 3089, -1, + 3085, 3089, 3087, -1, 3085, 3090, 3088, -1, + 3085, 3091, 3090, -1, 3085, 3086, 3091, -1, + 3368, 3369, 3092, -1, 3368, 3092, 3359, -1, + 3364, 3093, 3094, -1, 3364, 3365, 3093, -1, + 3364, 3094, 3095, -1, 3364, 3095, 3369, -1, + 3096, 3098, 3097, -1, 3096, 3100, 3099, -1, + 3096, 3099, 3098, -1, 3096, 3101, 3100, -1, + 3096, 3102, 3101, -1, 3096, 3097, 3102, -1, + 3377, 3103, 3104, -1, 3377, 3104, 3378, -1, + 3377, 3105, 3103, -1, 3377, 3380, 3105, -1, + 3379, 3378, 3371, -1, 3379, 3375, 3381, -1, + 3106, 3388, 3107, -1, 3106, 3108, 3388, -1, + 3106, 3109, 3108, -1, 3106, 3110, 3109, -1, + 3106, 3107, 3111, -1, 3106, 3111, 3110, -1, + 3386, 3113, 3112, -1, 3386, 3387, 3113, -1, + 3386, 3112, 3384, -1, 3391, 3114, 3117, -1, + 3391, 3392, 3114, -1, 3115, 3116, 3395, -1, + 3115, 3395, 3391, -1, 3115, 3391, 3117, -1, + 3115, 3117, 3118, -1, 3115, 3118, 3119, -1, + 3115, 3119, 3116, -1, 3393, 3395, 3120, -1, + 3393, 3120, 3121, -1, 3393, 3122, 3394, -1, + 3393, 3121, 3122, -1, 3399, 3168, 3123, -1, + 3399, 3398, 3168, -1, 3399, 3123, 3124, -1, + 3399, 3124, 3125, -1, 3399, 3125, 3402, -1, + 3405, 3126, 3406, -1, 3405, 3127, 3164, -1, + 3405, 3164, 3126, -1, 3405, 3128, 3127, -1, + 3405, 3407, 3128, -1, 3400, 3401, 3129, -1, + 3400, 3129, 3403, -1, 3408, 3406, 3403, -1, + 3408, 3403, 3409, -1, 3411, 3157, 3131, -1, + 3411, 3131, 3412, -1, 3411, 3416, 3130, -1, + 3411, 3130, 3157, -1, 3158, 3171, 3160, -1, + 3158, 3131, 3157, -1, 3158, 3160, 3419, -1, + 3158, 3419, 3418, -1, 3158, 3418, 3131, -1, + 3165, 3419, 3160, -1, 3165, 3162, 3420, -1, + 3132, 3420, 3162, -1, 3132, 3133, 3134, -1, + 3132, 3162, 3133, -1, 3132, 3134, 3135, -1, + 3132, 3135, 3514, -1, 3132, 3514, 3420, -1, + 3511, 3419, 3165, -1, 3511, 3165, 3420, -1, + 3424, 3136, 3137, -1, 3424, 3137, 3422, -1, + 3424, 3426, 3138, -1, 3424, 3138, 3136, -1, + 3429, 3140, 3139, -1, 3429, 3430, 3140, -1, + 3429, 3141, 3434, -1, 3429, 3139, 3141, -1, + 3146, 3150, 3149, -1, 3146, 3145, 3142, -1, + 3146, 3142, 3143, -1, 3146, 3143, 3150, -1, + 3144, 3194, 3145, -1, 3144, 3145, 3146, -1, + 3144, 3146, 3149, -1, 3144, 3147, 3194, -1, + 3144, 3153, 3147, -1, 3144, 3149, 3153, -1, + 3148, 3149, 3150, -1, 3148, 3150, 3151, -1, + 3148, 3151, 3152, -1, 3148, 3153, 3149, -1, + 3148, 3154, 3153, -1, 3148, 3152, 3154, -1, + 3155, 3170, 3171, -1, 3155, 3156, 3170, -1, + 3155, 3157, 3156, -1, 3155, 3171, 3158, -1, + 3155, 3158, 3157, -1, 3159, 3160, 3166, -1, + 3159, 3166, 3161, -1, 3159, 3163, 3162, -1, + 3159, 3164, 3163, -1, 3159, 3161, 3164, -1, + 3159, 3162, 3165, -1, 3159, 3165, 3160, -1, + 3173, 3167, 3166, -1, 3173, 3166, 3172, -1, + 3173, 3168, 3167, -1, 3173, 3175, 3168, -1, + 3169, 3171, 3170, -1, 3169, 3172, 3171, -1, + 3169, 3173, 3172, -1, 3169, 3170, 3174, -1, + 3169, 3174, 3175, -1, 3169, 3175, 3173, -1, + 3176, 3178, 3177, -1, 3176, 3179, 3180, -1, + 3176, 3181, 3179, -1, 3176, 3177, 3181, -1, + 3176, 3180, 3182, -1, 3176, 3182, 3178, -1, + 3183, 3184, 3520, -1, 3183, 3185, 3186, -1, + 3183, 3520, 3185, -1, 3183, 3186, 3187, -1, + 3183, 3187, 3188, -1, 3183, 3188, 3184, -1, + 3517, 3435, 3189, -1, 3517, 3190, 3518, -1, + 3517, 3189, 3190, -1, 3438, 3443, 3435, -1, + 3438, 3436, 3439, -1, 3191, 3192, 3193, -1, + 3191, 3193, 3442, -1, 3191, 3194, 3192, -1, + 3191, 3442, 3441, -1, 3191, 3195, 3194, -1, + 3191, 3441, 3195, -1, 3196, 3197, 3198, -1, + 3196, 3198, 3199, -1, 3196, 3199, 3200, -1, + 3196, 3201, 3197, -1, 3196, 3200, 3201, -1, + 3444, 3555, 3202, -1, 3444, 3203, 3527, -1, + 3444, 3202, 3203, -1, 3551, 3555, 3444, -1, + 3532, 3205, 3204, -1, 3532, 3204, 3445, -1, + 3532, 3531, 3205, -1, 3206, 3207, 3267, -1, + 3206, 3208, 3207, -1, 3206, 3267, 3446, -1, + 3206, 3446, 3209, -1, 3206, 3209, 3210, -1, + 3206, 3210, 3208, -1, 3211, 3212, 3213, -1, + 3211, 3213, 3214, -1, 3211, 3215, 3212, -1, + 3211, 3214, 3216, -1, 3211, 3217, 3215, -1, + 3211, 3216, 3217, -1, 3218, 3219, 3220, -1, + 3218, 3220, 3221, -1, 3218, 3223, 3222, -1, + 3218, 3222, 3219, -1, 3218, 3224, 3223, -1, + 3218, 3221, 3224, -1, 3449, 3450, 3225, -1, + 3449, 3225, 3227, -1, 3449, 3251, 3454, -1, + 3449, 3227, 3251, -1, 3226, 3250, 3227, -1, + 3226, 3228, 3250, -1, 3226, 3229, 3228, -1, + 3226, 3230, 3229, -1, 3226, 3231, 3230, -1, + 3226, 3227, 3231, -1, 3232, 3233, 3242, -1, + 3232, 3234, 3235, -1, 3232, 3235, 3233, -1, + 3232, 3236, 3234, -1, 3232, 3237, 3236, -1, + 3232, 3242, 3237, -1, 3238, 3240, 3239, -1, + 3238, 3241, 3240, -1, 3238, 3242, 3241, -1, + 3238, 3243, 3242, -1, 3238, 3244, 3243, -1, + 3238, 3239, 3244, -1, 3245, 3247, 3246, -1, + 3245, 3249, 3248, -1, 3245, 3248, 3247, -1, + 3245, 3250, 3249, -1, 3245, 3251, 3250, -1, + 3245, 3246, 3251, -1, 3252, 3253, 3254, -1, + 3252, 3255, 3253, -1, 3252, 3254, 3256, -1, + 3252, 3257, 3255, -1, 3252, 3258, 3257, -1, + 3252, 3256, 3258, -1, 3259, 3261, 3260, -1, + 3259, 3260, 3460, -1, 3259, 3262, 3261, -1, + 3259, 3263, 3262, -1, 3259, 3459, 3263, -1, + 3259, 3460, 3459, -1, 3456, 3460, 3264, -1, + 3456, 3344, 3265, -1, 3456, 3264, 3344, -1, + 3456, 3265, 3457, -1, 3447, 3269, 3535, -1, + 3447, 3266, 3269, -1, 3447, 3267, 3266, -1, + 3447, 3446, 3267, -1, 3268, 3535, 3269, -1, + 3268, 3273, 3270, -1, 3268, 3270, 3534, -1, + 3268, 3534, 3535, -1, 3268, 3269, 3468, -1, + 3268, 3468, 3273, -1, 3530, 3534, 3271, -1, + 3530, 3272, 3531, -1, 3530, 3271, 3337, -1, + 3530, 3336, 3272, -1, 3463, 3274, 3273, -1, + 3463, 3273, 3468, -1, 3463, 3275, 3274, -1, + 3463, 3464, 3275, -1, 3547, 3540, 3276, -1, + 3547, 3276, 3471, -1, 3537, 3277, 3538, -1, + 3537, 3278, 3277, -1, 3537, 3546, 3278, -1, + 3544, 3280, 3279, -1, 3544, 3279, 3548, -1, + 3544, 3469, 3280, -1, 3523, 3526, 3281, -1, + 3523, 3281, 3485, -1, 3523, 3485, 3484, -1, + 3523, 3484, 3524, -1, 3554, 3282, 3553, -1, + 3554, 3283, 3282, -1, 3554, 3474, 3283, -1, + 3284, 3293, 3285, -1, 3284, 3286, 3293, -1, + 3284, 3285, 3287, -1, 3284, 3287, 3288, -1, + 3284, 3288, 3289, -1, 3284, 3289, 3290, -1, + 3284, 3290, 3286, -1, 3295, 3294, 3304, -1, + 3295, 3304, 3296, -1, 3291, 3292, 3293, -1, + 3291, 3293, 3294, -1, 3291, 3294, 3295, -1, + 3291, 3296, 3292, -1, 3291, 3295, 3296, -1, + 3297, 3298, 3477, -1, 3297, 3477, 3476, -1, + 3297, 3476, 3299, -1, 3297, 3299, 3300, -1, + 3297, 3301, 3298, -1, 3297, 3300, 3301, -1, + 3302, 3304, 3303, -1, 3302, 3303, 3305, -1, + 3302, 3306, 3304, -1, 3302, 3305, 3306, -1, + 3560, 3475, 3492, -1, 3568, 3480, 3481, -1, + 3567, 3483, 3558, -1, 3486, 3307, 3473, -1, + 3486, 3308, 3565, -1, 3486, 3473, 3308, -1, + 3486, 3487, 3307, -1, 3490, 3492, 3309, -1, + 3490, 3309, 3310, -1, 3490, 3311, 3491, -1, + 3490, 3310, 3311, -1, 3495, 3312, 3501, -1, + 3495, 3324, 3312, -1, 3497, 3314, 3313, -1, + 3497, 3313, 3496, -1, 3497, 3500, 3314, -1, + 3315, 3323, 3322, -1, 3315, 3317, 3316, -1, + 3315, 3316, 3323, -1, 3315, 3318, 3317, -1, + 3315, 3319, 3318, -1, 3315, 3322, 3319, -1, + 3320, 3496, 3321, -1, 3320, 3321, 3322, -1, + 3320, 3322, 3323, -1, 3320, 3495, 3496, -1, + 3320, 3323, 3324, -1, 3320, 3324, 3495, -1, + 3325, 3327, 3326, -1, 3325, 3328, 3327, -1, + 3325, 3326, 3329, -1, 3325, 3330, 3328, -1, + 3325, 3331, 3330, -1, 3325, 3329, 3331, -1, + 3332, 3334, 3333, -1, 3332, 3335, 3334, -1, + 3332, 3333, 3336, -1, 3332, 3337, 3335, -1, + 3332, 3336, 3530, -1, 3332, 3530, 3337, -1, + 3338, 3340, 3339, -1, 3338, 3342, 3341, -1, + 3338, 3343, 3342, -1, 3338, 3339, 3343, -1, + 3338, 3341, 3344, -1, 3338, 3344, 3340, -1, + 3503, 3347, 3504, -1, 3503, 3348, 3347, -1, + 3503, 3345, 3348, -1, 3503, 3507, 3345, -1, + 3346, 3355, 3347, -1, 3346, 3357, 3355, -1, + 3346, 3347, 3348, -1, 3346, 3349, 3357, -1, + 3346, 3350, 3349, -1, 3346, 3348, 3350, -1, + 3351, 3352, 3353, -1, 3351, 3354, 3352, -1, + 3351, 3353, 3355, -1, 3351, 3356, 3354, -1, + 3351, 3357, 3356, -1, 3351, 3355, 3357, -1, + 3358, 3359, 3360, -1, 3358, 3368, 3359, -1, + 3358, 3360, 3361, -1, 3358, 3367, 3368, -1, + 3358, 3361, 3362, -1, 3358, 3362, 3367, -1, + 3363, 3365, 3364, -1, 3363, 3366, 3365, -1, + 3363, 3367, 3366, -1, 3363, 3368, 3367, -1, + 3363, 3369, 3368, -1, 3363, 3364, 3369, -1, + 3370, 3379, 3371, -1, 3370, 3372, 3373, -1, + 3370, 3371, 3372, -1, 3370, 3373, 3374, -1, + 3370, 3374, 3375, -1, 3370, 3375, 3379, -1, + 3376, 3377, 3378, -1, 3376, 3378, 3379, -1, + 3376, 3380, 3377, -1, 3376, 3379, 3381, -1, + 3376, 3382, 3380, -1, 3376, 3381, 3382, -1, + 3383, 3384, 3385, -1, 3383, 3386, 3384, -1, + 3383, 3387, 3386, -1, 3383, 3388, 3387, -1, + 3383, 3385, 3389, -1, 3383, 3389, 3388, -1, + 3390, 3392, 3391, -1, 3390, 3393, 3394, -1, + 3390, 3391, 3395, -1, 3390, 3395, 3393, -1, + 3390, 3396, 3392, -1, 3390, 3394, 3396, -1, + 3397, 3406, 3398, -1, 3397, 3398, 3399, -1, + 3397, 3401, 3400, -1, 3397, 3402, 3401, -1, + 3397, 3399, 3402, -1, 3397, 3403, 3406, -1, + 3397, 3400, 3403, -1, 3404, 3405, 3406, -1, + 3404, 3407, 3405, -1, 3404, 3406, 3408, -1, + 3404, 3409, 3407, -1, 3404, 3408, 3409, -1, + 3410, 3411, 3412, -1, 3410, 3414, 3413, -1, + 3410, 3412, 3414, -1, 3410, 3413, 3415, -1, + 3410, 3415, 3416, -1, 3410, 3416, 3411, -1, + 3510, 3513, 3417, -1, 3510, 3417, 3418, -1, + 3510, 3418, 3419, -1, 3510, 3419, 3511, -1, + 3512, 3420, 3514, -1, 3512, 3511, 3420, -1, + 3421, 3422, 3423, -1, 3421, 3424, 3422, -1, + 3421, 3423, 3425, -1, 3421, 3426, 3424, -1, + 3421, 3427, 3426, -1, 3421, 3425, 3427, -1, + 3428, 3430, 3429, -1, 3428, 3431, 3432, -1, + 3428, 3432, 3430, -1, 3428, 3433, 3431, -1, + 3428, 3434, 3433, -1, 3428, 3429, 3434, -1, + 3516, 3435, 3517, -1, 3516, 3438, 3435, -1, + 3516, 3521, 3436, -1, 3516, 3436, 3438, -1, + 3437, 3438, 3439, -1, 3437, 3439, 3440, -1, + 3437, 3440, 3441, -1, 3437, 3441, 3442, -1, + 3437, 3442, 3443, -1, 3437, 3443, 3438, -1, + 3525, 3524, 3472, -1, 3525, 3472, 3551, -1, + 3525, 3444, 3527, -1, 3525, 3551, 3444, -1, + 3533, 3445, 3446, -1, 3533, 3532, 3445, -1, + 3533, 3446, 3447, -1, 3533, 3447, 3535, -1, + 3448, 3450, 3449, -1, 3448, 3451, 3452, -1, + 3448, 3452, 3450, -1, 3448, 3453, 3451, -1, + 3448, 3454, 3453, -1, 3448, 3449, 3454, -1, + 3455, 3456, 3457, -1, 3455, 3458, 3459, -1, + 3455, 3459, 3460, -1, 3455, 3460, 3456, -1, + 3455, 3461, 3458, -1, 3455, 3457, 3461, -1, + 3462, 3464, 3463, -1, 3462, 3466, 3465, -1, + 3462, 3465, 3464, -1, 3462, 3467, 3466, -1, + 3462, 3468, 3467, -1, 3462, 3463, 3468, -1, + 3545, 3546, 3537, -1, 3545, 3540, 3547, -1, + 3543, 3469, 3544, -1, 3543, 3470, 3469, -1, + 3543, 3471, 3470, -1, 3543, 3547, 3471, -1, + 3550, 3551, 3472, -1, 3550, 3472, 3473, -1, + 3550, 3473, 3474, -1, 3550, 3474, 3554, -1, + 3559, 3475, 3560, -1, 3559, 3558, 3476, -1, + 3559, 3477, 3475, -1, 3559, 3476, 3477, -1, + 3562, 3561, 3478, -1, 3562, 3478, 3479, -1, + 3562, 3479, 3480, -1, 3557, 3567, 3558, -1, + 3557, 3568, 3567, -1, 3557, 3480, 3568, -1, + 3557, 3562, 3480, -1, 3569, 3568, 3481, -1, + 3569, 3481, 3482, -1, 3569, 3482, 3488, -1, + 3566, 3483, 3567, -1, 3566, 3565, 3484, -1, + 3566, 3484, 3485, -1, 3566, 3485, 3483, -1, + 3564, 3486, 3565, -1, 3564, 3487, 3486, -1, + 3564, 3488, 3487, -1, 3564, 3569, 3488, -1, + 3489, 3561, 3560, -1, 3489, 3490, 3491, -1, + 3489, 3560, 3492, -1, 3489, 3492, 3490, -1, + 3489, 3491, 3493, -1, 3489, 3493, 3561, -1, + 3494, 3496, 3495, -1, 3494, 3497, 3496, -1, + 3494, 3499, 3498, -1, 3494, 3498, 3500, -1, + 3494, 3500, 3497, -1, 3494, 3501, 3499, -1, + 3494, 3495, 3501, -1, 3502, 3503, 3504, -1, + 3502, 3506, 3505, -1, 3502, 3505, 3507, -1, + 3502, 3507, 3503, -1, 3502, 3508, 3506, -1, + 3502, 3504, 3508, -1, 3509, 3510, 3511, -1, + 3509, 3511, 3512, -1, 3509, 3513, 3510, -1, + 3509, 3514, 3513, -1, 3509, 3512, 3514, -1, + 3515, 3516, 3517, -1, 3515, 3518, 3519, -1, + 3515, 3517, 3518, -1, 3515, 3519, 3520, -1, + 3515, 3520, 3521, -1, 3515, 3521, 3516, -1, + 3522, 3523, 3524, -1, 3522, 3524, 3525, -1, + 3522, 3526, 3523, -1, 3522, 3525, 3527, -1, + 3522, 3528, 3526, -1, 3522, 3527, 3528, -1, + 3529, 3530, 3531, -1, 3529, 3531, 3532, -1, + 3529, 3532, 3533, -1, 3529, 3534, 3530, -1, + 3529, 3535, 3534, -1, 3529, 3533, 3535, -1, + 3536, 3537, 3538, -1, 3536, 3545, 3537, -1, + 3536, 3538, 3539, -1, 3536, 3540, 3545, -1, + 3536, 3541, 3540, -1, 3536, 3539, 3541, -1, + 3542, 3543, 3544, -1, 3542, 3546, 3545, -1, + 3542, 3545, 3547, -1, 3542, 3547, 3543, -1, + 3542, 3548, 3546, -1, 3542, 3544, 3548, -1, + 3549, 3551, 3550, -1, 3549, 3553, 3552, -1, + 3549, 3554, 3553, -1, 3549, 3550, 3554, -1, + 3549, 3552, 3555, -1, 3549, 3555, 3551, -1, + 3556, 3557, 3558, -1, 3556, 3558, 3559, -1, + 3556, 3559, 3560, -1, 3556, 3560, 3561, -1, + 3556, 3561, 3562, -1, 3556, 3562, 3557, -1, + 3563, 3564, 3565, -1, 3563, 3565, 3566, -1, + 3563, 3566, 3567, -1, 3563, 3567, 3568, -1, + 3563, 3568, 3569, -1, 3563, 3569, 3564, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link6.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link6.wrl new file mode 100644 index 0000000..495ade1 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link6.wrl @@ -0,0 +1,5883 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.039006501 -0.043162599 0.044169001, + 0.071154997 0.0023795499 -0.000647904, + 0.0624342 0.034215301 -0.00062255398, + -0.0707919 -0.0071169999 -0.00590479, + -0.0708372 -0.00712582 -0.00065547298, + -0.070202999 -0.0118413 -0.00065922801, + -0.00559822 -0.049641099 -0.056039501, + -0.0079920599 -0.059378002 -0.0460473, + -0.0030794099 -0.059884202 -0.046047699, + -0.036038801 -0.045671798 0.044167001, + -0.042302102 -0.046799 0.0348926, + -0.037645102 -0.047702 0.039600302, + -0.040745001 -0.045081198 0.039602399, + -0.0308173 -0.061001401 0.0200582, + 0.012099 -0.0595566 0.039590899, + -0.053073101 0.0448585 0.0150249, + -0.055010099 0.040515698 0.0201391, + -0.055951599 0.041213501 0.015022, + -0.058580201 0.037384301 0.015019, + -0.05218 0.044099499 0.0201419, + -0.049957599 0.048303202 0.0150277, + -0.034270301 -0.043435801 0.0485751, + -0.0607084 0.0019981 0.039639901, + 0.062394299 0.034197699 -0.0058718901, + 0.070894502 -0.0023739 0.00459135, + 0.060437299 -0.00611164 0.039633401, + 0.071154997 -0.0023785101 -0.00065169297, + 0.071109504 0.0023821399 -0.0058972202, + 0.071109504 -0.0023727401 -0.0059010098, + 0.070758201 -0.0023568501 -0.0111388, + 0.070158198 -0.0118295 -0.00590854, + 0.0708372 -0.00712582 -0.00065547298, + 0.0707919 -0.0071169999 -0.00590479, + 0.0704422 -0.00707768 -0.0111425, + 0.028144101 0.055728301 -0.0412881, + 0.0511765 0.049494501 -0.000610388, + 0.056997199 0.042004701 -0.0111035, + -0.051602099 0.019835399 0.048625499, + -0.047342401 0.0219271 0.0528595, + 0.027395399 0.054182101 0.039681502, + 0.0296345 0.049997602 0.044243202, + 0.0309553 0.0522312 0.0396799, + -0.064538799 0.029953901 -0.0058752699, + -0.059312899 0.037856098 0.0098423203, + -0.056651399 0.041733298 0.0098454002, + 0.027024901 0.053517699 -0.045957401, + -0.071109504 -0.0023727401 -0.0059010098, + -0.069150001 0.0069446 0.0149947, + -0.070014901 0.0070357602 0.0098177698, + -0.071154997 0.0023795499 -0.000647904, + -0.070329003 0.00234351 0.0098140398, + -0.0692553 -0.0165039 -0.00066294102, + -0.067998298 -0.0210928 -0.00066659501, + -0.063332699 -0.0151169 0.030082099, + -0.0588497 -0.022693301 0.0349118, + -0.055098802 -0.025600201 0.0396179, + 0.042336199 0.026646201 -0.055978801, + 0.066527799 -0.0067127701 0.0251422, + 0.0353553 -0.035310701 -0.056028102, + 0.039091598 -0.0311298 -0.056024801, + 0.0311745 -0.039046999 -0.0560311, + 0.059652399 -0.0059628799 -0.046004798, + 0.049685601 -0.00555368 -0.056004401, + 0.0597996 -0.0048635202 -0.0460039, + 0.0487464 -0.0110815 -0.056008801, + 0.047194201 -0.0164693 -0.0560131, + 0.067954801 -0.0210751 -0.0059159002, + 0.069211103 -0.0164891 -0.0059122499, + 0.0660671 -0.0254364 -0.0111572, + 0.0676191 -0.0209668 -0.0111536, + 0.0543552 -0.0251863 -0.046020102, + 0.045048401 -0.021649599 -0.056017298, + 0.061613798 -0.0285706 -0.0266257, + 0.055498298 -0.022765599 -0.046018101, + 0.040349599 -0.051119201 0.0300534, + 0.036846701 -0.053700201 0.0300513, + 0.063763797 -0.024574099 0.020087199, + 0.063861601 -0.0198301 0.025131701, + 0.067377701 -0.0113812 0.020097701, + 0.065932199 -0.0111413 0.0251386, + 0.065042198 -0.0155204 0.0251351, + 0.069150001 -0.0069684698 0.0149837, + 0.070014901 -0.0070513901 0.0098065604, + 0.066468097 -0.015856201 0.020094199, + 0.068530999 -0.0115716 0.01498, + 0.052415099 -0.038643699 0.030063299, + -0.054333299 -0.045931201 -0.0059357001, + -0.054368 -0.0459648 -0.00068639999, + -0.0511765 -0.049493499 -0.00068921002, + -0.046799898 -0.045285299 0.030058, + -0.040349599 -0.051119201 0.0300534, + -0.043672301 -0.048310202 0.030055599, + -0.034074798 -0.057549499 0.025101701, + -0.020686399 -0.059602 0.034882501, + -0.0246193 -0.0580872 0.0348837, + 0.035690598 -0.052019998 0.034888498, + 0.0295376 -0.043070901 0.0528077, + 0.0296345 -0.050067998 0.044163499, + 0.034270301 -0.043435801 0.0485751, + 0.031295199 -0.045627899 0.048573401, + 0.032345701 -0.041001901 0.052809399, + 0.004466 -0.066734202 0.025094399, + 0.0155008 -0.036433902 0.065556802, + 0.0135639 -0.040679 0.062858403, + 0.0167892 -0.039455701 0.062859401, + 0.0309553 -0.052294299 0.039596699, + 0.032138199 -0.054287799 0.034886699, + 0.027395399 -0.0542452 0.039595101, + 0.0160478 -0.058615599 0.039591599, + -0.028442301 -0.056313202 0.034885101, + -0.032345701 -0.041001901 0.052809399, + -0.049116898 0.047486201 0.0201446, + -0.037645102 0.047638901 0.039676201, + -0.041436601 0.056992799 0.00909831, + -0.0458344 0.0506608 0.0201471, + -0.046618901 0.051532201 0.0150302, + -0.040049799 -0.0152389 0.062878698, + -0.060437299 -0.00611164 0.039633401, + -0.0602322 -0.018712001 0.034915, + -0.0308914 -0.0297217 0.062867098, + -0.0276068 -0.040264402 0.056854099, + -0.0264073 -0.0411359 0.056853399, + -0.0295376 -0.043070901 0.0528077, + -0.033178799 -0.0271398 0.062869199, + -0.037092399 -0.041049901 0.048576999, + -0.043662999 0.042196099 0.039671902, + -0.046815298 0.0344586 0.044230901, + -0.044406801 0.037508398 0.0442333, + -0.049014699 0.031254601 0.0442283, + -0.048063099 0.046463002 0.025184499, + -0.044851098 0.049569499 0.025187001, + -0.042302102 0.0467434 0.034967098, + -0.063028298 -0.0021351101 0.034928199, + -0.0607084 -0.0020612199 0.039636701, + -0.059896201 0.0100717 0.039646301, + -0.0627468 0.0062845601 0.034934901, + -0.065069899 0.0021515801 0.030095801, + -0.063028298 0.0020794901 0.0349316, + -0.0684513 0.016304901 0.0098251598, + -0.069388099 0.0116965 0.0098214904, + -0.066378698 0.0205789 0.0150056, + -0.067605801 0.016099401 0.015002, + -0.067986399 0.0068234699 0.0201122, + -0.068530999 0.0115478 0.0149984, + -0.066527799 0.00667272 0.025152801, + -0.064779297 0.0064928802 0.030099301, + -0.062185101 0.0104616 0.034938201, + -0.0613456 0.0145916 0.034941498, + -0.053829901 0.039642099 0.025179099, + -0.0602322 0.018656399 0.034944799, + -0.059057299 0.0273815 0.030115901, + -0.055098802 0.025536999 0.039658599, + -0.0588497 0.022637701 0.034947898, + 0.067986399 -0.0068554902 0.0201013, + 0.063332699 -0.0151169 0.030082099, + 0.064199403 -0.0108531 0.0300855, + 0.066992298 0.0207943 -0.016328599, + 0.0682308 0.016273299 -0.0163322, + 0.069789298 -0.0070078499 -0.0163508, + 0.069811597 -0.0117669 -0.0111463, + 0.068869203 -0.0164035 -0.01115, + 0.0691441 -0.0022946401 -0.0215082, + 0.0272223 0.057031602 -0.039647002, + 0.025474999 0.057032801 -0.0412216, + 0.0353553 0.035399899 -0.055971801, + 0.040233102 0.0445216 -0.045964599, + 0.0477258 0.0527726 -0.0058570998, + 0.0477564 0.052802298 -0.00060775399, + 0.050891101 0.049226999 -0.0110977, + 0.051143799 0.049467102 -0.0058597298, + 0.047490101 0.0525162 -0.0110951, + 0.0540649 0.045717798 -0.0111005, + 0.059312899 0.037856098 0.0098423203, + 0.056651399 0.041733298 0.0098454002, + 0.028806301 0.056973599 0.033153199, + 0.028442301 0.056257602 0.034974702, + 0.0291795 0.056973901 0.032774001, + 0.027455101 0.0569725 0.0345258, + 0.032138199 0.054232199 0.0349731, + 0.042580601 0.056999199 0.00097616302, + 0.065454699 0.0252224 -0.016325099, + 0.064560004 0.024882 -0.021486601, + 0.053433701 0.039395399 -0.031585999, + 0.041858599 0.0463138 -0.041295599, + 0.049277499 0.041690599 -0.036499701, + 0.044856399 0.0434146 -0.041297901, + 0.050684799 0.042876501 -0.031583302, + -0.037805501 0.026047399 0.060007598, + -0.045899801 0.0018019601 0.059988301, + -0.042520899 0.0051128799 0.062894903, + -0.0379849 -0.0110546 0.065577, + -0.041142099 -0.0119671 0.062881298, + -0.054265 0.0208646 0.044220001, + -0.0566836 0.0217997 0.0396557, + -0.048704099 0.018716 0.0528569, + -0.052814402 0.016344501 0.048622701, + -0.033178799 0.027039601 0.0629123, + -0.030369001 0.0114615 0.0703125, + 0.045899801 0.0018019601 0.059988301, + -0.0226715 0.0431481 0.056920499, + -0.0145468 0.0435252 0.060021501, + -0.0180058 0.042213298 0.060020398, + -0.021348 0.040627498 0.060019199, + -0.019905601 0.0378769 0.062921003, + -0.0275963 0.036676198 0.060015999, + -0.0068709301 0.042228501 0.0629244, + -0.0102507 0.041538499 0.062923901, + 0.0262265 0.051865298 0.044244699, + 0.026597699 0.0448635 0.052877702, + 0.028180299 0.047538899 0.048647601, + 0.025645601 0.0569712 0.036176499, + 0.023751199 0.05697 0.037723199, + -0.070577897 0.0070965602 0.00459889, + -0.069945998 0.0117948 0.0046026302, + -0.062394299 0.034197699 -0.0058718901, + -0.0617094 0.0338099 0.0098390998, + -0.067208901 0.0208406 0.0098287696, + -0.065666303 0.0252831 0.0098323002, + -0.064343698 0.029854899 0.0046170098, + -0.063830398 0.0296127 0.0098357499, + 0.00559822 0.049730301 -0.055960398, + 0.0266016 0.042380799 -0.055966299, + 0.0216942 0.045093101 -0.055964101, + 0.029966 0.0520177 -0.045958601, + 0.011126 0.048790898 -0.055961199, + 0.016514 0.047238801 -0.055962399, + 0.023659701 0.057034001 -0.042692099, + 0.0217772 0.0570351 -0.044057, + 0.024479499 0.054815799 -0.045956399, + 0.0241732 0.057033699 -0.042276099, + 0.0253943 0.057032902 -0.041287001, + -0.0585334 -0.027133301 -0.0365545, + -0.050000001 4.4591801e-005 -0.056000002, + -0.067298099 0.0160551 -0.021493601, + -0.068218999 0.0115242 -0.021497199, + -0.0682308 0.016273299 -0.0163322, + -0.066076599 0.0205143 -0.021490101, + -0.067583501 -0.0067777601 -0.026608299, + -0.070894502 -0.0023739 0.00459135, + -0.071154997 -0.0023785101 -0.00065169297, + -0.070329003 -0.00235913 0.0098102903, + -0.070894502 0.0023665801 0.0045951302, + -0.055696901 -0.041020699 -0.0215391, + -0.0559441 -0.035688199 -0.031645801, + -0.053433701 -0.039345 -0.031648699, + -0.056997199 -0.041986901 -0.0111703, + -0.057280101 -0.0421996 -0.0059327199, + -0.066437602 -0.0255874 -0.00067017402, + -0.064343698 -0.029862201 0.0045694602, + -0.039696399 -0.057814602 -0.016391199, + -0.0386739 -0.048940498 -0.041371498, + -0.054390799 -0.034692701 -0.036560498, + -0.039991699 -0.050613001 -0.036573201, + -0.044521 -0.049199399 -0.031656601, + -0.047709402 -0.046115801 -0.031654101, + -0.060669798 -0.0332308 -0.021532901, + -0.057253201 -0.036527898 -0.026632, + -0.067954801 -0.0210751 -0.0059159002, + -0.069211103 -0.0164891 -0.0059122499, + -0.069388099 -0.0117121 0.00980285, + -0.0684513 -0.016320501 0.0097991796, + -0.067605801 -0.0161232 0.0149764, + -0.069945998 -0.0118022 0.0045838398, + -0.069001801 -0.016447701 0.0045801401, + -0.070014901 -0.0070513901 0.0098065604, + -0.070577897 -0.0071038799 0.00458758, + -0.0661944 -0.0254979 0.0045729401, + -0.067749403 -0.021019701 0.0045765, + -0.069150001 -0.0069684698 0.0149837, + -0.0627468 -0.0063401898 0.034924898, + -0.065069899 -0.0021995001 0.0300924, + -0.0623958 -0.024051299 0.0251284, + -0.063861601 -0.0198301 0.025131701, + -0.062183201 -0.019313401 0.0300787, + -0.059057299 -0.027429501 0.0300723, + -0.057204399 -0.0265735 0.034908801, + -0.060755901 -0.0234237 0.0300755, + -0.057094999 -0.031312902 0.0300692, + -0.060651399 -0.028165299 0.025125099, + -0.051199298 -0.032715902 0.039612301, + -0.0489018 -0.036062699 0.0396096, + -0.053268 -0.029223301 0.039615002, + -0.0553036 -0.0303351 0.034905799, + -0.053155798 -0.033961099 0.0349029, + -0.049014699 -0.031325001 0.044178501, + -0.051602099 -0.0199128 0.048593901, + 0.0457622 0.0387275 -0.045969199, + 0.044317201 0.040483899 -0.045967799, + 0.039091598 0.031219 -0.055975199, + 0.051950201 0.038306199 -0.036502399, + 0.047653802 0.0403217 -0.041300401, + 0.052555799 0.028839501 -0.045977101, + 0.050521001 -0.032216601 -0.046025701, + 0.042336199 -0.026557 -0.056021199, + 0.0528684 -0.0283347 -0.046022601, + 0.053433701 -0.039345 -0.031648699, + 0.0682308 -0.0162473 -0.0163581, + 0.058232799 -0.0223951 -0.041350301, + 0.0620891 -0.0062133102 -0.041337501, + 0.060217001 -0.023163 -0.036551401, + 0.048158601 -0.040743399 0.034897499, + 0.054877602 -0.035056598 0.0300662, + 0.053829901 -0.039682101 0.0251159, + 0.0692553 -0.0165039 -0.00066294102, + 0.065261699 -0.020260399 0.020090699, + 0.045331601 -0.043869101 0.034894999, + 0.0497186 -0.0420583 0.0300606, + 0.038670901 -0.056349698 0.020061901, + -0.0047378801 -0.070779398 0.0045368802, + -0.00470008 -0.070219003 0.0097562596, + 4.8665428e-013 -0.070937701 0.0045367498, + -3.964171e-012 -0.070376098 0.0097561302, + -0.036079701 -0.060905699 -0.0111854, + -0.0094832703 -0.070509702 -0.00595527, + -0.0094893305 -0.070559099 -0.00070598401, + -0.0141719 -0.0697188 -0.00595464, + -0.018704399 -0.068273298 -0.0111913, + -0.0093791699 -0.0697482 0.0097566303, + -0.0138432 -0.068118297 0.014935, + -0.027131701 -0.0639963 0.0149382, + -0.031344801 -0.062041201 0.0149398, + -0.027471 -0.064792298 0.00976058, + -0.031992 -0.0633137 0.0045428299, + 0.0092633199 -0.068890899 0.0149343, + 0.0138432 -0.068118297 0.014935, + 0.0091074398 -0.067735799 0.020052901, + 0.039991699 -0.050613001 -0.036573201, + 0.011126 -0.0487017 -0.056038801, + -0.011126 -0.0487017 -0.056038801, + 5.0195486e-012 -0.066346399 -0.031670202, + -4.600785e-012 -0.064499602 -0.036584299, + -0.0047552902 -0.071035303 -0.000706363, + -0.0047522499 -0.070985697 -0.00595565, + -0.0047287699 -0.070630699 -0.0111931, + 0.00470008 -0.070219003 0.0097562596, + 0.0093791699 -0.0697482 0.0097566303, + 0.0047378801 -0.070779398 0.0045368802, + 4.3017729e-012 -0.071194202 -0.00070649001, + -0.059121698 -0.037728898 -0.016375201, + -0.0596749 -0.038086198 -0.0111672, + -0.058313601 -0.0372089 -0.021536, + -0.050891101 -0.0492092 -0.0111761, + -0.054168999 -0.0458006 0.00455677, + -0.0477258 -0.052763201 -0.00594114, + -0.051143799 -0.049457699 -0.0059385002, + -0.0180523 -0.065917701 0.020054299, + -0.025416801 -0.059964001 0.0300464, + -0.0266751 -0.062923603 0.0200567, + -0.030156201 -0.059696998 0.0251, + -0.029363601 -0.058132499 0.0300478, + -0.031736799 -0.062812902 0.0097621595, + -0.0078717899 -0.0236379 0.0740401, + -0.048063099 -0.046503 0.0251105, + -0.035860799 -0.060552701 0.0097639598, + -0.035417899 -0.059808999 0.0149416, + -0.034821901 -0.0588069 0.020059999, + -0.044851098 -0.049609501 0.025108, + -0.035690598 -0.052019998 0.034888498, + -0.034377001 -0.050110001 0.039598402, + -0.0390836 -0.049520001 0.034890499, + -0.032138199 -0.054287799 0.034886699, + -0.036846701 -0.053700201 0.0300513, + -0.033179201 -0.056041501 0.030049499, + 0.028180299 -0.047616299 0.048571799, + 0.035009298 -0.03875 0.052811202, + 0.037092399 -0.041049901 0.048576999, + 0.043662999 -0.042259201 0.039604701, + 0.039006501 -0.043162599 0.044169001, + 0.0086778197 -0.064549297 0.0300427, + 0.0089120502 -0.066287003 0.025094699, + -0.004466 -0.066734202 0.025094399, + -0.0092633199 -0.068890899 0.0149343, + 0.0308173 -0.061001401 0.0200582, + 0.0039875298 -0.0245953 0.074039303, + 0.00687563 -0.027953099 0.072283603, + 0.0262265 -0.051935699 0.044162098, + 0.0249395 -0.049392302 0.048570398, + 0.020686399 -0.059602 0.034882501, + 0.019925 -0.057413001 0.039592601, + 0.023713199 -0.055954002 0.039593801, + 0.0246193 -0.0580872 0.0348837, + 0.0172008 -0.062816903 0.030044099, + 0.0166611 -0.060850699 0.034881499, + 0.0133183 -0.065543801 0.025095301, + 0.0129683 -0.063825503 0.0300433, + 0.0125614 -0.061827701 0.034880701, + -0.0125614 -0.061827701 0.034880701, + -0.0166611 -0.060850699 0.034881499, + -0.0084055504 -0.0625287 0.034880102, + 0.00775071 -0.057666901 0.044157501, + 0.0073703802 -0.054842401 0.048565999, + 0.0115828 -0.057020601 0.044158, + -0.0167892 -0.039455701 0.062859401, + -0.056358799 0.0359581 0.0251761, + -0.060947198 0.033388101 0.0150158, + -0.058635999 0.032113399 0.0251731, + -0.0575944 0.036750998 0.020136099, + -0.034270301 0.0433584 0.0486442, + -0.0137888 0.050294898 0.052882101, + -0.00893855 0.0569642 0.044988699, + -0.0073703802 0.054765001 0.048653301, + -0.028180299 0.047538899 0.048647601, + -0.031295199 0.045550499 0.048645999, + -0.026597699 0.0448635 0.052877702, + -0.0309553 0.0522312 0.0396799, + -0.032910202 0.0479066 0.0442416, + -0.0296345 0.049997602 0.044243202, + -0.0262265 0.051865298 0.044244699, + 0.00348601 0.052032899 0.052883402, + -0.049848199 -0.0155051 0.052829701, + -0.057858501 -0.0058558802 0.044198699, + -0.054265 -0.020935001 0.0441867, + -0.052814402 -0.016421899 0.048596598, + -0.0566836 -0.0218629 0.039620899, + -0.030369001 -0.0115735 0.070294201, + -0.036976401 -0.0140755 0.065574601, + -0.026224 -0.029653 0.065562204, + -0.0285208 -0.0274469 0.065563999, + -0.0239322 -0.027068 0.068038702, + -0.0257317 -0.034292798 0.062863499, + -0.028403699 -0.032111298 0.062865198, + -0.0245518 -0.038873401 0.059955899, + -0.0275963 -0.0367718 0.059957501, + -0.0260283 -0.025054701 0.068040296, + -0.0352511 -0.0243821 0.062871397, + -0.033129901 -0.031869601 0.059961401, + -0.0304619 -0.034432199 0.0599594, + -0.030919099 -0.037857801 0.056855999, + -0.042017799 -0.0310011 0.0528173, + -0.0422277 -0.035739999 0.048581298, + -0.044406801 -0.037578799 0.044173501, + -0.046815298 -0.034529001 0.044175901, + -0.044518001 -0.032839801 0.048583601, + -0.0418 -0.040461101 0.044171199, + -0.051060501 0.043149099 0.025181901, + -0.046799898 0.0452374 0.0301301, + -0.045331601 0.043813501 0.0349648, + -0.050770599 0.0373803 0.0349597, + -0.046386 0.0391853 0.039669499, + -0.0489018 0.035999499 0.039666999, + -0.048158601 0.040687799 0.0349623, + -0.052415099 0.038595799 0.0301248, + -0.0497186 0.0420104 0.0301276, + -0.0484928 0.026536001 0.0486308, + -0.0509951 0.027911 0.0442256, + -0.0457693 0.0250402 0.052862, + -0.050159499 0.0232378 0.0486282, + -0.052747902 0.0244425 0.044222899, + -0.034377001 0.050046898 0.039678201, + -0.040349599 0.051071301 0.030134801, + -0.043672301 0.048262302 0.0301325, + -0.0390836 0.049464401 0.0349693, + -0.041438699 0.052454501 0.025189299, + -0.060437299 0.0060485099 0.039643101, + -0.0553036 0.0302795 0.034954, + -0.057204399 0.0265179 0.034951001, + -0.057094999 0.031264901 0.030119, + -0.054877602 0.035008602 0.030122001, + -0.053155798 0.033905499 0.034956899, + -0.053268 0.029160099 0.039661501, + -0.051199298 0.032652698 0.039664298, + 0.066395096 0.0255764 -0.00587876, + 0.066437602 0.025588401 -0.000629424, + 0.0676191 0.020984599 -0.0111202, + 0.0660671 0.025454201 -0.0111166, + 0.064580098 0.029968901 -0.00062593498, + 0.064538799 0.029953901 -0.0058752699, + 0.064219996 0.0298102 -0.0111132, + 0.067954801 0.0210845 -0.0058823298, + 0.068291403 -0.0022992101 0.020105001, + 0.068291403 0.00226719 0.020108599, + 0.070329003 0.00234351 0.0098140398, + 0.070329003 -0.00235913 0.0098102903, + 0.069460303 -0.0023342001 0.0149873, + 0.070894502 0.0023665801 0.0045951302, + 0.057858501 0.0057854801 0.044208001, + 0.0607084 0.0019981 0.039639901, + 0.058118101 0.00190792 0.044204898, + 0.047194201 0.0165585 -0.055986799, + 0.045048401 0.021738799 -0.055982701, + 0.049685601 0.0056428602 -0.055995502, + 0.050000001 4.4591801e-005 -0.056000002, + 0.066076599 0.0205143 -0.021490101, + 0.064492702 -0.0021271601 -0.0365346, + 0.064874999 0.020145601 -0.0265869, + 0.056781799 0.019422799 -0.045984499, + 0.0691645 -0.0116536 -0.016354499, + 0.070102401 0.00235676 -0.016343299, + 0.070102401 -0.00233073 -0.016347099, + 0.070758201 0.0023745899 -0.011135, + 0.069789298 0.0070338799 -0.0163396, + 0.067886703 -0.00224847 -0.026604701, + 0.0691441 0.0023288899 -0.0215046, + 0.037516501 0.036240999 0.052870899, + 0.037136801 0.047064699 -0.045962501, + 0.0351368 0.048672002 -0.045961302, + 0.0311745 0.039136201 -0.055968899, + 0.039937399 0.044813801 -0.045964301, + 0.039991699 0.050671201 -0.036492601, + 0.0386739 0.049006298 -0.041293502, + 0.035316501 0.051479999 -0.041291501, + 0.031801298 0.053724099 -0.041289698, + 0.0305063 0.0570288 -0.036189001, + 0.0365199 0.053229298 -0.0364905, + 0.053736899 0.045423999 0.0098483404, + 0.0497302 0.0481124 -0.021468099, + 0.050419401 0.048774801 -0.0163064, + 0.053563699 0.045298301 -0.016309099, + 0.047049899 0.052033599 -0.0163038, + 0.0488258 0.0472419 -0.0265653, + 0.051870801 0.043875199 -0.026567999, + 0.039193299 0.057017099 -0.0214596, + 0.0420327 0.057008602 -0.0108373, + 0.042377401 0.057006601 -0.0082414597, + 0.043876901 0.0555709 -0.0110927, + 0.057316799 0.042231798 -0.00061617099, + 0.054168999 0.045793299 0.0046297102, + 0.054368 0.045965798 -0.00061319699, + 0.057106901 0.042073 0.0046267398, + 0.054333299 0.0459406 -0.0058625401, + 0.057280101 0.042208999 -0.0058655101, + 0.059971198 0.038288899 -0.00586863, + 0.060009498 0.038309101 -0.00061929401, + 0.059789799 0.038164798 0.0046236301, + 0.063763797 0.024542101 0.0201263, + 0.0623958 0.024011301 0.025166599, + 0.060651399 0.028125299 0.0251699, + 0.064343698 0.029854899 0.0046170098, + 0.062205698 0.0340859 0.0046203798, + 0.0617094 0.0338099 0.0098390998, + 0.058580201 0.037384301 0.015019, + 0.069388099 0.0116965 0.0098214904, + 0.0684513 0.016304901 0.0098251598, + 0.067749403 0.021012301 0.0046099699, + 0.0661944 0.025490601 0.0046135401, + 0.0390836 0.049464401 0.0349693, + 0.040349599 0.051071301 0.030134801, + 0.035690598 0.051964398 0.034971301, + 0.045331601 0.043813501 0.0349648, + 0.048158601 0.040687799 0.0349623, + 0.042302102 0.0467434 0.034967098, + 0.043662999 0.042196099 0.039671902, + 0.032368101 0.0569769 0.028975699, + 0.033179201 0.055993602 0.030138699, + 0.0308176 0.056975398 0.030923299, + 0.033231501 0.056977902 0.027794801, + 0.0269632 0.056972198 0.034974601, + 0.041247699 0.056992199 0.0098563498, + 0.0415016 0.056993 0.0087988004, + 0.041989401 0.056995101 0.00620881, + 0.042686898 0.057002399 -0.00296877, + 0.0425766 0.057004701 -0.0058535701, + 0.0426424 0.057000499 -0.00060462899, + 0.042596299 0.0570045 -0.0056181299, + 0.042683698 0.0570013 -0.0016617, + 0.0440947 0.055842601 -0.0058546602, + 0.044122901 0.055874199 -0.00060530799, + 0.0615106 0.0337217 -0.016318399, + 0.063624702 0.029538 -0.0163217, + 0.062086102 0.034033101 -0.0111098, + 0.062755004 0.0291386 -0.0214832, + 0.0596749 0.038104001 -0.0111066, + 0.059121698 0.037754901 -0.016315101, + 0.052831501 0.044683401 -0.0214708, + 0.0564688 0.041619599 -0.0163121, + 0.057253201 0.036570299 -0.0265738, + 0.058313601 0.037243102 -0.021476701, + 0.060669798 0.033264998 -0.021479901, + 0.059566502 0.0326645 -0.026576901, + 0.055696901 0.041054901 -0.0214737, + 0.054684099 0.0403127 -0.026570801, + 0.042096298 0.053328499 -0.0265604, + 0.046406701 0.0513267 -0.021465501, + 0.044521 0.049249802 -0.031578202, + 0.047709402 0.0461662 -0.031580601, + 0.0455628 0.050397702 -0.026562801, + 0.041133799 0.0521136 -0.0315759, + 0.0432849 0.047887001 -0.036494799, + 0.0463848 0.044888999 -0.036497202, + -0.0046473802 0.0569635 0.0457973, + -0.00680352 0.056963801 0.045456301, + -0.0024819099 0.056963399 0.046009399, + -0.000308338 0.056963298 0.046092499, + 5.5582036e-012 0.055258401 0.048653699, + -0.00369344 0.0551349 0.048653599, + -0.0038163599 0.0569635 0.045878701, + 5.9897703e-012 0.056963298 0.046093799, + -0.0076671098 0.056963999 0.045267198, + -0.043199599 0.0227488 0.0569042, + -0.0293185 0.0389731 0.056917202, + -0.0327521 0.036165498 0.056914899, + -0.0302254 0.0382316 0.056916598, + -0.044518001 0.032762401 0.048635799, + -0.046609499 0.0297157 0.0486334, + -0.033129901 0.031773999 0.060012098, + -0.0308914 0.029621501 0.062914401, + -0.0304619 0.0343366 0.060014199, + -0.035053499 0.033855598 0.0569131, + -0.058118101 -0.0019783201 0.044201799, + -0.058118101 0.00190792 0.044204898, + -0.057858501 0.0057854801 0.044208001, + -0.054526798 0.0091588004 0.048617002, + -0.0550193 0.0054963198 0.0486141, + -0.048525002 0.00483739 0.05689, + -0.045602102 0.0054893401 0.0599912, + -0.056566499 0.0134453 0.0442141, + -0.0573406 0.0096369199 0.044211101, + -0.0537907 0.0127803 0.0486199, + -0.055539802 0.017193399 0.044217099, + -0.059087601 0.0140497 0.039649501, + -0.058015201 0.0179649 0.039652601, + -0.049848199 0.0154209 0.0528543, + -0.050769702 0.0120569 0.052851599, + -0.048347302 0.0069059902 0.056891602, + -0.051464502 0.0086389501 0.052848902, + -0.029343801 0.0138678 0.070314497, + -0.036976401 0.0139711 0.065596901, + -0.033744901 0.0127435 0.068070397, + -0.0326056 0.0154174 0.068072498, + -0.031254999 0.0179908 0.068074502, + -0.035728101 0.016900901 0.0655993, + -0.038697701 0.018312201 0.062905401, + -0.041501898 0.0196451 0.060002498, + -0.032545902 0.0224126 0.065603703, + -0.034247998 0.019720901 0.065601498, + -0.0297016 0.020447399 0.068076499, + -0.030632701 0.0249587 0.0656057, + -0.0352511 0.0242819 0.062910199, + -0.037094701 0.021366499 0.0629078, + -0.038747001 0.0078580501 0.065592103, + -0.034665201 0.0099866996 0.068068199, + -0.0379849 0.0109502 0.065594502, + -0.0228929 0.036152199 0.062919602, + -0.0257317 0.034192599 0.062918, + -0.019288899 0.030448901 0.068084501, + -0.021136099 0.033371899 0.065612398, + -0.0167719 0.031902 0.068085603, + -0.027955599 0.0227709 0.068078399, + -0.0318233 0.00644085 0.070308499, + -0.0311973 0.0089803999 0.0703106, + -0.0138458 0.0155685 0.075567603, + 0.039514199 -0.00164463 0.065584503, + 0.039514199 0.0015401799 0.065586999, + 0.042798501 0.00167465 0.062892199, + 0.0150585 -0.0145241 0.075543597, + 0.0102853 -0.0308642 0.070278801, + 0.032545902 -0.022516999 0.065567903, + 0.058118101 -0.0019783201 0.044201799, + 0.057858501 -0.0058558802 0.044198699, + 0.055266201 -0.00188649 0.048608199, + 0.0550193 -0.00557373 0.0486053, + 0.052162301 -0.0017861 0.052840602, + -0.019013699 0.044946499 0.056921899, + -0.0146092 0.053293601 0.048652101, + -2.0726019e-013 0.036035899 0.068088897, + -0.0173593 0.0273955 0.070325203, + -0.0150941 0.0287033 0.070326298, + -0.0090979896 0.0271942 0.072327502, + -0.0133517 0.0253819 0.072325997, + -0.018378099 0.034964301 0.065613702, + -0.0167892 0.039355502 0.062922202, + -0.0135639 0.040578801 0.062923104, + -0.00318215 0.039365798 0.065617204, + -0.0029040501 0.035918899 0.0680888, + 5.3803797e-012 0.039494101 0.065617301, + -0.00532379 0.0158855 0.076800898, + -0.0040128902 0.0119582 0.077762298, + -0.0065897098 0.0154054 0.076800503, + -0.0066119302 0.019745 0.075570904, + 0.0249395 0.049314901 0.048648998, + 0.039748799 0.038403399 0.0486403, + 0.0418 0.0403907 0.044235598, + 0.036038801 0.045601401 0.0442397, + 0.032910202 0.0479066 0.0442416, + 0.039006501 0.043092199 0.044237699, + 0.034377001 0.050046898 0.039678201, + 0.037645102 0.047638901 0.039676201, + 0.040745001 0.045018099 0.0396742, + 0.031295199 0.045550499 0.048645999, + 0.0295376 0.042986698 0.052876201, + 0.034270301 0.0433584 0.0486442, + 0.037092399 0.040972501 0.0486423, + 0.035009298 0.038665801 0.052872799, + 0.00381625 0.0569635 0.0458811, + 0.00439747 0.0569635 0.045828398, + 0.00369344 0.0551349 0.048653599, + -0.069001801 0.0164403 0.0046063298, + -0.067749403 0.021012301 0.0046099699, + -0.0660671 0.025454201 -0.0111166, + -0.066992298 0.0207943 -0.016328599, + -0.0676191 0.020984599 -0.0111202, + -0.0624342 0.034215301 -0.00062255398, + -0.062205698 0.0340859 0.0046203798, + -0.042310499 0.056996901 0.0039320202, + -0.043610699 0.055217199 0.0098561402, + -0.0419368 0.0569948 0.0065254602, + -0.059121698 0.037754901 -0.016315101, + -0.0596749 0.038104001 -0.0111066, + -0.066437602 0.025588401 -0.000629424, + -0.066395096 0.0255764 -0.00587876, + -0.064580098 0.029968901 -0.00062593498, + -0.0661944 0.025490601 0.0046135401, + -0.064874999 0.020145601 -0.0265869, + -0.061936598 -0.0238293 -0.031636398, + -0.060217001 -0.023163 -0.036551401, + -0.059652399 -0.0059628799 -0.046004798, + -0.049685601 -0.00555368 -0.056004401, + -0.067583501 0.0068201302 -0.0265975, + -0.066978499 0.0113191 -0.026593899, + -0.066038199 0.0066687199 -0.031612098, + -0.066334501 0.00224295 -0.0316156, + -0.067954801 0.0210845 -0.0058823298, + -0.067998298 0.021093801 -0.00063300302, + -0.062367599 -0.0020522999 -0.0413341, + -0.0597996 -0.0048635202 -0.0460039, + -0.047194201 0.0165585 -0.055986799, + -0.064492702 0.00218534 -0.036531199, + -0.062367599 0.00211812 -0.041330799, + -0.064492702 -0.0021271601 -0.0365346, + -0.066334501 -0.0021925899 -0.031619199, + -0.066038199 -0.0066183698 -0.0316227, + -0.0642047 -0.0064300201 -0.036538001, + -0.070758201 -0.0023568501 -0.0111388, + -0.070758201 0.0023745899 -0.011135, + -0.0691441 0.0023288899 -0.0215046, + -0.067886703 0.00229083 -0.0266011, + -0.067886703 -0.00224847 -0.026604701, + -0.0691441 -0.0022946401 -0.0215082, + -0.070102401 -0.00233073 -0.016347099, + -0.051870801 -0.043832801 -0.0266378, + -0.050684799 -0.042826101 -0.031651501, + -0.0488258 -0.047199499 -0.026640501, + -0.054684099 -0.040270299 -0.026635, + -0.0617094 -0.033825502 0.0097852396, + -0.063830398 -0.029628299 0.0097885802, + -0.057316799 -0.0422308 -0.00068342697, + -0.0624342 -0.034214299 -0.00067704299, + -0.062205698 -0.034093201 0.0045660902, + -0.060009498 -0.038308099 -0.00068030303, + -0.059971198 -0.0382795 -0.0059296, + -0.062394299 -0.0341883 -0.0059263501, + -0.064580098 -0.0299679 -0.000673662, + -0.0361492 -0.061035499 0.00454464, + -0.036258802 -0.061212201 -0.00594786, + -0.0321096 -0.063542202 -0.00070039701, + -0.032088999 -0.063497402 -0.0059496802, + -0.043876901 -0.055553101 -0.0111811, + -0.040067799 -0.058359802 -0.0111834, + -0.0440947 -0.055833202 -0.0059435801, + -0.0434702 -0.055034 -0.016388999, + -0.047490101 -0.0524984 -0.0111787, + -0.0266016 -0.0422916 -0.056033701, + -0.037141401 -0.047085699 -0.046037499, + -0.051950201 -0.038247999 -0.0365634, + -0.049277499 -0.041632399 -0.036566101, + -0.054723799 -0.0299566 -0.0413564, + -0.056588501 -0.030982301 -0.0365576, + -0.037183098 -0.047049198 -0.046037499, + -0.052598599 -0.033544701 -0.041359201, + -0.050238401 -0.036982998 -0.041361999, + -0.047049899 -0.052007601 -0.0163866, + -0.042096298 -0.053286102 -0.026645301, + -0.0455628 -0.0503553 -0.026643001, + -0.041133799 -0.052063201 -0.031658899, + -0.042876001 -0.054277498 -0.021549599, + -0.046406701 -0.051292501 -0.0215472, + -0.061613798 -0.0285706 -0.0266257, + -0.060205001 -0.0279129 -0.031639598, + -0.063386001 -0.0243914 -0.026622299, + -0.059566502 -0.032622099 -0.0266289, + -0.058204498 -0.031871799 -0.031642798, + -0.064538799 -0.0299445 -0.0059229699, + -0.066395096 -0.025567001 -0.0059194802, + -0.0676191 -0.0209668 -0.0111536, + -0.0660671 -0.0254364 -0.0111572, + -0.064855203 -0.0249904 0.0149693, + -0.066378698 -0.020602699 0.0149728, + -0.067208901 -0.0208562 0.0097955596, + -0.065666303 -0.0252987 0.0097920299, + -0.063042 -0.029266501 0.0149659, + -0.061981101 -0.0287783 0.020083901, + -0.063763797 -0.024574099 0.020087199, + -0.065261699 -0.020260399 0.020090699, + -0.068530999 -0.0115716 0.01498, + -0.066468097 -0.015856201 0.020094199, + -0.068291403 -0.0022992101 0.020105001, + -0.069460303 -0.0023342001 0.0149873, + -0.069460303 0.00231033 0.014991, + -0.068291403 0.00226719 0.020108599, + -0.066826299 0.0022142199 0.025149301, + -0.066826299 -0.00225427 0.0251457, + -0.064779297 -0.0065408102 0.0300889, + -0.048158601 -0.040743399 0.034897499, + -0.050770599 -0.0374359 0.034900099, + -0.046386 -0.039248399 0.0396071, + -0.045331601 -0.043869101 0.034894999, + -0.043662999 -0.042259201 0.039604701, + -0.0497186 -0.0420583 0.0300606, + -0.0484928 -0.026613399 0.048588499, + -0.046609499 -0.0297931 0.048586, + -0.0509951 -0.0279814 0.044181101, + -0.052747902 -0.0245129 0.044183899, + 0.0559441 0.035738599 -0.031588901, + 0.052598599 0.0336105 -0.041305698, + 0.051634699 0.030595699 -0.0459757, + 0.048299 0.035623901 -0.045971598, + 0.050238401 0.037048802 -0.041303001, + 0.054390799 0.034750901 -0.0365052, + 0.04823 0.035727799 -0.045971598, + 0.064779297 -0.0065408102 0.0300889, + 0.065069899 0.0021515801 0.030095801, + 0.066826299 -0.00225427 0.0251457, + 0.066826299 0.0022142199 0.025149301, + 0.063028298 -0.0021351101 0.034928199, + 0.0607084 -0.0020612199 0.039636701, + 0.0627468 -0.0063401898 0.034924898, + 0.065069899 -0.0021995001 0.0300924, + 0.063028298 0.0020794901 0.0349316, + 0.039696399 -0.057814602 -0.016391199, + 0.0357453 -0.060336899 -0.0163932, + 0.041858599 -0.046248 -0.0413693, + 0.041776299 -0.043030102 -0.046034299, + 0.037183098 -0.047049198 -0.046037499, + 0.0386739 -0.048940498 -0.041371498, + 0.064219996 -0.0297924 -0.0111606, + 0.066395096 -0.025567001 -0.0059194802, + 0.047581501 -0.052611999 0.0045513501, + 0.0477258 -0.052763201 -0.00594114, + 0.043961398 -0.055672701 0.0045489101, + 0.044122901 -0.0558732 -0.00069428998, + 0.0094545903 -0.0703049 0.0045372602, + 0.035417899 -0.059808999 0.0149416, + 0.031344801 -0.062041201 0.0149398, + 0.043876901 -0.055553101 -0.0111811, + 0.0434702 -0.055034 -0.016388999, + 0.040067799 -0.058359802 -0.0111834, + 0.0440947 -0.055833202 -0.0059435801, + 0.047490101 -0.0524984 -0.0111787, + 0.0312021 -0.061729699 -0.021555601, + 0.059566502 -0.032622099 -0.0266289, + 0.060669798 -0.0332308 -0.021532901, + 0.058313601 -0.0372089 -0.021536, + 0.057253201 -0.036527898 -0.026632, + 0.062755004 -0.0291044 -0.0215296, + 0.063624702 -0.029511999 -0.0163687, + 0.065454699 -0.0251964 -0.016365301, + 0.066992298 -0.0207683 -0.0163617, + 0.0596749 -0.038086198 -0.0111672, + 0.0615106 -0.033695702 -0.016372001, + 0.059121698 -0.037728898 -0.016375201, + 0.056997199 -0.041986901 -0.0111703, + 0.056588501 -0.030982301 -0.0365576, + 0.056604698 -0.0262344 -0.041353401, + 0.054723799 -0.0299566 -0.0413564, + 0.0585334 -0.027133301 -0.0365545, + 0.060205001 -0.0279129 -0.031639598, + 0.058204498 -0.031871799 -0.031642798, + 0.0559441 -0.035688199 -0.031645801, + 0.064560004 -0.0248478 -0.021526201, + 0.066076599 -0.0204801 -0.021522701, + 0.068835303 -0.0069078002 -0.021511899, + 0.068218999 -0.01149 -0.0215156, + 0.067298099 -0.0160209 -0.021519201, + 0.066038199 -0.0066183698 -0.0316227, + 0.0642047 -0.0064300201 -0.036538001, + 0.067583501 -0.0067777601 -0.026608299, + 0.066978499 -0.0112767 -0.0266119, + 0.063629903 -0.0107039 -0.036541399, + 0.0623958 -0.024051299 0.0251284, + 0.062183201 -0.019313401 0.0300787, + 0.056358799 -0.035998099 0.0251188, + 0.0599216 -0.032853901 0.0200806, + 0.0575944 -0.036782999 0.0200775, + 0.061981101 -0.0287783 0.020083901, + 0.058635999 -0.032153402 0.025121899, + 0.069945998 -0.0118022 0.0045838398, + 0.070202999 -0.0118413 -0.00065922801, + 0.070577897 -0.0071038799 0.00458758, + 0.069388099 -0.0117121 0.00980285, + 0.048063099 -0.046503 0.0251105, + 0.046799898 -0.045285299 0.030058, + 0.043672301 -0.048310202 0.030055599, + 0.051060501 -0.043189101 0.0251131, + 0.055010099 -0.040547699 0.0200745, + 0.044851098 -0.049609501 0.025108, + 0.041438699 -0.0524945 0.0251057, + -0.0141019 -0.0693703 -0.0111921, + -0.0276387 -0.065171003 -0.0111888, + -0.031930499 -0.0631795 -0.0111872, + -0.0232234 -0.066871598 -0.0111902, + -0.018797301 -0.068616502 -0.0059537599, + -0.0141291 -0.069516301 0.0045378902, + -0.014181 -0.069767699 -0.00070535397, + -0.0094545903 -0.0703049 0.0045372602, + -0.018591 -0.067875803 0.0097581204, + -0.0140164 -0.068966098 0.0097572599, + -0.018740499 -0.0684174 0.0045387601, + -0.0183613 -0.067041598 0.0149358, + -0.0230825 -0.066482499 0.0097592296, + -0.0227974 -0.065665603 0.0149369, + 0.035256699 -0.059507798 -0.0215538, + -6.282158e-013 -0.0623696 -0.041382201, + 3.7236759e-012 -0.059884202 -0.046047699, + 6.0912636e-013 -0.049955402 -0.056039799, + 0.035316501 -0.051414199 -0.041373499, + 0.037141401 -0.047085699 -0.046037499, + 0.023392901 -0.055132501 -0.046043899, + 0.0216942 -0.045003898 -0.056035899, + 0.0266016 -0.0422916 -0.056033701, + 0.016514 -0.047149599 -0.056037601, + -0.0216942 -0.045003898 -0.056035899, + -0.00920578 -0.059252899 -0.0460472, + -0.0093489503 -0.0695026 -0.016400499, + -0.0094364202 -0.0701572 -0.0111928, + -0.0045368699 -0.067751698 -0.0266569, + -0.0092211496 -0.068548203 -0.021561, + -1.7666557e-012 -0.070788801 -0.0111933, + 0.0045368699 -0.067751698 -0.0266569, + 4.5561748e-013 -0.071144603 -0.0059557701, + 0.0047287699 -0.070630699 -0.0111931, + 0.0047552902 -0.071035303 -0.000706363, + -0.053563699 -0.045272298 -0.016381299, + -0.050419401 -0.048748799 -0.016384, + -0.0540649 -0.045700099 -0.0111733, + -0.0564688 -0.0415936 -0.0163783, + -0.052831501 -0.044649199 -0.021542, + -0.0497302 -0.048078202 -0.0215447, + -0.040292501 -0.058695398 -0.00069653703, + -0.044122901 -0.0558732 -0.00069428998, + -0.0402667 -0.058653701 -0.0059458301, + -0.036281999 -0.0612556 -0.00069857598, + -0.051060501 -0.043189101 0.0251131, + -0.052415099 -0.038643699 0.030063299, + -0.054877602 -0.035056598 0.0300662, + -0.058635999 -0.032153402 0.025121899, + -0.0599216 -0.032853901 0.0200806, + -0.056358799 -0.035998099 0.0251188, + -0.053829901 -0.039682101 0.0251159, + -0.057106901 -0.042080302 0.0045597302, + -0.059789799 -0.0381721 0.0045628501, + -0.0133183 -0.065543801 0.025095301, + -0.0136103 -0.066976301 0.0200535, + -0.0091074398 -0.067735799 0.020052901, + -0.0089120502 -0.066287003 0.025094699, + -0.0086778197 -0.064549297 0.0300427, + -0.0129683 -0.063825503 0.0300433, + -0.0172008 -0.062816903 0.030044099, + -0.0219329 -0.063183904 0.025097201, + -0.017665099 -0.064507902 0.0250961, + -0.0224138 -0.064564802 0.0200554, + -0.0261028 -0.061578002 0.025098501, + -0.021356501 -0.0615278 0.0300451, + 5.3040038e-012 -0.055335801 0.0485656, + 6.5230365e-012 -0.052233599 0.052800398, + -0.00369344 -0.0552123 0.048565701, + 0.00348601 -0.052117102 0.052800499, + 0.00369344 -0.0552123 0.048565701, + 1.2242733e-012 -0.058185801 0.044157099, + -0.00388403 -0.058056001 0.0441572, + -0.00775071 -0.057666901 0.044157501, + -0.012099 -0.0595566 0.039590899, + -0.0080961604 -0.060231801 0.0395904, + -0.0160478 -0.058615599 0.039591599, + -0.0073703802 -0.054842401 0.048565999, + -0.0111484 -0.012645 0.076778203, + -0.0130226 -0.0106937 0.076779701, + -0.0121248 -0.0117071 0.076778904, + -0.019255299 -0.0157804 0.074046403, + -0.0150585 -0.0145241 0.075543597, + -0.0102853 -0.0308642 0.070278801, + -0.047581501 -0.052611999 0.0045513501, + -0.0477564 -0.0528013 -0.00069184398, + -0.043961398 -0.055672701 0.0045489101, + -0.040144999 -0.0584847 0.0045466698, + -0.039824702 -0.058022302 0.0097659696, + -0.050989099 -0.049316499 0.0045539699, + -0.047201999 -0.052196499 0.0097706104, + -0.0458344 -0.0506928 0.020066399, + -0.038670901 -0.056349698 0.020061901, + -0.041438699 -0.0524945 0.0251057, + -0.037841301 -0.0551451 0.025103601, + 0.051929399 -0.0052661998 0.0528378, + 0.053155798 -0.033961099 0.0349029, + 0.030919099 -0.037857801 0.056855999, + 0.0276068 -0.040264402 0.056854099, + 0.0264073 -0.0411359 0.056853399, + 0.026224 -0.029653 0.065562204, + 0.0239322 -0.027068 0.068038702, + 0.023538901 -0.046624001 0.052804898, + 0.044406801 -0.037578799 0.044173501, + 0.0418 -0.040461101 0.044171199, + 0.037645102 -0.047702 0.039600302, + 0.040745001 -0.045081198 0.039602399, + 0.036038801 -0.045671798 0.044167001, + 0.032910202 -0.047977 0.044165201, + 0.034377001 -0.050110001 0.039598402, + 0.0390836 -0.049520001 0.034890499, + 0.042302102 -0.046799 0.0348926, + 4.2090619e-012 -0.068345599 0.020052399, + 2.7887005e-012 -0.066883601 0.0250942, + 0.00456391 -0.068193004 0.0200525, + -0.00456391 -0.068193004 0.0200525, + -4.297714e-013 -0.069510899 0.0149339, + 0.0046420302 -0.069355801 0.014934, + -0.0046420302 -0.069355801 0.014934, + 0.028442301 -0.056313202 0.034885101, + 0.034074798 -0.057549499 0.025101701, + 0.037841301 -0.0551451 0.025103601, + 0.033179201 -0.056041501 0.030049499, + 0.034821901 -0.0588069 0.020059999, + 0.0078717899 -0.0236379 0.0740401, + 0.0059489501 -0.0241949 0.074039698, + 0.0180058 -0.042308901 0.059953101, + 0.0191145 -0.044907998 0.0568504, + 0.0109935 -0.04465 0.059951302, + 0.00650266 -0.0484096 0.056847598, + 0.012523 -0.037563201 0.0655559, + 0.0114286 -0.034286998 0.068032898, + -0.0237571 -0.031667199 0.065560602, + -0.0228929 -0.036252402 0.062861897, + -0.019905601 -0.037977099 0.062860601, + -0.0141461 -0.0332563 0.068033703, + -0.0155008 -0.036433902 0.065556802, + -0.0167719 -0.032010399 0.068034701, + -0.021136099 -0.033476301 0.065559201, + -0.018378099 -0.035068698 0.065557897, + 0.0103958 -0.051187702 0.0528013, + 0.0110144 -0.054227699 0.048566502, + 0.0069564502 -0.051767901 0.052800801, + 0.00782206 -0.048181299 0.0568478, + 0.022701399 -0.0535716 0.044160798, + 0.019074799 -0.054968301 0.044159599, + 0.0153631 -0.056119699 0.044158701, + 0.0261028 -0.061578002 0.025098501, + 0.030156201 -0.059696998 0.0251, + 0.0266751 -0.062923603 0.0200567, + 0.0219329 -0.063183904 0.025097201, + 0.029363601 -0.058132499 0.0300478, + 0.025416801 -0.059964001 0.0300464, + 0.021356501 -0.0615278 0.0300451, + -0.0040571401 -0.0606382 0.039590001, + -0.0042121802 -0.062950499 0.0348798, + 0.0043486198 -0.064984798 0.030042401, + 5.4030754e-013 -0.065130197 0.030042199, + -0.0043486198 -0.064984798 0.030042401, + 0.0040571401 -0.0606382 0.039590001, + 0.00388403 -0.058056001 0.0441572, + 0.0080961604 -0.060231801 0.0395904, + -1.7289333e-012 -0.060773801 0.039589901, + 0.0084055504 -0.0625287 0.034880102, + 0.0042121802 -0.062950499 0.0348798, + 2.4092178e-013 -0.063091397 0.034879699, + -0.061981101 0.028746299 0.020129699, + -0.0599216 0.032821901 0.020132899, + -0.063042 0.0292427 0.0150125, + -0.064855203 0.024966599 0.0150091, + -0.032345701 0.040917698 0.052874599, + -0.033027399 0.035940401 0.056914698, + -0.039748799 0.038403399 0.0486403, + -0.039856199 0.033654202 0.052868798, + -0.037516501 0.036240999 0.052870899, + -0.0422277 0.035662599 0.048638102, + -0.035009298 0.038665801 0.052872799, + -0.039006501 0.043092199 0.044237699, + -0.037092399 0.040972501 0.0486423, + -0.0418 0.0403907 0.044235598, + -0.036038801 0.045601401 0.0442397, + -0.040745001 0.045018099 0.0396742, + -0.027395399 0.054182101 0.039681502, + -0.035690598 0.051964398 0.034971301, + -0.036846701 0.053652301 0.030136799, + -0.0374065 0.056983501 0.020728201, + -0.038670901 0.056317698 0.0201516, + -0.0128948 0.047022101 0.056923602, + -0.0103958 0.051103499 0.052882701, + -0.0116722 0.0473064 0.056923799, + -0.0137611 0.0468207 0.056923401, + -0.0109935 0.044554401 0.060022298, + -0.0110144 0.054150298 0.048652802, + 0.0032596199 0.048665401 0.056924898, + -5.5092662e-012 0.0521494 0.052883498, + -0.00348601 0.052032899 0.052883402, + -0.0069564502 0.051683702 0.0528832, + -0.00687563 0.0278379 0.072328001, + -0.0049968399 0.020212701 0.075571299, + -0.0059489501 0.0240769 0.074078098, + 0.0135639 0.040578801 0.062923104, + 0.00318215 0.039365798 0.065617204, + 0.00344664 0.042644199 0.062924802, + 0.0068709301 0.042228501 0.0629244, + 0.0102507 0.041538499 0.062923901, + 0.0029040501 0.035918899 0.0680888, + -0.041827898 -0.0252684 0.056866001, + -0.047342401 -0.022011301 0.052824501, + -0.048704099 -0.018800201 0.052827001, + -0.050159499 -0.023315201 0.0485911, + -0.041501898 -0.019740701 0.059971102, + -0.042951901 -0.0163374 0.059973799, + -0.038697701 -0.0184124 0.062876202, + -0.0464538 -0.0151391 0.0568741, + -0.050769702 -0.0121411 0.052832302, + -0.046853598 -0.0136183 0.0568753, + -0.045899801 -0.0018975 0.059985299, + -0.051929399 -0.0052661998 0.0528378, + -0.054526798 -0.00923621 0.048602398, + -0.051464502 -0.0087230997 0.052835099, + -0.0550193 -0.00557373 0.0486053, + -0.0486653 -0.0042251102 0.056882799, + -0.055266201 -0.00188649 0.048608199, + -0.0537907 -0.0128577 0.0485995, + -0.055539802 -0.0172638 0.044189699, + -0.0326056 -0.0155258 0.068047903, + -0.033744901 -0.0128519 0.068049997, + -0.029343801 -0.0139798 0.070292301, + -0.028128199 -0.016295901 0.070290402, + -0.030632701 -0.025063099 0.065565899, + -0.034247998 -0.0198253 0.065569997, + -0.035728101 -0.0170053 0.065572299, + -0.031254999 -0.0180992 0.068045802, + -0.0297016 -0.0205558 0.068043903, + -0.032545902 -0.022516999 0.065567903, + -0.037094701 -0.0214667 0.062873699, + -0.037516501 -0.036325201 0.052813102, + -0.035009298 -0.03875 0.052811202, + -0.039748799 -0.0384808 0.048579101, + -0.037242699 -0.031530902 0.056860998, + -0.035027899 -0.034086801 0.056859002, + -0.039856199 -0.033738401 0.052815098, + -0.035583101 -0.0291005 0.059963599, + -0.039282501 -0.028991001 0.056862999, + -0.041125 -0.0262964 0.0568652, + -0.0439918 -0.0281255 0.052819598, + -0.038679998 -0.029872101 0.056862298, + -0.037805501 -0.026143 0.059966002, + -0.037841301 0.055105101 0.0251914, + -0.034975499 0.056979999 0.0251571, + -0.036245398 0.056981701 0.022974901, + -0.0623958 0.024011301 0.025166599, + -0.060651399 0.028125299 0.0251699, + -0.063763797 0.024542101 0.0201263, + -0.060755901 0.023375699 0.030112701, + -0.065042198 0.0154804 0.0251598, + -0.065261699 0.020228401 0.020122901, + -0.066468097 0.015824201 0.020119401, + -0.063861601 0.0197901 0.0251633, + -0.067377701 0.0113492 0.0201158, + -0.065932199 0.0111013 0.025156301, + -0.064199403 0.0108051 0.0301027, + -0.063332699 0.0150689 0.030106099, + -0.062183201 0.0192654 0.0301094, + 0.069945998 0.0117948 0.0046026302, + 0.070577897 0.0070965602 0.00459889, + 0.068869203 0.016421299 -0.0111238, + 0.069811597 0.0117847 -0.0111275, + 0.0704422 0.0070954198 -0.0111313, + 0.0707919 0.00712639 -0.0058934502, + 0.0708372 0.0071268501 -0.000644124, + 0.069150001 0.0069446 0.0149947, + 0.069460303 0.00231033 0.014991, + 0.070014901 0.0070357602 0.0098177698, + 0.059057299 0.0273815 0.030115901, + 0.059896201 0.0100717 0.039646301, + 0.060437299 0.0060485099 0.039643101, + 0.0627468 0.0062845601 0.034934901, + 0.064779297 0.0064928802 0.030099301, + 0.062183201 0.0192654 0.0301094, + 0.060755901 0.023375699 0.030112701, + 0.063861601 0.0197901 0.0251633, + 0.0487464 0.0111707 -0.055991098, + 0.061613798 0.028612999 -0.026580101, + 0.058204498 0.031922199 -0.031592, + 0.063386001 0.024433799 -0.0265835, + 0.062367599 -0.0020522999 -0.0413341, + 0.066074297 0.0157675 -0.026590399, + 0.0590882 0.0100029 -0.045992099, + 0.061631601 0.0191474 -0.036517698, + 0.061936598 0.023879699 -0.0315984, + 0.063391604 0.0196895 -0.031601701, + 0.064563498 0.0154114 -0.031605098, + 0.054723799 0.0300224 -0.0413086, + 0.054495402 0.0251415 -0.045979999, + 0.066334501 0.00224295 -0.0316156, + 0.067886703 0.00229083 -0.0266011, + 0.066334501 -0.0021925899 -0.031619199, + 0.067583501 0.0068201302 -0.0265975, + 0.066038199 0.0066687199 -0.031612098, + 0.040188901 0.0276943 0.056908201, + 0.0293185 0.0389731 0.056917202, + 0.0327521 0.036165498 0.056914899, + 0.0302254 0.0382316 0.056916598, + 0.032345701 0.040917698 0.052874599, + 0.033129901 0.031773999 0.060012098, + 0.035053499 0.033855598 0.0569131, + 0.0369142 0.031941 0.056911599, + 0.0304619 0.0343366 0.060014199, + 0.033027399 0.035940401 0.056914698, + 0.055098802 0.025536999 0.039658599, + 0.0588497 0.022637701 0.034947898, + 0.052747902 0.0244425 0.044222899, + 0.051602099 0.019835399 0.048625499, + 0.030822501 0.057028499 -0.035815999, + 0.0328849 0.0555497 -0.036488701, + 0.033814698 0.057025399 -0.031851601, + 0.038578101 0.057018399 -0.023034601, + 0.032369301 0.057027001 -0.033872601, + 0.042349 0.056997199 0.00360044, + 0.0302375 0.057029098 -0.036486901, + 0.0415635 0.057010699 -0.013404, + 0.040970601 0.0570127 -0.015939999, + 0.0575944 0.036750998 0.020136099, + 0.063042 0.0292427 0.0150125, + 0.063830398 0.0296127 0.0098357499, + 0.060947198 0.033388101 0.0150158, + 0.061981101 0.028746299 0.020129699, + 0.065666303 0.0252831 0.0098323002, + 0.0599216 0.032821901 0.020132899, + 0.053073101 0.0448585 0.0150249, + 0.055951599 0.041213501 0.015022, + 0.066378698 0.0205789 0.0150056, + 0.067208901 0.0208406 0.0098287696, + 0.064855203 0.024966599 0.0150091, + 0.036846701 0.053652301 0.030136799, + 0.0349412 0.056979999 0.025191801, + 0.035982899 0.056981299 0.0234471, + 0.034664299 0.0569796 0.025655599, + 0.0408848 0.056991 0.0113678, + 0.050989099 0.049309202 0.0046325098, + 0.047581501 0.052604701 0.0046351301, + 0.043961398 0.0556654 0.0046375701, + 0.042017799 0.030916899 0.0528666, + 0.039856199 0.033654202 0.052868798, + -0.041115999 0.0262041 0.056906998, + -0.0439918 0.028041299 0.052864298, + -0.0428016 0.0234088 0.0569048, + -0.039782699 0.0229207 0.060005099, + -0.0276125 0.040176 0.0569181, + -0.02871 0.039470699 0.0569175, + -0.0248664 0.041940801 0.0569195, + -0.024018399 0.0424858 0.056919899, + -0.0295376 0.042986698 0.052876201, + -0.026063301 0.041171599 0.0569189, + -0.0245518 0.038777798 0.060017701, + -0.040188901 0.0276943 0.056908201, + -0.042017799 0.030916899 0.0528666, + -0.0403197 0.0275246 0.056908, + -0.035583101 0.0290049 0.0600099, + -0.0369142 0.031941 0.056911599, + -0.039514199 -0.00164463 0.065584503, + -0.036060899 -0.00150744 0.068058997, + -0.039514199 0.0015401799 0.065586999, + -0.042520899 -0.0052130399 0.0628867, + -0.042798501 -0.00177481 0.062889397, + -0.042798501 0.00167465 0.062892199, + -0.052162301 0.00170194 0.052843399, + -0.055266201 0.00180907 0.048611201, + -0.051929399 0.0051820399 0.0528461, + -0.052162301 -0.0017861 0.052840602, + -0.0488245 0.00134948 0.056887198, + -0.0441234 0.0127327 0.059997, + -0.047239799 0.0123718 0.056896001, + -0.0450087 0.0091408296 0.059994102, + -0.042951901 0.0162418 0.059999701, + -0.045516402 0.017675901 0.0569002, + -0.040049799 0.0151387 0.062902898, + -0.041142099 0.0118669 0.062900297, + -0.041967601 0.0085176704 0.0628976, + -0.035360798 -0.0072731799 0.0680544, + -0.0318233 -0.0065528098 0.070298202, + -0.034665201 -0.0100951 0.068052202, + -0.038747001 -0.0079624997 0.065579496, + -0.035827 -0.0044044098 0.068056703, + -0.039257899 -0.0048189401 0.065582, + -0.0311973 -0.0090923598 0.070296198, + -0.0287071 -0.00121444 0.072304897, + -0.028520901 -0.00352058 0.072302997, + -0.032453399 0.00125188 0.070304401, + -0.032453399 -0.00136384 0.0703023, + -0.032242902 -0.0039710202 0.070300303, + -0.021527801 -0.0124881 0.074049003, + -0.0236446 -0.0163783 0.072292797, + -0.024881201 -0.0144228 0.072294302, + -0.0259565 -0.0123741 0.072296001, + -0.0222547 0.018112799 0.072320201, + -0.025158901 0.0204856 0.070319697, + -0.035827 0.0042960201 0.068063602, + -0.032242902 0.0038590599 0.070306502, + -0.035360798 0.0071647898 0.068065897, + -0.036060899 0.00139905 0.0680613, + -0.039257899 0.0047144899 0.065589599, + -0.0260283 0.0249463 0.068080097, + -0.026224 0.0295486 0.065609299, + -0.028403699 0.032011099 0.062916301, + -0.0285208 0.0273425 0.0656076, + -0.0237571 0.031562801 0.065610997, + -0.0239322 0.0269596 0.068081699, + -0.021680901 0.0287979 0.068083197, + -0.0049671 0.0115963 0.077762097, + -0.00898539 0.014148 0.076799497, + -0.0058890898 0.0111588 0.077761702, + -0.0078128902 0.014825 0.076800004, + -0.0097032702 0.0184278 0.075569898, + -0.0076127499 0.0100688 0.077760801, + -0.0100996 0.0133791 0.076798901, + -0.00677288 0.0106485 0.0777613, + -0.028128199 0.0161839 0.0703163, + -0.026730301 0.018394601 0.070318103, + -0.021527801 0.0123701 0.0740688, + -0.0236446 0.016263099 0.0723188, + -0.024881201 0.0143076 0.072317198, + -0.0104291 -0.00726052 0.077747002, + -0.0180823 0.0103796 0.075563498, + -0.016173501 0.013145 0.075565703, + -0.0150585 0.0144037 0.075566702, + -0.0138359 0.0094891395 0.076795802, + -0.0171836 0.0118008 0.075564601, + -0.019255299 0.0156624 0.0740714, + -0.020457899 0.0140621 0.074070103, + -0.0100996 -0.0135013 0.076777503, + -0.0078128902 -0.0149473 0.076776303, + -0.0049671 -0.0117201 0.0777435, + -0.0097032702 -0.0185482 0.075540401, + -0.0081841396 -0.019269099 0.075539902, + -0.0049968399 -0.0203331 0.075539, + -1.9691373e-013 -0.0085408501 0.078437902, + -0.00068222702 -0.0085133901 0.078437902, + -0.0073425001 0.0041766702 0.078447998, + -0.0109745 0.0062742601 0.077757798, + -0.0145595 0.0083448598 0.0767949, + 0.027596001 0.0079357103 0.072312102, + 0.037094701 0.021366499 0.0629078, + 0.038697701 0.018312201 0.062905401, + 0.040049799 0.0151387 0.062902898, + 0.041967601 0.0085176704 0.0628976, + 0.042520899 0.0051128799 0.062894903, + 0.045602102 0.0054893401 0.0599912, + 0.0450087 0.0091408296 0.059994102, + 0.051929399 0.0051820399 0.0528461, + 0.048525002 0.00483739 0.05689, + 0.048347302 0.0069059902 0.056891602, + 0.052162301 0.00170194 0.052843399, + 0.0488245 0.00134948 0.056887198, + 0.0550193 0.0054963198 0.0486141, + 0.055266201 0.00180907 0.048611201, + 0.0171836 -0.0119212 0.075545698, + 0.027596001 -0.0080508599 0.072299398, + 0.037094701 -0.0214667 0.062873699, + 0.034247998 -0.0198253 0.065569997, + 0.0260283 -0.025054701 0.068040296, + 0.0141461 -0.0332563 0.068033703, + 0.018378099 -0.035068698 0.065557897, + 0.0112613 -0.026489001 0.072284698, + 0.0090979896 -0.027309399 0.072284102, + 0.0097435704 -0.022927999 0.074040703, + 0.021538001 -0.0243674 0.070284002, + 0.021680901 -0.028906301 0.068037197, + 0.0150941 -0.028815299 0.0702805, + 0.012731 -0.0299366 0.070279598, + 0.0167719 -0.032010399 0.068034701, + 0.019288899 -0.030557301 0.068035901, + 0.042951901 -0.0163374 0.059973799, + 0.041501898 -0.019740701 0.059971102, + 0.021527801 -0.0124881 0.074049003, + 0.026730301 -0.0185066 0.070288703, + 0.024881201 -0.0144228 0.072294302, + 0.025158901 -0.020597599 0.070286997, + 0.0297016 -0.0205558 0.068043903, + 0.027955599 -0.022879301 0.068042003, + 0.0232428 -0.0088737896 0.074051902, + 0.022458101 -0.0107155 0.074050397, + 0.042520899 -0.0052130399 0.0628867, + 0.045899801 -0.0018975 0.059985299, + 0.042798501 -0.00177481 0.062889397, + 0.0020290101 0.0081695896 0.078451201, + 0.00136003 0.0083061801 0.078451298, + -0.0215874 0.050870501 0.048650201, + -0.017120101 0.0492616 0.0528812, + -0.020375 0.048007902 0.052880201, + -0.0249395 0.049314901 0.048648998, + -0.023538901 0.046539798 0.052879099, + -0.0141461 0.033147901 0.068086602, + -0.012731 0.0298246 0.0703272, + -0.012523 0.0374588 0.065615602, + -0.0155008 0.0363295 0.0656147, + -0.0132858 0.0209509 0.074075602, + -0.0153554 0.024225 0.072325103, + -0.0111595 0.017587099 0.075569198, + -0.0125433 0.016631899 0.075568497, + -0.0097435704 0.022810001 0.0740771, + -0.0112613 0.0263738 0.072326802, + -0.0078717899 0.0235199 0.074077703, + -0.0115522 0.021951901 0.074076399, + -0.0081841396 0.0191487 0.075570501, + -0.0039400999 0.00744473 0.078450702, + -0.00101969 0.0125692 0.077762797, + -0.063624702 0.029538 -0.0163217, + -0.065454699 0.0252224 -0.016325099, + -0.064219996 0.0298102 -0.0111132, + -0.0615106 0.0337217 -0.016318399, + -0.064560004 0.024882 -0.021486601, + -0.062086102 0.034033101 -0.0111098, + -0.063386001 0.024433799 -0.0265835, + -0.057316799 0.042231798 -0.00061617099, + -0.060009498 0.038309101 -0.00061929401, + -0.059971198 0.038288899 -0.00586863, + -0.057280101 0.042208999 -0.0058655101, + -0.059789799 0.038164798 0.0046236301, + -0.057106901 0.042073 0.0046267398, + -0.054168999 0.045793299 0.0046297102, + -0.053736899 0.045423999 0.0098483404, + -0.050582401 0.048911601 0.0098511204, + -0.042336199 0.026646201 -0.055978801, + -0.031801298 0.053724099 -0.041289698, + -0.054390799 0.034750901 -0.0365052, + -0.039091598 0.031219 -0.055975199, + -0.066074297 0.0157675 -0.026590399, + -0.0620891 -0.0062133102 -0.041337501, + -0.057543401 -0.0169563 -0.046013501, + -0.058232799 -0.0223951 -0.041350301, + -0.058982201 -0.0109679 -0.046008699, + -0.047194201 -0.0164693 -0.0560131, + -0.0487464 -0.0110815 -0.056008801, + -0.062770903 -0.01493 -0.0365448, + -0.0596008 -0.018455399 -0.041347198, + -0.061631601 -0.0190892 -0.0365481, + -0.060702499 -0.0144333 -0.041343998, + -0.061533201 -0.0103465 -0.041340798, + -0.063629903 -0.0107039 -0.036541399, + -0.0543552 -0.0251863 -0.046020102, + -0.056604698 -0.0262344 -0.041353401, + -0.055498298 -0.022765599 -0.046018101, + -0.045048401 -0.021649599 -0.056017298, + -0.068835303 0.0069420501 -0.0215009, + -0.070102401 0.00235676 -0.016343299, + -0.071109504 0.0023821399 -0.0058972202, + -0.0691645 0.0116796 -0.016335901, + -0.069789298 0.0070338799 -0.0163396, + -0.052555799 0.028839501 -0.045977101, + -0.045048401 0.021738799 -0.055982701, + -0.059986901 0.00129237 -0.045999002, + -0.049685601 0.0056428602 -0.055995502, + -0.068218999 -0.01149 -0.0215156, + -0.068835303 -0.0069078002 -0.021511899, + -0.066074297 -0.0157251 -0.0266154, + -0.063391604 -0.019639101 -0.031633001, + -0.064563498 -0.015361 -0.0316296, + -0.065447003 -0.0110144 -0.031626198, + -0.066978499 -0.0112767 -0.0266119, + -0.038441699 -0.055978701 -0.026647501, + -0.037562799 -0.054694299 -0.031661, + -0.0273825 -0.064562798 -0.016396601, + -0.0204696 -0.0589168 -0.0413794, + -0.0353553 -0.035310701 -0.056028102, + -0.0311745 -0.039046999 -0.0560311, + -0.039091598 -0.0311298 -0.056024801, + -0.044856399 -0.0433488 -0.041367002, + -0.047653802 -0.0402559 -0.041364599, + -0.045971099 -0.038520701 -0.0460307, + -0.041776299 -0.043030102 -0.046034299, + -0.041858599 -0.046248 -0.0413693, + -0.0463848 -0.044830799 -0.036568601, + -0.0432849 -0.047828801 -0.036571, + -0.050521001 -0.032216601 -0.046025701, + -0.0528684 -0.0283347 -0.046022601, + -0.042336199 -0.026557 -0.056021199, + -0.0496815 -0.033604901 -0.0460268, + -0.063624702 -0.029511999 -0.0163687, + -0.064219996 -0.0297924 -0.0111606, + -0.065454699 -0.0251964 -0.016365301, + -0.062755004 -0.0291044 -0.0215296, + -0.0615106 -0.033695702 -0.016372001, + -0.062086102 -0.034015302 -0.011164, + -0.066076599 -0.0204801 -0.021522701, + -0.066992298 -0.0207683 -0.0163617, + -0.064560004 -0.0248478 -0.021526201, + -0.064874999 -0.020103199 -0.0266189, + -0.067298099 -0.0160209 -0.021519201, + -0.0682308 -0.0162473 -0.0163581, + -0.065932199 -0.0111413 0.0251386, + -0.064199403 -0.0108531 0.0300855, + -0.065042198 -0.0155204 0.0251351, + -0.066527799 -0.0067127701 0.0251422, + -0.067377701 -0.0113812 0.020097701, + -0.067986399 -0.0068554902 0.0201013, + 0.050238401 -0.036982998 -0.041361999, + 0.0496815 -0.033604901 -0.0460268, + 0.045971099 -0.038520701 -0.0460307, + 0.052598599 -0.033544701 -0.041359201, + 0.051950201 -0.038247999 -0.0365634, + 0.054390799 -0.034692701 -0.036560498, + 0.059312899 -0.0378717 0.00978202, + 0.056651399 -0.0417489 0.0097789299, + 0.058580201 -0.037408099 0.0149594, + 0.0617094 -0.033825502 0.0097852396, + 0.060947198 -0.033411901 0.0149626, + 0.0511765 -0.049493499 -0.00068921002, + 0.0477564 -0.0528013 -0.00069184398, + 0.051143799 -0.049457699 -0.0059385002, + 0.050989099 -0.049316499 0.0045539699, + 0.039824702 -0.058022302 0.0097659696, + 0.035860799 -0.060552701 0.0097639598, + 0.0393328 -0.057309899 0.0149436, + 0.036281999 -0.0612556 -0.00069857598, + 0.036258802 -0.061212201 -0.00594786, + 0.040144999 -0.0584847 0.0045466698, + 0.040292501 -0.058695398 -0.00069653703, + 0.0402667 -0.058653701 -0.0059458301, + 0.031992 -0.0633137 0.0045428299, + 0.0321096 -0.063542202 -0.00070039701, + 0.0361492 -0.061035499 0.00454464, + 0.0094893305 -0.070559099 -0.00070598401, + 0.0047522499 -0.070985697 -0.00595565, + 0.0141291 -0.069516301 0.0045378902, + 0.050891101 -0.0492092 -0.0111761, + 0.0540649 -0.045700099 -0.0111733, + 0.0137802 -0.067779303 -0.021560401, + 0.0092211496 -0.068548203 -0.021561, + 0.0093489503 -0.0695026 -0.016400499, + 0.023008199 -0.0662475 -0.016398, + 0.054684099 -0.040270299 -0.026635, + 0.055696901 -0.041020699 -0.0215391, + 0.0564688 -0.0415936 -0.0163783, + 0.057280101 -0.0421996 -0.0059327199, + 0.057106901 -0.042080302 0.0045597302, + 0.054168999 -0.0458006 0.00455677, + 0.054368 -0.0459648 -0.00068639999, + 0.054333299 -0.045931201 -0.0059357001, + 0.064874999 -0.020103199 -0.0266189, + 0.061936598 -0.0238293 -0.031636398, + 0.063386001 -0.0243914 -0.026622299, + 0.060702499 -0.0144333 -0.041343998, + 0.0596008 -0.018455399 -0.041347198, + 0.061533201 -0.0103465 -0.041340798, + 0.058982201 -0.0109679 -0.046008699, + 0.057543401 -0.0169563 -0.046013501, + 0.060651399 -0.028165299 0.025125099, + 0.059896201 -0.0101349 0.039630201, + 0.062185101 -0.0105172 0.034921501, + 0.066378698 -0.020602699 0.0149728, + 0.067605801 -0.0161232 0.0149764, + 0.0684513 -0.016320501 0.0097991796, + 0.055951599 -0.041237399 0.0149564, + 0.0423472 -0.053640999 0.020064101, + 0.043072 -0.054554701 0.0149458, + 0.0458344 -0.0506928 0.020066399, + 0.043610699 -0.055232801 0.0097681899, + 0.047201999 -0.052196499 0.0097706104, + -0.0233537 -0.067254998 -0.00070335303, + -0.0277937 -0.065544903 -0.00070199103, + -0.0277759 -0.065498799 -0.0059512798, + -0.0233387 -0.067207798 -0.00595264, + -0.027691901 -0.0653091 0.0045412402, + -0.0232682 -0.067012899 0.00453988, + -0.0188093 -0.0686647 -0.00070447603, + 0.039153799 -0.057020001 -0.021551801, + 0.0328849 -0.0554915 -0.036577102, + 0.0043100398 -0.0643555 -0.036584198, + 0.0044331299 -0.0661982 -0.031670101, + 0.0132203 -0.065016396 -0.031669199, + 0.0135296 -0.066542402 -0.026655899, + 0.017048201 -0.062206902 -0.036582399, + 0.0088464599 -0.065754101 -0.031669799, + 0.0090534696 -0.067297399 -0.026656499, + 0.00559822 -0.049641099 -0.056039501, + 0.028144101 -0.055662502 -0.041376799, + 0.027052401 -0.0534999 -0.046042599, + 0.032115102 -0.050644901 -0.0460403, + 0.031801298 -0.053658299 -0.041375201, + 0.026750499 -0.053670101 -0.0460428, + 0.015842799 -0.057803601 -0.046046, + 0.0204696 -0.0589168 -0.0413794, + 0.019663701 -0.0565877 -0.046045098, + 0.021104001 -0.0561294 -0.0460447, + -0.019663701 -0.0565877 -0.046045098, + -0.0152352 -0.057996899 -0.046046201, + -0.016514 -0.047149599 -0.056037601, + -0.015842799 -0.057803601 -0.046046, + -0.016486401 -0.0601524 -0.041380402, + 0.0251913 -0.059379201 -0.036580201, + 0.0291031 -0.057564002 -0.036578801, + 0.021167001 -0.060929202 -0.036581401, + 0.024361299 -0.057417899 -0.0413782, + 1.505779e-012 -0.069165602 -0.0215615, + -2.1433634e-012 -0.0701285 -0.016401, + 0.00468494 -0.069971897 -0.0164009, + 0.0046208999 -0.069011003 -0.021561399, + -0.0046208999 -0.069011003 -0.021561399, + -0.00468494 -0.069971897 -0.0164009, + 4.3554062e-012 -0.067903496 -0.026657, + -0.060947198 -0.033411901 0.0149626, + -0.0154543 -0.0463311 0.0568492, + -0.0164141 -0.0460492 0.056849401, + -0.0146092 -0.053371001 0.048567198, + -0.0115828 -0.057020601 0.044158, + -0.0110144 -0.054227699 0.048566502, + -0.0137888 -0.050379101 0.0528019, + -0.017120101 -0.049345799 0.052802701, + -0.0153631 -0.056119699 0.044158701, + 0.00101969 -0.012693 0.077742703, + 0.0020327701 -0.0125701 0.0777428, + 0.0013528001 -0.016818499 0.076774798, + 0.0040128902 -0.012082 0.077743202, + 0.0065897098 -0.0155277 0.076775901, + 0.0097032702 -0.0185482 0.075540401, + 0.0081841396 -0.019269099 0.075539902, + 0.0125433 -0.016752301 0.075541899, + -0.0171836 -0.0119212 0.075545698, + -0.0138359 -0.0096114296 0.076780602, + -0.016173501 -0.0132654 0.0755447, + -0.020457899 -0.0141801 0.074047603, + -0.0112613 -0.026489001 0.072284698, + -0.012731 -0.0299366 0.070279598, + -0.0097435704 -0.022927999 0.074040703, + -0.0150941 -0.028815299 0.0702805, + 0.0040233498 -0.016384499 0.076775201, + 0.0026968201 -0.0166553 0.076774999, + 0.0033493401 -0.020669499 0.075538799, + 0.0049968399 -0.0203331 0.075539, + 0.00532379 -0.0160078 0.076775499, + 0.0066119302 -0.019865399 0.075539403, + -0.0090979896 -0.027309399 0.072284102, + -1.3245728e-012 -0.020939801 0.075538501, + -0.0020002499 -0.0248366 0.074039102, + 0.00168012 -0.0208722 0.075538598, + 0.0020002499 -0.0248366 0.074039102, + -0.043072 -0.054554701 0.0149458, + -0.043610699 -0.055232801 0.0097681899, + -0.0393328 -0.057309899 0.0149436, + -0.0423472 -0.053640999 0.020064101, + -0.049957599 -0.0483271 0.0149507, + -0.050582401 -0.048927199 0.0097732097, + -0.046618901 -0.051556099 0.0149482, + -0.049116898 -0.047518201 0.020068999, + -0.020375 -0.048092101 0.052803699, + -0.0191145 -0.044907998 0.0568504, + -0.0180058 -0.042308901 0.059953101, + 0.041827898 -0.0252684 0.056866001, + 0.0442922 -0.020598199 0.056869701, + 0.039782699 -0.0230163 0.059968501, + 0.042769101 -0.0234848 0.056867398, + 0.039282501 -0.028991001 0.056862999, + 0.041125 -0.0262964 0.0568652, + 0.037805501 -0.026143 0.059966002, + 0.0352511 -0.0243821 0.062871397, + 0.030632701 -0.025063099 0.065565899, + 0.035583101 -0.0291005 0.059963599, + 0.054526798 -0.00923621 0.048602398, + 0.0573406 -0.0097073196 0.0441957, + 0.0489018 -0.036062699 0.0396096, + 0.046386 -0.039248399 0.0396071, + 0.051199298 -0.032715902 0.039612301, + 0.050770599 -0.0374359 0.034900099, + 0.0304619 -0.034432199 0.0599594, + 0.0275963 -0.0367718 0.059957501, + 0.022015801 -0.0436159 0.056851398, + 0.021348 -0.0407231 0.059954401, + 0.024857899 -0.0420109 0.056852698, + 0.021551199 -0.043878201 0.056851201, + 0.026597699 -0.044947699 0.052806199, + 0.039856199 -0.033738401 0.052815098, + 0.039748799 -0.0384808 0.048579101, + 0.037516501 -0.036325201 0.052813102, + 0.0422277 -0.035739999 0.048581298, + 0.038679998 -0.029872101 0.056862298, + 0.037242699 -0.031530902 0.056860998, + 0.035027899 -0.034086801 0.056859002, + 0.0154543 -0.0463311 0.0568492, + 0.0110631 -0.047620401 0.056848198, + 0.0145468 -0.043620799 0.059952099, + 0.017120101 -0.049345799 0.052802701, + 0.0164141 -0.0460492 0.056849401, + 0.020375 -0.048092101 0.052803699, + 0.0137888 -0.050379101 0.0528019, + 0.0215874 -0.050947901 0.048569102, + 0.0181388 -0.052276101 0.0485681, + 0.0146092 -0.053371001 0.048567198, + -0.00863693 -0.035095599 0.068032302, + -0.0114286 -0.034286998 0.068032898, + -0.0102507 -0.041638698 0.062857702, + -0.0094640302 -0.038449299 0.0655552, + -0.012523 -0.037563201 0.0655559, + -0.0135639 -0.040679 0.062858403, + -0.0145468 -0.043620799 0.059952099, + 0.0073688198 -0.045389902 0.059950698, + 0.0055678501 -0.0485714 0.056847401, + 0.0180523 -0.065917701 0.020054299, + 0.017665099 -0.064507902 0.0250961, + 0.0136103 -0.066976301 0.0200535, + 0.0224138 -0.064564802 0.0200554, + -0.032138199 0.054232199 0.0349731, + -0.0114773 0.0569648 0.044248901, + -0.0115828 0.0569502 0.044248801, + -0.0216677 0.056968801 0.0392332, + -0.023713199 0.055890899 0.039682802, + -0.023573499 0.0569699 0.037859499, + -0.038458601 0.0569853 0.018418999, + -0.0423472 0.053608999 0.020149499, + 0.0027884699 0.048719499 0.056924898, + 0.017259501 0.022910699 0.072324097, + 0.0149334 0.0198137 0.0740747, + 0.0153554 0.024225 0.072325103, + 0.0132858 0.0209509 0.074075602, + 6.6425788e-012 0.032423701 0.070329197, + 0.0145468 0.0435252 0.060021501, + 0.012523 0.0374588 0.065615602, + 0.025158901 0.0204856 0.070319697, + 0.032545902 0.0224126 0.065603703, + 0.019288899 0.030448901 0.068084501, + 0.0173593 0.0273955 0.070325203, + 0.019511901 0.025909699 0.070324101, + 0.021136099 0.033371899 0.065612398, + -0.0511765 0.049494501 -0.000610388, + -0.054368 0.045965798 -0.00061319699, + -0.0477258 0.0527726 -0.0058570998, + -0.0311745 0.039136201 -0.055968899, + -0.0442922 -0.020598199 0.056869701, + -0.044430502 -0.020336101 0.056869902, + -0.0457693 -0.025124401 0.052822001, + -0.042769101 -0.0234848 0.056867398, + -0.039782699 -0.0230163 0.059968501, + -0.0450087 -0.00923636 0.059979498, + -0.047871601 -0.0097453604 0.056878399, + -0.0441234 -0.0128283 0.0599766, + -0.045602102 -0.00558487 0.0599824, + -0.041967601 -0.0086178305 0.062884003, + -0.059087601 -0.0141129 0.039627101, + -0.056566499 -0.0135157 0.044192601, + -0.058015201 -0.018028099 0.039624002, + -0.0613456 -0.0146472 0.0349182, + -0.059896201 -0.0101349 0.039630201, + -0.0573406 -0.0097073196 0.0441957, + -0.062185101 -0.0105172 0.034921501, + -0.025158901 -0.020597599 0.070286997, + -0.027955599 -0.022879301 0.068042003, + -0.026730301 -0.0185066 0.070288703, + -0.0222547 -0.018228 0.0722913, + -0.033596501 0.0569783 0.0272724, + -0.031967498 0.056976501 0.029499101, + -0.033179201 0.055993602 0.030138699, + 0.0692553 0.016504901 -0.000636657, + 0.070202999 0.0118423 -0.00064036902, + 0.069001801 0.0164403 0.0046063298, + 0.067998298 0.021093801 -0.00063300302, + 0.069211103 0.0164985 -0.0058859801, + 0.070158198 0.0118389 -0.00588969, + 0.066468097 0.015824201 0.020119401, + 0.065261699 0.020228401 0.020122901, + 0.067605801 0.016099401 0.015002, + 0.068530999 0.0115478 0.0149984, + 0.065932199 0.0111013 0.025156301, + 0.066527799 0.00667272 0.025152801, + 0.065042198 0.0154804 0.0251598, + 0.067377701 0.0113492 0.0201158, + 0.067986399 0.0068234699 0.0201122, + 0.0613456 0.0145916 0.034941498, + 0.0602322 0.018656399 0.034944799, + 0.059087601 0.0140497 0.039649501, + 0.062185101 0.0104616 0.034938201, + 0.063332699 0.0150689 0.030106099, + 0.064199403 0.0108051 0.0301027, + 0.068218999 0.0115242 -0.021497199, + 0.066978499 0.0113191 -0.026593899, + 0.068835303 0.0069420501 -0.0215009, + 0.067298099 0.0160551 -0.021493601, + 0.0691645 0.0116796 -0.016335901, + 0.059542101 0.00743519 -0.045994099, + 0.059986901 0.00129237 -0.045999002, + 0.062367599 0.00211812 -0.041330799, + 0.064492702 0.00218534 -0.036531199, + 0.060702499 0.0144991 -0.041320998, + 0.0596008 0.018521201 -0.041317798, + 0.05847 0.0134999 -0.045989301, + 0.063629903 0.0107621 -0.0365243, + 0.061533201 0.0104123 -0.041324198, + 0.062770903 0.0149882 -0.036520999, + 0.0642047 0.0064881998 -0.036527701, + 0.065447003 0.0110648 -0.0316086, + 0.0620891 0.00627913 -0.041327499, + 0.0585334 0.027191499 -0.036511298, + 0.056604698 0.026300199 -0.041311599, + 0.056588501 0.031040501 -0.036508199, + 0.060205001 0.027963299 -0.0315951, + 0.060217001 0.0232212 -0.036514401, + 0.058232799 0.0224609 -0.041314598, + 0.041115999 0.0262041 0.056906998, + 0.037805501 0.026047399 0.060007598, + 0.0403197 0.0275246 0.056908, + 0.033178799 0.027039601 0.0629123, + 0.0308914 0.029621501 0.062914401, + 0.030632701 0.0249587 0.0656057, + 0.0352511 0.0242819 0.062910199, + 0.035583101 0.0290049 0.0600099, + 0.054526798 0.0091588004 0.048617002, + 0.051464502 0.0086389501 0.052848902, + 0.0573406 0.0096369199 0.044211101, + 0.050769702 0.0120569 0.052851599, + 0.055539802 0.017193399 0.044217099, + 0.054265 0.0208646 0.044220001, + 0.052814402 0.016344501 0.048622701, + 0.0537907 0.0127803 0.0486199, + 0.056566499 0.0134453 0.0442141, + 0.058015201 0.0179649 0.039652601, + 0.0566836 0.0217997 0.0396557, + 0.0484928 0.026536001 0.0486308, + 0.050159499 0.0232378 0.0486282, + 0.042951901 0.0162418 0.059999701, + 0.048704099 0.018716 0.0528569, + 0.0441234 0.0127327 0.059997, + 0.049848199 0.0154209 0.0528543, + 0.047239799 0.0123718 0.056896001, + 0.0364017 0.057022002 -0.027586499, + 0.033994399 0.057025202 -0.031571299, + 0.035158899 0.0570237 -0.0297556, + 0.036926098 0.057021201 -0.0265559, + 0.037562799 0.054744702 -0.031573799, + 0.038441699 0.056021102 -0.0265583, + 0.037542 0.057020199 -0.0253457, + 0.040254202 0.0570147 -0.018443299, + 0.039507899 0.057016499 -0.0206539, + 0.042876001 0.0543117 -0.0214632, + 0.040867899 0.057013001 -0.016299101, + 0.0434702 0.055059999 -0.016301399, + 0.058635999 0.032113399 0.0251731, + 0.056358799 0.0359581 0.0251761, + 0.057204399 0.0265179 0.034951001, + 0.057094999 0.031264901 0.030119, + 0.054877602 0.035008602 0.030122001, + 0.053155798 0.033905499 0.034956899, + 0.050770599 0.0373803 0.0349597, + 0.0553036 0.0302795 0.034954, + 0.044406801 0.037508398 0.0442333, + 0.046386 0.0391853 0.039669499, + 0.0489018 0.035999499 0.039666999, + 0.0422277 0.035662599 0.048638102, + 0.044518001 0.032762401 0.048635799, + 0.037841301 0.055105101 0.0251914, + 0.039746098 0.056988001 0.015033, + 0.039255802 0.056986898 0.016435999, + 0.040137399 0.056988899 0.0139132, + 0.043072 0.054530799 0.0150326, + 0.043610699 0.055217199 0.0098561402, + 0.047201999 0.052180901 0.0098537197, + 0.050582401 0.048911601 0.0098511204, + 0.037665099 0.056984 0.020150499, + 0.039129101 0.056986701 0.016747201, + 0.037188001 0.056983199 0.0211726, + 0.038279202 0.056984998 0.018834701, + 0.038670901 0.056317698 0.0201516, + -0.0281497 -0.0058044 0.072301202, + -0.027596001 -0.0080508599 0.072299398, + -0.0268634 -0.0102455 0.0722977, + -0.018863801 0.0088907601 0.075562298, + -0.0151887 0.0071459999 0.076793902, + -0.015719401 0.0059004002 0.076792903, + -0.028520901 0.0034054299 0.072308503, + -0.0287071 0.00109928 0.0723067, + -0.0200553 0.0057489099 0.075559802, + -0.024355801 0.0049133198 0.074062802, + -0.027596001 0.0079357103 0.072312102, + -0.0281497 0.0056892498 0.072310403, + -0.0232428 -0.0088737896 0.074051902, + -0.0109745 -0.0063980902 0.077747703, + -0.0121248 0.0115849 0.076797403, + -0.0111484 0.0125228 0.076798201, + -0.00840325 0.0094234301 0.077760302, + -0.00562221 0.00628372 0.078449696, + -0.00532379 -0.0160078 0.076775499, + -0.0065897098 -0.0155277 0.076775901, + -0.0066119302 -0.019865399 0.075539403, + -0.0040128902 -0.012082 0.077743202, + -0.0040233498 -0.016384499 0.076775201, + -0.0033493401 -0.020669499 0.075538799, + -0.0020327701 -0.0125701 0.0777428, + -0.0030326699 -0.0123659 0.077743001, + 0.00068222702 -0.0085133901 0.078437902, + 6.4100309e-012 -0.0043110801 0.078857601, + -0.00134529 -0.0040924498 0.078857802, + -0.00268483 -0.0081045702 0.078438297, + -0.0020290101 -0.00829452 0.078438103, + -0.00068147201 -0.0042560301 0.078857601, + -0.00034184399 -0.00429729 0.078857601, + -0.00136003 -0.0084311096 0.078437999, + -0.00101668 -0.0041876701 0.078857698, + -0.0034962599 0.0023505299 0.078862898, + -0.00367912 0.00206135 0.078862697, + -0.0030638699 0.0028800699 0.0788633, + -0.0032907401 0.0026239699 0.078863099, + -0.0061146398 0.0058106999 0.078449301, + -0.00255212 0.0033334401 0.078863703, + -0.0028171299 0.0031171299 0.078863502, + -0.0050933301 0.0067154798 0.078450099, + -0.0045314101 0.0071034199 0.078450397, + -0.00227056 0.0035277801 0.0788638, + -0.00383811 0.00175837 0.078862399, + -0.00424483 -0.000233817 0.078860797, + -0.00677288 -0.0107723 0.077744201, + -0.0076127499 -0.0101926 0.0777447, + -0.0058890898 -0.0112826 0.077743798, + -0.00898539 -0.0142703 0.076776899, + -0.00383811 -0.00188396 0.078859501, + -0.0073425001 -0.0043016002 0.078441299, + 0.039257899 -0.0048189401 0.065582, + 0.035827 -0.0044044098 0.068056703, + 0.0486653 -0.0042251102 0.056882799, + 0.039257899 0.0047144899 0.065589599, + 0.035827 0.0042960201 0.068063602, + 0.0180823 -0.0105 0.075546898, + 0.032242902 -0.0039710202 0.070300303, + 0.026730301 0.018394601 0.070318103, + 0.0297016 0.020447399 0.068076499, + 0.034247998 0.019720901 0.065601498, + 0.035728101 0.016900901 0.0655993, + 0.029343801 0.0138678 0.070314497, + 0.030369001 0.0114615 0.0703125, + 0.0326056 0.0154174 0.068072498, + 0.028128199 0.0161839 0.0703163, + 0.031254999 0.0179908 0.068074502, + 0.0268634 0.0101303 0.072313897, + 0.0379849 0.0109502 0.065594502, + 0.041142099 0.0118669 0.062900297, + 0.036976401 0.0139711 0.065596901, + 0.038747001 0.0078580501 0.065592103, + 0.034665201 0.0099866996 0.068068199, + 0.033744901 0.0127435 0.068070397, + 0.019255299 -0.0157804 0.074046403, + 0.016173501 -0.0132654 0.0755447, + 0.020457899 -0.0141801 0.074047603, + 0.0236446 -0.0163783 0.072292797, + 0.0259565 -0.0123741 0.072296001, + 0.028128199 -0.016295901 0.070290402, + 0.031254999 -0.0180992 0.068045802, + 0.0326056 -0.0155258 0.068047903, + 0.036976401 -0.0140755 0.065574601, + 0.035728101 -0.0170053 0.065572299, + 0.041142099 -0.0119671 0.062881298, + 0.040049799 -0.0152389 0.062878698, + 0.038697701 -0.0184124 0.062876202, + 0.019511901 -0.0260217 0.070282698, + 0.0207204 -0.0199598 0.072289899, + 0.0234244 -0.0225555 0.070285499, + 0.0222547 -0.018228 0.0722913, + 0.0450087 -0.00923636 0.059979498, + 0.041967601 -0.0086178305 0.062884003, + 0.045602102 -0.00558487 0.0599824, + 0.00134529 0.00396686 0.078864202, + 0.00101668 0.0040620798 0.078864299, + 0.00268483 0.0079796398 0.078451097, + 0.00166518 0.0038455301 0.078864098, + 0.00332325 0.0077374601 0.078450903, + -0.0156158 0.0569661 0.042635199, + -0.0110525 0.056964699 0.044395, + -0.0151744 0.056965899 0.0428451, + -0.0131314 0.056965198 0.0436799, + -0.019074799 0.054897901 0.044247098, + -0.0153631 0.056049298 0.044248, + -0.0181388 0.052198701 0.0486513, + -0.017180501 0.0569667 0.0418914, + -0.022701399 0.0535012 0.044245999, + -0.019148299 0.056967501 0.040819202, + -0.021075999 0.056968499 0.039628301, + -0.00863693 0.0349872 0.068088099, + -0.0102853 0.030752201 0.0703279, + -0.0077729002 0.031479899 0.070328496, + -0.0114286 0.0341786 0.068087399, + -0.00521011 0.032003101 0.070328899, + -0.0057892599 0.035568599 0.068088502, + -0.0094640302 0.038344901 0.065616399, + -0.0063436599 0.038982 0.065616898, + -0.0190518 0.0214474 0.072322898, + -0.016484 0.0185476 0.074073702, + -0.0149334 0.0198137 0.0740747, + -0.017259501 0.022910699 0.072324097, + -0.017927799 0.017160799 0.074072599, + -0.0207204 0.019844601 0.072321601, + -0.0234244 0.022443499 0.070321299, + -0.021538001 0.024255401 0.0703227, + -0.019511901 0.025909699 0.070324101, + 0.0222547 0.018112799 0.072320201, + 0.017927799 0.017160799 0.074072599, + 0.016484 0.0185476 0.074073702, + 0.019255299 0.0156624 0.0740714, + 0.0207204 0.019844601 0.072321601, + 0.0190518 0.0214474 0.072322898, + -0.00166518 0.0038455301 0.078864098, + -0.00197427 0.0036989199 0.078864001, + -0.00332325 0.0077374601 0.078450903, + -1.1773474e-012 0.0084159197 0.078451402, + -0.00101668 0.0040620798 0.078864299, + -0.00134529 0.00396686 0.078864202, + -0.0020290101 0.0081695896 0.078451201, + -0.00268483 0.0079796398 0.078451097, + -0.00136003 0.0083061801 0.078451298, + -0.0026968201 0.016533 0.076801397, + -0.0013528001 0.0166962 0.076801501, + -0.0020327701 0.0124463 0.077762701, + -0.0030326699 0.0122421 0.077762596, + -0.0040233498 0.0162622 0.076801203, + 0.022701399 0.0535012 0.044245999, + 0.019074799 0.054897901 0.044247098, + -0.054723799 0.0300224 -0.0413086, + -0.061613798 0.028612999 -0.026580101, + -0.062755004 0.0291386 -0.0214832, + -0.047581501 0.052604701 0.0046351301, + -0.050989099 0.049309202 0.0046325098, + -0.047201999 0.052180901 0.0098537197, + -0.048299 0.035623901 -0.045971598, + -0.052598599 0.0336105 -0.041305698, + -0.051634699 0.030595699 -0.0459757, + -0.037136801 0.047064699 -0.045962501, + -0.035316501 0.051479999 -0.041291501, + -0.0351368 0.048672002 -0.045961302, + -0.0455628 0.050397702 -0.026562801, + -0.044521 0.049249802 -0.031578202, + -0.050684799 0.042876501 -0.031583302, + -0.053433701 0.039395399 -0.031585999, + -0.047709402 0.0461662 -0.031580601, + -0.0488258 0.0472419 -0.0265653, + -0.0353553 0.035399899 -0.055971801, + -0.051950201 0.038306199 -0.036502399, + -0.050238401 0.037048802 -0.041303001, + -0.049277499 0.041690599 -0.036499701, + -0.0457622 0.0387275 -0.045969199, + -0.04823 0.035727799 -0.045971598, + -0.052831501 0.044683401 -0.0214708, + -0.051870801 0.043875199 -0.026567999, + -0.0564688 0.041619599 -0.0163121, + -0.0642047 0.0064881998 -0.036527701, + -0.054495402 0.0251415 -0.045979999, + -0.063391604 0.0196895 -0.031601701, + -0.070158198 0.0118389 -0.00588969, + -0.0707919 0.00712639 -0.0058934502, + -0.0704422 0.0070954198 -0.0111313, + -0.069811597 0.0117847 -0.0111275, + -0.070202999 0.0118423 -0.00064036902, + -0.0708372 0.0071268501 -0.000644124, + -0.0692553 0.016504901 -0.000636657, + -0.069211103 0.0164985 -0.0058859801, + -0.068869203 0.016421299 -0.0111238, + -0.0487464 0.0111707 -0.055991098, + -0.069811597 -0.0117669 -0.0111463, + -0.068869203 -0.0164035 -0.01115, + -0.070158198 -0.0118295 -0.00590854, + -0.0691645 -0.0116536 -0.016354499, + -0.0704422 -0.00707768 -0.0111425, + -0.069789298 -0.0070078499 -0.0163508, + -0.018531101 -0.067636304 -0.0163991, + -0.0139712 -0.068723001 -0.016399899, + -0.0137802 -0.067779303 -0.021560401, + -0.023392901 -0.055132501 -0.046043899, + -0.021104001 -0.0561294 -0.0460447, + 0.0463848 -0.044830799 -0.036568601, + 0.047653802 -0.0402559 -0.041364599, + 0.044856399 -0.0433488 -0.041367002, + 0.049277499 -0.041632399 -0.036566101, + 0.0432849 -0.047828801 -0.036571, + 0.060009498 -0.038308099 -0.00068030303, + 0.062205698 -0.034093201 0.0045660902, + 0.059789799 -0.0381721 0.0045628501, + 0.057316799 -0.0422308 -0.00068342697, + 0.062394299 -0.0341883 -0.0059263501, + 0.064538799 -0.0299445 -0.0059229699, + 0.0624342 -0.034214299 -0.00067704299, + 0.062086102 -0.034015302 -0.011164, + 0.059971198 -0.0382795 -0.0059296, + 0.031634498 -0.062589698 -0.016395001, + 0.036079701 -0.060905699 -0.0111854, + 0.0273825 -0.064562798 -0.016396601, + 0.032088999 -0.063497402 -0.0059496802, + 0.031930499 -0.0631795 -0.0111872, + 0.0276387 -0.065171003 -0.0111888, + 0.027131701 -0.0639963 0.0149382, + 0.031736799 -0.062812902 0.0097621595, + 0.027471 -0.064792298 0.00976058, + 0.018591 -0.067875803 0.0097581204, + 0.0183613 -0.067041598 0.0149358, + 0.0140164 -0.068966098 0.0097572599, + 0.018740499 -0.0684174 0.0045387601, + 0.0227974 -0.065665603 0.0149369, + 0.0230825 -0.066482499 0.0097592296, + 0.050419401 -0.048748799 -0.016384, + 0.053563699 -0.045272298 -0.016381299, + 0.052831501 -0.044649199 -0.021542, + 0.064563498 -0.015361 -0.0316296, + 0.065447003 -0.0110144 -0.031626198, + 0.066074297 -0.0157251 -0.0266154, + 0.063391604 -0.019639101 -0.031633001, + 0.062770903 -0.01493 -0.0365448, + 0.061631601 -0.0190892 -0.0365481, + 0.057094999 -0.031312902 0.0300692, + 0.0553036 -0.0303351 0.034905799, + 0.059057299 -0.027429501 0.0300723, + 0.058015201 -0.018028099 0.039624002, + 0.0613456 -0.0146472 0.0349182, + 0.059087601 -0.0141129 0.039627101, + 0.056566499 -0.0135157 0.044192601, + 0.069001801 -0.016447701 0.0045801401, + 0.067998298 -0.0210928 -0.00066659501, + 0.067208901 -0.0208562 0.0097955596, + 0.064855203 -0.0249904 0.0149693, + 0.063042 -0.029266501 0.0149659, + 0.049957599 -0.0483271 0.0149507, + 0.046618901 -0.051556099 0.0149482, + 0.049116898 -0.047518201 0.020068999, + 0.05218 -0.044131499 0.0200717, + 0.053073101 -0.044882402 0.0149535, + 0.050582401 -0.048927199 0.0097732097, + 0.053736899 -0.045439601 0.0097759897, + 0.037562799 -0.054694299 -0.031661, + 0.0365199 -0.053171098 -0.036575299, + 0.033824001 -0.057080999 -0.0316629, + 0.038441699 -0.055978701 -0.026647501, + 0.034615502 -0.058421299 -0.026649401, + 0.0041680299 -0.0622303 -0.0413821, + 0.0079920599 -0.059378002 -0.0460473, + 0.0030794099 -0.059884202 -0.046047699, + -0.0124297 -0.061119098 -0.041381199, + -0.0083174398 -0.061812799 -0.041381702, + -0.0128532 -0.063206598 -0.0365832, + -0.0041680299 -0.0622303 -0.0413821, + -0.0043100398 -0.0643555 -0.036584198, + 0.022693699 -0.065337501 -0.0215584, + 0.0217715 -0.062673897 -0.0316673, + 0.0179454 -0.06549 -0.0266551, + 0.0182778 -0.066707499 -0.021559499, + 0.0175351 -0.063988097 -0.031668399, + -0.055951599 -0.041237399 0.0149564, + -0.0575944 -0.036782999 0.0200775, + -0.055010099 -0.040547699 0.0200745, + -0.058580201 -0.037408099 0.0149594, + -0.05218 -0.044131499 0.0200717, + -0.053073101 -0.044882402 0.0149535, + -0.053736899 -0.045439601 0.0097759897, + -0.056651399 -0.0417489 0.0097789299, + -0.059312899 -0.0378717 0.00978202, + -0.0215874 -0.050947901 0.048569102, + -0.0181388 -0.052276101 0.0485681, + -0.019074799 -0.054968301 0.044159599, + -0.019925 -0.057413001 0.039592601, + 0.0030326699 -0.0123659 0.077743001, + 0.00383811 -0.00188396 0.078859501, + 0.016484 -0.018665601 0.074044101, + 0.0190518 -0.021562601 0.072288699, + 0.017927799 -0.0172788 0.074045204, + 0.0138458 -0.0156889 0.075542703, + -0.0138458 -0.0156889 0.075542703, + -0.0125433 -0.016752301 0.075541899, + -0.0133517 -0.025497099 0.072285503, + -0.017927799 -0.0172788 0.074045204, + -0.0207204 -0.0199598 0.072289899, + -0.016484 -0.018665601 0.074044101, + -0.0234244 -0.0225555 0.070285499, + -0.019511901 -0.0260217 0.070282698, + -0.017259501 -0.0230259 0.0722875, + -0.0173593 -0.027507501 0.070281498, + -0.021680901 -0.028906301 0.068037197, + -0.021538001 -0.0243674 0.070284002, + -0.0190518 -0.021562601 0.072288699, + -0.019288899 -0.030557301 0.068035901, + -0.0039875298 -0.0245953 0.074039303, + -0.00687563 -0.027953099 0.072283603, + -0.0059489501 -0.0241949 0.074039698, + -0.0077729002 -0.0315919 0.070278302, + -2.8003914e-012 -0.0249172 0.074039102, + -0.022015801 -0.0436159 0.056851398, + -0.024857899 -0.0420109 0.056852698, + -0.021551199 -0.043878201 0.056851201, + -0.021348 -0.0407231 0.059954401, + 0.0439918 -0.0281255 0.052819598, + 0.044518001 -0.032839801 0.048583601, + 0.046815298 -0.034529001 0.044175901, + 0.042017799 -0.0310011 0.0528173, + 0.047342401 -0.022011301 0.052824501, + 0.044430502 -0.020336101 0.056869902, + 0.0308914 -0.0297217 0.062867098, + 0.0285208 -0.0274469 0.065563999, + 0.028403699 -0.032111298 0.062865198, + 0.033178799 -0.0271398 0.062869199, + 0.033129901 -0.031869601 0.059961401, + 0.051464502 -0.0087230997 0.052835099, + 0.0228929 -0.036252402 0.062861897, + 0.0245518 -0.038873401 0.059955899, + 0.019905601 -0.037977099 0.062860601, + 0.0257317 -0.034292798 0.062863499, + 0.021136099 -0.033476301 0.065559201, + 0.0237571 -0.031667199 0.065560602, + 0.0077729002 -0.0315919 0.070278302, + -0.040231001 0.0569892 0.0136188, + -0.037669498 0.056984 0.020151, + -0.040947501 0.056991201 0.0111301, + -0.039129701 0.056986701 0.016730299, + -0.043072 0.054530799 0.0150326, + -0.0394006 0.0569872 0.0160487, + -0.0036964 0.045740299 0.0600232, + 1.3190448e-012 0.042783201 0.062924899, + -0.00344664 0.042644199 0.062924802, + 4.9841888e-012 0.045889199 0.060023401, + -0.0073688198 0.0452944 0.060022902, + -0.0027884699 0.048719499 0.056924898, + -0.0032596199 0.048665401 0.056924898, + -0.0065023 0.0482933 0.0569246, + -0.0083290599 0.0480837 0.056924399, + 0.0112613 0.0263738 0.072326802, + 0.0133517 0.0253819 0.072325997, + 0.0150941 0.0287033 0.070326298, + 0.00261353 0.032318398 0.070329197, + -0.00261353 0.032318398 0.070329197, + 0.0097435704 0.022810001 0.0740771, + 0.0059489501 0.0240769 0.074078098, + 0.00687563 0.0278379 0.072328001, + 0.0248664 0.041940801 0.0569195, + 0.026063301 0.041171599 0.0569189, + 0.0276125 0.040176 0.0569181, + 0.02871 0.039470699 0.0569175, + 0.0257317 0.034192599 0.062918, + 0.0237571 0.031562801 0.065610997, + 0.028403699 0.032011099 0.062916301, + 0.0228929 0.036152199 0.062919602, + 0.0275963 0.036676198 0.060015999, + 0.0141461 0.033147901 0.068086602, + 0.0155008 0.0363295 0.0656147, + 0.018378099 0.034964301 0.065613702, + 0.0167719 0.031902 0.068085603, + 0.012731 0.0298246 0.0703272, + 0.0090979896 0.0271942 0.072327502, + 0.00863693 0.0349872 0.068088099, + 0.0114286 0.0341786 0.068087399, + 0.0094640302 0.038344901 0.065616399, + 0.0063436599 0.038982 0.065616898, + 0.0057892599 0.035568599 0.068088502, + 0.0077729002 0.031479899 0.070328496, + 0.00521011 0.032003101 0.070328899, + 0.0102853 0.030752201 0.0703279, + 0.027955599 0.0227709 0.068078399, + -0.032471299 0.0570269 -0.033736899, + -0.0253777 0.057032902 -0.041286498, + -0.028144101 0.055728301 -0.0412881, + -0.026659399 0.057032 -0.040172499, + -0.043876901 0.0555709 -0.0110927, + -0.041683901 0.0570102 -0.0128086, + -0.0421267 0.057008199 -0.0102176, + -0.046406701 0.0513267 -0.021465501, + -0.056997199 0.042004701 -0.0111035, + -0.044122901 0.055874199 -0.00060530799, + -0.0477564 0.052802298 -0.00060775399, + -0.042557601 0.056999002 0.0013198199, + -0.042677399 0.057001099 -0.00130937, + -0.043961398 0.0556654 0.0046375701, + -0.037711799 0.057019901 -0.0249871, + -0.042442899 0.057006098 -0.0076003699, + -0.0216942 0.045093101 -0.055964101, + -0.027024901 0.053517699 -0.045957401, + -0.029966 0.0520177 -0.045958601, + -0.0266016 0.042380799 -0.055966299, + -0.024832301 0.0570333 -0.041760501, + 0.0198282 0.057036102 -0.0453141, + 0.028899999 0.057030302 -0.037969399, + -0.022928899 0.057034399 -0.043240398, + -0.0241739 0.057033699 -0.0422724, + -0.0209495 0.057035498 -0.044609498, + -0.018735001 0.057036601 -0.0459546, + -0.011126 0.048790898 -0.055961199, + -0.00559822 0.049730301 -0.055960398, + 6.254895e-012 0.0500446 -0.055960201, + -0.016514 0.047238801 -0.055962399, + 0.018735001 0.057036601 -0.0459546, + -0.024479499 0.054815799 -0.045956399, + -0.0207205 0.057035699 -0.0447574, + -0.0241735 0.056970298 0.0373757, + -0.0254042 0.056970999 0.036383498, + -0.034952201 0.056979999 0.025192801, + -0.028442301 0.056257602 0.034974702, + 0.043199599 0.0227488 0.0569042, + 0.0457693 0.0250402 0.052862, + 0.047342401 0.0219271 0.0528595, + 0.045516402 0.017675901 0.0569002, + 0.0439918 0.028041299 0.052864298, + 0.0428016 0.0234088 0.0569048, + 0.041501898 0.0196451 0.060002498, + 0.039782699 0.0229207 0.060005099, + 0.043672301 0.048262302 0.0301325, + 0.055010099 0.040515698 0.0201391, + 0.053829901 0.039642099 0.025179099, + 0.052415099 0.038595799 0.0301248, + 0.0497186 0.0420104 0.0301276, + 0.046799898 0.0452374 0.0301301, + 0.049014699 0.031254601 0.0442283, + 0.053268 0.029160099 0.039661501, + 0.0509951 0.027911 0.0442256, + 0.051199298 0.032652698 0.039664298, + 0.046815298 0.0344586 0.044230901, + 0.046609499 0.0297157 0.0486334, + -0.0232428 0.0087558497 0.074065901, + -0.019522799 0.0073438799 0.075561099, + -0.022458101 0.0105975 0.074067399, + -0.023876701 0.0068570501 0.074064396, + -0.0268634 0.0101303 0.072313897, + -0.0259565 0.0122589 0.072315603, + -0.0180823 -0.0105 0.075546898, + -0.022458101 -0.0107155 0.074050397, + -0.0164722 0.00330164 0.076790802, + -0.0161481 0.00461622 0.076791897, + -0.0042173001 -0.00057487999 0.078860603, + -0.0098159797 0.00795261 0.077759102, + -0.0104291 0.00713669 0.077758498, + -0.0130226 0.0105715 0.076796599, + -0.00913925 0.0087163998 0.077759802, + -0.0065673999 0.0052995901 0.078448899, + -0.00697758 0.0047538099 0.078448497, + -0.0013528001 -0.016818499 0.076774798, + 4.6385482e-012 -0.016873 0.076774798, + -0.00168012 -0.0208722 0.075538598, + -0.0026968201 -0.0166553 0.076774999, + -0.00101969 -0.012693 0.077742703, + 6.5216604e-012 -0.0127341 0.077742703, + -0.0079274299 0.0029440001 0.078447104, + -0.00397221 0.00144367 0.078862198, + -0.0076598101 0.0035721699 0.078447603, + -0.0114487 0.0053705801 0.077757098, + -0.0118488 0.0044317399 0.077756301, + -0.0081436504 0.0022964301 0.0784465, + -0.0121719 0.00346372 0.0777556, + -0.00424483 0.000108225 0.078861102, + -0.0040805498 -0.00124468 0.07886, + -0.0041624201 -0.00091252598 0.078860298, + -0.00397221 -0.00156927 0.078859799, + -0.0081436504 -0.00242135 0.078442797, + -0.0034962599 -0.0024761199 0.078859001, + -0.00367912 -0.0021869401 0.078859299, + -0.00697758 -0.0048787398 0.0784408, + -0.00197427 -0.0038245099 0.078858003, + -0.00166518 -0.0039711199 0.078857899, + -0.00332325 -0.00786239 0.078438498, + -0.0039400999 -0.00756966 0.078438699, + -0.0045314101 -0.0072283498 0.078438997, + -0.00227056 -0.0036533701 0.0788581, + -0.0032907401 -0.0027495599 0.0788588, + -0.0065673999 -0.00542452 0.078440398, + -0.0030638699 -0.0030056599 0.078858599, + -0.0098159797 -0.0080764396 0.077746399, + -0.00913925 -0.0088402303 0.077745803, + 0.034665201 -0.0100951 0.068052202, + 0.0379849 -0.0110546 0.065577, + 0.038747001 -0.0079624997 0.065579496, + 0.035360798 -0.0072731799 0.0680544, + 0.0318233 -0.0065528098 0.070298202, + 0.046853598 -0.0136183 0.0568753, + 0.0441234 -0.0128283 0.0599766, + 0.047871601 -0.0097453604 0.056878399, + 0.0318233 0.00644085 0.070308499, + 0.0311973 0.0089803999 0.0703106, + 0.035360798 0.0071647898 0.068065897, + 0.032453399 0.00125188 0.070304401, + 0.032242902 0.0038590599 0.070306502, + 0.032453399 -0.00136384 0.0703023, + 0.036060899 0.00139905 0.0680613, + 0.036060899 -0.00150744 0.068058997, + 0.016173501 0.013145 0.075565703, + 0.0076127499 0.0100688 0.077760801, + 0.0039400999 0.00744473 0.078450702, + 0.00677288 0.0106485 0.0777613, + 0.0032907401 -0.0027495599 0.0788588, + 0.0109745 0.0062742601 0.077757798, + 0.024881201 0.0143076 0.072317198, + 0.0236446 0.016263099 0.0723188, + 0.0281497 -0.0058044 0.072301202, + 0.028520901 -0.00352058 0.072302997, + 0.028520901 0.0034054299 0.072308503, + 0.0281497 0.0056892498 0.072310403, + 0.030369001 -0.0115735 0.070294201, + 0.0311973 -0.0090923598 0.070296198, + 0.033744901 -0.0128519 0.068049997, + 0.029343801 -0.0139798 0.070292301, + 0.0268634 -0.0102455 0.0722977, + 0.0173593 -0.027507501 0.070281498, + 0.0133517 -0.025497099 0.072285503, + 0.017259501 -0.0230259 0.0722875, + 0.0073425001 0.0041766702 0.078447998, + 0.00383811 0.00175837 0.078862399, + 0.00562221 0.00628372 0.078449696, + 0.0111484 0.0125228 0.076798201, + 0.0150585 0.0144037 0.075566702, + 0.0121248 0.0115849 0.076797403, + 0.0138458 0.0155685 0.075567603, + 0.0100996 0.0133791 0.076798901, + 0.00840325 0.0094234301 0.077760302, + 0.0125433 0.016631899 0.075568497, + -0.00034184399 0.0041717002 0.078864299, + -0.00068147201 0.0041304398 0.078864299, + -0.00068222702 0.0083884597 0.078451402, + 0.00034184399 0.0041717002 0.078864299, + 0.00068147201 0.0041304398 0.078864299, + 0.00068222702 0.0083884597 0.078451402, + -3.3245509e-012 0.0041854898 0.078864299, + 0.0209838 0.056968398 0.0396837, + 0.022786399 0.0569694 0.038446002, + 0.023713199 0.055890899 0.039682802, + 0.020850999 0.056968302 0.039774802, + 0.00220835 0.056963399 0.046027001, + 0.0065677101 0.056963801 0.045499999, + 0.0146092 0.053293601 0.048652101, + 0.0181388 0.052198701 0.0486513, + 0.0137888 0.050294898 0.052882101, + 0.0156169 0.0569661 0.042628501, + 0.0153631 0.056049298 0.044248, + 0.0147303 0.056965701 0.043037999, + 0.016821999 0.056966498 0.042071901, + 0.018862501 0.0569674 0.040983699, + 0.024173001 0.056970298 0.037378799, + 0.020375 0.048007902 0.052880201, + 0.0215874 0.050870501 0.048650201, + 0.023538901 0.046539798 0.052879099, + 0.017120101 0.0492616 0.0528812, + -0.057253201 0.036570299 -0.0265738, + -0.054684099 0.0403127 -0.026570801, + -0.0559441 0.035738599 -0.031588901, + -0.058204498 0.031922199 -0.031592, + -0.059566502 0.0326645 -0.026576901, + -0.055696901 0.041054901 -0.0214737, + -0.058313601 0.037243102 -0.021476701, + -0.060669798 0.033264998 -0.021479901, + -0.038441699 0.056021102 -0.0265583, + -0.042096298 0.053328499 -0.0265604, + -0.033942599 0.057025202 -0.031661801, + -0.039991699 0.050671201 -0.036492601, + -0.0365199 0.053229298 -0.0364905, + -0.041133799 0.0521136 -0.0315759, + -0.0386739 0.049006298 -0.041293502, + -0.0620891 0.00627913 -0.041327499, + -0.059542101 0.00743519 -0.045994099, + -0.0590882 0.0100029 -0.045992099, + -0.056604698 0.026300199 -0.041311599, + -0.056588501 0.031040501 -0.036508199, + -0.056781799 0.019422799 -0.045984499, + -0.05847 0.0134999 -0.045989301, + -0.062770903 0.0149882 -0.036520999, + -0.064563498 0.0154114 -0.031605098, + -0.065447003 0.0110648 -0.0316086, + -0.063629903 0.0107621 -0.0365243, + -0.061533201 0.0104123 -0.041324198, + -0.060702499 0.0144991 -0.041320998, + -0.0596008 0.018521201 -0.041317798, + -0.035256699 -0.059507798 -0.0215538, + -0.034615502 -0.058421299 -0.026649401, + -0.0312021 -0.061729699 -0.021555601, + -0.039153799 -0.057020001 -0.021551801, + -0.0357453 -0.060336899 -0.0163932, + -0.031634498 -0.062589698 -0.016395001, + -0.023008199 -0.0662475 -0.016398, + -0.030634699 -0.060602799 -0.0266512, + -0.017048201 -0.062206902 -0.036582399, + -0.027052401 -0.0534999 -0.046042599, + -0.026750499 -0.053670101 -0.0460428, + -0.032115102 -0.050644901 -0.0460403, + -0.035316501 -0.051414199 -0.041373499, + -0.0365199 -0.053171098 -0.036575299, + -0.024361299 -0.057417899 -0.0413782, + -0.028144101 -0.055662502 -0.041376799, + -0.031801298 -0.053658299 -0.041375201, + -0.0328849 -0.0554915 -0.036577102, + -0.033824001 -0.057080999 -0.0316629, + 0.014181 -0.069767699 -0.00070535397, + 0.0232234 -0.066871598 -0.0111902, + 0.0141019 -0.0693703 -0.0111921, + 0.018531101 -0.067636304 -0.0163991, + 0.018704399 -0.068273298 -0.0111913, + 0.0139712 -0.068723001 -0.016399899, + 0.018797301 -0.068616502 -0.0059537599, + 0.0141719 -0.0697188 -0.00595464, + 0.0094364202 -0.0701572 -0.0111928, + 0.0094832703 -0.070509702 -0.00595527, + 0.0233537 -0.067254998 -0.00070335303, + 0.0233387 -0.067207798 -0.00595264, + 0.0188093 -0.0686647 -0.00070447603, + 0.0232682 -0.067012899 0.00453988, + 0.0277759 -0.065498799 -0.0059512798, + 0.0277937 -0.065544903 -0.00070199103, + 0.027691901 -0.0653091 0.0045412402, + 0.047049899 -0.052007601 -0.0163866, + 0.042876001 -0.054277498 -0.021549599, + 0.0588497 -0.022693301 0.0349118, + 0.0602322 -0.018712001 0.034915, + 0.057204399 -0.0265735 0.034908801, + 0.060755901 -0.0234237 0.0300755, + 0.0661944 -0.0254979 0.0045729401, + 0.067749403 -0.021019701 0.0045765, + 0.066437602 -0.0255874 -0.00067017402, + 0.065666303 -0.0252987 0.0097920299, + 0.064580098 -0.0299679 -0.000673662, + 0.064343698 -0.029862201 0.0045694602, + 0.063830398 -0.029628299 0.0097885802, + 0.0124297 -0.061119098 -0.041381199, + 0.0086008403 -0.063923903 -0.0365838, + 0.0128532 -0.063206598 -0.0365832, + 0.0083174398 -0.061812799 -0.041381702, + 0.016486401 -0.0601524 -0.041380402, + 0.00920578 -0.059252899 -0.0460472, + 0.0152352 -0.057996899 -0.046046201, + -0.0088464599 -0.065754101 -0.031669799, + -0.0086008403 -0.063923903 -0.0365838, + -0.0044331299 -0.0661982 -0.031670101, + -0.0132203 -0.065016396 -0.031669199, + -0.0090534696 -0.067297399 -0.026656499, + 0.026517 -0.062513597 -0.026652699, + 0.0270082 -0.063676 -0.0215571, + 0.030634699 -0.060602799 -0.0266512, + 0.022281 -0.064145103 -0.026653999, + 0.0259107 -0.0610798 -0.031665999, + 0.0299342 -0.0592127 -0.031664599, + -0.023538901 -0.046624001 0.052804898, + -0.026597699 -0.044947699 0.052806199, + -0.031295199 -0.045627899 0.048573401, + -0.032910202 -0.047977 0.044165201, + -0.0262265 -0.051935699 0.044162098, + -0.022701399 -0.0535716 0.044160798, + -0.0249395 -0.049392302 0.048570398, + -0.028180299 -0.047616299 0.048571799, + -0.0296345 -0.050067998 0.044163499, + -0.0309553 -0.052294299 0.039596699, + -0.027395399 -0.0542452 0.039595101, + -0.023713199 -0.055954002 0.039593801, + 0.0100996 -0.0135013 0.076777503, + 0.00268483 -0.0081045702 0.078438297, + 0.00397221 -0.00156927 0.078859799, + -0.0132858 -0.021068901 0.074042097, + -0.0153554 -0.024340199 0.072286397, + -0.0115522 -0.022069899 0.074041396, + -0.0149334 -0.0199317 0.074043103, + -0.0111595 -0.017707501 0.075541101, + 0.00521011 -0.032115102 0.070277803, + 0.0046086698 -0.0284159 0.072283201, + 0.049014699 -0.031325001 0.044178501, + 0.0457693 -0.025124401 0.052822001, + 0.046609499 -0.0297931 0.048586, + 0.049848199 -0.0155051 0.052829701, + 0.0537907 -0.0128577 0.0485995, + 0.050769702 -0.0121411 0.052832302, + 0.048704099 -0.018800201 0.052827001, + 0.0464538 -0.0151391 0.0568741, + 0.052814402 -0.016421899 0.048596598, + 0.055539802 -0.0172638 0.044189699, + -0.0063436599 -0.039086401 0.065554701, + 0.0063436599 -0.039086401 0.065554701, + 0.0057892599 -0.035677001 0.068031803, + 0.0094640302 -0.038449299 0.0655552, + 0.00863693 -0.035095599 0.068032302, + 0.0068709301 -0.0423287 0.062857099, + 0.0102507 -0.041638698 0.062857702, + 0.00344664 -0.042744402 0.062856801, + -6.0626677e-012 -0.0459847 0.059950199, + 0.0036964 -0.0458358 0.0599503, + -4.8594202e-012 -0.048889801 0.0568472, + -0.00348601 -0.052117102 0.052800499, + -0.0069564502 -0.051767901 0.052800801, + -0.0103958 -0.051187702 0.0528013, + 0.0128948 0.047022101 0.056923602, + 0.0137611 0.0468207 0.056923401, + 0.0083290599 0.0480837 0.056924399, + 0.0116722 0.0473064 0.056923799, + 0.0103958 0.051103499 0.052882701, + 0.0109935 0.044554401 0.060022298, + 0.0069564502 0.051683702 0.0528832, + 0.0073688198 0.0452944 0.060022902, + 0.0065023 0.0482933 0.0569246, + 0.0036964 0.045740299 0.0600232, + 0.0046086698 0.028300701 0.072328404, + 0.0039875298 0.024477299 0.074078403, + 4.1901829e-012 0.028672701 0.072328702, + 0.0023118299 0.0285796 0.072328597, + 0.0020002499 0.024718599 0.074078597, + -3.6595345e-012 0.0208194 0.075571798, + 0.0111595 0.017587099 0.075569198, + 0.0115522 0.021951901 0.074076399, + 0.0097032702 0.0184278 0.075569898, + 0.00898539 0.014148 0.076799497, + 0.0058890898 0.0111588 0.077761702, + 0.0040128902 0.0119582 0.077762298, + 0.0013528001 0.0166962 0.076801501, + 0.00101969 0.0125692 0.077762797, + 0.0020327701 0.0124463 0.077762701, + 5.6609019e-012 0.016750701 0.076801598, + -5.6363568e-012 0.0126103 0.077762902, + 0.00168012 0.0207518 0.075571701, + 0.021348 0.040627498 0.060019199, + 0.0245518 0.038777798 0.060017701, + 0.019905601 0.0378769 0.062921003, + 0.0167892 0.039355502 0.062922202, + 0.0180058 0.042213298 0.060020398, + 0.024018399 0.0424858 0.056919899, + 0.0226715 0.0431481 0.056920499, + 0.019013699 0.044946499 0.056921899, + 0.0239322 0.0269596 0.068081699, + 0.026224 0.0295486 0.065609299, + 0.0285208 0.0273425 0.0656076, + 0.0260283 0.0249463 0.068080097, + 0.021680901 0.0287979 0.068083197, + 0.021538001 0.024255401 0.0703227, + 0.0234244 0.022443499 0.070321299, + -0.0302449 0.057029098 -0.0364873, + -0.028409099 0.0570307 -0.0384783, + -0.030079801 0.057029199 -0.0366797, + -0.0308927 0.057028499 -0.035732199, + -0.0328849 0.0555497 -0.036488701, + -0.0497302 0.0481124 -0.021468099, + -0.0391909 0.057017099 -0.021459401, + -0.038649999 0.057018202 -0.0228623, + -0.040420201 0.057014301 -0.017902801, + -0.039599001 0.057016298 -0.0204008, + -0.041115001 0.057012301 -0.0153712, + -0.0434702 0.055059999 -0.016301399, + -0.042876001 0.0543117 -0.0214632, + -0.042568501 0.057004701 -0.0058534802, + -0.0440947 0.055842601 -0.0058546602, + -0.042668398 0.0570032 -0.0039538299, + -0.0425286 0.057005301 -0.00661192, + -0.028803701 0.056973599 0.03317, + -0.033411801 0.056978099 0.027538599, + -0.0314449 0.056976002 0.030138399, + -0.0269734 0.056972198 0.034975, + -0.0304427 0.056975 0.0313644, + -0.028839599 0.056973599 0.0331343, + -0.0271597 0.056972299 0.034807801, + 0.041438699 0.052454501 0.025189299, + 0.0423472 0.053608999 0.020149499, + -0.0204577 0.0041163401 0.075558499, + -0.0246769 0.00293737 0.074061297, + -0.018863801 -0.0090110898 0.075548001, + -0.019522799 -0.00746421 0.075549297, + -0.0145595 -0.0084671499 0.076781496, + -0.0246769 -0.0030553101 0.074056499, + -0.024838001 -0.00105995 0.074058101, + -0.0118488 -0.0045555602 0.0777492, + -0.0079274299 -0.00306893 0.078442298, + -0.0076598101 -0.0036971001 0.078441799, + -0.0114487 -0.0054944102 0.077748403, + -0.015719401 -0.0060226899 0.076783396, + -0.0151887 -0.00726829 0.076782398, + -0.00830705 -0.00175838 0.078443304, + -0.0041624201 0.00078693498 0.078861602, + -0.00830705 0.0016334601 0.078446001, + -0.0042173001 0.00044928899 0.0788614, + -0.0040805498 0.00111908 0.0788619, + -0.0084715104 0.000278967 0.078444898, + -0.00562221 -0.00640865 0.078439601, + -0.0061146398 -0.0059356298 0.078440003, + -0.0028171299 -0.0032427199 0.078858398, + -0.00255212 -0.0034590301 0.078858301, + -0.0050933301 -0.0068404102 0.078439303, + -0.00840325 -0.0095472597 0.077745199, + 0.0180823 0.0103796 0.075563498, + 0.0145595 0.0083448598 0.0767949, + 0.0138359 0.0094891395 0.076795802, + 0.0171836 0.0118008 0.075564601, + 0.020457899 0.0140621 0.074070103, + 0.0034962599 -0.0024761199 0.078859001, + 0.0073425001 -0.0043016002 0.078441299, + 0.00367912 -0.0021869401 0.078859299, + 0.0076598101 -0.0036971001 0.078441799, + 0.0109745 -0.0063980902 0.077747703, + 0.0114487 -0.0054944102 0.077748403, + 0.0145595 -0.0084671499 0.076781496, + 0.018863801 -0.0090110898 0.075548001, + 0.0065673999 -0.00542452 0.078440398, + 0.00697758 -0.0048787398 0.0784408, + 0.0104291 -0.00726052 0.077747002, + 0.0130226 -0.0106937 0.076779701, + 0.0138359 -0.0096114296 0.076780602, + 0.022458101 0.0105975 0.074067399, + 0.021527801 0.0123701 0.0740688, + 0.018863801 0.0088907601 0.075562298, + 0.0232428 0.0087558497 0.074065901, + 0.0259565 0.0122589 0.072315603, + 0.0132858 -0.021068901 0.074042097, + 0.0153554 -0.024340199 0.072286397, + 0.0115522 -0.022069899 0.074041396, + 0.0149334 -0.0199317 0.074043103, + 0.0111595 -0.017707501 0.075541101, + 0.0079274299 0.0029440001 0.078447104, + 0.0081436504 0.0022964301 0.0784465, + 0.00397221 0.00144367 0.078862198, + 0.0076598101 0.0035721699 0.078447603, + 0.00367912 0.00206135 0.078862697, + 0.0028171299 0.0031171299 0.078863502, + 0.0050933301 0.0067154798 0.078450099, + -0.035306901 0.057023499 -0.029510099, + -0.037562799 0.054744702 -0.031573799, + -0.0339997 0.057025202 -0.031571802, + -0.036563601 0.0570217 -0.027284401, + -0.036927599 0.057021201 -0.026556101, + -0.044856399 0.0434146 -0.041297901, + -0.047653802 0.0403217 -0.041300401, + -0.0463848 0.044888999 -0.036497202, + -0.0432849 0.047887001 -0.036494799, + -0.041858599 0.0463138 -0.041295599, + -0.044317201 0.040483899 -0.045967799, + -0.040233102 0.0445216 -0.045964599, + -0.039937399 0.044813801 -0.045964301, + -0.060217001 0.0232212 -0.036514401, + -0.061631601 0.0191474 -0.036517698, + -0.058232799 0.0224609 -0.041314598, + -0.0585334 0.027191499 -0.036511298, + -0.061936598 0.023879699 -0.0315984, + -0.060205001 0.027963299 -0.0315951, + -0.022693699 -0.065337501 -0.0215584, + -0.0270082 -0.063676 -0.0215571, + -0.0259107 -0.0610798 -0.031665999, + -0.026517 -0.062513597 -0.026652699, + -0.0299342 -0.0592127 -0.031664599, + -0.0217715 -0.062673897 -0.0316673, + -0.0291031 -0.057564002 -0.036578801, + -0.0251913 -0.059379201 -0.036580201, + -0.021167001 -0.060929202 -0.036581401, + 0.046406701 -0.051292501 -0.0215472, + 0.042096298 -0.053286102 -0.026645301, + 0.041133799 -0.052063201 -0.031658899, + 0.044521 -0.049199399 -0.031656601, + 0.0076127499 -0.0101926 0.0777447, + 0.0020290101 -0.00829452 0.078438103, + 0.0050933301 -0.0068404102 0.078439303, + -0.0057892599 -0.035677001 0.068031803, + -0.00521011 -0.032115102 0.070277803, + -0.0046086698 -0.0284159 0.072283201, + 0.052747902 -0.0245129 0.044183899, + 0.0566836 -0.0218629 0.039620899, + 0.055098802 -0.025600201 0.0396179, + 0.054265 -0.020935001 0.0441867, + 0.053268 -0.029223301 0.039615002, + 0.0509951 -0.0279814 0.044181101, + 0.0484928 -0.026613399 0.048588499, + 0.050159499 -0.023315201 0.0485911, + 0.051602099 -0.0199128 0.048593901, + -2.7312111e-012 -0.039598498 0.065554298, + -0.0029040501 -0.036027301 0.068031497, + -0.00318215 -0.039470199 0.065554403, + 0.0029040501 -0.036027301 0.068031497, + 0.00318215 -0.039470199 0.065554403, + -6.4158275e-012 -0.0428834 0.062856697, + -0.0073688198 -0.045389902 0.059950698, + -0.0055678501 -0.0485714 0.056847401, + -0.0036964 -0.0458358 0.0599503, + -0.0109935 -0.04465 0.059951302, + -0.0068709301 -0.0423287 0.062857099, + -0.00650266 -0.0484096 0.056847598, + -0.00344664 -0.042744402 0.062856801, + -0.00782206 -0.048181299 0.0568478, + -0.0110631 -0.047620401 0.056848198, + -0.0020002499 0.024718599 0.074078597, + -3.6523397e-012 0.0247992 0.074078701, + -0.0023118299 0.0285796 0.072328597, + -0.0039875298 0.024477299 0.074078403, + -0.0046086698 0.028300701 0.072328404, + -0.00168012 0.0207518 0.075571701, + -0.0033493401 0.0205491 0.075571597, + 0.0078717899 0.0235199 0.074077703, + 0.0040233498 0.0162622 0.076801203, + 0.0033493401 0.0205491 0.075571597, + 0.0049968399 0.020212701 0.075571299, + 0.0026968201 0.016533 0.076801397, + 0.0066119302 0.019745 0.075570904, + 0.0030326699 0.0122421 0.077762596, + 0.0065897098 0.0154054 0.076800503, + 0.0078128902 0.014825 0.076800004, + 0.0081841396 0.0191487 0.075570501, + 0.00532379 0.0158855 0.076800898, + 0.0049671 0.0115963 0.077762097, + -0.050891101 0.049226999 -0.0110977, + -0.047049899 0.052033599 -0.0163038, + -0.047490101 0.0525162 -0.0110951, + -0.050419401 0.048774801 -0.0163064, + -0.051143799 0.049467102 -0.0058597298, + -0.054333299 0.0459406 -0.0058625401, + -0.0540649 0.045717798 -0.0111005, + -0.053563699 0.045298301 -0.016309099, + 0.049116898 0.047486201 0.0201446, + 0.044851098 0.049569499 0.025187001, + 0.048063099 0.046463002 0.025184499, + 0.0458344 0.0506608 0.0201471, + 0.051060501 0.043149099 0.025181901, + 0.05218 0.044099499 0.0201419, + 0.049957599 0.048303202 0.0150277, + 0.046618901 0.051532201 0.0150302, + -0.020862799 0.000780534 0.075555801, + -0.0207274 0.00245656 0.075557202, + -0.024838001 0.00094200799 0.074059702, + -0.024355801 -0.0050312602 0.074054897, + -0.023876701 -0.00697499 0.074053399, + -0.0164722 -0.0034239299 0.076785497, + -0.0121719 -0.00358754 0.077749997, + -0.0161481 -0.0047385101 0.076784402, + -0.0124161 -0.0025967001 0.077750698, + -0.0200553 -0.00586924 0.075550497, + -0.0204577 -0.0042366702 0.0755518, + -0.0207274 -0.0025768799 0.075553201, + -0.0084715104 -0.00040389501 0.078444399, + -0.0125799 -0.00158938 0.077751599, + -0.0084165698 -0.00108443 0.0784439, + -0.0125799 0.0014655601 0.077753998, + -0.0084165698 0.00095950498 0.078445502, + -0.0124161 0.0024728801 0.077754803, + -0.012662 0.00044834099 0.077753201, + -0.016689301 0.00196534 0.076789796, + 0.0098159797 0.00795261 0.077759102, + 0.00913925 0.0087163998 0.077759802, + 0.0130226 0.0105715 0.076796599, + 0.0104291 0.00713669 0.077758498, + 0.00697758 0.0047538099 0.078448497, + 0.015719401 0.0059004002 0.076792903, + 0.0118488 0.0044317399 0.077756301, + 0.0114487 0.0053705801 0.077757098, + 0.0151887 0.0071459999 0.076793902, + 0.019522799 0.0073438799 0.075561099, + 0.0287071 0.00109928 0.0723067, + 0.0287071 -0.00121444 0.072304897, + 0.0084165698 -0.00108443 0.0784439, + 0.00913925 -0.0088402303 0.077745803, + 0.00840325 -0.0095472597 0.077745199, + 0.0098159797 -0.0080764396 0.077746399, + 0.0121248 -0.0117071 0.076778904, + 0.0111484 -0.012645 0.076778203, + 0.0041624201 0.00078693498 0.078861602, + 0.0040805498 0.00111908 0.0788619, + 0.0042173001 0.00044928899 0.0788614, + 0.0041624201 -0.00091252598 0.078860298, + 0.0040805498 -0.00124468 0.07886, + 0.00424483 -0.000233817 0.078860797, + 0.00424483 0.00010822499 0.078861102, + 0.0042173001 -0.00057487999 0.078860603, + 0.0032907401 0.0026239699 0.078863099, + 0.0034962599 0.0023505299 0.078862898, + 0.0065673999 0.0052995901 0.078448899, + 0.0061146398 0.0058106999 0.078449301, + 0.0030638699 0.0028800699 0.0788633, + 0.00227056 0.0035277801 0.0788638, + 0.0045314101 0.0071034199 0.078450397, + 0.00197427 0.0036989199 0.078864001, + 0.00255212 0.0033334401 0.078863703, + 0.0114778 0.0569648 0.044248901, + 0.0125875 0.056965102 0.0438798, + 0.0115828 0.0569502 0.044248801, + 0.00871915 0.056964099 0.045042802, + 0.0076671699 0.056963999 0.0452663, + 0.0073703802 0.054765001 0.048653301, + 0.0108516 0.056964599 0.0444571, + 0.0110144 0.054150298 0.048652802, + -0.0179454 -0.06549 -0.0266551, + -0.0182778 -0.066707499 -0.021559499, + -0.0135296 -0.066542402 -0.026655899, + -0.022281 -0.064145103 -0.026653999, + -0.0175351 -0.063988097 -0.031668399, + 0.0488258 -0.047199499 -0.026640501, + 0.0455628 -0.0503553 -0.026643001, + 0.047709402 -0.046115801 -0.031654101, + 0.050684799 -0.042826101 -0.031651501, + 0.051870801 -0.043832801 -0.0266378, + 0.0497302 -0.048078202 -0.0215447, + 0.0058890898 -0.0112826 0.077743798, + 0.00677288 -0.0107723 0.077744201, + 0.0078128902 -0.0149473 0.076776303, + 0.0049671 -0.0117201 0.0777435, + 0.00898539 -0.0142703 0.076776899, + 0.0039400999 -0.00756966 0.078438699, + 0.00068147201 -0.0042560301 0.078857601, + 0.00034184399 -0.00429729 0.078857601, + 0.00136003 -0.0084311096 0.078437999, + 0.00101668 -0.0041876701 0.078857698, + 0.0028171299 -0.0032427199 0.078858398, + 0.00562221 -0.00640865 0.078439601, + 0.0061146398 -0.0059356298 0.078440003, + 0.0030638699 -0.0030056599 0.078858599, + 4.4055983e-012 -0.032535698 0.070277497, + 0.00261353 -0.032430399 0.070277601, + -4.3770768e-012 -0.036144301 0.0680314, + -0.00261353 -0.032430399 0.070277601, + -3.2989265e-012 -0.0287879 0.072282903, + 0.0023118299 -0.028694799 0.072283, + -0.0023118299 -0.028694799 0.072283, + -0.016798301 -0.00073814701 0.076787598, + -0.012662 -0.00057216699 0.077752396, + -0.016689301 -0.0020876301 0.0767866, + -0.016798301 0.00061585702 0.076788701, + -0.020862799 -0.00090086099 0.075554498, + 0.0200553 0.0057489099 0.075559802, + 0.023876701 0.0068570501 0.074064396, + 0.024355801 0.0049133198 0.074062802, + 0.0246769 0.00293737 0.074061297, + 0.0161481 0.00461622 0.076791897, + 0.0121719 0.00346372 0.0777556, + 0.00830705 0.0016334601 0.078446001, + 0.0246769 -0.0030553101 0.074056499, + 0.0151887 -0.00726829 0.076782398, + 0.0081436504 -0.00242135 0.078442797, + 0.0079274299 -0.00306893 0.078442298, + 0.0118488 -0.0045555602 0.0777492, + 0.00166518 -0.0039711199 0.078857899, + 0.00134529 -0.0040924498 0.078857802, + 0.00332325 -0.00786239 0.078438498, + 0.00227056 -0.0036533701 0.0788581, + 0.00255212 -0.0034590301 0.078858301, + 0.0045314101 -0.0072283498 0.078438997, + 0.00197427 -0.0038245099 0.078858003, + 6.1902705e-012 -6.29063e-005 0.079000004, + 0.012662 -0.00057216699 0.077752396, + 0.0084715104 -0.00040389501 0.078444399, + 0.0084715104 0.000278967 0.078444898, + 0.0084165698 0.00095950498 0.078445502, + 0.016689301 0.00196534 0.076789796, + 0.0124161 0.0024728801 0.077754803, + 0.0164722 0.00330164 0.076790802, + 0.0125799 0.0014655601 0.077753998, + 0.0207274 0.00245656 0.075557202, + 0.012662 0.00044834099 0.077753201, + 0.0204577 0.0041163401 0.075558499, + 0.020862799 -0.00090086099 0.075554498, + 0.016798301 0.00061585702 0.076788701, + 0.020862799 0.000780534 0.075555801, + 0.016798301 -0.00073814701 0.076787598, + 0.024838001 -0.00105995 0.074058101, + 0.024838001 0.00094200799 0.074059702, + 0.00830705 -0.00175838 0.078443304, + 0.015719401 -0.0060226899 0.076783396, + 0.019522799 -0.00746421 0.075549297, + 0.024355801 -0.0050312602 0.074054897, + 0.023876701 -0.00697499 0.074053399, + 0.0164722 -0.0034239299 0.076785497, + 0.016689301 -0.0020876301 0.0767866, + 0.0125799 -0.00158938 0.077751599, + 0.0124161 -0.0025967001 0.077750698, + 0.0121719 -0.00358754 0.077749997, + 0.0161481 -0.0047385101 0.076784402, + 0.0207274 -0.0025768799 0.075553201, + 0.0204577 -0.0042366702 0.0755518, + 0.0200553 -0.00586924 0.075550497 ] + + } + coordIndex [ 164, 288, 496, -1, 71, 288, 481, -1, + 71, 496, 288, -1, 7, 911, 6, -1, + 7, 6, 8, -1, 9, 2509, 21, -1, + 124, 9, 21, -1, 28, 1, 26, -1, + 2, 465, 23, -1, 544, 176, 178, -1, + 622, 1263, 621, -1, 175, 210, 39, -1, + 175, 178, 176, -1, 175, 39, 178, -1, + 2394, 39, 210, -1, 49, 46, 239, -1, + 228, 163, 34, -1, 3, 46, 2042, -1, + 4, 239, 46, -1, 4, 46, 3, -1, + 262, 5, 263, -1, 287, 164, 165, -1, + 287, 288, 164, -1, 287, 185, 290, -1, + 287, 165, 185, -1, 57, 153, 811, -1, + 60, 59, 58, -1, 910, 909, 1574, -1, + 910, 1713, 496, -1, 63, 481, 1765, -1, + 64, 71, 481, -1, 903, 8, 6, -1, + 903, 902, 8, -1, 903, 1574, 909, -1, + 327, 903, 909, -1, 327, 1562, 903, -1, + 12, 433, 796, -1, 2510, 2509, 9, -1, + 2510, 2516, 2515, -1, 2510, 358, 2516, -1, + 97, 994, 363, -1, 391, 14, 108, -1, + 385, 108, 14, -1, 1055, 216, 140, -1, + 1055, 217, 216, -1, 1408, 1407, 1406, -1, + 695, 694, 113, -1, 695, 113, 693, -1, + 1729, 410, 117, -1, 421, 121, 2165, -1, + 110, 21, 2509, -1, 0, 124, 433, -1, + 0, 9, 124, -1, 0, 433, 12, -1, + 0, 12, 9, -1, 130, 452, 114, -1, + 134, 609, 146, -1, 143, 48, 47, -1, + 143, 139, 48, -1, 147, 146, 609, -1, + 474, 1, 1151, -1, 474, 24, 26, -1, + 474, 26, 1, -1, 27, 1, 28, -1, + 1156, 1151, 1, -1, 1156, 1, 27, -1, + 1156, 27, 1155, -1, 25, 1536, 815, -1, + 877, 26, 24, -1, 29, 489, 27, -1, + 29, 27, 28, -1, 2261, 496, 1713, -1, + 507, 171, 36, -1, 521, 522, 2, -1, + 521, 2, 23, -1, 521, 23, 559, -1, + 521, 36, 520, -1, 517, 35, 1226, -1, + 528, 2, 522, -1, 528, 465, 2, -1, + 546, 176, 544, -1, 546, 210, 175, -1, + 1228, 556, 179, -1, 167, 1226, 35, -1, + 167, 1227, 1226, -1, 167, 1228, 1227, -1, + 167, 556, 1228, -1, 561, 36, 521, -1, + 561, 521, 559, -1, 183, 577, 185, -1, + 182, 186, 570, -1, 510, 570, 186, -1, + 1723, 1269, 1271, -1, 648, 1646, 25, -1, + 648, 25, 647, -1, 205, 2193, 2195, -1, + 41, 178, 39, -1, 41, 39, 207, -1, + 686, 216, 687, -1, 686, 138, 216, -1, + 686, 139, 138, -1, 212, 48, 139, -1, + 212, 2033, 49, -1, 215, 394, 43, -1, + 215, 43, 692, -1, 699, 700, 42, -1, + 45, 34, 223, -1, 45, 228, 34, -1, + 225, 2263, 228, -1, 2253, 2254, 229, -1, + 2253, 228, 2263, -1, 722, 2042, 46, -1, + 1413, 2016, 1713, -1, 1439, 232, 1438, -1, + 1439, 2037, 232, -1, 2040, 3, 2042, -1, + 2040, 5, 4, -1, 2040, 4, 3, -1, + 265, 239, 4, -1, 265, 4, 5, -1, + 265, 5, 262, -1, 50, 48, 212, -1, + 51, 263, 5, -1, 51, 5, 2040, -1, + 52, 257, 772, -1, 52, 263, 51, -1, + 773, 772, 257, -1, 777, 261, 260, -1, + 777, 260, 263, -1, 268, 786, 264, -1, + 272, 1479, 782, -1, 784, 261, 782, -1, + 784, 782, 1479, -1, 118, 1727, 53, -1, + 780, 779, 935, -1, 780, 935, 278, -1, + 479, 481, 288, -1, 479, 288, 56, -1, + 804, 479, 56, -1, 809, 57, 811, -1, + 293, 59, 60, -1, 293, 71, 294, -1, + 326, 2107, 823, -1, 326, 823, 2053, -1, + 1485, 58, 59, -1, 907, 909, 910, -1, + 907, 71, 293, -1, 907, 496, 71, -1, + 907, 910, 496, -1, 907, 293, 60, -1, + 62, 1532, 64, -1, 62, 481, 63, -1, + 62, 64, 481, -1, 65, 73, 71, -1, + 65, 71, 64, -1, 841, 848, 849, -1, + 68, 825, 824, -1, 68, 824, 845, -1, + 68, 69, 825, -1, 844, 848, 843, -1, + 844, 845, 824, -1, 2061, 844, 824, -1, + 2061, 848, 844, -1, 852, 853, 294, -1, + 367, 990, 365, -1, 367, 365, 993, -1, + 79, 153, 57, -1, 304, 83, 80, -1, + 313, 332, 314, -1, 313, 913, 332, -1, + 886, 313, 315, -1, 886, 913, 313, -1, + 336, 310, 337, -1, 336, 311, 310, -1, + 309, 311, 1004, -1, 309, 317, 893, -1, + 1002, 311, 1003, -1, 1002, 1004, 311, -1, + 328, 903, 6, -1, 328, 1574, 903, -1, + 328, 6, 911, -1, 901, 8, 902, -1, + 901, 2117, 8, -1, 901, 330, 2117, -1, + 901, 2111, 330, -1, 2115, 7, 8, -1, + 2115, 8, 2117, -1, 2115, 911, 7, -1, + 341, 750, 344, -1, 371, 317, 309, -1, + 371, 309, 1004, -1, 797, 932, 931, -1, + 11, 9, 12, -1, 11, 2510, 9, -1, + 11, 358, 2510, -1, 11, 359, 358, -1, + 90, 361, 359, -1, 90, 359, 91, -1, + 10, 91, 359, -1, 10, 795, 91, -1, + 10, 359, 11, -1, 10, 11, 12, -1, + 10, 796, 795, -1, 10, 12, 796, -1, + 356, 91, 352, -1, 362, 361, 980, -1, + 13, 348, 355, -1, 13, 347, 348, -1, + 13, 355, 320, -1, 13, 320, 347, -1, + 2517, 2516, 109, -1, 983, 96, 100, -1, + 105, 994, 97, -1, 99, 363, 994, -1, + 99, 100, 96, -1, 99, 994, 993, -1, + 364, 983, 100, -1, 364, 1664, 983, -1, + 996, 95, 75, -1, 325, 1686, 383, -1, + 325, 383, 369, -1, 1042, 101, 369, -1, + 1008, 75, 95, -1, 1008, 95, 106, -1, + 1623, 2872, 373, -1, 1032, 108, 378, -1, + 1032, 391, 108, -1, 1047, 385, 14, -1, + 1047, 14, 391, -1, 370, 1044, 943, -1, + 346, 94, 109, -1, 2163, 2165, 121, -1, + 2508, 2163, 121, -1, 1681, 1680, 392, -1, + 1054, 217, 1055, -1, 15, 19, 20, -1, + 15, 17, 19, -1, 15, 20, 1408, -1, + 15, 1408, 17, -1, 1409, 1408, 20, -1, + 44, 1408, 1406, -1, 44, 17, 1408, -1, + 148, 441, 434, -1, 148, 396, 393, -1, + 18, 394, 396, -1, 18, 43, 394, -1, + 18, 17, 44, -1, 18, 44, 43, -1, + 16, 19, 17, -1, 16, 17, 18, -1, + 16, 18, 396, -1, 16, 396, 148, -1, + 16, 434, 19, -1, 16, 148, 434, -1, + 111, 20, 19, -1, 111, 19, 434, -1, + 111, 130, 114, -1, 115, 20, 111, -1, + 115, 111, 114, -1, 115, 1409, 20, -1, + 115, 2003, 1409, -1, 115, 694, 2003, -1, + 115, 2189, 694, -1, 2187, 113, 694, -1, + 2187, 694, 2189, -1, 664, 654, 1091, -1, + 412, 409, 1109, -1, 1094, 412, 285, -1, + 1094, 409, 412, -1, 1728, 1729, 117, -1, + 1608, 1279, 967, -1, 422, 121, 421, -1, + 1092, 1716, 1131, -1, 123, 119, 417, -1, + 123, 417, 1115, -1, 425, 119, 123, -1, + 1123, 110, 427, -1, 1123, 124, 21, -1, + 1123, 21, 110, -1, 430, 431, 794, -1, + 430, 796, 433, -1, 430, 794, 796, -1, + 1061, 1065, 127, -1, 128, 460, 459, -1, + 131, 1067, 451, -1, 133, 599, 22, -1, + 133, 22, 137, -1, 133, 269, 117, -1, + 453, 22, 599, -1, 453, 134, 146, -1, + 453, 137, 22, -1, 142, 143, 47, -1, + 142, 144, 1146, -1, 149, 609, 610, -1, + 149, 147, 609, -1, 149, 610, 193, -1, + 149, 1149, 1148, -1, 149, 1148, 147, -1, + 151, 193, 447, -1, 151, 447, 459, -1, + 466, 23, 465, -1, 466, 467, 559, -1, + 466, 559, 23, -1, 472, 24, 474, -1, + 472, 473, 82, -1, 472, 82, 877, -1, + 472, 877, 24, -1, 814, 647, 25, -1, + 814, 25, 815, -1, 1535, 25, 1646, -1, + 1535, 1536, 25, -1, 303, 2095, 67, -1, + 31, 877, 876, -1, 31, 26, 877, -1, + 31, 28, 26, -1, 31, 32, 28, -1, + 1172, 63, 1765, -1, 1172, 298, 63, -1, + 1172, 483, 298, -1, 1154, 27, 489, -1, + 1154, 1155, 27, -1, 1763, 490, 1761, -1, + 33, 159, 158, -1, 33, 28, 32, -1, + 33, 29, 28, -1, 491, 865, 1183, -1, + 491, 860, 865, -1, 491, 161, 860, -1, + 488, 33, 158, -1, 488, 29, 33, -1, + 488, 158, 860, -1, 488, 860, 161, -1, + 488, 489, 29, -1, 30, 876, 303, -1, + 30, 303, 67, -1, 30, 67, 160, -1, + 30, 160, 159, -1, 30, 32, 31, -1, + 30, 31, 876, -1, 30, 33, 32, -1, + 30, 159, 33, -1, 162, 34, 163, -1, + 162, 2254, 34, -1, 495, 223, 500, -1, + 501, 223, 34, -1, 501, 500, 223, -1, + 501, 34, 2254, -1, 1841, 504, 1226, -1, + 564, 507, 36, -1, 564, 36, 561, -1, + 169, 35, 517, -1, 169, 167, 35, -1, + 508, 572, 1818, -1, 516, 1226, 504, -1, + 516, 517, 1226, -1, 519, 36, 171, -1, + 519, 520, 36, -1, 519, 169, 517, -1, + 523, 173, 172, -1, 523, 528, 522, -1, + 523, 172, 528, -1, 1217, 173, 504, -1, + 527, 465, 528, -1, 177, 546, 175, -1, + 1832, 671, 670, -1, 536, 1221, 537, -1, + 545, 546, 544, -1, 1205, 2254, 2187, -1, + 1205, 1228, 179, -1, 1205, 549, 1228, -1, + 555, 170, 514, -1, 555, 556, 167, -1, + 560, 181, 1171, -1, 562, 564, 561, -1, + 289, 290, 184, -1, 289, 184, 186, -1, + 289, 186, 182, -1, 583, 685, 2396, -1, + 1082, 1081, 400, -1, 587, 2396, 1949, -1, + 588, 38, 1262, -1, 588, 1262, 622, -1, + 445, 1232, 593, -1, 445, 446, 38, -1, + 445, 38, 588, -1, 445, 588, 1232, -1, + 1234, 588, 622, -1, 189, 1265, 604, -1, + 189, 1288, 1265, -1, 1250, 1723, 1271, -1, + 191, 116, 415, -1, 191, 1723, 1721, -1, + 191, 1721, 1097, -1, 191, 1097, 116, -1, + 1257, 188, 604, -1, 1257, 1102, 188, -1, + 598, 410, 1108, -1, 598, 599, 133, -1, + 598, 117, 410, -1, 598, 133, 117, -1, + 607, 612, 195, -1, 192, 195, 37, -1, + 192, 447, 193, -1, 192, 37, 446, -1, + 192, 446, 447, -1, 194, 37, 195, -1, + 194, 1262, 38, -1, 194, 38, 446, -1, + 194, 446, 37, -1, 1261, 1263, 622, -1, + 1261, 622, 1262, -1, 1272, 1112, 414, -1, + 1272, 1268, 1112, -1, 1248, 1276, 1275, -1, + 1248, 1277, 1276, -1, 627, 187, 1234, -1, + 2300, 2322, 2898, -1, 2199, 1077, 2195, -1, + 1075, 1077, 2199, -1, 636, 656, 1380, -1, + 1965, 661, 1381, -1, 663, 654, 664, -1, + 1391, 1300, 1299, -1, 1996, 39, 2394, -1, + 1996, 207, 39, -1, 675, 537, 178, -1, + 675, 178, 41, -1, 675, 41, 673, -1, + 40, 673, 41, -1, 40, 41, 207, -1, + 40, 209, 673, -1, 40, 207, 209, -1, + 211, 2393, 2394, -1, 213, 139, 686, -1, + 213, 212, 139, -1, 1396, 42, 1399, -1, + 1396, 699, 42, -1, 214, 1399, 42, -1, + 214, 42, 700, -1, 2694, 1713, 2016, -1, + 1405, 692, 43, -1, 1405, 44, 1406, -1, + 1405, 43, 44, -1, 218, 692, 700, -1, + 220, 2261, 2263, -1, 222, 228, 45, -1, + 222, 225, 228, -1, 222, 45, 223, -1, + 227, 228, 2253, -1, 227, 2253, 229, -1, + 231, 704, 1417, -1, 1430, 232, 1413, -1, + 1430, 1420, 232, -1, 1430, 1419, 1420, -1, + 1430, 910, 1463, -1, 1430, 1713, 910, -1, + 1430, 1413, 1713, -1, 1462, 1430, 1463, -1, + 714, 1438, 232, -1, 1433, 49, 2033, -1, + 1433, 46, 49, -1, 1433, 722, 46, -1, + 2431, 715, 2037, -1, 726, 725, 719, -1, + 1437, 2037, 715, -1, 1437, 1410, 1413, -1, + 1437, 2006, 1410, -1, 1437, 232, 2037, -1, + 1437, 1413, 232, -1, 787, 50, 786, -1, + 787, 142, 47, -1, 787, 788, 142, -1, + 787, 47, 48, -1, 787, 48, 50, -1, + 789, 145, 144, -1, 789, 144, 142, -1, + 789, 142, 788, -1, 241, 212, 49, -1, + 241, 50, 212, -1, 241, 49, 239, -1, + 240, 264, 786, -1, 240, 786, 50, -1, + 240, 265, 264, -1, 240, 50, 241, -1, + 242, 340, 256, -1, 774, 772, 773, -1, + 247, 52, 772, -1, 248, 734, 266, -1, + 1588, 935, 779, -1, 1588, 779, 734, -1, + 87, 342, 735, -1, 87, 735, 86, -1, + 87, 86, 344, -1, 87, 344, 88, -1, + 938, 735, 342, -1, 246, 245, 86, -1, + 246, 86, 735, -1, 752, 2451, 2452, -1, + 730, 244, 753, -1, 759, 753, 251, -1, + 243, 256, 770, -1, 243, 770, 756, -1, + 243, 756, 251, -1, 243, 251, 753, -1, + 243, 753, 244, -1, 1468, 1473, 768, -1, + 258, 51, 2040, -1, 258, 257, 52, -1, + 258, 52, 51, -1, 783, 268, 264, -1, + 783, 261, 784, -1, 776, 782, 261, -1, + 776, 261, 777, -1, 267, 247, 266, -1, + 267, 52, 247, -1, 267, 263, 52, -1, + 267, 777, 263, -1, 790, 270, 789, -1, + 1478, 53, 1727, -1, 1478, 1479, 53, -1, + 781, 780, 278, -1, 273, 276, 118, -1, + 273, 118, 53, -1, 273, 53, 1479, -1, + 273, 1479, 272, -1, 933, 277, 936, -1, + 934, 277, 278, -1, 934, 936, 277, -1, + 934, 278, 935, -1, 54, 118, 276, -1, + 54, 413, 118, -1, 275, 281, 55, -1, + 275, 54, 276, -1, 275, 55, 413, -1, + 275, 413, 54, -1, 411, 285, 412, -1, + 280, 794, 431, -1, 284, 800, 281, -1, + 801, 55, 281, -1, 801, 281, 800, -1, + 801, 413, 55, -1, 801, 411, 413, -1, + 801, 285, 411, -1, 808, 56, 288, -1, + 808, 804, 56, -1, 155, 815, 1536, -1, + 155, 809, 815, -1, 155, 154, 80, -1, + 155, 80, 79, -1, 155, 57, 809, -1, + 155, 79, 57, -1, 905, 60, 822, -1, + 821, 58, 1485, -1, 821, 60, 58, -1, + 821, 822, 60, -1, 1484, 59, 293, -1, + 1484, 1485, 59, -1, 1500, 1544, 1542, -1, + 835, 1505, 2064, -1, 1504, 1505, 829, -1, + 908, 907, 60, -1, 908, 60, 905, -1, + 61, 1532, 62, -1, 61, 62, 63, -1, + 61, 298, 1532, -1, 61, 63, 298, -1, + 1533, 64, 1532, -1, 1533, 65, 64, -1, + 1533, 73, 65, -1, 1520, 841, 849, -1, + 1520, 1513, 2079, -1, 295, 1487, 857, -1, + 66, 67, 2095, -1, 66, 2095, 825, -1, + 66, 825, 69, -1, 66, 160, 67, -1, + 66, 69, 160, -1, 1528, 843, 72, -1, + 846, 68, 845, -1, 846, 69, 68, -1, + 846, 160, 69, -1, 296, 160, 846, -1, + 850, 1513, 1520, -1, 70, 73, 852, -1, + 70, 852, 294, -1, 70, 71, 73, -1, + 70, 294, 71, -1, 855, 299, 1527, -1, + 855, 72, 856, -1, 855, 1527, 1528, -1, + 855, 1528, 72, -1, 839, 856, 72, -1, + 839, 72, 843, -1, 297, 1530, 299, -1, + 297, 852, 73, -1, 297, 73, 1533, -1, + 297, 1533, 1530, -1, 1650, 85, 301, -1, + 74, 75, 885, -1, 74, 885, 881, -1, + 74, 996, 75, -1, 74, 881, 996, -1, + 1007, 885, 75, -1, 1007, 75, 1008, -1, + 869, 154, 2479, -1, 869, 80, 154, -1, + 76, 304, 868, -1, 76, 868, 1534, -1, + 76, 1534, 873, -1, 76, 873, 2097, -1, + 76, 2097, 304, -1, 77, 868, 304, -1, + 77, 304, 80, -1, 77, 869, 868, -1, + 77, 80, 869, -1, 78, 84, 153, -1, + 78, 83, 84, -1, 78, 153, 79, -1, + 78, 80, 83, -1, 78, 79, 80, -1, + 81, 473, 153, -1, 81, 153, 84, -1, + 81, 82, 473, -1, 81, 84, 82, -1, + 878, 82, 84, -1, 878, 877, 82, -1, + 1538, 83, 304, -1, 1538, 84, 83, -1, + 1538, 878, 84, -1, 1493, 1492, 2488, -1, + 306, 882, 85, -1, 306, 85, 1650, -1, + 302, 85, 882, -1, 302, 870, 301, -1, + 302, 301, 85, -1, 302, 882, 883, -1, + 884, 881, 885, -1, 331, 314, 332, -1, + 1449, 2446, 889, -1, 1547, 745, 1548, -1, + 1547, 744, 745, -1, 334, 1003, 311, -1, + 334, 311, 336, -1, 962, 2136, 387, -1, + 946, 387, 951, -1, 93, 387, 2136, -1, + 93, 951, 387, -1, 93, 346, 951, -1, + 93, 94, 346, -1, 1000, 369, 101, -1, + 1000, 325, 369, -1, 1571, 909, 907, -1, + 1587, 914, 2498, -1, 1555, 330, 2111, -1, + 1555, 1556, 330, -1, 1560, 1561, 1556, -1, + 924, 242, 925, -1, 924, 340, 242, -1, + 924, 245, 339, -1, 923, 86, 245, -1, + 923, 344, 86, -1, 923, 341, 344, -1, + 923, 245, 924, -1, 975, 342, 87, -1, + 975, 87, 88, -1, 971, 975, 88, -1, + 971, 88, 344, -1, 897, 345, 899, -1, + 941, 371, 942, -1, 941, 318, 371, -1, + 941, 345, 897, -1, 941, 897, 318, -1, + 949, 899, 345, -1, 742, 974, 973, -1, + 742, 744, 322, -1, 354, 320, 355, -1, + 319, 347, 320, -1, 319, 899, 949, -1, + 319, 949, 347, -1, 1317, 964, 2144, -1, + 1317, 1895, 964, -1, 1615, 1623, 373, -1, + 351, 1611, 1619, -1, 89, 91, 795, -1, + 89, 795, 797, -1, 89, 352, 91, -1, + 89, 931, 352, -1, 89, 797, 931, -1, + 978, 355, 980, -1, 979, 90, 91, -1, + 979, 91, 356, -1, 979, 980, 361, -1, + 979, 361, 90, -1, 92, 362, 980, -1, + 92, 348, 362, -1, 92, 980, 355, -1, + 92, 355, 348, -1, 360, 2516, 358, -1, + 360, 109, 2516, -1, 360, 362, 109, -1, + 2518, 93, 2136, -1, 2518, 94, 93, -1, + 2518, 109, 94, -1, 2518, 2517, 109, -1, + 984, 985, 96, -1, 984, 96, 983, -1, + 995, 994, 105, -1, 995, 95, 996, -1, + 995, 106, 95, -1, 995, 105, 106, -1, + 1657, 363, 99, -1, 1657, 99, 96, -1, + 1657, 96, 985, -1, 1657, 985, 1655, -1, + 375, 379, 107, -1, 375, 105, 97, -1, + 375, 107, 105, -1, 375, 97, 363, -1, + 98, 100, 99, -1, 98, 364, 100, -1, + 98, 365, 364, -1, 98, 993, 365, -1, + 98, 99, 993, -1, 1660, 1664, 364, -1, + 997, 881, 305, -1, 997, 996, 881, -1, + 997, 305, 366, -1, 1049, 1050, 1042, -1, + 1049, 385, 1047, -1, 999, 101, 1042, -1, + 999, 1044, 370, -1, 999, 1000, 101, -1, + 2073, 1686, 324, -1, 2073, 324, 2074, -1, + 372, 832, 1009, -1, 372, 1035, 832, -1, + 2069, 832, 1035, -1, 102, 1348, 1017, -1, + 102, 1349, 1348, -1, 102, 2180, 1349, -1, + 1016, 2545, 103, -1, 1016, 103, 102, -1, + 1016, 102, 1017, -1, 1683, 955, 1028, -1, + 1683, 1029, 1015, -1, 104, 1012, 2180, -1, + 104, 2180, 102, -1, 104, 102, 103, -1, + 1667, 2545, 1014, -1, 1667, 103, 2545, -1, + 1667, 104, 103, -1, 1667, 1012, 104, -1, + 1031, 1032, 378, -1, 1005, 106, 105, -1, + 1005, 105, 107, -1, 1005, 380, 1038, -1, + 1005, 107, 379, -1, 1005, 379, 380, -1, + 1005, 1008, 106, -1, 382, 108, 385, -1, + 382, 378, 108, -1, 1685, 383, 1686, -1, + 388, 1040, 961, -1, 388, 1041, 1040, -1, + 388, 1044, 1041, -1, 1043, 1044, 999, -1, + 1043, 999, 1042, -1, 390, 1027, 1028, -1, + 390, 1028, 955, -1, 390, 955, 956, -1, + 390, 956, 1046, -1, 390, 391, 1027, -1, + 349, 362, 348, -1, 349, 109, 362, -1, + 349, 346, 109, -1, 122, 2508, 121, -1, + 122, 427, 110, -1, 122, 110, 2509, -1, + 122, 2509, 2508, -1, 1140, 1149, 149, -1, + 1138, 150, 456, -1, 1138, 1140, 150, -1, + 129, 434, 435, -1, 129, 111, 434, -1, + 129, 130, 111, -1, 112, 1067, 1066, -1, + 112, 1066, 448, -1, 112, 451, 1067, -1, + 112, 448, 451, -1, 397, 1056, 402, -1, + 2266, 2267, 1692, -1, 1078, 653, 398, -1, + 1078, 1082, 400, -1, 405, 448, 1066, -1, + 405, 397, 402, -1, 405, 1066, 397, -1, + 1068, 1956, 1692, -1, 1068, 1692, 2267, -1, + 1239, 402, 1056, -1, 1239, 403, 402, -1, + 1239, 1056, 1236, -1, 2243, 2187, 2244, -1, + 2243, 693, 113, -1, 2243, 113, 2187, -1, + 1695, 114, 452, -1, 1695, 452, 1134, -1, + 1695, 1134, 1072, -1, 1695, 115, 114, -1, + 1695, 2189, 115, -1, 1694, 1695, 1072, -1, + 1087, 664, 1091, -1, 1087, 2192, 664, -1, + 408, 2839, 685, -1, 408, 685, 583, -1, + 2203, 1091, 654, -1, 2203, 654, 1701, -1, + 1098, 116, 1097, -1, 1098, 415, 116, -1, + 1100, 1109, 409, -1, 1100, 1105, 1109, -1, + 1722, 1723, 1250, -1, 1104, 1729, 1109, -1, + 1104, 1109, 1105, -1, 1730, 117, 269, -1, + 1730, 1728, 117, -1, 1730, 1478, 1727, -1, + 1730, 269, 1478, -1, 1726, 118, 413, -1, + 1726, 1727, 118, -1, 420, 417, 119, -1, + 420, 119, 425, -1, 120, 121, 422, -1, + 120, 422, 427, -1, 120, 122, 121, -1, + 120, 427, 122, -1, 423, 417, 418, -1, + 423, 1115, 417, -1, 423, 418, 2149, -1, + 1718, 1092, 1133, -1, 1718, 1121, 1098, -1, + 424, 123, 1115, -1, 424, 1133, 123, -1, + 424, 1121, 1718, -1, 424, 1718, 1133, -1, + 1128, 123, 1133, -1, 1128, 425, 123, -1, + 1124, 124, 1123, -1, 1124, 433, 124, -1, + 125, 127, 1065, -1, 125, 438, 127, -1, + 125, 1065, 1067, -1, 125, 1067, 131, -1, + 125, 131, 436, -1, 440, 125, 436, -1, + 440, 438, 125, -1, 126, 439, 460, -1, + 126, 460, 128, -1, 126, 127, 438, -1, + 126, 438, 439, -1, 126, 592, 1061, -1, + 126, 1061, 127, -1, 126, 593, 592, -1, + 126, 128, 593, -1, 444, 593, 128, -1, + 444, 459, 447, -1, 444, 128, 459, -1, + 450, 130, 129, -1, 450, 129, 435, -1, + 450, 452, 130, -1, 450, 435, 436, -1, + 450, 436, 131, -1, 450, 131, 451, -1, + 1070, 1134, 452, -1, 1070, 1735, 1134, -1, + 132, 269, 133, -1, 132, 133, 137, -1, + 132, 270, 269, -1, 132, 137, 270, -1, + 606, 134, 453, -1, 606, 601, 607, -1, + 606, 609, 134, -1, 135, 453, 146, -1, + 135, 137, 453, -1, 135, 146, 145, -1, + 135, 145, 137, -1, 136, 270, 137, -1, + 136, 137, 145, -1, 136, 789, 270, -1, + 136, 145, 789, -1, 141, 143, 1143, -1, + 141, 140, 216, -1, 141, 216, 138, -1, + 141, 138, 139, -1, 141, 139, 143, -1, + 1142, 1055, 140, -1, 1142, 1139, 1055, -1, + 1142, 140, 141, -1, 1142, 141, 1143, -1, + 1145, 142, 1146, -1, 1145, 143, 142, -1, + 1145, 1143, 143, -1, 1147, 1146, 144, -1, + 1147, 144, 145, -1, 1147, 145, 146, -1, + 1147, 146, 147, -1, 1147, 147, 1148, -1, + 457, 148, 393, -1, 457, 441, 148, -1, + 152, 149, 193, -1, 152, 1140, 149, -1, + 455, 456, 150, -1, 455, 151, 459, -1, + 455, 150, 1140, -1, 455, 1140, 152, -1, + 455, 193, 151, -1, 455, 152, 193, -1, + 464, 180, 467, -1, 464, 463, 180, -1, + 156, 180, 463, -1, 156, 181, 180, -1, + 1152, 1763, 157, -1, 1152, 463, 468, -1, + 1152, 157, 156, -1, 1152, 156, 463, -1, + 469, 811, 153, -1, 469, 153, 473, -1, + 1158, 469, 473, -1, 1158, 470, 469, -1, + 1339, 1340, 651, -1, 1791, 1792, 1341, -1, + 1342, 475, 1341, -1, 1342, 1339, 651, -1, + 477, 647, 814, -1, 477, 1342, 647, -1, + 477, 475, 1342, -1, 1162, 475, 477, -1, + 2091, 2479, 154, -1, 2091, 154, 155, -1, + 2091, 155, 1536, -1, 1168, 481, 479, -1, + 1762, 157, 1763, -1, 482, 1171, 181, -1, + 482, 484, 1171, -1, 482, 181, 156, -1, + 482, 156, 157, -1, 482, 157, 1762, -1, + 486, 860, 158, -1, 486, 296, 862, -1, + 486, 158, 159, -1, 486, 159, 160, -1, + 486, 160, 296, -1, 492, 161, 491, -1, + 492, 488, 161, -1, 1194, 2211, 2216, -1, + 1194, 2216, 2214, -1, 230, 229, 2254, -1, + 230, 2254, 162, -1, 230, 162, 163, -1, + 230, 163, 228, -1, 497, 164, 496, -1, + 497, 165, 164, -1, 497, 185, 165, -1, + 497, 183, 185, -1, 1201, 1206, 502, -1, + 1201, 501, 2254, -1, 1201, 2254, 1206, -1, + 2777, 504, 1841, -1, 563, 507, 564, -1, + 563, 570, 510, -1, 1817, 1203, 1205, -1, + 513, 1207, 1817, -1, 513, 555, 514, -1, + 513, 1205, 551, -1, 513, 1817, 1205, -1, + 166, 169, 170, -1, 166, 167, 169, -1, + 166, 170, 555, -1, 166, 555, 167, -1, + 1820, 1207, 514, -1, 1820, 508, 1818, -1, + 1820, 514, 170, -1, 1820, 170, 508, -1, + 168, 170, 169, -1, 168, 508, 170, -1, + 168, 506, 508, -1, 168, 519, 171, -1, + 168, 169, 519, -1, 168, 171, 507, -1, + 168, 507, 506, -1, 518, 173, 523, -1, + 518, 504, 173, -1, 518, 516, 504, -1, + 1215, 1212, 1209, -1, 529, 528, 172, -1, + 529, 172, 1212, -1, 1827, 2282, 539, -1, + 530, 1209, 1212, -1, 530, 1212, 172, -1, + 530, 172, 173, -1, 530, 173, 1217, -1, + 533, 1740, 1741, -1, 534, 462, 465, -1, + 534, 465, 527, -1, 534, 1741, 462, -1, + 534, 533, 1741, -1, 174, 175, 176, -1, + 174, 177, 175, -1, 174, 176, 546, -1, + 174, 546, 177, -1, 1830, 1827, 539, -1, + 543, 1221, 545, -1, 543, 544, 178, -1, + 543, 178, 537, -1, 543, 537, 1221, -1, + 1224, 545, 1221, -1, 1844, 1225, 1205, -1, + 552, 1205, 179, -1, 552, 179, 556, -1, + 552, 556, 554, -1, 553, 513, 551, -1, + 553, 555, 513, -1, 558, 180, 181, -1, + 558, 181, 560, -1, 558, 467, 180, -1, + 558, 559, 467, -1, 566, 564, 562, -1, + 802, 807, 289, -1, 802, 289, 182, -1, + 802, 182, 570, -1, 568, 567, 560, -1, + 499, 495, 500, -1, 499, 577, 183, -1, + 499, 498, 577, -1, 499, 183, 497, -1, + 576, 577, 498, -1, 578, 186, 184, -1, + 578, 574, 186, -1, 578, 185, 577, -1, + 578, 290, 185, -1, 578, 184, 290, -1, + 509, 574, 575, -1, 509, 510, 186, -1, + 509, 186, 574, -1, 584, 579, 400, -1, + 584, 400, 1081, -1, 584, 1081, 583, -1, + 580, 400, 579, -1, 580, 587, 400, -1, + 1244, 1234, 187, -1, 1238, 199, 1378, -1, + 1238, 1378, 403, -1, 1238, 403, 1239, -1, + 1059, 1061, 592, -1, 1059, 1246, 1060, -1, + 597, 1057, 1060, -1, 597, 1060, 1246, -1, + 1245, 187, 627, -1, 1245, 1244, 187, -1, + 1252, 604, 188, -1, 1252, 189, 604, -1, + 1252, 188, 1102, -1, 1252, 1288, 189, -1, + 190, 191, 415, -1, 190, 1268, 1269, -1, + 190, 1269, 1723, -1, 190, 1723, 191, -1, + 190, 415, 1112, -1, 190, 1112, 1268, -1, + 602, 601, 606, -1, 608, 607, 195, -1, + 608, 195, 192, -1, 608, 193, 610, -1, + 608, 192, 193, -1, 611, 1262, 194, -1, + 611, 195, 612, -1, 611, 194, 195, -1, + 1260, 604, 1265, -1, 1260, 613, 604, -1, + 1849, 1272, 414, -1, 1270, 1277, 1248, -1, + 1270, 1248, 1271, -1, 196, 595, 1245, -1, + 196, 1245, 627, -1, 1305, 1283, 637, -1, + 1305, 637, 625, -1, 626, 196, 627, -1, + 626, 637, 1292, -1, 626, 1292, 595, -1, + 626, 595, 196, -1, 1285, 1853, 1858, -1, + 1285, 1275, 1854, -1, 1285, 1854, 1853, -1, + 631, 617, 616, -1, 1973, 637, 1283, -1, + 1296, 1989, 666, -1, 1302, 1862, 1863, -1, + 1386, 1969, 1968, -1, 1386, 1968, 640, -1, + 1386, 640, 1862, -1, 1386, 1862, 1302, -1, + 615, 2295, 1304, -1, 615, 617, 197, -1, + 615, 618, 617, -1, 2294, 2295, 615, -1, + 2294, 615, 197, -1, 630, 617, 631, -1, + 639, 1858, 1857, -1, 639, 1857, 2294, -1, + 639, 2294, 197, -1, 639, 197, 617, -1, + 639, 617, 630, -1, 639, 630, 1286, -1, + 1315, 1971, 1972, -1, 2353, 2354, 641, -1, + 2353, 641, 642, -1, 1335, 1808, 1806, -1, + 1338, 1335, 1334, -1, 1338, 1792, 1808, -1, + 1338, 1808, 1335, -1, 1343, 1905, 2664, -1, + 987, 1353, 1354, -1, 650, 1646, 648, -1, + 650, 1645, 1646, -1, 643, 1371, 1370, -1, + 643, 1334, 1333, -1, 643, 641, 1371, -1, + 643, 642, 641, -1, 198, 1340, 1334, -1, + 198, 1370, 1340, -1, 198, 1334, 643, -1, + 198, 643, 1370, -1, 206, 2195, 1077, -1, + 206, 205, 2195, -1, 206, 1077, 200, -1, + 206, 200, 661, -1, 206, 661, 1965, -1, + 1076, 398, 1375, -1, 1076, 200, 1077, -1, + 652, 1076, 1375, -1, 652, 1378, 199, -1, + 652, 201, 200, -1, 652, 200, 1076, -1, + 1954, 398, 653, -1, 1954, 1375, 398, -1, + 202, 1241, 203, -1, 202, 1238, 1241, -1, + 202, 199, 1238, -1, 202, 201, 652, -1, + 202, 652, 199, -1, 660, 200, 201, -1, + 660, 661, 200, -1, 660, 201, 202, -1, + 660, 202, 203, -1, 1379, 636, 1380, -1, + 659, 636, 1379, -1, 659, 660, 203, -1, + 204, 1241, 1236, -1, 204, 1236, 596, -1, + 632, 635, 659, -1, 632, 659, 203, -1, + 632, 203, 1241, -1, 632, 1241, 204, -1, + 632, 204, 633, -1, 1291, 204, 596, -1, + 1291, 633, 204, -1, 1291, 595, 1292, -1, + 1966, 2193, 205, -1, 1966, 205, 206, -1, + 1966, 206, 1965, -1, 1966, 1964, 663, -1, + 1993, 1990, 2387, -1, 668, 1995, 1084, -1, + 668, 1084, 1389, -1, 668, 1389, 1391, -1, + 667, 1391, 1299, -1, 667, 1299, 1296, -1, + 669, 2409, 209, -1, 669, 209, 207, -1, + 669, 207, 1996, -1, 208, 209, 2409, -1, + 208, 2409, 2586, -1, 208, 2586, 679, -1, + 2210, 2211, 679, -1, 2210, 679, 2209, -1, + 2208, 679, 2586, -1, 2208, 2209, 679, -1, + 674, 671, 677, -1, 682, 493, 670, -1, + 682, 1195, 493, -1, 678, 208, 679, -1, + 678, 209, 208, -1, 678, 673, 209, -1, + 678, 680, 673, -1, 2406, 2394, 210, -1, + 2406, 211, 2394, -1, 2406, 210, 546, -1, + 2406, 2393, 211, -1, 2406, 1205, 2187, -1, + 2406, 2187, 2266, -1, 684, 685, 2839, -1, + 684, 2839, 2397, -1, 2032, 2033, 212, -1, + 2032, 212, 213, -1, 2032, 686, 2034, -1, + 2032, 213, 686, -1, 711, 699, 690, -1, + 688, 690, 699, -1, 688, 699, 1396, -1, + 691, 700, 692, -1, 691, 214, 700, -1, + 1403, 1399, 214, -1, 1403, 214, 691, -1, + 219, 215, 692, -1, 219, 692, 218, -1, + 219, 394, 215, -1, 219, 1054, 394, -1, + 219, 217, 1054, -1, 701, 687, 216, -1, + 701, 216, 217, -1, 701, 218, 700, -1, + 701, 217, 219, -1, 701, 219, 218, -1, + 1414, 236, 702, -1, 1400, 1398, 2000, -1, + 1400, 236, 1398, -1, 1400, 702, 236, -1, + 224, 2261, 220, -1, 224, 496, 2261, -1, + 224, 2263, 225, -1, 224, 220, 2263, -1, + 221, 222, 223, -1, 221, 495, 496, -1, + 221, 223, 495, -1, 221, 496, 224, -1, + 221, 225, 222, -1, 221, 224, 225, -1, + 226, 228, 227, -1, 226, 227, 229, -1, + 226, 230, 228, -1, 226, 229, 230, -1, + 1422, 1417, 704, -1, 1422, 704, 1423, -1, + 1443, 1444, 1423, -1, 767, 704, 231, -1, + 767, 756, 770, -1, 767, 231, 756, -1, + 1428, 756, 231, -1, 1428, 231, 1417, -1, + 706, 1420, 1418, -1, 706, 232, 1420, -1, + 706, 714, 232, -1, 723, 722, 1433, -1, + 1431, 1434, 234, -1, 1431, 234, 708, -1, + 689, 236, 235, -1, 689, 1398, 236, -1, + 2036, 711, 690, -1, 2036, 690, 689, -1, + 2036, 689, 235, -1, 2036, 235, 1434, -1, + 233, 234, 1434, -1, 233, 1434, 235, -1, + 233, 235, 236, -1, 233, 236, 1414, -1, + 233, 708, 234, -1, 233, 1414, 708, -1, + 716, 718, 719, -1, 2432, 2431, 2037, -1, + 710, 719, 725, -1, 710, 716, 719, -1, + 710, 709, 2025, -1, 710, 2025, 716, -1, + 237, 1446, 1441, -1, 237, 1441, 726, -1, + 237, 720, 1446, -1, 237, 726, 719, -1, + 237, 719, 720, -1, 727, 726, 1441, -1, + 238, 239, 265, -1, 238, 265, 240, -1, + 238, 241, 239, -1, 238, 240, 241, -1, + 732, 242, 256, -1, 732, 243, 244, -1, + 732, 256, 243, -1, 732, 244, 730, -1, + 732, 925, 242, -1, 739, 339, 245, -1, + 739, 245, 246, -1, 739, 735, 738, -1, + 739, 246, 735, -1, 1470, 740, 771, -1, + 1470, 1469, 339, -1, 1470, 339, 739, -1, + 1470, 739, 740, -1, 741, 771, 740, -1, + 741, 772, 771, -1, 741, 247, 772, -1, + 741, 266, 247, -1, 741, 248, 266, -1, + 737, 734, 248, -1, 737, 248, 741, -1, + 929, 748, 747, -1, 249, 749, 764, -1, + 249, 2444, 747, -1, 249, 747, 749, -1, + 2443, 2444, 249, -1, 2443, 249, 764, -1, + 312, 2444, 2445, -1, 312, 745, 743, -1, + 312, 747, 2444, -1, 312, 743, 929, -1, + 312, 929, 747, -1, 2449, 2451, 2450, -1, + 751, 2451, 752, -1, 751, 2450, 2451, -1, + 751, 910, 2450, -1, 1460, 253, 1459, -1, + 757, 752, 1458, -1, 250, 2452, 2453, -1, + 250, 2453, 252, -1, 250, 752, 2452, -1, + 250, 1458, 752, -1, 250, 252, 1460, -1, + 250, 1460, 1458, -1, 754, 1459, 730, -1, + 754, 730, 753, -1, 758, 759, 251, -1, + 758, 251, 756, -1, 760, 750, 341, -1, + 760, 749, 750, -1, 760, 764, 749, -1, + 254, 731, 730, -1, 254, 730, 1459, -1, + 254, 1459, 253, -1, 763, 252, 2453, -1, + 763, 1460, 252, -1, 763, 253, 1460, -1, + 762, 926, 731, -1, 762, 253, 763, -1, + 762, 731, 254, -1, 762, 254, 253, -1, + 769, 770, 256, -1, 255, 340, 1469, -1, + 255, 1469, 1468, -1, 255, 1468, 769, -1, + 255, 256, 340, -1, 255, 769, 256, -1, + 2039, 773, 257, -1, 2039, 257, 258, -1, + 2039, 258, 2040, -1, 259, 260, 261, -1, + 259, 261, 783, -1, 259, 262, 263, -1, + 259, 263, 260, -1, 259, 783, 264, -1, + 259, 264, 265, -1, 259, 265, 262, -1, + 778, 734, 779, -1, 778, 266, 734, -1, + 778, 267, 266, -1, 778, 777, 267, -1, + 1482, 268, 783, -1, 1482, 786, 268, -1, + 791, 269, 270, -1, 791, 1478, 269, -1, + 791, 270, 790, -1, 271, 781, 278, -1, + 271, 278, 276, -1, 271, 272, 782, -1, + 271, 782, 781, -1, 271, 276, 273, -1, + 271, 273, 272, -1, 282, 281, 275, -1, + 282, 275, 277, -1, 282, 277, 933, -1, + 282, 933, 283, -1, 274, 275, 276, -1, + 274, 277, 275, -1, 274, 276, 278, -1, + 274, 278, 277, -1, 793, 933, 932, -1, + 793, 283, 933, -1, 793, 932, 797, -1, + 793, 794, 280, -1, 279, 280, 431, -1, + 279, 431, 284, -1, 279, 284, 281, -1, + 279, 281, 282, -1, 279, 282, 283, -1, + 279, 283, 793, -1, 279, 793, 280, -1, + 799, 431, 432, -1, 799, 284, 431, -1, + 799, 1131, 1716, -1, 799, 800, 284, -1, + 1095, 285, 801, -1, 1095, 1094, 285, -1, + 286, 288, 287, -1, 286, 808, 288, -1, + 286, 287, 290, -1, 286, 290, 808, -1, + 806, 290, 289, -1, 806, 808, 290, -1, + 806, 289, 807, -1, 291, 479, 804, -1, + 291, 1180, 479, -1, 291, 804, 1180, -1, + 1179, 1180, 804, -1, 817, 810, 1164, -1, + 904, 905, 823, -1, 904, 823, 2107, -1, + 904, 2107, 1566, -1, 2063, 838, 900, -1, + 2051, 821, 1485, -1, 292, 293, 294, -1, + 292, 294, 1484, -1, 292, 1484, 293, -1, + 1486, 294, 853, -1, 1486, 1484, 294, -1, + 1497, 2105, 2104, -1, 1545, 826, 1497, -1, + 1545, 1497, 2104, -1, 1545, 828, 826, -1, + 1545, 1544, 828, -1, 1512, 1513, 1496, -1, + 1512, 1496, 837, -1, 827, 837, 1496, -1, + 834, 835, 818, -1, 834, 818, 2477, -1, + 836, 1505, 835, -1, 836, 837, 827, -1, + 836, 829, 1505, -1, 1517, 2462, 2122, -1, + 1518, 295, 857, -1, 2850, 1487, 295, -1, + 2850, 295, 1518, -1, 2850, 1518, 2851, -1, + 859, 862, 296, -1, 859, 296, 846, -1, + 1525, 1513, 850, -1, 1525, 1496, 1513, -1, + 1525, 1524, 1496, -1, 854, 299, 855, -1, + 854, 297, 299, -1, 854, 852, 297, -1, + 840, 839, 843, -1, 840, 843, 848, -1, + 840, 848, 841, -1, 1531, 1532, 298, -1, + 1531, 298, 867, -1, 864, 298, 483, -1, + 864, 867, 298, -1, 864, 483, 1183, -1, + 2082, 867, 864, -1, 2086, 299, 1530, -1, + 2086, 1527, 299, -1, 300, 1650, 1648, -1, + 300, 1648, 366, -1, 300, 366, 305, -1, + 300, 305, 306, -1, 300, 306, 1650, -1, + 982, 301, 2088, -1, 982, 1650, 301, -1, + 307, 1009, 1500, -1, 307, 1007, 1009, -1, + 2087, 2088, 301, -1, 2087, 301, 870, -1, + 872, 883, 1540, -1, 872, 1540, 1491, -1, + 872, 870, 302, -1, 872, 302, 883, -1, + 872, 1491, 1493, -1, 2094, 303, 876, -1, + 2094, 2095, 303, -1, 1537, 304, 2097, -1, + 1537, 1538, 304, -1, 2098, 1493, 2488, -1, + 2098, 2097, 873, -1, 880, 305, 881, -1, + 880, 306, 305, -1, 880, 882, 306, -1, + 1541, 1500, 1542, -1, 1541, 307, 1500, -1, + 1541, 885, 1007, -1, 1541, 1007, 307, -1, + 308, 893, 314, -1, 308, 314, 331, -1, + 308, 309, 893, -1, 308, 310, 311, -1, + 308, 311, 309, -1, 308, 337, 310, -1, + 308, 331, 337, -1, 2044, 886, 316, -1, + 2044, 889, 2446, -1, 2044, 316, 889, -1, + 888, 1548, 745, -1, 888, 2445, 1449, -1, + 888, 312, 2445, -1, 888, 745, 312, -1, + 892, 315, 313, -1, 892, 313, 314, -1, + 892, 314, 893, -1, 890, 886, 315, -1, + 890, 316, 886, -1, 890, 315, 892, -1, + 890, 889, 316, -1, 895, 893, 317, -1, + 895, 317, 371, -1, 895, 371, 318, -1, + 895, 318, 897, -1, 898, 321, 1551, -1, + 898, 899, 319, -1, 898, 319, 321, -1, + 350, 742, 322, -1, 350, 319, 320, -1, + 350, 321, 319, -1, 350, 320, 354, -1, + 1550, 1551, 321, -1, 1550, 350, 322, -1, + 1550, 321, 350, -1, 1550, 322, 744, -1, + 1550, 744, 1547, -1, 323, 1003, 334, -1, + 323, 334, 335, -1, 323, 2074, 324, -1, + 323, 335, 2074, -1, 323, 1000, 1003, -1, + 323, 325, 1000, -1, 323, 324, 1686, -1, + 323, 1686, 325, -1, 2503, 900, 838, -1, + 2712, 2107, 326, -1, 2712, 326, 2053, -1, + 2712, 2053, 2713, -1, 2494, 1562, 327, -1, + 906, 1580, 1571, -1, 2495, 327, 909, -1, + 2495, 2494, 327, -1, 1573, 1450, 1575, -1, + 1573, 1576, 1450, -1, 1573, 1574, 328, -1, + 1573, 328, 911, -1, 2448, 2709, 1450, -1, + 2448, 1450, 1576, -1, 2500, 2498, 914, -1, + 2500, 2046, 2844, -1, 2500, 915, 2046, -1, + 2118, 2117, 330, -1, 2118, 330, 2498, -1, + 917, 1556, 1561, -1, 917, 1587, 1556, -1, + 329, 1556, 1587, -1, 329, 1587, 2498, -1, + 329, 330, 1556, -1, 329, 2498, 330, -1, + 2121, 1558, 2123, -1, 2121, 2122, 1558, -1, + 918, 337, 331, -1, 918, 331, 332, -1, + 918, 916, 919, -1, 333, 332, 913, -1, + 333, 918, 332, -1, 333, 916, 918, -1, + 1586, 916, 333, -1, 1586, 333, 913, -1, + 1583, 919, 916, -1, 1515, 1516, 1583, -1, + 830, 336, 1509, -1, 830, 334, 336, -1, + 830, 335, 334, -1, 830, 1511, 2074, -1, + 830, 2074, 335, -1, 920, 336, 337, -1, + 920, 1509, 336, -1, 920, 337, 918, -1, + 2467, 919, 1583, -1, 2467, 1583, 1516, -1, + 338, 924, 339, -1, 338, 340, 924, -1, + 338, 339, 1469, -1, 338, 1469, 340, -1, + 922, 341, 923, -1, 922, 760, 341, -1, + 922, 926, 760, -1, 928, 973, 972, -1, + 928, 972, 971, -1, 928, 971, 748, -1, + 928, 748, 929, -1, 2130, 342, 975, -1, + 2130, 938, 342, -1, 2126, 2128, 931, -1, + 343, 750, 748, -1, 343, 748, 971, -1, + 343, 344, 750, -1, 343, 971, 344, -1, + 948, 345, 941, -1, 948, 949, 345, -1, + 948, 946, 951, -1, 950, 951, 346, -1, + 950, 347, 949, -1, 950, 348, 347, -1, + 950, 349, 348, -1, 950, 346, 349, -1, + 353, 974, 742, -1, 353, 742, 350, -1, + 353, 350, 354, -1, 954, 2550, 963, -1, + 1596, 2136, 962, -1, 1323, 1324, 2312, -1, + 1598, 2137, 2861, -1, 2815, 2816, 644, -1, + 2674, 1604, 2857, -1, 2142, 644, 2816, -1, + 2142, 2816, 1604, -1, 2142, 2141, 644, -1, + 2519, 2857, 1604, -1, 2519, 1604, 2816, -1, + 2338, 966, 964, -1, 968, 964, 966, -1, + 1734, 2149, 2147, -1, 1734, 967, 1279, -1, + 2154, 2149, 418, -1, 2524, 1611, 1321, -1, + 1622, 1623, 1615, -1, 1614, 1622, 1615, -1, + 1614, 2137, 1598, -1, 1618, 1352, 1603, -1, + 1867, 1321, 1611, -1, 1867, 1611, 351, -1, + 2159, 1870, 1322, -1, 2159, 1322, 1867, -1, + 2159, 1867, 351, -1, 2159, 351, 1619, -1, + 1631, 352, 931, -1, 1631, 931, 2128, -1, + 1631, 356, 352, -1, 1626, 974, 353, -1, + 1626, 353, 354, -1, 1626, 354, 355, -1, + 1626, 355, 978, -1, 977, 979, 356, -1, + 977, 356, 1631, -1, 977, 1631, 1630, -1, + 357, 358, 359, -1, 357, 360, 358, -1, + 357, 359, 361, -1, 357, 361, 362, -1, + 357, 362, 360, -1, 1641, 1637, 1642, -1, + 1641, 1635, 1637, -1, 989, 1648, 2168, -1, + 989, 990, 366, -1, 989, 366, 1648, -1, + 1651, 983, 1664, -1, 2173, 1643, 1347, -1, + 2173, 1347, 987, -1, 1654, 1655, 985, -1, + 1654, 985, 2179, -1, 1654, 2180, 1012, -1, + 1654, 2179, 2180, -1, 988, 363, 1657, -1, + 988, 1670, 1672, -1, 376, 375, 363, -1, + 376, 363, 988, -1, 376, 988, 1672, -1, + 1659, 364, 365, -1, 1659, 1660, 364, -1, + 1659, 365, 990, -1, 992, 997, 366, -1, + 992, 366, 990, -1, 992, 990, 367, -1, + 992, 367, 993, -1, 368, 1049, 1042, -1, + 368, 1042, 369, -1, 368, 384, 385, -1, + 368, 385, 1049, -1, 368, 383, 384, -1, + 368, 369, 383, -1, 1001, 999, 370, -1, + 1001, 371, 1004, -1, 1001, 942, 371, -1, + 1001, 943, 942, -1, 1001, 370, 943, -1, + 1034, 1035, 372, -1, 1034, 372, 1009, -1, + 1011, 1615, 373, -1, 2184, 2543, 1017, -1, + 2184, 1017, 645, -1, 2528, 373, 2872, -1, + 2528, 2527, 2184, -1, 2528, 2184, 374, -1, + 2528, 1011, 373, -1, 2528, 374, 1011, -1, + 1351, 2184, 645, -1, 1351, 374, 2184, -1, + 1351, 1011, 374, -1, 2544, 1014, 2545, -1, + 2549, 2550, 953, -1, 2549, 953, 955, -1, + 2549, 955, 1683, -1, 1020, 421, 2165, -1, + 1020, 1019, 421, -1, 1022, 392, 1680, -1, + 1022, 1680, 1679, -1, 1022, 1020, 392, -1, + 1022, 1025, 1020, -1, 1022, 1679, 1676, -1, + 2153, 2154, 418, -1, 1023, 1610, 1612, -1, + 1666, 1667, 1014, -1, 1674, 1027, 391, -1, + 1674, 391, 1032, -1, 1030, 378, 379, -1, + 1030, 1031, 378, -1, 1030, 379, 375, -1, + 1030, 376, 1672, -1, 1030, 375, 376, -1, + 377, 378, 382, -1, 377, 379, 378, -1, + 377, 380, 379, -1, 377, 382, 1039, -1, + 377, 1038, 380, -1, 377, 1039, 1038, -1, + 381, 1685, 1039, -1, 381, 1039, 382, -1, + 381, 384, 383, -1, 381, 383, 1685, -1, + 381, 385, 384, -1, 381, 382, 385, -1, + 1036, 1039, 1685, -1, 1048, 1046, 957, -1, + 944, 1044, 388, -1, 944, 943, 1044, -1, + 386, 946, 945, -1, 386, 387, 946, -1, + 386, 945, 944, -1, 386, 944, 388, -1, + 386, 962, 387, -1, 386, 960, 962, -1, + 386, 961, 960, -1, 386, 388, 961, -1, + 389, 391, 390, -1, 389, 390, 1046, -1, + 389, 1047, 391, -1, 389, 1046, 1047, -1, + 1634, 1681, 392, -1, 1634, 1020, 2165, -1, + 1634, 392, 1020, -1, 395, 1138, 456, -1, + 395, 457, 393, -1, 395, 456, 457, -1, + 395, 393, 396, -1, 1053, 394, 1054, -1, + 1053, 1138, 395, -1, 1053, 396, 394, -1, + 1053, 395, 396, -1, 1064, 1056, 397, -1, + 1064, 397, 1066, -1, 2186, 1694, 1072, -1, + 1074, 1078, 398, -1, 1074, 1082, 1078, -1, + 1074, 2199, 1082, -1, 1074, 1075, 2199, -1, + 1074, 398, 1076, -1, 399, 400, 587, -1, + 399, 1078, 400, -1, 399, 587, 1949, -1, + 399, 1949, 1078, -1, 1951, 653, 1078, -1, + 1958, 1692, 1956, -1, 407, 1377, 1956, -1, + 407, 1956, 1068, -1, 401, 405, 402, -1, + 401, 406, 405, -1, 401, 402, 403, -1, + 401, 407, 406, -1, 401, 1377, 407, -1, + 401, 403, 1378, -1, 401, 1378, 1377, -1, + 404, 1688, 448, -1, 404, 1068, 1688, -1, + 404, 448, 405, -1, 404, 405, 406, -1, + 404, 406, 407, -1, 404, 407, 1068, -1, + 2587, 2586, 2409, -1, 2587, 2409, 2588, -1, + 1088, 2192, 1087, -1, 1088, 2562, 2192, -1, + 1080, 583, 1081, -1, 1080, 408, 583, -1, + 1080, 1696, 408, -1, 2559, 2839, 408, -1, + 2559, 408, 1696, -1, 2584, 1702, 1086, -1, + 2584, 1086, 2218, -1, 1099, 409, 1094, -1, + 1099, 1100, 409, -1, 1099, 1097, 1721, -1, + 1715, 1099, 1094, -1, 1715, 1097, 1099, -1, + 1106, 1108, 410, -1, 1106, 410, 1729, -1, + 1106, 1729, 1104, -1, 1110, 411, 412, -1, + 1110, 412, 1109, -1, 1110, 413, 411, -1, + 1110, 1726, 413, -1, 1113, 414, 1112, -1, + 1113, 1849, 414, -1, 1113, 1281, 1849, -1, + 1114, 1113, 1118, -1, 1114, 1280, 1281, -1, + 1114, 1281, 1113, -1, 1117, 1098, 1121, -1, + 1117, 415, 1098, -1, 1117, 1112, 415, -1, + 416, 420, 1018, -1, 416, 417, 420, -1, + 416, 418, 417, -1, 416, 2153, 418, -1, + 416, 1018, 2153, -1, 426, 420, 425, -1, + 426, 427, 422, -1, 419, 1019, 1018, -1, + 419, 1018, 420, -1, 419, 421, 1019, -1, + 419, 422, 421, -1, 419, 426, 422, -1, + 419, 420, 426, -1, 1732, 423, 2149, -1, + 1732, 1115, 423, -1, 1130, 1133, 1092, -1, + 1130, 1092, 1131, -1, 428, 432, 1127, -1, + 428, 1131, 799, -1, 428, 799, 432, -1, + 1120, 424, 1115, -1, 1120, 1121, 424, -1, + 1126, 425, 1128, -1, 1126, 426, 425, -1, + 1126, 1123, 427, -1, 1126, 427, 426, -1, + 1132, 428, 1127, -1, 1132, 1128, 1133, -1, + 1132, 1131, 428, -1, 429, 431, 430, -1, + 429, 432, 431, -1, 429, 430, 433, -1, + 429, 433, 1124, -1, 429, 1127, 432, -1, + 429, 1124, 1127, -1, 442, 434, 441, -1, + 442, 435, 434, -1, 442, 436, 435, -1, + 442, 440, 436, -1, 437, 439, 438, -1, + 437, 438, 440, -1, 437, 458, 460, -1, + 437, 460, 439, -1, 437, 457, 458, -1, + 437, 441, 457, -1, 437, 442, 441, -1, + 437, 440, 442, -1, 443, 593, 444, -1, + 443, 445, 593, -1, 443, 446, 445, -1, + 443, 447, 446, -1, 443, 444, 447, -1, + 1135, 1136, 1134, -1, 1069, 451, 448, -1, + 1069, 448, 1688, -1, 449, 450, 451, -1, + 449, 451, 1069, -1, 449, 1069, 1070, -1, + 449, 452, 450, -1, 449, 1070, 452, -1, + 600, 453, 599, -1, 600, 606, 453, -1, + 600, 602, 606, -1, 1144, 1139, 1142, -1, + 1144, 1149, 1140, -1, 454, 456, 455, -1, + 454, 458, 457, -1, 454, 457, 456, -1, + 454, 455, 459, -1, 454, 460, 458, -1, + 454, 459, 460, -1, 461, 462, 1741, -1, + 461, 1741, 468, -1, 461, 468, 463, -1, + 461, 463, 464, -1, 461, 465, 462, -1, + 461, 466, 465, -1, 461, 467, 466, -1, + 461, 464, 467, -1, 1742, 1152, 468, -1, + 1742, 468, 1741, -1, 1153, 1763, 1152, -1, + 1153, 1154, 490, -1, 1153, 490, 1763, -1, + 1752, 1747, 1751, -1, 1752, 470, 1158, -1, + 812, 1164, 810, -1, 812, 1749, 1164, -1, + 812, 811, 469, -1, 812, 469, 470, -1, + 812, 470, 1752, -1, 812, 1752, 1749, -1, + 471, 473, 472, -1, 471, 1158, 473, -1, + 471, 472, 474, -1, 471, 1159, 1158, -1, + 471, 474, 1151, -1, 471, 1151, 1159, -1, + 524, 1220, 1213, -1, 524, 1745, 1220, -1, + 1167, 525, 1166, -1, 1167, 1745, 524, -1, + 1167, 524, 525, -1, 1758, 1164, 1749, -1, + 1755, 1800, 1799, -1, 2276, 1329, 1330, -1, + 1754, 1800, 1755, -1, 1754, 1166, 1197, -1, + 1793, 1341, 475, -1, 1793, 1791, 1341, -1, + 1793, 1161, 1755, -1, 1793, 1755, 1799, -1, + 1793, 1162, 1161, -1, 1793, 475, 1162, -1, + 476, 477, 814, -1, 476, 1162, 477, -1, + 476, 814, 817, -1, 476, 817, 1162, -1, + 478, 485, 1168, -1, 478, 1168, 479, -1, + 478, 1180, 485, -1, 478, 479, 1180, -1, + 1770, 1168, 485, -1, 1770, 485, 1769, -1, + 480, 481, 1168, -1, 480, 1168, 1764, -1, + 480, 1765, 481, -1, 480, 1764, 1765, -1, + 1169, 1170, 568, -1, 1169, 560, 1171, -1, + 1169, 568, 560, -1, 1173, 484, 482, -1, + 1173, 482, 1762, -1, 1767, 483, 1172, -1, + 1767, 1183, 483, -1, 1177, 484, 1173, -1, + 1177, 1171, 484, -1, 1177, 1176, 1171, -1, + 1782, 485, 1180, -1, 1782, 1769, 485, -1, + 861, 486, 862, -1, 861, 860, 486, -1, + 487, 489, 488, -1, 487, 488, 492, -1, + 487, 1154, 489, -1, 487, 490, 1154, -1, + 487, 1761, 490, -1, 487, 492, 1761, -1, + 1182, 491, 1183, -1, 1182, 492, 491, -1, + 1182, 1761, 492, -1, 1182, 1184, 1761, -1, + 1185, 1774, 1775, -1, 2274, 2289, 1229, -1, + 1785, 2274, 1229, -1, 1192, 493, 1195, -1, + 1192, 1193, 493, -1, 1230, 493, 1193, -1, + 1230, 1193, 1229, -1, 1230, 670, 493, -1, + 1230, 1832, 670, -1, 1705, 1908, 1909, -1, + 1705, 1909, 1329, -1, 1802, 2286, 2289, -1, + 1802, 1198, 2286, -1, 1802, 1803, 1198, -1, + 494, 496, 495, -1, 494, 497, 496, -1, + 494, 495, 499, -1, 494, 499, 497, -1, + 503, 1813, 576, -1, 503, 576, 498, -1, + 503, 499, 500, -1, 503, 498, 499, -1, + 503, 500, 501, -1, 503, 501, 1201, -1, + 1200, 1201, 502, -1, 1200, 502, 1206, -1, + 1202, 1811, 1813, -1, 1202, 1813, 503, -1, + 1202, 503, 1201, -1, 1815, 1812, 1203, -1, + 1815, 1203, 1814, -1, 1839, 1228, 549, -1, + 1839, 549, 548, -1, 1216, 1217, 504, -1, + 1216, 504, 2777, -1, 505, 506, 507, -1, + 505, 507, 563, -1, 505, 572, 508, -1, + 505, 508, 506, -1, 505, 575, 572, -1, + 505, 509, 575, -1, 505, 563, 510, -1, + 505, 510, 509, -1, 511, 1818, 1203, -1, + 511, 1203, 1817, -1, 511, 1817, 1818, -1, + 512, 513, 514, -1, 512, 514, 1207, -1, + 512, 1207, 513, -1, 1208, 1207, 1820, -1, + 515, 517, 516, -1, 515, 516, 518, -1, + 515, 520, 519, -1, 515, 519, 517, -1, + 515, 522, 521, -1, 515, 521, 520, -1, + 515, 523, 522, -1, 515, 518, 523, -1, + 526, 1213, 1215, -1, 526, 1824, 1160, -1, + 526, 524, 1213, -1, 526, 525, 524, -1, + 526, 1166, 525, -1, 526, 1160, 1166, -1, + 1821, 1215, 1209, -1, 1821, 1824, 526, -1, + 1821, 526, 1215, -1, 1211, 527, 528, -1, + 1211, 528, 529, -1, 1211, 534, 527, -1, + 1211, 1214, 534, -1, 1211, 529, 1212, -1, + 2279, 2280, 1209, -1, 2279, 1209, 530, -1, + 2279, 530, 1217, -1, 2285, 1198, 1196, -1, + 2285, 2286, 1198, -1, 2281, 2282, 1827, -1, + 531, 1747, 1159, -1, 531, 1159, 1151, -1, + 531, 1151, 1150, -1, 531, 532, 1746, -1, + 531, 1746, 1747, -1, 531, 1740, 532, -1, + 531, 1150, 1740, -1, 1219, 1746, 532, -1, + 1219, 532, 1740, -1, 1219, 1740, 533, -1, + 1219, 534, 1214, -1, 1219, 533, 534, -1, + 1219, 1214, 1220, -1, 2620, 1221, 536, -1, + 2620, 536, 2278, -1, 1838, 1836, 2621, -1, + 1838, 1839, 1225, -1, 535, 2278, 536, -1, + 535, 540, 2278, -1, 535, 536, 537, -1, + 535, 537, 675, -1, 535, 675, 676, -1, + 535, 677, 540, -1, 535, 676, 677, -1, + 541, 540, 677, -1, 541, 1830, 539, -1, + 541, 677, 671, -1, 538, 539, 2282, -1, + 538, 2282, 2283, -1, 538, 541, 539, -1, + 538, 540, 541, -1, 538, 2283, 2278, -1, + 538, 2278, 540, -1, 1829, 671, 1832, -1, + 1829, 541, 671, -1, 1829, 1830, 541, -1, + 542, 543, 545, -1, 542, 545, 544, -1, + 542, 544, 543, -1, 1222, 1223, 1844, -1, + 1222, 545, 1224, -1, 1222, 546, 545, -1, + 1222, 2406, 546, -1, 1222, 1844, 1205, -1, + 1222, 1205, 2406, -1, 1843, 1225, 1844, -1, + 547, 548, 549, -1, 547, 1205, 1225, -1, + 547, 549, 1205, -1, 547, 1225, 1839, -1, + 547, 1839, 548, -1, 550, 551, 1205, -1, + 550, 1205, 552, -1, 550, 553, 551, -1, + 550, 552, 554, -1, 550, 555, 553, -1, + 550, 554, 556, -1, 550, 556, 555, -1, + 557, 559, 558, -1, 557, 560, 567, -1, + 557, 558, 560, -1, 557, 561, 559, -1, + 557, 562, 561, -1, 557, 567, 566, -1, + 557, 566, 562, -1, 569, 563, 564, -1, + 569, 564, 566, -1, 569, 570, 563, -1, + 565, 566, 567, -1, 565, 567, 568, -1, + 565, 570, 569, -1, 565, 569, 566, -1, + 565, 802, 570, -1, 565, 1170, 802, -1, + 565, 568, 1170, -1, 571, 1813, 1814, -1, + 571, 576, 1813, -1, 571, 575, 576, -1, + 571, 1818, 572, -1, 571, 572, 575, -1, + 571, 1203, 1818, -1, 571, 1814, 1203, -1, + 573, 575, 574, -1, 573, 576, 575, -1, + 573, 577, 576, -1, 573, 578, 577, -1, + 573, 574, 578, -1, 586, 583, 2396, -1, + 586, 582, 583, -1, 585, 579, 584, -1, + 585, 580, 579, -1, 585, 587, 580, -1, + 581, 583, 582, -1, 581, 584, 583, -1, + 581, 585, 584, -1, 581, 586, 2396, -1, + 581, 582, 586, -1, 581, 2396, 587, -1, + 581, 587, 585, -1, 1233, 1232, 588, -1, + 1233, 588, 1234, -1, 589, 1236, 1056, -1, + 589, 1056, 591, -1, 589, 596, 1236, -1, + 589, 591, 596, -1, 590, 1056, 1057, -1, + 590, 591, 1056, -1, 590, 1057, 596, -1, + 590, 596, 591, -1, 1243, 1246, 1059, -1, + 1243, 1232, 1244, -1, 1243, 1059, 592, -1, + 1243, 592, 593, -1, 1243, 593, 1232, -1, + 594, 1245, 595, -1, 594, 1291, 596, -1, + 594, 595, 1291, -1, 594, 1246, 1245, -1, + 594, 597, 1246, -1, 594, 596, 1057, -1, + 594, 1057, 597, -1, 1251, 1252, 1102, -1, + 1251, 1102, 1722, -1, 1251, 1722, 1250, -1, + 1249, 1288, 1252, -1, 1254, 1108, 1256, -1, + 1254, 1255, 602, -1, 1254, 599, 598, -1, + 1254, 598, 1108, -1, 1254, 600, 599, -1, + 1254, 602, 600, -1, 614, 1255, 613, -1, + 614, 607, 601, -1, 614, 612, 607, -1, + 614, 601, 602, -1, 614, 602, 1255, -1, + 603, 1255, 1257, -1, 603, 613, 1255, -1, + 603, 1257, 604, -1, 603, 604, 613, -1, + 605, 606, 607, -1, 605, 607, 608, -1, + 605, 609, 606, -1, 605, 610, 609, -1, + 605, 608, 610, -1, 1264, 616, 1263, -1, + 1264, 631, 616, -1, 1259, 1262, 611, -1, + 1259, 611, 612, -1, 1259, 613, 1260, -1, + 1259, 612, 614, -1, 1259, 614, 613, -1, + 1267, 1268, 1272, -1, 1847, 1274, 1277, -1, + 1847, 1277, 1267, -1, 1847, 1267, 1272, -1, + 619, 1304, 1305, -1, 619, 1305, 625, -1, + 619, 615, 1304, -1, 619, 618, 615, -1, + 619, 625, 624, -1, 620, 616, 617, -1, + 620, 617, 618, -1, 620, 618, 619, -1, + 620, 619, 624, -1, 620, 621, 1263, -1, + 620, 1263, 616, -1, 1307, 1316, 1315, -1, + 628, 627, 1234, -1, 628, 621, 620, -1, + 628, 620, 624, -1, 628, 622, 621, -1, + 628, 1234, 622, -1, 623, 624, 625, -1, + 623, 625, 637, -1, 623, 637, 626, -1, + 623, 626, 627, -1, 623, 627, 628, -1, + 623, 628, 624, -1, 1287, 1248, 1275, -1, + 1287, 1275, 1285, -1, 1287, 1288, 1249, -1, + 629, 1288, 1286, -1, 629, 1265, 1288, -1, + 629, 1286, 630, -1, 629, 630, 631, -1, + 629, 1264, 1265, -1, 629, 631, 1264, -1, + 1974, 1975, 1295, -1, 1293, 635, 632, -1, + 1293, 632, 633, -1, 1293, 633, 1291, -1, + 634, 659, 635, -1, 634, 636, 659, -1, + 634, 635, 1293, -1, 634, 1293, 1295, -1, + 634, 656, 636, -1, 634, 655, 656, -1, + 634, 1295, 1975, -1, 634, 1975, 655, -1, + 1289, 1292, 637, -1, 1289, 637, 1973, -1, + 1303, 1889, 1890, -1, 1303, 1890, 1392, -1, + 1385, 1386, 1302, -1, 1310, 1313, 1314, -1, + 1310, 1314, 1316, -1, 638, 1285, 1858, -1, + 638, 1858, 639, -1, 638, 1286, 1285, -1, + 638, 639, 1286, -1, 2626, 2296, 1606, -1, + 1312, 1862, 640, -1, 1312, 1971, 1315, -1, + 1312, 1968, 1971, -1, 1312, 640, 1968, -1, + 2302, 2303, 1313, -1, 2302, 1326, 2306, -1, + 2311, 1324, 1880, -1, 2311, 1880, 1871, -1, + 2311, 2312, 1324, -1, 2330, 1319, 1876, -1, + 2330, 2331, 1896, -1, 2330, 1896, 1319, -1, + 1872, 1877, 1876, -1, 1872, 1871, 1880, -1, + 1872, 1880, 1877, -1, 1866, 1321, 1867, -1, + 1879, 1880, 1324, -1, 1864, 1889, 1863, -1, + 1325, 2306, 1326, -1, 1325, 1326, 2315, -1, + 2327, 1899, 1309, -1, 1369, 1371, 641, -1, + 1900, 641, 2354, -1, 1900, 1369, 641, -1, + 2669, 2668, 1916, -1, 2669, 1914, 2361, -1, + 2919, 2920, 2363, -1, 1903, 2353, 642, -1, + 1903, 642, 643, -1, 1903, 643, 1333, -1, + 1920, 2349, 1903, -1, 1337, 1334, 1340, -1, + 1337, 1338, 1334, -1, 1924, 644, 2141, -1, + 1924, 1343, 2664, -1, 1924, 2815, 644, -1, + 646, 1643, 1642, -1, 1938, 1353, 987, -1, + 1938, 987, 1347, -1, 1938, 2140, 1353, -1, + 1365, 1643, 646, -1, 1365, 1346, 1929, -1, + 1365, 646, 1346, -1, 1356, 1017, 1348, -1, + 1356, 645, 1017, -1, 1356, 1351, 645, -1, + 1360, 1637, 2171, -1, 1360, 1935, 1637, -1, + 1345, 1346, 646, -1, 1345, 646, 1642, -1, + 1345, 1642, 1637, -1, 1345, 1637, 1935, -1, + 1344, 2920, 2371, -1, 1344, 2363, 2920, -1, + 1368, 1905, 1361, -1, 1368, 1361, 1927, -1, + 649, 1342, 651, -1, 649, 647, 1342, -1, + 649, 648, 647, -1, 649, 650, 648, -1, + 981, 649, 651, -1, 981, 650, 649, -1, + 981, 1645, 650, -1, 1902, 1340, 1370, -1, + 1902, 981, 651, -1, 1902, 651, 1340, -1, + 1376, 1378, 652, -1, 1376, 652, 1375, -1, + 1953, 1954, 653, -1, 1953, 653, 1951, -1, + 1953, 1951, 1950, -1, 1960, 1380, 657, -1, + 1960, 657, 1961, -1, 1083, 2748, 1961, -1, + 1083, 1961, 657, -1, 1083, 657, 1389, -1, + 2204, 1701, 654, -1, 2204, 654, 663, -1, + 2204, 663, 1964, -1, 1384, 656, 655, -1, + 1384, 658, 656, -1, 1384, 655, 1975, -1, + 1388, 1380, 656, -1, 1388, 656, 658, -1, + 1388, 657, 1380, -1, 1388, 1389, 657, -1, + 1390, 658, 1384, -1, 1390, 1388, 658, -1, + 1390, 1385, 1300, -1, 1390, 1300, 1391, -1, + 1382, 659, 1379, -1, 1382, 660, 659, -1, + 1382, 1381, 661, -1, 1382, 661, 660, -1, + 662, 663, 664, -1, 662, 1966, 663, -1, + 662, 2193, 1966, -1, 662, 2192, 2193, -1, + 662, 664, 2192, -1, 1907, 2361, 1914, -1, + 1976, 1704, 2595, -1, 1976, 1907, 1704, -1, + 1985, 2390, 2579, -1, 1985, 2579, 2387, -1, + 1994, 1988, 1990, -1, 1994, 1990, 1993, -1, + 1994, 666, 1989, -1, 1994, 1989, 1988, -1, + 1393, 2387, 2579, -1, 1393, 1993, 2387, -1, + 1373, 2577, 2390, -1, 1373, 2390, 2389, -1, + 2576, 2579, 2390, -1, 2576, 2390, 2577, -1, + 2757, 1372, 1945, -1, 2757, 1373, 1372, -1, + 2757, 2577, 1373, -1, 665, 1296, 666, -1, + 665, 667, 1296, -1, 665, 1994, 1995, -1, + 665, 666, 1994, -1, 665, 1995, 668, -1, + 665, 668, 1391, -1, 665, 1391, 667, -1, + 2408, 669, 1996, -1, 2408, 2409, 669, -1, + 681, 682, 670, -1, 681, 670, 671, -1, + 681, 671, 674, -1, 672, 673, 680, -1, + 672, 680, 681, -1, 672, 681, 674, -1, + 672, 675, 673, -1, 672, 676, 675, -1, + 672, 674, 677, -1, 672, 677, 676, -1, + 1190, 678, 679, -1, 1190, 680, 678, -1, + 1190, 679, 2211, -1, 1190, 681, 680, -1, + 1190, 682, 681, -1, 1190, 1195, 682, -1, + 683, 2397, 2396, -1, 683, 684, 2397, -1, + 683, 2396, 685, -1, 683, 685, 684, -1, + 712, 686, 687, -1, 712, 2034, 686, -1, + 712, 699, 711, -1, 712, 687, 701, -1, + 1395, 688, 1396, -1, 1395, 1398, 689, -1, + 1395, 690, 688, -1, 1395, 689, 690, -1, + 1397, 2418, 2000, -1, 1397, 2417, 2418, -1, + 1397, 696, 2417, -1, 697, 1399, 1403, -1, + 697, 1397, 1399, -1, 697, 696, 1397, -1, + 697, 1403, 2240, -1, 1402, 1403, 691, -1, + 1402, 692, 1405, -1, 1402, 691, 692, -1, + 1404, 2768, 2240, -1, 1404, 2240, 1403, -1, + 2245, 693, 2243, -1, 2245, 2003, 694, -1, + 2245, 694, 695, -1, 2245, 695, 693, -1, + 2005, 1412, 2018, -1, 2024, 2417, 696, -1, + 2024, 2240, 2770, -1, 2024, 697, 2240, -1, + 2024, 696, 697, -1, 698, 700, 699, -1, + 698, 701, 700, -1, 698, 699, 712, -1, + 698, 712, 701, -1, 2435, 2025, 709, -1, + 2435, 709, 708, -1, 2435, 708, 1414, -1, + 2027, 1414, 702, -1, 2027, 1400, 2699, -1, + 2027, 702, 1400, -1, 703, 1423, 704, -1, + 703, 1443, 1423, -1, 703, 704, 767, -1, + 703, 768, 1443, -1, 703, 767, 768, -1, + 1429, 1428, 1417, -1, 1429, 1419, 1430, -1, + 705, 1418, 1415, -1, 705, 1415, 714, -1, + 705, 706, 1418, -1, 705, 714, 706, -1, + 2030, 1432, 723, -1, 2030, 723, 1433, -1, + 707, 1431, 708, -1, 707, 725, 1431, -1, + 707, 708, 709, -1, 707, 710, 725, -1, + 707, 709, 710, -1, 2035, 711, 2036, -1, + 2035, 2034, 712, -1, 2035, 712, 711, -1, + 713, 1415, 718, -1, 713, 718, 716, -1, + 713, 716, 717, -1, 713, 714, 1415, -1, + 713, 1438, 714, -1, 713, 717, 1438, -1, + 2026, 715, 2431, -1, 2026, 1437, 715, -1, + 2426, 716, 2025, -1, 2426, 717, 716, -1, + 2426, 1438, 717, -1, 721, 719, 718, -1, + 721, 720, 719, -1, 721, 1415, 1426, -1, + 721, 718, 1415, -1, 1445, 1446, 720, -1, + 1445, 721, 1426, -1, 1445, 720, 721, -1, + 728, 1441, 2043, -1, 728, 727, 1441, -1, + 728, 2042, 722, -1, 728, 2043, 2042, -1, + 728, 723, 1432, -1, 728, 722, 723, -1, + 724, 1431, 725, -1, 724, 725, 726, -1, + 724, 726, 727, -1, 724, 1432, 1431, -1, + 724, 728, 1432, -1, 724, 727, 728, -1, + 1440, 1441, 1446, -1, 1440, 1446, 1475, -1, + 1474, 1443, 768, -1, 1474, 768, 1473, -1, + 729, 730, 731, -1, 729, 732, 730, -1, + 729, 925, 732, -1, 729, 926, 925, -1, + 729, 731, 926, -1, 733, 2132, 1588, -1, + 733, 737, 2132, -1, 733, 1588, 734, -1, + 733, 734, 737, -1, 939, 737, 738, -1, + 939, 2132, 737, -1, 939, 738, 735, -1, + 939, 735, 938, -1, 736, 738, 737, -1, + 736, 739, 738, -1, 736, 740, 739, -1, + 736, 741, 740, -1, 736, 737, 741, -1, + 930, 742, 973, -1, 930, 929, 743, -1, + 930, 744, 742, -1, 930, 743, 745, -1, + 930, 745, 744, -1, 746, 747, 748, -1, + 746, 749, 747, -1, 746, 748, 750, -1, + 746, 750, 749, -1, 2457, 2458, 2453, -1, + 1452, 751, 752, -1, 1452, 752, 757, -1, + 1452, 1453, 1463, -1, 1452, 1463, 910, -1, + 1452, 910, 751, -1, 1455, 753, 759, -1, + 1455, 754, 753, -1, 1455, 759, 1456, -1, + 1455, 1459, 754, -1, 755, 1428, 1462, -1, + 755, 1462, 758, -1, 755, 756, 1428, -1, + 755, 758, 756, -1, 1457, 1452, 757, -1, + 1457, 757, 1458, -1, 1464, 1463, 1453, -1, + 1464, 1453, 1456, -1, 1464, 758, 1462, -1, + 1464, 759, 758, -1, 1464, 1456, 759, -1, + 1448, 2453, 2458, -1, 1448, 763, 2453, -1, + 765, 926, 762, -1, 765, 764, 760, -1, + 765, 760, 926, -1, 761, 762, 763, -1, + 761, 1448, 1447, -1, 761, 763, 1448, -1, + 761, 1447, 2443, -1, 761, 2443, 764, -1, + 761, 764, 765, -1, 761, 765, 762, -1, + 766, 768, 767, -1, 766, 1468, 768, -1, + 766, 769, 1468, -1, 766, 767, 770, -1, + 766, 770, 769, -1, 1466, 774, 1467, -1, + 1466, 1470, 771, -1, 1466, 771, 772, -1, + 1466, 772, 774, -1, 1472, 773, 2039, -1, + 1472, 774, 773, -1, 1472, 1467, 774, -1, + 1472, 1473, 1467, -1, 775, 776, 777, -1, + 775, 777, 778, -1, 775, 778, 779, -1, + 775, 779, 780, -1, 775, 780, 781, -1, + 775, 782, 776, -1, 775, 781, 782, -1, + 1481, 783, 784, -1, 1481, 1482, 783, -1, + 1481, 784, 1479, -1, 785, 786, 1482, -1, + 785, 787, 786, -1, 785, 788, 787, -1, + 785, 1482, 790, -1, 785, 789, 788, -1, + 785, 790, 789, -1, 1480, 790, 1482, -1, + 1480, 791, 790, -1, 1480, 1478, 791, -1, + 792, 794, 793, -1, 792, 795, 796, -1, + 792, 796, 794, -1, 792, 797, 795, -1, + 792, 793, 797, -1, 798, 800, 799, -1, + 798, 801, 800, -1, 798, 1095, 801, -1, + 798, 799, 1716, -1, 798, 1716, 1095, -1, + 805, 804, 808, -1, 1779, 807, 802, -1, + 1779, 802, 1170, -1, 803, 1179, 804, -1, + 803, 804, 805, -1, 803, 806, 807, -1, + 803, 808, 806, -1, 803, 805, 808, -1, + 803, 807, 1779, -1, 803, 1779, 1179, -1, + 816, 815, 809, -1, 816, 810, 817, -1, + 816, 809, 811, -1, 816, 811, 812, -1, + 816, 812, 810, -1, 813, 814, 815, -1, + 813, 817, 814, -1, 813, 815, 816, -1, + 813, 816, 817, -1, 1163, 817, 1164, -1, + 1163, 1162, 817, -1, 819, 2064, 2063, -1, + 819, 2063, 900, -1, 819, 835, 2064, -1, + 819, 818, 835, -1, 1553, 2477, 818, -1, + 1553, 818, 819, -1, 1553, 819, 900, -1, + 1553, 2711, 2477, -1, 820, 821, 2051, -1, + 820, 822, 821, -1, 820, 2053, 823, -1, + 820, 2051, 2053, -1, 820, 905, 822, -1, + 820, 823, 905, -1, 2050, 2051, 1485, -1, + 1488, 857, 1487, -1, 1490, 1540, 2105, -1, + 1490, 2105, 1522, -1, 1490, 1522, 2056, -1, + 2055, 2488, 1492, -1, 2484, 825, 2095, -1, + 2484, 2486, 825, -1, 2059, 2061, 824, -1, + 2059, 824, 825, -1, 2059, 825, 2486, -1, + 1495, 1497, 826, -1, 1495, 827, 1496, -1, + 1495, 828, 829, -1, 1495, 826, 828, -1, + 1495, 829, 836, -1, 1495, 836, 827, -1, + 1523, 2105, 1497, -1, 1523, 1497, 1524, -1, + 1523, 1522, 2105, -1, 1503, 828, 1544, -1, + 1503, 1504, 829, -1, 1503, 829, 828, -1, + 1502, 2064, 1505, -1, 2070, 832, 2069, -1, + 2070, 1508, 1499, -1, 2459, 1511, 830, -1, + 2459, 830, 1509, -1, 2077, 2069, 2076, -1, + 831, 1499, 1500, -1, 831, 1009, 832, -1, + 831, 1500, 1009, -1, 831, 832, 2070, -1, + 831, 2070, 1499, -1, 2476, 1512, 837, -1, + 2476, 837, 834, -1, 2476, 834, 2477, -1, + 833, 835, 834, -1, 833, 836, 835, -1, + 833, 834, 837, -1, 833, 837, 836, -1, + 2464, 2122, 2462, -1, 2464, 2467, 1516, -1, + 2502, 2503, 838, -1, 2502, 838, 2063, -1, + 842, 1518, 857, -1, 842, 857, 856, -1, + 842, 856, 839, -1, 842, 840, 841, -1, + 842, 839, 840, -1, 1519, 841, 1520, -1, + 1519, 842, 841, -1, 1519, 1518, 842, -1, + 858, 843, 1528, -1, 858, 844, 843, -1, + 858, 845, 844, -1, 858, 846, 845, -1, + 858, 859, 846, -1, 847, 2061, 2062, -1, + 847, 849, 848, -1, 847, 848, 2061, -1, + 847, 2062, 850, -1, 847, 1520, 849, -1, + 847, 850, 1520, -1, 1521, 1525, 850, -1, + 1521, 850, 2062, -1, 851, 853, 852, -1, + 851, 852, 854, -1, 851, 1486, 853, -1, + 851, 1488, 1486, -1, 851, 855, 856, -1, + 851, 854, 855, -1, 851, 856, 857, -1, + 851, 857, 1488, -1, 1526, 858, 1528, -1, + 1526, 859, 858, -1, 1526, 862, 859, -1, + 1526, 2083, 862, -1, 866, 2083, 2082, -1, + 866, 865, 860, -1, 866, 860, 861, -1, + 866, 862, 2083, -1, 866, 861, 862, -1, + 863, 864, 1183, -1, 863, 2082, 864, -1, + 863, 1183, 865, -1, 863, 865, 866, -1, + 863, 866, 2082, -1, 2085, 2086, 1530, -1, + 2085, 1531, 867, -1, 2085, 867, 2082, -1, + 2481, 1534, 868, -1, 2481, 868, 869, -1, + 2481, 869, 2479, -1, 874, 2087, 870, -1, + 874, 1534, 2087, -1, 874, 870, 872, -1, + 871, 872, 1493, -1, 871, 2098, 873, -1, + 871, 1493, 2098, -1, 871, 874, 872, -1, + 871, 873, 1534, -1, 871, 1534, 874, -1, + 875, 2094, 876, -1, 875, 878, 2094, -1, + 875, 876, 877, -1, 875, 877, 878, -1, + 1539, 878, 1538, -1, 1539, 2094, 878, -1, + 879, 882, 880, -1, 879, 2101, 882, -1, + 879, 884, 2101, -1, 879, 881, 884, -1, + 879, 880, 881, -1, 2102, 883, 882, -1, + 2102, 882, 2101, -1, 2102, 1540, 883, -1, + 1543, 2101, 884, -1, 1543, 884, 885, -1, + 1543, 885, 1541, -1, 2045, 886, 2044, -1, + 2045, 913, 886, -1, 887, 1548, 888, -1, + 887, 888, 1449, -1, 887, 889, 1548, -1, + 887, 1449, 889, -1, 1552, 892, 896, -1, + 1552, 890, 892, -1, 1552, 896, 1551, -1, + 1549, 1548, 889, -1, 1549, 889, 890, -1, + 1549, 890, 1552, -1, 891, 896, 892, -1, + 891, 895, 896, -1, 891, 892, 893, -1, + 891, 893, 895, -1, 894, 896, 895, -1, + 894, 895, 897, -1, 894, 1551, 896, -1, + 894, 898, 1551, -1, 894, 897, 899, -1, + 894, 899, 898, -1, 2110, 900, 2503, -1, + 2110, 1553, 900, -1, 2110, 2503, 2506, -1, + 1554, 1566, 2107, -1, 1554, 1578, 1566, -1, + 1569, 1559, 2493, -1, 1569, 1571, 1580, -1, + 1569, 2493, 2495, -1, 1579, 2123, 1559, -1, + 1579, 1559, 1569, -1, 1579, 1569, 1580, -1, + 2491, 2493, 1559, -1, 2113, 901, 902, -1, + 2113, 2111, 901, -1, 2113, 902, 903, -1, + 2113, 903, 1562, -1, 1565, 904, 1566, -1, + 1565, 905, 904, -1, 1565, 908, 905, -1, + 1567, 1580, 906, -1, 1567, 1571, 907, -1, + 1567, 906, 1571, -1, 1567, 907, 908, -1, + 1567, 908, 1565, -1, 1570, 909, 1571, -1, + 1570, 2495, 909, -1, 2048, 1575, 1450, -1, + 2048, 910, 1574, -1, 2048, 2450, 910, -1, + 2114, 1573, 911, -1, 2114, 1576, 1573, -1, + 2114, 911, 2115, -1, 2499, 2500, 2844, -1, + 2505, 1578, 2506, -1, 912, 1586, 913, -1, + 912, 915, 1586, -1, 912, 913, 2045, -1, + 912, 2046, 915, -1, 912, 2045, 2046, -1, + 1585, 914, 1587, -1, 1585, 1586, 915, -1, + 1585, 2500, 914, -1, 1585, 915, 2500, -1, + 1582, 916, 1586, -1, 1582, 1583, 916, -1, + 1584, 1515, 1583, -1, 1584, 1587, 917, -1, + 1584, 917, 1561, -1, 1584, 1561, 1515, -1, + 1510, 918, 919, -1, 1510, 920, 918, -1, + 1510, 919, 2467, -1, 1510, 1509, 920, -1, + 921, 922, 923, -1, 921, 924, 925, -1, + 921, 923, 924, -1, 921, 925, 926, -1, + 921, 926, 922, -1, 927, 973, 928, -1, + 927, 928, 929, -1, 927, 930, 973, -1, + 927, 929, 930, -1, 937, 2126, 931, -1, + 937, 931, 932, -1, 937, 932, 933, -1, + 937, 933, 936, -1, 2125, 934, 935, -1, + 2125, 936, 934, -1, 2125, 935, 1588, -1, + 2125, 937, 936, -1, 2125, 2126, 937, -1, + 2131, 938, 2130, -1, 2131, 2132, 939, -1, + 2131, 939, 938, -1, 940, 948, 941, -1, + 940, 942, 943, -1, 940, 941, 942, -1, + 940, 943, 944, -1, 940, 944, 945, -1, + 940, 945, 946, -1, 940, 946, 948, -1, + 947, 949, 948, -1, 947, 950, 949, -1, + 947, 948, 951, -1, 947, 951, 950, -1, + 2551, 963, 2550, -1, 958, 963, 959, -1, + 958, 954, 963, -1, 958, 1048, 957, -1, + 958, 1040, 1048, -1, 958, 961, 1040, -1, + 958, 959, 961, -1, 952, 953, 2550, -1, + 952, 2550, 954, -1, 952, 955, 953, -1, + 952, 956, 955, -1, 952, 957, 1046, -1, + 952, 1046, 956, -1, 952, 958, 957, -1, + 952, 954, 958, -1, 1590, 1681, 1634, -1, + 1590, 1634, 1633, -1, 1590, 1632, 1595, -1, + 1590, 1633, 1632, -1, 1590, 1595, 1594, -1, + 2743, 1594, 2552, -1, 2743, 2552, 2742, -1, + 1592, 959, 963, -1, 1592, 960, 961, -1, + 1592, 961, 959, -1, 1592, 962, 960, -1, + 1592, 1596, 962, -1, 1593, 1592, 963, -1, + 1593, 963, 2551, -1, 1593, 2551, 2552, -1, + 1873, 1323, 2312, -1, 1600, 2137, 1617, -1, + 1601, 1600, 1617, -1, 1601, 2856, 1600, -1, + 1601, 1618, 1603, -1, 1601, 1617, 1618, -1, + 1602, 2674, 2857, -1, 2672, 2674, 1602, -1, + 2672, 1603, 1352, -1, 2672, 1602, 1603, -1, + 2646, 964, 1895, -1, 2646, 2338, 964, -1, + 2646, 1895, 2645, -1, 2337, 965, 966, -1, + 2337, 966, 2338, -1, 2337, 1309, 1606, -1, + 2337, 1606, 965, -1, 2337, 2327, 1309, -1, + 2337, 2335, 2327, -1, 2143, 2144, 964, -1, + 2143, 964, 968, -1, 1607, 966, 965, -1, + 1607, 968, 966, -1, 1607, 965, 1606, -1, + 1607, 1608, 967, -1, 2146, 1607, 967, -1, + 2146, 968, 1607, -1, 2146, 2148, 2143, -1, + 2146, 2143, 968, -1, 2146, 967, 1734, -1, + 2146, 1734, 2147, -1, 2145, 1612, 1610, -1, + 969, 2160, 1619, -1, 969, 1619, 1610, -1, + 969, 1676, 2160, -1, 969, 1610, 1676, -1, + 1620, 2308, 2309, -1, 1620, 1622, 2308, -1, + 1599, 2312, 2308, -1, 1599, 2308, 1622, -1, + 1599, 1622, 1614, -1, 1616, 1615, 1011, -1, + 1616, 1011, 1618, -1, 1621, 2309, 1870, -1, + 970, 971, 972, -1, 970, 972, 976, -1, + 970, 975, 971, -1, 970, 976, 975, -1, + 1625, 976, 972, -1, 1625, 972, 973, -1, + 1625, 973, 974, -1, 1625, 974, 1626, -1, + 1625, 1630, 976, -1, 1629, 2130, 975, -1, + 1629, 975, 976, -1, 1629, 976, 1630, -1, + 1627, 977, 1630, -1, 1627, 1626, 978, -1, + 1627, 979, 977, -1, 1627, 978, 980, -1, + 1627, 980, 979, -1, 2166, 1662, 2169, -1, + 1638, 1637, 1635, -1, 1640, 1635, 1641, -1, + 1640, 2166, 1635, -1, 1644, 1664, 1663, -1, + 1644, 1662, 1641, -1, 1644, 1663, 1662, -1, + 2177, 1645, 981, -1, 2177, 981, 1902, -1, + 1649, 2724, 2529, -1, 1649, 2088, 2724, -1, + 1649, 982, 2088, -1, 1649, 1650, 982, -1, + 1649, 2529, 2168, -1, 1652, 983, 1651, -1, + 1652, 984, 983, -1, 1652, 985, 984, -1, + 1652, 2179, 985, -1, 2182, 1349, 2180, -1, + 2182, 1358, 1349, -1, 2182, 1354, 1358, -1, + 2182, 2183, 1354, -1, 986, 2173, 987, -1, + 986, 987, 1354, -1, 986, 1354, 2183, -1, + 986, 2174, 2173, -1, 986, 2183, 2174, -1, + 1656, 1012, 1013, -1, 1656, 1654, 1012, -1, + 1656, 988, 1657, -1, 1656, 1013, 1670, -1, + 1656, 1670, 988, -1, 1661, 990, 989, -1, + 1661, 1659, 990, -1, 1661, 2168, 2167, -1, + 1661, 989, 2168, -1, 991, 992, 993, -1, + 991, 993, 994, -1, 991, 994, 995, -1, + 991, 995, 996, -1, 991, 996, 997, -1, + 991, 997, 992, -1, 998, 1000, 999, -1, + 998, 999, 1001, -1, 998, 1002, 1003, -1, + 998, 1003, 1000, -1, 998, 1004, 1002, -1, + 998, 1001, 1004, -1, 1037, 1034, 1008, -1, + 1037, 1005, 1038, -1, 1037, 1008, 1005, -1, + 1006, 1007, 1008, -1, 1006, 1008, 1034, -1, + 1006, 1009, 1007, -1, 1006, 1034, 1009, -1, + 1010, 1351, 1352, -1, 1010, 1011, 1351, -1, + 1010, 1352, 1618, -1, 1010, 1618, 1011, -1, + 1669, 1012, 1667, -1, 1669, 1013, 1012, -1, + 1669, 1670, 1013, -1, 2717, 2718, 2160, -1, + 1678, 1676, 1679, -1, 1682, 1014, 2544, -1, + 1682, 1683, 1015, -1, 1682, 2544, 2546, -1, + 1682, 1015, 1029, -1, 1682, 1666, 1014, -1, + 1682, 1029, 1666, -1, 2542, 2545, 1016, -1, + 2542, 1017, 2543, -1, 2542, 1016, 1017, -1, + 1024, 2153, 1018, -1, 1024, 1018, 1019, -1, + 1024, 1019, 1020, -1, 1024, 1020, 1025, -1, + 1021, 1676, 1610, -1, 1021, 1610, 1023, -1, + 1021, 1022, 1676, -1, 1021, 1025, 1022, -1, + 1021, 1023, 1025, -1, 2156, 1023, 1612, -1, + 2156, 2153, 1024, -1, 2156, 1025, 1023, -1, + 2156, 1024, 1025, -1, 1026, 1671, 1666, -1, + 1026, 1028, 1027, -1, 1026, 1666, 1029, -1, + 1026, 1027, 1674, -1, 1026, 1674, 1671, -1, + 1026, 1683, 1028, -1, 1026, 1029, 1683, -1, + 1673, 1030, 1672, -1, 1673, 1031, 1030, -1, + 1673, 1032, 1031, -1, 1673, 1674, 1032, -1, + 1687, 2076, 2069, -1, 1687, 2069, 1035, -1, + 1687, 1036, 1685, -1, 1033, 1035, 1034, -1, + 1033, 1687, 1035, -1, 1033, 1036, 1687, -1, + 1033, 1037, 1038, -1, 1033, 1034, 1037, -1, + 1033, 1038, 1039, -1, 1033, 1039, 1036, -1, + 1051, 1040, 1041, -1, 1051, 1048, 1040, -1, + 1051, 1042, 1050, -1, 1051, 1043, 1042, -1, + 1051, 1041, 1044, -1, 1051, 1044, 1043, -1, + 1045, 1047, 1046, -1, 1045, 1046, 1048, -1, + 1045, 1050, 1049, -1, 1045, 1049, 1047, -1, + 1045, 1051, 1050, -1, 1045, 1048, 1051, -1, + 1052, 1139, 1138, -1, 1052, 1138, 1053, -1, + 1052, 1053, 1054, -1, 1052, 1054, 1055, -1, + 1052, 1055, 1139, -1, 1062, 1056, 1064, -1, + 1062, 1060, 1057, -1, 1062, 1057, 1056, -1, + 1058, 1059, 1060, -1, 1058, 1061, 1059, -1, + 1058, 1060, 1062, -1, 1058, 1062, 1064, -1, + 1058, 1065, 1061, -1, 1058, 1064, 1065, -1, + 1063, 1065, 1064, -1, 1063, 1064, 1066, -1, + 1063, 1067, 1065, -1, 1063, 1066, 1067, -1, + 2269, 1688, 1068, -1, 2269, 1068, 2267, -1, + 1737, 1688, 2617, -1, 1737, 1069, 1688, -1, + 1737, 1070, 1069, -1, 1737, 1735, 1070, -1, + 2615, 1737, 2617, -1, 1071, 2186, 1072, -1, + 1071, 1136, 2186, -1, 1071, 1072, 1134, -1, + 1071, 1134, 1136, -1, 1073, 1075, 1074, -1, + 1073, 1074, 1076, -1, 1073, 1077, 1075, -1, + 1073, 1076, 1077, -1, 1690, 1078, 1949, -1, + 1690, 1951, 1078, -1, 1693, 2266, 1692, -1, + 1693, 1958, 2266, -1, 2190, 2189, 1695, -1, + 1079, 1696, 2562, -1, 1079, 2562, 2561, -1, + 1079, 2559, 1696, -1, 1079, 2561, 2559, -1, + 2198, 1082, 2199, -1, 2198, 2197, 1082, -1, + 2196, 1696, 1080, -1, 2196, 1080, 1081, -1, + 2196, 1081, 1082, -1, 2196, 1082, 2197, -1, + 1090, 2225, 1086, -1, 1090, 1086, 1702, -1, + 1090, 1702, 2558, -1, 2554, 2558, 1702, -1, + 2554, 1702, 2588, -1, 2560, 1088, 1089, -1, + 2560, 2562, 1088, -1, 2560, 1089, 1090, -1, + 2560, 1090, 2558, -1, 2557, 2554, 2400, -1, + 2202, 1699, 1707, -1, 2202, 2220, 2221, -1, + 1698, 2384, 1978, -1, 1698, 1700, 2384, -1, + 1698, 1978, 1981, -1, 2569, 2384, 1700, -1, + 2570, 1700, 1699, -1, 2570, 2569, 1700, -1, + 1085, 1389, 1084, -1, 1085, 2748, 1083, -1, + 1085, 1083, 1389, -1, 2750, 1084, 1995, -1, + 2750, 1085, 1084, -1, 2563, 2229, 2203, -1, + 2563, 2228, 2229, -1, 2747, 2748, 1085, -1, + 2747, 1085, 2750, -1, 1703, 2218, 1086, -1, + 1703, 1086, 2225, -1, 2226, 1087, 1091, -1, + 2226, 1089, 1088, -1, 2226, 1088, 1087, -1, + 2226, 1090, 1089, -1, 2226, 2225, 1090, -1, + 2227, 2226, 1091, -1, 2227, 1091, 2203, -1, + 2227, 2203, 2229, -1, 2591, 1787, 2214, -1, + 2591, 1788, 1787, -1, 2606, 2607, 2237, -1, + 2249, 2250, 2234, -1, 1717, 1716, 1092, -1, + 1717, 1092, 1718, -1, 1093, 1716, 1715, -1, + 1093, 1715, 1094, -1, 1093, 1095, 1716, -1, + 1093, 1094, 1095, -1, 1096, 1097, 1715, -1, + 1096, 1715, 1718, -1, 1096, 1098, 1097, -1, + 1096, 1718, 1098, -1, 1101, 1100, 1099, -1, + 1101, 1099, 1721, -1, 1720, 1105, 1100, -1, + 1720, 1100, 1101, -1, 1720, 1101, 1721, -1, + 1107, 1105, 1720, -1, 1107, 1257, 1256, -1, + 1107, 1720, 1722, -1, 1107, 1102, 1257, -1, + 1107, 1722, 1102, -1, 1103, 1104, 1105, -1, + 1103, 1106, 1104, -1, 1103, 1105, 1107, -1, + 1103, 1107, 1256, -1, 1103, 1256, 1108, -1, + 1103, 1108, 1106, -1, 1725, 1109, 1729, -1, + 1725, 1110, 1109, -1, 1725, 1726, 1110, -1, + 1111, 1112, 1117, -1, 1111, 1117, 1118, -1, + 1111, 1113, 1112, -1, 1111, 1118, 1113, -1, + 1733, 1114, 1118, -1, 1733, 1734, 1279, -1, + 1733, 1279, 1280, -1, 1733, 1280, 1114, -1, + 1119, 1115, 1732, -1, 1119, 1120, 1115, -1, + 1119, 1733, 1118, -1, 1119, 1732, 1733, -1, + 1116, 1118, 1117, -1, 1116, 1119, 1118, -1, + 1116, 1120, 1119, -1, 1116, 1117, 1121, -1, + 1116, 1121, 1120, -1, 1122, 1126, 1127, -1, + 1122, 1123, 1126, -1, 1122, 1127, 1124, -1, + 1122, 1124, 1123, -1, 1125, 1127, 1126, -1, + 1125, 1132, 1127, -1, 1125, 1126, 1128, -1, + 1125, 1128, 1132, -1, 1129, 1130, 1131, -1, + 1129, 1131, 1132, -1, 1129, 1133, 1130, -1, + 1129, 1132, 1133, -1, 2268, 1134, 1735, -1, + 2268, 1135, 1134, -1, 2268, 2266, 2187, -1, + 2268, 2187, 2186, -1, 2268, 2186, 1136, -1, + 2268, 1136, 1135, -1, 1137, 1138, 1139, -1, + 1137, 1139, 1144, -1, 1137, 1140, 1138, -1, + 1137, 1144, 1140, -1, 1141, 1142, 1143, -1, + 1141, 1144, 1142, -1, 1141, 1145, 1146, -1, + 1141, 1143, 1145, -1, 1141, 1146, 1147, -1, + 1141, 1147, 1148, -1, 1141, 1148, 1149, -1, + 1141, 1149, 1144, -1, 1739, 1740, 1150, -1, + 1739, 1151, 1156, -1, 1739, 1150, 1151, -1, + 1743, 1152, 1742, -1, 1743, 1153, 1152, -1, + 1743, 1155, 1154, -1, 1743, 1154, 1153, -1, + 1743, 1156, 1155, -1, 1743, 1739, 1156, -1, + 1157, 1747, 1752, -1, 1157, 1752, 1158, -1, + 1157, 1159, 1747, -1, 1157, 1158, 1159, -1, + 1823, 1197, 1166, -1, 1823, 1166, 1160, -1, + 1823, 1160, 1824, -1, 1823, 2285, 1196, -1, + 1750, 1757, 1758, -1, 1750, 1745, 1167, -1, + 1756, 1755, 1161, -1, 1756, 1161, 1162, -1, + 1756, 1162, 1163, -1, 1756, 1164, 1758, -1, + 1756, 1163, 1164, -1, 1165, 1166, 1754, -1, + 1165, 1754, 1757, -1, 1165, 1167, 1166, -1, + 1165, 1757, 1750, -1, 1165, 1750, 1167, -1, + 1174, 1764, 1168, -1, 1174, 1168, 1770, -1, + 1780, 1170, 1169, -1, 1780, 1779, 1170, -1, + 1780, 1171, 1176, -1, 1780, 1169, 1171, -1, + 1780, 1176, 1781, -1, 1760, 1775, 1173, -1, + 1760, 1185, 1775, -1, 1760, 1184, 1185, -1, + 1760, 1761, 1184, -1, 1760, 1173, 1762, -1, + 1766, 1172, 1765, -1, 1766, 1767, 1172, -1, + 1178, 1775, 1773, -1, 1178, 1173, 1775, -1, + 1178, 1177, 1173, -1, 1772, 1174, 1770, -1, + 1772, 1764, 1174, -1, 1175, 1781, 1176, -1, + 1175, 1176, 1177, -1, 1175, 1773, 1769, -1, + 1175, 1177, 1178, -1, 1175, 1178, 1773, -1, + 1175, 1782, 1781, -1, 1175, 1769, 1782, -1, + 1778, 1180, 1179, -1, 1778, 1782, 1180, -1, + 1778, 1179, 1779, -1, 1181, 1182, 1183, -1, + 1181, 1183, 1767, -1, 1181, 1184, 1182, -1, + 1181, 1185, 1184, -1, 1181, 1767, 1774, -1, + 1181, 1774, 1185, -1, 2277, 1329, 2276, -1, + 1186, 1229, 1193, -1, 1186, 1785, 1229, -1, + 1186, 1193, 1790, -1, 1186, 1790, 1785, -1, + 1187, 2211, 1194, -1, 1187, 1194, 1189, -1, + 1187, 1190, 2211, -1, 1187, 1189, 1190, -1, + 1188, 1194, 1195, -1, 1188, 1189, 1194, -1, + 1188, 1195, 1190, -1, 1188, 1190, 1189, -1, + 1191, 1193, 1192, -1, 1191, 1790, 1193, -1, + 1191, 1195, 1194, -1, 1191, 1192, 1195, -1, + 1191, 1787, 1790, -1, 1191, 1194, 2214, -1, + 1191, 2214, 1787, -1, 1789, 1705, 1329, -1, + 1789, 1329, 2277, -1, 1789, 1788, 1705, -1, + 1801, 1196, 1198, -1, 1801, 1823, 1196, -1, + 1801, 1197, 1823, -1, 1801, 1800, 1754, -1, + 1801, 1754, 1197, -1, 1794, 1808, 1792, -1, + 1796, 1198, 1803, -1, 1796, 1801, 1198, -1, + 2272, 1805, 1803, -1, 1199, 1803, 1805, -1, + 1199, 1805, 1797, -1, 1199, 1796, 1803, -1, + 1199, 1797, 1796, -1, 1204, 1201, 1200, -1, + 1204, 1202, 1201, -1, 1204, 1200, 1206, -1, + 1810, 1811, 1202, -1, 1810, 1203, 1812, -1, + 1810, 1202, 1204, -1, 1810, 2254, 1205, -1, + 1810, 1205, 1203, -1, 1810, 1206, 2254, -1, + 1810, 1204, 1206, -1, 1819, 1817, 1207, -1, + 1819, 1207, 1208, -1, 1819, 1208, 1820, -1, + 1822, 1209, 2280, -1, 1822, 1821, 1209, -1, + 1210, 1211, 1212, -1, 1210, 1213, 1220, -1, + 1210, 1220, 1214, -1, 1210, 1214, 1211, -1, + 1210, 1215, 1213, -1, 1210, 1212, 1215, -1, + 2776, 1216, 2777, -1, 2776, 1217, 1216, -1, + 2776, 2279, 1217, -1, 1831, 1827, 1830, -1, + 1218, 1219, 1220, -1, 1218, 1746, 1219, -1, + 1218, 1220, 1745, -1, 1218, 1745, 1746, -1, + 1834, 1221, 2620, -1, 1834, 1223, 1222, -1, + 1834, 1844, 1223, -1, 1834, 1224, 1221, -1, + 1834, 1222, 1224, -1, 1834, 2620, 2621, -1, + 1837, 1838, 1225, -1, 1837, 1843, 1836, -1, + 1837, 1225, 1843, -1, 1840, 1226, 1227, -1, + 1840, 1841, 1226, -1, 1840, 1227, 1228, -1, + 1840, 1228, 1839, -1, 1833, 1229, 2289, -1, + 1833, 1832, 1230, -1, 1833, 1230, 1229, -1, + 1231, 1244, 1232, -1, 1231, 1232, 1233, -1, + 1231, 1234, 1244, -1, 1231, 1233, 1234, -1, + 1235, 1239, 1236, -1, 1235, 1240, 1239, -1, + 1235, 1236, 1241, -1, 1235, 1241, 1240, -1, + 1237, 1238, 1239, -1, 1237, 1239, 1240, -1, + 1237, 1241, 1238, -1, 1237, 1240, 1241, -1, + 1242, 1243, 1244, -1, 1242, 1244, 1245, -1, + 1242, 1246, 1243, -1, 1242, 1245, 1246, -1, + 1247, 1271, 1248, -1, 1247, 1248, 1287, -1, + 1247, 1287, 1249, -1, 1247, 1250, 1271, -1, + 1247, 1251, 1250, -1, 1247, 1252, 1251, -1, + 1247, 1249, 1252, -1, 1253, 1255, 1254, -1, + 1253, 1254, 1256, -1, 1253, 1257, 1255, -1, + 1253, 1256, 1257, -1, 1258, 1259, 1260, -1, + 1258, 1261, 1262, -1, 1258, 1262, 1259, -1, + 1258, 1263, 1261, -1, 1258, 1264, 1263, -1, + 1258, 1260, 1265, -1, 1258, 1265, 1264, -1, + 1266, 1268, 1267, -1, 1266, 1269, 1268, -1, + 1266, 1277, 1270, -1, 1266, 1267, 1277, -1, + 1266, 1271, 1269, -1, 1266, 1270, 1271, -1, + 1848, 1272, 1849, -1, 1848, 1847, 1272, -1, + 1855, 2622, 2299, -1, 2627, 1847, 2782, -1, + 2627, 1274, 1847, -1, 1273, 2781, 1854, -1, + 1273, 2628, 2781, -1, 1273, 1274, 2627, -1, + 1273, 2627, 2628, -1, 1273, 1854, 1275, -1, + 1273, 1275, 1276, -1, 1273, 1276, 1277, -1, + 1273, 1277, 1274, -1, 1859, 1849, 1281, -1, + 1859, 1281, 2297, -1, 1278, 1608, 2296, -1, + 1278, 2296, 2297, -1, 1278, 1279, 1608, -1, + 1278, 1280, 1279, -1, 1278, 1281, 1280, -1, + 1278, 2297, 1281, -1, 1282, 1315, 1972, -1, + 1282, 1307, 1315, -1, 1282, 1972, 1973, -1, + 1282, 1973, 1283, -1, 1282, 1283, 1305, -1, + 1282, 1305, 1307, -1, 1284, 1285, 1286, -1, + 1284, 1287, 1285, -1, 1284, 1286, 1288, -1, + 1284, 1288, 1287, -1, 1294, 1292, 1289, -1, + 1294, 1974, 1295, -1, 1294, 1973, 1974, -1, + 1294, 1289, 1973, -1, 1290, 1291, 1292, -1, + 1290, 1293, 1291, -1, 1290, 1292, 1294, -1, + 1290, 1295, 1293, -1, 1290, 1294, 1295, -1, + 1984, 1989, 1296, -1, 1984, 1296, 1392, -1, + 1984, 1987, 1989, -1, 1298, 1296, 1299, -1, + 1298, 1392, 1296, -1, 1298, 1303, 1392, -1, + 1297, 1302, 1303, -1, 1297, 1385, 1302, -1, + 1297, 1298, 1299, -1, 1297, 1303, 1298, -1, + 1297, 1299, 1300, -1, 1297, 1300, 1385, -1, + 1301, 1302, 1863, -1, 1301, 1303, 1302, -1, + 1301, 1863, 1889, -1, 1301, 1889, 1303, -1, + 1308, 1304, 2295, -1, 1308, 1305, 1304, -1, + 1308, 1307, 1305, -1, 1306, 1850, 1310, -1, + 1306, 2292, 1850, -1, 1306, 1310, 1316, -1, + 1306, 1316, 1307, -1, 1306, 1307, 1308, -1, + 1306, 2295, 2292, -1, 1306, 1308, 2295, -1, + 1860, 2632, 2626, -1, 1860, 1309, 1899, -1, + 1860, 1606, 1309, -1, 1860, 2626, 1606, -1, + 1327, 2302, 1313, -1, 1327, 1326, 2302, -1, + 1327, 1313, 1310, -1, 1327, 1310, 1850, -1, + 1327, 1850, 1851, -1, 1861, 1862, 1312, -1, + 1861, 1312, 2303, -1, 1311, 2303, 1312, -1, + 1311, 1314, 1313, -1, 1311, 1313, 2303, -1, + 1311, 1312, 1315, -1, 1311, 1316, 1314, -1, + 1311, 1315, 1316, -1, 1868, 1876, 1319, -1, + 1868, 1872, 1876, -1, 1868, 1319, 1866, -1, + 1320, 2524, 1321, -1, 1320, 2526, 2524, -1, + 1897, 1895, 1317, -1, 1897, 1317, 2144, -1, + 1897, 2144, 2526, -1, 1897, 2526, 1320, -1, + 1318, 1319, 1896, -1, 1318, 1866, 1319, -1, + 1318, 1896, 1897, -1, 1318, 1897, 1320, -1, + 1318, 1321, 1866, -1, 1318, 1320, 1321, -1, + 1869, 1867, 1322, -1, 1869, 1322, 1870, -1, + 1874, 1324, 1323, -1, 1874, 1879, 1324, -1, + 1874, 1323, 1873, -1, 1874, 2898, 1879, -1, + 1881, 1877, 1880, -1, 2305, 1885, 1886, -1, + 1883, 2306, 1325, -1, 1883, 1892, 2898, -1, + 1883, 2315, 1892, -1, 1883, 1325, 2315, -1, + 1888, 1864, 1886, -1, 1888, 1889, 1864, -1, + 2319, 2299, 2796, -1, 2316, 2315, 1326, -1, + 2316, 1326, 1327, -1, 2316, 1327, 1851, -1, + 1852, 2299, 2319, -1, 1852, 2319, 2317, -1, + 1852, 2316, 1851, -1, 1852, 2317, 2316, -1, + 2320, 2898, 2638, -1, 2795, 2320, 2638, -1, + 2332, 1896, 2331, -1, 2332, 2645, 1895, -1, + 1941, 1900, 2341, -1, 1941, 1369, 1900, -1, + 1941, 1933, 2345, -1, 1901, 1900, 2354, -1, + 2536, 2171, 2535, -1, 1912, 2348, 1922, -1, + 1912, 1916, 2348, -1, 1328, 2348, 1916, -1, + 1328, 2366, 2348, -1, 1947, 2762, 1945, -1, + 1947, 2357, 2762, -1, 2383, 2681, 2377, -1, + 2382, 2384, 2569, -1, 2382, 2569, 2572, -1, + 2359, 2898, 2866, -1, 2521, 2821, 2898, -1, + 2521, 2888, 2821, -1, 2880, 2366, 1328, -1, + 2880, 1916, 2668, -1, 2880, 1328, 1916, -1, + 2929, 2918, 2920, -1, 1910, 1922, 1919, -1, + 1910, 1329, 1909, -1, 1910, 1330, 1329, -1, + 1913, 1922, 1910, -1, 1331, 1806, 1804, -1, + 1331, 2276, 1330, -1, 1331, 1804, 2276, -1, + 1331, 1330, 1910, -1, 1331, 1910, 1919, -1, + 1918, 1806, 1331, -1, 1918, 1331, 1919, -1, + 1332, 1903, 1333, -1, 1332, 1920, 1903, -1, + 1332, 1918, 1920, -1, 1332, 1333, 1334, -1, + 1332, 1334, 1335, -1, 1332, 1335, 1806, -1, + 1332, 1806, 1918, -1, 1921, 2349, 1920, -1, + 1921, 2348, 2349, -1, 1921, 1922, 2348, -1, + 1336, 1338, 1337, -1, 1336, 1792, 1338, -1, + 1336, 1340, 1339, -1, 1336, 1337, 1340, -1, + 1336, 1341, 1792, -1, 1336, 1342, 1341, -1, + 1336, 1339, 1342, -1, 1925, 1343, 1924, -1, + 1925, 1905, 1343, -1, 1925, 1361, 1905, -1, + 1925, 1926, 1361, -1, 2663, 1924, 2664, -1, + 2663, 2815, 1924, -1, 2368, 1344, 2371, -1, + 2368, 2343, 2363, -1, 2368, 2363, 1344, -1, + 2340, 1941, 2341, -1, 2340, 1933, 1941, -1, + 1932, 2369, 1930, -1, 1932, 1346, 1345, -1, + 1932, 1345, 1935, -1, 1932, 1929, 1346, -1, + 1932, 1930, 1929, -1, 1366, 1938, 1347, -1, + 1366, 1364, 1938, -1, 1366, 1347, 1643, -1, + 1366, 1643, 1365, -1, 1357, 1356, 1348, -1, + 1357, 1348, 1349, -1, 1357, 1349, 1358, -1, + 1350, 1356, 2373, -1, 1350, 1351, 1356, -1, + 1350, 1352, 1351, -1, 1350, 2672, 1352, -1, + 1350, 2373, 2672, -1, 1936, 1353, 2140, -1, + 1936, 1354, 1353, -1, 1936, 1358, 1354, -1, + 1936, 2372, 1358, -1, 1355, 2373, 1356, -1, + 1355, 2372, 2373, -1, 1355, 1356, 1357, -1, + 1355, 1358, 2372, -1, 1355, 1357, 1358, -1, + 1359, 1934, 1935, -1, 1359, 1935, 1360, -1, + 1359, 1933, 1934, -1, 1359, 2345, 1933, -1, + 1359, 2536, 2345, -1, 1359, 1360, 2171, -1, + 1359, 2171, 2536, -1, 1939, 1938, 1364, -1, + 1363, 1927, 1361, -1, 1363, 1361, 1926, -1, + 1363, 1928, 1927, -1, 1362, 1928, 1363, -1, + 1362, 1363, 1926, -1, 1362, 1939, 1364, -1, + 1362, 1926, 1939, -1, 1362, 1929, 1928, -1, + 1362, 1365, 1929, -1, 1362, 1364, 1366, -1, + 1362, 1366, 1365, -1, 2659, 1905, 1368, -1, + 2659, 1368, 2918, -1, 1367, 2920, 2918, -1, + 1367, 2918, 1368, -1, 1367, 2371, 2920, -1, + 1367, 1927, 2371, -1, 1367, 1368, 1927, -1, + 1942, 1369, 1941, -1, 1942, 1902, 1370, -1, + 1942, 1370, 1371, -1, 1942, 1371, 1369, -1, + 1944, 2389, 2898, -1, 1944, 1945, 1372, -1, + 1944, 1372, 1373, -1, 1944, 1373, 2389, -1, + 1374, 1375, 1954, -1, 1374, 1376, 1375, -1, + 1374, 1956, 1377, -1, 1374, 1954, 1956, -1, + 1374, 1377, 1378, -1, 1374, 1378, 1376, -1, + 1955, 1953, 1950, -1, 1955, 2266, 1958, -1, + 1955, 1949, 2396, -1, 1955, 2396, 2406, -1, + 1955, 2406, 2266, -1, 1962, 1379, 1380, -1, + 1962, 1380, 1960, -1, 1962, 1965, 1381, -1, + 1962, 1381, 1382, -1, 1962, 1382, 1379, -1, + 1963, 2204, 1964, -1, 1963, 1961, 2748, -1, + 1963, 2748, 2204, -1, 1970, 1384, 1975, -1, + 1383, 1390, 1384, -1, 1383, 1970, 1969, -1, + 1383, 1384, 1970, -1, 1383, 1385, 1390, -1, + 1383, 1969, 1386, -1, 1383, 1386, 1385, -1, + 1387, 1389, 1388, -1, 1387, 1388, 1390, -1, + 1387, 1391, 1389, -1, 1387, 1390, 1391, -1, + 1979, 2355, 2651, -1, 2362, 2361, 1907, -1, + 2362, 1907, 1976, -1, 2362, 1979, 2651, -1, + 2362, 1976, 1979, -1, 2379, 2355, 1979, -1, + 1983, 1891, 2898, -1, 1983, 1890, 1891, -1, + 1983, 1392, 1890, -1, 1983, 1984, 1392, -1, + 2386, 2387, 1990, -1, 1992, 1993, 1393, -1, + 1992, 2579, 2578, -1, 1992, 1393, 2579, -1, + 1992, 2578, 2749, -1, 1992, 2749, 2750, -1, + 2574, 1945, 2762, -1, 2574, 2757, 1945, -1, + 2405, 2393, 2406, -1, 2399, 1996, 1997, -1, + 2399, 2408, 1996, -1, 1394, 1395, 1396, -1, + 1394, 1397, 2000, -1, 1394, 2000, 1398, -1, + 1394, 1398, 1395, -1, 1394, 1396, 1399, -1, + 1394, 1399, 1397, -1, 2700, 2699, 1400, -1, + 2430, 1412, 2005, -1, 2430, 2413, 1412, -1, + 2430, 2414, 2413, -1, 2430, 2700, 2414, -1, + 1999, 2414, 2700, -1, 1999, 1400, 2000, -1, + 1999, 2700, 1400, -1, 1401, 1403, 1402, -1, + 1401, 1404, 1403, -1, 1401, 1405, 1406, -1, + 1401, 1402, 1405, -1, 1401, 1406, 1407, -1, + 1401, 1407, 1711, -1, 1401, 1711, 2768, -1, + 1401, 2768, 1404, -1, 2002, 1711, 1407, -1, + 2002, 1710, 1711, -1, 2002, 1407, 1408, -1, + 2002, 1408, 1409, -1, 2002, 2242, 1710, -1, + 2002, 1409, 2003, -1, 2021, 2005, 2018, -1, + 2021, 2020, 1413, -1, 2021, 1413, 1410, -1, + 2021, 1410, 2006, -1, 2423, 2421, 2600, -1, + 1411, 2234, 2250, -1, 1411, 2250, 2008, -1, + 1411, 2600, 2598, -1, 1411, 2423, 2600, -1, + 1411, 2008, 2423, -1, 1411, 2597, 2234, -1, + 1411, 2598, 2597, -1, 2007, 1713, 2694, -1, + 2009, 2008, 2250, -1, 2009, 2250, 2251, -1, + 2009, 2251, 1713, -1, 2009, 1713, 2007, -1, + 2010, 2239, 2420, -1, 2419, 2420, 2603, -1, + 2601, 2239, 2010, -1, 2017, 2413, 2013, -1, + 2017, 1412, 2413, -1, 2017, 2018, 1412, -1, + 2014, 2010, 2011, -1, 2692, 2016, 1413, -1, + 2692, 1413, 2020, -1, 2412, 2013, 2413, -1, + 2416, 2417, 2024, -1, 2434, 2435, 1414, -1, + 2434, 1414, 2027, -1, 1425, 1426, 1415, -1, + 1425, 1415, 1418, -1, 1425, 1418, 1424, -1, + 1416, 1422, 1424, -1, 1416, 1417, 1422, -1, + 1416, 1429, 1417, -1, 1416, 1424, 1418, -1, + 1416, 1419, 1429, -1, 1416, 1420, 1419, -1, + 1416, 1418, 1420, -1, 1421, 1422, 1423, -1, + 1421, 1424, 1422, -1, 1421, 1423, 1444, -1, + 1421, 1426, 1425, -1, 1421, 1425, 1424, -1, + 1421, 1444, 1445, -1, 1421, 1445, 1426, -1, + 1427, 1462, 1428, -1, 1427, 1428, 1429, -1, + 1427, 1430, 1462, -1, 1427, 1429, 1430, -1, + 1435, 1431, 1432, -1, 1435, 1432, 2030, -1, + 1435, 1434, 1431, -1, 2029, 1433, 2033, -1, + 2029, 2030, 1433, -1, 2031, 2036, 1434, -1, + 2031, 1434, 1435, -1, 2031, 1435, 2030, -1, + 1436, 2006, 1437, -1, 1436, 2026, 2006, -1, + 1436, 1437, 2026, -1, 2427, 1438, 2426, -1, + 2427, 1439, 1438, -1, 2427, 2037, 1439, -1, + 2041, 1440, 1475, -1, 2041, 2043, 1441, -1, + 2041, 1441, 1440, -1, 1442, 1444, 1443, -1, + 1442, 1443, 1474, -1, 1442, 1445, 1444, -1, + 1442, 1446, 1445, -1, 1442, 1475, 1446, -1, + 1442, 1474, 1475, -1, 2441, 2443, 1447, -1, + 2441, 1447, 1448, -1, 2441, 1448, 2458, -1, + 2441, 2458, 2705, -1, 2441, 2705, 2447, -1, + 2702, 1449, 2445, -1, 2702, 2446, 1449, -1, + 2454, 2048, 1450, -1, 2454, 1450, 2709, -1, + 2454, 2709, 2708, -1, 1451, 1453, 1452, -1, + 1451, 1452, 1457, -1, 1451, 1456, 1453, -1, + 1451, 1457, 1456, -1, 1454, 1455, 1456, -1, + 1454, 1456, 1457, -1, 1454, 1457, 1458, -1, + 1454, 1459, 1455, -1, 1454, 1460, 1459, -1, + 1454, 1458, 1460, -1, 1461, 1462, 1463, -1, + 1461, 1463, 1464, -1, 1461, 1464, 1462, -1, + 1465, 1466, 1467, -1, 1465, 1473, 1468, -1, + 1465, 1467, 1473, -1, 1465, 1468, 1469, -1, + 1465, 1469, 1470, -1, 1465, 1470, 1466, -1, + 1476, 1472, 2039, -1, 1476, 2041, 1475, -1, + 1476, 2039, 2041, -1, 1471, 1473, 1472, -1, + 1471, 1474, 1473, -1, 1471, 1475, 1474, -1, + 1471, 1476, 1475, -1, 1471, 1472, 1476, -1, + 1477, 1479, 1478, -1, 1477, 1478, 1480, -1, + 1477, 1481, 1479, -1, 1477, 1482, 1481, -1, + 1477, 1480, 1482, -1, 2052, 1487, 2850, -1, + 2052, 2050, 1487, -1, 1483, 1485, 1484, -1, + 1483, 2050, 1485, -1, 1483, 1484, 1486, -1, + 1483, 1487, 2050, -1, 1483, 1488, 1487, -1, + 1483, 1486, 1488, -1, 1489, 1490, 2056, -1, + 1489, 1491, 1540, -1, 1489, 1540, 1490, -1, + 1489, 2055, 1492, -1, 1489, 2056, 2055, -1, + 1489, 1492, 1493, -1, 1489, 1493, 1491, -1, + 2487, 2488, 2055, -1, 2487, 2055, 2486, -1, + 2060, 2486, 2055, -1, 1494, 1495, 1496, -1, + 1494, 1497, 1495, -1, 1494, 1496, 1524, -1, + 1494, 1524, 1497, -1, 1498, 1499, 1508, -1, + 1498, 1508, 1503, -1, 1498, 1500, 1499, -1, + 1498, 1544, 1500, -1, 1498, 1503, 1544, -1, + 2066, 2064, 1502, -1, 2066, 1507, 2474, -1, + 1501, 1508, 1507, -1, 1501, 1507, 2066, -1, + 1501, 2066, 1502, -1, 1501, 1503, 1508, -1, + 1501, 1504, 1503, -1, 1501, 1505, 1504, -1, + 1501, 1502, 1505, -1, 2475, 2474, 1507, -1, + 1506, 1507, 1508, -1, 1506, 1508, 2070, -1, + 1506, 2475, 1507, -1, 1506, 2070, 2475, -1, + 2468, 2459, 1509, -1, 2468, 1509, 1510, -1, + 2468, 1510, 2467, -1, 2075, 1511, 2459, -1, + 2075, 2459, 2471, -1, 2075, 2074, 1511, -1, + 2460, 2463, 2462, -1, 2460, 2462, 1517, -1, + 2078, 1512, 2476, -1, 2078, 2079, 1513, -1, + 2078, 1513, 1512, -1, 1514, 2122, 2464, -1, + 1514, 1558, 2122, -1, 1514, 1516, 1515, -1, + 1514, 2464, 1516, -1, 1514, 1561, 1558, -1, + 1514, 1515, 1561, -1, 2119, 1517, 2122, -1, + 2119, 2502, 1517, -1, 2065, 1517, 2502, -1, + 2065, 2068, 2460, -1, 2065, 2460, 1517, -1, + 2065, 2502, 2063, -1, 2080, 2851, 1518, -1, + 2080, 1518, 1519, -1, 2080, 1520, 2079, -1, + 2080, 1519, 1520, -1, 2057, 1521, 2062, -1, + 2057, 2056, 1522, -1, 2057, 1523, 1524, -1, + 2057, 1522, 1523, -1, 2057, 1524, 1525, -1, + 2057, 1525, 1521, -1, 2084, 2083, 1526, -1, + 2084, 1527, 2086, -1, 2084, 1528, 1527, -1, + 2084, 1526, 1528, -1, 1529, 2085, 1530, -1, + 1529, 1531, 2085, -1, 1529, 1532, 1531, -1, + 1529, 1533, 1532, -1, 1529, 1530, 1533, -1, + 2089, 2087, 1534, -1, 2089, 1534, 2481, -1, + 2092, 1536, 1535, -1, 2092, 2091, 1536, -1, + 2092, 1535, 1646, -1, 2092, 1646, 2093, -1, + 2096, 1538, 1537, -1, 2096, 1539, 1538, -1, + 2096, 1537, 2097, -1, 2096, 2094, 1539, -1, + 2103, 2105, 1540, -1, 2103, 1540, 2102, -1, + 2100, 1541, 1542, -1, 2100, 1543, 1541, -1, + 2100, 1542, 1544, -1, 2100, 1544, 1545, -1, + 2100, 2101, 1543, -1, 2100, 1545, 2104, -1, + 1546, 1547, 1548, -1, 1546, 1548, 1549, -1, + 1546, 1551, 1550, -1, 1546, 1550, 1547, -1, + 1546, 1552, 1551, -1, 1546, 1549, 1552, -1, + 2109, 2711, 1553, -1, 2109, 1553, 2110, -1, + 2108, 2110, 2506, -1, 2108, 2506, 1578, -1, + 2108, 1578, 1554, -1, 2108, 1554, 2107, -1, + 2490, 1555, 2111, -1, 2490, 1556, 1555, -1, + 2490, 1560, 1556, -1, 1557, 2123, 1558, -1, + 1557, 1559, 2123, -1, 1557, 2491, 1559, -1, + 1557, 1560, 2490, -1, 1557, 2490, 2491, -1, + 1557, 1561, 1560, -1, 1557, 1558, 1561, -1, + 2112, 1562, 2494, -1, 2112, 2113, 1562, -1, + 1563, 1580, 1567, -1, 1563, 1567, 1566, -1, + 1563, 1578, 1580, -1, 1563, 1566, 1578, -1, + 1564, 1565, 1566, -1, 1564, 1566, 1567, -1, + 1564, 1567, 1565, -1, 1568, 1569, 2495, -1, + 1568, 2495, 1570, -1, 1568, 1571, 1569, -1, + 1568, 1570, 1571, -1, 1572, 1574, 1573, -1, + 1572, 2048, 1574, -1, 1572, 1573, 1575, -1, + 1572, 1575, 2048, -1, 2116, 2448, 1576, -1, + 2116, 1576, 2114, -1, 2116, 2499, 2448, -1, + 2120, 2123, 1579, -1, 2120, 1579, 2505, -1, + 1577, 1578, 2505, -1, 1577, 2505, 1579, -1, + 1577, 1580, 1578, -1, 1577, 1579, 1580, -1, + 1581, 1583, 1582, -1, 1581, 1584, 1583, -1, + 1581, 1586, 1585, -1, 1581, 1582, 1586, -1, + 1581, 1585, 1587, -1, 1581, 1587, 1584, -1, + 2127, 1588, 2132, -1, 2127, 2125, 1588, -1, + 1589, 1681, 1590, -1, 1589, 2743, 1681, -1, + 1589, 1590, 1594, -1, 1589, 1594, 2743, -1, + 1591, 1596, 1592, -1, 1591, 1592, 1593, -1, + 1591, 2134, 1596, -1, 1591, 2552, 1594, -1, + 1591, 1593, 2552, -1, 1591, 1594, 1595, -1, + 1591, 1595, 2134, -1, 2133, 1595, 1632, -1, + 2133, 2134, 1595, -1, 2133, 1632, 2507, -1, + 2135, 2136, 1596, -1, 2135, 1596, 2134, -1, + 1597, 1598, 2861, -1, 1597, 2861, 1873, -1, + 1597, 1873, 2312, -1, 1597, 2312, 1599, -1, + 1597, 1614, 1598, -1, 1597, 1599, 1614, -1, + 2520, 1600, 2856, -1, 2520, 2137, 1600, -1, + 2855, 2856, 1601, -1, 2855, 1602, 2857, -1, + 2855, 1601, 1603, -1, 2855, 1603, 1602, -1, + 2673, 2142, 1604, -1, 2673, 1604, 2674, -1, + 1605, 1606, 2296, -1, 1605, 1607, 1606, -1, + 1605, 2296, 1608, -1, 1605, 1608, 1607, -1, + 1609, 1610, 1619, -1, 1609, 2145, 1610, -1, + 1609, 1619, 1611, -1, 1609, 1611, 2524, -1, + 1609, 2524, 2145, -1, 2152, 1612, 2145, -1, + 2152, 2156, 1612, -1, 1613, 1614, 1615, -1, + 1613, 1615, 1616, -1, 1613, 1617, 2137, -1, + 1613, 2137, 1614, -1, 1613, 1618, 1617, -1, + 1613, 1616, 1618, -1, 2158, 2159, 1619, -1, + 2158, 1619, 2160, -1, 2157, 1870, 2159, -1, + 2157, 1621, 1870, -1, 2157, 2873, 1621, -1, + 2161, 1620, 2309, -1, 2161, 2309, 1621, -1, + 2161, 1623, 1622, -1, 2161, 1622, 1620, -1, + 2161, 2872, 1623, -1, 2161, 1621, 2873, -1, + 1624, 1630, 1625, -1, 1624, 1625, 1626, -1, + 1624, 1627, 1630, -1, 1624, 1626, 1627, -1, + 1628, 1629, 1630, -1, 1628, 1630, 1631, -1, + 1628, 2129, 2130, -1, 1628, 2130, 1629, -1, + 1628, 2128, 2129, -1, 1628, 1631, 2128, -1, + 2164, 1632, 1633, -1, 2164, 2507, 1632, -1, + 2164, 1633, 1634, -1, 2164, 2508, 2507, -1, + 2164, 1634, 2165, -1, 2530, 1635, 2166, -1, + 2530, 1638, 1635, -1, 1636, 2171, 1637, -1, + 1636, 1637, 1638, -1, 1636, 2530, 2171, -1, + 1636, 1638, 2530, -1, 1639, 1662, 2166, -1, + 1639, 2166, 1640, -1, 1639, 1641, 1662, -1, + 1639, 1640, 1641, -1, 2175, 1641, 1642, -1, + 2175, 1644, 1641, -1, 2175, 1642, 1643, -1, + 2175, 1643, 2173, -1, 2176, 1651, 1664, -1, + 2176, 1664, 1644, -1, 2176, 1644, 2175, -1, + 2176, 2174, 1651, -1, 2533, 2538, 2093, -1, + 2533, 2537, 2538, -1, 2533, 1646, 1645, -1, + 2533, 2093, 1646, -1, 2533, 1645, 2177, -1, + 1647, 2168, 1648, -1, 1647, 1649, 2168, -1, + 1647, 1648, 1650, -1, 1647, 1650, 1649, -1, + 2181, 1651, 2174, -1, 2181, 1652, 1651, -1, + 2181, 2174, 2183, -1, 2181, 2179, 1652, -1, + 1653, 1655, 1654, -1, 1653, 1654, 1656, -1, + 1653, 1657, 1655, -1, 1653, 1656, 1657, -1, + 1658, 1660, 1659, -1, 1658, 1659, 1661, -1, + 1658, 2169, 1662, -1, 1658, 2167, 2169, -1, + 1658, 1661, 2167, -1, 1658, 1662, 1663, -1, + 1658, 1664, 1660, -1, 1658, 1663, 1664, -1, + 1665, 1667, 1666, -1, 1665, 1669, 1667, -1, + 1665, 1666, 1671, -1, 1665, 1671, 1669, -1, + 1668, 1670, 1669, -1, 1668, 1669, 1671, -1, + 1668, 1672, 1670, -1, 1668, 1673, 1672, -1, + 1668, 1671, 1674, -1, 1668, 1674, 1673, -1, + 1675, 2539, 2717, -1, 1675, 1678, 2539, -1, + 1675, 1676, 1678, -1, 1675, 2160, 1676, -1, + 1675, 2717, 2160, -1, 2741, 2539, 2739, -1, + 2738, 1681, 2743, -1, 1677, 2539, 1678, -1, + 1677, 2739, 2539, -1, 1677, 1679, 1680, -1, + 1677, 1678, 1679, -1, 1677, 2738, 2739, -1, + 1677, 1680, 1681, -1, 1677, 1681, 2738, -1, + 2548, 1683, 1682, -1, 2548, 1682, 2546, -1, + 2548, 2549, 1683, -1, 2548, 2546, 2734, -1, + 1684, 1685, 1686, -1, 1684, 1687, 1685, -1, + 1684, 1686, 2073, -1, 1684, 2073, 2076, -1, + 1684, 2076, 1687, -1, 1736, 1737, 2615, -1, + 2618, 2269, 2619, -1, 2618, 2617, 1688, -1, + 2618, 1688, 2269, -1, 1689, 1949, 1951, -1, + 1689, 1690, 1949, -1, 1689, 1951, 1690, -1, + 1691, 1692, 1958, -1, 1691, 1693, 1692, -1, + 1691, 1958, 1693, -1, 2188, 1694, 2186, -1, + 2188, 1695, 1694, -1, 2188, 2190, 1695, -1, + 2194, 2192, 2562, -1, 2194, 2562, 1696, -1, + 2194, 1696, 2196, -1, 2594, 1981, 2595, -1, + 1708, 1707, 1699, -1, 1708, 1981, 2594, -1, + 1708, 2594, 2593, -1, 2201, 1699, 2202, -1, + 2201, 2570, 1699, -1, 1697, 1698, 1981, -1, + 1697, 1708, 1699, -1, 1697, 1981, 1708, -1, + 1697, 1699, 1700, -1, 1697, 1700, 1698, -1, + 2565, 2203, 1701, -1, 2565, 1701, 2204, -1, + 2207, 2222, 2228, -1, 2207, 2228, 2563, -1, + 2207, 2751, 2222, -1, 2568, 2749, 2578, -1, + 2568, 2578, 2580, -1, 2219, 2584, 2218, -1, + 2219, 2583, 2584, -1, 2215, 1709, 2213, -1, + 2215, 2219, 1709, -1, 2215, 2583, 2219, -1, + 2585, 2588, 1702, -1, 2585, 1702, 2584, -1, + 2224, 2218, 1703, -1, 2224, 1703, 2225, -1, + 2231, 2595, 1704, -1, 2231, 1788, 2591, -1, + 2231, 1907, 1908, -1, 2231, 1704, 1907, -1, + 2231, 1908, 1705, -1, 2231, 1705, 1788, -1, + 1706, 2202, 1707, -1, 1706, 2220, 2202, -1, + 1706, 1707, 1708, -1, 1706, 1708, 2593, -1, + 1706, 1709, 2219, -1, 1706, 2219, 2220, -1, + 1706, 2213, 1709, -1, 1706, 2593, 2213, -1, + 2590, 2213, 2593, -1, 2590, 2214, 2213, -1, + 2590, 2591, 2214, -1, 2232, 2421, 2684, -1, + 2232, 2600, 2421, -1, 2235, 2597, 2252, -1, + 2235, 2234, 2597, -1, 2608, 2603, 2420, -1, + 2608, 2420, 2239, -1, 2767, 1710, 2242, -1, + 2767, 2242, 1712, -1, 2767, 2768, 1711, -1, + 2767, 1711, 1710, -1, 2767, 1712, 2765, -1, + 2610, 1712, 2242, -1, 2610, 2765, 1712, -1, + 2686, 2606, 2684, -1, 2238, 2684, 2606, -1, + 2238, 2187, 2254, -1, 2238, 2254, 2684, -1, + 2238, 2244, 2187, -1, 2238, 2611, 2244, -1, + 2238, 2247, 2611, -1, 2238, 2606, 2237, -1, + 2264, 2252, 2256, -1, 2264, 2234, 2252, -1, + 2264, 2249, 2234, -1, 2259, 2260, 2261, -1, + 2259, 2251, 2262, -1, 2259, 2261, 1713, -1, + 2259, 1713, 2251, -1, 1714, 1715, 1716, -1, + 1714, 1716, 1717, -1, 1714, 1718, 1715, -1, + 1714, 1717, 1718, -1, 1719, 1720, 1721, -1, + 1719, 1722, 1720, -1, 1719, 1721, 1723, -1, + 1719, 1723, 1722, -1, 1724, 1726, 1725, -1, + 1724, 1727, 1726, -1, 1724, 1729, 1728, -1, + 1724, 1725, 1729, -1, 1724, 1730, 1727, -1, + 1724, 1728, 1730, -1, 1731, 1732, 2149, -1, + 1731, 1733, 1732, -1, 1731, 2149, 1734, -1, + 1731, 1734, 1733, -1, 2614, 2268, 1735, -1, + 2614, 1736, 2615, -1, 2614, 1735, 1737, -1, + 2614, 1737, 1736, -1, 1738, 1740, 1739, -1, + 1738, 1741, 1740, -1, 1738, 1742, 1741, -1, + 1738, 1743, 1742, -1, 1738, 1739, 1743, -1, + 1744, 1750, 1751, -1, 1744, 1745, 1750, -1, + 1744, 1746, 1745, -1, 1744, 1751, 1747, -1, + 1744, 1747, 1746, -1, 1748, 1758, 1749, -1, + 1748, 1750, 1758, -1, 1748, 1751, 1750, -1, + 1748, 1752, 1751, -1, 1748, 1749, 1752, -1, + 1753, 1754, 1755, -1, 1753, 1755, 1756, -1, + 1753, 1757, 1754, -1, 1753, 1758, 1757, -1, + 1753, 1756, 1758, -1, 1759, 1761, 1760, -1, + 1759, 1760, 1762, -1, 1759, 1763, 1761, -1, + 1759, 1762, 1763, -1, 1776, 1765, 1764, -1, + 1776, 1766, 1765, -1, 1776, 1764, 1772, -1, + 1776, 1774, 1767, -1, 1776, 1767, 1766, -1, + 1768, 1769, 1773, -1, 1768, 1773, 1772, -1, + 1768, 1770, 1769, -1, 1768, 1772, 1770, -1, + 1771, 1772, 1773, -1, 1771, 1775, 1774, -1, + 1771, 1773, 1775, -1, 1771, 1774, 1776, -1, + 1771, 1776, 1772, -1, 1777, 1778, 1779, -1, + 1777, 1780, 1781, -1, 1777, 1779, 1780, -1, + 1777, 1781, 1782, -1, 1777, 1782, 1778, -1, + 1783, 2277, 2275, -1, 1783, 1785, 2277, -1, + 1783, 2275, 2274, -1, 1783, 2274, 1785, -1, + 1784, 1790, 1789, -1, 1784, 1789, 2277, -1, + 1784, 1785, 1790, -1, 1784, 2277, 1785, -1, + 1786, 1787, 1788, -1, 1786, 1788, 1789, -1, + 1786, 1790, 1787, -1, 1786, 1789, 1790, -1, + 1798, 1792, 1791, -1, 1798, 1794, 1792, -1, + 1798, 1797, 1794, -1, 1798, 1793, 1799, -1, + 1798, 1791, 1793, -1, 1807, 1797, 1805, -1, + 1807, 1794, 1797, -1, 1807, 1808, 1794, -1, + 1795, 1796, 1797, -1, 1795, 1798, 1799, -1, + 1795, 1797, 1798, -1, 1795, 1799, 1800, -1, + 1795, 1800, 1801, -1, 1795, 1801, 1796, -1, + 2271, 1803, 1802, -1, 2271, 2272, 1803, -1, + 2271, 2289, 2274, -1, 2271, 1802, 2289, -1, + 2273, 2276, 1804, -1, 2273, 1805, 2272, -1, + 2273, 1804, 1806, -1, 2273, 1807, 1805, -1, + 2273, 1806, 1808, -1, 2273, 1808, 1807, -1, + 1809, 1811, 1810, -1, 1809, 1810, 1812, -1, + 1809, 1813, 1811, -1, 1809, 1814, 1813, -1, + 1809, 1812, 1815, -1, 1809, 1815, 1814, -1, + 1816, 1818, 1817, -1, 1816, 1817, 1819, -1, + 1816, 1820, 1818, -1, 1816, 1819, 1820, -1, + 1825, 1824, 1821, -1, 1825, 1821, 1822, -1, + 1825, 2280, 2281, -1, 1825, 1822, 2280, -1, + 1825, 2281, 1827, -1, 1825, 1827, 1826, -1, + 2773, 2278, 2283, -1, 1828, 2285, 1823, -1, + 1828, 1823, 1824, -1, 1828, 1824, 1825, -1, + 1828, 1825, 1826, -1, 2287, 1826, 1827, -1, + 2287, 1827, 1831, -1, 2287, 2285, 1828, -1, + 2287, 1828, 1826, -1, 2288, 1830, 1829, -1, + 2288, 1831, 1830, -1, 2288, 1829, 1832, -1, + 2288, 1832, 1833, -1, 2288, 1833, 2289, -1, + 2288, 2287, 1831, -1, 1846, 1834, 2621, -1, + 1846, 1844, 1834, -1, 1846, 1843, 1845, -1, + 1846, 2621, 1836, -1, 1846, 1836, 1843, -1, + 1835, 1836, 1838, -1, 1835, 1837, 1836, -1, + 1835, 1838, 1837, -1, 2778, 1839, 1838, -1, + 2778, 1840, 1839, -1, 2778, 1838, 2621, -1, + 2778, 2777, 1841, -1, 2778, 1841, 1840, -1, + 1842, 1843, 1844, -1, 1842, 1845, 1843, -1, + 1842, 1844, 1846, -1, 1842, 1846, 1845, -1, + 2783, 2782, 1847, -1, 2783, 1847, 1848, -1, + 2783, 1848, 1849, -1, 2783, 1849, 1859, -1, + 2291, 1850, 2292, -1, 2291, 1851, 1850, -1, + 2291, 1852, 1851, -1, 2291, 1855, 2299, -1, + 2291, 2299, 1852, -1, 2623, 2622, 1856, -1, + 2623, 1853, 1854, -1, 2623, 1854, 2781, -1, + 2623, 1858, 1853, -1, 2623, 1856, 1858, -1, + 2293, 2622, 1855, -1, 2293, 1856, 2622, -1, + 2293, 1855, 2291, -1, 2293, 2294, 1857, -1, + 2293, 1857, 1858, -1, 2293, 1858, 1856, -1, + 2625, 1859, 2297, -1, 2625, 2783, 1859, -1, + 2625, 2788, 2783, -1, 2786, 2788, 2625, -1, + 2631, 1860, 1899, -1, 2631, 2632, 1860, -1, + 2304, 1861, 2303, -1, 2304, 1863, 1862, -1, + 2304, 1862, 1861, -1, 2304, 1864, 1863, -1, + 2304, 1886, 1864, -1, 2304, 2305, 1886, -1, + 1865, 1866, 1867, -1, 1865, 1867, 1869, -1, + 1865, 1868, 1866, -1, 1865, 1872, 1868, -1, + 1865, 1869, 1872, -1, 2310, 1869, 1870, -1, + 2310, 1870, 2309, -1, 2310, 2311, 1871, -1, + 2310, 1871, 1872, -1, 2310, 1872, 1869, -1, + 2860, 1873, 2861, -1, 2860, 1874, 1873, -1, + 2860, 2898, 1874, -1, 1875, 2330, 1876, -1, + 1875, 2329, 2330, -1, 1875, 1876, 1877, -1, + 1875, 1877, 1881, -1, 1875, 2898, 2329, -1, + 1875, 1881, 2898, -1, 1878, 1880, 1879, -1, + 1878, 1881, 1880, -1, 1878, 1879, 2898, -1, + 1878, 2898, 1881, -1, 1882, 2306, 1883, -1, + 1882, 2305, 2306, -1, 1882, 1885, 2305, -1, + 1882, 2898, 1885, -1, 1882, 1883, 2898, -1, + 1884, 1886, 1885, -1, 1884, 1888, 1886, -1, + 1884, 1885, 2898, -1, 1884, 2898, 1888, -1, + 1887, 1889, 1888, -1, 1887, 1891, 1890, -1, + 1887, 1890, 1889, -1, 1887, 2898, 1891, -1, + 1887, 1888, 2898, -1, 2314, 1892, 2315, -1, + 2314, 2898, 1892, -1, 2314, 2639, 2898, -1, + 1893, 2300, 2898, -1, 1893, 2898, 2320, -1, + 2791, 1893, 2320, -1, 2791, 2793, 2300, -1, + 2791, 2300, 1893, -1, 1894, 2332, 1895, -1, + 1894, 1896, 2332, -1, 1894, 1895, 1897, -1, + 1894, 1897, 1896, -1, 2323, 1898, 2898, -1, + 2323, 2324, 2630, -1, 2323, 2630, 2631, -1, + 2323, 2631, 1898, -1, 2326, 2898, 1898, -1, + 2326, 1899, 2327, -1, 2326, 2631, 1899, -1, + 2326, 1898, 2631, -1, 2336, 2898, 2334, -1, + 2336, 2643, 2898, -1, 1906, 2354, 2352, -1, + 1906, 1901, 2354, -1, 1906, 2352, 2810, -1, + 1906, 2363, 2343, -1, 2342, 2341, 1900, -1, + 2342, 1900, 1901, -1, 2342, 1906, 2343, -1, + 2342, 1901, 1906, -1, 2346, 1902, 1942, -1, + 2346, 2177, 1902, -1, 1904, 1903, 2349, -1, + 1904, 2353, 1903, -1, 2351, 2366, 2365, -1, + 2351, 1904, 2349, -1, 2351, 2365, 2809, -1, + 2351, 2353, 1904, -1, 2800, 2383, 2377, -1, + 2358, 2382, 2572, -1, 2652, 2654, 2898, -1, + 2652, 2898, 2359, -1, 2138, 2898, 2654, -1, + 2138, 2521, 2898, -1, 2881, 2366, 2880, -1, + 2667, 2648, 2807, -1, 2658, 2656, 2664, -1, + 2658, 2664, 1905, -1, 2658, 1905, 2659, -1, + 2364, 2363, 1906, -1, 2364, 1906, 2810, -1, + 1915, 1908, 1907, -1, 1915, 1907, 1914, -1, + 1915, 1909, 1908, -1, 1915, 1910, 1909, -1, + 1915, 1913, 1910, -1, 1911, 1912, 1922, -1, + 1911, 1922, 1913, -1, 1911, 1914, 2669, -1, + 1911, 1915, 1914, -1, 1911, 1913, 1915, -1, + 1911, 2669, 1916, -1, 1911, 1916, 1912, -1, + 1917, 1918, 1919, -1, 1917, 1920, 1918, -1, + 1917, 1921, 1920, -1, 1917, 1919, 1922, -1, + 1917, 1922, 1921, -1, 1923, 1924, 2141, -1, + 1923, 1925, 1924, -1, 1923, 2141, 1939, -1, + 1923, 1926, 1925, -1, 1923, 1939, 1926, -1, + 2370, 2371, 1927, -1, 2370, 1927, 1928, -1, + 2370, 1928, 1929, -1, 2370, 1929, 1930, -1, + 2370, 1930, 2369, -1, 1931, 2340, 2369, -1, + 1931, 2369, 1932, -1, 1931, 1934, 1933, -1, + 1931, 1933, 2340, -1, 1931, 1935, 1934, -1, + 1931, 1932, 1935, -1, 2374, 1936, 2140, -1, + 2374, 2140, 2673, -1, 2374, 2372, 1936, -1, + 1937, 2140, 1938, -1, 1937, 1938, 1939, -1, + 1937, 2141, 2140, -1, 1937, 1939, 2141, -1, + 1940, 1941, 2345, -1, 1940, 1942, 1941, -1, + 1940, 2345, 2346, -1, 1940, 2346, 1942, -1, + 1943, 2898, 1946, -1, 1943, 1944, 2898, -1, + 1943, 1945, 1944, -1, 1943, 1947, 1945, -1, + 1943, 1946, 1947, -1, 2375, 2678, 2360, -1, + 2375, 2360, 2803, -1, 2832, 1946, 2898, -1, + 2832, 2357, 1947, -1, 2832, 1947, 1946, -1, + 1957, 1955, 1958, -1, 1948, 1949, 1955, -1, + 1948, 1955, 1950, -1, 1948, 1951, 1949, -1, + 1948, 1950, 1951, -1, 1952, 1954, 1953, -1, + 1952, 1953, 1955, -1, 1952, 1956, 1954, -1, + 1952, 1955, 1957, -1, 1952, 1958, 1956, -1, + 1952, 1957, 1958, -1, 1959, 1960, 1961, -1, + 1959, 1962, 1960, -1, 1959, 1963, 1964, -1, + 1959, 1961, 1963, -1, 1959, 1965, 1962, -1, + 1959, 1964, 1966, -1, 1959, 1966, 1965, -1, + 1967, 1968, 1969, -1, 1967, 1969, 1970, -1, + 1967, 1972, 1971, -1, 1967, 1971, 1968, -1, + 1967, 1973, 1972, -1, 1967, 1974, 1973, -1, + 1967, 1975, 1974, -1, 1967, 1970, 1975, -1, + 1980, 1979, 1976, -1, 1980, 1976, 2595, -1, + 1980, 2595, 1981, -1, 2381, 1978, 2384, -1, + 2381, 2379, 1978, -1, 1977, 1978, 2379, -1, + 1977, 2379, 1979, -1, 1977, 1979, 1980, -1, + 1977, 1981, 1978, -1, 1977, 1980, 1981, -1, + 1982, 2898, 1987, -1, 1982, 1983, 2898, -1, + 1982, 1987, 1984, -1, 1982, 1984, 1983, -1, + 2391, 1985, 2387, -1, 2391, 2390, 1985, -1, + 1986, 1987, 2898, -1, 1986, 2898, 2386, -1, + 1986, 1988, 1989, -1, 1986, 1989, 1987, -1, + 1986, 1990, 1988, -1, 1986, 2386, 1990, -1, + 1991, 1993, 1992, -1, 1991, 1995, 1994, -1, + 1991, 1994, 1993, -1, 1991, 2750, 1995, -1, + 1991, 1992, 2750, -1, 2404, 1997, 2405, -1, + 2395, 2405, 1997, -1, 2395, 1996, 2394, -1, + 2395, 1997, 1996, -1, 2841, 2839, 2559, -1, + 2841, 2559, 2557, -1, 2841, 2557, 2400, -1, + 2841, 2835, 2836, -1, 2402, 2399, 1997, -1, + 2402, 1997, 2404, -1, 2402, 2403, 2835, -1, + 2410, 2399, 2400, -1, 2410, 2554, 2588, -1, + 2410, 2400, 2554, -1, 2410, 2408, 2399, -1, + 1998, 2429, 2430, -1, 1998, 2430, 2005, -1, + 1998, 2005, 2006, -1, 1998, 2006, 2026, -1, + 1998, 2026, 2429, -1, 2415, 2414, 1999, -1, + 2415, 2000, 2418, -1, 2415, 1999, 2000, -1, + 2001, 2002, 2003, -1, 2001, 2242, 2002, -1, + 2001, 2003, 2245, -1, 2001, 2245, 2242, -1, + 2004, 2006, 2005, -1, 2004, 2021, 2006, -1, + 2004, 2005, 2021, -1, 2424, 2011, 2010, -1, + 2424, 2010, 2420, -1, 2424, 2690, 2011, -1, + 2425, 2007, 2694, -1, 2425, 2423, 2008, -1, + 2425, 2008, 2009, -1, 2425, 2009, 2007, -1, + 2015, 2010, 2014, -1, 2015, 2023, 2601, -1, + 2015, 2601, 2010, -1, 2689, 2011, 2690, -1, + 2689, 2014, 2011, -1, 2012, 2017, 2013, -1, + 2012, 2019, 2017, -1, 2012, 2689, 2019, -1, + 2012, 2014, 2689, -1, 2012, 2013, 2412, -1, + 2012, 2412, 2023, -1, 2012, 2023, 2015, -1, + 2012, 2015, 2014, -1, 2693, 2694, 2016, -1, + 2693, 2016, 2692, -1, 2688, 2018, 2017, -1, + 2688, 2017, 2019, -1, 2688, 2692, 2020, -1, + 2688, 2019, 2689, -1, 2688, 2021, 2018, -1, + 2688, 2020, 2021, -1, 2022, 2601, 2023, -1, + 2022, 2023, 2412, -1, 2022, 2412, 2416, -1, + 2022, 2770, 2601, -1, 2022, 2024, 2770, -1, + 2022, 2416, 2024, -1, 2436, 2025, 2435, -1, + 2436, 2426, 2025, -1, 2697, 2026, 2431, -1, + 2697, 2429, 2026, -1, 2696, 2434, 2027, -1, + 2696, 2027, 2699, -1, 2028, 2030, 2029, -1, + 2028, 2031, 2030, -1, 2028, 2033, 2032, -1, + 2028, 2029, 2033, -1, 2028, 2032, 2034, -1, + 2028, 2034, 2035, -1, 2028, 2035, 2036, -1, + 2028, 2036, 2031, -1, 2428, 2432, 2037, -1, + 2428, 2037, 2427, -1, 2038, 2039, 2040, -1, + 2038, 2041, 2039, -1, 2038, 2040, 2042, -1, + 2038, 2042, 2043, -1, 2038, 2043, 2041, -1, + 2442, 2702, 2445, -1, 2442, 2447, 2702, -1, + 2843, 2044, 2446, -1, 2843, 2046, 2045, -1, + 2843, 2045, 2044, -1, 2843, 2844, 2046, -1, + 2047, 2450, 2048, -1, 2047, 2454, 2450, -1, + 2047, 2048, 2454, -1, 2455, 2450, 2454, -1, + 2049, 2051, 2050, -1, 2049, 2050, 2052, -1, + 2049, 2053, 2051, -1, 2049, 2849, 2713, -1, + 2049, 2713, 2053, -1, 2049, 2850, 2849, -1, + 2049, 2052, 2850, -1, 2054, 2055, 2056, -1, + 2054, 2060, 2055, -1, 2054, 2062, 2060, -1, + 2054, 2056, 2057, -1, 2054, 2057, 2062, -1, + 2058, 2059, 2486, -1, 2058, 2486, 2060, -1, + 2058, 2061, 2059, -1, 2058, 2062, 2061, -1, + 2058, 2060, 2062, -1, 2067, 2063, 2064, -1, + 2067, 2064, 2066, -1, 2067, 2068, 2065, -1, + 2067, 2065, 2063, -1, 2473, 2066, 2474, -1, + 2473, 2068, 2067, -1, 2473, 2067, 2066, -1, + 2473, 2460, 2068, -1, 2473, 2470, 2460, -1, + 2071, 2069, 2077, -1, 2071, 2070, 2069, -1, + 2071, 2475, 2070, -1, 2466, 2459, 2468, -1, + 2472, 2071, 2077, -1, 2472, 2475, 2071, -1, + 2472, 2075, 2471, -1, 2072, 2073, 2074, -1, + 2072, 2074, 2075, -1, 2072, 2076, 2073, -1, + 2072, 2077, 2076, -1, 2072, 2472, 2077, -1, + 2072, 2075, 2472, -1, 2852, 2078, 2476, -1, + 2852, 2079, 2078, -1, 2852, 2080, 2079, -1, + 2852, 2851, 2080, -1, 2081, 2082, 2083, -1, + 2081, 2083, 2084, -1, 2081, 2085, 2082, -1, + 2081, 2086, 2085, -1, 2081, 2084, 2086, -1, + 2480, 2088, 2087, -1, 2480, 2087, 2089, -1, + 2480, 2722, 2724, -1, 2480, 2724, 2088, -1, + 2480, 2721, 2722, -1, 2480, 2089, 2481, -1, + 2090, 2479, 2091, -1, 2090, 2091, 2092, -1, + 2090, 2721, 2479, -1, 2090, 2538, 2721, -1, + 2090, 2093, 2538, -1, 2090, 2092, 2093, -1, + 2483, 2095, 2094, -1, 2483, 2094, 2096, -1, + 2483, 2484, 2095, -1, 2485, 2096, 2097, -1, + 2485, 2097, 2098, -1, 2485, 2098, 2488, -1, + 2485, 2483, 2096, -1, 2099, 2101, 2100, -1, + 2099, 2102, 2101, -1, 2099, 2103, 2102, -1, + 2099, 2100, 2104, -1, 2099, 2104, 2105, -1, + 2099, 2105, 2103, -1, 2106, 2107, 2712, -1, + 2106, 2108, 2107, -1, 2106, 2712, 2711, -1, + 2106, 2711, 2109, -1, 2106, 2109, 2110, -1, + 2106, 2110, 2108, -1, 2492, 2490, 2111, -1, + 2492, 2112, 2494, -1, 2492, 2111, 2113, -1, + 2492, 2113, 2112, -1, 2497, 2114, 2115, -1, + 2497, 2116, 2114, -1, 2497, 2115, 2117, -1, + 2497, 2117, 2118, -1, 2497, 2118, 2498, -1, + 2497, 2499, 2116, -1, 2504, 2502, 2119, -1, + 2504, 2120, 2505, -1, 2504, 2122, 2121, -1, + 2504, 2119, 2122, -1, 2504, 2121, 2123, -1, + 2504, 2123, 2120, -1, 2124, 2126, 2125, -1, + 2124, 2125, 2127, -1, 2124, 2129, 2128, -1, + 2124, 2128, 2126, -1, 2124, 2130, 2129, -1, + 2124, 2131, 2130, -1, 2124, 2132, 2131, -1, + 2124, 2127, 2132, -1, 2513, 2133, 2507, -1, + 2512, 2134, 2133, -1, 2512, 2135, 2134, -1, + 2512, 2133, 2513, -1, 2512, 2518, 2136, -1, + 2512, 2136, 2135, -1, 2715, 2861, 2137, -1, + 2715, 2137, 2520, -1, 2655, 2653, 2656, -1, + 2655, 2521, 2138, -1, 2655, 2654, 2653, -1, + 2655, 2138, 2654, -1, 2865, 2359, 2866, -1, + 2865, 2864, 2813, -1, 2139, 2140, 2141, -1, + 2139, 2673, 2140, -1, 2139, 2141, 2142, -1, + 2139, 2142, 2673, -1, 2525, 2144, 2143, -1, + 2525, 2143, 2148, -1, 2525, 2526, 2144, -1, + 2523, 2145, 2524, -1, 2523, 2525, 2151, -1, + 2523, 2152, 2145, -1, 2523, 2151, 2152, -1, + 2155, 2146, 2147, -1, 2155, 2148, 2146, -1, + 2155, 2525, 2148, -1, 2155, 2151, 2525, -1, + 2155, 2147, 2149, -1, 2155, 2149, 2154, -1, + 2150, 2152, 2151, -1, 2150, 2154, 2153, -1, + 2150, 2155, 2154, -1, 2150, 2151, 2155, -1, + 2150, 2153, 2156, -1, 2150, 2156, 2152, -1, + 2719, 2873, 2157, -1, 2719, 2159, 2158, -1, + 2719, 2157, 2159, -1, 2719, 2160, 2718, -1, + 2719, 2158, 2160, -1, 2871, 2872, 2161, -1, + 2871, 2161, 2873, -1, 2162, 2163, 2508, -1, + 2162, 2508, 2164, -1, 2162, 2165, 2163, -1, + 2162, 2164, 2165, -1, 2531, 2530, 2166, -1, + 2531, 2167, 2168, -1, 2531, 2168, 2529, -1, + 2531, 2169, 2167, -1, 2531, 2166, 2169, -1, + 2170, 2535, 2171, -1, 2170, 2171, 2530, -1, + 2170, 2727, 2535, -1, 2170, 2530, 2727, -1, + 2172, 2173, 2174, -1, 2172, 2175, 2173, -1, + 2172, 2174, 2176, -1, 2172, 2176, 2175, -1, + 2534, 2533, 2177, -1, 2534, 2177, 2346, -1, + 2728, 2537, 2535, -1, 2728, 2535, 2727, -1, + 2178, 2180, 2179, -1, 2178, 2179, 2181, -1, + 2178, 2182, 2180, -1, 2178, 2183, 2182, -1, + 2178, 2181, 2183, -1, 2733, 2734, 2546, -1, + 2541, 2543, 2184, -1, 2541, 2184, 2527, -1, + 2737, 2734, 2741, -1, 2185, 2186, 2187, -1, + 2185, 2188, 2186, -1, 2185, 2187, 2189, -1, + 2185, 2190, 2188, -1, 2185, 2189, 2190, -1, + 2191, 2193, 2192, -1, 2191, 2192, 2194, -1, + 2191, 2195, 2193, -1, 2191, 2194, 2196, -1, + 2191, 2196, 2197, -1, 2191, 2197, 2198, -1, + 2191, 2199, 2195, -1, 2191, 2198, 2199, -1, + 2200, 2205, 2570, -1, 2200, 2570, 2201, -1, + 2200, 2751, 2205, -1, 2200, 2222, 2751, -1, + 2200, 2221, 2222, -1, 2200, 2202, 2221, -1, + 2200, 2201, 2202, -1, 2566, 2563, 2203, -1, + 2566, 2203, 2565, -1, 2746, 2204, 2748, -1, + 2746, 2565, 2204, -1, 2760, 2570, 2205, -1, + 2760, 2205, 2751, -1, 2755, 2577, 2757, -1, + 2206, 2754, 2751, -1, 2206, 2751, 2207, -1, + 2206, 2564, 2753, -1, 2206, 2753, 2754, -1, + 2206, 2563, 2564, -1, 2206, 2207, 2563, -1, + 2582, 2215, 2216, -1, 2582, 2208, 2586, -1, + 2582, 2583, 2215, -1, 2582, 2209, 2208, -1, + 2582, 2210, 2209, -1, 2582, 2216, 2211, -1, + 2582, 2211, 2210, -1, 2212, 2213, 2214, -1, + 2212, 2215, 2213, -1, 2212, 2214, 2216, -1, + 2212, 2216, 2215, -1, 2217, 2218, 2224, -1, + 2217, 2219, 2218, -1, 2217, 2220, 2219, -1, + 2217, 2221, 2220, -1, 2217, 2224, 2221, -1, + 2230, 2221, 2224, -1, 2230, 2222, 2221, -1, + 2230, 2228, 2222, -1, 2223, 2224, 2225, -1, + 2223, 2225, 2226, -1, 2223, 2226, 2227, -1, + 2223, 2229, 2228, -1, 2223, 2227, 2229, -1, + 2223, 2228, 2230, -1, 2223, 2230, 2224, -1, + 2592, 2231, 2591, -1, 2592, 2595, 2231, -1, + 2599, 2684, 2597, -1, 2599, 2232, 2684, -1, + 2599, 2600, 2232, -1, 2233, 2252, 2234, -1, + 2233, 2235, 2252, -1, 2233, 2234, 2235, -1, + 2236, 2237, 2607, -1, 2236, 2607, 2765, -1, + 2236, 2238, 2237, -1, 2236, 2765, 2610, -1, + 2236, 2610, 2247, -1, 2236, 2247, 2238, -1, + 2764, 2765, 2607, -1, 2764, 2608, 2239, -1, + 2764, 2607, 2608, -1, 2764, 2239, 2601, -1, + 2769, 2240, 2768, -1, 2769, 2770, 2240, -1, + 2241, 2610, 2242, -1, 2241, 2243, 2244, -1, + 2241, 2244, 2611, -1, 2241, 2611, 2610, -1, + 2241, 2245, 2243, -1, 2241, 2242, 2245, -1, + 2605, 2686, 2603, -1, 2605, 2606, 2686, -1, + 2246, 2419, 2603, -1, 2246, 2603, 2686, -1, + 2246, 2686, 2419, -1, 2685, 2419, 2686, -1, + 2612, 2611, 2247, -1, 2612, 2247, 2610, -1, + 2248, 2249, 2264, -1, 2248, 2250, 2249, -1, + 2248, 2251, 2250, -1, 2248, 2262, 2251, -1, + 2248, 2264, 2262, -1, 2265, 2264, 2257, -1, + 2265, 2256, 2252, -1, 2265, 2254, 2253, -1, + 2265, 2253, 2263, -1, 2265, 2252, 2597, -1, + 2265, 2684, 2254, -1, 2265, 2597, 2684, -1, + 2255, 2264, 2256, -1, 2255, 2257, 2264, -1, + 2255, 2256, 2265, -1, 2255, 2265, 2257, -1, + 2258, 2260, 2259, -1, 2258, 2261, 2260, -1, + 2258, 2259, 2262, -1, 2258, 2263, 2261, -1, + 2258, 2262, 2264, -1, 2258, 2265, 2263, -1, + 2258, 2264, 2265, -1, 2616, 2267, 2266, -1, + 2616, 2266, 2268, -1, 2616, 2268, 2614, -1, + 2616, 2269, 2267, -1, 2616, 2619, 2269, -1, + 2270, 2272, 2271, -1, 2270, 2273, 2272, -1, + 2270, 2274, 2275, -1, 2270, 2271, 2274, -1, + 2270, 2276, 2273, -1, 2270, 2275, 2277, -1, + 2270, 2277, 2276, -1, 2772, 2620, 2278, -1, + 2772, 2278, 2773, -1, 2775, 2280, 2279, -1, + 2775, 2279, 2776, -1, 2775, 2282, 2281, -1, + 2775, 2281, 2280, -1, 2775, 2283, 2282, -1, + 2775, 2773, 2283, -1, 2284, 2286, 2285, -1, + 2284, 2285, 2287, -1, 2284, 2287, 2288, -1, + 2284, 2289, 2286, -1, 2284, 2288, 2289, -1, + 2290, 2291, 2292, -1, 2290, 2293, 2291, -1, + 2290, 2294, 2293, -1, 2290, 2295, 2294, -1, + 2290, 2292, 2295, -1, 2624, 2296, 2626, -1, + 2624, 2297, 2296, -1, 2624, 2625, 2297, -1, + 2298, 2796, 2299, -1, 2298, 2798, 2796, -1, + 2298, 2299, 2622, -1, 2298, 2622, 2798, -1, + 2878, 2781, 2628, -1, 2633, 2786, 2625, -1, + 2635, 2324, 2322, -1, 2635, 2322, 2300, -1, + 2635, 2300, 2793, -1, 2635, 2793, 2792, -1, + 2785, 2630, 2324, -1, 2785, 2324, 2635, -1, + 2785, 2786, 2633, -1, 2301, 2303, 2302, -1, + 2301, 2304, 2303, -1, 2301, 2305, 2304, -1, + 2301, 2302, 2306, -1, 2301, 2306, 2305, -1, + 2307, 2309, 2308, -1, 2307, 2310, 2309, -1, + 2307, 2311, 2310, -1, 2307, 2308, 2312, -1, + 2307, 2312, 2311, -1, 2313, 2314, 2315, -1, + 2313, 2639, 2314, -1, 2313, 2318, 2639, -1, + 2313, 2315, 2316, -1, 2313, 2316, 2317, -1, + 2313, 2317, 2319, -1, 2313, 2319, 2318, -1, + 2637, 2639, 2318, -1, 2637, 2795, 2638, -1, + 2637, 2796, 2795, -1, 2637, 2319, 2796, -1, + 2637, 2318, 2319, -1, 2640, 2320, 2795, -1, + 2640, 2791, 2320, -1, 2321, 2898, 2322, -1, + 2321, 2323, 2898, -1, 2321, 2322, 2324, -1, + 2321, 2324, 2323, -1, 2325, 2334, 2898, -1, + 2325, 2898, 2326, -1, 2325, 2326, 2327, -1, + 2325, 2327, 2335, -1, 2325, 2335, 2334, -1, + 2328, 2329, 2898, -1, 2328, 2898, 2333, -1, + 2328, 2331, 2330, -1, 2328, 2330, 2329, -1, + 2328, 2332, 2331, -1, 2328, 2333, 2332, -1, + 2644, 2645, 2332, -1, 2644, 2332, 2333, -1, + 2644, 2898, 2643, -1, 2644, 2333, 2898, -1, + 2642, 2334, 2335, -1, 2642, 2336, 2334, -1, + 2642, 2643, 2336, -1, 2642, 2335, 2337, -1, + 2642, 2337, 2338, -1, 2642, 2338, 2646, -1, + 2339, 2369, 2340, -1, 2339, 2368, 2369, -1, + 2339, 2340, 2341, -1, 2339, 2341, 2342, -1, + 2339, 2343, 2368, -1, 2339, 2342, 2343, -1, + 2344, 2345, 2536, -1, 2344, 2346, 2345, -1, + 2344, 2536, 2534, -1, 2344, 2534, 2346, -1, + 2347, 2348, 2366, -1, 2347, 2366, 2351, -1, + 2347, 2349, 2348, -1, 2347, 2351, 2349, -1, + 2350, 2351, 2809, -1, 2350, 2809, 2810, -1, + 2350, 2810, 2352, -1, 2350, 2353, 2351, -1, + 2350, 2354, 2353, -1, 2350, 2352, 2354, -1, + 2650, 2355, 2649, -1, 2650, 2651, 2355, -1, + 2828, 2800, 2377, -1, 2802, 2803, 2360, -1, + 2802, 2360, 2648, -1, 2802, 2648, 2649, -1, + 2801, 2380, 2800, -1, 2801, 2649, 2355, -1, + 2801, 2802, 2649, -1, 2801, 2379, 2380, -1, + 2801, 2355, 2379, -1, 2831, 2358, 2357, -1, + 2831, 2681, 2358, -1, 2831, 2357, 2832, -1, + 2356, 2681, 2383, -1, 2356, 2358, 2681, -1, + 2356, 2383, 2382, -1, 2356, 2382, 2358, -1, + 2573, 2762, 2357, -1, 2573, 2357, 2358, -1, + 2573, 2358, 2572, -1, 2660, 2652, 2359, -1, + 2660, 2359, 2865, -1, 2806, 2360, 2678, -1, + 2806, 2807, 2648, -1, 2806, 2648, 2360, -1, + 2662, 2664, 2656, -1, 2662, 2656, 2653, -1, + 2666, 2669, 2361, -1, 2666, 2361, 2362, -1, + 2666, 2362, 2651, -1, 2808, 2667, 2807, -1, + 2808, 2880, 2668, -1, 2808, 2879, 2880, -1, + 2886, 2919, 2363, -1, 2886, 2363, 2364, -1, + 2886, 2810, 2914, -1, 2886, 2364, 2810, -1, + 2882, 2809, 2365, -1, 2882, 2365, 2366, -1, + 2882, 2366, 2881, -1, 2367, 2369, 2368, -1, + 2367, 2370, 2369, -1, 2367, 2368, 2371, -1, + 2367, 2371, 2370, -1, 2671, 2373, 2372, -1, + 2671, 2372, 2374, -1, 2671, 2672, 2373, -1, + 2671, 2374, 2673, -1, 2677, 2678, 2376, -1, + 2677, 2376, 2898, -1, 2677, 2898, 2818, -1, + 2679, 2375, 2803, -1, 2679, 2376, 2678, -1, + 2679, 2678, 2375, -1, 2679, 2898, 2376, -1, + 2680, 2377, 2681, -1, 2680, 2828, 2377, -1, + 2680, 2829, 2828, -1, 2680, 2898, 2829, -1, + 2378, 2380, 2379, -1, 2378, 2379, 2381, -1, + 2378, 2382, 2383, -1, 2378, 2384, 2382, -1, + 2378, 2381, 2384, -1, 2378, 2800, 2380, -1, + 2378, 2383, 2800, -1, 2385, 2387, 2386, -1, + 2385, 2391, 2387, -1, 2385, 2386, 2898, -1, + 2385, 2898, 2391, -1, 2388, 2389, 2390, -1, + 2388, 2390, 2391, -1, 2388, 2898, 2389, -1, + 2388, 2391, 2898, -1, 2392, 2394, 2393, -1, + 2392, 2395, 2394, -1, 2392, 2393, 2405, -1, + 2392, 2405, 2395, -1, 2838, 2406, 2396, -1, + 2838, 2835, 2406, -1, 2838, 2396, 2397, -1, + 2838, 2397, 2839, -1, 2398, 2400, 2399, -1, + 2398, 2841, 2400, -1, 2398, 2399, 2402, -1, + 2398, 2835, 2841, -1, 2398, 2402, 2835, -1, + 2401, 2403, 2402, -1, 2401, 2402, 2404, -1, + 2401, 2835, 2403, -1, 2401, 2404, 2405, -1, + 2401, 2405, 2406, -1, 2401, 2406, 2835, -1, + 2407, 2409, 2408, -1, 2407, 2408, 2410, -1, + 2407, 2588, 2409, -1, 2407, 2410, 2588, -1, + 2411, 2412, 2413, -1, 2411, 2413, 2414, -1, + 2411, 2414, 2415, -1, 2411, 2417, 2416, -1, + 2411, 2416, 2412, -1, 2411, 2418, 2417, -1, + 2411, 2415, 2418, -1, 2683, 2420, 2419, -1, + 2683, 2424, 2420, -1, 2683, 2419, 2685, -1, + 2683, 2423, 2424, -1, 2683, 2684, 2421, -1, + 2683, 2421, 2423, -1, 2422, 2423, 2425, -1, + 2422, 2425, 2690, -1, 2422, 2424, 2423, -1, + 2422, 2690, 2424, -1, 2691, 2425, 2694, -1, + 2691, 2690, 2425, -1, 2437, 2426, 2436, -1, + 2437, 2427, 2426, -1, 2437, 2428, 2427, -1, + 2437, 2438, 2432, -1, 2437, 2432, 2428, -1, + 2698, 2429, 2697, -1, 2698, 2430, 2429, -1, + 2698, 2700, 2430, -1, 2439, 2696, 2697, -1, + 2439, 2697, 2431, -1, 2439, 2431, 2432, -1, + 2439, 2432, 2438, -1, 2433, 2434, 2696, -1, + 2433, 2435, 2434, -1, 2433, 2436, 2435, -1, + 2433, 2438, 2437, -1, 2433, 2437, 2436, -1, + 2433, 2439, 2438, -1, 2433, 2696, 2439, -1, + 2440, 2441, 2447, -1, 2440, 2447, 2442, -1, + 2440, 2443, 2441, -1, 2440, 2444, 2443, -1, + 2440, 2445, 2444, -1, 2440, 2442, 2445, -1, + 2701, 2446, 2702, -1, 2701, 2843, 2446, -1, + 2704, 2702, 2447, -1, 2704, 2447, 2705, -1, + 2846, 2499, 2844, -1, 2846, 2448, 2499, -1, + 2846, 2709, 2448, -1, 2846, 2706, 2709, -1, + 2456, 2449, 2450, -1, 2456, 2450, 2455, -1, + 2456, 2451, 2449, -1, 2456, 2452, 2451, -1, + 2456, 2453, 2452, -1, 2456, 2457, 2453, -1, + 2707, 2454, 2708, -1, 2707, 2455, 2454, -1, + 2707, 2457, 2456, -1, 2707, 2456, 2455, -1, + 2707, 2705, 2458, -1, 2707, 2458, 2457, -1, + 2465, 2471, 2459, -1, 2465, 2459, 2466, -1, + 2465, 2470, 2471, -1, 2465, 2463, 2460, -1, + 2465, 2460, 2470, -1, 2461, 2462, 2463, -1, + 2461, 2464, 2462, -1, 2461, 2463, 2465, -1, + 2461, 2465, 2466, -1, 2461, 2467, 2464, -1, + 2461, 2468, 2467, -1, 2461, 2466, 2468, -1, + 2469, 2471, 2470, -1, 2469, 2472, 2471, -1, + 2469, 2473, 2474, -1, 2469, 2470, 2473, -1, + 2469, 2474, 2475, -1, 2469, 2475, 2472, -1, + 2710, 2476, 2477, -1, 2710, 2852, 2476, -1, + 2710, 2477, 2711, -1, 2478, 2479, 2721, -1, + 2478, 2721, 2480, -1, 2478, 2481, 2479, -1, + 2478, 2480, 2481, -1, 2482, 2484, 2483, -1, + 2482, 2483, 2485, -1, 2482, 2486, 2484, -1, + 2482, 2487, 2486, -1, 2482, 2488, 2487, -1, + 2482, 2485, 2488, -1, 2489, 2491, 2490, -1, + 2489, 2490, 2492, -1, 2489, 2493, 2491, -1, + 2489, 2492, 2494, -1, 2489, 2495, 2493, -1, + 2489, 2494, 2495, -1, 2496, 2497, 2498, -1, + 2496, 2499, 2497, -1, 2496, 2498, 2500, -1, + 2496, 2500, 2499, -1, 2501, 2503, 2502, -1, + 2501, 2502, 2504, -1, 2501, 2504, 2505, -1, + 2501, 2506, 2503, -1, 2501, 2505, 2506, -1, + 2514, 2507, 2508, -1, 2514, 2513, 2507, -1, + 2514, 2508, 2509, -1, 2514, 2510, 2515, -1, + 2514, 2509, 2510, -1, 2511, 2512, 2513, -1, + 2511, 2514, 2515, -1, 2511, 2513, 2514, -1, + 2511, 2515, 2516, -1, 2511, 2516, 2517, -1, + 2511, 2517, 2518, -1, 2511, 2518, 2512, -1, + 2893, 2520, 2856, -1, 2714, 2896, 2854, -1, + 2714, 2519, 2816, -1, 2714, 2816, 2813, -1, + 2714, 2857, 2519, -1, 2714, 2854, 2857, -1, + 2892, 2715, 2520, -1, 2892, 2520, 2893, -1, + 2889, 2888, 2521, -1, 2889, 2521, 2655, -1, + 2889, 2655, 2890, -1, 2522, 2523, 2524, -1, + 2522, 2525, 2523, -1, 2522, 2524, 2526, -1, + 2522, 2526, 2525, -1, 2868, 2541, 2527, -1, + 2868, 2528, 2872, -1, 2868, 2527, 2528, -1, + 2725, 2531, 2529, -1, 2725, 2529, 2724, -1, + 2726, 2727, 2530, -1, 2726, 2530, 2531, -1, + 2726, 2531, 2725, -1, 2532, 2537, 2533, -1, + 2532, 2533, 2534, -1, 2532, 2535, 2537, -1, + 2532, 2536, 2535, -1, 2532, 2534, 2536, -1, + 2723, 2538, 2537, -1, 2723, 2537, 2728, -1, + 2723, 2721, 2538, -1, 2731, 2717, 2539, -1, + 2731, 2730, 2717, -1, 2731, 2539, 2741, -1, + 2731, 2741, 2734, -1, 2732, 2733, 2541, -1, + 2732, 2868, 2869, -1, 2732, 2541, 2868, -1, + 2540, 2541, 2733, -1, 2540, 2542, 2543, -1, + 2540, 2543, 2541, -1, 2540, 2544, 2545, -1, + 2540, 2545, 2542, -1, 2540, 2546, 2544, -1, + 2540, 2733, 2546, -1, 2547, 2548, 2734, -1, + 2547, 2734, 2737, -1, 2547, 2549, 2548, -1, + 2547, 2737, 2549, -1, 2736, 2549, 2737, -1, + 2736, 2550, 2549, -1, 2736, 2551, 2550, -1, + 2736, 2742, 2552, -1, 2736, 2552, 2551, -1, + 2553, 2558, 2554, -1, 2553, 2556, 2558, -1, + 2553, 2554, 2557, -1, 2553, 2557, 2556, -1, + 2555, 2556, 2557, -1, 2555, 2558, 2556, -1, + 2555, 2557, 2559, -1, 2555, 2560, 2558, -1, + 2555, 2559, 2561, -1, 2555, 2562, 2560, -1, + 2555, 2561, 2562, -1, 2567, 2564, 2563, -1, + 2567, 2563, 2566, -1, 2567, 2753, 2564, -1, + 2567, 2580, 2753, -1, 2745, 2565, 2746, -1, + 2745, 2566, 2565, -1, 2745, 2567, 2566, -1, + 2745, 2749, 2568, -1, 2745, 2568, 2580, -1, + 2745, 2580, 2567, -1, 2571, 2572, 2569, -1, + 2571, 2569, 2570, -1, 2571, 2570, 2760, -1, + 2759, 2572, 2571, -1, 2759, 2571, 2760, -1, + 2759, 2762, 2573, -1, 2759, 2573, 2572, -1, + 2761, 2757, 2574, -1, 2761, 2574, 2762, -1, + 2575, 2576, 2577, -1, 2575, 2577, 2755, -1, + 2575, 2578, 2579, -1, 2575, 2579, 2576, -1, + 2575, 2580, 2578, -1, 2575, 2753, 2580, -1, + 2575, 2755, 2753, -1, 2581, 2583, 2582, -1, + 2581, 2584, 2583, -1, 2581, 2585, 2584, -1, + 2581, 2582, 2586, -1, 2581, 2586, 2587, -1, + 2581, 2587, 2588, -1, 2581, 2588, 2585, -1, + 2589, 2591, 2590, -1, 2589, 2592, 2591, -1, + 2589, 2590, 2593, -1, 2589, 2593, 2594, -1, + 2589, 2594, 2595, -1, 2589, 2595, 2592, -1, + 2596, 2597, 2598, -1, 2596, 2599, 2597, -1, + 2596, 2598, 2600, -1, 2596, 2600, 2599, -1, + 2766, 2601, 2770, -1, 2766, 2764, 2601, -1, + 2602, 2603, 2608, -1, 2602, 2605, 2603, -1, + 2602, 2608, 2605, -1, 2604, 2606, 2605, -1, + 2604, 2607, 2606, -1, 2604, 2608, 2607, -1, + 2604, 2605, 2608, -1, 2609, 2610, 2611, -1, + 2609, 2611, 2612, -1, 2609, 2612, 2610, -1, + 2613, 2614, 2615, -1, 2613, 2616, 2614, -1, + 2613, 2615, 2617, -1, 2613, 2617, 2618, -1, + 2613, 2618, 2619, -1, 2613, 2619, 2616, -1, + 2774, 2621, 2620, -1, 2774, 2620, 2772, -1, + 2774, 2778, 2621, -1, 2780, 2798, 2622, -1, + 2780, 2622, 2623, -1, 2780, 2623, 2781, -1, + 2634, 2625, 2624, -1, 2634, 2633, 2625, -1, + 2634, 2624, 2626, -1, 2634, 2626, 2632, -1, + 2877, 2798, 2780, -1, 2790, 2876, 2878, -1, + 2790, 2627, 2782, -1, 2790, 2628, 2627, -1, + 2790, 2878, 2628, -1, 2629, 2630, 2785, -1, + 2629, 2632, 2631, -1, 2629, 2631, 2630, -1, + 2629, 2785, 2633, -1, 2629, 2634, 2632, -1, + 2629, 2633, 2634, -1, 2787, 2635, 2792, -1, + 2787, 2785, 2635, -1, 2636, 2637, 2638, -1, + 2636, 2639, 2637, -1, 2636, 2638, 2898, -1, + 2636, 2898, 2639, -1, 2797, 2791, 2640, -1, + 2797, 2640, 2795, -1, 2797, 2798, 2877, -1, + 2641, 2643, 2642, -1, 2641, 2645, 2644, -1, + 2641, 2644, 2643, -1, 2641, 2646, 2645, -1, + 2641, 2642, 2646, -1, 2647, 2648, 2667, -1, + 2647, 2649, 2648, -1, 2647, 2650, 2649, -1, + 2647, 2667, 2666, -1, 2647, 2651, 2650, -1, + 2647, 2666, 2651, -1, 2827, 2800, 2828, -1, + 2661, 2652, 2660, -1, 2661, 2653, 2654, -1, + 2661, 2654, 2652, -1, 2661, 2662, 2653, -1, + 2885, 2884, 2676, -1, 2885, 2676, 2818, -1, + 2883, 2879, 2808, -1, 2657, 2655, 2656, -1, + 2657, 2890, 2655, -1, 2657, 2656, 2658, -1, + 2887, 2657, 2658, -1, 2887, 2890, 2657, -1, + 2887, 2659, 2918, -1, 2887, 2658, 2659, -1, + 2814, 2660, 2865, -1, 2814, 2661, 2660, -1, + 2814, 2662, 2661, -1, 2814, 2815, 2663, -1, + 2814, 2663, 2664, -1, 2814, 2664, 2662, -1, + 2665, 2666, 2667, -1, 2665, 2808, 2668, -1, + 2665, 2667, 2808, -1, 2665, 2668, 2669, -1, + 2665, 2669, 2666, -1, 2670, 2672, 2671, -1, + 2670, 2671, 2673, -1, 2670, 2674, 2672, -1, + 2670, 2673, 2674, -1, 2675, 2818, 2676, -1, + 2675, 2677, 2818, -1, 2675, 2678, 2677, -1, + 2675, 2806, 2678, -1, 2675, 2805, 2806, -1, + 2675, 2676, 2884, -1, 2675, 2884, 2805, -1, + 2900, 2811, 2899, -1, 2819, 2823, 2902, -1, + 2819, 2902, 2885, -1, 2819, 2898, 2823, -1, + 2824, 2916, 2811, -1, 2824, 2811, 2900, -1, + 2826, 2679, 2803, -1, 2826, 2803, 2827, -1, + 2826, 2898, 2679, -1, 2833, 2680, 2681, -1, + 2833, 2681, 2831, -1, 2833, 2898, 2680, -1, + 2840, 2841, 2836, -1, 2682, 2684, 2683, -1, + 2682, 2683, 2685, -1, 2682, 2686, 2684, -1, + 2682, 2685, 2686, -1, 2687, 2688, 2689, -1, + 2687, 2689, 2690, -1, 2687, 2690, 2691, -1, + 2687, 2692, 2688, -1, 2687, 2693, 2692, -1, + 2687, 2694, 2693, -1, 2687, 2691, 2694, -1, + 2695, 2697, 2696, -1, 2695, 2698, 2697, -1, + 2695, 2696, 2699, -1, 2695, 2699, 2700, -1, + 2695, 2700, 2698, -1, 2845, 2843, 2701, -1, + 2845, 2706, 2846, -1, 2845, 2701, 2702, -1, + 2845, 2702, 2704, -1, 2703, 2704, 2705, -1, + 2703, 2706, 2845, -1, 2703, 2845, 2704, -1, + 2703, 2705, 2707, -1, 2703, 2707, 2708, -1, + 2703, 2708, 2709, -1, 2703, 2709, 2706, -1, + 2848, 2710, 2711, -1, 2848, 2711, 2712, -1, + 2848, 2712, 2713, -1, 2848, 2713, 2849, -1, + 2848, 2852, 2710, -1, 2716, 2896, 2714, -1, + 2716, 2813, 2864, -1, 2716, 2714, 2813, -1, + 2862, 2861, 2715, -1, 2862, 2715, 2892, -1, + 2862, 2892, 2898, -1, 2895, 2896, 2716, -1, + 2895, 2716, 2864, -1, 2870, 2730, 2869, -1, + 2870, 2718, 2717, -1, 2870, 2717, 2730, -1, + 2870, 2719, 2718, -1, 2870, 2873, 2719, -1, + 2720, 2722, 2721, -1, 2720, 2721, 2723, -1, + 2720, 2724, 2722, -1, 2720, 2725, 2724, -1, + 2720, 2727, 2726, -1, 2720, 2726, 2725, -1, + 2720, 2728, 2727, -1, 2720, 2723, 2728, -1, + 2729, 2869, 2730, -1, 2729, 2730, 2731, -1, + 2729, 2732, 2869, -1, 2729, 2733, 2732, -1, + 2729, 2734, 2733, -1, 2729, 2731, 2734, -1, + 2740, 2742, 2736, -1, 2735, 2736, 2737, -1, + 2735, 2739, 2738, -1, 2735, 2740, 2736, -1, + 2735, 2741, 2739, -1, 2735, 2737, 2741, -1, + 2735, 2742, 2740, -1, 2735, 2743, 2742, -1, + 2735, 2738, 2743, -1, 2744, 2745, 2746, -1, + 2744, 2748, 2747, -1, 2744, 2746, 2748, -1, + 2744, 2749, 2745, -1, 2744, 2750, 2749, -1, + 2744, 2747, 2750, -1, 2756, 2761, 2760, -1, + 2756, 2751, 2754, -1, 2756, 2760, 2751, -1, + 2752, 2754, 2753, -1, 2752, 2753, 2755, -1, + 2752, 2756, 2754, -1, 2752, 2761, 2756, -1, + 2752, 2755, 2757, -1, 2752, 2757, 2761, -1, + 2758, 2759, 2760, -1, 2758, 2760, 2761, -1, + 2758, 2762, 2759, -1, 2758, 2761, 2762, -1, + 2763, 2765, 2764, -1, 2763, 2764, 2766, -1, + 2763, 2767, 2765, -1, 2763, 2768, 2767, -1, + 2763, 2769, 2768, -1, 2763, 2770, 2769, -1, + 2763, 2766, 2770, -1, 2771, 2772, 2773, -1, + 2771, 2774, 2772, -1, 2771, 2775, 2776, -1, + 2771, 2773, 2775, -1, 2771, 2776, 2777, -1, + 2771, 2777, 2778, -1, 2771, 2778, 2774, -1, + 2779, 2878, 2877, -1, 2779, 2877, 2780, -1, + 2779, 2781, 2878, -1, 2779, 2780, 2781, -1, + 2789, 2790, 2782, -1, 2789, 2782, 2783, -1, + 2789, 2783, 2788, -1, 2784, 2786, 2785, -1, + 2784, 2785, 2787, -1, 2784, 2792, 2876, -1, + 2784, 2787, 2792, -1, 2784, 2788, 2786, -1, + 2784, 2789, 2788, -1, 2784, 2876, 2790, -1, + 2784, 2790, 2789, -1, 2875, 2791, 2797, -1, + 2875, 2792, 2793, -1, 2875, 2793, 2791, -1, + 2875, 2876, 2792, -1, 2875, 2797, 2877, -1, + 2794, 2795, 2796, -1, 2794, 2797, 2795, -1, + 2794, 2796, 2798, -1, 2794, 2798, 2797, -1, + 2799, 2800, 2827, -1, 2799, 2801, 2800, -1, + 2799, 2802, 2801, -1, 2799, 2803, 2802, -1, + 2799, 2827, 2803, -1, 2804, 2805, 2884, -1, + 2804, 2884, 2883, -1, 2804, 2807, 2806, -1, + 2804, 2806, 2805, -1, 2804, 2808, 2807, -1, + 2804, 2883, 2808, -1, 2915, 2809, 2882, -1, + 2915, 2810, 2809, -1, 2915, 2914, 2810, -1, + 2907, 2915, 2882, -1, 2907, 2912, 2915, -1, + 2923, 2811, 2916, -1, 2923, 2899, 2811, -1, + 2812, 2865, 2813, -1, 2812, 2814, 2865, -1, + 2812, 2815, 2814, -1, 2812, 2816, 2815, -1, + 2812, 2813, 2816, -1, 2901, 2902, 2823, -1, + 2901, 2823, 2900, -1, 2817, 2885, 2818, -1, + 2817, 2819, 2885, -1, 2817, 2818, 2898, -1, + 2817, 2898, 2819, -1, 2820, 2916, 2824, -1, + 2820, 2821, 2888, -1, 2820, 2888, 2916, -1, + 2820, 2898, 2821, -1, 2820, 2824, 2898, -1, + 2822, 2823, 2898, -1, 2822, 2898, 2824, -1, + 2822, 2900, 2823, -1, 2822, 2824, 2900, -1, + 2825, 2826, 2827, -1, 2825, 2828, 2829, -1, + 2825, 2827, 2828, -1, 2825, 2829, 2898, -1, + 2825, 2898, 2826, -1, 2830, 2831, 2832, -1, + 2830, 2833, 2831, -1, 2830, 2832, 2898, -1, + 2830, 2898, 2833, -1, 2834, 2835, 2838, -1, + 2834, 2838, 2840, -1, 2834, 2836, 2835, -1, + 2834, 2840, 2836, -1, 2837, 2838, 2839, -1, + 2837, 2840, 2838, -1, 2837, 2839, 2841, -1, + 2837, 2841, 2840, -1, 2842, 2844, 2843, -1, + 2842, 2843, 2845, -1, 2842, 2846, 2844, -1, + 2842, 2845, 2846, -1, 2847, 2848, 2849, -1, + 2847, 2849, 2850, -1, 2847, 2850, 2851, -1, + 2847, 2851, 2852, -1, 2847, 2852, 2848, -1, + 2853, 2854, 2896, -1, 2853, 2896, 2858, -1, + 2853, 2856, 2855, -1, 2853, 2893, 2856, -1, + 2853, 2858, 2893, -1, 2853, 2855, 2857, -1, + 2853, 2857, 2854, -1, 2897, 2893, 2858, -1, + 2897, 2858, 2896, -1, 2859, 2860, 2861, -1, + 2859, 2861, 2862, -1, 2859, 2898, 2860, -1, + 2859, 2862, 2898, -1, 2863, 2895, 2864, -1, + 2863, 2865, 2866, -1, 2863, 2864, 2865, -1, + 2863, 2866, 2898, -1, 2863, 2898, 2895, -1, + 2867, 2869, 2868, -1, 2867, 2870, 2869, -1, + 2867, 2872, 2871, -1, 2867, 2868, 2872, -1, + 2867, 2871, 2873, -1, 2867, 2873, 2870, -1, + 2874, 2876, 2875, -1, 2874, 2875, 2877, -1, + 2874, 2878, 2876, -1, 2874, 2877, 2878, -1, + 2909, 2880, 2879, -1, 2909, 2881, 2880, -1, + 2909, 2882, 2881, -1, 2909, 2907, 2882, -1, + 2909, 2879, 2883, -1, 2909, 2883, 2905, -1, + 2904, 2883, 2884, -1, 2904, 2905, 2883, -1, + 2904, 2884, 2885, -1, 2904, 2885, 2902, -1, + 2904, 2902, 2906, -1, 2911, 2899, 2913, -1, + 2911, 2912, 2907, -1, 2927, 2919, 2886, -1, + 2927, 2886, 2914, -1, 2917, 2887, 2918, -1, + 2917, 2890, 2887, -1, 2925, 2916, 2888, -1, + 2925, 2888, 2889, -1, 2925, 2889, 2890, -1, + 2925, 2890, 2917, -1, 2922, 2913, 2899, -1, + 2922, 2899, 2923, -1, 2891, 2892, 2893, -1, + 2891, 2893, 2897, -1, 2891, 2898, 2892, -1, + 2891, 2897, 2898, -1, 2894, 2896, 2895, -1, + 2894, 2897, 2896, -1, 2894, 2895, 2898, -1, + 2894, 2898, 2897, -1, 2908, 2899, 2911, -1, + 2908, 2900, 2899, -1, 2908, 2901, 2900, -1, + 2908, 2906, 2902, -1, 2908, 2902, 2901, -1, + 2903, 2905, 2904, -1, 2903, 2904, 2906, -1, + 2903, 2911, 2907, -1, 2903, 2906, 2908, -1, + 2903, 2908, 2911, -1, 2903, 2909, 2905, -1, + 2903, 2907, 2909, -1, 2910, 2912, 2911, -1, + 2910, 2911, 2913, -1, 2910, 2927, 2914, -1, + 2910, 2913, 2922, -1, 2910, 2922, 2927, -1, + 2910, 2914, 2915, -1, 2910, 2915, 2912, -1, + 2924, 2923, 2916, -1, 2924, 2916, 2925, -1, + 2926, 2925, 2917, -1, 2926, 2918, 2929, -1, + 2926, 2917, 2918, -1, 2928, 2919, 2927, -1, + 2928, 2920, 2919, -1, 2928, 2929, 2920, -1, + 2921, 2922, 2923, -1, 2921, 2923, 2924, -1, + 2921, 2924, 2925, -1, 2921, 2925, 2926, -1, + 2921, 2927, 2922, -1, 2921, 2928, 2927, -1, + 2921, 2926, 2929, -1, 2921, 2929, 2928, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link7.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link7.wrl new file mode 100644 index 0000000..88598d7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-link7.wrl @@ -0,0 +1,455 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.025 0.0035000001 0.078000002, + 0.017208399 -0.0142146 0.078000002, + -0.028000001 0.00050000002 0.078000002, + -0.031500001 0.00050000002 0.078000002, + -0.00109933 -0.030980799 0.078000002, + -0.016219201 -0.0247376 0.046999998, + -0.035052299 -0.018770101 0.057, + -0.0287848 -0.0079519805 0.046999998, + -0.035052299 -0.018770101 0.061999999, + -0.038743299 -0.0094475998 0.061999999, + -0.0371911 -0.014225 0.057, + -0.038743299 -0.0094475998 0.057, + -0.039684601 -0.0045133298 0.061999999, + -0.0311934 -0.0038839499 0.078000002, + -0.0025116201 -0.0394211 0.057, + -0.0042694402 -0.029194601 0.046999998, + -0.0084519796 -0.028284799 0.046999998, + 0.025497001 -0.030320499 0.061999999, + 0.0213388 -0.022570601 0.078000002, + 0.0240729 0.0033531699 0.078000002, + 0.0203507 0.0195396 0.078000002, + 0.0214331 0.034273099 0.061999999, + 0.0170312 0.0366931 0.061999999, + 0.0214331 0.034273099 0.057, + 0.0170312 0.0366931 0.057, + 0.0256724 -0.0177138 0.078000002, + 0.022659199 -0.0213817 0.078000002, + 0.0301551 -0.0083388304 0.078000002, + 0.0308116 -0.00604922 0.078000002, + 0.032360699 -0.023011399 0.061999999, + 0.025483999 -0.0180152 0.078000002, + 0.0291587 -0.0268819 0.061999999, + 0.035052299 -0.018770101 0.057, + 0.032360699 -0.023011399 0.057, + 0.0123607 0.0385423 0.057, + 0.0124625 0.027789 0.046999998, + 0.0123607 -0.037542298 0.057, + 0.019645801 0.0231725 0.046999998, + 0.016219201 0.0257376 0.046999998, + 0.025497001 0.031320501 0.057, + -0.00109933 0.031980801 0.078000002, + -0.0302229 -0.0083388304 0.078000002, + -0.0302797 -0.0081825797 0.078000002, + -0.0371911 -0.014225 0.061999999, + -0.0287767 -0.0123122 0.078000002, + 0.00176336 -0.0220729 0.078000002, + -0.019799 -0.0150563 0.078000002, + 0.019393301 -0.024322299 0.078000002, + 0.0155563 -0.0150563 0.078000002, + 0.0074952501 -0.0387915 0.061999999, + 0.00329265 -0.030827399 0.078000002, + 0.0025116201 -0.0394211 0.061999999, + -0.0226725 -0.0191458 0.046999998, + -0.0124625 -0.026789 0.046999998, + -0.019645801 -0.022172499 0.046999998, + -0.025237599 -0.0157192 0.046999998, + -0.0296946 -0.0037694499 0.046999998, + -0.0296946 0.0047694398 0.046999998, + -0.0287848 0.0089519797 0.046999998, + -0.039999999 0.00050000002 0.057, + -0.039684601 -0.0045133298 0.057, + -0.039999999 0.00050000002 0.061999999, + -0.029999999 0.00050000002 0.046999998, + -0.0025116201 -0.0394211 0.061999999, + -0.0074952501 -0.0387915 0.057, + 0.018213799 0.0261179 0.078000002, + 0.01575 0.027779801 0.078000002, + 0.0213388 0.023570601 0.078000002, + 0.019393301 0.025322299 0.078000002, + 0.0256724 0.0187138 0.078000002, + -0.0371911 0.015225 0.057, + -0.0214331 0.034273099 0.061999999, + -0.038743299 0.0104476 0.057, + -0.039684601 0.00551333 0.061999999, + -0.039684601 0.00551333 0.057, + 0.0371911 -0.014225 0.061999999, + 0.035052299 -0.018770101 0.061999999, + 0.038743299 -0.0094475998 0.061999999, + 0.0296003 -0.0102736 0.078000002, + 0.027812799 -0.0142884 0.078000002, + 0.0301551 0.0093388297 0.078000002, + 0.0371911 0.015225 0.061999999, + 0.0296003 0.0112736 0.078000002, + 0.027812799 0.0152884 0.078000002, + 0.0308116 0.0070492201 0.078000002, + 0.038743299 0.0104476 0.061999999, + 0.0042694402 -0.029194601 0.046999998, + 0.0074952501 -0.0387915 0.057, + 0.0025116201 -0.0394211 0.057, + 0.0124625 -0.026789 0.046999998, + 0.019645801 -0.022172499 0.046999998, + 0.0226725 -0.0191458 0.046999998, + 0.0084519796 -0.028284799 0.046999998, + 0.016219201 -0.0247376 0.046999998, + 0.025497001 -0.030320499 0.057, + 0.0291587 -0.0268819 0.057, + 0.035052299 0.019770101 0.057, + 0.025237599 0.0167192 0.046999998, + 0.0074952501 0.039791498 0.061999999, + 0.00329265 0.031827401 0.078000002, + -0.0025116201 0.040421098 0.061999999, + 0.0088388296 0.030668501 0.078000002, + 0.0123607 0.0385423 0.061999999, + 0.0118001 0.029706299 0.078000002, + 0.00762054 0.0310643 0.078000002, + -0.0203507 -0.0185396 0.078000002, + -0.0054699201 -0.0305214 0.078000002, + -0.0123607 -0.037542298 0.057, + -0.018213799 -0.025146499 0.078000002, + -0.0291587 -0.0268819 0.061999999, + -0.021077599 -0.022909099 0.078000002, + -0.0291587 -0.0268819 0.057, + -0.032360699 -0.023011399 0.057, + -0.025608201 -0.0177138 0.078000002, + -0.0267135 -0.0161925 0.078000002, + -0.032360699 -0.023011399 0.061999999, + -0.0241304 -0.019747799 0.078000002, + -0.0088388296 0.0306815 0.078000002, + -0.0138087 0.028812001 0.078000002, + -0.0097340401 0.030458299 0.078000002, + -0.0074952501 0.039791498 0.061999999, + -0.0054699201 0.031521399 0.078000002, + 0.025497001 0.031320501 0.061999999, + -0.0170312 0.0366931 0.061999999, + -0.0123607 0.0385423 0.061999999, + -0.0287767 0.0133122 0.078000002, + -0.032360699 0.0240114 0.057, + -0.035052299 0.019770101 0.057, + -0.025237599 0.0167192 0.046999998, + -0.035052299 0.019770101 0.061999999, + -0.0302797 0.0091825798 0.078000002, + -0.0302229 0.0093388297 0.078000002, + -0.0311934 0.0048839501 0.078000002, + -0.038743299 0.0104476 0.061999999, + -0.0371911 0.015225 0.061999999, + 0.039999999 0.00050000002 0.061999999, + 0.039684601 0.00551333 0.061999999, + 0.031423301 0.00269733 0.078000002, + 0.031423301 -0.00169733 0.078000002, + 0.039684601 -0.0045133298 0.061999999, + 0.0084519796 0.029284799 0.046999998, + 0.0371911 0.015225 0.057, + 0.0025116201 0.040421098 0.057, + 0.0025116201 0.040421098 0.061999999, + 0.0074952501 0.039791498 0.057, + 0.0042694402 0.030194599 0.046999998, + -0.0097340401 -0.029458299 0.078000002, + -0.0088388296 -0.0296815 0.078000002, + -0.0123607 -0.037542298 0.061999999, + -0.0074952501 -0.0387915 0.061999999, + -0.0214331 -0.033273101 0.061999999, + -0.0138087 -0.027812 0.078000002, + -0.017614599 -0.025614699 0.078000002, + -0.0170312 -0.035693102 0.061999999, + -0.025497001 -0.030320499 0.061999999, + -0.025497001 -0.030320499 0.057, + -0.0214331 -0.033273101 0.057, + -0.0170312 -0.035693102 0.057, + 0.0088388296 -0.029668501 0.078000002, + 0.00762054 -0.0300643 0.078000002, + 0.0170312 -0.035693102 0.061999999, + 0.0118001 -0.028706299 0.078000002, + 0.0123607 -0.037542298 0.061999999, + 0.0170312 -0.035693102 0.057, + 0.01575 -0.026779801 0.078000002, + 0.0214331 -0.033273101 0.061999999, + 0.0214331 -0.033273101 0.057, + 0.0231148 0.021838799 0.078000002, + 0.022659199 0.022381701 0.078000002, + 0.032360699 0.0240114 0.061999999, + 0.025483999 0.0190152 0.078000002, + 0.035052299 0.019770101 0.061999999, + 0.0291587 0.0278819 0.061999999, + 0.032360699 0.0240114 0.057, + 0.0291587 0.0278819 0.057, + -0.025608201 0.0187138 0.078000002, + -0.032360699 0.0240114 0.061999999, + -0.0291587 0.0278819 0.061999999, + -0.025497001 0.031320501 0.061999999, + -0.0074952501 0.039791498 0.057, + -0.0025116201 0.040421098 0.057, + -0.0123607 0.0385423 0.057, + -0.0084519796 0.029284799 0.046999998, + -0.0042694402 0.030194599 0.046999998, + 0.038743299 0.0104476 0.057, + 0.0287848 0.0089519797 0.046999998, + -0.023076801 0.021838799 0.078000002, + -0.021077599 0.023909099 0.078000002, + -0.017614599 0.0266147 0.078000002, + -0.0241304 0.020747799 0.078000002, + -0.0267135 0.0171925 0.078000002, + -0.0170312 0.0366931 0.057, + -0.0214331 0.034273099 0.057, + -0.0124625 0.027789 0.046999998, + -0.027288999 0.0129625 0.046999998, + -0.027288999 -0.0119625 0.046999998, + 0.039684601 0.00551333 0.057, + 0.039999999 0.00050000002 0.057, + -0.019645801 0.0231725 0.046999998, + -0.0226725 0.0201458 0.046999998, + -0.025497001 0.031320501 0.057, + -0.0291587 0.0278819 0.057, + 0.039684601 -0.0045133298 0.057, + 0.029999999 0.00050000002 0.046999998, + 0.025237599 -0.0157192 0.046999998, + 5.0128144e-012 0.0305 0.046999998, + 0.0226725 0.0201458 0.046999998, + 0.0296946 0.0047694398 0.046999998, + -0.016219201 0.0257376 0.046999998, + 0.027288999 0.0129625 0.046999998, + -3.8160434e-012 -0.0295 0.046999998, + 0.0287848 -0.0079519805 0.046999998, + 0.0296946 -0.0037694499 0.046999998, + 0.038743299 -0.0094475998 0.057, + 0.027288999 -0.0119625 0.046999998, + 0.0371911 -0.014225 0.057 ] + + } + coordIndex [ 0, 46, 20, -1, 188, 0, 20, -1, + 3, 61, 12, -1, 48, 20, 46, -1, + 2, 46, 0, -1, 2, 188, 125, -1, + 2, 0, 188, -1, 103, 188, 20, -1, + 69, 103, 20, -1, 13, 2, 125, -1, + 13, 3, 12, -1, 155, 111, 54, -1, + 14, 210, 88, -1, 50, 4, 51, -1, + 89, 163, 36, -1, 8, 6, 115, -1, + 8, 115, 114, -1, 112, 115, 6, -1, + 1, 47, 20, -1, 1, 20, 48, -1, + 1, 48, 47, -1, 63, 51, 4, -1, + 63, 4, 106, -1, 63, 88, 51, -1, + 63, 14, 88, -1, 18, 26, 47, -1, + 121, 188, 103, -1, 121, 99, 40, -1, + 121, 40, 100, -1, 84, 138, 137, -1, + 66, 103, 69, -1, 66, 22, 103, -1, + 28, 138, 78, -1, 120, 121, 100, -1, + 178, 200, 201, -1, 178, 192, 200, -1, + 73, 61, 3, -1, 77, 213, 202, -1, + 33, 95, 91, -1, 171, 141, 96, -1, + 171, 96, 173, -1, 23, 38, 24, -1, + 23, 39, 38, -1, 23, 122, 39, -1, + 35, 34, 24, -1, 35, 24, 38, -1, + 204, 33, 91, -1, 204, 214, 32, -1, + 204, 32, 33, -1, 102, 24, 34, -1, + 102, 22, 24, -1, 102, 34, 144, -1, + 102, 103, 22, -1, 44, 13, 42, -1, + 44, 2, 13, -1, 44, 46, 2, -1, + 44, 43, 8, -1, 44, 8, 114, -1, + 105, 46, 44, -1, 105, 44, 114, -1, + 108, 105, 114, -1, 132, 13, 125, -1, + 132, 3, 13, -1, 132, 73, 3, -1, + 159, 106, 4, -1, 159, 4, 50, -1, + 159, 105, 106, -1, 159, 46, 105, -1, + 162, 87, 36, -1, 162, 36, 163, -1, + 5, 157, 156, -1, 5, 155, 54, -1, + 5, 156, 155, -1, 15, 210, 14, -1, + 53, 195, 210, -1, 53, 5, 54, -1, + 53, 210, 15, -1, 53, 15, 16, -1, + 53, 157, 5, -1, 53, 107, 157, -1, + 53, 16, 107, -1, 194, 58, 70, -1, + 55, 6, 195, -1, 55, 112, 6, -1, + 60, 12, 61, -1, 60, 56, 11, -1, + 7, 56, 195, -1, 7, 11, 56, -1, + 10, 195, 6, -1, 10, 7, 195, -1, + 10, 11, 7, -1, 10, 8, 43, -1, + 10, 6, 8, -1, 9, 43, 42, -1, + 9, 10, 43, -1, 9, 11, 10, -1, + 9, 12, 60, -1, 9, 60, 11, -1, + 9, 42, 13, -1, 9, 13, 12, -1, + 64, 14, 63, -1, 64, 15, 14, -1, + 64, 107, 16, -1, 64, 16, 15, -1, + 17, 94, 95, -1, 17, 95, 31, -1, + 17, 165, 166, -1, 17, 166, 94, -1, + 17, 47, 165, -1, 17, 18, 47, -1, + 17, 26, 18, -1, 17, 31, 26, -1, + 119, 120, 124, -1, 19, 47, 84, -1, + 19, 84, 69, -1, 19, 20, 47, -1, + 19, 69, 20, -1, 79, 84, 47, -1, + 79, 47, 26, -1, 79, 78, 138, -1, + 79, 138, 84, -1, 79, 25, 76, -1, + 83, 84, 82, -1, 83, 69, 84, -1, + 83, 171, 69, -1, 21, 66, 68, -1, + 21, 68, 122, -1, 21, 22, 66, -1, + 21, 122, 23, -1, 21, 24, 22, -1, + 21, 23, 24, -1, 30, 76, 25, -1, + 30, 26, 31, -1, 30, 79, 26, -1, + 30, 25, 79, -1, 179, 120, 100, -1, + 179, 124, 120, -1, 123, 119, 124, -1, + 72, 70, 58, -1, 72, 57, 74, -1, + 72, 58, 57, -1, 72, 134, 70, -1, + 215, 213, 77, -1, 215, 32, 214, -1, + 215, 76, 32, -1, 27, 28, 78, -1, + 27, 78, 77, -1, 27, 77, 28, -1, + 139, 202, 197, -1, 139, 77, 202, -1, + 139, 138, 28, -1, 139, 28, 77, -1, + 29, 76, 30, -1, 29, 30, 31, -1, + 29, 32, 76, -1, 29, 33, 32, -1, + 29, 31, 95, -1, 29, 95, 33, -1, + 85, 196, 184, -1, 85, 184, 141, -1, + 140, 144, 34, -1, 140, 34, 35, -1, + 140, 35, 38, -1, 140, 38, 206, -1, + 92, 210, 204, -1, 92, 89, 36, -1, + 92, 36, 87, -1, 174, 173, 206, -1, + 174, 39, 122, -1, 37, 38, 39, -1, + 37, 206, 38, -1, 37, 39, 174, -1, + 37, 174, 206, -1, 97, 173, 96, -1, + 97, 206, 173, -1, 143, 40, 99, -1, + 143, 100, 40, -1, 104, 99, 121, -1, + 104, 121, 103, -1, 41, 42, 43, -1, + 41, 43, 44, -1, 41, 44, 42, -1, + 151, 108, 152, -1, 116, 108, 114, -1, + 131, 125, 134, -1, 131, 132, 125, -1, + 164, 165, 47, -1, 164, 47, 159, -1, + 45, 46, 159, -1, 45, 159, 47, -1, + 45, 48, 46, -1, 45, 47, 48, -1, + 49, 162, 159, -1, 49, 50, 51, -1, + 49, 159, 50, -1, 49, 87, 162, -1, + 49, 51, 88, -1, 49, 88, 87, -1, + 52, 53, 54, -1, 52, 195, 53, -1, + 52, 55, 195, -1, 52, 54, 111, -1, + 52, 111, 112, -1, 52, 112, 55, -1, + 62, 194, 195, -1, 62, 195, 56, -1, + 62, 57, 58, -1, 62, 58, 194, -1, + 62, 56, 60, -1, 62, 74, 57, -1, + 128, 199, 194, -1, 59, 60, 61, -1, + 59, 61, 73, -1, 59, 73, 74, -1, + 59, 74, 62, -1, 59, 62, 60, -1, + 149, 63, 106, -1, 149, 64, 63, -1, + 149, 107, 64, -1, 149, 148, 107, -1, + 118, 119, 123, -1, 65, 66, 69, -1, + 65, 69, 168, -1, 65, 68, 66, -1, + 65, 168, 68, -1, 67, 122, 68, -1, + 67, 68, 168, -1, 67, 168, 122, -1, + 170, 69, 171, -1, 170, 168, 69, -1, + 181, 124, 179, -1, 177, 178, 201, -1, + 127, 70, 134, -1, 127, 194, 70, -1, + 127, 128, 194, -1, 190, 125, 188, -1, + 71, 192, 178, -1, 71, 123, 192, -1, + 71, 178, 188, -1, 71, 188, 118, -1, + 71, 118, 123, -1, 133, 134, 72, -1, + 133, 74, 73, -1, 133, 72, 74, -1, + 133, 73, 132, -1, 75, 76, 215, -1, + 75, 215, 77, -1, 75, 77, 78, -1, + 75, 79, 76, -1, 75, 78, 79, -1, + 80, 82, 84, -1, 80, 85, 82, -1, + 80, 84, 85, -1, 81, 82, 85, -1, + 81, 83, 82, -1, 81, 171, 83, -1, + 81, 141, 171, -1, 81, 85, 141, -1, + 136, 84, 137, -1, 136, 85, 84, -1, + 136, 196, 85, -1, 136, 197, 196, -1, + 205, 140, 206, -1, 86, 210, 92, -1, + 86, 92, 87, -1, 86, 88, 210, -1, + 86, 87, 88, -1, 93, 89, 92, -1, + 93, 94, 166, -1, 93, 163, 89, -1, + 93, 166, 163, -1, 90, 204, 91, -1, + 90, 92, 204, -1, 90, 93, 92, -1, + 90, 94, 93, -1, 90, 91, 95, -1, + 90, 95, 94, -1, 209, 96, 141, -1, + 209, 97, 96, -1, 209, 206, 97, -1, + 98, 102, 144, -1, 98, 144, 143, -1, + 98, 104, 102, -1, 98, 143, 99, -1, + 98, 99, 104, -1, 180, 179, 100, -1, + 180, 100, 143, -1, 101, 103, 102, -1, + 101, 104, 103, -1, 101, 102, 104, -1, + 147, 108, 151, -1, 147, 106, 105, -1, + 147, 105, 108, -1, 147, 149, 106, -1, + 153, 157, 107, -1, 153, 107, 148, -1, + 110, 108, 116, -1, 110, 154, 152, -1, + 110, 152, 108, -1, 109, 116, 115, -1, + 109, 154, 110, -1, 109, 110, 116, -1, + 109, 155, 154, -1, 109, 111, 155, -1, + 109, 112, 111, -1, 109, 115, 112, -1, + 113, 114, 115, -1, 113, 115, 116, -1, + 113, 116, 114, -1, 161, 164, 159, -1, + 117, 119, 118, -1, 117, 121, 120, -1, + 117, 120, 119, -1, 117, 188, 121, -1, + 117, 118, 188, -1, 172, 122, 168, -1, + 172, 174, 122, -1, 191, 123, 124, -1, + 191, 124, 181, -1, 191, 192, 123, -1, + 129, 127, 134, -1, 129, 190, 176, -1, + 129, 134, 125, -1, 129, 125, 190, -1, + 126, 177, 201, -1, 126, 176, 177, -1, + 126, 128, 127, -1, 126, 129, 176, -1, + 126, 127, 129, -1, 126, 201, 199, -1, + 126, 199, 128, -1, 189, 177, 176, -1, + 130, 132, 131, -1, 130, 133, 132, -1, + 130, 131, 134, -1, 130, 134, 133, -1, + 135, 136, 137, -1, 135, 137, 138, -1, + 135, 138, 139, -1, 135, 139, 197, -1, + 135, 197, 136, -1, 145, 144, 140, -1, + 145, 140, 205, -1, 182, 181, 179, -1, + 185, 141, 184, -1, 185, 209, 141, -1, + 142, 143, 144, -1, 142, 180, 143, -1, + 142, 205, 180, -1, 142, 144, 145, -1, + 142, 145, 205, -1, 146, 147, 151, -1, + 146, 153, 148, -1, 146, 151, 153, -1, + 146, 148, 149, -1, 146, 149, 147, -1, + 150, 151, 152, -1, 150, 153, 151, -1, + 150, 152, 154, -1, 150, 154, 155, -1, + 150, 155, 156, -1, 150, 156, 157, -1, + 150, 157, 153, -1, 158, 159, 162, -1, + 158, 161, 159, -1, 158, 162, 161, -1, + 160, 161, 162, -1, 160, 162, 163, -1, + 160, 165, 164, -1, 160, 164, 161, -1, + 160, 163, 166, -1, 160, 166, 165, -1, + 167, 168, 170, -1, 167, 172, 168, -1, + 167, 170, 172, -1, 169, 170, 171, -1, + 169, 172, 170, -1, 169, 171, 173, -1, + 169, 173, 174, -1, 169, 174, 172, -1, + 175, 176, 190, -1, 175, 189, 176, -1, + 175, 190, 189, -1, 187, 178, 177, -1, + 187, 177, 189, -1, 187, 188, 178, -1, + 183, 182, 179, -1, 183, 179, 180, -1, + 183, 180, 205, -1, 193, 191, 181, -1, + 193, 181, 182, -1, 193, 182, 183, -1, + 193, 183, 205, -1, 207, 184, 196, -1, + 207, 185, 184, -1, 207, 209, 185, -1, + 186, 188, 187, -1, 186, 187, 189, -1, + 186, 190, 188, -1, 186, 189, 190, -1, + 208, 192, 191, -1, 208, 191, 193, -1, + 208, 200, 192, -1, 208, 194, 199, -1, + 208, 195, 194, -1, 208, 210, 195, -1, + 208, 193, 205, -1, 203, 196, 197, -1, + 203, 207, 196, -1, 203, 197, 202, -1, + 198, 208, 199, -1, 198, 200, 208, -1, + 198, 199, 201, -1, 198, 201, 200, -1, + 212, 202, 213, -1, 212, 203, 202, -1, + 212, 214, 204, -1, 212, 205, 206, -1, + 212, 207, 203, -1, 212, 208, 205, -1, + 212, 206, 209, -1, 212, 209, 207, -1, + 212, 204, 210, -1, 212, 210, 208, -1, + 211, 212, 213, -1, 211, 214, 212, -1, + 211, 213, 215, -1, 211, 215, 214, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-lwr4-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-lwr4-right.wrl new file mode 100644 index 0000000..1f612ee --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-lwr4-right.wrl @@ -0,0 +1,83 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF link0 Transform { + children [ + Inline { + url "link0-right.wrl" + } + Transform { + translation 0.05 0 0.03 + children [ + Shape { + appearance Appearance { + material Material { + } + } + geometry Box { + size 0.1 0.1 0.06 + } + } + ] + } + ] + } + DEF link1 Transform { + rotation 1 0 0 1.570796 + translation 0 0 0.31 + children [ + Inline { + url "link1-right.wrl" + } + ] + } + DEF link2 Transform { + translation 0 0 0.31 + children [ + Inline { + url "link2-right.wrl" + } + ] + } + DEF link3 Transform { + rotation 1 0 0 -1.570796 + translation 0 0 0.71 + children [ + Inline { + url "link3-right.wrl" + } + ] + } + DEF link4 Transform { + translation 0 0 0.71 + children [ + Inline { + url "link4-right.wrl" + } + ] + } + DEF link5 Transform { + rotation 1 0 0 1.570796 + translation 0 0 1.1 + children [ + Inline { + url "link5-right.wrl" + } + ] + } + DEF link6 Transform { + translation 0 0 1.1 + children [ + Inline { + url "link6-right.wrl" + } + ] + } DEF link7 Transform { + translation 0 0 1.1 + children [ + Inline { + url "link7-right.wrl" + } + ] + } ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-swiwel.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-swiwel.wrl new file mode 100644 index 0000000..d60b98b --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/kuka-swiwel.wrl @@ -0,0 +1,479 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.056213904 -0.020976201 0.119, + -0.070977002 -0.016730102 3.9378813e-012, + -0.070213303 -0.0199774 3.9095558e-012, + -0.028153701 0.041320302 0.119, + 0.071871698 -0.012591501 -5.2022206e-012, + -0.0199774 0.070213303 -1.5665737e-012, + -0.016575301 0.057665005 0.119, + 0.036642503 -0.034019504 0.119, + -0.056033403 -0.046668001 -3.5770198e-012, + -0.047172103 -0.037078202 0.119, + 0.019903 0.056602802 0.119, + -0.00602694 0.072721399 1.0694802e-012, + -0.0044293702 0.059836302 0.119, + -0.053759106 -0.026645001 0.119, + -0.048300102 -0.012926601 0.119, + -0.037908301 -0.0326031 0.119, + -0.045822203 0.020008201 0.119, + -0.0378718 -0.062376503 2.6590856e-012, + -0.033661801 -0.049667705 0.119, + -0.038429502 -0.062065803 3.947398e-012, + -0.041884605 -0.059699103 5.7574952e-012, + 0.059702404 0.0059685605 0.119, + 0.072688602 0.0067355903 2.3853254e-012, + 0.039893102 0.061063305 3.5121764e-012, + 0.0439923 0.0582553 -1.7502679e-012, + 0.051137004 0.051990505 5.8210381e-012, + 0.036174003 0.047869001 0.119, + 0.057219204 0.018054601 0.119, + 0.055059504 0.023842201 0.119, + 0.0727771 -0.0048216903 2.9971134e-012, + 0.073000006 3.4749131e-012 -3.7486763e-012, + 0.072286598 -0.0096175708 1.6362103e-012, + 0.072688602 -0.0067355903 2.3561294e-012, + 0.071529604 0.0143806 2.708924e-012, + 0.058772303 0.0120756 0.119, + 0.057575405 -0.044811103 -3.6366669e-012, + 0.053947702 -0.0491798 -3.8776855e-012, + -0.061358005 -0.026450802 -6.5593551e-012, + -0.041884605 0.059699103 2.657574e-012, + 0.0067355903 -0.072688602 6.5862624e-012, + -0.045739401 -0.056804504 -3.6201708e-012, + -0.0439923 -0.0582553 -6.044454e-012, + -0.051431704 -0.051695805 7.2353446e-013, + -0.049430601 -0.053696901 3.3864036e-012, + -0.052843802 -0.050283603 -1.1747271e-012, + -0.053947702 -0.0491798 4.1224146e-012, + -0.0491798 -0.053947702 5.5354579e-012, + -0.0431097 -0.041731901 0.119, + -0.024823202 -0.068589106 -9.9301101e-013, + -0.038590305 -0.045943301 0.119, + -0.025012802 -0.043293901 0.119, + 0.026910601 -0.058455303 -6.6585075e-012, + 0.013203001 -0.071786404 1.5855443e-012, + 0.013413701 -0.071757004 3.4408715e-012, + 0.0135848 -0.0584419 0.119, + 0.0075038001 -0.059528902 0.119, + 0.019521901 -0.0567353 0.119, + -0.0048316303 -0.059805103 0.119, + -0.0067355903 -0.072688602 6.4104551e-012, + -0.00602694 -0.072721399 6.5919752e-012, + -0.016962701 -0.0575523 0.119, + 0.0013432 -0.059985004 0.119, + -5.7254861e-012 -0.073000006 6.3253065e-013, + 0.037500001 0.062583603 -2.1847492e-013, + 0.035763402 0.063550904 6.6492432e-012, + 0.031060303 0.051334705 0.119, + 0.0256174 0.054256305 0.119, + 0.026370602 0.068070509 5.7587377e-013, + -0.010813001 0.072119802 4.5856843e-012, + -0.013413701 0.071757004 5.8895488e-012, + -0.010558301 0.059063703 0.119, + -0.067545101 -0.0275605 -4.2153993e-012, + -0.068205707 -0.025967101 -2.7440686e-012, + -0.068070509 -0.026370602 9.0261842e-013, + -0.066292904 -0.030396501 5.4767219e-012, + -0.065346904 -0.032538898 4.0575196e-013, + -0.064676702 -0.033742201 -4.62024e-012, + -0.069739707 -0.021390202 -5.4169763e-012, + -0.0617451 -0.038897704 4.737861e-013, + -0.0582553 -0.0439923 -4.962046e-012, + -0.062065803 -0.038429502 -6.2577456e-012, + -0.059017103 -0.0428802 3.7608506e-012, + -0.050734505 -0.032031402 0.119, + -0.029292401 0.066780403 1.7883187e-012, + -0.022416702 0.055655103 0.119, + -0.032538898 0.065346904 3.8656812e-012, + 0.0017465302 0.059974603 0.119, + 0.013413701 0.071757004 -3.2091693e-012, + 7.3656752e-014 0.073000006 -1.4251266e-012, + 0.0067355903 0.072688602 2.2405294e-012, + 0.013203001 0.071786404 3.9151638e-012, + 0.0199774 0.070213303 1.9184279e-012, + 0.013977501 0.058349203 0.119, + 0.0079039205 0.059477102 0.119, + 0.071871698 0.012591501 -1.222684e-012, + 0.070213303 0.0199774 -1.6042847e-012, + 0.072286598 0.0096175708 -1.3253017e-012, + 0.0704244 0.0190796 -1.1615373e-012, + 0.071757004 0.013413701 2.1058435e-012, + 0.068070509 0.026370602 -4.4326496e-012, + 0.0653124 0.032600902 6.2881696e-012, + 0.052316204 0.0293772 0.119, + 0.065346904 0.032538898 1.6082361e-012, + 0.064676702 0.033742201 2.4429113e-012, + 0.059999701 -0.00020173201 0.119, + 0.068070509 -0.026370602 -3.6197562e-012, + 0.058689702 -0.012470501 0.119, + 0.059660904 -0.0063698906 0.119, + 0.071757004 -0.013413701 -1.161255e-012, + 0.057096504 -0.018439 0.119, + 0.071529604 -0.0143806 5.8002548e-012, + 0.070213303 -0.0199774 -5.2450791e-012, + 0.051137004 -0.051990505 6.6236595e-012, + 0.040608104 -0.044169903 0.119, + 0.051431704 -0.051695805 5.9433946e-012, + 0.0653124 -0.032600902 4.252502e-012, + 0.065346904 -0.032538898 2.3456603e-012, + -0.0067355903 0.072688602 -5.5867949e-012, + -0.071953103 0.0120083 1.3692479e-012, + -0.072620004 0.0072273901 -3.8348031e-012, + -0.057970002 0.0154753 0.119, + -0.056071501 0.021353802 0.119, + -0.0378718 0.062376503 -6.0180884e-012, + -0.038429502 0.062065803 -4.2052091e-012, + -0.026370602 0.068070509 -5.2132461e-012, + -0.0336546 0.064725503 -1.6731672e-012, + -0.0155552 0.071253404 -6.4243927e-012, + -0.037500001 0.062583603 -1.2976232e-013, + -0.061967902 0.0239105 -6.5107433e-012, + -0.028020401 0.053055201 0.119, + -0.071757004 0.013413701 -5.7320203e-012, + 0.0491798 -0.053947702 -6.5992316e-012, + 0.039893102 -0.061063305 1.9649135e-012, + 0.0439923 -0.0582553 4.514535e-012, + 0.043875303 -0.058335401 -1.6965106e-013, + -0.013413701 -0.071757004 -1.9532861e-012, + -0.0199774 -0.070213303 -2.9158978e-012, + -0.0155552 -0.071253404 -4.3786087e-013, + -0.010955201 -0.058991406 0.119, + -0.037500001 -0.062583603 -3.2140581e-012, + -0.0336546 -0.064725503 -1.2447427e-012, + -0.028376501 -0.052865602 0.119, + 0.0084222499 -0.072453305 -1.5886412e-012, + -0.010813001 -0.072119802 -2.9756542e-012, + -0.026152501 -0.061612803 -5.9000803e-012, + 0.0199774 -0.070213303 -1.3465062e-012, + 0.031500403 -0.065805398 -4.7746334e-012, + 0.027084501 -0.067755304 4.6675001e-013, + 0.026370602 -0.068070509 -4.0715654e-013, + 0.0307144 -0.051542401 0.119, + 0.038429502 -0.062065803 -4.6598385e-012, + 0.025252001 -0.054427303 0.119, + 0.037500001 -0.062583603 -6.1442925e-012, + 0.035763402 -0.063550904 4.6713991e-012, + 0.032538898 -0.065346904 -5.362627e-012, + 0.031500403 0.065805398 -3.3911851e-012, + 0.027084501 0.067755304 -1.8692951e-012, + 0.032538898 0.065346904 -2.7645232e-012, + 0.022534501 0.069356203 -4.322149e-012, + -0.072888605 0.0024103201 3.4652173e-012, + -0.072688602 0.0067355903 -2.8184e-012, + -0.072888605 -0.0024103201 1.2668977e-013, + -0.073000006 2.2234859e-012 2.1290158e-014, + -0.059909701 0.0032901701 0.119, + -0.059253901 0.0094327098 0.119, + -0.065346904 0.032538898 6.6077976e-012, + -0.053578705 0.027005902 0.119, + 0.051431704 0.051695805 4.2773671e-012, + 0.040904205 0.043895803 0.119, + 0.045200802 0.039457403 0.119, + 0.055045106 0.047858201 -1.5536796e-012, + 0.053947702 0.0491798 1.3589982e-012, + 0.0603812 0.040888805 -1.8005718e-013, + 0.062963605 0.0368177 -3.4939215e-012, + 0.062065803 0.038429502 6.6365186e-013, + 0.057575405 0.044811103 -1.1695922e-012, + 0.0582553 0.0439923 6.1843399e-012, + 0.049018301 0.034600701 0.119, + 0.048784502 -0.034929503 0.119, + 0.0358513 -0.0481112 0.119, + 0.044934504 -0.0397604 0.119, + 0.054897901 -0.024211902 0.119, + 0.0582553 -0.0439923 6.2191467e-012, + 0.0603812 -0.040888805 -4.7300219e-012, + 0.062963605 -0.0368177 2.9197343e-012, + 0.064676702 -0.033742201 -1.1249638e-012, + 0.052117504 -0.029728301 0.119, + 0.062065803 -0.038429502 -4.6619983e-013, + 0.0491798 0.053947702 -4.2071316e-012, + 0.057121001 0.025074201 -6.3608533e-012, + 0.027934402 0.042677503 -6.4282199e-012, + 0.0727771 0.0048216903 -6.3887814e-012, + 0.0239105 0.061967902 -6.1033873e-012, + 0.059199102 0.027152302 -5.8843681e-012, + 0.038429502 0.062065803 -4.8265979e-012, + -0.029292401 -0.066780403 -5.5823754e-013, + -0.0227904 -0.055503104 0.119, + -0.026370602 -0.068070509 4.4010828e-012, + -0.032538898 -0.065346904 -7.1310096e-013, + -0.0275605 -0.067545101 -3.3819874e-012, + -0.038280502 0.046201803 0.119, + -0.0439923 0.0582553 -3.2262537e-012, + -0.033327099 0.049893003 0.119, + -0.059316006 -0.0090340506 0.119, + -0.072688602 -0.0067355903 -9.0680973e-013, + -0.072620004 -0.0072273901 3.4354815e-012, + -0.059930503 -0.0028872401 0.119, + -0.071953103 -0.0120083 1.9088407e-012, + -0.071757004 -0.013413701 4.5129937e-012, + -0.058072705 -0.015085101 0.119, + -0.068205707 0.025967101 -3.9020076e-013, + -0.066292904 0.030396501 2.845391e-012, + -0.067545101 0.0275605 4.1456552e-012, + -0.069739707 0.021390202 -3.8812087e-012, + -0.068070509 0.026370602 5.4274705e-012, + -0.070213303 0.0199774 2.33012e-012, + -0.052843802 0.050283603 -5.7208817e-012, + -0.0582553 0.0439923 5.8075142e-012, + -0.0469217 0.037394501 0.119, + -0.042828102 0.042020902 0.119, + -0.051431704 0.051695805 1.8871124e-012, + -0.0491798 0.053947702 1.7745629e-013, + -0.0617451 0.038897704 1.3612112e-012, + -0.062065803 0.038429502 3.8964452e-012, + -0.064676702 0.033742201 -4.5627725e-012, + -0.053947702 0.0491798 -5.2583055e-012, + -0.059017103 0.0428802 4.1131473e-012, + -0.050518002 0.0323718 0.119 ] + + } + coordIndex [ 209, 2, 0, -1, 139, 19, 41, -1, + 13, 209, 0, -1, 13, 47, 209, -1, + 208, 2, 209, -1, 208, 207, 77, -1, + 10, 92, 86, -1, 3, 65, 129, -1, + 15, 209, 47, -1, 15, 47, 50, -1, + 49, 50, 47, -1, 49, 47, 46, -1, + 49, 46, 41, -1, 26, 194, 65, -1, + 27, 169, 65, -1, 111, 109, 105, -1, + 111, 4, 108, -1, 111, 105, 183, -1, + 111, 183, 131, -1, 32, 4, 30, -1, + 5, 6, 126, -1, 55, 50, 61, -1, + 53, 54, 55, -1, 79, 80, 41, -1, + 79, 41, 8, -1, 44, 8, 41, -1, + 204, 77, 207, -1, 204, 207, 205, -1, + 204, 162, 119, -1, 204, 119, 77, -1, + 128, 126, 51, -1, 76, 80, 13, -1, + 73, 13, 0, -1, 73, 74, 13, -1, + 73, 0, 2, -1, 73, 2, 77, -1, + 82, 9, 47, -1, 82, 47, 13, -1, + 82, 13, 80, -1, 82, 79, 9, -1, + 1, 77, 2, -1, 1, 2, 208, -1, + 1, 208, 77, -1, 84, 86, 70, -1, + 84, 70, 6, -1, 84, 10, 86, -1, + 84, 129, 65, -1, 84, 65, 10, -1, + 91, 10, 67, -1, 91, 92, 10, -1, + 202, 166, 129, -1, 202, 129, 123, -1, + 16, 3, 129, -1, 16, 129, 166, -1, + 16, 65, 3, -1, 16, 7, 65, -1, + 16, 50, 7, -1, 20, 41, 19, -1, + 141, 139, 140, -1, 168, 65, 169, -1, + 168, 26, 65, -1, 101, 169, 27, -1, + 101, 27, 28, -1, 101, 28, 102, -1, + 104, 65, 7, -1, 104, 27, 65, -1, + 104, 21, 27, -1, 104, 22, 21, -1, + 34, 21, 98, -1, 34, 27, 21, -1, + 34, 95, 27, -1, 36, 180, 113, -1, + 110, 111, 108, -1, 191, 30, 4, -1, + 191, 111, 131, -1, 191, 4, 111, -1, + 191, 104, 30, -1, 191, 22, 104, -1, + 31, 108, 4, -1, 31, 4, 32, -1, + 124, 5, 126, -1, 124, 6, 5, -1, + 124, 84, 6, -1, 127, 129, 125, -1, + 69, 6, 70, -1, 69, 126, 6, -1, + 12, 70, 86, -1, 12, 86, 88, -1, + 12, 88, 11, -1, 179, 113, 180, -1, + 179, 104, 7, -1, 179, 7, 50, -1, + 179, 50, 55, -1, 39, 61, 62, -1, + 39, 55, 61, -1, 56, 55, 54, -1, + 45, 8, 44, -1, 45, 47, 9, -1, + 45, 9, 79, -1, 45, 79, 8, -1, + 144, 41, 51, -1, 144, 143, 41, -1, + 199, 139, 41, -1, 199, 41, 143, -1, + 142, 62, 143, -1, 142, 39, 62, -1, + 58, 143, 62, -1, 58, 62, 59, -1, + 138, 143, 58, -1, 48, 197, 199, -1, + 64, 157, 65, -1, 66, 67, 10, -1, + 66, 10, 65, -1, 66, 65, 157, -1, + 117, 11, 88, -1, 117, 126, 69, -1, + 117, 70, 12, -1, 117, 12, 11, -1, + 160, 119, 162, -1, 161, 162, 204, -1, + 37, 128, 51, -1, 37, 41, 80, -1, + 37, 51, 41, -1, 75, 13, 74, -1, + 75, 76, 13, -1, 72, 73, 77, -1, + 81, 79, 82, -1, 85, 124, 125, -1, + 85, 125, 129, -1, 85, 129, 84, -1, + 89, 88, 86, -1, 158, 91, 67, -1, + 227, 166, 202, -1, 14, 15, 50, -1, + 14, 50, 16, -1, 14, 209, 15, -1, + 14, 16, 209, -1, 164, 119, 160, -1, + 164, 209, 16, -1, 164, 16, 166, -1, + 214, 215, 121, -1, 214, 121, 166, -1, + 17, 19, 139, -1, 17, 141, 19, -1, + 17, 139, 141, -1, 18, 19, 141, -1, + 18, 141, 49, -1, 18, 20, 19, -1, + 18, 49, 41, -1, 18, 41, 20, -1, + 96, 98, 21, -1, 96, 21, 22, -1, + 96, 22, 191, -1, 23, 194, 26, -1, + 23, 24, 194, -1, 23, 26, 24, -1, + 167, 25, 168, -1, 188, 194, 24, -1, + 188, 25, 167, -1, 188, 168, 25, -1, + 188, 26, 168, -1, 188, 24, 26, -1, + 99, 95, 191, -1, 99, 191, 188, -1, + 99, 27, 95, -1, 99, 28, 27, -1, + 99, 102, 28, -1, 177, 176, 169, -1, + 177, 169, 101, -1, 177, 101, 174, -1, + 29, 32, 30, -1, 29, 30, 104, -1, + 29, 104, 32, -1, 107, 104, 109, -1, + 107, 108, 31, -1, 107, 32, 104, -1, + 107, 31, 32, -1, 33, 98, 95, -1, + 33, 34, 98, -1, 33, 95, 34, -1, + 35, 131, 183, -1, 35, 36, 131, -1, + 35, 183, 182, -1, 35, 182, 180, -1, + 35, 180, 36, -1, 114, 36, 113, -1, + 114, 131, 36, -1, 185, 183, 105, -1, + 185, 105, 116, -1, 190, 191, 131, -1, + 190, 131, 51, -1, 190, 51, 126, -1, + 130, 77, 119, -1, 130, 215, 213, -1, + 130, 128, 37, -1, 130, 80, 77, -1, + 130, 37, 80, -1, 216, 128, 130, -1, + 38, 202, 123, -1, 38, 123, 201, -1, + 38, 201, 202, -1, 133, 131, 113, -1, + 133, 113, 179, -1, 52, 53, 55, -1, + 52, 55, 39, -1, 52, 39, 142, -1, + 40, 44, 41, -1, 40, 43, 44, -1, + 40, 41, 46, -1, 40, 46, 43, -1, + 42, 44, 43, -1, 42, 45, 44, -1, + 42, 43, 46, -1, 42, 46, 47, -1, + 42, 47, 45, -1, 136, 199, 143, -1, + 136, 48, 199, -1, 136, 138, 60, -1, + 136, 137, 138, -1, 136, 60, 197, -1, + 136, 197, 48, -1, 196, 197, 60, -1, + 196, 49, 141, -1, 196, 61, 50, -1, + 196, 50, 49, -1, 152, 144, 51, -1, + 152, 51, 131, -1, 152, 131, 150, -1, + 145, 146, 148, -1, 145, 52, 142, -1, + 145, 148, 56, -1, 145, 53, 52, -1, + 145, 56, 54, -1, 145, 54, 53, -1, + 151, 179, 55, -1, 151, 55, 56, -1, + 151, 56, 148, -1, 151, 148, 147, -1, + 57, 138, 58, -1, 57, 58, 59, -1, + 57, 60, 138, -1, 57, 62, 61, -1, + 57, 59, 62, -1, 57, 61, 196, -1, + 57, 196, 60, -1, 63, 194, 157, -1, + 63, 157, 64, -1, 63, 65, 194, -1, + 63, 64, 65, -1, 156, 67, 66, -1, + 156, 66, 157, -1, 156, 158, 67, -1, + 68, 69, 70, -1, 68, 70, 117, -1, + 68, 117, 69, -1, 71, 73, 72, -1, + 71, 74, 73, -1, 71, 75, 74, -1, + 71, 76, 75, -1, 71, 72, 77, -1, + 71, 77, 80, -1, 71, 80, 76, -1, + 78, 80, 79, -1, 78, 79, 81, -1, + 78, 82, 80, -1, 78, 81, 82, -1, + 83, 84, 124, -1, 83, 85, 84, -1, + 83, 124, 85, -1, 93, 86, 92, -1, + 93, 89, 86, -1, 93, 90, 89, -1, + 87, 117, 88, -1, 87, 158, 117, -1, + 87, 88, 89, -1, 87, 89, 90, -1, + 87, 91, 158, -1, 87, 92, 91, -1, + 87, 93, 92, -1, 87, 90, 93, -1, + 219, 218, 227, -1, 219, 227, 202, -1, + 163, 164, 160, -1, 217, 227, 218, -1, + 97, 95, 98, -1, 94, 191, 95, -1, + 94, 96, 191, -1, 94, 95, 97, -1, + 94, 98, 96, -1, 94, 97, 98, -1, + 175, 169, 176, -1, 173, 103, 102, -1, + 173, 102, 99, -1, 173, 174, 101, -1, + 173, 101, 103, -1, 173, 99, 188, -1, + 100, 101, 102, -1, 100, 102, 103, -1, + 100, 103, 101, -1, 181, 104, 179, -1, + 181, 109, 104, -1, 181, 105, 109, -1, + 181, 116, 105, -1, 181, 186, 116, -1, + 106, 108, 107, -1, 106, 107, 109, -1, + 106, 110, 108, -1, 106, 109, 111, -1, + 106, 111, 110, -1, 112, 113, 131, -1, + 112, 114, 113, -1, 112, 131, 114, -1, + 187, 183, 185, -1, 115, 116, 186, -1, + 115, 185, 116, -1, 115, 186, 185, -1, + 192, 190, 126, -1, 192, 126, 117, -1, + 192, 158, 194, -1, 192, 117, 158, -1, + 118, 119, 164, -1, 118, 130, 119, -1, + 118, 164, 130, -1, 120, 215, 130, -1, + 120, 130, 164, -1, 120, 121, 215, -1, + 120, 166, 121, -1, 120, 164, 166, -1, + 122, 201, 123, -1, 122, 216, 201, -1, + 122, 125, 124, -1, 122, 124, 126, -1, + 122, 127, 125, -1, 122, 126, 128, -1, + 122, 128, 216, -1, 122, 123, 129, -1, + 122, 129, 127, -1, 224, 130, 213, -1, + 224, 216, 130, -1, 224, 165, 166, -1, + 134, 150, 131, -1, 134, 131, 133, -1, + 132, 179, 150, -1, 132, 133, 179, -1, + 132, 150, 134, -1, 132, 134, 133, -1, + 135, 137, 136, -1, 135, 136, 143, -1, + 135, 138, 137, -1, 135, 143, 138, -1, + 198, 140, 139, -1, 198, 139, 199, -1, + 198, 141, 140, -1, 198, 196, 141, -1, + 154, 142, 143, -1, 154, 143, 144, -1, + 154, 144, 152, -1, 154, 152, 153, -1, + 154, 145, 142, -1, 154, 146, 145, -1, + 154, 151, 147, -1, 154, 148, 146, -1, + 154, 147, 148, -1, 149, 150, 179, -1, + 149, 179, 151, -1, 149, 152, 150, -1, + 149, 153, 152, -1, 149, 154, 153, -1, + 149, 151, 154, -1, 155, 156, 157, -1, + 155, 158, 156, -1, 155, 157, 194, -1, + 155, 194, 158, -1, 221, 201, 216, -1, + 159, 160, 162, -1, 159, 162, 163, -1, + 159, 163, 160, -1, 206, 162, 161, -1, + 206, 163, 162, -1, 206, 161, 204, -1, + 206, 209, 164, -1, 206, 164, 163, -1, + 223, 166, 227, -1, 223, 224, 166, -1, + 211, 212, 214, -1, 211, 166, 165, -1, + 211, 214, 166, -1, 211, 165, 224, -1, + 171, 188, 167, -1, 171, 168, 169, -1, + 171, 167, 168, -1, 171, 169, 175, -1, + 170, 188, 171, -1, 170, 173, 188, -1, + 170, 175, 173, -1, 170, 171, 175, -1, + 172, 174, 173, -1, 172, 173, 175, -1, + 172, 175, 176, -1, 172, 177, 174, -1, + 172, 176, 177, -1, 178, 179, 180, -1, + 178, 181, 179, -1, 178, 186, 181, -1, + 178, 180, 182, -1, 178, 182, 183, -1, + 178, 183, 187, -1, 178, 187, 186, -1, + 184, 185, 186, -1, 184, 186, 187, -1, + 184, 187, 185, -1, 193, 194, 188, -1, + 193, 188, 191, -1, 189, 191, 190, -1, + 189, 190, 192, -1, 189, 193, 191, -1, + 189, 192, 194, -1, 189, 194, 193, -1, + 195, 197, 196, -1, 195, 196, 198, -1, + 195, 199, 197, -1, 195, 198, 199, -1, + 200, 201, 221, -1, 200, 221, 219, -1, + 200, 202, 201, -1, 200, 219, 202, -1, + 220, 219, 221, -1, 203, 204, 205, -1, + 203, 206, 204, -1, 203, 205, 207, -1, + 203, 207, 208, -1, 203, 208, 209, -1, + 203, 209, 206, -1, 226, 227, 217, -1, + 210, 212, 211, -1, 210, 211, 224, -1, + 210, 224, 213, -1, 210, 214, 212, -1, + 210, 213, 215, -1, 210, 215, 214, -1, + 225, 216, 224, -1, 225, 226, 217, -1, + 225, 217, 218, -1, 225, 218, 219, -1, + 225, 219, 220, -1, 225, 221, 216, -1, + 225, 220, 221, -1, 222, 224, 223, -1, + 222, 225, 224, -1, 222, 226, 225, -1, + 222, 223, 227, -1, 222, 227, 226, -1 ] + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link0-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link0-right.wrl new file mode 100644 index 0000000..320ce16 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link0-right.wrl @@ -0,0 +1,12 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + children [ + Inline { + url "kuka-swiwel.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link1-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link1-right.wrl new file mode 100644 index 0000000..8b1f4b5 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link1-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link1.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link2-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link2-right.wrl new file mode 100644 index 0000000..de49eaa --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link2-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link2.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link3-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link3-right.wrl new file mode 100644 index 0000000..8ebd7b7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link3-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link3.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link4-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link4-right.wrl new file mode 100644 index 0000000..8cdbb77 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link4-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link4.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link5-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link5-right.wrl new file mode 100644 index 0000000..6ed5cd0 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link5-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link5.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link6-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link6-right.wrl new file mode 100644 index 0000000..93c0136 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link6-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link6.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link7-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link7-right.wrl new file mode 100644 index 0000000..4f70805 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4.convex/link7-right.wrl @@ -0,0 +1,12 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + children [ + Inline { + url "kuka-link7.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link1.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link1.wrl new file mode 100644 index 0000000..a57ca19 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link1.wrl @@ -0,0 +1,44404 @@ +#VRML V2.0 utf8 + + +Group { + children [ + Group { + children + Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.041876599 0.0074999998 0.043469001, + 0.037236601 0.0074999998 0.047547001, + 0.039609101 -0.0094999997 0.045568001, + -0.0322018 0.0074999998 0.051127002, + -0.037236601 0.0074999998 0.047547001, + -0.034765299 -0.0094999997 0.049401999, + -0.056669399 0.0074999998 -0.019213, + -0.057608999 -0.0094999997 -0.016269, + -0.0583959 0.0074999998 -0.013281, + 0 0.0074999998 -0.059500001, + -0.0030887299 -0.0094999997 -0.059420001, + -0.00616926 0.0074999998 -0.059181999, + 0.0182469 0.0074999998 -0.056658, + 0.0152803 -0.0094999997 -0.057521999, + 0.0122731 0.0074999998 -0.058231, + 0.0240272 0.0074999998 -0.054478999, + 0.021165101 -0.0094999997 -0.055643, + 0.029552899 0.0074999998 -0.051716998, + 0.026825599 -0.0094999997 -0.053169001, + 0.034765299 0.0074999998 -0.048402, + 0.0322018 -0.0094999997 -0.050127, + 0.039609101 0.0074999998 -0.044567998, + 0.037236601 -0.0094999997 -0.046546999, + 0.044033099 0.0074999998 -0.040256001, + 0.041876599 -0.0094999997 -0.042468999, + 0.043974701 -0.0094999997 -0.040201999, + 0.0460728 -0.0094999997 -0.037935998, + 0.034719199 -0.0094999997 -0.048337001, + 0.0295137 -0.0094999997 -0.051647998, + 0.023995399 -0.0094999997 -0.054405998, + 0.018222701 -0.0094999997 -0.056582, + 0.0122569 -0.0094999997 -0.058153, + 0.00923343 -0.0094999997 -0.058784999, + 0.00616926 0.0074999998 -0.059181999, + 0.0061610802 -0.0094999997 -0.059103001, + 0.0030887299 -0.0094999997 -0.059420001, + -0.051438902 0.0074999998 -0.030387999, + -0.0479904 0.0074999998 -0.035512999, + -0.0497806 -0.0094999997 -0.032995, + -0.044033099 0.0074999998 -0.040256001, + -0.0460728 -0.0094999997 -0.037935998, + -0.039609101 0.0074999998 -0.044567998, + -0.041876599 -0.0094999997 -0.042468999, + -0.034765299 0.0074999998 -0.048402, + -0.037236601 -0.0094999997 -0.046546999, + -0.029552899 0.0074999998 -0.051716998, + -0.0322018 -0.0094999997 -0.050127, + -0.0240272 0.0074999998 -0.054478999, + -0.026825599 -0.0094999997 -0.053169001, + -0.0182469 0.0074999998 -0.056658, + -0.021165101 -0.0094999997 -0.055643, + -0.0122731 0.0074999998 -0.058231, + -0.0152803 -0.0094999997 -0.057521999, + -0.00923343 -0.0094999997 -0.058784999, + -0.0061610802 -0.0094999997 -0.059103001, + -0.0122569 -0.0094999997 -0.058153, + -0.018222701 -0.0094999997 -0.056582, + -0.023995399 -0.0094999997 -0.054405998, + -0.0295137 -0.0094999997 -0.051647998, + -0.034719199 -0.0094999997 -0.048337001, + -0.043974701 -0.0094999997 -0.040201999, + -0.047926702 -0.0094999997 -0.035464998, + -0.051370699 -0.0094999997 -0.030347001, + -0.052960701 -0.0094999997 -0.027698999, + -0.054342099 0.0074999998 -0.024935, + -0.0542701 -0.0094999997 -0.024901001, + -0.055579402 -0.0094999997 -0.022104001, + -0.0460728 0.0074999998 0.038936, + -0.0497806 0.0074999998 0.033994999, + -0.0479904 -0.0094999997 0.036513001, + -0.052960701 0.0074999998 0.028698999, + -0.051438902 -0.0094999997 0.031388, + -0.055579402 0.0074999998 0.023104001, + -0.054342099 -0.0094999997 0.025935, + -0.057608999 0.0074999998 0.017269, + -0.056669399 -0.0094999997 0.020213, + -0.059027899 0.0074999998 0.011257, + -0.0583959 -0.0094999997 0.014281, + -0.059821099 0.0074999998 0.0051310002, + -0.059503399 -0.0094999997 0.0082039898, + -0.059980098 0.0074999998 -0.001045, + -0.059980098 -0.0094999997 0.002045, + -0.059503399 0.0074999998 -0.0072039901, + -0.059821099 -0.0094999997 -0.004131, + -0.059027899 -0.0094999997 -0.010257, + -0.0565942 -0.0094999997 -0.019185999, + -0.058318399 -0.0094999997 -0.013263, + -0.0599006 -0.0094999997 -0.001043, + -0.059741698 -0.0094999997 0.0051239901, + -0.058949601 -0.0094999997 0.011243, + -0.057532601 -0.0094999997 0.017247001, + -0.0555057 -0.0094999997 0.023073999, + -0.052890498 -0.0094999997 0.028661, + -0.049714599 -0.0094999997 0.033950001, + -0.046011701 -0.0094999997 0.038885001, + -0.044033099 -0.0094999997 0.041255999, + -0.041876599 0.0074999998 0.043469001, + -0.0418211 -0.0094999997 0.043412, + -0.039609101 -0.0094999997 0.045568001, + 0.021165101 0.0074999998 0.056643002, + 0.0152803 0.0074999998 0.058522001, + 0.0182469 -0.0094999997 0.057658002, + 0.00923343 0.0074999998 0.059785001, + 0.0122731 -0.0094999997 0.059230998, + 0.0030887299 0.0074999998 0.060419999, + 0.00616926 -0.0094999997 0.060182001, + -0.0030887299 0.0074999998 0.060419999, + 0 -0.0094999997 0.0605, + -0.00923343 0.0074999998 0.059785001, + -0.00616926 -0.0094999997 0.060182001, + -0.0152803 0.0074999998 0.058522001, + -0.0122731 -0.0094999997 0.059230998, + -0.021165101 0.0074999998 0.056643002, + -0.0182469 -0.0094999997 0.057658002, + -0.026825599 0.0074999998 0.054168999, + -0.0240272 -0.0094999997 0.055479001, + -0.029552899 -0.0094999997 0.052717, + -0.0371872 -0.0094999997 0.047485001, + -0.032159101 -0.0094999997 0.051059, + -0.026790099 -0.0094999997 0.054097999, + -0.0211371 -0.0094999997 0.056568999, + -0.01526 -0.0094999997 0.058444999, + -0.0092211897 -0.0094999997 0.059707001, + 0.0092211897 -0.0094999997 0.059707001, + 0.01526 -0.0094999997 0.058444999, + 0.0211371 -0.0094999997 0.056568999, + 0.0240272 -0.0094999997 0.055479001, + 0.026825599 0.0074999998 0.054168999, + 0.026790099 -0.0094999997 0.054097999, + 0.029552899 -0.0094999997 0.052717, + 0.0322018 0.0074999998 0.051127002, + 0.032159101 -0.0094999997 0.051059, + 0.034765299 -0.0094999997 0.049401999, + 0.057608999 0.0074999998 0.017269, + 0.055579402 0.0074999998 0.023104001, + 0.056669399 -0.0094999997 0.020213, + 0.052960701 0.0074999998 0.028698999, + 0.054342099 -0.0094999997 0.025935, + 0.0497806 0.0074999998 0.033994999, + 0.051438902 -0.0094999997 0.031388, + 0.0460728 0.0074999998 0.038936, + 0.0479904 -0.0094999997 0.036513001, + 0.044033099 -0.0094999997 0.041255999, + 0.0371872 -0.0094999997 0.047485001, + 0.0418211 -0.0094999997 0.043412, + 0.046011701 -0.0094999997 0.038885001, + 0.049714599 -0.0094999997 0.033950001, + 0.052890498 -0.0094999997 0.028661, + 0.0555057 -0.0094999997 0.023073999, + 0.059027899 0.0074999998 0.011257, + 0.0583959 -0.0094999997 0.014281, + 0.057532601 -0.0094999997 0.017247001, + 0.059503399 -0.0094999997 0.0082039898, + 0.059821099 0.0074999998 0.0051310002, + 0.058949601 -0.0094999997 0.011243, + 0.059980098 -0.0094999997 0.002045, + 0.059980098 0.0074999998 -0.001045, + 0.059741698 -0.0094999997 0.0051239901, + 0.059821099 -0.0094999997 -0.004131, + 0.059503399 0.0074999998 -0.0072039901, + 0.0599006 -0.0094999997 -0.001043, + 0.059027899 -0.0094999997 -0.010257, + 0.0583959 0.0074999998 -0.013281, + 0.058318399 -0.0094999997 -0.013263, + 0.057608999 -0.0094999997 -0.016269, + 0.056669399 0.0074999998 -0.019213, + 0.055579402 -0.0094999997 -0.022104001, + 0.054342099 0.0074999998 -0.024935, + 0.0565942 -0.0094999997 -0.019185999, + 0.0479904 0.0074999998 -0.035512999, + 0.051438902 0.0074999998 -0.030387999, + 0.0497806 -0.0094999997 -0.032995, + 0.051370699 -0.0094999997 -0.030347001, + 0.052960701 -0.0094999997 -0.027698999, + 0.047926702 -0.0094999997 -0.035464998, + 0.0542701 -0.0094999997 -0.024901001, + 0.011126 -0.0094999997 -0.048246, + 0.016514 -0.0094999997 -0.046693999, + 0.011126 0.0074999998 -0.048246, + 0.016514 0.0074999998 -0.046693999, + 0.00559822 0.0074999998 -0.049185999, + 0.00559822 -0.0094999997 -0.049185999, + 0.0216942 -0.0094999997 -0.044548001, + 0.0216942 0.0074999998 -0.044548001, + 0.0266016 -0.0094999997 -0.041836001, + 0.0266016 0.0074999998 -0.041836001, + 0.0311745 -0.0094999997 -0.038592, + 0.0311745 0.0074999998 -0.038592, + 0.0353553 -0.0094999997 -0.034855001, + 0.039091598 -0.0094999997 -0.030673999, + 0.0353553 0.0074999998 -0.034855001, + 0.039091598 0.0074999998 -0.030673999, + 0.042336199 -0.0094999997 -0.026102001, + 0.042336199 0.0074999998 -0.026102001, + 0.0395566 -0.0094999997 -0.044507999, + 0 0.0074999998 -0.0495, + 0 -0.0094999997 -0.0495, + -0.042336199 0.0074999998 -0.026102001, + -0.045048401 0.0074999998 -0.021194, + -0.042336199 -0.0094999997 -0.026102001, + -0.045048401 -0.0094999997 -0.021194, + -0.039091598 -0.0094999997 -0.030673999, + -0.039091598 0.0074999998 -0.030673999, + -0.0353553 -0.0094999997 -0.034855001, + -0.0353553 0.0074999998 -0.034855001, + -0.0311745 -0.0094999997 -0.038592, + -0.0311745 0.0074999998 -0.038592, + -0.00559822 -0.0094999997 -0.049185999, + -0.00559822 0.0074999998 -0.049185999, + -0.011126 0.0074999998 -0.048246, + -0.011126 -0.0094999997 -0.048246, + -0.016514 0.0074999998 -0.046693999, + -0.016514 -0.0094999997 -0.046693999, + -0.0216942 0.0074999998 -0.044548001, + -0.0216942 -0.0094999997 -0.044548001, + -0.0266016 0.0074999998 -0.041836001, + -0.0266016 -0.0094999997 -0.041836001, + 0 -0.0094999997 -0.059420001, + -0.0395566 -0.0094999997 -0.044507999, + -0.047194201 0.0074999998 -0.016014, + -0.047194201 -0.0094999997 -0.016014, + -0.039091598 0.0074999998 0.031674001, + -0.0353553 0.0074999998 0.035854999, + -0.039091598 -0.0094999997 0.031674001, + -0.0353553 -0.0094999997 0.035854999, + -0.042336199 -0.0094999997 0.027101999, + -0.042336199 0.0074999998 0.027101999, + -0.045048401 -0.0094999997 0.022194, + -0.045048401 0.0074999998 0.022194, + -0.047194201 -0.0094999997 0.017014001, + -0.047194201 0.0074999998 0.017014001, + -0.0487464 -0.0094999997 -0.010626, + -0.0487464 0.0074999998 -0.010626, + -0.049685601 0.0074999998 -0.0050980099, + -0.049685601 -0.0094999997 -0.0050980099, + -0.050000001 0.0074999998 0.00050000002, + -0.050000001 -0.0094999997 0.00050000002, + -0.049685601 0.0074999998 0.0060980101, + -0.049685601 -0.0094999997 0.0060980101, + -0.0487464 0.0074999998 0.011626, + -0.0487464 -0.0094999997 0.011626, + -0.059424501 -0.0094999997 -0.0071939998, + -0.0311745 0.0074999998 0.039592002, + -0.0311745 -0.0094999997 0.039592002, + 0.016514 0.0074999998 0.047694001, + 0.0216942 0.0074999998 0.045547999, + 0.016514 -0.0094999997 0.047694001, + 0.0216942 -0.0094999997 0.045547999, + 0.011126 -0.0094999997 0.049245998, + 0.011126 0.0074999998 0.049245998, + 0.00559822 -0.0094999997 0.050186001, + 0.00559822 0.0074999998 0.050186001, + 0 -0.0094999997 0.050500002, + 0 0.0074999998 0.050500002, + -0.0266016 -0.0094999997 0.042835999, + -0.0266016 0.0074999998 0.042835999, + -0.0216942 0.0074999998 0.045547999, + -0.0216942 -0.0094999997 0.045547999, + -0.016514 0.0074999998 0.047694001, + -0.016514 -0.0094999997 0.047694001, + -0.011126 0.0074999998 0.049245998, + -0.011126 -0.0094999997 0.049245998, + -0.00559822 0.0074999998 0.050186001, + -0.00559822 -0.0094999997 0.050186001, + -0.00308463 -0.0094999997 0.060341001, + 0.00308463 -0.0094999997 0.060341001, + 0.0266016 0.0074999998 0.042835999, + 0.0266016 -0.0094999997 0.042835999, + 0.0311745 0.0074999998 0.039592002, + 0.0311745 -0.0094999997 0.039592002, + 0.0353553 -0.0094999997 0.035854999, + 0.0353553 0.0074999998 0.035854999, + 0.039091598 0.0074999998 0.031674001, + 0.039091598 -0.0094999997 0.031674001, + 0.042336199 0.0074999998 0.027101999, + 0.042336199 -0.0094999997 0.027101999, + 0.045048401 0.0074999998 0.022194, + 0.045048401 -0.0094999997 0.022194, + 0.047194201 0.0074999998 0.017014001, + 0.047194201 -0.0094999997 0.017014001, + 0.0487464 0.0074999998 0.011626, + 0.0487464 -0.0094999997 0.011626, + 0.049685601 0.0074999998 0.0060980101, + 0.049685601 -0.0094999997 0.0060980101, + 0.050000001 0.0074999998 0.00050000002, + 0.050000001 -0.0094999997 0.00050000002, + 0.049685601 0.0074999998 -0.0050980099, + 0.049685601 -0.0094999997 -0.0050980099, + 0.059424501 -0.0094999997 -0.0071939998, + 0.0487464 0.0074999998 -0.010626, + 0.0487464 -0.0094999997 -0.010626, + 0.047194201 0.0074999998 -0.016014, + 0.047194201 -0.0094999997 -0.016014, + 0.045048401 -0.0094999997 -0.021194, + 0.045048401 0.0074999998 -0.021194 ] + + } + normal + Normal { + vector [ 0.6601463 0.0046896623 0.75112236, + -0.57948703 0.0046876199 0.81496799, + -0.96014863 0.0046738279 -0.27945092, + -0.051475927 0.0046529523 -0.99866349, + 0.25463399 0.0047125299 -0.967026, + 0.35273489 0.0046826783 -0.93571162, + 0.44709989 0.0046710293 -0.89447176, + 0.53664124 0.0046985522 -0.84379745, + 0.62062877 0.0046632281 -0.7840907, + 0.69797593 0.0046796394 -0.71610594, + 0.7337594 -0.0046787527 -0.67939341, + 0.73390883 -0.004678749 -0.67923182, + 0.57948703 -0.0046868902 -0.81496799, + 0.57948405 -0.0046868906 -0.81497014, + 0.49245277 -0.0046680477 -0.87032658, + 0.49245712 -0.0046680509 -0.87032419, + 0.40048516 -0.0046837321 -0.9162913, + 0.40047285 -0.0046837283 -0.91629672, + 0.30401704 -0.0046919403 -0.95265514, + 0.30431286 -0.0046919375 -0.95256054, + 0.20430003 -0.0046862704 -0.97889709, + 0.20460795 -0.0046862592 -0.97883278, + 0.15394506 0.0046734121 -0.98806834, + 0.10295095 -0.0046724374 -0.99467552, + 0.10263304 -0.0046724416 -0.99470836, + 0.051475927 0.0046529523 -0.99866349, + -0.82965487 0.0046798293 -0.55825692, + -0.76783019 0.0046984111 -0.64063621, + -0.69797593 0.0046796394 -0.71610594, + -0.62062877 0.0046632281 -0.7840907, + -0.53664124 0.0046985522 -0.84379745, + -0.44709989 0.0046710293 -0.89447176, + -0.35273489 0.0046826783 -0.93571162, + -0.25463399 0.0047125299 -0.967026, + -0.15394506 0.0046734121 -0.98806834, + -0.10263304 -0.0046724416 -0.99470836, + -0.10295095 -0.0046724374 -0.99467552, + -0.20460795 -0.0046862592 -0.97883278, + -0.20430003 -0.0046862704 -0.97889709, + -0.30431286 -0.0046919375 -0.95256054, + -0.30401704 -0.0046919403 -0.95265514, + -0.40047285 -0.0046837283 -0.91629672, + -0.40048516 -0.0046837321 -0.9162913, + -0.49245712 -0.0046680509 -0.87032419, + -0.49245277 -0.0046680477 -0.87032658, + -0.57948405 -0.0046868906 -0.81497014, + -0.57948703 -0.0046868902 -0.81496799, + -0.73390883 -0.004678749 -0.67923182, + -0.7337594 -0.0046787527 -0.67939341, + -0.799891 -0.0046917601 -0.60012698, + -0.79977351 -0.0046917573 -0.60028362, + -0.8572976 -0.0046808175 -0.51479977, + -0.85731131 -0.0046808217 -0.51477718, + -0.88268387 0.0046818694 -0.46994394, + -0.90571833 -0.0046835318 -0.42385414, + -0.90567213 -0.0046835304 -0.42395306, + -0.9263019 0.0046780896 -0.37675294, + -0.79983234 0.0046739825 0.6002053, + -0.85730481 0.004683319 0.51478785, + -0.90569514 0.0046736207 0.42390406, + -0.94448465 0.0046899579 0.32852188, + -0.97325075 0.0046772892 0.22969794, + -0.99171054 0.0046781576 0.12840694, + -0.99965787 0.0046779094 0.025736095, + -0.99700713 0.0046831607 -0.07716731, + -0.98378533 0.0046813218 -0.17928906, + -0.944502 -0.0046995399 -0.32847199, + -0.94446725 -0.0046995408 -0.32857209, + -0.97325426 -0.0046801311 -0.22968306, + -0.97324687 -0.0046801297 -0.22971398, + -0.99965787 -0.0046777995 -0.025736697, + -0.99965787 -0.0046777995 -0.025735496, + -0.99700499 -0.00468835 0.077195801, + -0.99700934 -0.0046883519 0.077138826, + -0.98378766 -0.0046789581 0.17927594, + -0.98378301 -0.00467896 0.17930201, + -0.96014422 -0.0046767611 0.27946606, + -0.96015322 -0.0046767611 0.27943507, + -0.92629665 -0.0046806182 0.37676585, + -0.92630726 -0.004680621 0.3767401, + -0.88264769 -0.004695788 0.47001183, + -0.88271999 -0.0046957899 0.46987599, + -0.82959688 -0.0046987897 0.55834293, + -0.82971317 -0.0046987808 0.55817014, + -0.76788801 -0.0046819602 0.640567, + -0.76777202 -0.0046819602 0.640706, + -0.73383397 0.0046587097 0.67931294, + -0.69797695 -0.0046793898 0.71610492, + -0.69797492 -0.0046793898 0.71610695, + -0.6601463 0.0046896623 0.75112236, + 0.30416501 0.00466287 0.95260799, + 0.20445403 0.0046568103 0.97886515, + 0.10279395 0.0047010076 0.99469155, + 0 0.0047050398 0.99998897, + -0.10279395 0.0047010076 0.99469155, + -0.20445403 0.0046568103 0.97886515, + -0.30416501 0.00466287 0.95260799, + -0.40047899 0.0046848999 0.91629398, + -0.49245277 0.0046680477 0.87032658, + -0.62062991 -0.0046629491 0.7840898, + -0.62063092 -0.0046629496 0.78408891, + -0.53652203 -0.0047243405 0.84387314, + -0.53676105 -0.0047243303 0.84372109, + -0.44709989 -0.0046701292 0.89447176, + -0.44709513 -0.004670131 0.89447427, + -0.3528809 -0.0046543484 0.93565667, + -0.35258508 -0.0046543512 0.93576825, + -0.25479096 -0.0046838894 0.96698487, + -0.25447688 -0.0046838876 0.96706754, + -0.15410703 -0.004644501 0.98804325, + -0.15378799 -0.0046444996 0.9880929, + 0.15378799 -0.0046444996 0.9880929, + 0.15410703 -0.004644501 0.98804325, + 0.25447688 -0.0046838876 0.96706754, + 0.25479096 -0.0046838894 0.96698487, + 0.35258508 -0.0046543512 0.93576825, + 0.3528809 -0.0046543484 0.93565667, + 0.40047899 0.0046848999 0.91629398, + 0.44709513 -0.004670131 0.89447427, + 0.44709989 -0.0046701292 0.89447176, + 0.49245277 0.0046680477 0.87032658, + 0.53676105 -0.0047243303 0.84372109, + 0.53652203 -0.0047243405 0.84387314, + 0.57948703 0.0046876199 0.81496799, + 0.94448465 0.0046899579 0.32852188, + 0.90569514 0.0046736207 0.42390406, + 0.85730481 0.004683319 0.51478785, + 0.79983234 0.0046739825 0.6002053, + 0.73383397 0.0046587097 0.67931294, + 0.62063092 -0.0046629496 0.78408891, + 0.62062991 -0.0046629491 0.7840898, + 0.69797492 -0.0046793898 0.71610695, + 0.69797695 -0.0046793898 0.71610492, + 0.76777202 -0.0046819602 0.640706, + 0.76788801 -0.0046819602 0.640567, + 0.82971317 -0.0046987808 0.55817014, + 0.82959688 -0.0046987897 0.55834293, + 0.88271999 -0.0046957899 0.46987599, + 0.88264769 -0.004695788 0.47001183, + 0.92630726 -0.004680621 0.3767401, + 0.92629665 -0.0046806182 0.37676585, + 0.97325075 0.0046772892 0.22969794, + 0.96014422 -0.0046767611 0.27946606, + 0.96015322 -0.0046767611 0.27943507, + 0.99171054 0.0046781576 0.12840694, + 0.98378766 -0.0046789581 0.17927594, + 0.98378301 -0.00467896 0.17930201, + 0.99965787 0.0046779094 0.025736095, + 0.99700499 -0.00468835 0.077195801, + 0.99700934 -0.0046883519 0.077138826, + 0.99700713 0.0046831607 -0.07716731, + 0.99965787 -0.0046777995 -0.025736697, + 0.99965787 -0.0046777995 -0.025735496, + 0.98378533 0.0046813218 -0.17928906, + 0.97324687 -0.0046801297 -0.22971398, + 0.97325426 -0.0046801311 -0.22968306, + 0.9263019 0.0046780896 -0.37675294, + 0.96014863 0.0046738279 -0.27945092, + 0.94446725 -0.0046995408 -0.32857209, + 0.944502 -0.0046995399 -0.32847199, + 0.82965487 0.0046798293 -0.55825692, + 0.85731131 -0.0046808217 -0.51477718, + 0.8572976 -0.0046808175 -0.51479977, + 0.79977351 -0.0046917573 -0.60028362, + 0.799891 -0.0046917601 -0.60012698, + 0.76783019 0.0046984111 -0.64063621, + 0.90567213 -0.0046835304 -0.42395306, + 0.90571833 -0.0046835318 -0.42385414, + 0.88268387 0.0046818694 -0.46994394, + -0.27679408 0 0.96092933, + -0.16764393 0 0.98584765, + -0.38272718 0 0.92386144, + -0.48368895 0 0.87523991, + -0.57859498 0 0.815615, + -0.74564898 0 0.66633898, + -0.6664266 0 0.7455706, + -0.81550997 0 0.57874298, + 0.6601463 -0.0046896623 -0.75112236, + -0.056000385 0 0.99843079, + 0.87525058 0 0.48366976, + 0.81550997 0 0.57874298, + 0.74564898 0 0.66633898, + 0.6664266 0 0.7455706, + 0.056000385 0 0.99843079, + 0.16764393 0 0.98584765, + 0.27679408 0 0.96092933, + 0.38272718 0 0.92386144, + 0.48368895 0 0.87523991, + 0.57859498 0 0.815615, + 0 -0.0047059399 -0.99998897, + -0.6601463 -0.0046896623 -0.75112236, + 0.9238686 0 0.38270983, + 0.74564898 0 -0.66633898, + 0.81550997 0 -0.57874298, + 0.87525058 0 -0.48366976, + 0.9238686 0 -0.38270983, + 0.9609201 0 0.27682602, + 0.98587233 0 0.16749907, + 0.99842662 0 0.056074381, + 0.99842662 0 -0.056074381, + 0.98587233 0 -0.16749907, + 0.9609201 0 -0.27682602, + -0.99171054 -0.0046781576 -0.12840694, + 0.6664266 0 -0.7455706, + -0.38272718 0 -0.92386144, + -0.27679408 0 -0.96092933, + -0.16764393 0 -0.98584765, + -0.056000385 0 -0.99843079, + 0.57859498 0 -0.815615, + 0.48368895 0 -0.87523991, + 0.38272718 0 -0.92386144, + 0.27679408 0 -0.96092933, + 0.16764393 0 -0.98584765, + 0.056000385 0 -0.99843079, + -0.05147592 -0.004653852 0.99866337, + 0.05147592 -0.004653852 0.99866337, + -0.48368895 0 -0.87523991, + -0.57859498 0 -0.815615, + -0.6664266 0 -0.7455706, + -0.74564898 0 -0.66633898, + -0.81550997 0 -0.57874298, + -0.87525058 0 -0.48366976, + -0.9238686 0 -0.38270983, + -0.9609201 0 -0.27682602, + -0.98587233 0 -0.16749907, + -0.99842662 0 -0.056074381, + -0.99842662 0 0.056074381, + 0.99171054 -0.0046781576 -0.12840694, + -0.98587233 0 0.16749907, + -0.9609201 0 0.27682602, + -0.9238686 0 0.38270983, + -0.87525058 0 0.48366976, + 0 -1 0, + 0 1 0 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 9, 10, 11, -1, + 12, 13, 14, -1, 12, 15, 16, -1, + 17, 18, 15, -1, 19, 20, 17, -1, + 19, 21, 22, -1, 23, 24, 21, -1, + 25, 23, 26, -1, 25, 24, 23, -1, + 27, 19, 22, -1, 27, 20, 19, -1, + 28, 17, 20, -1, 28, 18, 17, -1, + 29, 15, 18, -1, 29, 16, 15, -1, + 30, 12, 16, -1, 30, 13, 12, -1, + 31, 14, 13, -1, 31, 32, 14, -1, + 14, 32, 33, -1, 34, 33, 32, -1, + 34, 35, 33, -1, 33, 35, 9, -1, + 36, 37, 38, -1, 39, 40, 37, -1, + 41, 42, 39, -1, 43, 44, 41, -1, + 45, 46, 43, -1, 47, 48, 45, -1, + 47, 49, 50, -1, 51, 52, 49, -1, + 11, 53, 51, -1, 54, 11, 10, -1, + 54, 53, 11, -1, 55, 51, 53, -1, + 55, 52, 51, -1, 56, 49, 52, -1, + 56, 50, 49, -1, 57, 47, 50, -1, + 57, 48, 47, -1, 58, 45, 48, -1, + 58, 46, 45, -1, 59, 43, 46, -1, + 59, 44, 43, -1, 60, 39, 42, -1, + 60, 40, 39, -1, 61, 37, 40, -1, + 61, 38, 37, -1, 62, 36, 38, -1, + 62, 63, 36, -1, 36, 63, 64, -1, + 65, 64, 63, -1, 65, 66, 64, -1, + 6, 64, 66, -1, 67, 68, 69, -1, + 70, 71, 68, -1, 70, 72, 73, -1, + 74, 75, 72, -1, 76, 77, 74, -1, + 76, 78, 79, -1, 78, 80, 81, -1, + 82, 83, 80, -1, 8, 84, 82, -1, + 85, 6, 66, -1, 85, 7, 6, -1, + 86, 8, 7, -1, 86, 84, 8, -1, + 87, 80, 83, -1, 87, 81, 80, -1, + 88, 78, 81, -1, 88, 79, 78, -1, + 89, 76, 79, -1, 89, 77, 76, -1, + 90, 74, 77, -1, 90, 75, 74, -1, + 91, 72, 75, -1, 91, 73, 72, -1, + 92, 70, 73, -1, 92, 71, 70, -1, + 93, 68, 71, -1, 93, 69, 68, -1, + 94, 67, 69, -1, 94, 95, 67, -1, + 96, 67, 95, -1, 97, 96, 95, -1, + 97, 98, 96, -1, 96, 98, 4, -1, + 99, 100, 101, -1, 102, 103, 100, -1, + 104, 105, 102, -1, 104, 106, 107, -1, + 108, 109, 106, -1, 110, 111, 108, -1, + 110, 112, 113, -1, 114, 115, 112, -1, + 3, 116, 114, -1, 117, 4, 98, -1, + 117, 5, 4, -1, 118, 3, 5, -1, + 118, 116, 3, -1, 119, 114, 116, -1, + 119, 115, 114, -1, 120, 112, 115, -1, + 120, 113, 112, -1, 121, 110, 113, -1, + 121, 111, 110, -1, 122, 108, 111, -1, + 122, 109, 108, -1, 123, 102, 105, -1, + 123, 103, 102, -1, 124, 100, 103, -1, + 124, 101, 100, -1, 125, 99, 101, -1, + 125, 126, 99, -1, 99, 126, 127, -1, + 128, 127, 126, -1, 128, 129, 127, -1, + 127, 129, 130, -1, 131, 130, 129, -1, + 131, 132, 130, -1, 130, 132, 1, -1, + 133, 134, 135, -1, 136, 137, 134, -1, + 136, 138, 139, -1, 140, 141, 138, -1, + 0, 142, 140, -1, 143, 1, 132, -1, + 143, 2, 1, -1, 144, 0, 2, -1, + 144, 142, 0, -1, 145, 140, 142, -1, + 145, 141, 140, -1, 146, 138, 141, -1, + 146, 139, 138, -1, 147, 136, 139, -1, + 147, 137, 136, -1, 148, 134, 137, -1, + 148, 135, 134, -1, 149, 133, 150, -1, + 151, 150, 133, -1, 151, 133, 135, -1, + 149, 152, 153, -1, 154, 152, 149, -1, + 154, 149, 150, -1, 153, 155, 156, -1, + 157, 155, 153, -1, 157, 153, 152, -1, + 156, 158, 159, -1, 160, 158, 156, -1, + 160, 156, 155, -1, 159, 161, 162, -1, + 163, 162, 161, -1, 163, 164, 162, -1, + 165, 166, 167, -1, 165, 162, 164, -1, + 168, 165, 164, -1, 168, 166, 165, -1, + 169, 170, 171, -1, 172, 170, 173, -1, + 172, 171, 170, -1, 174, 169, 171, -1, + 174, 26, 169, -1, 169, 26, 23, -1, + 175, 167, 166, -1, 175, 173, 167, -1, + 167, 173, 170, -1, 176, 177, 178, -1, + 178, 177, 179, -1, 178, 180, 176, -1, + 176, 180, 181, -1, 177, 182, 179, -1, + 179, 182, 183, -1, 182, 184, 183, -1, + 183, 184, 185, -1, 184, 186, 185, -1, + 185, 186, 187, -1, 188, 189, 190, -1, + 190, 189, 191, -1, 190, 187, 188, -1, + 188, 187, 186, -1, 189, 192, 191, -1, + 191, 192, 193, -1, 24, 194, 21, -1, + 21, 194, 22, -1, 180, 195, 181, -1, + 181, 195, 196, -1, 197, 198, 199, -1, + 199, 198, 200, -1, 199, 201, 197, -1, + 197, 201, 202, -1, 201, 203, 202, -1, + 202, 203, 204, -1, 203, 205, 204, -1, + 204, 205, 206, -1, 207, 196, 208, -1, + 208, 196, 195, -1, 208, 209, 207, -1, + 207, 209, 210, -1, 209, 211, 210, -1, + 210, 211, 212, -1, 211, 213, 212, -1, + 212, 213, 214, -1, 213, 215, 214, -1, + 214, 215, 216, -1, 215, 206, 216, -1, + 216, 206, 205, -1, 35, 217, 9, -1, + 9, 217, 10, -1, 44, 218, 41, -1, + 41, 218, 42, -1, 198, 219, 200, -1, + 200, 219, 220, -1, 221, 222, 223, -1, + 223, 222, 224, -1, 223, 225, 221, -1, + 221, 225, 226, -1, 225, 227, 226, -1, + 226, 227, 228, -1, 227, 229, 228, -1, + 228, 229, 230, -1, 231, 220, 232, -1, + 232, 220, 219, -1, 232, 233, 231, -1, + 231, 233, 234, -1, 233, 235, 234, -1, + 234, 235, 236, -1, 235, 237, 236, -1, + 236, 237, 238, -1, 237, 239, 238, -1, + 238, 239, 240, -1, 239, 230, 240, -1, + 240, 230, 229, -1, 84, 241, 82, -1, + 82, 241, 83, -1, 222, 242, 224, -1, + 224, 242, 243, -1, 244, 245, 246, -1, + 246, 245, 247, -1, 246, 248, 244, -1, + 244, 248, 249, -1, 248, 250, 249, -1, + 249, 250, 251, -1, 250, 252, 251, -1, + 251, 252, 253, -1, 254, 243, 255, -1, + 255, 243, 242, -1, 255, 256, 254, -1, + 254, 256, 257, -1, 256, 258, 257, -1, + 257, 258, 259, -1, 258, 260, 259, -1, + 259, 260, 261, -1, 260, 262, 261, -1, + 261, 262, 263, -1, 262, 253, 263, -1, + 263, 253, 252, -1, 109, 264, 106, -1, + 106, 264, 107, -1, 107, 265, 104, -1, + 104, 265, 105, -1, 245, 266, 247, -1, + 247, 266, 267, -1, 266, 268, 267, -1, + 267, 268, 269, -1, 270, 269, 271, -1, + 271, 269, 268, -1, 271, 272, 270, -1, + 270, 272, 273, -1, 272, 274, 273, -1, + 273, 274, 275, -1, 274, 276, 275, -1, + 275, 276, 277, -1, 276, 278, 277, -1, + 277, 278, 279, -1, 278, 280, 279, -1, + 279, 280, 281, -1, 280, 282, 281, -1, + 281, 282, 283, -1, 282, 284, 283, -1, + 283, 284, 285, -1, 284, 286, 285, -1, + 285, 286, 287, -1, 158, 288, 159, -1, + 159, 288, 161, -1, 286, 289, 287, -1, + 287, 289, 290, -1, 289, 291, 290, -1, + 290, 291, 292, -1, 293, 292, 294, -1, + 294, 292, 291, -1, 294, 193, 293, -1, + 293, 193, 192, -1, 186, 184, 27, -1, + 27, 184, 20, -1, 20, 184, 28, -1, + 28, 184, 182, -1, 28, 182, 18, -1, + 18, 182, 29, -1, 182, 177, 29, -1, + 29, 177, 16, -1, 16, 177, 30, -1, + 30, 177, 176, -1, 30, 176, 13, -1, + 13, 176, 31, -1, 31, 176, 32, -1, + 32, 176, 181, -1, 32, 181, 34, -1, + 34, 181, 35, -1, 181, 196, 35, -1, + 35, 196, 217, -1, 217, 196, 10, -1, + 10, 196, 207, -1, 10, 207, 54, -1, + 54, 207, 53, -1, 207, 210, 53, -1, + 53, 210, 55, -1, 55, 210, 52, -1, + 52, 210, 56, -1, 210, 212, 56, -1, + 56, 212, 50, -1, 50, 212, 57, -1, + 57, 212, 214, -1, 57, 214, 48, -1, + 48, 214, 58, -1, 214, 216, 58, -1, + 58, 216, 46, -1, 46, 216, 59, -1, + 59, 216, 205, -1, 59, 205, 44, -1, + 44, 205, 218, -1, 205, 203, 218, -1, + 218, 203, 42, -1, 42, 203, 60, -1, + 60, 203, 201, -1, 60, 201, 40, -1, + 40, 201, 61, -1, 201, 199, 61, -1, + 61, 199, 38, -1, 38, 199, 62, -1, + 62, 199, 63, -1, 199, 200, 63, -1, + 63, 200, 65, -1, 65, 200, 66, -1, + 66, 200, 220, -1, 66, 220, 85, -1, + 85, 220, 7, -1, 220, 231, 7, -1, + 7, 231, 86, -1, 86, 231, 84, -1, + 84, 231, 234, -1, 84, 234, 241, -1, + 241, 234, 83, -1, 83, 234, 87, -1, + 87, 234, 236, -1, 87, 236, 81, -1, + 81, 236, 88, -1, 236, 238, 88, -1, + 88, 238, 79, -1, 79, 238, 89, -1, + 89, 238, 240, -1, 89, 240, 77, -1, + 77, 240, 90, -1, 240, 229, 90, -1, + 90, 229, 75, -1, 75, 229, 91, -1, + 91, 229, 227, -1, 91, 227, 73, -1, + 73, 227, 92, -1, 227, 225, 92, -1, + 92, 225, 71, -1, 71, 225, 93, -1, + 93, 225, 223, -1, 93, 223, 69, -1, + 69, 223, 94, -1, 94, 223, 95, -1, + 95, 223, 224, -1, 95, 224, 97, -1, + 97, 224, 98, -1, 224, 243, 98, -1, + 98, 243, 117, -1, 117, 243, 5, -1, + 5, 243, 254, -1, 5, 254, 118, -1, + 118, 254, 116, -1, 254, 257, 116, -1, + 116, 257, 119, -1, 119, 257, 115, -1, + 115, 257, 259, -1, 115, 259, 120, -1, + 120, 259, 113, -1, 113, 259, 121, -1, + 121, 259, 261, -1, 121, 261, 111, -1, + 111, 261, 122, -1, 261, 263, 122, -1, + 122, 263, 109, -1, 109, 263, 264, -1, + 264, 263, 252, -1, 264, 252, 107, -1, + 107, 252, 265, -1, 252, 250, 265, -1, + 265, 250, 105, -1, 105, 250, 123, -1, + 123, 250, 248, -1, 123, 248, 103, -1, + 103, 248, 124, -1, 248, 246, 124, -1, + 124, 246, 101, -1, 101, 246, 125, -1, + 125, 246, 126, -1, 246, 247, 126, -1, + 126, 247, 128, -1, 128, 247, 129, -1, + 129, 247, 267, -1, 129, 267, 131, -1, + 131, 267, 132, -1, 267, 269, 132, -1, + 132, 269, 143, -1, 143, 269, 2, -1, + 2, 269, 270, -1, 2, 270, 144, -1, + 144, 270, 142, -1, 270, 273, 142, -1, + 142, 273, 145, -1, 145, 273, 141, -1, + 141, 273, 146, -1, 273, 275, 146, -1, + 146, 275, 139, -1, 139, 275, 147, -1, + 147, 275, 277, -1, 147, 277, 137, -1, + 137, 277, 148, -1, 277, 279, 148, -1, + 148, 279, 135, -1, 135, 279, 151, -1, + 151, 279, 281, -1, 151, 281, 150, -1, + 150, 281, 154, -1, 281, 283, 154, -1, + 154, 283, 152, -1, 152, 283, 157, -1, + 157, 283, 285, -1, 157, 285, 155, -1, + 155, 285, 160, -1, 285, 287, 160, -1, + 160, 287, 158, -1, 158, 287, 288, -1, + 288, 287, 161, -1, 287, 290, 161, -1, + 161, 290, 163, -1, 163, 290, 164, -1, + 164, 290, 292, -1, 164, 292, 168, -1, + 168, 292, 166, -1, 292, 293, 166, -1, + 166, 293, 175, -1, 175, 293, 173, -1, + 173, 293, 192, -1, 173, 192, 172, -1, + 172, 192, 171, -1, 171, 192, 174, -1, + 174, 192, 189, -1, 174, 189, 26, -1, + 26, 189, 25, -1, 189, 188, 25, -1, + 25, 188, 24, -1, 24, 188, 194, -1, + 194, 188, 186, -1, 194, 186, 22, -1, + 22, 186, 27, -1, 178, 179, 12, -1, + 12, 179, 15, -1, 179, 183, 15, -1, + 15, 183, 17, -1, 183, 185, 17, -1, + 17, 185, 19, -1, 185, 187, 19, -1, + 19, 187, 21, -1, 187, 190, 21, -1, + 21, 190, 23, -1, 190, 191, 23, -1, + 23, 191, 169, -1, 191, 193, 169, -1, + 169, 193, 170, -1, 193, 294, 170, -1, + 170, 294, 167, -1, 294, 291, 167, -1, + 167, 291, 165, -1, 165, 291, 162, -1, + 162, 291, 289, -1, 162, 289, 159, -1, + 159, 289, 286, -1, 159, 286, 156, -1, + 156, 286, 284, -1, 156, 284, 153, -1, + 153, 284, 282, -1, 153, 282, 149, -1, + 149, 282, 280, -1, 149, 280, 133, -1, + 133, 280, 278, -1, 133, 278, 134, -1, + 134, 278, 276, -1, 134, 276, 136, -1, + 136, 276, 274, -1, 136, 274, 138, -1, + 138, 274, 272, -1, 138, 272, 140, -1, + 140, 272, 271, -1, 140, 271, 0, -1, + 0, 271, 268, -1, 0, 268, 1, -1, + 1, 268, 130, -1, 268, 266, 130, -1, + 130, 266, 127, -1, 266, 245, 127, -1, + 127, 245, 99, -1, 245, 244, 99, -1, + 99, 244, 100, -1, 244, 249, 100, -1, + 100, 249, 102, -1, 249, 251, 102, -1, + 102, 251, 104, -1, 251, 253, 104, -1, + 104, 253, 106, -1, 253, 262, 106, -1, + 106, 262, 108, -1, 262, 260, 108, -1, + 108, 260, 110, -1, 260, 258, 110, -1, + 110, 258, 112, -1, 258, 256, 112, -1, + 112, 256, 114, -1, 256, 255, 114, -1, + 114, 255, 3, -1, 255, 242, 3, -1, + 3, 242, 4, -1, 4, 242, 96, -1, + 96, 242, 222, -1, 96, 222, 67, -1, + 67, 222, 221, -1, 67, 221, 68, -1, + 68, 221, 226, -1, 68, 226, 70, -1, + 70, 226, 228, -1, 70, 228, 72, -1, + 72, 228, 230, -1, 72, 230, 74, -1, + 74, 230, 239, -1, 74, 239, 76, -1, + 76, 239, 237, -1, 76, 237, 78, -1, + 78, 237, 235, -1, 78, 235, 80, -1, + 80, 235, 233, -1, 80, 233, 82, -1, + 82, 233, 232, -1, 82, 232, 8, -1, + 8, 232, 219, -1, 8, 219, 6, -1, + 6, 219, 64, -1, 219, 198, 64, -1, + 64, 198, 36, -1, 198, 197, 36, -1, + 36, 197, 37, -1, 197, 202, 37, -1, + 37, 202, 39, -1, 202, 204, 39, -1, + 39, 204, 41, -1, 204, 206, 41, -1, + 41, 206, 43, -1, 206, 215, 43, -1, + 43, 215, 45, -1, 215, 213, 45, -1, + 45, 213, 47, -1, 213, 211, 47, -1, + 47, 211, 49, -1, 211, 209, 49, -1, + 49, 209, 51, -1, 209, 208, 51, -1, + 51, 208, 11, -1, 208, 195, 11, -1, + 11, 195, 9, -1, 9, 195, 33, -1, + 33, 195, 180, -1, 33, 180, 14, -1, + 14, 180, 178, -1, 14, 178, 12, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 169, 169, 169, -1, 170, 170, 170, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 171, 171, 171, -1, 172, 172, 172, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 173, 173, 173, -1, 174, 174, 174, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 177, 177, 177, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 179, 179, 179, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 181, 181, 181, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 187, 187, 187, -1, 188, 188, 188, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 190, 190, 190, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 191, 191, 191, -1, 192, 192, 192, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 194, 194, 194, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 195, 195, 195, -1, 196, 196, 196, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 197, 197, 197, -1, 198, 198, 198, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 200, 200, 200, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 201, 201, 201, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 203, 203, 203, -1, 204, 204, 204, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 205, 205, 205, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 207, 207, 207, -1, 208, 208, 208, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 209, 209, 209, -1, 210, 210, 210, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 211, 211, 211, -1, 212, 212, 212, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 213, 213, 213, -1, 214, 214, 214, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 215, 215, 215, -1, 216, 216, 216, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 217, 217, 217, -1, 218, 218, 218, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 219, 219, 219, -1, 220, 220, 220, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 221, 221, 221, -1, 222, 222, 222, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 224, 224, 224, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 225, 225, 225, -1, 226, 226, 226, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 230, 230, 230, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 231, 231, 231, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 233, 233, 233, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + + } + + }, + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.0078125 0.1875 0.65625 + ambientIntensity 0.46584472 + specularColor 0 0.1 0.5 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.054964401 0.0125 -0.023521001, + 0.0546159 0.0131798 -0.024374001, + 0.055364501 0.0125 -0.022624999, + 0.054163702 0.0125 -0.025312999, + 0.0532961 0.0131651 -0.027093001, + 0.0546159 0.0138806 -0.024537001, + 0.055787299 0.0139105 -0.021777, + 0.055787299 0.0145843 -0.022035001, + 0.056809202 0.0146307 -0.019241, + 0.056809202 0.0152407 -0.019559, + 0.0576833 0.0153061 -0.016737999, + 0.0576833 0.0162641 -0.017417001, + 0.058412101 0.016378799 -0.014566, + 0.058412101 0.0171008 -0.015178, + 0.058998398 0.0172756 -0.012311, + 0.058998398 0.0201499 -0.014707, + 0.059445001 0.020571001 -0.011764, + 0.059445001 0.023581799 -0.014041, + 0.059757002 0.024248499 -0.011037, + 0.059757002 0.0257478 -0.01214, + 0.0599402 0.0265269 -0.0091319997, + 0.0599402 0.0280958 -0.010342, + 0.059999999 0.0289884 -0.0073220101, + 0.059999999 0.0306841 -0.0086840102, + 0.0599402 0.031699002 -0.0056380001, + 0.0599402 0.0334807 -0.0071799899, + 0.059757002 0.034627698 -0.0040939902, + 0.059757002 0.036484201 -0.005843, + 0.059445001 0.037772499 -0.0027089999, + 0.059445001 0.039671801 -0.0046840101, + 0.058998398 0.041099899 -0.0015210001, + 0.058998398 0.043001398 -0.00373599, + 0.058412101 0.044562198 -0.00056799297, + 0.058412101 0.046424299 -0.003026, + 0.0576833 0.048108499 0.000126007, + 0.0576833 0.049887601 -0.00257201, + 0.056809202 0.051683102 0.00054200698, + 0.0220857 0.089458697 0.0048090098, + 0.0248404 0.088420898 0.00372701, + 0.0220857 0.0896248 0.0025780001, + 0.0248404 0.088226303 0.0059349998, + 0.027557701 0.087069102 0.0046979999, + 0.027557701 0.086849302 0.006881, + 0.0302257 0.085577697 0.0054880101, + 0.0302257 0.085061103 0.0097890003, + 0.0328326 0.083695598 0.0082189897, + 0.0328326 0.083401203 0.010311, + 0.035366699 0.081933402 0.0085819997, + 0.035366699 0.0816027 0.010551, + 0.0378174 0.0800412 0.0086679999, + 0.0378174 0.079643399 0.010617, + 0.040174201 0.077997997 0.0085819997, + 0.040174201 0.077531204 0.010523, + 0.0424264 0.075811803 0.008343, + 0.0424264 0.075281702 0.010256, + 0.044564299 0.073499098 0.0079340097, + 0.044564299 0.072910301 0.0098120002, + 0.0465803 0.071076803 0.0073569901, + 0.0465803 0.0704339 0.0091939997, + 0.048467699 0.068562299 0.0066150101, + 0.048467699 0.067869902 0.0084070005, + 0.050219599 0.065972701 0.005715, + 0.050219599 0.065235801 0.0074579902, + 0.051830001 0.063325599 0.0046620001, + 0.051830001 0.062550902 0.0063510002, + 0.0532961 0.060640302 0.0034650001, + 0.0532961 0.059834499 0.0050959899, + 0.0546159 0.057935901 0.0021319999, + 0.0546159 0.0571055 0.003701, + 0.055787299 0.055230699 0.00067399599, + 0.055787299 0.054382201 0.0021790001, + 0.056809202 0.053338401 -0.002382, + 0.0546159 0.059379701 -0.001112, + 0.055787299 0.056722 -0.00245399, + 0.0546159 0.059989899 -0.0027769899, + 0.0532961 0.0620239 0.000110001, + 0.0532961 0.062598698 -0.00160201, + 0.051830001 0.064636201 0.001205, + 0.051830001 0.065170698 -0.00055200199, + 0.050219599 0.067198701 0.0021639999, + 0.050219599 0.067688398 0.00036500499, + 0.048467699 0.069694102 0.0029770101, + 0.048467699 0.070134401 0.00114101, + 0.0465803 0.072105303 0.00364101, + 0.0465803 0.072491497 0.00177499, + 0.044564299 0.074414998 0.0041530002, + 0.044564299 0.0747412 0.0022749901, + 0.0424264 0.0766045 0.00452299, + 0.0424264 0.076872103 0.0026199999, + 0.040174201 0.078663103 0.0047300002, + 0.040174201 0.078900598 0.0027059901, + 0.0378174 0.080609903 0.0046710102, + 0.0378174 0.081024297 0.00050300598, + 0.035366699 0.082661301 0.002295, + 0.0220857 0.089885898 -0.0041470001, + 0.0248404 0.088808797 -0.0051660002, + 0.0220857 0.089861304 -0.008649, + 0.019305199 0.090816297 -0.0077889999, + 0.019305199 0.090646103 -0.012324, + 0.0165099 0.091475099 -0.011614, + 0.0165099 0.091154397 -0.016171001, + 0.0137106 0.0918549 -0.015599, + 0.0137106 0.0913807 -0.020166, + 0.0109179 0.091950797 -0.019723, + 0.0109179 0.091320902 -0.024287, + 0.0081421202 0.091759801 -0.023963001, + 0.0081421202 0.090972401 -0.028511999, + 0.0053918599 0.091281898 -0.028294999, + 0.0053918599 0.090336502 -0.032816, + 0.00267513 0.090519503 -0.032692999, + 0.00267513 0.089417599 -0.037175, + 0 0.0894778 -0.037136, + 0 0.088221803 -0.041565001, + -0.00267513 0.089418098 -0.037174001, + -0.00267513 0.090520002 -0.032692999, + -0.0053918599 0.0903375 -0.032816, + -0.0053918599 0.091282599 -0.028294999, + -0.0081421202 0.090973496 -0.028511999, + -0.0081421202 0.0917603 -0.023963001, + -0.0109179 0.091321602 -0.024288001, + -0.0109179 0.091951601 -0.019723, + -0.0137106 0.091381699 -0.020166, + -0.0137106 0.091856599 -0.015599, + -0.0165099 0.091156401 -0.016171001, + -0.0165099 0.091477998 -0.011614, + -0.019305199 0.0906495 -0.012325, + -0.019305199 0.090820901 -0.0077889999, + -0.0220857 0.089793801 -0.010902, + 0.051830001 0.0131508 -0.029762, + 0.051374301 0.0125 -0.030494999, + 0.050219599 0.0131367 -0.032370999, + 0.0576833 0.018132599 -0.019347999, + 0.058412101 0.019726099 -0.017669, + 0.0576833 0.016925599 -0.018052001, + 0.056809202 0.0167506 -0.020922, + 0.056809202 0.0161495 -0.020262999, + 0.055787299 0.0160356 -0.023095001, + 0.055787299 0.0151756 -0.022365, + 0.0546159 0.0151111 -0.025145, + 0.0546159 0.0145384 -0.024804, + 0.0532961 0.0144931 -0.027535001, + 0.0532961 0.0138511 -0.027261, + 0.051830001 0.0138222 -0.029934, + 0.045067899 0.0074999998 -0.039108999, + 0.046573199 0.0125 -0.037312001, + 0.048901699 0.0074999998 -0.034265, + 0.040756401 0.0074999998 -0.043533001, + 0.042423598 0.0125 -0.041924, + -0.0053912001 0.0125 0.060247999, + -0.0046292599 0.0125 0.060304001, + -0.0053918599 0.0308768 0.060242001, + 0.00267513 0.062080499 0.056425001, + 0 0.062108699 0.056494001, + 0.00267513 0.059909798 0.057291999, + 0 0.064253204 0.055520002, + -0.00267513 0.062080801 0.056426998, + 0 0.059936602 0.057360999, + 0 0.057745099 0.058120001, + -0.00267513 0.059909899 0.057294, + -0.0053918599 0.061994899 0.056217998, + -0.00267513 0.0642239 0.055452, + 0 0.066361703 0.054439001, + 0.00267513 0.064223602 0.055450998, + 0.0053918599 0.0619945 0.056214999, + -0.00267513 0.053309601 0.059245002, + 0 0.0533324 0.059312999, + -0.00267513 0.0555178 0.058701999, + -0.0053918599 0.055444401 0.058495, + -0.0053918599 0.057642199 0.057844002, + -0.0081421202 0.05751 0.057489999, + -0.0081421202 0.059689 0.056729998, + -0.0109179 0.059489701 0.056221001, + -0.0081421202 0.061848599 0.055863, + -0.0053918599 0.0598283 0.057085, + -0.00267513 0.0577197 0.058052, + 0 0.055541899 0.058770001, + 0.00267513 0.055518001 0.058701001, + 0.00267513 0.057719801 0.058051001, + 0.0053918599 0.057642199 0.057842001, + 0.0053918599 0.059827998 0.057082999, + 0.0081421202 0.059688699 0.056726001, + -0.0053918599 0.064133897 0.055243999, + -0.00267513 0.066331103 0.054370999, + 0 0.068426102 0.053252999, + 0.00267513 0.066330701 0.054370001, + 0.0053918599 0.064133301 0.055241, + 0.0081421202 0.061847899 0.055858999, + 0.0109179 0.059489299 0.056216002, + 0.0081421202 0.0575101 0.057486001, + 0.0053918599 0.055444799 0.058492001, + 0.00267513 0.053309899 0.059243999, + 0 0.051121201 0.059751, + -0.00267513 0.0510999 0.059684001, + -0.0053918599 0.053240299 0.059039, + -0.0081421202 0.055319302 0.058141001, + -0.0109179 0.0573209 0.056981001, + -0.0137106 0.0592281 0.055553, + -0.0109179 0.061639201 0.055353999, + -0.0081421202 0.063980602 0.054887999, + -0.0053918599 0.066237003 0.054163001, + -0.00267513 0.068394199 0.053185001, + 0 0.070438899 0.051964998, + 0.00267513 0.0683937 0.053183999, + 0.0053918599 0.066236198 0.054161001, + 0.0081421202 0.063979603 0.054884002, + 0.0109179 0.061638199 0.055348001, + 0.0137106 0.059227601 0.055546001, + 0.0109179 0.057321101 0.056976002, + 0.0081421202 0.055319902 0.058137, + 0.0053918599 0.053240899 0.059036002, + 0.00267513 0.051100101 0.059682999, + 0 0.048913099 0.060086999, + -0.00267513 0.0488934 0.06002, + -0.0053918599 0.051034801 0.059478, + -0.0081421202 0.053122401 0.058685999, + -0.0109179 0.055140398 0.057634, + -0.0137106 0.057072699 0.056313999, + -0.0165099 0.058902901 0.054722998, + -0.0137106 0.0613642 0.054685, + -0.0109179 0.063761003 0.05438, + -0.0081421202 0.066076703 0.053808, + -0.0053918599 0.068296097 0.052978002, + -0.00267513 0.070405804 0.051897999, + 0 0.072392799 0.050579999, + 0.00267513 0.0704052 0.051897001, + 0.0053918599 0.068295099 0.052974999, + 0.0081421202 0.0660754 0.053803999, + 0.0109179 0.063759699 0.054373998, + 0.0137106 0.061363 0.054678001, + 0.0165099 0.0589022 0.054714002, + 0.0137106 0.0570729 0.056308001, + 0.0109179 0.055141199 0.057629, + 0.0081421202 0.053123299 0.058681998, + 0.0053918599 0.051035199 0.059475999, + 0.00267513 0.048893198 0.060019001, + 0 0.046718199 0.060323, + -0.00267513 0.046700101 0.060256001, + -0.0053918599 0.0488327 0.059815001, + -0.0081421202 0.050923999 0.059126001, + -0.0109179 0.052953601 0.058180001, + -0.0137106 0.054905601 0.056968, + -0.0165099 0.0567641 0.055484999, + -0.019305199 0.058512799 0.053725999, + -0.0165099 0.0610223 0.053854, + -0.0137106 0.063472703 0.053711001, + -0.0109179 0.065847099 0.053300001, + -0.0081421202 0.068128802 0.052623998, + -0.0053918599 0.070303701 0.051690999, + -0.00267513 0.0723584 0.050512999, + 0 0.0742805 0.0491, + 0.00267513 0.072357699 0.050510999, + 0.0053918599 0.070302501 0.051688001, + 0.0081421202 0.068127297 0.052618999, + 0.0109179 0.0658454 0.053293999, + 0.0137106 0.063471101 0.053704001, + 0.0165099 0.0610209 0.053846002, + 0.019305199 0.058511999 0.053716, + 0.0165099 0.056764301 0.055477001, + 0.0137106 0.054906599 0.056961998, + 0.0109179 0.0529548 0.058175001, + 0.0081421202 0.050924599 0.059122998, + 0.0053918599 0.048832301 0.059813, + 0.00267513 0.0466993 0.060254999, + 0 0.044567902 0.060456999, + -0.00267513 0.044551302 0.060391001, + -0.0053918599 0.046643902 0.060052, + -0.0081421202 0.048729099 0.059464999, + -0.0109179 0.050765499 0.058623001, + -0.0137106 0.052732199 0.057517, + -0.0165099 0.054613601 0.056141, + -0.019305199 0.056394 0.05449, + -0.0220857 0.058056802 0.052561, + -0.019305199 0.060612202 0.052857, + -0.0165099 0.0631143 0.05288, + -0.0137106 0.065545604 0.052632999, + -0.0109179 0.067889303 0.052115999, + -0.0081421202 0.070129603 0.051337998, + -0.0053918599 0.072252497 0.050306, + -0.00267513 0.074244902 0.049033999, + 0 0.076094903 0.047532, + 0.00267513 0.074244097 0.049033001, + 0.0053918599 0.072251 0.050303999, + 0.0081421202 0.0701278 0.051332999, + 0.0109179 0.067887299 0.052111, + 0.0137106 0.065543503 0.052625, + 0.0165099 0.063112304 0.052871998, + 0.019305199 0.0606106 0.052847002, + 0.0220857 0.058055799 0.052549999, + 0.019305199 0.056394201 0.054480001, + 0.0165099 0.054614801 0.056132998, + 0.0137106 0.0527336 0.05751, + 0.0109179 0.0507663 0.058618002, + 0.0081421202 0.0487285 0.059462, + 0.0053918599 0.046642099 0.060051002, + 0.00267513 0.044550199 0.060391001, + 0 0.042432401 0.0605, + -0.00267513 0.042416699 0.060433999, + -0.0053918599 0.044499099 0.060187999, + -0.0081421202 0.0465477 0.059703, + -0.0109179 0.0485809 0.058963999, + -0.0137106 0.050557401 0.057962, + -0.0165099 0.0524568 0.056690998, + -0.019305199 0.054263499 0.055148002, + -0.0220857 0.0559614 0.053326, + -0.0248404 0.057534002 0.051226001, + -0.0220857 0.060132898 0.051692002, + -0.019305199 0.062684402 0.051883999, + -0.0165099 0.065170802 0.051801998, + -0.0137106 0.067574799 0.051449999, + -0.0109179 0.069880299 0.050832, + -0.0081421202 0.072071701 0.049954001, + -0.0053918599 0.074135102 0.048827998, + -0.00267513 0.076058201 0.047465, + 0 0.077830501 0.045878999, + 0.00267513 0.076057203 0.047463998, + 0.0053918599 0.0741335 0.048826002, + 0.0081421202 0.072069503 0.04995, + 0.0109179 0.069877803 0.050825998, + 0.0137106 0.067572303 0.051442999, + 0.0165099 0.065168202 0.051794, + 0.019305199 0.0626821 0.051874001, + 0.0220857 0.060130998 0.051679999, + 0.0248404 0.057532899 0.051213, + 0.0220857 0.055961601 0.053316001, + 0.019305199 0.054264899 0.055137999, + 0.0165099 0.052458599 0.056683999, + 0.0137106 0.0505585 0.057955999, + 0.0109179 0.048580099 0.058959998, + 0.0081421202 0.046545099 0.059702002, + 0.0053918599 0.044496998 0.060187001, + 0.00267513 0.042416301 0.060433999, + -0.0053918599 0.042368099 0.060231999, + -0.00267513 0.0401132 0.060435001, + -0.0081421202 0.044409901 0.059841, + -0.0109179 0.046409901 0.059204999, + -0.0137106 0.048386399 0.058306001, + -0.0165099 0.050298799 0.05714, + -0.019305199 0.052126698 0.055702001, + -0.0220857 0.053854201 0.053987, + -0.0248404 0.0554654 0.051993001, + -0.027557701 0.056944899 0.049720999, + -0.0248404 0.059583299 0.050354999, + -0.0220857 0.062181801 0.050717998, + -0.019305199 0.064721197 0.050806999, + -0.0165099 0.0671838 0.050620999, + -0.0137106 0.069553003 0.050167002, + -0.0109179 0.071812801 0.049449999, + -0.0081421202 0.073947802 0.048478, + -0.0053918599 0.075944699 0.047261, + -0.00267513 0.077792503 0.045813002, + 0 0.079481803 0.044149999, + 0.00267513 0.077791497 0.045812, + 0.0053918599 0.075942799 0.047258001, + 0.0081421202 0.073945299 0.048473999, + 0.0109179 0.071809903 0.049445, + 0.0137106 0.069549903 0.050159998, + 0.0165099 0.067180701 0.050613001, + 0.019305199 0.064718202 0.050797001, + 0.0220857 0.0621791 0.050707001, + 0.0248404 0.059581202 0.050342999, + 0.027557701 0.0569437 0.049706999, + 0.0248404 0.055465698 0.05198, + 0.0220857 0.053855799 0.053975999, + 0.019305199 0.052128799 0.055693001, + 0.0165099 0.050299998 0.057133, + 0.0137106 0.0483854 0.058301002, + 0.0109179 0.046406399 0.059202, + 0.0081421202 0.044406701 0.059841, + 0.0053918599 0.042367399 0.060231999, + 0.00267513 0.0401132 0.060435001, + 0 0.040127698 0.060501002, + 0 0.0309135 0.0605, + -0.0053918599 0.040068701 0.060235001, + -0.00267513 0.0309045 0.060435999, + -0.0081421202 0.042285401 0.059888002, + -0.0109179 0.044282001 0.059346002, + -0.0137106 0.0462288 0.05855, + -0.0165099 0.048144501 0.057487, + -0.019305199 0.049988601 0.056154002, + -0.0220857 0.051740699 0.054544002, + -0.0248404 0.053385001 0.052655999, + -0.027557701 0.054906599 0.050489999, + -0.0302257 0.054285899 0.048820999, + -0.027557701 0.052856501 0.051157001, + -0.0248404 0.051298302 0.053218, + -0.0220857 0.049626101 0.055001002, + -0.019305199 0.047854401 0.056506, + -0.0165099 0.046003599 0.057735998, + -0.0137106 0.044113901 0.058695, + -0.0109179 0.042166799 0.059395999, + -0.0081421202 0.039992899 0.059893001, + -0.00289505 0.0125 0.060430001, + -0.0046305298 0.0074999998 0.060320999, + 0.0081421202 0.021683199 0.059930999, + 0.0088465102 0.0125 0.059843998, + 0.0109179 0.017083 0.059486002, + 0.0137072 0.0125 0.058897, + 0.013778 0.0125 0.058881, + 0.0137106 0.0170689 0.058894001, + 0.0117463 0.0125 0.059339002, + 0.0137106 0.021618299 0.058871001, + 0.0165099 0.021572599 0.058122002, + 0.0165099 0.030561499 0.058042999, + 0.019305199 0.0304287 0.057116002, + 0.019305199 0.039352901 0.057009999, + 0.0220857 0.039104801 0.055892002, + 0.0220857 0.041310899 0.055856999, + 0.0248404 0.040999301 0.054566, + 0.0248404 0.043014601 0.054478999, + 0.027557701 0.042634498 0.053013999, + 0.027557701 0.044638399 0.052831002, + 0.0302257 0.0441841 0.051192999, + 0.0302257 0.046199199 0.050905, + 0.0328326 0.0456644 0.049095001, + 0.0328326 0.047653101 0.048705999, + 0.035366699 0.047031801 0.046728, + 0.035366699 0.048980501 0.046238001, + 0.0378174 0.048268098 0.044098999, + 0.0378174 0.050169699 0.043508001, + 0.040174201 0.049362499 0.041216001, + 0.0378174 0.052063599 0.042824, + 0.035366699 0.0509253 0.045653999, + 0.0328326 0.049641799 0.048223, + 0.0302257 0.0482243 0.050524, + 0.027557701 0.046686102 0.052552, + 0.0248404 0.045047399 0.054304998, + 0.0220857 0.043352 0.055780001, + 0.019305199 0.0415827 0.056983002, + 0.0165099 0.039565101 0.057966001, + 0.0137106 0.0306722 0.058816001, + 0.0109179 0.021655099 0.059473, + 0.0109179 0.030761199 0.059438001, + 0.0137106 0.039742101 0.058763999, + 0.0165099 0.0418153 0.057946999, + 0.019305199 0.0436465 0.056914002, + 0.0220857 0.045410499 0.055613998, + 0.0248404 0.047124401 0.054035001, + 0.027557701 0.048744202 0.052179001, + 0.0302257 0.050249599 0.050048999, + 0.0328326 0.051626801 0.047646001, + 0.035366699 0.0528627 0.044973999, + 0.035366699 0.0547885 0.044197001, + 0.0328326 0.055570502 0.046195999, + 0.0328326 0.057517901 0.045322999, + 0.0302257 0.058273699 0.047161002, + 0.0302257 0.0602316 0.046188999, + 0.027557701 0.060953099 0.047862999, + 0.027557701 0.062909797 0.04679, + 0.0248404 0.063589104 0.048294999, + 0.0248404 0.065532997 0.047121, + 0.0220857 0.066162199 0.048455, + 0.0220857 0.068081997 0.047180001, + 0.019305199 0.068653397 0.04834, + 0.019305199 0.070538104 0.046967, + 0.0165099 0.071045801 0.047956001, + 0.0165099 0.072884202 0.046487998, + 0.0137106 0.073323101 0.047309998, + 0.0137106 0.075104602 0.04575, + 0.0109179 0.075469799 0.046406999, + 0.0109179 0.077185102 0.044760998, + 0.0081421202 0.077472404 0.045258999, + 0.0081421202 0.079112798 0.043533999, + 0.0053918599 0.079319902 0.043880001, + 0.0053918599 0.080876999 0.042082001, + 0.00267513 0.081002198 0.042282999, + 0.00267513 0.082468398 0.040419001, + 0 0.082510799 0.040484998, + 0 0.0838807 0.038564, + -0.00267513 0.082469702 0.04042, + -0.00267513 0.081003398 0.042284001, + -0.0053918599 0.080879398 0.042084001, + -0.0053918599 0.0793221 0.043882001, + -0.0081421202 0.079116203 0.043536998, + -0.0081421202 0.077475503 0.045263, + -0.0109179 0.0771892 0.044766001, + -0.0109179 0.075473599 0.046411999, + -0.0137106 0.075109303 0.045756001, + -0.0137106 0.073327303 0.047316, + -0.0165099 0.072889298 0.046496, + -0.0165099 0.071050197 0.047965001, + -0.019305199 0.0705432 0.046976998, + -0.019305199 0.068657801 0.048349999, + -0.0220857 0.068086997 0.047191001, + -0.0220857 0.066166297 0.048466001, + -0.0248404 0.065537699 0.047134001, + -0.0248404 0.063592903 0.048308, + -0.027557701 0.062913999 0.046805002, + -0.027557701 0.0609564 0.047876999, + -0.0302257 0.060235199 0.046204999, + -0.0302257 0.058276299 0.047177002, + -0.0328326 0.057520699 0.045338999, + -0.0328326 0.055571899 0.046213001, + -0.035366699 0.054790001 0.044215001, + -0.035366699 0.052862301 0.044992, + -0.0165099 0.039565202 0.057966001, + -0.0137106 0.039742202 0.058763999, + -0.0165099 0.041817602 0.057946999, + -0.019305199 0.041585401 0.056983002, + -0.019305199 0.043653999 0.056915998, + -0.0220857 0.043360598 0.055782001, + -0.0220857 0.045417599 0.055619001, + -0.0248404 0.045055401 0.054310001, + -0.0248404 0.047126301 0.054042999, + -0.027557701 0.046688199 0.052561, + -0.027557701 0.048742201 0.052189998, + -0.0302257 0.048222002 0.050535999, + -0.0302257 0.050246298 0.050062001, + -0.0328326 0.049638201 0.048238002, + -0.0328326 0.051624399 0.047662001, + -0.035366699 0.0509228 0.045671001, + -0.0378174 0.052063201 0.042842001, + -0.019305199 0.030429799 0.057116002, + -0.0220857 0.0214555 0.056177001, + -0.020158799 0.0125 0.057011999, + -0.0030847499 0.0125 -0.059420999, + -0.002688 0.0125 -0.059431002, + -0.0046305298 0.0074999998 -0.059321001, + 0.00154487 0.0074999998 -0.05948, + 0.026817599 0.053653099 -0.171, + 0.0275521 0.053284999 -0.171, + 0.026825599 0.053669199 -0.191, + 0.032192402 0.0506116 -0.171, + 0.032827299 0.050211199 -0.171, + 0.0322018 0.050626501 -0.191, + -0.00267493 0.0599325 -0.171, + -0.0030887299 0.0599204 -0.191, + -0.0030374301 0.059923101 -0.171, + -0.033491299 0.0125 0.050276, + -0.035362199 0.0125 0.048960999, + -0.033494599 0.0074999998 0.050280999, + -0.035366699 0.0146786 0.048946999, + -0.0328326 0.016882399 0.050639998, + -0.0332799 0.0125 0.050423998, + -0.0328269 0.0125 0.050710998, + -0.0307914 0.0125 0.051996998, + -0.0302257 0.0212081 0.052113999, + -0.028228801 0.0125 0.053445, + -0.030219801 0.0125 0.05232, + -0.0281986 0.0074999998 0.053461, + 0.051042698 0.015985001 -0.033481002, + 0.050219599 0.015903899 -0.034809999, + 0.051830001 0.016664701 -0.033663001, + -0.0465803 0.0154075 -0.039112002, + -0.0465803 0.0155251 -0.039510999, + -0.045588002 0.0153585 -0.040325001, + -0.047540501 0.0155878 -0.038268998, + -0.0465803 0.0155959 -0.039925002, + -0.048467699 0.015749499 -0.037409, + -0.048467699 0.0161171 -0.039028, + -0.055787299 0.0223398 -0.033682, + -0.055787299 0.0216594 -0.032111999, + -0.056809202 0.0233895 -0.030532001, + -0.056809202 0.024168501 -0.032203998, + -0.0576833 0.025351901 -0.02902, + -0.0576833 0.026209399 -0.030817, + -0.058412101 0.027523 -0.027621999, + -0.058412101 0.028435299 -0.029563, + -0.058998398 0.029872401 -0.026380001, + -0.058998398 0.0308112 -0.028480001, + -0.059445001 0.0323622 -0.025332, + -0.059445001 0.033295501 -0.027598999, + -0.059757002 0.034947202 -0.024507999, + -0.059757002 0.0358399 -0.026945001, + -0.0599402 0.037579902 -0.023928, + -0.0599402 0.0383978 -0.026528001, + -0.059999999 0.040227201 -0.023574, + -0.059999999 0.0409371 -0.026324, + -0.0599402 0.042861801 -0.023415999, + -0.0599402 0.043436401 -0.026298, + -0.059757002 0.045464002 -0.023419, + -0.059757002 0.045879401 -0.026409, + -0.059445001 0.048014801 -0.023549, + -0.059445001 0.048257999 -0.026626, + -0.058998398 0.050489299 -0.023796, + -0.058998398 0.050547902 -0.026922001, + -0.058412101 0.052858099 -0.024134999, + -0.058412101 0.0527547 -0.027350999, + -0.0576833 0.0551278 -0.024622999, + -0.0576833 0.054963201 -0.028023001, + -0.056809202 0.057387002 -0.025369, + -0.056809202 0.0571649 -0.028865, + -0.055787299 0.059627 -0.026296999, + -0.055787299 0.059335299 -0.029872, + -0.0546159 0.061822299 -0.027402001, + -0.0546159 0.061453499 -0.03105, + -0.0532961 0.063950799 -0.028688001, + -0.0532961 0.063498601 -0.032405999, + -0.051830001 0.065990902 -0.030161001, + -0.051830001 0.065448903 -0.033945002, + -0.050219599 0.067920402 -0.031824999, + -0.050219599 0.067281798 -0.035670001, + -0.048467699 0.069716603 -0.033682, + -0.048467699 0.0689748 -0.037581, + -0.0465803 0.0713576 -0.035728998, + -0.0465803 0.070511602 -0.039675001, + -0.044564299 0.072827101 -0.037962999, + -0.044564299 0.071877599 -0.041955002, + -0.0424264 0.074109599 -0.040383998, + -0.0424264 0.073044203 -0.044419002, + -0.040174201 0.075177699 -0.042987999, + -0.040174201 0.073991299 -0.047052, + -0.0378174 0.076014198 -0.045756999, + -0.0378174 0.0747042 -0.049835, + -0.035366699 0.076605499 -0.048672002, + -0.035366699 0.075169399 -0.052749, + -0.0328326 0.076938704 -0.051713001, + -0.0328326 0.075374402 -0.055776998, + -0.0302257 0.077002302 -0.054862998, + -0.0302257 0.075309999 -0.058897998, + -0.027557701 0.076791197 -0.0581, + -0.027557701 0.073375501 -0.066290997, + -0.0248404 0.074706003 -0.065632001, + -0.0248404 0.071537398 -0.07401, + -0.0220857 0.072716497 -0.073477, + -0.0220857 0.069804199 -0.082023002, + -0.019305199 0.070831597 -0.081602, + -0.019305199 0.068182103 -0.090294003, + -0.0165099 0.069060303 -0.089971997, + -0.0165099 0.066679798 -0.098791003, + -0.0137106 0.067411698 -0.098553002, + -0.0137106 0.065305397 -0.107478, + -0.0109179 0.065893799 -0.107311, + -0.0109179 0.064064302 -0.116325, + -0.0081421202 0.064512298 -0.116216, + -0.0081421202 0.062961802 -0.12529799, + -0.0053918599 0.063274898 -0.12523501, + -0.0053918599 0.062005602 -0.13436601, + -0.00267513 0.062189501 -0.13433699, + -0.00267513 0.061203498 -0.143499, + 0 0.061264101 -0.143492, + 0 0.060561098 -0.152668, + 0.00267513 0.061205 -0.1435, + 0.00267513 0.0621906 -0.13433699, + 0.0053918599 0.0620078 -0.134367, + 0.0053918599 0.063276798 -0.125236, + 0.0081421202 0.0629647 -0.12530001, + 0.0081421202 0.064515598 -0.116219, + 0.0109179 0.064068697 -0.116329, + 0.0109179 0.065899096 -0.107316, + 0.0137106 0.065312199 -0.107484, + 0.0137106 0.067419402 -0.098558001, + 0.0165099 0.066689096 -0.098797001, + 0.0165099 0.069069803 -0.089978002, + 0.019305199 0.068193197 -0.090301998, + 0.019305199 0.070841603 -0.081609003, + 0.0220857 0.069815598 -0.082030997, + 0.0220857 0.072724998 -0.073484004, + 0.0248404 0.071547002 -0.074018002, + 0.0248404 0.074710399 -0.065636002, + 0.027557701 0.0733805 -0.066295996, + 0.027557701 0.076789796 -0.058100998, + 0.0302257 0.075308502 -0.058899, + 0.0302257 0.077001303 -0.054862998, + 0.0328326 0.075373396 -0.055776, + 0.0328326 0.076936297 -0.051713001, + 0.035366699 0.075166903 -0.052749, + 0.035366699 0.0766012 -0.048672002, + 0.0378174 0.074699499 -0.049835, + 0.0378174 0.076007903 -0.045758002, + 0.040174201 0.073984601 -0.047053002, + 0.040174201 0.075170398 -0.042989001, + 0.0424264 0.073036499 -0.04442, + 0.0424264 0.074103497 -0.040383998, + 0.044564299 0.071871199 -0.041955002, + 0.044564299 0.072824001 -0.037960999, + 0.0465803 0.070508301 -0.039671998, + 0.0465803 0.071354099 -0.035728, + 0.048467699 0.068971097 -0.037579998, + 0.048467699 0.069710597 -0.033681002, + 0.050219599 0.067275703 -0.035668999, + 0.050219599 0.067911401 -0.031824, + 0.051830001 0.065439597 -0.033944, + 0.051830001 0.065978497 -0.030161001, + 0.0532961 0.063485898 -0.032405999, + 0.0532961 0.063935101 -0.028689999, + 0.0546159 0.061437398 -0.031052001, + 0.0546159 0.061804298 -0.027409, + 0.055787299 0.0593169 -0.029879, + 0.055787299 0.0596085 -0.026314, + 0.056809202 0.057146002 -0.028881, + 0.056809202 0.057370301 -0.025397001, + 0.0576833 0.054946199 -0.028051, + 0.0576833 0.0551158 -0.024641, + 0.058412101 0.0527426 -0.027369, + 0.058412101 0.052848399 -0.024133001, + 0.058998398 0.0505381 -0.02692, + 0.058998398 0.050473999 -0.023798, + 0.059445001 0.048242498 -0.026629001, + 0.059445001 0.047992401 -0.023558, + 0.059757002 0.0458568 -0.026418, + 0.059757002 0.0454363 -0.023434, + 0.0599402 0.043408599 -0.026311999, + 0.0599402 0.042833 -0.023436001, + 0.059999999 0.040908299 -0.026342999, + 0.059999999 0.040200599 -0.023597, + 0.0599402 0.038371202 -0.026551001, + 0.0599402 0.037556998 -0.023955001, + 0.059757002 0.035817102 -0.026972, + 0.059757002 0.034929 -0.024537001, + 0.059445001 0.0332774 -0.027628001, + 0.059445001 0.0323487 -0.025362, + 0.058998398 0.030797901 -0.028510001, + 0.058998398 0.0298634 -0.02641, + 0.058412101 0.028426301 -0.029593, + 0.058412101 0.027518 -0.027651999, + 0.0576833 0.0262045 -0.030846, + 0.0576833 0.0253525 -0.029048, + 0.056809202 0.0241691 -0.032232001, + 0.056809202 0.0233957 -0.030556999, + 0.055787299 0.022345901 -0.033707999, + 0.055787299 0.0216552 -0.032131001, + 0.0546159 0.0207406 -0.035225, + 0.0546159 0.020156899 -0.033721998, + 0.0532961 0.0193756 -0.036738001, + 0.0532961 0.018867699 -0.035278998, + 0.051830001 0.018219899 -0.038197, + 0.051830001 0.017734401 -0.036695998, + 0.050219599 0.017221199 -0.039503999, + 0.050219599 0.016824501 -0.037948001, + 0.048467699 0.01644 -0.040635001, + 0.048467699 0.0161146 -0.039028, + 0.0465803 0.0158523 -0.041586, + 0.0465803 0.015592 -0.039928, + 0.045588002 0.0154564 -0.040727999, + 0.044564299 0.0154445 -0.042348001, + 0.047540501 0.015667999 -0.038681999, + 0.0465803 0.0155177 -0.03951, + 0.045588002 0.015343 -0.040328, + 0.044564299 0.0152953 -0.041515, + 0.0423088 0.0125 -0.042043999, + 0.040746599 0.0125 -0.043522999, + 0.0424264 0.0130855 -0.041971002, + 0.040174201 0.0130741 -0.044110999, + -0.0465803 0.073556803 -0.011773, + -0.0465803 0.073537797 -0.015767001, + -0.048467699 0.071386904 -0.014036, + -0.048467699 0.071313299 -0.010123, + -0.050219599 0.069116101 -0.012528, + -0.050219599 0.068964504 -0.0087139998, + -0.051830001 0.066754602 -0.011255, + -0.051830001 0.0666591 -0.0094170095, + -0.0532961 0.064424202 -0.012049, + -0.0532961 0.064312503 -0.010317, + -0.055787299 0.0596641 -0.014098, + -0.055787299 0.059468798 -0.012404, + -0.0546159 0.0619119 -0.011319, + -0.0546159 0.0620648 -0.013028, + -0.0532961 0.064493001 -0.013855, + -0.051830001 0.066855803 -0.015003, + -0.050219599 0.069143102 -0.016375, + -0.048467699 0.071325399 -0.017964, + -0.0465803 0.073379703 -0.019768, + -0.044564299 0.075545497 -0.017719001, + -0.044564299 0.075283803 -0.021788999, + -0.0424264 0.077387497 -0.019893, + -0.0424264 0.077015497 -0.024022, + -0.040174201 0.079042204 -0.022283999, + -0.040174201 0.078553103 -0.026465001, + 0.048467699 0.0137664 -0.035087001, + 0.0465803 0.0137399 -0.037542, + 0.048467699 0.0143629 -0.035383999, + 0.050219599 0.0144051 -0.032837, + 0.052581199 0.0161501 -0.030772001, + 0.0532961 0.016233999 -0.029394999, + 0.052581199 0.0157566 -0.030033, + 0.051830001 0.0157023 -0.031383999, + 0.051830001 0.0154012 -0.030986, + 0.0532961 0.0154852 -0.028281, + 0.051830001 0.0149851 -0.030579999, + 0.050219599 0.0149242 -0.033209998, + 0.048467699 0.0148649 -0.035767, + 0.0465803 0.014322 -0.037847001, + 0.044564299 0.0137143 -0.039903998, + 0.044564299 0.0130975 -0.039717998, + 0.044344399 0.0125 -0.039918002, + 0.046273202 0.0125 -0.037694, + 0.045055199 0.0125 -0.039097998, + 0.0465803 0.01311 -0.037358999, + 0.0484582 0.0125 -0.03486, + 0.0480907 0.0125 -0.035379, + 0.048467699 0.0131232 -0.034906998, + 0.050219599 0.0137939 -0.032547001, + 0.051830001 0.0144486 -0.030216999, + 0.0532961 0.0150475 -0.027887, + 0.0546159 0.0159228 -0.025900001, + 0.0576833 0.020434299 -0.021921, + 0.058412101 0.022229901 -0.020130999, + 0.0576833 0.019301301 -0.020638, + 0.056809202 0.0188771 -0.023602, + 0.056809202 0.017833401 -0.022265, + 0.055787299 0.017535901 -0.025167, + 0.055787299 0.016576501 -0.023777001, + 0.0546159 0.0164041 -0.026605001, + 0.0532961 0.015811499 -0.028666999, + 0.0546159 0.0172411 -0.028042, + 0.055787299 0.0184552 -0.026551001, + 0.056809202 0.0198841 -0.024932001, + 0.0576833 0.021550201 -0.023193, + 0.058412101 0.023357101 -0.021368001, + 0.058998398 0.024160201 -0.018268, + 0.058998398 0.0253633 -0.019586001, + 0.059445001 0.0262847 -0.016469, + 0.059445001 0.0276099 -0.01791, + 0.059757002 0.0286464 -0.0148, + 0.059757002 0.0300574 -0.01639, + 0.0599402 0.031204401 -0.013304, + 0.0599402 0.0326901 -0.015071, + 0.059999999 0.033951499 -0.012003, + 0.059999999 0.035481598 -0.013966, + 0.0599402 0.036864899 -0.010902, + 0.0599402 0.038401902 -0.013074, + 0.059757002 0.039916001 -0.0099999998, + 0.059757002 0.041423 -0.012385, + 0.059445001 0.0430746 -0.0092940098, + 0.059445001 0.044513501 -0.011891, + 0.058998398 0.046295799 -0.0088, + 0.058998398 0.047630299 -0.011599, + 0.058412101 0.049530901 -0.0085300002, + 0.058412101 0.050725002 -0.011513, + 0.0576833 0.052729499 -0.0084849996, + 0.0576833 0.053754099 -0.011627, + 0.056809202 0.055846501 -0.008657, + 0.056809202 0.056675401 -0.011929, + 0.055787299 0.0588383 -0.0090319999, + 0.055787299 0.0594543 -0.012406, + 0.0546159 0.061669499 -0.0095959902, + -0.035366699 0.082027003 -0.025544001, + -0.035366699 0.081713103 -0.027681001, + -0.0378174 0.080490001 -0.024883, + -0.0328326 0.083416402 -0.026357001, + -0.0328326 0.082696803 -0.030665001, + -0.0302257 0.084279001 -0.029495001, + -0.0302257 0.083428301 -0.033824001, + -0.027557701 0.084881097 -0.032802001, + -0.027557701 0.083891198 -0.037140999, + -0.0248404 0.085208103 -0.036258001, + -0.0248404 0.084076896 -0.040594999, + -0.0220857 0.085252203 -0.039841998, + -0.0220857 0.083979003 -0.044160999, + -0.019305199 0.085008301 -0.043531001, + -0.019305199 0.083593197 -0.047818001, + -0.0165099 0.084475897 -0.047301002, + -0.0165099 0.082919002 -0.051543999, + -0.0137106 0.083655797 -0.051130999, + -0.0137106 0.081959799 -0.055317, + -0.0109179 0.082552001 -0.054997999, + -0.0109179 0.079124503 -0.063445002, + -0.0081421202 0.079574898 -0.063222997, + -0.0081421202 0.076399297 -0.071814001, + -0.0053918599 0.0767138 -0.071672998, + -0.0053918599 0.073797099 -0.080390997, + -0.00267513 0.073981903 -0.080316, + -0.00267513 0.071329698 -0.089140996, + 0 0.071390502 -0.089120001, + 0 0.069008201 -0.098035999, + 0.00267513 0.0713313 -0.089142002, + 0.00267513 0.0739832 -0.080316998, + 0.0053918599 0.073799901 -0.080392003, + 0.0053918599 0.076715797 -0.071673997, + 0.0081421202 0.076402403 -0.071817003, + 0.0081421202 0.079576299 -0.063224003, + 0.0109179 0.079126403 -0.063446999, + 0.0109179 0.082551397 -0.054997999, + 0.0137106 0.081959099 -0.055317, + 0.0137106 0.083655298 -0.051130999, + 0.0165099 0.082918502 -0.051543999, + 0.0165099 0.084474698 -0.047301002, + 0.019305199 0.083591796 -0.047818001, + 0.019305199 0.085005999 -0.043531999, + 0.0220857 0.083976299 -0.044160999, + 0.0220857 0.0852485 -0.039843, + 0.0248404 0.084072702 -0.040594999, + 0.0248404 0.085203603 -0.036258999, + 0.027557701 0.083886199 -0.037142001, + 0.027557701 0.084877104 -0.032800999, + 0.0302257 0.083423898 -0.033824001, + 0.0302257 0.0842769 -0.029494001, + 0.0328326 0.082694598 -0.030664001, + 0.0328326 0.083413899 -0.026357001, + 0.035366699 0.081710398 -0.02768, + 0.035366699 0.082298897 -0.023402, + 0.0378174 0.080485299 -0.024882, + 0.0378174 0.080946602 -0.020643, + 0.040174201 0.079034999 -0.022283001, + 0.040174201 0.079374798 -0.018093999, + 0.0424264 0.077377297 -0.019893, + 0.0424264 0.077602804 -0.015763, + 0.044564299 0.075532399 -0.017720999, + 0.044564299 0.075650699 -0.013659, + 0.0465803 0.073522501 -0.015773, + 0.0465803 0.073541299 -0.011787, + 0.048467699 0.071370803 -0.01405, + 0.048467699 0.071299002 -0.010146, + 0.050219599 0.069101296 -0.012552, + 0.050219599 0.068953998 -0.0087299999, + 0.051830001 0.066743903 -0.011271, + 0.051830001 0.066510797 -0.0076529998, + 0.0532961 0.064303599 -0.010315, + 0.0532961 0.064118303 -0.0085770003, + 0.0546159 0.061900701 -0.011318, + 0.0546159 0.0620557 -0.013027, + 0.0532961 0.064481899 -0.013872, + 0.051830001 0.0668405 -0.015028, + 0.050219599 0.069126397 -0.01639, + 0.048467699 0.071309499 -0.017969999, + 0.0465803 0.073366001 -0.01977, + 0.044564299 0.075273097 -0.021787999, + 0.0424264 0.077007897 -0.024022, + 0.040174201 0.078548104 -0.026464, + 0.0378174 0.079875 -0.029107001, + 0.035366699 0.080973104 -0.031936001, + 0.0328326 0.0818277 -0.034947, + 0.0302257 0.0824228 -0.038123999, + 0.027557701 0.0827481 -0.041443001, + 0.0248404 0.082795903 -0.044883002, + 0.0220857 0.082559697 -0.048422001, + 0.019305199 0.082034796 -0.05204, + 0.0165099 0.081222601 -0.055714, + 0.0137106 0.078535803 -0.06374, + 0.0109179 0.075953603 -0.072021, + 0.0081421202 0.073487103 -0.080522001, + 0.0053918599 0.071148202 -0.089210004, + 0.00267513 0.068948999 -0.098056003, + 0 0.066900499 -0.107027, + -0.00267513 0.068947501 -0.098054998, + -0.0053918599 0.071145102 -0.089207999, + -0.0081421202 0.073482901 -0.080518998, + -0.0109179 0.075949401 -0.072016999, + -0.0137106 0.078533404 -0.063738003, + -0.0165099 0.081223398 -0.055713002, + -0.019305199 0.082035497 -0.05204, + -0.0220857 0.082561202 -0.048422001, + -0.0248404 0.082799003 -0.044883002, + -0.027557701 0.082752697 -0.041441999, + -0.0302257 0.082428299 -0.038123, + -0.0328326 0.081832498 -0.034947999, + -0.035366699 0.0809756 -0.031938002, + -0.0378174 0.079877898 -0.029108001, + -0.0378174 0.080740303 -0.022764999, + -0.035366699 0.082303204 -0.023402, + -0.0328326 0.083720498 -0.024195001, + -0.0302257 0.084982201 -0.025140001, + -0.027557701 0.085719503 -0.02843, + -0.0248404 0.086188801 -0.031881001, + -0.0220857 0.086377002 -0.035473999, + -0.019305199 0.086277403 -0.039186001, + -0.0165099 0.085888803 -0.042993002, + -0.0137106 0.085211903 -0.046870999, + -0.0109179 0.084248297 -0.050797999, + -0.0081421202 0.083003096 -0.054754999, + -0.0053918599 0.0798897 -0.063066997, + -0.00267513 0.076898597 -0.071589999, + 0 0.074042603 -0.080291003, + 0.00267513 0.076899603 -0.071590997, + 0.0053918599 0.079890601 -0.063068002, + 0.0081421202 0.083002701 -0.054754999, + 0.0109179 0.084247999 -0.050797999, + 0.0137106 0.085210897 -0.046870999, + 0.0165099 0.085886799 -0.042993002, + 0.019305199 0.086274199 -0.039186001, + 0.0220857 0.086373001 -0.035473999, + 0.0248404 0.086185202 -0.031881001, + 0.027557701 0.085717499 -0.028429, + 0.0302257 0.084979899 -0.025140001, + 0.0328326 0.083982296 -0.022027001, + 0.035366699 0.082736202 -0.019107999, + 0.0378174 0.081258401 -0.016396999, + 0.040174201 0.079567999 -0.013905, + 0.0424264 0.077684604 -0.01164, + 0.044564299 0.075628698 -0.0096109901, + 0.0465803 0.073424399 -0.0078189997, + 0.048467699 0.071102597 -0.0062599899, + 0.050219599 0.068667501 -0.0050509898, + 0.051830001 0.066295698 -0.0058849901, + 0.0532961 0.063854598 -0.006825, + 0.0546159 0.061363101 -0.0078760097, + 0.0546159 0.0609813 -0.0061629899, + 0.0532961 0.063513599 -0.0050740102, + 0.051830001 0.066000096 -0.0041029998, + 0.050219599 0.068423197 -0.0032540001, + 0.048467699 0.070763998 -0.0025220001, + 0.0302257 0.086163498 -0.011979, + 0.027557701 0.087533399 -0.010746, + 0.0302257 0.086224899 -0.0097829998, + 0.0328326 0.084732004 -0.01116, + 0.0328326 0.084766999 -0.0089880098, + 0.035366699 0.083156399 -0.010511, + 0.035366699 0.083167203 -0.0083650099, + 0.0378174 0.081435896 -0.0079149902, + 0.0378174 0.081421301 -0.012152, + 0.040174201 0.079615302 -0.0097230095, + 0.040174201 0.079517096 -0.0055559999, + 0.0424264 0.077623501 -0.0075310101, + 0.0424264 0.077421598 -0.0034419999, + 0.044564299 0.075468302 -0.0055809901, + 0.044564299 0.0751784 -0.00157401, + 0.0465803 0.073180303 -0.0038709999, + 0.0465803 0.073010802 -0.00192799, + 0.048467699 0.070957698 -0.0043459898, + 0.035366699 0.083021902 -0.014809, + -0.0302257 0.085277103 -0.022954, + -0.0302257 0.085533403 -0.020764001, + -0.027557701 0.086407602 -0.024033001, + -0.0328326 0.083986297 -0.022027999, + -0.0328326 0.084214002 -0.019857001, + -0.035366699 0.082541801 -0.021257, + -0.035366699 0.082742497 -0.019109, + -0.0378174 0.0809533 -0.020644, + -0.0378174 0.081129096 -0.018521, + -0.040174201 0.079384401 -0.018093999, + -0.040174201 0.079500496 -0.015998, + -0.0424264 0.077615201 -0.015761999, + -0.0378174 0.081267498 -0.016396999, + -0.035366699 0.082905397 -0.016959, + -0.0328326 0.084403299 -0.017684, + -0.0302257 0.085750997 -0.01857, + -0.027557701 0.086941898 -0.019614, + -0.0248404 0.0876908 -0.023034999, + -0.0248404 0.087016098 -0.027472001, + -0.0220857 0.088166997 -0.026621001, + -0.0220857 0.087349601 -0.031064, + -0.019305199 0.088362098 -0.030351, + -0.019305199 0.087396599 -0.034789, + -0.0165099 0.088268802 -0.034203999, + -0.0165099 0.087154403 -0.038624, + -0.0137106 0.087885603 -0.038155999, + -0.0137106 0.086622901 -0.042543001, + -0.0109179 0.087213397 -0.042181998, + -0.0109179 0.085803799 -0.046523999, + -0.0081421202 0.086254701 -0.046259999, + -0.0081421202 0.084699802 -0.050545, + -0.0053918599 0.0850152 -0.050368, + -0.0053918599 0.083318397 -0.054584999, + -0.00267513 0.083503298 -0.054485999, + -0.00267513 0.080074497 -0.062976003, + 0 0.080135003 -0.062945999, + 0 0.0769592 -0.071562998, + 0.00267513 0.080075003 -0.062976003, + 0.00267513 0.083503202 -0.054485999, + 0.0053918599 0.083318099 -0.054584999, + 0.0053918599 0.085014999 -0.050368, + 0.0081421202 0.084699497 -0.050545, + 0.0081421202 0.086254202 -0.046259999, + 0.0109179 0.085803002 -0.046523999, + 0.0109179 0.087211996 -0.042181998, + 0.0137106 0.086621299 -0.042544, + 0.0137106 0.087883301 -0.038155999, + 0.0165099 0.087151602 -0.038624998, + 0.0165099 0.088265799 -0.034205001, + 0.019305199 0.087393098 -0.034790002, + 0.019305199 0.088359296 -0.030351, + 0.0220857 0.087346397 -0.031064, + 0.0220857 0.088165402 -0.026620001, + 0.0248404 0.087014399 -0.02747, + 0.0248404 0.087688901 -0.023034999, + 0.027557701 0.086405501 -0.024032, + 0.027557701 0.0869385 -0.019613, + 0.0302257 0.0855297 -0.020763, + 0.0302257 0.085924402 -0.016373999, + 0.0328326 0.084397398 -0.017684, + 0.0328326 0.084547304 -0.015509, + 0.035366699 0.082897998 -0.016959, + -0.044564299 0.075665399 -0.013654, + -0.044564299 0.075643502 -0.0095969997, + -0.0465803 0.073438101 -0.007797, + -0.048467699 0.071112603 -0.0062449998, + -0.050219599 0.068842798 -0.0068439902, + -0.051830001 0.066519499 -0.0076540099, + -0.0532961 0.0641293 -0.0085770003, + -0.0546159 0.061683699 -0.0095939897, + -0.055787299 0.059200801 -0.01071, + -0.056809202 0.056696899 -0.011921, + -0.0532961 0.0131806 -0.027114, + -0.051830001 0.0131658 -0.029782999, + -0.0529669 0.0125 -0.027687, + -0.0532961 0.0138535 -0.027246, + -0.0546159 0.013883 -0.024522999, + -0.0546159 0.0145412 -0.024768, + -0.055787299 0.0145872 -0.021999, + -0.055787299 0.0151891 -0.022329999, + -0.056809202 0.0152545 -0.019523, + -0.056809202 0.0161689 -0.020259, + -0.0576833 0.0162837 -0.017413, + -0.0576833 0.0169305 -0.018048, + -0.058412101 0.017105799 -0.015174, + -0.058412101 0.019729501 -0.01767, + -0.058998398 0.020153301 -0.014708, + -0.058998398 0.0229083 -0.017077001, + -0.059445001 0.023582101 -0.014041, + -0.059445001 0.024981299 -0.015182, + -0.059757002 0.025770999 -0.012135, + -0.059757002 0.027200799 -0.013365, + -0.0599402 0.028100301 -0.010322, + -0.0599402 0.0296627 -0.011703, + -0.059999999 0.030677499 -0.008657, + -0.059999999 0.032341901 -0.010212, + -0.0599402 0.0334801 -0.0071499902, + -0.0599402 0.035218101 -0.0089040101, + -0.059757002 0.0364893 -0.005812, + -0.059757002 0.038268201 -0.0077829999, + -0.059445001 0.039680898 -0.0046540098, + -0.059445001 0.0414638 -0.0068549998, + -0.058998398 0.043014701 -0.00370599, + -0.058998398 0.044762101 -0.0061410102, + -0.058412101 0.046442099 -0.00299699, + -0.058412101 0.0481118 -0.0056639998, + -0.0576833 0.049909599 -0.0025460101, + -0.0576833 0.0514616 -0.0054310001, + -0.056809202 0.053363599 -0.00235899, + -0.056809202 0.054758299 -0.00544299, + -0.055787299 0.0156783 -0.022714, + -0.055787299 0.0160546 -0.023091, + -0.0546159 0.015591 -0.025506999, + -0.0546159 0.0151244 -0.025110999, + -0.0532961 0.0150605 -0.027853999, + -0.0532961 0.0144958 -0.0275, + -0.051830001 0.0144512 -0.030183, + -0.051830001 0.0138245 -0.029921001, + -0.050219599 0.0137961 -0.032533001, + -0.050219599 0.0131513 -0.032391001, + -0.048467699 0.0131372 -0.034926001, + -0.0499507 0.0125 -0.032740001, + -0.0532961 0.0162386 -0.029391, + -0.0532961 0.015829699 -0.028664, + -0.0546159 0.016408799 -0.026601, + -0.0546159 0.017243899 -0.028042, + -0.055787299 0.017538801 -0.025167, + -0.055787299 0.0184584 -0.026551001, + -0.056809202 0.0198838 -0.024932999, + -0.056809202 0.018880401 -0.023603, + -0.0576833 0.0215504 -0.023194, + -0.055787299 0.016581301 -0.023773, + -0.0546159 0.0159414 -0.025896, + -0.0532961 0.015505 -0.028262001, + -0.051830001 0.0154204 -0.030967001, + -0.051830001 0.0149977 -0.030547, + -0.050219599 0.0149364 -0.033178002, + -0.050219599 0.0144077 -0.032804001, + -0.048467699 0.0143654 -0.035351999, + -0.048467699 0.0137686 -0.035073999, + -0.0465803 0.0137419 -0.037530001, + -0.0465803 0.0131235 -0.037377998, + -0.044564299 0.0131104 -0.039735999, + -0.046453901 0.0125 -0.037473999, + -0.044563901 0.0125 -0.039673999, + -0.047047202 0.0074999998 -0.036736999, + -0.048260398 0.0125 -0.035149999, + -0.0470348 0.0125 -0.036727, + -0.046577401 0.0125 -0.037315, + -0.056809202 0.0167554 -0.020918, + -0.0576833 0.0193046 -0.020638, + -0.058412101 0.0222302 -0.020132, + -0.058412101 0.023379801 -0.021362999, + -0.058998398 0.0241831 -0.018262999, + -0.058998398 0.0253677 -0.019567, + -0.059445001 0.0262892 -0.016450001, + -0.059445001 0.027603401 -0.017883001, + -0.059757002 0.0286399 -0.014773, + -0.059757002 0.030056801 -0.016361, + -0.0599402 0.031203801 -0.013275, + -0.0599402 0.0326952 -0.015041, + -0.059999999 0.033956699 -0.011973, + -0.059999999 0.035490699 -0.013935, + -0.0599402 0.036874101 -0.010871, + -0.0599402 0.038415499 -0.013043, + -0.059757002 0.039929502 -0.0099689905, + -0.059757002 0.041441198 -0.012356, + -0.059445001 0.043092798 -0.009265, + -0.059445001 0.044536099 -0.011865, + -0.058998398 0.0463183 -0.0087740002, + -0.058998398 0.047656499 -0.011576, + -0.058412101 0.049556799 -0.0085070003, + -0.058412101 0.050753102 -0.011494, + -0.0576833 0.052757099 -0.008467, + -0.0576833 0.053780802 -0.011614, + -0.056809202 0.055872802 -0.0086439997, + -0.0506116 0.0125 -0.031691998, + -0.051520798 0.0125 -0.030251, + -0.050626501 0.0074999998 -0.031702001, + -0.050211199 0.0125 -0.032327, + -0.048462 0.0125 -0.034862999, + -0.037814599 0.0125 0.047077, + -0.0356883 0.0125 0.048732001, + -0.0378174 0.0146582 0.047056001, + -0.038435601 0.0074999998 0.046572998, + -0.038010798 0.0125 0.046923999, + 0.0532961 0.049663 0.017447, + 0.051830001 0.051036101 0.020488, + 0.0532961 0.048287801 0.018487001, + 0.051830001 0.052435402 0.019367, + 0.050219599 0.053835198 0.022333, + 0.050219599 0.05525 0.021128999, + 0.048467699 0.056666501 0.024005, + 0.048467699 0.058087699 0.022717001, + 0.0465803 0.059510499 0.025489001, + 0.0465803 0.060928602 0.024116, + 0.044564299 0.0623466 0.026769999, + 0.044564299 0.063751496 0.025312999, + 0.0424264 0.065153196 0.027836001, + 0.0424264 0.0665356 0.026296999, + 0.040174201 0.067909099 0.028678, + 0.040174201 0.069259599 0.027059, + 0.0378174 0.070594102 0.029291, + 0.0378174 0.071903102 0.027595, + 0.035366699 0.073187999 0.02967, + 0.035366699 0.074446201 0.027902, + 0.0328326 0.075670697 0.029812999, + 0.0328326 0.076870397 0.02798, + 0.0302257 0.078024 0.029722, + 0.0302257 0.079158098 0.027829999, + 0.027557701 0.080232799 0.029402001, + 0.027557701 0.081294097 0.027458001, + 0.0248404 0.082282603 0.028860999, + 0.0248404 0.083264798 0.026872, + 0.0220857 0.084159903 0.028105, + 0.0220857 0.085059002 0.026079001, + 0.019305199 0.085854404 0.027143, + 0.019305199 0.086667202 0.025086001, + 0.0165099 0.087359399 0.025986999, + 0.0165099 0.088083103 0.023906, + 0.0137106 0.088669501 0.02465, + 0.0137106 0.0893014 0.022554001, + 0.0109179 0.089780003 0.023146, + 0.0109179 0.090316102 0.021059999, + 0.0081421202 0.090685703 0.021505, + 0.0081421202 0.091131203 0.019415, + 0.0053918599 0.0913928 0.019723, + 0.0053918599 0.091783799 0.017519999, + 0.00267513 0.0919393 0.017698999, + 0.00267513 0.092614397 0.013195, + 0 0.092666604 0.013252, + 0 0.093193002 0.0087019997, + -0.00267513 0.092615098 0.013196, + -0.00267513 0.091939896 0.0177, + -0.0053918599 0.091784902 0.017521, + -0.0053918599 0.091393702 0.019724, + -0.0081421202 0.091132499 0.019416001, + -0.0081421202 0.090687104 0.021505, + -0.0109179 0.090317897 0.021059001, + -0.0109179 0.089782298 0.023146, + -0.0137106 0.089304201 0.022554001, + -0.0137106 0.0886731 0.02465, + -0.0165099 0.088087402 0.023907, + -0.0165099 0.087364703 0.025989, + -0.019305199 0.086673401 0.025087999, + -0.019305199 0.085861698 0.027146, + -0.0220857 0.085067399 0.026082, + -0.0220857 0.084169298 0.028108999, + -0.0248404 0.083275497 0.026877001, + -0.0248404 0.082294099 0.028867001, + -0.027557701 0.081306897 0.027465001, + -0.027557701 0.080246001 0.029410001, + -0.0302257 0.079172596 0.027838999, + -0.0302257 0.078038603 0.029732, + -0.0328326 0.076886199 0.027991001, + -0.0328326 0.075686 0.029825, + -0.035366699 0.074462697 0.027915001, + -0.035366699 0.073203698 0.029684, + -0.0378174 0.071919903 0.02761, + -0.0378174 0.070609801 0.029307, + -0.040174201 0.069276199 0.027076, + -0.040174201 0.067924403 0.028696001, + -0.0424264 0.066551797 0.026316, + -0.0424264 0.0651678 0.027856, + -0.044564299 0.0637668 0.025334001, + -0.044564299 0.062360201 0.026791999, + -0.0465803 0.060942799 0.024139, + -0.0465803 0.059522901 0.025512001, + -0.048467699 0.0581006 0.022741999, + -0.048467699 0.056677401 0.02403, + -0.050219599 0.055261299 0.021155, + -0.050219599 0.053844601 0.022359001, + -0.051830001 0.052445099 0.019393999, + -0.051830001 0.051043998 0.020515, + -0.0532961 0.049671199 0.017473999, + -0.0532961 0.048294201 0.018515, + -0.0546159 0.046957299 0.015414, + -0.0546159 0.0456126 0.016378, + -0.0546159 0.048273001 0.014377, + -0.0532961 0.051012799 0.016359, + -0.051830001 0.053804599 0.018198, + -0.050219599 0.056629799 0.019877, + -0.048467699 0.059468701 0.02138, + -0.0465803 0.062300801 0.022694999, + -0.044564299 0.065105602 0.023808001, + -0.0424264 0.067862101 0.024711, + -0.040174201 0.070548497 0.025395, + -0.0378174 0.073144801 0.025857, + -0.035366699 0.075632498 0.026095999, + -0.0328326 0.077993497 0.026112, + -0.0302257 0.080210201 0.025908001, + -0.027557701 0.082268402 0.025488, + -0.0248404 0.084156699 0.024862001, + -0.0220857 0.0858652 0.024033999, + -0.019305199 0.087384902 0.023015, + -0.0165099 0.088709697 0.021818999, + -0.0137106 0.0898332 0.020474, + -0.0109179 0.090758599 0.018975001, + -0.0081421202 0.0915206 0.017217999, + -0.0053918599 0.092456698 0.013023, + -0.00267513 0.093140401 0.0086470004, + 0 0.093558699 0.0041200002, + 0.00267513 0.093139596 0.0086460002, + 0.0053918599 0.092455097 0.01302, + 0.0081421202 0.091518998 0.017215, + 0.0109179 0.090756796 0.018975001, + 0.0137106 0.089830898 0.020475, + 0.0165099 0.0887063 0.021818999, + 0.019305199 0.087379903 0.023014, + 0.0220857 0.085858099 0.024032, + 0.0248404 0.084147297 0.024858, + 0.027557701 0.0822566 0.025482999, + 0.0302257 0.080196202 0.025900001, + 0.0328326 0.077977702 0.026102999, + 0.035366699 0.075615503 0.026085, + 0.0378174 0.073127098 0.025844, + 0.040174201 0.070530698 0.025379, + 0.0424264 0.067844503 0.024692999, + 0.044564299 0.065088697 0.023788, + 0.0465803 0.062284801 0.022673, + 0.048467699 0.059454001 0.021357, + 0.050219599 0.0566165 0.019851999, + 0.051830001 0.053792901 0.018170999, + 0.0532961 0.0510028 0.016331, + 0.0546159 0.0482646 0.014349, + 0.0546159 0.045607999 0.016349999, + 0.055787299 0.044315301 0.013206, + 0.055787299 0.041693199 0.014917, + 0.056809202 0.040516 0.01175, + 0.056809202 0.0379721 0.01319, + 0.0576833 0.0369169 0.010023, + 0.0576833 0.034470499 0.011224, + 0.058412101 0.033541001 0.0080800001, + 0.058412101 0.031243499 0.0090709999, + 0.058998398 0.0304402 0.0059709898, + 0.058998398 0.028209999 0.0068100002, + 0.059445001 0.0275362 0.0037740001, + 0.059445001 0.023042399 0.005506, + 0.059757002 0.0226257 0.002595, + 0.059757002 0.0182971 0.004439, + 0.0599402 0.018127499 0.0016580001, + 0.0599402 0.017051401 0.002134, + 0.059999999 0.0169411 -0.00060299702, + 0.059999999 0.0156931 -7.6003998e-005, + 0.0599402 0.0156301 -0.002789, + 0.0599402 0.014121 -0.0023360001, + 0.059757002 0.0140916 -0.0050519998, + 0.059692498 0.0125 -0.0055669998, + 0.059679601 0.0125 -0.0056690099, + 0.059757002 0.0132853 -0.0049200002, + 0.059445001 0.0132703 -0.0076660002, + 0.059931099 0.0125 -0.0021879999, + 0.059999999 0.0074999998 0.00050000002, + 0.059918199 0.0125 -0.002632, + 0.059999999 0.0133147 0.00048100299, + 0.059999 0.0125 0.000154999, + 0.0599402 0.0133 -0.0022090001, + 0.059999999 0.0141502 0.000358002, + 0.0599402 0.0141794 0.003052, + 0.0599402 0.015756199 0.0026380001, + 0.059757002 0.015819799 0.0053719901, + 0.059757002 0.017162601 0.00489301, + 0.059445001 0.018469 0.0072579999, + 0.040171701 0.0125 0.045061, + 0.040174201 0.0146346 0.045024, + 0.038084399 0.0125 0.046863999, + 0.040312301 0.0125 0.044939999, + 0.040756401 0.0074999998 0.044532999, + 0.045067899 0.0074999998 0.040109001, + 0.042443302 0.0125 0.042909998, + 0.045056298 0.0125 0.040098999, + 0.044562198 0.0125 0.040672, + 0.046393901 0.0125 0.038547002, + 0.0465803 0.0145612 0.038261998, + 0.059432399 0.0125 0.0086410102, + 0.0596756 0.0125 0.006668, + 0.059445001 0.0133593 0.0086280098, + 0.055787299 0.030921601 0.019026, + 0.0546159 0.031590499 0.02204, + 0.055787299 0.025158299 0.020292001, + 0.056809202 0.024736401 0.017344, + 0.056809202 0.019168001 0.018718001, + 0.0576833 0.018992901 0.015849, + 0.0576833 0.0160807 0.016588001, + 0.058412101 0.0160149 0.013763, + 0.058412101 0.0142991 0.014099, + 0.058998398 0.0142688 0.0113, + 0.058998398 0.0133745 0.011404, + 0.051830001 0.032898098 0.027930999, + 0.051830001 0.0263937 0.028925, + 0.0532961 0.0322503 0.025012, + 0.050219599 0.0267893 0.031688999, + 0.051830001 0.019851901 0.029929999, + 0.0532961 0.019684801 0.027191, + 0.0532961 0.016340399 0.02774, + 0.0546159 0.016276499 0.024997, + 0.0546159 0.0144201 0.025255, + 0.055787299 0.0143901 0.022492999, + 0.055787299 0.013436 0.022577001, + 0.056809202 0.0134207 0.019795001, + 0.056496199 0.0125 0.020702999, + 0.055772699 0.0125 0.02258, + 0.057158101 0.0074999998 0.018747, + 0.057668701 0.0125 0.017006001, + 0.058203701 0.0125 0.015071, + 0.0576833 0.0134053 0.016999001, + 0.057419099 0.0125 0.017907999, + 0.0571438 0.0125 0.018742001, + 0.056794401 0.0125 0.0198, + 0.056809202 0.0143599 0.019707, + 0.055787299 0.0162117 0.022216, + 0.0546159 0.0195146 0.024401, + 0.0532961 0.0259888 0.026094999, + 0.0546159 0.0255764 0.023213999, + 0.055787299 0.0193421 0.021573, + 0.056809202 0.016146399 0.019409999, + 0.0576833 0.0143296 0.016905, + 0.058412101 0.0133899 0.014198, + 0.058397699 0.0125 0.014207, + 0.058720101 0.0125 0.012771, + 0.0546159 0.034445301 0.021426, + 0.0546159 0.037236702 0.020583, + 0.055787299 0.036321901 0.017488001, + 0.0546159 0.040061701 0.019462001, + 0.059746899 0.0125 0.005897, + 0.0597114 0.0125 0.0063780099, + 0.059682 0.0074999998 0.00666901, + 0.059757002 0.0133443 0.0058809998, + 0.059927799 0.0125 0.0034419999, + 0.059351299 0.0125 0.0092989998, + 0.058731299 0.0074999998 0.012773, + 0.059934001 0.0125 0.0031880001, + 0.059999999 0.0125 0.00050000002, + 0.0599402 0.0133294 0.0031699999, + 0.059757002 0.0142088 0.0057669999, + 0.059445001 0.0142387 0.0085190004, + 0.059445001 0.0158842 0.0081430096, + 0.058998398 0.0159494 0.010944, + 0.058998398 0.0186428 0.010107, + 0.058412101 0.0188176 0.012974, + 0.058412101 0.023887301 0.011411, + 0.0576833 0.024312099 0.014379, + 0.0576833 0.0295678 0.012927, + 0.056809202 0.0302465 0.015985001, + 0.056809202 0.032852899 0.015281, + 0.055787299 0.033652801 0.018368, + 0.0532961 0.038139001 0.023635, + 0.058984298 0.0125 0.011415, + 0.058848299 0.0125 0.012199, + 0.054979 0.0074999998 0.024527, + 0.055437401 0.0125 0.02345, + 0.0546159 0.0134512 0.025333, + 0.0532961 0.0144496 0.027977999, + 0.051830001 0.0164031 0.030432999, + 0.050219599 0.020015201 0.032607, + 0.048467699 0.027174 0.034377001, + 0.050219599 0.0335311 0.030781999, + 0.051830001 0.034513101 0.027682999, + 0.0532961 0.035227001 0.024442, + 0.051830001 0.037492301 0.027055999, + 0.048467699 0.0145345 0.035805002, + 0.048887499 0.0125 0.035255, + 0.050219599 0.014507 0.033264998, + 0.048204001 0.0125 0.036226001, + 0.0465803 0.0165819 0.038097002, + 0.044564299 0.0166374 0.040476002, + 0.044564299 0.020475101 0.040144999, + 0.0424264 0.0206162 0.042456999, + 0.044564299 0.0279036 0.039475001, + 0.0465803 0.020327499 0.037725002, + 0.048467699 0.016524101 0.035622999, + 0.052201401 0.0125 0.030044001, + 0.0522171 0.0074999998 0.030053001, + 0.052922402 0.0125 0.028771, + 0.051819 0.0125 0.030719001, + 0.051830001 0.0134811 0.030720999, + 0.051472198 0.0125 0.031332001, + 0.050209999 0.0125 0.033326998, + 0.0532961 0.0134663 0.028051, + 0.051830001 0.0144786 0.030652, + 0.050219599 0.0164645 0.033064999, + 0.048467699 0.020174 0.035209, + 0.0465803 0.027545899 0.036975998, + 0.0465803 0.034741499 0.036235001, + 0.048467699 0.034146398 0.033553999, + 0.048467699 0.0358801 0.033349998, + 0.050219599 0.035206299 0.030556999, + 0.050219599 0.036744699 0.030298, + 0.051830001 0.035994601 0.027403999, + 0.054245099 0.0125 0.026141001, + 0.0546025 0.0125 0.025334001, + 0.054963201 0.0125 0.02452, + 0.053284001 0.0125 0.028052, + 0.048901699 0.0074999998 0.035264999, + 0.0498982 0.0125 0.033819001, + 0.048460599 0.0125 0.035861999, + 0.0465759 0.0125 0.038314, + 0.036012899 0.0074999998 0.048489999, + 0.037813399 0.0125 0.047075, + 0.035366699 0.0146771 0.048937, + 0.036008701 0.0125 0.048485, + 0.0378174 0.0146565 0.047045, + 0.035366699 0.016833 0.04885, + 0.0328326 0.016874401 0.050618999, + 0.0328326 0.0211046 0.050459001, + 0.0302257 0.016912499 0.052244999, + 0.0328326 0.0146962 0.050693002, + 0.033358999 0.0125 0.050372001, + 0.035361301 0.0125 0.04896, + 0.035764702 0.0125 0.048675999, + 0.0378174 0.016788499 0.046944, + 0.035366699 0.020994799 0.048659999, + 0.035366699 0.029162399 0.048269998, + 0.0378174 0.028875999 0.046269, + 0.0378174 0.036869202 0.045821, + 0.040174201 0.036379699 0.043616001, + 0.040174201 0.038325898 0.043487001, + 0.0424264 0.0377574 0.041131001, + 0.0424264 0.0395054 0.040948, + 0.044564299 0.0388573 0.038447, + 0.044564299 0.0405734 0.038169999, + 0.0465803 0.039843399 0.035537001, + 0.0465803 0.041545901 0.035161, + 0.048467699 0.040732101 0.032407999, + 0.048467699 0.042385198 0.031939, + 0.0465803 0.043254402 0.034705002, + 0.044564299 0.042328499 0.037808999, + 0.0424264 0.041271001 0.040686, + 0.040174201 0.040120699 0.043320999, + 0.0378174 0.038862102 0.045708999, + 0.035366699 0.037327498 0.047885999, + 0.0328326 0.0294284 0.050128002, + 0.0302257 0.0212055 0.052111998, + 0.027557701 0.016947299 0.053725999, + 0.0302257 0.0147137 0.052308001, + 0.0308873 0.0125 0.051938999, + 0.0302191 0.0125 0.052317999, + 0.0308876 0.0074999998 0.051938999, + 0.030873001 0.0125 0.051948, + 0.0283127 0.0125 0.053399999, + 0.0328261 0.0125 0.050709002, + 0.0254349 0.0074999998 0.054841999, + 0.0275514 0.0125 0.053784002, + 0.025684301 0.0125 0.054724999, + 0.027557701 0.0147297 0.053778, + 0.0248404 0.0169785 0.055059001, + 0.027557701 0.021297401 0.053617001, + 0.0302257 0.0296728 0.051835999, + 0.0328326 0.0377529 0.049802002, + 0.035366699 0.039363999 0.047789, + 0.0378174 0.040700998 0.045559, + 0.040174201 0.041933201 0.043074999, + 0.0424264 0.0430764 0.040339001, + 0.044564299 0.044090301 0.037365999, + 0.0465803 0.044960398 0.034168001, + -0.0402418 0.0125 0.045003999, + -0.040174201 0.0146363 0.045035001, + -0.042376 0.0125 0.042977002, + -0.0429691 0.0074999998 0.042376999, + -0.0424252 0.0125 0.042925, + -0.044560701 0.0125 0.040670998, + -0.044408198 0.0125 0.040847, + -0.047047202 0.0074999998 0.037737001, + -0.050219599 0.039894301 0.029577, + -0.050219599 0.041482601 0.029099001, + -0.051830001 0.039028801 0.026649, + -0.048467699 0.040735699 0.032423999, + -0.048467699 0.039099999 0.032809, + -0.0465803 0.0398583 0.035546999, + -0.0465803 0.038197201 0.035835002, + -0.044564299 0.0388746 0.038451001, + -0.044564299 0.035313901 0.038812999, + -0.0424264 0.035860699 0.041276999, + -0.0424264 0.0282479 0.041862998, + -0.040174201 0.0285723 0.044130001, + -0.040174201 0.0207536 0.044654999, + -0.0378174 0.020879701 0.046725001, + -0.040174201 0.0167506 0.044934001, + -0.0424264 0.016700801 0.042777002, + -0.0424264 0.0146132 0.042893, + -0.044564299 0.0145888 0.040635999, + -0.042958502 0.0125 0.042366002, + -0.0465803 0.0145632 0.038274001, + -0.046333499 0.0125 0.038621001, + -0.044564299 0.016648199 0.040504999, + -0.0424264 0.0206198 0.042459998, + -0.044564299 0.0279062 0.039475001, + -0.0465803 0.034741599 0.036235001, + -0.048467699 0.0374927 0.033115, + -0.050219599 0.038315699 0.029978, + -0.050611299 0.0125 0.032692, + -0.050219599 0.0145092 0.033279002, + -0.051423199 0.0125 0.031413998, + -0.051830001 0.0144809 0.030665999, + -0.050219599 0.0164767 0.033096999, + -0.053653602 0.0125 0.027318001, + -0.0532961 0.014452 0.027992001, + -0.054204401 0.0125 0.026226999, + -0.0532961 0.0163533 0.027774001, + -0.0546159 0.0144225 0.025269, + -0.054601699 0.0125 0.025334001, + -0.055400901 0.0125 0.023538001, + -0.056143001 0.0074999998 0.021664999, + -0.055771999 0.0125 0.02258, + -0.058396801 0.0125 0.014207, + -0.0581805 0.0125 0.015164, + -0.058412101 0.0143017 0.014115, + -0.0580099 0.0125 0.015776999, + -0.0576833 0.0143321 0.016921001, + -0.0576833 0.0160947 0.016625, + -0.059445001 0.0150916 0.0083900001, + -0.059445001 0.0142413 0.0085349996, + -0.058998398 0.0159637 0.010981, + -0.059431199 0.0125 0.0086410102, + -0.059337199 0.0125 0.0093930103, + -0.059285302 0.0074999998 0.0097329998, + -0.059702002 0.0125 0.0064730099, + -0.059757002 0.0142115 0.005783, + -0.0599402 0.014182 0.0030679901, + -0.059919201 0.0125 0.0035890001, + -0.059757002 0.0150458 0.00563, + -0.059445001 0.0158986 0.0081799896, + -0.058998398 0.018647799 0.010112, + -0.058412101 0.018822599 0.012979, + -0.058412101 0.0238907 0.01141, + -0.0576833 0.024315501 0.014379, + -0.0576833 0.029568 0.012927, + -0.056809202 0.030246699 0.015984001, + -0.056809202 0.032875001 0.015286, + -0.055787299 0.033674501 0.018373, + -0.055787299 0.036326099 0.017506, + -0.0546159 0.037240699 0.0206, + -0.0532961 0.039611399 0.023146, + -0.0546159 0.0400557 0.019486999, + -0.0546159 0.034466501 0.021431001, + -0.0532961 0.036683202 0.024086, + -0.0546159 0.0315907 0.022039, + -0.0532961 0.032250501 0.025012, + -0.0546159 0.025579499 0.023212999, + -0.055787299 0.025161499 0.020292001, + -0.055787299 0.0193469 0.021577001, + -0.056809202 0.019172801 0.018723, + -0.056809202 0.016160199 0.019446, + -0.056793701 0.0125 0.0198, + -0.056464098 0.0125 0.020793, + -0.056809202 0.0143624 0.019722, + -0.057391401 0.0125 0.017999001, + -0.055787299 0.016225301 0.022252001, + -0.0546159 0.019519299 0.024405001, + -0.0532961 0.0259919 0.026094999, + -0.051830001 0.026396699 0.028924, + -0.0532961 0.0196894 0.027194999, + -0.0546159 0.0162897 0.025032001, + -0.055787299 0.0143926 0.022507999, + -0.056128498 0.0125 0.021659, + -0.051830001 0.0198563 0.029934, + -0.050219599 0.0267922 0.031688999, + -0.051830001 0.032898299 0.027930001, + -0.0532961 0.035247799 0.024447, + -0.051830001 0.036014799 0.027408, + -0.050219599 0.033531301 0.030781999, + -0.048467699 0.027176799 0.034375999, + -0.050219599 0.0200195 0.032611001, + -0.051830001 0.0164157 0.030466, + -0.0528774 0.0125 0.028853999, + -0.048467699 0.0201781 0.035211999, + -0.0465803 0.0275486 0.036975, + -0.048467699 0.034146599 0.033553999, + -0.050219599 0.036764201 0.030301999, + -0.051830001 0.037508901 0.027066, + -0.0465803 0.0203314 0.037728999, + -0.048467699 0.016535901 0.035654001, + -0.0498452 0.0125 0.033898, + -0.048467699 0.0145366 0.035817999, + -0.0465803 0.016593199 0.038127001, + -0.044564299 0.020478901 0.040148001, + -0.047033701 0.0125 0.037726, + -0.048147298 0.0125 0.036302999, + -0.046574499 0.0125 0.038313001, + -0.0378174 0.016797701 0.046967998, + -0.035366699 0.0209978 0.048663002, + -0.0378174 0.0288781 0.046268001, + -0.040174201 0.036379799 0.043614998, + -0.0424264 0.039521899 0.040950999, + -0.044564299 0.0405876 0.038178999, + -0.0465803 0.041549399 0.035176001, + -0.048467699 0.0423816 0.031959001, + -0.048467699 0.04403 0.031413, + -0.0465803 0.044955298 0.034189001, + -0.0465803 0.0466577 0.033569001, + -0.044564299 0.047601499 0.036247, + -0.044564299 0.049350999 0.035546999, + -0.0424264 0.050304499 0.038112, + -0.0424264 0.0520937 0.037324999, + -0.040174201 0.053047799 0.039763, + -0.040174201 0.054867301 0.038887002, + -0.0378174 0.055813201 0.041187, + -0.0378174 0.057652701 0.040217001, + -0.035366699 0.058581199 0.042369999, + -0.035366699 0.060429901 0.041303001, + -0.0328326 0.061331298 0.043299001, + -0.0328326 0.0631781 0.042135, + -0.0302257 0.064042397 0.043965999, + -0.0302257 0.065876298 0.042704001, + -0.027557701 0.066695303 0.044365998, + -0.027557701 0.068505101 0.043007001, + -0.0248404 0.069270797 0.044498999, + -0.0248404 0.071045198 0.043044999, + -0.0220857 0.071749501 0.044362999, + -0.0220857 0.073477499 0.042817999, + -0.019305199 0.0741129 0.043962002, + -0.019305199 0.075784802 0.042330001, + -0.0165099 0.076345697 0.043303002, + -0.0165099 0.077952199 0.041590001, + -0.0137106 0.078433901 0.042396002, + -0.0137106 0.079966001 0.040607002, + -0.0109179 0.080364302 0.041251, + -0.0109179 0.081813604 0.039395001, + -0.0081421202 0.082125001 0.039880998, + -0.0081421202 0.083485298 0.037965, + -0.0053918599 0.0837081 0.038302001, + -0.0053918599 0.084973998 0.036334999, + -0.00267513 0.085107498 0.036531001, + -0.00267513 0.086273998 0.034520999, + 0 0.086318098 0.034584001, + 0 0.087381199 0.032540001, + 0.00267513 0.086272798 0.03452, + 0.00267513 0.085106201 0.036529999, + 0.0053918599 0.084971398 0.036332998, + 0.0053918599 0.0837055 0.0383, + 0.0081421202 0.083481401 0.037962001, + 0.0081421202 0.082121201 0.039878, + 0.0109179 0.081808597 0.039391, + 0.0109179 0.080359504 0.041246999, + 0.0137106 0.079960003 0.040601999, + 0.0137106 0.078428201 0.04239, + 0.0165099 0.077945396 0.041583002, + 0.0165099 0.076339401 0.043295, + 0.019305199 0.075777397 0.042321, + 0.019305199 0.074106202 0.043953001, + 0.0220857 0.0734699 0.042808, + 0.0220857 0.071742803 0.044353001, + 0.0248404 0.071037598 0.043033, + 0.0248404 0.069264203 0.044486001, + 0.027557701 0.068497799 0.042993002, + 0.027557701 0.066689096 0.044351999, + 0.0302257 0.065869503 0.042688001, + 0.0302257 0.064036801 0.043951001, + 0.0328326 0.063171901 0.042118002, + 0.0328326 0.061326198 0.043281998, + 0.035366699 0.060424499 0.041285001, + 0.035366699 0.058577001 0.042351998, + 0.0378174 0.057648201 0.040197, + 0.0378174 0.055810001 0.041168001, + 0.040174201 0.0548639 0.038865998, + 0.040174201 0.0530461 0.039742999, + 0.0424264 0.0520918 0.037303999, + 0.0424264 0.050305001 0.038091, + 0.044564299 0.049351402 0.035525002, + 0.044564299 0.047604699 0.036226001, + 0.0465803 0.046661101 0.033546999, + 0.048467699 0.044035301 0.031390999, + 0.050219599 0.041486301 0.029079, + 0.044564299 0.0145868 0.040624, + 0.0424264 0.0146113 0.042881999, + 0.044472098 0.0125 0.040777002, + 0.0424264 0.0166905 0.042750001, + 0.040174201 0.0167409 0.044909, + 0.040174201 0.0207502 0.044652, + 0.0378174 0.020876501 0.046721999, + 0.040174201 0.028569899 0.044131, + 0.0424264 0.028245499 0.041862998, + 0.0424264 0.035860602 0.041276999, + 0.044564299 0.035313699 0.038812999, + 0.044564299 0.0371585 0.038648002, + 0.0465803 0.036531799 0.036051001, + 0.0465803 0.0381791 0.035831001, + 0.048467699 0.037473898 0.033110999, + 0.048467699 0.039084502 0.032799002, + 0.050219599 0.038299602 0.029967999, + 0.050219599 0.039890599 0.029561, + 0.051830001 0.039024901 0.026633, + 0.040748298 0.0125 0.044525001, + 0.051830001 0.040561698 0.026136, + 0.050219599 0.043078698 0.028519001, + 0.048467699 0.0456798 0.030761, + 0.0465803 0.048353601 0.032839999, + 0.044564299 0.0510865 0.034734, + 0.0424264 0.053860601 0.036424998, + 0.040174201 0.0566561 0.037896, + 0.0378174 0.0594531 0.039133001, + 0.035366699 0.062231101 0.040123999, + 0.0328326 0.0649691 0.040860001, + 0.0302257 0.067646399 0.041335002, + 0.027557701 0.070243299 0.041547, + 0.0248404 0.0727406 0.041494999, + 0.0220857 0.075120598 0.041182, + 0.019305199 0.077366397 0.040615, + 0.0165099 0.079463303 0.039799999, + 0.0137106 0.081398398 0.038750999, + 0.0109179 0.083160996 0.037478998, + 0.0081421202 0.084742099 0.035998002, + 0.0053918599 0.086135 0.034325, + 0.00267513 0.087334901 0.032476999, + 0 0.088339999 0.030469, + -0.00267513 0.087336101 0.032476999, + -0.0053918599 0.0861376 0.034325998, + -0.0081421202 0.084746003 0.035999998, + -0.0109179 0.083166197 0.037482999, + -0.0137106 0.081404798 0.038756002, + -0.0165099 0.079470702 0.039806999, + -0.019305199 0.077374399 0.040623002, + -0.0220857 0.075129002 0.041191999, + -0.0248404 0.072749101 0.041506, + -0.027557701 0.070251703 0.041560002, + -0.0302257 0.067654401 0.04135, + -0.0328326 0.064976603 0.040876999, + -0.035366699 0.062237699 0.040142, + -0.0378174 0.0594589 0.039152998, + -0.040174201 0.056660902 0.037916999, + -0.0424264 0.0538642 0.036447, + -0.044564299 0.051088501 0.034756999, + -0.0465803 0.048353199 0.032862999, + -0.048467699 0.045676298 0.030784, + -0.050219599 0.0430732 0.028542001, + -0.051830001 0.040557802 0.026156999, + -0.0532961 0.038142901 0.023653001, + -0.051830001 0.042089 0.025589, + -0.050219599 0.0446615 0.027904, + -0.048467699 0.047315601 0.030072, + -0.0465803 0.050036602 0.032069001, + -0.044564299 0.052807499 0.033877, + -0.0424264 0.0556092 0.035478, + -0.040174201 0.058421601 0.036855001, + -0.0378174 0.061224598 0.037996002, + -0.035366699 0.063997798 0.03889, + -0.0328326 0.066720001 0.039530002, + -0.0302257 0.069370098 0.03991, + -0.027557701 0.071928397 0.040029, + -0.0248404 0.074377201 0.039887998, + -0.0220857 0.076698802 0.039492, + -0.019305199 0.078876503 0.038846999, + -0.0165099 0.080896199 0.037962001, + -0.0137106 0.082747199 0.036849, + -0.0109179 0.084419496 0.035521999, + -0.0081421202 0.085904598 0.033994999, + -0.0053918599 0.087196797 0.032285001, + -0.00267513 0.088293999 0.030407, + 0 0.0891954 0.028377, + 0.00267513 0.088293001 0.030406, + 0.0053918599 0.087194502 0.032283999, + 0.0081421202 0.085900798 0.033992998, + 0.0109179 0.084414199 0.035519, + 0.0137106 0.082740597 0.036844, + 0.0165099 0.080888502 0.037955999, + 0.019305199 0.078867897 0.038839001, + 0.0220857 0.076689601 0.039483, + 0.0248404 0.074367702 0.039877001, + 0.027557701 0.071919002 0.040015999, + 0.0302257 0.069360897 0.039896, + 0.0328326 0.066711299 0.039514001, + 0.035366699 0.063989803 0.038872, + 0.0378174 0.061217502 0.037976, + 0.040174201 0.058415499 0.036834002, + 0.0424264 0.0556041 0.035456002, + 0.044564299 0.052803699 0.033854, + 0.0465803 0.050034601 0.032044999, + 0.048467699 0.0473161 0.030048, + 0.050219599 0.044665098 0.02788, + 0.051830001 0.042094599 0.025565, + 0.0532961 0.0396153 0.023125, + 0.0532961 0.0410874 0.022542, + 0.051830001 0.043621302 0.024917001, + 0.050219599 0.046243198 0.027161, + 0.048467699 0.0489407 0.029248999, + 0.0465803 0.051697701 0.031164, + 0.044564299 0.0544958 0.032885998, + 0.0424264 0.057315201 0.034396999, + 0.040174201 0.060134798 0.035682, + 0.0378174 0.062934697 0.036729999, + 0.035366699 0.065694101 0.037533, + 0.0328326 0.068391703 0.038082, + 0.0302257 0.071006298 0.038373001, + 0.027557701 0.073519602 0.038407002, + 0.0248404 0.075913899 0.038185999, + 0.0220857 0.078171901 0.037716001, + 0.019305199 0.080277197 0.037002001, + 0.0165099 0.082218103 0.036056001, + 0.0137106 0.083984099 0.03489, + 0.0109179 0.085565902 0.033518001, + 0.0081421202 0.086955599 0.031955, + 0.0053918599 0.088150002 0.030215001, + 0.00267513 0.089147598 0.028315, + 0 0.089948103 0.026269, + -0.00267513 0.089148499 0.028315, + -0.0053918599 0.088151999 0.030215999, + -0.0081421202 0.086959101 0.031957, + -0.0109179 0.085570998 0.033521, + -0.0137106 0.083990701 0.034894001, + -0.0165099 0.082226001 0.036061, + -0.019305199 0.080286302 0.037009001, + -0.0220857 0.078181699 0.037725002, + -0.0248404 0.075924203 0.038197, + -0.027557701 0.0735301 0.038419001, + -0.0302257 0.071016699 0.038387001, + -0.0328326 0.068401702 0.038098, + -0.035366699 0.065703399 0.037549999, + -0.0378174 0.062943198 0.036749002, + -0.040174201 0.060142402 0.035703, + -0.0424264 0.057321701 0.034419, + -0.044564299 0.054501198 0.032908998, + -0.0465803 0.051701698 0.031188, + -0.048467699 0.048942801 0.029274, + -0.050219599 0.046242598 0.027185, + -0.051830001 0.043617502 0.024941999, + -0.0532961 0.0410816 0.022566, + -0.0532961 0.0425491 0.021910001, + -0.051830001 0.045138899 0.024216, + -0.050219599 0.047811698 0.026382999, + -0.048467699 0.050551798 0.028391, + -0.0465803 0.053341798 0.03022, + -0.044564299 0.056162801 0.031851999, + -0.0424264 0.0589948 0.033271, + -0.040174201 0.0618168 0.034463, + -0.0378174 0.064608201 0.035417002, + -0.035366699 0.0673481 0.036125999, + -0.0328326 0.070015199 0.036584001, + -0.0302257 0.072589003 0.036787, + -0.027557701 0.075051501 0.036736999, + -0.0248404 0.077385202 0.036437999, + -0.0220857 0.079572998 0.035895001, + -0.019305199 0.0816008 0.035115998, + -0.0165099 0.083457403 0.034113001, + -0.0137106 0.085132897 0.032898001, + -0.0109179 0.086618699 0.031486999, + -0.0081421202 0.087909803 0.029890999, + -0.0053918599 0.089004003 0.028125999, + -0.00267513 0.089900397 0.026209, + 0 0.090598501 0.024156, + 0.00267513 0.089899696 0.026208, + 0.0053918599 0.089002296 0.028125999, + 0.0081421202 0.087906703 0.029890001, + 0.0109179 0.086613998 0.031484999, + 0.0137106 0.085126497 0.032894999, + 0.0165099 0.083449498 0.034108002, + 0.019305199 0.081591599 0.035110001, + 0.0220857 0.079562701 0.035886999, + 0.0248404 0.077374101 0.036428001, + 0.027557701 0.075040102 0.036725, + 0.0302257 0.072577499 0.036773, + 0.0328326 0.070003897 0.036568001, + 0.035366699 0.067337401 0.036109, + 0.0378174 0.064598203 0.035397999, + 0.040174201 0.0618077 0.034442, + 0.0424264 0.058986802 0.033248998, + 0.044564299 0.056155998 0.031829, + 0.0465803 0.053336199 0.030196, + 0.048467699 0.0505476 0.028365999, + 0.050219599 0.0478095 0.026357999, + 0.051830001 0.045139499 0.024191, + 0.0532961 0.042553 0.021884, + 0.0546159 0.042859402 0.018056, + 0.055787299 0.039021801 0.016341001, + 0.056809202 0.035398699 0.014365, + 0.0576833 0.032048799 0.012178, + 0.058412101 0.028888101 0.0098650102, + 0.058998398 0.023463501 0.0084490096, + 0.0532961 0.045455098 0.020339999, + -0.0546159 0.044244599 0.017268, + -0.0546159 0.042858899 0.018082, + -0.0532961 0.0454574 0.020367, + -0.0532961 0.046887599 0.019478999, + -0.051830001 0.048139501 0.022523999, + -0.051830001 0.0496068 0.021559, + -0.050219599 0.050889298 0.024533, + -0.050219599 0.052385401 0.023486, + -0.048467699 0.053689301 0.026373999, + -0.048467699 0.055204999 0.025241001, + -0.0465803 0.0565206 0.028029, + -0.0465803 0.058046799 0.02681, + -0.044564299 0.0593637 0.029483, + -0.044564299 0.0608906 0.028176, + -0.0424264 0.0621976 0.030722, + -0.0424264 0.063714802 0.029327, + -0.040174201 0.065000601 0.031732999, + -0.040174201 0.066497602 0.030251, + -0.0378174 0.067751601 0.032508001, + -0.0378174 0.069218799 0.030941, + -0.035366699 0.070430502 0.033043001, + -0.035366699 0.071858197 0.031394999, + -0.0328326 0.073016897 0.033333, + -0.0328326 0.074395299 0.031608, + -0.0302257 0.075490601 0.033376999, + -0.0302257 0.076810397 0.031580999, + -0.027557701 0.077834003 0.033179, + -0.027557701 0.0790876 0.031316999, + -0.0248404 0.080031797 0.032745, + -0.0248404 0.0812122 0.030825, + -0.0220857 0.082069799 0.032081001, + -0.0220857 0.083170198 0.030111, + -0.019305199 0.083934397 0.031196, + -0.019305199 0.084949002 0.029184001, + -0.0165099 0.085615799 0.030104, + -0.0165099 0.086541101 0.028057, + -0.0137106 0.087107502 0.028816, + -0.0137106 0.087940998 0.02674, + -0.0109179 0.088404499 0.027345, + -0.0109179 0.089144103 0.025248, + -0.0081421202 0.089502901 0.025703, + -0.0081421202 0.0901464 0.023596, + -0.0053918599 0.0904008 0.023910999, + -0.0053918599 0.090944998 0.021817001, + -0.00267513 0.091096297 0.021999, + -0.00267513 0.091546901 0.019904001, + 0 0.091596797 0.019963, + 0 0.0919903 0.017757, + 0.00267513 0.091546401 0.019904001, + 0.00267513 0.091095902 0.021999, + 0.0053918599 0.090944096 0.021817001, + 0.0053918599 0.090399697 0.023910999, + 0.0081421202 0.090144798 0.023596, + 0.0081421202 0.089500703 0.025703, + 0.0109179 0.089141302 0.025248, + 0.0109179 0.088400997 0.027342999, + 0.0137106 0.087936603 0.026738999, + 0.0137106 0.087102301 0.028813999, + 0.0165099 0.086534798 0.028054001, + 0.0165099 0.085608698 0.030099999, + 0.019305199 0.084940702 0.02918, + 0.019305199 0.083925501 0.031191999, + 0.0220857 0.083159998 0.030106001, + 0.0220857 0.082059197 0.032074001, + 0.0248404 0.081200302 0.030818, + 0.0248404 0.080019899 0.032737002, + 0.027557701 0.079074301 0.031309001, + 0.027557701 0.077821098 0.033169001, + 0.0302257 0.076796301 0.031569999, + 0.0302257 0.075477198 0.033365998, + 0.0328326 0.074380703 0.031594999, + 0.0328326 0.0730033 0.033319, + 0.035366699 0.071843497 0.031380001, + 0.035366699 0.070417002 0.033027001, + 0.0378174 0.069204397 0.030924, + 0.0378174 0.0677386 0.032490999, + 0.040174201 0.066483803 0.030231999, + 0.040174201 0.064988397 0.031713001, + 0.0424264 0.063701898 0.029306, + 0.0424264 0.062186401 0.030701, + 0.044564299 0.060878798 0.028154001, + 0.044564299 0.059353601 0.02946, + 0.0465803 0.058036301 0.026786, + 0.0465803 0.056511901 0.028005, + 0.048467699 0.055195902 0.025217, + 0.048467699 0.053681899 0.026349001, + 0.050219599 0.052377701 0.023460001, + 0.050219599 0.050883301 0.024506999, + 0.051830001 0.049600601 0.021531999, + 0.051830001 0.048135102 0.022498, + 0.0532961 0.046883099 0.019452, + -0.055787299 0.044319998 0.013234, + 0.058998398 0.0132552 -0.010443, + 0.0587232 0.0125 -0.011771, + 0.058412101 0.01324 -0.013237, + 0.059445001 0.0148168 -0.0080199996, + 0.059757002 0.0155666 -0.0055229901, + 0.059445001 0.0140618 -0.0078029898, + 0.058998398 0.0140317 -0.010584, + -0.0302257 0.085344099 0.0076580001, + -0.0302257 0.085067399 0.0097989999, + -0.027557701 0.086857498 0.0068939999, + -0.0328326 0.083702497 0.0082299998, + -0.0328326 0.083406404 0.010313, + -0.035366699 0.081938997 0.0085840002, + -0.035366699 0.081608601 0.01055, + -0.0378174 0.080047503 0.0086670099, + -0.0378174 0.079651199 0.010616, + -0.040174201 0.078006297 0.0085819997, + -0.040174201 0.077541597 0.010525, + -0.0424264 0.075822897 0.00834399, + -0.0424264 0.075295299 0.01026, + -0.044564299 0.073513299 0.0079380004, + -0.044564299 0.072927199 0.009819, + -0.0465803 0.071094401 0.0073640002, + -0.0465803 0.0704538 0.009203, + -0.048467699 0.068582997 0.0066249999, + -0.048467699 0.067892298 0.0084190099, + -0.050219599 0.065995999 0.0057270098, + -0.050219599 0.065259904 0.0074720001, + -0.051830001 0.063350499 0.004677, + -0.051830001 0.062575802 0.0063680001, + -0.0532961 0.060665902 0.00348199, + -0.0532961 0.059859298 0.0051150098, + -0.0546159 0.057961401 0.0021519901, + -0.0546159 0.0571297 0.00372301, + -0.055787299 0.055255398 0.00069599901, + -0.055787299 0.054405302 0.002203, + -0.056809202 0.051704701 0.000567001, + 0.0546159 0.0519768 0.010815, + 0.055787299 0.0503776 0.0077, + 0.0546159 0.053120501 0.009505, + 0.0532961 0.054755401 0.012564, + 0.0532961 0.0559 0.011178, + 0.051830001 0.057560299 0.014167, + 0.051830001 0.058697801 0.012706, + 0.050219599 0.060372401 0.01561, + 0.050219599 0.0614946 0.014074, + 0.048467699 0.063171797 0.016879, + 0.048467699 0.064269997 0.01527, + 0.0465803 0.0659381 0.017964, + 0.0465803 0.067003399 0.016286001, + 0.044564299 0.068650298 0.018856, + 0.044564299 0.069675401 0.017113, + 0.0424264 0.071288399 0.019548999, + 0.0424264 0.072266102 0.017746, + 0.040174201 0.073832802 0.020037999, + 0.040174201 0.074755803 0.01818, + 0.0378174 0.076265298 0.020322001, + 0.0378174 0.0771266 0.018416001, + 0.035366699 0.078568198 0.020401999, + 0.035366699 0.0793631 0.018452, + 0.0328326 0.080726303 0.020277999, + 0.0328326 0.081450403 0.018291, + 0.0302257 0.082725197 0.019951999, + 0.0302257 0.083374798 0.017935, + 0.027557701 0.084554002 0.019431001, + 0.027557701 0.085124999 0.017392, + 0.0248404 0.086202197 0.018724, + 0.0248404 0.086689502 0.016687, + 0.0220857 0.0876588 0.017855, + 0.0220857 0.088065997 0.015806001, + 0.019305199 0.088922299 0.016814001, + 0.019305199 0.089283302 0.014644, + 0.0165099 0.090024598 0.015497, + 0.0165099 0.090655297 0.011049, + 0.0137106 0.091287702 0.011741, + 0.0137106 0.091784596 0.0072339899, + 0.0109179 0.092304103 0.0077760001, + 0.0109179 0.0926525 0.0032209901, + 0.0081421202 0.093056202 0.0036219901, + 0.0081421202 0.093249798 -0.00096699502, + 0.0053918599 0.093537003 -0.00069599901, + 0.0053918599 0.093571797 -0.0053079999, + 0.00267513 0.093743198 -0.0051540099, + 0.00267513 0.093616098 -0.0097780004, + 0 0.093672998 -0.00973, + 0 0.093381301 -0.014353, + -0.00267513 0.0936165 -0.0097780004, + -0.00267513 0.093743898 -0.0051540099, + -0.0053918599 0.093573101 -0.0053079999, + -0.0053918599 0.093538597 -0.00069599901, + -0.0081421202 0.093252197 -0.00096699502, + -0.0081421202 0.093058899 0.0036230001, + -0.0109179 0.092656098 0.0032230101, + -0.0109179 0.092307799 0.0077790101, + -0.0137106 0.091789097 0.0072380099, + -0.0137106 0.091291703 0.011748, + -0.055787299 0.0503924 0.0077280002, + -0.055787299 0.0492558 0.008963, + -0.0546159 0.051991299 0.010842, + -0.0546159 0.053137101 0.0095319999, + -0.0532961 0.054771598 0.01259, + -0.0532961 0.055918299 0.011203, + -0.051830001 0.057578102 0.014192, + -0.051830001 0.0587175 0.012729, + -0.050219599 0.060391501 0.015632, + -0.050219599 0.061515398 0.014095, + -0.048467699 0.063191898 0.016899001, + -0.048467699 0.0642915 0.015289, + -0.0465803 0.065958701 0.017982, + -0.0465803 0.0670252 0.016302001, + -0.044564299 0.0686711 0.018872, + -0.044564299 0.069696799 0.017127, + -0.0424264 0.071308799 0.019563001, + -0.0424264 0.072286502 0.017757, + -0.040174201 0.073852099 0.020049, + -0.040174201 0.074774399 0.01819, + -0.0378174 0.076282799 0.020331001, + -0.0378174 0.077142797 0.018423, + -0.035366699 0.078583397 0.020408999, + -0.035366699 0.0793764 0.018457999, + -0.0328326 0.080738701 0.020283001, + -0.0328326 0.081460901 0.018294999, + -0.0302257 0.082734898 0.019955, + -0.0302257 0.083382599 0.017936001, + -0.027557701 0.084561102 0.019432001, + -0.027557701 0.085130602 0.017392, + -0.0248404 0.0862073 0.018724, + -0.0248404 0.086693697 0.016686, + -0.0220857 0.087662503 0.017855, + -0.0220857 0.088069603 0.015807001, + -0.019305199 0.088925399 0.016814999, + -0.019305199 0.089287303 0.01465, + -0.0165099 0.090028003 0.015502, + -0.0165099 0.090660103 0.011056, + -0.0165099 0.0911441 0.0065649999, + -0.0137106 0.092127301 0.0026970101, + -0.0109179 0.092842102 -0.001355, + -0.0081421202 0.093281902 -0.0055709998, + -0.0053918599 0.093443103 -0.0099269999, + -0.00267513 0.093323998 -0.0144, + 0 0.092925198 -0.018966001, + 0.00267513 0.0933237 -0.0144, + 0.0053918599 0.093442202 -0.0099269999, + 0.0081421202 0.093280002 -0.0055709998, + 0.0109179 0.092838898 -0.001356, + 0.0137106 0.092122801 0.00269501, + 0.0165099 0.091138601 0.0065600001, + 0.019305199 0.089896902 0.010218, + 0.0220857 0.088416703 0.013648, + 0.0248404 0.087084502 0.014649, + 0.027557701 0.085597597 0.01537, + 0.0302257 0.083928302 0.015913, + 0.0328326 0.0820795 0.016292, + 0.035366699 0.080063596 0.016485, + 0.0378174 0.077894501 0.016486, + 0.040174201 0.075586803 0.016294001, + 0.0424264 0.073155098 0.015907999, + 0.044564299 0.070615597 0.01533, + 0.0465803 0.067987598 0.014563, + 0.048467699 0.065291002 0.013613, + 0.050219599 0.062545098 0.012485, + 0.051830001 0.059769299 0.011188, + 0.0532961 0.056984 0.0097339898, + 0.0546159 0.054209001 0.008134, + 0.055787299 0.051463101 0.0064040101, + 0.056809202 0.047689099 0.0057799998, + 0.058412101 0.0140014 -0.013383, + 0.0576833 0.013971 -0.016189, + 0.058412101 0.014724 -0.013617, + 0.058998398 0.0147705 -0.01081, + 0.058998398 0.0154372 -0.011095, + 0.059445001 0.0155022 -0.0082940096, + 0.059445001 0.0166071 -0.0088959998, + 0.059757002 0.016719701 -0.0061000101, + 0.059757002 0.017621201 -0.0066430098, + 0.0599402 0.0177908 -0.0038620001, + 0.0599402 0.021398701 -0.0059799999, + 0.059999999 0.0218067 -0.0031290001, + 0.059999999 0.025559001 -0.0051330002, + 0.0599402 0.026211699 -0.0021929899, + 0.0599402 0.028073199 -0.0031640001, + 0.059757002 0.028852399 -0.00015699799, + 0.059757002 0.0307806 -0.001259, + 0.059445001 0.031692199 0.001825, + 0.059445001 0.033758201 0.00054200698, + 0.058998398 0.034805801 0.0036869999, + 0.058998398 0.036964901 0.00219501, + 0.058412101 0.0381473 0.0053760102, + 0.058412101 0.040385202 0.0036460001, + 0.0576833 0.041698799 0.0068410002, + 0.0576833 0.0439776 0.0048529999, + 0.056809202 0.045416102 0.0080390004, + 0.055787299 0.0492431 0.0089349998, + 0.0546159 0.0507828 0.012061, + 0.0532961 0.0535542 0.013887, + 0.051830001 0.056360599 0.015568, + 0.050219599 0.059182599 0.017088, + 0.048467699 0.062000301 0.018433001, + 0.0465803 0.0647939 0.019591, + 0.044564299 0.0675423 0.020554001, + 0.0424264 0.070224203 0.021313, + 0.040174201 0.072819598 0.021862, + 0.0378174 0.075310402 0.0222, + 0.035366699 0.077678502 0.022328001, + 0.0328326 0.079906397 0.022244999, + 0.0302257 0.081979401 0.021956, + 0.027557701 0.083885796 0.021464, + 0.0248404 0.085615501 0.020777, + 0.0220857 0.087158501 0.019905999, + 0.019305199 0.088504396 0.018874999, + 0.0165099 0.089654699 0.017677, + 0.0137106 0.090642802 0.016208, + 0.0109179 0.091796398 0.012298, + 0.0081421202 0.092700101 0.0081879999, + 0.0053918599 0.0933384 0.0039019899, + 0.00267513 0.093705699 -0.00053700298, + 0 0.093799397 -0.0051040002, + -0.00267513 0.093706504 -0.00053700298, + -0.0053918599 0.093340203 0.0039029999, + -0.0081421202 0.092702799 0.0081909904, + -0.0109179 0.091799699 0.012304, + -0.0137106 0.090645596 0.016212, + -0.0165099 0.089657404 0.017678, + -0.019305199 0.0885076 0.018874999, + -0.0220857 0.087163001 0.019905999, + -0.0248404 0.085621998 0.020778, + -0.027557701 0.083894603 0.021466, + -0.0302257 0.081990801 0.02196, + -0.0328326 0.079920501 0.022252001, + -0.035366699 0.0776949 0.022336001, + -0.0378174 0.075328499 0.022211, + -0.040174201 0.072838902 0.021875, + -0.0424264 0.070243999 0.021328, + -0.044564299 0.067561999 0.020571001, + -0.0465803 0.064813197 0.019610999, + -0.048467699 0.062018801 0.018454, + -0.050219599 0.059199799 0.017112, + -0.051830001 0.056376401 0.015594, + -0.0532961 0.0535684 0.013914, + -0.0546159 0.050795201 0.012088, + -0.055787299 0.048075099 0.010134, + -0.056809202 0.0454248 0.0080690002, + -0.058998398 0.0140343 -0.010568, + -0.058998398 0.0147736 -0.010771, + -0.058412101 0.0140039 -0.013368, + -0.058412101 0.013257 -0.013261, + -0.057669599 0.0125 -0.016006, + -0.058007602 0.0125 -0.014776, + -0.0576833 0.0132416 -0.016062001, + -0.0576833 0.0139735 -0.016173, + -0.056809202 0.0132262 -0.018858001, + -0.058412101 0.014727 -0.013579, + -0.058998398 0.0154515 -0.011057, + -0.059445001 0.0155166 -0.0082559995, + -0.059445001 0.016627301 -0.0088919997, + -0.059757002 0.01674 -0.0060959901, + -0.059757002 0.0176263 -0.0066390098, + -0.0599402 0.0177959 -0.003858, + -0.0599402 0.021402201 -0.0059810001, + -0.059999999 0.021810099 -0.0031300001, + -0.059999999 0.0255592 -0.005134, + -0.0599402 0.026211901 -0.0021929899, + -0.0599402 0.028096501 -0.0031590001, + -0.059757002 0.028875601 -0.00015199299, + -0.059757002 0.030785101 -0.00124001, + -0.059445001 0.031696599 0.0018439899, + -0.059445001 0.0337517 0.00056900003, + -0.058998398 0.034799401 0.0037130001, + -0.058998398 0.036964301 0.0022239999, + -0.058412101 0.038146701 0.0054049999, + -0.058412101 0.040390201 0.00367599, + -0.0576833 0.041703701 0.0068709999, + -0.0576833 0.043986399 0.0048830002, + -0.056809202 0.047701899 0.00580901, + -0.055787299 0.0514801 0.0064309998, + -0.0546159 0.054227799 0.0081599997, + -0.0532961 0.057004299 0.0097580003, + -0.051830001 0.059790801 0.01121, + -0.050219599 0.062567398 0.012505, + -0.048467699 0.0653136 0.01363, + -0.0465803 0.068009898 0.014578, + -0.044564299 0.070637003 0.015343, + -0.0424264 0.073174797 0.015919, + -0.040174201 0.075603999 0.016302001, + -0.0378174 0.077908799 0.016492, + -0.035366699 0.080074899 0.016488999, + -0.0328326 0.082088098 0.016294001, + -0.0302257 0.083934501 0.015913, + -0.027557701 0.085602097 0.015369, + -0.0248404 0.087088503 0.014651, + -0.0220857 0.0884213 0.013655, + -0.019305199 0.089902602 0.010227, + -0.019305199 0.090370499 0.0057589998, + -0.0220857 0.089260504 0.0070409998, + -0.055787299 0.052514002 0.0050750002, + -0.055787299 0.0534903 0.003664, + -0.056809202 0.049807601 0.00330099, + -0.0546159 0.055259299 0.0067319898, + -0.0546159 0.0562279 0.0052510099, + -0.0532961 0.058025599 0.008258, + -0.0532961 0.058978502 0.0067090001, + -0.051830001 0.060793798 0.0096399998, + -0.051830001 0.061722901 0.0080239996, + -0.050219599 0.063543603 0.010867, + -0.050219599 0.0644418 0.0091869999, + -0.048467699 0.0662558 0.011928, + -0.048467699 0.067116 0.010189, + -0.0465803 0.068911001 0.012816, + -0.0465803 0.069726102 0.011022, + -0.044564299 0.071489602 0.013526, + -0.044564299 0.072252899 0.011683, + -0.0424264 0.073972099 0.014052, + -0.0424264 0.0746786 0.012165, + -0.040174201 0.0763411 0.014392, + -0.040174201 0.0769867 0.012464, + -0.0378174 0.078581698 0.014543, + -0.0378174 0.079162396 0.012582, + -0.035366699 0.0806797 0.014507, + -0.035366699 0.081191197 0.01252, + -0.0328326 0.082620598 0.014288, + -0.0328326 0.083057597 0.012299, + -0.0302257 0.084389597 0.013906, + -0.0302257 0.084755197 0.011902, + -0.027557701 0.085983098 0.013349, + -0.027557701 0.086309999 0.011228, + -0.0248404 0.087428503 0.012514, + -0.0248404 0.088001497 0.0081460001, + -0.0220857 0.089016899 0.0092580002, + -0.0576833 0.046139799 0.0026380001, + -0.058412101 0.042546 0.001692, + -0.058998398 0.0390797 0.000488007, + -0.059445001 0.0357894 -0.00093699602, + -0.059757002 0.032715201 -0.00254201, + -0.0599402 0.029885501 -0.0042829998, + -0.059999999 0.027323401 -0.0061430102, + -0.0599402 0.024906499 -0.0080740098, + -0.059757002 0.020990999 -0.0088539999, + -0.059445001 0.017454401 -0.0094579896, + -0.058998398 0.0165134 -0.011718, + -0.058412101 0.0153859 -0.013876, + -0.0576833 0.0146802 -0.016393, + -0.056809202 0.0139432 -0.018975001, + -0.055787299 0.0132108 -0.021640001, + -0.056127101 0.0125 -0.020659, + -0.0546159 0.0131956 -0.024396, + -0.0554736 0.0125 -0.022361999, + -0.055787299 0.0139129 -0.021762, + -0.056809202 0.0146336 -0.019203, + -0.0576833 0.0153201 -0.016702, + -0.058412101 0.0163987 -0.014562, + -0.058998398 0.017280599 -0.012307, + -0.059445001 0.0205744 -0.011765, + -0.059757002 0.024248701 -0.011038, + -0.0599402 0.0265502 -0.0091270003, + -0.059999999 0.028992901 -0.0073020002, + -0.0599402 0.031692401 -0.0056109899, + -0.059757002 0.034627099 -0.0040640002, + -0.059445001 0.037777599 -0.0026789999, + -0.058998398 0.041108899 -0.0014909999, + -0.058412101 0.044575401 -0.00053799403, + -0.0576833 0.048126101 0.00015400699, + -0.0248404 0.088234201 0.0059450101, + -0.0220857 0.089466102 0.0048159901, + -0.019305199 0.090545699 0.003513, + -0.0165099 0.091469601 0.00204401, + -0.0137106 0.092303701 -0.00186501, + -0.0109179 0.092864998 -0.0059470101, + -0.0081421202 0.093147501 -0.010181, + -0.0053918599 0.093148202 -0.014544, + -0.00267513 0.092867099 -0.019012, + 0 0.092305399 -0.023560001, + 0.00267513 0.092866898 -0.019012, + 0.0053918599 0.093147598 -0.014544, + 0.0081421202 0.093145996 -0.010181, + 0.0109179 0.092862397 -0.0059470101, + 0.0137106 0.0922997 -0.00186501, + 0.0165099 0.091464199 0.00204201, + 0.019305199 0.090364099 0.00575301, + 0.0220857 0.0892535 0.007032, + 0.055787299 0.052494802 0.0050479998, + 0.056809202 0.0497902 0.00327299, + 0.055787299 0.053469099 0.00363901, + 0.0546159 0.0552385 0.0067070001, + 0.0546159 0.056205198 0.0052280002, + 0.0532961 0.0580035 0.0082350001, + 0.0532961 0.058954898 0.0066880002, + 0.051830001 0.060770798 0.0096199997, + 0.051830001 0.061698701 0.008006, + 0.050219599 0.063520201 0.010849, + 0.050219599 0.064417697 0.00917101, + 0.048467699 0.066232502 0.011912, + 0.048467699 0.067092799 0.010175, + 0.0465803 0.068888597 0.012803, + 0.0465803 0.0697046 0.011011, + 0.044564299 0.071468897 0.013515, + 0.044564299 0.072233804 0.011674, + 0.0424264 0.073953897 0.014044, + 0.0424264 0.074662603 0.012158, + 0.040174201 0.076325901 0.014386, + 0.040174201 0.0769739 0.01246, + 0.0378174 0.078569703 0.014539, + 0.0378174 0.079152502 0.01258, + 0.035366699 0.080670498 0.014505, + 0.035366699 0.081183903 0.012521, + 0.0328326 0.082613803 0.014288, + 0.0328326 0.083052203 0.0123, + 0.0302257 0.084384598 0.013907, + 0.0302257 0.084750399 0.0119, + 0.027557701 0.085978702 0.013347, + 0.027557701 0.0863043 0.011219, + 0.0248404 0.087423399 0.012506, + 0.0248404 0.087994203 0.008134, + 0.0220857 0.089010403 0.0092469901, + 0.0576833 0.046126802 0.0026089901, + 0.058412101 0.042537 0.001662, + 0.058998398 0.0390747 0.00045799301, + 0.059445001 0.03579 -0.00096600299, + 0.059757002 0.032721698 -0.002569, + 0.0599402 0.029881001 -0.0043020002, + 0.059999999 0.0273 -0.00614799, + 0.0599402 0.0249063 -0.0080740098, + 0.059757002 0.0209876 -0.0088529997, + 0.059445001 0.017449399 -0.0094620101, + 0.058998398 0.0164933 -0.011722, + 0.058412101 0.0153717 -0.013913, + 0.0576833 0.0146773 -0.016431, + 0.056809202 0.0139407 -0.018990001, + 0.056809202 0.0132097 -0.018835001, + 0.056432001 0.0125 -0.019881999, + 0.055787299 0.0131947 -0.021617001, + 0.0576833 0.0132249 -0.016038001, + 0.057145901 0.0125 -0.017743001, + 0.058157299 0.0125 -0.014256, + 0.0599402 0.0168308 -0.0033410001, + 0.059999999 0.0179592 -0.00110201, + 0.0599402 0.022214601 -0.00027799999, + 0.059757002 0.0268695 0.00077099598, + 0.059445001 0.029642001 0.0028910099, + 0.058998398 0.032613602 0.0049429899, + 0.058412101 0.035860099 0.0068509998, + 0.0576833 0.039332502 0.0085650003, + 0.056809202 0.043010499 0.010032, + 0.055787299 0.046847001 0.011209, + 0.0546159 0.049543701 0.01324, + 0.0532961 0.052301601 0.015144, + 0.051830001 0.055103101 0.016904, + 0.050219599 0.057929199 0.018503999, + 0.048467699 0.0607596 0.019927001, + 0.0465803 0.063574702 0.021163, + 0.044564299 0.066353701 0.0222, + 0.0424264 0.069075398 0.023029, + 0.040174201 0.071718201 0.023645001, + 0.0378174 0.074263602 0.024042999, + 0.035366699 0.076693699 0.024224, + 0.0328326 0.078990303 0.024188999, + 0.0302257 0.081136599 0.023940001, + 0.027557701 0.083120301 0.023483001, + 0.0248404 0.084930703 0.022824001, + 0.0220857 0.086557798 0.021972001, + 0.019305199 0.087992698 0.020936999, + 0.0165099 0.089227699 0.019747, + 0.0137106 0.090265498 0.018395999, + 0.0109179 0.091140099 0.016779, + 0.0081421202 0.092184097 0.012723, + 0.0053918599 0.092976898 0.0084770098, + 0.00267513 0.093504302 0.00406599, + 0 0.093761101 -0.00048500099, + -0.00267513 0.093505099 0.004067, + -0.0053918599 0.092978701 0.0084779998, + -0.0081421202 0.092186503 0.012727, + -0.0109179 0.091142297 0.016783001, + -0.0137106 0.090267703 0.018397, + -0.0165099 0.0892305 0.019747, + -0.019305199 0.087996602 0.020936999, + -0.0220857 0.086563602 0.021973001, + -0.0248404 0.084938601 0.022826999, + -0.027557701 0.083130702 0.023487, + -0.0302257 0.081149504 0.023946, + -0.0328326 0.079005502 0.024196999, + -0.035366699 0.076710597 0.024234001, + -0.0378174 0.074281797 0.024055, + -0.040174201 0.071736902 0.023659, + -0.0424264 0.069094203 0.023046, + -0.044564299 0.066372201 0.022219, + -0.0465803 0.063592397 0.021183001, + -0.048467699 0.060776301 0.019950001, + -0.050219599 0.057944499 0.018528, + -0.051830001 0.055116799 0.016930001, + -0.0532961 0.0523136 0.015171, + -0.0546159 0.049554002 0.013268, + -0.055787299 0.046855502 0.011238, + -0.056809202 0.043015402 0.010061, + -0.0576833 0.039331902 0.0085939895, + -0.058412101 0.035853699 0.006877, + -0.058998398 0.032618102 0.0049620098, + -0.059445001 0.0296652 0.0028959999, + -0.059757002 0.0268698 0.000770004, + -0.0599402 0.022218101 -0.00027900701, + -0.059999999 0.0179643 -0.00109801, + -0.0599402 0.0168512 -0.00333701, + -0.059757002 0.0155811 -0.0054850001, + -0.059445001 0.0148199 -0.0079809995, + -0.058985401 0.0125 -0.010416, + -0.0592747 0.0125 -0.0087319901, + -0.059445001 0.0140644 -0.0077869999, + -0.059757002 0.0148657 -0.0052209902, + -0.0599402 0.015644601 -0.00275101, + -0.059999999 0.016961601 -0.00059899897, + -0.0599402 0.018132599 0.001662, + -0.059757002 0.0226292 0.0025939899, + -0.059445001 0.0275364 0.0037740001, + -0.058998398 0.0304632 0.0059759999, + -0.058412101 0.0335453 0.008099, + -0.0576833 0.036910601 0.010049, + -0.056809202 0.0405154 0.011778, + 0.059323099 0.0125 -0.0084870001, + 0.058982499 0.0125 -0.010415, + 0.058731299 0.0074999998 -0.011773, + 0.058811001 0.0125 -0.011386, + 0.058396202 0.0125 -0.013207, + 0.057158101 0.0074999998 -0.017747, + 0.0573637 0.0125 -0.01709, + 0.0576673 0.0125 -0.016005, + 0.056793101 0.0125 -0.0188, + 0.054979 0.0074999998 -0.023527, + 0.059682 0.0074999998 -0.0056690099, + 0.0594301 0.0125 -0.00764101, + 0.059744101 0.0125 -0.004896, + 0.0137813 0.0074999998 0.058896001, + 0.0109153 0.0125 0.059484001, + 0.0077038999 0.0074999998 0.060003001, + 0.0193002 0.0125 0.057294, + 0.019709 0.0125 0.057158999, + 0.019305199 0.014768 0.057300001, + 0.017454101 0.0125 0.057905, + 0.0165099 0.017051499 0.058157001, + 0.019305199 0.017030699 0.057273999, + 0.019305199 0.0215177 0.057225, + 0.0220857 0.0214536 0.056175001, + 0.0220857 0.0302736 0.056031998, + 0.0248404 0.0300957 0.054790001, + 0.0248404 0.0388203 0.054611001, + 0.027557701 0.038499899 0.053167, + 0.027557701 0.0406482 0.053111002, + 0.0302257 0.0402583 0.051495001, + 0.0302257 0.0422123 0.051387001, + 0.0328326 0.041748699 0.049598999, + 0.0328326 0.043685101 0.049392998, + 0.035366699 0.043142401 0.047435999, + 0.035366699 0.045082599 0.047127001, + 0.0378174 0.0444558 0.045006, + 0.0378174 0.0463624 0.044597, + 0.040174201 0.045647401 0.042321999, + 0.040174201 0.0475072 0.041813999, + 0.0424264 0.046700198 0.039391, + 0.0424264 0.048506498 0.038786002, + 0.044564299 0.045850001 0.036839001, + 0.0424264 0.0448891 0.039907999, + 0.040174201 0.043786298 0.042741001, + 0.0378174 0.042557701 0.045327, + 0.035366699 0.041244298 0.047653999, + 0.0328326 0.039829899 0.04972, + 0.0302257 0.038143899 0.051564001, + 0.027557701 0.029895401 0.053390998, + 0.0248404 0.0213801 0.054972999, + 0.0220857 0.017006399 0.056242, + 0.0220799 0.0125 0.056272, + 0.0197125 0.0074999998 0.057169002, + 0.022994 0.0125 0.055918999, + 0.0202484 0.0125 0.056979999, + 0.0220857 0.0147568 0.056274999, + 0.0248404 0.0147441 0.055101, + 0.0165058 0.0125 0.058168001, + 0.0146178 0.0125 0.058692001, + 0.024834299 0.0125 0.055101998, + 0.0254324 0.0125 0.054837, + 0.040174201 0.051210102 0.040527001, + 0.0378174 0.053946 0.042043999, + 0.035366699 0.0566958 0.043322999, + 0.0328326 0.0594391 0.044351, + 0.0302257 0.062155101 0.045118999, + 0.027557701 0.064824097 0.045619, + 0.0248404 0.067427002 0.045850001, + 0.0220857 0.069944501 0.045811001, + 0.019305199 0.0723579 0.045504, + 0.0165099 0.074650601 0.044932999, + 0.0137106 0.076807998 0.044108, + 0.0109179 0.078816697 0.043039002, + 0.0081421202 0.080664001 0.041738, + 0.0053918599 0.082339898 0.040219001, + 0.00267513 0.083837301 0.038499001, + 0 0.085150696 0.036594, + -0.00267513 0.0838385 0.0385, + -0.0053918599 0.082342401 0.040220998, + -0.0081421202 0.0806676 0.041740999, + -0.0109179 0.078821301 0.043044001, + -0.0137106 0.076813303 0.044114001, + -0.0165099 0.0746563 0.044939999, + -0.019305199 0.072363801 0.045513, + -0.0220857 0.069950402 0.045821998, + -0.0248404 0.067432597 0.045862999, + -0.027557701 0.064829297 0.045632999, + -0.0302257 0.062159799 0.045134, + -0.0328326 0.059443001 0.044367999, + -0.035366699 0.056698799 0.043341, + -0.0378174 0.053947601 0.042063002, + -0.040174201 0.051209699 0.040546998, + -0.0424264 0.048503399 0.038805999, + -0.044564299 0.045845199 0.036858998, + -0.044564299 0.044087 0.037384, + -0.0424264 0.044886 0.039925002, + -0.0424264 0.0430796 0.040353, + -0.040174201 0.043789301 0.042753998, + -0.040174201 0.041946001 0.043083001, + -0.0378174 0.042569801 0.045334999, + -0.0378174 0.040715698 0.045561999, + -0.035366699 0.0412581 0.047657002, + -0.0248347 0.0125 0.055103, + -0.0229061 0.0125 0.055955, + -0.0248404 0.0213823 0.054974001, + -0.0226037 0.0074999998 0.056079, + -0.0255982 0.0125 0.054765001, + -0.027557701 0.021299699 0.053619999, + -0.027557701 0.029897001 0.05339, + -0.0302257 0.029674601 0.051835001, + -0.0302257 0.038144 0.051562998, + -0.0328326 0.037753001 0.049802002, + -0.0328326 0.039834399 0.049720999, + -0.035366699 0.039368901 0.047789998, + -0.0378174 0.036869299 0.045821, + -0.040174201 0.040136401 0.043324001, + -0.0424264 0.041284502 0.040695, + -0.044564299 0.0423318 0.037822999, + -0.0465803 0.0432509 0.034724001, + -0.035366699 0.029164501 0.048269998, + -0.0328326 0.0211074 0.050461002, + -0.035366699 0.0168416 0.048872001, + -0.0384284 0.0125 0.046564002, + -0.040173098 0.0125 0.045063, + -0.033437699 0.0125 -0.049318999, + -0.032825399 0.0125 -0.049708001, + -0.033494599 0.0074999998 -0.049281001, + -0.0302257 0.0140902 -0.051908001, + -0.0302257 0.0135894 -0.051576, + -0.0328326 0.0141172 -0.050287999, + -0.024833901 0.0125 -0.054101001, + -0.0226037 0.0074999998 -0.055078998, + -0.025769901 0.0125 -0.053684, + -0.0230815 0.0125 -0.054883, + -0.0248404 0.0130286 -0.054180998, + -0.027557701 0.0130362 -0.052861001, + -0.027557701 0.0135734 -0.053045999, + -0.027557701 0.0140657 -0.053383, + -0.0248404 0.013559 -0.054368999, + -0.0220857 0.0130218 -0.055351999, + -0.0225999 0.0125 -0.055070002, + -0.0220796 0.0125 -0.055272002, + -0.0203376 0.0125 -0.055948, + -0.019300001 0.0125 -0.056293, + -0.0107568 0.0074999998 -0.058527999, + -0.0167691 0.0074999998 -0.057108998, + -0.013707 0.0125 -0.057895999, + -0.0175448 0.0125 -0.056878, + -0.019305199 0.0130158 -0.056373999, + -0.0220857 0.0135462 -0.055543002, + -0.0248404 0.0140436 -0.054710001, + -0.0109179 0.059135299 -0.161883, + -0.0117927 0.058829699 -0.171, + -0.0137106 0.058548201 -0.161907, + -0.0137106 0.058968 -0.152798, + -0.048467699 0.0152574 -0.036180001, + -0.050219599 0.0153378 -0.033611, + -0.049361002 0.0155602 -0.035335999, + -0.048467699 0.0148767 -0.035737, + -0.040174201 0.0130857 -0.044126999, + -0.040382501 0.0125 -0.043876, + -0.0424264 0.0130978 -0.041988, + -0.0424264 0.0136918 -0.042149998, + -0.044564299 0.0137163 -0.039891999, + -0.044564299 0.0142851 -0.040185999, + -0.0465803 0.0143244 -0.037815999, + -0.0465803 0.014819 -0.038210999, + -0.0465803 0.0151797 -0.038665999, + -0.047540501 0.0154575 -0.037875, + -0.044564299 0.0147635 -0.040589999, + -0.0424264 0.0142474 -0.042451002, + -0.040174201 0.0136685 -0.044293001, + -0.0378174 0.0130744 -0.046144001, + -0.038430501 0.0125 -0.045566998, + -0.0328326 0.0130538 -0.049784001, + -0.033493701 0.0125 -0.049279001, + -0.035366699 0.0130637 -0.048032001, + -0.035366699 0.013626 -0.048206002, + -0.030218599 0.0125 -0.051318001, + -0.0281986 0.0074999998 -0.052460998, + -0.030954201 0.0125 -0.050898999, + -0.0283962 0.0125 -0.052354999, + -0.0302257 0.0130446 -0.051394999, + -0.0328326 0.0136069 -0.049961999, + -0.035366699 0.0141465 -0.048526, + -0.0378174 0.014178 -0.046627998, + -0.036603201 0.0145897 -0.048027001, + -0.040174201 0.0142117 -0.044601001, + -0.0390082 0.0146358 -0.046055999, + -0.0378174 0.0136466 -0.046314001, + -0.035840798 0.0125 -0.047619, + -0.0424264 0.0147104 -0.042863999, + -0.043510102 0.0150687 -0.042211, + -0.0053918599 0.059895601 -0.161852, + -0.0059725801 0.059702002 -0.171, + -0.0081421202 0.059582699 -0.161865, + -0.0081421202 0.060003102 -0.152714, + -0.0378174 0.0150725 -0.048470002, + -0.0378174 0.0150465 -0.048036002, + -0.0390082 0.0151237 -0.047455002, + -0.0378174 0.0150469 -0.048921999, + -0.040174201 0.0151732 -0.046852, + -0.040174201 0.0151325 -0.048627, + -0.051830001 0.019267 -0.042906001, + -0.051830001 0.018956499 -0.041257001, + -0.0532961 0.020674599 -0.041604999, + -0.050219599 0.018090799 -0.044186, + -0.050219599 0.0178787 -0.042589001, + -0.048467699 0.017149501 -0.045402002, + -0.048467699 0.0169718 -0.043821, + -0.0465803 0.0163767 -0.046502002, + -0.0465803 0.016239701 -0.044875, + -0.044564299 0.0157758 -0.047412999, + -0.044564299 0.0157132 -0.045733999, + -0.0424264 0.0153713 -0.048122, + -0.0424264 0.0153614 -0.046395998, + -0.0424264 0.0153072 -0.044656999, + -0.041313998 0.0152311 -0.045331001, + -0.044564299 0.0156025 -0.044046, + -0.0465803 0.0160709 -0.043235, + -0.048467699 0.0167222 -0.042234998, + -0.050219599 0.017587099 -0.041049, + -0.051830001 0.0186287 -0.039694998, + -0.0532961 0.019842399 -0.038260002, + -0.0546159 0.021825001 -0.038509998, + -0.0546159 0.022300201 -0.040325999, + -0.055787299 0.0235929 -0.037182, + -0.055787299 0.0241253 -0.039110001, + -0.056809202 0.025556199 -0.035939999, + -0.056809202 0.026123499 -0.037997, + -0.0576833 0.027685801 -0.034825001, + -0.0576833 0.028261701 -0.037018999, + -0.058412101 0.0299458 -0.033868, + -0.058412101 0.030500401 -0.036205001, + -0.058998398 0.032294199 -0.033094, + -0.058998398 0.0327974 -0.035572, + -0.059445001 0.034685899 -0.032522, + -0.059445001 0.035107002 -0.035131, + -0.059757002 0.0370727 -0.032161999, + -0.059757002 0.037384499 -0.034887999, + -0.0599402 0.039412301 -0.03201, + -0.0599402 0.039590102 -0.034832001, + -0.059999999 0.0416812 -0.032032002, + -0.059999999 0.0417105 -0.034931999, + -0.0599402 0.043872099 -0.032189999, + -0.0599402 0.043740101 -0.035135001, + -0.059757002 0.045981199 -0.032430999, + -0.059757002 0.045707401 -0.035452999, + -0.059445001 0.048034798 -0.032777999, + -0.059445001 0.047708001 -0.035966001, + -0.058998398 0.0501143 -0.033332001, + -0.058998398 0.0497378 -0.036609001, + -0.058412101 0.0522108 -0.034030002, + -0.058412101 0.051773801 -0.037381001, + -0.0576833 0.054301199 -0.034871001, + -0.0576833 0.053797301 -0.038291998, + -0.056809202 0.056366298 -0.035861999, + -0.056809202 0.055789702 -0.039351001, + -0.055787299 0.058387101 -0.037011001, + -0.055787299 0.0577318 -0.040564999, + -0.0546159 0.0603434 -0.038325001, + -0.0546159 0.059603199 -0.041940998, + -0.0532961 0.062213901 -0.039809, + -0.0532961 0.061381798 -0.043481998, + -0.051830001 0.063975997 -0.041466001, + -0.051830001 0.063052498 -0.045189001, + -0.050219599 0.065613799 -0.043296002, + -0.050219599 0.064602099 -0.047076002, + -0.048467699 0.067113496 -0.045308001, + -0.048467699 0.065998897 -0.049144998, + -0.0465803 0.068444699 -0.047504999, + -0.0465803 0.067221299 -0.051385999, + -0.044564299 0.069586203 -0.049872, + -0.044564299 0.0682505 -0.053782001, + -0.0424264 0.070519499 -0.052395001, + -0.0424264 0.069068402 -0.05632, + -0.040174201 0.071227401 -0.055055998, + -0.040174201 0.069657698 -0.058983002, + -0.0378174 0.071695603 -0.057840001, + -0.0378174 0.070006303 -0.061755002, + -0.035366699 0.071913101 -0.060727999, + -0.035366699 0.068508103 -0.068700999, + -0.0328326 0.0702741 -0.067827001, + -0.0328326 0.067112803 -0.076010004, + -0.0302257 0.068733498 -0.075277999, + -0.0302257 0.065825902 -0.083650999, + -0.027557701 0.067299701 -0.083048001, + -0.027557701 0.064653397 -0.091590002, + -0.0248404 0.0659789 -0.091103002, + -0.0248404 0.063600697 -0.099793002, + -0.0220857 0.064776503 -0.099409997, + -0.0220857 0.062672101 -0.108227, + -0.019305199 0.063697197 -0.107935, + -0.019305199 0.0618692 -0.116859, + -0.0165099 0.062745497 -0.116646, + -0.0165099 0.061195999 -0.12565599, + -0.0137106 0.061926499 -0.125508, + -0.0137106 0.060657501 -0.13458499, + -0.0109179 0.061245002 -0.13449, + -0.0109179 0.060258601 -0.14361501, + -0.0081421202 0.060706299 -0.14356001, + -0.0053918599 0.060316201 -0.152688, + -0.00267513 0.0600795 -0.161844, + -0.00308863 0.059919201 -0.171, + 0 0.060140099 -0.161842, + -9.4966999e-005 0.059999902 -0.171, + -0.00267513 0.060500398 -0.15267301, + -0.0053918599 0.061019398 -0.14352199, + -0.0081421202 0.061692599 -0.134417, + -0.0109179 0.062514096 -0.12538899, + -0.0137106 0.063476399 -0.116468, + -0.0165099 0.0645741 -0.107686, + -0.019305199 0.065802298 -0.099076003, + -0.0220857 0.0671556 -0.090671003, + -0.0248404 0.068626396 -0.082505003, + -0.027557701 0.070209101 -0.074611001, + -0.0302257 0.071897499 -0.067023002, + -0.0328326 0.073683098 -0.059774, + -0.035366699 0.073603503 -0.056770001, + -0.0378174 0.073263399 -0.053865001, + -0.040174201 0.072673202 -0.051077001, + -0.0424264 0.071846098 -0.048425, + -0.044564299 0.070796601 -0.045926999, + -0.0465803 0.069542103 -0.043598998, + -0.048467699 0.068103701 -0.041455001, + -0.050219599 0.0665107 -0.039496001, + -0.051830001 0.064777203 -0.037716001, + -0.0532961 0.062919497 -0.036114998, + -0.0546159 0.060960401 -0.034692999, + -0.055787299 0.058921698 -0.033445001, + -0.056809202 0.056825001 -0.032365002, + -0.0576833 0.054689702 -0.031445, + -0.058412101 0.052535899 -0.030680999, + -0.058998398 0.050387301 -0.030073, + -0.059445001 0.048252299 -0.029691, + -0.059757002 0.0460504 -0.029426999, + -0.0599402 0.043772198 -0.029231001, + -0.059999999 0.041424301 -0.029154001, + -0.0599402 0.039012399 -0.029231999, + -0.059757002 0.036554199 -0.029505, + -0.059445001 0.034076501 -0.030003, + -0.058998398 0.031626001 -0.030723, + -0.058412101 0.0292504 -0.031649001, + -0.0576833 0.0269947 -0.032754, + -0.056809202 0.0248977 -0.034008, + -0.055787299 0.0229913 -0.035372, + -0.0546159 0.0207447 -0.035207, + -0.0532961 0.0193964 -0.036734, + -0.051830001 0.018220101 -0.038198002, + -0.050219599 0.017221 -0.039505001, + -0.048467699 0.0164428 -0.040635999, + -0.0465803 0.0158548 -0.041586, + -0.044564299 0.0154483 -0.042344, + -0.043510102 0.0153445 -0.043086, + -0.0424264 0.0150333 -0.043338999, + -0.0424264 0.0152177 -0.043806002, + -0.041313998 0.0149989 -0.044438001, + -0.043510102 0.0152635 -0.042672999, + -0.044564299 0.0154034 -0.041919999, + -0.045588002 0.0154636 -0.040727999, + -0.044564299 0.0153105 -0.041512001, + -0.040174201 0.0146599 -0.045022, + -0.040174201 0.0149654 -0.045506999, + -0.041313998 0.0151731 -0.044909999, + -0.0424264 0.0152871 -0.044222999, + -0.040174201 0.0151296 -0.045983002, + -0.0390082 0.0149329 -0.046544999, + -0.0378174 0.0146124 -0.047058001, + -0.0378174 0.0149013 -0.047552001, + -0.0390082 0.0150874 -0.047026001, + -0.040174201 0.0151766 -0.046409, + -0.036603201 0.0148707 -0.048525002, + -0.035366699 0.0145678 -0.048962999, + -0.034109399 0.0145467 -0.049865, + -0.035366699 0.0148412 -0.049465999, + -0.036603201 0.0150069 -0.049013998, + -0.035366699 0.0149749 -0.0504, + -0.0328326 0.0148844 -0.052191, + -0.034109399 0.0149318 -0.050868001, + -0.035366699 0.0149286 -0.050859999, + -0.0378174 0.0149166 -0.050731, + -0.040174201 0.0150468 -0.050390001, + -0.0424264 0.0153325 -0.04984, + -0.044564299 0.015804499 -0.049079999, + -0.0465803 0.016444299 -0.048122998, + -0.048467699 0.017249299 -0.047033001, + -0.050219599 0.0182829 -0.04586, + -0.051830001 0.019545 -0.044645, + -0.0532961 0.021025101 -0.043428, + -0.0546159 0.022707701 -0.04225, + -0.055787299 0.0245694 -0.041152, + -0.056809202 0.0265799 -0.040166002, + -0.0576833 0.0287023 -0.039322998, + -0.058412101 0.0308969 -0.038640998, + -0.058998398 0.033120099 -0.038132999, + -0.059445001 0.035329599 -0.037804998, + -0.059757002 0.037482802 -0.037654001, + -0.0599402 0.0395489 -0.037675001, + -0.059999999 0.0415163 -0.037817001, + -0.0599402 0.0434107 -0.038093999, + -0.059757002 0.045327399 -0.038573001, + -0.059445001 0.047280401 -0.039170999, + -0.058998398 0.049252398 -0.039884999, + -0.058412101 0.0512245 -0.040725999, + -0.0576833 0.0531785 -0.041703001, + -0.056809202 0.055095799 -0.042826999, + -0.055787299 0.0569565 -0.044103, + -0.0546159 0.058739699 -0.045536, + -0.0532961 0.0604311 -0.047127999, + -0.051830001 0.062018599 -0.048893999, + -0.050219599 0.063469902 -0.050841998, + -0.048467699 0.064762197 -0.052960001, + -0.0465803 0.065876298 -0.055234998, + -0.044564299 0.066793904 -0.057650998, + -0.0424264 0.067496598 -0.060196001, + -0.040174201 0.067969501 -0.062852003, + -0.0378174 0.066605501 -0.069642998, + -0.035366699 0.065349601 -0.076807998, + -0.0328326 0.064207204 -0.084314004, + -0.0302257 0.063180998 -0.092130996, + -0.027557701 0.062276199 -0.100224, + -0.0248404 0.0614972 -0.108561, + -0.0220857 0.060844801 -0.117108, + -0.019305199 0.060320102 -0.125834, + -0.0165099 0.0599273 -0.134703, + -0.0137106 0.059671201 -0.143686, + -0.0109179 0.0595554 -0.15275, + -0.0092321504 0.0592779 -0.171, + -0.0165099 0.058940999 -0.143775, + -0.019305199 0.0590517 -0.134846, + -0.0220857 0.059296198 -0.126041, + -0.0248404 0.0596705 -0.117395, + -0.027557701 0.0601735 -0.108938, + -0.0302257 0.0608049 -0.100703, + -0.0328326 0.0615637 -0.092725001, + -0.035366699 0.062446199 -0.085035004, + -0.0378174 0.063450202 -0.077666, + -0.040174201 0.064573303 -0.070648998, + -0.0424264 0.0658096 -0.064015001, + -0.044564299 0.065219902 -0.061473001, + -0.0465803 0.064413801 -0.059044, + -0.048467699 0.063407399 -0.056745, + -0.050219599 0.062219299 -0.054588001, + -0.051830001 0.0608683 -0.052586999, + -0.0532961 0.059374601 -0.050755002, + -0.0546159 0.0577613 -0.049100999, + -0.055787299 0.056061201 -0.047617, + -0.056809202 0.054285102 -0.046284001, + -0.0576833 0.052445699 -0.0451, + -0.058412101 0.050563499 -0.044059001, + -0.058998398 0.0486577 -0.043152999, + -0.059445001 0.046746898 -0.042373002, + -0.059757002 0.044849198 -0.041706, + -0.0599402 0.042978201 -0.041145001, + -0.059999999 0.041131798 -0.040713999, + -0.0599402 0.039292499 -0.0405, + -0.059757002 0.037370499 -0.040438, + -0.059445001 0.035347302 -0.040514, + -0.058998398 0.0332525 -0.040752999, + -0.058412101 0.0311205 -0.041154001, + -0.0576833 0.028991699 -0.041717, + -0.056809202 0.0269069 -0.042436, + -0.055787299 0.024907099 -0.043297, + -0.0546159 0.023029801 -0.044277001, + -0.0532961 0.021309299 -0.045348, + -0.051830001 0.0197731 -0.046473, + -0.050219599 0.018441301 -0.047614999, + -0.048467699 0.017326299 -0.048732001, + -0.0465803 0.0164355 -0.049786001, + -0.044564299 0.015766099 -0.050739001, + -0.0424264 0.0152576 -0.051543999, + -0.040174201 0.0149116 -0.052143, + -0.0378174 0.0147408 -0.052528001, + -0.035366699 0.0147146 -0.052701, + -0.0328326 0.0148188 -0.052657999, + -0.0302257 0.0148011 -0.053837001, + -0.031537499 0.0148623 -0.052581001, + -0.027557701 0.0147253 -0.055335999, + -0.0288986 0.0147987 -0.054148, + -0.0302257 0.0147179 -0.054311998, + -0.0328326 0.014527 -0.054529, + -0.035366699 0.0144543 -0.054529, + -0.0378174 0.0145148 -0.054313999, + -0.040174201 0.0147385 -0.053883001, + -0.0424264 0.0151179 -0.053238999, + -0.044564299 0.015652901 -0.052432999, + -0.0465803 0.0164012 -0.051509, + -0.048467699 0.0173684 -0.050501999, + -0.050219599 0.0185498 -0.049449001, + -0.051830001 0.0199362 -0.048388999, + -0.0532961 0.021511 -0.047361001, + -0.0546159 0.023249701 -0.046397999, + -0.055787299 0.025120899 -0.045533001, + -0.056809202 0.0270894 -0.044789001, + -0.0576833 0.029115999 -0.044181999, + -0.058412101 0.0311621 -0.043719999, + -0.058998398 0.033188701 -0.043405, + -0.059445001 0.0351629 -0.043239001, + -0.059757002 0.037051398 -0.043203, + -0.0599402 0.0388528 -0.043334, + -0.059999999 0.040647101 -0.043697, + -0.0599402 0.042450201 -0.044206999, + -0.059757002 0.044268101 -0.044835001, + -0.059445001 0.046107199 -0.045566, + -0.058998398 0.0479546 -0.046409, + -0.058412101 0.049791701 -0.047377001, + -0.0576833 0.051599398 -0.048478, + -0.056809202 0.053357601 -0.049718998, + -0.055787299 0.055054698 -0.051102001, + -0.0546159 0.0566817 -0.052650999, + -0.0532961 0.058205601 -0.054373998, + -0.051830001 0.059603401 -0.056263, + -0.050219599 0.060854401 -0.058307, + -0.048467699 0.0619388 -0.060493, + -0.0465803 0.062837496 -0.062808998, + -0.044564299 0.063534103 -0.065240003, + -0.0424264 0.0624182 -0.071717001, + -0.040174201 0.061421402 -0.078584, + -0.0378174 0.0605492 -0.085812002, + -0.035366699 0.059804499 -0.093370996, + -0.0328326 0.059188899 -0.10123, + -0.0302257 0.058703199 -0.109356, + -0.027557701 0.058347698 -0.117717, + -0.0248404 0.058122501 -0.12627999, + -0.0220857 0.058028098 -0.135012, + -0.019305199 0.0580655 -0.14388201, + -0.0165099 0.058237899 -0.152858, + -0.0165099 0.057818498 -0.161937, + -0.015277 0.0580099 -0.171, + -0.019305199 0.057362501 -0.15293001, + -0.0220857 0.0570421 -0.144007, + -0.0248404 0.0568549 -0.135203, + -0.027557701 0.056800298 -0.12654801, + -0.0302257 0.056878202 -0.118075, + -0.0328326 0.057088301 -0.109816, + -0.035366699 0.057431001 -0.101803, + -0.0378174 0.057909202 -0.094067998, + -0.040174201 0.058522899 -0.086641997, + -0.0424264 0.059269998 -0.079557002, + -0.044564299 0.0601479 -0.072841004, + -0.0465803 0.061153099 -0.066523001, + -0.048467699 0.060360201 -0.064199001, + -0.050219599 0.0593796 -0.061990999, + -0.051830001 0.058228102 -0.059912998, + -0.0532961 0.056926101 -0.057976998, + -0.0546159 0.055493802 -0.056193002, + -0.055787299 0.053951699 -0.054572001, + -0.056809202 0.052322801 -0.053121999, + -0.0576833 0.0506396 -0.051831, + -0.058412101 0.048909798 -0.050673999, + -0.058998398 0.047143999 -0.049648002, + -0.059445001 0.045362301 -0.048744999, + -0.059757002 0.0435839 -0.047952998, + -0.0599402 0.041822098 -0.047263999, + -0.059999999 0.040069599 -0.046689, + -0.0599402 0.038316101 -0.046248998, + -0.059757002 0.036556199 -0.045975, + -0.059445001 0.034780301 -0.045942999, + -0.058998398 0.032931399 -0.046069, + -0.058412101 0.0310163 -0.046314999, + -0.0576833 0.0290667 -0.046693999, + -0.056809202 0.027114499 -0.047205001, + -0.055787299 0.0251971 -0.047844999, + -0.0546159 0.0233515 -0.048602, + -0.0532961 0.021614799 -0.049458001, + -0.051830001 0.020019701 -0.050388001, + -0.050219599 0.0185946 -0.051360998, + -0.048467699 0.0173606 -0.052342001, + -0.0465803 0.016330799 -0.053293999, + -0.044564299 0.0155116 -0.05418, + -0.0424264 0.014905 -0.054963998, + -0.040174201 0.0145026 -0.055613, + -0.0378174 0.014249 -0.056088001, + -0.035366699 0.0141433 -0.056348, + -0.0328326 0.0141884 -0.056387, + -0.0302257 0.0143546 -0.05621, + -0.027557701 0.014626 -0.055817001, + -0.0248404 0.014657 -0.056685999, + -0.0262044 0.0147411 -0.055567, + -0.0248404 0.0144223 -0.055172, + -0.023467001 0.014408 -0.055782001, + -0.0248404 0.0146451 -0.055700999, + -0.0262044 0.0146656 -0.055050001, + -0.027557701 0.0147692 -0.054876, + -0.027557701 0.0146873 -0.054361999, + -0.0262044 0.0144375 -0.054524001, + -0.027557701 0.0144536 -0.053839002, + -0.0288986 0.0147101 -0.053637002, + -0.0302257 0.0148298 -0.053383, + -0.0302257 0.0147341 -0.052875001, + -0.0288986 0.0144705 -0.053117, + -0.0302257 0.0144883 -0.052359, + -0.031537499 0.0147592 -0.052076999, + -0.0328326 0.0148963 -0.051743001, + -0.0328326 0.0147854 -0.051242001, + -0.031537499 0.0145069 -0.051564001, + -0.0328326 0.0145264 -0.050732002, + -0.034109399 0.0148128 -0.050370999, + -0.035366699 0.0149686 -0.049958002, + -0.028196299 0.0125 -0.052455999, + -0.0275509 0.0125 -0.052783001, + -0.0353604 0.0125 -0.047959, + -0.038435601 0.0074999998 -0.045573, + -0.0381575 0.0125 -0.045802999, + -0.037812401 0.0125 -0.046073999, + -0.040170401 0.0125 -0.044059999, + -0.0429691 0.0074999998 -0.041377001, + -0.050626501 0.0074999998 0.032701999, + -0.051817998 0.0125 0.030719001, + -0.053669199 0.0074999998 0.027326001, + -0.048459399 0.0125 0.035861, + -0.0502089 0.0125 0.033326, + -0.0532832 0.0125 0.028051, + -0.0445357 0.0125 -0.039707001, + -0.0429601 0.0125 -0.041368, + -0.0425102 0.0125 -0.041841999, + -0.0424245 0.0125 -0.041924, + -0.051830001 0.0157199 -0.031381, + -0.051830001 0.015916999 -0.031748999, + -0.050219599 0.0156127 -0.034035999, + -0.050219599 0.015782399 -0.034414001, + -0.051830001 0.0160715 -0.032129999, + -0.0532961 0.016953001 -0.030878, + -0.0546159 0.0180404 -0.029472999, + -0.055787299 0.019336499 -0.027928, + -0.056809202 0.020871701 -0.026252, + -0.0576833 0.0225746 -0.02447, + -0.058412101 0.0244404 -0.022704, + -0.058998398 0.026555801 -0.021028001, + -0.059445001 0.0288944 -0.019487999, + -0.059757002 0.031424001 -0.018133, + -0.0599402 0.034107398 -0.016999001, + -0.059999999 0.036913101 -0.016093001, + -0.0599402 0.039811399 -0.015406, + -0.059757002 0.0427729 -0.014922, + -0.059445001 0.045768201 -0.014625, + -0.058998398 0.048753701 -0.014515, + -0.058412101 0.051685799 -0.014588, + -0.0576833 0.054522701 -0.014833, + -0.056809202 0.057233199 -0.01524, + -0.055787299 0.0597861 -0.015776999, + -0.0546159 0.062189601 -0.016503001, + -0.0532961 0.064542502 -0.017535999, + -0.051830001 0.0668348 -0.018781999, + -0.050219599 0.069037601 -0.020236, + -0.048467699 0.071127497 -0.021899, + -0.0465803 0.073082402 -0.023771999, + -0.044564299 0.074880302 -0.025854001, + -0.0424264 0.076499097 -0.028143, + -0.040174201 0.077917702 -0.030631, + -0.0378174 0.079121202 -0.033309001, + -0.035366699 0.080096401 -0.036169998, + -0.0328326 0.080821298 -0.039200999, + -0.0302257 0.081281699 -0.042383999, + -0.027557701 0.081469499 -0.045696001, + -0.0248404 0.081378303 -0.049114998, + -0.0220857 0.081002504 -0.052618999, + -0.019305199 0.0803404 -0.056189001, + -0.0165099 0.077798396 -0.064102001, + -0.0137106 0.075359002 -0.072283998, + -0.0109179 0.0730334 -0.080701999, + -0.0081421202 0.070831098 -0.089322999, + -0.0053918599 0.068763003 -0.098113999, + -0.00267513 0.066839904 -0.107044, + 0 0.0650701 -0.116082, + 0.00267513 0.0668412 -0.107045, + 0.0053918599 0.068766102 -0.098116003, + 0.0081421202 0.070835799 -0.089326002, + 0.0109179 0.0730391 -0.080706, + 0.0137106 0.075364299 -0.072287999, + 0.0165099 0.077801399 -0.064103998, + 0.019305199 0.080339402 -0.056189001, + 0.0220857 0.081001803 -0.052618999, + 0.0248404 0.0813765 -0.049114998, + 0.027557701 0.081466101 -0.045697, + 0.0302257 0.0812767 -0.042385001, + 0.0328326 0.0808153 -0.039202001, + 0.035366699 0.080091298 -0.036169, + 0.0378174 0.079118602 -0.033307001, + 0.040174201 0.077914603 -0.03063, + 0.0424264 0.076493897 -0.028142, + 0.044564299 0.0748723 -0.025853001, + 0.0465803 0.073071197 -0.023771999, + 0.048467699 0.071113199 -0.021901, + 0.050219599 0.069021098 -0.020243, + 0.051830001 0.0668175 -0.018797001, + 0.0532961 0.064526796 -0.017561, + 0.0546159 0.062178198 -0.016520999, + 0.055787299 0.059776802 -0.015776001, + 0.056809202 0.057218399 -0.015243, + 0.0576833 0.054501001 -0.014841, + 0.058412101 0.051658701 -0.014601, + 0.058998398 0.0487254 -0.014534, + 0.059445001 0.0457418 -0.014649, + 0.059757002 0.042750102 -0.014949, + 0.0599402 0.0397931 -0.015435, + 0.059999999 0.0368995 -0.016124001, + 0.0599402 0.034098201 -0.017030001, + 0.059757002 0.031418901 -0.018164, + 0.059445001 0.028895 -0.019517001, + 0.058998398 0.0265623 -0.021055, + 0.058412101 0.024436001 -0.022723, + 0.0576833 0.022552099 -0.024475001, + 0.056809202 0.0208715 -0.026250999, + 0.055787299 0.0193367 -0.027928, + 0.0546159 0.0180372 -0.029472001, + 0.0532961 0.0169503 -0.030878, + 0.051830001 0.016067101 -0.032134, + 0.051042698 0.0156486 -0.03272, + 0.050219599 0.0153192 -0.033629, + 0.048467699 0.0152395 -0.036198001, + 0.049361002 0.0155434 -0.035339002, + 0.0465803 0.0148077 -0.038240001, + 0.044564299 0.0142828 -0.040215001, + 0.0424264 0.0136899 -0.042160999, + 0.037815802 0.0125 -0.046078, + 0.0360066 0.0125 -0.047481999, + 0.0378174 0.0130634 -0.046128001, + 0.036012899 0.0074999998 -0.047490001, + 0.037937399 0.0125 -0.045984, + 0.040174201 0.0136667 -0.044303, + 0.0424264 0.0142453 -0.042479001, + 0.044564299 0.0147526 -0.040617999, + 0.0465803 0.0151624 -0.038681999, + 0.047540501 0.0154413 -0.037879001, + 0.049361002 0.015823999 -0.036121, + 0.048467699 0.015745301 -0.037411999, + 0.050219599 0.016385799 -0.036382999, + 0.048467699 0.0156439 -0.037004001, + 0.047540501 0.0155802 -0.038268998, + 0.0465803 0.0153917 -0.039115001, + 0.051830001 0.0172201 -0.035183001, + 0.0532961 0.0182596 -0.033822, + 0.0546159 0.0195275 -0.032306001, + 0.055787299 0.0209489 -0.030664001, + 0.056809202 0.0225784 -0.029007001, + 0.0576833 0.024451001 -0.027389999, + 0.058412101 0.0265377 -0.025859, + 0.058998398 0.0288285 -0.024464, + 0.059445001 0.031291399 -0.023247, + 0.059757002 0.033883099 -0.022247, + 0.0599402 0.036558699 -0.021488, + 0.059999999 0.0392836 -0.020961, + 0.0599402 0.042029899 -0.020643, + 0.059757002 0.044772699 -0.020505, + 0.059445001 0.0474912 -0.020517001, + 0.058998398 0.050151002 -0.020667, + 0.058412101 0.0527196 -0.020949, + 0.0576833 0.055164199 -0.02134, + 0.056809202 0.057485599 -0.021916, + 0.055787299 0.059781399 -0.022756999, + 0.0546159 0.0620481 -0.023770001, + 0.0532961 0.064257897 -0.024972999, + 0.051830001 0.066387497 -0.02637, + 0.050219599 0.068414003 -0.027967, + 0.048467699 0.070314102 -0.029763, + 0.0465803 0.072065398 -0.031757999, + 0.044564299 0.073645703 -0.033946998, + 0.0424264 0.075037003 -0.036325, + 0.040174201 0.076222397 -0.038892001, + 0.0378174 0.077182703 -0.041639, + 0.035366699 0.077902198 -0.044544999, + 0.0328326 0.078366302 -0.047593001, + 0.0302257 0.078562804 -0.050760999, + 0.027557701 0.078483403 -0.054032002, + 0.0248404 0.078123301 -0.057383001, + 0.0220857 0.075890899 -0.065050997, + 0.019305199 0.073752597 -0.073018, + 0.0165099 0.071719103 -0.081248999, + 0.0137106 0.0698006 -0.089708999, + 0.0109179 0.068006597 -0.098366, + 0.0081421202 0.066346101 -0.107187, + 0.0053918599 0.064827703 -0.116142, + 0.00267513 0.063459702 -0.12519901, + 0 0.062249899 -0.13432699, + -0.00267513 0.0634588 -0.12519801, + -0.0053918599 0.064825602 -0.11614, + -0.0081421202 0.066342101 -0.107184, + -0.0109179 0.068000503 -0.098361, + -0.0137106 0.069792703 -0.089703001, + -0.0165099 0.071710601 -0.081243001, + -0.019305199 0.073745199 -0.073013, + -0.0220857 0.075886898 -0.065048002, + -0.0248404 0.078124501 -0.057381999, + -0.027557701 0.078484297 -0.054032002, + -0.0302257 0.078565001 -0.050760999, + -0.0328326 0.0783704 -0.047591999, + -0.035366699 0.077908002 -0.044544, + -0.0378174 0.077189498 -0.041638002, + -0.040174201 0.076228201 -0.038892001, + -0.0424264 0.075039998 -0.036327001, + -0.044564299 0.073649101 -0.033948999, + -0.0465803 0.072071098 -0.031759001, + -0.048467699 0.070322797 -0.029764, + -0.050219599 0.068425998 -0.027967, + -0.051830001 0.066402704 -0.026368, + -0.0532961 0.064275503 -0.024964999, + -0.0546159 0.062066302 -0.023754001, + -0.055787299 0.059797902 -0.02273, + -0.056809202 0.057497401 -0.021898, + -0.0576833 0.055173799 -0.021342, + -0.058412101 0.0527348 -0.020947, + -0.058998398 0.050173301 -0.020657999, + -0.059445001 0.047518801 -0.020502999, + -0.059757002 0.044801399 -0.020486001, + -0.0599402 0.042056501 -0.020618999, + -0.059999999 0.039306398 -0.020934001, + -0.0599402 0.036577001 -0.021458, + -0.059757002 0.033896599 -0.022217, + -0.059445001 0.0313005 -0.023217, + -0.058998398 0.028833499 -0.024434, + -0.058412101 0.0265371 -0.025831001, + -0.0576833 0.024444699 -0.027364001, + -0.056809202 0.0225827 -0.028989, + -0.055787299 0.0209706 -0.03066, + -0.0546159 0.0201781 -0.033716999, + -0.0546159 0.0195277 -0.032306999, + -0.0532961 0.018867901 -0.035278998, + -0.0532961 0.018259401 -0.033822998, + -0.051830001 0.0177342 -0.036697, + -0.051830001 0.017223099 -0.035184, + -0.050219599 0.016827401 -0.037948001, + -0.050219599 0.0163884 -0.036382999, + -0.050219599 0.0159082 -0.034807, + -0.049361002 0.015716501 -0.035719, + -0.051830001 0.0166674 -0.033663001, + -0.0532961 0.017627999 -0.032354001, + -0.0546159 0.0187943 -0.030896001, + -0.055787299 0.0201966 -0.029293001, + -0.056809202 0.0217705 -0.027573001, + -0.0576833 0.023510899 -0.025849, + -0.058412101 0.025501501 -0.024192, + -0.058998398 0.0277195 -0.022648999, + -0.059445001 0.0301357 -0.021267001, + -0.059757002 0.032713301 -0.020087, + -0.0599402 0.035410699 -0.019143, + -0.059999999 0.038194198 -0.018432001, + -0.0599402 0.041032899 -0.01794, + -0.059757002 0.043900002 -0.017642001, + -0.059445001 0.046767 -0.017516, + -0.058998398 0.049595699 -0.017554, + -0.058412101 0.052345399 -0.017749, + -0.0576833 0.054985698 -0.018091001, + -0.056809202 0.057486098 -0.018552, + -0.055787299 0.059854399 -0.019188, + -0.0546159 0.062186401 -0.020114999, + -0.0532961 0.064472303 -0.021245001, + -0.051830001 0.066684201 -0.022573, + -0.050219599 0.068798497 -0.024102001, + -0.048467699 0.070793197 -0.025834, + -0.0465803 0.072646096 -0.027771, + -0.044564299 0.074335299 -0.02991, + -0.0424264 0.075838998 -0.032246999, + -0.040174201 0.077140398 -0.034773, + -0.0378174 0.078226097 -0.037486002, + -0.035366699 0.079072997 -0.040374, + -0.0328326 0.079665899 -0.043419, + -0.0302257 0.0799926 -0.046599999, + -0.027557701 0.080045499 -0.049895, + -0.0248404 0.079818398 -0.053284001, + -0.0220857 0.079308003 -0.056745, + -0.019305199 0.076917201 -0.064538002, + -0.0165099 0.074625202 -0.072614998, + -0.0137106 0.072443701 -0.080943003, + -0.0109179 0.070381999 -0.089487001, + -0.0081421202 0.068449199 -0.098215997, + -0.0053918599 0.066655599 -0.107096, + -0.00267513 0.065009601 -0.116096, + 0 0.063519098 -0.125186, + 0.00267513 0.065010697 -0.116097, + 0.0053918599 0.066658303 -0.107098, + 0.0081421202 0.068453804 -0.098219, + 0.0109179 0.070388302 -0.089492001, + 0.0137106 0.072450802 -0.080948003, + 0.0165099 0.074631497 -0.072619997, + 0.019305199 0.076920599 -0.064540997, + 0.0220857 0.079306901 -0.056745, + 0.0248404 0.079817601 -0.053284001, + 0.027557701 0.080043502 -0.049895, + 0.0302257 0.079988897 -0.046599999, + 0.0328326 0.079660401 -0.043419998, + 0.035366699 0.079066597 -0.040375002, + 0.0378174 0.078220598 -0.037486002, + 0.040174201 0.077137597 -0.034772001, + 0.0424264 0.075835802 -0.032246001, + 0.044564299 0.074329801 -0.029909, + 0.0465803 0.072637796 -0.02777, + 0.048467699 0.070781603 -0.025834, + 0.050219599 0.068783797 -0.024103999, + 0.051830001 0.066667102 -0.02258, + 0.0532961 0.0644546 -0.021260999, + 0.0546159 0.062170301 -0.020141, + 0.055787299 0.059842799 -0.019206, + 0.056809202 0.057476599 -0.018549999, + 0.0576833 0.0549707 -0.018093999, + 0.058412101 0.052323401 -0.017757, + 0.058998398 0.0495684 -0.017568, + 0.059445001 0.046738502 -0.017535999, + 0.059757002 0.0438735 -0.017666001, + 0.0599402 0.0410101 -0.017967001, + 0.059999999 0.0381759 -0.018461, + 0.0599402 0.035397101 -0.019173, + 0.059757002 0.0327041 -0.020118, + 0.059445001 0.030130601 -0.021297, + 0.058998398 0.027720099 -0.022678001, + 0.058412101 0.025507901 -0.024219001, + 0.0576833 0.0235065 -0.025867, + 0.056809202 0.021748399 -0.027578, + 0.055787299 0.020196401 -0.029293001, + 0.0546159 0.018794499 -0.030895, + 0.0532961 0.0176249 -0.032354001, + 0.049361002 0.0157087 -0.035719, + 0.048467699 0.0154919 -0.036619, + 0.050219599 0.0157745 -0.034412999, + 0.050219599 0.0155956 -0.034038998, + -0.048467699 0.0155084 -0.036616001, + -0.048467699 0.0156516 -0.037005, + -0.044564299 0.0151049 -0.041055001, + 0.00267513 0.060502201 -0.15267301, + 0.0053918599 0.061022501 -0.14352199, + 0.0081421202 0.061696 -0.13441899, + 0.0109179 0.062518001 -0.125392, + 0.0137106 0.063481897 -0.116473, + 0.0165099 0.064582199 -0.107692, + 0.019305199 0.065813199 -0.099083997, + 0.0220857 0.067168303 -0.090680003, + 0.0248404 0.068639196 -0.082514003, + 0.027557701 0.070219703 -0.074619003, + 0.0302257 0.071902998 -0.067028001, + 0.0328326 0.073681399 -0.059774999, + 0.035366699 0.073602401 -0.056770001, + 0.0378174 0.073260702 -0.053865001, + 0.040174201 0.072668299 -0.051077999, + 0.0424264 0.071839102 -0.048425999, + 0.044564299 0.070788503 -0.045928001, + 0.0465803 0.069535397 -0.043598998, + 0.048467699 0.068100303 -0.041453, + 0.050219599 0.0665069 -0.039494999, + 0.051830001 0.064770803 -0.037714999, + 0.0532961 0.062909998 -0.036114, + 0.0546159 0.060947299 -0.034692999, + 0.055787299 0.0589054 -0.033447001, + 0.056809202 0.0568063 -0.032372002, + 0.0576833 0.054670502 -0.031463001, + 0.058412101 0.052518699 -0.030708, + 0.058998398 0.050375 -0.030091999, + 0.059445001 0.048242401 -0.029689999, + 0.059757002 0.046034899 -0.029429, + 0.0599402 0.0437495 -0.029239999, + 0.059999999 0.041396499 -0.029168, + 0.0599402 0.038983699 -0.029251, + 0.059757002 0.036527701 -0.029527999, + 0.059445001 0.034053899 -0.030029999, + 0.058998398 0.031608 -0.030751999, + 0.058412101 0.0292372 -0.031679001, + 0.0576833 0.0269859 -0.032784, + 0.056809202 0.0248928 -0.034037001, + 0.055787299 0.022991801 -0.035399001, + 0.0546159 0.0213059 -0.036828998, + 0.0532961 0.0198384 -0.038277, + 0.0424264 0.0153036 -0.044659998, + 0.041313998 0.0152245 -0.045329999, + 0.040174201 0.0151698 -0.046854999, + 0.0424264 0.0153591 -0.046395998, + 0.044564299 0.0156001 -0.044045001, + 0.044564299 0.0157106 -0.045733001, + 0.0465803 0.0160682 -0.043234002, + 0.0465803 0.0162399 -0.044874001, + 0.048467699 0.016722299 -0.042234, + 0.048467699 0.016971599 -0.043821, + 0.050219599 0.0175869 -0.041049, + 0.050219599 0.017859099 -0.042594001, + 0.051830001 0.0186086 -0.039700001, + 0.051830001 0.0187777 -0.040476002, + 0.0532961 0.0196034 -0.037496001, + 0.043510102 0.0153376 -0.043085001, + 0.0424264 0.0150176 -0.043354001, + 0.043510102 0.0152487 -0.042676002, + 0.044564299 0.0150884 -0.041071001, + 0.0424264 0.0147001 -0.042890999, + 0.041313998 0.0149836 -0.044452999, + 0.0424264 0.0152033 -0.043809, + 0.044564299 0.0153963 -0.041919999, + 0.040174201 0.0142096 -0.044627, + 0.0378174 0.0136449 -0.046324, + 0.035366699 0.0130535 -0.048016999, + 0.035611998 0.0125 -0.047789, + 0.035363302 0.0125 -0.047963001, + 0.033201002 0.0125 -0.049477, + 0.0308876 0.0074999998 -0.050939001, + 0.0254349 0.0074999998 -0.053842001, + 0.028145101 0.0125 -0.052489001, + 0.021159001 0.056127101 -0.171, + 0.022080399 0.055773601 -0.171, + 0.021165101 0.056143001 -0.191, + 0.0201142 0.056527998 -0.171, + 0.019305199 0.056954499 -0.161972, + 0.019300601 0.056795198 -0.171, + 0.017317699 0.057446498 -0.171, + -0.0053966301 -0.059746899 -0.171, + -0.0058778701 -0.0597114 -0.171, + -0.00616926 -0.059682 -0.191, + -0.0053973799 -0.059725899 -0.168887, + -0.00294237 -0.059927799 -0.171, + 0 -0.059999999 -0.191, + 0.0026879699 -0.059931099 -0.171, + 0.0031320599 -0.059918199 -0.171, + 0.00268824 -0.0599076 -0.16889, + 0.000344617 -0.059999 -0.171, + 0 -0.059967902 -0.168891, + 0 -0.059870999 -0.166768, + -0.00268824 -0.059908599 -0.16889, + -0.0026880901 -0.059934001 -0.171, + 0 -0.059999999 -0.171, + -0.00268824 -0.059811998 -0.166766, + 0 -0.059708498 -0.164634, + 0.00268824 -0.059810501 -0.166766, + 0.0053973799 -0.059723999 -0.16888601, + 0.0053963801 -0.059744101 -0.171, + 0.0060668602 -0.059692498 -0.171, + 0.00616926 -0.059682 -0.191, + -0.0109154 -0.058984298 -0.171, + -0.0122731 -0.058731299 -0.191, + -0.0087992204 -0.059351299 -0.171, + -0.0116994 -0.058848299 -0.171, + -0.0109179 -0.058968201 -0.168871, + -0.0081428103 -0.059414301 -0.16888, + -0.0081428103 -0.0593183 -0.16674601, + -0.0053973799 -0.0596296 -0.166759, + -0.0053973799 -0.059467301 -0.16462, + -0.00268824 -0.059649602 -0.16463099, + -0.00268824 -0.0594205 -0.162487, + 0 -0.059479401 -0.16249201, + 0 -0.059182901 -0.160344, + 0.00268824 -0.059418701 -0.162487, + 0.00268824 -0.059647799 -0.16463, + 0.0053973799 -0.059463698 -0.164619, + 0.0053973799 -0.059626501 -0.166758, + 0.0081428103 -0.059313599 -0.16674501, + 0.0081428103 -0.059411399 -0.16888, + 0.0109179 -0.058964301 -0.168871, + 0.0089870598 -0.059323099 -0.171, + 0.010915 -0.058982499 -0.171, + 0.0122731 -0.058731299 -0.191, + 0.0118856 -0.058811001 -0.171, + -0.051818501 -0.0302191 -0.171, + -0.051830001 -0.0301087 -0.165548, + -0.0528998 -0.0283127 -0.171, + -0.0514476 -0.030873001 -0.171, + -0.050219599 -0.032715399 -0.165655, + -0.049871601 -0.033358999 -0.171, + -0.048467699 -0.0353426 -0.168386, + -0.048459999 -0.035361301 -0.171, + -0.0479904 -0.036012899 -0.191, + -0.048175599 -0.035764702 -0.171, + -0.059999999 -4.7590001e-005 -0.171, + -0.0599989 -2.7e-008 -0.171, + -0.059980098 -0.00154487 -0.191, + -0.050219599 -0.0020664099 -0.094806999, + -0.050219599 -0.00047607001 -0.092881002, + -0.051830001 -0.00106013 -0.095097996, + -0.048467699 -0.0029877101 -0.094648004, + -0.048467699 -0.00139537 -0.092836, + -0.0465803 -0.00380336 -0.094616003, + -0.0465803 -0.0021862099 -0.092883997, + -0.044564299 -0.0044778599 -0.094664998, + -0.044564299 -0.0028637799 -0.092954002, + -0.0424264 -0.00502788 -0.094720997, + -0.0424264 -0.00343258 -0.093033001, + -0.040174201 -0.00545967 -0.094770998, + -0.040174201 -0.00387826 -0.093101002, + -0.0378174 -0.0057619102 -0.094797, + -0.0378174 -0.0041926899 -0.093139999, + -0.035366699 -0.0059277699 -0.094780996, + -0.035366699 -0.0043703499 -0.093134001, + -0.0328326 -0.0059525501 -0.094705001, + -0.0328326 -0.00440718 -0.093062997, + -0.0302257 -0.0058337101 -0.094549999, + -0.0302257 -0.00430104 -0.092909999, + -0.027557701 -0.00557272 -0.094302997, + -0.027557701 -0.0040531098 -0.092666, + -0.0248404 -0.0051722201 -0.093952999, + -0.0248404 -0.00366685 -0.092318997, + -0.0220857 -0.0046361401 -0.093488, + -0.0220857 -0.0031524601 -0.091839001, + -0.019305199 -0.0039745001 -0.092882, + -0.019305199 -0.00251473 -0.091215, + -0.0165099 -0.0031951601 -0.092125997, + -0.0165099 -0.00175948 -0.090442002, + -0.0137106 -0.0023056599 -0.091216996, + -0.0137106 -0.00089510198 -0.089511998, + -0.0109179 -0.00131548 -0.090145998, + -0.0109179 6.8232999e-005 -0.088417001, + 0.0109179 -0.0057387301 -0.095114999, + 0.0137106 -0.00526773 -0.094517, + 0.0109179 -0.0042232699 -0.093497999, + 0.059744701 0.0053964402 -0.171, + 0.0596973 0.0060197199 -0.171, + 0.059757002 0.0055494001 -0.16408101, + 0.048467699 -0.0127898 -0.106344, + 0.0465803 -0.0152657 -0.107678, + 0.048467699 -0.0144104 -0.108428, + 0.050219599 -0.0118532 -0.107106, + 0.050219599 -0.0134293 -0.109299, + 0.051830001 -0.0108016 -0.107997, + 0.051830001 -0.0123307 -0.110297, + 0.0532961 -0.00964393 -0.109024, + 0.0532961 -0.0111235 -0.111428, + 0.0546159 -0.0083893603 -0.110191, + 0.0546159 -0.0098168803 -0.112699, + 0.055787299 -0.0070470702 -0.111505, + 0.055787299 -0.0084201004 -0.114113, + 0.056809202 -0.0056261099 -0.112968, + 0.056809202 -0.0069423201 -0.115674, + 0.0576833 -0.00539209 -0.117384, + 0.0576833 -0.0028172601 -0.111817, + 0.058412101 -0.00258193 -0.11635, + 0.058412101 -0.0049097301 -0.122168, + 0.058998398 -0.00210838 -0.121254, + 0.058998398 -0.0041756099 -0.12730099, + 0.059445001 -0.00139369 -0.126508, + 0.059445001 -0.00319232 -0.13276, + 0.059757002 -0.000441518 -0.132089, + 0.059757002 -0.00196498 -0.138522, + 0.0599402 0.000748233 -0.13797, + 0.0599402 -0.00049375801 -0.14455999, + 0.059999999 0.0021974 -0.14412101, + 0.059999999 0.00124025 -0.150846, + 0.0599402 0.0039303098 -0.150517, + 0.0599402 0.0032507901 -0.157359, + 0.059757002 0.0059607802 -0.15713701, + 0.059445001 0.0082949996 -0.163968, + 0.059011199 0.0107539 -0.171, + 0.058998398 0.0110702 -0.163854, + 0.059330199 0.0089402199 -0.171, + 0.059430599 0.0081410101 -0.171, + 0.059821099 0.0046305298 -0.191, + 0.056809202 -0.0125839 -0.129697, + 0.055787299 -0.0153714 -0.130491, + 0.056809202 -0.0143768 -0.13549, + 0.0576833 -0.0115759 -0.13480701, + 0.0576833 -0.0130945 -0.14078601, + 0.058412101 -0.0102908 -0.14021599, + 0.058412101 -0.0115283 -0.146357, + 0.058998398 -0.0087324604 -0.14590199, + 0.058998398 -0.0096853599 -0.15218399, + 0.059445001 -0.0069082901 -0.15184399, + 0.059445001 -0.0075840899 -0.158246, + 0.059757002 -0.0048376201 -0.158021, + 0.059757002 -0.0052463501 -0.164524, + 0.0599402 -0.0025369099 -0.16441301, + 0.059934601 -0.0028003999 -0.171, + 0.059749398 -0.0053968299 -0.171, + 0.059980098 -0.00154487 -0.191, + 0.059920698 0.0030847499 -0.171, + 0.059931301 0.002688 -0.171, + 0.059999801 0.000142344 -0.171, + 0.059999999 0.00015159399 -0.164303, + 0.059996702 7.3000002e-008 -0.171, + 0.059962399 -0.00154448 -0.171, + 0.059937101 -0.0026881699 -0.171, + 0.0599402 -0.0021275 -0.15779901, + 0.059757002 -0.0041608899 -0.15150701, + 0.059445001 -0.0059543299 -0.145449, + 0.058998398 -0.00749382 -0.13964701, + 0.058412101 -0.00877102 -0.134122, + 0.0576833 -0.0097816298 -0.12889799, + 0.056809202 -0.0105218 -0.123998, + 0.055787299 -0.013311 -0.124908, + -0.0081428103 -0.00609536 -0.095570996, + -0.0109179 -0.0072933799 -0.096693002, + -0.0081428103 -0.0092677996 -0.098663002, + 0.0109179 -0.0088911699 -0.098229997, + 0.0109179 -0.0121885 -0.101175, + 0.0137106 -0.0100151 -0.099169999, + 0.0081428103 -0.0092694797 -0.098664999, + 0.0081428103 -0.0060974802 -0.095570996, + 0.0053973799 -0.00634806 -0.095889002, + 0.0053973799 -0.00331669 -0.092648, + 0.00268824 -0.0034531499 -0.092841998, + 0.00268824 -0.00057569699 -0.089455001, + 0 -0.00061579898 -0.08952, + 0 0.00208969 -0.085993998, + -0.00268824 -0.00057450403 -0.089454003, + -0.00268824 -0.0034519001 -0.092840999, + -0.0053973799 -0.0033141901 -0.092646003, + -0.0053973799 -0.0063466602 -0.095889002, + -0.0109179 -0.0121849 -0.101172, + -0.0137106 -0.0133527 -0.102052, + -0.0109179 -0.0156102 -0.103937, + -0.0081428103 -0.0125808 -0.101585, + -0.0053973799 -0.00953265 -0.098967001, + -0.00268824 -0.00649428 -0.096075997, + 0 -0.00349729 -0.092905, + 0.00268824 -0.0064949798 -0.096075997, + 0.0053973799 -0.0095337601 -0.098968998, + 0.0081428103 -0.0125835 -0.101587, + 0.0109179 -0.0156134 -0.103937, + 0.0137106 -0.0133572 -0.102054, + 0.0137106 -0.015075 -0.103428, + 0.0165099 -0.0144055 -0.102794, + 0.0165099 -0.016140601 -0.104141, + 0.019305199 -0.0153244 -0.103405, + 0.019305199 -0.0170743 -0.104729, + 0.0220857 -0.0161057 -0.103898, + 0.0220857 -0.0178691 -0.105203, + 0.0248404 -0.016743699 -0.104284, + 0.0248404 -0.0185229 -0.105577, + 0.027557701 -0.0172398 -0.10458, + 0.027557701 -0.0207623 -0.107155, + 0.0302257 -0.0193095 -0.106132, + 0.0302257 -0.0210339 -0.107528, + 0.0328326 -0.019426901 -0.106449, + 0.0328326 -0.021131299 -0.107943, + 0.035366699 -0.0193734 -0.106818, + 0.035366699 -0.021058699 -0.10841, + 0.0378174 -0.0191574 -0.107246, + 0.0378174 -0.0208252 -0.108934, + 0.040174201 -0.0187892 -0.107743, + 0.040174201 -0.020441899 -0.109525, + 0.0424264 -0.0182808 -0.108312, + 0.0424264 -0.019922201 -0.110186, + 0.044564299 -0.017646801 -0.10896, + 0.044564299 -0.0192615 -0.110935, + 0.0465803 -0.016883399 -0.109706, + 0.0465803 -0.018454 -0.111787, + 0.048467699 -0.015983701 -0.110563, + 0.048467699 -0.017508 -0.112749, + 0.050219599 -0.014956 -0.11154, + 0.050219599 -0.0164313 -0.113829, + 0.051830001 -0.0138081 -0.112643, + 0.051830001 -0.0152318 -0.115033, + 0.0532961 -0.0125491 -0.113877, + 0.0532961 -0.0139188 -0.116367, + 0.0546159 -0.0111882 -0.115248, + 0.0546159 -0.0125015 -0.117835, + 0.055787299 -0.0097348504 -0.11676, + 0.055787299 -0.0109895 -0.119442, + 0.056809202 -0.00819821 -0.118416, + 0.0576833 -0.0077178101 -0.123084, + 0.058412101 -0.0069752601 -0.12809899, + 0.058998398 -0.0059728101 -0.133439, + 0.059445001 -0.0047145602 -0.139081, + 0.059757002 -0.00320586 -0.14500099, + 0.0599402 -0.00144984 -0.15117501, + 0.059999999 0.00056166499 -0.157579, + 0.0599402 0.00284006 -0.16419201, + 0.059803098 0.0046291598 -0.171, + 0.044564299 -0.0160041 -0.107035, + 0.0424264 -0.016630201 -0.106479, + 0.040174201 -0.0171264 -0.106004, + 0.0378174 -0.0174796 -0.105605, + 0.035366699 -0.0176787 -0.105276, + 0.0328326 -0.017713699 -0.105009, + 0.0302257 -0.015814301 -0.103472, + 0.027557701 -0.0154758 -0.103249, + 0.0248404 -0.0149953 -0.102946, + 0.0220857 -0.0143701 -0.102545, + 0.019305199 -0.0136025 -0.102034, + 0.0165099 -0.0126995 -0.1014, + 0.0137106 -0.0116698 -0.100634, + 0.0165099 -0.0110249 -0.099962004, + 0.019305199 -0.0119108 -0.100617, + 0.0220857 -0.0126637 -0.101146, + 0.0248404 -0.0132761 -0.10156, + 0.027557701 -0.0137443 -0.101872, + 0.0302257 -0.0140674 -0.102098, + 0.0328326 -0.0142486 -0.102255, + 0.035366699 -0.015977601 -0.103787, + 0.0378174 -0.015795199 -0.104013, + 0.040174201 -0.0154567 -0.10431, + 0.0424264 -0.0149727 -0.104687, + 0.044564299 -0.0143557 -0.105148, + 0.0465803 -0.0136218 -0.105699, + 0.0465803 -0.0119756 -0.103755, + 0.044564299 -0.0127037 -0.103299, + 0.0424264 -0.0133115 -0.102937, + 0.040174201 -0.0137833 -0.102663, + 0.0378174 -0.0141073 -0.10247, + 0.035366699 -0.0125452 -0.100931, + 0.0328326 -0.0125203 -0.100835, + 0.0302257 -0.0123546 -0.10068, + 0.027557701 -0.0120435 -0.100449, + 0.0248404 -0.0115875 -0.100127, + 0.0220857 -0.0109886 -0.099701002, + 0.019305199 -0.0102513 -0.099155001, + 0.0165099 -0.0093834903 -0.098479003, + 0.0137106 -0.0083945002 -0.097658999, + 0.0137106 -0.00681049 -0.096106999, + 0.0165099 -0.0077768802 -0.096949004, + 0.019305199 -0.0086259302 -0.097649001, + 0.0220857 -0.0093467897 -0.098212004, + 0.0248404 -0.0099313604 -0.098650999, + 0.027557701 -0.0103748 -0.098980002, + 0.0302257 -0.0106743 -0.099215001, + 0.0328326 -0.010828 -0.099370003, + 0.035366699 -0.0108372 -0.099459998, + 0.0378174 -0.0107101 -0.099505, + 0.040174201 -0.0121094 -0.101064, + 0.0424264 -0.0116498 -0.101232, + 0.044564299 -0.0110515 -0.10149, + 0.0465803 -0.0103295 -0.101846, + 0.048467699 -0.0095006404 -0.102306, + 0.050219599 -0.0102295 -0.104965, + 0.051830001 -0.0092226705 -0.105746, + 0.0532961 -0.0081122797 -0.106665, + 0.0546159 -0.0069075502 -0.107727, + 0.055787299 -0.0056175902 -0.108938, + 0.056809202 -0.00425138 -0.1103, + 0.056809202 -0.00281993 -0.107672, + 0.055787299 -0.0041335099 -0.106413, + 0.0546159 -0.0053733299 -0.105309, + 0.0532961 -0.0065304502 -0.104355, + 0.051830001 -0.0075956602 -0.103547, + 0.050219599 -0.0069413702 -0.100808, + 0.048467699 -0.0078606298 -0.100336, + 0.0465803 -0.0086867204 -0.099976003, + 0.044564299 -0.0094022201 -0.099724002, + 0.0424264 -0.0099908505 -0.099573001, + 0.040174201 -0.0087498296 -0.097980998, + 0.0378174 -0.0090239104 -0.097979002, + 0.035366699 -0.0091672502 -0.097944997, + 0.0328326 -0.0091701597 -0.097860001, + 0.0302257 -0.00902774 -0.097705998, + 0.027557701 -0.00874021 -0.097468004, + 0.0248404 -0.0083098803 -0.097130999, + 0.0220857 -0.0077402401 -0.09668, + 0.019305199 -0.0070361602 -0.096097998, + 0.0165099 -0.00620776 -0.095380001, + 0.0081428103 -0.0030837499 -0.092316002, + 0.0053973799 -0.000451667 -0.089253999, + 0.00268824 0.00212526 -0.085927002, + 0 0.0046106302 -0.082340002, + -0.00268824 0.00212608 -0.085925996, + -0.0053973799 -0.00044927199 -0.089252003, + -0.0081428103 -0.0030799799 -0.092313997, + -0.0109179 -0.0042191502 -0.093497001, + -0.0465803 -0.0103239 -0.101845, + -0.0465803 -0.0086789699 -0.099974997, + -0.048467699 -0.0094971601 -0.102306, + -0.044564299 -0.0110441 -0.101489, + -0.044564299 -0.0093941102 -0.099722996, + -0.0424264 -0.0116421 -0.101231, + -0.0424264 -0.0099847 -0.099573001, + -0.040174201 -0.0121036 -0.101064, + -0.040174201 -0.0104327 -0.099517003, + -0.0378174 -0.0124136 -0.100982, + -0.0378174 -0.0107072 -0.099505998, + -0.035366699 -0.0125425 -0.100932, + -0.035366699 -0.0108328 -0.099460997, + -0.0328326 -0.0125162 -0.100835, + -0.0328326 -0.0108221 -0.099371001, + -0.0302257 -0.0123491 -0.10068, + -0.0302257 -0.010667 -0.099215001, + -0.027557701 -0.0120369 -0.100449, + -0.027557701 -0.0103668 -0.098978996, + -0.0248404 -0.0115802 -0.100126, + -0.0248404 -0.0099232001 -0.098646998, + -0.0220857 -0.0109813 -0.099698, + -0.0220857 -0.0093394499 -0.098205, + -0.019305199 -0.0102448 -0.099149004, + -0.019305199 -0.00862025 -0.09764, + -0.0165099 -0.0093786297 -0.098471001, + -0.0165099 -0.0077734599 -0.096943997, + -0.0465803 -0.0136203 -0.105699, + -0.0465803 -0.0119723 -0.103754, + -0.048467699 -0.0127873 -0.106344, + -0.044564299 -0.0143525 -0.105147, + -0.044564299 -0.0126983 -0.103298, + -0.0424264 -0.0149675 -0.104686, + -0.0424264 -0.0133045 -0.102936, + -0.040174201 -0.01545 -0.104309, + -0.040174201 -0.013776 -0.102662, + -0.0378174 -0.0157883 -0.104012, + -0.0378174 -0.0141018 -0.10247, + -0.035366699 -0.015972501 -0.103787, + -0.035366699 -0.0142682 -0.102353, + -0.0328326 -0.0159896 -0.103625, + -0.0328326 -0.014246 -0.102256, + -0.0302257 -0.015812 -0.103473, + -0.0302257 -0.0140637 -0.102099, + -0.027557701 -0.0154725 -0.103249, + -0.027557701 -0.0137394 -0.101873, + -0.0248404 -0.0149908 -0.102946, + -0.0248404 -0.0132702 -0.10156, + -0.0220857 -0.0143648 -0.102546, + -0.0220857 -0.0126572 -0.101145, + -0.019305199 -0.0135969 -0.102033, + -0.019305199 -0.0119044 -0.100614, + -0.0165099 -0.0126941 -0.101398, + -0.0165099 -0.0110194 -0.099956997, + -0.0137106 -0.0116653 -0.10063, + -0.050219599 -0.0102269 -0.104965, + -0.050219599 -0.0118554 -0.107102, + -0.051830001 -0.0092249 -0.105742, + -0.051830001 -0.0108109 -0.107989, + -0.0532961 -0.00812189 -0.106656, + -0.0532961 -0.0096594803 -0.109011, + -0.0546159 -0.0069234902 -0.107714, + -0.0546159 -0.0084103802 -0.110176, + -0.055787299 -0.00707271 -0.111487, + -0.055787299 -0.0056390599 -0.108921, + -0.056809202 -0.0056554498 -0.112948, + -0.055787299 -0.0041497899 -0.1064, + -0.0546159 -0.00538318 -0.1053, + -0.0532961 -0.0065327398 -0.10435, + -0.051830001 -0.0075930599 -0.103546, + -0.050219599 -0.0069377599 -0.100808, + -0.048467699 -0.0062195198 -0.098399997, + -0.0465803 -0.0070418199 -0.098145001, + -0.044564299 -0.0077524399 -0.098002002, + -0.0424264 -0.0083320402 -0.097964004, + -0.040174201 -0.0087467702 -0.097981997, + -0.0378174 -0.0090192696 -0.09798, + -0.035366699 -0.0091609098 -0.097946003, + -0.0328326 -0.00916229 -0.097860001, + -0.0302257 -0.0090188701 -0.097704001, + -0.027557701 -0.0087311501 -0.097464003, + -0.0248404 -0.0083016204 -0.097122997, + -0.0220857 -0.0077337399 -0.096669003, + -0.019305199 -0.0070321602 -0.096092001, + -0.0165099 -0.00620502 -0.095380001, + -0.0137106 -0.0068082102 -0.096107997, + -0.0137106 -0.0052641602 -0.094517, + -0.0109179 -0.00573589 -0.095114999, + -0.0137106 -0.0083916504 -0.097654998, + -0.0109179 -0.0088889003 -0.098227002, + -0.0165099 -0.0144007 -0.102793, + -0.019305199 -0.0153198 -0.103405, + -0.0220857 -0.016101699 -0.103899, + -0.0248404 -0.0167407 -0.104285, + -0.027557701 -0.017237701 -0.10458, + -0.0302257 -0.017572001 -0.104795, + -0.0328326 -0.017709 -0.105009, + -0.035366699 -0.0176722 -0.105275, + -0.0378174 -0.017473301 -0.105604, + -0.040174201 -0.017121499 -0.106003, + -0.0424264 -0.0166272 -0.106479, + -0.044564299 -0.0160027 -0.107035, + -0.0465803 -0.0152634 -0.107677, + -0.048467699 -0.0144125 -0.108424, + -0.050219599 -0.0134384 -0.10929, + -0.051830001 -0.0123458 -0.110284, + -0.0532961 -0.011144 -0.111413, + -0.0546159 -0.0098419897 -0.112681, + -0.055787299 -0.0084488997 -0.114093, + -0.056809202 -0.0082309199 -0.118394, + -0.0576833 -0.0054253102 -0.117362, + -0.0576833 -0.0077503398 -0.123062, + -0.058412101 -0.00494267 -0.122145, + -0.058412101 -0.0070039299 -0.128077, + -0.058998398 -0.0042045699 -0.127279, + -0.058998398 -0.00599661 -0.13341901, + -0.059445001 -0.0032162999 -0.13274001, + -0.059445001 -0.0047358298 -0.139064, + -0.059757002 -0.00198637 -0.138504, + -0.059757002 -0.0032303899 -0.144989, + -0.0599402 -0.00051835901 -0.144547, + -0.0599402 -0.00148428 -0.15117, + -0.059999999 0.00120578 -0.150841, + -0.059999999 0.00052004401 -0.157581, + -0.0599402 0.00320921 -0.157361, + -0.0599402 0.0028059799 -0.164197, + -0.059757002 0.0055154301 -0.164086, + -0.059803601 0.0046292599 -0.171, + -0.059445001 0.0082612 -0.163973, + -0.059716001 0.0058307201 -0.171, + -0.059757002 0.0059193298 -0.157139, + -0.0599402 0.0038958699 -0.15051199, + -0.059999999 0.00217277 -0.144109, + -0.0599402 0.000726778 -0.137952, + -0.059757002 -0.00046563 -0.13206799, + -0.059445001 -0.00142287 -0.126486, + -0.058998398 -0.0021416501 -0.121231, + -0.058412101 -0.0026155601 -0.116328, + -0.0576833 -0.0028470501 -0.111796, + -0.056809202 -0.00284179 -0.107656, + -0.055787299 -0.00260673 -0.103924, + -0.0546159 -0.0037908501 -0.102933, + -0.0532961 -0.0048974399 -0.102094, + -0.051830001 -0.0043049101 -0.099266998, + -0.050219599 -0.0036763099 -0.096772, + -0.048467699 -0.0045957598 -0.096504003, + -0.0465803 -0.0054166298 -0.096358001, + -0.044564299 -0.0061190301 -0.096327998, + -0.0424264 -0.0066679199 -0.096367002, + -0.040174201 -0.0070820898 -0.096398003, + -0.0378174 -0.0073712701 -0.096410997, + -0.035366699 -0.0075253798 -0.096386001, + -0.0328326 -0.0075383498 -0.096303999, + -0.0302257 -0.0074069998 -0.096148998, + -0.027557701 -0.0071324501 -0.095904, + -0.0248404 -0.0067175399 -0.095556997, + -0.0220857 -0.0061655799 -0.095095001, + -0.019305199 -0.0054816999 -0.094508, + -0.0165099 -0.0046777101 -0.093773, + -0.0137106 -0.0037626401 -0.092886001, + -0.0109179 -0.00274507 -0.091839999, + -0.0532961 -0.00161035 -0.097689003, + -0.0546159 -0.0021520499 -0.100616, + -0.055787299 -0.00101121 -0.101496, + -0.056809202 0.000195692 -0.102536, + -0.0576833 -2.958e-005 -0.106383, + -0.058412101 -3.4516001e-005 -0.110643, + -0.058998398 0.000187531 -0.115296, + -0.059445001 0.00064169598 -0.120323, + -0.059757002 0.00132917 -0.125701, + -0.0599402 0.00224871 -0.131405, + -0.059999999 0.00341901 -0.13740399, + -0.0599402 0.0048639202 -0.14366999, + -0.059757002 0.0066069202 -0.15018, + -0.059445001 0.0086658001 -0.156914, + -0.058998398 0.0110366 -0.16385899, + -0.059358198 0.00875236 -0.171, + -0.058984801 0.0109155 -0.171, + -0.0590127 0.0107542 -0.171, + -0.059027899 0.0107568 -0.191, + 0.059027899 0.0107568 -0.191, + 0.057608999 0.0167691 -0.191, + 0.0583965 0.013707 -0.171, + -0.0518195 0.030219801 -0.171, + -0.052944701 0.028228801 -0.171, + -0.051830001 0.030348299 -0.163066, + -0.052960701 0.0281986 -0.191, + -0.058398101 0.0137074 -0.171, + -0.057608999 0.0167691 -0.191, + -0.0109179 0.0094012301 -0.073583998, + -0.0137106 0.0086279698 -0.074851997, + -0.0109179 0.0073633799 -0.077430002, + -0.0109179 0.0103456 -0.071635999, + -0.0109179 0.0112337 -0.069672003, + -0.0137106 0.0105148 -0.070984997, + -0.0137106 0.0095959799 -0.072926, + -0.0165099 0.0098380996 -0.072105996, + -0.0165099 0.0089029903 -0.074024998, + -0.019305199 0.0092328303 -0.073034003, + -0.019305199 0.0082901996 -0.074934997, + -0.0220857 0.0087228296 -0.073770002, + -0.0220857 0.0077772201 -0.075655997, + -0.0248404 0.0083270296 -0.074317999, + -0.0248404 0.0073831598 -0.076196, + -0.027557701 0.0080625098 -0.074690998, + -0.027557701 0.0071234698 -0.076568998, + -0.0302257 0.0079431301 -0.074905001, + -0.0302257 0.0070092701 -0.076788999, + -0.0328326 0.0079784598 -0.074974999, + -0.0328326 0.0070473002 -0.076872997, + -0.035366699 0.00817296 -0.074922003, + -0.035366699 0.0072396998 -0.076839998, + -0.0378174 0.0085246097 -0.074766003, + -0.0378174 0.0075818701 -0.076710001, + -0.040174201 0.0090258596 -0.074529, + -0.040174201 0.00806507 -0.076500997, + -0.0424264 0.0096657099 -0.07423, + -0.0424264 0.0086770598 -0.076229997, + -0.044564299 0.0104293 -0.073884003, + -0.044564299 0.0094048297 -0.075912997, + -0.0465803 0.0113001 -0.073508002, + -0.0465803 0.0102312 -0.075556003, + -0.048467699 0.0122587 -0.073110998, + -0.048467699 0.0111486 -0.075186998, + -0.050219599 0.0132971 -0.072717004, + -0.050219599 0.0121753 -0.074869998, + -0.051830001 0.0144361 -0.072393999, + -0.051830001 0.0133017 -0.074598998, + -0.0532961 0.0156646 -0.072135001, + -0.0532961 0.0145122 -0.074383996, + -0.0546159 0.0157912 -0.074239999, + -0.055787299 0.0145164 -0.078760996, + -0.055787299 0.015853399 -0.07649, + -0.056809202 0.017188 -0.076578997, + -0.056809202 0.015814601 -0.078895003, + -0.0576833 0.0185326 -0.076783001, + -0.0576833 0.015701201 -0.081495002, + -0.058412101 0.0184756 -0.079542004, + -0.058412101 0.0155135 -0.084487997, + -0.058998398 0.018316001 -0.082694001, + -0.058998398 0.0151949 -0.087853, + -0.059445001 0.0179976 -0.086213, + -0.059445001 0.0147182 -0.091530003, + -0.059757002 0.017492 -0.090035997, + -0.059757002 0.0142136 -0.095592, + -0.0599402 0.0169442 -0.094238997, + -0.0599402 0.0138762 -0.100091, + -0.059999999 0.0165808 -0.098866999, + -0.059999999 0.013741 -0.104995, + -0.0599402 0.0164421 -0.103888, + -0.0599402 0.0138448 -0.110272, + -0.059757002 0.0165642 -0.109271, + -0.059757002 0.0142229 -0.115892, + -0.059445001 0.0169768 -0.114994, + -0.059445001 0.0149024 -0.121833, + -0.058998398 0.017684299 -0.12104, + -0.058998398 0.0158813 -0.128077, + -0.058412101 0.0186795 -0.12739401, + -0.058412101 0.0171503 -0.13461, + -0.0576833 0.019954 -0.13404, + -0.0576833 0.018701 -0.141416, + -0.056809202 0.0214995 -0.14095999, + -0.056809202 0.0205251 -0.148476, + -0.055787299 0.0233078 -0.14813501, + -0.055787299 0.022614701 -0.155773, + -0.0546159 0.0253707 -0.15554699, + -0.0546159 0.024961701 -0.163287, + -0.054602899 0.0248347 -0.171, + -0.055455498 0.0229061 -0.171, + -0.055579402 0.0226037 -0.191, + -0.054265399 0.0255982 -0.171, + -0.0532961 0.0276796 -0.163176, + -0.0532961 0.0280894 -0.155325, + -0.0546159 0.0260647 -0.147798, + -0.055787299 0.024283201 -0.140506, + -0.056809202 0.0227536 -0.133471, + -0.0576833 0.021484399 -0.12671, + -0.058412101 0.020484 -0.120242, + -0.058998398 0.0197604 -0.114086, + -0.059445001 0.019320101 -0.108258, + -0.059757002 0.019164201 -0.102772, + -0.0599402 0.0192855 -0.097643003, + -0.059999999 0.0196537 -0.092896998, + -0.0599402 0.0202292 -0.088561997, + -0.059757002 0.0207703 -0.084590003, + -0.059445001 0.021100899 -0.080911003, + -0.058998398 0.021243401 -0.077593997, + -0.058412101 0.0212547 -0.074666999, + -0.0576833 0.019873699 -0.074386001, + -0.056809202 0.0184897 -0.074228004, + -0.055787299 0.0171228 -0.074184, + -0.0546159 0.0145493 -0.076502003, + -0.0532961 0.0132935 -0.076603003, + -0.051830001 0.012103 -0.076775998, + -0.050219599 0.0109929 -0.077005997, + -0.048467699 0.0099775903 -0.077275999, + -0.0465803 0.0090708304 -0.077575997, + -0.044564299 0.0082814898 -0.077908002, + -0.0424264 0.0075935498 -0.078210004, + -0.040174201 0.0070137298 -0.078458004, + -0.0378174 0.0065555898 -0.078643002, + -0.035366699 0.0062299799 -0.078752004, + -0.0328326 0.0060469699 -0.078766003, + -0.0302257 0.0060125198 -0.078667998, + -0.027557701 0.0061268802 -0.078440003, + -0.0248404 0.0063855802 -0.078066997, + -0.0220857 0.0067801401 -0.077532001, + -0.019305199 0.0072976002 -0.076823004, + -0.0165099 0.0079201404 -0.075930998, + -0.0081428103 0.0092528304 -0.074087001, + -0.0081428103 0.0071743098 -0.077940002, + -0.0109179 0.0062699802 -0.079324, + -0.0081428103 0.0048968699 -0.081704997, + -0.0053973799 0.0070421998 -0.078295998, + -0.0053973799 0.0091491099 -0.074437998, + -0.00268824 0.0090881903 -0.074643999, + -0.00268824 0.011005 -0.070702001, + 0 0.0109905 -0.070767999, + 0 0.0127033 -0.066758998, + 0.00268824 0.011005 -0.070702001, + 0.00268824 0.00908799 -0.074644998, + 0.0053973799 0.0091487002 -0.074438997, + 0.0053973799 0.0070422501 -0.078299001, + 0.0081428103 0.0071744001 -0.077944003, + 0.054601401 0.024833901 -0.171, + 0.055579402 0.0226037 -0.191, + 0.054184102 0.025769901 -0.171, + 0.055569701 0.0225999 -0.171, + 0.055771701 0.0220796 -0.171, + 0.056448001 0.0203376 -0.171, + 0.056793399 0.019300001 -0.171, + 0.055787299 0.0222381 -0.163396, + 0.0109179 0.0073635001 -0.077436, + 0.0109179 0.0084079998 -0.075521, + 0.0137106 0.0076116999 -0.076769002, + 0.0137106 0.0065440098 -0.078661002, + 0.0165099 0.0068859099 -0.077830002, + 0.0165099 0.0058015399 -0.079703003, + 0.019305199 0.0062511298 -0.078708, + 0.019305199 0.0051548001 -0.080565996, + 0.0220857 0.00572559 -0.079407997, + 0.0220857 0.0046206401 -0.081256002, + 0.0248404 0.0053249402 -0.079938002, + 0.0248404 0.0042128102 -0.081782997, + 0.027557701 0.0050599198 -0.080312997, + 0.027557701 0.00394005 -0.082158998, + 0.0302257 0.0049371198 -0.080548003, + 0.0302257 0.00380693 -0.082399003, + 0.0328326 0.0049593002 -0.080658004, + 0.0328326 0.0038153499 -0.082517996, + 0.035366699 0.0051259999 -0.080656998, + 0.035366699 0.0039632302 -0.082529999, + 0.0378174 0.0054308502 -0.080564, + 0.0378174 0.0042429999 -0.082448997, + 0.040174201 0.0058637699 -0.080392003, + 0.040174201 0.0046427902 -0.082287997, + 0.0424264 0.0064111301 -0.080154002, + 0.0424264 0.0051543699 -0.082083002, + 0.044564299 0.0070634801 -0.079888001, + 0.044564299 0.0057951999 -0.081862003, + 0.0465803 0.00783851 -0.079625003, + 0.0465803 0.0065624402 -0.081623003, + 0.048467699 0.0087323599 -0.079360999, + 0.048467699 0.00744467 -0.081393003, + 0.050219599 0.0097324597 -0.079121001, + 0.050219599 0.0084301103 -0.081189997, + 0.051830001 0.0108259 -0.078924, + 0.051830001 0.0095056295 -0.081033997, + 0.0532961 0.0119979 -0.078789003, + 0.0532961 0.0106557 -0.080939002, + 0.0546159 0.0132318 -0.078729004, + 0.0546159 0.0118629 -0.080921002, + 0.055787299 0.0145096 -0.078759998, + 0.055787299 0.0131067 -0.080995001, + 0.056809202 0.0158103 -0.078893997, + 0.056809202 0.0129226 -0.083443999, + 0.0576833 0.015692901 -0.081495002, + 0.0576833 0.0126946 -0.086287998, + 0.058412101 0.0155038 -0.084490001, + 0.058412101 0.0123703 -0.089504004, + 0.058998398 0.0151907 -0.087853, + 0.058998398 0.0119115 -0.093041003, + 0.059445001 0.0147152 -0.091531001, + 0.059445001 0.0114571 -0.096972004, + 0.059757002 0.0142244 -0.095601998, + 0.059757002 0.0111735 -0.101341, + 0.0599402 0.0138993 -0.100108, + 0.0599402 0.0110709 -0.106124, + 0.059999999 0.013772 -0.105017, + 0.059999999 0.0111809 -0.111287, + 0.0599402 0.0138793 -0.110295, + 0.0599402 0.0115393 -0.116802, + 0.059757002 0.0142566 -0.115915, + 0.059757002 0.0121796 -0.12264, + 0.059445001 0.0149316 -0.121855, + 0.059445001 0.0131247 -0.128777, + 0.058998398 0.015905101 -0.128098, + 0.058998398 0.0143744 -0.135197, + 0.058412101 0.0171712 -0.134628, + 0.058412101 0.015922399 -0.141884, + 0.0576833 0.0187247 -0.14142799, + 0.0576833 0.0177608 -0.14882299, + 0.056809202 0.0205578 -0.148481, + 0.056809202 0.0198723 -0.155999, + 0.055787299 0.022653401 -0.155771, + 0.0546159 0.024992799 -0.16328301, + 0.055382699 0.0230815 -0.171, + 0.0532961 0.027709899 -0.16317201, + 0.0546159 0.0254086 -0.15554599, + 0.055787299 0.023339801 -0.14814, + 0.056809202 0.0215228 -0.140972, + 0.0576833 0.019974601 -0.134057, + 0.058412101 0.018703001 -0.127415, + 0.058998398 0.017713301 -0.121062, + 0.059445001 0.017010299 -0.115017, + 0.059757002 0.0165987 -0.109294, + 0.0599402 0.016473001 -0.103909, + 0.059999999 0.0166039 -0.098885, + 0.0599402 0.016954999 -0.094249003, + 0.059757002 0.017488999 -0.090038002, + 0.059445001 0.017993299 -0.086213, + 0.058998398 0.018306199 -0.082695998, + 0.058412101 0.0184671 -0.079542004, + 0.0576833 0.018528201 -0.076780997, + 0.056809202 0.017181 -0.076577999, + 0.055787299 0.015843401 -0.076489002, + 0.0546159 0.0145362 -0.076502003, + 0.0532961 0.0132779 -0.076605, + 0.051830001 0.012086 -0.076783001, + 0.050219599 0.0109762 -0.077021003, + 0.048467699 0.0099633299 -0.077298999, + 0.0465803 0.0090611698 -0.077591002, + 0.044564299 0.0082740895 -0.077907003, + 0.0424264 0.0075825201 -0.078212, + 0.040174201 0.0069985599 -0.078464001, + 0.0378174 0.0065380698 -0.078652002, + 0.035366699 0.006213 -0.078763001, + 0.0328326 0.0060324101 -0.078778997, + 0.0302257 0.0060010101 -0.078681, + 0.027557701 0.0061184801 -0.078452997, + 0.0248404 0.0063799601 -0.078079, + 0.0220857 0.0067767599 -0.077544004, + 0.019305199 0.0072959601 -0.076833002, + 0.0165099 0.0079203099 -0.075939, + 0.0137106 0.0086294701 -0.074858002, + 0.0109179 0.0094004096 -0.073587999, + 0.0081428103 0.0092522204 -0.074088998, + 0.0053973799 0.0110495 -0.070501998, + 0.00268824 0.0127123 -0.066694997, + 0 0.0142051 -0.062701002, + -0.00268824 0.0127124 -0.066694997, + -0.0053973799 0.0110495 -0.070501998, + -0.0137106 0.0065451702 -0.078653999, + -0.0137106 0.0054287701 -0.080526002, + -0.0165099 0.00580406 -0.079695001, + -0.0165099 0.0046703401 -0.081549004, + -0.019305199 0.0051591699 -0.080557004, + -0.019305199 0.0040122001 -0.082396999, + -0.0220857 0.0046273698 -0.081246004, + -0.0220857 0.0034693801 -0.083076999, + -0.0248404 0.0042222701 -0.081772, + -0.0248404 0.00305359 -0.083599001, + -0.027557701 0.0039522802 -0.082148001, + -0.027557701 0.0027711401 -0.083976001, + -0.0302257 0.00382144 -0.082388997, + -0.0302257 0.00262463 -0.084221996, + -0.0328326 0.00383056 -0.082510002, + -0.0328326 0.0026134099 -0.084349997, + -0.035366699 0.0039765802 -0.082524002, + -0.035366699 0.00273487 -0.084372997, + -0.0378174 0.0042528301 -0.082447, + -0.0378174 0.00298152 -0.084301002, + -0.040174201 0.0046494701 -0.082289003, + -0.040174201 0.0033505601 -0.084152997, + -0.0424264 0.0051631699 -0.082069002, + -0.0424264 0.00385499 -0.083980002, + -0.044564299 0.0058083101 -0.081840999, + -0.044564299 0.0044905902 -0.083786003, + -0.0465803 0.0065779299 -0.081610002, + -0.0465803 0.0052475701 -0.083584003, + -0.048467699 0.0074606002 -0.081386, + -0.048467699 0.0061154198 -0.083392002, + -0.050219599 0.0084448596 -0.081188001, + -0.050219599 0.0070825298 -0.083228, + -0.051830001 0.0095180497 -0.081033997, + -0.051830001 0.0081356401 -0.083109997, + -0.0532961 0.0106653 -0.080940001, + -0.0532961 0.0092587499 -0.083053999, + -0.0546159 0.0118696 -0.080922, + -0.0546159 0.0104324 -0.083077997, + -0.056809202 0.0194254 -0.163515, + -0.055787299 0.0222064 -0.16339999, + -0.056512099 0.020158799 -0.171, + -0.056809202 0.0198329 -0.156, + -0.0576833 0.017036401 -0.156229, + -0.0576833 0.017727699 -0.148818, + -0.058412101 0.0149262 -0.149161, + -0.058412101 0.0158985 -0.141872, + -0.058998398 0.0131026 -0.14232799, + -0.058998398 0.0143533 -0.135179, + -0.059445001 0.011574 -0.135745, + -0.059445001 0.0131008 -0.128756, + -0.059757002 0.01035 -0.129428, + -0.059757002 0.0121502 -0.122617, + -0.0599402 0.0094344299 -0.123391, + -0.0599402 0.0115055 -0.116779, + -0.059999999 0.0088090803 -0.117658, + -0.059999999 0.0111464 -0.111265, + -0.0599402 0.0084480001 -0.112257, + -0.0599402 0.01104 -0.106103, + -0.059757002 0.0083179604 -0.107218, + -0.059757002 0.0111505 -0.101324, + -0.059445001 0.00838836 -0.102574, + -0.059445001 0.0114464 -0.096963003, + -0.058998398 0.0086493799 -0.098347999, + -0.058998398 0.0119145 -0.093039997, + -0.058412101 0.0090928897 -0.094559997, + -0.058412101 0.0123745 -0.089504004, + -0.0576833 0.0095472699 -0.091159001, + -0.0576833 0.0127042 -0.086286001, + -0.056809202 0.0098990602 -0.088082001, + -0.056809202 0.0129308 -0.083444998, + -0.055787299 0.0101752 -0.085383996, + -0.055787299 0.013111 -0.080995999, + -0.0546159 0.0132416 -0.078730002, + -0.0532961 0.0120106 -0.078789003, + -0.051830001 0.0108411 -0.078922004, + -0.050219599 0.0097489702 -0.079113998, + -0.048467699 0.0087484699 -0.079346001, + -0.0465803 0.00785222 -0.079603001, + -0.044564299 0.0070727202 -0.079874001, + -0.0424264 0.0064181802 -0.080155, + -0.040174201 0.0058742198 -0.080390997, + -0.0378174 0.0054451302 -0.080558002, + -0.035366699 0.00514238 -0.080649003, + -0.0328326 0.00497506 -0.080646999, + -0.0302257 0.0049505299 -0.080536, + -0.027557701 0.0050704102 -0.080301002, + -0.0248404 0.0053325202 -0.079925999, + -0.0220857 0.0057305801 -0.079397, + -0.019305199 0.0062540802 -0.078698002, + -0.0165099 0.0068873102 -0.077822, + -0.0137106 0.0076115602 -0.076761998, + -0.0555728 0.0226011 -0.171, + -0.055773102 0.0220802 -0.171, + -0.0567948 0.0193005 -0.171, + -0.057432801 0.017363001 -0.171, + -0.0532845 0.0275518 -0.171, + -0.052960001 0.028198199 -0.171, + 0.0465803 0.037968699 -0.162751, + 0.046066999 0.038430501 -0.171, + 0.044564299 0.040325101 -0.162654, + 0.048467699 0.0355183 -0.16285101, + 0.048119001 0.035840798 -0.171, + 0.048467699 0.0359364 -0.15468401, + 0.050219599 0.033402 -0.154891, + 0.050219599 0.034092501 -0.146823, + 0.051830001 0.031484298 -0.14714199, + 0.051830001 0.0324541 -0.13919, + 0.0532961 0.0297835 -0.139625, + 0.0532961 0.031037999 -0.131805, + 0.0546159 0.0283169 -0.132359, + 0.0546159 0.029853599 -0.124692, + 0.055787299 0.0270938 -0.125366, + 0.055787299 0.0289075 -0.117871, + 0.056809202 0.026120501 -0.118665, + 0.056809202 0.0282059 -0.111363, + 0.0576833 0.0254023 -0.112278, + 0.0576833 0.027752601 -0.10519, + 0.058412101 0.024942899 -0.106224, + 0.058412101 0.027547499 -0.099368997, + 0.058998398 0.0247417 -0.100519, + 0.058998398 0.027588399 -0.093914002, + 0.059445001 0.0247964 -0.095178001, + 0.059445001 0.027871899 -0.088841997, + 0.059757002 0.0251047 -0.090212002, + 0.059757002 0.028395301 -0.084164001, + 0.0599402 0.0256582 -0.085638002, + 0.0599402 0.028931901 -0.079810999, + 0.059999999 0.0262169 -0.0814, + 0.059999999 0.029262301 -0.075681999, + 0.0599402 0.0265646 -0.077408999, + 0.0599402 0.029390801 -0.071852997, + 0.059757002 0.0267059 -0.073743001, + 0.059757002 0.0293335 -0.068383999, + 0.059445001 0.026664 -0.070459001, + 0.059445001 0.027905701 -0.067819998, + 0.058998398 0.025239499 -0.069996998, + 0.058998398 0.0264313 -0.067405999, + 0.058412101 0.0237836 -0.069677003, + 0.058412101 0.024932999 -0.067134999, + 0.0576833 0.022318 -0.069490999, + 0.0576833 0.0234314 -0.067000002, + 0.056809202 0.0208623 -0.069430001, + -0.0532961 0.016749799 -0.069861002, + -0.0532961 0.017769201 -0.067575, + -0.0546159 0.018071201 -0.069626004, + -0.051830001 0.0155073 -0.070175998, + -0.051830001 0.0165119 -0.067979999, + -0.050219599 0.0143552 -0.070582002, + -0.050219599 0.0153089 -0.068424001, + -0.048467699 0.0132709 -0.071009003, + -0.048467699 0.0141695 -0.068875998, + -0.0465803 0.0122629 -0.071428999, + -0.0465803 0.0131163 -0.069333002, + -0.044564299 0.0113519 -0.071837001, + -0.044564299 0.0121701 -0.06978, + -0.0424264 0.010557 -0.072215997, + -0.0424264 0.0113523 -0.070200004, + -0.040174201 0.0098970402 -0.072549999, + -0.040174201 0.0106809 -0.070573002, + -0.0378174 0.0093856202 -0.072819002, + -0.0378174 0.0101686 -0.070877001, + -0.035366699 0.0090327803 -0.073002003, + -0.035366699 0.0098228203 -0.071089, + -0.0328326 0.0088434396 -0.073077001, + -0.0328326 0.0096460404 -0.071184002, + -0.0302257 0.00881714 -0.073019996, + -0.0302257 0.0096344901 -0.071137004, + -0.027557701 0.0089464299 -0.072811, + -0.027557701 0.0097775199 -0.070931002, + -0.0248404 0.0092187803 -0.072434999, + -0.0248404 0.0100606 -0.070547998, + -0.0220857 0.0096184602 -0.071875997, + -0.0220857 0.0104678 -0.069976002, + -0.019305199 0.0101284 -0.071124002, + -0.019305199 0.0109769 -0.069205999, + -0.0165099 0.010725 -0.070175998, + -0.0165099 0.0115531 -0.068232998, + -0.0137106 0.0113761 -0.069031, + -0.0137106 0.0121858 -0.067060001, + -0.0109179 0.0120704 -0.067690998, + -0.0109179 0.0128556 -0.065696999, + -0.0109179 0.0142683 -0.061671998, + -0.0137106 0.0136496 -0.063079998, + -0.0081428103 0.0142402 -0.062130999, + -0.0081428103 0.0144067 -0.061623, + -0.0053973799 0.0143904 -0.061942, + -0.0053973799 0.0145003 -0.061455999, + -0.00268824 0.0144923 -0.061643001, + -0.00268824 0.0144728 -0.061103001, + 0 0.0144704 -0.061163999, + 0 0.014293 -0.060614001, + 0.00268824 0.0144718 -0.061104, + 0.00268824 0.0144914 -0.061643001, + 0.0053973799 0.0144985 -0.061455999, + 0.0053973799 0.0143895 -0.061942, + 0.0081428103 0.0144054 -0.061623, + 0.0081428103 0.0142395 -0.062130999, + 0.0109179 0.0142673 -0.061673, + 0.055787299 0.0214788 -0.064691998, + 0.056809202 0.0229543 -0.064531997, + 0.055787299 0.022396799 -0.062259, + 0.0546159 0.020061599 -0.064943999, + 0.0546159 0.0209579 -0.062604003, + 0.0532961 0.0187102 -0.065315999, + 0.0532961 0.019536899 -0.063045003, + 0.051830001 0.017391801 -0.065766998, + 0.051830001 0.0181494 -0.063527003, + 0.050219599 0.016122 -0.066243, + 0.050219599 0.016824899 -0.064048, + 0.048467699 0.0149285 -0.066739999, + 0.048467699 0.0155897 -0.064594999, + 0.0465803 0.0138355 -0.067244999, + 0.0465803 0.014469 -0.065153003, + 0.044564299 0.0128657 -0.067741998, + 0.044564299 0.0134843 -0.065701999, + 0.0424264 0.0120382 -0.068209998, + 0.0424264 0.0126553 -0.06622, + 0.040174201 0.0113695 -0.068626001, + 0.040174201 0.0119958 -0.066679001, + 0.0378174 0.0108694 -0.068966001, + 0.0378174 0.0115134 -0.067054003, + 0.035366699 0.0105423 -0.069204003, + 0.035366699 0.0112094 -0.067316003, + 0.0328326 0.0103875 -0.069315001, + 0.0328326 0.0110804 -0.067441002, + 0.0302257 0.0103985 -0.069274999, + 0.0302257 0.0111153 -0.067404002, + 0.027557701 0.0105617 -0.069063999, + 0.027557701 0.0112932 -0.067185, + 0.0248404 0.0108551 -0.068667002, + 0.0248404 0.0115991 -0.066772997, + 0.0220857 0.0112627 -0.068072997, + 0.0220857 0.0120134 -0.066159002, + 0.019305199 0.0117652 -0.067276999, + 0.019305199 0.0125014 -0.065333001, + 0.0165099 0.0123293 -0.066275001, + 0.0165099 0.0130544 -0.064301997, + 0.0137106 0.0129438 -0.065075003, + 0.0137106 0.0136489 -0.063079, + 0.0109179 0.0135863 -0.063690998, + 0.0081428103 0.0127873 -0.06617, + 0.0053973799 0.0142201 -0.062452, + 0.00268824 0.0143803 -0.062128998, + 0 0.0144894 -0.061703999, + -0.00268824 0.0143807 -0.062128998, + -0.0053973799 0.0142205 -0.062451001, + -0.0081428103 0.0127877 -0.06617, + -0.0081428103 0.0111253 -0.070160002, + -0.0053973799 0.0127403 -0.066500999, + -0.00268824 0.014209 -0.062638998, + 0 0.0143774 -0.06219, + 0.00268824 0.0142087 -0.062639996, + 0.0053973799 0.01274 -0.066500999, + 0.0081428103 0.0111253 -0.070160002, + 0.0109179 0.0120704 -0.067690998, + 0.055787299 0.019434899 -0.069485001, + 0.055787299 0.0204923 -0.067098998, + 0.0546159 0.018053001 -0.069642, + 0.0546159 0.0190902 -0.067307003, + 0.0532961 0.0167342 -0.069886997, + 0.0532961 0.0177582 -0.067592002, + 0.051830001 0.0154965 -0.070192002, + 0.051830001 0.0165032 -0.067979001, + 0.050219599 0.0143468 -0.070579998, + 0.050219599 0.0152958 -0.068425998, + 0.048467699 0.0132583 -0.071010999, + 0.048467699 0.0141512 -0.068883002, + 0.0465803 0.0122453 -0.071436003, + 0.0465803 0.0130947 -0.069343999, + 0.044564299 0.0113313 -0.071846999, + 0.044564299 0.0121487 -0.069793999, + 0.0424264 0.0105367 -0.072229996, + 0.0424264 0.0113335 -0.070216998, + 0.040174201 0.00987921 -0.072566003, + 0.040174201 0.0106656 -0.070591003, + 0.0378174 0.0093712201 -0.072835997, + 0.0378174 0.0101571 -0.070895001, + 0.035366699 0.0090220002 -0.073018998, + 0.035366699 0.0098148296 -0.071107, + 0.0328326 0.0088360095 -0.073094003, + 0.0328326 0.0096410196 -0.071199998, + 0.0302257 0.0088125197 -0.073035002, + 0.0302257 0.0096319197 -0.071153, + 0.027557701 0.0089440905 -0.072825, + 0.027557701 0.0097778104 -0.070943996, + 0.0248404 0.0092190299 -0.072447002, + 0.0248404 0.0100633 -0.070559002, + 0.0220857 0.0096208705 -0.071886003, + 0.0220857 0.0104662 -0.069982998, + 0.019305199 0.010127 -0.07113, + 0.019305199 0.0109694 -0.069206998, + 0.0165099 0.0107185 -0.070178002, + 0.0165099 0.011553 -0.068232998, + 0.0137106 0.011376 -0.069031, + 0.0137106 0.0121858 -0.067060001, + 0.0109179 0.0128549 -0.065696001, + 0.0576833 0.024468901 -0.064485997, + 0.058412101 0.026004201 -0.064567, + 0.058998398 0.0275419 -0.064785004, + 0.059445001 0.0290622 -0.065149002, + 0.059757002 0.030543501 -0.065665998, + 0.0599402 0.0319677 -0.066336997, + 0.059999999 0.032055002 -0.069977999, + 0.0599402 0.031959999 -0.073954999, + 0.059757002 0.031667899 -0.078208998, + 0.059445001 0.0311691 -0.082670003, + 0.058998398 0.030668899 -0.087456003, + 0.058412101 0.030398 -0.092643, + 0.0576833 0.030360101 -0.098215997, + 0.056809202 0.030558201 -0.104158, + 0.055787299 0.030994499 -0.110453, + 0.0546159 0.0316687 -0.117083, + 0.0532961 0.032575902 -0.124027, + 0.051830001 0.033709701 -0.13126101, + 0.050219599 0.035063401 -0.13876399, + 0.048467699 0.0366279 -0.146512, + 0.0465803 0.038387202 -0.15448301, + 0.040173799 0.044563901 -0.171, + 0.037974101 0.046453901 -0.171, + 0.040174201 0.044714399 -0.16247401, + 0.0424264 0.042576998 -0.162561, + 0.041868102 0.0429601 -0.171, + 0.0424264 0.042996299 -0.15410601, + 0.044564299 0.0407441 -0.15429001, + 0.044564299 0.041437499 -0.145923, + 0.0465803 0.0390797 -0.146212, + 0.0465803 0.040052999 -0.137951, + 0.048467699 0.037599999 -0.13835099, + 0.048467699 0.0388579 -0.13021301, + 0.050219599 0.036320198 -0.13073, + 0.050219599 0.0378603 -0.122736, + 0.051830001 0.035248701 -0.123374, + 0.051830001 0.0370664 -0.115544, + 0.0532961 0.0343922 -0.116307, + 0.0532961 0.036482401 -0.108662, + 0.0546159 0.033757199 -0.109552, + 0.0546159 0.036113702 -0.102114, + 0.055787299 0.033348899 -0.103131, + 0.055787299 0.0359619 -0.095918998, + 0.056809202 0.033168498 -0.097064003, + 0.056809202 0.036026601 -0.090095997, + 0.0576833 0.033214401 -0.091369003, + 0.0576833 0.0363052 -0.084664002, + 0.058412101 0.033483699 -0.086061999, + 0.058412101 0.036794402 -0.079640001, + 0.058998398 0.0339729 -0.081160001, + 0.058998398 0.0356436 -0.078063004, + 0.059445001 0.034440599 -0.076586001, + 0.059757002 0.038653601 -0.063221999, + 0.0599402 0.037195601 -0.062274002, + 0.059757002 0.037404198 -0.066212997, + 0.059445001 0.040125102 -0.064297996, + 0.059445001 0.037433699 -0.070450999, + 0.058998398 0.040218599 -0.068668, + 0.058998398 0.041588198 -0.065516002, + 0.058412101 0.043021102 -0.066873997, + 0.058412101 0.041582901 -0.070092, + 0.0576833 0.044403199 -0.068366997, + 0.0576833 0.042890899 -0.07164, + 0.056809202 0.045713998 -0.069987997, + 0.056809202 0.0441222 -0.073307, + 0.055787299 0.046932999 -0.071730003, + 0.055787299 0.045256201 -0.075083002, + 0.0546159 0.048039399 -0.073585004, + 0.0546159 0.044701502 -0.080504999, + 0.0532961 0.047440201 -0.079148002, + 0.0532961 0.044328801 -0.086338997, + 0.051830001 0.047012899 -0.085124001, + 0.051830001 0.044139698 -0.092565, + 0.050219599 0.0467586 -0.091490999, + 0.050219599 0.0441349 -0.099160999, + 0.048467699 0.0466781 -0.098224998, + 0.048467699 0.0443138 -0.106106, + 0.0465803 0.0467714 -0.105304, + 0.0465803 0.044675399 -0.113374, + 0.044564299 0.0470373 -0.1127, + 0.044564299 0.045214999 -0.120939, + 0.0424264 0.047471099 -0.120388, + 0.0424264 0.045926999 -0.128774, + 0.040174201 0.0480676 -0.12833799, + 0.040174201 0.046805799 -0.136849, + 0.0378174 0.048823498 -0.13652, + 0.0378174 0.047846101 -0.145138, + 0.035366699 0.049734101 -0.144907, + 0.035366699 0.049037199 -0.153612, + 0.0328326 0.050788801 -0.153468, + 0.056809202 0.0247538 -0.059549, + 0.0576833 0.027123399 -0.056825001, + 0.056809202 0.025536601 -0.057080999, + 0.055787299 0.023236601 -0.059854999, + 0.055787299 0.023936599 -0.057463001, + 0.0546159 0.0217217 -0.060272999, + 0.0546159 0.0223378 -0.057916999, + 0.0532961 0.0202244 -0.060748, + 0.0532961 0.0207722 -0.058444999, + 0.051830001 0.0187757 -0.061278999, + 0.051830001 0.019269699 -0.059034999, + 0.050219599 0.017403699 -0.061854001, + 0.050219599 0.017860301 -0.059675999, + 0.048467699 0.016136199 -0.062460002, + 0.048467699 0.0165712 -0.060348999, + 0.0465803 0.0149976 -0.063078001, + 0.0465803 0.0154274 -0.061032001, + 0.044564299 0.0140099 -0.063685, + 0.044564299 0.0144489 -0.061700001, + 0.0424264 0.0131904 -0.064254001, + 0.0424264 0.0136506 -0.062320001, + 0.040174201 0.0125507 -0.064755999, + 0.040174201 0.0130409 -0.062862001, + 0.0378174 0.012095 -0.065163001, + 0.0378174 0.0126212 -0.063297004, + 0.035366699 0.0118221 -0.065445997, + 0.035366699 0.0123849 -0.063594997, + 0.0328326 0.0117234 -0.065580003, + 0.0328326 0.0123145 -0.063730001, + 0.0302257 0.0117799 -0.065539002, + 0.0302257 0.0123993 -0.063680999, + 0.027557701 0.0119781 -0.065307997, + 0.027557701 0.0126182 -0.063433997, + 0.0248404 0.0122978 -0.064878002, + 0.0248404 0.0129331 -0.062969998, + 0.0220857 0.0127025 -0.064231999, + 0.0220857 0.0133419 -0.062291, + 0.019305199 0.0131869 -0.063375004, + 0.019305199 0.0138203 -0.061407, + 0.0165099 0.0137269 -0.062318999, + 0.0165099 0.0143494 -0.060323, + 0.0137106 0.0143039 -0.061071001, + 0.0137106 0.0144582 -0.060566999, + 0.0109179 0.0144282 -0.061166, + 0.0109179 0.0145287 -0.060683999, + 0.0081428103 0.0145108 -0.061138999, + 0.0081428103 0.0144865 -0.060603, + 0.0053973799 0.0144771 -0.060919002, + 0.0053973799 0.014298 -0.060371, + 0.00268824 0.0142941 -0.060555, + 0.00268824 0.0139541 -0.060072001, + 0 0.0139531 -0.060130998, + 0.0302257 -0.051792402 -0.168723, + 0.030994801 -0.051374301 -0.171, + 0.0328326 -0.050181501 -0.168689, + -0.0302257 -0.051803101 -0.168724, + -0.0328326 -0.050193101 -0.16869099, + -0.030832 -0.051472198 -0.171, + -0.0302257 -0.051708899 -0.166434, + -0.027557701 -0.053174399 -0.166494, + -0.027557701 -0.053012598 -0.164223, + -0.0248404 -0.054331701 -0.164304, + -0.0248404 -0.0541021 -0.16205101, + -0.0220857 -0.055273 -0.162147, + -0.0220857 -0.054975301 -0.159913, + -0.019305199 -0.055996802 -0.160018, + -0.019305199 -0.055630598 -0.157803, + -0.0165099 -0.056504499 -0.15791, + -0.0165099 -0.056069199 -0.15571401, + -0.0137106 -0.056798 -0.155819, + -0.0137106 -0.056293 -0.153642, + -0.0109179 -0.056879301 -0.15373801, + -0.0109179 -0.0563039 -0.151581, + -0.0081428103 -0.056750599 -0.15166301, + -0.0081428103 -0.0561052 -0.149526, + -0.0053973799 -0.056417301 -0.14959, + -0.0053973799 -0.055702601 -0.14747301, + -0.00268824 -0.055885602 -0.147515, + -0.00268824 -0.055102199 -0.14542, + 0 -0.055161599 -0.14543501, + 0 -0.054310299 -0.143362, + 0.00268824 -0.055101201 -0.145421, + 0.00268824 -0.0558846 -0.147516, + 0.0053973799 -0.0557006 -0.147475, + 0.0053973799 -0.056415401 -0.149591, + 0.0081428103 -0.056102298 -0.149528, + 0.0081428103 -0.0567476 -0.151665, + 0.0109179 -0.056299899 -0.151583, + 0.0109179 -0.0568748 -0.15374, + 0.0137106 -0.0562874 -0.15364499, + 0.0137106 -0.056791399 -0.155821, + 0.0165099 -0.056061201 -0.155717, + 0.0165099 -0.056495 -0.157912, + 0.019305199 -0.055619501 -0.157805, + 0.019305199 -0.055984199 -0.160018, + 0.0220857 -0.054960899 -0.159914, + 0.0220857 -0.0552576 -0.162147, + 0.0248404 -0.054084901 -0.16205101, + 0.0248404 -0.0543149 -0.16430201, + 0.027557701 -0.052994002 -0.164221, + 0.027557701 -0.0531587 -0.166492, + 0.0302257 -0.0516917 -0.16643199, + -0.044561401 -0.040171701 -0.171, + -0.044440001 -0.040312301 -0.171, + -0.044564299 -0.040149398 -0.168485, + -0.0378174 -0.046554599 -0.168617, + -0.0378174 -0.0464609 -0.166219, + -0.040174201 -0.0445389 -0.168575, + -0.039599199 -0.045056298 -0.171, + -0.040172402 -0.044562198 -0.171, + -0.0402769 -0.044472098 -0.171, + -0.0424264 -0.042401399 -0.168531, + -0.040174201 -0.044445299 -0.166136, + -0.0378174 -0.046298899 -0.16381, + -0.035366699 -0.048185799 -0.16392601, + -0.035366699 -0.047955502 -0.161548, + -0.0328326 -0.0497071 -0.16169199, + -0.0328326 -0.049408302 -0.159344, + -0.0302257 -0.0510187 -0.159509, + -0.0302257 -0.0506512 -0.15719301, + -0.027557701 -0.0521175 -0.157372, + -0.027557701 -0.0516809 -0.15508699, + -0.0248404 -0.053001098 -0.155276, + -0.0248404 -0.052494898 -0.15302099, + -0.0220857 -0.053667001 -0.15321299, + -0.0220857 -0.0530908 -0.15098999, + -0.019305199 -0.0541135 -0.151178, + -0.019305199 -0.053467501 -0.148987, + -0.0165099 -0.0543424 -0.149165, + -0.0165099 -0.053627402 -0.147007, + -0.0137106 -0.054357 -0.14717001, + -0.0137106 -0.0535735 -0.145044, + -0.0109179 -0.054160301 -0.145188, + -0.0109179 -0.0533089 -0.143094, + -0.0081428103 -0.053755902 -0.143213, + -0.0081428103 -0.052837402 -0.14115401, + -0.0053973799 -0.0531496 -0.141243, + -0.0053973799 -0.0521647 -0.139218, + -0.00268824 -0.0523476 -0.139274, + -0.00268824 -0.051297002 -0.137284, + 0 -0.0513562 -0.13730399, + 0 -0.050241001 -0.13535, + 0.00268824 -0.0512955 -0.13728499, + 0.00268824 -0.0523462 -0.139275, + 0.0053973799 -0.052161802 -0.13922, + 0.0053973799 -0.053146899 -0.14124499, + 0.0081428103 -0.052833401 -0.141157, + 0.0081428103 -0.053752299 -0.143216, + 0.0109179 -0.053304099 -0.143098, + 0.0109179 -0.054155901 -0.145192, + 0.0137106 -0.053567901 -0.14504901, + 0.0137106 -0.0543519 -0.147175, + 0.0165099 -0.053621199 -0.147012, + 0.0165099 -0.054336499 -0.14917, + 0.019305199 -0.053460602 -0.148993, + 0.019305199 -0.054106299 -0.15118299, + 0.0220857 -0.0530826 -0.150996, + 0.0220857 -0.053658001 -0.153217, + 0.0248404 -0.052484699 -0.153027, + 0.0248404 -0.052989099 -0.155279, + 0.027557701 -0.0516675 -0.155091, + 0.027557701 -0.052101601 -0.15737399, + 0.0302257 -0.050633799 -0.157195, + 0.0302257 -0.050999001 -0.15951, + 0.0328326 -0.0493869 -0.159345, + 0.0328326 -0.049684402 -0.161691, + 0.035366699 -0.047931001 -0.16154701, + 0.035366699 -0.048161998 -0.16392399, + 0.0378174 -0.046273399 -0.163808, + 0.0378174 -0.046439402 -0.166216, + 0.040174201 -0.0444225 -0.166133, + 0.0424264 -0.042283799 -0.166045, + 0.040174201 -0.044256199 -0.163684, + 0.0378174 -0.0460421 -0.161393, + 0.035366699 -0.047633301 -0.15916599, + 0.0328326 -0.049021501 -0.15699799, + 0.0302257 -0.050199501 -0.154882, + 0.027557701 -0.051162999 -0.152812, + 0.0248404 -0.051909201 -0.15078101, + 0.0220857 -0.052436698 -0.148785, + 0.019305199 -0.0527451 -0.146816, + 0.0165099 -0.0528371 -0.144871, + 0.0137106 -0.052715901 -0.14294299, + 0.0109179 -0.052384999 -0.14103, + 0.0081428103 -0.051848099 -0.139125, + 0.0053973799 -0.051111002 -0.137226, + 0.00268824 -0.0501802 -0.13532899, + 0 -0.049063198 -0.133432, + -0.00268824 -0.050181799 -0.13532799, + -0.0053973799 -0.051114101 -0.137224, + -0.0081428103 -0.051852498 -0.13912199, + -0.0109179 -0.0523904 -0.14102501, + -0.0137106 -0.0527221 -0.142939, + -0.0165099 -0.052843802 -0.14486501, + -0.019305199 -0.052752301 -0.14681, + -0.0220857 -0.0524446 -0.14877801, + -0.0248404 -0.051918399 -0.150775, + -0.027557701 -0.051174302 -0.152806, + -0.0302257 -0.050214101 -0.15487701, + -0.0328326 -0.049040399 -0.156995, + -0.035366699 -0.047656398 -0.15916499, + -0.0378174 -0.0460683 -0.161394, + -0.040174201 -0.0442832 -0.16368601, + -0.0424264 -0.042307898 -0.166049, + -0.044024602 -0.040748298 -0.171, + -0.044033099 -0.040756401 -0.191, + -0.0463636 -0.038084399 -0.171, + -0.0465803 -0.037792999 -0.168437, + -0.044564299 -0.040056001 -0.16595601, + -0.0424264 -0.042145699 -0.163555, + -0.040174201 -0.0440524 -0.161229, + -0.0378174 -0.045768801 -0.158972, + -0.035366699 -0.047288001 -0.15678, + -0.0328326 -0.048602998 -0.15464699, + -0.0302257 -0.0497072 -0.152566, + -0.027557701 -0.050597399 -0.15053301, + -0.0248404 -0.051271901 -0.14853901, + -0.0220857 -0.051729199 -0.14658099, + -0.019305199 -0.0519685 -0.144651, + -0.0165099 -0.0519922 -0.142745, + -0.0137106 -0.051803399 -0.140857, + -0.0109179 -0.0514054 -0.13898399, + -0.0081428103 -0.050801799 -0.13712101, + -0.0053973799 -0.049998801 -0.13526399, + -0.00268824 -0.049004 -0.13341001, + 0 -0.047825299 -0.13155501, + 0.00268824 -0.049002402 -0.13341101, + 0.0053973799 -0.049995702 -0.13526601, + 0.0081428103 -0.050797202 -0.137124, + 0.0109179 -0.0513996 -0.138988, + 0.0137106 -0.051796701 -0.140863, + 0.0165099 -0.051984899 -0.14275099, + 0.019305199 -0.051960699 -0.144658, + 0.0220857 -0.051720999 -0.146588, + 0.0248404 -0.051263001 -0.14854699, + 0.027557701 -0.0505872 -0.15053999, + 0.0302257 -0.049694799 -0.152573, + 0.0328326 -0.048587002 -0.154652, + 0.035366699 -0.047267701 -0.156783, + 0.0378174 -0.045744199 -0.15897299, + 0.040174201 -0.044024602 -0.161228, + 0.0424264 -0.0421171 -0.163552, + 0.044564299 -0.040030699 -0.165953, + 0.044564299 -0.0401337 -0.16848201, + 0.0465803 -0.037776601 -0.16843399, + 0.0479904 -0.036012899 -0.191, + 0.0464839 -0.037937399 -0.171, + 0.044033099 -0.040756401 -0.191, + 0.046578299 -0.037815802 -0.171, + 0.047982302 -0.0360066 -0.171, + 0.044567399 -0.0401715 -0.171, + 0.042543601 -0.0423088 -0.171, + 0.044022799 -0.040746599 -0.171, + 0.0424264 -0.042386401 -0.168529, + 0.040174201 -0.044524699 -0.16857301, + 0.0404175 -0.044344399 -0.171, + 0.035878699 -0.0480907 -0.171, + 0.034765299 -0.048901699 -0.191, + 0.037811901 -0.046573199 -0.171, + 0.0378174 -0.046541199 -0.168614, + 0.038194101 -0.046273202 -0.171, + 0.0395981 -0.045055199 -0.171, + 0.035366699 -0.048327599 -0.16629399, + 0.0328326 -0.049915101 -0.164032, + 0.0302257 -0.051296201 -0.16182201, + 0.027557701 -0.052466702 -0.159659, + 0.0248404 -0.053423099 -0.157536, + 0.0220857 -0.054162201 -0.15544599, + 0.019305199 -0.054681499 -0.153384, + 0.0165099 -0.0549821 -0.151343, + 0.0137106 -0.055066999 -0.14931799, + 0.0109179 -0.054939602 -0.147306, + 0.0081428103 -0.054603901 -0.1453, + 0.0053973799 -0.0540656 -0.143298, + 0.00268824 -0.0533312 -0.141297, + 0 -0.052406799 -0.139293, + -0.00268824 -0.0533325 -0.141296, + -0.0053973799 -0.054067999 -0.143297, + -0.0081428103 -0.054607201 -0.145298, + -0.0109179 -0.054943699 -0.147302, + -0.0137106 -0.055071902 -0.149314, + -0.0165099 -0.054988202 -0.15133899, + -0.019305199 -0.0546894 -0.15338001, + -0.0220857 -0.0541729 -0.155443, + -0.0248404 -0.053437401 -0.157534, + -0.027557701 -0.052484602 -0.159659, + -0.0302257 -0.0513172 -0.161823, + -0.0328326 -0.0499373 -0.16403399, + -0.035366699 -0.0483477 -0.16629601, + -0.037813999 -0.0465759 -0.171, + -0.035726301 -0.048204001 -0.171, + -0.034765299 -0.048901699 -0.191, + -0.0353618 -0.048460599 -0.171, + -0.034755301 -0.048887499 -0.171, + -0.035366699 -0.0484416 -0.16865499, + -0.0328326 -0.050099101 -0.16636799, + -0.0302257 -0.051547099 -0.164133, + -0.027557701 -0.0527828 -0.161943, + -0.0248404 -0.0538042 -0.159794, + -0.0220857 -0.0546088 -0.15767799, + -0.019305199 -0.055195 -0.155589, + -0.0165099 -0.055563901 -0.153523, + -0.0137106 -0.055717502 -0.151473, + -0.0109179 -0.055658501 -0.149434, + -0.0081428103 -0.0553905 -0.147403, + -0.0053973799 -0.054919299 -0.145374, + -0.00268824 -0.054251 -0.143346, + 0 -0.053391799 -0.141314, + 0.00268824 -0.054249801 -0.143347, + 0.0053973799 -0.054917101 -0.145376, + 0.0081428103 -0.055387501 -0.147406, + 0.0109179 -0.0556546 -0.14943799, + 0.0137106 -0.055712398 -0.151476, + 0.0165099 -0.055557098 -0.15352599, + 0.019305199 -0.055185601 -0.15559199, + 0.0220857 -0.0545961 -0.15768, + 0.0248404 -0.053787999 -0.159794, + 0.027557701 -0.0527637 -0.161943, + 0.0302257 -0.051526699 -0.164131, + 0.0328326 -0.0500804 -0.166366, + 0.035366699 -0.048429102 -0.168653, + 0.035360001 -0.0484582 -0.171, + 0.033477101 -0.049792401 -0.171, + 0.034754898 -0.048886999 -0.171, + -0.033319298 -0.0498982 -0.171, + -0.029552899 -0.0522171 -0.191, + -0.032826498 -0.050209999 -0.171, + -0.029544 -0.052201401 -0.171, + -0.0302194 -0.051819 -0.171, + -0.0282706 -0.052922402 -0.171, + -0.027551601 -0.053284001 -0.171, + -0.0256411 -0.054245099 -0.171, + -0.027557701 -0.053268701 -0.168754, + 0.029552899 -0.0522171 -0.191, + 0.027550699 -0.053282399 -0.171, + 0.0240272 -0.054979 -0.191, + 0.028437899 -0.0528326 -0.171, + 0.027557701 -0.053259 -0.168753, + 0.0258127 -0.054163702 -0.171, + 0.0248338 -0.054601099 -0.171, + -0.019305199 -0.056685399 -0.166638, + -0.019305199 -0.056780402 -0.168826, + -0.0165099 -0.057558801 -0.166674, + -0.0165099 -0.0573969 -0.164492, + -0.0137106 -0.058125 -0.164537, + -0.0137106 -0.057895798 -0.16236199, + -0.0109179 -0.058481202 -0.16241001, + -0.0109179 -0.0581843 -0.16024201, + -0.0081428103 -0.058630198 -0.16028699, + -0.0081428103 -0.058265001 -0.158126, + -0.0053973799 -0.058576498 -0.15816499, + -0.0053973799 -0.0581421 -0.156011, + -0.00268824 -0.058324799 -0.156038, + -0.00268824 -0.057820398 -0.153892, + 0 -0.057879802 -0.15390199, + 0 -0.0573048 -0.151766, + 0.00268824 -0.057819299 -0.15389299, + 0.00268824 -0.058323398 -0.156038, + 0.0053973799 -0.058139499 -0.156012, + 0.0053973799 -0.058573399 -0.15816499, + 0.0081428103 -0.058260299 -0.15812699, + 0.0081428103 -0.058624901 -0.16028801, + 0.0109179 -0.058177199 -0.16024201, + 0.0109179 -0.058473699 -0.16241001, + 0.0137106 -0.057886299 -0.16236199, + 0.0137106 -0.058115698 -0.164536, + 0.0165099 -0.057385799 -0.164491, + 0.0165099 -0.057549398 -0.166673, + 0.019305199 -0.056674398 -0.166637, + 0.022079499 -0.055771399 -0.171, + 0.0231252 -0.055364501 -0.171, + 0.0220857 -0.055751201 -0.168804, + 0.020382199 -0.056432001 -0.171, + 0.019305199 -0.056773599 -0.168825, + 0.0165055 -0.0576673 -0.171, + 0.0175901 -0.0573637 -0.171, + 0.0165099 -0.057648201 -0.168843, + 0.018242801 -0.057145901 -0.171, + 0.0137106 -0.058279101 -0.166703, + 0.0109179 -0.058703002 -0.164572, + 0.0081428103 -0.0589214 -0.16244601, + 0.0053973799 -0.058938101 -0.16032, + 0.00268824 -0.058757398 -0.158188, + 0 -0.058384001 -0.156046, + -0.00268824 -0.058759 -0.158187, + -0.0053973799 -0.058941599 -0.160319, + -0.0081428103 -0.058927 -0.16244701, + -0.0109179 -0.0587104 -0.164573, + -0.0137106 -0.058286902 -0.166704, + -0.0165099 -0.057654001 -0.168844, + -0.018242201 -0.0571438 -0.171, + -0.019300301 -0.056794401 -0.171, + -0.0202034 -0.056496199 -0.171, + -0.0220857 -0.055759002 -0.168805, + -0.0248404 -0.054588001 -0.168781, + -0.0229499 -0.055437401 -0.171, + -0.0220857 -0.0556642 -0.166596, + -0.019305199 -0.056523599 -0.16443899, + -0.0165099 -0.057167601 -0.162302, + -0.0137106 -0.057598699 -0.160182, + -0.0109179 -0.057818901 -0.15807199, + -0.0081428103 -0.057830401 -0.155966, + -0.0053973799 -0.057637598 -0.153862, + -0.00268824 -0.0572454 -0.15175501, + 0 -0.056659698 -0.14963999, + 0.00268824 -0.057244401 -0.15175501, + 0.0053973799 -0.0576354 -0.153863, + 0.0081428103 -0.0578265 -0.155968, + 0.0109179 -0.057812601 -0.15807199, + 0.0137106 -0.057589799 -0.160182, + 0.0165099 -0.057156201 -0.162302, + 0.019305199 -0.056510501 -0.164437, + 0.0220857 -0.055651698 -0.166595, + 0.0248404 -0.054579299 -0.16878, + 0.0240207 -0.054964401 -0.171, + 0.0248404 -0.054479301 -0.166547, + 0.0220857 -0.055487499 -0.16437399, + 0.019305199 -0.056280799 -0.16223, + 0.0165099 -0.056859601 -0.160108, + 0.0137106 -0.057225201 -0.15800101, + 0.0109179 -0.057378799 -0.155904, + 0.0081428103 -0.057322498 -0.153813, + 0.0053973799 -0.057060599 -0.151722, + 0.00268824 -0.0565993 -0.149628, + 0 -0.055945002 -0.14752901, + -0.00268824 -0.056600198 -0.149628, + -0.0053973799 -0.0570626 -0.151721, + -0.0081428103 -0.057325799 -0.15381099, + -0.0109179 -0.0573841 -0.155902, + -0.0137106 -0.057232998 -0.15800001, + -0.0165099 -0.056870401 -0.160107, + -0.019305199 -0.056294199 -0.162231, + -0.0220857 -0.0555024 -0.16437601, + -0.0248404 -0.054493502 -0.166548, + -0.024834501 -0.0546025 -0.171, + -0.024020201 -0.054963201 -0.171, + -0.0240272 -0.054979 -0.191, + 0.0295441 -0.052201699 -0.171, + 0.0302184 -0.051817201 -0.171, + 0.032825101 -0.050207902 -0.171, + 0.0182469 -0.057158101 -0.191, + 0.0192999 -0.056793101 -0.171, + 0.0147556 -0.058157299 -0.171, + 0.0137106 -0.058377601 -0.16885801, + 0.0109179 -0.058866199 -0.16672701, + 0.0081428103 -0.059150599 -0.1646, + 0.0053973799 -0.0592345 -0.16247199, + 0.00268824 -0.059122201 -0.160338, + 0 -0.058818001 -0.158195, + -0.00268824 -0.0591239 -0.160338, + -0.0053973799 -0.0592383 -0.16247199, + -0.0081428103 -0.059156101 -0.1646, + -0.0109179 -0.058872402 -0.166728, + -0.0137106 -0.058382399 -0.168859, + -0.0137073 -0.058397699 -0.171, + -0.0122706 -0.058720101 -0.171, + -0.0145714 -0.058203701 -0.171, + -0.016505901 -0.057668701 -0.171, + -0.0182469 -0.057158101 -0.191, + -0.017408401 -0.057419099 -0.171, + -0.022080099 -0.055772699 -0.171, + 0.0030883299 0.059914999 -0.171, + 0.0053912699 0.059748899 -0.171, + 0.0030887299 0.0599204 -0.191, + 0.0053918599 0.059898701 -0.161851, + 0.032827701 0.0125 -0.049711999, + 0.0308851 0.0125 -0.050935, + 0.0328326 0.0130443 -0.049771, + 0.0302257 0.0130358 -0.051382001, + 0.035366699 0.0141446 -0.048549, + 0.036603201 0.0145808 -0.048050001, + 0.0378174 0.0141761 -0.046652999, + 0.035366699 0.0136245 -0.048215002, + 0.0328326 0.0136055 -0.049970999, + 0.034109399 0.0148698 -0.051778998, + 0.035366699 0.0149256 -0.050861999, + 0.034109399 0.0149234 -0.051313002, + 0.0328326 0.0148851 -0.051745001, + 0.0302257 0.0135881 -0.051584002, + 0.027557701 0.0135722 -0.053052999, + 0.0302257 0.0140887 -0.051927999, + 0.0328326 0.0141155 -0.050310001, + 0.031537499 0.0144993 -0.051584002, + 0.0302257 0.014481 -0.052377999, + 0.031537499 0.0147475 -0.052088, + 0.0328326 0.0147733 -0.051254001, + 0.034109399 0.0149201 -0.050870001, + 0.035366699 0.0149693 -0.050399002, + 0.036603201 0.0149836 -0.049910001, + 0.0378174 0.0149147 -0.050731, + 0.050219599 0.018087 -0.044202, + 0.048467699 0.017245701 -0.047047999, + 0.050219599 0.0182884 -0.045883, + 0.051830001 0.0192727 -0.04293, + 0.051830001 0.019545499 -0.044670001, + 0.0532961 0.0206751 -0.041632, + 0.0532961 0.021020601 -0.043455001, + 0.0546159 0.0222956 -0.040353999, + 0.0546159 0.0226993 -0.042277999, + 0.055787299 0.024116799 -0.039138999, + 0.055787299 0.024556801 -0.04118, + 0.056809202 0.026110601 -0.038026001, + 0.056809202 0.026562599 -0.040194001, + 0.0576833 0.028244101 -0.037046999, + 0.0576833 0.028680401 -0.039349001, + 0.058412101 0.0304782 -0.036231, + 0.058412101 0.0308709 -0.038663998, + 0.058998398 0.0327712 -0.035595, + 0.058998398 0.033091798 -0.038152002, + 0.059445001 0.035078499 -0.035151001, + 0.059445001 0.035302099 -0.037819002, + 0.059757002 0.037356898 -0.034901999, + 0.059757002 0.037460301 -0.037663002, + 0.0599402 0.0395675 -0.034841001, + 0.0599402 0.039533298 -0.037677001, + 0.059999999 0.041694898 -0.034935001, + 0.059999999 0.041506398 -0.037815999, + 0.0599402 0.043730199 -0.035133, + 0.0599402 0.043398298 -0.038113002, + 0.059757002 0.045694999 -0.035471998, + 0.059757002 0.045309801 -0.038601, + 0.059445001 0.0476905 -0.035994999, + 0.059445001 0.047260702 -0.039188001, + 0.058998398 0.049718201 -0.036626, + 0.058998398 0.049233001 -0.039893001, + 0.058412101 0.051754601 -0.037388999, + 0.058412101 0.0512073 -0.040727999, + 0.0576833 0.053780299 -0.038293999, + 0.0576833 0.053164698 -0.041703001, + 0.056809202 0.055776101 -0.039351001, + 0.056809202 0.055085599 -0.042826001, + 0.055787299 0.057721801 -0.040564999, + 0.055787299 0.056949601 -0.044101998, + 0.0546159 0.059596401 -0.04194, + 0.0546159 0.058735501 -0.045534998, + 0.0532961 0.0613777 -0.043481, + 0.0532961 0.060427401 -0.047125001, + 0.051830001 0.063048899 -0.045187, + 0.051830001 0.0620111 -0.048893999, + 0.050219599 0.064594798 -0.047076002, + 0.050219599 0.063460797 -0.050843999, + 0.048467699 0.065990098 -0.049146999, + 0.048467699 0.064754099 -0.052962001, + 0.0465803 0.067213602 -0.051387001, + 0.0465803 0.065870598 -0.055236001, + 0.044564299 0.068245098 -0.053783, + 0.044564299 0.0667907 -0.057652, + 0.0424264 0.069065303 -0.05632, + 0.0424264 0.067495197 -0.060196001, + 0.040174201 0.069656402 -0.058983002, + 0.040174201 0.0679674 -0.062852003, + 0.0378174 0.070004404 -0.061755002, + 0.0378174 0.066612303 -0.069649003, + 0.035366699 0.068514504 -0.068706997, + 0.035366699 0.065363303 -0.076817997, + 0.0328326 0.067125402 -0.076020002, + 0.0328326 0.064224102 -0.084325999, + 0.0302257 0.065841503 -0.083662003, + 0.0302257 0.063198403 -0.092142001, + 0.027557701 0.064669199 -0.091600001, + 0.027557701 0.062291801 -0.100235, + 0.0248404 0.063614801 -0.099802002, + 0.0248404 0.061509401 -0.10857, + 0.0220857 0.062683001 -0.108235, + 0.0220857 0.060853701 -0.117116, + 0.019305199 0.061877001 -0.116866, + 0.019305199 0.060327001 -0.12583899, + 0.0165099 0.0612019 -0.125661, + 0.0165099 0.059934098 -0.134707, + 0.0137106 0.060663201 -0.134588, + 0.0137106 0.059679098 -0.14368699, + 0.0109179 0.0602649 -0.14361501, + 0.0109179 0.059563 -0.15275, + 0.0081421202 0.060008701 -0.152713, + 0.0081421202 0.0595873 -0.161864, + 0.0109179 0.059141502 -0.161882, + 0.0092316195 0.0592747 -0.171, + 0.0137106 0.0589775 -0.152798, + 0.0165099 0.058950499 -0.143777, + 0.019305199 0.059059601 -0.13485, + 0.0220857 0.0593041 -0.126048, + 0.0248404 0.0596806 -0.117403, + 0.027557701 0.060187001 -0.108948, + 0.0302257 0.060821999 -0.100715, + 0.0328326 0.061582599 -0.092738003, + 0.035366699 0.062464502 -0.085047998, + 0.0378174 0.063464798 -0.077676997, + 0.040174201 0.0645805 -0.070656002, + 0.0424264 0.065807402 -0.064015999, + 0.044564299 0.065218396 -0.061473001, + 0.0465803 0.0644105 -0.059044998, + 0.048467699 0.063401498 -0.056745999, + 0.050219599 0.062210899 -0.054590002, + 0.051830001 0.060858801 -0.052588999, + 0.0532961 0.0593668 -0.050755002, + 0.0546159 0.057757501 -0.049098998, + 0.055787299 0.056056902 -0.047616001, + 0.056809202 0.054278102 -0.046282999, + 0.0576833 0.052435402 -0.045099001, + 0.058412101 0.0505495 -0.044059001, + 0.058998398 0.0486404 -0.043156002, + 0.059445001 0.0467274 -0.042381, + 0.059757002 0.044829398 -0.041724, + 0.0599402 0.042960599 -0.041173, + 0.059999999 0.0411194 -0.040732998, + 0.0599402 0.039282601 -0.040498, + 0.059757002 0.037354901 -0.040440999, + 0.059445001 0.035324801 -0.040523, + 0.058998398 0.033225201 -0.040766999, + 0.058412101 0.0310924 -0.041173, + 0.0576833 0.0289662 -0.04174, + 0.056809202 0.026885301 -0.042461999, + 0.055787299 0.02489 -0.043324001, + 0.0546159 0.023017401 -0.044305, + 0.0532961 0.0213011 -0.045375001, + 0.051830001 0.0197687 -0.046500001, + 0.050219599 0.0184418 -0.04764, + 0.048467699 0.0173316 -0.048753999, + 0.0465803 0.016432 -0.049800999, + 0.0465803 0.0164262 -0.048126999, + 0.044564299 0.015748801 -0.050742999, + 0.044564299 0.0158043 -0.049079999, + 0.0424264 0.0152575 -0.051543999, + 0.0424264 0.0153326 -0.049839001, + 0.040174201 0.0149118 -0.052142002, + 0.040174201 0.0150445 -0.050388999, + 0.0378174 0.0147386 -0.052526999, + 0.035366699 0.0147127 -0.052701, + 0.0328326 0.0148161 -0.052661002, + 0.0328326 0.0148792 -0.052189998, + 0.031537499 0.0148516 -0.052583002, + 0.0302257 0.0147964 -0.053837001, + 0.0302257 0.0147229 -0.052886002, + 0.0288986 0.0144635 -0.053135, + 0.027557701 0.0140643 -0.053401001, + 0.0248404 0.0135579 -0.054375999, + 0.0220857 0.0140229 -0.055902999, + 0.023467001 0.0144023 -0.055796999, + 0.0248404 0.0140423 -0.054726001, + 0.0220857 0.0135453 -0.055548999, + 0.019305199 0.0135342 -0.056573, + 0.0165099 0.0130058 -0.057241, + 0.019305199 0.0130102 -0.056366, + 0.017272299 0.0125 -0.056960002, + 0.0220806 0.0125 -0.055273999, + 0.0200695 0.0125 -0.056044001, + 0.0220857 0.0130154 -0.055342998, + 0.019710001 0.0125 -0.056162, + 0.0262044 0.0144312 -0.054540999, + 0.0288986 0.0147889 -0.05415, + 0.0302257 0.0148195 -0.053385001, + 0.0288986 0.0146994 -0.053647999, + 0.027557701 0.0146771 -0.054372001, + 0.027557701 0.0144469 -0.053856999, + 0.027557701 0.014721 -0.055335999, + 0.0302257 0.0147153 -0.054313999, + 0.0328326 0.0145253 -0.054529, + 0.035366699 0.0144523 -0.054529, + 0.0378174 0.0145149 -0.054313999, + 0.040174201 0.0147384 -0.053881999, + 0.0424264 0.0151014 -0.053243, + 0.044564299 0.0156496 -0.052448001, + 0.0465803 0.0164063 -0.05153, + 0.048467699 0.0173689 -0.050526001, + 0.050219599 0.018545499 -0.049474999, + 0.051830001 0.019928301 -0.048416, + 0.0532961 0.0214989 -0.047387999, + 0.0546159 0.023233 -0.046425, + 0.055787299 0.0250997 -0.045558002, + 0.056809202 0.0270642 -0.044810999, + 0.0576833 0.0290883 -0.044199999, + 0.058412101 0.031135101 -0.043733999, + 0.058998398 0.033166401 -0.043414, + 0.059445001 0.035147399 -0.043241002, + 0.059757002 0.0370415 -0.043202002, + 0.0599402 0.038840398 -0.043352999, + 0.059999999 0.040629499 -0.043724999, + 0.0599402 0.0424302 -0.044225, + 0.059757002 0.044248499 -0.044842999, + 0.059445001 0.046089798 -0.045568001, + 0.058998398 0.0479405 -0.046409, + 0.058412101 0.0497812 -0.047375999, + 0.0576833 0.051592302 -0.048475999, + 0.056809202 0.053353298 -0.049717002, + 0.055787299 0.055050801 -0.051100001, + 0.0546159 0.056673799 -0.052650999, + 0.0532961 0.0581959 -0.054375, + 0.051830001 0.059594698 -0.056263998, + 0.050219599 0.060848299 -0.058308002, + 0.048467699 0.061935298 -0.060493, + 0.0465803 0.062835999 -0.062808998, + 0.044564299 0.063531898 -0.065241002, + 0.0424264 0.0624259 -0.071723998, + 0.040174201 0.061436899 -0.078594998, + 0.0378174 0.060568701 -0.085826002, + 0.035366699 0.059824798 -0.093385004, + 0.0328326 0.059207398 -0.101242, + 0.0302257 0.0587181 -0.109367, + 0.027557701 0.0583588 -0.117726, + 0.0248404 0.0581314 -0.126287, + 0.0220857 0.058037199 -0.13501699, + 0.019305199 0.058076601 -0.143884, + 0.0165099 0.058249399 -0.15285701, + 0.0137106 0.058556002 -0.161906, + 0.0116065 0.058866698 -0.171, + 0.0137075 0.058398601 -0.171, + 0.0152803 0.058021698 -0.191, + 0.0144795 0.058226701 -0.171, + 0.0152764 0.058007602 -0.171, + 0.016506201 0.057669599 -0.171, + 0.0165099 0.057827901 -0.161936, + 0.019305199 0.0573759 -0.15292899, + 0.0220857 0.057054799 -0.14400899, + 0.0248404 0.0568651 -0.135208, + 0.027557701 0.0568102 -0.12655599, + 0.0302257 0.056890398 -0.118086, + 0.0328326 0.057104401 -0.109828, + 0.035366699 0.057450902 -0.101816, + 0.0378174 0.057930999 -0.094081998, + 0.040174201 0.058543701 -0.086657003, + 0.0424264 0.059286401 -0.079568997, + 0.044564299 0.060155999 -0.072848, + 0.0465803 0.0611507 -0.066523001, + 0.048467699 0.060358599 -0.064199001, + 0.050219599 0.059376001 -0.061990999, + 0.051830001 0.058221798 -0.059914, + 0.0532961 0.056917202 -0.057978, + 0.0546159 0.0554839 -0.056194998, + 0.055787299 0.053943601 -0.054572001, + 0.056809202 0.0523188 -0.053119998, + 0.0576833 0.0506352 -0.051828999, + 0.058412101 0.048902601 -0.050673001, + 0.058998398 0.047133502 -0.049647, + 0.059445001 0.045348 -0.048744999, + 0.059757002 0.043566398 -0.047954999, + 0.0599402 0.041802399 -0.047272, + 0.059999999 0.040049698 -0.046707001, + 0.0599402 0.038298398 -0.046278, + 0.059757002 0.036543801 -0.045993999, + 0.059445001 0.034770399 -0.045940999, + 0.058998398 0.032916099 -0.046071999, + 0.058412101 0.030994199 -0.046323001, + 0.0576833 0.029039999 -0.046707999, + 0.056809202 0.0270872 -0.047224, + 0.055787299 0.025172301 -0.047867, + 0.0546159 0.0233307 -0.048625998, + 0.0532961 0.021598499 -0.049484, + 0.051830001 0.020008 -0.050414, + 0.050219599 0.0185869 -0.051387001, + 0.048467699 0.017356399 -0.052367002, + 0.0465803 0.0163313 -0.053316999, + 0.044564299 0.0155165 -0.054200001, + 0.0424264 0.0149018 -0.054977998, + 0.040174201 0.014487 -0.055615999, + 0.0378174 0.0142489 -0.056088001, + 0.035366699 0.0141434 -0.056347001, + 0.0328326 0.0141865 -0.056387, + 0.0302257 0.014353 -0.05621, + 0.027557701 0.0146237 -0.055819001, + 0.0248404 0.0146531 -0.056685001, + 0.0248404 0.0147061 -0.056221001, + 0.023467001 0.0146171 -0.056322001, + 0.0220857 0.0146585 -0.057413999, + 0.027557701 0.0147598 -0.054878, + 0.0262044 0.0146559 -0.055059999, + 0.0248404 0.0144163 -0.055188, + 0.0248404 0.0146359 -0.055709999, + 0.0220857 0.0143891 -0.056368999, + 0.019305199 0.0140059 -0.056930002, + 0.0165099 0.0135248 -0.057449002, + 0.0137106 0.0130023 -0.057971001, + 0.0144335 0.0125 -0.057737999, + 0.0137785 0.0125 -0.057882998, + 0.016506299 0.0125 -0.05717, + 0.0197125 0.0074999998 -0.056169, + 0.0193008 0.0125 -0.056295998, + 0.0228185 0.0125 -0.054992002, + 0.0248404 0.0130214 -0.054171, + 0.027557701 0.0130282 -0.052850001, + 0.034109399 0.0145384 -0.049887002, + 0.0390082 0.0151058 -0.047906, + 0.0378174 0.0150437 -0.048925001, + 0.040174201 0.0151304 -0.048627, + 0.0378174 0.0150665 -0.048470002, + 0.036603201 0.0150171 -0.049451001, + 0.036603201 0.0149944 -0.049017001, + 0.035366699 0.0149566 -0.049961001, + 0.035366699 0.0148281 -0.049477998, + 0.034109399 0.0148002 -0.050384, + 0.0328326 0.0145184 -0.050753001, + 0.0424264 0.0153689 -0.048122, + 0.044564299 0.015776001 -0.047412999, + 0.0465803 0.0163766 -0.046502002, + 0.048467699 0.0171306 -0.045407001, + 0.050219599 0.017970899 -0.043388002, + 0.051830001 0.018952601 -0.041274, + 0.0532961 0.02028 -0.039907001, + 0.0546159 0.0218256 -0.038536999, + 0.055787299 0.023588199 -0.037209999, + 0.056809202 0.025547501 -0.035969999, + 0.0576833 0.027672799 -0.034853999, + 0.058412101 0.029928001 -0.033895999, + 0.058998398 0.032271702 -0.033121001, + 0.059445001 0.034659501 -0.032545, + 0.059757002 0.0370441 -0.032180998, + 0.0599402 0.039384499 -0.032024, + 0.059999999 0.041658498 -0.03204, + 0.0599402 0.043856502 -0.032193001, + 0.059757002 0.0459713 -0.032428999, + 0.059445001 0.048022401 -0.032795999, + 0.058998398 0.050096899 -0.033360001, + 0.058412101 0.052191399 -0.034047, + 0.0576833 0.0542823 -0.034878999, + 0.056809202 0.056349698 -0.035863999, + 0.055787299 0.058373701 -0.037011001, + 0.0546159 0.060333699 -0.038323998, + 0.0532961 0.0622073 -0.039808001, + 0.051830001 0.063971996 -0.041464999, + 0.050219599 0.065610297 -0.043292999, + 0.048467699 0.0671065 -0.045308001, + 0.0465803 0.068436198 -0.047506001, + 0.044564299 0.0695787 -0.049872998, + 0.0424264 0.070514299 -0.052395001, + 0.040174201 0.071224503 -0.055055998, + 0.0378174 0.071694396 -0.057840001, + 0.035366699 0.071911298 -0.060727999, + 0.0328326 0.070280097 -0.067832001, + 0.0302257 0.068745099 -0.075286001, + 0.027557701 0.067313902 -0.083058, + 0.0248404 0.065993197 -0.091113001, + 0.0220857 0.064788997 -0.099417999, + 0.019305199 0.063706599 -0.107943, + 0.0165099 0.062752202 -0.116651, + 0.0137106 0.061931401 -0.125512, + 0.0109179 0.061249401 -0.13449199, + 0.0081421202 0.060711 -0.14356101, + 0.0053918599 0.060320001 -0.152688, + 0.00267513 0.060081098 -0.161844, + 0.0028477299 0.0599324 -0.171, + 0.0026750399 0.0599363 -0.171, + -5.2000001e-008 0.0599977 -0.171, + -0.019300099 0.056793701 -0.171, + -0.019305199 0.056943499 -0.161973, + -0.0174994 0.057391401 -0.171, + -0.020292999 0.056464098 -0.171, + -0.021165101 0.056143001 -0.191, + -0.0165057 0.0576679 -0.171, + -0.0152803 0.058021698 -0.191, + -0.050219599 0.0329559 -0.16295899, + -0.048467699 0.0354908 -0.162855, + -0.049775898 0.033491299 -0.171, + -0.050219599 0.033367101 -0.154893, + -0.0424264 0.042552799 -0.16256499, + -0.042476799 0.042376 -0.171, + -0.044564299 0.040299799 -0.16265699, + -0.044564299 0.040713102 -0.154292, + -0.058998398 0.0356455 -0.078063004, + -0.058998398 0.033975799 -0.081159003, + -0.059445001 0.034444898 -0.076586001, + -0.058412101 0.036797401 -0.079640001, + -0.058412101 0.033473201 -0.086052001, + -0.0576833 0.036294799 -0.084655002, + -0.0576833 0.033192199 -0.091352001, + -0.056809202 0.0360047 -0.09008, + -0.056809202 0.033139098 -0.097043999, + -0.055787299 0.0359331 -0.095899001, + -0.055787299 0.033316799 -0.10311, + -0.0546159 0.036082301 -0.102093, + -0.0546159 0.033726402 -0.109531, + -0.0532961 0.036452301 -0.108642, + -0.0532961 0.034366101 -0.116287, + -0.051830001 0.0370409 -0.115525, + -0.051830001 0.035227802 -0.123356, + -0.050219599 0.037840098 -0.122718, + -0.050219599 0.036302298 -0.130715, + -0.048467699 0.038840499 -0.130199, + -0.048467699 0.037580099 -0.13834, + -0.0465803 0.040033799 -0.137941, + -0.0465803 0.039053001 -0.146208, + -0.044564299 0.041411899 -0.145919, + -0.0424264 0.042966899 -0.154107, + -0.040174201 0.044691499 -0.162477, + -0.0418665 0.042958502 -0.171, + -0.040347401 0.044408198 -0.171, + -0.040171102 0.044560701 -0.171, + -0.038121 0.046333499 -0.171, + -0.037236601 0.047047202 -0.191, + -0.0378129 0.046574499 -0.171, + -0.058998398 0.038776401 -0.071811996, + -0.058998398 0.037247501 -0.074946001, + -0.059445001 0.037443601 -0.070449002, + -0.058412101 0.0400679 -0.073294997, + -0.058412101 0.038468499 -0.076479003, + -0.0576833 0.041298401 -0.074891999, + -0.0576833 0.0396256 -0.078116, + -0.056809202 0.042449798 -0.076595001, + -0.056809202 0.0391124 -0.083259001, + -0.055787299 0.041914999 -0.081871003, + -0.055787299 0.0388024 -0.088813998, + -0.0546159 0.041574199 -0.087559998, + -0.0546159 0.0387013 -0.094764002, + -0.0532961 0.0414318 -0.093644999, + -0.0532961 0.038810201 -0.10109, + -0.051830001 0.0414887 -0.100105, + -0.051830001 0.0391289 -0.107769, + -0.050219599 0.041744102 -0.106916, + -0.050219599 0.039654601 -0.11478, + -0.048467699 0.042195398 -0.114056, + -0.048467699 0.040379498 -0.122099, + -0.0465803 0.042835299 -0.1215, + -0.0465803 0.041295201 -0.12970001, + -0.044564299 0.043655802 -0.12921999, + -0.044564299 0.042393502 -0.137557, + -0.0424264 0.044648599 -0.137189, + -0.0424264 0.043666299 -0.145643, + -0.040174201 0.045806199 -0.145382, + -0.040174201 0.045106299 -0.15393201, + -0.0378174 0.047123801 -0.153767, + -0.0378174 0.046708401 -0.162394, + -0.035366699 0.048596699 -0.16231599, + -0.037225999 0.047033701 -0.171, + -0.0358027 0.048147298 -0.171, + -0.035360798 0.048459399 -0.171, + -0.0322018 0.050626501 -0.191, + -0.033398401 0.0498452 -0.171, + -0.032825802 0.0502089 -0.171, + -0.059757002 0.034688599 -0.072213002, + -0.059757002 0.036089402 -0.069210999, + -0.0599402 0.034727901 -0.068103001, + -0.059999999 0.033354599 -0.067146003, + -0.059999999 0.0320637 -0.069977999, + -0.0599402 0.0319723 -0.066338003, + -0.0599402 0.031970002 -0.073953003, + -0.059757002 0.031672198 -0.078208998, + -0.059445001 0.0311721 -0.082668997, + -0.058998398 0.030658299 -0.087445997, + -0.058412101 0.030375499 -0.092625998, + -0.0576833 0.0303303 -0.098195001, + -0.056809202 0.0305255 -0.104136, + -0.055787299 0.030963 -0.110432, + -0.0546159 0.0316418 -0.117063, + -0.0532961 0.032554299 -0.124008, + -0.051830001 0.033691201 -0.131246, + -0.050219599 0.0350428 -0.138754, + -0.048467699 0.036600001 -0.14650799, + -0.0465803 0.0383549 -0.154485, + -0.044562999 0.040173098 -0.171, + -0.0460645 0.0384284 -0.171, + -0.0465803 0.037942301 -0.162754, + -0.048467699 0.035902701 -0.15468501, + -0.050219599 0.0340636 -0.146819, + -0.051830001 0.032432798 -0.13917901, + -0.0532961 0.0310189 -0.131789, + -0.0546159 0.029831599 -0.124673, + -0.055787299 0.028880101 -0.11785, + -0.056809202 0.028173801 -0.111342, + -0.0576833 0.027719401 -0.105168, + -0.058412101 0.027517401 -0.099348001, + -0.058998398 0.027565699 -0.093897, + -0.059445001 0.0278612 -0.088831998, + -0.059757002 0.0283983 -0.084163003, + -0.0599402 0.0289362 -0.079810001, + -0.059999999 0.029272299 -0.075680003, + -0.0599402 0.029399499 -0.071854003, + -0.059757002 0.029338101 -0.068384998, + -0.059757002 0.030550901 -0.065667003, + -0.059445001 0.027913 -0.067821003, + -0.059445001 0.029072899 -0.06515, + -0.058998398 0.026441799 -0.067406997, + -0.058998398 0.027556 -0.064785004, + -0.058412101 0.024947001 -0.067135997, + -0.058412101 0.0260214 -0.064563997, + -0.0576833 0.0234483 -0.066997997, + -0.0576833 0.024487801 -0.064478002, + -0.056809202 0.021963799 -0.066983998, + -0.056809202 0.0229732 -0.064515002, + -0.055787299 0.021495201 -0.064666003, + -0.055787299 0.0205108 -0.067082003, + -0.0546159 0.0200729 -0.064926997, + -0.055787299 0.0194532 -0.069476999, + -0.056809202 0.020879 -0.069427997, + -0.0576833 0.0223318 -0.069490999, + -0.058412101 0.023793999 -0.069678001, + -0.058998398 0.0252467 -0.069998004, + -0.059445001 0.0266685 -0.070459999, + -0.059757002 0.026714601 -0.073743001, + -0.0599402 0.0265746 -0.077407002, + -0.059999999 0.0262213 -0.081399001, + -0.0599402 0.0256612 -0.085637003, + -0.059757002 0.025094001 -0.090203002, + -0.059445001 0.0247736 -0.09516, + -0.058998398 0.024711199 -0.100498, + -0.058412101 0.0249092 -0.106202, + -0.0576833 0.025369801 -0.112256, + -0.056809202 0.026092701 -0.118644, + -0.055787299 0.027071301 -0.125346, + -0.0546159 0.0282974 -0.13234299, + -0.0532961 0.029761599 -0.139614, + -0.051830001 0.0314545 -0.147138, + -0.048232201 0.0356883 -0.171, + -0.046576701 0.037814599 -0.171, + -0.0460728 0.038435601 -0.191, + -0.046423901 0.038010798 -0.171, + -0.044503901 0.0402418 -0.171, + -0.041876599 0.0429691 -0.191, + -0.0424252 0.0424252 -0.171, + -0.028354499 0.0528774 -0.171, + -0.0275511 0.0532832 -0.171, + -0.026825599 0.053669199 -0.191, + -0.030218899 0.051817998 -0.171, + -0.0302257 0.0519608 -0.16217799, + -0.030913601 0.051423199 -0.171, + -0.0248341 0.054601699 -0.171, + -0.025727101 0.054204401 -0.171, + -0.027557701 0.053427801 -0.162118, + -0.0302257 0.052377898 -0.153337, + -0.0328326 0.050766099 -0.153469, + -0.0328326 0.051467601 -0.14468899, + -0.035366699 0.049713701 -0.144904, + -0.035366699 0.0506979 -0.136205, + -0.0378174 0.048808001 -0.136512, + -0.0378174 0.0500727 -0.12791499, + -0.040174201 0.048053201 -0.128326, + -0.040174201 0.049596399 -0.119851, + -0.0424264 0.047454 -0.120373, + -0.0424264 0.0492737 -0.11204, + -0.044564299 0.047015399 -0.112684, + -0.044564299 0.0491096 -0.104515, + -0.0465803 0.0467452 -0.105286, + -0.0465803 0.049110699 -0.097301997, + -0.048467699 0.046650201 -0.098206997, + -0.048467699 0.049279399 -0.090429001, + -0.050219599 0.046732701 -0.091472998, + -0.050219599 0.049616098 -0.083922997, + -0.051830001 0.046992902 -0.085109003, + -0.051830001 0.050119899 -0.077807002, + -0.0532961 0.047430601 -0.079139002, + -0.0532961 0.0507874 -0.072104998, + -0.0546159 0.0480421 -0.073583998, + -0.0546159 0.049719401 -0.070168003, + -0.055787299 0.046934702 -0.071730003, + -0.055787299 0.048526101 -0.068343997, + -0.056809202 0.0457181 -0.069987997, + -0.056809202 0.047226399 -0.066643, + -0.0576833 0.044410199 -0.068365999, + -0.0576833 0.045839999 -0.065073997, + -0.058412101 0.043030798 -0.066872001, + -0.058412101 0.044386201 -0.063644998, + -0.058998398 0.041599002 -0.065514997, + -0.058998398 0.042883899 -0.062362999, + -0.059445001 0.0401337 -0.064297996, + -0.059445001 0.041355301 -0.061230998, + -0.059757002 0.038657699 -0.063225001, + -0.059757002 0.039834399 -0.060228001, + -0.0599402 0.037200101 -0.062275, + -0.0599402 0.038319599 -0.059323002, + -0.059999999 0.035736699 -0.061432, + -0.059999999 0.036793001 -0.058527999, + -0.0599402 0.034244299 -0.060713999, + -0.0599402 0.0352441 -0.057859998, + -0.059757002 0.032713301 -0.060139999, + -0.059757002 0.033662301 -0.057337001, + -0.059445001 0.031138901 -0.059723999, + -0.059445001 0.032042701 -0.056976002, + -0.058998398 0.0295371 -0.059464, + -0.058998398 0.030401099 -0.056770001, + -0.058412101 0.0279279 -0.059349, + -0.058412101 0.028758001 -0.056713998, + -0.0576833 0.0263304 -0.059372, + -0.0576833 0.0271353 -0.056807, + -0.056809202 0.024765501 -0.059531, + -0.056809202 0.0255461 -0.057082001, + -0.055787299 0.023245901 -0.059857, + -0.055787299 0.0239511 -0.057461001, + -0.0546159 0.021735899 -0.060270999, + -0.0546159 0.022358401 -0.057909001, + -0.0532961 0.0202446 -0.060740001, + -0.0532961 0.020796901 -0.058432002, + -0.051830001 0.0187997 -0.061266001, + -0.051830001 0.019294599 -0.059018001, + -0.050219599 0.0174278 -0.061838001, + -0.050219599 0.0178826 -0.059656002, + -0.048467699 0.0161577 -0.062440999, + -0.048467699 0.016589699 -0.060327001, + -0.0465803 0.0150153 -0.063056998, + -0.0465803 0.0154416 -0.061009999, + -0.044564299 0.0140235 -0.063662998, + -0.044564299 0.0144589 -0.061677001, + -0.0424264 0.0132 -0.064232998, + -0.0424264 0.0136571 -0.062298, + -0.040174201 0.0125568 -0.064736001, + -0.040174201 0.0130443 -0.062841997, + -0.0378174 0.0120982 -0.065144002, + -0.0378174 0.0126208 -0.063277997, + -0.035366699 0.0118217 -0.065429002, + -0.035366699 0.0123811 -0.063579001, + -0.0328326 0.0117198 -0.065564997, + -0.0328326 0.0123169 -0.063720003, + -0.0302257 0.0117821 -0.065528996, + -0.0302257 0.012411 -0.063677996, + -0.027557701 0.0119889 -0.065306, + -0.027557701 0.0126183 -0.063433997, + -0.0248404 0.0122979 -0.064878002, + -0.0248404 0.012933 -0.062969998, + -0.0220857 0.0127024 -0.064231999, + -0.0220857 0.0133432 -0.062291, + -0.019305199 0.013188 -0.063375004, + -0.019305199 0.0138214 -0.061407, + -0.0165099 0.0137277 -0.062318999, + -0.0165099 0.0143509 -0.060322002, + -0.0137106 0.0143051 -0.061069999, + -0.0137106 0.0144604 -0.060566999, + -0.0109179 0.0144299 -0.061166, + -0.0109179 0.0145324 -0.060683001, + -0.0081428103 0.0145136 -0.061138, + -0.0081428103 0.0144895 -0.060600001, + -0.0053973799 0.0144791 -0.060917001, + -0.0053973799 0.0142993 -0.060366999, + -0.00268824 0.0142947 -0.060552999, + -0.00268824 0.0139542 -0.060070001, + 0 0.0135 -0.059767999, + 0.00268824 0.0135006 -0.059709001, + 0.0053973799 0.013957 -0.059888002, + 0.0081428103 0.014305 -0.060056001, + 0.0109179 0.0145001 -0.060151, + 0.0137106 0.0145522 -0.060086999, + 0.0165099 0.0144956 -0.059822001, + 0.019305199 0.0144041 -0.059425998, + 0.0220857 0.0139296 -0.060339998, + 0.0248404 0.0135196 -0.061048999, + 0.027557701 0.0131929 -0.061547998, + 0.0302257 0.0129742 -0.061829999, + 0.0328326 0.0128619 -0.061893001, + 0.035366699 0.0128961 -0.061763, + 0.0378174 0.0130976 -0.061457001, + 0.040174201 0.0134748 -0.061000999, + 0.0424264 0.014044 -0.060423002, + 0.044564299 0.0148094 -0.059753001, + 0.0465803 0.0157657 -0.059025999, + 0.048467699 0.0169014 -0.058274001, + 0.050219599 0.018198499 -0.057526998, + 0.051830001 0.019633999 -0.056811001, + 0.0532961 0.0211796 -0.056148998, + 0.0546159 0.0228057 -0.055558, + 0.055787299 0.0244803 -0.055048, + 0.056809202 0.0261722 -0.054627001, + 0.0576833 0.027848899 -0.054290999, + 0.058412101 0.0294965 -0.054095998, + 0.058412101 0.028740801 -0.056742001, + 0.058998398 0.031162299 -0.054090001, + 0.058998398 0.030381501 -0.056788001, + 0.059445001 0.032838799 -0.054226, + 0.059445001 0.032023199 -0.056983002, + 0.059757002 0.034502 -0.054522, + 0.059757002 0.033644799 -0.05734, + 0.0599402 0.036134701 -0.054984, + 0.0599402 0.035229798 -0.057859998, + 0.059999999 0.037741099 -0.055597, + 0.059999999 0.036782298 -0.058527, + 0.0599402 0.039331 -0.056340002, + 0.0599402 0.0383122 -0.059321001, + 0.059757002 0.040915199 -0.057195999, + 0.059757002 0.039829802 -0.060226999, + 0.059445001 0.042499401 -0.058152001, + 0.059445001 0.041351099 -0.061228, + 0.058998398 0.044077799 -0.059211999, + 0.058998398 0.042875402 -0.062362, + 0.058412101 0.045643099 -0.060414001, + 0.058412101 0.044375502 -0.063646004, + 0.0576833 0.047169499 -0.061772, + 0.0576833 0.045830399 -0.065076001, + 0.056809202 0.048635501 -0.063280001, + 0.056809202 0.047219399 -0.066643998, + 0.055787299 0.050020698 -0.064930998, + 0.055787299 0.0485221 -0.068343997, + 0.0546159 0.051304199 -0.066716, + 0.0546159 0.049717601 -0.070168003, + 0.0532961 0.0524645 -0.068627, + 0.0532961 0.0507848 -0.072105996, + 0.051830001 0.053480402 -0.070653997, + 0.051830001 0.050129201 -0.077816002, + 0.050219599 0.052756701 -0.076513998, + 0.050219599 0.049635399 -0.083936997, + 0.048467699 0.052184701 -0.082782999, + 0.048467699 0.0493044 -0.090447001, + 0.0465803 0.051766299 -0.089437, + 0.0465803 0.049137499 -0.097319998, + 0.044564299 0.0515026 -0.096449003, + 0.044564299 0.049134798 -0.104532, + 0.0424264 0.0513932 -0.103795, + 0.0424264 0.049294502 -0.112056, + 0.040174201 0.051437002 -0.111445, + 0.040174201 0.049612701 -0.119865, + 0.0378174 0.051632099 -0.119371, + 0.0378174 0.0500862 -0.12792601, + 0.035366699 0.051975999 -0.12754101, + 0.035366699 0.050712399 -0.13621201, + 0.0328326 0.0524657 -0.13592599, + 0.0328326 0.051486399 -0.144692, + 0.0302257 0.0530972 -0.144495, + 0.0302257 0.052398901 -0.153336, + 0.027557701 0.053864501 -0.153216, + 0.059999999 0.0357293 -0.061430998, + 0.0599402 0.0342336 -0.060713001, + 0.059757002 0.0326989 -0.060139, + 0.059445001 0.031121399 -0.059726, + 0.058998398 0.029517701 -0.059471998, + 0.058412101 0.0279085 -0.059365999, + 0.0576833 0.0263134 -0.059399001, + 0.0576833 0.025429601 -0.061951, + 0.058412101 0.0269963 -0.061976001, + 0.058998398 0.0285709 -0.062139001, + 0.059445001 0.030134199 -0.062449999, + 0.059757002 0.031665102 -0.062916003, + 0.0599402 0.033146501 -0.063539997, + 0.059999999 0.034581602 -0.064305, + 0.0599402 0.034719199 -0.068103001, + 0.059757002 0.034678601 -0.072214, + 0.058998398 0.037243299 -0.074946001, + 0.058412101 0.038466699 -0.076479003, + 0.0576833 0.039622799 -0.078116998, + 0.056809202 0.0391226 -0.083268002, + 0.055787299 0.038823798 -0.088830002, + 0.0546159 0.0387295 -0.094783999, + 0.0532961 0.038840901 -0.10111, + 0.051830001 0.039158098 -0.107789, + 0.050219599 0.039679199 -0.114799, + 0.048467699 0.040399 -0.122116, + 0.0465803 0.041311901 -0.129714, + 0.044564299 0.0424118 -0.137566, + 0.0424264 0.0436906 -0.145647, + 0.040174201 0.045134101 -0.15393101, + 0.0378174 0.0467299 -0.16239101, + 0.0372269 0.0470348 -0.171, + 0.037815198 0.046577401 -0.171, + 0.037236601 0.047047202 -0.191, + 0.030220101 0.051820099 -0.171, + 0.024834899 0.054603402 -0.171, + 0.035362698 0.048462 -0.171, + 0.041876599 0.0429691 -0.191, + 0.0402066 0.0445357 -0.171, + 0.042342398 0.0425102 -0.171, + 0.042424399 0.0424245 -0.171, + 0.044376299 0.040382501 -0.171, + -0.0165099 0.0130553 -0.064301997, + -0.019305199 0.0125013 -0.065333001, + -0.0220857 0.0120134 -0.066159002, + -0.0248404 0.0116088 -0.066771001, + -0.027557701 0.0112952 -0.067175999, + -0.0302257 0.011112 -0.067390002, + -0.0328326 0.01108 -0.067424998, + -0.035366699 0.0112125 -0.067298003, + -0.0378174 0.0115192 -0.067033999, + -0.040174201 0.0120049 -0.066659003, + -0.0424264 0.0126682 -0.066198997, + -0.044564299 0.0135013 -0.065682001, + -0.0465803 0.0144896 -0.065133996, + -0.048467699 0.015613 -0.064579003, + -0.050219599 0.0168481 -0.064035997, + -0.051830001 0.018169001 -0.063519999, + -0.0532961 0.0195508 -0.063042998, + -0.0546159 0.020966999 -0.062605999, + -0.055787299 0.022408299 -0.062240999, + -0.056809202 0.0239064 -0.062026002, + -0.0576833 0.025448799 -0.061934002, + -0.058412101 0.0270155 -0.061967999, + -0.058998398 0.0285882 -0.062137, + -0.059445001 0.030148501 -0.062449999, + -0.059757002 0.031675801 -0.062917002, + -0.0599402 0.033153798 -0.063541003, + -0.059999999 0.034586199 -0.064306997, + -0.0599402 0.035995901 -0.065192997, + -0.059757002 0.0374128 -0.066212997, + -0.059445001 0.038829401 -0.067373, + -0.058998398 0.0402284 -0.068666004, + -0.058412101 0.041590001 -0.070091002, + -0.0576833 0.042895101 -0.07164, + -0.056809202 0.0441241 -0.073307, + -0.055787299 0.045258999 -0.075081997, + -0.0546159 0.0446916 -0.080495998, + -0.0532961 0.044308301 -0.086323, + -0.051830001 0.044112999 -0.092546001, + -0.050219599 0.044105899 -0.099142, + -0.048467699 0.044286501 -0.106087, + -0.0465803 0.044652499 -0.113357, + -0.044564299 0.045196999 -0.120924, + -0.0424264 0.0459118 -0.12876099, + -0.040174201 0.0467893 -0.136841, + -0.0378174 0.047824401 -0.145135, + -0.035366699 0.049012698 -0.153613, + -0.0328326 0.0503495 -0.16224401, + -0.0321921 0.050611299 -0.171, + -0.0532961 0.018719099 -0.065318003, + -0.051830001 0.017405299 -0.065764003, + -0.050219599 0.016140999 -0.066235997, + -0.048467699 0.014951 -0.066729002, + -0.0465803 0.0138579 -0.067230001, + -0.044564299 0.0128855 -0.067725003, + -0.0424264 0.0120544 -0.068190999, + -0.040174201 0.0113818 -0.068607002, + -0.0378174 0.0108779 -0.068947002, + -0.035366699 0.0105478 -0.069186002, + -0.0328326 0.0103903 -0.069298998, + -0.0302257 0.0103982 -0.069260001, + -0.027557701 0.0105587 -0.069052003, + -0.0248404 0.0108569 -0.068659, + -0.0220857 0.0112713 -0.068071, + -0.019305199 0.0117653 -0.067276999, + -0.0165099 0.0123292 -0.066275001, + -0.0137106 0.0129446 -0.065075003, + -0.055787299 0.0183233 -0.071845002, + -0.056809202 0.0197204 -0.071843997, + -0.0576833 0.021139899 -0.071955003, + -0.058412101 0.0225634 -0.072190002, + -0.058998398 0.0239702 -0.072557002, + -0.059445001 0.023993701 -0.075658001, + -0.059757002 0.023855999 -0.079147004, + -0.0599402 0.023506301 -0.082988001, + -0.059999999 0.022945199 -0.087099999, + -0.0599402 0.0223633 -0.091554999, + -0.059757002 0.022011301 -0.096409999, + -0.059445001 0.021922801 -0.101641, + -0.058998398 0.0221058 -0.107233, + -0.058412101 0.022561699 -0.113172, + -0.0576833 0.023290301 -0.119442, + -0.056809202 0.0242853 -0.126026, + -0.055787299 0.0255384 -0.13290399, + -0.0546159 0.0270411 -0.140057, + -0.0532961 0.028784201 -0.14746501, + -0.051830001 0.0307588 -0.15510599, + 0.0109179 0.0112337 -0.069672003, + 0.0137106 0.0105094 -0.070987001, + 0.0165099 0.0098368702 -0.072112001, + 0.019305199 0.0092349397 -0.073043004, + 0.0220857 0.0087230597 -0.073780999, + 0.0248404 0.00832491 -0.074331, + 0.027557701 0.00805829 -0.074706003, + 0.0302257 0.0079362905 -0.074919999, + 0.0328326 0.00796845 -0.074991003, + 0.035366699 0.0081594996 -0.074937001, + 0.0378174 0.0085078301 -0.074781001, + 0.040174201 0.0090065803 -0.074542001, + 0.0424264 0.0096460497 -0.074239999, + 0.044564299 0.0104125 -0.073890999, + 0.0465803 0.011288 -0.073509999, + 0.048467699 0.0122506 -0.073109001, + 0.050219599 0.0132867 -0.072733, + 0.051830001 0.0144208 -0.072419003, + 0.0532961 0.015646899 -0.072150998, + 0.0546159 0.0169478 -0.071955003, + 0.055787299 0.0183069 -0.071847998, + 0.056809202 0.019706801 -0.071843997, + 0.0576833 0.021129601 -0.071953997, + 0.058412101 0.022556299 -0.072187997, + 0.058998398 0.0239657 -0.072555996, + 0.059445001 0.023985101 -0.075658001, + 0.059757002 0.023846 -0.079149, + 0.0599402 0.023502 -0.082989, + 0.059999999 0.0229422 -0.087100998, + 0.0599402 0.022374099 -0.091564998, + 0.059757002 0.0220343 -0.096427999, + 0.059445001 0.021953501 -0.101662, + 0.058998398 0.022139801 -0.107256, + 0.058412101 0.0225947 -0.113195, + 0.0576833 0.0233187 -0.119464, + 0.056809202 0.024308201 -0.126046, + 0.055787299 0.0255583 -0.132921, + 0.0546159 0.0270635 -0.14006799, + 0.0532961 0.028814901 -0.147469, + 0.051830001 0.030794701 -0.15510499, + 0.050219599 0.032984398 -0.162955, + 0.0497793 0.033493701 -0.171, + 0.050208401 0.032825399 -0.171, + 0.0497806 0.033494599 -0.191, + 0.049818899 0.033437699 -0.171, + 0.051398799 0.030954201 -0.171, + 0.0484588 0.0353604 -0.171, + 0.0460728 0.038435601 -0.191, + 0.046303399 0.0381575 -0.171, + 0.0465739 0.037812401 -0.171, + 0.04456 0.040170401 -0.171, + 0.052960701 0.0281986 -0.191, + 0.0518176 0.030218599 -0.171, + 0.052855 0.0283962 -0.171, + 0.051830001 0.0303778 -0.16306201, + 0.0532961 0.028126299 -0.155323, + 0.0546159 0.0260961 -0.147802, + 0.055787299 0.0243061 -0.14051799, + 0.056809202 0.022773899 -0.133488, + 0.0576833 0.021507701 -0.12673, + 0.058412101 0.0205127 -0.120264, + 0.058998398 0.0197937 -0.114108, + 0.059445001 0.019354399 -0.108281, + 0.059757002 0.0191951 -0.102793, + 0.0599402 0.019308601 -0.097661003, + 0.059999999 0.0196646 -0.092906997, + 0.0599402 0.0202261 -0.088563003, + 0.059757002 0.020765999 -0.084590003, + 0.059445001 0.021090999 -0.080913, + 0.058998398 0.021234799 -0.077593997, + 0.058412101 0.0212502 -0.074666001, + 0.0576833 0.019866699 -0.074385002, + 0.056809202 0.0184795 -0.074226998, + 0.055787299 0.0171094 -0.074184, + 0.0546159 0.0157752 -0.074242003, + 0.0532961 0.0144946 -0.074391, + 0.051830001 0.0132845 -0.074614003, + 0.050219599 0.0121605 -0.074894004, + 0.048467699 0.0111385 -0.075203001, + 0.0465803 0.0102235 -0.075554997, + 0.044564299 0.0093932496 -0.075914003, + 0.0424264 0.0086610401 -0.076237001, + 0.040174201 0.0080464603 -0.076511003, + 0.0378174 0.00756372 -0.076722004, + 0.035366699 0.0072240098 -0.076853998, + 0.0328326 0.0070348 -0.076888002, + 0.0302257 0.00700005 -0.076802999, + 0.027557701 0.0071172402 -0.076582998, + 0.0248404 0.00737936 -0.076209001, + 0.0220857 0.0077753402 -0.075667001, + 0.019305199 0.0082903998 -0.074943997, + 0.0165099 0.0089047896 -0.074033, + 0.0137106 0.0095949499 -0.072930001, + 0.052956201 0.028196299 -0.171, + 0.053282801 0.0275509 -0.171, + 0.057377499 0.0175448 -0.171, + 0.056809202 0.0194577 -0.16350999, + 0.0576833 0.017076399 -0.15622699, + 0.058412101 0.0149597 -0.149166, + 0.058998398 0.0131268 -0.14234, + 0.059445001 0.0115953 -0.135763, + 0.059757002 0.0103741 -0.12944899, + 0.0599402 0.0094638597 -0.123414, + 0.059999999 0.00884292 -0.117681, + 0.0599402 0.0084825195 -0.11228, + 0.059757002 0.0083488198 -0.10724, + 0.059445001 0.0084112296 -0.102591, + 0.058998398 0.0086600203 -0.098357998, + 0.058412101 0.0090899598 -0.094561003, + 0.0576833 0.0095431199 -0.091159001, + 0.056809202 0.0098896101 -0.088083997, + 0.055787299 0.0101671 -0.085383996, + 0.0546159 0.0104282 -0.083076, + 0.0532961 0.0092521999 -0.083053, + 0.051830001 0.0081263604 -0.083108999, + 0.050219599 0.0070704902 -0.083228, + 0.048467699 0.0061011901 -0.083393998, + 0.0465803 0.0052322601 -0.083590001, + 0.044564299 0.0044757701 -0.083798997, + 0.0424264 0.0038425101 -0.083999999, + 0.040174201 0.0033422399 -0.084165998, + 0.0378174 0.0029752399 -0.084299996, + 0.035366699 0.0027256799 -0.084374003, + 0.0328326 0.00260101 -0.084354997, + 0.0302257 0.0026106299 -0.084229, + 0.027557701 0.0027579099 -0.083985001, + 0.0248404 0.0030425701 -0.083609, + 0.0220857 0.00346097 -0.083086997, + 0.019305199 0.0040063099 -0.082405999, + 0.0165099 0.0046665999 -0.081556998, + 0.0137106 0.0054266802 -0.080534004, + 0.0109179 0.0062690498 -0.079329997, + 0.0081428103 0.00489562 -0.081708997, + 0.0081428103 0.00242235 -0.085371003, + 0.0081428103 -0.00023990701 -0.088912003, + 0.0109179 0.00140076 -0.086661004, + 0.0053973799 0.00223502 -0.085721999, + -0.0081428103 0.0024248301 -0.085367002, + -0.0109179 0.00140492 -0.086655997, + -0.0081428103 -0.000236294 -0.088909, + -0.0053973799 0.0022366701 -0.085718997, + -0.0053973799 0.0047360598 -0.082061999, + -0.00268824 0.0046416102 -0.082271002, + -0.00268824 0.00696467 -0.078505002, + 0 0.0069393599 -0.078574002, + 0 0.0090682302 -0.074711002, + 0.00268824 0.0069646998 -0.078506999, + 0.00268824 0.0046412 -0.082272001, + 0.0053973799 0.0047352398 -0.082064003, + 0.0109179 0.00393226 -0.083048001, + -0.0109179 0.0039347298 -0.083043002, + -0.051830001 0.00365609 -0.089102, + -0.051830001 0.0051958598 -0.087146997, + -0.0532961 0.00475191 -0.089201003, + -0.050219599 0.00266097 -0.089116998, + -0.050219599 0.0041903998 -0.087192997, + -0.048467699 0.00175545 -0.089181997, + -0.048467699 0.0032611501 -0.087291002, + -0.0465803 0.000937504 -0.089284003, + -0.0465803 0.00242531 -0.087422997, + -0.044564299 0.00022344499 -0.089405999, + -0.044564299 0.00169628 -0.087571003, + -0.0424264 -0.000374094 -0.089529, + -0.0424264 0.00108548 -0.087716997, + -0.040174201 -0.00084516202 -0.089634001, + -0.040174201 0.000602171 -0.087839998, + -0.0378174 -0.00118354 -0.089702003, + -0.0378174 0.00025229799 -0.087925002, + -0.035366699 -0.0013846999 -0.089717001, + -0.035366699 4.0940002e-005 -0.087958999, + -0.0328326 -0.0014445001 -0.089667, + -0.0328326 -2.9459999e-005 -0.087931998, + -0.0302257 -0.00136186 -0.089538999, + -0.0302257 3.0604999e-005 -0.087802, + -0.027557701 -0.0011486 -0.089298002, + -0.027557701 0.00021941699 -0.087554999, + -0.0248404 -0.00080765202 -0.088930003, + -0.0248404 0.00053829199 -0.087182, + -0.0220857 -0.00033912199 -0.088427, + -0.0220857 0.00098621298 -0.086671002, + -0.019305199 0.00025392001 -0.087777004, + -0.019305199 0.00155983 -0.086010002, + -0.0165099 0.00096438703 -0.086971, + -0.0165099 0.0022506099 -0.085189998, + -0.0137106 0.00178195 -0.086002, + -0.0137106 0.0030470099 -0.084202997, + -0.0109179 0.0026939299 -0.084863, + -0.0137106 0.00046776701 -0.087773003, + -0.0165099 -0.000372576 -0.088722996, + -0.019305199 -0.0011046 -0.089512996, + -0.0220857 -0.00171936 -0.090150997, + -0.0248404 -0.00221016 -0.090644002, + -0.027557701 -0.0025748699 -0.091002002, + -0.0302257 -0.00280998 -0.091237001, + -0.0328326 -0.00290422 -0.091380998, + -0.035366699 -0.00285534 -0.091444999, + -0.0378174 -0.0026658301 -0.091441996, + -0.040174201 -0.0023393701 -0.091388002, + -0.0424264 -0.00188083 -0.091302, + -0.044564299 -0.0012970601 -0.091201, + -0.0465803 -0.00059930701 -0.091104001, + -0.048467699 0.00019680501 -0.091031998, + -0.050219599 0.00109463 -0.090994999, + -0.051830001 0.00210764 -0.091062002, + -0.0532961 0.0016173701 -0.093383998, + -0.0546159 0.0043442901 -0.091637999, + -0.0546159 0.00113397 -0.096083, + -0.055787299 0.0039160699 -0.094454996, + -0.055787299 0.00063114997 -0.099117003, + -0.056809202 0.0034403701 -0.097603999, + -0.056809202 0.00179443 -0.100046, + -0.0576833 0.00301307 -0.10114, + -0.058412101 0.0138298 -0.163744, + -0.0576833 0.016629601 -0.163629, + -0.058215201 0.0145255 -0.171, + -0.058412101 0.0142358 -0.15645801, + -0.058998398 0.0114419 -0.15668701, + -0.058998398 0.0121314 -0.14950299, + -0.059445001 0.0093543204 -0.14984301, + -0.059445001 0.0103245 -0.14278001, + -0.059757002 0.0075760302 -0.14322799, + -0.059757002 0.0088244705 -0.13630401, + -0.0599402 0.00611126 -0.136856, + -0.0599402 0.0076355599 -0.13009, + -0.059999999 0.0049421201 -0.130748, + -0.059999999 0.0067396299 -0.124159, + -0.0599402 0.0040448601 -0.124927, + -0.0599402 0.0061126999 -0.118538, + -0.059757002 0.00339538 -0.119425, + -0.059757002 0.0057286699 -0.113258, + -0.059445001 0.00297294 -0.114272, + -0.059445001 0.0055595199 -0.108349, + -0.058998398 0.0027713501 -0.109493, + -0.058998398 0.00559643 -0.103837, + -0.058412101 0.00278677 -0.105109, + -0.058412101 0.0058345799 -0.099743001, + -0.0576833 0.0062645702 -0.096083, + -0.056809202 0.00672419 -0.092811003, + -0.055787299 0.0071087601 -0.089868002, + -0.0546159 0.0074450001 -0.087306, + -0.0532961 0.0077901701 -0.085130997, + -0.051830001 0.0066952198 -0.085147999, + -0.050219599 0.0056639202 -0.08523, + -0.048467699 0.0047149402 -0.085359998, + -0.0465803 0.0038626799 -0.085522003, + -0.044564299 0.00311936 -0.085697003, + -0.0424264 0.0024957501 -0.085865997, + -0.040174201 0.0020008399 -0.086010002, + -0.0378174 0.0016412199 -0.086119004, + -0.035366699 0.00142 -0.086184002, + -0.0328326 0.00132585 -0.086159997, + -0.0302257 0.00136029 -0.086028002, + -0.027557701 0.00152671 -0.085780002, + -0.0248404 0.00182558 -0.085404001, + -0.0220857 0.00225582 -0.084886998, + -0.019305199 0.0028125399 -0.084215999, + -0.0165099 0.0034859199 -0.083382003, + -0.0137106 0.0042626699 -0.082377002, + -0.0109179 0.0051269 -0.081194997, + -0.057597399 0.0167659 -0.171, + -0.057669099 0.016505999 -0.171, + -0.058857501 0.0116529 -0.171, + 0.0109179 -0.00132072 -0.090149999, + 0.050219599 -0.0053076302 -0.098774001, + 0.051830001 -0.00430864 -0.099266998, + 0.050219599 -0.00368467 -0.096773997, + 0.048467699 -0.0062275799 -0.098402001, + 0.048467699 -0.0046045799 -0.096505001, + 0.0465803 -0.0070503 -0.098145999, + 0.0465803 -0.0054233801 -0.096358001, + 0.044564299 -0.0077588898 -0.098002002, + 0.044564299 -0.0044812602 -0.094664, + 0.0424264 -0.00667116 -0.096366003, + 0.0424264 -0.0050330898 -0.094719999, + 0.040174201 -0.00708703 -0.096396998, + 0.040174201 -0.00546687 -0.094770998, + 0.0378174 -0.0073780501 -0.096409999, + 0.0378174 -0.0057709701 -0.094797, + 0.035366699 -0.0075338599 -0.096386001, + 0.035366699 -0.0059381598 -0.094783001, + 0.0328326 -0.00754799 -0.096306004, + 0.0328326 -0.0059633399 -0.094709001, + 0.0302257 -0.00741693 -0.096152999, + 0.0302257 -0.00584376 -0.094558999, + 0.027557701 -0.0071416101 -0.095913, + 0.027557701 -0.0055808299 -0.094315998, + 0.0248404 -0.0067248498 -0.095568001, + 0.0248404 -0.00517736 -0.093961, + 0.0220857 -0.0061701601 -0.095101997, + 0.0220857 -0.00463981 -0.093488, + 0.019305199 -0.0054849102 -0.094507001, + 0.019305199 -0.0039795102 -0.092882, + 0.0165099 -0.0046819998 -0.093773998, + 0.0165099 -0.0032013999 -0.092129, + 0.0137106 -0.0037678201 -0.092887998, + 0.0137106 -0.0023120199 -0.091219999, + 0.0109179 -0.0027501299 -0.091842003, + 0.0532961 -0.0049001202 -0.102095, + 0.0546159 -0.0037885101 -0.102938, + 0.055787299 -0.0025966701 -0.103933, + 0.056809202 -0.00133356 -0.105086, + 0.0576833 -7.3830001e-006 -0.1064, + 0.058412101 -4.3529999e-006 -0.110664, + 0.058998398 0.000221505 -0.115319, + 0.059445001 0.000675224 -0.120346, + 0.059757002 0.0013585 -0.125724, + 0.0599402 0.0022728899 -0.13142601, + 0.059999999 0.00344049 -0.137422, + 0.0599402 0.0048885201 -0.143683, + 0.059757002 0.0066412501 -0.150185, + 0.059445001 0.00870704 -0.156912, + 0.0532961 0.0016085 -0.093385004, + 0.051830001 -0.0010687599 -0.095099002, + 0.0532961 -0.00161418 -0.097690001, + 0.0546159 0.00113004 -0.096083, + 0.0546159 -0.0021547901 -0.100617, + 0.055787299 0.00062835001 -0.099118002, + 0.055787299 -0.00100881 -0.101501, + 0.056809202 0.00179687 -0.100051, + 0.056809202 0.000205936 -0.102545, + 0.0576833 0.0030234801 -0.10115, + 0.0576833 0.0014813 -0.103753, + 0.058412101 0.00280924 -0.105126, + 0.058412101 0.0058451202 -0.099752001, + 0.058998398 0.0056191399 -0.103854, + 0.058998398 0.0028018199 -0.109513, + 0.059445001 0.0055902102 -0.108371, + 0.059445001 0.00300717 -0.114294, + 0.059757002 0.00576308 -0.113281, + 0.059757002 0.0034290799 -0.119448, + 0.0599402 0.0061464999 -0.118561, + 0.0599402 0.0040742899 -0.12495, + 0.059999999 0.00676909 -0.124182, + 0.059999999 0.0049663298 -0.130769, + 0.0599402 0.0076597398 -0.13011099, + 0.0599402 0.00613272 -0.13687401, + 0.059757002 0.0088458601 -0.13632201, + 0.059757002 0.0076005501 -0.143241, + 0.059445001 0.0103489 -0.142793, + 0.059445001 0.0093884803 -0.149848, + 0.058998398 0.0121653 -0.149508, + 0.058998398 0.0114829 -0.15668499, + 0.058412101 0.0142763 -0.15645701, + 0.058412101 0.013863 -0.16373999, + 0.058168899 0.0147097 -0.171, + 0.0576833 0.0166624 -0.163625, + 0.0588204 0.0118392 -0.171, + 0.050219599 -0.0020755499 -0.094807997, + 0.048467699 -0.0029947299 -0.094648004, + 0.0465803 -0.0021897701 -0.092882998, + 0.044564299 -0.00286926 -0.092952996, + 0.0424264 -0.0034401801 -0.093032002, + 0.040174201 -0.0038878899 -0.093101002, + 0.0378174 -0.0042037899 -0.093142003, + 0.035366699 -0.00438197 -0.093139, + 0.0328326 -0.00441809 -0.093073003, + 0.0302257 -0.0043099299 -0.092924997, + 0.027557701 -0.0040588202 -0.092675, + 0.0248404 -0.00367098 -0.092318997, + 0.0220857 -0.0031582001 -0.091839999, + 0.019305199 -0.0025220199 -0.091218002, + 0.0165099 -0.00176713 -0.090446003, + 0.0137106 -0.000901683 -0.089515999, + 0.0109179 6.3389001e-005 -0.088422, + 0.0137106 0.000461683 -0.087778002, + 0.0165099 -0.00038050101 -0.088728003, + 0.019305199 -0.00111354 -0.089516997, + 0.0220857 -0.0017277 -0.090154, + 0.0248404 -0.0022166199 -0.090645, + 0.027557701 -0.0025794499 -0.091002002, + 0.0302257 -0.0028162401 -0.091246001, + 0.0328326 -0.0029138799 -0.091397002, + 0.035366699 -0.0028671001 -0.091456003, + 0.0378174 -0.00267825 -0.091447003, + 0.040174201 -0.0023511599 -0.091389, + 0.0424264 -0.00189099 -0.091301002, + 0.044564299 -0.00130504 -0.091200002, + 0.0465803 -0.00060502702 -0.091104001, + 0.048467699 0.000193103 -0.091031, + 0.050219599 -0.00048334501 -0.092881002, + 0.051830001 0.000526088 -0.093062997, + 0.051830001 0.0021001301 -0.091062002, + 0.050219599 0.0026571399 -0.089116, + 0.048467699 0.0017495001 -0.089180999, + 0.0465803 0.00092916097 -0.089282997, + 0.044564299 0.000212764 -0.089405999, + 0.0424264 -0.00038655 -0.089530997, + 0.040174201 -0.000858363 -0.089639001, + 0.0378174 -0.0011961201 -0.089713, + 0.035366699 -0.0013951 -0.089734003, + 0.0328326 -0.0014513 -0.089676999, + 0.0302257 -0.00136688 -0.089538001, + 0.027557701 -0.00115576 -0.089299001, + 0.0248404 -0.00081703102 -0.088933997, + 0.0220857 -0.00034935601 -0.088431999, + 0.019305199 0.00024465399 -0.087783001, + 0.0165099 0.00095706101 -0.086978003, + 0.0137106 0.0017767299 -0.086007997, + 0.0109179 0.0026906 -0.084868997, + 0.0137106 0.0030428299 -0.084209003, + 0.0165099 0.00224433 -0.085197002, + 0.019305199 0.00155126 -0.086018004, + 0.0220857 0.00097561203 -0.086677998, + 0.0248404 0.00052678102 -0.087187998, + 0.027557701 0.00020901101 -0.087559, + 0.0302257 2.2749e-005 -0.087803997, + 0.0328326 -3.4917e-005 -0.087931, + 0.035366699 3.3610999e-005 -0.087970003, + 0.0378174 0.00024117 -0.087943003, + 0.040174201 0.00058881298 -0.087852001, + 0.0424264 0.00107153 -0.087722003, + 0.044564299 0.0016832 -0.087572999, + 0.0465803 0.0024141399 -0.087422997, + 0.048467699 0.0032524699 -0.087289996, + 0.050219599 0.0041842302 -0.087191999, + 0.051830001 0.0051919101 -0.087145999, + 0.0532961 0.0047441898 -0.089201003, + 0.0546159 0.0043351999 -0.091640003, + 0.055787299 0.0039120601 -0.094454996, + 0.056809202 0.00343752 -0.097604997, + 0.0576833 0.0046175201 -0.098592997, + 0.0576833 0.00626167 -0.096083999, + 0.056809202 0.0067201001 -0.092811003, + 0.055787299 0.0070994799 -0.089869998, + 0.0546159 0.0074370899 -0.087306, + 0.0532961 0.0077860998 -0.085129999, + 0.051830001 0.00668885 -0.085147001, + 0.050219599 0.0056549301 -0.085229002, + 0.048467699 0.0047033201 -0.085359998, + 0.0465803 0.003849 -0.085524, + 0.044564299 0.00310472 -0.085703, + 0.0424264 0.0024816401 -0.085878, + 0.040174201 0.00198902 -0.086029001, + 0.0378174 0.00163339 -0.086130999, + 0.035366699 0.00141412 -0.086182997, + 0.0328326 0.00131732 -0.086161003, + 0.0302257 0.00134888 -0.086032003, + 0.027557701 0.00151394 -0.085786, + 0.0248404 0.00181366 -0.085412003, + 0.0220857 0.0022460199 -0.084895, + 0.019305199 0.0028051899 -0.084224001, + 0.0165099 0.0034808901 -0.083389997, + 0.0137106 0.00425957 -0.082383998, + 0.0109179 0.0051252302 -0.081201002, + 0.0575951 0.0167653 -0.171, + 0.057667602 0.016505601 -0.171, + 0.058982901 0.0109151 -0.171, + -0.0137106 -0.0222128 -0.108446, + -0.0137106 -0.0258296 -0.110724, + -0.0109179 -0.022782899 -0.108889, + -0.0165099 -0.025107101 -0.110215, + -0.0165099 -0.0268714 -0.111446, + -0.019305199 -0.025998799 -0.11086, + -0.019305199 -0.027739599 -0.112176, + -0.0220857 -0.0267139 -0.111519, + -0.0220857 -0.028429501 -0.11292, + -0.0248404 -0.0272491 -0.112198, + -0.0248404 -0.028938301 -0.113684, + -0.027557701 -0.027605301 -0.112904, + -0.027557701 -0.0292677 -0.114476, + -0.0302257 -0.027785599 -0.113645, + -0.0302257 -0.029421199 -0.115302, + -0.0328326 -0.0277941 -0.114425, + -0.0328326 -0.0293997 -0.116172, + -0.035366699 -0.027631899 -0.115258, + -0.035366699 -0.029196201 -0.117098, + -0.0378174 -0.027294001 -0.116155, + -0.0378174 -0.0288122 -0.118089, + -0.040174201 -0.0267825 -0.117127, + -0.040174201 -0.028252101 -0.119156, + -0.0424264 -0.0261016 -0.118183, + -0.0424264 -0.027519999 -0.120306, + -0.044564299 -0.025256099 -0.119329, + -0.044564299 -0.0266208 -0.121546, + -0.0465803 -0.024253299 -0.120575, + -0.0465803 -0.0255617 -0.122884, + -0.048467699 -0.023101101 -0.121926, + -0.048467699 -0.0243508 -0.124327, + -0.050219599 -0.021807499 -0.123391, + -0.050219599 -0.0229961 -0.125881, + -0.051830001 -0.020380899 -0.124973, + -0.051830001 -0.021506101 -0.127551, + -0.0532961 -0.0188304 -0.126678, + -0.0532961 -0.0198904 -0.129342, + -0.0546159 -0.0181599 -0.131258, + -0.055787299 -0.0199359 -0.14771201, + -0.055787299 -0.0186988 -0.14190599, + -0.056809202 -0.017152701 -0.147258, + -0.056809202 -0.0181117 -0.15320601, + -0.0576833 -0.0153148 -0.15286399, + -0.0576833 -0.0159947 -0.158932, + -0.058412101 -0.0131946 -0.158703, + -0.058412101 -0.0135939 -0.16486999, + -0.058998398 -0.0108011 -0.164756, + -0.058839001 -0.0117463 -0.171, + -0.059445001 -0.0080259303 -0.16464201, + -0.059344199 -0.0088465102 -0.171, + -0.058998398 -0.0104012 -0.158475, + -0.058412101 -0.0125137 -0.152521, + -0.0576833 -0.0143545 -0.14680199, + -0.056809202 -0.015914399 -0.141339, + -0.055787299 -0.017185399 -0.136151, + -0.0546159 -0.0199451 -0.136825, + -0.0546159 -0.0214574 -0.14246701, + -0.0546159 -0.022693399 -0.14816099, + -0.055787299 -0.020893799 -0.153547, + -0.056809202 -0.018790601 -0.159161, + -0.0576833 -0.0163933 -0.164985, + -0.0581921 -0.0146178 -0.171, + -0.0583813 -0.013778 -0.171, + -0.0583959 -0.0137813 -0.191, + -0.0583972 -0.0137072 -0.171, + -0.058983799 -0.0109153 -0.171, + -0.059503399 -0.0077038999 -0.191, + -0.059431799 -0.0081411703 -0.171, + -0.0594863 -0.0077017802 -0.171, + -0.059706699 -0.0059254402 -0.171, + -0.059757002 -0.0052803298 -0.164529, + -0.059445001 -0.0076253298 -0.15824699, + -0.058998398 -0.00971926 -0.152179, + -0.058412101 -0.0115523 -0.146345, + -0.0576833 -0.0131151 -0.140769, + -0.056809202 -0.0143997 -0.135471, + -0.055787299 -0.0153988 -0.13046999, + -0.0546159 -0.016105199 -0.125788, + -0.0532961 -0.0177042 -0.124043, + -0.051830001 -0.0191912 -0.122428, + -0.050219599 -0.020556699 -0.120937, + -0.048467699 -0.0217914 -0.119565, + -0.0465803 -0.0228871 -0.118308, + -0.044564299 -0.023836 -0.117157, + -0.0424264 -0.0246301 -0.116107, + -0.040174201 -0.025262199 -0.115148, + -0.0378174 -0.025727499 -0.114273, + -0.035366699 -0.026024001 -0.113472, + -0.0328326 -0.026157601 -0.112732, + -0.0302257 -0.0261246 -0.112037, + -0.027557701 -0.0259194 -0.111384, + -0.0248404 -0.0255381 -0.110767, + -0.0220857 -0.024978699 -0.110176, + -0.019305199 -0.0242406 -0.109606, + -0.0165099 -0.021504 -0.107896, + -0.0137106 -0.020388801 -0.107263, + -0.0109179 -0.0191471 -0.10651, + -0.0081428103 -0.0195708 -0.106873, + -0.0081428103 -0.016021101 -0.104325, + -0.0053973799 -0.0163083 -0.104596, + -0.0053973799 -0.0128577 -0.101873, + -0.00268824 -0.0130203 -0.102043, + -0.00268824 -0.0096881902 -0.099146001, + 0 -0.0097391699 -0.099205002, + 0 -0.0065427199 -0.096137002, + 0.00268824 -0.0096887499 -0.099146999, + 0.00268824 -0.0130212 -0.102044, + 0.0053973799 -0.0128594 -0.101875, + 0.0053973799 -0.0163099 -0.104597, + 0.0081428103 -0.0160235 -0.104325, + 0.0081428103 -0.0195722 -0.106873, + 0.0109179 -0.019149 -0.10651, + 0.0109179 -0.022783799 -0.108889, + 0.0137106 -0.020390499 -0.107263, + 0.0165099 -0.0286198 -0.112738, + 0.019305199 -0.027742799 -0.112176, + 0.0165099 -0.026874401 -0.111446, + 0.019305199 -0.029461499 -0.11355, + 0.0220857 -0.0284322 -0.11292, + 0.0220857 -0.0301231 -0.114377, + 0.0248404 -0.0289401 -0.113684, + 0.0248404 -0.0306026 -0.115225, + 0.027557701 -0.0292686 -0.114476, + 0.027557701 -0.0309039 -0.1161, + 0.0302257 -0.0294227 -0.115302, + 0.0302257 -0.031023299 -0.117014, + 0.0328326 -0.029398199 -0.116174, + 0.0328326 -0.030955801 -0.117978, + 0.035366699 -0.029189801 -0.117103, + 0.035366699 -0.030702099 -0.118999, + 0.0378174 -0.028801201 -0.118098, + 0.0378174 -0.030265501 -0.120085, + 0.040174201 -0.0282366 -0.119168, + 0.040174201 -0.029650399 -0.121246, + 0.0424264 -0.027500501 -0.12032, + 0.0424264 -0.028861299 -0.122489, + 0.044564299 -0.026597699 -0.121562, + 0.044564299 -0.0279031 -0.123821, + 0.0465803 -0.0255358 -0.122901, + 0.0465803 -0.026783399 -0.12525, + 0.048467699 -0.024322901 -0.124345, + 0.048467699 -0.0255103 -0.126782, + 0.050219599 -0.0229671 -0.1259, + 0.050219599 -0.024092101 -0.128424, + 0.051830001 -0.0214769 -0.127571, + 0.051830001 -0.022537701 -0.13018, + 0.0532961 -0.019862 -0.129362, + 0.0532961 -0.020857301 -0.132054, + 0.0546159 -0.0181331 -0.13127799, + 0.0546159 -0.0190621 -0.13405, + 0.055787299 -0.0171628 -0.13617, + -0.0109179 -0.026410799 -0.111133, + -0.0137106 -0.0275991 -0.111934, + -0.0109179 -0.0299372 -0.113582, + -0.0081428103 -0.026853601 -0.111444, + -0.0081428103 -0.0232173 -0.109227, + -0.0053973799 -0.023520799 -0.109462, + -0.0053973799 -0.019866901 -0.107127, + -0.00268824 -0.020040801 -0.107276, + -0.00268824 -0.016477101 -0.104756, + 0 -0.016532401 -0.104808, + 0 -0.0130737 -0.102098, + 0.00268824 -0.0164779 -0.104756, + 0.00268824 -0.0200413 -0.107276, + 0.0053973799 -0.019867901 -0.107127, + 0.0053973799 -0.0235213 -0.109462, + 0.0081428103 -0.0232179 -0.109227, + 0.0081428103 -0.0268548 -0.111444, + 0.0109179 -0.026412399 -0.111133, + 0.0109179 -0.029939 -0.113582, + 0.0137106 -0.029351 -0.113206, + 0.0137106 -0.0310762 -0.114538, + 0.0165099 -0.030342 -0.114089, + 0.0165099 -0.032037701 -0.115498, + 0.019305199 -0.031155 -0.114981, + 0.019305199 -0.032819699 -0.116468, + 0.0220857 -0.031786799 -0.115889, + 0.0220857 -0.033420701 -0.117455, + 0.0248404 -0.032237198 -0.116818, + 0.0248404 -0.033834498 -0.118467, + 0.027557701 -0.0325027 -0.117779, + 0.027557701 -0.0340572 -0.119513, + 0.0302257 -0.032579198 -0.118782, + 0.0302257 -0.0340885 -0.120602, + 0.0328326 -0.032466501 -0.119834, + 0.0328326 -0.033927999 -0.121741, + 0.035366699 -0.032164901 -0.120944, + 0.035366699 -0.033576 -0.122938, + 0.0378174 -0.031677902 -0.12212, + 0.0378174 -0.033036198 -0.124199, + 0.040174201 -0.031009899 -0.123369, + 0.040174201 -0.032313 -0.125535, + 0.0424264 -0.030165499 -0.1247, + 0.0424264 -0.031411 -0.12695099, + 0.044564299 -0.029149599 -0.12612, + 0.044564299 -0.0303351 -0.128455, + 0.0465803 -0.0279698 -0.127635, + 0.0465803 -0.0290932 -0.130054, + 0.048467699 -0.026634499 -0.129253, + 0.048467699 -0.027693599 -0.131754, + 0.050219599 -0.0251521 -0.130978, + 0.050219599 -0.0261459 -0.133561, + 0.051830001 -0.023532201 -0.132816, + 0.051830001 -0.024459699 -0.135478, + 0.0532961 -0.0217856 -0.134771, + 0.0532961 -0.0226459 -0.137508, + 0.0546159 -0.0199231 -0.13684399, + 0.0546159 -0.0207153 -0.13965601, + 0.0137106 -0.025831601 -0.110724, + -0.0165099 -0.028617 -0.112737, + -0.019305199 -0.029459201 -0.113549, + -0.0220857 -0.0301215 -0.114377, + -0.0248404 -0.030601799 -0.115225, + -0.027557701 -0.030902499 -0.116099, + -0.0302257 -0.031024599 -0.117012, + -0.0328326 -0.0309618 -0.117972, + -0.035366699 -0.0307124 -0.11899, + -0.0378174 -0.03028 -0.120074, + -0.040174201 -0.029668899 -0.121233, + -0.0424264 -0.0288832 -0.122474, + -0.044564299 -0.027927799 -0.123805, + -0.0465803 -0.026810201 -0.125232, + -0.048467699 -0.0255384 -0.126763, + -0.050219599 -0.0241205 -0.12840401, + -0.051830001 -0.0225653 -0.13016, + -0.0532961 -0.020883501 -0.132034, + -0.0532961 -0.0218093 -0.13475101, + -0.051830001 -0.0235577 -0.132797, + -0.050219599 -0.025178799 -0.130959, + -0.048467699 -0.0266618 -0.129234, + -0.0465803 -0.027996801 -0.127617, + -0.044564299 -0.0291753 -0.126103, + -0.0424264 -0.030189 -0.124685, + -0.040174201 -0.0310307 -0.123355, + -0.0378174 -0.031695198 -0.122107, + -0.035366699 -0.032178499 -0.120934, + -0.0328326 -0.032476101 -0.119826, + -0.0302257 -0.032584701 -0.118777, + -0.027557701 -0.032503899 -0.117777, + -0.0248404 -0.032235999 -0.116817, + -0.0220857 -0.031786099 -0.115889, + -0.019305199 -0.031153601 -0.114981, + -0.0165099 -0.030339999 -0.114088, + -0.0137106 -0.029348699 -0.113205, + -0.0137106 -0.0310745 -0.114537, + -0.0165099 -0.032036498 -0.115498, + -0.019305199 -0.0328191 -0.116468, + -0.0220857 -0.033419602 -0.117455, + -0.0248404 -0.033835601 -0.118465, + -0.027557701 -0.034062199 -0.119509, + -0.0302257 -0.034097299 -0.120595, + -0.0328326 -0.033940598 -0.121732, + -0.035366699 -0.033592202 -0.122926, + -0.0378174 -0.0330557 -0.124186, + -0.040174201 -0.0323353 -0.12552001, + -0.0424264 -0.0314354 -0.12693501, + -0.044564299 -0.0303609 -0.128438, + -0.0465803 -0.0291194 -0.130036, + -0.048467699 -0.027719401 -0.131736, + -0.050219599 -0.0261705 -0.133542, + -0.051830001 -0.0244828 -0.13545901, + -0.0532961 -0.022667401 -0.13749, + -0.0532961 -0.024178499 -0.143021, + -0.051830001 -0.0261296 -0.140846, + -0.0532961 -0.025413301 -0.148605, + -0.051830001 -0.027501799 -0.14629699, + -0.0546159 -0.0236501 -0.15388501, + -0.055787299 -0.021571601 -0.159389, + -0.056809202 -0.0191886 -0.16509999, + -0.0574052 -0.017454101 -0.171, + -0.057668298 -0.0165058 -0.171, + -0.056669399 -0.0197125 -0.191, + -0.054342099 -0.0254349 -0.191, + -0.055419099 -0.022994 -0.171, + -0.054336499 -0.0254324 -0.171, + -0.0542247 -0.025684301 -0.171, + -0.054602101 -0.024834299 -0.171, + -0.0546159 -0.024723699 -0.165327, + -0.0532961 -0.027440799 -0.16543899, + -0.0532961 -0.0270446 -0.15983699, + -0.051830001 -0.029712999 -0.160055, + -0.051830001 -0.0290382 -0.15454499, + -0.050219599 -0.0320182 -0.15756699, + 0.051830001 -0.030079201 -0.165544, + 0.051830001 -0.0296771 -0.160053, + 0.050219599 -0.0325187 -0.162962, + 0.0532961 -0.0274105 -0.165435, + 0.0529892 -0.028145101 -0.171, + 0.051820699 -0.030220401 -0.171, + 0.051545098 -0.030710001 -0.171, + 0.051438902 -0.0308876 -0.191, + 0.053285599 -0.0275524 -0.171, + 0.054305699 -0.0255125 -0.171, + 0.054342099 -0.0254349 -0.191, + 0.0557741 -0.0220806 -0.171, + 0.056543902 -0.0200695 -0.171, + 0.055787299 -0.0219373 -0.16520999, + 0.056669399 -0.0197125 -0.191, + 0.0554916 -0.0228185 -0.171, + 0.0546159 -0.024692601 -0.165323, + 0.0546159 -0.024289001 -0.159613, + 0.0532961 -0.0270076 -0.159835, + 0.0532961 -0.026338199 -0.154222, + 0.051830001 -0.029376701 -0.15730201, + -0.00268824 -0.034316301 -0.116832, + -0.00268824 -0.035984501 -0.118244, + 0 -0.0343768 -0.116867, + 0 -0.0309432 -0.114226, + 0.00268824 -0.034316499 -0.116832, + 0.00268824 -0.037616 -0.119715, + 0.0053973799 -0.037431002 -0.119615, + 0.0053973799 -0.039022699 -0.121148, + 0.0081428103 -0.0387077 -0.120985, + 0.0081428103 -0.040256601 -0.122582, + 0.0109179 -0.039806198 -0.122359, + 0.0109179 -0.041309498 -0.12402, + 0.0137106 -0.040718801 -0.123741, + 0.0137106 -0.042174298 -0.125468, + 0.0165099 -0.041440401 -0.125136, + 0.0165099 -0.042845499 -0.126929, + 0.019305199 -0.041966099 -0.126551, + 0.019305199 -0.043318599 -0.12841, + 0.0220857 -0.042291101 -0.12798899, + 0.0220857 -0.043588601 -0.129914, + 0.0248404 -0.042411499 -0.129457, + 0.0248404 -0.043651599 -0.131449, + 0.027557701 -0.042326 -0.130962, + 0.027557701 -0.043506399 -0.133021, + 0.0302257 -0.0420346 -0.132511, + 0.0302257 -0.043152899 -0.134636, + 0.0328326 -0.041536901 -0.13411, + 0.0328326 -0.042591099 -0.13630299, + 0.035366699 -0.0408337 -0.135766, + 0.035366699 -0.041822702 -0.138025, + 0.0378174 -0.039930101 -0.13748699, + 0.0378174 -0.040853001 -0.13981099, + 0.040174201 -0.038832098 -0.139277, + 0.040174201 -0.039687999 -0.141666, + 0.0424264 -0.037545498 -0.14114299, + 0.0424264 -0.038333599 -0.14359599, + 0.044564299 -0.036077101 -0.14309201, + 0.044564299 -0.036796302 -0.14560699, + 0.0465803 -0.034435701 -0.145127, + 0.0465803 -0.035085201 -0.14770301, + 0.048467699 -0.032630999 -0.14725301, + 0.048467699 -0.033209901 -0.14988901, + 0.050219599 -0.030672699 -0.14947601, + 0.050219599 -0.031180499 -0.15217, + 0.051830001 -0.0285709 -0.15179799, + 0.051830001 -0.0290085 -0.154549, + 0.050219599 -0.0316176 -0.15486801, + 0.048467699 -0.033717301 -0.152532, + 0.0465803 -0.035663702 -0.150289, + 0.044564299 -0.037445299 -0.14813501, + 0.0424264 -0.0390523 -0.146065, + 0.040174201 -0.040475499 -0.14407501, + 0.0378174 -0.041708399 -0.142159, + 0.035366699 -0.042745098 -0.140311, + 0.0328326 -0.0435795 -0.13852499, + 0.0302257 -0.044206601 -0.136796, + 0.027557701 -0.044624198 -0.135116, + 0.0248404 -0.044831399 -0.13348, + 0.0220857 -0.044828199 -0.131881, + 0.019305199 -0.0446156 -0.13031299, + 0.0165099 -0.0441976 -0.128769, + 0.0137106 -0.043579001 -0.12724499, + 0.0109179 -0.0427646 -0.125734, + 0.0081428103 -0.041759599 -0.124233, + 0.0053973799 -0.040571399 -0.122737, + 0.00268824 -0.0392076 -0.121243, + 0 -0.037676401 -0.119747, + -0.050219599 -0.031204799 -0.152163, + -0.050219599 -0.031646501 -0.154864, + -0.048467699 -0.0337408 -0.15252499, + -0.048467699 -0.033229802 -0.14987899, + -0.0465803 -0.035682801 -0.150279, + -0.0465803 -0.035102401 -0.147691, + -0.044564299 -0.037461799 -0.148123, + -0.044564299 -0.036812302 -0.145593, + -0.0424264 -0.039067499 -0.146053, + -0.0424264 -0.038349301 -0.143582, + -0.040174201 -0.0404904 -0.144062, + -0.040174201 -0.0397042 -0.141652, + -0.0378174 -0.041723698 -0.14214601, + -0.0378174 -0.040869899 -0.139797, + -0.035366699 -0.042760801 -0.14029799, + -0.035366699 -0.041840099 -0.13801201, + -0.0328326 -0.043595601 -0.138513, + -0.0328326 -0.0426086 -0.13629, + -0.0302257 -0.044222701 -0.136784, + -0.0302257 -0.043170001 -0.134625, + -0.027557701 -0.0446398 -0.135105, + -0.027557701 -0.043522399 -0.13301, + -0.0248404 -0.044845801 -0.13347, + -0.0248404 -0.043665901 -0.131439, + -0.0220857 -0.044840999 -0.131873, + -0.0220857 -0.043600898 -0.129906, + -0.019305199 -0.044626299 -0.13030501, + -0.019305199 -0.043328598 -0.12840299, + -0.0165099 -0.044206101 -0.12876301, + -0.0165099 -0.042853098 -0.12692399, + -0.0137106 -0.0435853 -0.12724, + -0.0137106 -0.042179499 -0.12546401, + -0.0109179 -0.042768799 -0.12573101, + -0.0109179 -0.041312698 -0.124018, + -0.0081428103 -0.041762002 -0.124231, + -0.0081428103 -0.040258002 -0.12258, + -0.0053973799 -0.040572301 -0.122736, + -0.0053973799 -0.0390229 -0.121147, + -0.00268824 -0.039207701 -0.121243, + -0.00268824 -0.037615899 -0.119715, + -0.0053973799 -0.0374308 -0.119615, + -0.0081428103 -0.038708098 -0.120985, + -0.0109179 -0.039808098 -0.122357, + -0.0137106 -0.040722799 -0.123738, + -0.0165099 -0.041446701 -0.12513199, + -0.019305199 -0.041974999 -0.126544, + -0.0220857 -0.0423025 -0.12798101, + -0.0248404 -0.042425301 -0.129448, + -0.027557701 -0.042341899 -0.130952, + -0.0302257 -0.042052101 -0.13249899, + -0.0328326 -0.041555401 -0.13409699, + -0.035366699 -0.040852599 -0.13575301, + -0.0378174 -0.039948702 -0.137472, + -0.040174201 -0.038849998 -0.13926201, + -0.0424264 -0.037562702 -0.141129, + -0.044564299 -0.036093701 -0.143077, + -0.0465803 -0.034452401 -0.14511301, + -0.048467699 -0.032648899 -0.147241, + -0.050219599 -0.0306933 -0.14946499, + -0.051830001 -0.0280839 -0.14904, + -0.050219599 -0.030111801 -0.14677601, + -0.048467699 -0.0319984 -0.144613, + -0.0465803 -0.033733301 -0.14254799, + -0.044564299 -0.035306498 -0.140577, + -0.0424264 -0.036708001 -0.138695, + -0.040174201 -0.037928302 -0.136896, + -0.0378174 -0.038960699 -0.13517401, + -0.035366699 -0.0397989 -0.133523, + -0.0328326 -0.040437002 -0.131938, + -0.0302257 -0.040871099 -0.13041, + -0.027557701 -0.041100699 -0.128932, + -0.0248404 -0.041126199 -0.127498, + -0.0220857 -0.040948201 -0.126101, + -0.019305199 -0.0405678 -0.124733, + -0.0165099 -0.0399893 -0.12339, + -0.0137106 -0.039217498 -0.122064, + -0.0109179 -0.038257498 -0.120752, + -0.0081428103 -0.037115399 -0.119445, + -0.0053973799 -0.035799298 -0.11814, + -0.0053973799 -0.034131199 -0.116723, + -0.00268824 -0.030882999 -0.114187, + 0 -0.027404301 -0.111831, + 0.00268824 -0.0308835 -0.114187, + 0.0053973799 -0.034131601 -0.116724, + 0.0081428103 -0.035484001 -0.117963, + 0.056809202 -0.0187512 -0.15916, + 0.0576833 -0.015954699 -0.158931, + 0.056809202 -0.0180791 -0.153211, + 0.055787299 -0.020861801 -0.153552, + 0.055787299 -0.019912999 -0.147723, + 0.0546159 -0.0226709 -0.148173, + 0.0546159 -0.0214379 -0.142483, + 0.055787299 -0.0186789 -0.141922, + 0.056809202 -0.0171293 -0.14726999, + 0.0576833 -0.0152816 -0.152869, + 0.058412101 -0.0131541 -0.158701, + 0.058412101 -0.0135607 -0.164866, + 0.058998398 -0.0107676 -0.16475099, + 0.0588759 -0.01156 -0.171, + 0.0583992 -0.0137077 -0.171, + 0.0583959 -0.0137813 -0.191, + 0.058383498 -0.0137785 -0.171, + 0.0582381 -0.0144335 -0.171, + 0.0576833 -0.016360501 -0.16498099, + 0.056809202 -0.0191563 -0.165096, + 0.057460099 -0.017272299 -0.171, + 0.055787299 -0.021532901 -0.15938701, + 0.0546159 -0.0236187 -0.153889, + 0.0532961 -0.0259002 -0.151417, + 0.0532961 -0.0253914 -0.148616, + 0.051830001 -0.028062601 -0.149051, + 0.051830001 -0.0274827 -0.146311, + 0.050219599 -0.030093299 -0.146789, + 0.050219599 -0.0294428 -0.14411099, + 0.048467699 -0.031980999 -0.144627, + 0.048467699 -0.031260699 -0.142014, + 0.0465803 -0.033716001 -0.142564, + 0.0465803 -0.032926802 -0.140017, + 0.044564299 -0.035288502 -0.14059301, + 0.044564299 -0.034431498 -0.13811401, + 0.0424264 -0.036689099 -0.13871101, + 0.0424264 -0.035765 -0.136301, + 0.040174201 -0.037908599 -0.136911, + 0.040174201 -0.036918402 -0.134571, + 0.0378174 -0.038940601 -0.135188, + 0.0378174 -0.0378851 -0.13292, + 0.035366699 -0.039779 -0.13353699, + 0.035366699 -0.038659401 -0.131341, + 0.0328326 -0.040417999 -0.131951, + 0.0328326 -0.0392364 -0.12982699, + 0.0302257 -0.040853702 -0.130421, + 0.0302257 -0.039612301 -0.12837, + 0.027557701 -0.0410854 -0.128942, + 0.027557701 -0.0397866 -0.126964, + 0.0248404 -0.041113399 -0.127507, + 0.0248404 -0.039759699 -0.12560099, + 0.0220857 -0.040938102 -0.12610801, + 0.0220857 -0.0395317 -0.124274, + 0.019305199 -0.040560398 -0.124739, + 0.019305199 -0.039103899 -0.122977, + 0.0165099 -0.039984498 -0.123394, + 0.0165099 -0.038480099 -0.121703, + 0.0137106 -0.039215099 -0.122066, + 0.0137106 -0.037665401 -0.120447, + 0.0109179 -0.038256999 -0.120753, + 0.0109179 -0.036664601 -0.119202, + 0.0081428103 -0.037115801 -0.119445, + 0.056661699 -0.019710001 -0.171, + 0.056795701 -0.0193008 -0.171, + 0.057670102 -0.016506299 -0.171, + 0.054603901 -0.0248351 -0.171, + 0.054340299 -0.025434 -0.171, + 0.050219599 -0.031985499 -0.15756799, + 0.048467699 -0.034154002 -0.15517899, + 0.0465803 -0.036170602 -0.15288199, + 0.044564299 -0.038023401 -0.150673, + 0.0424264 -0.039700899 -0.14854801, + 0.040174201 -0.041193701 -0.146501, + 0.0378174 -0.0424954 -0.144527, + 0.035366699 -0.0435999 -0.14262, + 0.0328326 -0.044501401 -0.140775, + 0.0302257 -0.045194499 -0.13898499, + 0.027557701 -0.045677401 -0.137244, + 0.0248404 -0.045948699 -0.135547, + 0.0220857 -0.0460076 -0.13388699, + 0.019305199 -0.045854799 -0.132258, + 0.0165099 -0.045494199 -0.13065401, + 0.0137106 -0.0449307 -0.129069, + 0.0109179 -0.044169001 -0.127498, + 0.0081428103 -0.0432145 -0.125937, + 0.0053973799 -0.0420743 -0.124382, + 0.00268824 -0.0407562 -0.122828, + 0 -0.039267998 -0.121274, + -0.00268824 -0.040756699 -0.122828, + -0.0053973799 -0.042075898 -0.12438, + -0.0081428103 -0.043217599 -0.125935, + -0.0109179 -0.044174001 -0.12749501, + -0.0137106 -0.0449377 -0.12906399, + -0.0165099 -0.0455033 -0.130647, + -0.019305199 -0.045865901 -0.13225, + -0.0220857 -0.0460204 -0.13387901, + -0.0248404 -0.045962699 -0.135538, + -0.027557701 -0.045692001 -0.137234, + -0.0302257 -0.0452093 -0.138974, + -0.0328326 -0.044516001 -0.140763, + -0.035366699 -0.043614201 -0.142608, + -0.0378174 -0.0425095 -0.14451399, + -0.040174201 -0.0412081 -0.14648899, + -0.0424264 -0.039716501 -0.148537, + -0.044564299 -0.038041599 -0.150664, + -0.0465803 -0.036193199 -0.15287501, + -0.048467699 -0.0341819 -0.155175, + -0.0532961 -0.026368801 -0.154218, + -0.0546159 -0.0243269 -0.159614, + -0.055787299 -0.0219691 -0.165214, + -0.055772301 -0.0220799 -0.171, + -0.056480099 -0.0202484 -0.171, + -0.0566587 -0.019709 -0.171, + -0.056793999 -0.0193002 -0.171, + -0.050219599 -0.0294607 -0.144096, + -0.048467699 -0.0312788 -0.14199901, + -0.0465803 -0.032945599 -0.140001, + -0.044564299 -0.034451298 -0.138098, + -0.0424264 -0.035785802 -0.13628501, + -0.040174201 -0.0369398 -0.134556, + -0.0378174 -0.037906501 -0.132906, + -0.035366699 -0.038679902 -0.131327, + -0.0328326 -0.039255299 -0.129814, + -0.0302257 -0.039629102 -0.128359, + -0.027557701 -0.039800901 -0.126954, + -0.0248404 -0.039771099 -0.12559301, + -0.0220857 -0.039540201 -0.124268, + -0.019305199 -0.039109498 -0.122972, + -0.0165099 -0.038483098 -0.1217, + -0.0137106 -0.037666 -0.120446, + -0.0109179 -0.036664099 -0.119202, + -0.0081428103 -0.0354838 -0.117963, + -0.0081428103 -0.033815999 -0.116539, + -0.0109179 -0.035032202 -0.11771, + -0.0137106 -0.0360718 -0.118883, + -0.0165099 -0.036930598 -0.120065, + -0.019305199 -0.037602302 -0.121263, + -0.0220857 -0.038080901 -0.122484, + -0.0248404 -0.038362201 -0.123734, + -0.027557701 -0.038444899 -0.12502, + -0.0302257 -0.038328499 -0.12635, + -0.0328326 -0.038012601 -0.12773, + -0.035366699 -0.037497502 -0.12916701, + -0.0378174 -0.036786798 -0.13067, + -0.040174201 -0.035884999 -0.132245, + -0.0424264 -0.0347967 -0.1339, + -0.044564299 -0.0335286 -0.13564099, + -0.0465803 -0.0320899 -0.137472, + -0.048467699 -0.0304906 -0.139401, + -0.050219599 -0.0287406 -0.14143001, + -0.051830001 -0.026850199 -0.143565, + -0.050219599 -0.0279519 -0.138781, + -0.048467699 -0.029634301 -0.136822, + -0.0465803 -0.0311666 -0.134967, + -0.044564299 -0.032538898 -0.13321, + -0.0424264 -0.033741198 -0.13154501, + -0.040174201 -0.034764599 -0.129967, + -0.0378174 -0.035603698 -0.12847, + -0.035366699 -0.036254 -0.12704501, + -0.0328326 -0.0367111 -0.125686, + -0.0302257 -0.036971498 -0.124384, + -0.027557701 -0.037034899 -0.123133, + -0.0248404 -0.036901802 -0.121925, + -0.0220857 -0.036572602 -0.120753, + -0.019305199 -0.036048599 -0.119609, + -0.0165099 -0.035335299 -0.118487, + -0.0137106 -0.034439601 -0.117378, + -0.0109179 -0.033364799 -0.116275, + -0.0081428103 -0.0321154 -0.115174, + -0.0053973799 -0.030699 -0.11407, + -0.00268824 -0.027344801 -0.11179, + 0 -0.023757299 -0.109646, + 0.00268824 -0.027345199 -0.11179, + 0.0053973799 -0.030699899 -0.11407, + 0.0081428103 -0.033816598 -0.116539, + 0.0109179 -0.0350326 -0.11771, + 0.0137106 -0.036072399 -0.118883, + 0.0165099 -0.036929902 -0.120067, + 0.019305199 -0.0375989 -0.121267, + 0.0220857 -0.038074501 -0.12249, + 0.0248404 -0.038352601 -0.123741, + 0.027557701 -0.0384322 -0.125029, + 0.0302257 -0.038312901 -0.12636, + 0.0328326 -0.0379944 -0.12774201, + 0.035366699 -0.037477199 -0.129181, + 0.0378174 -0.036764901 -0.130684, + 0.040174201 -0.035862301 -0.13226099, + 0.0424264 -0.034774099 -0.13391601, + 0.044564299 -0.033506699 -0.135657, + 0.0465803 -0.032069199 -0.13748901, + 0.048467699 -0.030471001 -0.13941801, + 0.050219599 -0.028721901 -0.14144699, + 0.051830001 -0.0268317 -0.14358, + 0.0532961 -0.024811 -0.14582101, + 0.0109179 -0.0333656 -0.116275, + 0.0137106 -0.0327737 -0.115928, + 0.0109179 -0.031666599 -0.114899, + 0.0137106 -0.0344401 -0.117377, + 0.0165099 -0.033703301 -0.116964, + 0.0165099 -0.0353361 -0.118487, + 0.019305199 -0.034453001 -0.118011, + 0.019305199 -0.036047801 -0.119611, + 0.0220857 -0.0350166 -0.119078, + 0.0220857 -0.036568601 -0.120757, + 0.0248404 -0.035387699 -0.120172, + 0.0248404 -0.0368945 -0.121931, + 0.027557701 -0.035565201 -0.121301, + 0.027557701 -0.037024301 -0.123141, + 0.0302257 -0.035548698 -0.122474, + 0.0302257 -0.036957599 -0.124394, + 0.0328326 -0.035337899 -0.123697, + 0.0328326 -0.036694098 -0.125698, + 0.035366699 -0.034933198 -0.124976, + 0.035366699 -0.036234301 -0.127058, + 0.0378174 -0.034338299 -0.126322, + 0.0378174 -0.035581902 -0.128484, + 0.040174201 -0.033557601 -0.12774, + 0.040174201 -0.034741402 -0.12998299, + 0.0424264 -0.032595601 -0.12923899, + 0.0424264 -0.033717301 -0.131561, + 0.044564299 -0.031457599 -0.130825, + 0.044564299 -0.032515202 -0.13322701, + 0.0465803 -0.030151499 -0.132505, + 0.0465803 -0.031143799 -0.134984, + 0.048467699 -0.0286866 -0.134285, + 0.048467699 -0.0296127 -0.13684, + 0.050219599 -0.0270727 -0.136169, + 0.050219599 -0.027931601 -0.138798, + 0.051830001 -0.025319399 -0.138161, + 0.051830001 -0.026110301 -0.140863, + 0.0532961 -0.0234375 -0.140265, + 0.0532961 -0.0241594 -0.14303701, + 0.0081428103 -0.030386901 -0.113869, + 0.0053973799 -0.0271639 -0.111662, + 0.00268824 -0.0236992 -0.109601, + 0 -0.020097701 -0.107325, + -0.00268824 -0.023699 -0.109601, + -0.0053973799 -0.027163099 -0.111662, + -0.0081428103 -0.0303856 -0.113869, + -0.0109179 -0.031665299 -0.114899, + -0.0137106 -0.032772701 -0.115928, + -0.0165099 -0.033702798 -0.116964, + -0.019305199 -0.034452099 -0.118011, + -0.0220857 -0.035017598 -0.119076, + -0.0248404 -0.035392102 -0.120168, + -0.027557701 -0.035573199 -0.121295, + -0.0302257 -0.035560299 -0.122465, + -0.0328326 -0.035353001 -0.123686, + -0.035366699 -0.034951501 -0.124964, + -0.0378174 -0.034359299 -0.12630799, + -0.040174201 -0.033580702 -0.12772501, + -0.0424264 -0.032620199 -0.129223, + -0.044564299 -0.031482801 -0.130808, + -0.0465803 -0.030176301 -0.132487, + -0.048467699 -0.028710401 -0.134266, + -0.050219599 -0.027094999 -0.13615, + -0.051830001 -0.0253403 -0.138143, + 0.056809202 -0.0158941 -0.14135601, + 0.0576833 -0.0143309 -0.146814, + 0.058412101 -0.0124801 -0.15252601, + 0.058998398 -0.0103602 -0.158473, + 0.059445001 -0.0079921298 -0.164637, + 0.059372 -0.0086586103 -0.171, + 0.059434399 -0.00814154 -0.171, + 0.0594876 -0.0077019902 -0.171, + 0.059725199 -0.0057364102 -0.171, + 0.059503399 -0.0077038999 -0.191, + 0.058986001 -0.0109157 -0.171, + 0.0546159 -0.017137 -0.12853, + 0.0532961 -0.0188003 -0.126698, + 0.051830001 -0.0203509 -0.124993, + 0.050219599 -0.0217786 -0.12341, + 0.048467699 -0.0230742 -0.121945, + 0.0465803 -0.024229299 -0.120591, + 0.044564299 -0.025235601 -0.119344, + 0.0424264 -0.0260853 -0.118195, + 0.040174201 -0.0267708 -0.117137, + 0.0378174 -0.0272872 -0.116161, + 0.035366699 -0.0276304 -0.115261, + 0.0328326 -0.0277957 -0.114426, + 0.0302257 -0.027786599 -0.113645, + 0.027557701 -0.027607299 -0.112904, + 0.0248404 -0.027252199 -0.112198, + 0.0220857 -0.026717599 -0.11152, + 0.019305199 -0.026002301 -0.110861, + 0.0165099 -0.025109399 -0.110215, + 0.0137106 -0.0222139 -0.108446, + 0.0165099 -0.021505199 -0.107895, + 0.019305199 -0.0242434 -0.109605, + 0.0220857 -0.0249827 -0.110177, + 0.0248404 -0.0255423 -0.110767, + 0.027557701 -0.025922701 -0.111385, + 0.0302257 -0.0261268 -0.112038, + 0.0328326 -0.0261587 -0.112732, + 0.035366699 -0.0260258 -0.113473, + 0.0378174 -0.025725801 -0.114276, + 0.040174201 -0.025255 -0.115155, + 0.0424264 -0.0246177 -0.116117, + 0.044564299 -0.0238188 -0.11717, + 0.0465803 -0.0228657 -0.118323, + 0.048467699 -0.0217664 -0.119582, + 0.050219599 -0.020528801 -0.120955, + 0.051830001 -0.019161399 -0.122447, + 0.0532961 -0.017673399 -0.124064, + 0.0546159 -0.0160744 -0.125809, + 0.055787299 -0.0143744 -0.12768599, + 0.0546159 -0.0149465 -0.123118, + 0.0532961 -0.016482901 -0.121463, + 0.051830001 -0.0179104 -0.119938, + 0.050219599 -0.0192197 -0.118539, + 0.048467699 -0.0204014 -0.117261, + 0.0465803 -0.021447301 -0.116098, + 0.044564299 -0.022349499 -0.115042, + 0.0424264 -0.023099899 -0.114088, + 0.040174201 -0.0236915 -0.113225, + 0.0378174 -0.024119001 -0.112446, + 0.035366699 -0.024387799 -0.111738, + 0.0328326 -0.0245005 -0.111086, + 0.0302257 -0.0244458 -0.110481, + 0.027557701 -0.024218099 -0.10992, + 0.0248404 -0.023813801 -0.109393, + 0.0220857 -0.0232308 -0.108893, + 0.019305199 -0.020655399 -0.107235, + 0.0165099 -0.0196904 -0.106691, + 0.0137106 -0.018593499 -0.106033, + 0.0137106 -0.0168212 -0.104754, + 0.0165099 -0.0179027 -0.10544, + 0.019305199 -0.018850701 -0.106005, + 0.0220857 -0.0196619 -0.106462, + 0.0248404 -0.022070101 -0.108076, + 0.027557701 -0.0224969 -0.108509, + 0.0302257 -0.022747099 -0.108978, + 0.0328326 -0.0228236 -0.109489, + 0.035366699 -0.0227313 -0.11005, + 0.0378174 -0.022479899 -0.110668, + 0.040174201 -0.0220821 -0.111349, + 0.0424264 -0.021534201 -0.11211, + 0.044564299 -0.020829599 -0.112963, + 0.0465803 -0.0199761 -0.113918, + 0.048467699 -0.0189813 -0.114982, + 0.050219599 -0.0178532 -0.116163, + 0.051830001 -0.016599899 -0.117465, + 0.0532961 -0.0152307 -0.118896, + 0.0546159 -0.0137549 -0.120459, + 0.055787299 -0.0121822 -0.122159, + -0.0137106 -0.016817899 -0.104754, + -0.0248404 -0.0203094 -0.106818, + -0.0248404 -0.0220665 -0.108076, + -0.0220857 -0.019660201 -0.106463, + -0.027557701 -0.020758299 -0.107155, + -0.027557701 -0.0224918 -0.108508, + -0.0302257 -0.021028399 -0.107527, + -0.0302257 -0.0227421 -0.108977, + -0.0328326 -0.021125801 -0.107942, + -0.0328326 -0.022819599 -0.109489, + -0.035366699 -0.0210544 -0.108409, + -0.035366699 -0.0227287 -0.11005, + -0.0378174 -0.020822501 -0.108934, + -0.0378174 -0.0224787 -0.110668, + -0.040174201 -0.020440601 -0.109525, + -0.040174201 -0.022080099 -0.111348, + -0.0424264 -0.0199201 -0.110185, + -0.0424264 -0.021536 -0.112106, + -0.044564299 -0.0192634 -0.110932, + -0.044564299 -0.0208377 -0.112956, + -0.0465803 -0.018462401 -0.111779, + -0.0465803 -0.0199896 -0.113907, + -0.048467699 -0.017522199 -0.112738, + -0.048467699 -0.018999901 -0.114968, + -0.050219599 -0.016450601 -0.113814, + -0.050219599 -0.0178762 -0.116146, + -0.051830001 -0.0152557 -0.115016, + -0.051830001 -0.016626701 -0.117447, + -0.0532961 -0.0139463 -0.116348, + -0.0532961 -0.0152603 -0.118876, + -0.0546159 -0.0125319 -0.117815, + -0.0546159 -0.0137864 -0.120438, + -0.0546159 -0.0149781 -0.123097, + -0.055787299 -0.0133425 -0.124886, + -0.0532961 -0.016513599 -0.121442, + -0.051830001 -0.017939201 -0.119918, + -0.050219599 -0.0192456 -0.118521, + -0.048467699 -0.020423699 -0.117245, + -0.0465803 -0.021465201 -0.116084, + -0.044564299 -0.0223625 -0.115032, + -0.0424264 -0.023107599 -0.114081, + -0.040174201 -0.0236932 -0.113221, + -0.0378174 -0.024117099 -0.112445, + -0.035366699 -0.0243866 -0.111738, + -0.0328326 -0.024498099 -0.111086, + -0.0302257 -0.0244422 -0.110481, + -0.027557701 -0.0242135 -0.109919, + -0.0248404 -0.023809301 -0.109392, + -0.0220857 -0.0232276 -0.108893, + -0.019305199 -0.0206539 -0.107235, + -0.019305199 -0.0188483 -0.106006, + -0.0165099 -0.019688301 -0.106692, + -0.0165099 -0.0178998 -0.105441, + -0.0137106 -0.0185911 -0.106033, + -0.056809202 -0.0126118 -0.129676, + -0.0576833 -0.0115992 -0.13478699, + -0.058412101 -0.0103117 -0.14019801, + -0.058998398 -0.0087566804 -0.14589, + -0.059445001 -0.0069424398 -0.151839, + -0.059757002 -0.00487907 -0.158023, + -0.0599402 -0.00257099 -0.164418, + -0.0599254 -0.0029901101 -0.171, + -0.059999999 0.000117479 -0.164307, + -0.059962101 -0.00154442 -0.171, + -0.0599402 -0.0021690801 -0.157801, + -0.059757002 -0.0041952198 -0.151502, + -0.059445001 -0.0059787198 -0.145437, + -0.058998398 -0.0075149299 -0.13962901, + -0.058412101 -0.0087945899 -0.134102, + -0.0576833 -0.0098099401 -0.128877, + -0.056809202 -0.0105539 -0.123976, + -0.055787299 -0.0110216 -0.119421, + -0.0546159 -0.0112164 -0.115228, + -0.0532961 -0.0125736 -0.113859, + -0.051830001 -0.0138281 -0.112628, + -0.050219599 -0.0149706 -0.111528, + -0.048467699 -0.0159925 -0.110556, + -0.0465803 -0.0168854 -0.109702, + -0.044564299 -0.0176445 -0.108959, + -0.0424264 -0.0182795 -0.108313, + -0.040174201 -0.0187863 -0.107743, + -0.0378174 -0.0191528 -0.107246, + -0.035366699 -0.019367499 -0.106817, + -0.0328326 -0.019420899 -0.106448, + -0.0302257 -0.019305101 -0.106132, + -0.027557701 -0.0190126 -0.10586, + -0.0248404 -0.018521 -0.105578, + -0.0220857 -0.0178663 -0.105204, + -0.019305199 -0.0170708 -0.10473, + -0.0165099 -0.0161367 -0.104141, + -0.0137106 -0.015071 -0.103427, + -0.059935 0.0026881101 -0.171, + -0.0599331 -0.00268806 -0.171, + -0.059746101 -0.0053965598 -0.171, + -0.059821099 0.0046305298 -0.191, + -0.059930101 0.00289505 -0.171, + -0.0597477 0.0053966902 -0.171, + -0.059432998 0.00814135 -0.171, + -0.051496498 0.0307914 -0.171, + -0.0497806 0.033494599 -0.191, + -0.050210599 0.0328269 -0.171, + -0.0499245 0.0332799 -0.171, + -0.048461299 0.035362199 -0.171, + -0.039609101 -0.045067899 -0.191, + -0.038047399 -0.046393901 -0.171, + -0.042409498 -0.042443302 -0.171, + -0.0465752 -0.037813399 -0.171, + -0.047984999 -0.036008701 -0.171, + -0.0465803 -0.037699699 -0.165859, + -0.044564299 -0.039893702 -0.163417, + -0.0424264 -0.041914601 -0.161054, + -0.040174201 -0.043752499 -0.158766, + -0.0378174 -0.045400001 -0.15654901, + -0.035366699 -0.0468501 -0.154397, + -0.0328326 -0.048095599 -0.152303, + -0.0302257 -0.0491299 -0.150263, + -0.027557701 -0.0499507 -0.14827, + -0.0248404 -0.050556298 -0.146318, + -0.0220857 -0.0509452 -0.1444, + -0.019305199 -0.051116802 -0.14251199, + -0.0165099 -0.051073499 -0.14064901, + -0.0137106 -0.050818302 -0.138804, + -0.0109179 -0.0503546 -0.13697401, + -0.0081428103 -0.049686398 -0.13515501, + -0.0053973799 -0.048820902 -0.133342, + -0.00268824 -0.047766 -0.131531, + 0 -0.046529599 -0.12972, + 0.00268824 -0.047764499 -0.131532, + 0.0053973799 -0.048817798 -0.13334399, + 0.0081428103 -0.049681701 -0.135158, + 0.0109179 -0.050348502 -0.136978, + 0.0137106 -0.050811 -0.138809, + 0.0165099 -0.0510654 -0.140655, + 0.019305199 -0.0511082 -0.14252, + 0.0220857 -0.0509363 -0.144408, + 0.0248404 -0.050547101 -0.14632601, + 0.027557701 -0.049940798 -0.148278, + 0.0302257 -0.049118798 -0.150271, + 0.0328326 -0.048082098 -0.15231, + 0.035366699 -0.0468329 -0.154402, + 0.0378174 -0.045378301 -0.156552, + 0.040174201 -0.043726299 -0.158767, + 0.0424264 -0.041885201 -0.161053, + 0.044564299 -0.039863698 -0.163414, + 0.0465803 -0.037673201 -0.165856, + 0.048467699 -0.035325501 -0.168383, + 0.048288502 -0.035611998 -0.171, + 0.0484627 -0.035363302 -0.171, + 0.049977001 -0.033201002 -0.171, + 0.050211899 -0.032827701 -0.171, + 0.051434901 -0.0308851 -0.171, + 0.050219599 -0.0326868 -0.16565099, + -0.048467699 -0.035086699 -0.163121, + -0.048467699 -0.0352493 -0.165759, + -0.0465803 -0.037537199 -0.16327199, + -0.0465803 -0.0373055 -0.160676, + -0.044564299 -0.039662302 -0.160869, + -0.044564299 -0.0393617 -0.158317, + -0.0424264 -0.041614302 -0.158548, + -0.0424264 -0.0412446 -0.15604, + -0.040174201 -0.0433833 -0.15630201, + -0.040174201 -0.042944402 -0.15383901, + -0.0378174 -0.044961698 -0.154127, + -0.0378174 -0.044453301 -0.15170901, + -0.035366699 -0.046342298 -0.152018, + -0.035366699 -0.045764301 -0.149646, + -0.0328326 -0.047517899 -0.149967, + -0.0328326 -0.0468706 -0.147642, + -0.0302257 -0.048482899 -0.147971, + -0.0302257 -0.0477667 -0.14569201, + -0.027557701 -0.0492348 -0.14602099, + -0.027557701 -0.048450299 -0.14379001, + -0.0248404 -0.049772099 -0.144113, + -0.0248404 -0.048920002 -0.14193, + -0.0220857 -0.050093401 -0.142241, + -0.0220857 -0.049174201 -0.14010599, + -0.019305199 -0.050197899 -0.140398, + -0.019305199 -0.0492125 -0.138312, + -0.0165099 -0.050088201 -0.13857999, + -0.0165099 -0.049037099 -0.13654301, + -0.0137106 -0.049767401 -0.13678201, + -0.0137106 -0.048651699 -0.134794, + -0.0109179 -0.049239099 -0.13499901, + -0.0109179 -0.048060901 -0.13306101, + -0.0081428103 -0.048508398 -0.13322601, + -0.0081428103 -0.047270201 -0.131337, + -0.0053973799 -0.047582801 -0.131459, + -0.0053973799 -0.0462869 -0.129619, + -0.00268824 -0.046470199 -0.129695, + -0.00268824 -0.045118999 -0.127904, + 0 -0.0451786 -0.127931, + 0 -0.0437745 -0.12618899, + 0.00268824 -0.045117799 -0.127905, + 0.00268824 -0.046468802 -0.129696, + 0.0053973799 -0.046284098 -0.129621, + 0.0053973799 -0.047579799 -0.13146099, + 0.0081428103 -0.047265701 -0.13134, + 0.0081428103 -0.048503701 -0.133229, + 0.0109179 -0.048054699 -0.133065, + 0.0109179 -0.0492328 -0.135003, + 0.0137106 -0.048643801 -0.134799, + 0.0137106 -0.049759701 -0.136787, + 0.0165099 -0.049027801 -0.136549, + 0.0165099 -0.050079402 -0.138587, + 0.019305199 -0.0492022 -0.138319, + 0.019305199 -0.0501884 -0.140406, + 0.0220857 -0.049163401 -0.14011399, + 0.0220857 -0.050083499 -0.142249, + 0.0248404 -0.0489089 -0.141939, + 0.0248404 -0.0497621 -0.144122, + 0.027557701 -0.048439201 -0.14380001, + 0.027557701 -0.0492245 -0.14602999, + 0.0302257 -0.047755498 -0.145702, + 0.0302257 -0.048472099 -0.14798, + 0.0328326 -0.046858799 -0.147652, + 0.0328326 -0.0475059 -0.149976, + 0.035366699 -0.045751199 -0.149655, + 0.035366699 -0.0463278 -0.152025, + 0.0378174 -0.0444378 -0.15171701, + 0.0378174 -0.044943299 -0.15413301, + 0.040174201 -0.0429249 -0.153845, + 0.040174201 -0.0433602 -0.156305, + 0.0424264 -0.041220199 -0.15604299, + 0.0424264 -0.041586701 -0.158549, + 0.044564299 -0.039332598 -0.158318, + 0.044564299 -0.0396314 -0.160868, + 0.0465803 -0.037273198 -0.160675, + 0.0465803 -0.037505802 -0.163269, + 0.048467699 -0.035053998 -0.163118, + 0.048467699 -0.0352217 -0.165755, + -0.050219599 -0.032320201 -0.16026799, + -0.051438499 -0.0308873 -0.171, + -0.051438902 -0.0308876 -0.191, + -0.050209399 -0.0328261 -0.171, + -0.053283598 -0.0275514 -0.171, + -0.048467699 -0.034553099 -0.15782601, + -0.0465803 -0.0366337 -0.15547501, + -0.044564299 -0.038551498 -0.153212, + -0.0424264 -0.040295899 -0.151031, + -0.040174201 -0.041856699 -0.148929, + -0.0378174 -0.0432267 -0.1469, + -0.035366699 -0.0443996 -0.14493801, + -0.0328326 -0.045368999 -0.14303701, + -0.0302257 -0.046129301 -0.14119001, + -0.027557701 -0.046678301 -0.139393, + -0.0248404 -0.047014698 -0.137639, + -0.0220857 -0.047137 -0.135921, + -0.019305199 -0.047044899 -0.13423499, + -0.0165099 -0.046742499 -0.13257401, + -0.0137106 -0.0462345 -0.130932, + -0.0109179 -0.045526002 -0.129306, + -0.0081428103 -0.044622399 -0.127689, + -0.0053973799 -0.043531101 -0.126077, + -0.00268824 -0.042259902 -0.124468, + 0 -0.040816698 -0.122858, + 0.00268824 -0.042259101 -0.124469, + 0.0053973799 -0.043529 -0.12607899, + 0.0081428103 -0.0446187 -0.127691, + 0.0109179 -0.045520399 -0.12931, + 0.0137106 -0.0462269 -0.13093799, + 0.0165099 -0.046732999 -0.13258, + 0.019305199 -0.047033802 -0.134242, + 0.0220857 -0.047124501 -0.13593, + 0.0248404 -0.047001399 -0.137648, + 0.027557701 -0.0466648 -0.139403, + 0.0302257 -0.046115801 -0.141201, + 0.0328326 -0.0453557 -0.143048, + 0.035366699 -0.044386499 -0.144949, + 0.0378174 -0.0432132 -0.146911, + 0.040174201 -0.041841902 -0.148939, + 0.0424264 -0.040278502 -0.15104, + 0.044564299 -0.038529899 -0.153218, + 0.0465803 -0.0366069 -0.155479, + 0.048467699 -0.034521502 -0.157827, + 0.050219599 -0.0322854 -0.160267, + 0.048467699 -0.034821 -0.160475, + 0.0465803 -0.036974002 -0.158078, + 0.044564299 -0.038965799 -0.15576801, + 0.0424264 -0.040784601 -0.15354, + 0.040174201 -0.042419098 -0.151389, + 0.0378174 -0.043861002 -0.14930899, + 0.035366699 -0.0451039 -0.147295, + 0.0328326 -0.0461418 -0.14534099, + 0.0302257 -0.046969801 -0.143442, + 0.027557701 -0.0475857 -0.14159, + 0.0248404 -0.0479884 -0.13978, + 0.0220857 -0.048176799 -0.138007, + 0.019305199 -0.048150301 -0.136264, + 0.0165099 -0.047911599 -0.134546, + 0.0137106 -0.047465399 -0.13284899, + 0.0109179 -0.046816401 -0.131166, + 0.0081428103 -0.045969799 -0.129493, + 0.0053973799 -0.044932999 -0.12782601, + 0.00268824 -0.043713801 -0.12616199, + 0 -0.0423197 -0.124497, + -0.00268824 -0.043714799 -0.12616099, + -0.0053973799 -0.044935498 -0.12782399, + -0.0081428103 -0.045974098 -0.12949, + -0.0109179 -0.046822499 -0.131162, + -0.0137106 -0.0474733 -0.132843, + -0.0165099 -0.047921199 -0.13454001, + -0.019305199 -0.048161201 -0.13625599, + -0.0220857 -0.048188601 -0.137998, + -0.0248404 -0.0480006 -0.139771, + -0.027557701 -0.047598001 -0.14158, + -0.0302257 -0.046982002 -0.14343099, + -0.0328326 -0.0461541 -0.145331, + -0.035366699 -0.045116499 -0.147285, + -0.0378174 -0.043874901 -0.149299, + -0.040174201 -0.042435601 -0.15138, + -0.0424264 -0.040805198 -0.153533, + -0.044564299 -0.038991399 -0.155764, + -0.0465803 -0.0370044 -0.158077, + -0.048467699 -0.034854699 -0.160476, + 0.042423699 -0.042423598 -0.171, + 0.039609101 -0.045067899 -0.191, + 0.040169802 -0.0445593 -0.171, + 0.0137069 -0.058396202 -0.171, + 0.0122713 -0.0587232 -0.171, + -0.0081412597 -0.059432399 -0.171, + -0.0061684698 -0.0596756 -0.171, + 0.0061689499 -0.059679601 -0.171, + 0.00814093 -0.0594301 -0.171, + 0.0057835602 0.059720598 -0.171, + 0.00923343 0.059285302 -0.191, + 0.0081407595 0.059433799 -0.171, + 0.00870548 0.059365101 -0.171, + 0.0109156 0.058985401 -0.171, + 0.0220857 0.056354702 -0.15301199, + 0.0248404 0.0558834 -0.144153, + 0.027557701 0.055544399 -0.135424, + 0.0302257 0.055342399 -0.126855, + 0.0328326 0.0552774 -0.11848, + 0.035366699 0.055348799 -0.110329, + 0.0378174 0.055558499 -0.102434, + 0.040174201 0.055907998 -0.094826996, + 0.0424264 0.056396201 -0.087537996, + 0.044564299 0.057020798 -0.080594003, + 0.0465803 0.057780702 -0.074024998, + 0.048467699 0.058674701 -0.067856997, + 0.050219599 0.057796899 -0.065636002, + 0.051830001 0.0567431 -0.063532002, + 0.0532961 0.0555338 -0.061558001, + 0.0546159 0.0541903 -0.059723999, + 0.055787299 0.052734502 -0.058038998, + 0.056809202 0.051187899 -0.056511998, + 0.0576833 0.0495723 -0.055149999, + 0.058412101 0.047913201 -0.053945001, + 0.058998398 0.0462193 -0.052864, + 0.059445001 0.0445024 -0.051904, + 0.059757002 0.042783201 -0.051054999, + 0.0599402 0.041076299 -0.050310001, + 0.059999999 0.039375201 -0.049681999, + 0.0599402 0.0376691 -0.049189001, + 0.059757002 0.0359492 -0.04885, + 0.059445001 0.0342164 -0.048670001, + 0.058998398 0.032474801 -0.048710998, + 0.058412101 0.0306706 -0.048920002, + 0.0576833 0.028816899 -0.049238998, + 0.056809202 0.026947999 -0.049676999, + 0.055787299 0.0250967 -0.050230999, + 0.0546159 0.023298001 -0.050894, + 0.0532961 0.021585699 -0.051651999, + 0.051830001 0.0199937 -0.052487001, + 0.050219599 0.018551299 -0.053371001, + 0.048467699 0.017283 -0.054274999, + 0.0465803 0.016206499 -0.055163, + 0.044564299 0.0153335 -0.056001, + 0.0424264 0.0146661 -0.056752, + 0.040174201 0.014192 -0.057379, + 0.0378174 0.0139076 -0.057854, + 0.035366699 0.0137906 -0.058152001, + 0.0328326 0.0137985 -0.058233999, + 0.0302257 0.0139422 -0.058093999, + 0.027557701 0.0141961 -0.057739999, + 0.0248404 0.0145411 -0.057174001, + 0.0220857 0.0145929 -0.057882998, + 0.019305199 0.0146171 -0.058455002, + 0.019305199 0.0145677 -0.057932999, + 0.0165099 0.0145406 -0.058818001, + 0.0165099 0.0143453 -0.058281001, + 0.0137106 0.0143286 -0.059016, + 0.0137106 0.0139793 -0.058538999, + 0.0109179 0.0139696 -0.059126999, + 0.0109179 0.0135106 -0.058766, + 0.0081428103 0.0135059 -0.059213001, + 0.0081428103 0.0129974 -0.059006002, + 0.0053973799 0.0129961 -0.059319001, + 0.0077019902 0.0125 -0.058988001, + 0.00814154 0.0125 -0.058933999, + 0.0086586103 0.0125 -0.058871999, + 0.0109179 0.0129995 -0.058557998, + 0.0137106 0.0135169 -0.058178999, + 0.0165099 0.0139914 -0.057806998, + 0.019305199 0.0143655 -0.057399999, + 0.0220857 0.0145994 -0.056896999, + 0.01156 0.0125 -0.058375999, + 0.0137077 0.0125 -0.057898998, + 0.0137813 0.0074999998 -0.057895999, + 0.0248351 0.0125 -0.054104, + 0.025434 0.0125 -0.05384, + 0.0255125 0.0125 -0.053805999, + 0.0275524 0.0125 -0.052786, + 0.030220401 0.0125 -0.051321, + 0.030710001 0.0125 -0.051045001, + 0.040174201 0.0146502 -0.045047998, + 0.040174201 0.0149505 -0.045520999, + 0.041313998 0.015159 -0.044911999, + 0.0424264 0.0152803 -0.044222001, + 0.040174201 0.0151159 -0.045986, + 0.0390082 0.0149184 -0.046558999, + 0.0378174 0.0146032 -0.047081999, + 0.0378174 0.0148873 -0.047564998, + 0.0390082 0.0150741 -0.047028001, + 0.040174201 0.0151703 -0.046408001, + 0.0390082 0.0151176 -0.047455002, + 0.0378174 0.0150336 -0.048039, + 0.036603201 0.0148572 -0.048537999, + 0.035366699 0.0145592 -0.048985999, + -0.00923343 0.059285302 -0.191, + -0.0088933604 0.059337199 -0.171, + -0.0081404103 0.0594313 -0.171, + -0.0109152 0.0589833 -0.171, + -0.0137071 0.058396801 -0.171, + -0.0146637 0.0581805 -0.171, + -0.0220857 0.056339402 -0.15301301, + -0.0248404 0.055869099 -0.144151, + -0.027557701 0.0555331 -0.135418, + -0.0302257 0.055331599 -0.126846, + -0.0328326 0.055264201 -0.118468, + -0.035366699 0.055331498 -0.110316, + -0.0378174 0.055537101 -0.10242, + -0.040174201 0.055884901 -0.094811998, + -0.0424264 0.0563743 -0.087522998, + -0.044564299 0.057003599 -0.080582, + -0.0465803 0.057772301 -0.074017003, + -0.048467699 0.0586771 -0.067855999, + -0.050219599 0.057798501 -0.065636002, + -0.051830001 0.056746799 -0.063532002, + -0.0532961 0.055540301 -0.061556999, + -0.0546159 0.054199401 -0.059721999, + -0.055787299 0.052744601 -0.058037002, + -0.056809202 0.051196098 -0.056511998, + -0.0576833 0.049576301 -0.055153001, + -0.058412101 0.047917701 -0.053946, + -0.058998398 0.046226598 -0.052864999, + -0.059445001 0.044513099 -0.051904999, + -0.059757002 0.042797599 -0.051054999, + -0.0599402 0.041093901 -0.050308, + -0.059999999 0.0393949 -0.049674001, + -0.0599402 0.037689 -0.049171001, + -0.059757002 0.035966799 -0.048820999, + -0.059445001 0.034228701 -0.048650999, + -0.058998398 0.032484598 -0.048712999, + -0.058412101 0.030685799 -0.048918001, + -0.0576833 0.0288387 -0.049231, + -0.056809202 0.026974401 -0.049663998, + -0.055787299 0.025123499 -0.050213002, + -0.0546159 0.0233222 -0.050872002, + -0.0532961 0.021606 -0.051628001, + -0.051830001 0.020009501 -0.052462, + -0.050219599 0.0185626 -0.053346001, + -0.048467699 0.0172904 -0.054249998, + -0.0465803 0.0162105 -0.05514, + -0.044564299 0.015333 -0.055978999, + -0.0424264 0.0146614 -0.056731999, + -0.040174201 0.014195 -0.057365999, + -0.0378174 0.0139224 -0.057851002, + -0.035366699 0.0137907 -0.058153, + -0.0328326 0.0137984 -0.058235001, + -0.0302257 0.0139439 -0.058095001, + -0.027557701 0.0141976 -0.057739999, + -0.0248404 0.0145433 -0.057172, + -0.0220857 0.0145964 -0.057882998, + -0.0220857 0.014666 -0.057413001, + -0.019305199 0.0146236 -0.058453999, + -0.020698 0.0145906 -0.057425998, + -0.0220857 0.0146076 -0.056889001, + -0.0220857 0.0143945 -0.056355, + -0.023467001 0.0146258 -0.056313999, + -0.020698 0.0143819 -0.05689, + -0.0220857 0.014024 -0.055888999, + -0.019305199 0.0140069 -0.056917001, + -0.019305199 0.0135351 -0.056568, + -0.0165099 0.0135255 -0.057443999, + -0.0165099 0.0130106 -0.057248, + -0.0137106 0.0130062 -0.057976998, + -0.0147097 0.0125 -0.057668999, + -0.0109179 0.0130026 -0.058563001, + -0.0118392 0.0125 -0.058320001, + -0.0137106 0.0135175 -0.058175001, + -0.0165099 0.0139922 -0.057796001, + -0.019305199 0.0143702 -0.057387002, + -0.0248404 0.0147146 -0.056219999, + -0.0167653 0.0125 -0.057094999, + -0.016505601 0.0125 -0.057167999, + -0.0109151 0.0125 -0.058483001, + -0.0107539 0.0125 -0.058511, + -0.0089402199 0.0125 -0.05883, + -0.0081428103 0.0129998 -0.059009001, + -0.0109179 0.0135111 -0.058763001, + -0.0137106 0.01398 -0.058529999, + -0.0165099 0.0143493 -0.058270998, + -0.019305199 0.0145748 -0.057925999, + -0.0165099 0.0145467 -0.058812, + -0.0137106 0.0143319 -0.059007, + -0.0109179 0.0139701 -0.059119999, + -0.0081428103 0.0135062 -0.059211001, + -0.0053973799 0.0129977 -0.059321001, + -0.0060197199 0.0125 -0.059197001, + 0 0.0129956 -0.059563, + -0.000142344 0.0125 -0.059500001, + -0.00268824 0.0129963 -0.059503, + -0.00268824 0.0135007 -0.059707999, + -0.0220857 0.055920701 -0.16201501, + -0.023037801 0.055400901 -0.171, + -0.0248404 0.054748401 -0.162064, + -0.0248404 0.055166598 -0.153109, + -0.027557701 0.053845402 -0.153217, + -0.027557701 0.054547701 -0.14431199, + -0.0302257 0.053079799 -0.144492, + -0.0302257 0.0540649 -0.135657, + -0.0328326 0.052452199 -0.135919, + -0.0328326 0.053718299 -0.127174, + -0.035366699 0.0519633 -0.12753101, + -0.035366699 0.053508401 -0.118896, + -0.0378174 0.0516169 -0.119358, + -0.0378174 0.053438898 -0.110854, + -0.040174201 0.051417299 -0.11143, + -0.040174201 0.053514302 -0.103079, + -0.0424264 0.051369298 -0.103778, + -0.0424264 0.0537383 -0.095601, + -0.044564299 0.0514769 -0.096432, + -0.044564299 0.054110799 -0.08845, + -0.0465803 0.0517423 -0.089419998, + -0.0465803 0.054632101 -0.081653997, + -0.048467699 0.052166 -0.082768999, + -0.048467699 0.055302002 -0.075240999, + -0.050219599 0.0527476 -0.076505996, + -0.050219599 0.056116801 -0.069234997, + -0.051830001 0.053482998 -0.070652999, + -0.051830001 0.055163201 -0.067114003, + -0.0532961 0.052466199 -0.068627, + -0.0532961 0.054052401 -0.065109, + -0.0546159 0.0513082 -0.066716, + -0.0546159 0.052802801 -0.063231997, + -0.055787299 0.050027501 -0.064929999, + -0.055787299 0.051435102 -0.061492, + -0.056809202 0.048645001 -0.063277997, + -0.056809202 0.049969699 -0.059898999, + -0.0576833 0.047180001 -0.061771002, + -0.0576833 0.048425902 -0.058462001, + -0.058412101 0.0456516 -0.060415, + -0.058412101 0.0468258 -0.057186, + -0.058998398 0.0440819 -0.059215002, + -0.058998398 0.045202199 -0.056056999, + -0.059445001 0.042503901 -0.058154002, + -0.059445001 0.0435603 -0.055043001, + -0.059757002 0.0409225 -0.057197001, + -0.059757002 0.041910201 -0.054138001, + -0.0599402 0.039341699 -0.056341, + -0.0599402 0.040266801 -0.053335, + -0.059999999 0.0377554 -0.055597, + -0.059999999 0.038623098 -0.052645002, + -0.0599402 0.036152299 -0.054981999, + -0.0599402 0.036967698 -0.052085001, + -0.059757002 0.034521598 -0.054513998, + -0.059757002 0.035289899 -0.051672999, + -0.059445001 0.032858599 -0.054207999, + -0.059445001 0.0335861 -0.051428001, + -0.058998398 0.0311797 -0.054062001, + -0.058998398 0.031876098 -0.051355999, + -0.058412101 0.0295086 -0.054078002, + -0.058412101 0.0301743 -0.051499002, + -0.0576833 0.027858499 -0.054292999, + -0.0576833 0.028434699 -0.051773001, + -0.056809202 0.0261869 -0.054625001, + -0.056809202 0.0266643 -0.052143, + -0.055787299 0.024501299 -0.055039998, + -0.055787299 0.024893099 -0.052618001, + -0.0546159 0.022831 -0.055544998, + -0.0546159 0.023150999 -0.053192999, + -0.0532961 0.0212052 -0.056132, + -0.0532961 0.021472801 -0.053858001, + -0.051830001 0.019657001 -0.056791, + -0.051830001 0.019892201 -0.0546, + -0.050219599 0.018217601 -0.057503998, + -0.050219599 0.018440999 -0.055397, + -0.048467699 0.016916201 -0.058249999, + -0.048467699 0.017146099 -0.056221999, + -0.0465803 0.015776301 -0.059002999, + -0.0465803 0.0160292 -0.057043999, + -0.044564299 0.0148162 -0.059730001, + -0.044564299 0.0151045 -0.057829998, + -0.0424264 0.0140476 -0.060401, + -0.0424264 0.0143795 -0.058545001, + -0.040174201 0.0134743 -0.060981002, + -0.040174201 0.0138545 -0.059154999, + -0.0378174 0.0130935 -0.061439998, + -0.0378174 0.0135255 -0.059631001, + -0.035366699 0.0128987 -0.061751001, + -0.035366699 0.0133791 -0.059946001, + -0.0328326 0.0128747 -0.061891001, + -0.0328326 0.0133653 -0.060068998, + -0.0302257 0.0129743 -0.061831001, + -0.0302257 0.0134814 -0.059969001, + -0.027557701 0.0131928 -0.061549, + -0.027557701 0.0137214 -0.05965, + -0.0248404 0.013521 -0.061048999, + -0.0248404 0.0140562 -0.059117999, + -0.0220857 0.0139308 -0.060339998, + -0.0220857 0.0144698 -0.058375001, + -0.019305199 0.0144057 -0.059424002, + -0.019305199 0.0145435 -0.058928002, + -0.0165099 0.0144982 -0.059822001, + -0.0165099 0.0145873 -0.059344001, + -0.0137106 0.0145569 -0.060086001, + -0.0137106 0.0145231 -0.059551999, + -0.0109179 0.0145041 -0.060146999, + -0.0109179 0.0143178 -0.059599999, + -0.0081428103 0.014307 -0.060051002, + -0.0081428103 0.0139626 -0.05957, + -0.0053973799 0.0139573 -0.059884999, + -0.0053973799 0.0135028 -0.059524, + -0.0046291598 0.0125 -0.059303001, + -0.0211595 0.056128498 -0.171, + -0.022079799 0.055771999 -0.171, + 0.00268824 0.0129955 -0.059502002, + 0.00154448 0.0125 -0.059462, + 0.0053973799 0.0135025 -0.059526, + 0.0081428103 0.0139622 -0.059574999, + 0.0109179 0.0143152 -0.059606999, + 0.0137106 0.0145181 -0.059556998, + 0.0165099 0.0145817 -0.059344999, + 0.019305199 0.0145404 -0.058928002, + 0.0220857 0.0144679 -0.058377001, + 0.0248404 0.0140549 -0.059117001, + 0.027557701 0.0137198 -0.059649002, + 0.0302257 0.0134815 -0.059969001, + 0.0328326 0.0133652 -0.060068998, + 0.035366699 0.0133653 -0.059948999, + 0.0378174 0.0135227 -0.059643, + 0.040174201 0.0138588 -0.059172999, + 0.0424264 0.0143799 -0.058566, + 0.044564299 0.0151007 -0.057852998, + 0.0465803 0.016022 -0.057068001, + 0.048467699 0.017135199 -0.056246001, + 0.050219599 0.018425699 -0.055420998, + 0.051830001 0.019872401 -0.054623999, + 0.0532961 0.021449201 -0.053879, + 0.0546159 0.023124799 -0.053210001, + 0.055787299 0.024867199 -0.052630998, + 0.056809202 0.026642799 -0.052150998, + 0.0576833 0.0284197 -0.051775999, + 0.058412101 0.030164599 -0.051498, + 0.058998398 0.031863902 -0.051375002, + 0.059445001 0.033568598 -0.051456001, + 0.059757002 0.035270002 -0.051690999, + 0.0599402 0.036947999 -0.052092999, + 0.059999999 0.0386055 -0.052646998, + 0.0599402 0.040252399 -0.053335, + 0.059757002 0.041899499 -0.054136999, + 0.059445001 0.043552998 -0.055041999, + 0.058998398 0.045197699 -0.056054998, + 0.058412101 0.046821699 -0.057184, + 0.0576833 0.048417501 -0.058462001, + 0.056809202 0.049959399 -0.059900999, + 0.055787299 0.0514258 -0.061494, + 0.0546159 0.052796099 -0.063233003, + 0.0532961 0.054048501 -0.065109998, + 0.051830001 0.055161599 -0.067114003, + 0.050219599 0.056114301 -0.069236003, + 0.048467699 0.055310801 -0.075249001, + 0.0465803 0.054650001 -0.081667997, + 0.044564299 0.054133799 -0.088466004, + 0.0424264 0.0537627 -0.095616996, + 0.040174201 0.053537 -0.103094, + 0.0378174 0.053457402 -0.110869, + 0.035366699 0.053522699 -0.118909, + 0.0328326 0.0537301 -0.127184, + 0.0302257 0.054077301 -0.135663, + 0.027557701 0.0545635 -0.144315, + 0.0248404 0.055183802 -0.153108, + 0.0220857 0.0559333 -0.16201399, + 0.0248404 0.054762501 -0.162062, + 0.0228623 0.0554736 -0.171, + 0.027557701 0.053443398 -0.16211601, + 0.0255554 0.054285601 -0.171, + 0.0302257 0.051978 -0.162176, + 0.028186901 0.0529669 -0.171, + 0.0328326 0.050368201 -0.162242, + 0.030750699 0.051520798 -0.171, + 0.035366699 0.0486168 -0.162314, + 0.0332404 0.0499507 -0.171, + 0.0378174 0.047150001 -0.15376601, + 0.040174201 0.0458293 -0.145385, + 0.0424264 0.044666 -0.137198, + 0.044564299 0.043671701 -0.129233, + 0.0465803 0.0428541 -0.121516, + 0.048467699 0.042219099 -0.114075, + 0.050219599 0.0417725 -0.106935, + 0.051830001 0.041518599 -0.100124, + 0.0532961 0.0414594 -0.093663998, + 0.0546159 0.041595198 -0.087576002, + 0.055787299 0.041924998 -0.081880003, + 0.056809202 0.042447001 -0.076595999, + 0.0576833 0.041296501 -0.074891999, + 0.058412101 0.040063702 -0.073294997, + 0.058998398 0.0387692 -0.071813002, + 0.035650201 0.048260398 -0.171, + 0.0028003999 0.0125 -0.059434999, + 0.0053968299 0.0125 -0.059248999, + 0.0026881699 0.0125 -0.059436999, + -7.3000002e-008 0.0125 -0.059496999, + -0.0053964402 0.0125 -0.059245002, + -0.0081410101 0.0125 -0.058931001, + 0.0077038999 0.0074999998 -0.059002999, + 0.0057364102 0.0125 -0.059225, + 0.0109157 0.0125 -0.058486, + -0.0328326 0.0294303 0.050128002, + -0.035366699 0.037327599 0.047885001, + -0.028198199 0.0125 0.053459998, + -0.0275518 0.0125 0.053785, + -0.0107568 0.0074999998 0.059528001, + -0.0081406701 0.0125 0.059932999, + -0.0137074 0.0125 0.058897998, + -0.0167691 0.0074999998 0.058109, + -0.0193005 0.0125 0.057294998, + -0.017363001 0.0125 0.057932999, + -0.0220802 0.0125 0.056272998, + -0.0226011 0.0125 0.056072999, + -0.0248404 0.0300972 0.054790001, + -0.027557701 0.0385 0.053167, + -0.0302257 0.040262401 0.051495001, + -0.0328326 0.041761398 0.049601998, + -0.035366699 0.043153699 0.047442999, + -0.0378174 0.044458698 0.045019001, + -0.040174201 0.045644399 0.042337999, + -0.0424264 0.046695601 0.039409999, + -0.040174201 0.047502801 0.041832, + -0.0378174 0.046359599 0.044613, + -0.035366699 0.0450853 0.047138002, + -0.0328326 0.043695599 0.049400002, + -0.0302257 0.042224102 0.051389001, + -0.027557701 0.040651999 0.053111002, + -0.0248404 0.038820401 0.054611001, + -0.0220857 0.0302749 0.056031998, + -0.0220857 0.039104901 0.055892002, + -0.0248404 0.041002698 0.054566, + -0.027557701 0.042645201 0.053017002, + -0.0302257 0.044193801 0.051199, + -0.0328326 0.0456669 0.049106002, + -0.035366699 0.047029201 0.046742, + -0.0378174 0.048264001 0.044116002, + -0.040174201 0.0493595 0.041235998, + 0.0081404904 0.0125 0.059932001, + 0.0077017802 0.0125 0.059985999, + 0.0059254402 0.0125 0.060206998, + 0.0053918599 0.021702901 0.060252, + 0.0081421202 0.030828999 0.059911001, + 0.0109179 0.0398845 0.059404999, + 0.0137106 0.042009301 0.05875, + 0.0165099 0.0438984 0.057884999, + 0.019305199 0.045727301 0.056756001, + 0.0220857 0.0475135 0.055351, + 0.0248404 0.049212299 0.053668998, + 0.027557701 0.050802998 0.051709998, + 0.0302257 0.0522715 0.049477, + 0.0328326 0.053604402 0.046971001, + 0.0302257 0.0562893 0.048034001, + 0.027557701 0.058961801 0.048836, + 0.0248404 0.0616026 0.049369998, + 0.0220857 0.064192101 0.049631, + 0.019305199 0.066711098 0.049617998, + 0.0165099 0.0691422 0.049332999, + 0.0137106 0.071469299 0.048781, + 0.0109179 0.073676199 0.047970001, + 0.0081421202 0.075748198 0.046907999, + 0.0053918599 0.077673398 0.045607999, + 0.00267513 0.0794416 0.044082999, + 0 0.081043497 0.042350002, + -0.00267513 0.079442702 0.044084001, + -0.0053918599 0.077675402 0.045609999, + -0.0081421202 0.075750999 0.046912, + -0.0109179 0.073679604 0.047975, + -0.0137106 0.071472898 0.048788, + -0.0165099 0.069146 0.049341001, + -0.019305199 0.066714697 0.049628001, + -0.0220857 0.064195499 0.049642999, + -0.0248404 0.061605599 0.049382001, + -0.027557701 0.0589641 0.04885, + -0.0302257 0.0562906 0.048048999, + -0.0328326 0.0536041 0.046987001, + -0.0302257 0.052269299 0.049490999, + -0.027557701 0.050799999 0.051723, + -0.0248404 0.049210399 0.053679001, + -0.0220857 0.047515199 0.055358, + -0.019305199 0.0457335 0.056759998, + -0.0165099 0.0439048 0.057886001, + -0.0137106 0.042011201 0.05875, + -0.0109179 0.0398845 0.059404999, + -0.0081421202 0.0308295 0.059911001, + -0.0109179 0.030761801 0.059438001, + -0.00875236 0.0125 0.059858002, + -0.0137106 0.0306729 0.058816001, + -0.0116529 0.0125 0.059358001, + -0.0165099 0.030562401 0.058042999, + -0.0145255 0.0125 0.058715001, + -0.019305199 0.039352998 0.057009999, + -0.0220857 0.041313902 0.055856999, + -0.0248404 0.043024302 0.054481, + -0.027557701 0.044647198 0.052836001, + -0.0302257 0.046201501 0.050914001, + -0.0328326 0.047650699 0.048719, + -0.035366699 0.048976701 0.046254002, + -0.0378174 0.050166901 0.043527, + -0.0167659 0.0125 0.058097001, + -0.016505999 0.0125 0.058169, + -0.0107542 0.0125 0.059512999, + -0.0109155 0.0125 0.059485, + -0.0058307201 0.0125 0.060215998, + 0.0302257 0.054286201 0.048806001, + 0.027557701 0.052858502 0.051144, + 0.0248404 0.051301099 0.053206, + 0.0220857 0.049627699 0.054992002, + 0.019305199 0.0478529 0.056499999, + 0.0165099 0.045998398 0.057732999, + 0.0137106 0.044108599 0.058694001, + 0.0109179 0.042165302 0.059395999, + 0.0081421202 0.039992899 0.059893001, + 0.0053918599 0.030876501 0.060242001, + 0.00267513 0.021714401 0.06044, + 0.0029901101 0.0125 0.060424998, + 0 0.021718301 0.060501002, + 0.00154442 0.0125 0.060462002, + 0.00267513 0.030904399 0.060435999, + 0.0053918599 0.040068701 0.060235001, + 0.0081421202 0.042284299 0.059888002, + 0.0109179 0.044277702 0.059344999, + 0.0137106 0.046224501 0.058547001, + 0.0165099 0.048143301 0.057482, + 0.019305199 0.049990099 0.056146, + 0.0220857 0.051743198 0.054533999, + 0.0248404 0.0533868 0.052643999, + 0.027557701 0.054906901 0.050476, + -0.0026750199 0.0125 0.060435001, + 0.00154487 0.0074999998 0.060479999, + 2.7e-008 0.0125 0.060499001, + 4.7590001e-005 0.0125 0.0605, + 0.0026749601 0.0125 0.060433, + 0.0053910702 0.0125 0.060247, + 0.0401715 0.0125 -0.044066999, + 0.0445593 0.0125 -0.039670002, + 0.049792401 0.0125 -0.032977, + 0.048886999 0.0125 -0.034255002, + 0.058998398 0.022908 -0.017076001, + 0.059445001 0.024958201 -0.015187, + 0.059757002 0.027196299 -0.013385, + 0.0599402 0.029669199 -0.01173, + 0.059999999 0.032342501 -0.010242, + 0.0599402 0.035213001 -0.0089349998, + 0.059757002 0.038259 -0.0078140004, + 0.059445001 0.0414504 -0.0068849898, + 0.058998398 0.0447441 -0.0061699999, + 0.058412101 0.048089601 -0.00569, + 0.0576833 0.051436 -0.0054539898, + 0.056809202 0.054731 -0.0054620099, + 0.055787299 0.057927798 -0.0057029999, + 0.0546159 0.0605237 -0.0044610002, + 0.0532961 0.0630951 -0.003332, + 0.051830001 0.065625198 -0.002323, + 0.050219599 0.068096504 -0.0014440001, + 0.048467699 0.070491403 -0.00069700601, + 0.0465803 0.072791502 -7.6995799e-005, + 0.044564299 0.074985199 0.000397995, + 0.0424264 0.077087998 0.00062199403, + 0.040174201 0.079275802 -0.001412, + 0.0378174 0.081302799 -0.003694, + 0.027557701 0.087583996 -0.0085279997, + 0.0248404 0.088766702 -0.0096349902, + 0.027557701 0.087595403 -0.0063129999, + 0.0302257 0.086247496 -0.007588, + 0.0302257 0.086231597 -0.0053960001, + 0.0328326 0.084763899 -0.00681799, + 0.0328326 0.084722698 -0.0046519898, + 0.035366699 0.0831405 -0.0062230099, + 0.035366699 0.083076201 -0.0040839999, + 0.0378174 0.081387803 -0.0058019999, + 0.0248404 0.088566102 -0.014108, + 0.0220857 0.089676999 -0.013156, + 0.0220857 0.089332402 -0.017658001, + 0.019305199 0.090314403 -0.016857, + 0.019305199 0.089821801 -0.021376999, + 0.0165099 0.0906718 -0.020717001, + 0.0165099 0.090028502 -0.025242001, + 0.0137106 0.090744801 -0.024713, + 0.0137106 0.089948401 -0.029232999, + 0.0109179 0.090529501 -0.028824, + 0.0109179 0.0895788 -0.033323999, + 0.0081421202 0.090024799 -0.033025, + 0.0081421202 0.088920198 -0.037493002, + 0.0053918599 0.0892336 -0.037292, + 0.0053918599 0.087976702 -0.041715, + 0.00267513 0.088161401 -0.041602001, + 0.00267513 0.086754501 -0.045967001, + 0 0.086815 -0.045931999, + 0 0.085260697 -0.05023, + -0.00267513 0.086754702 -0.045967001, + -0.00267513 0.088161699 -0.041602001, + -0.0053918599 0.087977402 -0.041715, + -0.0053918599 0.089234501 -0.037292, + -0.0081421202 0.088921502 -0.037493002, + -0.0081421202 0.0900262 -0.033025, + -0.0109179 0.089580797 -0.033323999, + -0.0109179 0.090531103 -0.028824, + -0.0137106 0.089950398 -0.029232999, + -0.0137106 0.090745702 -0.024714001, + -0.0165099 0.090029702 -0.025242999, + -0.0165099 0.090673096 -0.020717001, + -0.019305199 0.089823298 -0.021377999, + -0.019305199 0.090316802 -0.016857, + -0.0220857 0.089335099 -0.017658999, + -0.0220857 0.089681 -0.013156, + -0.0248404 0.088409998 -0.016344, + -0.040174201 0.0796225 -0.011809, + -0.040174201 0.0795798 -0.013903, + -0.0424264 0.077698603 -0.011634, + -0.0378174 0.081432402 -0.01215, + -0.0378174 0.081368603 -0.014273, + -0.035366699 0.0831175 -0.012659, + -0.035366699 0.083030403 -0.014809, + -0.0328326 0.084666699 -0.013335, + -0.0328326 0.084554203 -0.01551, + -0.0302257 0.086069703 -0.014177, + -0.0302257 0.085929804 -0.016373999, + -0.027557701 0.087319598 -0.015182, + -0.027557701 0.087150402 -0.017399, + -0.0248404 0.0882098 -0.018578, + -0.0220857 0.0888298 -0.022150001, + -0.019305199 0.089170903 -0.025877999, + -0.0165099 0.089228198 -0.029741, + -0.0137106 0.088996001 -0.033716001, + -0.0109179 0.088473603 -0.037779, + -0.0081421202 0.087663099 -0.041907001, + -0.0053918599 0.086569801 -0.046076, + -0.00267513 0.085200302 -0.050264001, + 0 0.0835637 -0.054453, + 0.00267513 0.085200198 -0.050264001, + 0.0053918599 0.086569399 -0.046076, + 0.0081421202 0.087662101 -0.041907001, + 0.0109179 0.0884718 -0.037780002, + 0.0137106 0.088993497 -0.033716999, + 0.0165099 0.089225799 -0.029741, + 0.019305199 0.089169599 -0.025877001, + 0.0220857 0.088828102 -0.022149, + 0.0248404 0.088206701 -0.018578, + 0.027557701 0.087314598 -0.015182, + 0.0302257 0.0860634 -0.014177, + 0.0328326 0.084658802 -0.013335, + 0.035366699 0.083108 -0.012659, + -0.0424264 0.077686101 -0.00957401, + -0.040174201 0.079628497 -0.0097169997, + -0.0378174 0.081459001 -0.010029, + -0.035366699 0.0831668 -0.01051, + -0.0328326 0.084740803 -0.01116, + -0.0302257 0.0861708 -0.011979, + -0.027557701 0.087449498 -0.012964, + -0.0248404 0.088570602 -0.014109, + -0.0248404 0.088691399 -0.011872, + -0.027557701 0.087540001 -0.010746, + -0.0302257 0.086232997 -0.0097820004, + -0.0328326 0.084776603 -0.0089870002, + -0.035366699 0.083178297 -0.0083619999, + -0.0378174 0.081448399 -0.0079100002, + -0.040174201 0.079597801 -0.0076290001, + -0.0424264 0.077637598 -0.0075180102, + -0.044564299 0.0754814 -0.00556, + -0.0465803 0.073190004 -0.003856, + -0.048467699 0.070965499 -0.0043439898, + -0.050219599 0.068675801 -0.0050529898, + -0.051830001 0.066306397 -0.0058849901, + -0.0532961 0.0638685 -0.00682201, + -0.0546159 0.061380502 -0.0078699999, + -0.055787299 0.0588594 -0.0090239998, + -0.055787299 0.058444001 -0.0073489998, + -0.0546159 0.061001901 -0.0061550001, + -0.0532961 0.063530602 -0.0050690002, + -0.051830001 0.066013597 -0.0041009998, + -0.050219599 0.068433598 -0.0032550001, + -0.048467699 0.070772097 -0.0025239999, + -0.0465803 0.073018298 -0.001925, + -0.044564299 0.075187698 -0.00155901, + -0.0424264 0.0774341 -0.003422, + -0.040174201 0.079530403 -0.0055440101, + -0.0378174 0.081400499 -0.0057940101, + -0.035366699 0.0831521 -0.0062179998, + -0.0328326 0.084774204 -0.006815, + -0.0302257 0.0862564 -0.00758701, + -0.027557701 0.087591402 -0.0085279997, + -0.0248404 0.088772602 -0.0096349902, + 0.027557701 0.087567799 -0.0041009998, + 0.0302257 0.086177103 -0.003207, + 0.0328326 0.084643498 -0.0024900101, + 0.035366699 0.082974598 -0.001951, + 0.0528326 0.0125 -0.027938001, + 0.052201699 0.0125 -0.029044, + 0.0522171 0.0074999998 -0.029053001, + 0.051817201 0.0125 -0.029718, + 0.050207902 0.0125 -0.032325, + 0.053282399 0.0125 -0.027051, + 0.054601099 0.0125 -0.024334, + 0.055771399 0.0125 -0.021578999, + 0.019305199 0.090674497 0.001258, + 0.0165099 0.091629297 -0.0024989899, + 0.0137106 0.0923144 -0.0064400001, + 0.0109179 0.092722401 -0.010544, + 0.0081421202 0.092847601 -0.014789, + 0.0053918599 0.092688702 -0.01915, + 0.00267513 0.092246503 -0.023603, + 0 0.091522999 -0.028124999, + -0.00267513 0.092246696 -0.023603, + -0.0053918599 0.092689097 -0.01915, + -0.0081421202 0.092848599 -0.014789, + -0.0109179 0.092724301 -0.010544, + -0.0137106 0.0923177 -0.0064400001, + -0.0165099 0.091634199 -0.0024979999, + -0.019305199 0.090776101 -0.00099699397, + -0.035366699 0.082461402 0.0044240002, + -0.035366699 0.082671702 0.0023119999, + -0.0378174 0.0806178 0.004683, + -0.0328326 0.084190503 0.003974, + -0.0328326 0.084382303 0.00183, + -0.0302257 0.085793398 0.00333701, + -0.0302257 0.085963003 0.00116299, + -0.027557701 0.087260902 0.0025160101, + -0.027557701 0.0874051 0.000315994, + -0.0248404 0.088584997 0.001517, + -0.0248404 0.088701501 -0.00070599403, + -0.0220857 0.089758702 0.000343994, + -0.0220857 0.089845397 -0.001899, + -0.019305199 0.090831198 -0.0032579999, + -0.0165099 0.091637202 -0.0070540002, + -0.0137106 0.092168801 -0.011021, + -0.0109179 0.092419602 -0.015139, + -0.0081421202 0.092385799 -0.019386001, + -0.0053918599 0.092066899 -0.023737, + -0.00267513 0.091463998 -0.028167, + 0 0.090579502 -0.032653, + 0.00267513 0.091463603 -0.028167, + 0.0053918599 0.092066497 -0.023736, + 0.0081421202 0.092385203 -0.019386001, + 0.0109179 0.092418298 -0.015139, + 0.0137106 0.092166297 -0.011021, + 0.0165099 0.091633201 -0.0070540002, + 0.019305199 0.090825498 -0.0032589999, + 0.0220857 0.0897514 0.000341003, + 0.0248404 0.088576697 0.00151199, + 0.027557701 0.0872517 0.002508, + 0.0302257 0.085783698 0.0033249999, + 0.0328326 0.084180802 0.0039590001, + 0.035366699 0.082210198 0.006511, + 0.0378174 0.080352202 0.0067199999, + 0.040174201 0.078373201 0.0066560102, + 0.0424264 0.076253198 0.0064249998, + 0.044564299 0.0740005 0.0060450002, + 0.0465803 0.071633801 0.005504, + 0.048467699 0.069170199 0.0048039998, + 0.050219599 0.066627003 0.0039490098, + 0.051830001 0.0640212 0.0029450101, + 0.0532961 0.061370701 0.00180099, + 0.0546159 0.0586945 0.00052600098, + 0.055787299 0.0560112 -0.00087199401, + 0.0328326 0.084371798 0.00181599, + 0.0302257 0.085952997 0.00115401, + 0.027557701 0.087395899 0.00031100499, + 0.0248404 0.088693298 -0.00070899999, + 0.0248404 0.088770702 -0.002935, + 0.027557701 0.087501302 -0.00189301, + 0.0302257 0.086084202 -0.001024, + 0.0328326 0.084526397 -0.00033299299, + 0.035366699 0.082835898 0.00017500301, + -0.0220857 0.089899503 -0.006397, + -0.0378174 0.081193298 -0.001577, + -0.0378174 0.081315398 -0.0036830001, + -0.040174201 0.079287603 -0.00139301, + -0.035366699 0.0829864 -0.00194099, + -0.035366699 0.0830881 -0.0040770001, + -0.0328326 0.084654503 -0.002483, + -0.0328326 0.084733501 -0.0046470002, + -0.0302257 0.086186998 -0.0032029999, + -0.0302257 0.086241104 -0.0053930101, + -0.027557701 0.087576501 -0.0040989998, + -0.027557701 0.087603502 -0.0063120001, + -0.0248404 0.088816099 -0.0051649902, + -0.0248404 0.088814199 -0.0073990002, + -0.0220857 0.089866601 -0.008649, + -0.0424264 0.077096798 0.000634995, + -0.044564299 0.074992299 0.00039999399, + -0.0465803 0.072799198 -7.80029e-005, + -0.048467699 0.070501402 -0.00069799798, + -0.050219599 0.068109602 -0.001442, + -0.051830001 0.065641701 -0.0023179899, + -0.0532961 0.063115202 -0.0033240099, + -0.0546159 0.060547002 -0.0044510001, + -0.055787299 0.0579536 -0.00569, + -0.055787299 0.057388101 -0.0040509901, + -0.0546159 0.060015202 -0.0027640101, + -0.0532961 0.062621497 -0.001592, + -0.051830001 0.065190203 -0.00054499798, + -0.050219599 0.067704402 0.00036900301, + -0.048467699 0.070147 0.00114301, + -0.0465803 0.072501101 0.00177499, + -0.044564299 0.074748598 0.0022740001, + -0.0424264 0.076878801 0.0026229999, + -0.040174201 0.078908898 0.00271899, + -0.0378174 0.081035502 0.00052099599, + -0.035366699 0.0828472 0.00018899501, + -0.0328326 0.084537402 -0.000324005, + -0.0302257 0.086094297 -0.00101801, + -0.027557701 0.087510303 -0.00188901, + -0.0248404 0.088778503 -0.002933, + -0.0220857 0.089892402 -0.0041470001, + -0.040174201 0.078669503 0.0047319899, + -0.0424264 0.076611601 0.0045210002, + -0.044564299 0.074424103 0.0041519902, + -0.0465803 0.072117403 0.00364301, + -0.048467699 0.069709599 0.0029819901, + -0.050219599 0.0672177 0.00217101, + -0.051830001 0.064658299 0.0012150001, + -0.0532961 0.062048599 0.00012300099, + -0.0546159 0.059405901 -0.001097, + -0.055787299 0.056748699 -0.0024359999, + -0.055787299 0.056037299 -0.00085200497, + -0.0546159 0.0587207 0.00054299901, + -0.0532961 0.061396301 0.00181599, + -0.051830001 0.064045198 0.0029569999, + -0.050219599 0.066648498 0.0039579901, + -0.048467699 0.069188498 0.0048110001, + -0.0465803 0.071648598 0.0055089998, + -0.044564299 0.074012101 0.0060470002, + -0.0424264 0.0762619 0.0064249998, + -0.040174201 0.078379899 0.0066550002, + -0.0378174 0.0803582 0.006722, + -0.035366699 0.0822175 0.0065229898, + -0.0328326 0.083963402 0.0061089899, + -0.0302257 0.0855866 0.00550301, + -0.027557701 0.087077901 0.0047089998, + -0.0248404 0.088429101 0.00373399, + -0.0220857 0.089632198 0.0025829901, + -0.019305199 0.090680897 0.00125999, + -0.053653099 0.0125 -0.026318001, + -0.054285601 0.0125 -0.025055001, + -0.053669199 0.0074999998 -0.026326001, + -0.053284999 0.0125 -0.027052, + -0.051820099 0.0125 -0.029720001, + -0.058021698 0.0074999998 0.01578, + -0.0576679 0.0125 0.017006001, + -0.058829699 0.0125 0.012293, + -0.058998398 0.0142714 0.011316, + -0.058412101 0.016029101 0.0138, + -0.0576833 0.0189978 0.015853001, + -0.056809202 0.024739601 0.017343, + -0.055787299 0.0309218 0.019026, + -0.0592779 0.0125 0.0097319903, + -0.0589833 0.0125 0.011415, + -0.0599204 0.0074999998 0.0035890001, + -0.059745401 0.0125 0.0058960002, + -0.059923101 0.0125 0.0035369999, + -0.059932198 0.0125 0.0031880001, + -0.059999902 0.0125 0.00059500098, + -0.0599977 0.0125 0.00050000002, + -0.0599402 0.0141237 -0.00232001, + -0.059757002 0.0140942 -0.0050360002, + -0.059914999 0.0125 -0.0025879999, + -0.0599402 0.0149109 -0.0024979999, + -0.059999999 0.0149558 0.000205002, + -0.059999999 0.0157077 -3.7994399e-005, + -0.0599402 0.0157708 0.0026750001, + -0.0599402 0.0170718 0.002138, + -0.059757002 0.017183 0.0048969998, + -0.059757002 0.0183022 0.0044439998, + -0.055787299 0.039015699 0.016365999, + -0.0546159 0.041460998 0.018821999, + -0.055787299 0.0416926 0.014945, + -0.056809202 0.037965901 0.013216, + -0.056809202 0.035402901 0.014383, + -0.0576833 0.034474801 0.011243, + -0.0576833 0.032071199 0.012183, + -0.058412101 0.031266298 0.0090760002, + -0.058412101 0.0288883 0.0098639997, + -0.058998398 0.0282102 0.0068090102, + -0.058998398 0.0234669 0.0084480001, + -0.059445001 0.023045801 0.005506, + -0.059445001 0.0184741 0.0072630001, + -0.059757002 0.0158343 0.0054100002, + -0.0599402 0.0150006 0.002907, + -0.059999999 0.0141529 0.00037399301, + -0.059935998 0.0125 -0.0021879999, + -0.0532961 0.044009302 0.021176999, + -0.051830001 0.046648201 0.02341, + -0.050219599 0.0493627 0.025498999, + -0.048467699 0.052136101 0.027424, + -0.0465803 0.054950301 0.029167, + -0.044564299 0.057785802 0.030710001, + -0.0424264 0.0606222 0.032037999, + -0.040174201 0.063438296 0.033137999, + -0.0378174 0.066213101 0.034001999, + -0.035366699 0.0689255 0.034621999, + -0.0328326 0.071555197 0.034993999, + -0.0302257 0.074081898 0.035115, + -0.027557701 0.076487698 0.034988001, + -0.0248404 0.078755297 0.034618001, + -0.0220857 0.080869898 0.034010999, + -0.019305199 0.082817703 0.033176001, + -0.0165099 0.084587999 0.032124002, + -0.0137106 0.086171702 0.03087, + -0.0109179 0.087562896 0.029425999, + -0.0081421202 0.088757403 0.027805001, + -0.0053918599 0.089753397 0.026022, + -0.00267513 0.090549998 0.024095999, + 0 0.091145597 0.022058999, + 0.00267513 0.090549499 0.024095999, + 0.0053918599 0.089752004 0.026022, + 0.0081421202 0.088754803 0.027804, + 0.0109179 0.087558798 0.029425001, + 0.0137106 0.086165898 0.030867999, + 0.0165099 0.084580302 0.032120999, + 0.019305199 0.082808398 0.03317, + 0.0220857 0.080859303 0.034003999, + 0.0248404 0.078743704 0.034609001, + 0.027557701 0.076475397 0.034977, + 0.0302257 0.074069403 0.035101999, + 0.0328326 0.071542703 0.034979001, + 0.035366699 0.0689134 0.034605, + 0.0378174 0.066201597 0.033984002, + 0.040174201 0.063427597 0.033117998, + 0.0424264 0.0606126 0.032016002, + 0.044564299 0.057777401 0.030687001, + 0.0465803 0.0549431 0.029143, + 0.048467699 0.052130301 0.027399, + 0.050219599 0.049358401 0.025473, + 0.051830001 0.046645898 0.023383999, + 0.0532961 0.044009902 0.021151001, + -0.059720598 0.0125 -0.0052840002, + -0.059433699 0.0125 -0.00764101, + -0.059285302 0.0074999998 -0.0087329997, + -0.059365101 0.0125 -0.0082050003, + -0.058866698 0.0125 -0.011106, + -0.058021698 0.0074999998 -0.01478, + -0.058398601 0.0125 -0.013208, + -0.058226701 0.0125 -0.013979, + -0.057446498 0.0125 -0.016818, + -0.056143001 0.0074999998 -0.020664999, + -0.056795198 0.0125 -0.018801, + -0.056527998 0.0125 -0.019614, + -0.055773601 0.0125 -0.021579999, + -0.054603402 0.0125 -0.024335001, + -0.0599204 0.0074999998 -0.0025889999, + -0.0599324 0.0125 -0.00234801, + -0.059748501 0.0125 -0.0048969998, + -0.0268177 0.053653602 -0.171, + 0.050000001 0 -0.208, + 0.049685601 0.00559822 -0.208, + 0.050000001 0 -0.191, + 0.049685601 0.00559822 -0.191, + 0.049685601 -0.00559822 -0.191, + 0.049685601 -0.00559822 -0.208, + 0.0487464 0.011126 -0.208, + 0.047194201 0.016514 -0.208, + 0.0487464 0.011126 -0.191, + 0.047194201 0.016514 -0.191, + 0.045048401 0.0216942 -0.208, + 0.045048401 0.0216942 -0.191, + 0.0353553 0.0353553 -0.208, + 0.0311745 0.039091598 -0.208, + 0.0353553 0.0353553 -0.191, + 0.0311745 0.039091598 -0.191, + 0.039091598 0.0311745 -0.191, + 0.039091598 0.0311745 -0.208, + -0.049685601 0.00559822 -0.208, + -0.050000001 0 -0.208, + -0.049685601 0.00559822 -0.191, + -0.050000001 0 -0.191, + -0.0487464 0.011126 -0.191, + -0.0487464 0.011126 -0.208, + -0.047194201 0.016514 -0.208, + -0.047194201 0.016514 -0.191, + -0.045048401 0.0216942 -0.191, + -0.045048401 0.0216942 -0.208, + -0.042336199 0.0266016 -0.208, + -0.049685601 -0.00559822 -0.208, + -0.0487464 -0.011126 -0.208, + -0.047194201 -0.016514 -0.208, + -0.045048401 -0.0216942 -0.208, + -0.042336199 -0.0266016 -0.208, + -0.039091598 -0.0311745 -0.208, + -0.0353553 -0.0353553 -0.208, + -0.0311745 -0.039091598 -0.208, + -0.0266016 -0.042336199 -0.208, + -0.039091598 0.0311745 -0.208, + -0.0353553 0.0353553 -0.208, + -0.0311745 0.039091598 -0.208, + -0.0266016 0.042336199 -0.208, + -0.0216942 0.045048401 -0.208, + -0.016514 0.047194201 -0.208, + -0.011126 0.0487464 -0.208, + -0.00559822 0.049685601 -0.208, + 0 0.050000001 -0.208, + -0.0216942 -0.045048401 -0.208, + -0.016514 -0.047194201 -0.208, + -0.011126 -0.0487464 -0.208, + -0.00559822 -0.049685601 -0.208, + 0 -0.050000001 -0.208, + 0.00559822 -0.049685601 -0.208, + 0.011126 -0.0487464 -0.208, + 0.00559822 0.049685601 -0.208, + 0.011126 0.0487464 -0.208, + 0.016514 0.047194201 -0.208, + 0.0216942 0.045048401 -0.208, + 0.0266016 0.042336199 -0.208, + 0.042336199 0.0266016 -0.208, + 0.0487464 -0.011126 -0.208, + 0.047194201 -0.016514 -0.208, + 0.045048401 -0.0216942 -0.208, + 0.042336199 -0.0266016 -0.208, + 0.039091598 -0.0311745 -0.208, + 0.0353553 -0.0353553 -0.208, + 0.016514 -0.047194201 -0.208, + 0.0216942 -0.045048401 -0.208, + 0.0311745 -0.039091598 -0.208, + 0.0266016 -0.042336199 -0.208, + -0.042336199 0.0266016 -0.191, + -0.00559822 0.049685601 -0.191, + 0 0.050000001 -0.191, + -0.011126 0.0487464 -0.191, + -0.016514 0.047194201 -0.191, + -0.0216942 0.045048401 -0.191, + 0.042336199 -0.0266016 -0.191, + 0.045048401 -0.0216942 -0.191, + 0.039091598 -0.0311745 -0.191, + 0.0266016 -0.042336199 -0.191, + 0.0216942 -0.045048401 -0.191, + 0.0311745 -0.039091598 -0.191, + 0.016514 -0.047194201 -0.191, + -0.016514 -0.047194201 -0.191, + -0.011126 -0.0487464 -0.191, + -0.0216942 -0.045048401 -0.191, + 0.0353553 -0.0353553 -0.191, + 0.011126 -0.0487464 -0.191, + -0.00559822 -0.049685601 -0.191, + -0.0266016 -0.042336199 -0.191, + -0.0311745 -0.039091598 -0.191, + 0.00559822 0.049685601 -0.191, + -0.0266016 0.042336199 -0.191, + -0.0353553 0.0353553 -0.191, + -0.039091598 0.0311745 -0.191, + -0.0311745 0.039091598 -0.191, + 0.0216942 0.045048401 -0.191, + 0.0266016 0.042336199 -0.191, + 0.016514 0.047194201 -0.191, + 0.042336199 0.0266016 -0.191, + -0.047194201 -0.016514 -0.191, + -0.045048401 -0.0216942 -0.191, + -0.0487464 -0.011126 -0.191, + 0.047194201 -0.016514 -0.191, + 0.0487464 -0.011126 -0.191, + -0.049685601 -0.00559822 -0.191, + -0.0353553 -0.0353553 -0.191, + -0.039091598 -0.0311745 -0.191, + -0.042336199 -0.0266016 -0.191, + 0.00559822 -0.049685601 -0.191, + 0 -0.050000001 -0.191, + 0.011126 0.0487464 -0.191, + -0.0053910101 0.0597458 -0.171 ] + + } + normal + Normal { + vector [ 0.91223741 -0.043468721 -0.4073492, + 0.89959979 0.0047923592 -0.4366889, + 0.895239 -0.100951 -0.43399999, + 0.91711313 -0.09031181 -0.38826206, + 0.911035 -0.147448 -0.38506401, + 0.93191612 -0.12969202 -0.33869204, + 0.92560089 -0.17497298 -0.33562997, + 0.94524676 -0.15086697 -0.28939193, + 0.93674409 -0.20239803 -0.28556204, + 0.95659626 -0.16851304 -0.23775406, + 0.95129734 -0.19933207 -0.23516008, + 0.96901298 -0.15971801 -0.188425, + 0.96937209 -0.15725602 -0.18864903, + 0.98477751 -0.11129694 -0.13351494, + 0.98558074 -0.10206497 -0.13495697, + 0.99384087 -0.06684459 -0.088386692, + 0.99391311 -0.065284111 -0.088740505, + 0.99798936 -0.037559114 -0.051054019, + 0.99795145 -0.039070919 -0.050660122, + 0.99979275 -0.012433897 -0.016121997, + 0.99978948 -0.012850407 -0.015998807, + 0.99980277 0.012437097 0.015484196, + 0.99979699 0.0131852 0.0152349, + 0.99824035 0.038805217 0.044837616, + 0.99818045 0.041347917 0.043889023, + 0.99517488 0.067280792 0.071415693, + 0.99497652 0.072157264 0.06939137, + 0.990529 0.0989668 0.095173202, + 0.99006063 0.10671296 0.091609567, + 0.98409367 0.13479395 0.11571596, + 0.98318988 0.14553899 0.11025499, + 0.97570652 0.17462891 0.13229294, + 0.97412515 0.18868104 0.12441801, + 0.96493363 0.21913892 0.14450295, + 0.37527218 0.9243564 0.068818927, + 0.37916884 0.92175466 0.081236273, + 0.42103791 0.90354079 0.079631075, + 0.42486399 0.90070301 0.090690397, + 0.46588683 0.88039273 0.088645473, + 0.47205696 0.87527686 0.10513099, + 0.50935084 0.85441768 0.10262597, + 0.51614195 0.8481459 0.11935698, + 0.55583888 0.82317883 0.11584397, + 0.56469494 0.81389987 0.13669899, + 0.60287106 0.78681815 0.13215101, + 0.61402392 0.77334386 0.15784098, + 0.65060782 0.74407381 0.15186697, + 0.6609242 0.72964817 0.17547904, + 0.69573939 0.69838142 0.16795911, + 0.70504218 0.68341219 0.18937604, + 0.73797196 0.65032494 0.18020798, + 0.74609923 0.63534021 0.19919507, + 0.77645653 0.60130966 0.18852589, + 0.78345299 0.58656698 0.205282, + 0.81122285 0.55191392 0.19315398, + 0.81712091 0.53772295 0.20776796, + 0.84250313 0.50248706 0.19415303, + 0.84737539 0.48908064 0.20677285, + 0.87049073 0.45333484 0.19165993, + 0.87438685 0.44104788 0.20229796, + 0.89489222 0.4056471 0.18606004, + 0.89794624 0.3945761 0.19494204, + 0.91607869 0.35951489 0.17761993, + 0.91844773 0.3495979 0.18502696, + 0.93441337 0.31481713 0.16661906, + 0.93618113 0.30620602 0.17263502, + 0.95134503 0.26840901 0.151325, + 0.95126289 0.26836297 0.15192199, + 0.96239275 0.23640893 0.13383196, + 0.92971522 0.34578907 0.12672703, + 0.91034824 0.3885701 0.14240603, + 0.90726161 0.39869481 0.13386095, + 0.88758779 0.43668291 0.14661497, + 0.88357478 0.4480179 0.13629197, + 0.86136568 0.48599482 0.14784494, + 0.85631555 0.49832076 0.13564694, + 0.83141279 0.53614688 0.14594297, + 0.82520986 0.54925293 0.13171898, + 0.79804516 0.5859831 0.14052702, + 0.7905758 0.59965587 0.12410797, + 0.76109791 0.63517594 0.13145898, + 0.75230509 0.64909607 0.11274502, + 0.72038084 0.68334681 0.11869497, + 0.71043605 0.69690508 0.097999215, + 0.67623121 0.72951216 0.10258402, + 0.66854781 0.7386018 0.08666718, + 0.63291705 0.76894414 0.090227507, + 0.59330177 0.8010307 0.079641469, + 0.62668693 0.77544791 0.077097893, + 0.36251798 0.93196291 -0.0050934595, + 0.32340309 0.94624722 -0.0051715313, + 0.31476587 0.94850165 -0.035596788, + 0.27571505 0.96056324 -0.036049508, + 0.26784688 0.96108454 -0.067635171, + 0.22902289 0.97101951 -0.068334267, + 0.22210692 0.96980864 -0.10069596, + 0.183496 0.97776401 -0.101522, + 0.17766294 0.97485065 -0.13454396, + 0.13930401 0.98095113 -0.13538602, + 0.13465606 0.97637349 -0.16900508, + 0.096970282 0.98070389 -0.16975498, + 0.093590558 0.97453153 -0.20378689, + 0.056575816 0.97726023 -0.20435704, + 0.054521807 0.96963912 -0.23838504, + 0.018367592 0.97091967 -0.23869991, + 0.017668001 0.96191311 -0.27278402, + -0.01759241 0.96191448 -0.27278411, + -0.018276498 0.97090888 -0.23875096, + -0.054339509 0.96963626 -0.23843805, + -0.056398883 0.97728276 -0.20429796, + -0.093454793 0.97455686 -0.20372798, + -0.096839853 0.98073852 -0.16962892, + -0.13454394 0.97641051 -0.16887993, + -0.13918595 0.98096865 -0.13537996, + -0.17759694 0.97486365 -0.13453695, + -0.18340296 0.97776574 -0.10167298, + -0.22197694 0.96982276 -0.10084698, + -0.2288851 0.97103846 -0.068527527, + -0.26761791 0.96113467 -0.067828581, + -0.27548495 0.96061975 -0.036298994, + -0.3106811 0.94983637 -0.035891511, + 0.85095316 -0.004290171 -0.52522409, + 0.95367712 -0.22014503 -0.20502703, + 0.92217201 -0.283041 -0.263603, + 0.92078763 -0.28818592 -0.26286691, + 0.88981313 -0.33714002 -0.30752102, + 0.90928876 -0.26931393 -0.31727591, + 0.87915921 -0.30837607 -0.36329508, + 0.90021086 -0.22278097 -0.37415096, + 0.87364143 -0.24893212 -0.41807121, + 0.88658297 -0.181576 -0.42544201, + 0.85990769 -0.20037092 -0.46947882, + 0.87078041 -0.12202506 -0.47628924, + 0.84368527 -0.13323404 -0.52004218, + 0.78406054 -0.013024593 -0.62054765, + 0.71608293 -0.014194098 -0.69787097, + -0.073298603 0.000321981 0.99730998, + 0.027852291 0.37077588 0.92830461, + 0.027832707 0.41337109 0.91013724, + -0.02710199 0.41337886 0.91015571, + -0.027112586 0.37057781 0.92840558, + 0.027658496 0.37057197 0.92839187, + 0.027640697 0.32714197 0.9445709, + -0.026917892 0.32714787 0.94458961, + -0.026946209 0.37075612 0.92833936, + -0.082889661 0.36961481 0.9254806, + -0.082837291 0.41268593 0.90709889, + -0.027659597 0.41395095 0.90987891, + -0.027603405 0.45604604 0.8895281, + 0.02798859 0.45604086 0.88951868, + 0.028048107 0.4135921 0.91003025, + 0.083177872 0.41232085 0.90723372, + 0.083234027 0.36963311 0.92544234, + -0.02670721 0.23870309 0.97072536, + -0.080183007 0.23801903 0.9679451, + -0.080468625 0.28308806 0.95571226, + -0.13579796 0.28137791 0.94993967, + -0.13608904 0.32625511 0.93543434, + -0.19308604 0.32312208 0.92645025, + -0.19321093 0.36554289 0.91052067, + -0.13733594 0.36903283 0.91921359, + -0.137233 0.32488501 0.93574399, + -0.081415266 0.32689986 0.94154555, + -0.081239775 0.28218293 0.95591474, + -0.02691781 0.28301609 0.95873737, + -0.026822796 0.23856997 0.97075486, + 0.027169997 0.23856696 0.97074586, + 0.027257096 0.28302598 0.95872486, + 0.081591465 0.28218687 0.9558835, + 0.081763372 0.32693088 0.94150466, + 0.13790596 0.32489488 0.93564165, + 0.13799699 0.36835396 0.91938686, + 0.082325093 0.37064996 0.9251169, + 0.082264006 0.32635704 0.94166011, + 0.027457591 0.32734287 0.94450665, + 0.0274048 0.282859 0.95876998, + -0.0270546 0.28286201 0.95877898, + -0.027114097 0.32693198 0.94465888, + -0.082249038 0.32594416 0.94180447, + -0.082308263 0.37026483 0.92527258, + -0.13825598 0.36795697 0.91950691, + -0.13817304 0.41043615 0.90136027, + -0.083120927 0.41297716 0.90694028, + -0.082957871 0.45486984 0.88668573, + -0.027825208 0.45626611 0.88940823, + -0.027726499 0.49795601 0.866759, + 0.028126312 0.49795023 0.86674941, + 0.028227413 0.4562782 0.8893894, + 0.083651364 0.45485979 0.88662559, + 0.083824508 0.41298506 0.90687209, + 0.13854 0.410447 0.901299, + 0.13862704 0.36902413 0.91902333, + 0.19354098 0.36557698 0.91043687, + 0.1934211 0.32315314 0.92636943, + 0.13674897 0.32627892 0.93532974, + 0.13646801 0.28099802 0.94995612, + 0.081139833 0.28271708 0.95576537, + 0.080867976 0.23801593 0.96788877, + 0.027045906 0.23871006 0.97071421, + 0.026926413 0.19424509 0.98058349, + -0.026579088 0.19424692 0.98059255, + -0.02611419 0.19479293 0.98049664, + -0.079092763 0.19424891 0.97775853, + -0.079475462 0.23886688 0.96779454, + -0.13462898 0.23744297 0.96202689, + -0.13509095 0.28224385 0.9497835, + -0.19156691 0.27957889 0.94081753, + -0.19194695 0.32454991 0.92618775, + -0.24865203 0.32031304 0.91409612, + -0.2487931 0.36230713 0.89824027, + -0.19449303 0.36692604 0.9096911, + -0.19435796 0.40796191 0.89207178, + -0.13951704 0.41182515 0.90051931, + -0.13923396 0.45269486 0.88072771, + -0.083637074 0.45554584 0.8862747, + -0.083350711 0.49664906 0.86394012, + -0.027967095 0.49818793 0.86661786, + -0.027825 0.53878599 0.84198302, + 0.0282431 0.53877997 0.84197301, + 0.028386693 0.49820089 0.86659682, + 0.083732329 0.49665219 0.86390132, + 0.084022209 0.45522907 0.88640112, + 0.139617 0.45236999 0.88083398, + 0.13989903 0.41185108 0.90044826, + 0.19502297 0.40795493 0.89192986, + 0.19516693 0.3673299 0.90938371, + 0.24941097 0.36269596 0.89791191, + 0.24928197 0.32034898 0.91391188, + 0.19225095 0.3246209 0.92609978, + 0.19187704 0.27962005 0.94074225, + 0.13541301 0.28229001 0.94972402, + 0.13495804 0.23745309 0.96197838, + 0.080151401 0.238874 0.96773702, + 0.07978078 0.19424295 0.97770375, + 0.026457196 0.19479597 0.98048687, + 0.026304897 0.15038298 0.98827785, + -0.025955796 0.15038398 0.98828685, + -0.025866296 0.15049098 0.98827291, + -0.078325935 0.15007907 0.9855665, + -0.078797176 0.19460896 0.97771078, + -0.13305597 0.19348095 0.97203976, + -0.13368498 0.23862197 0.96186686, + -0.18930598 0.23642997 0.95302886, + -0.18993795 0.28166795 0.94052476, + -0.24644797 0.27804196 0.92841589, + -0.24690895 0.32261291 0.91375977, + -0.30328006 0.31724009 0.89854324, + -0.30341798 0.35871196 0.88275886, + -0.25072888 0.36443383 0.89684057, + -0.2505399 0.40388185 0.87983471, + -0.19548196 0.40913892 0.89128679, + -0.19509792 0.44921485 0.8718617, + -0.14004 0.45350301 0.88018399, + -0.13956201 0.49391106 0.85823911, + -0.083756693 0.49703994 0.86367589, + -0.083353475 0.53704888 0.83942282, + -0.02775109 0.53871679 0.84202969, + -0.027574297 0.57807595 0.81551689, + 0.028011199 0.57806897 0.81550699, + 0.02818911 0.53872919 0.84200728, + 0.084059179 0.53703588 0.83936083, + 0.084470131 0.49736318 0.86342031, + 0.14027004 0.49421218 0.85795027, + 0.14076097 0.45351687 0.88006175, + 0.19575191 0.4492158 0.87171459, + 0.19614697 0.40913194 0.89114386, + 0.250855 0.40389499 0.87973899, + 0.25104788 0.36449483 0.89672661, + 0.30400896 0.35873097 0.88254786, + 0.30388388 0.31765187 0.89819372, + 0.24722002 0.32307002 0.91351414, + 0.24676389 0.27807689 0.9283216, + 0.19024791 0.28170985 0.94044954, + 0.18962395 0.23644593 0.95296174, + 0.13400599 0.23864301 0.96181703, + 0.13339198 0.19388196 0.97191375, + 0.079147138 0.19501609 0.97760147, + 0.078678019 0.15004803 0.98554325, + 0.026237912 0.15046307 0.98826748, + 0.026057595 0.10686599 0.99393189, + -0.025686985 0.10686693 0.99394143, + -0.02561209 0.10695796 0.99393362, + -0.077179909 0.10667402 0.99129415, + -0.077729084 0.15081897 0.98550075, + -0.13145506 0.14996408 0.97991347, + -0.13223097 0.19453095 0.97194278, + -0.18731 0.192781 0.96319801, + -0.18817404 0.23791206 0.95288426, + -0.24413097 0.23490997 0.94085985, + -0.24491212 0.28011411 0.92819941, + -0.30076814 0.27553511 0.91302741, + -0.30128893 0.3200129 0.89822978, + -0.35751188 0.31342688 0.8797437, + -0.3576189 0.35427791 0.86405784, + -0.30564094 0.3612119 0.88097078, + -0.30539197 0.39932495 0.86445087, + -0.25232804 0.40578905 0.87844515, + -0.25181398 0.44494393 0.85942686, + -0.19664395 0.45078188 0.87070483, + -0.19598804 0.49006712 0.84936619, + -0.14048298 0.49480289 0.85757482, + -0.13980398 0.53438389 0.83359981, + -0.084128305 0.53777105 0.8388831, + -0.083596706 0.57652605 0.81279111, + -0.027853087 0.5783267 0.81532961, + -0.027629592 0.61675674 0.78666872, + 0.028383195 0.61674392 0.78665191, + 0.028616603 0.57861304 0.81510013, + 0.08431711 0.57678908 0.8125301, + 0.0848637 0.53778499 0.83880001, + 0.14049803 0.53437912 0.8334862, + 0.14118204 0.49509713 0.85729021, + 0.19662292 0.49034381 0.8490597, + 0.19729508 0.45078021 0.87055844, + 0.25213906 0.44496211 0.85932219, + 0.25265494 0.4058159 0.87833875, + 0.30569816 0.39934519 0.86433339, + 0.30595088 0.36091787 0.88098371, + 0.35790187 0.35398489 0.8640607, + 0.35780317 0.31387514 0.8794654, + 0.30187786 0.32044587 0.89787757, + 0.30136704 0.27557403 0.91281813, + 0.24519908 0.28018808 0.92810136, + 0.24442503 0.23493204 0.94077814, + 0.18848293 0.23793791 0.95281667, + 0.18763593 0.19315493 0.96305966, + 0.13258196 0.19491096 0.97181875, + 0.13180594 0.14989093 0.97987753, + 0.078113712 0.15074803 0.98548126, + 0.077563509 0.10662802 0.99126911, + 0.026017895 0.10691398 0.99392778, + 0.025798392 0.062176779 0.99773163, + -0.025404494 0.062177386 0.99774176, + -0.025007995 0.062672883 0.99772078, + -0.076022469 0.062511079 0.99514467, + -0.076658159 0.10733195 0.99126351, + -0.12947901 0.106743 0.98582, + -0.13039795 0.15133092 0.97984451, + -0.18458298 0.15001199 0.9713009, + -0.18565999 0.19497997 0.96307486, + -0.2410861 0.19257708 0.95120537, + -0.24216007 0.23762205 0.94068825, + -0.29782197 0.23379797 0.92554885, + -0.29871807 0.27845305 0.91281521, + -0.354478 0.27282801 0.89437699, + -0.35502201 0.317099 0.87943602, + -0.41019785 0.30934489 0.85792971, + -0.41025907 0.34879604 0.84263211, + -0.35983402 0.35684603 0.86207914, + -0.35950997 0.39385894 0.84594786, + -0.30750084 0.40162781 0.8626346, + -0.306885 0.43912101 0.84438998, + -0.25317806 0.44635212 0.8582952, + -0.25233099 0.48533401 0.83712602, + -0.19762602 0.49167207 0.8480581, + -0.19668603 0.53012204 0.82479411, + -0.14078295 0.53529882 0.83284771, + -0.13990298 0.57360291 0.80709785, + -0.084386095 0.57723397 0.81220686, + -0.083718091 0.61481696 0.7842139, + -0.027618701 0.61674798 0.78667599, + -0.027360504 0.65362006 0.75632811, + 0.02784059 0.65361178 0.75631768, + 0.028100604 0.61649907 0.78685415, + 0.083903022 0.61456811 0.7843892, + 0.084558293 0.57700592 0.81235087, + 0.14060095 0.57332683 0.80717272, + 0.14148393 0.53530079 0.83272761, + 0.19677505 0.53016812 0.82474315, + 0.19771509 0.49141324 0.84818745, + 0.25296801 0.48500401 0.837125, + 0.25381005 0.44668913 0.85793316, + 0.30720714 0.4394792 0.84408641, + 0.30783302 0.40167707 0.8624931, + 0.36006409 0.39386109 0.84571117, + 0.3603971 0.35687909 0.86183017, + 0.41053295 0.34886298 0.84247088, + 0.41047707 0.30944204 0.85776114, + 0.35556799 0.31717199 0.87918901, + 0.35503608 0.27288207 0.89413923, + 0.29929987 0.2785179 0.91260469, + 0.29840404 0.23339103 0.92546409, + 0.24276611 0.23721611 0.94063449, + 0.24170803 0.19252503 0.95105809, + 0.18630005 0.19493507 0.96296036, + 0.18523099 0.14992599 0.97119087, + 0.13075002 0.15125701 0.97980911, + 0.12983997 0.10711898 0.98573178, + 0.076702259 0.10771495 0.99121851, + 0.076052673 0.062966779 0.99511367, + 0.025036005 0.063129917 0.99769121, + 0.024795797 0.020125197 0.9994899, + -0.024787603 0.020125201 0.99949014, + -0.024780804 0.020133702 0.99949014, + -0.074884199 0.020083301 0.99699003, + -0.07557261 0.063094705 0.9951421, + -0.12779894 0.062756769 0.98981255, + -0.12885894 0.10755895 0.98581254, + -0.18212104 0.10665002 0.97747523, + -0.18340304 0.15161103 0.97127622, + -0.23827595 0.14978397 0.95957774, + -0.23962393 0.19462596 0.95115775, + -0.29505485 0.19154191 0.93608457, + -0.29629898 0.23601097 0.9254759, + -0.35125887 0.23136091 0.90724272, + -0.35224912 0.27618808 0.89422631, + -0.40724909 0.26952207 0.87264317, + -0.40778092 0.3131299 0.85770881, + -0.46157521 0.30422115 0.83330542, + -0.46157581 0.34252784 0.8183046, + -0.41268006 0.35170802 0.84023613, + -0.41228092 0.3872219 0.8246718, + -0.3616409 0.39625791 0.84391683, + -0.36090392 0.43298292 0.82599884, + -0.30916083 0.44152874 0.84230155, + -0.30813313 0.47913817 0.82187629, + -0.25411308 0.48711118 0.83555329, + -0.25294399 0.52434701 0.81306797, + -0.19788392 0.53125381 0.82377869, + -0.19666091 0.5690127 0.79846662, + -0.14095698 0.57455194 0.80623889, + -0.139874 0.611444 0.77882701, + -0.084297173 0.61531675 0.78375971, + -0.083492406 0.65204507 0.75356913, + -0.027907092 0.65407485 0.75591481, + -0.02758879 0.68940377 0.72385174, + 0.028114296 0.68939394 0.72384095, + 0.028431 0.65410298 0.755871, + 0.083959781 0.65205681 0.75350684, + 0.084765397 0.61531198 0.78371298, + 0.14057501 0.61140299 0.77873302, + 0.14167397 0.5742929 0.80629784, + 0.19708496 0.56876594 0.79853791, + 0.19828989 0.53159869 0.82345855, + 0.25356492 0.52464283 0.8126837, + 0.25476304 0.48679605 0.8355391, + 0.30821884 0.47889876 0.82198358, + 0.30923012 0.44162014 0.84222829, + 0.36145988 0.43298286 0.82575572, + 0.36220509 0.39627409 0.84366715, + 0.41280091 0.38722792 0.82440883, + 0.41320714 0.35208213 0.83982033, + 0.46204379 0.34288785 0.81788957, + 0.46206081 0.30465189 0.83287871, + 0.4077822 0.31366315 0.85751343, + 0.407251 0.269649 0.872603, + 0.3527981 0.27625805 0.89398825, + 0.35183087 0.23175392 0.90692073, + 0.29628712 0.23646709 0.92536336, + 0.29505202 0.19192003 0.9360081, + 0.23994701 0.194994 0.95100099, + 0.23860788 0.15008293 0.95944852, + 0.18376099 0.15191598 0.97116089, + 0.18249705 0.10742304 0.97732037, + 0.12890603 0.10834602 0.98572022, + 0.127817 0.062762 0.98980999, + 0.075951405 0.063098304 0.99511313, + 0.075248055 0.020089388 0.99696243, + 0.024783896 0.020140298 0.9994899, + -0.074155569 0.00043599185 0.99724662, + -0.074498467 0.020588793 0.99700862, + -0.12580003 0.020482106 0.99184424, + -0.12695602 0.063897304 0.98984814, + -0.17928709 0.063374832 0.98175347, + -0.18076904 0.10851202 0.97752124, + -0.23507792 0.10723796 0.96604264, + -0.23668496 0.15205099 0.95961487, + -0.29127806 0.14971103 0.94485122, + -0.29287195 0.19477096 0.93610376, + -0.34738001 0.191017 0.91806298, + -0.34876099 0.23520499 0.90721798, + -0.40360808 0.22961406 0.88565123, + -0.40463206 0.27371302 0.87255609, + -0.45827201 0.266031 0.84806502, + -0.45876583 0.30890989 0.83313173, + -0.51113087 0.29880893 0.80588984, + -0.51103598 0.336225 0.79107201, + -0.46463495 0.34637296 0.8149479, + -0.46413478 0.38028881 0.79997462, + -0.41515893 0.39058593 0.8216359, + -0.414307 0.42543799 0.804582, + -0.36322787 0.43551686 0.8236447, + -0.3620548 0.47169673 0.80400151, + -0.31004393 0.48109087 0.82001483, + -0.30863115 0.51758522 0.79803038, + -0.25485402 0.52618206 0.81128412, + -0.25332391 0.56271982 0.78687572, + -0.19795008 0.57018316 0.79731232, + -0.19646697 0.60627192 0.77060688, + -0.14071502 0.61217105 0.77810413, + -0.13941205 0.64822322 0.74857926, + -0.083815411 0.65231204 0.7533021, + -0.082897492 0.68734092 0.72158897, + -0.02764811 0.68945122 0.72380424, + -0.027299404 0.72290105 0.69041204, + 0.027831009 0.72289026 0.69040221, + 0.028179597 0.68944591 0.72378892, + 0.083654732 0.68730223 0.72153825, + 0.084577501 0.65256703 0.75299603, + 0.14013804 0.64845121 0.74824625, + 0.14145893 0.6121667 0.77797264, + 0.19688091 0.6062817 0.77049363, + 0.19837396 0.56993586 0.79738384, + 0.25370494 0.56246686 0.78693384, + 0.25522193 0.52623385 0.81113482, + 0.30897897 0.51762795 0.79786789, + 0.31039402 0.48112205 0.81986409, + 0.36261296 0.47167295 0.80376387, + 0.36379379 0.43553072 0.8233875, + 0.41458791 0.4254919 0.80440885, + 0.41544715 0.39032516 0.82161433, + 0.46416822 0.38008219 0.80005336, + 0.46466321 0.34618118 0.81501341, + 0.51126504 0.33599204 0.79102314, + 0.51136202 0.29893899 0.805695, + 0.45947912 0.30896506 0.83271819, + 0.45899394 0.26571098 0.84777486, + 0.40486899 0.27346799 0.87252301, + 0.403869 0.230046 0.88542002, + 0.34931481 0.23562588 0.90689558, + 0.34793288 0.19092493 0.91787267, + 0.29317188 0.19469993 0.93602467, + 0.29159603 0.14998202 0.94471014, + 0.23703088 0.15232792 0.95948553, + 0.23542798 0.10753898 0.96592391, + 0.18148795 0.10881196 0.97735465, + 0.18000305 0.063808918 0.98159426, + 0.12664597 0.064346083 0.98985875, + 0.12547494 0.02095109 0.99187553, + 0.074508399 0.021059301 0.99699801, + 0.074155673 0.00043606685 0.99724662, + 0.02466719 -0.00010926296 0.99969566, + -0.02466719 -0.00010926296 0.99969566, + -0.073425487 0.00010906697 0.99730074, + -0.073444836 0.0012971406 0.99729848, + -0.12414798 0.0012905899 0.9922629, + -0.12473001 0.021943402 0.99194813, + -0.17648704 0.021768905 0.98406225, + -0.17809007 0.065070622 0.98186034, + -0.23182203 0.064326309 0.9706291, + -0.23368606 0.10925602 0.96615422, + -0.2877261 0.10761504 0.95164734, + -0.28962302 0.15220101 0.94496214, + -0.34362102 0.14933401 0.92715913, + -0.34541413 0.19409907 0.91815835, + -0.39979985 0.18958093 0.8967827, + -0.40127686 0.23342691 0.8857137, + -0.45476785 0.22696793 0.86120373, + -0.45579311 0.27026507 0.84806216, + -0.50780207 0.26157704 0.82080114, + -0.5082221 0.30399707 0.80578917, + -0.55512589 0.29359794 0.77822584, + -0.55479926 0.25741312 0.79116136, + -0.50478721 0.26708409 0.82088733, + -0.50381589 0.22463395 0.83409184, + -0.45189485 0.23198292 0.86137968, + -0.4503738 0.18860291 0.87269258, + -0.39723507 0.19385803 0.89700812, + -0.3953051 0.14948803 0.90630424, + -0.34134212 0.15296906 0.92740834, + -0.33920297 0.10867499 0.93441486, + -0.28570509 0.11070903 0.95190138, + -0.28348106 0.065603413 0.95673126, + -0.230317 0.066570498 0.97083598, + -0.22827497 0.023002299 0.97332489, + -0.17544509 0.023259612 0.98421448, + -0.17461702 0.0021496103 0.9846341, + -0.12345301 0.0021664503 0.99234813, + -0.12341499 0.00075777387 0.99235487, + -0.071235813 0.00076167216 0.99745923, + -0.071232177 0.00040823486 0.99745965, + -0.072468564 0.00054014777 0.99737054, + -0.072468191 0.0034151895 0.99736488, + -0.073298216 0.0034152006 0.99730426, + 0.16344796 0.0031901794 0.98654675, + 0.22031492 0.00047455583 0.97542864, + 0.21988305 0.00047494113 0.97552621, + 0.20739198 0.006109389 0.97823888, + 0.20738807 0.0049478416 0.97824633, + 0.25854403 0.0048858305 0.96598715, + 0.2585921 0.008490433 0.96594936, + 0.31511709 0.0083415918 0.94901621, + 0.31523311 0.011270104 0.94894737, + 0.37388489 0.011014297 0.92740965, + 0.37415102 0.014712502 0.9272511, + 0.42564514 0.014355905 0.90477628, + 0.42764807 0.038989305 0.90310413, + 0.47832018 0.037878215 0.87736827, + 0.48166588 0.07970468 0.8727228, + 0.53114706 0.077060305 0.84376812, + 0.53416175 0.11960494 0.8368786, + 0.5823493 0.11501505 0.80476135, + 0.58472109 0.15573302 0.79614609, + 0.63087368 0.14894693 0.76145464, + 0.63258523 0.18886307 0.75111032, + 0.67599893 0.17969699 0.71465695, + 0.67696172 0.21844189 0.70285565, + 0.71759158 0.20670289 0.66508359, + 0.71782267 0.23649488 0.65482873, + 0.68035829 0.24894512 0.68930334, + 0.67996895 0.21087997 0.70226192, + 0.63650596 0.22181797 0.73868597, + 0.63535792 0.18225199 0.75040287, + 0.58929002 0.190679 0.78509802, + 0.58742696 0.14963599 0.7953229, + 0.53930277 0.15570693 0.8275916, + 0.53683919 0.11389704 0.83596128, + 0.48714283 0.11789796 0.86532772, + 0.48414207 0.074627608 0.87180114, + 0.43346891 0.076860383 0.89788479, + 0.43020809 0.034029208 0.90208822, + 0.37805507 0.034898203 0.92512512, + 0.37627381 0.011221395 0.9264406, + 0.3243559 0.011456598 0.94586575, + 0.32413808 0.0080896718 0.94597524, + 0.26647609 0.0082421629 0.96380633, + 0.26639199 0.00585433 0.96384698, + 0.21078889 0.0059373374 0.97751355, + 0.21075307 0.0027795609 0.97753537, + 0.16282694 0.0028054791 0.98665065, + 0.16283599 0.0037926496 0.98664588, + 0.21750192 0.0037519287 0.97605264, + 0.21755596 0.0055960384 0.97603178, + 0.27446905 0.0055131912 0.96158022, + 0.27461708 0.0081241028 0.96151936, + 0.3266021 0.0079856114 0.94512826, + 0.32820204 0.031564005 0.94408011, + 0.38026592 0.030904692 0.92436075, + 0.383331 0.074233599 0.920623, + 0.43583894 0.072337896 0.89711291, + 0.43872586 0.11583696 0.89112371, + 0.48993176 0.11237495 0.86448759, + 0.49242911 0.15521704 0.85640019, + 0.54210389 0.14985897 0.82684082, + 0.54405677 0.19157691 0.81688458, + 0.59233505 0.18396102 0.78440911, + 0.59364378 0.22461993 0.7727437, + 0.63962471 0.2145599 0.73813564, + 0.64021105 0.25441402 0.72484708, + 0.68327117 0.24181806 0.68895918, + 0.68319285 0.27322495 0.6771968, + 0.64631933 0.28550819 0.70764142, + 0.64589703 0.31229204 0.69662803, + 0.60607129 0.32537615 0.72581536, + 0.6053009 0.3539539 0.71297079, + 0.56357789 0.36732391 0.73990083, + 0.56240994 0.39757493 0.72500294, + 0.51816404 0.41124207 0.74992406, + 0.51660198 0.44264999 0.73292798, + 0.47008881 0.45629486 0.7555207, + 0.46813017 0.48887217 0.73611021, + 0.41882178 0.50237578 0.75644362, + 0.41655901 0.53530002 0.73480099, + 0.36569908 0.54803312 0.75227916, + 0.36319098 0.58137697 0.72807497, + 0.31105888 0.59303075 0.74266875, + 0.30840185 0.62667572 0.71565765, + 0.25447702 0.63710004 0.72756106, + 0.25189498 0.67005593 0.69826496, + 0.19716507 0.67879021 0.70736825, + 0.19483 0.71076697 0.67590803, + 0.1398759 0.71752959 0.6823386, + 0.13795203 0.74870521 0.64839017, + 0.08298517 0.7533257 0.65239078, + 0.081689976 0.78335685 0.6161809, + 0.027700104 0.78568214 0.61801004, + 0.027219096 0.81388289 0.58039093, + -0.0266074 0.813896 0.580401, + -0.027088504 0.78567511 0.61804605, + -0.08112102 0.78337318 0.61623514, + -0.082416952 0.75331849 0.65247142, + -0.13740002 0.74872106 0.64848906, + -0.13931501 0.71772105 0.68225205, + -0.19433704 0.71097118 0.67583519, + -0.19668791 0.67879373 0.70749766, + -0.2514649 0.67007077 0.69840574, + -0.25404996 0.63707292 0.72773397, + -0.30776793 0.62671185 0.71589881, + -0.31040102 0.59327608 0.74274808, + -0.36282796 0.58157492 0.72809792, + -0.36535481 0.54798073 0.7524845, + -0.41625795 0.53525293 0.73500592, + -0.41851994 0.50229394 0.75666487, + -0.46764395 0.48885894 0.73642796, + -0.46959504 0.45627606 0.75583911, + -0.51616788 0.44263488 0.73324281, + -0.51773292 0.41092595 0.75039488, + -0.56202686 0.3972739 0.72546482, + -0.56317294 0.36729598 0.74022293, + -0.60528868 0.35381383 0.71305066, + -0.60605323 0.32549512 0.72577721, + -0.64572799 0.31245899 0.69670999, + -0.64615279 0.28532395 0.7078678, + -0.27461594 0.008116168 0.96151978, + -0.32659999 0.0079778098 0.94512898, + -0.32813603 0.030587204 0.94413513, + -0.38017109 0.029948907 0.92443126, + -0.38321915 0.072974533 0.92077035, + -0.43571791 0.071111985 0.89726979, + -0.43863505 0.11491302 0.8912881, + -0.48962006 0.11149502 0.8647781, + -0.49215487 0.15473098 0.85664582, + -0.54186618 0.14939106 0.82708132, + -0.54384494 0.19132397 0.81708491, + -0.59194273 0.18375391 0.78475362, + -0.59326434 0.22421613 0.77315247, + -0.63944596 0.21414196 0.73841196, + -0.64004904 0.25387803 0.72517806, + -0.68326771 0.24126688 0.68915564, + -0.68319905 0.27299604 0.67728305, + -0.35265812 0.011361804 0.93568337, + -0.025181109 -0.012208505 -0.99960834, + -0.025736395 -0.011992497 -0.99959677, + 0.44804084 0.89401269 0.00089896563, + 0.53342992 0.84584385 0.00088085886, + -0.0259207 0.99966401 -6.8508198e-005, + -0.57503682 0.0011984195 0.81812668, + -0.57503307 0.0040731006 0.81812012, + -0.56530893 0.016466098 0.8247149, + -0.57344782 0.018160794 0.81904072, + -0.57354212 0.0011984803 0.81917518, + -0.53412092 -0.0013775099 0.84540689, + -0.53516865 -0.0011805892 0.84474438, + -0.53512388 0.012985697 0.84467381, + -0.53407621 0.012997806 0.84533644, + -0.51984906 0.022296602 0.85396713, + -0.49194199 -0.000186755 0.870628, + -0.49184117 0.020257607 0.8704493, + -0.49186417 0.020257307 0.87043631, + -0.491965 -0.000198974 0.87061501, + -0.51471525 -0.015920708 0.85721344, + 0.57842714 -0.75360316 -0.31225705, + -0.36573198 -0.89275187 -0.26312396, + -0.3937211 -0.88173026 -0.25987607, + -0.27177307 -0.94859022 -0.16222204, + -0.35304183 -0.91192758 -0.20916389, + -0.35073191 -0.91323179 -0.20735195, + -0.90807378 -0.38427591 -0.16653496, + -0.91265613 -0.37049004 -0.17261502, + -0.94040889 -0.30823296 -0.14360899, + -0.94138265 -0.30445388 -0.14528096, + -0.96182698 -0.24698 -0.117855, + -0.9614411 -0.24889003 -0.11698201, + -0.97646689 -0.19518296 -0.09173879, + -0.97570425 -0.20001504 -0.08941672, + -0.98660177 -0.14894097 -0.066583984, + -0.98591441 -0.15465692 -0.063670561, + -0.9934091 -0.10599201 -0.043635603, + -0.99295264 -0.11128096 -0.040763184, + -0.99765712 -0.064239509 -0.023531504, + -0.99745935 -0.067954622 -0.021376908, + -0.99974185 -0.021671299 -0.0068172989, + -0.99971622 -0.023064505 -0.0059539913, + -0.99973363 0.022345593 0.0057684183, + -0.99970376 0.023869794 0.0047590393, + -0.99743199 0.070237704 0.0140037, + -0.99711001 0.075248502 0.0104542, + -0.99235463 0.12224495 0.016983394, + -0.99133134 0.13097705 0.010352104, + -0.98375463 0.17895994 0.014144495, + -0.9814139 0.19186898 0.0035968795, + -0.97054785 0.24086598 0.0045153894, + -0.96683449 0.25527212 -0.0082075335, + -0.95268351 0.30380684 -0.009768025, + -0.9508695 0.30922985 -0.014970393, + -0.93439037 0.35583413 -0.017226605, + -0.93216634 0.36130211 -0.022953307, + -0.91348624 0.4060511 -0.025796205, + -0.91015267 0.41290087 -0.033690188, + -0.88930124 0.45580712 -0.037191108, + -0.88494223 0.46333912 -0.046841912, + -0.86226982 0.50388086 -0.050940588, + -0.85689199 0.51172501 -0.0622385, + -0.83249956 0.54997277 -0.066890374, + -0.8260479 0.55790591 -0.079911292, + -0.79983115 0.59416109 -0.085104123, + -0.79223502 0.60197002 -0.099979199, + -0.76426888 0.63618296 -0.10566098, + -0.7555151 0.64358705 -0.12244502, + -0.72636783 0.6751948 -0.12845898, + -0.71704715 0.68153715 -0.14611803, + -0.68684596 0.71065396 -0.15235999, + -0.67741108 0.71564007 -0.17021601, + -0.64571375 0.74285579 -0.17668894, + -0.63492125 0.74697721 -0.19723107, + -0.60188931 0.77211833 -0.2038691, + -0.590289 0.77485001 -0.2262, + -0.55658913 0.79750019 -0.23281306, + -0.54448289 0.79857981 -0.25653195, + -0.51038074 0.81874156 -0.26300889, + -0.49787307 0.81798714 -0.28813103, + -0.46324199 0.83589101 -0.29443699, + -0.45059013 0.83314216 -0.32069108, + -0.41552508 0.84886819 -0.32674408, + -0.40293795 0.84400189 -0.35397997, + -0.36841282 0.85731357 -0.35956281, + -0.36921692 0.85775185 -0.35768792, + -0.33753604 0.86879909 -0.36229503, + -0.34881184 0.87659359 -0.33153287, + -0.31501189 0.88771969 -0.33573988, + -0.32422686 0.89541459 -0.30513886, + -0.28814697 0.90640086 -0.30888298, + -0.29548603 0.91383511 -0.27855602, + -0.25790298 0.92418885 -0.28171098, + -0.26362804 0.93129313 -0.25138304, + -0.22439402 0.94082612 -0.25395602, + -0.22871096 0.94746691 -0.22360197, + -0.18791603 0.95592511 -0.22559904, + -0.19100598 0.96197486 -0.19524597, + -0.14870206 0.96912235 -0.19669707, + -0.15075497 0.97447175 -0.16636595, + -0.10772198 0.98000175 -0.16730995, + -0.10894296 0.98458165 -0.13685896, + -0.065406106 0.98835611 -0.13738401, + -0.065992728 0.99209249 -0.10675905, + -0.022229902 0.99401414 -0.10696601, + -0.022376008 0.99682838 -0.076371528, + 0.021663692 0.99403065 -0.10692896, + 0.065574601 0.99212402 -0.106724, + 0.064983696 0.98838687 -0.13736299, + 0.10855095 0.98462754 -0.13683994, + 0.10731998 0.98003578 -0.16736895, + 0.15032202 0.97452813 -0.16642801, + 0.14825694 0.96916366 -0.19682893, + 0.19042803 0.96206111 -0.19538604, + 0.18733506 0.95601737 -0.22569108, + 0.22811407 0.94758737 -0.22370107, + 0.22379592 0.94095367 -0.25401092, + 0.26295996 0.9314639 -0.25144997, + 0.25724593 0.92439777 -0.28162593, + 0.29500914 0.91401744 -0.27846313, + 0.28770706 0.90663123 -0.30861706, + 0.3238979 0.89562476 -0.30487093, + 0.31477991 0.88802677 -0.33514491, + 0.34876683 0.8768416 -0.33092386, + 0.33753592 0.86910284 -0.36156592, + 0.36957297 0.85792089 -0.35691398, + 0.36843288 0.8573007 -0.35957289, + 0.40304375 0.84395355 -0.35397479, + 0.41571808 0.84885716 -0.32652709, + 0.45071584 0.83315271 -0.32048687, + 0.46343911 0.83590919 -0.29407507, + 0.49815288 0.81794882 -0.28775594, + 0.51060385 0.81869072 -0.26273391, + 0.54471207 0.79851115 -0.25625902, + 0.55674267 0.79743254 -0.23267786, + 0.59044111 0.77477318 -0.22606605, + 0.60184222 0.7720893 -0.20411807, + 0.63484526 0.74697626 -0.19747907, + 0.64549083 0.74292082 -0.17722896, + 0.67720282 0.71571285 -0.17073795, + 0.68689924 0.71059626 -0.15238906, + 0.71705961 0.68151659 -0.14615291, + 0.72662395 0.67500192 -0.12802398, + 0.75574964 0.64339072 -0.12202794, + 0.7645489 0.63593292 -0.10513899, + 0.79253501 0.601659 -0.099472597, + 0.80012214 0.59384209 -0.084594809, + 0.82632411 0.55756605 -0.079427205, + 0.83274871 0.54964983 -0.066442981, + 0.85713387 0.51137096 -0.061815791, + 0.86240572 0.5036698 -0.050725982, + 0.88506532 0.46312419 -0.046642516, + 0.88929021 0.45582113 -0.037284307, + 0.91014773 0.41290486 -0.033773988, + 0.91336524 0.4063001 -0.026157705, + 0.93205315 0.36157304 -0.023278102, + 0.93421662 0.35626587 -0.017719094, + 0.95072037 0.30966711 -0.015401506, + 0.95262879 0.30397293 -0.0099383472, + 0.96679312 0.25542402 -0.0083510308, + 0.97066653 0.24037889 0.0049355575, + 0.98149562 0.19144392 0.0039307987, + 0.98383963 0.17846094 0.014533695, + 0.99137902 0.130593 0.0106353, + 0.99238563 0.12196495 0.017187195, + 0.99712187 0.075073496 0.010579299, + 0.99743533 0.070181325 0.014046105, + 0.99970412 0.023850504 0.0047734305, + 0.99973339 0.022358088 0.0057621268, + 0.9997161 -0.023075702 -0.0059470609, + 0.99974149 -0.021693088 -0.0068037766, + 0.99745524 -0.068028614 -0.021336306, + 0.99765146 -0.06434983 -0.023469811, + 0.99293464 -0.11147896 -0.040658984, + 0.99339163 -0.10620096 -0.043525387, + 0.985874 -0.15497801 -0.0635162, + 0.98656267 -0.14927094 -0.066425681, + 0.97563291 -0.20045698 -0.089203991, + 0.97640097 -0.195608 -0.091535099, + 0.96131355 -0.24949089 -0.11674995, + 0.96163476 -0.24790794 -0.11747397, + 0.94110024 -0.30555806 -0.14479204, + 0.94003779 -0.30965495 -0.14297797, + 0.91213256 -0.37214082 -0.17182992, + 0.90879256 -0.38219681 -0.16739693, + 0.87122917 -0.44964013 -0.19693504, + 0.85982656 -0.47595477 -0.18483891, + 0.80956918 -0.54720813 -0.21251105, + 0.79495728 -0.5729422 -0.19945008, + 0.731121 -0.64432299 -0.224299, + 0.71846706 -0.66180307 -0.21406002, + 0.64311403 -0.72860503 -0.23566703, + 0.59461796 -0.77908689 -0.19862796, + 0.50915998 -0.83399397 -0.21262699, + 0.46100616 -0.86974531 -0.17611507, + 0.37553108 -0.90837425 -0.18393704, + 0.25444904 -0.95478213 -0.15377502, + 0.25023487 -0.95646954 -0.15016192, + 0.32824096 -0.93316388 -0.14650299, + 0.35592696 -0.90852088 -0.21887396, + 0.29175398 -0.94173187 -0.16739398, + 0.26572707 -0.94917023 -0.16871604, + 0.33962786 -0.90489757 -0.25654089, + 0.36675599 -0.89504302 -0.253748, + 0.68672717 -0.047476713 -0.72536319, + 0.68791062 -0.055324875 -0.72368366, + -0.75289088 0.65813792 -0.0031303796, + -0.76072663 0.64895773 0.012206495, + -0.78797299 0.615601 0.011579, + -0.79436314 0.60696405 0.024125203, + -0.82022411 0.57159108 0.022719203, + -0.82363111 0.56636208 0.029426605, + -0.85027981 0.52562189 0.027309895, + -0.85333884 0.52027589 0.033554293, + -0.90878689 0.41451493 0.047789391, + -0.90463871 0.42448387 0.037977684, + -0.88280326 0.46787411 0.041859712, + -0.87771976 0.47818089 0.030839393, + -0.87581849 0.48229071 0.018371388, + -0.84932798 0.52748299 0.020092901, + -0.84648484 0.53221887 0.014369897, + -0.8222087 0.56897885 0.015362495, + -0.81651628 0.57730818 0.0040518814, + -0.79036897 0.612616 0.00429969, + -0.78322285 0.62166494 -0.0097333593, + -0.75568414 0.65485609 -0.010253001, + -0.74750274 0.66374075 -0.026228391, + -0.71860361 0.69487756 -0.027458783, + -0.70952499 0.703228 -0.045217901, + -0.67906827 0.73256224 -0.04710412, + -0.66915196 0.74012792 -0.066680394, + -0.63729906 0.76750809 -0.06914711, + -0.62664932 0.77402335 -0.090546042, + 0.76034963 -0.28949386 -0.58143067, + 0.79536271 -0.27015892 -0.54259783, + 0.71022338 -0.62137628 -0.33086914, + 0.67266804 -0.65312403 -0.34777403, + 0.75252903 -0.52520102 -0.39732099, + 0.74767441 -0.5385533 -0.38851425, + 0.80577284 -0.41358492 -0.42388391, + 0.76699013 -0.44810805 -0.45926607, + 0.80320317 -0.34761208 -0.48376712, + 0.76682889 -0.37453997 -0.52124196, + 0.76314628 -0.39197716 -0.51377219, + 0.72434735 -0.41818622 -0.54812527, + 0.75906485 -0.30213997 -0.57665592, + 0.72206056 -0.32108283 -0.61280864, + 0.72500294 -0.036614496 -0.68777192, + 0.71081579 -0.20307992 -0.67342377, + 0.74752599 -0.191778 -0.63594502, + 0.75521314 -0.020395502 -0.65516204, + 0.75941968 -0.04923078 -0.64873576, + 0.74752802 -0.185325 -0.63785303, + 0.78159767 -0.17403995 -0.59901178, + 0.81483787 -0.055936191 -0.57698393, + 0.79235286 -0.017470598 -0.60981292, + 0.78158683 -0.16811796 -0.60071486, + 0.81382042 -0.15661508 -0.55961424, + 0.79634482 -0.25928494 -0.54644889, + 0.82884115 -0.23984006 -0.50546914, + 0.80619121 -0.33156008 -0.49002412, + 0.83952618 -0.30447307 -0.44999111, + 0.8124851 -0.39003906 -0.43328705, + 0.84229702 -0.360623 -0.400608, + 0.96094799 -0.207427 -0.183175, + 0.93372875 -0.26833093 -0.23695794, + 0.92686862 -0.29590288 -0.2309889, + 0.8923347 -0.35580188 -0.2777479, + 0.8799997 -0.39090386 -0.26980492, + 0.83076221 -0.45810413 -0.3161881, + 0.82907069 -0.46179181 -0.31526187, + 0.78129315 -0.51549113 -0.35192308, + 0.81720102 -0.44015801 -0.37208, + 0.79084212 -0.46739706 -0.39510605, + 0.71595883 -0.60382086 -0.3504329, + 0.7608788 -0.56122589 -0.32571292, + 0.76163316 -0.5599491 -0.32614708, + 0.8237139 -0.48995394 -0.28537798, + 0.84306902 -0.44798201 -0.29756799, + 0.88892031 -0.38155714 -0.2534461, + 0.900527 -0.34664801 -0.26246199, + 0.93246657 -0.28801486 -0.2180679, + 0.93958825 -0.25732005 -0.22574405, + 0.96093303 -0.20806301 -0.182531, + 0.96191853 -0.20203692 -0.18410291, + 0.97692251 -0.15787792 -0.14386393, + 0.97694778 -0.15766795 -0.14392297, + 0.98735821 -0.11706603 -0.10686103, + 0.98741335 -0.11641704 -0.10706104, + 0.99413526 -0.079601124 -0.073203817, + 0.99401754 -0.081691764 -0.072495162, + 0.9980191 -0.047055408 -0.041758105, + 0.99796033 -0.04886172 -0.041083217, + 0.99979323 -0.015565503 -0.013087602, + 0.99978465 -0.016367195 -0.012757795, + 0.999798 0.0158519 0.0123561, + 0.99978733 0.016834106 0.011912504, + 0.99815488 0.049564492 0.035073895, + 0.99804038 0.052898519 0.03342491, + 0.99479949 0.086103752 0.054406174, + 0.99442637 0.092224427 0.051098119, + 0.98949689 0.12644298 0.070057392, + 0.98865145 0.13560405 0.064653032, + 0.98186338 0.17113405 0.081593029, + 0.98023552 0.18366492 0.073521465, + 0.97148663 0.22011392 0.088111773, + 0.96870977 0.23596694 0.076948583, + 0.9577291 0.27349702 0.089187011, + 0.95325923 0.29290107 0.074201018, + 0.93971026 0.33150008 0.083979324, + 0.9329409 0.35417497 0.064662591, + 0.91650701 0.39351401 0.071844898, + -0.55067295 0.82585889 -0.12131099, + -0.50756299 0.852467 -0.125219, + -0.49969912 0.85436219 -0.14271003, + -0.46461895 0.87340987 -0.14589198, + -0.4536162 0.87447244 -0.17184408, + -0.4182409 0.89128977 -0.17514895, + -0.40708515 0.89050931 -0.20316207, + -0.37156412 0.90515029 -0.20650208, + -0.36086199 0.90242797 -0.235377, + -0.3251659 0.91504377 -0.23866694, + -0.31504396 0.91034585 -0.26836097, + -0.27942207 0.92098439 -0.27149808, + -0.27008504 0.91431212 -0.30180702, + -0.23511 0.922984 -0.30467001, + -0.2266819 0.9143576 -0.33550784, + -0.19260095 0.92121875 -0.33802491, + -0.18528005 0.91077131 -0.36900812, + -0.15185992 0.91606957 -0.37115383, + -0.15176706 0.91588932 -0.37163612, + -0.11942296 0.91999167 -0.37330088, + -0.12351397 0.93078876 -0.3440589, + -0.089128889 0.9342379 -0.34533396, + -0.091789998 0.94432998 -0.315936, + -0.055665791 0.94686288 -0.31678396, + -0.057108283 0.95612264 -0.2873469, + -0.019505704 0.95750326 -0.28776205, + -0.019929903 0.9659161 -0.25808704, + 0.0192552 0.96592897 -0.25808999, + 0.018825401 0.95752501 -0.28773499, + 0.056582525 0.95616049 -0.28732514, + 0.05514748 0.94691664 -0.31671387, + 0.091193505 0.94440812 -0.31587502, + 0.088529497 0.93437397 -0.34512001, + 0.12325694 0.93090457 -0.34383783, + 0.11916996 0.92014563 -0.37300187, + 0.15185894 0.91600168 -0.37132189, + 0.15188399 0.91605085 -0.37118998, + 0.1852679 0.91075844 -0.36904579, + 0.19262992 0.92126262 -0.33788887, + 0.22678408 0.91438431 -0.33536613, + 0.23520409 0.92299938 -0.30455112, + 0.27033892 0.91428071 -0.30167487, + 0.2796731 0.92095536 -0.27133808, + 0.31532884 0.91029561 -0.26819688, + 0.32539403 0.9149701 -0.23863903, + 0.36100996 0.90237486 -0.23535398, + 0.37166783 0.90508556 -0.20659889, + 0.40708816 0.89048427 -0.20326607, + 0.418127 0.89125901 -0.175577, + 0.45345786 0.87447071 -0.17226994, + 0.464656 0.87339503 -0.145863, + 0.49980381 0.8543067 -0.14267495, + 0.51121211 0.8514362 -0.11712603, + 0.54547608 0.83030713 -0.11421902, + 0.5568189 0.82575881 -0.089862175, + 0.59016889 0.80254179 -0.087335579, + 0.60111624 0.79654533 -0.064613022, + 0.63381469 0.77095264 -0.06253697, + 0.64410794 0.76379687 -0.041703995, + 0.67587924 0.73591626 -0.040181715, + 0.68543303 0.72782707 -0.021197202, + 0.71567422 0.69813824 -0.020332608, + 0.72436792 0.68940592 -0.0032513896, + 0.75299591 0.65801793 -0.0031033596, + 0.76067871 0.64901876 0.011935095, + 0.78790927 0.61568725 0.011322204, + 0.79407412 0.60737008 0.023408102, + 0.81990373 0.5720768 0.022047892, + 0.8269999 0.56103891 0.036145497, + 0.8508082 0.52438915 0.033784308, + 0.86055619 0.5064851 0.05399821, + 0.88399976 0.46485287 0.049559589, + 0.88902289 0.45379093 0.060927391, + 0.90990168 0.41113484 0.055200282, + 0.90774769 0.41780186 0.037892785, + 0.88306421 0.46733412 0.042385112, + 0.87460941 0.48422024 0.024273211, + 0.8523401 0.52233207 0.026183704, + 0.84619087 0.53270394 0.013697398, + 0.82191288 0.56942493 0.014641598, + 0.81643629 0.57742316 0.0037763815, + 0.79030085 0.61270589 0.004007129, + 0.78330791 0.62155795 -0.0097189089, + 0.75577939 0.65474629 -0.010237904, + 0.74772274 0.66350275 -0.02597929, + 0.71883225 0.69465125 -0.027198909, + 0.7098338 0.70294183 -0.044817489, + 0.67937469 0.73230463 -0.046689577, + 0.66951215 0.73984617 -0.066190213, + 0.63760662 0.76729751 -0.068646066, + 0.62692493 0.7738499 -0.090119094, + 0.59421796 0.7989049 -0.09303689, + 0.58299381 0.80413067 -0.11615595, + 0.54967213 0.82679915 -0.11943103, + 0.53818321 0.8304584 -0.14386708, + 0.50409698 0.850972 -0.147421, + 0.49274093 0.8528809 -0.17262799, + 0.45761713 0.87147719 -0.17639205, + 0.44626114 0.8715933 -0.20291908, + 0.41093805 0.8879171 -0.20672002, + 0.39973915 0.88613027 -0.23448209, + 0.36449191 0.90022278 -0.23821095, + 0.35369599 0.89646298 -0.26693299, + 0.318407 0.90853298 -0.27052701, + 0.30817088 0.9027487 -0.30012587, + 0.27293307 0.91290426 -0.30350205, + 0.26345405 0.90508723 -0.33378008, + 0.22897008 0.91330731 -0.33681211, + 0.22044307 0.90353632 -0.36746013, + 0.18693306 0.90999532 -0.37008712, + 0.18698391 0.91007161 -0.36987382, + 0.15453798 0.91528177 -0.37199092, + 0.15984495 0.92578775 -0.34258792, + 0.12513794 0.93047458 -0.34432182, + 0.12889205 0.94032735 -0.31491512, + 0.092437908 0.94417709 -0.31620404, + 0.094873436 0.95331836 -0.28667608, + 0.057239193 0.95606786 -0.28750297, + 0.058548026 0.96443647 -0.25774911, + 0.0194472 0.96591097 -0.25814301, + 0.019837206 0.97341424 -0.22819106, + -0.020466294 0.97340178 -0.22818895, + -0.020083494 0.96590173 -0.25812894, + -0.059171878 0.96440363 -0.2577289, + -0.057866521 0.95601535 -0.28755209, + -0.095555387 0.95323789 -0.28671697, + -0.093132667 0.94407964 -0.31629089, + -0.12935606 0.94023448 -0.31500214, + -0.12558395 0.9303146 -0.34459183, + -0.15995102 0.92566514 -0.34287003, + -0.15462592 0.9151206 -0.37235081, + -0.18699598 0.90992188 -0.37023598, + -0.18702805 0.90997022 -0.37010109, + -0.22037406 0.90354222 -0.3674871, + -0.22886908 0.91328031 -0.33695412, + -0.26338002 0.90505713 -0.33392003, + -0.27282989 0.91285557 -0.30374086, + -0.30796513 0.90273631 -0.30037412, + -0.31821096 0.90853286 -0.27075797, + -0.3535811 0.89644223 -0.26715505, + -0.36442199 0.90022898 -0.238295, + -0.39956605 0.88618314 -0.23457703, + -0.41086814 0.88798732 -0.20655708, + -0.44617012 0.87167621 -0.20276305, + -0.45768288 0.8715468 -0.17587696, + -0.49285194 0.85291988 -0.17211798, + -0.50397515 0.85104132 -0.14743707, + -0.53813201 0.83048999 -0.143876, + -0.54945713 0.82688916 -0.11979603, + -0.58275193 0.80425388 -0.11651599, + -0.59394723 0.79905528 -0.093474329, + -0.59457701 0.798482 -0.0943648, + -0.55306399 0.82738101 -0.097779997, + -0.54881006 0.82908314 -0.10690501, + -0.51115394 0.85243189 -0.10991599, + -0.50662702 0.85376102 -0.120088, + -0.46812794 0.87504691 -0.12308198, + -0.46033379 0.87639457 -0.14151092, + -0.42490292 0.89366376 -0.14429997, + -0.41420391 0.89389676 -0.17141695, + -0.37840384 0.90907669 -0.17432794, + -0.36777997 0.90741485 -0.20331296, + -0.33189508 0.92049426 -0.20624304, + -0.32186112 0.91687536 -0.23610409, + -0.28579006 0.92801726 -0.23897307, + -0.27655292 0.92245567 -0.2694329, + -0.24107194 0.93158275 -0.27209893, + -0.23275305 0.92410421 -0.30308005, + -0.19796291 0.93139559 -0.30547184, + -0.19069408 0.92205936 -0.33681211, + -0.15642001 0.92773402 -0.338884, + -0.15034004 0.91669226 -0.3702341, + -0.11709096 0.92085266 -0.37191388, + -0.11697596 0.92055762 -0.37267989, + -0.084509104 0.92360514 -0.37391403, + -0.087410174 0.93456578 -0.34488592, + -0.053162392 0.93682986 -0.34572196, + -0.054745808 0.94699913 -0.31653702, + -0.018554002 0.9482581 -0.31695804, + -0.019038903 0.95755112 -0.28763402, + 0.01846741 0.95756149 -0.28763714, + 0.017976491 0.94827753 -0.31693286, + 0.054401811 0.94702625 -0.31651509, + 0.05282652 0.93688536 -0.34562311, + 0.087250657 0.93461758 -0.34478581, + 0.084362328 0.92370033 -0.37371212, + 0.11707401 0.9206301 -0.37247002, + 0.11715 0.92082298 -0.37196901, + 0.15039393 0.91666168 -0.3702879, + 0.15650505 0.92775625 -0.3387841, + 0.19078009 0.92207843 -0.33671114, + 0.19806197 0.9314279 -0.30530897, + 0.2327899 0.92414665 -0.30292189, + 0.24113905 0.93163526 -0.27186006, + 0.27669102 0.92248511 -0.26919004, + 0.2858991 0.92801434 -0.2388541, + 0.32197201 0.91686702 -0.235985, + 0.33193108 0.92045122 -0.20637704, + 0.36791191 0.90733379 -0.20343596, + 0.37842906 0.90898913 -0.17472902, + 0.41406614 0.89388227 -0.17182507, + 0.424934 0.89365101 -0.144288, + 0.46038812 0.87636822 -0.14149803, + 0.47162282 0.87429971 -0.11476895, + 0.50688785 0.85467982 -0.11219297, + 0.51820594 0.85085487 -0.086651392, + 0.55259514 0.82916117 -0.084442124, + 0.56366819 0.82378328 -0.060493223, + 0.59709072 0.80001962 -0.05874807, + 0.60769689 0.79332584 -0.036588691, + 0.64032084 0.76729184 -0.035387993, + 0.65030491 0.75952387 -0.015069298, + 0.68196601 0.73123997 -0.0145082, + 0.69120401 0.72264898 0.0039280001, + 0.72125566 0.69265866 0.0037649882, + 0.72956496 0.68361497 0.020139297, + 0.75794202 0.65203899 0.0192091, + 0.76474899 0.643507 0.032523599, + 0.79172415 0.61010003 0.030835204, + 0.79975528 0.59851426 0.046608813, + 0.82514417 0.5632171 0.043860011, + 0.83617312 0.54445106 0.066240206, + 0.86141872 0.50417781 0.061340477, + 0.86725086 0.49232593 0.074102595, + 0.88978785 0.45129094 0.067926191, + 0.89426523 0.44060111 0.07848902, + 0.91675442 0.39326018 0.070055932, + 0.91822624 0.38657108 0.086159222, + 0.89895773 0.42754486 0.095291466, + 0.89489114 0.43805507 0.085309707, + 0.8731584 0.47844824 0.093176246, + 0.8679387 0.48997581 0.081278168, + 0.84354091 0.52982491 0.08788839, + 0.83692569 0.54232782 0.073729172, + 0.80980146 0.58135635 0.079035148, + 0.44745705 0.89395612 -0.024995504, + 0.48706281 0.87302572 -0.024410291, + 0.49131107 0.87087113 -0.014031802, + 0.53048897 0.84758186 -0.013656599, + 0.53457212 0.8451122 -0.0042514009, + 0.57749087 0.81638682 -0.004106889, + 0.57657814 0.81703717 -0.0028144207, + 0.61001396 0.79238588 -0.0027294997, + 0.62006593 0.78433186 0.018484699, + 0.65256417 0.75752318 0.017852904, + 0.66189474 0.74868476 0.036966685, + 0.69323742 0.71983242 0.035542123, + 0.7011888 0.71111685 0.051448587, + 0.73084164 0.68076771 0.049252879, + 0.73575437 0.67468631 0.058855031, + 0.76690716 0.63933021 0.055770714, + 0.77262628 0.63131124 0.067043521, + 0.80195719 0.59404111 0.063085616, + 0.80012536 0.59812129 0.045280121, + 0.76643687 0.64048696 0.048487391, + 0.76203901 0.64629698 0.039960202, + 0.73389083 0.67797279 0.041918688, + 0.72648293 0.68664092 0.027329396, + 0.69663405 0.71685904 0.028532105, + 0.68776721 0.72585118 0.010794003, + 0.65628481 0.75442982 0.011218897, + 0.64657104 0.7628051 -0.0086280406, + 0.61400199 0.78925401 -0.0089272102, + 0.6037001 0.7966252 -0.030570608, + 0.57026595 0.82085586 -0.031500395, + -0.42377594 0.89962685 -0.10528699, + -0.47041512 0.87646323 -0.10257602, + -0.47491181 0.8752327 -0.09179607, + -0.51364392 0.85332286 -0.089498192, + -0.51802617 0.8516553 -0.079574227, + -0.55583596 0.82768691 -0.077334791, + -0.55998385 0.82567769 -0.068370774, + -0.60138512 0.79623419 -0.065932713, + -0.64391392 0.76392686 -0.042316496, + -0.60405314 0.79572415 -0.04407781, + -0.60025501 0.79811603 -0.052007299, + -0.56334692 0.82447189 -0.053724691, + -0.55923897 0.82663703 -0.0626335, + -0.52139407 0.85087711 -0.064470105, + -0.51707673 0.85270947 -0.074283957, + -0.47821975 0.87492657 -0.076219462, + -0.47377595 0.87634587 -0.086914793, + -0.43478286 0.89613873 -0.088877767, + -0.42711285 0.89766067 -0.10853596, + -0.39093307 0.91376412 -0.11048301, + -0.38066199 0.91420501 -0.139017, + -0.34420297 0.92822486 -0.14114898, + -0.33454689 0.92682463 -0.17051195, + -0.29760912 0.93893033 -0.17273906, + -0.28849614 0.93559641 -0.2035421, + -0.25199893 0.94560874 -0.20571996, + -0.24380513 0.94039547 -0.23709811, + -0.20777297 0.94849485 -0.23913997, + -0.20061097 0.94144988 -0.27097496, + -0.16514206 0.94779134 -0.27280009, + -0.15914398 0.93901187 -0.30484396, + -0.12416506 0.94377345 -0.30639014, + -0.11939406 0.93330044 -0.33866715, + -0.085534066 0.93657959 -0.33985686, + -0.082088336 0.9245854 -0.37202618, + -0.049476724 0.92658043 -0.37282819, + -0.0494009 0.92610401 -0.37402001, + -0.0167688 0.92710602 -0.37442401, + -0.017340306 0.93816239 -0.34576112, + 0.017166404 0.93816525 -0.3457621, + 0.016598104 0.92713124 -0.37436908, + 0.049469389 0.92612374 -0.3739619, + 0.049540389 0.92656976 -0.37284592, + 0.082119346 0.92457545 -0.37204379, + 0.085571721 0.93659025 -0.33981809, + 0.119501 0.93330199 -0.33862501, + 0.12428494 0.94379753 -0.30626684, + 0.15912405 0.93905324 -0.30472705, + 0.16514799 0.94784689 -0.27260298, + 0.20072493 0.94148362 -0.2707729, + 0.20786311 0.94848645 -0.23909512, + 0.24397688 0.94036353 -0.23704788, + 0.25213397 0.94555289 -0.20581096, + 0.28859109 0.93554735 -0.20363307, + 0.29764798 0.93886489 -0.17302698, + 0.33453384 0.92677659 -0.17079893, + 0.34427091 0.92819679 -0.14116697, + 0.38075492 0.91416377 -0.13903297, + 0.39112014 0.91371727 -0.11020803, + 0.4273009 0.89760375 -0.10826498, + 0.43806189 0.89533174 -0.080516279, + 0.47405118 0.87695831 -0.078864031, + 0.48179507 0.87421012 -0.060251009, + 0.52073383 0.8516987 -0.058699477, + 0.5249998 0.8496927 -0.048963681, + 0.56294185 0.82512772 -0.047548082, + 0.56477004 0.82291913 -0.061959807, + 0.52169079 0.8507266 -0.064053468, + 0.51392788 0.8539418 -0.081619181, + 0.47837806 0.87417012 -0.083552711, + 0.46727282 0.87721968 -0.11018996, + 0.43156508 0.89504826 -0.11242903, + 0.420683 0.89630198 -0.14024501, + 0.38486105 0.91187912 -0.14268301, + 0.3744719 0.91127676 -0.17130496, + 0.33828789 0.92484367 -0.17385495, + 0.32841408 0.92233324 -0.20358205, + 0.29193401 0.93395799 -0.206148, + 0.28282198 0.92953587 -0.23658997, + 0.246804 0.93912297 -0.239031, + 0.23858409 0.93280333 -0.2701031, + 0.20309907 0.94052237 -0.27233908, + 0.19589092 0.93234664 -0.30390188, + 0.160947 0.93837202 -0.305866, + 0.15486699 0.92839801 -0.33777699, + 0.12079999 0.93285388 -0.33939797, + 0.11600297 0.92123973 -0.3712959, + 0.082972109 0.92430311 -0.37253103, + 0.082886368 0.92398763 -0.37333187, + 0.050182194 0.92600989 -0.37414896, + 0.051904213 0.93702722 -0.3453781, + 0.017282294 0.93815166 -0.34579289, + 0.017810896 0.94829577 -0.31688792, + -0.018284297 0.94828779 -0.31688491, + -0.017761298 0.93811285 -0.34587398, + -0.052164182 0.93698364 -0.34545687, + -0.050446793 0.92593688 -0.37429398, + -0.082837299 0.923931 -0.373483, + -0.082941025 0.92431325 -0.37251309, + -0.116006 0.92124701 -0.371277, + -0.12078501 0.93282014 -0.33949602, + -0.15478401 0.92837512 -0.33787802, + -0.16087206 0.93836635 -0.30592313, + -0.19564597 0.93237591 -0.30396998, + -0.20285396 0.94054186 -0.27245396, + -0.23833995 0.93283176 -0.27021995, + -0.246595 0.93917203 -0.23905399, + -0.2825889 0.92959964 -0.23661791, + -0.29176188 0.93404466 -0.20599893, + -0.32835212 0.92238933 -0.20342807, + -0.33827496 0.9249059 -0.17354898, + -0.37455609 0.91130024 -0.17099604, + -0.38481295 0.91189587 -0.14270599, + -0.42066091 0.89630878 -0.14026697, + -0.428312 0.89551902 -0.120808, + -0.46698511 0.87632722 -0.11821903, + -0.47153282 0.87528872 -0.10736096, + -0.51020706 0.85365415 -0.10470702, + -0.51460016 0.85217428 -0.094793141, + -0.55232787 0.82851684 -0.092161477, + -0.55657715 0.82663816 -0.083013423, + -0.59343833 0.80085135 -0.080423936, + -0.60079575 0.79674971 -0.065071277, + -0.63346976 0.7711997 -0.062984578, + -0.64379299 0.76403999 -0.042113502, + -0.67555767 0.73618966 -0.04057838, + -0.68517596 0.72806096 -0.021473998, + -0.71543974 0.69837075 -0.020598292, + -0.72425526 0.68952423 -0.0032796711, + -0.72112596 0.69279397 0.0037391295, + -0.72958577 0.68358475 0.020407492, + -0.75798112 0.65198606 0.019464202, + -0.76503682 0.64312583 0.033283692, + -0.79202402 0.60967398 0.031552501, + -0.79600817 0.60400814 0.039310113, + -0.82446867 0.56471282 0.036752686, + -0.82821691 0.55865896 0.044237196, + -0.85436487 0.51805192 0.041021798, + -0.86026073 0.50705183 0.053385083, + -0.88373888 0.46540794 0.049000591, + -0.88867509 0.45457706 0.060135409, + -0.90958786 0.41192293 0.054492794, + -0.9133023 0.40227914 0.063642219, + -0.93359077 0.35393891 0.055994485, + -0.87636375 -0.018693596 -0.48128688, + -0.87281615 -0.093950711 -0.47892106, + -0.89696932 -0.085104033 -0.43382415, + -0.88899428 -0.15974806 -0.42915013, + -0.91239077 -0.14279497 -0.38360491, + -0.90207839 -0.20796511 -0.37816018, + -0.92518163 -0.18288495 -0.33255389, + -0.90892774 -0.26143995 -0.3248069, + -0.93420357 -0.22368489 -0.27790087, + -0.92394465 -0.26798791 -0.2729629, + -0.94812536 -0.22271007 -0.22684507, + -0.94940013 -0.21647403 -0.22754903, + -0.97228324 -0.16115205 -0.16939704, + -0.97402966 -0.14762394 -0.17167795, + -0.98698765 -0.10483796 -0.12191995, + -0.98732913 -0.10028601 -0.12298001, + -0.99410415 -0.068525508 -0.08403191, + -0.99395603 -0.071593001 -0.083221696, + -0.99800164 -0.041208986 -0.04790248, + -0.9979769 -0.042105198 -0.047636092, + -0.99979526 -0.013402402 -0.015162904, + -0.99979013 -0.013984902 -0.014968702, + -0.99980336 0.013540004 0.014492505, + -0.99979651 0.014329594 0.014198793, + -0.99823487 0.042186398 0.041801296, + -0.99815947 0.045019921 0.040632017, + -0.99511576 0.073282182 0.066139586, + -0.99486637 0.078635126 0.063697919, + -0.99032533 0.10782704 0.087344632, + -0.98975551 0.11599595 0.08324036, + -0.98360634 0.14650907 0.10513704, + -0.9824965 0.15789093 0.098848559, + -0.97470355 0.18943891 0.11859994, + -0.97279686 0.20401298 0.10974999, + -0.96315622 0.23684606 0.12741303, + -0.96004897 0.254971 0.115307, + -0.86666113 -0.35310102 -0.35244602, + -0.88141859 -0.30563986 -0.36011881, + -0.85034227 -0.34051311 -0.40120915, + -0.87261671 -0.25941592 -0.41381586, + -0.84292716 -0.28577307 -0.45585912, + -0.86195469 -0.19554693 -0.46775582, + -0.83260471 -0.21362893 -0.51101083, + -0.84616584 -0.11461397 -0.52044886, + -0.82224619 -0.035091206 -0.56804913, + -0.81662184 -0.12413097 -0.56366688, + -0.75424314 -0.57228607 -0.32187903, + -0.76059544 -0.56171656 -0.32552877, + -0.8229267 -0.49156681 -0.28487492, + -0.84312457 -0.4478648 -0.29758686, + -0.93858922 -0.27544206 -0.20780304, + -0.90019375 -0.3476499 -0.26227993, + -0.88890791 -0.38153893 -0.25351697, + -0.88969278 -0.37633592 -0.25849193, + -0.83002728 -0.45972317 -0.31576812, + -0.8244428 -0.47169688 -0.3127239, + -0.77578068 -0.5259198 -0.34867287, + -0.81048566 -0.45568478 -0.36805481, + -0.769319 -0.49699801 -0.40142399, + -0.80344838 -0.4196412 -0.4223412, + -0.76444662 -0.45439878 -0.45732179, + -0.80476755 -0.34279779 -0.48460171, + -0.76856786 -0.36946598 -0.52230096, + -0.79897368 -0.2539289 -0.54512483, + -0.76438487 -0.27225196 -0.58446091, + -0.78496784 -0.14787097 -0.60163087, + -0.75100732 -0.15759906 -0.64121026, + -0.759112 -0.054017 -0.64871502, + -0.756845 -0.066535398 -0.650199, + -0.75851202 -0.0060454002 -0.651631, + -0.78891867 -0.041127186 -0.61311978, + -0.78958273 0.0031844089 -0.61363578, + -0.78930283 0.0031844394 -0.61399591, + -0.7897408 0.0032907594 -0.61343187, + -0.78804821 -0.065517716 -0.61211711, + -0.78760785 -0.065572187 -0.61267787, + -0.79121882 -0.058788285 -0.60870087, + -0.78484672 -0.14143096 -0.60333478, + -0.81678754 -0.13167393 -0.56171167, + -0.79980683 -0.24316894 -0.54879689, + -0.8318724 -0.22482111 -0.50738925, + -0.8076241 -0.32689703 -0.49079707, + -0.84069818 -0.30018106 -0.45068613, + -0.81019288 -0.39636493 -0.43183595, + -0.84527183 -0.3613199 -0.3936539, + -0.82238853 -0.42271376 -0.38077575, + -0.85854787 -0.38096195 -0.34316698, + -0.83871198 -0.43100399 -0.332863, + -0.87889773 -0.37752986 -0.29156491, + -0.88155788 -0.37017098 -0.29296598, + -0.92773455 -0.29267085 -0.23162989, + -0.93350714 -0.26935703 -0.23666704, + -0.96097636 -0.20781107 -0.18259005, + -0.9625265 -0.19819991 -0.18509291, + -0.97727352 -0.15492892 -0.14468393, + -0.97688043 -0.15824091 -0.14375091, + -0.98732275 -0.11748597 -0.10672798, + -0.98739362 -0.11665495 -0.10698396, + -0.99412638 -0.079761833 -0.073149428, + -0.9940359 -0.081371091 -0.072603896, + -0.99802476 -0.04687579 -0.04182519, + -0.99796522 -0.048713312 -0.041138712, + -0.99979365 -0.015519194 -0.013106096, + -0.99978501 -0.016333999 -0.0127709, + -0.99979836 0.015820805 0.012369704, + -0.99978763 0.016804194 0.011925495, + -0.9981575 0.049482279 0.035116084, + -0.99804264 0.052832682 0.03345909, + -0.99480551 0.085998155 0.054462872, + -0.99443209 0.092135705 0.051145807, + -0.98950624 0.12633103 0.070127815, + -0.98866087 0.13550499 0.064715691, + -0.98187524 0.17102504 0.08167962, + -0.98023677 0.18364696 0.073551089, + -0.97147787 0.22013196 0.088163294, + -0.96865851 0.23621288 0.076838464, + -0.95311654 0.29346585 0.073800661, + -0.95767564 0.2737309 0.089043073, + -0.95701665 0.2739059 0.095366165, + -0.96075678 0.25513494 0.10886898, + -0.97098589 0.21994898 0.093854882, + -0.97332436 0.20453107 0.10395604, + -0.98152864 0.17054994 0.086684473, + -0.98286635 0.15867706 0.093783841, + -0.98928785 0.12566899 0.074275091, + -0.98998898 0.116937 0.079041399, + -0.99468833 0.085278928 0.057642922, + -0.9949919 0.07958179 0.060480293, + -0.99811363 0.04887988 0.037147585, + -0.99820709 0.045788404 0.038548905, + -0.99979347 0.015548607 0.013090206, + -0.99980187 0.014669598 0.013451698, + -0.99978876 -0.015148097 -0.013890496, + -0.99979562 -0.014438194 -0.014154395, + -0.99798226 -0.045339812 -0.044448812, + -0.99802375 -0.043944988 -0.044915989, + -0.99403054 -0.076299161 -0.077985063, + -0.99405891 -0.075762093 -0.078146696, + -0.98723012 -0.11088402 -0.11437401, + -0.98751265 -0.10730796 -0.11534195, + -0.97720289 -0.14461298 -0.15543999, + -0.97643554 -0.15140593 -0.15378493, + -0.95729262 -0.20283893 -0.20602693, + -0.95398736 -0.22103608 -0.20261107, + -0.92112398 -0.286955 -0.263035, + -0.91909391 -0.29434696 -0.26196596, + -0.88750172 -0.34422088 -0.30635387, + -0.89766067 -0.31190187 -0.31132388, + -0.90937859 -0.25684288 -0.32720384, + -0.88507611 -0.28739202 -0.36612302, + -0.90079576 -0.22013594 -0.37430891, + -0.87435687 -0.24600998 -0.41830495, + -0.88863122 -0.16865404 -0.42648607, + -0.86245382 -0.18612696 -0.4706699, + -0.87298781 -0.10001298 -0.47737789, + -0.84603184 -0.10931998 -0.52180386, + -0.84986299 -0.051401 -0.52449101, + -0.84559518 -0.017668704 -0.53353214, + -0.84572184 0.003586919 -0.53361189, + -0.84587461 0.0035868983 -0.53336978, + -0.84418881 -0.063203484 -0.53230691, + -0.84411716 -0.063213617 -0.53241915, + -0.84580386 0.0035668795 -0.53348196, + -0.81873149 -0.0085272444 -0.57411337, + -0.81708568 -0.063945979 -0.57295883, + -0.81659913 -0.064009406 -0.57364506, + -0.81817132 -0.016095005 -0.57474917, + -0.81496912 -0.013465302 -0.57934809, + -0.6142059 0.006880078 0.78911585, + -0.61421674 -0.0032584588 0.78913069, + -0.61494327 -0.0031112412 0.78856528, + -0.61493206 0.0068736309 0.78855014, + 0.91172075 0.24779494 0.32766291, + 0.91067547 0.25829485 0.32241881, + 0.89269531 0.2817651 0.35171512, + 0.89131939 0.29382914 0.34527418, + 0.87115717 0.3182151 0.37393108, + 0.86938298 0.33183101 0.366144, + 0.847175 0.35679501 0.39368999, + 0.84490788 0.37207997 0.38430095, + 0.82045114 0.39768106 0.41074306, + 0.81762844 0.4144572 0.39963618, + 0.79059786 0.44079593 0.42503393, + 0.78717571 0.45881084 0.41212484, + 0.75745183 0.48571387 0.43628991, + 0.75332987 0.50500995 0.42125893, + 0.72131783 0.53185689 0.44365388, + 0.71642596 0.55229396 0.42626894, + 0.68194598 0.57900298 0.44688401, + 0.67629719 0.60016811 0.4271071, + 0.63909876 0.62664378 0.44594884, + 0.63282436 0.64786834 0.42402825, + 0.59286809 0.67381018 0.44100711, + 0.58596295 0.69503796 0.41661695, + 0.54405802 0.71966302 0.43137699, + 0.5365901 0.74065715 0.40434909, + 0.49303883 0.76362169 0.41688684, + 0.48513281 0.78405273 0.38717884, + 0.43967584 0.8053177 0.39767885, + 0.43167686 0.82448667 0.36589187, + 0.38463894 0.84371686 0.37442598, + 0.37671509 0.86151218 0.34041509, + 0.32930192 0.87815577 0.34699091, + 0.32170308 0.89430422 0.31101006, + 0.27422702 0.90830612 0.31587902, + 0.26719892 0.92262465 0.2781519, + 0.21976103 0.93403012 0.28159004, + 0.21369302 0.94615412 0.24316204, + 0.16650794 0.95500565 0.24543691, + 0.16149999 0.96518886 0.20573796, + 0.11559495 0.97147155 0.20707689, + 0.112506 0.97836101 0.17364401, + 0.067716412 0.98235226 0.17435205, + 0.066227615 0.98678124 0.14790803, + 0.022450002 0.98870313 0.14819601, + 0.021827111 0.99313748 0.11489806, + -0.021526897 0.99314386 0.11489899, + -0.022138899 0.98870701 0.14821699, + -0.06604939 0.98678988 0.14792998, + -0.067542672 0.9823485 0.17443991, + -0.11237395 0.97836053 0.17373191, + -0.11545997 0.97147673 0.20712796, + -0.16144295 0.96518779 0.20578796, + -0.16642092 0.95510352 0.24511488, + -0.21348095 0.94628179 0.24285094, + -0.21955292 0.93417364 0.2812759, + -0.26683208 0.92281938 0.27785808, + -0.27381909 0.9085983 0.31539211, + -0.32133508 0.89460224 0.31053305, + -0.32894012 0.87849027 0.3464871, + -0.37629607 0.86188412 0.33993703, + -0.38424408 0.84408915 0.37399209, + -0.43113115 0.82494229 0.36550811, + -0.43915489 0.80575484 0.39736891, + -0.48463005 0.78450614 0.38689005, + -0.49257699 0.76400799 0.41672501, + -0.53615195 0.74105293 0.40420493, + -0.54365027 0.72000444 0.43132126, + -0.58559686 0.6953758 0.41656792, + -0.59254587 0.67403281 0.44109988, + -0.63252878 0.64809376 0.42412484, + -0.63882303 0.62681508 0.44610307, + -0.67606205 0.60032904 0.42725307, + -0.6817252 0.57911313 0.44707811, + -0.71625179 0.55238479 0.42644385, + -0.72115076 0.53191584 0.44385484, + -0.75318182 0.5050689 0.42145291, + -0.75731319 0.48572412 0.43651909, + -0.78707218 0.45880613 0.41232809, + -0.79049355 0.44078273 0.42524174, + -0.81754416 0.41443908 0.39982709, + -0.8203941 0.39747506 0.41105607, + -0.84480888 0.37194297 0.38465095, + -0.84707469 0.35662389 0.39406085, + -0.86935586 0.33160397 0.36641398, + -0.87112284 0.3180069 0.37418792, + -0.89129728 0.29362813 0.34550211, + -0.89266813 0.28157803 0.35193402, + -0.91069132 0.25807109 0.32255313, + -0.91171777 0.24774495 0.3277089, + -0.92846566 0.21640292 0.3018629, + -0.92771 0.22512101 0.29778299, + -0.92841202 0.22999699 0.29180899, + -0.92753577 0.23887993 0.28742594, + -0.91152424 0.26285705 0.31627509, + -0.9103353 0.27336809 0.31074011, + -0.89225912 0.29823804 0.33901003, + -0.89070398 0.31026599 0.33223701, + -0.87044513 0.33598503 0.35977703, + -0.8683998 0.3498449 0.35141191, + -0.84604341 0.37612519 0.37781018, + -0.84350216 0.39127809 0.36797509, + -0.81884414 0.41815105 0.39324805, + -0.8156687 0.43487886 0.38152984, + -0.78852791 0.46230093 0.40558794, + -0.78469849 0.48018131 0.39201325, + -0.75473416 0.50818712 0.4148761, + -0.75013787 0.52728093 0.39908394, + -0.71787292 0.55510294 0.42014194, + -0.71245307 0.57521105 0.40192407, + -0.67777395 0.60271293 0.42114094, + -0.67163503 0.62314504 0.40074506, + -0.63435704 0.65019304 0.41813907, + -0.62748694 0.67081195 0.39531195, + -0.58750379 0.69716978 0.41084486, + -0.58000118 0.71758223 0.38558316, + -0.53804904 0.74250907 0.39897805, + -0.52993494 0.7626279 0.37090096, + -0.48651493 0.78567988 0.38211295, + -0.47812918 0.80470431 0.35191411, + -0.43299007 0.82587713 0.36117402, + -0.42447609 0.84368515 0.32865709, + -0.37811586 0.86261868 0.33603188, + -0.3697761 0.87879926 0.30162507, + -0.32300192 0.89514077 0.30723393, + -0.31507897 0.90952986 0.27107298, + -0.26830903 0.92320311 0.27514803, + -0.26115108 0.93551636 0.23792709, + -0.21471104 0.94654524 0.24073106, + -0.20846196 0.95686978 0.20234595, + -0.162469 0.96536499 0.204143, + -0.15825404 0.97235721 0.17168905, + -0.11306195 0.9784525 0.17276491, + -0.110635 0.98295802 0.14681099, + -0.066920027 0.98681247 0.14738707, + -0.065085106 0.99129212 0.11447202, + -0.021884687 0.99316043 0.11468793, + -0.021229891 0.99660552 0.079541266, + 0.021558087 0.99659842 0.079540752, + 0.022224594 0.99315578 0.11466297, + 0.065497503 0.99126798 0.114446, + 0.067346677 0.98680967 0.14721094, + 0.11090299 0.98295391 0.14663598, + 0.11333697 0.97847164 0.17247593, + 0.15832901 0.97239512 0.17140502, + 0.16255495 0.96537077 0.20404695, + 0.20860793 0.95685863 0.20224793, + 0.21492092 0.94641763 0.24104491, + 0.26140106 0.93536925 0.23823106, + 0.26858297 0.9229849 0.27561197, + 0.31539008 0.90928823 0.27152205, + 0.32332787 0.8948307 0.30779389, + 0.37016109 0.87845325 0.30216005, + 0.37849382 0.86223257 0.33659685, + 0.4249801 0.84322816 0.32917809, + 0.43348405 0.82539815 0.36167604, + 0.47853893 0.80424488 0.35240698, + 0.48691899 0.78516901 0.38264799, + 0.53045112 0.76203817 0.37137508, + 0.53847277 0.74210465 0.39915884, + 0.58032101 0.71722102 0.38577399, + 0.58781505 0.69678408 0.41105404, + 0.62776417 0.67043519 0.39551109, + 0.63459098 0.64990097 0.41823801, + 0.67185432 0.62285328 0.40083119, + 0.6779623 0.60249031 0.4211562, + 0.71268582 0.57494086 0.40189791, + 0.71805084 0.5550279 0.41993693, + 0.75029635 0.52720523 0.39888617, + 0.7548852 0.50814313 0.41465509, + 0.78480399 0.48016399 0.39182299, + 0.78862989 0.46231195 0.40537694, + 0.8157562 0.43488908 0.38133109, + 0.81892943 0.41818622 0.39303318, + 0.8435061 0.39138907 0.36784804, + 0.8460775 0.37605876 0.37779975, + 0.86842358 0.34978881 0.35140881, + 0.87044215 0.3361091 0.35966808, + 0.89074343 0.31032515 0.33207616, + 0.89228088 0.29845697 0.33875996, + 0.91034877 0.27357593 0.31051794, + 0.91152591 0.26320297 0.31598198, + 0.92753214 0.23920304 0.28716904, + 0.92905444 0.2231441 0.29506716, + 0.92923725 0.22229806 0.29513007, + 0.942038 0.201856 0.26798999, + 0.94362974 0.18088596 0.27720594, + 0.95513576 0.16184996 0.24803294, + 0.95614535 0.14428304 0.2548891, + 0.96619612 0.12700002 0.22435702, + 0.96681535 0.11258504 0.22933109, + 0.9755041 0.096942715 0.19746903, + 0.97583914 0.086536109 0.20062304, + 0.98326802 0.072149001 0.16726799, + 0.98346913 0.063758709 0.16948001, + 0.98964274 0.050546188 0.13435897, + 0.98961854 0.051685773 0.13410294, + 0.99412709 0.038919304 0.10097902, + 0.99402553 0.042777482 0.10041595, + 0.99757349 0.027286412 0.064052232, + 0.99754924 0.028304407 0.063988514, + 0.99972463 0.0094924662 0.021459892, + 0.99972826 0.0090691121 0.021477006, + 0.99971938 -0.0092145847 -0.021821586, + 0.99973899 -0.0065689902 -0.0218834, + 0.99754524 -0.020132806 -0.067068815, + 0.99185878 0.021891195 -0.12544698, + 0.99355346 0.0097954944 -0.11294105, + 0.99344897 -0.018463001 -0.112775, + 0.99768043 -0.010997893 -0.067176864, + 0.99957663 -0.0018354394 -0.029036088, + 0.99972254 0.007683346 -0.022265989, + 0.99974811 -0.0032692405 -0.022206701, + 0.99974924 0.0032618106 0.022156306, + 0.99973834 0.0058099921 0.022128407, + 0.99763763 0.017445493 0.066444375, + 0.99752003 0.023646999 0.066292197, + 0.99322379 0.039046094 0.10946197, + 0.65363777 0.012352095 0.75670671, + 0.65225101 0.0123745 0.75790203, + 0.65229601 -0.0037603099 0.75795501, + 0.65368384 -0.003471859 0.75675982, + 0.71607339 -0.015062209 0.69786245, + 0.7573157 0.0030624089 0.65304178, + 0.75748652 0.0030624082 0.65284359, + 0.75731081 0.021763394 0.65269184, + 0.99240863 -0.012700995 0.12232696, + 0.93496233 0.076111533 0.34648612, + 0.94558823 0.069807716 0.31778908, + 0.94536376 0.078102484 0.31652391, + 0.9553861 0.070758104 0.28675902, + 0.95528334 0.072729424 0.2866081, + 0.96673155 0.062915869 0.24793488, + 0.96742314 0.048652206 0.24844603, + 0.97806036 0.040034514 0.20443907, + 0.98715276 0.018457396 0.15870996, + 0.97853249 0.023807511 0.20471311, + 0.89748478 0.066627085 0.4359839, + 0.86623782 0.075477585 0.49389789, + 0.86623579 0.075866789 0.49384189, + 0.88118476 0.071787886 0.46728989, + 0.88098824 0.076643817 0.46688911, + 0.89950198 0.070776202 0.431146, + 0.9000411 0.059993509 0.43165606, + 0.91948688 0.054117493 0.38937795, + 0.92021638 0.03432731 0.38990214, + 0.93829811 0.030329604 0.34449503, + 0.93850964 0.020818392 0.34462488, + 0.93299925 -0.013397103 0.35962909, + 0.93294501 -0.017176401 0.35960901, + 0.96375066 -0.013479895 0.26646391, + 0.9638229 -0.0056363493 0.26648396, + 0.96376663 -0.005559078 0.26668891, + 0.96369398 -0.0134774 0.26666901, + 0.94892925 0.037594609 0.31324109, + 0.94959623 0.0030289006 0.3134611, + 0.94955498 0.0030289099 0.313586, + 0.94955897 0.0030318401 0.31357399, + 0.94947588 -0.013559198 0.31354696, + 0.94947189 -0.013559098 0.31355897, + 0.95443988 0.0056405594 0.29834998, + 0.95411748 0.027932713 0.29812714, + 0.93846178 0.032219291 0.3438769, + 0.93773836 0.05221672 0.34339511, + 0.92047811 0.058748808 0.38635305, + 0.91984522 0.071009018 0.38580108, + 0.90304929 0.07775303 0.42244115, + 0.90324122 0.073505118 0.42279109, + 0.88972932 0.078190729 0.44974214, + 0.88973391 0.077798896 0.44980094, + 0.91066498 0.070413299 0.40710101, + 0.91052699 0.079451002 0.40574399, + 0.92293513 0.073975608 0.37778106, + 0.92276078 0.077539384 0.37749192, + 0.93785626 0.069823414 0.33992708, + 0.93854421 0.056604113 0.34048608, + 0.95361549 0.049366821 0.29695216, + 0.95428425 0.030239908 0.29736707, + 0.96749437 0.025585309 0.25159508, + 0.96760511 0.020276602 0.25165302, + 0.97561634 -0.013571405 0.21906307, + 0.975622 -0.0135717 0.21903799, + 0.97865075 0.0094888378 0.20531096, + 0.97846478 0.022343494 0.20520096, + 0.96759677 0.027332194 0.25101694, + 0.96700901 0.045378398 0.25066799, + 0.95421964 0.053281281 0.29432288, + 0.95350355 0.067279972 0.29377586, + 0.94024348 0.076013438 0.33191016, + 0.94039023 0.073151618 0.33213708, + 0.9291296 0.079530463 0.36109981, + 0.92932063 0.070750378 0.36243287, + 0.91744459 0.07622806 0.39049283, + 0.91748935 0.083636127 0.38886815, + 0.93496013 0.074593008 0.34682202, + 0.93954855 0.12629394 0.31827384, + 0.99728638 -0.0015803205 0.073603027, + 0.99723226 -0.010535703 0.073599018, + 0.99724078 -0.010537997 0.073483184, + 0.9972949 -0.0015983097 0.073487192, + 0.98796713 -0.015594502 0.15387602, + 0.99854833 -0.015867706 0.05147332, + 0.99967462 -0.0069432277 0.02454629, + 0.99969864 0 0.024546791, + 0.99970233 8.0068232e-005 0.02439801, + 0.99967825 -0.006946492 0.024397405, + 0.99770147 0.0071799732 0.067382127, + 0.99768847 0.0088840844 0.06737183, + 0.99354339 0.014832205 0.11247904, + 0.99333841 0.025668886 0.11233793, + 0.98702353 0.035769183 0.15654093, + 0.98653775 0.04853059 0.15616697, + 0.97862113 0.061035406 0.19640604, + 0.97864389 0.060562793 0.19643897, + 0.97102726 0.070404612 0.22836205, + 0.97126067 0.06338308 0.22942391, + 0.96311003 0.071662098 0.25939101, + 0.96312946 0.070154026 0.25973111, + 0.95229477 0.079578079 0.29462194, + 0.9521119 0.095735282 0.29037496, + 0.93994439 0.10687504 0.32416412, + 0.92372066 0.11074597 0.36670887, + 0.93752462 0.10058496 0.33306187, + 0.93759722 0.08144372 0.33805108, + 0.95016253 0.073019162 0.30308285, + 0.95015234 0.074660733 0.30271512, + 0.95958054 0.067392573 0.27324587, + 0.95933855 0.075185761 0.27205989, + 0.96814251 0.06669987 0.24135289, + 0.9680801 0.06791921 0.24126303, + 0.977727 0.056873798 0.20202801, + 0.97834647 0.042891819 0.20248109, + 0.98685253 0.033493586 0.15811493, + 0.98719275 0.019624995 0.15831995, + 0.99352324 0.013978303 0.11276603, + 0.99357414 0.0093485713 0.11279701, + 0.99229538 0.018519107 0.12250304, + 0.99246466 0.0012952395 0.12252396, + 0.99248779 0.0012952397 0.12233697, + 0.99248874 0.0012983097 0.12232897, + 0.99240953 -0.012701194 0.12231894, + 0.98718786 0.016297998 0.15872799, + 0.98519713 -0.013741402 0.17087401, + 0.98528433 -0.0034416511 0.17088906, + 0.98528051 -0.0034354883 0.17091092, + 0.98519325 -0.013741104 0.17089604, + 0.97531253 0.031319886 0.21859689, + 0.97578865 0.0022731894 0.21870393, + 0.97570926 0.0022731505 0.21905807, + 0.97570378 0.0022657195 0.21908194, + 0.96692222 -0.014998903 0.25463006, + 0.93565214 -0.011166401 0.35274702, + 0.9330681 -0.0080843214 0.35960904, + 0.93301463 -0.013397495 0.35958889, + 0.92016274 0.020694494 0.39098892, + 0.91992563 0.031458188 0.39082885, + 0.89946699 0.035060201 0.43557999, + 0.89875388 0.054755192 0.43502095, + 0.87728626 0.059939615 0.47621012, + 0.87684101 0.069387503 0.47574699, + 0.8565191 0.074487105 0.51071209, + 0.85670185 0.069267586 0.51113987, + 0.84028518 0.072803818 0.53723413, + 0.84028316 0.072285816 0.53730714, + 0.87495172 0.064560778 0.47988683, + 0.87524056 0.07341516 0.47808376, + 0.897493 0.066940203 0.43591899, + 0.90122002 0.081501298 0.42562899, + 0.92050266 0.073484771 0.38376385, + 0.92077422 0.10418102 0.37592709, + 0.90526903 0.11346 0.409408, + 0.82315755 0.016417691 0.56757563, + 0.7929371 0.023216601 0.60886109, + 0.79231173 0.049651682 0.60809278, + 0.76245868 0.052656282 0.64489079, + 0.76237082 0.055608086 0.64474684, + 0.73473173 0.058290478 0.67584878, + 0.73469597 0.0609392 0.67565399, + 0.76877671 0.057446677 0.63693178, + 0.76868099 0.063213997 0.63650101, + 0.7942937 0.060041778 0.60455978, + 0.79445732 0.055321518 0.60479522, + 0.8223412 0.051830411 0.56662911, + 0.87012541 0.0036175917 0.49281725, + 0.87006783 0.0036175891 0.49291888, + 0.84840029 0.020026708 0.5289762, + 0.84500188 0.012471898 0.53461796, + 0.84501749 -0.010868006 0.53462827, + 0.87036216 0.0037104608 0.49239811, + 0.87031782 -0.010762497 0.49237287, + 0.87002289 -0.010760199 0.49289393, + 0.87008184 -0.010667997 0.49279189, + 0.8764267 0.019559393 0.48113781, + 0.87614089 0.033265796 0.48090595, + 0.85092616 0.036249109 0.52403313, + 0.85035086 0.053484894 0.52349097, + 0.82431072 0.057542477 0.56320584, + 0.82406288 0.06384749 0.56288892, + 0.80008471 0.06761048 0.59606475, + 0.80021483 0.061896186 0.59651089, + 0.7811808 0.064434282 0.6209709, + 0.7811718 0.063953385 0.62103188, + 0.82234913 0.058285207 0.56599003, + 0.82277018 0.066419214 0.56448013, + 0.85213101 0.0611552 0.51974303, + 0.85323 0.086586103 0.51429701, + 0.87964827 0.078964129 0.46902418, + 0.88033402 0.107361 0.46204501, + 0.90177113 0.097823516 0.42099807, + 0.90144169 0.080114469 0.42542285, + 0.8779127 0.088612773 0.47054982, + 0.87709421 0.063936017 0.47604412, + 0.85020256 0.070077471 0.52177078, + 0.84985083 0.061779186 0.52338988, + 0.81188089 0.068437293 0.57979792, + 0.81188655 0.068905659 0.57973462, + 0.82956183 0.065907784 0.5545119, + 0.82940072 0.07146918 0.5540638, + 0.85177732 0.06702362 0.5195992, + 0.85211915 0.059171308 0.51999205, + 0.87579471 0.054573782 0.47958881, + 0.87645757 0.03564588 0.48015776, + 0.89915514 0.032399505 0.43642905, + 0.89941633 0.020283407 0.43662214, + 0.91427273 -0.012448396 0.40490785, + 0.91418898 -0.012447 0.40509701, + 0.91417027 -0.012489202 0.40513808, + 0.91423613 0.0034553804 0.40516707, + 0.91425431 0.0034553811 0.40512615, + 0.91433787 0.0034921095 0.40493694, + 0.89329129 -0.013905805 0.44926316, + 0.89332622 -0.010718203 0.44928113, + 0.89332879 -0.010718198 0.44927588, + 0.89332801 -0.0108194 0.44927499, + 0.89443469 -0.011950395 0.44703886, + 0.84369087 -0.012743098 0.53667796, + 0.84459019 -0.013535103 0.53524214, + 0.84460127 0.012493305 0.53525019, + 0.81744015 0.027908508 0.57533711, + 0.81775367 0.0034726288 0.57555783, + 0.81795698 0.0034726299 0.57526898, + 0.81788987 0.013263798 0.57522196, + 0.8172521 0.013291402 0.57612705, + 0.81731981 0.0033081493 0.57617486, + 0.78857535 -0.008142774 0.61488432, + 0.788526 0.0138293 0.61484599, + 0.78800368 0.013847295 0.61551476, + 0.78796935 -0.016691407 0.61548829, + 0.7840538 -0.013696096 0.62054187, + 0.64049417 -0.015668403 0.76780319, + 0.61433989 0.0020732796 0.78903884, + 0.61110789 0.015894696 0.7913878, + 0.61095804 0.031923104 0.79101914, + 0.57245106 0.033063404 0.8192721, + 0.57246596 0.030984996 0.81934285, + 0.52928996 0.032062497 0.84783489, + 0.52930892 0.028809097 0.84793991, + 0.56948191 0.027911793 0.82152981, + 0.56956887 0.016411796 0.82177985, + 0.57565832 -0.0018431609 0.81768841, + 0.57630908 -0.0017152702 0.81723011, + 0.57629502 0.0071969801 0.81721002, + 0.5756439 0.0072034281 0.8176688, + 0.61631197 0.018280298 0.78728986, + 0.61641473 0.0013059794 0.78742063, + 0.61566162 0.0013059292 0.78800952, + 0.61563295 0.0098189991 0.78797185, + 0.61431134 0.009835816 0.78900248, + 0.65095299 0.016896499 0.75893003, + 0.65072769 0.035930082 0.75846064, + 0.61391497 0.037352495 0.78848785, + 0.6139307 0.035999883 0.78853863, + 0.57954991 0.037166294 0.81408882, + 0.57956111 0.038869709 0.8140012, + 0.63460726 0.036862016 0.77195531, + 0.63489103 0.043234404 0.77139109, + 0.68712485 0.04065679 0.72540081, + 0.68771106 0.048014209 0.72439504, + 0.72755277 0.045373186 0.68454975, + 0.72954321 0.07121212 0.68021727, + 0.76691532 0.066819623 0.63826025, + 0.76905727 0.10185604 0.63101226, + 0.80293649 0.094985537 0.58844763, + 0.80427402 0.128157 0.580275, + 0.8349641 0.11867802 0.53735507, + 0.8355692 0.14995103 0.52852511, + 0.83783382 0.14077798 0.52746189, + 0.80754685 0.15209298 0.56985593, + 0.80664015 0.11907402 0.57892406, + 0.7730009 0.12780999 0.62139696, + 0.77134371 0.093413971 0.62952578, + 0.73448879 0.099608466 0.67127079, + 0.73197156 0.062748566 0.67843956, + 0.6924386 0.066445462 0.71841061, + 0.69030178 0.040597387 0.72238177, + 0.64843595 0.042715397 0.76006991, + 0.64785701 0.035784502 0.760921, + 0.59344906 0.037809603 0.80398309, + 0.59317309 0.031991303 0.80443913, + 0.53612679 0.03354349 0.84347069, + 0.53604108 0.026140204 0.84378713, + 0.48543283 0.02707169 0.8738547, + 0.48543888 0.025046794 0.8739118, + 0.52660584 0.02435459 0.84976071, + 0.52665496 0.015717298 0.84993386, + 0.49246082 -0.00012900896 0.87033468, + 0.49360195 7.2510193e-005 0.86968786, + 0.49359983 0.0024489891 0.86968571, + 0.49245983 0.002455299 0.8703317, + 0.53264779 0.018140391 0.84614259, + 0.53273505 3.1905904e-005 0.84628212, + 0.5356971 3.2083306e-005 0.84441018, + 0.5356909 0.0045745592 0.84440184, + 0.53448176 0.0045837276 0.84516758, + 0.53448719 0.00068944925 0.84517628, + 0.55822587 -0.015945597 0.82953584, + 0.46988711 -0.015908204 0.88258326, + 0.45035499 -0.00170622 0.89284801, + 0.4500652 -0.0015523107 0.8929944, + 0.45006505 0.0011239201 0.89299512, + 0.45035616 0.0011227103 0.89284831, + 0.48258877 0.014941293 0.87571961, + 0.48256719 0.020533007 0.87561828, + 0.440512 0.0210461 0.89749998, + 0.440512 0.022489499 0.89746499, + 0.49176875 0.021812588 0.87045258, + 0.49185887 0.028365493 0.87021279, + 0.54961598 0.0272169 0.83497399, + 0.5498842 0.032683112 0.83460128, + 0.60612971 0.031122785 0.79475665, + 0.60670322 0.037820216 0.79402828, + 0.65095592 0.036116295 0.7582559, + 0.65316021 0.061559822 0.7547133, + 0.69494897 0.058457401 0.71667898, + 0.6977638 0.096340477 0.70981979, + 0.73707217 0.090891719 0.66967416, + 0.73907608 0.12714401 0.66151404, + 0.77545911 0.11917402 0.62004906, + 0.77666914 0.15361002 0.61089206, + 0.80999303 0.14301001 0.568735, + 0.81046164 0.1758839 0.55876374, + 0.83807129 0.16380405 0.5203892, + -0.68861681 0.011267297 0.72503781, + -0.68865067 -0.0053217676 0.72507364, + -0.72638702 0.0036903501 0.68727601, + -0.7556392 -0.017130204 0.65476418, + -0.75105089 -0.013849298 0.66009897, + -0.88450527 0.13444504 0.44673815, + -0.86122233 0.14646205 0.48666719, + -0.86087328 0.11658005 0.49528417, + -0.832753 0.12684999 0.53891701, + -0.83170485 0.094851382 0.54705596, + -0.80056316 0.10237302 0.59043914, + -0.7981782 0.060931314 0.59933209, + -0.76085365 0.065634668 0.64559573, + -0.75983191 0.049896892 0.64820194, + -0.71223181 0.053874489 0.69987381, + -0.71199 0.047043201 0.70061201, + -0.66059595 0.050295994 0.74905497, + -0.66058892 0.052200094 0.74893093, + -0.69138604 0.050235007 0.72073704, + -0.69158673 0.040077586 0.72118074, + -0.72601718 0.011334803 0.68758321, + -0.72567976 0.038176585 0.68697274, + -0.76059049 0.018166889 0.64897764, + -0.7601921 0.041243404 0.64838809, + -0.72808319 0.043515511 0.68410617, + -0.72779518 0.055289514 0.68356216, + -0.69854593 0.057689693 0.71323591, + -0.69856304 0.055830408 0.71336704, + -0.74771667 0.051809773 0.66199368, + -0.74792993 0.059084293 0.66114295, + -0.7923888 0.054298788 0.60759491, + -0.79328728 0.070008121 0.60480922, + -0.82761955 0.064539559 0.55756664, + -0.82955348 0.10443806 0.54857427, + -0.8581059 0.096030787 0.50441295, + -0.85881591 0.12612699 0.49651495, + -0.88436359 0.11492795 0.4524298, + -0.84404629 0.0078907525 0.53621221, + -0.85119259 0.023191189 0.52434075, + -0.8505441 0.048442706 0.52366805, + -0.89265591 0.0078721894 0.45066994, + -0.89896375 0.049896687 0.4351719, + -0.89970469 0.024591891 0.43580586, + -0.91363376 0.006996118 0.4064779, + -0.91360456 0.0069985366 0.40654379, + -0.91349971 -0.016692294 0.40649685, + -0.93247789 0.0030874996 0.36121398, + -0.97539198 0.0029732101 0.220458, + -0.9628849 0.032249197 0.26797897, + -0.96780866 0.015670894 0.25119892, + -0.96713853 0.042108182 0.25073889, + -0.98660201 0.0274258 0.160824, + -0.99227822 -0.00031426808 0.12403203, + -0.99227649 -0.001865531 0.12403206, + -0.99228734 -0.0018848306 0.12394504, + -0.99228913 -0.00031964504 0.12394501, + -0.99356139 0.013425005 0.11249704, + -0.99347526 0.019172104 0.11242503, + -0.99770236 0.0083688926 0.067231022, + -0.99766439 0.012320993 0.067185462, + -0.99349964 0.020533493 0.11196797, + -0.99330425 0.029095007 0.11180403, + -0.98685485 0.040700197 0.15639998, + -0.9864465 0.050540924 0.15610607, + -0.97849786 0.063530892 0.19622897, + -0.97863209 0.060809009 0.19642203, + -0.97103488 0.070662595 0.22824997, + -0.97127724 0.063401014 0.22934906, + -0.96308786 0.071723893 0.25945598, + -0.96312052 0.069063172 0.26005587, + -0.95229536 0.078331031 0.29495412, + -0.95212287 0.095011182 0.29057696, + -0.926085 0.138734 0.35088399, + -0.93952709 0.12592402 0.31848404, + -0.93991852 0.10610095 0.32449284, + -0.92358786 0.11001199 0.36726397, + -0.93752915 0.099830717 0.33327603, + -0.9374941 0.071983211 0.34047502, + -0.91753101 0.0822559 0.38906401, + -0.91749114 0.07624191 0.39038107, + -0.92927676 0.070803583 0.36253491, + -0.92907941 0.079815336 0.36116618, + -0.94034022 0.073418416 0.33222008, + -0.94001138 0.079610333 0.33172411, + -0.95328176 0.070494883 0.29374194, + -0.95435125 0.049467713 0.29456207, + -0.94906998 0.00529576 0.31502101, + -0.94906598 -0.0060096402 0.31501999, + -0.94908249 -0.0060301726 0.31497014, + -0.94908625 0.0052935514 0.3149721, + -0.9544149 0.023037499 0.29759297, + -0.95374399 0.0456172 0.29713899, + -0.93873167 0.052298281 0.34065789, + -0.93763566 0.073469967 0.33976689, + -0.92254937 0.081556126 0.37716216, + -0.92291862 0.074302368 0.37775686, + -0.91057312 0.079774305 0.40557706, + -0.91071779 0.070425183 0.4069809, + -0.88966823 0.077855818 0.44992113, + -0.88965988 0.07850989 0.44982395, + -0.90322858 0.073787861 0.4227688, + -0.90284324 0.08194492 0.4220891, + -0.91956323 0.074888013 0.3857401, + -0.92063344 0.054011725 0.38667417, + -0.93792289 0.047982294 0.34350896, + -0.93865162 0.023912391 0.34403688, + -0.9324159 0.0060061188 0.36133698, + -0.93242812 0.0031373505 0.36134204, + -0.93256867 0.0031373189 0.36097887, + -0.93255574 0.0061944085 0.36097291, + -0.93246424 0.0062041013 0.36120909, + -0.92039323 0.024461405 0.39022809, + -0.91963965 0.049455781 0.38963684, + -0.90019733 0.054834917 0.43201613, + -0.89920813 0.074815311 0.43107706, + -0.88079321 0.080967821 0.4665271, + -0.88116831 0.072157919 0.46726418, + -0.86631012 0.076233305 0.49365506, + -0.8663131 0.075489506 0.49376407, + -0.89742732 0.066672921 0.43609515, + -0.897726 0.081606798 0.43292999, + -0.92047256 0.072391666 0.38404381, + -0.92078578 0.095140375 0.37828791, + -0.90175903 0.105426 0.41918501, + -0.90111578 0.071623184 0.4276219, + -0.87547511 0.079830505 0.47662407, + -0.87502289 0.064569093 0.47975594, + -0.84019285 0.072332993 0.53744197, + -0.84019583 0.073148683 0.53732687, + -0.85668886 0.069580793 0.51111895, + -0.85634357 0.078910865 0.51034176, + -0.87654257 0.073549964 0.47567177, + -0.87742513 0.054645706 0.47659105, + -0.87670678 0.024100395 0.48042089, + -0.87599885 0.049591593 0.47975695, + -0.85223091 0.053792093 0.52039295, + -0.85147715 0.071269505 0.51952606, + -0.82915086 0.075976491 0.55383795, + -0.82945281 0.066251382 0.55463386, + -0.81188887 0.069244392 0.57969093, + -0.81187916 0.068381518 0.5798071, + -0.84984815 0.061728913 0.52340013, + -0.85045803 0.077255897 0.52033901, + -0.87926722 0.069954813 0.47116411, + -0.88030571 0.10585696 0.46244583, + -0.90341645 0.095672742 0.41795376, + -0.90358609 0.11334702 0.41314006, + -0.88249475 0.12443697 0.45356187, + -0.88208932 0.096300036 0.46113417, + -0.85613841 0.10563505 0.50583422, + -0.85465872 0.06753698 0.51477879, + -0.8231051 0.073871911 0.56306404, + -0.82234544 0.058229428 0.5660013, + -0.78128833 0.063876621 0.62089324, + -0.78130668 0.064853176 0.62076879, + -0.80031645 0.062300336 0.59633237, + -0.80006886 0.072271995 0.59553891, + -0.82376111 0.068299904 0.56280804, + -0.82439119 0.052138012 0.56361413, + -0.82299829 0.021515407 0.56763619, + -0.82242399 0.046503998 0.566971, + -0.79450732 0.049641419 0.60522223, + -0.79400355 0.064358965 0.60449666, + -0.76845717 0.067745514 0.63630515, + -0.76864165 0.057724975 0.6370697, + -0.73469198 0.061219301 0.67563301, + -0.73466492 0.062954791 0.67550296, + -0.7620855 0.060082462 0.64468265, + -0.76247817 0.046731412 0.64532417, + -0.79237115 0.044060912 0.60844612, + -0.79291433 0.012436706 0.60920632, + -0.78731364 0.022865189 0.61612868, + -0.78751481 0.003482349 0.61628586, + -0.78762901 0.0034823399 0.61614001, + -0.78759891 0.009433249 0.61611593, + -0.7875213 0.0094353436 0.61621523, + -0.7875517 0.0034635989 0.61623877, + -0.75637269 -0.0076799071 0.65409577, + -0.75636017 0.0096570514 0.65408421, + -0.75571513 0.0096706413 0.65482908, + -0.7233268 0.015676897 0.69032782, + -0.72341192 0.0030529096 0.69040996, + -0.72354478 0.0030528789 0.69027078, + -0.72351193 0.010041399 0.69023895, + -0.72635603 0.0099944295 0.68724602, + -0.68917018 0.012361903 0.72449416, + -0.68893015 0.034584809 0.72400218, + -0.65334606 0.036122702 0.75619709, + -0.65321201 0.044994 0.75583702, + -0.62098628 0.046577424 0.78243637, + -0.62098402 0.044712 0.782547, + -0.67428696 0.042124797 0.73726696, + -0.67454857 0.048589669 0.73662961, + -0.72447222 0.045369416 0.68780923, + -0.72559333 0.061028231 0.68541229, + -0.7660079 0.057011392 0.64029795, + -0.7688455 0.10027794 0.63152266, + -0.8027398 0.093517974 0.58895087, + -0.80413628 0.12738304 0.5806362, + -0.83485156 0.11796094 0.53768778, + -0.8354798 0.14940196 0.52882189, + -0.863298 0.137214 0.48568401, + -0.86336589 0.15865599 0.47898594, + -0.84035385 0.17043495 0.51454586, + -0.84026015 0.18553601 0.50945008, + -0.81536841 0.19811486 0.5439896, + -0.81514484 0.21518296 0.53780586, + -0.78793103 0.228744 0.57169998, + -0.78751087 0.24814297 0.56413794, + -0.75781167 0.26270789 0.59724867, + -0.75716287 0.28336698 0.58856392, + -0.72525108 0.29866204 0.62033206, + -0.72428322 0.32161212 0.60990125, + -0.69020134 0.33752516 0.64007729, + -0.68885392 0.36236197 0.62783295, + -0.65203792 0.37900093 0.65666193, + -0.65029579 0.40506691 0.6426788, + -0.61057806 0.42227605 0.66998309, + -0.60837597 0.44991595 0.65379995, + -0.56635606 0.46721306 0.67893505, + -0.56369841 0.49597237 0.66049647, + -0.51968122 0.51301324 0.68319029, + -0.51657116 0.54270118 0.66229123, + -0.46976006 0.55952907 0.68282706, + -0.46628407 0.58963805 0.65947407, + -0.41718191 0.60575986 0.67750585, + -0.41342899 0.63602602 0.651573, + -0.3627378 0.65094256 0.66685456, + -0.35886618 0.6808303 0.6385023, + -0.30691615 0.69421333 0.65105331, + -0.30303487 0.72382075 0.61988175, + -0.25011709 0.73539323 0.62979221, + -0.24649097 0.76385087 0.59646791, + -0.19250791 0.77342767 0.60394567, + -0.18934388 0.80064553 0.56843263, + -0.13572499 0.80784988 0.57354796, + -0.133238 0.833408 0.53635699, + -0.08010719 0.83820289 0.53944296, + -0.07847099 0.86223388 0.50039494, + -0.026070099 0.86460698 0.50177199, + -0.02548369 0.8868897 0.46127781, + 0.026053894 0.88687676 0.46127087, + 0.026645696 0.86457491 0.50179696, + 0.079068206 0.86217409 0.50040406, + 0.08070571 0.83816409 0.53941405, + 0.13381396 0.8333447 0.53631181, + 0.13629995 0.80780572 0.57347381, + 0.18987295 0.80058181 0.5683459, + 0.19303608 0.77338231 0.60383523, + 0.24698897 0.76378685 0.59634393, + 0.25063193 0.73517883 0.62983781, + 0.30351382 0.72359359 0.61991262, + 0.30738711 0.69401622 0.65104121, + 0.35931218 0.68062031 0.6384753, + 0.36315182 0.65096968 0.66660273, + 0.41377223 0.63605338 0.65132844, + 0.41752407 0.60582703 0.67723507, + 0.46678388 0.58962989 0.65912783, + 0.47029006 0.55930704 0.68264407, + 0.51685804 0.54254907 0.66219205, + 0.51994193 0.51312095 0.68291092, + 0.56409085 0.49600783 0.66013473, + 0.56673533 0.46752122 0.6784063, + 0.60871398 0.45020801 0.65328401, + 0.61094868 0.4223038 0.66962773, + 0.65045482 0.40516692 0.6424548, + 0.65220106 0.37911505 0.65643406, + 0.68913424 0.36240512 0.62750024, + 0.69047594 0.33785897 0.63960493, + 0.72451818 0.32193208 0.60945314, + 0.72549605 0.29905102 0.61985809, + 0.75726402 0.28379199 0.588229, + 0.75792712 0.26294902 0.59699607, + 0.78760731 0.24837309 0.5639022, + 0.78802919 0.22929706 0.57134312, + 0.81521517 0.21571004 0.5374881, + 0.81545013 0.19853503 0.54371405, + 0.84032768 0.18592994 0.50919485, + 0.8404277 0.17079794 0.51430482, + 0.86336088 0.15902999 0.47887093, + 0.86330312 0.13775001 0.48552305, + 0.72613376 0.018309293 0.68730974, + 0.72570193 0.043592397 0.68662691, + 0.69182056 0.045750473 0.72061861, + 0.6918118 0.046191789 0.72059882, + 0.66060394 0.048024993 0.74919695, + 0.66060019 0.049908113 0.7490772, + 0.71212882 0.04667129 0.70049584, + 0.71238303 0.053846508 0.69972205, + 0.75983202 0.049881998 0.64820302, + 0.76037449 0.057862435 0.64690238, + 0.79504561 0.054037273 0.60413772, + 0.79665327 0.080013633 0.59911722, + 0.82822216 0.074184217 0.55546814, + 0.82961857 0.10618295 0.54814076, + 0.85817212 0.097630814 0.50399303, + 0.85883415 0.12695302 0.49627307, + 0.88437998 0.11568 0.45220599, + 0.88450873 0.13490096 0.44659385, + 0.8612234 0.14696008 0.48651522, + 0.86089784 0.11747497 0.49502987, + 0.83278471 0.12782395 0.53863782, + 0.83179456 0.096558154 0.54662079, + 0.80065298 0.10422 0.58999401, + 0.79887933 0.070670925 0.59732527, + 0.76458764 0.075726464 0.64005572, + 0.76275885 0.049628191 0.64477593, + 0.72517401 0.0528423 0.686535, + 0.72461522 0.045346215 0.68766022, + 0.67455125 0.048575319 0.73662823, + 0.67427403 0.041752499 0.73729998, + 0.62098813 0.044315811 0.78256619, + 0.62098402 0.0425032 0.78267002, + 0.65346825 0.041046117 0.7558403, + 0.65346497 0.0412689 0.755831, + 0.68883294 0.039522298 0.72384197, + 0.68915522 0.015995605 0.72443724, + 0.68936819 0.016100904 0.7242322, + 0.68945599 0.00227774 0.72432399, + 0.68981093 0.0022777799 0.72398597, + 0.68973398 0.0151211 0.72390503, + 0.72450435 0.014937907 0.68910837, + 0.72457308 -0.0057330206 0.68917406, + 0.75888389 0.0034265495 0.65121692, + 0.75881183 0.014214696 0.65115482, + 0.75724238 0.014258207 0.6529783, + 0.76060712 0.016048701 0.64901406, + 0.76003689 0.046781197 0.64819396, + 0.72826105 0.049330909 0.68352205, + 0.72821933 0.051009625 0.68344331, + 0.69858575 0.05325608 0.71354175, + 0.69856793 0.055541992 0.71338493, + 0.74770999 0.051543001 0.66202199, + 0.74793118 0.059065115 0.66114318, + 0.79238689 0.054281592 0.60759896, + 0.79287112 0.062304508 0.60619605, + 0.82482517 0.057805713 0.56242514, + 0.82618761 0.083554961 0.55716479, + 0.85514939 0.076879337 0.51264924, + 0.85618269 0.10726596 0.5054158, + 0.88213629 0.09778294 0.46073219, + 0.88250357 0.12512794 0.45335481, + 0.90535289 0.11298399 0.40935394, + 0.90532643 0.13068706 0.40411019, + 0.88646877 0.14240196 0.44033489, + 0.8863669 0.15359598 0.43676293, + 0.86547661 0.16619092 0.47257876, + 0.8652932 0.17932504 0.46809211, + 0.8425703 0.19267708 0.5029422, + 0.84226298 0.207782 0.49741301, + 0.81754953 0.22196287 0.5313617, + 0.81706309 0.23915803 0.52460605, + 0.79008085 0.25427994 0.55777586, + 0.78936785 0.27320996 0.54977691, + 0.75985312 0.28930804 0.58217204, + 0.758856 0.30999199 0.57274997, + 0.72707105 0.32679603 0.60379803, + 0.72571898 0.349388 0.59267199, + 0.69168699 0.366759 0.62213898, + 0.689897 0.39136899 0.60899299, + 0.65320241 0.40935925 0.63698637, + 0.65096182 0.4353109 0.6218949, + 0.61134994 0.45380494 0.64831495, + 0.6086663 0.48066324 0.63125932, + 0.56666487 0.49915388 0.65554285, + 0.56351489 0.52701187 0.63616782, + 0.5192709 0.54519588 0.65811783, + 0.5156132 0.57427716 0.63588423, + 0.46910781 0.59191775 0.65541679, + 0.46508089 0.62124187 0.6306808, + 0.41610208 0.63811916 0.64781415, + 0.41191593 0.66678792 0.62106293, + 0.36139488 0.68229479 0.63550574, + 0.35701013 0.71126223 0.60551625, + 0.30549002 0.72504008 0.61724603, + 0.30123103 0.75293714 0.58510303, + 0.24854809 0.7648353 0.59434927, + 0.24459302 0.79161614 0.55992705, + 0.19112803 0.80136311 0.56682205, + 0.18773399 0.82657999 0.530586, + 0.13471901 0.83387113 0.53526604, + 0.13203898 0.85764891 0.49699494, + 0.079620734 0.86247742 0.49979323, + 0.077875011 0.8845681 0.45986405, + 0.026209185 0.88695747 0.46110672, + 0.025590805 0.90717024 0.41998509, + -0.025184792 0.90717971 0.41998884, + -0.02580969 0.88705969 0.46093282, + -0.077412516 0.88469225 0.45970312, + -0.079169497 0.86261702 0.49962401, + -0.13163097 0.85780382 0.49683589, + -0.13432203 0.83403915 0.5351041, + -0.1871569 0.82679451 0.53045571, + -0.19057393 0.80141169 0.56693983, + -0.24403897 0.79169089 0.56006294, + -0.24799988 0.76486665 0.59453768, + -0.30051988 0.75303572 0.58534175, + -0.30477589 0.72509474 0.61753476, + -0.35657787 0.71127075 0.60576075, + -0.36093596 0.68249291 0.63555396, + -0.41152185 0.66698474 0.62111276, + -0.41574299 0.63807702 0.64808601, + -0.46476528 0.62120533 0.63094938, + -0.46876481 0.59207773 0.65551776, + -0.51531017 0.57443619 0.63598621, + -0.51897299 0.545331 0.65824097, + -0.56325519 0.52714419 0.63628823, + -0.5664081 0.49927813 0.65567017, + -0.60842925 0.48079017 0.63139123, + -0.61113638 0.45367926 0.64860433, + -0.65080118 0.43517908 0.62215513, + -0.65303499 0.40924099 0.63723397, + -0.68961805 0.39132506 0.60933703, + -0.69140118 0.3666971 0.62249315, + -0.72558993 0.34926596 0.59290195, + -0.72693837 0.32666215 0.60403031, + -0.75874603 0.30986199 0.57296598, + -0.75975132 0.28887209 0.5825212, + -0.78918916 0.27285007 0.55021214, + -0.78989518 0.25382006 0.5582481, + -0.81699514 0.23867203 0.52493304, + -0.81747359 0.2214009 0.53171277, + -0.84220582 0.20725195 0.49773088, + -0.84250218 0.19226204 0.50321513, + -0.86523813 0.17893802 0.46834207, + -0.86541659 0.16559793 0.47289675, + -0.8863216 0.15304393 0.43704879, + -0.88641632 0.14178905 0.44063815, + -0.90523303 0.13015801 0.40448999, + -0.90527922 0.12081303 0.40727609, + -0.92376202 0.108911 0.367154, + -0.92362386 0.12508999 0.36231396, + -0.90686899 0.137528 0.39833999, + -0.90672475 0.14667097 0.3953959, + -0.88806725 0.15988305 0.4310151, + -0.88783169 0.17152295 0.42700684, + -0.86718315 0.18562101 0.46210206, + -0.8668412 0.19862305 0.45731312, + -0.84426701 0.213497 0.491561, + -0.84374511 0.22897303 0.48545405, + -0.81922072 0.24464391 0.51867783, + -0.8184849 0.26180598 0.51140994, + -0.79155189 0.27847198 0.54396594, + -0.79054928 0.29730511 0.53538918, + -0.76112098 0.31488499 0.567047, + -0.75976169 0.33582488 0.5567618, + -0.72812116 0.3540301 0.58694309, + -0.72635299 0.37670699 0.57489401, + -0.69215655 0.39557475 0.60368866, + -0.68995619 0.41957209 0.58984715, + -0.65327132 0.43885821 0.61696029, + -0.65056896 0.46432495 0.60096794, + -0.61089295 0.48405194 0.62650096, + -0.60769302 0.51055902 0.60830802, + -0.56576306 0.53010005 0.63159007, + -0.56203002 0.55771798 0.61079699, + -0.51766795 0.57691193 0.63181692, + -0.51351303 0.604864 0.60864103, + -0.46701187 0.62331086 0.62720281, + -0.46250299 0.65138 0.60149401, + -0.41373992 0.66884881 0.61762488, + -0.40899515 0.69674623 0.58929425, + -0.35854891 0.71276081 0.60283887, + -0.35373709 0.74016017 0.57186812, + -0.30234501 0.75428802 0.582784, + -0.29769894 0.78064281 0.5495199, + -0.24560297 0.79267186 0.55798793, + -0.24132594 0.81770581 0.52260786, + -0.18841095 0.82751882 0.52887988, + -0.18476404 0.8509292 0.49171311, + -0.13239494 0.85821456 0.49592277, + -0.12953505 0.88011628 0.45674515, + -0.077827834 0.88490242 0.45922822, + -0.075993329 0.90491527 0.41875216, + -0.025329409 0.90724832 0.41983214, + -0.02467919 0.92532957 0.37835982, + 0.025164811 0.92531842 0.37835518, + 0.025822194 0.90728074 0.41973191, + 0.076507092 0.9049229 0.41864195, + 0.07835722 0.88481122 0.45931411, + 0.13008197 0.87999874 0.45681587, + 0.13293999 0.85813302 0.49591801, + 0.1853559 0.85081446 0.4916887, + 0.18901409 0.8273204 0.52897525, + 0.24191006 0.81748319 0.52268612, + 0.24615903 0.79259712 0.55784905, + 0.29820493 0.78055382 0.5493719, + 0.3028731 0.75406432 0.5827992, + 0.35421208 0.73992819 0.57187414, + 0.35898313 0.71275425 0.60258824, + 0.40940079 0.69672567 0.5890367, + 0.41416979 0.66868269 0.6175167, + 0.46288395 0.65121192 0.60138291, + 0.46735594 0.62337595 0.62688196, + 0.5139578 0.60486376 0.60826576, + 0.51812118 0.57691419 0.63144326, + 0.56227314 0.55778813 0.6105091, + 0.56603289 0.52998388 0.63144583, + 0.60792422 0.51044816 0.60817021, + 0.61112523 0.48392418 0.62637323, + 0.65076131 0.46420622 0.6008513, + 0.65343881 0.43900588 0.61667788, + 0.69022876 0.41964287 0.58947778, + 0.69243795 0.39563093 0.60332894, + 0.72647184 0.37683192 0.57466191, + 0.72824508 0.35415003 0.58671707, + 0.75986987 0.33593798 0.55654591, + 0.7612322 0.3150281 0.56681812, + 0.79064029 0.29744312 0.53517818, + 0.79164517 0.27864406 0.54374212, + 0.81855673 0.26197192 0.51120985, + 0.81928581 0.24513994 0.51834089, + 0.84379309 0.22944203 0.48514906, + 0.84432232 0.21404608 0.49122718, + 0.86688513 0.19913504 0.45700705, + 0.86723697 0.18602601 0.46183801, + 0.88787425 0.17189905 0.42676708, + 0.88811272 0.16043894 0.43071485, + 0.90671331 0.14721707 0.39521915, + 0.9068681 0.13760002 0.39831707, + 0.92358464 0.12518595 0.36238089, + 0.92611635 0.13913804 0.35064113, + 0.92616463 0.13885696 0.35062489, + 0.90820611 0.15410201 0.38912007, + 0.90794373 0.16374195 0.38578084, + 0.88952345 0.17850909 0.42057422, + 0.88915455 0.18972892 0.4164218, + 0.86867356 0.2053919 0.45079979, + 0.86812615 0.21905206 0.44539112, + 0.84575987 0.23547897 0.47878993, + 0.84503829 0.25030008 0.47250417, + 0.82060987 0.26751897 0.50500792, + 0.81961697 0.28448501 0.497289, + 0.79281729 0.30263311 0.5290122, + 0.79148614 0.32164302 0.51970708, + 0.76213586 0.34070998 0.55051392, + 0.76040918 0.36150408 0.5395301, + 0.72878933 0.38115019 0.56885028, + 0.72661865 0.40348983 0.55607677, + 0.69263303 0.42360407 0.58379704, + 0.68999106 0.44716907 0.56916803, + 0.65321332 0.46777621 0.59539729, + 0.65000683 0.49289888 0.5783959, + 0.61047322 0.51372516 0.60283422, + 0.60669905 0.53998303 0.58338207, + 0.56474012 0.56059015 0.60564613, + 0.56051594 0.58711797 0.58404994, + 0.51625806 0.60717404 0.60400105, + 0.51158184 0.63411176 0.5798158, + 0.465202 0.65327698 0.597341, + 0.46018595 0.68018496 0.57059395, + 0.4113839 0.69829583 0.58578688, + 0.40613601 0.72503 0.55622399, + 0.35623398 0.74136192 0.56875294, + 0.35099912 0.7671833 0.53687018, + 0.29985902 0.78160912 0.54696608, + 0.29488105 0.80613816 0.51301712, + 0.243314 0.81829798 0.52075601, + 0.23872396 0.84163588 0.48441693, + 0.18659295 0.8514728 0.49007887, + 0.18267898 0.87315589 0.45191494, + 0.13099298 0.88044786 0.45568895, + 0.12795705 0.90040028 0.41582015, + 0.077034682 0.90516573 0.41801992, + 0.075110413 0.92305821 0.3772561, + 0.02529919 0.92537659 0.37820381, + 0.024612796 0.94147891 0.33617198, + -0.024296204 0.94148612 0.33617502, + -0.024984896 0.92546189 0.37801594, + -0.074761398 0.92316002 0.377076, + -0.076696388 0.90523875 0.4179239, + -0.12741295 0.90051359 0.4157418, + -0.13044493 0.88056445 0.45562074, + -0.18211696 0.87330085 0.45186189, + -0.18603306 0.85160428 0.49006319, + -0.23818401 0.84179002 0.48441499, + -0.24275997 0.81853688 0.52063894, + -0.29451197 0.80635387 0.51288992, + -0.29951003 0.78179812 0.54688704, + -0.35047299 0.76744199 0.53684402, + -0.35572389 0.74156779 0.56880385, + -0.40569505 0.72523606 0.55627704, + -0.41098022 0.69831842 0.58604336, + -0.45967117 0.68027526 0.57090116, + -0.46468607 0.65332305 0.59769207, + -0.51128113 0.63409418 0.58010012, + -0.51593304 0.60729206 0.60416007, + -0.56022006 0.58723909 0.58421206, + -0.56447786 0.56049585 0.60597789, + -0.60634738 0.53995627 0.58377236, + -0.61011612 0.51366913 0.60324311, + -0.64984083 0.49276689 0.57869488, + -0.653014 0.467879 0.59553498, + -0.68982315 0.44726512 0.56929612, + -0.69246501 0.42369699 0.583929, + -0.72646827 0.40358216 0.55620617, + -0.72866023 0.38099715 0.5691182, + -0.76030183 0.36135691 0.5397799, + -0.76202285 0.34057796 0.55075192, + -0.79139501 0.32151499 0.519925, + -0.79272413 0.30247703 0.52924109, + -0.81954068 0.28433591 0.49749982, + -0.8205319 0.26731998 0.50523996, + -0.84497631 0.2501111 0.47271517, + -0.84570682 0.23497394 0.47913188, + -0.86815387 0.21852697 0.44559494, + -0.86868715 0.20505905 0.45092511, + -0.88911772 0.18945992 0.41662285, + -0.88948476 0.17812896 0.4208169, + -0.9079603 0.16335206 0.38590714, + -0.90822172 0.15357694 0.38929084, + -0.92613935 0.13841805 0.35086513, + -0.92568791 0.15437798 0.34535396, + -0.90932488 0.16980298 0.37986195, + -0.90895498 0.179544 0.37625101, + -0.8906737 0.19580093 0.41031986, + -0.89015412 0.20738003 0.40573305, + -0.86984688 0.22451997 0.43926895, + -0.86913091 0.23794398 0.43358293, + -0.84684098 0.25587201 0.46625099, + -0.84587848 0.27110514 0.45933828, + -0.82155418 0.28978705 0.49099112, + -0.82026982 0.30699995 0.48260587, + -0.79353988 0.32661298 0.51343793, + -0.7918852 0.34550309 0.50353312, + -0.76253772 0.36602589 0.5334428, + -0.76045591 0.38647595 0.52186495, + -0.72865701 0.40759701 0.550385, + -0.72608984 0.42953691 0.53692788, + -0.69208497 0.45091194 0.56364596, + -0.68894696 0.47443295 0.54796493, + -0.65224123 0.49616417 0.57306421, + -0.64852083 0.52086186 0.55508888, + -0.60871369 0.54289079 0.5785647, + -0.60446614 0.5681991 0.55836409, + -0.56249779 0.58971673 0.57950884, + -0.55772203 0.61557108 0.55679303, + -0.51362079 0.63632876 0.5755688, + -0.5083791 0.66243619 0.55020809, + -0.46200711 0.68223917 0.56665611, + -0.456397 0.708314 0.53851002, + -0.40785599 0.72683799 0.55259401, + -0.40215084 0.75204068 0.52221584, + -0.35238409 0.76870018 0.53378409, + -0.34675792 0.79283082 0.50117689, + -0.29619604 0.80734611 0.51035309, + -0.29078892 0.83043271 0.47520882, + -0.23975311 0.84262443 0.48218524, + -0.23485591 0.86413068 0.44510785, + -0.183391 0.873918 0.45015001, + -0.17923494 0.89372271 0.41125986, + -0.12833002 0.90092212 0.41457307, + -0.12516597 0.91872978 0.37452492, + -0.075300604 0.92338312 0.37642205, + -0.073286012 0.93924421 0.33533508, + -0.024326297 0.94149786 0.33613998, + -0.02363299 0.95547962 0.29410887, + 0.023994191 0.95547163 0.29410589, + 0.024698604 0.94151211 0.33607304, + 0.073558293 0.93924791 0.33526498, + 0.075584091 0.92325389 0.37668195, + 0.125549 0.918576 0.37477401, + 0.12870698 0.90073478 0.4148629, + 0.17964196 0.89351374 0.41153592, + 0.18378694 0.8736937 0.45042384, + 0.235275 0.86388302 0.44536701, + 0.24015303 0.84239614 0.48238507, + 0.29133603 0.8301481 0.47537106, + 0.29670405 0.80721319 0.51026809, + 0.34723991 0.79267985 0.50108188, + 0.3528901 0.76842916 0.53384012, + 0.40261105 0.75176311 0.52226108, + 0.40829515 0.72663224 0.55254018, + 0.45682916 0.70808923 0.53843915, + 0.4624238 0.68206769 0.56652272, + 0.50872803 0.66227299 0.55008203, + 0.5139308 0.63635778 0.5752598, + 0.55813193 0.61552793 0.55642992, + 0.56290698 0.58972299 0.57910502, + 0.60482389 0.56820285 0.55797291, + 0.60907429 0.54293323 0.57814533, + 0.64869076 0.52098584 0.55477381, + 0.65241373 0.49631077 0.57274067, + 0.68921691 0.47449794 0.54756892, + 0.69236016 0.45099813 0.5632391, + 0.72632283 0.42962292 0.53654391, + 0.72889775 0.40767986 0.55000484, + 0.76055562 0.38662982 0.52160579, + 0.7626431 0.36617902 0.53318703, + 0.79196972 0.34565189 0.50329781, + 0.79363 0.326749 0.51321203, + 0.82034141 0.30713215 0.48240024, + 0.82162851 0.28994283 0.49077469, + 0.84594142 0.27125111 0.45913622, + 0.8469041 0.25608003 0.46602207, + 0.8691178 0.23819394 0.43347192, + 0.8698231 0.22507703 0.43903106, + 0.89017999 0.207853 0.40543401, + 0.8907131 0.19610703 0.41008806, + 0.90898371 0.17982794 0.37604585, + 0.90934676 0.17040096 0.3795419, + 0.92570078 0.15492597 0.34507391, + 0.9278236 0.16750093 0.33329687, + 0.94094414 0.15202801 0.30250904, + 0.94171649 0.13153906 0.30962515, + 0.953565 0.117767 0.27720901, + 0.95398378 0.10151998 0.28214994, + 0.96449077 0.08941938 0.24851894, + 0.96472102 0.076089799 0.25203899, + 0.97391075 0.065586284 0.21724695, + 0.97388476 0.067058586 0.21691395, + 0.9808799 0.057480693 0.18593198, + 0.98067427 0.063631214 0.18501104, + 0.98707438 0.052122917 0.15155005, + 0.98708397 0.051894601 0.151566, + 0.99310154 0.037982982 0.11093495, + 0.99342161 0.02727019 0.11121996, + 0.99760789 0.016461598 0.067137696, + 0.99769443 0.0093315141 0.067220762, + 0.99974847 0.0030840114 0.022216011, + 0.99975276 0.00051836291 0.022230195, + 0.99999577 -6.7550784e-005 -0.0028969394, + 0.99999577 0 -0.0028969394, + 0.99957865 -0.0017990193 -0.028968388, + 0.99950677 -0.012131897 -0.028966293, + 0.99950475 -0.012133697 -0.029033992, + 0.99768764 0.0082370071 -0.067465276, + 0.99767411 -0.010420301 -0.06736321, + 0.99974865 -0.0034270289 -0.022154493, + 0.99973589 -0.0062232693 -0.022123897, + 0.99974149 0.0061560073 0.021884689, + 0.99972564 0.0084946575 0.021829993, + 0.99754852 0.02537719 0.065215468, + 0.99753213 0.026086403 0.065185808, + 0.99329686 0.042946596 0.10731699, + 0.9933601 0.041156005 0.10743301, + 0.98834014 0.054469209 0.14218602, + 0.98849964 0.049358781 0.14294095, + 0.98267937 0.060485922 0.17516506, + 0.98270702 0.059149802 0.175466, + 0.97505379 0.070905186 0.21033895, + 0.97481948 0.081732839 0.20747711, + 0.96593463 0.094850764 0.24077691, + 0.96553767 0.10809996 0.23675191, + 0.95530653 0.12278394 0.26891187, + 0.95459163 0.14013895 0.26289892, + 0.94297874 0.15657295 0.29372793, + 0.94181025 0.17726804 0.28560406, + 0.92886126 0.19534704 0.31473207, + -0.92796433 0.18875708 0.32133013, + -0.92741901 0.197293 0.31775701, + -0.91141415 0.21705604 0.34958702, + -0.91068387 0.22699396 0.34514996, + -0.89266825 0.24766006 0.3765741, + -0.8916629 0.25956398 0.37089598, + -0.871526 0.281151 0.40174201, + -0.87017602 0.29501399 0.394665, + -0.8480702 0.3172521 0.42441508, + -0.84637982 0.33237591 0.41613391, + -0.82204801 0.35536599 0.44491801, + -0.81988686 0.37230498 0.43494195, + -0.79313487 0.39605394 0.46268594, + -0.7904411 0.41459107 0.45090705, + -0.76094329 0.43914714 0.47761416, + -0.75764489 0.45917594 0.46382293, + -0.72573996 0.48401195 0.48891094, + -0.72180879 0.50520682 0.47303084, + -0.68766022 0.52998215 0.49622819, + -0.68309069 0.55199778 0.47821075, + -0.64602774 0.5769248 0.49980581, + -0.64076531 0.59977132 0.47926423, + -0.60094178 0.62442374 0.49896282, + -0.59504968 0.64762872 0.47591275, + -0.55306596 0.67135894 0.49335095, + -0.54660803 0.69463009 0.46766305, + -0.502837 0.71702099 0.48273799, + -0.49601617 0.73970222 0.45476216, + -0.4500728 0.76072562 0.4676868, + -0.44300705 0.78269213 0.43719307, + -0.39521599 0.80195999 0.447956, + -0.38810217 0.82290739 0.41497022, + -0.33970711 0.8397963 0.42348716, + -0.33281389 0.85928172 0.38841984, + -0.28387585 0.87374157 0.39495581, + -0.27745092 0.89156371 0.35795987, + -0.22852293 0.90344071 0.36272889, + -0.22282694 0.91935378 0.3242479, + -0.17373995 0.92872179 0.3275519, + -0.16903599 0.94262791 0.28788796, + -0.12102605 0.94936037 0.28994408, + -0.11751605 0.96114337 0.24978709, + -0.070574239 0.96543646 0.25090212, + -0.068372115 0.97535425 0.20978405, + -0.022868607 0.97738636 0.21022107, + -0.022231705 0.98421723 0.17556304, + 0.022414105 0.98421323 0.17556204, + 0.023048894 0.97739178 0.21017596, + 0.068549596 0.97535187 0.20973697, + 0.070756875 0.96540064 0.25098792, + 0.11769498 0.96109986 0.24986997, + 0.12121496 0.94926363 0.29018191, + 0.16926402 0.94251615 0.28812003, + 0.173999 0.92848301 0.328091, + 0.22308198 0.91910487 0.32477796, + 0.22873995 0.90321374 0.36315691, + 0.27797192 0.89124668 0.35834488, + 0.28439596 0.87340188 0.39533293, + 0.33322999 0.85895199 0.38879201, + 0.34006584 0.8395806 0.42362678, + 0.38859293 0.82262486 0.41507095, + 0.39575893 0.8014909 0.44831595, + 0.44340894 0.78225988 0.43755895, + 0.45039588 0.76047784 0.46777889, + 0.49634299 0.73943698 0.45483699, + 0.50316685 0.71669179 0.48288289, + 0.54700679 0.69424963 0.46776178, + 0.55336523 0.67132229 0.49306524, + 0.59543973 0.64751476 0.47557983, + 0.60135996 0.62421596 0.49871895, + 0.64102107 0.59964108 0.47908506, + 0.64627576 0.57682383 0.49960181, + 0.68328875 0.55191284 0.47802582, + 0.68781662 0.53011078 0.49587375, + 0.72203082 0.50526386 0.47263089, + 0.72599596 0.48391894 0.48862293, + 0.75777388 0.45916194 0.46362594, + 0.76104349 0.43933427 0.47728229, + 0.79051727 0.41477615 0.45060316, + 0.79324389 0.39603993 0.46251094, + 0.81997055 0.3723008 0.43478772, + 0.82210928 0.35556713 0.44464415, + 0.84636718 0.3326281 0.41595808, + 0.84808344 0.31729016 0.42436022, + 0.87023669 0.29499689 0.39454386, + 0.8715713 0.2813161 0.40152815, + 0.89169729 0.25972009 0.37070411, + 0.89268875 0.24803095 0.3762809, + 0.91069579 0.22733994 0.34489092, + 0.9114396 0.2172679 0.34938881, + 0.92878824 0.19571005 0.31472209, + 0.9276669 0.21143697 0.30777997, + 0.91169399 0.232649 0.33865699, + 0.91081625 0.24280307 0.33385709, + 0.89284778 0.26488695 0.3642219, + 0.8916533 0.27693108 0.35813913, + 0.8715319 0.29994398 0.38789895, + 0.8699798 0.3135989 0.38051391, + 0.84779453 0.33728179 0.40924975, + 0.84584028 0.35235712 0.40049815, + 0.82152081 0.37662691 0.4280839, + 0.81901473 0.39362684 0.41745985, + 0.79215902 0.41869599 0.444047, + 0.78907365 0.43714678 0.43158481, + 0.75958163 0.4628458 0.4569568, + 0.75586909 0.48250806 0.44254705, + 0.72387218 0.50845712 0.46634811, + 0.71955794 0.52885091 0.45005894, + 0.68517894 0.55469996 0.47205696, + 0.68008107 0.57632709 0.45314106, + 0.64297277 0.60207379 0.47338483, + 0.63715792 0.62431794 0.45194793, + 0.59741431 0.64959031 0.47024325, + 0.59097892 0.67192596 0.44638494, + 0.54912615 0.69612515 0.46246111, + 0.54219908 0.71812308 0.43625605, + 0.49837899 0.74094999 0.450124, + 0.49110207 0.7622931 0.42157805, + 0.44538978 0.78350067 0.43330678, + 0.43779784 0.8042537 0.40188184, + 0.39037219 0.82356143 0.41152921, + 0.38286906 0.84289014 0.37808406, + 0.3349379 0.85971284 0.38562992, + 0.32768998 0.8775329 0.35007897, + 0.27946201 0.89181 0.355775, + 0.27275288 0.90783358 0.31850284, + 0.22442697 0.91954088 0.32260996, + 0.21848603 0.93368912 0.28370503, + 0.17035004 0.94282025 0.28648007, + 0.16551894 0.95477867 0.24698392, + 0.11852897 0.96130776 0.24867295, + 0.11487298 0.97133088 0.20813598, + 0.069078393 0.97546786 0.20902297, + 0.067197897 0.98226798 0.175026, + 0.022567293 0.98424262 0.17537694, + 0.022067498 0.98867786 0.14842199, + -0.021789799 0.98868388 0.14842299, + -0.022282902 0.98422712 0.17550102, + -0.066995576 0.98225963 0.17514995, + -0.068863109 0.97546214 0.20912103, + -0.11470605 0.97132933 0.20823507, + -0.11834797 0.96135074 0.24859294, + -0.16527404 0.95484024 0.24691007, + -0.17009506 0.94292438 0.2862891, + -0.21819989 0.9338116 0.28352186, + -0.22411007 0.91976821 0.32218209, + -0.27229699 0.90811199 0.31809899, + -0.27899107 0.89214522 0.35530409, + -0.32730603 0.87786114 0.34961504, + -0.33456814 0.86006242 0.38517118, + -0.38247514 0.84326428 0.37764814, + -0.39000976 0.82391053 0.41117376, + -0.437271 0.80469 0.401582, + -0.44489995 0.78387386 0.43313494, + -0.49063671 0.7626785 0.42142275, + -0.49797988 0.74116182 0.45021689, + -0.54171509 0.71840507 0.43639305, + -0.54863811 0.69642019 0.46259612, + -0.59065497 0.67215097 0.44647494, + -0.59710389 0.64978385 0.47036988, + -0.63688993 0.62450296 0.45206994, + -0.6427207 0.60220373 0.47356176, + -0.679865 0.57644999 0.453309, + -0.68497616 0.5547691 0.47227013, + -0.71938878 0.52891183 0.45025784, + -0.72370797 0.50849003 0.46656701, + -0.75573313 0.48253405 0.44275105, + -0.75944984 0.46284187 0.45717987, + -0.78896582 0.4371379 0.43179092, + -0.7920801 0.41849205 0.44438004, + -0.81895584 0.39342692 0.41776392, + -0.8214317 0.37660286 0.42827585, + -0.8457756 0.35232282 0.40066481, + -0.84777015 0.33689708 0.4096171, + -0.86991483 0.31329092 0.38091591, + -0.8714391 0.29982302 0.38820106, + -0.89162499 0.276761 0.35834101, + -0.89281541 0.26472211 0.36442119, + -0.91079128 0.24265009 0.33403611, + -0.91168302 0.232287 0.33893499, + -0.92766315 0.21110103 0.30802202, + -0.92828703 0.20279001 0.31170401, + -0.94365478 0.18046795 0.27739295, + -0.94265467 0.19446692 0.27126491, + -0.94379061 0.20461193 0.25960192, + 0.97866952 0.0045414176 -0.2053909, + 0.9929145 -0.032826684 -0.11420695, + 0.98640901 -0.0453896 -0.157915, + 0.98699087 -0.028725896 -0.15818898, + 0.97804666 -0.037232384 -0.20503293, + -0.46542889 0.87778479 0.11344497, + -0.51221889 0.85177082 0.11008297, + -0.5164237 0.84781051 0.12051492, + -0.55622613 0.82276016 0.11695403, + -0.5646407 0.81392258 0.13678794, + -0.60282171 0.78684163 0.13223594, + -0.61371791 0.77369291 0.15731998, + -0.65025079 0.74448484 0.15138097, + -0.66043407 0.73028809 0.17466001, + -0.69531077 0.69899577 0.16717593, + -0.70455724 0.68418223 0.18839808, + -0.73747891 0.65113497 0.17929898, + -0.74560982 0.63621384 0.19823696, + -0.77597928 0.60220224 0.18764007, + -0.783077 0.58731198 0.204585, + -0.81082797 0.55271101 0.192532, + -0.81679648 0.53840131 0.20728612, + -0.84223109 0.50311708 0.19370103, + -0.84718502 0.489526 0.206499, + -0.8702991 0.45380005 0.19142903, + -0.87424999 0.44136301 0.20220201, + -0.8948037 0.40589187 0.18595193, + -0.8979004 0.39467818 0.1949461, + -0.91601843 0.35965517 0.17764708, + -0.91840667 0.34966087 0.18511194, + -0.93440437 0.31481913 0.16666606, + -0.93617988 0.30616796 0.17270899, + -0.95136923 0.26830807 0.15135203, + 0.94086885 0.25519696 0.22280097, + 0.92625058 0.28392586 0.24788289, + 0.92481357 0.29332685 0.24223788, + 0.90830678 0.3225379 0.26636094, + 0.90642297 0.33327201 0.25947499, + 0.8877297 0.36325088 0.2828159, + 0.88526624 0.3755351 0.27436706, + 0.86419815 0.40627307 0.29682302, + 0.86106372 0.41999385 0.28666091, + 0.83782482 0.45091888 0.30776894, + 0.83394182 0.46589389 0.29577693, + 0.80831373 0.49704581 0.31555387, + 0.80364603 0.512968 0.30169001, + 0.7754122 0.54429913 0.3201161, + 0.76989114 0.56100208 0.30421102, + 0.73890907 0.59232306 0.32119602, + 0.73242491 0.60975492 0.30290696, + 0.69918501 0.640288 0.318075, + 0.69175333 0.65806329 0.29737216, + 0.65626144 0.68758839 0.31071419, + 0.64792305 0.70535207 0.28753102, + 0.61016804 0.73365706 0.29906902, + 0.601098 0.750871 0.27363101, + 0.56095493 0.7778089 0.28344798, + 0.55129987 0.79413682 0.25576395, + 0.50980163 0.81887043 0.26372981, + 0.49965018 0.83413732 0.23359109, + 0.457095 0.85646898 0.23984399, + 0.4469218 0.87002456 0.2081299, + 0.40340006 0.8899141 0.21288803, + 0.39329582 0.90177661 0.17921291, + 0.34925187 0.91905564 0.18264695, + 0.34144989 0.92715764 0.15424193, + 0.29755703 0.94176114 0.15667102, + 0.29208884 0.9469195 0.13426694, + 0.25016606 0.95861423 0.13592602, + 0.24403585 0.96392542 0.10627393, + 0.20192292 0.97350264 0.10732996, + 0.19638103 0.9776721 0.074778706, + 0.15416592 0.9851675 0.075351864, + 0.14969102 0.98785412 0.041676305, + 0.10785501 0.99328309 0.041905303, + 0.10459001 0.99448711 0.0075034308, + 0.063389368 0.99796051 0.0075296364, + 0.061393887 0.99773675 -0.027426092, + 0.020764397 0.99940687 -0.027471997, + 0.020093698 0.99781388 -0.06295839, + -0.019942999 0.99781686 -0.062958591, + -0.020612307 0.99940836 -0.02753471, + -0.061169684 0.99774873 -0.027488992, + -0.063165314 0.99797523 0.0074653719, + -0.10429804 0.99451834 0.0074395128, + -0.10756198 0.9933179 0.041831598, + -0.14935306 0.98790836 0.041603714, + -0.15382197 0.98522377 0.075318389, + -0.19607905 0.97773522 0.074745916, + -0.20162304 0.97356021 0.10737202, + -0.94191426 0.24712506 0.22743505, + -0.94087863 0.25497392 0.22301492, + -0.92625713 0.28368804 0.24813104, + -0.92480421 0.29321107 0.24241406, + -0.90832078 0.32236791 0.26651895, + -0.90641272 0.33324987 0.25953892, + -0.88767499 0.363291 0.28293601, + -0.8852337 0.37547284 0.27455691, + -0.86415213 0.40621507 0.29703602, + -0.8610093 0.41998315 0.28684008, + -0.83774513 0.45092705 0.30797404, + -0.83382303 0.46605301 0.29586101, + -0.80822414 0.49715805 0.31560704, + -0.8035202 0.51318812 0.30165106, + -0.77527469 0.54452282 0.32006887, + -0.76966864 0.56144977 0.30394784, + -0.738657 0.59279001 0.320914, + -0.73218805 0.61013806 0.30270803, + -0.69886196 0.64073396 0.31788698, + -0.69132167 0.65872473 0.29691085, + -0.65589684 0.68817484 0.31018493, + -0.64751905 0.70596105 0.28694603, + -0.60969496 0.73429692 0.29846296, + -0.60060424 0.7514953 0.27300107, + -0.56047219 0.77840132 0.28277609, + -0.55075985 0.79476881 0.25496295, + -0.50935113 0.81942618 0.26287305, + -0.49926418 0.83454031 0.23297609, + -0.45676088 0.8568278 0.23919794, + -0.4466491 0.8702662 0.20770505, + -0.40319484 0.89011371 0.21244192, + -0.39322409 0.90179825 0.17926204, + -0.34911713 0.91909635 0.18270005, + -0.34149987 0.9270196 0.15495993, + -0.29749805 0.94165725 0.15740605, + -0.29194707 0.94691223 0.13462603, + -0.24998097 0.95861089 0.13628899, + -0.24378388 0.96398455 0.10631595, + -0.24695694 0.96344775 0.10382998, + -0.24037506 0.96799922 0.072092816, + -0.19876988 0.97733939 0.072788358, + -0.19313507 0.98036337 0.039832216, + -0.15152298 0.98763889 0.040127795, + -0.14702407 0.98911238 0.0063809422, + -0.10589595 0.99435651 0.0064147669, + -0.10260396 0.99432862 -0.02798439, + -0.062138472 0.9976725 -0.028078487, + -0.060126591 0.99619788 -0.063044496, + -0.02026459 0.9977985 -0.063145772, + -0.019584894 0.99495673 -0.098374076, + 0.019695492 0.99495465 -0.09837386, + 0.020375995 0.99779779 -0.063122682, + 0.060309224 0.99618834 -0.063020922, + 0.062324721 0.99766338 -0.02799261, + 0.10282799 0.99430788 -0.027898395, + 0.10612198 0.99433178 0.0065217088, + 0.14732301 0.98906714 0.0064871809, + 0.15183099 0.98758787 0.040220197, + 0.19345297 0.98029691 0.039923295, + 0.19907504 0.97727525 0.072817512, + 0.24072906 0.96790922 0.072119713, + 0.24729188 0.96337354 0.10372095, + 0.28873193 0.95190877 0.10248698, + 0.29572001 0.94622499 0.131179, + 0.33697513 0.93259436 0.12928905, + 0.3429521 0.92718923 0.15067904, + 0.38649407 0.91034913 0.14794202, + 0.39480183 0.90198058 0.17482191, + 0.43763113 0.88272727 0.17109005, + 0.4483538 0.87039757 0.20343789, + 0.490549 0.848544 0.19833, + 0.50106013 0.83470416 0.22849005, + 0.54241318 0.8103013 0.22181007, + 0.55267179 0.79496163 0.25017989, + 0.59273708 0.76825011 0.24177402, + 0.60236531 0.75195938 0.26779312, + 0.64033306 0.72358209 0.25768703, + 0.64913636 0.70678341 0.28121018, + 0.68487757 0.6770376 0.26937485, + 0.69287783 0.65984184 0.29073894, + 0.72646958 0.62885964 0.27708781, + 0.73346597 0.61190796 0.29596698, + 0.76479101 0.579997 0.280532, + 0.77082682 0.56350088 0.29714093, + 0.7993952 0.53144515 0.28023806, + 0.80447012 0.51577806 0.29462004, + 0.83037668 0.48383182 0.2763719, + 0.83464301 0.46891999 0.28893799, + 0.85824001 0.43695799 0.269243, + 0.86167616 0.42331409 0.27985606, + 0.88308132 0.39141616 0.25876808, + 0.8857947 0.37913886 0.2676219, + 0.90474224 0.34799808 0.24564005, + 0.90686029 0.33703312 0.2530081, + 0.92360491 0.30657497 0.23014297, + 0.92517263 0.29725188 0.23600191, + 0.93995911 0.26728803 0.21221203, + 0.94114739 0.25911409 0.21702908, + 0.95509237 0.22715507 0.19026108, + 0.96492833 -0.08087793 -0.24974409, + 0.97697586 -0.065731093 -0.20297197, + 0.97549313 -0.086488105 -0.20231903, + 0.98557812 -0.066516407 -0.15560001, + 0.98430246 -0.084438935 -0.15498008, + 0.99235737 -0.059037521 -0.10835804, + 0.99200922 -0.065096714 -0.10807502, + 0.99726009 -0.038168103 -0.063367605, + 0.99729162 -0.037234183 -0.063426577, + 0.99974847 -0.011356005 -0.01934441, + 0.9997561 -0.010404101 -0.019480802, + 0.99978763 0.0097094066 0.018179994, + 0.99978876 0.0095066484 0.018224996, + 0.99817288 0.027944697 0.053572092, + 0.99813735 0.030271711 0.052967019, + 0.99506825 0.04921921 0.086119823, + 0.9949761 0.052814707 0.085047707, + 0.9905439 0.072378293 0.11655098, + 0.99029934 0.078992933 0.11431304, + 0.98448187 0.099763185 0.14436999, + 0.98401737 0.10891104 0.14088404, + 0.97689354 0.13071693 0.16909193, + 0.97606802 0.14296 0.16387101, + 0.96753913 0.16613701 0.19043803, + 0.96615535 0.18184206 0.18296807, + 0.95607787 0.20662098 0.20790097, + 0.95470566 0.21912792 0.20129593, + 0.94190723 0.24734905 0.22722106, + 0.94156533 0.24319609 0.23304608, + 0.92709363 0.27063191 0.25933692, + 0.92582136 0.27982908 0.25406808, + 0.90950614 0.30776203 0.27943003, + 0.90778869 0.31858188 0.27280992, + 0.88933599 0.347314 0.29741299, + 0.88712221 0.35951808 0.28941506, + 0.86630481 0.38910392 0.31323192, + 0.8634876 0.40274882 0.30361584, + 0.84049487 0.43265295 0.32615897, + 0.83699656 0.44760379 0.31478184, + 0.81174117 0.47771311 0.3359561, + 0.80740303 0.494109 0.32242301, + 0.7795428 0.5245499 0.34228691, + 0.77441502 0.54172999 0.32681799, + 0.74375325 0.5723632 0.34529912, + 0.73780864 0.59008372 0.32777986, + 0.70480824 0.62014526 0.34447813, + 0.69796693 0.63834995 0.32457897, + 0.66274208 0.66751409 0.33940804, + 0.65496993 0.68599892 0.31689098, + 0.61717838 0.71429443 0.32996121, + 0.6087209 0.7323128 0.30524895, + 0.56866801 0.75924897 0.316477, + 0.55947506 0.77679813 0.28908902, + 0.51785988 0.80174482 0.29837295, + 0.50828606 0.81813115 0.26889902, + 0.46537581 0.84085971 0.2763699, + 0.45553884 0.8559497 0.24461091, + 0.4116469 0.87626374 0.25041693, + 0.40193093 0.88958687 0.21699497, + 0.35716796 0.90743387 0.22134797, + 0.34779492 0.91887176 0.18631496, + 0.30316493 0.93393278 0.18936895, + 0.29606897 0.9417069 0.15978499, + 0.25183192 0.95413363 0.16189393, + 0.24697299 0.95907903 0.13846201, + 0.20437789 0.96884751 0.13987194, + 0.19919696 0.97384089 0.10933599, + 0.15638506 0.98152936 0.11019903, + 0.15198593 0.98539054 0.076848663, + 0.10955202 0.9909721 0.077284008, + 0.10630196 0.99340767 0.042908184, + 0.064430676 0.99699265 0.043062985, + 0.062448323 0.99801534 0.0081057027, + 0.021154007 0.99974334 0.0081197331, + 0.020484902 0.99941713 -0.027308803, + -0.020225709 0.99942249 -0.027308913, + -0.020894298 0.99974889 0.0080982987, + -0.062153891 0.99803388 0.0080844089, + -0.064134903 0.99701399 0.0430099, + -0.10597499 0.99344486 0.042855896, + -0.109228 0.99101001 0.0772551, + -0.15163203 0.98544723 0.076821417, + -0.15603901 0.98158211 0.11022002, + -0.19892408 0.97389436 0.10935704, + -0.20415197 0.96884388 0.14022699, + -0.24680494 0.95907176 0.13881198, + -0.25170499 0.95406598 0.162489, + -0.29608595 0.94160277 0.16036595, + -0.30305493 0.93395776 0.18942195, + -0.34766111 0.91891134 0.18637006, + -0.35693917 0.9076004 0.22103411, + -0.40167499 0.88977599 0.216693, + -0.41130692 0.87660176 0.24979194, + -0.45519212 0.8563062 0.24400806, + -0.46501395 0.84128886 0.27567196, + -0.50777203 0.81866097 0.26825699, + -0.51736283 0.8022967 0.29775089, + -0.55896902 0.77737999 0.28850299, + -0.56813914 0.75993317 0.3157841, + -0.60826379 0.73297077 0.30457988, + -0.61683404 0.71477407 0.32956603, + -0.65456659 0.68654156 0.31654882, + -0.66236216 0.66804618 0.3391031, + -0.69766617 0.63883317 0.32427508, + -0.70456696 0.62051493 0.34430596, + -0.73752856 0.59050363 0.3276538, + -0.74355882 0.57254887 0.3454099, + -0.77425301 0.54189998 0.32692, + -0.77941018 0.52462614 0.34247208, + -0.80729467 0.49417475 0.32259384, + -0.81160682 0.4778809 0.3360419, + -0.83693409 0.44769606 0.31481704, + -0.84047586 0.43256193 0.32632896, + -0.86344069 0.40270686 0.30380487, + -0.86623615 0.38915908 0.31335309, + -0.88706499 0.35956901 0.289527, + -0.88930327 0.3472231 0.29761705, + -0.90780258 0.31843185 0.27293888, + -0.90951675 0.30761993 0.27955195, + -0.92583477 0.27969095 0.25417095, + -0.92712474 0.27034894 0.25952095, + -0.94156963 0.24298291 0.23325092, + -0.94247866 0.23538591 0.23733391, + -0.9560591 0.20644903 0.20815803, + -0.97735733 -0.056027818 -0.20404308, + -0.97841638 -0.029302811 -0.20455508, + -0.9635669 -0.037793096 -0.26478398, + -0.96770865 -0.013325496 -0.25171891, + -0.96719688 -0.036022197 -0.25146097, + -0.95354253 -0.045175377 -0.29785186, + -0.96726364 -0.038054686 -0.2509039, + -0.96547675 -0.072966985 -0.25006095, + -0.97736585 -0.059260193 -0.20308697, + -0.97560054 -0.085345566 -0.20228592, + -0.98563164 -0.06565918 -0.15562494, + -0.98395646 -0.088653848 -0.15482308, + -0.99219388 -0.061967593 -0.10821898, + -0.99194324 -0.066181913 -0.10802102, + -0.99723834 -0.038799316 -0.063327722, + -0.99728835 -0.037335016 -0.063420221, + -0.99974811 -0.011385601 -0.019340603, + -0.9997561 -0.010412601 -0.019480001, + -0.99978763 0.0097138463 0.018172795, + -0.99978966 0.0093557062 0.018252293, + -0.99817878 0.027517293 0.05368419, + -0.99813855 0.030192286 0.052988574, + -0.99507111 0.049092509 0.08615911, + -0.99497712 0.052772809 0.085061908, + -0.99054134 0.072338223 0.11659805, + -0.99030685 0.078711696 0.11444099, + -0.98449862 0.099393159 0.14451095, + -0.98403174 0.10865198 0.14098297, + -0.97691089 0.13041599 0.16922398, + -0.97608048 0.14278407 0.16395007, + -0.96755362 0.16593894 0.19053693, + -0.96617055 0.18167691 0.18305191, + -0.95607752 0.20647989 0.20804289, + -0.95471627 0.21891706 0.20147504, + -0.95511055 0.22699289 0.19036292, + -0.9411639 0.25894496 0.21715897, + -0.93997866 0.2671119 0.21234693, + -0.92516547 0.29711682 0.23619987, + -0.92359567 0.30646589 0.23032491, + -0.90684342 0.33692315 0.2532151, + -0.90472269 0.34791389 0.24583091, + -0.88576388 0.37905893 0.26783696, + -0.88304269 0.39138085 0.25895292, + -0.86162311 0.42328605 0.28006202, + -0.85813981 0.43711591 0.26930594, + -0.8345297 0.46908283 0.2890009, + -0.83026314 0.48398706 0.27644104, + -0.8043322 0.51594913 0.29469705, + -0.79922253 0.53171271 0.28022283, + -0.77056903 0.56384498 0.29715699, + -0.76451337 0.58038032 0.28049612, + -0.73320997 0.61224794 0.29589796, + -0.72605598 0.62954098 0.27662399, + -0.69245499 0.66050899 0.29023099, + -0.68442804 0.67770606 0.26883602, + -0.64873272 0.70739162 0.28061187, + -0.63985026 0.72427624 0.25693509, + -0.60190922 0.75261128 0.2669861, + -0.59226906 0.76885611 0.24099302, + -0.55213505 0.79558814 0.24937204, + -0.54193485 0.8107897 0.22119392, + -0.50068623 0.83510941 0.2278281, + -0.49022093 0.84884787 0.19783998, + -0.44810921 0.87064439 0.20292009, + -0.43760589 0.88270879 0.17124896, + -0.39468616 0.90199828 0.17499106, + -0.38658705 0.91017812 0.14874901, + -0.34295088 0.92705464 0.15150695, + -0.33687699 0.93256801 0.12973399, + -0.29546204 0.94624209 0.13163601, + -0.28840807 0.95199525 0.10259602, + -0.29197299 0.95122498 0.099613599, + -0.32952413 0.93901235 0.09833464, + -0.95355523 0.24770406 0.17139204, + -0.93907303 0.282653 0.195574, + -0.93764025 0.29091305 0.19026405, + -0.92233324 0.32337508 0.21149504, + -0.92039102 0.333029 0.204871, + -0.90302825 0.3658911 0.22508606, + -0.90042377 0.37712592 0.21682495, + -0.88078243 0.4105092 0.23601812, + -0.87746233 0.42298615 0.22614707, + -0.85531068 0.45691186 0.24428491, + -0.85119772 0.47043782 0.23270291, + -0.82674581 0.5042569 0.24943194, + -0.82166886 0.51891595 0.23576798, + -0.79491663 0.55237776 0.25097087, + -0.78882718 0.56784111 0.23517706, + -0.75933719 0.6011771 0.24898405, + -0.75222737 0.61707228 0.2310321, + -0.72017092 0.64974993 0.24326697, + -0.71198493 0.66585594 0.22296497, + -0.67778981 0.69720584 0.23346294, + -0.66871029 0.71292233 0.2111121, + -0.63253927 0.74265134 0.21991611, + -0.6224981 0.75791216 0.19510305, + -0.58440286 0.78584385 0.20229396, + -0.57381481 0.79990572 0.17574795, + -0.53384411 0.82588416 0.18145505, + -0.52280194 0.83861285 0.15299198, + -0.48198381 0.86195368 0.15724994, + -0.47342589 0.8705548 0.13417298, + -0.43193093 0.89138186 0.13738298, + -0.42512605 0.89744514 0.11772902, + -0.38564599 0.91480899 0.120007, + -0.37974083 0.91955858 0.10103896, + -0.33429298 0.93683088 0.10293698, + -0.34074789 0.93164665 0.12619595, + -0.38152018 0.91599542 0.12407606, + -0.38802209 0.91020226 0.14481303, + -0.43055472 0.89135349 0.14181492, + -0.43897295 0.88293189 0.16653499, + -0.48071906 0.8616811 0.16252701, + -0.49156424 0.84928042 0.19258109, + -0.53266203 0.82537413 0.18716002, + -0.54325712 0.81146318 0.21540505, + -0.58328795 0.7850759 0.20840096, + -0.59348804 0.76980013 0.23490404, + -0.63153607 0.74158806 0.22629502, + -0.64097297 0.72553802 0.250496, + -0.67687893 0.69579196 0.24022597, + -0.68544376 0.67929578 0.26215291, + -0.71938759 0.64802665 0.25008586, + -0.72697717 0.63148916 0.26967707, + -0.75866163 0.59913868 0.25586188, + -0.76533109 0.58267808 0.27341303, + -0.79432201 0.54996097 0.25806099, + -0.79992503 0.53428602 0.27323699, + -0.82624054 0.50153768 0.25648886, + -0.83086932 0.48684818 0.26950908, + -0.85488719 0.45390511 0.25127307, + -0.8586629 0.44028094 0.26239398, + -0.88044089 0.40730795 0.24274297, + -0.88348114 0.39478207 0.25220704, + -0.90275246 0.36250079 0.23158386, + -0.90508312 0.35149604 0.23932204, + -0.92211664 0.31981888 0.21775393, + -0.92388642 0.31020314 0.2240711, + -0.93890989 0.27899098 0.20152497, + -0.94020033 0.27086908 0.20652707, + -0.95336235 0.24001908 0.18300606, + -0.95508265 0.22695492 0.19054793, + -0.96538699 0.199753 0.16771001, + -0.96709001 0.18361899 0.176128, + -0.97574401 0.157985 0.15154, + -0.97678912 0.14505401 0.15761502, + -0.98395336 0.12082604 0.13128905, + -0.98454249 0.11110906 0.13539205, + -0.99033511 0.087985709 0.10721502, + -0.99063563 0.08114887 0.10979896, + -0.99503064 0.059179876 0.080073573, + -0.99515724 0.054970615 0.081488825, + -0.9981721 0.033797905 0.050102308, + -0.99820709 0.031843103 0.050682306, + -0.99979287 0.010825999 0.017230898, + -0.99979788 0.0099802893 0.017450098, + -0.99978387 -0.010320099 -0.018044299, + -0.99978137 -0.010723704 -0.017954705, + -0.99766725 -0.035004407 -0.058607616, + -0.99757499 -0.038270101 -0.058134299, + -0.99198288 -0.069486395 -0.10555398, + -0.99181461 -0.072109476 -0.10537496, + -0.98307621 -0.10345902 -0.15118703, + -0.98390937 -0.094417639 -0.15168306, + -0.97205877 -0.12404697 -0.19928396, + -0.97544938 -0.090500928 -0.20076908, + -0.96246946 -0.11152805 -0.24741513, + -0.96546489 -0.077440396 -0.24875797, + -0.95085913 -0.092032105 -0.29563004, + -0.953655 -0.048462 -0.296974, + -0.93838412 -0.026918903 -0.34454402, + -0.93729657 -0.056133173 -0.34398282, + -0.92029977 -0.0088857077 -0.39111292, + -0.91833812 -0.067756906 -0.38995406, + -0.93741536 -0.059610922 -0.34307313, + -0.93329924 -0.11260703 -0.34098709, + -0.95080835 -0.09714134 -0.29415512, + -0.94599426 -0.14096503 -0.29193106, + -0.96216035 -0.11848505 -0.2453751, + -0.95605999 -0.164408 -0.242733, + -0.97186202 -0.13209499 -0.195026, + -0.96966237 -0.14886005 -0.19389607, + -0.98264313 -0.11296701 -0.14714302, + -0.9830429 -0.10902499 -0.14744599, + -0.99281311 -0.071152508 -0.096226811, + -0.99313986 -0.065114096 -0.097125985, + -0.99790865 -0.035994988 -0.053691182, + -0.99794126 -0.034596108 -0.054003712, + -0.99979174 -0.011008097 -0.017183397, + -0.99978638 -0.011788605 -0.016981106, + -0.99979991 0.011406799 0.016431099, + -0.99979621 0.011956602 0.016268503, + -0.99823421 0.035178509 0.04786491, + -0.99818689 0.037488297 0.047092292, + -0.99519253 0.06099727 0.076624066, + -0.99503052 0.06561707 0.074890666, + -0.99063426 0.089982219 0.10269902, + -0.99026024 0.097209521 0.099675119, + -0.98441666 0.12277895 0.12589295, + -0.98367852 0.13307793 0.12110694, + -0.97639638 0.15974106 0.14537205, + -0.97511137 0.17316106 0.13846704, + -0.96624964 0.20119293 0.16088194, + -0.96414179 0.21803795 0.15129498, + -0.95349073 0.24764293 0.17183796, + -0.95140266 0.2609899 0.16345394, + -0.93773824 0.29437605 0.18436304, + -0.93614686 0.30280596 0.17871098, + -0.92053276 0.33644092 0.19856195, + -0.9183439 0.34641498 0.19141898, + -0.90061623 0.3804031 0.21020004, + -0.89779776 0.39152992 0.20165196, + -0.87770802 0.42601299 0.219412, + -0.87409973 0.43841887 0.20913793, + -0.85151118 0.47324911 0.22575206, + -0.84697884 0.48685789 0.21353295, + -0.82205915 0.52145213 0.22870606, + -0.81652272 0.53601182 0.21443392, + -0.78930098 0.57007998 0.228063, + -0.78272581 0.5852499 0.21171395, + -0.7528013 0.61899126 0.22392008, + -0.74515676 0.63447076 0.20539792, + -0.71266001 0.66740799 0.216061, + -0.70399636 0.68279427 0.19540009, + -0.66950005 0.71414405 0.20437203, + -0.65977305 0.72926307 0.18131402, + -0.62339896 0.75880289 0.18865797, + -0.61295706 0.77295715 0.16377102, + -0.57480294 0.8005209 0.16961099, + -0.56376207 0.8134861 0.14287302, + -0.52388203 0.8389501 0.14734502, + -0.51531106 0.84771311 0.12584502, + -0.47470105 0.87060612 0.12924401, + -0.46773994 0.87689686 0.11077598, + -0.42937708 0.89600426 0.11318903, + -0.42322099 0.90100503 0.095257498, + -0.38119492 0.91937077 0.097199179, + -0.37744313 0.92210436 0.08520823, + -0.33462101 0.93835503 0.086709902, + -0.33090085 0.94080752 0.073388465, + -0.28588399 0.95536202 0.074523903, + -0.28022897 0.95745486 0.068934396, + -0.2435369 0.96738762 0.06964948, + -0.236853 0.97082001 0.037540302, + -0.19583395 0.97990477 0.037891593, + -0.19016191 0.98174053 0.0048949677, + -0.14917801 0.98879814 0.0049301605, + -0.14464393 0.9890635 -0.028834987, + -0.10417398 0.99413675 -0.028982893, + -0.10085896 0.99287754 -0.063417368, + -0.061083991 0.99610287 -0.063623391, + -0.059064467 0.99339139 -0.098411642, + -0.019913189 0.9949314 -0.09856414, + -0.019220604 0.99083823 -0.13368003, + 0.019296892 0.99083662 -0.13367996, + 0.019990198 0.99493188 -0.098544486, + 0.059176784 0.99338675 -0.098391481, + 0.061199091 0.99609989 -0.063559093, + 0.10107804 0.99285936 -0.063352324, + 0.10439502 0.99411613 -0.028895104, + 0.14489995 0.98902863 -0.028747289, + 0.14943901 0.98875803 0.0050608502, + 0.19045405 0.98168325 0.0050246413, + 0.19611095 0.97984475 0.038010791, + 0.2371731 0.97073734 0.037657514, + 0.243843 0.96730602 0.069711201, + 0.28480402 0.95610613 0.068904005, + 0.29226911 0.95114338 0.099524237, + 0.32983312 0.93891335 0.098244436, + 0.95353127 0.24781705 0.17136204, + 0.93906885 0.28271997 0.19549698, + 0.93763578 0.29097694 0.19018796, + 0.92233658 0.32342884 0.2113979, + 0.92040533 0.33302712 0.20481007, + 0.90307343 0.36583918 0.2249891, + 0.90047872 0.37703285 0.21675892, + 0.88082576 0.41044492 0.23596793, + 0.87753028 0.42283714 0.22616208, + 0.8553887 0.45675585 0.24430391, + 0.85132486 0.47013593 0.23284797, + 0.82692909 0.50389004 0.24956603, + 0.82191569 0.51839483 0.23605391, + 0.79514098 0.55190003 0.251311, + 0.78912389 0.56722397 0.23566997, + 0.75971514 0.60048908 0.24949104, + 0.75264531 0.61634827 0.23160309, + 0.72059906 0.64904207 0.24388804, + 0.71249801 0.66504198 0.223754, + 0.67827129 0.69644934 0.2343211, + 0.66918218 0.71224821 0.21189104, + 0.63300478 0.74200875 0.22074392, + 0.62299699 0.75728101 0.19596, + 0.58481407 0.78530115 0.20321102, + 0.57411373 0.79956466 0.17632291, + 0.53416425 0.82554543 0.18205309, + 0.52284098 0.838615 0.15284701, + 0.48203313 0.8619532 0.15710105, + 0.47318083 0.87083071 0.13324295, + 0.4318082 0.8915894 0.13641906, + 0.42513499 0.89751297 0.117178, + 0.38573983 0.91484356 0.11944094, + 0.37996519 0.91947943 0.10091604, + 0.334564 0.93674803 0.102811, + 0.34092608 0.93165123 0.12568003, + 0.38154399 0.916053 0.123576, + 0.38794801 0.91036803 0.143967, + 0.43038085 0.89156771 0.14099395, + 0.43901515 0.88294929 0.16633207, + 0.48077682 0.86168671 0.16232593, + 0.49188095 0.8489759 0.19311397, + 0.53299999 0.82503998 0.18767001, + 0.54369181 0.81095672 0.21621393, + 0.58372414 0.7845462 0.20917304, + 0.5939399 0.76918679 0.23576894, + 0.63200217 0.74094117 0.22711106, + 0.64143723 0.72482723 0.25136408, + 0.67736506 0.69503903 0.24103403, + 0.68586868 0.67859173 0.26286387, + 0.719809 0.647304 0.25074399, + 0.72736806 0.63076705 0.27031204, + 0.75903165 0.59841871 0.25644889, + 0.76557785 0.58220994 0.27371898, + 0.79455084 0.54949886 0.25834095, + 0.80008572 0.5339818 0.27336091, + 0.82642901 0.501185 0.25657099, + 0.83098418 0.48671511 0.26939505, + 0.85497415 0.45379612 0.25117406, + 0.85876018 0.44013011 0.26232907, + 0.88048476 0.4072279 0.24271794, + 0.88350958 0.39476183 0.25213888, + 0.90280044 0.3624388 0.23149386, + 0.90509975 0.35158792 0.23912394, + 0.92212546 0.31991181 0.21757987, + 0.92389256 0.31032285 0.22387989, + 0.93891078 0.27910694 0.20135996, + 0.94018245 0.27112013 0.2062791, + 0.95334655 0.24024688 0.18278891, + 0.95507735 0.22713508 0.19036007, + 0.96536452 0.19996391 0.16758792, + 0.96707553 0.18379191 0.17602691, + 0.97573179 0.15813896 0.15145797, + 0.97677702 0.145237 0.15752099, + 0.98394287 0.12098698 0.13121998, + 0.98452777 0.11137597 0.13527897, + 0.99032462 0.088203073 0.10713296, + 0.9906249 0.081417695 0.10969698, + 0.99502414 0.059380908 0.080006011, + 0.99515665 0.05499018 0.081482172, + 0.99817187 0.033810295 0.050098691, + 0.99820626 0.031894606 0.050667111, + 0.99979287 0.010843699 0.017226098, + 0.99979699 0.0101479 0.0174064, + 0.99978298 -0.0104937 -0.017999601, + 0.99978149 -0.010716105 -0.017950209, + 0.99766755 -0.034990184 -0.058610771, + 0.99757779 -0.038174294 -0.058149487, + 0.99199414 -0.069303811 -0.10556801, + 0.9918949 -0.07086809 -0.10546198, + 0.98324752 -0.10166395 -0.15128992, + 0.98427022 -0.090190224 -0.15191403, + 0.97268099 -0.118511 -0.199617, + 0.97532755 -0.091758057 -0.20078991, + 0.962309 -0.113037 -0.247354, + 0.96488678 -0.085139975 -0.24848494, + 0.95000738 -0.10120504 -0.29537013, + 0.93861347 0.0098496145 -0.34483019, + 0.93630964 -0.07284268 -0.34353787, + 0.95290047 -0.062908627 -0.29668716, + 0.95446837 -0.0060896822 -0.29825011, + 0.9528389 -0.060199294 -0.29744598, + 0.96677452 -0.050708279 -0.25055087, + 0.96766925 0.013614602 -0.25185505, + 0.96671611 -0.048181009 -0.25127402, + 0.97809076 -0.039203487 -0.20445396, + 0.97698635 -0.062394723 -0.20397207, + 0.98641288 -0.048056394 -0.15709898, + 0.98565114 -0.062657811 -0.15673502, + 0.99286026 -0.044279013 -0.11076103, + 0.99234402 -0.055268101 -0.110448, + 0.99736178 -0.032484893 -0.064917788, + 0.99727809 -0.035169505 -0.064804204, + 0.99971545 -0.011378306 -0.02096601, + 0.99971867 -0.011055997 -0.020985693, + 0.99975711 0.010273201 0.019499902, + 0.99976325 0.0094021019 0.019624706, + 0.99808663 0.026715191 0.05576168, + 0.9980945 0.026154786 0.055886574, + 0.99495834 0.042510014 0.090833731, + 0.99487066 0.046664987 0.089748271, + 0.99035048 0.063932329 0.12295806, + 0.99018162 0.069491975 0.12128995, + 0.98429865 0.08774817 0.15315494, + 0.98392624 0.096782021 0.15007503, + 0.97677523 0.11612503 0.18007004, + 0.97612786 0.12789698 0.17554699, + 0.96763146 0.14860807 0.2039731, + 0.96654975 0.16362795 0.19750296, + 0.95658398 0.18594299 0.224438, + 0.95484865 0.20451392 0.21549493, + 0.94325286 0.22859597 0.24086897, + 0.94334435 0.22872707 0.24038608, + 0.92773157 0.25728789 0.2704019, + 0.92659891 0.26637498 0.26544097, + 0.91043133 0.29301512 0.2919881, + 0.90891325 0.30364007 0.28579605, + 0.89065313 0.33109102 0.31163403, + 0.88864487 0.34339297 0.30395997, + 0.86801517 0.37180308 0.32910809, + 0.86549586 0.38535994 0.32002297, + 0.84279019 0.41407508 0.3438701, + 0.83959413 0.42924505 0.33291203, + 0.81461513 0.45831406 0.35545802, + 0.81073612 0.47460505 0.34272003, + 0.78307688 0.50420696 0.36409596, + 0.77839428 0.52166718 0.34923613, + 0.74806798 0.55145502 0.36917701, + 0.74251705 0.56986809 0.35202104, + 0.70977926 0.59930223 0.37020311, + 0.70347196 0.61799496 0.35101196, + 0.6684286 0.64673567 0.36733678, + 0.66130221 0.66568023 0.34575912, + 0.62369078 0.69367975 0.3603029, + 0.61568093 0.71281296 0.33590898, + 0.57567984 0.73966074 0.34856087, + 0.56711769 0.75807363 0.32202786, + 0.52531594 0.78317291 0.33269098, + 0.51623088 0.80082083 0.30363095, + 0.47309917 0.82378531 0.31233811, + 0.46376112 0.8401922 0.28107405, + 0.41942185 0.86089569 0.2879999, + 0.41004816 0.8757953 0.25464308, + 0.36464688 0.89411873 0.25996992, + 0.35561982 0.90711659 0.22510889, + 0.31017888 0.92269164 0.22897393, + 0.30169705 0.93374425 0.19261505, + 0.25669008 0.94656438 0.19525908, + 0.2504279 0.95405465 0.16451594, + 0.20572902 0.96437609 0.16629602, + 0.20159605 0.96912926 0.14194202, + 0.15836105 0.97695822 0.14308903, + 0.15421793 0.98170251 0.11170094, + 0.11118405 0.98742849 0.11235305, + 0.10797296 0.99106467 0.07831087, + 0.065491073 0.99475253 0.078602262, + 0.063518383 0.99702674 0.043624189, + 0.021533089 0.9988125 0.043702278, + 0.020864099 0.99974799 0.0082896501, + -0.020567702 0.99975413 0.0082897013, + -0.021236807 0.99881935 0.043693013, + -0.063149668 0.99705052 0.043615676, + -0.065123864 0.99477643 0.078604452, + -0.10759901 0.99110514 0.078314409, + -0.11078998 0.98746789 0.11239499, + -0.15383606 0.98175734 0.11174504, + -0.15799206 0.97697335 0.14339304, + -0.20144807 0.96911633 0.14224005, + -0.2056119 0.9643175 0.16677992, + -0.25036609 0.95398837 0.16499406, + -0.25654092 0.94659364 0.19531293, + -0.30158702 0.93376911 0.19266704, + -0.30999506 0.92282325 0.22869305, + -0.35537291 0.90727979 0.22484094, + -0.36432204 0.89442509 0.25937104, + -0.4096902 0.8761304 0.25406611, + -0.41903585 0.86132473 0.28727791, + -0.46340087 0.84062481 0.28037393, + -0.47274405 0.82428211 0.31156403, + -0.51576298 0.80139399 0.30291301, + -0.52488005 0.7837531 0.33201203, + -0.56656468 0.75874567 0.32141784, + -0.57522202 0.740183 0.34820801, + -0.615327 0.71328503 0.33555499, + -0.62336421 0.69414026 0.35998112, + -0.66091108 0.66620606 0.34549403, + -0.66812098 0.64707601 0.36729699, + -0.70320183 0.61832291 0.3509759, + -0.70956105 0.59949207 0.37031403, + -0.74231964 0.57005668 0.35213181, + -0.74785644 0.55170238 0.3692362, + -0.77828914 0.52182204 0.34923902, + -0.78298271 0.5043388 0.36411589, + -0.81060171 0.47478983 0.34278187, + -0.8145628 0.45814788 0.3557919, + -0.839553 0.42908499 0.333222, + -0.84269214 0.41417405 0.34399104, + -0.86542672 0.38543385 0.32012087, + -0.86799872 0.37157688 0.32940689, + -0.88859522 0.34323609 0.30428207, + -0.89060372 0.33089989 0.31197789, + -0.90890777 0.30340895 0.28605893, + -0.91042358 0.29276985 0.29225785, + -0.92662722 0.26609206 0.26562607, + -0.92773789 0.25716296 0.27049896, + -0.94207877 0.23108993 0.24307394, + -0.94289464 0.22353692 0.24694291, + -0.95548803 0.19799399 0.21872599, + -0.95658487 0.18571198 0.22462498, + -0.96655524 0.16341305 0.19765404, + -0.96763742 0.14831191 0.20415989, + -0.97614563 0.12760696 0.17565894, + -0.97679549 0.11570105 0.18023309, + -0.98394275 0.096420579 0.15019897, + -0.98430037 0.087704532 0.15316907, + -0.99018312 0.069455408 0.12129901, + -0.99035686 0.063709289 0.12302198, + -0.99487448 0.046500523 0.089791842, + -0.99497086 0.041834395 0.091010496, + -0.99809915 0.025739804 0.055996809, + -0.9980855 0.026730113 0.055776127, + -0.99976325 0.0094045922 0.019624006, + -0.99975687 0.010300899 0.019495599, + -0.99971837 -0.011087203 -0.020983808, + -0.99971366 -0.011556596 -0.020955093, + -0.99725986 -0.035725497 -0.064779595, + -0.99730951 -0.034187384 -0.064844869, + -0.99218702 -0.0581843 -0.110361, + -0.99288315 -0.043724302 -0.11077601, + -0.98569751 -0.061872669 -0.15675493, + -0.98662078 -0.043168887 -0.15721296, + -0.98525155 -0.025115589 -0.16925892, + -0.98730111 -0.011780002 -0.15842302, + -0.98660547 -0.040571719 -0.15799907, + -0.99331462 -0.028711289 -0.11181096, + -0.99290478 -0.04116869 -0.11155797, + -0.99750179 -0.024457095 -0.066273086, + -0.99729788 -0.032093495 -0.06608209, + -0.99971652 -0.010400395 -0.021414891, + -0.99971414 -0.010652301 -0.021404702, + -0.99972433 0.010462103 0.021022407, + -0.99972838 0.010001103 0.021050608, + -0.99782234 0.028305009 0.059577323, + -0.9978689 0.025782296 0.059941292, + -0.99471599 0.040565599 0.0943112, + -0.99474454 0.039038882 0.094652958, + -0.99010855 0.053495675 0.12970494, + -0.98995239 0.060204264 0.12794392, + -0.98395324 0.075968511 0.16144605, + -0.98368913 0.084157206 0.15897602, + -0.97644126 0.10095602 0.19071004, + -0.97595626 0.11226903 0.18682905, + -0.96739602 0.13045201 0.217088, + -0.96656066 0.14517896 0.21138492, + -0.95658785 0.16499698 0.24024098, + -0.9552505 0.1829659 0.23242189, + -0.94374686 0.20453598 0.25982097, + -0.94242066 0.21889192 0.2528429, + -0.92817461 0.24357791 0.2813569, + -0.92716509 0.25265202 0.27664402, + -0.91109622 0.27796805 0.30436406, + -0.90975541 0.28848115 0.29853615, + -0.89158624 0.31468308 0.32565108, + -0.88982344 0.32678416 0.31847516, + -0.86937088 0.35389397 0.34489596, + -0.86709273 0.36762589 0.33615687, + -0.84460217 0.39511409 0.36129209, + -0.84168983 0.41055992 0.35071191, + -0.81692368 0.43852887 0.37460387, + -0.81344861 0.45482379 0.36254182, + -0.78603011 0.48340607 0.38532507, + -0.78173584 0.50128287 0.37095091, + -0.75160718 0.53022212 0.39236608, + -0.74652499 0.54903501 0.37584701, + -0.71398991 0.57774997 0.39550394, + -0.70812404 0.59715503 0.37678406, + -0.67325592 0.62533593 0.39456493, + -0.66660219 0.64508516 0.3735061, + -0.62916708 0.67265403 0.38946807, + -0.62175798 0.69246298 0.36594, + -0.58174992 0.71912694 0.38003093, + -0.573587 0.73883897 0.35371599, + -0.53172493 0.7638889 0.36570796, + -0.52315998 0.78265703 0.337271, + -0.47990417 0.8056953 0.34719911, + -0.47101077 0.82343757 0.31638485, + -0.42620701 0.84443903 0.32445401, + -0.41730493 0.86069191 0.29166096, + -0.3714121 0.87935126 0.29798406, + -0.36268404 0.89398414 0.26315904, + -0.31664899 0.90993798 0.26785499, + -0.30850798 0.9225269 0.23187697, + -0.26257005 0.93580526 0.23521405, + -0.25518292 0.94640565 0.19798492, + -0.20966797 0.95705485 0.20021297, + -0.20442307 0.96422136 0.16878507, + -0.15920793 0.97245854 0.17022693, + -0.15586691 0.97709543 0.14487891, + -0.11225501 0.9829331 0.14574401, + -0.10922702 0.98752511 0.11341801, + -0.06608662 0.99129736 0.11385104, + -0.064139716 0.99479222 0.079212524, + -0.021542188 0.99661338 0.079357453, + -0.020883892 0.99881762 0.043900285, + 0.0211966 0.99881101 0.043900099, + 0.021867506 0.99660623 0.079358622, + 0.064503774 0.99476862 0.079212271, + 0.066449374 0.99127263 0.11385496, + 0.10955297 0.98748875 0.11341997, + 0.11257097 0.98292774 0.14553598, + 0.15609807 0.97708946 0.14467107, + 0.15941101 0.97250915 0.16974701, + 0.20453303 0.96428114 0.16831002, + 0.20984395 0.95704776 0.20006296, + 0.25538093 0.94638377 0.19783396, + 0.26285398 0.93566591 0.23545097, + 0.30871388 0.92239863 0.23211291, + 0.31691602 0.90968615 0.26839402, + 0.36304504 0.89368612 0.26367304, + 0.37177783 0.8790006 0.29856184, + 0.4177618 0.86028558 0.29220486, + 0.42667592 0.84396982 0.32505792, + 0.47143295 0.82297087 0.31696996, + 0.48029682 0.80522871 0.34773788, + 0.52366012 0.78211319 0.3377561, + 0.53222471 0.76329255 0.36622578, + 0.57399893 0.73827595 0.35422298, + 0.58205801 0.71875697 0.38025901, + 0.62212205 0.69203907 0.36612302, + 0.62948406 0.67232609 0.38952205, + 0.66691202 0.64474398 0.37354201, + 0.67352092 0.62510991 0.39447093, + 0.7083382 0.59695214 0.37670308, + 0.71421999 0.57748199 0.39548001, + 0.74673384 0.5487709 0.37581792, + 0.75176209 0.53014904 0.39216805, + 0.78186184 0.50122088 0.3707689, + 0.78614187 0.48341393 0.38508695, + 0.8134765 0.45490474 0.36237779, + 0.81698179 0.43846589 0.37455091, + 0.84178799 0.41044301 0.350613, + 0.84463698 0.39534599 0.360957, + 0.86711329 0.36785311 0.33585513, + 0.86942184 0.35396591 0.3446939, + 0.88985676 0.3268629 0.3183009, + 0.8916229 0.31475198 0.32548398, + 0.90974772 0.28860191 0.29844287, + 0.91109061 0.27808288 0.30427584, + 0.92715925 0.25275907 0.27656606, + 0.92815566 0.24381492 0.28121391, + 0.94242364 0.21907192 0.25267592, + 0.94374824 0.20478605 0.25961906, + 0.95525026 0.18319304 0.23224406, + 0.95658773 0.16530995 0.24002594, + 0.96655548 0.14546508 0.2112121, + 0.96738887 0.13088898 0.21685697, + 0.97593534 0.11268104 0.18669006, + 0.97643709 0.10105102 0.19068103, + 0.98368722 0.084233724 0.15894705, + 0.98394465 0.076311067 0.16133694, + 0.98994547 0.060480531 0.12786806, + 0.99009275 0.054297891 0.12949197, + 0.99473065 0.039644986 0.094546862, + 0.99471349 0.040549617 0.094344348, + 0.99786925 0.025764206 0.059943914, + 0.99782389 0.028226396 0.059588693, + 0.99972862 0.0099722063 0.021052293, + 0.99972564 0.010308396 0.021031793, + 0.99971563 -0.010494497 -0.021411393, + 0.99972165 -0.0098554567 -0.021437293, + 0.99734825 -0.030399807 -0.066124812, + 0.99757123 -0.021187905 -0.066353612, + 0.99303514 -0.035838805 -0.11223602, + 0.99346536 -0.019465007 -0.11246204, + 0.98696536 -0.027446309 -0.15857506, + 0.9872185 0.013064793 -0.15883593, + 0.98475635 -0.0022355006 -0.17392506, + 0.98474878 -0.0022237096 -0.17396796, + 0.98438752 -0.027177487 -0.17390391, + 0.98439503 -0.027176101 -0.173862, + 0.97434735 0.03567991 -0.22220308, + 0.97496688 0.0016680597 -0.22234397, + 0.97503775 0.0016680496 -0.22203293, + 0.97460186 -0.029942296 -0.22193398, + 0.97459686 -0.029943096 -0.22195597, + 0.97503275 0.0016615296 -0.22205494, + 0.96691543 -0.01544659 -0.25462884, + 0.96300113 -0.0041911504 -0.26946503, + 0.96291673 -0.0040769191 -0.26976794, + 0.96238387 -0.033510298 -0.26961896, + 0.9624691 -0.033498403 -0.26931602, + 0.94783109 0.040903904 -0.31613803, + 0.94862211 0.0025675101 -0.31640103, + 0.94855434 0.002567501 -0.31660411, + 0.94790411 -0.037111003 -0.31638703, + 0.94791609 -0.037109505 -0.31635103, + 0.94856638 0.0025759109 -0.31656811, + 0.93560863 -0.014747594 -0.35273087, + 0.98796374 -0.015808497 -0.15387598, + 0.99209648 0.00049358222 -0.12547706, + 0.99182826 -0.023255605 -0.12544303, + 0.99182266 -0.023256892 -0.12548696, + 0.99209088 0.00047609294 -0.12552099, + 0.99209636 0.00047609617 -0.12547804, + 0.99705648 -0.00053005322 -0.076669641, + 0.99688178 -0.018720197 -0.076656185, + 0.99688148 -0.01872031 -0.076661035, + 0.99705613 -0.00052931008 -0.076674409, + 0.99854773 -0.015906896 -0.05147329, + 0.17918591 -0.012979894 0.98372954, + 0.3135969 -0.0031957694 0.94955075, + 0.31420103 -0.0031965806 0.94935113, + 0.30016693 0.0094554182 0.95383978, + 0.30127993 0.010956497 0.95347273, + 0.30127785 0.010408295 0.95347953, + 0.35347301 0.0102108 0.93538898, + 0.3535499 0.015161396 0.93529278, + 0.41177005 0.014770302 0.9111681, + 0.41195315 0.018692708 0.91101331, + 0.47085181 0.018097894 0.88202667, + 0.47125405 0.022983203 0.88169813, + 0.52032208 0.022252902 0.85368013, + 0.52252173 0.047054678 0.85132658, + 0.57050407 0.045325603 0.82004315, + 0.57392102 0.086626701 0.81431597, + 0.62018293 0.082982093 0.78005588, + 0.62294686 0.12303697 0.77252781, + 0.66687179 0.11720295 0.73589778, + 0.6689077 0.15591292 0.72681063, + 0.70972633 0.14776008 0.68880737, + 0.71100491 0.18528998 0.67833596, + 0.74951708 0.17443301 0.63859004, + 0.75001121 0.21007004 0.62717921, + 0.78285486 0.19761397 0.58998895, + 0.78256762 0.17089193 0.59865171, + 0.74684858 0.1825379 0.63945067, + 0.74582517 0.14630704 0.64987618, + 0.70709836 0.15530607 0.68984938, + 0.70531917 0.11820603 0.69896519, + 0.66412097 0.124665 0.737158, + 0.66154701 0.0855662 0.74500602, + 0.61758411 0.089742519 0.7813682, + 0.61431199 0.049660798 0.78749901, + 0.56785607 0.051804706 0.82149613, + 0.56562191 0.026897397 0.8242259, + 0.51754725 0.027908213 0.8551994, + 0.51706892 0.022274999 0.85565388, + 0.45897311 0.023121005 0.88814926, + 0.45875579 0.018651191 0.88836658, + 0.40028614 0.019235307 0.9161883, + 0.40019992 0.013808397 0.91632378, + 0.34803089 0.014125695 0.93737662, + 0.34802008 0.010772103 0.93742526, + 0.36024004 -0.0032117004 0.93285412, + 0.36056709 -0.0033893208 0.93272722, + 0.36056811 -0.0021624607 0.93273038, + 0.36024091 -0.0021617794 0.93285674, + 0.39207277 0.012701993 0.91984648, + 0.39207184 0.013488995 0.91983563, + 0.34589982 0.013757894 0.93817055, + 0.34590092 0.011486597 0.93820077, + 0.31493613 -0.0029298612 0.94910836, + 0.31493708 0.0021205305 0.94911021, + 0.31359816 0.0021204809 0.94955349, + 0.31420189 0.0021752494 0.94935364, + 0.26719192 -0.021127593 0.96341163, + 0.26725093 0.0020853092 0.96362466, + 0.26742604 0.0020850303 0.96357614, + 0.267423 -0.00542454 0.96356398, + 0.27953911 -0.012537706 0.96005249, + 0.3766461 -0.015636804 0.92622524, + 0.4057669 0.0012179198 0.91397578, + 0.40576708 -0.00070553017 0.91397625, + 0.4050681 -0.00070349319 0.91428626, + 0.40506795 0.0011177598 0.9142859, + 0.40627179 0.0011178195 0.9137516, + 0.40627205 -0.00032300802 0.91375214, + 0.43776879 0.013996794 0.89897859, + 0.43776199 0.016906399 0.89893198, + 0.39469206 0.017277202 0.9186511, + 0.3946929 0.017948397 0.91863775, + 0.44687012 0.017475404 0.89442825, + 0.446962 0.023506699 0.89424402, + 0.50482911 0.022683406 0.86292118, + 0.50507808 0.027698604 0.86262912, + 0.56251395 0.026534095 0.82636189, + 0.56303716 0.032602411 0.82578832, + 0.6094293 0.031277314 0.79222333, + 0.61168921 0.056650318 0.78906727, + 0.65573704 0.054064609 0.7530511, + 0.65882379 0.093280174 0.74649179, + 0.70029795 0.088512994 0.70834196, + 0.70260406 0.12622002 0.70029706, + 0.74160981 0.11899197 0.6601938, + 0.74311006 0.15479101 0.65102005, + 0.7792027 0.14498396 0.60977274, + 0.7799471 0.17954901 0.59953707, + 0.8129074 0.16708307 0.55791122, + 0.8130067 0.19202992 0.54967684, + 0.78556818 0.20407504 0.58415413, + 0.78543347 0.22310014 0.57733935, + 0.7556628 0.23608194 0.61093289, + 0.75531912 0.25736403 0.60270804, + 0.7234292 0.27112505 0.63493419, + 0.72282863 0.29391584 0.62540573, + 0.68858594 0.30843198 0.65629196, + 0.68766952 0.33299977 0.64515251, + 0.6507318 0.34826592 0.67472881, + 0.64943123 0.37480211 0.66163623, + 0.61001903 0.390558 0.68945003, + 0.60829711 0.41858608 0.6743592, + 0.56613809 0.43472406 0.70035905, + 0.56398231 0.46404621 0.6830703, + 0.5198921 0.48003113 0.70659918, + 0.51732737 0.51014334 0.68711448, + 0.47064307 0.52596205 0.70842004, + 0.46771294 0.55665392 0.68657196, + 0.41855708 0.57196414 0.70545518, + 0.41525495 0.60371196 0.68051094, + 0.36456102 0.61796308 0.69657505, + 0.36111996 0.64924592 0.66938192, + 0.30910698 0.66213095 0.68266791, + 0.30568016 0.69268835 0.65325528, + 0.25222299 0.70398992 0.66391397, + 0.24895599 0.73397601 0.63190198, + 0.19474591 0.74332666 0.63995272, + 0.19181697 0.77256989 0.60526192, + 0.13773301 0.77968514 0.61083609, + 0.135415 0.807253 0.57446098, + 0.08172287 0.8120327 0.57786185, + 0.080199502 0.837865 0.53995401, + 0.026932299 0.84026802 0.541502, + 0.026390703 0.86443114 0.50205809, + -0.025782997 0.86444485 0.50206596, + -0.026321905 0.84026217 0.5415411, + -0.079574689 0.83788788 0.54001093, + -0.081097499 0.81205398 0.57792002, + -0.13484003 0.80729717 0.57453412, + -0.13716002 0.77970713 0.61093706, + -0.19128397 0.77261186 0.60537696, + -0.19419597 0.74354094 0.63987094, + -0.24845603 0.73420304 0.63183504, + -0.25174996 0.70399892 0.66408396, + -0.30504307 0.69275719 0.65348017, + -0.30848601 0.66194499 0.68312901, + -0.36054319 0.64908028 0.66985327, + -0.36395413 0.61796224 0.69689322, + -0.41492501 0.60365701 0.68076098, + -0.41820306 0.57214808 0.70551604, + -0.46720412 0.55690211 0.68671715, + -0.47015375 0.52593279 0.70876664, + -0.51707995 0.51005393 0.68736696, + -0.51964009 0.47994205 0.70684505, + -0.56377393 0.46395695 0.68330294, + -0.56592387 0.43465191 0.70057684, + -0.60794097 0.418585 0.67468101, + -0.60965908 0.39050707 0.68979704, + -0.6492672 0.3746911 0.66186017, + -0.65056229 0.34816119 0.67494631, + -0.68752521 0.33289912 0.64535826, + -0.68843818 0.30827406 0.6565212, + -0.72270292 0.29376498 0.62562191, + -0.72329921 0.27091706 0.63517118, + -0.75521618 0.25716206 0.6029231, + -0.75555563 0.23553687 0.61127567, + -0.78534329 0.22258407 0.57766116, + -0.78546721 0.20365304 0.58443713, + -0.81292641 0.1916301 0.54993522, + -0.81281441 0.16667308 0.55816925, + -0.77983981 0.17910695 0.59980887, + -0.77907813 0.14453702 0.61003804, + -0.74296063 0.15431492 0.65130371, + -0.74141133 0.11790706 0.66061127, + -0.70253092 0.12504098 0.70058197, + -0.70015538 0.086763047 0.70869935, + -0.65868223 0.091433033 0.74684525, + -0.40405706 0.013024002 0.91464114, + -0.40409106 -0.0017500302 0.91471714, + -0.40478599 -0.0021202399 0.91440898, + -0.40475193 0.013019098 0.91433388, + -0.44633895 0.017028999 0.8947019, + -0.44644386 0.02392789 0.89449167, + -0.50485593 0.023082698 0.86289489, + -0.50508374 0.027704086 0.8626256, + -0.56229711 0.026544206 0.82650918, + -0.56277984 0.032141488 0.82598168, + -0.60938609 0.030829804 0.79227412, + -0.61159778 0.05555908 0.78921568, + -0.65563017 0.053025011 0.75321817, + -0.65642977 0.050682981 0.75268269, + -0.69401395 0.048370093 0.71833491, + -0.69763321 0.094586223 0.71018416, + -0.73680717 0.089259021 0.67018521, + -0.73887962 0.12611394 0.66193068, + -0.77540737 0.11818306 0.62030327, + -0.77665013 0.15284501 0.61110806, + -0.80988067 0.14232896 0.56906581, + -0.81037301 0.175474 0.559021, + -0.83799112 0.16342601 0.52063704, + -0.83773881 0.14019898 0.52776688, + -0.80743349 0.15146708 0.57018334, + -0.80649817 0.11823803 0.57929313, + -0.77295184 0.12688297 0.62164789, + -0.77121091 0.091495693 0.62996995, + -0.7343598 0.097558379 0.67171282, + -0.73109782 0.052693591 0.68023485, + -0.6884672 0.056014214 0.7231012, + -0.68727893 0.040569097 0.72525996, + -0.63507378 0.043141384 0.77124572, + -0.63480681 0.037140194 0.77177781, + -0.57934582 0.039178785 0.81413972, + -0.57935596 0.040938295 0.81404591, + -0.61347973 0.039664283 0.78871369, + -0.61355895 0.032450695 0.78898185, + -0.65080583 0.031201292 0.7586028, + -0.65097481 0.011261197 0.7590158, + -0.65289307 0.012183502 0.75735211, + -0.65294003 0.0023042501 0.75740612, + -0.65217501 0.00230434 0.75806499, + -0.6521458 0.0095999381 0.7580328, + -0.65153104 0.009607181 0.75856113, + -0.65155917 0.0026777808 0.7585932, + -0.67918408 -0.015077402 0.73381305, + -0.53623605 -0.00031159603 -0.84406811, + -0.46391287 -0.48949188 -0.73836482, + -0.40694594 -0.0028441697 -0.91344786, + -0.40750808 -0.0031441906 -0.91319627, + -0.40339383 -0.14177392 -0.90397656, + -0.40283495 -0.14180498 -0.90422088, + -0.43583593 -0.076748393 -0.89674789, + -0.41806599 -0.295809 -0.85890502, + -0.46337295 -0.28856197 -0.83786488, + -0.419808 -0.50150001 -0.75647801, + -0.41894516 -0.51289916 -0.74927926, + -0.37519193 -0.52359492 -0.76490486, + -0.4184109 -0.30343893 -0.85607082, + -0.37258491 -0.31003395 -0.87467682, + -0.39012793 -0.07996279 -0.91728187, + -0.3581281 -0.14551003 -0.92226422, + -0.36197996 0.0019507898 -0.93218386, + -0.3619121 0.0019507805 -0.93221027, + -0.35805589 -0.14558895 -0.92227966, + -0.35791808 -0.14559503 -0.92233223, + -0.36177188 0.0019340293 -0.93226463, + -0.31543887 -0.021920092 -0.94869262, + -0.22968797 -0.012513998 -0.97318387, + -0.32857892 -0.012195298 -0.94439775, + -0.31619409 -0.0052277213 -0.94868022, + -0.312601 -0.150426 -0.93789798, + -0.31192306 -0.15045403 -0.93811923, + -0.34393004 -0.084004305 -0.93523014, + -0.32706597 -0.32340196 -0.88794088, + -0.37301883 -0.31752285 -0.8718006, + -0.33136711 -0.5429672 -0.77161032, + -0.37463796 -0.53356892 -0.75825489, + -0.205604 0.97854799 -0.0130726, + -0.2051471 0.9776935 -0.045057721, + -0.60423708 -0.69466108 -0.39031205, + -0.70374733 -0.53881824 -0.4630492, + -0.68735319 -0.065530315 -0.72336119, + -0.67613316 -0.19384505 -0.71082217, + -0.71475118 -0.18400505 -0.67473918, + -0.68626404 -0.33398303 -0.64614004, + -0.72521484 -0.3161529 -0.61164588, + -0.68131399 -0.45679501 -0.57196999, + -0.72193605 -0.43181306 -0.54069006, + -0.65957719 -0.57005513 -0.48989311, + -0.53219789 -0.75634181 -0.38041091, + -0.64787269 -0.59693271 -0.47321478, + -0.60237372 -0.62550873 -0.49586776, + -0.67679894 -0.47496793 -0.56244892, + -0.63445926 -0.49870318 -0.59055626, + -0.68488067 -0.34709981 -0.64067173, + -0.64388704 -0.36447003 -0.67273408, + -0.67623919 -0.20180504 -0.70850217, + -0.64886898 -0.068637997 -0.75779802, + -0.63610673 -0.2113699 -0.74208564, + -0.56745297 -0.070665896 -0.82036787, + -0.55178696 -0.24653196 -0.79671389, + -0.49493381 -0.0013147396 -0.86892968, + -0.49456689 -0.0011190098 -0.86913884, + -0.49048099 -0.12828401 -0.86195803, + -0.49084589 -0.12825997 -0.86175382, + -0.5245508 -0.071022078 -0.84841168, + -0.50773001 -0.263937 -0.82009, + -0.55196905 -0.25546503 -0.79376811, + -0.51086205 -0.45024106 -0.73232704, + -0.47333989 -0.64449179 -0.60048288, + -0.55459589 -0.4358159 -0.70886379, + -0.52112788 -0.61114991 -0.59575289, + -0.59883606 -0.40742806 -0.68949103, + -0.55600208 -0.42284706 -0.71558505, + -0.59484589 -0.23762093 -0.76791584, + -0.60911179 -0.066698074 -0.79027468, + -0.59470373 -0.22895792 -0.77065271, + -0.63622379 -0.21971893 -0.73955584, + -0.60027307 -0.39448807 -0.69573808, + -0.64239895 -0.37800193 -0.66666192, + -0.58587366 -0.53945172 -0.60476762, + -0.62956131 -0.51718426 -0.5798043, + -0.51986802 -0.71192098 -0.47212899, + -0.11296701 0.99350214 -0.013854002, + -0.11271297 0.99258077 -0.04559879, + -0.093479648 -0.99383938 -0.059537962, + 0.0052721999 -0.99838603 0.056547198, + -0.026483109 -0.99917436 0.030811911, + -0.033422887 -0.99917865 0.022910792, + -0.74227834 -0.65851933 -0.12399706, + -0.65414274 -0.74330878 -0.13996196, + -0.61125714 -0.78454316 -0.10419602, + -0.52939308 -0.84099209 -0.11169302, + -0.51004595 -0.85476488 -0.096073583, + -0.42683208 -0.89867222 -0.10100902, + -0.39764082 -0.91430557 -0.076987766, + -0.31759012 -0.94488436 -0.079562627, + -0.26681793 -0.96307778 -0.035907492, + -0.19746293 -0.97962964 -0.036524683, + -0.16407301 -0.98643202 -0.0056580398, + -0.10670099 -0.99427485 -0.0057030297, + -0.078654893 -0.99663991 0.022852598, + -0.08274883 -0.99627936 -0.02408411, + -0.089469321 -0.99550623 -0.031026907, + -0.14539997 -0.98889273 -0.030820692, + -0.18140395 -0.98130077 -0.064354487, + -0.24997309 -0.96617734 -0.063362725, + -0.29034385 -0.95189351 -0.097975552, + -0.36939618 -0.92438841 -0.095144644, + -0.42535293 -0.8940239 -0.14069898, + -0.51002085 -0.84970385 -0.13372397, + -0.53873187 -0.8277688 -0.15673795, + -0.62082803 -0.7702601 -0.14584902, + -0.63632971 -0.75497162 -0.15843692, + -0.71104217 -0.68815917 -0.14441603, + -0.73373401 -0.659338 -0.16403601, + -0.8160761 -0.56084806 -0.13953301, + -0.82079399 -0.55261803 -0.144605, + -0.86788172 -0.48058981 -0.12575695, + -0.87161958 -0.47249877 -0.13047694, + -0.90860075 -0.4025979 -0.11117397, + -0.90853876 -0.4027639 -0.11107897, + -0.9372341 -0.33615103 -0.092707507, + -0.93560565 -0.34147888 -0.089634269, + -0.95781255 -0.27797687 -0.072965562, + -0.95569354 -0.28640884 -0.067968369, + -0.97283155 -0.22525789 -0.053456374, + -0.97090238 -0.23468609 -0.047656819, + -0.98388785 -0.17521098 -0.035579395, + -0.98242211 -0.18428801 -0.029744403, + -0.99174863 -0.12655996 -0.020426992, + -0.99084878 -0.13410197 -0.015338496, + -0.99695379 -0.077489987 -0.0088632582, + -0.99656552 -0.082644165 -0.0052069575, + -0.99965113 -0.026363004 -0.0016609902, + -0.99960214 -0.028204104 -0.00028496402, + -0.99962711 0.027304003 0.00027587102, + -0.99956924 0.029319407 -0.0013141504, + -0.99627924 0.086097926 -0.0038590708, + -0.99578065 0.091391571 -0.008280267, + -0.98889989 0.14797698 -0.013406998, + -0.98853314 0.15021701 -0.015398702, + -0.97862411 0.20458503 -0.020971902, + -0.97792143 0.20760688 -0.023852285, + -0.96515524 0.25996807 -0.029868107, + -0.96378011 0.26445904 -0.034487903, + -0.94847423 0.31419408 -0.040973712, + -0.9463641 0.31965303 -0.047083806, + -0.92860639 0.36710519 -0.054073326, + -0.92565358 0.37330881 -0.061693769, + -0.90553731 0.41858914 -0.069176823, + -0.90160877 0.4253819 -0.078433581, + -0.87924999 0.46846399 -0.086377203, + -0.87423569 0.47563881 -0.097363859, + -0.85005814 0.51598907 -0.10562401, + -0.84379715 0.52339906 -0.11857402, + -0.81796986 0.56104392 -0.12710199, + -0.81102747 0.56780034 -0.14084509, + -0.78345329 0.60317123 -0.14961806, + -0.77654231 0.60864222 -0.16290106, + -0.74707693 0.64213592 -0.17186499, + -0.73844504 0.64754605 -0.18810403, + -0.70782197 0.67834991 -0.19705197, + -0.69797838 0.68298829 -0.2152981, + -0.66607994 0.71137291 -0.22424597, + -0.65520728 0.71488738 -0.24421212, + -0.62211895 0.74088591 -0.25309297, + -0.61034012 0.74298817 -0.27468807, + -0.57594013 0.7667672 -0.28348005, + -0.56334418 0.76720232 -0.30666611, + -0.52872485 0.78816068 -0.31504387, + -0.51562423 0.78670233 -0.33945715, + -0.48081869 0.80507052 -0.34738278, + -0.48255989 0.80548382 -0.3439939, + -0.45109114 0.82076329 -0.35052013, + -0.46537417 0.8256433 -0.31896713, + -0.43180406 0.84136415 -0.32504103, + -0.44375494 0.84655786 -0.29397497, + -0.40861008 0.86220217 -0.29940805, + -0.41848707 0.86754513 -0.26876402, + -0.38165992 0.88290477 -0.27352294, + -0.38973007 0.88826615 -0.24309203, + -0.35111883 0.90312159 -0.24715789, + -0.35757697 0.90836787 -0.21680997, + -0.31700012 0.92251235 -0.22018607, + -0.32200083 0.92748046 -0.18998788, + -0.28011701 0.94043797 -0.192642, + -0.28384596 0.94499791 -0.16251299, + -0.24090497 0.95650786 -0.16449198, + -0.2435571 0.96054536 -0.13428605, + -0.19952404 0.97045523 -0.13567203, + -0.20127796 0.97386074 -0.10527298, + -0.15629494 0.98198962 -0.10615196, + -0.15732396 0.98464578 -0.075642385, + -0.112088 0.99077898 -0.076113597, + -0.11257798 0.99259788 -0.045558296, + -0.067488991 0.99761587 -0.014417898, + -0.067337006 0.99668109 -0.045745805, + -0.022630708 0.99963033 -0.015067806, + -0.022580698 0.99869388 -0.045833997, + -0.067323014 0.99668223 -0.04574161, + -0.067027397 0.99482799 -0.076319098, + -0.11174495 0.99082553 -0.07601206, + -0.11100799 0.98808688 -0.10658999, + -0.15559906 0.98212236 -0.10594704, + -0.15422697 0.97856677 -0.13645896, + -0.19847102 0.97071409 -0.13536401, + -0.19628005 0.96644622 -0.16569805, + -0.23943909 0.95694834 -0.16407005, + -0.23624405 0.95206726 -0.19431104, + -0.27812913 0.9411425 -0.19208109, + -0.27374098 0.93574786 -0.22235496, + -0.31437203 0.92358309 -0.21946403, + -0.30858493 0.91779375 -0.24985994, + -0.34780696 0.90464187 -0.24627897, + -0.34046304 0.89862114 -0.27670404, + -0.37762195 0.88495588 -0.27249697, + -0.36852491 0.87883276 -0.30305493, + -0.40377977 0.86487746 -0.29824281, + -0.39266983 0.85876161 -0.32914886, + -0.42617905 0.84471714 -0.32376602, + -0.4128148 0.83875757 -0.35506281, + -0.44467294 0.8248319 -0.34916797, + -0.44325113 0.82436216 -0.3520731, + -0.47818282 0.80768269 -0.34494889, + -0.49126771 0.8102625 -0.31957883, + -0.52584493 0.79125887 -0.31208396, + -0.53867286 0.79186082 -0.28772894, + -0.57286584 0.77036971 -0.27991992, + -0.58510488 0.76915181 -0.25701693, + -0.618963 0.74493098 -0.248923, + -0.63037729 0.74214238 -0.22770411, + -0.6630308 0.71566385 -0.21957994, + -0.67361379 0.71153474 -0.19990693, + -0.70492804 0.68284106 -0.19184503, + -0.71437001 0.67774498 -0.17417599, + -0.74444318 0.64667219 -0.16619104, + -0.75228983 0.64121383 -0.15134297, + -0.78107721 0.60773611 -0.14344104, + -0.788867 0.60100001 -0.128405, + -0.8159759 0.56532693 -0.12078398, + -0.82311887 0.55778491 -0.10654298, + -0.84845287 0.51987195 -0.099301584, + -0.8543418 0.51237088 -0.087040976, + -0.87800491 0.47189093 -0.080164395, + -0.88278031 0.46459419 -0.069650121, + -0.90461314 0.42152306 -0.063193105, + -0.90833509 0.41469106 -0.054395106, + -0.92795777 0.36951992 -0.04846999, + -0.93077278 0.36326993 -0.041193988, + -0.94804615 0.31610703 -0.035845906, + -0.95000887 0.31076196 -0.030166896, + -0.96489912 0.26139203 -0.025374305, + -0.96603674 0.25750294 -0.021570394, + -0.97849387 0.20555598 -0.017218998, + -0.97922337 0.20228307 -0.014252105, + -0.98886174 0.14846897 -0.010460497, + -0.99015826 0.13991503 -0.0032230108, + -0.99626637 0.086310633 -0.0019882107, + -0.99676001 0.080387697 0.0027139799, + -0.9996255 0.027350686 0.00092339056, + -0.99967134 0.02553561 0.002279371, + -0.99964952 -0.026369587 -0.0023538189, + -0.99968934 -0.02467091 -0.0035514212, + -0.99694252 -0.077341564 -0.011133495, + -0.99724954 -0.072744764 -0.014195793, + -0.99173439 -0.12593192 -0.024575084, + -0.99245423 -0.11917803 -0.028831907, + -0.98390633 -0.17367506 -0.042015813, + -0.98505265 -0.16579494 -0.046724986, + -0.97297174 -0.22226594 -0.062639982, + -0.9744525 -0.21431589 -0.067163371, + -0.95826012 -0.27281502 -0.08549621, + -0.95971966 -0.26651192 -0.088936068, + -0.93836588 -0.32786998 -0.10941099, + -0.93913347 -0.32518315 -0.11083505, + -0.91111302 -0.39011899 -0.132967, + -0.90974778 -0.39396992 -0.13094497, + -0.87297541 -0.4628672 -0.15384407, + -0.87172711 -0.46571505 -0.15232001, + -0.80748731 -0.56065917 -0.18337306, + -0.79378611 -0.58377504 -0.17061801, + -0.73034078 -0.65565377 -0.19162592, + -0.71981716 -0.66966718 -0.18278204, + -0.64558792 -0.73673594 -0.20108797, + -0.62034106 -0.76317209 -0.18095702, + -0.53699481 -0.82082671 -0.19462793, + -0.48104113 -0.86361319 -0.15090303, + -0.39589915 -0.90458828 -0.15806305, + -0.35054919 -0.92860442 -0.12169306, + -0.27198812 -0.95414245 -0.12503906, + -0.22852807 -0.96956635 -0.087841228, + -0.16121204 -0.98289424 -0.089048721, + -0.15637693 -0.98407555 -0.084507361, + -0.3646439 -0.86607385 -0.3419809, + -0.38980192 -0.85654181 -0.3382169, + -0.23584098 -0.95362389 -0.18703099, + -0.25859395 -0.94792676 -0.18591395, + -0.16954802 -0.9800421 -0.10378402, + -0.17820191 -0.97852254 -0.10362295, + -0.30118397 -0.92976886 -0.21170297, + -0.27673098 -0.93696588 -0.21334197, + -0.42459199 -0.83425897 -0.351758, + -0.39850795 -0.84511387 -0.35633397, + -0.52211672 -0.70533556 -0.47947469, + -0.50235802 -0.71508199 -0.486101, + -0.46283981 -0.75444973 -0.46538681, + -0.580944 -0.557266 -0.593261, + -0.55113786 -0.5712809 -0.60818189, + -0.44010687 -0.75977981 -0.47858188, + -0.46465179 -0.74924362 -0.47194576, + -0.33228701 -0.884839 -0.32656601, + -0.35623002 -0.87660211 -0.32352602, + -0.19844896 -0.96681374 -0.16090095, + -0.21903697 -0.96247888 -0.16017899, + -0.10093299 -0.99382788 -0.046029896, + -0.095925659 -0.99432254 -0.046052776, + -0.18268204 -0.97397226 -0.13418403, + -0.16403694 -0.97722363 -0.13463196, + -0.32450286 -0.89417756 -0.30845484, + -0.30187905 -0.90123123 -0.31088805, + -0.43715709 -0.76863819 -0.46700013, + -0.41317391 -0.77826685 -0.47285089, + -0.52190596 -0.60008097 -0.60623193, + -0.50193036 -0.60845643 -0.61469239, + -0.38645914 -0.79615527 -0.46560317, + -0.41022399 -0.78724498 -0.46039301, + -0.27308893 -0.91590077 -0.29419094, + -0.29436603 -0.90990615 -0.29226604, + -0.13288197 -0.98515373 -0.10869398, + -0.14954601 -0.98279113 -0.10843302, + -0.040520113 -0.99914926 0.0076700817, + -0.038453002 -0.99923098 0.0076707099, + -0.11997106 -0.98924249 -0.083704337, + -0.10515005 -0.99091548 -0.083845936, + -0.26660708 -0.92315733 -0.27695009, + -0.24655201 -0.92825699 -0.27847999, + -0.38389182 -0.80418962 -0.45376879, + -0.36125779 -0.81210452 -0.45823473, + -0.47388011 -0.6339522 -0.61118114, + -0.45433515 -0.64132524 -0.61828923, + -0.33650792 -0.8273648 -0.44969988, + -0.35879612 -0.82010329 -0.44575316, + -0.22152807 -0.93939835 -0.26164109, + -0.24028191 -0.93511063 -0.26044691, + -0.080461591 -0.9949739 -0.059605993, + -0.072515577 -0.99649566 -0.041687384, + 0.0047714077 -0.99838853 0.056547374, + -0.032668304 -0.99945712 0.0042803106, + 0.035222981 -0.9943555 0.10008196, + 0.031149704 -0.99449015 0.10009602, + 0.0086651659 -0.99737853 0.071839459, + -0.027224109 -0.99704635 0.071815521, + -0.04809818 -0.99766463 0.048496783, + -0.094591603 -0.99434203 0.048335299, + -0.12042505 -0.99246937 0.022413908, + -0.178743 -0.98364502 0.022214601, + -0.22124186 -0.97507441 -0.016787291, + -0.29243189 -0.95614463 -0.016461395, + -0.31923786 -0.94685155 -0.039486282, + -0.39764401 -0.91674298 -0.038230699, + -0.41864607 -0.90645415 -0.055465106, + -0.50086987 -0.8639068 -0.052861691, + -0.55227894 -0.82822388 -0.095043384, + -0.6323328 -0.76964581 -0.088321179, + -0.66607118 -0.7365362 -0.11774403, + -0.73629922 -0.66817224 -0.10681504, + -0.75407428 -0.64497626 -0.12400705, + -0.81225669 -0.5728088 -0.11013196, + -0.81990802 -0.56007099 -0.118623, + -0.86693072 -0.48761183 -0.10327596, + -0.86851019 -0.48434913 -0.10533802, + -0.90613157 -0.4133338 -0.089893453, + -0.90473586 -0.41684493 -0.08771199, + -0.93444866 -0.34846687 -0.073323973, + -0.93174678 -0.35664591 -0.068202183, + -0.955185 -0.290741 -0.055599201, + -0.95235246 -0.30103815 -0.048998922, + -0.97071022 -0.23713306 -0.038597308, + -0.96820676 -0.24818894 -0.031272892, + -0.98236746 -0.1854941 -0.023373112, + -0.98051476 -0.19576795 -0.016297197, + -0.99084449 -0.13454306 -0.011200406, + -0.98970211 -0.14305201 -0.0050839204, + -0.99656999 -0.0827021 -0.00293915, + -0.99609226 -0.088310324 0.0012797303, + -0.99960309 -0.028171403 0.00040824007, + -0.99954075 -0.030234193 0.0020351596, + -0.99957013 0.029253904 -0.0019691803, + -0.99951202 0.0310455 -0.00345602, + -0.9957909 0.091091789 -0.010140399, + -0.99566251 0.092355758 -0.011248494, + -0.98859334 0.14950506 -0.018209105, + -0.9882229 0.15167698 -0.020236198, + -0.97806537 0.20646907 -0.02754641, + -0.97719777 0.21003796 -0.031120993, + -0.96405125 0.26284707 -0.038945809, + -0.96257287 0.26744097 -0.043917995, + -0.94681138 0.31753612 -0.052144419, + -0.94458002 0.32300901 -0.0585979, + -0.92633241 0.37065718 -0.067241929, + -0.92323261 0.37680686 -0.075220473, + -0.90256357 0.4222258 -0.08428736, + -0.8984223 0.42895415 -0.093998939, + -0.87551975 0.47198287 -0.10342798, + -0.8701638 0.47913489 -0.11508597, + -0.8454473 0.5192892 -0.12473004, + -0.83940917 0.52591515 -0.13713303, + -0.81303602 0.56337601 -0.146901, + -0.80704284 0.5687629 -0.15871595, + -0.77885401 0.60412401 -0.168584, + -0.77116352 0.60968065 -0.1832929, + -0.74102396 0.64304692 -0.19332397, + -0.73203576 0.64806575 -0.21008192, + -0.70074338 0.67864633 -0.21999511, + -0.69059581 0.68275583 -0.23858294, + -0.65807879 0.71080077 -0.24838391, + -0.64685935 0.71370542 -0.26869616, + -0.61321968 0.73925763 -0.27831587, + -0.60099721 0.74066722 -0.30035713, + -0.56614769 0.76388365 -0.30977187, + -0.55320776 0.76352364 -0.33315584, + -0.5182339 0.78386682 -0.34203291, + -0.52034205 0.78418112 -0.33808902, + -0.48909205 0.80096209 -0.34532404, + -0.50420272 0.80467153 -0.31350183, + -0.47104895 0.82192987 -0.32022497, + -0.48376018 0.82609028 -0.2890521, + -0.44870687 0.84353173 -0.29515487, + -0.45928112 0.84800118 -0.26449007, + -0.42273614 0.86514831 -0.26983809, + -0.43144506 0.8697741 -0.23947503, + -0.39335209 0.88640422 -0.24405307, + -0.4004201 0.89104825 -0.21376805, + -0.360459 0.90703797 -0.217604, + -0.36601713 0.91151631 -0.18753508, + -0.32426211 0.92656034 -0.19063108, + -0.32849208 0.93074322 -0.16065505, + -0.28556103 0.94439512 -0.16301201, + -0.28865099 0.94815803 -0.132955, + -0.24476203 0.9601891 -0.13464202, + -0.24688298 0.96340489 -0.10440198, + -0.20208608 0.97366738 -0.10551403, + -0.20340003 0.97620809 -0.075142011, + -0.15779899 0.98455888 -0.075784795, + -0.15848504 0.98632121 -0.045311213, + -0.15901995 0.98717666 -0.013962596, + -0.15866899 0.98628902 -0.045367502, + -0.20488103 0.9777531 -0.044974804, + -0.20400396 0.97606778 -0.075326182, + -0.24947909 0.96550936 -0.074511431, + -0.24789213 0.96311247 -0.10470905, + -0.29252204 0.95065713 -0.10335401, + -0.29005805 0.94766927 -0.13337703, + -0.33390304 0.93340814 -0.13137001, + -0.33040604 0.92996812 -0.16121802, + -0.37321603 0.91411012 -0.15846902, + -0.36852282 0.91035759 -0.18825491, + -0.4095901 0.89336824 -0.18474105, + -0.4035309 0.88943577 -0.21463196, + -0.442875 0.871566 -0.21032, + -0.4352639 0.86758882 -0.24048895, + -0.47308993 0.84900087 -0.23533697, + -0.4638128 0.8451736 -0.26562989, + -0.50018883 0.8260777 -0.25962791, + -0.48901707 0.82255411 -0.29028803, + -0.52345985 0.80348283 -0.28355795, + -0.51014608 0.80041212 -0.31478804, + -0.54275376 0.78161764 -0.30739585, + -0.5269857 0.77916753 -0.3393878, + -0.55834264 0.76058954 -0.33129579, + -0.55580384 0.76042569 -0.33590889, + -0.59105992 0.73784494 -0.32593396, + -0.6036827 0.73716062 -0.30358085, + -0.63800085 0.7120198 -0.29322794, + -0.64962327 0.70973837 -0.27250913, + -0.68273628 0.68211329 -0.26190212, + -0.69326693 0.67852396 -0.24287097, + -0.72526199 0.64819998 -0.232017, + -0.73455578 0.64362776 -0.21487492, + -0.76537013 0.61046904 -0.20380403, + -0.77343267 0.60519969 -0.18850791, + -0.80235887 0.56983894 -0.17749299, + -0.80903471 0.56430781 -0.16437595, + -0.8360942 0.52669615 -0.15342003, + -0.8411079 0.52158093 -0.14314598, + -0.86637712 0.48158306 -0.13216901, + -0.8715052 0.47520512 -0.12107303, + -0.89498776 0.4322809 -0.11013697, + -0.89942431 0.42553216 -0.099791341, + -0.92063338 0.38011613 -0.089140728, + -0.92393959 0.37393683 -0.080665365, + -0.94270891 0.32611498 -0.070349291, + -0.94504875 0.3206839 -0.063597783, + -0.96129614 0.27025402 -0.053596508, + -0.96285933 0.26564109 -0.048340417, + -0.97641134 0.21243007 -0.038657214, + -0.97735077 0.20874795 -0.034780491, + -0.98782974 0.15342396 -0.025562795, + -0.98829103 0.15083399 -0.0230223, + -0.99554443 0.093213551 -0.014227492, + -0.99568188 0.09191259 -0.013029298, + -0.99949914 0.031333905 -0.0044418103, + -0.99951249 0.030950315 -0.004107812, + -0.99947888 -0.032000795 0.0042472393, + -0.99954063 -0.030183388 0.0027394891, + -0.99547738 -0.094609737 0.0085869227, + -0.99608874 -0.08828678 0.0035613191, + -0.98826379 -0.15263297 0.0061569088, + -0.98967326 -0.14333902 -0.00093654922, + -0.97805142 -0.20835888 -0.0013613792, + -0.98041499 -0.196692 -0.0099396901, + -0.96475625 -0.26281005 -0.013280903, + -0.96794367 -0.2501789 -0.022260293, + -0.94797838 -0.31708211 -0.028213209, + -0.95176023 -0.30462506 -0.036824808, + -0.92673385 -0.37300298 -0.045090795, + -0.93052334 -0.36249113 -0.052217718, + -0.89936256 -0.43273678 -0.062336769, + -0.9023447 -0.42577085 -0.06703148, + -0.8636421 -0.49797207 -0.078398407, + -0.86408716 -0.49710512 -0.078992523, + -0.81661117 -0.57003611 -0.090581723, + -0.8121227 -0.57719785 -0.085436366, + -0.75428832 -0.64946723 -0.096133634, + -0.74132478 -0.66598177 -0.083101772, + -0.67240894 -0.73448396 -0.091649592, + -0.64692426 -0.7594673 -0.068546422, + -0.56858695 -0.8192929 -0.073945992, + -0.52675408 -0.84914613 -0.038484003, + -0.44489914 -0.89466232 -0.040546916, + -0.38993192 -0.92083079 0.0048729992, + -0.31298104 -0.94974613 0.0050260206, + -0.29286194 -0.95589876 0.022125594, + -0.22329003 -0.97449112 0.022555903, + -0.20078008 -0.97869134 0.043018915, + -0.14039604 -0.98914033 0.043478213, + -0.10708106 -0.99130648 0.076453939, + -0.059589323 -0.99526733 0.076759428, + -0.040859882 -0.99441755 0.097283855, + -0.0037667386 -0.99524164 0.09736456, + 0.010940903 -0.99325222 0.11545703, + 0.038855683 -0.99256152 0.11537695, + 0.055702467 -0.98874038 0.13888691, + -0.0034854112 -0.99897933 0.045035817, + 0.056098767 -0.98871839 0.1388839, + 0.017167805 -0.99657035 0.08095023, + 0.068788432 -0.98267049 0.17212509, + 0.071161538 -0.98250645 0.17209609, + 0.059421193 -0.98630989 0.15382399, + 0.037985992 -0.98734277 0.15398496, + 0.028390907 -0.98961425 0.14091703, + -0.00063231809 -0.99001312 0.14097401, + -0.013476198 -0.99199873 0.12552696, + -0.051322918 -0.99078137 0.12537305, + -0.076125339 -0.99220049 0.098707743, + -0.125543 -0.98721498 0.098211698, + -0.14291899 -0.98638988 0.081297494, + -0.201873 -0.97610199 0.080449603, + -0.21909603 -0.97353214 0.065055504, + -0.28716004 -0.95575112 0.063867308, + -0.34037101 -0.94010502 0.018714599, + -0.41847801 -0.90804702 0.0180765, + -0.46482906 -0.88515013 -0.021054002, + -0.54583186 -0.83765781 -0.019924294, + -0.57820231 -0.8144694 -0.048184924, + -0.65526217 -0.75408316 -0.044612411, + -0.67450494 -0.73560995 -0.062618695, + -0.74269825 -0.66721326 -0.056796517, + -0.75138611 -0.65657508 -0.065788507, + -0.80934966 -0.58440071 -0.058556672, + -0.81088102 -0.58209097 -0.060349699, + -0.85933816 -0.50868112 -0.052738812, + -0.85664016 -0.5135721 -0.049105812, + -0.89691174 -0.44020188 -0.04209039, + -0.89232701 -0.45003799 -0.034905002, + -0.92538935 -0.37788314 -0.02930871, + -0.92018634 -0.39098415 -0.019715607, + -0.9472689 -0.32003298 -0.016137898, + -0.94239825 -0.33444908 -0.0054220115, + -0.96440226 -0.26440507 -0.004286461, + -0.96030778 -0.27886194 0.0067083687, + -0.97789115 -0.20905402 0.0050290506, + -0.97497255 -0.2218179 0.015010593, + -0.98820603 -0.15278099 0.0103388, + -0.98639274 -0.16332196 0.018848397, + -0.99546188 -0.094533287 0.010909799, + -0.99486154 -0.10004795 0.015522593, + -0.99947822 -0.031918708 0.0049522612, + -0.99946612 -0.032249402 0.0052401503, + -0.99950075 0.031187892 -0.0050676586, + -0.99948555 0.031606086 -0.0054500373, + -0.99556679 0.092689477 -0.015983095, + -0.99539334 0.094264239 -0.017506106, + -0.98790252 0.15246892 -0.028315486, + -0.98740077 0.15515597 -0.031084593, + -0.97657335 0.21099207 -0.042271115, + -0.975582 0.214687 -0.046359301, + -0.96159637 0.26828408 -0.057933223, + -0.95994252 0.27291089 -0.063481972, + -0.94320089 0.32358396 -0.075269192, + -0.94070727 0.32905009 -0.08243832, + -0.92136747 0.37703976 -0.09446124, + -0.91782534 0.38325915 -0.10348504, + -0.89601856 0.4286648 -0.11574595, + -0.89179111 0.43468207 -0.12554002, + -0.86773628 0.47750917 -0.13790904, + -0.8636899 0.48221794 -0.14664799, + -0.83774114 0.52244306 -0.15888101, + -0.83205539 0.52783823 -0.17050107, + -0.80431402 0.56543702 -0.182647, + -0.79726064 0.57078868 -0.19640692, + -0.76758009 0.60607606 -0.20854902, + -0.75922889 0.61097592 -0.22423197, + -0.72767121 0.64392918 -0.23632605, + -0.71800059 0.64806765 -0.25393584, + -0.68524277 0.67811579 -0.26570892, + -0.67429507 0.68117106 -0.28518802, + -0.64054871 0.70834166 -0.29656285, + -0.62846321 0.70998621 -0.31773213, + -0.59351975 0.73461276 -0.32875288, + -0.59649998 0.73455501 -0.32344499, + -0.56493109 0.75517017 -0.33252209, + -0.58121496 0.7562719 -0.30040297, + -0.54864788 0.77699983 -0.30863693, + -0.56245989 0.77890581 -0.27738893, + -0.52867919 0.79962832 -0.28476807, + -0.54031789 0.80214584 -0.25420195, + -0.50479281 0.82290769 -0.26078191, + -0.51454401 0.82587302 -0.23060399, + -0.47697723 0.84653443 -0.23637313, + -0.48504913 0.8497802 -0.20640005, + -0.44614115 0.86967731 -0.21123308, + -0.45263514 0.8730163 -0.18156005, + -0.41222805 0.89199513 -0.18550701, + -0.41732514 0.8952713 -0.15597805, + -0.375303 0.91314697 -0.15909199, + -0.37917015 0.91621828 -0.12951505, + -0.33549488 0.93276864 -0.13185495, + -0.33827791 0.93549174 -0.10209398, + -0.29366294 0.95026678 -0.10370698, + -0.29550603 0.9524911 -0.07373511, + -0.25017393 0.96531278 -0.074727587, + -0.25123191 0.96690065 -0.044560384, + -0.25207913 0.9676075 -0.013857907, + -0.25154305 0.96681523 -0.04465951, + -0.29753804 0.95369309 -0.044053305, + -0.29631105 0.95222121 -0.073990911, + -0.3416059 0.93701875 -0.072809584, + -0.33952704 0.93499613 -0.10248802, + -0.38393608 0.91786224 -0.10060902, + -0.3808651 0.91544026 -0.13004203, + -0.42376393 0.89676988 -0.12738898, + -0.41957209 0.89410126 -0.15666005, + -0.46089894 0.87413585 -0.15316199, + -0.45545387 0.8713758 -0.18238996, + -0.49534306 0.85027111 -0.17797302, + -0.48848793 0.8475709 -0.20737197, + -0.52699196 0.82552087 -0.20197697, + -0.51856399 0.823053 -0.23167901, + -0.55510974 0.80066162 -0.22537589, + -0.54499 0.79860699 -0.25536799, + -0.57981873 0.77603567 -0.24815089, + -0.5678249 0.77456385 -0.27861395, + -0.60134494 0.75182986 -0.27043697, + -0.5872097 0.75113761 -0.30162385, + -0.61967301 0.728333 -0.29246601, + -0.60309762 0.72863358 -0.32460183, + -0.63401508 0.70639408 -0.31469402, + -0.63070709 0.70673406 -0.32052404, + -0.66531491 0.67990595 -0.30835697, + -0.67663831 0.67742032 -0.28855214, + -0.71022475 0.64766675 -0.27587792, + -0.72029597 0.64398092 -0.25780296, + -0.75272882 0.61117589 -0.24466994, + -0.76139432 0.60665321 -0.22858408, + -0.79186034 0.57148027 -0.21533111, + -0.79919618 0.56641513 -0.20114504, + -0.82771218 0.52879912 -0.18778704, + -0.83371681 0.52353388 -0.17558095, + -0.86037672 0.48320782 -0.16205594, + -0.86504561 0.47811976 -0.15197892, + -0.88971591 0.43506393 -0.13829298, + -0.89285713 0.43086007 -0.13101801, + -0.91526985 0.38541594 -0.11719899, + -0.91860163 0.37992585 -0.10875396, + -0.93852609 0.33187902 -0.095000915, + -0.94122487 0.32630897 -0.087282591, + -0.95849079 0.27543995 -0.073675983, + -0.96025962 0.27075791 -0.067760475, + -0.97470313 0.21681704 -0.054261208, + -0.97575402 0.213098 -0.0499328, + -0.98694879 0.15678796 -0.036738392, + -0.98747885 0.15408498 -0.033811796, + -0.99522787 0.095309786 -0.020914398, + -0.99541765 0.093665972 -0.019244792, + -0.99946791 0.031950098 -0.0065645291, + -0.99948752 0.031431686 -0.0060667973, + -0.99945176 -0.032509591 0.0062748385, + -0.99946678 -0.032113392 0.0059125884, + -0.99474776 -0.10066498 0.018533995, + -0.99483979 -0.099876881 0.017842397, + -0.98454267 -0.17241494 0.030800888, + -0.98629135 -0.16338606 0.023118207, + -0.97097534 -0.23682109 0.033508711, + -0.97473979 -0.22230893 0.021471594, + -0.95476913 -0.29597104 0.028586203, + -0.95983362 -0.28012791 0.015738895, + -0.93523467 -0.35347089 0.019859692, + -0.94153225 -0.33685809 0.0066110212, + -0.91187042 -0.4103992 0.0080543142, + -0.91866988 -0.39500493 -0.0041038496, + -0.8831529 -0.46905994 -0.0048732297, + -0.88974613 -0.45620805 -0.015036002, + -0.8473981 -0.53067005 -0.017490203, + -0.85234261 -0.52242678 -0.024129888, + -0.80237317 -0.59618711 -0.027536808, + -0.803949 -0.59397101 -0.029401099, + -0.74535197 -0.66585594 -0.032959297, + -0.74069077 -0.67126077 -0.028039191, + -0.67278892 -0.73918992 -0.030876696, + -0.65896672 -0.75196564 -0.017619291, + -0.58285987 -0.8123498 -0.019034196, + -0.55764616 -0.83007127 0.0035192613, + -0.47751093 -0.87861788 0.0037250896, + -0.44075784 -0.89692873 0.03537469, + -0.36230481 -0.93133557 0.036731683, + -0.31596187 -0.94568366 0.076488674, + -0.24549794 -0.96624178 0.078151479, + -0.19817208 -0.97278637 0.12006105, + -0.14061595 -0.98260862 0.12127396, + -0.12723798 -0.98277777 0.13400897, + -0.07913854 -0.98772347 0.13468306, + -0.066622771 -0.98676354 0.14784792, + -0.026923412 -0.98860246 0.14812307, + -0.0095476201 -0.98565203 0.16852, + 0.020131405 -0.98549724 0.16849305, + 0.028212804 -0.98340511 0.17921601, + 0.05048421 -0.98254222 0.17905904, + 0.056184299 -0.980618 0.187701, + 0.072030105 -0.97961813 0.18751003, + 0.080056526 -0.97620523 0.20153004, + 0.075613201 -0.97654498 0.2016, + 0.030732885 -0.99322051 0.11210895, + -0.27818999 -0.74284798 -0.60892302, + -0.17905098 -0.9067049 -0.38187295, + -0.19527003 -0.90385711 -0.38067305, + -0.083546393 -0.98604488 -0.14399798, + -0.093912616 -0.98513114 -0.14386502, + 0.027829004 -0.99509114 0.094969116, + 0.029667685 -0.99503851 0.094964057, + -0.106547 -0.98192102 -0.15645701, + -0.095394284 -0.9830389 -0.15663499, + -0.21204093 -0.89658773 -0.38880485, + -0.19539091 -0.89976656 -0.39018282, + -0.29591399 -0.73874003 -0.60555601, + -0.29680395 -0.74665481 -0.5953269, + -0.31937402 -0.72180706 -0.61399907, + -0.21240403 -0.89216214 -0.39866206, + -0.22979006 -0.88856322 -0.39705408, + -0.108479 -0.97948498 -0.169828, + -0.12067906 -0.97809845 -0.16958807, + 0.012978398 -0.99792385 0.063082896, + 0.013843304 -0.99791235 0.063082226, + -0.13624802 -0.97355014 -0.18340302, + -0.12312596 -0.97523665 -0.18372095, + -0.24864991 -0.87969768 -0.40534586, + -0.23040894 -0.88378477 -0.4072299, + -0.33744892 -0.7170198 -0.60992688, + -0.33795998 -0.72572494 -0.59925497, + -0.36176601 -0.69892102 -0.616956, + -0.24958791 -0.87423271 -0.41644084, + -0.268635 -0.86961901 -0.414244, + -0.13929194 -0.97016054 -0.19845991, + -0.15355599 -0.96809191 -0.19803697, + -0.0090622231 -0.99960637 0.026552008, + -0.0095962435 -0.99960136 0.02655191, + -0.17262991 -0.96170652 -0.21288389, + -0.15712099 -0.96423787 -0.21344396, + -0.28970984 -0.85886359 -0.42239979, + -0.26979294 -0.86407185 -0.42496091, + -0.38069209 -0.69324815 -0.61194813, + -0.38082024 -0.70260543 -0.60110039, + -0.4076609 -0.67146081 -0.61883187, + -0.2911281 -0.85299432 -0.43318015, + -0.31167889 -0.8472017 -0.43023884, + -0.17688499 -0.95717603 -0.229185, + -0.193286 -0.95417202 -0.22846501, + -0.039550703 -0.99911612 -0.014240702, + -0.041814797 -0.99902385 -0.014239398, + -0.21613097 -0.94518888 -0.24475597, + -0.19828905 -0.94884723 -0.24570405, + -0.3345651 -0.83406717 -0.43863213, + -0.31348896 -0.8404569 -0.44199196, + -0.42674708 -0.66501719 -0.61289412, + -0.42651594 -0.67486793 -0.60219395, + -0.50954032 -0.46321926 -0.7251184, + -0.46508783 -0.47657982 -0.74603277, + -0.50793469 -0.27158585 -0.81746155, + -0.46305287 -0.27944794 -0.84112483, + -0.48044094 -0.07341589 -0.87394887, + -0.44677514 -0.13580805 -0.8842783, + -0.45095301 0.00110088 -0.89254701, + -0.45197293 0.0011008299 -0.89203089, + -0.44788188 -0.13424698 -0.88395679, + -0.4473289 -0.13427997 -0.88423175, + -0.45141721 0.0010106905 -0.89231241, + -0.42376885 -0.015677594 -0.9056347, + -0.51471591 -0.015877197 -0.8572138, + -0.53695422 -0.00017651709 -0.84361142, + -0.53295386 -0.12184297 -0.83732581, + -0.53223777 -0.12189494 -0.83777356, + -0.58049893 -0.048220493 -0.81283188, + -0.58117533 0.00042997522 -0.8137784, + -0.57736504 0.00043037205 -0.81648612, + -0.57376492 -0.11148498 -0.8113969, + -0.57409316 -0.11145904 -0.81116831, + -0.57769305 0.00024664204 -0.81625414, + -0.60015893 -0.015789898 -0.79972488, + -0.61762476 -0.0018248193 -0.78647071, + -0.61680412 -0.0019916105 -0.7871142, + -0.61366564 -0.10076694 -0.78310955, + -0.61448598 -0.100697 -0.78247499, + -0.65272003 -0.061791908 -0.7550751, + -0.65396941 0.0015744109 -0.7565195, + -0.65470439 0.0015743909 -0.75588346, + -0.65202796 -0.090345696 -0.75279289, + -0.65259916 -0.090293519 -0.7523042, + -0.65527523 0.0012269205 -0.75538927, + -0.67918003 -0.0154055 -0.73381001, + -0.87021571 -0.012037395 0.49252382, + -0.8149761 -0.012808002 0.57935303, + -0.81679857 -0.014300893 0.57674569, + -0.81685019 0.0088484315 0.57678211, + -0.81690598 0.00884654 0.57670301, + -0.81689441 -0.010297605 0.57669532, + -0.84385228 0.0035142512 0.53656417, + -0.84383011 0.0080564907 0.53655005, + -0.84426987 0.008037949 0.53585792, + -0.84429199 0.00363742 0.53587103, + -0.84406716 0.003637451 0.53622514, + -0.86944842 -0.011311206 0.49389425, + -0.8694768 0.0079456484 0.4939099, + -0.86948013 0.0079454705 0.49390405, + -0.86943132 -0.013245204 0.49387619, + -0.89250398 0.0035036399 0.45102599, + -0.89248288 0.0077312589 0.45101494, + -0.89249361 0.0077305362 0.45099381, + -0.892515 0.0035076099 0.451004, + -0.89267814 0.0035076004 0.45068106, + -0.91362321 -0.0084510716 0.40647408, + -0.91627002 -0.0113644 0.40040001, + -0.75104117 -0.014724704 -0.66009116, + -0.76012599 -0.0212541 -0.64942801, + -0.75862384 -0.066327788 -0.64814383, + -0.72390264 -0.066531673 -0.68668669, + -0.72550803 0.0025454503 -0.68820906, + -0.72530401 0.0025454699 -0.68842399, + -0.69133174 -0.0037440686 -0.72252774, + -0.69099474 -0.0038160086 -0.72284979, + -0.68882108 -0.079346009 -0.72057605, + -0.68915874 -0.079312868 -0.72025675, + -0.72370881 -0.066324882 -0.68691081, + -0.72384185 -0.066085085 -0.6867938, + -0.71461225 -0.17442206 -0.67742622, + -0.75112385 -0.16460796 -0.63930982, + -0.72651893 -0.30284196 -0.61681193, + -0.76328433 -0.2847361 -0.57993317, + -0.72608799 -0.413605 -0.54929698, + -0.76488262 -0.38747981 -0.51460075, + -0.71339804 -0.51390809 -0.47640505, + -0.75567472 -0.48031181 -0.44525984, + -0.70847607 -0.57179707 -0.41365406, + -0.7537303 -0.53246015 -0.38519716, + -0.69764698 -0.624448 -0.351217, + -0.68979084 -0.63822883 -0.3418369, + -0.64188093 -0.67595392 -0.36204296, + -0.6892426 -0.60836065 -0.39349976, + -0.65793383 -0.63232881 -0.4090029, + -0.55997914 -0.75583416 -0.33932009, + -0.60204864 -0.72842258 -0.32701379, + -0.57309198 -0.75942898 -0.30794999, + -0.62832475 -0.72093374 -0.29233989, + -0.67375219 -0.66607517 -0.32000309, + -0.74863964 -0.59758872 -0.28709984, + -0.77783054 -0.54914069 -0.30565381, + -0.83623683 -0.47914687 -0.26669493, + -0.85408771 -0.43854886 -0.27965891, + -0.89683688 -0.37297896 -0.23784497, + -0.90933925 -0.33300808 -0.24941505, + -0.93852538 -0.2763041 -0.20694508, + -0.94156748 -0.26267412 -0.21083911, + -0.96214211 -0.21254803 -0.17060502, + -0.96175414 -0.21484102 -0.16991901, + -0.97678435 -0.16802406 -0.13289204, + -0.97720367 -0.16471495 -0.13394795, + -0.98749167 -0.12232795 -0.099478565, + -0.98740739 -0.12327004 -0.099153034, + -0.99412525 -0.084338821 -0.067838512, + -0.99397975 -0.086745776 -0.066929184, + -0.99800402 -0.049998 -0.038576301, + -0.99792552 -0.052215174 -0.037660081, + -0.99978954 -0.016638793 -0.012000695, + -0.99977863 -0.017569294 -0.011580396, + -0.99979222 0.017020004 0.011218303, + -0.99977922 0.018094303 0.010688903, + -0.99808311 0.053285208 0.031477205, + -0.99794263 0.056906782 0.029533489, + -0.99453902 0.092633702 0.048075002, + -0.99408662 0.09915816 0.044265587, + -0.98886186 0.13590899 0.060671594, + -0.987822 0.145762 0.054416601, + -0.98055762 0.18383794 0.06863118, + -0.97856945 0.19715409 0.059432831, + -0.96911901 0.236099 0.071172997, + -0.96567434 0.25312009 0.058338221, + -0.95372826 0.29298905 0.067527018, + -0.94826734 0.31340811 0.050642017, + -0.93345487 0.35410196 0.057217494, + -0.92802078 0.37007692 0.042666089, + -0.92603838 0.37643716 0.027352609, + -0.90366888 0.42710593 0.031034196, + -0.89691168 0.44192484 0.015871294, + -0.87598813 0.48202205 0.017311402, + -0.87090284 0.49141088 0.0066091688, + -0.84813941 0.52972525 0.0071244733, + -0.84316599 0.53764498 -0.0029871601, + -0.81856418 0.57440615 -0.0031914008, + -0.81215501 0.583224 -0.0159362, + -0.78567088 0.61841393 -0.016897798, + -0.7781927 0.62723279 -0.03154479, + -0.75033802 0.66022003 -0.033203799, + -0.74187803 0.66869408 -0.049651407, + -0.71274179 0.6995008 -0.051938888, + -0.70335323 0.70736426 -0.070213623, + -0.67272103 0.736278 -0.073083602, + -0.66250008 0.74324906 -0.093136609, + -0.63049066 0.77017355 -0.096510343, + -0.61952889 0.77599984 -0.11835597, + -0.58685005 0.80043912 -0.12208302, + -0.57565212 0.80474418 -0.14495303, + -0.54234296 0.82685089 -0.14893499, + -0.53125882 0.82949769 -0.17232995, + -0.49695995 0.84963191 -0.17651199, + -0.48525193 0.85066086 -0.20225397, + -0.45012012 0.86875015 -0.20655504, + -0.43843094 0.86789191 -0.23354197, + -0.40324807 0.8836571 -0.23778403, + -0.39183509 0.88083422 -0.26570007, + -0.35686791 0.89435178 -0.26977795, + -0.34586802 0.88949913 -0.29860803, + -0.31082395 0.90104973 -0.30248594, + -0.30041304 0.8941381 -0.33206803, + -0.26584995 0.90370476 -0.33562091, + -0.25630397 0.89479786 -0.36557496, + -0.22231293 0.90255469 -0.36874387, + -0.22237507 0.90263122 -0.3685191, + -0.19039004 0.90887815 -0.37106904, + -0.19692405 0.91906321 -0.3413851, + -0.162691 0.92492998 -0.343564, + -0.16758005 0.93458736 -0.31378913, + -0.131382 0.939776 -0.31553099, + -0.13480002 0.94876909 -0.28577304, + -0.096804738 0.95301133 -0.28705108, + -0.099002026 0.96129525 -0.25711906, + -0.059887908 0.96430713 -0.25792503, + -0.061048586 0.97178078 -0.22784895, + -0.020600205 0.97339022 -0.22822607, + -0.020940498 0.97995889 -0.19809598, + 0.020388806 0.97997022 -0.19809805, + 0.020040194 0.97339678 -0.22824794, + 0.060393315 0.97181523 -0.22787707, + 0.059226613 0.96434522 -0.25793505, + 0.098354913 0.96135712 -0.25713602, + 0.096155077 0.95308673 -0.28701895, + 0.13420098 0.94886178 -0.28574693, + 0.13078794 0.9398995 -0.31540984, + 0.16724306 0.93469036 -0.31366211, + 0.16239299 0.92510486 -0.34323397, + 0.19680899 0.919213 -0.341048, + 0.19028997 0.90905488 -0.37068698, + 0.222674 0.90272599 -0.36810601, + 0.22248593 0.90249568 -0.36878389, + 0.25628501 0.89477998 -0.365632, + 0.26589909 0.90374827 -0.33546513, + 0.30055699 0.89415097 -0.33190301, + 0.311001 0.901079 -0.30221701, + 0.34595397 0.88955188 -0.29835096, + 0.35695511 0.89439029 -0.26953509, + 0.3920469 0.88081676 -0.26544493, + 0.40339893 0.88361889 -0.23766997, + 0.43860888 0.86783379 -0.23342393, + 0.45018905 0.8686831 -0.20668703, + 0.48526117 0.85062331 -0.20239007, + 0.49681911 0.84961516 -0.17698805, + 0.53105223 0.82953143 -0.17280409, + 0.54237795 0.82683289 -0.14890799, + 0.57571006 0.80470812 -0.14492401, + 0.58707565 0.80033153 -0.12170292, + 0.61975998 0.77587199 -0.117984, + 0.63074994 0.77001691 -0.096065283, + 0.66282469 0.74301463 -0.092696555, + 0.67306727 0.73601234 -0.072569638, + 0.70368063 0.70708764 -0.069717668, + 0.71302903 0.69924003 -0.051508199, + 0.74218839 0.66838044 -0.049235031, + 0.7505511 0.65999007 -0.032958303, + 0.77838898 0.62700099 -0.031310901, + 0.78574616 0.61831814 -0.016898403, + 0.8122285 0.58312166 -0.01593649, + 0.81848019 0.5745241 -0.0035063808, + 0.84306097 0.537808 -0.0032823, + 0.84785569 0.53018785 0.0064529176, + 0.87063003 0.49190199 0.0059869401, + 0.87583131 0.48232117 0.016910406, + 0.89675885 0.44224793 0.015505398, + 0.90747857 0.4181878 0.040019281, + 0.92544127 0.37716809 0.036093809, + 0.93371814 0.35329804 0.057888009, + 0.94847786 0.31267396 0.051231693, + 0.95386666 0.29243788 0.067959279, + 0.96578938 0.25259709 0.058700822, + 0.96916538 0.23586509 0.071317226, + 0.9786011 0.19696003 0.059553806, + 0.980555 0.183863 0.068602502, + 0.98782313 0.14576502 0.054387607, + 0.98885322 0.13601503 0.060575515, + 0.99408162 0.099239364 0.044197187, + 0.99453366 0.092730969 0.047996383, + 0.99793965 0.056980181 0.029492188, + 0.99808067 0.05335398 0.031438489, + 0.99977887 0.018119298 0.010676599, + 0.99979186 0.017050799 0.011203199, + 0.99977821 -0.017601803 -0.011565203, + 0.99978924 -0.016673403 -0.011984603, + 0.99792224 -0.05231801 -0.037605409, + 0.99799901 -0.0501603 -0.038496699, + 0.9939605 -0.087055348 -0.066812627, + 0.99410534 -0.08467333 -0.067712523, + 0.98736191 -0.12377199 -0.098979682, + 0.9875195 -0.12201394 -0.099587955, + 0.97725791 -0.16427998 -0.13408598, + 0.97688723 -0.16722204 -0.13314703, + 0.96192753 -0.2138079 -0.17023993, + 0.96142924 -0.21672104 -0.16936904, + 0.94042873 -0.26788795 -0.20935595, + 0.93850255 -0.27640387 -0.2069149, + 0.90935087 -0.33304796 -0.24931897, + 0.897219 -0.37190801 -0.23808099, + 0.85449302 -0.43749699 -0.28006801, + 0.8361963 -0.47917819 -0.2667661, + 0.77785212 -0.54909104 -0.30568802, + 0.74973857 -0.59586763 -0.28780884, + 0.68622708 -0.65498608 -0.31636304, + 0.68004876 -0.65198076 -0.33534288, + 0.66583329 -0.67094231 -0.32634714, + 0.62639701 -0.70098102 -0.340958, + 0.73319209 -0.54231703 -0.41027007, + 0.68401796 -0.61144894 -0.39780593, + 0.75820613 -0.47442707 -0.44726107, + 0.71606708 -0.50791007 -0.47882706, + 0.61434692 -0.68141592 -0.39780694, + 0.70579356 -0.5346877 -0.46471974, + 0.66164482 -0.5659349 -0.49187788, + 0.7200492 -0.43649408 -0.53944612, + 0.67918092 -0.46168494 -0.57057893, + 0.72077483 -0.33266592 -0.60812587, + 0.68166274 -0.35114187 -0.64189976, + 0.71080178 -0.21094392 -0.67101675, + 0.67221606 -0.22202903 -0.70627809, + 0.61150306 -0.071674809 -0.78798914, + 0.61307788 0.0020384595 -0.79001981, + 0.61162812 0.0028778408 -0.7911402, + 0.61005276 -0.07176958 -0.78910369, + 0.64935666 -0.055563267 -0.75845152, + 0.63201994 -0.23885797 -0.73722297, + 0.67220581 -0.22819795 -0.70431882, + 0.63888282 -0.38225892 -0.66761285, + 0.68011516 -0.36427209 -0.63619918, + 0.63185072 -0.50464875 -0.58829772, + 0.67428744 -0.48080531 -0.56050235, + 0.60486931 -0.62107128 -0.49840122, + 0.6501047 -0.59261972 -0.47556877, + 0.54122198 -0.74597198 -0.388078, + 0.46735299 -0.84115398 -0.27210501, + 0.39817607 -0.89022809 -0.22124603, + 0.3679691 -0.90238726 -0.22426806, + 0.4630698 -0.83494759 -0.29736984, + 0.43312892 -0.84908783 -0.30240595, + 0.54384702 -0.741615 -0.39273101, + 0.52413779 -0.7526167 -0.39855686, + 0.38586593 -0.87891889 -0.28037298, + 0.4139908 -0.86722559 -0.27664289, + 0.31544396 -0.92820185 -0.19732296, + 0.3440049 -0.91844374 -0.19524795, + 0.36044908 -0.90933621 -0.20780805, + 0.43803513 -0.87636524 -0.20027305, + 0.48632187 -0.84134883 -0.23584594, + 0.57344568 -0.78883666 -0.2211259, + 0.61755323 -0.74468225 -0.25313309, + 0.69628102 -0.67958099 -0.231003, + 0.73551857 -0.62523365 -0.26095086, + 0.7990579 -0.55486596 -0.23158197, + 0.80808085 -0.53829092 -0.23926596, + 0.85904711 -0.46776906 -0.20791903, + 0.86721641 -0.44864121 -0.21600211, + 0.90597677 -0.38142192 -0.18363896, + 0.91211289 -0.36261696 -0.19120397, + 0.94010562 -0.30153289 -0.15899494, + 0.94141233 -0.29629213 -0.16110206, + 0.96191263 -0.24015291 -0.13057795, + 0.96205747 -0.23940212 -0.13089006, + 0.97688287 -0.18757097 -0.10255198, + 0.97645622 -0.19045804 -0.10128702, + 0.9870311 -0.14173302 -0.075374804, + 0.98651278 -0.14640898 -0.073190488, + 0.99369538 -0.10028204 -0.050131619, + 0.99334002 -0.104806 -0.0478676, + 0.99778688 -0.060483191 -0.027624195, + 0.99762678 -0.063825786 -0.025827894, + 0.99975914 -0.020347701 -0.0082339412, + 0.99973851 -0.021596989 -0.0075130663, + 0.99975455 0.020926191 0.0072797067, + 0.99973035 0.022318007 0.0064173322, + 0.99766153 0.06568677 0.018887591, + 0.99740773 0.070177987 0.015899597, + 0.99313354 0.11409495 0.025849488, + 0.99231386 0.12209898 0.020123698, + 0.98556638 0.16703606 0.02752991, + 0.98370963 0.17881595 0.018446892, + 0.97410703 0.224894 0.0232003, + 0.97047365 0.24100991 0.0097493865, + 0.95774335 0.2873891 0.011625504, + 0.9523111 0.30509603 -0.0044734506, + 0.93626302 0.351262 -0.0051503698, + 0.93364286 0.35800898 -0.011858098, + 0.9153074 0.40253517 -0.013332906, + 0.91254014 0.40850505 -0.019856501, + 0.8921327 0.45124084 -0.021933792, + 0.88816559 0.4584958 -0.030717785, + 0.86596048 0.49899369 -0.033430982, + 0.8609401 0.50679904 -0.044012003, + 0.8369934 0.54516125 -0.047343623, + 0.83090985 0.55319691 -0.059682384, + 0.80512983 0.58967686 -0.063617982, + 0.79789031 0.59774923 -0.077891827, + 0.77030033 0.63233531 -0.082398735, + 0.76191986 0.64012194 -0.098599687, + 0.73312879 0.67216277 -0.10353496, + 0.72361177 0.67938876 -0.12172496, + 0.69368798 0.70898598 -0.127027, + 0.68352896 0.71509391 -0.14638598, + 0.65231395 0.74254996 -0.15200698, + 0.64196903 0.74722397 -0.171849, + 0.60929513 0.77277017 -0.17772405, + 0.59820008 0.77616811 -0.19929802, + 0.56486964 0.79925251 -0.20522588, + 0.55314708 0.80113512 -0.22849703, + 0.51924109 0.82185316 -0.23440605, + 0.50711787 0.82199985 -0.25912893, + 0.47262093 0.84049189 -0.26495796, + 0.46024612 0.83870816 -0.29110506, + 0.42512521 0.85509241 -0.29679215, + 0.41277292 0.85124379 -0.32404092, + 0.37804994 0.86521685 -0.32935998, + 0.36590683 0.85919958 -0.35761482, + 0.33163598 0.87097585 -0.36251697, + 0.3324669 0.87153381 -0.3604089, + 0.30032298 0.8814429 -0.36450598, + 0.310426 0.88994998 -0.33410299, + 0.27594689 0.89985061 -0.33781984, + 0.28404209 0.90809631 -0.30770311, + 0.24798906 0.91752124 -0.31089607, + 0.25433895 0.92543077 -0.28087294, + 0.21663393 0.93417466 -0.2835269, + 0.22148506 0.94166625 -0.25339505, + 0.18207794 0.94950765 -0.25550491, + 0.18562201 0.95646203 -0.22522201, + 0.14456092 0.96315354 -0.22679789, + 0.14698091 0.96943039 -0.19647188, + 0.10508502 0.97464824 -0.19753005, + 0.10655896 0.98015565 -0.16715294, + 0.063903123 0.98375338 -0.16776706, + 0.064640701 0.98842299 -0.137265, + 0.021436999 0.99026686 -0.13752098, + 0.021634901 0.99403214 -0.10692102, + -0.022068392 0.99402267 -0.10691996, + -0.021875799 0.99025488 -0.13753799, + -0.065042332 0.9883945 -0.13728006, + -0.064312994 0.98373187 -0.16773598, + -0.10704497 0.98010862 -0.16711794, + -0.10558295 0.97461152 -0.19744492, + -0.14757201 0.9693591 -0.19638103, + -0.14517191 0.96308541 -0.22669686, + -0.18616399 0.9563809 -0.22511896, + -0.18261304 0.94942427 -0.25543305, + -0.22200505 0.94156426 -0.25331905, + -0.21712703 0.93404013 -0.28359303, + -0.2548781 0.92526537 -0.28092909, + -0.24848697 0.91729391 -0.31116897, + -0.28449005 0.90786523 -0.30797106, + -0.27633899 0.89953399 -0.33834201, + -0.31046689 0.88972872 -0.33465388, + -0.30034107 0.88117921 -0.3651281, + -0.33215412 0.87138027 -0.36106813, + -0.33158591 0.8709988 -0.36250791, + -0.36588612 0.85921329 -0.35760313, + -0.37792286 0.86518073 -0.32960087, + -0.41261193 0.85122889 -0.32428497, + -0.42495495 0.8550809 -0.29706898, + -0.45997119 0.83875728 -0.29139808, + -0.47237599 0.84054798 -0.26521701, + -0.50687408 0.82206911 -0.25938603, + -0.51906997 0.82192689 -0.23452596, + -0.55297905 0.80121714 -0.22861603, + -0.56487614 0.79930615 -0.20499904, + -0.59826297 0.7761789 -0.19906697, + -0.60949612 0.77272916 -0.17721204, + -0.64221907 0.74712604 -0.17134002, + -0.65226305 0.74258208 -0.15206802, + -0.68351984 0.71509182 -0.14643897, + -0.69348902 0.70910603 -0.127443, + -0.72334421 0.67959917 -0.12214003, + -0.73282605 0.67241508 -0.10403802, + -0.76162273 0.64040077 -0.099084161, + -0.77000111 0.63263303 -0.082908109, + -0.79758912 0.59808707 -0.078380704, + -0.80486417 0.58999211 -0.064055115, + -0.83064753 0.55354565 -0.060098164, + -0.83683419 0.54538614 -0.047564913, + -0.86079514 0.50702703 -0.044219505, + -0.86594331 0.49902719 -0.033377912, + -0.88817132 0.45848817 -0.030666411, + -0.89225829 0.45100814 -0.021608707, + -0.91265786 0.40825593 -0.019560399, + -0.9155249 0.40205795 -0.012787698, + -0.93382561 0.35754782 -0.011371994, + -0.93634075 0.35105792 -0.0049220286, + -0.95237797 0.30489001 -0.0042747199, + -0.95758367 0.28793991 0.011136697, + -0.9703539 0.24150798 0.009340859, + -0.97397947 0.2254961 0.022707511, + -0.98362374 0.17932695 0.018058296, + -0.98551285 0.16739598 0.027258396, + -0.99228251 0.12238594 0.019929091, + -0.99312425 0.11418803 0.025796305, + -0.9974041 0.070237905 0.015867501, + -0.99766225 0.065670013 0.018907504, + -0.99973053 0.02230629 0.0064223567, + -0.99975491 0.020903898 0.0072910292, + -0.99973887 -0.021576498 -0.0075256289, + -0.9997595 -0.02032011 -0.0082506035, + -0.99763227 -0.063721918 -0.025873106, + -0.9977929 -0.060359493 -0.027679496, + -0.99335647 -0.10460405 -0.047969021, + -0.99371099 -0.100074 -0.0502357, + -0.98654938 -0.14609006 -0.073335133, + -0.98706335 -0.14143704 -0.075508431, + -0.97651637 -0.19005507 -0.10146404, + -0.97698611 -0.18686202 -0.10286301, + -0.96223497 -0.23847599 -0.131275, + -0.96210939 -0.23913209 -0.13100204, + -0.94174314 -0.29497102 -0.16159202, + -0.93975848 -0.30292815 -0.15839407, + -0.91154027 -0.36440313 -0.19053808, + -0.90490776 -0.38453391 -0.18241596, + -0.86573887 -0.45219493 -0.21451297, + -0.86289859 -0.4589068 -0.2116849, + -0.8131789 -0.52849692 -0.24378496, + -0.79918885 -0.55459493 -0.23177896, + -0.73576725 -0.62486023 -0.2611441, + -0.69505697 -0.68114102 -0.230093, + -0.61605203 -0.74627608 -0.25209504, + -0.57354093 -0.78873289 -0.22124897, + -0.48652688 -0.84119684 -0.23596494, + -0.43660995 -0.87732089 -0.19919796, + -0.46891394 -0.84276789 -0.26431397, + -0.46104005 -0.84885013 -0.25864202, + -0.54968983 -0.79909772 -0.24348292, + -0.59605575 -0.75418472 -0.27554092, + -0.67777699 -0.69061899 -0.25231701, + -0.71268797 -0.64447194 -0.27700496, + -0.78040886 -0.57445395 -0.24690998, + -0.81023961 -0.52004576 -0.27030388, + -0.86105901 -0.451197 -0.23451801, + -0.8700133 -0.42903116 -0.24291809, + -0.9081707 -0.36426389 -0.20624693, + -0.90907913 -0.36139402 -0.20729104, + -0.93810153 -0.30044484 -0.17233191, + -0.94131553 -0.28733185 -0.17710291, + -0.96189666 -0.23275191 -0.14346196, + -0.9625541 -0.22917503 -0.14480501, + -0.97721386 -0.17943898 -0.11337899, + -0.97702497 -0.180804 -0.112837, + -0.98735386 -0.13448998 -0.083933495, + -0.98699462 -0.13800696 -0.082436472, + -0.99392664 -0.094473764 -0.056432482, + -0.99364865 -0.098367363 -0.054647282, + -0.99789113 -0.056742307 -0.031522803, + -0.99776453 -0.05968127 -0.030067585, + -0.99977291 -0.019029697 -0.0095872292, + -0.9997561 -0.020181602 -0.0089712506, + -0.999771 0.0195543 0.0086923698, + -0.99975145 0.020827509 0.007957804, + -0.99784279 0.061324384 0.023430895, + -0.99763101 0.065577 0.020784499, + -0.99372125 0.10665602 0.033804409, + -0.99304223 0.11419703 0.028742308, + -0.98691851 0.15634392 0.039350383, + -0.98536164 0.16759995 0.03118749, + -0.97668886 0.21103697 0.039270498, + -0.97374237 0.22598408 0.027516309, + -0.96233052 0.26988888 0.032862283, + -0.95726001 0.288746 0.016706901, + -0.94269311 0.33310404 0.019273402, + -0.93586987 0.35234398 0.0011898399, + -0.91804022 0.39648509 0.0013389003, + -0.91473532 0.40400216 -0.0064443625, + -0.89470786 0.44659495 -0.007123779, + -0.89116114 0.45344007 -0.014965402, + -0.86937284 0.49388787 -0.016300397, + -0.86451101 0.501912 -0.0265528, + -0.84100252 0.54027569 -0.028582383, + -0.83504117 0.54868013 -0.040698312, + -0.80965716 0.58529514 -0.04341431, + -0.80268013 0.59365904 -0.057215307, + -0.77546436 0.6284793 -0.060571231, + -0.76741719 0.63660419 -0.076197714, + -0.7389434 0.6689924 -0.080074348, + -0.72985518 0.67660517 -0.09755522, + -0.70019567 0.70664364 -0.10188594, + -0.69012958 0.71346259 -0.12121192, + -0.65914625 0.74139124 -0.12595704, + -0.64863181 0.7469148 -0.14626998, + -0.61631 0.77282399 -0.151344, + -0.60576206 0.77682412 -0.17203702, + -0.57273018 0.80035228 -0.17724706, + -0.56115699 0.80306 -0.20049299, + -0.52738893 0.82432187 -0.20580196, + -0.51539588 0.82534784 -0.23058194, + -0.48101825 0.8443774 -0.23589912, + -0.46890181 0.84353572 -0.26187491, + -0.43380699 0.860493 -0.26713899, + -0.42172185 0.85765171 -0.29425189, + -0.38687286 0.8722257 -0.29925188, + -0.37503907 0.86730611 -0.32730103, + -0.3405121 0.87968522 -0.33197209, + -0.32915291 0.87266481 -0.3607139, + -0.29497606 0.88304126 -0.36500308, + -0.29534706 0.88334525 -0.36396608, + -0.26311496 0.89201289 -0.36753696, + -0.27207205 0.90122223 -0.33730608, + -0.2378981 0.90966332 -0.34046611, + -0.24498799 0.91853303 -0.310287, + -0.20908904 0.92646325 -0.31296608, + -0.21450704 0.93485224 -0.28291005, + -0.17673907 0.94206434 -0.2850931, + -0.18073004 0.94992024 -0.25492805, + -0.14115702 0.95615411 -0.25660104, + -0.14390199 0.96335787 -0.22634897, + -0.10309599 0.96830291 -0.22750998, + -0.10479904 0.97474039 -0.19722708, + -0.063023403 0.97818899 -0.197925, + -0.063896216 0.98377925 -0.16761805, + -0.021474307 0.98556638 -0.16792206, + -0.021714494 0.99026477 -0.13749197, + 0.021340199 0.99027288 -0.13749298, + 0.021092391 0.98557055 -0.16794592, + 0.063473694 0.9838019 -0.16764499, + 0.06259048 0.97820264 -0.19799493, + 0.10426998 0.97478187 -0.19730197, + 0.10255895 0.96834254 -0.2275839, + 0.14322601 0.96343911 -0.22643203, + 0.14046595 0.95624352 -0.25664687, + 0.18011202 0.95002413 -0.25497803, + 0.17613205 0.94220138 -0.28501609, + 0.21398197 0.93499488 -0.28283596, + 0.20858303 0.92664814 -0.31275603, + 0.24470305 0.91868323 -0.31006706, + 0.23766898 0.9098829 -0.34003899, + 0.2720269 0.90139973 -0.33686787, + 0.26312095 0.89225078 -0.36695492, + 0.29547095 0.88354677 -0.3633759, + 0.29488602 0.88306814 -0.36501104, + 0.32918209 0.87265617 -0.36070809, + 0.34062287 0.87972468 -0.33175388, + 0.3751891 0.86732519 -0.3270781, + 0.38705316 0.87225032 -0.29894713, + 0.42187086 0.85768068 -0.2939539, + 0.43395293 0.86050791 -0.26685396, + 0.46911311 0.8435092 -0.26158205, + 0.48115006 0.84433913 -0.23576704, + 0.51555389 0.82528681 -0.23044693, + 0.52738589 0.82427484 -0.20599796, + 0.56112295 0.8030349 -0.20068897, + 0.57252783 0.8003757 -0.17779393, + 0.6055699 0.77685583 -0.17256896, + 0.61639428 0.77275938 -0.15133107, + 0.64871418 0.7468462 -0.14625603, + 0.65940821 0.74122322 -0.12557505, + 0.69035894 0.71330297 -0.12084498, + 0.70048022 0.70643222 -0.10139504, + 0.73017067 0.67633373 -0.097075254, + 0.73926193 0.66870093 -0.079566494, + 0.76772863 0.63628668 -0.075709559, + 0.77573913 0.62818205 -0.060134709, + 0.80295682 0.5933249 -0.056797884, + 0.80984211 0.58505803 -0.043161903, + 0.83520639 0.54844624 -0.040460918, + 0.84102714 0.54023504 -0.028627304, + 0.864537 0.50186503 -0.026594101, + 0.86926013 0.49407506 -0.016637102, + 0.89104658 0.4536548 -0.015275992, + 0.8944661 0.44706905 -0.0077303709, + 0.91451031 0.40450215 -0.0069943522, + 0.91793603 0.396727 0.00106063, + 0.93577713 0.35259104 0.00094264012, + 0.94289351 0.33250386 0.019821191, + 0.9574219 0.28818098 0.017178997, + 0.96249622 0.26922905 0.033417609, + 0.97387302 0.225364 0.027973, + 0.97677338 0.21058607 0.039589215, + 0.98541635 0.16723105 0.031438611, + 0.98693788 0.15619898 0.039439995, + 0.99305153 0.11409895 0.028809886, + 0.99371874 0.10668298 0.033789892, + 0.99763048 0.06558983 0.020774309, + 0.99784011 0.061383009 0.023392402, + 0.99975109 0.020849101 0.0079453513, + 0.99977064 0.019581992 0.0086763874, + 0.99975574 -0.020208394 -0.008953928, + 0.99977255 -0.01906389 -0.0095657054, + 0.99775887 -0.059804991 -0.030008396, + 0.99788702 -0.0568395 -0.031476598, + 0.99363333 -0.098558635 -0.05457982, + 0.99391139 -0.094677337 -0.056359917, + 0.98696476 -0.13828897 -0.082320876, + 0.98730814 -0.13494201 -0.083745204, + 0.97692978 -0.18145695 -0.11261197, + 0.97711039 -0.18016006 -0.11312704, + 0.96237862 -0.2301079 -0.14449096, + 0.96204865 -0.23190291 -0.14381695, + 0.94157445 -0.28623116 -0.17750908, + 0.93867576 -0.29815695 -0.17317696, + 0.90988714 -0.35873502 -0.20836203, + 0.90588158 -0.37128183 -0.2037849, + 0.86678869 -0.43715584 -0.23994191, + 0.86094844 -0.4514142 -0.23450612, + 0.81016117 -0.52020115 -0.27024007, + 0.78138769 -0.57280082 -0.24765392, + 0.71379894 -0.64283997 -0.27793497, + 0.67768532 -0.69068837 -0.25237313, + 0.59605712 -0.75417316 -0.27557006, + 0.55103827 -0.79787737 -0.24443512, + 0.47258005 -0.84263211 -0.25814602, + 0.45461807 -0.85616809 -0.24555802, + 0.42262295 -0.87118191 -0.24986397, + 0.51179087 -0.7990858 -0.31548691, + 0.48177776 -0.8150686 -0.32179686, + 0.59771591 -0.68760496 -0.41223195, + 0.61807013 -0.6742382 -0.40421808, + 0.52966374 -0.77780062 -0.33835286, + 0.56063193 -0.75932986 -0.33031797, + 0.47802994 -0.83510286 -0.27219597, + 0.51072508 -0.81741911 -0.26643202, + 0.58393693 -0.73232591 -0.35030898, + 0.57794988 -0.73618084 -0.35215291, + 0.66763383 -0.61731488 -0.4161579, + 0.68842524 -0.60140926 -0.40543514, + 0.57717603 -0.74689907 -0.33016604, + 0.61850101 -0.718696 -0.31769899, + 0.58427626 -0.75587231 -0.29542911, + 0.65762597 -0.70165598 -0.274239, + 0.69507593 -0.65387791 -0.29885298, + 0.76607066 -0.58459169 -0.26718587, + 0.79299998 -0.53780502 -0.28621101, + 0.847781 -0.46817601 -0.249156, + 0.86719811 -0.42135805 -0.26537704, + 0.90637589 -0.35747996 -0.22514597, + 0.9098199 -0.34623596 -0.22879797, + 0.93875253 -0.28749186 -0.18997891, + 0.94041777 -0.28043595 -0.19227596, + 0.96134365 -0.22709893 -0.15570594, + 0.9625271 -0.22044003 -0.15794902, + 0.97722465 -0.17249794 -0.12359796, + 0.97715789 -0.17300498 -0.12341698, + 0.98744911 -0.12857501 -0.091721304, + 0.98723 -0.130863 -0.090839699, + 0.99403977 -0.089555979 -0.062165987, + 0.99384034 -0.092589326 -0.060898822, + 0.99795711 -0.053377409 -0.035107903, + 0.99785548 -0.055977125 -0.033928216, + 0.99978226 -0.017844304 -0.010815603, + 0.99976873 -0.018873597 -0.010308097, + 0.99978298 0.018283799 0.0099860197, + 0.99976677 0.019463597 0.0093551679, + 0.9979769 0.057302892 0.027542597, + 0.99780613 0.061180707 0.025296504, + 0.99418038 0.09955404 0.041162815, + 0.99362814 0.10653801 0.036780905, + 0.9880085 0.14594707 0.050386522, + 0.98676854 0.15621692 0.043405078, + 0.97889423 0.19690804 0.054711416, + 0.97650689 0.21085997 0.044410195, + 0.96620691 0.25223398 0.053123992, + 0.96211922 0.26983106 0.038960908, + 0.94903463 0.31193689 0.045040585, + 0.94240326 0.33346409 0.026035905, + 0.92613697 0.37604299 0.029360401, + 0.91724187 0.39825693 0.0076634991, + 0.8976993 0.44052714 0.0084768729, + 0.89340711 0.44924706 -0.00098042807, + 0.87198186 0.48953694 -0.0010683599, + 0.86787856 0.49668175 -0.0096926251, + 0.84476483 0.53503591 -0.010441097, + 0.83928156 0.54326779 -0.021598289, + 0.81431085 0.5799709 -0.023057494, + 0.80770898 0.588471 -0.036168501, + 0.7808677 0.62351978 -0.038322683, + 0.77321237 0.63190532 -0.053276826, + 0.74505591 0.66464394 -0.056036994, + 0.7363438 0.67266685 -0.072919086, + 0.70691103 0.703183 -0.076227099, + 0.69719499 0.710554 -0.095037699, + 0.6663838 0.7390278 -0.098845981, + 0.65577197 0.74543601 -0.119534, + 0.62362558 0.77186245 -0.12377191, + 0.61251813 0.77690518 -0.14573903, + 0.57974994 0.80082589 -0.15022598, + 0.56858999 0.80426198 -0.172824, + 0.53509122 0.82594043 -0.17748208, + 0.52351207 0.8278051 -0.20167802, + 0.48919401 0.84738898 -0.206449, + 0.47741294 0.8474859 -0.23204397, + 0.44229287 0.86503184 -0.23684794, + 0.43048716 0.86320633 -0.2637341, + 0.39550585 0.87838072 -0.26836991, + 0.38389891 0.87452585 -0.29635495, + 0.34905303 0.88752711 -0.30076203, + 0.33784491 0.88158476 -0.32964993, + 0.30313697 0.89258587 -0.33376396, + 0.29253298 0.88453287 -0.36335397, + 0.25841692 0.89357769 -0.36706889, + 0.25878111 0.8939414 -0.36592519, + 0.22635897 0.90144485 -0.36899698, + 0.23407994 0.91114277 -0.33915392, + 0.19984809 0.9182744 -0.34180814, + 0.20579593 0.92751062 -0.31204489, + 0.16953894 0.93407762 -0.31425387, + 0.1739549 0.94277853 -0.28444386, + 0.135801 0.948506 -0.286172, + 0.13889496 0.95658666 -0.2562229, + 0.099500485 0.96115589 -0.25744697, + 0.10146702 0.96852821 -0.22728306, + 0.060972128 0.9717415 -0.2280371, + 0.062001169 0.97827351 -0.19782992, + 0.020641809 0.97995049 -0.19816908, + 0.020937605 0.98558122 -0.16790305, + -0.021398693 0.98557162 -0.16790093, + -0.021110894 0.97994578 -0.19814296, + -0.062575221 0.97824335 -0.19779907, + -0.061554607 0.97171611 -0.22798903, + -0.10207302 0.96847725 -0.22722906, + -0.10011098 0.96109974 -0.25741994, + -0.13961594 0.95649153 -0.25618589, + -0.13652897 0.94838375 -0.28623095, + -0.17449802 0.94266009 -0.28450403, + -0.17006993 0.93392158 -0.31443086, + -0.20617789 0.9273656 -0.31222385, + -0.20019197 0.91805285 -0.34220198, + -0.23421302 0.91095811 -0.33955804, + -0.22646803 0.9012081 -0.36950803, + -0.25858203 0.8937791 -0.36646202, + -0.25841203 0.89360911 -0.36699602, + -0.29253113 0.88456333 -0.36328113, + -0.30303994 0.89254475 -0.3339619, + -0.33771086 0.88156056 -0.32985187, + -0.3489159 0.88750774 -0.30097795, + -0.38362992 0.87456483 -0.29658794, + -0.39525416 0.87842643 -0.26859111, + -0.43026292 0.86325181 -0.26395094, + -0.44211593 0.86508989 -0.23696597, + -0.47726312 0.84753919 -0.23215806, + -0.48916683 0.84744167 -0.20629692, + -0.52355212 0.82781816 -0.20152004, + -0.5352779 0.82592481 -0.17699096, + -0.56884092 0.80418986 -0.17233299, + -0.57971781 0.8008377 -0.15028694, + -0.61246806 0.77693313 -0.14580101, + -0.62341112 0.77197218 -0.12416703, + -0.655514 0.74559999 -0.119925, + -0.66608775 0.73922974 -0.099330463, + -0.69689715 0.71078318 -0.095508225, + -0.706599 0.70344001 -0.076746099, + -0.73601878 0.67296773 -0.073421471, + -0.74476665 0.66492969 -0.056490272, + -0.77293169 0.63221174 -0.05371068, + -0.78068763 0.62372971 -0.03857518, + -0.80751216 0.5887261 -0.036410406, + -0.81424654 0.58006161 -0.023043986, + -0.8392508 0.54331589 -0.021584194, + -0.84487885 0.53486192 -0.010124099, + -0.8679859 0.49649993 -0.0093979789, + -0.87224329 0.48907217 -0.00043335813, + -0.89366078 0.44874287 -0.00039762291, + -0.89783531 0.44024315 0.0088154431, + -0.91736257 0.39797282 0.0079690265, + -0.92589766 0.37667784 0.028762588, + -0.94219911 0.33408102 0.025509903, + -0.94882667 0.31265587 0.044431686, + -0.96195024 0.27050707 0.038441908, + -0.96609449 0.25274512 0.052740127, + -0.97642112 0.21132302 0.044096604, + -0.978863 0.197092 0.054607201, + -0.98674774 0.15637095 0.04332469, + -0.98800826 0.14593703 0.050419211, + -0.99362999 0.106514 0.036799099, + -0.99418646 0.099470846 0.041218217, + -0.99780875 0.061124984 0.025328694, + -0.99798 0.057227399 0.027586199, + -0.99976724 0.019436903 0.0093694422, + -0.99978334 0.018257707 0.0099999439, + -0.99976921 -0.018842403 -0.010320202, + -0.99978274 -0.017812395 -0.010827797, + -0.99785924 -0.055883616 -0.033970509, + -0.99796087 -0.053276893 -0.035153296, + -0.99385488 -0.092391491 -0.060961992, + -0.99406064 -0.089249268 -0.062274177, + -0.98727202 -0.130429 -0.091007203, + -0.98749864 -0.12804796 -0.091924071, + -0.97725224 -0.17228304 -0.12368003, + -0.97715074 -0.17305395 -0.12340497, + -0.96241778 -0.22111194 -0.15767495, + -0.96108878 -0.22853895 -0.15517198, + -0.9399991 -0.28226304 -0.19164903, + -0.9400925 -0.28186384 -0.19177791, + -0.91178113 -0.33953702 -0.23101903, + -0.90637159 -0.35744083 -0.2252259, + -0.86730289 -0.42114794 -0.26536798, + -0.84727889 -0.46934694 -0.24865997, + -0.7921828 -0.53927487 -0.28570795, + -0.76611489 -0.58448392 -0.26729497, + -0.69521308 -0.65369004 -0.29894504, + -0.65628082 -0.70325381 -0.27336693, + -0.57169062 -0.76472551 -0.29726183, + -0.51660383 -0.81546569 -0.26102892, + -0.47273088 -0.83925885 -0.26864493, + -0.54224211 -0.77793521 -0.31747508, + -0.51139683 -0.79563969 -0.32470089, + -0.60767031 -0.68828434 -0.39623418, + -0.58698386 -0.70163882 -0.4039219, + -0.46176574 -0.83239454 -0.30641782, + -0.49224424 -0.81686842 -0.30070215, + -0.37908584 -0.89933169 -0.21793692, + -0.36167592 -0.90607876 -0.21957193, + -0.44244912 -0.85144019 -0.28158206, + -0.41334599 -0.86452401 -0.28590801, + -0.534468 -0.75269097 -0.38444799, + -0.51450211 -0.76364517 -0.39004308, + -0.45914921 -0.81122935 -0.36206219, + -0.59025496 -0.65067494 -0.47772494, + -0.56041193 -0.66759992 -0.49015194, + -0.43362308 -0.82176119 -0.3697021, + -0.4602952 -0.80960637 -0.36423317, + -0.32018697 -0.91669285 -0.23906997, + -0.34657112 -0.9076643 -0.23671509, + -0.25870895 -0.95213276 -0.16282795, + -0.24694991 -0.95775664 -0.14736994, + -0.249037 -0.95693898 -0.149159, + -0.32702109 -0.93374223 -0.14554302, + -0.37559009 -0.90834022 -0.18398404, + -0.46118379 -0.86964458 -0.17614691, + -0.50743085 -0.8354128 -0.21118596, + -0.59291679 -0.78070468 -0.19735692, + -0.64328599 -0.72841001 -0.235801, + -0.71868163 -0.66153967 -0.2141539, + -0.73842663 -0.63381672 -0.2302229, + -0.80082083 -0.5629189 -0.20447096, + -0.80691785 -0.55209386 -0.20994295, + -0.85780698 -0.48041001 -0.182684, + -0.87030715 -0.45189807 -0.19584103, + -0.8668704 -0.4651652 -0.17932409, + -0.90965289 -0.38756695 -0.14940998, + -0.91244286 -0.37938294 -0.15335098, + -0.9401651 -0.31588903 -0.12768601, + -0.94028085 -0.31545997 -0.12789398, + -0.96104062 -0.25615591 -0.10385096, + -0.96013278 -0.26037294 -0.10173998, + -0.97563386 -0.20435797 -0.079852395, + -0.97455275 -0.21068795 -0.076534785, + -0.98594779 -0.15701495 -0.057037484, + -0.98504275 -0.16387896 -0.053239889, + -0.99299455 -0.11237895 -0.036509082, + -0.99242491 -0.11833298 -0.033017695, + -0.99748045 -0.068332829 -0.01906641, + -0.99723309 -0.072490208 -0.016476601, + -0.9997189 -0.023120698 -0.0052551897, + -0.99968725 -0.024648406 -0.0042433809, + -0.99970651 0.023876589 0.0041104881, + -0.99966913 0.025556805 0.0029260002, + -0.99713385 0.075166292 0.008605809, + -0.99674052 0.080545262 0.0045637279, + -0.99139225 0.13071603 0.007406442, + -0.99011409 0.14026402 -0.00026081203, + -0.98151636 0.19137807 -0.0003558571, + -0.97913176 0.20296295 -0.010344797, + -0.96701354 0.25439489 -0.012966193, + -0.96579951 0.25873187 -0.017000092, + -0.95124978 0.30775794 -0.020221394, + -0.94960034 0.31246713 -0.024973409, + -0.93276662 0.35933489 -0.028719289, + -0.93014622 0.36547008 -0.035492409, + -0.91101426 0.41044408 -0.039860111, + -0.9074434 0.41738722 -0.048315521, + -0.88611197 0.46039701 -0.0532941, + -0.88157469 0.46777883 -0.063316479, + -0.8584013 0.50834316 -0.068807125, + -0.85278088 0.51601696 -0.080567993, + -0.82793415 0.55411208 -0.086515911, + -0.82117814 0.56182903 -0.10007402, + -0.79450917 0.5978421 -0.10648903, + -0.7865231 0.60538805 -0.12201101, + -0.75819999 0.63916999 -0.12882, + -0.74958581 0.64578283 -0.14520897, + -0.72009903 0.67696804 -0.15222201, + -0.71142417 0.68224818 -0.16856204, + -0.68064672 0.71122563 -0.17572191, + -0.67047131 0.71589637 -0.1948351, + -0.63829672 0.74277365 -0.20214991, + -0.62712222 0.74626023 -0.22318907, + -0.59373671 0.77091962 -0.23056389, + -0.5818727 0.77289164 -0.25310588, + -0.54790282 0.79499871 -0.26034492, + -0.53548509 0.79524809 -0.28431702, + -0.5010938 0.81487972 -0.2913349, + -0.48825213 0.81321418 -0.31669009, + -0.45361206 0.83045012 -0.32340202, + -0.44065073 0.8267135 -0.3498168, + -0.40563914 0.8417753 -0.35619012, + -0.40676206 0.84226215 -0.35375002, + -0.37499502 0.85470212 -0.35897502, + -0.38735795 0.8616389 -0.32792097, + -0.3537409 0.87417585 -0.33269191, + -0.36394098 0.88112485 -0.30193698, + -0.32845604 0.89351511 -0.30618203, + -0.33669785 0.90033358 -0.27574289, + -0.29895994 0.91243178 -0.27944794, + -0.30552098 0.91903889 -0.24904697, + -0.26634508 0.93032438 -0.25210509, + -0.27140608 0.93657935 -0.22171608, + -0.23070505 0.94685423 -0.22414806, + -0.23446307 0.95260924 -0.19381104, + -0.192422 0.96161199 -0.19564299, + -0.19505502 0.96675414 -0.16534801, + -0.15170003 0.97427922 -0.16663505, + -0.15341099 0.97872788 -0.13622299, + -0.10952204 0.98449433 -0.13702504, + -0.11050196 0.98815966 -0.10644196, + -0.066348881 0.99205762 -0.10686196, + -0.066789426 0.99484938 -0.076249726, + -0.022478195 0.99682379 -0.076400988, + -0.022576701 0.998694 -0.045832802, + 0.021906598 0.9987089 -0.045833495, + 0.066200085 0.99489075 -0.076223187, + 0.065758906 0.99210614 -0.10677701, + 0.11005604 0.98821837 -0.10635903, + 0.10906995 0.98454952 -0.13698894, + 0.15302502 0.97879314 -0.13618901, + 0.15130003 0.97432923 -0.16670604, + 0.19462596 0.96682775 -0.16542296, + 0.19197491 0.96166551 -0.19581892, + 0.2340261 0.95268047 -0.19398908, + 0.23027401 0.94692498 -0.224292, + 0.27074203 0.93673313 -0.22187804, + 0.26567698 0.93049687 -0.25217298, + 0.30495799 0.91920799 -0.24911299, + 0.29842687 0.91263872 -0.27934191, + 0.33624503 0.90053511 -0.27563703, + 0.32804808 0.89376324 -0.30589506, + 0.36376813 0.88130128 -0.30163011, + 0.35367787 0.8744337 -0.33208087, + 0.38747093 0.8618269 -0.32729298, + 0.3751941 0.85495317 -0.3581681, + 0.40720078 0.84240258 -0.35290983, + 0.4057079 0.84175783 -0.35615292, + 0.44057989 0.82675582 -0.34980592, + 0.45367095 0.83051986 -0.32313997, + 0.48844489 0.81320983 -0.31640393, + 0.50134015 0.81487328 -0.29092908, + 0.53565609 0.79527116 -0.28393006, + 0.54805589 0.79500884 -0.25999194, + 0.58212966 0.77281952 -0.25273484, + 0.59387314 0.7708602 -0.23041105, + 0.62728196 0.74617296 -0.22303197, + 0.63823283 0.74275684 -0.20241295, + 0.67037976 0.71591073 -0.19509692, + 0.68043458 0.71130461 -0.17622289, + 0.71112609 0.68243307 -0.16907002, + 0.72008467 0.67698568 -0.15221192, + 0.74960995 0.64575893 -0.14519098, + 0.75843072 0.63898075 -0.12839895, + 0.78677785 0.60513991 -0.12159899, + 0.79480499 0.59754002 -0.105976, + 0.8214463 0.5615232 -0.099588238, + 0.82820129 0.55379117 -0.086011231, + 0.85305232 0.51564318 -0.080086328, + 0.85863799 0.50800103 -0.068380304, + 0.88177198 0.46746001 -0.0629232, + 0.88622421 0.46020612 -0.053075612, + 0.90754932 0.41718015 -0.048113517, + 0.91099888 0.41046995 -0.039941598, + 0.93012178 0.36552492 -0.035568193, + 0.93264401 0.359626 -0.029058799, + 0.94950724 0.31272608 -0.025269106, + 0.95110822 0.30816606 -0.020664506, + 0.96568835 0.2591221 -0.017375706, + 0.96698189 0.25450897 -0.013086598, + 0.97910821 0.20307204 -0.010441802, + 0.98159713 0.19096403 -6.1875908e-006, + 0.99015933 0.13994505 -4.5344818e-006, + 0.9914391 0.13034202 0.0077097011, + 0.99675989 0.080294393 0.0047494094, + 0.99714565 0.074995272 0.0087314975, + 0.99967051 0.025496487 0.0029684885, + 0.99970686 0.023858696 0.0041231294, + 0.99968755 -0.02462999 -0.004256418, + 0.99971867 -0.023133092 -0.005247748, + 0.99723047 -0.07253094 -0.016453708, + 0.99747586 -0.068411991 -0.019019399, + 0.99240988 -0.11848099 -0.032938994, + 0.99297535 -0.11258504 -0.036395811, + 0.98500079 -0.16418396 -0.05307639, + 0.98590434 -0.15735306 -0.056856118, + 0.97447038 -0.21115507 -0.076296233, + 0.97555691 -0.20481597 -0.07961899, + 0.95999837 -0.2609801 -0.10145204, + 0.9609009 -0.25680396 -0.10354298, + 0.94006789 -0.31624898 -0.12751098, + 0.93984926 -0.31705508 -0.12712003, + 0.91195029 -0.38083115 -0.15269005, + 0.90908241 -0.38919216 -0.14865607, + 0.87184483 -0.45754188 -0.17476295, + 0.8648814 -0.47343424 -0.16685407, + 0.8163349 -0.54473794 -0.19198397, + 0.089628391 -0.99548388 -0.031282496, + 0.090151958 -0.9954195 -0.031823784, + 0.14621998 -0.98874688 -0.031610396, + 0.18126595 -0.98133373 -0.064240187, + 0.24979612 -0.96623045 -0.063251533, + 0.292162 -0.95117003 -0.0995837, + 0.37126812 -0.92347836 -0.096684538, + 0.425033 -0.89421201 -0.14047, + 0.50975084 -0.84989971 -0.13350895, + 0.52720481 -0.83684969 -0.14743695, + 0.61017311 -0.7802512 -0.13746603, + 0.6420058 -0.74911982 -0.16324195, + 0.70103824 -0.69677222 -0.15183505, + 0.74740398 -0.63619298 -0.191431, + 0.79729229 -0.57799417 -0.17391907, + 0.79718685 -0.57818693 -0.17376098, + 0.73454058 -0.64985263 -0.19529888, + 0.71143019 -0.68037218 -0.17595704, + 0.63590872 -0.74718165 -0.19323491, + 0.62010109 -0.7634272 -0.18070304, + 0.53668791 -0.82109284 -0.19435196, + 0.48283613 -0.86237419 -0.15225004, + 0.39765808 -0.90356022 -0.15952104, + 0.3504619 -0.92864174 -0.12165897, + 0.27184302 -0.95418811 -0.12500602, + 0.229644 -0.96920902 -0.088868201, + 0.16219805 -0.98263621 -0.090099424, + 0.16337901 -0.98233813 -0.091209508, + 0.39774406 -0.84970909 -0.34611303, + 0.53379089 -0.69739282 -0.47823688, + 0.50426304 -0.71218306 -0.48837906, + 0.37268507 -0.8591572 -0.35064909, + 0.39800775 -0.84936553 -0.34665281, + 0.25434506 -0.94504821 -0.20540805, + 0.27775407 -0.93873423 -0.20403604, + 0.17620106 -0.97817135 -0.11015504, + 0.18537395 -0.97649562 -0.10996696, + 0.32081512 -0.91899538 -0.22918409, + 0.29555595 -0.92693573 -0.23116393, + 0.45094994 -0.8090229 -0.37699595, + 0.46966717 -0.80022532 -0.37289712, + 0.46830389 -0.80220979 -0.37033892, + 0.59232676 -0.64725876 -0.47979683, + 0.54667515 -0.67268217 -0.49864313, + 0.62680209 -0.52312207 -0.57746208, + 0.58294928 -0.54549927 -0.60216331, + 0.63734192 -0.39490494 -0.66169894, + 0.59541273 -0.41173381 -0.68989766, + 0.63202083 -0.24752094 -0.73435885, + 0.59051198 -0.25776699 -0.76475602, + 0.60956275 -0.059380177 -0.79051071, + 0.61320031 -0.052897025 -0.78815436, + 0.61405873 0.0020384693 -0.78925771, + 0.57325292 -0.0030341996 -0.81937289, + 0.57127011 -0.08317142 -0.8165372, + 0.57157713 -0.083152525 -0.81632417, + 0.57356071 -0.0029738387 -0.8191576, + 0.55822593 -0.015723998 -0.8295399, + 0.46988499 -0.015869699 -0.88258499, + 0.35819808 0.93364525 0.00085147715, + 0.358215 0.93356198 -0.0120031, + 0.3582409 0.93362874 0.0008514768, + 0.31202111 0.95007336 -0.0018937207, + 0.3119761 0.94993937 -0.016920205, + 0.31201097 0.94992787 -0.016919998, + 0.31205505 0.95006222 -0.0018901405, + -0.073566914 -0.99729025 -0.0003941771, + -0.073563367 -0.99724162 0.0098830359, + -0.073505782 -0.99724579 0.0098830974, + -0.07350944 -0.99729449 -0.00039641417, + -0.051477317 -0.99866635 -0.0039680316, + 0.029028488 -0.99951667 0.011128697, + 0.029030314 -0.99957848 -0.00045802322, + 0.028964112 -0.99958038 -0.00044912516, + 0.028962286 -0.99951851 0.011128695, + 0.022412308 -0.99957937 0.018407308, + 0.022379695 -0.99870974 0.045584589, + -0.022010298 -0.9987179 0.045584895, + -0.02204649 -0.99968451 0.012033395, + -0.024543196 -0.99958289 0.015218098, + 0.0028998298 -0.9998799 0.015222598, + 0.0029001692 -0.99999577 0, + -0.024546094 -0.99969876 0, + -0.024371 -0.99970299 2.3548801e-005, + -0.024369191 -0.99963063 0.012032595, + -0.06725271 -0.9975881 0.017179701, + -0.06715522 -0.99671239 0.045328416, + -0.021880008 -0.99872833 0.045420114, + -0.021813298 -0.9968769 0.075898893, + 0.022363195 -0.99686474 0.075897887, + 0.022432789 -0.99870551 0.045651779, + 0.06748049 -0.9966799 0.045559198, + 0.067575894 -0.99752885 0.019227598, + 0.076659873 -0.99701262 0.0094445366, + 0.076725937 -0.99700749 0.0094444649, + 0.07672929 -0.99705189 -0.00013069199, + 0.076663397 -0.99705702 -0.000133255, + 0.051477309 -0.99866623 -0.0039770207, + -0.17087506 -0.98529238 -0.00086399232, + -0.17091393 -0.98528564 -0.0008612817, + -0.17091 -0.98526001 0.0072498, + -0.17087096 -0.98526675 0.0072498983, + -0.15861894 -0.98714167 0.019780893, + -0.15841506 -0.98637533 0.044367116, + -0.11235099 -0.99266487 0.044649996, + -0.112005 -0.99085999 0.075176001, + -0.066639684 -0.99491775 0.075483888, + -0.066328108 -0.9921481 0.10603201, + -0.021587102 -0.99410611 0.10624102, + -0.021449793 -0.99037564 0.13673295, + 0.022107789 -0.99036151 0.13673094, + 0.022248693 -0.99409163 0.10623996, + 0.066972822 -0.99210536 0.10602704, + 0.067287393 -0.99485689 0.07571169, + 0.11256604 -0.99077934 0.075401329, + 0.11290997 -0.99256378 0.045480687, + 0.1587529 -0.98628342 0.045192875, + 0.15895006 -0.98703736 0.022186408, + 0.17397305 -0.98475033 -0.00055474817, + 0.17396691 -0.98471755 0.0081794262, + 0.17399104 -0.98471326 0.0081793619, + 0.17399701 -0.9847461 -0.00055304903, + -0.86979669 -0.49334282 0.0081551475, + -0.8697899 -0.49335495 0.0081554092, + -0.82496589 -0.56500095 0.014321298, + -0.81731129 -0.57619619 -0.00041802015, + -0.8173098 -0.5761959 0.0017139196, + -0.81730282 -0.57620591 0.0017140096, + -0.81730384 -0.57620686 -0.00041751491, + -0.99972963 0.023092192 -0.0027235691, + -0.51252884 -0.66212076 0.54672682, + -0.42037299 -0.69965899 0.57772303, + -0.38024607 -0.69474703 0.61052406, + -0.31834498 -0.71209097 0.62576592, + -0.27755606 -0.70220619 0.65564418, + -0.22225787 -0.71264261 0.66538858, + -0.21547 -0.71032202 0.67008603, + -0.16679704 -0.71721816 0.67659217, + -0.16566396 -0.71673983 0.67737681, + -0.12314397 -0.72125083 0.68163985, + -0.12200803 -0.72068018 0.6824472, + -0.085222393 -0.72346294 0.68508291, + -0.085179172 -0.72343779 0.68511474, + -0.053551793 -0.72503495 0.68662691, + -0.054274134 -0.72551841 0.68605942, + -0.027699299 -0.72631001 0.686809, + -0.029772311 -0.72788626 0.68505126, + -0.0075524691 -0.72818792 0.68533593, + -0.010326197 -0.73057079 0.68275881, + 0.0082569895 -0.73058492 0.68277192, + 0.005885181 -0.73288405 0.68032807, + 0.020386299 -0.73274398 0.68019903, + 0.018016709 -0.73534334 0.67745531, + 0.028737707 -0.73515916 0.67728519, + 0.022260688 -0.74320465 0.66869372, + 0.0311053 -0.743029 0.66853601, + 0.024696484 -0.75209254 0.65859461, + 0.031559516 -0.75194734 0.65846729, + 0.026190801 -0.76072299 0.64854801, + 0.031122796 -0.76061487 0.64845693, + 0.026134999 -0.77023703 0.63722199, + 0.024318585 -0.78052551 0.62465066, + 0.028719082 -0.77018255 0.63717663, + -0.023363888 -0.72944462 0.68364072, + 0.99711466 0.075832069 -0.0034489189, + 0.51552415 -0.67640918 0.5260281, + 0.56738973 -0.6500237 0.50550777, + 0.59732038 -0.65120441 0.46812525, + 0.64904618 -0.61770713 0.44404611, + 0.67353207 -0.61549807 0.40928805, + 0.72257519 -0.57564014 0.3827841, + 0.74169993 -0.57125396 0.35149696, + 0.78645164 -0.52604675 0.32367986, + 0.80072552 -0.52058172 0.29636681, + 0.84039509 -0.47099707 0.26813802, + 0.85057509 -0.46531206 0.24496303, + 0.88464868 -0.41257784 0.21720092, + 0.89156067 -0.40727785 0.19810192, + 0.92586958 -0.33978084 0.16527092, + 0.920968 -0.35364401 0.16356599, + 0.94552189 -0.29548398 0.13666598, + 0.95032185 -0.28899297 0.11563499, + 0.96799576 -0.23300594 0.093232878, + 0.97038287 -0.22858398 0.078143694, + 0.98278838 -0.17480306 0.059758123, + 0.98384464 -0.17204694 0.049493682, + 0.99203974 -0.12101697 0.034813594, + 0.99243462 -0.11946996 0.028292891, + 0.99735314 -0.070752509 0.016755601, + 0.99745715 -0.070036009 0.013199802, + 0.99972802 -0.022918399 0.0043194699, + 0.99973613 -0.022742203 0.0032368805, + 0.99973899 0.0226181 -0.0032192201, + 0.99974447 0.022497611 -0.0022342713, + 0.99766266 0.067996681 -0.0067528677, + 0.99769253 0.067774668 -0.0040150881, + 0.99355203 0.113179 -0.0067049302, + 0.99360067 0.11294597 -0.00089569762, + 0.98486477 0.17322396 -0.0059038685, + 0.98728675 0.15894195 -0.0015341697, + 0.99219036 0.12464204 -0.004761592, + 0.99217778 0.12474197 -0.0047637592, + 0.99218589 0.12474298 -0.0025230597, + 0.99712014 0.075832605 0.00090480014, + 0.92169738 -0.37057012 0.11468104, + 0.94286275 -0.31828791 0.09850128, + 0.9458279 -0.31467798 0.079920694, + 0.96225977 -0.26375893 0.066988386, + 0.96383476 -0.26124993 0.052639488, + 0.97640234 -0.21170507 0.042656817, + 0.97715878 -0.21010695 0.031872593, + 0.98654276 -0.16165395 0.024522394, + 0.98684466 -0.16077794 0.016972095, + 0.99342674 -0.11383697 0.012016897, + 0.99351847 -0.11344706 0.0071299234, + 0.99770111 -0.06763491 0.0042507006, + 0.997715 -0.067537397 0.00185341, + 0.99746567 -0.071147777 0.00048284684, + 0.99746335 -0.071147725 -0.0021972808, + 0.99963897 0.0267101 -0.0029139, + 0.99966425 0.025738705 -0.0030083808, + 0.99963814 0.026899103 -6.675961e-005, + 0.99963289 0.026898896 -0.0032539996, + 0.99976212 -0.021793703 0.00085362012, + 0.99976248 -0.021793712 4.8894924e-007, + 0.99975353 -0.022202689 9.7476759e-006, + 0.99975312 -0.022202702 0.00088522414, + 0.99975502 -0.0221151 0.00088522403, + 0.99975187 -0.022257898 0.00087705691, + 0.99975234 -0.022257907 4.0406016e-005, + 0.99975538 -0.022115188 3.7126178e-005, + 0.99975276 -0.022237794 1.8636396e-005, + 0.99975049 -0.022293711 0.0013799907, + 0.99769109 -0.067786105 0.0041960003, + 0.99765903 -0.068018898 0.0070668198, + 0.99337953 -0.11426394 0.011871395, + 0.9932301 -0.11489201 0.017140402, + 0.98640722 -0.16252105 0.024245905, + 0.98596323 -0.16378304 0.032431409, + 0.97609651 -0.2131979 0.042216282, + 0.97506613 -0.21531902 0.053701907, + 0.96166688 -0.26606998 0.06635949, + 0.95958 -0.269292 0.081780203, + 0.94182199 -0.32160899 0.097668096, + 0.91472256 -0.37997183 0.13749194, + 0.93790662 -0.32618988 0.11803096, + 0.0117774 -0.69792098 0.71607798, + -0.017046701 -0.66603905 0.74572206, + -0.026090594 -0.66590881 0.7455768, + -0.017020091 -0.69814956 0.71574956, + -0.019182498 -0.69812196 0.71572196, + -0.012462505 -0.73027438 0.68304032, + -0.012128104 -0.73027724 0.68304324, + -0.0079760831 -0.76208133 0.64743227, + -0.0042849584 -0.76209867 0.64744669, + -0.0028828792 -0.79336083 0.60874486, + 0.0027571302 -0.79336113 0.60874504, + 0.0041871895 -0.76210487 0.64743996, + 0.0078624533 -0.76208836 0.64742529, + 0.012032102 -0.73036504 0.68295103, + 0.012252394 -0.73036265 0.68294972, + 0.019056901 -0.69784307 0.71599704, + 0.017460598 -0.62802297 0.77799886, + 0.0261855 -0.62790298 0.77785099, + 0.017246801 -0.66136605 0.74986506, + 0.019230301 -0.66134202 0.74983799, + 0.012606602 -0.69475806 0.71913308, + 0.011780703 -0.69476515 0.71914017, + 0.0075940071 -0.72843975 0.68506777, + 0.0040091695 -0.72845495 0.68508196, + 0.0025737698 -0.76146591 0.64819992, + -0.0026868586 -0.76146567 0.64819968, + -0.0040949979 -0.7284106 0.68512857, + -0.0077878055 -0.72839457 0.68511361, + -0.011927998 -0.69502991 0.71888196, + -0.012696604 -0.69502324 0.71887523, + -0.0193896 -0.66122502 0.749937, + -0.017220503 -0.66125107 0.74996704, + -0.026203703 -0.62753403 0.77814811, + -0.017694997 -0.6276508 0.77829385, + -0.021903589 -0.6244787 0.78073466, + -0.027467307 -0.62439311 0.78062719, + -0.032223493 -0.61290687 0.78949779, + -0.028914392 -0.61296886 0.78957784, + -0.033773601 -0.60302502 0.79700702, + -0.028135192 -0.60313088 0.79714584, + -0.032991499 -0.59454399 0.80338597, + -0.025132591 -0.59467977 0.80356967, + -0.02968711 -0.58762825 0.8085863, + -0.019206392 -0.58777875 0.80879372, + -0.017537095 -0.59005475 0.80717272, + 0.011806798 -0.59010392 0.8072409, + 0.044564091 -0.62858784 0.77646083, + 0.066029087 -0.6278398 0.77553684, + 0.094657555 -0.65620768 0.74861962, + 0.12248904 -0.65420425 0.74633324, + 0.15173407 -0.67863429 0.71863234, + 0.18427798 -0.67482597 0.71459895, + 0.21328114 -0.69506443 0.6865834, + 0.25103608 -0.68865222 0.68024921, + 0.27816805 -0.70423317 0.65320617, + 0.31974608 -0.69468117 0.64434516, + 0.3444601 -0.70606416 0.61872512, + 0.38932419 -0.69275236 0.6070593, + 0.418814 -0.703049 0.57473201, + 0.46648318 -0.68482226 0.55983216, + 0.49794018 -0.69216925 0.52245319, + 0.54742694 -0.66793895 0.50416392, + 0.57496518 -0.67108727 0.46803519, + 0.624717 -0.64047098 0.44668299, + 0.64787269 -0.64026672 0.41269779, + 0.69625884 -0.60331887 0.38888291, + 0.71493298 -0.60071802 0.35778299, + 0.75976962 -0.55861878 0.33270887, + 0.77418983 -0.55458486 0.30506694, + 0.81454486 -0.50827593 0.27959296, + 0.82524318 -0.5036211 0.25561607, + 0.86069316 -0.45399413 0.23042706, + 0.86829913 -0.44932905 0.21014303, + 0.89865923 -0.39734009 0.18582904, + 0.90564275 -0.39148292 0.16294895, + 0.93143213 -0.33597302 0.13984402, + 0.93660778 -0.33019891 0.11719397, + 0.95607936 -0.2762261 0.098038137, + 0.95883614 -0.27212402 0.081128411, + 0.97330689 -0.21994098 0.065571189, + 0.97467226 -0.21721305 0.05322231, + 0.98517686 -0.16661298 0.040824097, + 0.98578125 -0.16493705 0.032111209, + 0.99294275 -0.11640897 0.022663394, + 0.99316233 -0.11550404 0.016955605, + 0.99759012 -0.068646505 0.010077101, + 0.99764234 -0.068271421 0.0069847424, + 0.99974602 -0.022419199 0.0022936701, + 0.99974948 -0.022343012 0.0013626807, + 0.99975049 0.022293089 -0.0013596293, + 0.99974948 0.022311412 -0.0018053508, + 0.99964148 0.026710114 -0.001903471, + 0.99711353 0.075925462 -0.00012724694, + 0.99711311 0.07592541 0.00090249011, + 0.99711555 0.075892366 0.00090248958, + 0.99711013 0.075892009 -0.0034502305, + 0.99771249 0.067559533 -0.0023379512, + 0.99770224 0.067629717 -0.004064911, + 0.99974948 0.022341812 -0.0013428607, + 0.99974614 0.022416702 -0.0022592703, + 0.99974424 -0.022501405 0.0022678105, + 0.99973875 -0.022623995 0.0032694994, + 0.9975661 -0.069009908 0.0099729709, + 0.99748951 -0.06954997 0.013319193, + 0.99285126 -0.11722803 0.022449905, + 0.99255276 -0.11842997 0.028520992, + 0.9849419 -0.16807999 0.040478196, + 0.98414153 -0.17023793 0.049843878, + 0.97281033 -0.22227207 0.065079026, + 0.97100675 -0.22575393 0.078619681, + 0.95514566 -0.27966291 0.097393565, + 0.95149654 -0.28485885 0.11623095, + 0.92980623 -0.34077409 0.13904503, + 0.92458886 -0.34635997 0.15865098, + 0.89809513 -0.39985007 0.18315302, + 0.89212775 -0.40460593 0.20100296, + 0.86001372 -0.45698586 0.22702493, + 0.85123742 -0.46213421 0.24865012, + 0.81378168 -0.51179284 0.27536792, + 0.80143553 -0.51685172 0.30094081, + 0.7589798 -0.56268185 0.3276259, + 0.74239081 -0.56691688 0.35701692, + 0.69549978 -0.60800678 0.38289386, + 0.67412758 -0.61047465 0.41577977, + 0.62405121 -0.64582324 0.43985516, + 0.59775501 -0.64543903 0.47549701, + 0.54688698 -0.674043 0.49656901, + 0.51576996 -0.66976094 0.53422993, + 0.46606693 -0.69166791 0.55170393, + 0.43685907 -0.68426907 0.58389205, + 0.38896215 -0.70079422 0.59799325, + 0.36468396 -0.69202095 0.62298691, + 0.31931114 -0.70429736 0.63403928, + 0.29172617 -0.69132543 0.66103339, + 0.2504119 -0.69973677 0.66907579, + 0.22027211 -0.68204927 0.69734436, + 0.18332204 -0.68737316 0.70278817, + 0.15217806 -0.66516024 0.73102921, + 0.12101602 -0.66805208 0.73420805, + 0.08918532 -0.64086521 0.76245517, + 0.06397593 -0.6421113 0.76393735, + 0.027911913 -0.60537428 0.79545134, + -0.0068993666 -0.60559571 0.79574263, + -0.0096967779 -0.60228688 0.79822081, + -0.023001801 -0.60215604 0.79804713, + -0.018908396 -0.60762388 0.79399985, + -0.029463993 -0.6074689 0.79379684, + -0.024723111 -0.61462831 0.78842938, + -0.032903615 -0.6144833 0.78824335, + -0.028173083 -0.62264067 0.78200054, + -0.033744194 -0.6225329 0.78186584, + -0.028759396 -0.63248092 0.77404189, + -0.032233391 -0.6324138 0.77395982, + -0.027466012 -0.64363527 0.76483935, + -0.028618103 -0.64361507 0.76481414, + -0.022006106 -0.66247219 0.7487632, + -0.027126396 -0.66238892 0.74866897, + -0.032023586 -0.65114468 0.75827765, + -0.028685886 -0.65121073 0.75835466, + -0.033541992 -0.64175981 0.76617181, + -0.028010912 -0.64186931 0.76630235, + -0.032888893 -0.63366783 0.77290583, + -0.0247199 -0.63381702 0.77308798, + -0.029104996 -0.62736297 0.77818286, + -0.018749392 -0.62751877 0.77837569, + -0.022783987 -0.62227064 0.78247052, + -0.0090795392 -0.62240595 0.78264189, + -0.012738594 -0.61817068 0.78594065, + 0.0043649701 -0.61821502 0.78599697, + 0.0082250116 -0.62218112 0.78283018, + 0.048698489 -0.62146389 0.78192782, + 0.088034369 -0.65608174 0.74953777, + 0.11758894 -0.65406972 0.74723864, + 0.15159799 -0.67895395 0.71835893, + 0.18688905 -0.67479026 0.71395421, + 0.22004607 -0.69474024 0.68477422, + 0.26116693 -0.68747884 0.67761683, + 0.29168695 -0.70219582 0.64949185, + 0.33729219 -0.69110042 0.63922936, + 0.36468112 -0.70125026 0.61258125, + 0.41336921 -0.68575931 0.59904927, + 0.4367801 -0.69197315 0.57480115, + 0.48690981 -0.67188376 0.55811381, + 0.486774 -0.666623 0.56450403, + 0.41371906 -0.69476503 0.58833504, + 0.38725108 -0.68753117 0.61427814, + 0.33778998 -0.70188391 0.62710196, + 0.30716512 -0.69020623 0.65518326, + 0.26165912 -0.70000035 0.66448027, + 0.227523 -0.68306398 0.69401503, + 0.18719395 -0.68906176 0.70010877, + 0.15143196 -0.66693485 0.7295658, + 0.11746203 -0.6700452 0.73296815, + 0.074825302 -0.63781899 0.76654297, + 0.028306592 -0.63935584 0.76838982, + 0.023026899 -0.63465697 0.77245086, + 0.0024069403 -0.63482404 0.7726531, + 0.0052649002 -0.63769501 0.770271, + -0.011978204 -0.63765824 0.7702263, + -0.008418018 -0.64166981 0.76693481, + -0.022496402 -0.64153004 0.7667681, + -0.018229203 -0.64693516 0.76232719, + -0.029245611 -0.64676523 0.76212829, + -0.024904706 -0.65298516 0.75696117, + -0.032790404 -0.65283608 0.75678915, + -0.027934209 -0.66078722 0.75005329, + -0.033660188 -0.66067076 0.74992079, + -0.028671717 -0.6701194 0.7416994, + -0.031884007 -0.6700542 0.74162716, + -0.026669094 -0.68169981 0.7311458, + -0.028254399 -0.68167001 0.73111397, + -0.021575695 -0.69968879 0.71412182, + -0.026747797 -0.69960093 0.71403295, + -0.031501107 -0.6892882 0.72380215, + -0.028112484 -0.68935758 0.72387558, + -0.033589214 -0.67927331 0.73311633, + -0.0276691 -0.67939699 0.73324901, + -0.032664586 -0.67143571 0.74034262, + -0.024504997 -0.67159194 0.74051595, + -0.029189492 -0.6650548 0.74622381, + -0.018185498 -0.66522896 0.74641794, + -0.021935102 -0.66060507 0.75041312, + -0.0080638295 -0.66074294 0.75056887, + -0.011366499 -0.65712494 0.75369591, + 0.0060717063 -0.65715557 0.75373054, + 0.0033511894 -0.65450191 0.75605285, + 0.024467211 -0.65431029 0.75583035, + 0.022287192 -0.65241778 0.7575317, + 0.047702912 -0.65183717 0.75685716, + 0.053915583 -0.65659976 0.75230968, + 0.10733899 -0.65375692 0.74905294, + 0.15237497 -0.68267781 0.71465582, + 0.19129696 -0.67798692 0.70974594, + 0.22870408 -0.69716024 0.67945725, + 0.27376804 -0.68878108 0.67129105, + 0.30832189 -0.70241177 0.64152575, + 0.35809591 -0.68941784 0.62965882, + 0.38819194 -0.69793797 0.60182196, + 0.44127527 -0.67960542 0.58601433, + 0.46956611 -0.68454117 0.55759412, + 0.53664714 -0.65423316 0.53290612, + 0.56725895 -0.65618193 0.49763694, + 0.62048113 -0.62485415 0.47387812, + 0.64867377 -0.62306976 0.43704286, + 0.69993162 -0.58470869 0.41013581, + 0.72202981 -0.58024889 0.3768079, + 0.76921564 -0.53590578 0.34801182, + 0.78581846 -0.53002167 0.31869477, + 0.82793701 -0.480627 0.288995, + 0.83976531 -0.47437617 0.2641241, + 0.87604231 -0.42132914 0.23458809, + 0.88408715 -0.41541806 0.21405102, + 0.91402727 -0.36059812 0.18580405, + 0.91518879 -0.35392791 0.19278096, + 0.87549657 -0.42435679 0.23114289, + 0.86608082 -0.4309569 0.25333795, + 0.8273657 -0.48419881 0.2846359, + 0.8134622 -0.49110311 0.31160405, + 0.76870871 -0.54006082 0.34266788, + 0.74939102 -0.54631501 0.37410301, + 0.699588 -0.58956498 0.40371999, + 0.67379797 -0.59400392 0.43949494, + 0.62040526 -0.63047326 0.46647719, + 0.5930149 -0.6315158 0.49952087, + 0.52403909 -0.66798818 0.52837014, + 0.49889219 -0.66606522 0.5544942, + 0.44250211 -0.68920118 0.57375413, + 0.41392595 -0.68389392 0.60079491, + 0.35978308 -0.70096719 0.61579311, + 0.32588515 -0.69094837 0.64528227, + 0.27577192 -0.70250577 0.65607578, + 0.23762691 -0.68686378 0.68684179, + 0.19332708 -0.69377834 0.69375533, + 0.14663701 -0.66882008 0.72881907, + 0.085623927 -0.67364621 0.73407722, + 0.078422904 -0.66894305 0.73916507, + 0.048357692 -0.67022496 0.74058092, + 0.049513012 -0.67108619 0.73972416, + 0.023856714 -0.67171943 0.74042141, + 0.02556281 -0.67315423 0.73906022, + 0.0042574811 -0.67336816 0.73929518, + 0.0066392822 -0.67562425 0.73721623, + -0.010909996 -0.67559874 0.73718876, + -0.007694908 -0.67902285 0.7340768, + -0.021926299 -0.67887992 0.73392195, + -0.017822998 -0.68380094 0.72945094, + -0.0288516 -0.68362498 0.72926301, + -0.024217604 -0.68991303 0.72348708, + -0.032364804 -0.68975407 0.72332007, + -0.026997009 -0.69807124 0.71551925, + -0.032845996 -0.69794893 0.71539396, + -0.0279007 -0.70680398 0.70685899, + -0.031389315 -0.70673138 0.70678538, + -0.026314404 -0.71744007 0.69612306, + -0.02806 -0.71740597 0.69608998, + -0.017070204 -0.70276821 0.71121418, + -0.026010796 -0.70263296 0.71107692, + -0.018038401 -0.72952509 0.68371606, + -0.011933098 -0.73372585 0.67934084, + -0.019895094 -0.7336328 0.67925483, + -0.013168407 -0.76407737 0.64499032, + -0.0128739 -0.76407999 0.64499301, + -0.0087496955 -0.79399347 0.60786337, + -0.0046445108 -0.79401517 0.60788012, + -0.0032623892 -0.82310981 0.56787288, + 0.0032224695 -0.82310987 0.56787294, + 0.0046264399 -0.794056 0.60782701, + 0.0086157899 -0.79403502 0.60781097, + 0.012771297 -0.7640928 0.64497983, + 0.012812398 -0.76409286 0.64497894, + 0.01955099 -0.73366064 0.67923468, + 0.011615601 -0.73375106 0.67931908, + -0.44017205 -0.67419606 0.59305006, + -0.359184 -0.70074099 0.6164, + -0.32574692 -0.69084483 0.64546281, + -0.27566203 -0.70238805 0.65624803, + -0.23794003 -0.68692404 0.68667305, + -0.19360803 -0.69385403 0.69360107, + -0.15161206 -0.67152524 0.72530526, + -0.11414199 -0.67493892 0.72899193, + -0.079474419 -0.65213317 0.75392717, + -0.049778879 -0.65339172 0.75538164, + -0.047291666 -0.65147752 0.75719249, + -0.022242002 -0.65204608 0.75785309, + -0.024102896 -0.65366292 0.7564019, + -0.0030751796 -0.65384996 0.7566179, + -0.0060524191 -0.65675592 0.75407887, + 0.011560595 -0.65672368 0.75404263, + 0.0079428162 -0.66068673 0.75061965, + 0.021813601 -0.66055006 0.7504651, + 0.017555904 -0.66579616 0.74592716, + 0.028847508 -0.66562116 0.74573219, + 0.023849403 -0.67258108 0.73963904, + 0.032108393 -0.67242581 0.7394678, + 0.027142886 -0.68031973 0.73241264, + 0.028384216 -0.68896741 0.72423643, + 0.033155102 -0.68019605 0.73228008, + -0.487039 -0.66634899 0.56459898, + -0.41346991 -0.69468385 0.58860588, + -0.38660783 -0.68732673 0.61491168, + -0.33719015 -0.70163035 0.62770832, + -0.30666098 -0.68996996 0.65566796, + -0.26121196 -0.69972897 0.66494197, + -0.22742587 -0.68295556 0.69415361, + -0.18713506 -0.68894422 0.70024025, + -0.15163101 -0.66698009 0.72948307, + -0.11765201 -0.67009604 0.73289108, + -0.079989567 -0.64175874 0.76272368, + -0.0531861 -0.64291102 0.76409203, + -0.024689296 -0.61736292 0.78629088, + -0.0037883294 -0.61754692 0.78652489, + -0.0041398997 -0.61790997 0.7862379, + 0.012616803 -0.6178661 0.78618217, + 0.0092405844 -0.62177628 0.78314036, + 0.022891592 -0.62163979 0.7829687, + 0.018611901 -0.62721097 0.77862698, + 0.029462405 -0.62704706 0.77842414, + 0.024671089 -0.63409472 0.77286166, + 0.032520313 -0.63395226 0.77268827, + 0.027591508 -0.64223015 0.76601517, + 0.033403613 -0.64211625 0.76587927, + 0.028327404 -0.65197504 0.75771111, + 0.031728201 -0.65190798 0.75763398, + 0.023300199 -0.67110193 0.74099892, + 0.028218897 -0.67101693 0.74090493, + 0.033299197 -0.66141796 0.74927795, + 0.027260603 -0.66153908 0.74941504, + 0.032372091 -0.65318185 0.75650883, + 0.024474088 -0.65332872 0.75667864, + 0.029090712 -0.64671922 0.7621733, + 0.018102 -0.646887 0.762371, + 0.022420403 -0.64141905 0.76686311, + 0.0086614415 -0.6415562 0.7670272, + 0.012239804 -0.63752526 0.77033228, + -0.0049372585 -0.63756484 0.7703808, + -0.0021463695 -0.63476181 0.77270484, + -0.022983806 -0.63459617 0.77250218, + -0.0239738 -0.63547999 0.77174503, + -0.049125399 -0.63489503 0.77103502, + -0.080451235 -0.65908128 0.74775636, + -0.112359 -0.65703702 0.74543798, + -0.15259402 -0.68275106 0.71453905, + -0.19155705 -0.67804819 0.7096172, + -0.228605 -0.697034 0.67962003, + -0.27365804 -0.68866205 0.67145807, + -0.30780986 -0.70214564 0.64206272, + -0.35750404 -0.68920404 0.63022906, + -0.38754219 -0.69772935 0.60248232, + -0.44085994 -0.67935497 0.58661693, + -0.46970412 -0.68440318 0.55764711, + -0.53653926 -0.6542083 0.53304523, + -0.56531769 -0.65608472 0.49996877, + -0.61860675 -0.62492776 0.47622582, + -0.64654702 -0.62325901 0.439915, + -0.69778985 -0.58521086 0.41305891, + -0.72041297 -0.58073395 0.37914795, + -0.76784301 -0.53643298 0.35022399, + -0.78479719 -0.53048712 0.3204321, + -0.88573486 -0.40520594 0.22645497, + -0.83915371 -0.47478083 0.26533791, + -0.8270852 -0.48111811 0.29061207, + -0.82651883 -0.48467788 0.28627595, + -0.81229883 -0.49167687 0.3137269, + -0.76734531 -0.54056519 0.34492111, + -0.74760115 -0.54686713 0.37686709, + -0.69745594 -0.59007996 0.40664595, + -0.67206293 -0.59435892 0.44166595, + -0.61854011 -0.63068616 0.46866113, + -0.59268093 -0.63163394 0.49976793, + -0.52392906 -0.66796207 0.52851206, + -0.49486059 -0.66566145 0.55857652, + -0.41925699 -0.69545698 0.58357799, + -0.38313618 -0.68841434 0.61586732, + -0.32843116 -0.70394337 0.62975931, + -0.29087192 -0.69230074 0.66038877, + -0.24099888 -0.70225966 0.66988868, + -0.19786395 -0.68378782 0.70234179, + -0.15469106 -0.68918222 0.70788324, + -0.11724602 -0.66858906 0.73433107, + -0.081591226 -0.67098826 0.73696524, + -0.077931516 -0.66858816 0.73953819, + -0.047935206 -0.66985708 0.74094105, + -0.0490315 -0.67067498 0.74012899, + -0.023474894 -0.67129785 0.74081582, + -0.025453599 -0.67296302 0.73923802, + -0.004201361 -0.67317516 0.7394712, + -0.0069307801 -0.67575902 0.73708999, + 0.010835201 -0.67573607 0.73706406, + 0.0072845565 -0.67951268 0.73362762, + 0.02129369 -0.67937672 0.73348063, + 0.0168084 -0.68474603 0.72858799, + 0.028192993 -0.68456984 0.72840184, + 0.023399107 -0.69105822 0.72242022, + 0.031943604 -0.69089508 0.72224903, + 0.027513292 -0.6977458 0.7158168, + 0.03313411 -0.69762623 0.71569526, + 0.028561508 -0.70581615 0.70781916, + 0.031988211 -0.70574325 0.70774525, + 0.026479904 -0.71736509 0.69619405, + 0.027900709 -0.71733725 0.69616723, + 0.023204014 -0.72937042 0.68372542, + 0.01787271 -0.72945035 0.68380028, + 0.023230495 -0.7115258 0.70227581, + 0.023496896 -0.71152097 0.70227194, + 0.028417613 -0.69854534 0.71500134, + 0.027340103 -0.69856608 0.71502304, + 0.03179691 -0.68889624 0.72416222, + 0.021392498 -0.67238891 0.73988897, + 0.031813405 -0.67220306 0.73968303, + 0.0242368 -0.69286799 0.72065699, + 0.018625589 -0.69295156 0.7207436, + 0.026178105 -0.66605717 0.7454412, + 0.020751702 -0.66614205 0.74553609, + 0.0284987 -0.64414901 0.76436901, + 0.027029509 -0.64417523 0.7644003, + 0.031971198 -0.63255793 0.77385288, + 0.028508108 -0.63262415 0.77393419, + 0.033538099 -0.622594 0.78182602, + 0.027702408 -0.6227051 0.78196615, + 0.032633103 -0.61420304 0.78847313, + 0.025089812 -0.61433631 0.78864539, + 0.029668396 -0.60742491 0.79382288, + 0.01916619 -0.60758072 0.79402661, + 0.023427799 -0.60188901 0.79823601, + 0.0095738806 -0.60202605 0.79841912, + 0.0108207 -0.600546 0.79951698, + -0.0057043703 -0.60057104 0.79955113, + -0.030981384 -0.62673467 0.77861667, + -0.053952713 -0.62612218 0.77785617, + -0.088199295 -0.65612894 0.74947697, + -0.11776204 -0.65411222 0.74717426, + -0.15154709 -0.67882943 0.71848744, + -0.18683001 -0.67466909 0.71408409, + -0.21966296 -0.69443291 0.68520892, + -0.26072496 -0.68719894 0.67807096, + -0.29141095 -0.70200884 0.64981782, + -0.33670714 -0.69100934 0.63963628, + -0.36422589 -0.70121378 0.61289376, + -0.41312885 -0.68567479 0.59931177, + -0.43679994 -0.69195992 0.57480192, + -0.48718125 -0.67176229 0.55802321, + -0.51377892 -0.67600691 0.52824795, + -0.56543708 -0.64990103 0.50784808, + -0.59503597 -0.65117002 0.471073, + -0.64691395 -0.61784095 0.44696194, + -0.67187619 -0.61568713 0.4117181, + -0.72095919 -0.57604712 0.38521108, + -0.74053323 -0.5716272 0.35334513, + -0.78543019 -0.5264861 0.32544109, + -0.79999679 -0.52095389 0.29767793, + -0.83978319 -0.47139212 0.26935807, + -0.8501429 -0.46563494 0.24584797, + -0.88430601 -0.412891 0.21799999, + -0.89371014 -0.40558407 0.19179103, + -0.92289102 -0.34810299 0.16461, + -0.92978424 -0.34083909 0.13903303, + -0.95148426 -0.28490606 0.11621703, + -0.95517087 -0.27965096 0.097179987, + -0.97102565 -0.22573392 0.078443669, + -0.97283125 -0.22224206 0.064868517, + -0.98415411 -0.17021301 0.049682207, + -0.98494738 -0.16807106 0.040384714, + -0.9925555 -0.11842306 0.028455013, + -0.99284863 -0.11724196 0.022490993, + -0.99748886 -0.069555692 0.013343099, + -0.99756402 -0.069026902 0.0100668, + -0.99973851 -0.022627989 0.0033000384, + -0.99974412 -0.022504402 0.0022896903, + -0.99974614 0.022418002 -0.0022809103, + -0.99974954 0.022339288 -0.0013176494, + -0.99771464 0.067540281 -0.0019319893, + -0.9977029 0.067623995 -0.0039887098, + -0.99360234 0.11293304 -0.00074214931, + -0.99355423 0.11316703 -0.0065797516, + -0.99769354 0.067765273 -0.0039399983, + -0.99766213 0.067998707 -0.0068172407, + -0.99974436 0.022499908 -0.0022557408, + -0.99973887 0.022621399 -0.0032492096, + -0.99973589 -0.022747397 0.0032673096, + -0.9997279 -0.022919899 0.0043272194, + -0.99745637 -0.070042521 0.013223805, + -0.99735433 -0.070746325 0.016716406, + -0.99243754 -0.11946094 0.028227087, + -0.99204624 -0.12099703 0.034698807, + -0.98385751 -0.17201991 0.049330976, + -0.98280001 -0.174784 0.0596212, + -0.97040236 -0.22856207 0.077965833, + -0.96799052 -0.2330339 0.093218058, + -0.95030963 -0.2890389 0.11562096, + -0.94543701 -0.29562399 0.13695, + -0.92084301 -0.35381201 0.16390599, + -0.91165423 -0.36285409 0.19293405, + -0.87814075 -0.4224039 0.22459695, + -0.86541086 -0.43142694 0.25482297, + -0.86656117 -0.4235521 0.26396105, + -0.81180698 -0.49556699 0.30884099, + -0.79508573 -0.5032258 0.33852988, + -0.74725682 -0.55138189 0.37092492, + -0.72477818 -0.55784214 0.40436208, + -0.67199492 -0.59959894 0.43463093, + -0.64960974 -0.60283679 0.46324381, + -0.58070773 -0.64553171 0.49605176, + -0.55671483 -0.64611274 0.52211779, + -0.47856799 -0.68293899 0.55187601, + -0.44587693 -0.67985195 0.58223295, + -0.38628781 -0.70057464 0.59998071, + -0.35013896 -0.69297493 0.63022894, + -0.29479 -0.70693099 0.64292097, + -0.25141799 -0.69274002 0.67594397, + -0.20218897 -0.70094794 0.68395293, + -0.16242495 -0.6832118 0.71192682, + -0.12084296 -0.68733275 0.71621978, + -0.11600398 -0.68467993 0.71955293, + -0.080059476 -0.6871208 0.72211879, + -0.080350608 -0.68730503 0.72191107, + -0.049839176 -0.68867767 0.72335267, + -0.050719399 -0.68931198 0.72268701, + -0.024925191 -0.68998575 0.72339374, + -0.026896009 -0.69159126 0.72178823, + -0.0051459107 -0.69183207 0.72204006, + -0.0078078774 -0.69427574 0.71966678, + 0.0101323 -0.69426101 0.719652, + 0.0061432426 -0.69837737 0.71570337, + 0.020576101 -0.69824302 0.71556503, + 0.016531499 -0.702941 0.71105599, + 0.027714804 -0.70276707 0.71088004, + 0.023569405 -0.70822215 0.70559621, + 0.032270115 -0.70805037 0.70542437, + 0.028083596 -0.71434993 0.69922495, + 0.033270493 -0.7142368 0.69911283, + 0.027330194 -0.7245788 0.68864983, + 0.031226808 -0.72449619 0.68857116, + 0.0258746 -0.73545903 0.67707503, + 0.027909892 -0.7354188 0.67703784, + 0.02327951 -0.74694133 0.6644823, + 0.023354601 -0.74694008 0.66448104, + 0.017928394 -0.76410568 0.64484179, + 0.0236219 -0.76401502 0.64476597, + 0.028162386 -0.75303662 0.65737569, + 0.02582011 -0.7530843 0.65741724, + 0.030952984 -0.74288267 0.6687057, + 0.026266696 -0.74298191 0.66879594, + 0.032172989 -0.73301077 0.67945576, + 0.026346013 -0.73313636 0.67957127, + 0.032603096 -0.72398692 0.68904293, + 0.0245844 -0.72415298 0.689201, + 0.027926017 -0.7198754 0.69354141, + 0.016775101 -0.72005504 0.69371408, + 0.0202547 -0.71613097 0.69767201, + 0.0054647001 -0.71626699 0.69780499, + 0.0089462725 -0.71278524 0.70132524, + -0.0092052817 -0.71278417 0.70132315, + -0.0060925311 -0.71001804 0.70415705, + -0.0280497 -0.70975202 0.70389301, + -0.026446505 -0.70848906 0.70522606, + -0.05249938 -0.70775974 0.70449978, + -0.05166398 -0.70717978 0.70514375, + -0.082739107 -0.70569706 0.70366603, + -0.082705051 -0.70567656 0.70369059, + -0.11922303 -0.70305216 0.70107317, + -0.11968606 -0.70329535 0.70075035, + -0.16160695 -0.69907582 0.69654584, + -0.16752708 -0.70170438 0.69249237, + -0.21585198 -0.69498396 0.68586093, + -0.25682706 -0.70908719 0.65668517, + -0.31217206 -0.6970312 0.64552015, + -0.35469419 -0.70664638 0.61224431, + -0.4155671 -0.6874342 0.59559911, + -0.44930488 -0.69106281 0.5661779, + -0.51315373 -0.66392571 0.54394478, + -0.54117012 -0.66360515 0.51649112, + -0.61956203 -0.61944008 0.48211706, + -0.63834822 -0.61691624 0.46035418, + -0.70618582 -0.56744987 0.4234409, + -0.72466904 -0.56259608 0.39792007, + -0.77565211 -0.51529509 0.36446503, + -0.79473615 -0.50723803 0.33332303, + -0.83964229 -0.45390716 0.29827711, + -0.85733742 -0.44271022 0.26264113, + -0.89653528 -0.38097414 0.22601607, + -0.90903974 -0.36963892 0.19238995, + -0.9374401 -0.30882102 0.16073501, + -0.94395214 -0.30055502 0.13645901, + -0.96401238 -0.24207509 0.10990804, + -0.9672035 -0.23644611 0.092794344, + -0.9810155 -0.18052492 0.070847966, + -0.98242712 -0.17698002 0.059289109, + -0.99137622 -0.12425903 0.041627411, + -0.99189711 -0.12227801 0.034470703, + -0.99717635 -0.072278619 0.020375608, + -0.99731249 -0.071363434 0.016590007, + -0.99971366 -0.023307893 0.005418458, + -0.99972451 -0.023078488 0.0042899284, + -0.9997285 0.022908689 -0.0042583481, + -0.99973625 0.022739206 -0.0032174806, + -0.99759686 0.068601891 -0.0097068092, + -0.99764597 0.0682422 -0.0067424402, + -0.99344277 0.11377597 -0.011241198, + -0.99352849 0.11339705 -0.0064996835, + -0.98719966 0.15922794 -0.0091265962, + -0.98729199 0.158913 -0.0010879301, + -0.98535633 0.17044106 -0.0047674719, + -0.98541963 0.17007494 -0.0047528683, + -0.98543054 0.17007692 0.00077111163, + -0.98536724 0.17044304 0.00077111216, + 0.97325897 0.229689 -0.00315552, + -0.8705548 0.49198687 -0.0091205882, + -0.87059081 0.49200788 -4.6319688e-005, + -0.97325873 0.22968894 -0.0032380894, + 0.032064009 -0.88316828 0.46795917, + 0.040806796 -0.91041487 0.41167894, + 0.044931084 -0.9029327 0.42742684, + 0.04710272 -0.90284228 0.42738414, + 0.050499689 -0.89780277 0.43749291, + 0.049165383 -0.89786267 0.43752185, + 0.05171008 -0.89470768 0.44364884, + 0.046683613 -0.89492929 0.44375914, + 0.048642892 -0.89287388 0.44767195, + 0.03925091 -0.89324325 0.44785711, + 0.03975499 -0.89279276 0.44870988, + 0.02532851 -0.89321232 0.44892114, + 0.024081595 -0.89416075 0.44709787, + 0.0041479077 -0.89441246 0.44722372, + 0.0017293902 -0.89596909 0.44411305, + -0.024062105 -0.89571112 0.44398504, + -0.027278891 -0.8974427 0.44028684, + -0.059587829 -0.8961814 0.43966821, + -0.062450677 -0.89744669 0.43667984, + -0.10066199 -0.8946349 0.43531093, + -0.10194995 -0.89509058 0.43407279, + -0.14591007 -0.89014941 0.43167621, + -0.14395604 -0.88961321 0.4334341, + -0.19352096 -0.88198286 0.42971593, + -0.18691598 -0.88065386 0.43532893, + -0.24113591 -0.86999971 0.43006286, + -0.23065206 -0.86859518 0.43856812, + -0.28868005 -0.85466015 0.43153208, + -0.270928 -0.85336202 0.445389, + -0.33281308 -0.83598018 0.43631709, + -0.31887689 -0.83580571 0.44692984, + -0.38459605 -0.81401414 0.43527806, + -0.39975694 -0.81289488 0.42355195, + -0.47143087 -0.7821058 0.40750891, + -0.47853494 -0.7807979 0.40169495, + -0.55333209 -0.74068719 0.38105908, + -0.55543238 -0.74006343 0.37921125, + -0.63068718 -0.6906482 0.35389107, + -0.76006937 -0.56000024 0.32968816, + -0.75729412 -0.56173307 0.33310902, + -0.8217715 -0.49012071 0.29064283, + -0.8177641 -0.49333906 0.29644302, + -0.88316178 -0.40206492 0.24159694, + -0.88380641 -0.40137717 0.24038012, + -0.92992359 -0.31549984 0.18894991, + -0.92877859 -0.31711784 0.19185092, + -0.96086633 -0.23701409 0.14338905, + -0.95967078 -0.23927493 0.14757897, + -0.98097551 -0.16523093 0.10191095, + -0.98216277 -0.16194196 0.09555658, + -0.99399489 -0.094243288 0.055609692, + -0.99480438 -0.090165727 0.047270719, + -0.99946475 -0.028972492 0.015189297, + -0.99952489 -0.027964497 0.012959098, + -0.99954665 0.027316891 -0.012658996, + -0.99958891 0.026558096 -0.010805199, + -0.99636209 0.078937709 -0.032115903, + -0.99664325 0.077182911 -0.027294505, + -0.99089974 0.12690097 -0.04487649, + -0.99147838 0.12466305 -0.037813216, + -0.98355424 0.17283705 -0.052425712, + -0.98439276 0.17047895 -0.043677088, + -0.97440052 0.2177849 -0.055796973, + -0.97542876 0.21552895 -0.045673888, + -0.96354097 0.26174799 -0.0554685, + -0.96467125 0.25973505 -0.044125512, + -0.95079935 0.30543113 -0.051888719, + -0.95193797 0.303749 -0.039378501, + -0.93593502 0.34924999 -0.045277402, + -0.936979 0.347956 -0.031576499, + -0.91867661 0.39339384 -0.035699889, + -0.91950834 0.39252314 -0.020741608, + -0.91458088 0.40431994 -0.0081987688, + -0.91461128 0.40433416 -0.00044759116, + -0.91462409 0.40430507 -0.00044379907, + -0.91459322 0.40429208 -0.0081983218, + -0.89946222 0.43697208 -0.0048137708, + -0.89893687 0.43746793 -0.023116598, + -0.89862901 0.438113 -0.022868199, + -0.8976379 0.43897694 -0.039312698, + -0.9182266 0.39447683 -0.035327382, + -0.91694134 0.39580014 -0.05060542, + -0.93541491 0.35069698 -0.044838697, + -0.93395877 0.3524729 -0.059023887, + -0.95026726 0.30715907 -0.051435713, + -0.94874924 0.30936006 -0.064586416, + -0.96304274 0.26366395 -0.055046383, + -0.96156335 0.26624009 -0.06717322, + -0.97397566 0.21976593 -0.055447582, + -0.97263634 0.22262408 -0.066461921, + -0.98322612 0.17476901 -0.052175406, + -0.98213238 0.17774406 -0.061832123, + -0.99068499 0.12861399 -0.044741299, + -0.98993367 0.13140796 -0.05256718, + -0.99626201 0.080203399 -0.032083798, + -0.99589223 0.082407519 -0.037520807, + -0.99953222 0.027834207 -0.012673103, + -0.999475 0.028808201 -0.0148283, + -0.9994455 -0.029605584 0.015238693, + -0.99936187 -0.030916996 0.017890098, + -0.99374998 -0.096619003 0.055908602, + -0.99338549 -0.098377652 0.05921977, + -0.98004979 -0.17028095 0.10250298, + -0.98089349 -0.16790007 0.098273344, + -0.95856786 -0.24584797 0.14389698, + -0.95982689 -0.24335296 0.13968399, + -0.92531759 -0.32886684 0.18876991, + -0.92615426 -0.32764509 0.18678105, + -0.87494481 -0.4206689 0.23981094, + -0.87883401 -0.41638699 0.23296501, + -0.82437855 -0.49397969 0.27637681, + -0.82731044 -0.49144423 0.27210313, + -0.76417118 -0.56429213 0.31243706, + -0.76625729 -0.56288517 0.30985513, + -0.69728804 -0.62793708 0.34566504, + -0.69660795 -0.62890095 0.34528396, + -0.62337869 -0.68541169 0.37631083, + -0.62321091 -0.68547583 0.37647191, + -0.54788709 -0.73324406 0.40270707, + -0.54648024 -0.73361439 0.40394217, + -0.47170287 -0.77240783 0.42530292, + -0.46860507 -0.77289212 0.42784005, + -0.39688894 -0.80303991 0.44452894, + -0.3893699 -0.8034578 0.45038489, + -0.32304996 -0.82552689 0.46275693, + -0.30830404 -0.82487714 0.47384205, + -0.24934691 -0.8397277 0.48237282, + -0.26092988 -0.84117556 0.47364476, + -0.20653008 -0.8525753 0.48006317, + -0.22178097 -0.85539585 0.46809295, + -0.17045404 -0.8644042 0.47302312, + -0.17946409 -0.8666234 0.46557119, + -0.13290302 -0.87311119 0.46905613, + -0.13816196 -0.87476373 0.46443483, + -0.096048377 -0.87915075 0.46676388, + -0.09821628 -0.87999374 0.46471989, + -0.061165009 -0.88261312 0.46610406, + -0.060929608 -0.88250214 0.46634507, + -0.0292364 -0.88376701 0.467013, + -0.027975988 -0.88305557 0.4684338, + -0.0021803405 -0.88339925 0.46861613, + -0.00098715548 -0.88260257 0.47011876, + 0.019491596 -0.88243574 0.47002888, + 0.019744702 -0.88223714 0.47039106, + 0.034992702 -0.88186914 0.47019407, + 0.034296885 -0.88250661 0.46904776, + 0.044616699 -0.88214701 0.46885601, + 0.04259152 -0.88432443 0.46492621, + 0.048573293 -0.88408285 0.46479893, + 0.045591716 -0.88786632 0.45783713, + 0.048026092 -0.88776487 0.45778495, + 0.044843197 -0.89259785 0.44861794, + 0.043458715 -0.89265227 0.44864616, + 0.040000681 -0.89911461 0.43588179, + 0.030935904 -0.89940411 0.43602207, + 0.037585594 -0.88299876 0.46786788, + 0.020699807 -0.85545516 0.51746315, + 0.025932295 -0.85535079 0.51739991, + 0.019914502 -0.87747812 0.47920305, + 0.016706299 -0.87752986 0.47923094, + 0.013026604 -0.89924127 0.43725914, + 0.0058869813 -0.89930224 0.43728808, + 0.0046871509 -0.91957825 0.3928791, + -0.0046871509 -0.91957825 0.3928791, + -0.0058855307 -0.89932811 0.43723506, + -0.013094096 -0.89926672 0.43720484, + -0.016753005 -0.87767732 0.47895917, + -0.019683905 -0.87763023 0.47893411, + 0.91334057 0.40719578 -0.00074399065, + 0.93220741 0.36192417 0.00052094721, + 0.948798 0.315837 -0.00542052, + 0.93221134 0.36191413 0.0005206542, + 0.93216974 0.36189792 -0.0094558578, + 0.93216586 0.36190796 -0.0094560487, + -0.027820287 -0.87756556 0.47864875, + -0.036317211 -0.87732631 0.47851819, + -0.039948482 -0.8702026 0.49107176, + -0.039494604 -0.8702181 0.49108106, + -0.042995699 -0.86462599 0.50057298, + -0.039124914 -0.86476332 0.50065321, + -0.042333305 -0.86047614 0.50772905, + -0.034823187 -0.86072558 0.50787675, + -0.037508491 -0.85767585 0.5128209, + -0.026086085 -0.85798746 0.5130077, + -0.02802079 -0.85610372 0.51604384, + -0.012283803 -0.85637516 0.51620811, + -0.014050595 -0.8548907 0.51861781, + 0.0063315486 -0.85495782 0.51865888, + 0.0042939605 -0.85347509 0.52111608, + 0.029238304 -0.85311812 0.52089804, + 0.026654797 -0.85149187 0.52368993, + 0.055739898 -0.85047001 0.52306199, + 0.05200642 -0.84844631 0.52672017, + 0.085357033 -0.84649527 0.52550918, + 0.078715689 -0.84340489 0.53148097, + 0.11571497 -0.84034681 0.52955389, + 0.10504898 -0.83609885 0.53842688, + 0.14554907 -0.83179742 0.53565723, + 0.13926105 -0.8297013 0.54055721, + 0.18452105 -0.82347816 0.53650314, + 0.19262892 -0.8255617 0.53041685, + 0.24519794 -0.81563485 0.52403986, + 0.24884705 -0.81626719 0.52132809, + 0.30808601 -0.80178499 0.51207799, + 0.31303385 -0.80222565 0.50837374, + 0.37845886 -0.78184873 0.49546081, + 0.38276318 -0.78184938 0.49214223, + 0.453942 -0.75407797 0.47466099, + 0.45769081 -0.75372064 0.47161877, + 0.53232783 -0.71763074 0.44903585, + 0.53370887 -0.71735781 0.44783089, + 0.60959089 -0.67243981 0.41978991, + 0.6093961 -0.67250019 0.41997609, + 0.68461704 -0.61824703 0.38609606, + 0.68215108 -0.61931509 0.38874006, + 0.75397199 -0.55638099 0.34923699, + 0.74947083 -0.55896688 0.3547529, + 0.82878172 -0.47245383 0.29984689, + 0.83279771 -0.46931481 0.29358387, + 0.8907097 -0.38537985 0.24107791, + 0.89087939 -0.38520318 0.24073312, + 0.93274122 -0.30575007 0.19107805, + 0.93154263 -0.30737787 0.19428593, + 0.96152836 -0.23220909 0.14677306, + 0.96444112 -0.22675303 0.13578102, + 0.98299903 -0.157528 0.094328403, + 0.98531437 -0.15077005 0.080150232, + 0.99501598 -0.088047802 0.046806902, + 0.99558061 -0.08498697 0.039956287, + 0.99954122 -0.027410107 0.012886803, + 0.9995845 -0.026641414 0.011008806, + 0.99960041 0.026123285 -0.010794694, + 0.99963188 0.025530396 -0.0091812192, + 0.99672174 0.076132186 -0.027378492, + 0.99693537 0.07474643 -0.023087308, + 0.99164122 0.12327903 -0.038077906, + 0.99208236 0.12151705 -0.03172151, + 0.98464251 0.16892193 -0.044096276, + 0.98528934 0.16705506 -0.036020711, + 0.97575724 0.21393904 -0.046129912, + 0.97655535 0.21214807 -0.036508914, + 0.96506089 0.25822997 -0.044439197, + 0.96592188 0.25666296 -0.033452496, + 0.95235014 0.30244902 -0.039420106, + 0.95315367 0.30123687 -0.027467091, + 0.93732911 0.34700602 -0.031640403, + 0.93797278 0.34619591 -0.018855495, + 0.91972691 0.39197794 -0.021349099, + 0.92015636 0.39151216 -0.0055356617, + 0.93215388 0.36193898 -0.009454269, + 0.93219548 0.36195478 0.00052094669, + 0.91333514 0.40720806 -0.0007456431, + 0.91328901 0.40718701 -0.0101005, + 0.91329432 0.40717515 -0.010100204, + 0.89938015 0.43712205 -0.006306001, + 0.8988716 0.43758079 -0.023514489, + 0.91944975 0.39264092 -0.021099593, + 0.9186551 0.39347205 -0.035391904, + 0.93696964 0.34800589 -0.031302389, + 0.93593812 0.34929204 -0.044888303, + 0.95195401 0.303743 -0.039034799, + 0.95079452 0.30546084 -0.051801175, + 0.96467024 0.25975206 -0.044049609, + 0.96351862 0.26180291 -0.05559738, + 0.97541291 0.21557797 -0.045780998, + 0.97437447 0.2178531 -0.055987626, + 0.98437679 0.17053296 -0.043826289, + 0.98353899 0.172885 -0.052552801, + 0.99146962 0.12470396 -0.037906885, + 0.99089634 0.12692004 -0.044897914, + 0.99664265 0.077187769 -0.027305091, + 0.99636579 0.07891608 -0.032053094, + 0.99958915 0.026555104 -0.010785801, + 0.99954766 0.027301991 -0.012608696, + 0.9995265 -0.027932987 0.012900094, + 0.99946803 -0.0289184 0.0150821, + 0.99483454 -0.090004057 0.046940677, + 0.99403977 -0.094028175 0.055169784, + 0.98231441 -0.16149291 0.09475404, + 0.98100448 -0.16513307 0.10179105, + 0.95970351 -0.23921788 0.14745793, + 0.96094674 -0.23686394 0.14309697, + 0.92893261 -0.31690684 0.19145291, + 0.92991626 -0.31551608 0.18895905, + 0.88378191 -0.40141693 0.24040397, + 0.88295245 -0.40230078 0.24196886, + 0.81733871 -0.49373183 0.29696187, + 0.82222861 -0.48980275 0.28988487, + 0.75800717 -0.56130713 0.3322041, + 0.7609328 -0.55947286 0.32858992, + 0.69026804 -0.62390506 0.36643204, + 0.69151777 -0.62331074 0.36508489, + 0.61686337 -0.67914844 0.39779025, + 0.61654079 -0.67925978 0.39809984, + 0.54091507 -0.72563607 0.42528006, + 0.53848189 -0.7261948 0.4274089, + 0.4635188 -0.76364064 0.44944778, + 0.45970526 -0.76411349 0.45255026, + 0.38830984 -0.79290068 0.46959981, + 0.38337001 -0.79303098 0.473423, + 0.31759691 -0.81417984 0.48604888, + 0.31334704 -0.81390911 0.48925006, + 0.25370097 -0.82903087 0.49834093, + 0.24381495 -0.82753181 0.50571287, + 0.19185603 -0.83743113 0.51176208, + 0.19922803 -0.83912009 0.50614804, + 0.15174706 -0.84636933 0.51052117, + 0.16442701 -0.85007215 0.50034106, + 0.120402 -0.855533 0.50355399, + 0.12804903 -0.8582502 0.49700111, + 0.088284492 -0.86199486 0.49916995, + 0.092103302 -0.86362499 0.49564999, + 0.056766108 -0.86591309 0.49696305, + 0.058649223 -0.8668673 0.49507719, + 0.028303107 -0.86801416 0.49573213, + 0.029066296 -0.86846989 0.49488893, + 0.0036175014 -0.86883128 0.49509519, + 0.0040024486 -0.86909968 0.49462083, + -0.016501907 -0.86898839 0.49455723, + -0.015752697 -0.8695969 0.49351093, + -0.031513795 -0.86927289 0.49332693, + -0.030058004 -0.87064815 0.49098706, + -0.040934898 -0.87031186 0.49079695, + -0.03861098 -0.87287956 0.48640576, + -0.045429904 -0.87262911 0.48626605, + -0.042434111 -0.87653124 0.47947112, + -0.045525186 -0.87641168 0.47940582, + -0.042035986 -0.88184673 0.46965882, + -0.041565981 -0.88186359 0.46966878, + -0.037852608 -0.88896924 0.45640013, + -0.034930088 -0.88906372 0.45644885, + -0.022954911 -0.88004345 0.47433823, + -0.027282987 -0.8799476 0.47428676, + -0.021465695 -0.90032774 0.43468291, + -0.017302193 -0.90040058 0.4347178, + -0.013824496 -0.91988474 0.39194492, + -0.0062513575 -0.91995466 0.39197484, + -0.0051226206 -0.93782413 0.34707302, + 0.0050876895 -0.93782389 0.34707397, + 0.0062175784 -0.91994679 0.39199391, + 0.013826095 -0.91987664 0.39196384, + 0.017303195 -0.90039468 0.43472984, + 0.021561602 -0.90032011 0.43469405, + 0.027439509 -0.87977427 0.47459918, + 0.027282603 -0.87977815 0.47460106, + 0.0328614 -0.86557901 0.49969301, + 0.034586187 -0.8655287 0.49966383, + 0.038222697 -0.85823786 0.51182693, + 0.036881398 -0.85828102 0.51185298, + 0.040459212 -0.85243517 0.52126509, + 0.03592401 -0.85258329 0.52135515, + 0.039296102 -0.84797102 0.528584, + 0.0312101 -0.84821302 0.52873498, + 0.034255594 -0.84466583 0.53419685, + 0.02221911 -0.84495342 0.53437823, + 0.025032295 -0.84213281 0.5386889, + 0.009136701 -0.84236109 0.53883606, + 0.012009595 -0.83986157 0.54266775, + -0.0078316275 -0.83989668 0.5426898, + -0.0044284295 -0.8373149 0.54670292, + -0.02829409 -0.83698767 0.54648983, + -0.0234928 -0.83380502 0.55155897, + -0.051040206 -0.83294815 0.55099207, + -0.044805896 -0.82933789 0.55694795, + -0.075842746 -0.82778049 0.55590236, + -0.066244386 -0.82291883 0.56428391, + -0.100377 -0.82056499 0.56266999, + -0.092173092 -0.81695485 0.56928796, + -0.13017003 -0.8134672 0.5668571, + -0.14003402 -0.81704509 0.55931008, + -0.18549095 -0.81085581 0.5550729, + -0.19161803 -0.81255013 0.55049509, + -0.2441631 -0.80283427 0.54391319, + -0.24743398 -0.8034699 0.54149091, + -0.30605799 -0.78946197 0.53205103, + -0.30929095 -0.78982383 0.52963889, + -0.37432781 -0.77016366 0.51645577, + -0.37704399 -0.77023399 0.51437098, + -0.44798911 -0.74349219 0.49651313, + -0.44985107 -0.74337006 0.49501005, + -0.52434874 -0.70874465 0.47195277, + -0.52486193 -0.70866096 0.47150794, + -0.60109425 -0.66536021 0.44269815, + -0.60001105 -0.66565305 0.44372606, + -0.93858463 0.34503189 -0.0034476588, + -0.93822211 0.34552604 -0.018737901, + -0.95395613 0.29950604 -0.016242202, + -0.95343179 0.30030495 -0.028012892, + -0.96680337 0.25441709 -0.023732409, + -0.96620065 0.25552791 -0.03408549, + -0.97740591 0.20951498 -0.027947797, + -0.97682214 0.21085003 -0.036891203, + -0.9859941 0.16428502 -0.028744103, + -0.98550725 0.16572504 -0.036204908, + -0.9925639 0.11891998 -0.025979696, + -0.99222785 0.12030298 -0.031799298, + -0.99716491 0.07274799 -0.019229298, + -0.99700123 0.073848717 -0.023129806, + -0.99966514 0.024693003 -0.0077339909, + -0.99964076 0.025171295 -0.0092016282, + -0.99962866 -0.025594791 0.0093564559, + -0.99959546 -0.026213612 0.011040306, + -0.99612826 -0.081019722 0.034122907, + -0.99570578 -0.083439276 0.040099189, + -0.98741686 -0.14253399 0.06849879, + -0.98573202 -0.147797 0.0805507, + -0.97035766 -0.21220392 0.11565296, + -0.96553373 -0.22169293 0.13636997, + -0.93942451 -0.29194385 0.17958391, + -0.93450421 -0.29857507 0.19379105, + -0.8959896 -0.37249282 0.24176788, + -0.89628869 -0.37219188 0.24112192, + -0.84439784 -0.44961089 0.29127693, + -0.84213591 -0.45135495 0.29510298, + -0.7730391 -0.53094608 0.34714103, + -0.76452911 -0.53574008 0.35843801, + -0.67392308 -0.61404306 0.41082707, + -0.67579299 -0.61331499 0.408838, + -0.68172705 -0.62014705 0.38815707, + -0.60821474 -0.67284179 0.42113984, + -0.60864007 -0.67271107 0.42073405, + -0.53270519 -0.71752322 0.44876015, + -0.53173214 -0.71771419 0.44960812, + -0.45713285 -0.75371867 0.47216281, + -0.45478222 -0.75394338 0.47407025, + -0.38366118 -0.78177035 0.49156824, + -0.38111082 -0.78177565 0.49353975, + -0.31517297 -0.80249691 0.50662094, + -0.31157318 -0.80218947 0.50932729, + -0.25241786 -0.81687552 0.51865172, + -0.24487901 -0.81558597 0.52426499, + -0.19250707 -0.82546329 0.5306142, + -0.18091999 -0.82245886 0.53928596, + -0.13590503 -0.82850015 0.5432471, + -0.14459002 -0.83142012 0.53650206, + -0.10448694 -0.8356505 0.53923172, + -0.115365 -0.83999503 0.53018802, + -0.078310803 -0.84304398 0.53211302, + -0.084994681 -0.84615982 0.52610791, + -0.051782001 -0.84809297 0.52731103, + -0.056581426 -0.8506934 0.52260822, + -0.027267091 -0.85174173 0.52325183, + -0.030177511 -0.85356832 0.5201062, + -0.0051234486 -0.85394579 0.52033687, + -0.0071769417 -0.85543519 0.51786011, + 0.013337305 -0.85538131 0.51782715, + 0.011531698 -0.85689384 0.51536387, + 0.027597109 -0.85662431 0.51520216, + 0.025690205 -0.85847521 0.51221114, + 0.037253916 -0.85816228 0.51202518, + 0.034625698 -0.86113787 0.50719094, + 0.042253103 -0.86088514 0.50704205, + 0.039175589 -0.86498582 0.50026488, + 0.042959105 -0.86485112 0.50018704, + 0.039429512 -0.87047815 0.49062511, + 0.039996885 -0.87045872 0.49061382, + 0.033898309 -0.88227725 0.46950811, + 0.042106416 -0.88200128 0.46936217, + 0.045504395 -0.87671888 0.47884595, + 0.042456411 -0.87683624 0.47891113, + 0.045498285 -0.8728857 0.48579884, + 0.038584083 -0.87313968 0.48594081, + 0.040750302 -0.87075311 0.49002907, + 0.029559907 -0.87109619 0.49022213, + 0.031066507 -0.86967617 0.49264413, + 0.015178202 -0.86999613 0.49282506, + 0.015751103 -0.86953217 0.4936251, + -0.0049123885 -0.8696298 0.49367988, + -0.0044710306 -0.86932313 0.49422407, + -0.030055296 -0.86893886 0.49400595, + -0.029244404 -0.86845714 0.49490106, + -0.059901424 -0.86726832 0.49422419, + -0.057577707 -0.86609411 0.49655405, + -0.092741877 -0.8637948 0.49523488, + -0.087898895 -0.86172891 0.49969694, + -0.12772894 -0.85799158 0.49752977, + -0.11998396 -0.85523373 0.50416183, + -0.16362694 -0.84984672 0.5009858, + -0.15077198 -0.84607881 0.51129091, + -0.19832192 -0.83886272 0.50692981, + -0.18852203 -0.83659011 0.51437008, + -0.24005206 -0.82695615 0.50844711, + -0.25355491 -0.82903469 0.49840882, + -0.31324688 -0.8139087 0.48931482, + -0.32086903 -0.81437814 0.48356107, + -0.38694495 -0.79286391 0.47078693, + -0.39078605 -0.79274809 0.46780005, + -0.46211481 -0.76375771 0.45069286, + -0.46425107 -0.76348811 0.44895107, + -0.53914797 -0.72599697 0.42690501, + -0.54028112 -0.72573715 0.4259131, + -0.61595964 -0.67941761 0.39872977, + -0.615897 -0.67943901 0.39879, + -0.69062322 -0.62371624 0.36608413, + -0.68922257 -0.62437963 0.3675898, + -0.68310779 -0.6182459 0.38876191, + -0.75325412 -0.55679709 0.35012203, + -0.75002986 -0.55864793 0.35407296, + -0.82907391 -0.47227094 0.29932696, + -0.83271599 -0.469421 0.29364601, + -0.89072371 -0.38535884 0.24105991, + -0.89065403 -0.38543099 0.241202, + -0.93260002 -0.30594301 0.191458, + -0.93148273 -0.30745894 0.19444495, + -0.96149576 -0.23226795 0.14689296, + -0.96415633 -0.22730108 0.13688305, + -0.98285735 -0.15794006 0.095112734, + -0.98521835 -0.15108407 0.080737032, + -0.99498755 -0.088195354 0.047130376, + -0.99556655 -0.085068263 0.04013158, + -0.99953961 -0.027439591 0.012944795, + -0.99958378 -0.026655594 0.011031097, + -0.99960011 0.026130404 -0.010813701, + -0.99963188 0.025529396 -0.0091782194, + -0.99672264 0.07612507 -0.02736819, + -0.99693823 0.074724816 -0.023031106, + -0.99164945 0.12324206 -0.037984718, + -0.99209088 0.12147599 -0.031610698, + -0.98465645 0.16888008 -0.043946523, + -0.98529702 0.16702799 -0.035936199, + -0.97577065 0.21390092 -0.046020884, + -0.97655445 0.21214211 -0.03656932, + -0.96506023 0.25822005 -0.044512313, + -0.96590549 0.25668612 -0.033749416, + -0.95233762 0.30244288 -0.039765485, + -0.95315135 0.30122212 -0.027710309, + -0.93734187 0.34694597 -0.031916596, + -0.93801552 0.34609783 -0.01852609, + -0.91976988 0.39189693 -0.020977698, + -0.92021388 0.39139393 -0.0041406397, + -0.9333269 0.35894498 -0.0077008391, + -0.93335485 0.35895497 0.00035463896, + -0.93337214 0.35891002 0.00035463902, + -0.93334466 0.35889888 -0.0077036773, + -0.93331814 0.35896802 -0.0077047711, + -0.93334597 0.358978 0.000356687, + -0.94978851 0.31283385 -0.0060510873, + -0.94978237 0.31283212 -0.0070470022, + -0.94980538 0.31276211 -0.0070458925, + -0.94982851 0.31276986 -0.00091967254, + -0.94448346 0.32854414 -0.0031339014, + -0.90569514 0.42391106 -0.0039659906, + -0.89367586 0.44871294 4.2840496e-005, + -0.89364213 0.44869706 -0.0086537106, + -0.89367324 0.44863513 -0.0086527523, + -0.89370668 0.44865185 4.0349987e-005, + -0.89441597 0.447236 4.03466e-005, + -0.89438158 0.44721881 -0.0087770559, + -0.87634009 0.48166105 -0.0055492604, + -0.87573558 0.48213476 -0.025165988, + 0.75959212 0.65030909 -0.010859601, + 0.79200637 0.61043531 -0.0097322343, + 0.79122913 0.61072004 -0.031264503, + 0.82113117 0.56999314 -0.029179607, + 0.81974488 0.57064295 -0.048835993, + 0.84751785 0.52883387 -0.045257889, + 0.84553999 0.52998602 -0.064628899, + 0.87091899 0.487813 -0.059486099, + 0.86843014 0.48955205 -0.078536905, + 0.89162409 0.44706005 -0.071720108, + 0.88877189 0.44941294 -0.090068892, + 0.91015071 0.40619984 -0.081408367, + 0.9070611 0.40918905 -0.099017613, + 0.92680377 0.36501092 -0.08832708, + 0.92357963 0.36866587 -0.10529096, + 0.94161451 0.32374784 -0.092462555, + 0.93837279 0.32806093 -0.10877698, + 0.95481789 0.28208897 -0.093533695, + 0.95170701 0.28698999 -0.109044, + 0.96669066 0.23925892 -0.09090817, + 0.96386963 0.24462192 -0.10542996, + 0.97737598 0.19423699 -0.083714597, + 0.97500426 0.19988304 -0.097023323, + 0.9866631 0.14643602 -0.071080409, + 0.98491663 0.15198994 -0.082694568, + 0.99424225 0.094126225 -0.051212311, + 0.99399614 0.095391512 -0.053592507, + 0.99929237 0.032792412 -0.018423308, + 0.99934345 0.031979416 -0.017032208, + 0.99927467 -0.033610187 0.017900795, + 0.99932063 -0.032848388 0.016709194, + 0.99296379 -0.10554798 0.053689487, + 0.99333364 -0.10350297 0.050749183, + 0.97858834 -0.18480806 0.090614133, + 0.97988713 -0.18056402 0.084959008, + 0.95766562 -0.2604889 0.12256496, + 0.95906538 -0.25727308 0.11834005, + 0.92765325 -0.33927208 0.15605803, + 0.92943966 -0.33620289 0.15201794, + 0.88862211 -0.41790506 0.18896103, + 0.89044291 -0.41548094 0.18570699, + 0.84011912 -0.49518806 0.22133403, + -0.64404505 -0.69866806 0.31155902, + -0.565974 -0.75295103 0.335765, + -0.55370122 -0.75724036 0.34641317, + -0.47900993 -0.79824686 0.36517298, + -0.49639601 -0.79401398 0.350903, + -0.42356908 -0.82855821 0.36617008, + -0.44663516 -0.82453328 0.34736413, + -0.37600386 -0.85393268 0.35974988, + -0.39154306 -0.85222811 0.34698904, + -0.32377315 -0.87628543 0.35678416, + -0.33384216 -0.8758834 0.34839317, + -0.26959905 -0.89478624 0.3559131, + -0.2729691 -0.89490527 0.35303313, + -0.21314989 -0.90885556 0.35853681, + -0.21120505 -0.90862823 0.3602601, + -0.15765598 -0.91797286 0.36396497, + -0.15159605 -0.91673636 0.36961213, + -0.10502397 -0.92232662 0.37186489, + -0.096930698 -0.91992801 0.379917, + -0.057666194 -0.92274189 0.38107994, + -0.049531292 -0.91953689 0.38986993, + -0.017819297 -0.92052078 0.39028692, + -0.011244003 -0.91725224 0.39814809, + 0.013260297 -0.91722977 0.3981379, + 0.017811894 -0.91447169 0.40425786, + 0.03569911 -0.91403329 0.40406516, + 0.037688401 -0.91259497 0.40712401, + 0.049767502 -0.912112 0.40690899, + 0.050146177 -0.91178858 0.40758678, + 0.05696398 -0.91145468 0.40743786, + 0.055321481 -0.91310769 0.40394786, + 0.057881106 -0.91297513 0.40388906, + 0.053078901 -0.91863698 0.39152101, + 0.053525198 -0.91861498 0.39151201, + 0.04977598 -0.92384362 0.37951985, + 0.047580793 -0.92394286 0.37955993, + 0.044294413 -0.92954433 0.36604011, + 0.04203368 -0.94273555 0.33088186, + 0.045175716 -0.94260633 0.33083612, + 0.041855995 -0.9494279 0.31118298, + 0.030533016 -0.94981748 0.31131116, + 0.019832691 -0.97518152 0.22051689, + 0.012343902 -0.97529912 0.22054303, + -0.0054421597 -0.99933386 -0.036086097, + -0.0017112604 -0.99934721 -0.036086608, + -0.0078157 -0.95169002 -0.306961, + 0.0073465738 -0.95169348 -0.30696216, + 0.0013314795 -0.99933863 -0.03633929, + 0.0051275017 -0.99932635 -0.03633891, + -0.012548299 -0.97568387 0.21882297, + -0.019772595 -0.97556978 0.21879794, + -0.030551512 -0.95014834 0.31029812, + -0.041675713 -0.94976622 0.31017306, + 0.79163337 -0.57165831 0.2156931, + 0.72609562 -0.64332372 0.24273388, + 0.72141182 -0.64668983 0.24770394, + 0.65001976 -0.70964074 0.27181691, + 0.66790873 -0.69934762 0.25457987, + 0.59473032 -0.75542939 0.27499512, + 0.62046379 -0.74289578 0.2512579, + 0.54630488 -0.7934348 0.26835093, + 0.56491238 -0.78584146 0.25164914, + 0.49011883 -0.8301307 0.26583192, + 0.50288421 -0.82600141 0.25461611, + 0.42875615 -0.8633343 0.2661241, + 0.43464008 -0.86195016 0.26101705, + 0.36249918 -0.89198339 0.27011111, + 0.36205217 -0.89204741 0.27049911, + 0.29337898 -0.91485989 0.27741697, + 0.28611699 -0.91520101 0.28380299, + 0.22310993 -0.93105465 0.28871992, + 0.211458 -0.93043399 0.29929599, + 0.15589593 -0.94032162 0.30247587, + 0.14174204 -0.93811923 0.3159771, + 0.095059216 -0.94339609 0.31775403, + 0.081076123 -0.93976927 0.33205509, + 0.042963587 -0.94200265 0.33284387, + 0.030625511 -0.93750036 0.34663412, + 0.0013644096 -0.93793964 0.34679589, + -0.00742525 -0.93378901 0.35774699, + -0.028815603 -0.9334271 0.35760802, + -0.032339592 -0.93138677 0.36259192, + -0.047563877 -0.93081957 0.36237082, + -0.049284998 -0.92963302 0.36517599, + -0.058778692 -0.92915487 0.36498797, + -0.058527485 -0.92935878 0.3645089, + -0.063584588 -0.92907077 0.36439592, + -0.058820624 -0.93356633 0.35354513, + -0.061654806 -0.93340611 0.35348502, + -0.058359675 -0.93701959 0.34436682, + -0.058072407 -0.93703514 0.34437302, + -0.054641809 -0.94148827 0.33258709, + -0.051787693 -0.94163185 0.33263698, + -0.04877349 -0.94637477 0.31936792, + -0.043238178 -0.94661653 0.31944886, + -0.031287313 -0.94056338 0.3381741, + -0.032891892 -0.94051474 0.33815691, + -0.030136907 -0.94858623 0.31508109, + -0.018532204 -0.94885427 0.31517008, + -0.012070995 -0.9747805 0.22283889, + -0.004330771 -0.97484225 0.22285406, + 0.0015412506 -0.99938035 -0.035163913, + -0.0018759295 -0.99937975 -0.035163894, + 0.0040261517 -0.97462547 0.2238061, + 0.011957794 -0.97456354 0.2237919, + 0.018454993 -0.94839162 0.31656387, + 0.030084901 -0.94812399 0.31647399, + 0.032674409 -0.94049937 0.33822113, + 0.034632705 -0.94043714 0.33819902, + 0.039652199 -0.929726 0.36611101, + 0.027794087 -0.9227286 0.38444683, + 0.030418508 -0.92265826 0.38441709, + 0.02516371 -0.93893838 0.34316412, + 0.019830806 -0.93905121 0.34320509, + 0.01811569 -0.94757754 0.31901184, + 0.0060771722 -0.94771534 0.31905913, + 0.0038998809 -0.97445226 0.22456107, + -0.0040450697 -0.9744519 0.22455996, + -0.0062016621 -0.94795835 0.31833413, + -0.018099403 -0.94782126 0.31828809, + -0.019869292 -0.93903065 0.34325889, + -0.025204388 -0.93891752 0.34321785, + -0.030441815 -0.92269039 0.38433817, + -0.027712988 -0.92276359 0.38436881, + 0.78213573 -0.56967282 0.2524609, + 0.71551985 -0.6386838 0.28304493, + 0.71468735 -0.63921827 0.28394014, + 0.64222407 -0.70051605 0.31116802, + 0.64034081 -0.7014358 0.31297192, + 0.56579101 -0.752994 0.33597699, + 0.5565452 -0.75624627 0.34401911, + 0.481971 -0.797544 0.36280501, + 0.497953 -0.79359698 0.34963799, + 0.42491505 -0.82839811 0.36497104, + 0.44830793 -0.82425988 0.34585497, + 0.37760007 -0.85385013 0.35827103, + 0.3925111 -0.85218316 0.3460041, + 0.324763 -0.87631798 0.35580301, + 0.33319688 -0.87597871 0.34877089, + 0.26877412 -0.89488143 0.35629717, + 0.27117005 -0.89497024 0.35425308, + 0.21162893 -0.90874869 0.35970688, + 0.20934197 -0.90847486 0.36173096, + 0.15594098 -0.91769487 0.36540198, + 0.14986797 -0.91643876 0.37105191, + 0.10349999 -0.92192888 0.37327597, + 0.095439643 -0.9195174 0.38128617, + 0.056371793 -0.92226487 0.38242593, + 0.048709501 -0.91922802 0.390701, + 0.017141702 -0.92018515 0.39110807, + 0.0103966 -0.91681802 0.39917001, + -0.013791503 -0.91678023 0.3991541, + -0.018245298 -0.91406989 0.40514594, + -0.036111496 -0.9136259 0.40494895, + -0.038045783 -0.91222256 0.4079248, + -0.049968012 -0.91174322 0.40771008, + -0.048721399 -0.91280597 0.40547699, + -0.055889599 -0.91246301 0.40532401, + -0.053705018 -0.91464531 0.40067413, + -0.057073314 -0.91447425 0.40059909, + -0.054396681 -0.91762465 0.39370784, + -0.054214388 -0.91763377 0.39371192, + -0.049788292 -0.92382687 0.37955895, + -0.047590394 -0.92392588 0.37959993, + -0.0441874 -0.92972302 0.36559901, + -0.039805684 -0.92989463 0.36566588, + -0.035627212 -0.93884933 0.34248012, + -0.046249576 -0.9384405 0.34233084, + -0.049527481 -0.93305767 0.35630089, + -0.052079018 -0.93293637 0.35625511, + -0.055615392 -0.92816389 0.36799297, + -0.055396818 -0.92817533 0.36799711, + -0.060081594 -0.92282391 0.38050795, + -0.057850685 -0.92294574 0.38055792, + -0.059509907 -0.92132711 0.38420707, + -0.053494319 -0.92164135 0.38433814, + -0.054117307 -0.9211241 0.38548905, + -0.043162502 -0.92161614 0.38569507, + -0.042407501 -0.92215002 0.38450101, + -0.026013499 -0.92266798 0.38471699, + -0.021017194 -0.92563474 0.3778339, + 0.00189309 -0.92583799 0.37791601, + 0.009882764 -0.92970437 0.36817411, + 0.040633097 -0.9289819 0.36788797, + 0.050896011 -0.93286526 0.35661209, + 0.089634605 -0.93031609 0.35563704, + 0.10053898 -0.93333477 0.34464192, + 0.14745604 -0.92783326 0.3426111, + 0.15762495 -0.92965162 0.33301988, + 0.212276 -0.91996503 0.32955, + 0.21931793 -0.92055565 0.3232289, + 0.2808961 -0.90553927 0.31795612, + 0.28268385 -0.90552658 0.31640387, + 0.34932089 -0.88455969 0.30907789, + 0.34552801 -0.88491303 0.31231299, + 0.4156858 -0.85766059 0.30269384, + 0.40498483 -0.8595286 0.31176585, + 0.477662 -0.82589298 0.299566, + 0.46045321 -0.83021343 0.31421116, + 0.53474593 -0.7903049 0.29910696, + 0.50958288 -0.79840779 0.3207339, + 0.58418387 -0.75312483 0.30254295, + 0.56672513 -0.76009417 0.3179301, + 0.64133519 -0.7078352 0.29607207, + 0.64824528 -0.70424736 0.28950614, + 0.71989167 -0.64195973 0.26390088, + 0.72089702 -0.64127302 0.262824, + 0.78723967 -0.57058471 0.23385189, + 0.77565253 -0.58043367 0.24791086, + 0.84962028 -0.48500818 0.20715308, + 0.84523112 -0.49398807 0.20386302, + 0.89350057 -0.41510278 0.17130792, + 0.89196068 -0.41726586 0.17405593, + 0.93163598 -0.33538401 0.1399, + 0.93015522 -0.33806908 0.14325003, + 0.96051788 -0.25616997 0.10854699, + 0.95931953 -0.25907987 0.11217695, + 0.98069549 -0.17944309 0.077695735, + 0.97993052 -0.18210891 0.081071161, + 0.99329448 -0.10561905 0.047019422, + 0.99281663 -0.10839996 0.050640982, + 0.99931961 -0.033417188 0.015611394, + 0.9992739 -0.034220595 0.016754499, + 0.99935448 0.032265514 -0.015797308, + 0.99930489 0.033112697 -0.017122298, + 0.99420625 0.095480226 -0.049372211, + 0.99371433 0.098107539 -0.053915519, + 0.9837845 0.15718308 -0.086380646, + 0.98434722 0.15544903 -0.083043724, + 0.97100425 0.21086004 -0.11264503, + 0.97419977 0.20369996 -0.097165778, + 0.95918286 0.25523597 -0.12174898, + 0.96286315 0.24858703 -0.10535201, + 0.94659811 0.29685703 -0.12580901, + 0.95055324 0.29089406 -0.10876203, + 0.93301874 0.33703992 -0.12601598, + 0.93710786 0.33180597 -0.10832199, + 0.91818166 0.37659886 -0.12294596, + 0.922252 0.37213901 -0.104708, + 0.90182167 0.41595685 -0.11703695, + 0.9057284 0.41228822 -0.098358944, + 0.88384587 0.45500895 -0.10855099, + 0.88748199 0.45209101 -0.089383699, + 0.863967 0.49398601 -0.0976668, + 0.86724389 0.49175495 -0.077878989, + 0.8417241 0.53326207 -0.084452406, + 0.8445279 0.53166693 -0.064054489, + 0.81677085 0.57281995 -0.06901259, + 0.81895989 0.57180697 -0.048388094, + 0.78916752 0.61199063 -0.051788568, + 0.7906785 0.61144865 -0.030952081, + 0.75877732 0.65051723 -0.032929812, + 0.65163499 0.75841397 -0.0134176, + 0.68806601 0.72553903 -0.0125845, + 0.68719578 0.72558075 -0.035980888, + 0.7234478 0.6895318 -0.034193192, + 0.72174376 0.68979573 -0.057164282, + 0.75565284 0.65273482 -0.054092988, + 0.75311589 0.65336895 -0.076976292, + 0.78471279 0.6156019 -0.072526783, + 0.7813673 0.61674625 -0.09533824, + 0.81105483 0.5781039 -0.089364775, + 0.80701613 0.57986605 -0.11171602, + 0.83499712 0.54031807 -0.10409702, + 0.8303501 0.54280704 -0.12601301, + 0.85646313 0.50283605 -0.11673401, + 0.85126168 0.50616181 -0.13839695, + 0.87574625 0.46567813 -0.12732802, + 0.87004131 0.46995518 -0.14889707, + 0.89332724 0.4284181 -0.13573703, + 0.88724297 0.43371299 -0.15714, + 0.9095369 0.39076594 -0.14157899, + 0.90316522 0.39718008 -0.16291304, + 0.92442012 0.35284704 -0.14472902, + 0.91783136 0.36051112 -0.16618507, + 0.93828279 0.31410292 -0.14479198, + 0.93155915 0.32317302 -0.16660401, + 0.9514029 0.27371696 -0.14110799, + 0.9488259 0.27793697 -0.14993499, + 0.96928209 0.21646303 -0.11677302, + 0.99431491 0.098252185 -0.041041795, + 0.98485965 0.15995894 -0.066817977, + 0.98404121 0.16302705 -0.071309917, + 0.97169524 0.21643804 -0.094672821, + 0.97140813 0.21774803 -0.094615512, + 0.95352525 0.27635205 -0.12008003, + 0.95215279 0.27902395 -0.12470197, + 0.93180442 0.33137214 -0.14809808, + 0.92949736 0.33481613 -0.15470307, + 0.9059031 0.38443205 -0.17762801, + 0.90244913 0.38843307 -0.18629402, + 0.87560397 0.43553001 -0.20888101, + 0.87063581 0.43997788 -0.22002894, + 0.84078419 0.48419911 -0.24214306, + 0.84565586 0.48072594 -0.23188096, + 0.81804788 0.51803392 -0.24987698, + 0.83139479 0.50999087 -0.22066294, + 0.80379981 0.54598391 -0.23623595, + 0.81555986 0.53982693 -0.20844397, + 0.78728515 0.57519811 -0.22210206, + 0.79771829 0.57057118 -0.19517708, + 0.7683838 0.60554087 -0.20713896, + 0.77765316 0.60217911 -0.18065405, + 0.74743617 0.63631618 -0.19089505, + 0.755584 0.63401598 -0.164671, + 0.72412062 0.66752571 -0.17337491, + 0.73116034 0.66610628 -0.14733307, + 0.69798702 0.699211 -0.15465499, + 0.70395398 0.69850302 -0.128617, + 0.66883278 0.73112178 -0.13462396, + 0.6737628 0.73095983 -0.10835798, + 0.63701975 0.76251471 -0.11303596, + 0.64090729 0.76272833 -0.086507142, + 0.6024729 0.79305482 -0.089946575, + 0.60528612 0.79346919 -0.063523814, + 0.5648421 0.82256716 -0.065853417, + 0.85405731 -0.49583519 0.15726906, + 0.79811716 -0.57430613 0.18215804, + 0.81328082 -0.55844986 0.16342595, + 0.75203419 -0.63259315 0.18512304, + 0.77400303 -0.61258298 0.160192, + 0.70940399 -0.68187302 0.178312, + 0.72786683 -0.66710579 0.15868096, + 0.6595673 -0.73124337 0.17393708, + 0.674793 -0.72074902 0.158667, + 0.60269004 -0.77931511 0.17156002, + 0.61252022 -0.77363729 0.16218606, + 0.53733706 -0.82542413 0.17304301, + 0.54093623 -0.8237564 0.16974507, + 0.46467182 -0.86726171 0.17870994, + 0.46043 -0.86873502 0.182493, + 0.38532394 -0.90307087 0.18970597, + 0.37327987 -0.90583068 0.20033193, + 0.30201 -0.93081301 0.20585699, + 0.28393915 -0.93279743 0.22196311, + 0.21925303 -0.94916612 0.22585803, + 0.19779296 -0.94897479 0.24561094, + 0.14245002 -0.95822811 0.24800603, + 0.12042003 -0.95546025 0.26943406, + 0.07561706 -0.95970851 0.27063188, + 0.05678568 -0.95520866 0.29043391, + 0.021875994 -0.95652378 0.29083294, + 0.0102493 -0.95250899 0.30433801, + -0.015856102 -0.95243913 0.30431604, + -0.024907697 -0.94837886 0.31615996, + -0.043052476 -0.94779354 0.31596485, + -0.047664218 -0.94524336 0.32286713, + -0.060079724 -0.94460934 0.32265112, + -0.055919327 -0.94730347 0.31541914, + -0.065164424 -0.94677138 0.31524211, + -0.063699499 -0.947864 0.312244, + -0.068868175 -0.94753766 0.31213689, + -0.066231295 -0.94982189 0.30569896, + -0.067993596 -0.94970888 0.30566296, + -0.06510181 -0.9526251 0.29709804, + -0.063908584 -0.95269877 0.29712093, + -0.062558785 -0.95431876 0.29216793, + -0.052445181 -0.95487565 0.29233888, + -0.033246201 -0.978405 0.204006, + -0.027142908 -0.97858536 0.20404407, + 0.013867698 -0.99887788 -0.045285095, + 0.0086328173 -0.99893665 -0.045287784, + 0.038981907 -0.94980127 -0.31041607, + 0.022460693 -0.95028377 -0.31057394, + 0.040238496 -0.81704789 -0.57516396, + 0.012934498 -0.81764179 -0.57558191, + 0.52535719 -0.85061628 0.021255607, + -0.52524096 -0.8507989 0.016224798, + -0.52481693 -0.85049587 0.034983996, + -0.48050305 -0.87625211 0.036043406, + -0.47942293 -0.87536585 0.062355593, + -0.43426594 -0.89850789 0.064004093, + -0.43267021 -0.89690542 0.091418147, + -0.38671294 -0.91744685 0.09351179, + -0.38466907 -0.91496509 0.12193701, + -0.33804888 -0.93288064 0.12432496, + -0.33565596 -0.9293679 0.15365699, + -0.28927007 -0.94442624 0.15614703, + -0.28665206 -0.93974823 0.18629004, + -0.24083294 -0.95204073 0.18872696, + -0.238141 -0.94610202 0.21949901, + -0.19303897 -0.95580488 0.22174998, + -0.19043905 -0.94853622 0.25300607, + -0.146304 -0.95582199 0.25494999, + -0.14401296 -0.94731963 0.28608692, + -0.10155801 -0.95234913 0.28760603, + -0.099747062 -0.94271964 0.31832388, + -0.058996271 -0.94579452 0.31936187, + -0.057809483 -0.93509477 0.34965092, + -0.018725796 -0.93649673 0.35017592, + -0.01830229 -0.9248696 0.37984383, + 0.0187872 -0.92486101 0.379841, + 0.019203791 -0.93648261 0.35018781, + 0.058268499 -0.93506402 0.349657, + 0.059447184 -0.94574678 0.31941992, + 0.10017604 -0.94265634 0.31837711, + 0.10198595 -0.95231152 0.28757885, + 0.14440992 -0.94726855 0.28605586, + 0.14670594 -0.95580167 0.25479493, + 0.19087192 -0.94849163 0.2528469, + 0.19348291 -0.95579851 0.22138989, + 0.23864703 -0.94605911 0.21913403, + 0.2413521 -0.95202035 0.18816608, + 0.2872051 -0.93969035 0.18572906, + 0.28981894 -0.94435173 0.15557897, + 0.33624092 -0.92924976 0.15309097, + 0.33861485 -0.93272561 0.12394794, + 0.385198 -0.914792 0.121565, + 0.38720399 -0.91722202 0.093685299, + 0.43313494 -0.8966639 0.091585495, + 0.4346849 -0.89822376 0.065138988, + 0.47974494 -0.87510985 0.063462794, + 0.48079181 -0.87598872 0.038508885, + 0.52495986 -0.8503058 0.037379894, + -0.7568838 -0.65353084 0.0049224086, + -0.64938325 -0.75988132 0.029696912, + -0.64986819 -0.76000416 0.0080649117, + -0.65289772 -0.75741565 0.0067943069, + -0.65297985 -0.75734484 0.0067935684, + -0.68827194 -0.72539496 0.0091685392, + -0.68784279 -0.72532576 0.02783579, + -0.64908415 -0.76015717 0.029172508, + -0.64806628 -0.75986737 0.051105328, + -0.60761195 -0.79244387 0.053296294, + -0.60598797 -0.79176986 0.076675594, + -0.5637427 -0.82210457 0.079613164, + -0.56147993 -0.82086688 0.10448799, + -0.51752692 -0.84881788 0.10804599, + -0.51463205 -0.84682012 0.13434902, + -0.46984023 -0.87184739 0.13832006, + -0.46634912 -0.86888617 0.16599804, + -0.42103791 -0.89092976 0.17020896, + -0.41702616 -0.88680828 0.19914907, + -0.371333 -0.90593702 0.203445, + -0.36692801 -0.90048403 0.233436, + -0.3211329 -0.91673177 0.23764794, + -0.31653598 -0.90985686 0.26826397, + -0.27155107 -0.92313522 0.27217907, + -0.26698792 -0.91483772 0.30296788, + -0.22323506 -0.92534125 0.30644706, + -0.21888289 -0.9155826 0.33734086, + -0.17653091 -0.9235996 0.34029484, + -0.17259505 -0.91241729 0.37108713, + -0.13190401 -0.91822499 0.373449, + -0.12858702 -0.90572923 0.4038811, + -0.090183958 -0.90958959 0.40560281, + -0.087642126 -0.89585823 0.4356111, + -0.051493973 -0.89812559 0.43671378, + -0.049873222 -0.88326442 0.46621522, + -0.015982596 -0.88425177 0.46673688, + -0.015419397 -0.86845684 0.49552488, + 0.016107501 -0.86844712 0.49552006, + 0.016666496 -0.88421375 0.46678489, + 0.050547607 -0.88320613 0.46625307, + 0.052162692 -0.8980509 0.43678793, + 0.08822722 -0.89576823 0.43567809, + 0.090757757 -0.9094696 0.40574381, + 0.12909597 -0.90559673 0.4040159, + 0.13240601 -0.91809011 0.37360302, + 0.17308001 -0.91226614 0.37123302, + 0.17700395 -0.92343378 0.34049892, + 0.21929394 -0.91541076 0.33753991, + 0.22364897 -0.92519188 0.30659598, + 0.26734397 -0.91468489 0.30311498, + 0.27193287 -0.9230426 0.27211189, + 0.31689811 -0.9097513 0.26819408, + 0.32151192 -0.91665876 0.23741694, + 0.36734211 -0.90037632 0.23320009, + 0.37179092 -0.90588379 0.20284496, + 0.4175089 -0.88671476 0.19855295, + 0.421545 -0.89085299 0.16935401, + 0.46684694 -0.86877888 0.16515799, + 0.47031882 -0.87171268 0.13753995, + 0.51512587 -0.84664083 0.13358396, + 0.51797479 -0.84859771 0.10762896, + 0.56191564 -0.82062054 0.10408094, + 0.56411684 -0.8218227 0.079872169, + 0.60631174 -0.79149771 0.076924868, + 0.60787499 -0.792153 0.054604199, + 0.64823818 -0.75963515 0.05236261, + 0.68675357 -0.72522056 0.049240671, + 0.64781535 -0.7600475 0.05160543, + 0.64631593 -0.75959486 0.072742395, + 0.60570592 -0.79206491 0.075851895, + 0.60355514 -0.79116219 0.098911621, + 0.56111681 -0.82134271 0.10268496, + 0.55827487 -0.81978184 0.12761997, + 0.51416594 -0.84748286 0.13193199, + 0.5106312 -0.84503531 0.15865406, + 0.46573982 -0.8697257 0.16328993, + 0.46154588 -0.86615282 0.19171496, + 0.41626093 -0.88775885 0.19649696, + 0.41152105 -0.88286114 0.22628903, + 0.36600202 -0.9014731 0.23106003, + 0.36094704 -0.89517111 0.26150703, + 0.31552801 -0.91084599 0.26608601, + 0.31035784 -0.90306157 0.29691386, + 0.26596892 -0.91575468 0.30108789, + 0.26090404 -0.90648609 0.33198202, + 0.21793292 -0.9164387 0.33562687, + 0.21315607 -0.90565932 0.36653212, + 0.17183501 -0.91317499 0.369573, + 0.16755992 -0.90095758 0.40024883, + 0.12800997 -0.90635973 0.40264791, + 0.12443103 -0.89279723 0.43293208, + 0.087363467 -0.89634973 0.43465486, + 0.084635369 -0.88152069 0.46449783, + 0.049949691 -0.88359088 0.46558794, + 0.048224088 -0.86767185 0.49479288, + 0.0159047 -0.86857301 0.49530599, + 0.015316902 -0.8519581 0.52338606, + -0.014614697 -0.8519668 0.5233919, + -0.015203401 -0.86859012 0.49529806, + -0.047550391 -0.86770791 0.49479493, + -0.0492783 -0.88364702 0.46555299, + -0.083993107 -0.88159513 0.46447307, + -0.086732507 -0.89647013 0.43453306, + -0.12384898 -0.89293289 0.43281895, + -0.12744203 -0.90653223 0.4024401, + -0.16701598 -0.90114689 0.40004995, + -0.17129607 -0.91336441 0.36935517, + -0.21273196 -0.90584677 0.36631492, + -0.21751292 -0.91661572 0.33541587, + -0.26053187 -0.9066686 0.33177584, + -0.26559609 -0.9159193 0.30091611, + -0.31001186 -0.9032346 0.29674885, + -0.31515184 -0.91096157 0.26613587, + -0.36059612 -0.89529729 0.2615591, + -0.36562011 -0.90155429 0.23134808, + -0.4111411 -0.88296425 0.22657706, + -0.4158282 -0.88781041 0.19717909, + -0.46111879 -0.86623156 0.19238591, + -0.46528989 -0.86979282 0.16421296, + -0.51013613 -0.84516317 0.15956305, + -0.51369786 -0.8476398 0.13274497, + -0.55780494 -0.81997788 0.12841299, + -0.56069577 -0.82157558 0.10311995, + -0.60317004 -0.79140311 0.099333115, + -0.60538369 -0.79233462 0.075607963, + -0.64605623 -0.75983828 0.072507024, + -0.64762002 -0.76030099 0.0503067, + -0.68660104 -0.72544807 0.048000507, + -0.68756163 -0.72561163 0.027327588, + -0.72473097 -0.68854392 0.025931597, + -0.72512966 -0.68856162 0.0083607566, + -0.72397494 -0.68976897 0.0088961991, + -0.72400337 -0.68979633 0.00058712129, + -0.75689316 -0.65353817 -0.00088712922, + -0.75690609 -0.65352309 -0.00088794914, + -0.75689769 -0.65351474 0.0049222582, + -0.75972337 -0.65017432 0.0096867746, + -0.75939471 -0.65018678 0.024014091, + -0.72446883 -0.68883783 0.025441594, + -0.72357798 -0.68878698 0.044805199, + -0.68617779 -0.72589976 0.047219381, + -0.68470228 -0.72563034 0.068143331, + -0.64545685 -0.76045084 0.071413286, + -0.64332426 -0.75980431 0.093975239, + -0.60241675 -0.79214573 0.097975262, + -0.59957832 -0.79093534 0.12217706, + -0.55689621 -0.82084644 0.12679806, + -0.55334377 -0.81886458 0.15254992, + -0.50903517 -0.84618729 0.15764005, + -0.50477624 -0.8432014 0.18496609, + -0.45987794 -0.86735886 0.19026497, + -0.45497885 -0.8631447 0.21903293, + -0.40980914 -0.8841483 0.22436208, + -0.40444699 -0.87856603 0.25405601, + -0.35916299 -0.89654303 0.25925401, + -0.35352808 -0.88948321 0.28954706, + -0.30851504 -0.90450311 0.29443604, + -0.30279705 -0.89586127 0.32518709, + -0.25903007 -0.90790623 0.3295601, + -0.25344712 -0.89765841 0.36051917, + -0.21127801 -0.90700901 0.36427501, + -0.20605704 -0.89519322 0.39518309, + -0.16567302 -0.90218312 0.39826906, + -0.16102906 -0.88886827 0.42893216, + -0.12265097 -0.89382178 0.4313229, + -0.11877196 -0.87906969 0.46165982, + -0.08302968 -0.88227975 0.46334487, + -0.080101028 -0.86630332 0.49305418, + -0.046915494 -0.86813891 0.49409893, + -0.045103602 -0.85134912 0.52265704, + -0.014366397 -0.8521288 0.52313489, + -0.013754196 -0.83475882 0.55044389, + 0.01445619 -0.83475041 0.55043858, + 0.015068596 -0.8521198 0.52312988, + 0.045783985 -0.85132271 0.52264082, + 0.047592491 -0.86810088 0.49410093, + 0.08078292 -0.86624515 0.49304512, + 0.083700627 -0.88218528 0.46340418, + 0.11937697 -0.87896079 0.46171087, + 0.12324195 -0.89367968 0.43144885, + 0.16155596 -0.88871479 0.42905191, + 0.16618904 -0.90201622 0.39843208, + 0.20649503 -0.89502209 0.39534205, + 0.21170105 -0.90682322 0.36449209, + 0.25385109 -0.89746028 0.36072811, + 0.25942397 -0.90770686 0.32979897, + 0.30311999 -0.895666 0.32542399, + 0.30885088 -0.90433973 0.29458588, + 0.35384911 -0.88930929 0.28968909, + 0.35951498 -0.8964169 0.25920197, + 0.4047671 -0.87843424 0.25400206, + 0.41017106 -0.88406211 0.22404003, + 0.45534316 -0.86303431 0.21871108, + 0.46029401 -0.86729002 0.18957201, + 0.50524014 -0.8430742 0.18427804, + 0.50952113 -0.84606719 0.15671204, + 0.55379015 -0.81873029 0.15164806, + 0.55732417 -0.82069027 0.12592605, + 0.59999233 -0.79075146 0.12133207, + 0.60277623 -0.79193032 0.097505137, + 0.64366704 -0.75957012 0.09352091, + 0.64573079 -0.76019382 0.071673788, + 0.68495005 -0.72537309 0.068390809, + 0.68636292 -0.72563893 0.048519094, + 0.72369325 -0.68858427 0.046041515, + 0.72454697 -0.68865496 0.028039696, + 0.75941682 -0.65006584 0.026468394, + 0.76786703 -0.640598 -0.0038019801, + 0.78998929 -0.61305821 0.0087497225, + 0.79001987 -0.61308092 0.00051308091, + 0.78990668 -0.61322677 0.0004920268, + 0.78987688 -0.61320293 0.0087520191, + 0.75977212 -0.65007508 0.012193502, + 0.75895232 -0.65105826 0.010710504, + 0.75899518 -0.65109515 -0.0012353504, + 0.72607285 -0.68749779 0.012846397, + 0.72613198 -0.68755502 0.00071084697, + 0.72609794 -0.68759096 0.00071084691, + 0.72605217 -0.68754816 0.011217803, + 0.72517818 -0.68846315 0.011628402, + 0.72476107 -0.68841308 0.028441304, + 0.68767494 -0.72539991 0.029969396, + 0.68829674 -0.72527176 0.015119194, + 0.68790078 -0.72516876 0.030377489, + 0.64921796 -0.75993586 0.031833895, + 0.61745578 -0.78660172 -0.0024770291, + 0.61743212 -0.7865712 0.0091277221, + 0.61741489 -0.78658479 0.0091279382, + 0.65518671 -0.75523764 0.018613791, + 0.64995384 -0.75988179 0.011815697, + 0.64945394 -0.75971687 0.032247197, + 0.60931498 -0.79221499 0.033626601, + 0.60829395 -0.79178089 0.055331394, + 0.56633615 -0.8221693 0.057455022, + 0.56473297 -0.82129586 0.080930389, + 0.52097106 -0.84946012 0.083705708, + 0.51875895 -0.84794891 0.10895798, + 0.47410589 -0.8732878 0.11221397, + 0.47129518 -0.87092727 0.13916405, + 0.42599306 -0.8933931 0.14275402, + 0.422647 -0.88998699 0.171151, + 0.37676305 -0.9096421 0.17493102, + 0.37297001 -0.90497798 0.204715, + 0.32683203 -0.92179209 0.20851903, + 0.32275504 -0.91572613 0.23932204, + 0.27733392 -0.92955261 0.24293591, + 0.27322087 -0.9221006 0.27400887, + 0.2288401 -0.9331364 0.27728811, + 0.22489293 -0.92430764 0.30834788, + 0.18171801 -0.932814 0.31118599, + 0.17813495 -0.92265576 0.34201491, + 0.13645598 -0.92888188 0.34432298, + 0.13340904 -0.91742533 0.37487713, + 0.093896635 -0.92161036 0.37658715, + 0.091551997 -0.90896499 0.40669501, + 0.054208312 -0.91145623 0.40781009, + 0.052708082 -0.89771968 0.43740284, + 0.017362395 -0.89883369 0.43794584, + 0.016838405 -0.88411331 0.46696919, + -0.016204607 -0.88412243 0.4669742, + -0.016732296 -0.89886075 0.43791488, + -0.052086309 -0.89776611 0.43738207, + -0.05359422 -0.91153628 0.40771216, + -0.091019623 -0.90905923 0.40660408, + -0.093370706 -0.92170912 0.37647605, + -0.132945 -0.91753602 0.374771, + -0.13599901 -0.92899513 0.34419802, + -0.17772505 -0.92277926 0.3418951, + -0.18131301 -0.93293309 0.31106502, + -0.22450392 -0.92444062 0.30823287, + -0.22843793 -0.93322462 0.27732292, + -0.27282104 -0.92220712 0.27404904, + -0.27691898 -0.92962289 0.24313997, + -0.32236099 -0.915811 0.239528, + -0.32639509 -0.92181426 0.20910504, + -0.37250412 -0.90503728 0.20530008, + -0.37627894 -0.90968591 0.17574298, + -0.42211109 -0.89008623 0.17195605, + -0.42547885 -0.89352572 0.14345595, + -0.47076499 -0.87110299 0.13985699, + -0.47360882 -0.8735007 0.11265496, + -0.51832008 -0.84816211 0.10938702, + -0.5205878 -0.8497147 0.083506569, + -0.56439871 -0.82154459 0.080737963, + -0.56606388 -0.8224448 0.056180585, + -0.60807776 -0.79203171 0.05410308, + -0.60913765 -0.79245955 0.030970082, + -0.61494774 -0.7885437 0.0061695478, + -0.61495811 -0.78855717 -0.0020398605, + -0.57557613 -0.81773019 0.0054243612, + -0.57558411 -0.81774217 0.00086838123, + -0.57564992 -0.81769586 0.00086539291, + -0.57564193 -0.81768388 0.0054238397, + -0.60990101 -0.79236698 0.0132435, + -0.60946923 -0.79218233 0.031535011, + -0.56762367 -0.8226366 0.032747284, + -0.56653988 -0.82206184 0.056981783, + -0.52287805 -0.85036713 0.058943808, + -0.52120703 -0.84923309 0.084537305, + -0.47662389 -0.87478381 0.08708068, + -0.47438806 -0.87291211 0.11393201, + -0.42914096 -0.89564091 0.11689898, + -0.42639419 -0.89285141 0.14492908, + -0.380449 -0.91285402 0.148176, + -0.37727708 -0.90896821 0.17731005, + -0.33096802 -0.92618513 0.18066901, + -0.32749501 -0.92104203 0.21078099, + -0.28167215 -0.93533039 0.2140511, + -0.2780669 -0.92883664 0.24482891, + -0.23310994 -0.94033277 0.24785894, + -0.22957291 -0.93246865 0.2789239, + -0.18566006 -0.94140035 0.28159508, + -0.18240601 -0.93222815 0.31253603, + -0.13974501 -0.93883109 0.31475002, + -0.13695396 -0.92840075 0.3454209, + -0.096339621 -0.93287224 0.34708509, + -0.094167434 -0.92123336 0.37744114, + -0.055549376 -0.92391658 0.37853983, + -0.054151393 -0.91121787 0.40834993, + -0.017449703 -0.91241825 0.40888709, + -0.016956292 -0.89873761 0.43815878, + 0.017553899 -0.89872801 0.438155, + 0.018042497 -0.9123919 0.40891993, + 0.054701615 -0.91117424 0.4083741, + 0.05609192 -0.92385137 0.37861913, + 0.094661713 -0.92115313 0.37751305, + 0.096823975 -0.93277377 0.34721491, + 0.13741101 -0.92828715 0.34554502, + 0.14019997 -0.93873078 0.3148469, + 0.18279009 -0.9321214 0.31263015, + 0.18605402 -0.94133514 0.28155303, + 0.22996603 -0.9323861 0.27887604, + 0.23351502 -0.94028813 0.24764703, + 0.27847502 -0.92877114 0.24461403, + 0.28210995 -0.93531978 0.21351996, + 0.32796714 -0.92099541 0.21025011, + 0.33145297 -0.92615086 0.17995399, + 0.37782386 -0.9088797 0.17659794, + 0.38098285 -0.91274172 0.14749494, + 0.42692485 -0.89270669 0.14425695, + 0.42964008 -0.89545625 0.11648003, + 0.47489977 -0.87268758 0.11351895, + 0.47708201 -0.87450999 0.087321803, + 0.52161014 -0.84896219 0.084770821, + 0.52322584 -0.85006469 0.060205776, + 0.56678092 -0.82180989 0.058204692, + 0.56782788 -0.8223868 0.035376094, + 0.60957438 -0.79199648 0.034068819, + 0.60997194 -0.7921989 0.018845499, + 0.57808888 -0.81592983 0.0084671881, + 0.57810909 -0.8159591 0.0009038311, + 0.57797605 -0.81570512 0.023853503, + 0.57814008 -0.8159371 0.00090023311, + 0.57818872 -0.81590259 0.00090023258, + 0.57816792 -0.81587386 0.0084662689, + 0.56861532 -0.82251239 0.012252105, + 0.56806719 -0.82220429 0.035773013, + 0.52472579 -0.85046673 0.037002586, + 0.52366894 -0.84973991 0.060933493, + 0.47931311 -0.87539625 0.062773317, + 0.47771394 -0.87406188 0.088346392, + 0.43255299 -0.89703798 0.090668701, + 0.4304401 -0.89490521 0.11775403, + 0.38446385 -0.91525072 0.12043095, + 0.38189709 -0.91212821 0.14891903, + 0.33538496 -0.92977089 0.15179898, + 0.3324711 -0.92548424 0.18149905, + 0.28629208 -0.94023234 0.18439107, + 0.28317207 -0.93464124 0.21508004, + 0.23772509 -0.94659233 0.21783008, + 0.23458005 -0.93962526 0.24915206, + 0.18998107 -0.94899237 0.25163609, + 0.18704399 -0.94073701 0.282893, + 0.14358905 -0.94771433 0.28499109, + 0.14104892 -0.93823552 0.31594184, + 0.099505283 -0.94300687 0.31754798, + 0.097521245 -0.93238342 0.34806716, + 0.057835385 -0.93528074 0.3491489, + 0.05655038 -0.92360562 0.37914985, + 0.018654298 -0.92492491 0.37969193, + 0.018203106 -0.91230929 0.40909714, + -0.017643502 -0.91231811 0.40910205, + -0.018101297 -0.92496586 0.37961894, + -0.05601928 -0.92366463 0.37908486, + -0.057309825 -0.9353444 0.34906518, + -0.097078323 -0.93245924 0.3479881, + -0.099067159 -0.94307452 0.31748384, + -0.14062402 -0.93831915 0.31588304, + -0.14316604 -0.94777924 0.28498805, + -0.18662108 -0.94082046 0.28289515, + -0.18954791 -0.94903654 0.25179589, + -0.23414192 -0.93969065 0.24931692, + -0.23726504 -0.94660813 0.21826203, + -0.28267005 -0.93469322 0.21551405, + -0.28577793 -0.94026679 0.18501195, + -0.33192489 -0.92555863 0.18211794, + -0.33484408 -0.92986226 0.15243302, + -0.38133019 -0.91226244 0.14954807, + -0.38392609 -0.91542923 0.12079003, + -0.42990279 -0.89511657 0.11810994, + -0.43205991 -0.89729679 0.090458378, + -0.47727981 -0.87431967 0.088142067, + -0.4789297 -0.87569147 0.061568365, + -0.523377 -0.850003 0.059762198, + -0.52446985 -0.8507328 0.034423992, + -0.56794357 -0.82239443 0.033277277, + -0.56848007 -0.8226561 0.0082113212, + -0.575481 -0.81764102 0.0168781, + -0.57556301 -0.81775701 0.000868381, + -0.53669024 -0.84377342 -0.0031686414, + -0.53467 -0.84505397 -0.00344828, + -0.53466719 -0.84504932 0.0047729318, + -0.53474873 -0.84499758 0.0047723376, + -0.53475302 -0.84500402 -0.00272795, + -0.49269405 -0.87020212 0.00090224011, + -0.49264812 -0.87022817 0.00090428925, + -0.49264288 -0.87021881 0.0047161491, + -0.49268889 -0.87019283 0.0047158389, + -0.49270025 -0.87018639 0.0047114422, + -0.49270499 -0.87019598 0.00090223999, + -0.44939494 -0.8933199 0.0048660897, + 0.44708893 -0.89448488 -0.0028866297, + 0.45218995 -0.8919189 -0.0022392597, + 0.45217714 -0.89189333 0.007878473, + 0.452243 -0.89186001 0.0078779198, + 0.45225286 -0.89188069 -0.0040174085, + 0.4079549 -0.91300178 0.00079832383, + -0.29749498 -0.95382488 0.041410495, + -0.29666406 -0.95236325 0.070672914, + -0.25000608 -0.96558934 0.071654424, + -0.24890706 -0.96319425 0.10150002, + -0.20238893 -0.97391266 0.10262996, + -0.20115496 -0.97050273 0.13289496, + -0.15506101 -0.97877097 0.134028, + -0.15383594 -0.97428167 0.16464993, + -0.108899 -0.98015499 0.16564199, + -0.10783003 -0.97453827 0.19659105, + -0.064046904 -0.97824115 0.19733803, + -0.063289911 -0.97150612 0.22840802, + -0.020644907 -0.97325033 0.22881807, + -0.020355895 -0.96544278 0.25981894, + 0.020808093 -0.96543366 0.25981691, + 0.0210944 -0.97326702 0.228706, + 0.063755497 -0.97150302 0.228292, + 0.064512469 -0.9782505 0.1971399, + 0.10841198 -0.97451478 0.19638695, + 0.109482 -0.98013002 0.16540501, + 0.15446793 -0.97422254 0.16440792, + 0.15569103 -0.97869223 0.13387303, + 0.20182504 -0.97038525 0.13273703, + 0.203051 -0.97376502 0.102723, + 0.249477 -0.96303701 0.101592, + 0.2505579 -0.96539062 0.072399177, + 0.29713097 -0.95216286 0.071407191, + 0.36262313 -0.93190533 0.0075487429, + 0.36263201 -0.93193102 -0.00160814, + 0.36270192 -0.93190378 -0.0016002797, + 0.36269182 -0.93187857 0.0075482964, + 0.34486198 -0.93836188 0.023391398, + 0.34451583 -0.93781751 0.042509783, + 0.29794496 -0.95360386 0.043225296, + 0.26955009 -0.96295333 0.0079787727, + 0.31635591 -0.94805276 0.033389192, + 0.29845685 -0.95426154 0.017560693, + 0.29806995 -0.95355678 0.043403689, + 0.25155684 -0.9668414 0.044008374, + 0.25084287 -0.96528655 0.072799161, + 0.20432693 -0.97613066 0.073616967, + 0.20341896 -0.97363478 0.10322798, + 0.15706305 -0.98208421 0.10412402, + 0.15609403 -0.97855425 0.13441104, + 0.11075205 -0.98460346 0.13524106, + 0.10987103 -0.98000222 0.16590405, + 0.065451518 -0.98385721 0.16655704, + 0.064809583 -0.97815675 0.19750695, + 0.021481005 -0.97999126 0.19787805, + 0.021232799 -0.97322488 0.22887197, + -0.020692103 -0.97323614 0.22887403, + -0.020940792 -0.97998863 0.19794893, + -0.064245775 -0.97817862 0.19758293, + -0.064886525 -0.98386735 0.16671807, + -0.10923205 -0.9800455 0.16607007, + -0.11011194 -0.98465955 0.13535494, + -0.15543696 -0.97864276 0.13452797, + -0.15640901 -0.98219413 0.10407201, + -0.20279005 -0.97377121 0.10317902, + -0.2037109 -0.97630954 0.072948061, + -0.25035003 -0.96546412 0.07213781, + -0.25107613 -0.9670375 0.042418819, + -0.297791 -0.95371401 0.041834399, + -0.29818812 -0.95440835 0.013736605, + -0.3135561 -0.94955438 0.0054091318, + -0.31353989 -0.94955963 0.0054091983, + -0.34461817 -0.93853647 0.01969301, + -0.34425992 -0.93799078 0.040723089, + -0.39099792 -0.92019278 0.019124396, + -0.39061406 -0.91970813 0.039467406, + -0.34394217 -0.93812746 0.04025792, + -0.34302297 -0.93679589 0.068911396, + -0.29624507 -0.95253825 0.070069417, + -0.29498398 -0.95030689 0.099505387, + -0.24846198 -0.96337485 0.10087398, + -0.24698392 -0.96014565 0.13084096, + -0.2007039 -0.97068053 0.13227694, + -0.19914696 -0.96636778 0.16270795, + -0.15339798 -0.97444874 0.16406895, + -0.15190601 -0.96897411 0.19497102, + -0.10746004 -0.97467434 0.19611807, + -0.10619698 -0.96802986 0.22724497, + -0.063025087 -0.97159976 0.22808294, + -0.062153623 -0.96381235 0.25923508, + -0.020241491 -0.96548152 0.25968388, + -0.019919006 -0.95671624 0.29034007, + 0.020349894 -0.95670778 0.29033795, + 0.020668007 -0.96548134 0.25965109, + 0.06259279 -0.96379387 0.25919798, + 0.063464582 -0.97160578 0.22793494, + 0.10669599 -0.9680109 0.22709197, + 0.10796095 -0.97468054 0.19581191, + 0.15248792 -0.9689455 0.19465891, + 0.15397798 -0.97440976 0.16375695, + 0.199761 -0.96629399 0.162393, + 0.20131491 -0.97058654 0.13203794, + 0.24760206 -0.96001923 0.13060004, + 0.24906403 -0.9632051 0.10101002, + 0.29558694 -0.95010579 0.099636078, + 0.29682395 -0.95229179 0.070964485, + 0.34342891 -0.93658179 0.069793783, + 0.34433091 -0.93789774 0.042237289, + 0.39082295 -0.91953391 0.041410297, + 0.39119014 -0.92001837 0.023165908, + 0.40791091 -0.91298878 0.007760718, + 0.40792301 -0.91301602 0.00079902902, + 0.40794101 -0.91300797 0.00079902902, + 0.40792891 -0.91298074 0.0077527082, + 0.40794322 -0.91297442 0.0077526039, + 0.43672985 -0.89930069 0.022920093, + 0.43634978 -0.89887661 0.040244583, + 0.39066491 -0.91961175 0.041172989, + 0.38969609 -0.91843522 0.067924917, + 0.34308115 -0.93674743 0.069279328, + 0.34171498 -0.93475491 0.097283788, + 0.29508293 -0.95033878 0.098905675, + 0.29340705 -0.94737226 0.12805504, + 0.24703497 -0.96027386 0.12979898, + 0.24517597 -0.95621288 0.15982999, + 0.19915208 -0.96655947 0.16155908, + 0.197257 -0.96130198 0.192323, + 0.15191397 -0.96918774 0.19389996, + 0.150149 -0.96268803 0.22513799, + 0.10617605 -0.9682225 0.2264331, + 0.10471696 -0.96049863 0.25783092, + 0.062226694 -0.96393687 0.25875396, + 0.061251577 -0.95515466 0.28970292, + 0.020222293 -0.95675564 0.29018891, + 0.019870399 -0.94702387 0.32054797, + -0.019457908 -0.94703138 0.32055113, + -0.019815201 -0.9567551 0.29021904, + -0.060824901 -0.95517099 0.28973901, + -0.061804131 -0.96394849 0.25881213, + -0.10427795 -0.96052951 0.25789389, + -0.10573295 -0.96821851 0.2266569, + -0.14962898 -0.96271491 0.22536898, + -0.15138702 -0.9691931 0.19428504, + -0.19672297 -0.96133387 0.19270997, + -0.19861896 -0.96659786 0.16198498, + -0.24453899 -0.95630401 0.16026001, + -0.24641003 -0.96040314 0.13003102, + -0.29277384 -0.94753653 0.12828894, + -0.29446998 -0.95054388 0.098761387, + -0.34119189 -0.93496066 0.097142264, + -0.34259292 -0.93699974 0.068275988, + -0.38926095 -0.91869187 0.066941895, + -0.39025599 -0.91988301 0.038929898, + -0.43614006 -0.89907414 0.038049202, + -0.43653807 -0.89949512 0.018523501, + -0.40510505 -0.91425711 0.0048975702, + -0.40499693 -0.91430485 0.0048981695, + -0.40507194 -0.91427189 0.0048649595, + -0.40507707 -0.91428214 0.00086408114, + -0.40500176 -0.91431546 0.0008640805, + -0.40510982 -0.9142676 0.00085881958, + -0.44939715 -0.89332527 -0.0034834212, + -0.44708878 -0.89448458 -0.0029784087, + -0.44929716 -0.89337832 -0.002698411, + -0.44929388 -0.89337075 0.004866709, + -0.4812367 -0.87641346 0.017622588, + -0.48082593 -0.87605387 0.036552098, + -0.43579605 -0.89926314 0.037520505, + -0.43474805 -0.89822114 0.064753406, + -0.38880306 -0.91893613 0.066246808, + -0.3872931 -0.91711122 0.094398521, + -0.34060296 -0.9352659 0.096267186, + -0.338716 -0.93250501 0.125323, + -0.29215205 -0.94785023 0.12738603, + -0.29000306 -0.94402426 0.15721504, + -0.24386995 -0.95663273 0.15931496, + -0.24159488 -0.95163351 0.18980391, + -0.19605903 -0.96165115 0.19180202, + -0.19381592 -0.95540154 0.2228079, + -0.14902702 -0.96299314 0.22457802, + -0.14699297 -0.95547575 0.25584993, + -0.103776 -0.96075302 0.257263, + -0.10213698 -0.95206887 0.28832796, + -0.060469978 -0.95532262 0.2893129, + -0.059389908 -0.94561213 0.31982902, + -0.019271107 -0.94710833 0.32033512, + -0.018879903 -0.93642825 0.3503511, + 0.019344697 -0.93641979 0.35034791, + 0.019729201 -0.94708198 0.32038501, + 0.059829313 -0.94556922 0.31987408, + 0.060906615 -0.95530224 0.28928906, + 0.10256396 -0.95203167 0.2882989, + 0.10420001 -0.96072912 0.25718102, + 0.14744608 -0.95542949 0.25576213, + 0.14948994 -0.96299267 0.22427192, + 0.19429508 -0.95537639 0.22249807, + 0.19654408 -0.96164238 0.19134907, + 0.24218588 -0.9515745 0.18934591, + 0.24446088 -0.95656455 0.15881793, + 0.29060003 -0.94392312 0.15671901, + 0.29273406 -0.94771224 0.12707603, + 0.3393251 -0.93232524 0.12501302, + 0.34117991 -0.93503278 0.096487381, + 0.38780984 -0.91687065 0.094613165, + 0.38928482 -0.91865557 0.067300268, + 0.4350999 -0.89797574 0.065785289, + 0.43611807 -0.89900512 0.039887704, + 0.48101488 -0.87585074 0.038860291, + 0.48140281 -0.8762157 0.022300493, + 0.49540606 -0.86862612 0.0078414408, + 0.49542081 -0.8686527 0.00088685669, + 0.49534687 -0.86869484 0.00088685675, + 0.49533206 -0.86866814 0.0078711808, + 0.49548611 -0.86858016 0.0078697316, + 0.49550095 -0.86860687 0.00087998086, + 0.53741723 -0.84331042 -0.0032080116, + 0.53741723 -0.84331143 -0.0029418613, + 0.53669071 -0.84377354 -0.0030425582, + 0.35275099 -0.93571001 -0.00369044, + 0.31648988 -0.94859564 0.00064875977, + 0.31648111 -0.94856733 0.0077328426, + 0.31656989 -0.94853765 0.0077323574, + 0.31657898 -0.9485659 0.00064350793, + 0.31653312 -0.94858134 0.00064350822, + 0.26955789 -0.96298355 -0.0010472095, + 0.26964295 -0.96295977 -0.0010392098, + 0.26963395 -0.96292979 0.0079783881, + 0.25196004 -0.96745414 0.023424102, + 0.25167802 -0.96680212 0.044179402, + 0.20515388 -0.97770941 0.044677775, + 0.20455295 -0.97605973 0.073928282, + 0.15806802 -0.98460811 0.074575707, + 0.15734993 -0.98199755 0.10450695, + 0.11171403 -0.98816025 0.10516302, + 0.11101596 -0.98452663 0.13558295, + 0.066232793 -0.98847491 0.13612698, + 0.065701969 -0.98378754 0.16686893, + 0.021772303 -0.9856841 0.16719101, + 0.021561097 -0.97996986 0.19797496, + -0.020964108 -0.9799825 0.1979771, + -0.021174008 -0.98569036 0.16723105, + -0.065044232 -0.98382348 0.16691507, + -0.065571912 -0.98850322 0.13624203, + -0.11037997 -0.98458177 0.13570197, + -0.11107899 -0.9882369 0.10511498, + -0.15670295 -0.98210573 0.10446298, + -0.15742791 -0.9847514 0.074034058, + -0.20403492 -0.97620863 0.07339187, + -0.20464304 -0.97787726 0.043327611, + -0.25137809 -0.96694034 0.042843014, + -0.21895297 -0.9757129 0.006636139, + -0.21905406 -0.97569025 0.0066358312, + -0.25166804 -0.96759814 0.020425502, + -0.26654693 -0.96380275 0.0060785688, + -0.26655096 -0.96381986 -0.0014030599, + -0.26655796 -0.96381789 -0.0014024499, + -0.26655304 -0.96380115 0.0060785408, + -0.31341404 -0.94922709 0.027198303, + -0.31353 -0.94957799 0.00075268501, + -0.3135609 -0.94956774 0.00075268483, + -0.31354412 -0.94957334 0.00075365527, + -0.35970801 -0.93305498 -0.0043090298, + -0.35970712 -0.93305236 0.004908042, + -0.35968703 -0.93306011 0.0049081403, + -0.35968992 -0.93306977 -0.0020112596, + -0.35275191 -0.93571275 -0.0027916294, + 0.071938105 0.99740911 0.00027063003, + 0.071928501 0.99727601 -0.0163339, + 0.5303092 -0.09606424 -0.84234428, + 0.52482092 -0.062352594 -0.84892589, + 0.47021699 -0.65000099 -0.59698802, + 0.54963487 -0.45141688 -0.70293981, + 0.50630689 -0.46597889 -0.72561485, + 0.54807323 -0.28078413 -0.78789335, + 0.50379294 -0.28997996 -0.81369787, + -0.039220285 -0.99268562 0.11417996, + -0.0088609103 -0.993411 0.114263, + 0.41577405 -0.51506907 -0.74955708, + 0.45950028 -0.50301129 -0.73201042, + 0.37803006 -0.70728403 -0.59736305, + 0.37797019 -0.69787037 -0.60837132, + 0.26956293 -0.8639068 -0.42544192, + 0.28943098 -0.85871786 -0.42288694, + 0.16029605 -0.96243435 -0.21914707, + 0.17608301 -0.95980811 -0.21854803, + 0.032498505 -0.99944413 -0.0074442811, + 0.04188389 -0.99909478 -0.0074416781, + -0.0319486 -0.995067 0.093919799, + -0.025639797 -0.9952479 0.093936883, + -0.00825781 -0.99740702 0.071491897, + 0.55665189 -0.8248468 -0.098824978, + 0.63638729 -0.76589239 -0.091761641, + 0.66393328 -0.73876739 -0.11582505, + 0.73443002 -0.67049402 -0.105121, + 0.75257713 -0.64698708 -0.12261902, + 0.81109232 -0.5746882 -0.10891604, + 0.81911755 -0.56140065 -0.11779493, + 0.86634088 -0.48880893 -0.10256398, + 0.8679533 -0.48549217 -0.10466404, + 0.9057219 -0.41435295 -0.089327089, + 0.90430897 -0.41789299 -0.087125197, + 0.93417162 -0.34931287 -0.07282728, + 0.93148023 -0.35742909 -0.067743719, + 0.95501453 -0.29137185 -0.055223875, + 0.95219624 -0.30158406 -0.048677113, + 0.97061962 -0.23754491 -0.038340885, + 0.96815538 -0.24840508 -0.03114571, + 0.98233813 -0.18566102 -0.023278601, + 0.98053676 -0.19564995 -0.016397197, + 0.99085563 -0.13445495 -0.011268497, + 0.98975199 -0.14269701 -0.0053440998, + 0.99658579 -0.082505479 -0.0030898794, + 0.99611777 -0.088024579 0.0010615898, + 0.99960554 -0.028082987 0.00033868483, + 0.99954337 -0.030154411 0.0019729608, + 0.99957234 0.029182712 -0.0019093807, + 0.9995119 0.031049697 -0.0034581895, + 0.99579024 0.09109842 -0.010146203, + 0.995646 0.092516497 -0.0113894, + 0.98855478 0.14973196 -0.018432997, + 0.98818666 0.15188494 -0.020444693, + 0.97799939 0.20674288 -0.027828783, + 0.97717899 0.210113 -0.031205, + 0.96402663 0.2629219 -0.039047986, + 0.96260822 0.26733005 -0.043818813, + 0.94685835 0.31741512 -0.05202822, + 0.94470078 0.32271391 -0.058275986, + 0.92648125 0.37035108 -0.066878513, + 0.92340744 0.37646118 -0.07480444, + 0.90278298 0.42184901 -0.083823197, + 0.89863425 0.42860308 -0.093573019, + 0.87572926 0.47169212 -0.10298003, + 0.87036312 0.47887105 -0.11467601, + 0.84566432 0.51904017 -0.12429505, + 0.83941019 0.52590913 -0.13715003, + 0.81307268 0.56332183 -0.14690594, + 0.8067919 0.56895995 -0.15928398, + 0.77857113 0.60432106 -0.16918401, + 0.77107817 0.60972613 -0.18350105, + 0.74095309 0.64306504 -0.19353503, + 0.73215783 0.6479758 -0.20993395, + 0.70082998 0.67860198 -0.21985599, + 0.69081897 0.68266493 -0.23819697, + 0.65835005 0.71069205 -0.24797603, + 0.64716196 0.71359897 -0.26824996, + 0.61339593 0.73926795 -0.27789998, + 0.60111827 0.74069625 -0.30004311, + 0.56635213 0.76387018 -0.30943105, + 0.55314302 0.76350498 -0.33330601, + 0.51819885 0.78382671 -0.34217787, + 0.52096719 0.78423828 -0.33699211, + 0.48952094 0.80115688 -0.34426296, + 0.50449586 0.8048088 -0.31267691, + 0.47112781 0.82219368 -0.31943089, + 0.48367682 0.8262887 -0.2886239, + 0.44845301 0.84381002 -0.294745, + 0.45892689 0.84822685 -0.26438093, + 0.42227805 0.86540413 -0.26973504, + 0.43095008 0.87000418 -0.23953006, + 0.39278784 0.8866387 -0.24410991, + 0.39983308 0.89125526 -0.21400404, + 0.35998204 0.90717411 -0.21782602, + 0.36554709 0.91165423 -0.18778205, + 0.32384604 0.92665613 -0.19087203, + 0.32810196 0.9308579 -0.16078798, + 0.28519604 0.9444831 -0.16314101, + 0.28831205 0.94826925 -0.13289703, + 0.24438488 0.96029353 -0.13458194, + 0.24651894 0.96351975 -0.10420198, + 0.20155405 0.97379923 -0.10531402, + 0.20286396 0.97632879 -0.075022481, + 0.15711299 0.98467785 -0.075664096, + 0.11217999 0.99263591 -0.045711696, + 0.15779102 0.98642713 -0.045425802, + 0.15845905 0.98725337 -0.014883406, + 0.15811592 0.9863705 -0.045524877, + 0.20423996 0.97787988 -0.045132995, + 0.20337392 0.97621065 -0.075177968, + 0.24896203 0.96565413 -0.074365005, + 0.24737898 0.9632709 -0.10446399, + 0.29217994 0.95078874 -0.10310998, + 0.2896969 0.94778866 -0.13331296, + 0.3335759 0.93353379 -0.13130797, + 0.33004698 0.93007088 -0.16135998, + 0.37281102 0.91425014 -0.15861501, + 0.36809102 0.91047913 -0.18851203, + 0.40913376 0.89352345 -0.1850009, + 0.40306193 0.88958389 -0.21489897, + 0.44236499 0.871759 -0.210593, + 0.4347972 0.86780542 -0.24055211, + 0.47257 0.84926897 -0.235414, + 0.46334207 0.84547514 -0.26549202, + 0.49984807 0.82633013 -0.25948104, + 0.488787 0.82285303 -0.289828, + 0.52338177 0.80370164 -0.28308186, + 0.51023996 0.8006919 -0.31392297, + 0.54301387 0.78178483 -0.30650994, + 0.52738696 0.77938986 -0.33825198, + 0.55891395 0.76067686 -0.33012998, + 0.55568403 0.76047313 -0.33600003, + 0.59104413 0.73783016 -0.3259961, + 0.60384578 0.73713374 -0.30332187, + 0.63816583 0.71197784 -0.29297093, + 0.64990216 0.70966518 -0.27203405, + 0.68303329 0.6819973 -0.26142913, + 0.69349617 0.6784212 -0.24250306, + 0.7255072 0.64805716 -0.23164906, + 0.73467624 0.64354026 -0.21472508, + 0.76550263 0.61035371 -0.20365189, + 0.77336287 0.60521692 -0.18873897, + 0.80227417 0.5698871 -0.17772104, + 0.808788 0.56449902 -0.164933, + 0.83580017 0.52700013 -0.15397704, + 0.84109747 0.52160132 -0.14313309, + 0.86639702 0.481554 -0.132144, + 0.87170202 0.47494999 -0.120657, + 0.89516324 0.43201607 -0.10975003, + 0.89962769 0.42521185 -0.099322863, + 0.92080873 0.3797909 -0.088713378, + 0.92411065 0.37360689 -0.080233373, + 0.94285274 0.32578191 -0.069962785, + 0.94516736 0.32039911 -0.063271523, + 0.96137589 0.27002397 -0.053323694, + 0.96289039 0.26554909 -0.04822712, + 0.97643661 0.21233092 -0.038561985, + 0.9773289 0.20883398 -0.034879696, + 0.98781502 0.153506 -0.0256387, + 0.9882521 0.15105602 -0.023236401, + 0.995529 0.093358897 -0.0143611, + 0.99566603 0.092064202 -0.0131688, + 0.99949723 0.031389106 -0.0044898507, + 0.99951261 0.030947989 -0.0041058888, + 0.999479 -0.031996101 0.0042449399, + 0.99954325 -0.030104907 0.0026753808, + 0.99550277 -0.094360575 0.0083856881, + 0.99611413 -0.088008806 0.0033391404, + 0.98834378 -0.15212896 0.0057719187, + 0.98972303 -0.142993 -0.00120029, + 0.97815746 -0.2078581 -0.0017447708, + 0.98043466 -0.19658892 -0.010028596, + 0.96479326 -0.26266807 -0.013399503, + 0.96788561 -0.2504169 -0.022107393, + 0.94786787 -0.31742898 -0.028023396, + 0.95159054 -0.30519584 -0.036480382, + 0.92648202 -0.37367901 -0.044666201, + 0.93023038 -0.36331713 -0.051694117, + 0.89892799 -0.43372801 -0.0617125, + 0.90187597 -0.426871 -0.0663395, + 0.863002 -0.499208 -0.077581301, + 0.86346745 -0.49830571 -0.078200057, + 0.81576014 -0.57139707 -0.089670509, + 0.81125629 -0.57854921 -0.084522627, + 0.75323629 -0.65084124 -0.095084138, + 0.73965734 -0.6680333 -0.081478037, + 0.67043942 -0.7365064 -0.089829549, + 0.64461076 -0.76161373 -0.066494077, + 0.56603396 -0.82125789 -0.071701489, + 0.53174615 -0.84583229 -0.042588916, + 0.45001706 -0.89189011 -0.044908002, + 0.39979708 -0.91659826 -0.0031748908, + 0.32233113 -0.94662136 -0.0032788811, + 0.28077489 -0.95923954 0.032013185, + 0.21223308 -0.97667533 0.032595113, + 0.20063692 -0.97871667 0.043109383, + 0.14026093 -0.98915553 0.043569177, + 0.10847698 -0.99126285 0.075037792, + 0.060836706 -0.99530011 0.075343408, + 0.0406183 -0.99440598 0.097503103, + 0.0035889996 -0.9952209 0.097583085, + -0.010564899 -0.99330986 0.11499499, + -0.039757598 -0.99258 0.11491, + -0.038658008 -0.99245125 0.11638803, + 0.011646601 -0.99942613 0.031809803, + -0.05233971 -0.98978627 0.13260403, + -0.049977608 -0.98990613 0.13262002, + -0.011628594 -0.99984455 0.013256993, + 0.017283795 -0.99976277 0.013255897, + 0.15652494 -0.96653163 -0.20326492, + 0.14208992 -0.96866453 -0.20371389, + 0.26826304 -0.86976814 -0.41417205, + 0.2490399 -0.8744157 -0.41638485, + 0.35910088 -0.70350975 -0.61328673, + 0.33545297 -0.72996491 -0.59550196, + 0.41493908 -0.52534211 -0.7428602, + 0.37184188 -0.5359928 -0.7579217, + 0.25605294 -0.76832581 -0.58661085, + 0.32820508 -0.56248814 -0.75887316, + 0.28580397 -0.57063496 -0.76986486, + 0.29790115 -0.079441935 -0.95128548, + 0.28003898 -0.35270998 -0.89284587, + 0.32528192 -0.34742892 -0.87947977, + 0.35464591 -0.12751397 -0.92626476, + 0.30915311 -0.13131805 -0.94190234, + 0.34445 -0.074612997 -0.935835, + 0.32494915 -0.34266314 -0.88147044, + 0.37021899 -0.33658099 -0.86582398, + 0.32852188 -0.55314583 -0.76557368, + 0.37137797 -0.54376692 -0.75259286, + 0.29429385 -0.75101864 -0.59106869, + 0.12293702 -0.9770081 -0.17418902, + 0.11046203 -0.97845125 -0.17444605, + 0.22924592 -0.88863373 -0.39721084, + 0.21192305 -0.89221025 -0.39881009, + 0.31659508 -0.72665817 -0.6097011, + 0.33502704 -0.72179204 -0.60561806, + 0.22987705 -0.88421321 -0.40660009, + 0.24797909 -0.88016629 -0.40473914, + 0.12551394 -0.9740085 -0.18855691, + 0.13886391 -0.97226042 -0.18821888, + -0.0067651891 -0.99867386 0.051036894, + -0.0063930624 -0.99867636 0.051037118, + -0.010679697 -0.99754661 0.069185577, + -0.066169411 -0.9836911 0.16725302, + -0.068008013 -0.98356926 0.16723205, + -0.059225015 -0.98636425 0.15355103, + -0.037862208 -0.98739022 0.15371104, + -0.028507587 -0.98960352 0.14096892, + 0.00044917682 -0.99000567 0.14102696, + 0.014446704 -0.99215221 0.12419903, + 0.052557319 -0.99088436 0.12404004, + 0.075968273 -0.99219567 0.098877065, + 0.12541002 -0.9872151 0.098380715, + 0.13333897 -0.98691374 0.090675376, + 0.19098096 -0.97747678 0.089808278, + 0.22820294 -0.97196978 0.056551084, + 0.29712304 -0.95322722 0.055460613, + 0.34580198 -0.93820387 0.013945298, + 0.42412809 -0.90550226 0.013459203, + 0.46211681 -0.88662273 -0.018663093, + 0.54318875 -0.83942461 -0.01766959, + 0.57586998 -0.816239 -0.046127599, + 0.65316409 -0.75601012 -0.042724002, + 0.67315978 -0.73694474 -0.061386876, + 0.74155098 -0.66858101 -0.0556922, + 0.75023651 -0.65800059 -0.064655863, + 0.80842584 -0.58577687 -0.057559084, + 0.80995101 -0.58348799 -0.059339099, + 0.85863811 -0.50995207 -0.051860709, + 0.85599661 -0.51471877 -0.048315879, + 0.89644122 -0.44122311 -0.04141691, + 0.89191312 -0.45090106 -0.034340605, + 0.92511237 -0.37859714 -0.028833911, + 0.92000109 -0.39143407 -0.019428702, + 0.94714445 -0.32041314 -0.015903607, + 0.94244778 -0.3343069 -0.0055739586, + 0.96443564 -0.26428092 -0.0044064084, + 0.96050155 -0.27820587 0.0061799772, + 0.97799754 -0.20856489 0.0046329978, + 0.97514486 -0.22109798 0.014430598, + 0.98828626 -0.15228803 0.0099395532, + 0.9864735 -0.16287492 0.018487891, + 0.99548721 -0.094290622 0.010702902, + 0.99486512 -0.10001702 0.015491302, + 0.99947864 -0.031906888 0.0049419482, + 0.99946409 -0.032306403 0.0052897106, + 0.99949878 0.031239692 -0.0051150587, + 0.99948347 0.031663816 -0.0055028126, + 0.99555051 0.092838153 -0.016134193, + 0.99538714 0.094318718 -0.017566402, + 0.98788613 0.15255702 -0.028412905, + 0.98741221 0.15509503 -0.031028807, + 0.97659713 0.21089803 -0.042192806, + 0.97564089 0.21446598 -0.046143796, + 0.96167487 0.26805797 -0.057674393, + 0.96004736 0.27262008 -0.063145623, + 0.94334263 0.32326189 -0.074875467, + 0.94084275 0.32875291 -0.08207608, + 0.92154413 0.37671107 -0.094049312, + 0.91798335 0.38297415 -0.10313804, + 0.89619511 0.42839706 -0.11537101, + 0.89182377 0.4346239 -0.12550896, + 0.86775488 0.47748193 -0.13788599, + 0.8634339 0.48250493 -0.14720999, + 0.83746368 0.52270681 -0.15947494, + 0.83193344 0.52794522 -0.17076507, + 0.80424285 0.56545687 -0.18289895, + 0.79737979 0.5706619 -0.19629195, + 0.76772416 0.60593611 -0.20842505, + 0.7595287 0.61074978 -0.22383192, + 0.7279042 0.64380521 -0.23594606, + 0.71825093 0.64794493 -0.25354096, + 0.68556774 0.67795378 -0.26528391, + 0.67456877 0.68102974 -0.2848779, + 0.64070004 0.70831805 -0.29629204, + 0.62843508 0.70998907 -0.31778103, + 0.5934943 0.73461133 -0.32880214, + 0.59717363 0.73453659 -0.32224181, + 0.56544268 0.75530165 -0.33135185, + 0.58156413 0.75636315 -0.29949605, + 0.54886788 0.77719784 -0.30774593, + 0.56249714 0.77906215 -0.27687407, + 0.52853411 0.79989821 -0.28427905, + 0.54004616 0.80237627 -0.2540521, + 0.50445104 0.82316411 -0.26063403, + 0.51412117 0.82610029 -0.2307331, + 0.47660723 0.84671044 -0.23648912, + 0.48463893 0.84994787 -0.20667297, + 0.44565988 0.86985582 -0.21151395, + 0.45216385 0.8731997 -0.18185194, + 0.41185194 0.89210987 -0.18578999, + 0.41698092 0.89540279 -0.15614296, + 0.37495887 0.91325969 -0.15925694, + 0.37886509 0.91635525 -0.12943903, + 0.33512101 0.93291402 -0.131778, + 0.33792698 0.93564987 -0.10180698, + 0.29317501 0.95044899 -0.103417, + 0.29501089 0.95265865 -0.073553368, + 0.24953789 0.96549153 -0.074544162, + 0.25058001 0.96706098 -0.044751801, + 0.204611 0.97779697 -0.045248602, + 0.20505695 0.97864974 -0.014008996, + 0.2174339 0.97592753 -0.016965793, + 0.21746504 0.97606725 -0.0012925003, + 0.21734807 0.97609335 -0.0013022604, + 0.21731597 0.97595388 -0.016966198, + 0.2650829 0.96414465 -0.012499696, + 0.26510388 0.96421951 0.00073161867, + 0.26501197 0.9642449 0.00073161797, + 0.26497391 0.96410662 -0.016945994, + 0.25154608 0.96772838 -0.015046805, + 0.25102198 0.96693987 -0.044892598, + 0.29694113 0.95386833 -0.044285715, + 0.295733 0.95241702 -0.073782802, + 0.34114012 0.93720436 -0.072604321, + 0.33906999 0.935197 -0.102167, + 0.38364407 0.91801912 -0.10029101, + 0.38054693 0.91558391 -0.12996198, + 0.42347595 0.89691687 -0.12731199, + 0.41924214 0.89422631 -0.15682906, + 0.46054918 0.87429029 -0.15333305, + 0.45506611 0.87151217 -0.18270604, + 0.49493283 0.85044372 -0.17828894, + 0.48807475 0.84774256 -0.2076429, + 0.52654403 0.82573915 -0.20225303, + 0.51814514 0.82328016 -0.23180906, + 0.55474913 0.8008762 -0.22550106, + 0.54472089 0.79883784 -0.25521994, + 0.57954603 0.77628314 -0.24801403, + 0.56771207 0.7748431 -0.27806702, + 0.60135311 0.75202417 -0.26987806, + 0.58739811 0.75136518 -0.30068907, + 0.6200909 0.72836983 -0.29148695, + 0.60366905 0.72870004 -0.32338804, + 0.63484716 0.70621717 -0.31341109, + 0.63074428 0.70664233 -0.32065314, + 0.66523284 0.67991084 -0.30852294, + 0.67686325 0.67735523 -0.2881771, + 0.71044916 0.64757818 -0.27550805, + 0.72053295 0.64387894 -0.25739497, + 0.75297481 0.61103487 -0.24426495, + 0.76166165 0.60649073 -0.22812389, + 0.79211819 0.57129115 -0.21488404, + 0.79929799 0.56632698 -0.20098899, + 0.82776111 0.52876806 -0.18765903, + 0.83358932 0.5236572 -0.17581806, + 0.86029559 0.48328277 -0.16226293, + 0.86479884 0.47838289 -0.15255398, + 0.88948524 0.43536308 -0.13883503, + 0.89288568 0.43081686 -0.13096595, + 0.91529399 0.385373 -0.117152, + 0.91875398 0.379666 -0.108374, + 0.93863565 0.33166289 -0.09467186, + 0.94135523 0.32603908 -0.086884625, + 0.95859712 0.27516302 -0.073327005, + 0.96036261 0.27047992 -0.067410976, + 0.97477835 0.21655108 -0.053970519, + 0.97581136 0.21288808 -0.049707517, + 0.9869805 0.15662707 -0.036571119, + 0.98748887 0.15403199 -0.033761498, + 0.99523199 0.095274597 -0.0208827, + 0.9954105 0.093727753 -0.01931159, + 0.9994669 0.031976398 -0.0065883691, + 0.99948525 0.031491607 -0.0061230315, + 0.99944925 -0.032575309 0.0063337213, + 0.99946475 -0.032166891 0.0059604887, + 0.99472743 -0.10083694 0.018684989, + 0.99484622 -0.099821925 0.017794104, + 0.98456562 -0.17229994 0.030713988, + 0.98637265 -0.16294594 0.022751993, + 0.97113866 -0.23622391 0.032983787, + 0.97491252 -0.22160789 0.020868491, + 0.95509589 -0.29499197 0.027779097, + 0.96002787 -0.27949098 0.015210598, + 0.93554527 -0.35268509 0.019193904, + 0.94157463 -0.33674189 0.0064850878, + 0.91192627 -0.41027814 0.0079012727, + 0.91846037 -0.39549515 -0.0037698713, + 0.88284886 -0.46963593 -0.0044765794, + 0.88928527 -0.45712712 -0.014372904, + 0.84675854 -0.53171468 -0.016718091, + 0.85163182 -0.5236249 -0.023243094, + 0.80143565 -0.59749269 -0.026521986, + 0.80293709 -0.59539205 -0.028292503, + 0.74407935 -0.66733831 -0.031711414, + 0.73944408 -0.67268306 -0.026832704, + 0.67134869 -0.74055266 -0.029539986, + 0.65752405 -0.7532571 -0.016310502, + 0.58126014 -0.81352717 -0.017615603, + 0.5551939 -0.83170182 0.0056474088, + 0.47494194 -0.8799969 0.0059753489, + 0.43802786 -0.89817071 0.037695386, + 0.35965404 -0.9322651 0.039126303, + 0.32171112 -0.94411737 0.07172472, + 0.2508471 -0.96524537 0.073329829, + 0.20761497 -0.97180086 0.11179899, + 0.14891396 -0.98237073 0.11301497, + 0.11796904 -0.98274237 0.14248104, + 0.071065865 -0.98715055 0.14311993, + 0.066456422 -0.98675835 0.14795806, + 0.026891697 -0.9885869 0.14823198, + 0.010485698 -0.98581576 0.16750295, + -0.019407509 -0.98568445 0.16748008, + -0.028328408 -0.98338324 0.17931804, + -0.050589021 -0.98251849 0.17916009, + -0.056019794 -0.98068589 0.18739499, + -0.071964979 -0.97968167 0.18720295, + -0.077507287 -0.97735775 0.19688696, + -0.073345028 -0.97766638 0.19694908, + 0.073681518 -0.98868221 -0.13068503, + -0.031964097 -0.99303186 0.11342798, + -0.031497888 -0.99304664 0.11342996, + 0.096426778 -0.98307174 -0.15579396, + -0.022024399 -0.99618888 0.084395193, + -0.024199797 -0.99613887 0.084390894, + 0.10834793 -0.98109639 -0.16034491, + 0.097001337 -0.98225236 -0.16053405, + 0.2114719 -0.89692956 -0.38832581, + 0.19468898 -0.90012389 -0.38970894, + 0.29343212 -0.74303424 -0.60149622, + 0.27579209 -0.74710524 -0.60479122, + 0.17843099 -0.90696388 -0.38154793, + 0.19451903 -0.90414912 -0.38036406, + 0.079138033 -0.98758733 -0.13567804, + 0.074006967 -0.98797762 -0.13573195, + 0.17849407 -0.91066933 -0.37258711, + 0.16342704 -0.91308922 -0.37357709, + 0.25469598 -0.7603429 -0.59750193, + 0.22694397 -0.76575786 -0.60175693, + 0.28577095 -0.57831091 -0.76412785, + 0.24428488 -0.58519369 -0.77322263, + 0.28042191 -0.35709289 -0.89098167, + 0.23569287 -0.36153883 -0.90207458, + 0.21398392 -0.14042796 -0.96669066, + 0.25152111 -0.085200436 -0.96409446, + 0.26183087 -0.13598494 -0.95548552, + 0.26192996 -0.13598199 -0.95545888, + 0.26431203 -0.023533804 -0.96415013, + 0.31109312 0.0014759806 -0.95037836, + 0.30837598 -0.13189898 -0.94207591, + 0.30849484 -0.13189495 -0.94203752, + 0.31121299 0.0014868299 -0.95033902, + 0.31185398 0.0014868598 -0.95012885, + 0.35756403 -0.0021829102 -0.93388611, + 0.35698217 -0.0018673509 -0.93410939, + 0.35406703 -0.12753701 -0.92648309, + 0.39067194 -0.069641493 -0.91789186, + 0.36995289 -0.33161488 -0.86785167, + 0.41542014 -0.32468212 -0.84971029, + 0.41515893 -0.31804296 -0.85234487, + 0.45991111 -0.31042805 -0.83193517, + 0.45976299 -0.30502799 -0.83401197, + 0.50390887 -0.29668593 -0.81120485, + 0.46064395 -0.49134395 -0.73918092, + 0.505 -0.47780001 -0.71880603, + 0.42350778 -0.68030071 -0.59819072, + 0.034095995 -0.99919689 0.021048198, + 0.0092582013 -0.99870414 0.050043609, + 0.00019965497 -0.99874687 0.050045792, + 0.082547277 -0.99522674 -0.052054487, + 0.070231311 -0.99616909 -0.052103806, + 0.22027807 -0.94264734 -0.2507861, + 0.20243102 -0.9463771 -0.25177804, + 0.33493522 -0.83365649 -0.43913028, + 0.31334713 -0.84020132 -0.44257814, + 0.42383406 -0.67006904 -0.60940307, + 0.4047479 -0.6764968 -0.61524886, + 0.29095501 -0.85271198 -0.43385199, + 0.311463 -0.84693801 -0.43091401, + 0.18064506 -0.95491636 -0.23558909, + 0.19739692 -0.95178562 -0.23481591, + 0.049910206 -0.99833411 -0.028947104, + 0.060749676 -0.99773365 -0.028929688, + -0.017250994 -0.99719864 0.072781779, + -0.009684654 -0.99730039 0.072789222, + -0.0084257526 -0.99742335 0.071244925, + 0.02767409 -0.99707663 0.071220078, + 0.04788889 -0.99766779 0.048637088, + 0.09442886 -0.99435067 0.048475381, + 0.12181502 -0.99233115 0.020979602, + 0.18036096 -0.98338073 0.020790394, + 0.22102706 -0.97512722 -0.016554404, + 0.29220894 -0.95621675 -0.016233396, + 0.30715784 -0.95121551 -0.029034387, + 0.38488206 -0.92253613 -0.028159004, + 0.42767709 -0.90171623 -0.063246712, + 0.50987703 -0.85813898 -0.060190201, + 0.53760183 -0.83475071 -0.11906096, + 0.61934209 -0.77725512 -0.11086001, + 0.65756524 -0.73970526 -0.14298305, + 0.72929096 -0.67176896 -0.12985098, + 0.74888998 -0.64596701 -0.147954, + 0.80838573 -0.57379484 -0.13142295, + 0.81972915 -0.55450112 -0.14343204, + 0.86706811 -0.48231506 -0.12476002, + 0.87107718 -0.47368312 -0.12980303, + 0.90819198 -0.40367201 -0.110618, + 0.90816587 -0.40374193 -0.11057699, + 0.93700099 -0.33691901 -0.092275597, + 0.93535078 -0.3422969 -0.089172281, + 0.95764786 -0.27864197 -0.072589591, + 0.95553702 -0.287011 -0.067629002, + 0.97273213 -0.22574903 -0.053193606, + 0.97081977 -0.23506694 -0.047459587, + 0.98384774 -0.17546695 -0.035426393, + 0.98239535 -0.18444505 -0.029655412, + 0.9917385 -0.12665007 -0.020363109, + 0.99086124 -0.13400303 -0.015404603, + 0.99695712 -0.077442311 -0.0089025414, + 0.99658149 -0.082442738 -0.0053557721, + 0.99965262 -0.026299791 -0.0017085294, + 0.99960464 -0.028113591 -0.00035348089, + 0.9996295 0.027220013 0.00034224518, + 0.9995715 0.029246187 -0.0012563594, + 0.99629736 0.085895531 -0.0036899114, + 0.99577826 0.091415823 -0.0083003817, + 0.98889321 0.14801903 -0.013439903, + 0.98849267 0.15046094 -0.015610694, + 0.97855538 0.20488387 -0.021257088, + 0.97785926 0.20787105 -0.024103105, + 0.96507013 0.26024804 -0.030176304, + 0.96375978 0.26452193 -0.034572791, + 0.94845212 0.31424803 -0.041072004, + 0.94641614 0.31951603 -0.046968207, + 0.92867702 0.36694601 -0.0539403, + 0.92580777 0.37298191 -0.061354384, + 0.90570414 0.41828907 -0.068807304, + 0.90182686 0.42500693 -0.077957496, + 0.87948877 0.46810988 -0.08586368, + 0.87444913 0.47533706 -0.096920513, + 0.85030168 0.51568484 -0.10514797, + 0.84402072 0.5231328 -0.11815695, + 0.81819582 0.56081289 -0.12666696, + 0.81105411 0.56777006 -0.14081402, + 0.78344589 0.60318595 -0.14959699, + 0.77623117 0.60889214 -0.16344905, + 0.74683279 0.64227378 -0.17240994, + 0.73837095 0.64756894 -0.18831597, + 0.70770025 0.67840922 -0.19728507, + 0.69805992 0.68295294 -0.21514598, + 0.66620308 0.71131009 -0.22407903, + 0.65547425 0.71478522 -0.24379408, + 0.62230867 0.74086457 -0.25268885, + 0.61053127 0.74297935 -0.2742871, + 0.5762068 0.76672471 -0.28305292, + 0.56356388 0.76717085 -0.30634093, + 0.5289129 0.78816283 -0.31472293, + 0.51557297 0.78667986 -0.33958697, + 0.48077404 0.80504113 -0.34751302, + 0.48311388 0.8055948 -0.3429549, + 0.45135716 0.82103932 -0.34953013, + 0.46553394 0.82585388 -0.31818798, + 0.43166301 0.84172201 -0.324301, + 0.44349593 0.84683686 -0.29356197, + 0.40830085 0.86249369 -0.29898989, + 0.41807708 0.86777121 -0.26867205, + 0.38128799 0.88309801 -0.27341801, + 0.389303 0.88842797 -0.243185, + 0.35057011 0.90330732 -0.24725808, + 0.35701808 0.90854025 -0.21700904, + 0.31650501 0.92263699 -0.220376, + 0.32150403 0.92760813 -0.19020604, + 0.27968991 0.94052166 -0.19285393, + 0.28344014 0.94509947 -0.16263108, + 0.24052492 0.95658362 -0.16460694, + 0.24320009 0.96064335 -0.13423204, + 0.19906695 0.97055674 -0.13561697, + 0.20083195 0.97397178 -0.10509798, + 0.15574098 0.98209679 -0.10597498, + 0.156767 0.98474097 -0.075560302, + 0.11144895 0.99085754 -0.076029666, + 0.11193597 0.99266678 -0.045638587, + 0.066793993 0.99671388 -0.045824695, + 0.066940106 0.99764311 -0.015077202, + 0.072117984 0.99728578 -0.014837096, + 0.072125964 0.99739552 0.00027062988, + 0.022570105 0.99974525 -0.0003279291, + 0.022567308 0.99962038 -0.015809005, + 0.022944095 0.99961174 -0.015808897, + 0.022946892 0.99973667 -0.00032012688, + 0 0.99999255 -0.003865018, + -0.31498501 0.94896299 -0.015926201, + -0.3150129 0.94895375 -0.015925996, + -0.31505296 0.9490729 -0.0014993898, + -0.31502384 0.94908249 -0.0015023493, + -0.26806888 0.96339953 0.0006180167, + -0.30412197 0.95262587 -0.0037217496, + -0.82248461 0.56873769 -0.0075155464, + -0.8217485 0.56911135 -0.029012717, + -0.72514898 0.68851799 -0.0100983, + -0.72427416 0.68867218 -0.034023609, + -0.96920878 0.21673095 -0.11688497, + -0.94887286 0.27782997 -0.14983599, + -0.95112699 0.27414799 -0.14212801, + -0.93120956 0.32358384 -0.16775693, + -0.93804562 0.31440988 -0.14565995, + -0.91756213 0.36075804 -0.16713302, + -0.92430198 0.35294899 -0.145234, + -0.90302414 0.39727107 -0.16347201, + -0.90951276 0.3907519 -0.14177297, + -0.8872267 0.43367186 -0.15734494, + -0.8933894 0.42831022 -0.13566805, + -0.87012947 0.46981773 -0.14881492, + -0.87588429 0.46550018 -0.12702905, + -0.85140544 0.5060057 -0.13808291, + -0.85660613 0.50267404 -0.11638202, + -0.83051503 0.542642 -0.125636, + -0.83511919 0.54017115 -0.10388003, + -0.80712229 0.57976121 -0.11149304, + -0.81109589 0.57802796 -0.089482091, + -0.7814402 0.61663514 -0.09545882, + -0.78473413 0.61551607 -0.073023006, + -0.7532078 0.65320182 -0.077494085, + -0.75576669 0.65257174 -0.054467283, + -0.72195709 0.68954009 -0.057552908, + -0.72372103 0.68926698 -0.033748601, + -0.68743598 0.72537601 -0.035516702, + -0.68833727 0.72531027 -0.010804604, + -0.69035375 0.72340274 -0.010016397, + -0.65416616 0.75625819 -0.011843903, + -0.65405083 0.75635785 -0.011845397, + -0.65409607 0.75640911 -0.0019316502, + -0.61611992 0.7876519 0.0008625589, + -0.97043025 0.21694304 -0.10583402, + -0.95138311 0.27682602 -0.13504702, + -0.94976175 0.27967194 -0.14048597, + -0.92808264 0.33275187 -0.16714895, + -0.92550886 0.33616897 -0.17442398, + -0.9001469 0.38663995 -0.20061196, + -0.90363085 0.38296995 -0.19179498, + -0.87905771 0.42624885 -0.21346992, + -0.88952512 0.41690806 -0.18690301, + -0.86466527 0.45839217 -0.20550108, + -0.8743127 0.45083585 -0.17978995, + -0.8491295 0.49061128 -0.19565211, + -0.85792118 0.48461413 -0.17064704, + -0.83206683 0.52318686 -0.18422896, + -0.84003448 0.51851028 -0.15965308, + -0.8129788 0.55650985 -0.17135395, + -0.820153 0.55295902 -0.14692, + -0.79162085 0.5905239 -0.15690096, + -0.7979055 0.58798063 -0.13276093, + -0.76803553 0.62468165 -0.14104691, + -0.7734431 0.62297308 -0.11700601, + -0.74202025 0.65885723 -0.12374604, + -0.74655795 0.65782297 -0.099600486, + -0.713117 0.69314498 -0.104949, + -0.71678317 0.69263619 -0.080479823, + -0.68115783 0.72724384 -0.084500976, + -0.68393505 0.72711104 -0.059517309, + -0.64652497 0.76034987 -0.062238093, + -0.64838803 0.76042902 -0.0366157, + -0.60914612 0.79214019 -0.038142707, + -0.61006665 0.79225951 -0.011976892, + -0.57689065 0.81681353 -0.003568738, + -0.57941288 0.81502783 -0.0032060493, + -0.53616232 0.84411448 0.00089678151, + -0.57684064 0.81685251 -0.0026019984, + -0.57679188 0.81678283 -0.013306097, + -0.57684338 0.81674647 -0.013305509, + -0.61618006 0.78754413 -0.0098191611, + -0.61620969 0.78758162 0.00085813162, + -0.61621308 0.78757912 0.00085813215, + -0.61616486 0.78751683 -0.012575197, + -0.61607111 0.78759021 -0.012576303, + -0.64995426 0.75990528 -0.010174904, + -0.64900196 0.75989187 -0.036888596, + -0.68684816 0.72594619 -0.035240807, + -0.6850208 0.72604883 -0.059996687, + -0.720927 0.69065702 -0.057072099, + -0.71824008 0.69105107 -0.081114605, + -0.75184232 0.65484726 -0.076865129, + -0.74833983 0.65567982 -0.10035698, + -0.77979064 0.61883372 -0.094717756, + -0.77550668 0.62024277 -0.11784796, + -0.80523884 0.58252889 -0.11068197, + -0.80020016 0.58465409 -0.13363902, + -0.82844609 0.54598707 -0.12480102, + -0.8226673 0.54897618 -0.14779606, + -0.84920168 0.50991285 -0.13727896, + -0.8427031 0.51391107 -0.16045901, + -0.8678118 0.47431087 -0.14809397, + -0.86070585 0.47941193 -0.17131698, + -0.88484573 0.43871388 -0.15677395, + -0.87715787 0.44508794 -0.18025199, + -0.90064102 0.402787 -0.163121, + -0.8924067 0.41062185 -0.18708295, + -0.915214 0.36670199 -0.167072, + -0.90652514 0.37616307 -0.19160803, + -0.92892259 0.32993686 -0.16806093, + -0.92602998 0.333689 -0.17640901, + -0.94849354 0.28006789 -0.14806093, + -0.95015264 0.2773039 -0.14252196, + -0.96870679 0.22075795 -0.11345997, + -0.97051245 0.21657911 -0.10582605, + -0.98358887 0.16210699 -0.079209991, + -0.98448765 0.15899594 -0.074190967, + -0.99425888 0.096964188 -0.045245696, + -0.99929613 -0.034135103 0.015559602, + -0.99934113 0.033025105 -0.015053702, + -0.99931121 0.033567108 -0.015824703, + -0.99435622 0.095963322 -0.04524051, + -0.99386775 0.098780178 -0.04969319, + -0.98443353 0.15700893 -0.078986064, + -0.98304635 0.16147006 -0.086874932, + -0.96906662 0.21733892 -0.11693396, + -0.96977377 0.21580395 -0.11387497, + -0.95275146 0.26864412 -0.14175707, + -0.95773876 0.26019993 -0.12260697, + -0.939834 0.30904099 -0.145622, + -0.94506311 0.30157602 -0.12612602, + -0.92619574 0.34784693 -0.14547797, + -0.93144763 0.34142789 -0.12582596, + -0.91147572 0.38597786 -0.14224295, + -0.91663313 0.38054907 -0.12233602, + -0.89535201 0.423989 -0.13630199, + -0.90030074 0.41949892 -0.11609997, + -0.87780714 0.46166006 -0.12776801, + -0.8823787 0.45809785 -0.10749096, + -0.85844469 0.49934381 -0.11716896, + -0.86256689 0.49661294 -0.096715488, + -0.83681411 0.53739107 -0.10465702, + -0.84042668 0.53539383 -0.083884068, + -0.81261939 0.57577056 -0.090210035, + -0.81566328 0.57440621 -0.068927221, + -0.78602165 0.6137957 -0.073653765, + -0.78842288 0.61295694 -0.051701292, + -0.75672972 0.65141475 -0.054945081, + -0.75840813 0.65098608 -0.032161705, + -0.75792032 0.65227026 -0.010024304, + -0.75978881 0.65010482 -0.0092026079, + -0.7589491 0.65034103 -0.032448404, + -0.79087687 0.61121494 -0.030496197, + -0.78930587 0.61177993 -0.052169394, + -0.81903082 0.57167488 -0.048749387, + -0.81681788 0.57268995 -0.069532491, + -0.84453332 0.53159916 -0.064543523, + -0.84177583 0.53316087 -0.084575579, + -0.86727816 0.49167612 -0.077994816, + -0.86405969 0.49386683 -0.097449362, + -0.8875497 0.45199686 -0.08918757, + -0.88394731 0.45489314 -0.10821003, + -0.90582711 0.41214705 -0.098041818, + -0.90191901 0.41582301 -0.116762, + -0.92233962 0.37199289 -0.10445496, + -0.91823262 0.37649685 -0.12287796, + -0.93713838 0.33173713 -0.10826904, + -0.9329946 0.33703884 -0.12619793, + -0.95052451 0.29092485 -0.10893095, + -0.94649422 0.29699007 -0.12627603, + -0.96278012 0.24873602 -0.10575902, + -0.95901185 0.25552097 -0.12249599, + -0.97407866 0.20398092 -0.097788259, + -0.97082454 0.21123789 -0.11348195, + -0.9842391 0.15578601 -0.083691508, + -0.98377287 0.15721798 -0.086448893, + -0.99371302 0.098104402 -0.0539442, + -0.99419665 0.095524162 -0.049479481, + -0.99930334 0.033140611 -0.017166106, + -0.99935454 0.032263685 -0.015794592, + -0.99927354 -0.034228183 0.016756292, + -0.99932063 -0.033399887 0.015578494, + -0.99283361 -0.10830297 0.050515283, + -0.99327302 -0.105746 0.047185201, + -0.97986639 -0.18232706 0.081356429, + -0.98061991 -0.17970699 0.078038789, + -0.95915973 -0.25945693 0.11267097, + -0.96037275 -0.25651893 0.10900598, + -0.92985278 -0.33862591 0.14389697, + -0.93148023 -0.33568108 0.14022402, + -0.89173913 -0.41758105 0.17443502, + -0.89355189 -0.41503593 0.17120199, + -0.84438211 -0.49526006 0.20429502, + -0.84617817 -0.49326912 0.20166305, + -0.72095174 -0.64175874 0.26148492, + -0.78887498 -0.569125 0.23188999, + -0.78798419 -0.56990713 0.23299506, + -0.78375602 -0.56814098 0.25088301, + -0.78227884 -0.56936187 0.25271896, + -0.8416872 -0.4935331 0.21906106, + -0.83971184 -0.49559987 0.22195694, + -0.8902123 -0.41575515 0.18619806, + -0.8881973 -0.41843116 0.18979208, + -0.92912787 -0.33673796 0.15273799, + -0.92736524 -0.33975708 0.15671304, + -0.95890415 -0.25764403 0.11883801, + -0.95752615 -0.26080203 0.12298802, + -0.97982264 -0.18077594 0.085250169, + -0.97863674 -0.18464996 0.090412378, + -0.99335039 -0.10340104 0.050629418, + -0.99296713 -0.10552102 0.053680506, + -0.99932063 -0.032849789 0.016711194, + -0.99927288 -0.033639196 0.017945997, + -0.99934191 0.032005195 -0.017074298, + -0.9992919 0.032800697 -0.018435199, + -0.99399298 0.095407598 -0.0536227, + -0.99420166 0.094337061 -0.051608883, + -0.98481148 0.15232307 -0.083331436, + -0.98658764 0.14670093 -0.071579278, + -0.97489876 0.20009996 -0.097634174, + -0.97732788 0.19433898 -0.084038891, + -0.96379626 0.24473706 -0.10583302, + -0.96667111 0.23928203 -0.091055609, + -0.95168579 0.28699595 -0.10921298, + -0.95484054 0.28202784 -0.093486652, + -0.93840212 0.32799503 -0.10872401, + -0.94167554 0.32363585 -0.092232555, + -0.92365313 0.36855504 -0.10503402, + -0.92687637 0.36489511 -0.088044032, + -0.90715432 0.40905914 -0.098700337, + -0.91021425 0.4060941 -0.081226222, + -0.88883787 0.44932193 -0.089872696, + -0.89163989 0.44701093 -0.071829095, + -0.86846483 0.48947188 -0.07865198, + -0.87091172 0.48776883 -0.059953779, + -0.84556991 0.52987695 -0.065129593, + -0.84756887 0.52872193 -0.045609396, + -0.81984085 0.5704729 -0.049210887, + -0.82128519 0.56979412 -0.028728608, + -0.79138172 0.61054677 -0.030783288, + -0.79218203 0.61023098 -0.0081074899, + -0.7890057 0.61430675 -0.0098577961, + -0.78904414 0.61433607 -0.00080481113, + -0.78896266 0.61444068 -0.00079953461, + -0.78892469 0.61441076 -0.0098593663, + -0.7579155 0.65229142 -0.0089565553, + -0.75794554 0.65231758 0.00054948067, + -0.75795811 0.65230304 0.00054948108, + -0.73387504 0.67927408 -0.0037762704, + -0.75807601 0.65216601 0.000570192, + -0.75803769 0.65213376 -0.010022196, + -0.72502905 0.68864506 -0.010037101, + -0.72506505 0.68867904 -0.0013364002, + -0.69010597 0.72370797 0.00075148401, + -0.69006461 0.72366357 -0.011044594, + -0.69042897 0.72331601 -0.0110394, + -0.69047081 0.72335982 0.00073201983, + -0.69038802 0.72343898 0.00073202001, + -0.6542058 0.75630385 -0.0043993089, + -0.6601584 0.75111848 -0.0034790121, + -0.45085412 0.89259726 0.00087247923, + -0.49403483 0.86943573 -0.0033454788, + -0.49398589 0.86934984 -0.014452997, + -0.49403882 0.86931968 -0.014452594, + -0.49408889 0.86940682 -0.0028085292, + -0.49254295 0.87028289 -0.0030139696, + -0.400455 0.91631198 -0.00284775, + -0.40648991 0.91365278 -0.0021228495, + -0.45080405 0.89249915 -0.014864801, + -0.48159483 0.8763237 -0.011100196, + -0.48068893 0.8759169 -0.041324295, + -0.52399081 0.85077769 -0.040138286, + -0.52218199 0.85012501 -0.067922801, + -0.56410283 0.82308167 -0.06576208, + -0.56129801 0.82236701 -0.093043201, + -0.60110825 0.7941013 -0.089845233, + -0.59727025 0.7935003 -0.11672904, + -0.63519174 0.76413071 -0.11240796, + -0.63027519 0.7638132 -0.13907804, + -0.66661471 0.73334461 -0.13353094, + -0.66056329 0.73348337 -0.16018207, + -0.69544774 0.70203078 -0.15331393, + -0.68818563 0.70280564 -0.18017991, + -0.72119892 0.67102695 -0.17203198, + -0.71264744 0.67262143 -0.19928412, + -0.744075 0.64057201 -0.189789, + -0.73421317 0.6431672 -0.21741004, + -0.76458889 0.61057794 -0.20639397, + -0.75330234 0.61439329 -0.23464112, + -0.78303897 0.58104098 -0.22190399, + -0.77016997 0.58633697 -0.25109199, + -0.7989648 0.55281991 -0.23673894, + -0.78428888 0.55990595 -0.26720098, + -0.812675 0.52590102 -0.25097299, + -0.8083778 0.52840286 -0.25945294, + -0.83968484 0.4874799 -0.23935895, + -0.84563172 0.48307282 -0.22704093, + -0.87444812 0.43904507 -0.20634903, + -0.87902075 0.43464091 -0.19598396, + -0.90495741 0.38789219 -0.17490509, + -0.90819502 0.383901 -0.166739, + -0.93110287 0.33456296 -0.14530998, + -0.93327338 0.33114311 -0.13908705, + -0.9530645 0.27914387 -0.11724594, + -0.95443135 0.27635109 -0.11265404, + -0.97107548 0.22110711 -0.090133846, + -0.97175503 0.21924099 -0.087324701, + -0.98478836 0.16142505 -0.064296424, + -0.98502052 0.16050893 -0.063019671, + -0.99426991 0.099503584 -0.039067596, + -0.99448574 0.098056979 -0.037186593, + -0.99935746 0.033515316 -0.012710107, + -0.99938655 0.032912984 -0.011971794, + -0.99934226 -0.034079108 0.012395903, + -0.99936914 -0.033519104 0.011742202, + -0.99377853 -0.10511095 0.036821883, + -0.99400812 -0.10353401 0.035053305, + -0.98205489 -0.17863499 0.060479794, + -0.98261487 -0.17636198 0.058004491, + -0.96330649 -0.25496811 0.083857536, + -0.96429265 -0.25218692 0.080879569, + -0.9366219 -0.33360496 0.10699099, + -0.93781954 -0.33108285 0.10430095, + -0.90134889 -0.41308093 0.13013199, + -0.90175372 -0.41242084 0.12941895, + -0.85571218 -0.49371412 0.15492903, + -0.85332841 -0.49675024 0.15833507, + -0.79707587 -0.57535893 0.18339099, + -0.81227219 -0.55954611 0.16468805, + -0.75084299 -0.63360697 0.18648601, + -0.77270114 -0.61381108 0.16176802, + -0.70783883 -0.68305081 0.18001595, + -0.72688407 -0.66790307 0.15982802, + -0.65849692 -0.73191893 0.17514698, + -0.67497295 -0.72058696 0.15863799, + -0.60286123 -0.77918732 0.17153905, + -0.61381012 -0.7728442 0.16108705, + -0.53875369 -0.8247385 0.17190389, + -0.54284501 -0.82282799 0.168147, + -0.46668687 -0.8665148 0.17707495, + -0.46256796 -0.86796188 0.18075699, + -0.38750395 -0.90250486 0.18795097, + -0.37561306 -0.90527612 0.19846903, + -0.30404797 -0.93055588 0.20401096, + -0.28577897 -0.9326269 0.22031197, + -0.22099108 -0.94915235 0.22421607, + -0.19921793 -0.94902265 0.24427091, + -0.14378199 -0.95837188 0.24667796, + -0.12221996 -0.95572865 0.26766592, + -0.077051304 -0.96008509 0.26888603, + -0.057976376 -0.95558763 0.28894791, + -0.022950789 -0.95694554 0.28935885, + -0.0069700992 -0.95139289 0.30790097, + 0.018482296 -0.95125377 0.30785495, + 0.028981708 -0.94644421 0.32156408, + 0.046451297 -0.94581985 0.32135198, + 0.044459514 -0.94692236 0.31837311, + 0.057495676 -0.94629163 0.31816089, + 0.055868287 -0.94733578 0.31533092, + 0.065121189 -0.94680375 0.3151539, + 0.063997723 -0.94764239 0.31285512, + 0.06905067 -0.94732255 0.31274885, + 0.0661631 -0.949826 0.30570099, + 0.067892373 -0.9497155 0.30566484, + 0.065057084 -0.95257479 0.29726893, + 0.063853204 -0.95264912 0.29729202, + 0.063068919 -0.95359439 0.29441512, + 0.052765481 -0.95416564 0.29459089, + 0.033823196 -0.97765589 0.20747297, + 0.027399408 -0.97784823 0.20751405, + -0.014103697 -0.99889874 -0.044747189, + -0.0089511508 -0.99895811 -0.044749904, + -0.039447702 -0.94976014 -0.31048304, + -0.022940088 -0.95024955 -0.31064385, + -0.040910888 -0.8166278 -0.57571286, + -0.013405492 -0.81723851 -0.57614362, + -0.017959002 -0.62513107 -0.78031313, + 0.017355688 -0.62513763 -0.78032154, + 0.017272795 -0.62481874 -0.78057867, + 0.053616811 -0.62401313 -0.77957219, + 0.040015403 -0.81626713 -0.57628703, + 0.06809891 -0.81502509 -0.57541007, + 0.038525116 -0.94841135 -0.31469312, + 0.055858213 -0.94763422 -0.31443509, + 0.013619498 -0.9984709 -0.053575493, + 0.019852895 -0.99836677 -0.053569891, + -0.032807786 -0.98083055 0.19208091, + -0.038008492 -0.98064977 0.19204496, + -0.061612114 -0.95813626 0.27960506, + -0.070930615 -0.95754224 0.27943105, + -0.071754888 -0.95674175 0.28195095, + -0.070594206 -0.95682114 0.28197503, + -0.072849676 -0.95495766 0.2876609, + -0.068117581 -0.95527762 0.2877579, + -0.069787376 -0.95408565 0.29129091, + -0.061250877 -0.95462161 0.29145491, + -0.060966879 -0.95479566 0.29094392, + -0.047548912 -0.95549321 0.29115605, + -0.050829325 -0.95376348 0.29622915, + -0.033951286 -0.95444751 0.29644084, + -0.025798414 -0.95803648 0.28548315, + -0.0017169998 -0.95835388 0.28557798, + 0.012440205 -0.96312934 0.26875108, + 0.045589078 -0.96220255 0.26849189, + 0.062740587 -0.96617079 0.25015494, + 0.105845 -0.96263999 0.24924099, + 0.13039695 -0.96556455 0.22512589, + 0.18462606 -0.95713735 0.22316207, + 0.21132404 -0.95705312 0.19847304, + 0.27579197 -0.94119185 0.19518398, + 0.29989395 -0.93802875 0.17368296, + 0.37200889 -0.91271567 0.16899595, + 0.38997608 -0.90800321 0.15313002, + 0.46628287 -0.87231785 0.14711197, + 0.47624981 -0.86838371 0.13818796, + 0.55326813 -0.82265216 0.13091102, + 0.554986 -0.82174599 0.12932201, + 0.63009501 -0.76707703 0.120719, + 0.62437695 -0.77084988 0.12626898, + 0.69528317 -0.70928317 0.11618403, + 0.68442971 -0.71786565 0.12737694, + 0.75029087 -0.65093994 0.11550198, + 0.73555285 -0.66452181 0.13180597, + 0.79655135 -0.59301829 0.11762306, + 0.77999002 -0.610511 0.137448, + 0.83619869 -0.53503484 0.12045495, + 0.81798089 -0.55686992 0.14423299, + 0.86952287 -0.47811595 0.12383498, + 0.85721409 -0.49506906 0.14174202, + 0.90283871 -0.41337085 0.11835095, + 0.90307188 -0.41297695 0.11794598, + 0.93895334 -0.33081713 0.09448114, + 0.93816149 -0.33255213 0.096240543, + 0.96519625 -0.25121805 0.072702512, + 0.96443754 -0.25345287 0.074978463, + 0.98316622 -0.17520805 0.051831312, + 0.98269635 -0.17720705 0.05390422, + 0.99421978 -0.10271697 0.031245392, + 0.99402249 -0.10414305 0.032767214, + 0.99939364 -0.03321499 0.010450697, + 0.99936938 -0.03374901 0.011043903, + 0.99941146 0.032603815 -0.010669204, + 0.99938512 0.033178102 -0.011339101, + 0.99472123 0.09710072 -0.033185609, + 0.99446636 0.098905034 -0.03541781, + 0.98552525 0.15960404 -0.057154115, + 0.9849059 0.16215998 -0.060535993, + 0.9720605 0.2199069 -0.08209306, + 0.97144365 0.22166993 -0.084614769, + 0.95514613 0.27666402 -0.10560702, + 0.953987 0.27914599 -0.109482, + 0.93471903 0.33085099 -0.129761, + 0.93274599 0.33413401 -0.135423, + 0.91053373 0.38316086 -0.15529394, + 0.90750891 0.38712993 -0.16296598, + 0.88247412 0.43351606 -0.18249202, + 0.87819213 0.43795004 -0.19229802, + 0.85033703 0.48183599 -0.211568, + 0.84461218 0.48645711 -0.22358406, + 0.81442028 0.52725118 -0.24233408, + 0.80702162 0.53178477 -0.25675088, + 0.77469486 0.56943893 -0.27493098, + 0.7797907 0.56703579 -0.26532391, + 0.7503649 0.59872192 -0.28015098, + 0.76574862 0.59285969 -0.24929188, + 0.73565596 0.62439996 -0.26255497, + 0.74898922 0.62022722 -0.23309509, + 0.71840507 0.65115803 -0.24471903, + 0.72999793 0.64834893 -0.21620996, + 0.69855398 0.67880797 -0.226367, + 0.70865625 0.67710024 -0.19834708, + 0.67579824 0.70736122 -0.20721208, + 0.68450898 0.70656198 -0.179493, + 0.6499303 0.73659736 -0.18712309, + 0.65732604 0.73651505 -0.15958701, + 0.62137663 0.76574254 -0.1659199, + 0.62751716 0.76619518 -0.13844603, + 0.59009111 0.7944712 -0.14355503, + 0.59505922 0.79528129 -0.11589804, + 0.55567992 0.82270586 -0.11989498, + 0.55951309 0.82369715 -0.09202192, + 0.51805812 0.85005718 -0.094966725, + 0.47791988 0.87567675 -0.069157586, + 0.52077079 0.85104656 -0.067212373, + 0.52180481 0.85038269 -0.067594275, + 0.56377596 0.82333088 -0.065443993, + 0.56099278 0.82262957 -0.092561558, + 0.60095423 0.79427129 -0.089370728, + 0.59706706 0.79367012 -0.11661401, + 0.63502163 0.76428854 -0.11229693, + 0.63003421 0.76396918 -0.13931303, + 0.66639984 0.73349881 -0.13375597, + 0.66030174 0.73363578 -0.16056193, + 0.69514441 0.70224839 -0.15369309, + 0.68787706 0.70301908 -0.18052502, + 0.72091305 0.67124808 -0.17236702, + 0.71241796 0.67283094 -0.19939697, + 0.74389124 0.64075524 -0.18989107, + 0.73413199 0.643323 -0.217223, + 0.76455164 0.61068869 -0.20620389, + 0.7534532 0.61445212 -0.23400205, + 0.78317463 0.58108968 -0.22129689, + 0.77052712 0.58632505 -0.25002202, + 0.79944313 0.55259806 -0.23564003, + 0.78495491 0.55963892 -0.26580098, + 0.8133862 0.52546811 -0.24957205, + 0.80835372 0.52840781 -0.25951791, + 0.83963788 0.48752195 -0.23943797, + 0.84580803 0.48294601 -0.22665399, + 0.87462473 0.43887186 -0.20596893, + 0.87920141 0.4344562 -0.19558309, + 0.90510315 0.38771605 -0.17454101, + 0.90832025 0.38374409 -0.16641805, + 0.93121123 0.3343901 -0.14501403, + 0.93334436 0.33102512 -0.13889104, + 0.95311826 0.27903205 -0.11707603, + 0.95438474 0.27644393 -0.11282097, + 0.9710319 0.22123498 -0.090289392, + 0.97167188 0.21947996 -0.087648794, + 0.98474348 0.16160308 -0.064536028, + 0.98501521 0.16053204 -0.063044615, + 0.99426776 0.099519581 -0.039083488, + 0.99450254 0.097943954 -0.03703488, + 0.99935925 0.033478409 -0.012659003, + 0.99938834 0.032876212 -0.011921004, + 0.99934465 -0.034030888 0.012339695, + 0.99937135 -0.033472512 0.011687804, + 0.99380451 -0.10492895 0.036638882, + 0.99402291 -0.10342599 0.034951895, + 0.98209876 -0.17845196 0.060306285, + 0.98262835 -0.17630106 0.057961423, + 0.96330464 -0.2549839 0.083829567, + 0.96414322 -0.25262207 0.081302024, + 0.93639076 -0.33408391 0.10751898, + 0.93737614 -0.33201703 0.10531201, + 0.90064287 -0.41422194 0.13138698, + 0.90147471 -0.41287184 0.12992395, + 0.85526019 -0.49430212 0.15554903, + 0.8523528 -0.49417189 0.17113996, + 0.89904875 -0.41373992 0.14328498, + 0.89797503 -0.41540599 0.14518499, + 0.93562967 -0.33321789 0.11645996, + 0.93443888 -0.33560297 0.11914098, + 0.96302003 -0.253905 0.090137601, + 0.96210355 -0.25636789 0.092909954, + 0.98203725 -0.17739704 0.064290315, + 0.98145211 -0.17966202 0.066883408, + 0.99380749 -0.10413405 0.038766317, + 0.99356174 -0.10574298 0.040662788, + 0.99934685 -0.033728395 0.012969998, + 0.99931645 -0.034332115 0.013710206, + 0.99936289 0.033146396 -0.013236698, + 0.99931246 0.034125116 -0.014497707, + 0.99445379 0.096801177 -0.041125089, + 0.99398738 0.09969414 -0.045280114, + 0.98497391 0.15724398 -0.071418889, + 0.98363054 0.16195093 -0.079011261, + 0.97056675 0.21644695 -0.10559798, + 0.96876436 0.22062407 -0.11322804, + 0.95023865 0.27715391 -0.14223996, + 0.9484545 0.28012711 -0.14819908, + 0.92601913 0.33366004 -0.17652102, + 0.92935061 0.32932889 -0.16688295, + 0.90696311 0.37572405 -0.19039303, + 0.91552889 0.36635098 -0.16611399, + 0.89274031 0.41035816 -0.18606706, + 0.90079856 0.40266183 -0.16255893, + 0.87732112 0.44500807 -0.17965402, + 0.88487124 0.43873611 -0.15656805, + 0.86068648 0.47951671 -0.1711209, + 0.86771232 0.47446817 -0.14817306, + 0.8425892 0.51407212 -0.16054104, + 0.8490321 0.51011205 -0.13758701, + 0.82247633 0.54917419 -0.14812306, + 0.82825583 0.54619086 -0.12517098, + 0.80001783 0.58481586 -0.13402197, + 0.80510414 0.58267504 -0.11089302, + 0.77536172 0.62038177 -0.11806995, + 0.77971411 0.61894906 -0.094594613, + 0.74822307 0.65583205 -0.10023201, + 0.75177997 0.65497798 -0.076358803, + 0.71809906 0.69125909 -0.080588505, + 0.72076219 0.6908592 -0.056705315, + 0.68478179 0.72630578 -0.059614778, + 0.68654883 0.72620779 -0.035677992, + 0.64872295 0.76010787 -0.037343495, + 0.6496278 0.76014882 -0.012545997, + 0.61380005 0.78946114 0.00078709511, + 0.61373925 0.78938228 -0.014140205, + 0.61361313 0.78948015 -0.014141904, + 0.61367404 0.78955913 0.0007930611, + 0.65169269 0.75848162 -0.0015307793, + 0.49254277 0.87028259 -0.0031348085, + 0.40045491 0.91631174 -0.0029416992, + 0.57941306 0.81502712 -0.0033671104, + 0.6601578 0.75111783 -0.0036883592, + 0.65191603 0.75827497 -0.0049608299, + 0.65186524 0.75821632 -0.013414104, + 0.68804693 0.72555697 -0.012592098, + 0.68810183 0.72561383 0.00061903783, + 0.68819636 0.72552437 0.00061903731, + 0.68814182 0.72546685 -0.012592797, + 0.72247505 0.69128108 -0.012663902, + 0.72253293 0.69133592 -0.00096510287, + 0.72287405 0.69097906 -0.00098419411, + 0.72281682 0.69092381 -0.012657598, + 0.72493875 0.68871576 -0.011592996, + 0.72408593 0.68884593 -0.034510195, + 0.75820017 0.65120518 -0.032624409, + 0.75658387 0.65161693 -0.054555591, + 0.78831011 0.61313307 -0.051333506, + 0.78593314 0.61397207 -0.073126309, + 0.81565017 0.57448512 -0.068423212, + 0.81255603 0.57587999 -0.090083398, + 0.84038311 0.53548104 -0.083764009, + 0.83670789 0.53751296 -0.10487998, + 0.86246079 0.49675587 -0.096927479, + 0.85830343 0.49950424 -0.11751906, + 0.8822456 0.45827678 -0.10781994, + 0.87767214 0.46183407 -0.12806602, + 0.90018874 0.41966391 -0.11637197, + 0.89528471 0.42410985 -0.13636796, + 0.91657168 0.38067585 -0.12240195, + 0.91147971 0.38604084 -0.14204696, + 0.93146437 0.34145111 -0.12564005, + 0.926301 0.347776 -0.144977, + 0.94517475 0.30142295 -0.12565397, + 0.94006377 0.30874494 -0.14476398, + 0.95792454 0.25987187 -0.12184894, + 0.95302188 0.26821297 -0.14075199, + 0.96997088 0.21536697 -0.11301999, + 0.96909076 0.21728295 -0.11683797, + 0.98305899 0.161431 -0.086804897, + 0.98446602 0.156901 -0.078796104, + 0.99387854 0.098727152 -0.049580976, + 0.99435264 0.09599176 -0.045259785, + 0.99931109 0.033569206 -0.015827801, + 0.99936026 0.032671809 -0.014551104, + 0.9992671 -0.034967203 0.015573402, + 0.99931902 -0.034001801 0.0143301, + 0.99328613 -0.10660301 0.044927903, + 0.99356723 -0.10485803 0.042766713, + 0.98074526 -0.18083005 0.073752113, + 0.98139566 -0.17843693 0.070872076, + 0.96078002 -0.257727 0.102365, + 0.96182966 -0.2550419 0.099182963, + 0.93237126 -0.33692208 0.13102503, + 0.93369138 -0.33440313 0.12804304, + 0.89505631 -0.41646716 0.15946606, + 0.89639831 -0.41448316 0.15707906, + 0.84824389 -0.49523494 0.18768197, + 0.85665613 -0.48521805 0.17522502, + 0.78534567 -0.58225381 0.21026793, + 0.79327285 -0.57480294 0.20079798, + 0.72820175 -0.64701974 0.22602592, + 0.74529624 -0.63358724 0.20760708, + 0.67670119 -0.69965518 0.22925606, + 0.70125723 -0.68297327 0.20441608, + 0.63053697 -0.743568 0.222553, + 0.64970881 -0.73229384 0.20401995, + 0.57645398 -0.78715098 0.219304, + 0.59103101 -0.77996403 0.205763, + 0.51581407 -0.82836014 0.21853003, + 0.52393621 -0.82515341 0.21121711, + 0.44858578 -0.86582458 0.22162689, + 0.44989905 -0.86543912 0.22046803, + 0.3762579 -0.89783978 0.22872195, + 0.36992809 -0.89903724 0.23427606, + 0.29969493 -0.92320478 0.24057394, + 0.28732008 -0.92421335 0.25154909, + 0.223244 -0.94054699 0.25599501, + 0.20654997 -0.94007987 0.27126896, + 0.15080199 -0.94981086 0.27407697, + 0.13285801 -0.94734114 0.29136503, + 0.08680889 -0.9522059 0.29286197, + 0.06969519 -0.94798088 0.31060398, + 0.03299861 -0.94977438 0.31119111, + 0.019540409 -0.94499248 0.32650813, + -0.0080197239 -0.94514245 0.32656014, + -0.015134407 -0.9418695 0.33563814, + -0.035233282 -0.94139254 0.33546785, + -0.040075719 -0.93865949 0.34250915, + -0.053703588 -0.93805873 0.34228891, + -0.055560209 -0.93680614 0.34540904, + -0.063872769 -0.93633956 0.34523681, + -0.059264291 -0.93994987 0.33612797, + -0.065091297 -0.93960798 0.33600599, + -0.062459014 -0.94198525 0.32979208, + -0.064708382 -0.94184977 0.32974491, + -0.061501514 -0.94523025 0.3205581, + -0.060694698 -0.94527698 0.32057399, + -0.057607975 -0.94912052 0.30959886, + -0.054309618 -0.94929636 0.30965611, + -0.052640691 -0.95183188 0.30206797, + -0.041945711 -0.95231426 0.30222207, + -0.027003797 -0.97674286 0.21270697, + -0.020186102 -0.9769001 0.21274103, + 0.0090739578 -0.99916577 -0.039817788, + 0.0046740598 -0.99919599 -0.039818998, + 0.022883911 -0.95115548 -0.30786315, + 0.0071482118 -0.95138025 -0.30793607, + 0.0129655 -0.81773001 -0.57545602, + -0.013575798 -0.81772286 -0.57545197, + -0.0075922599 -0.95133698 -0.30805901, + -0.023355698 -0.95110488 -0.30798396, + -0.0050218487 -0.99921477 -0.039302588, + -0.0093925716 -0.99918324 -0.03930131, + 0.020196194 -0.97636074 0.21520196, + 0.027272291 -0.97619665 0.21516593, + 0.042099494 -0.95175385 0.30396098, + 0.052952491 -0.95126188 0.30380398, + 0.054225888 -0.94932175 0.30959293, + 0.057667106 -0.9491381 0.30953404, + 0.060764123 -0.94528735 0.32053012, + 0.061419331 -0.9452495 0.32051715, + 0.064819388 -0.94166279 0.33025691, + 0.062674709 -0.94179213 0.33030203, + 0.065073073 -0.93962455 0.33596286, + 0.059208523 -0.93996835 0.33608612, + 0.061901409 -0.93787313 0.34141204, + 0.052903812 -0.93835926 0.34158909, + 0.056275785 -0.93608177 0.34725192, + 0.04355929 -0.93667775 0.34747291, + 0.037404504 -0.94020611 0.33854604, + 0.017804109 -0.94071549 0.33872914, + 0.0072400565 -0.9455955 0.32526386, + -0.020563606 -0.94542027 0.3252041, + -0.034161508 -0.95021325 0.30972207, + -0.071050078 -0.94836563 0.30911887, + -0.08776439 -0.95244986 0.29178196, + -0.13411996 -0.94750065 0.29026592, + -0.15239307 -0.94997048 0.27264011, + -0.20823011 -0.94012749 0.26981613, + -0.22504011 -0.94054747 0.25441611, + -0.28928787 -0.92403358 0.24994887, + -0.30193213 -0.92295837 0.23871508, + -0.37220901 -0.89858001 0.23241, + -0.37819901 -0.897425 0.227143, + -0.45198113 -0.86475819 0.21887507, + -0.45020205 -0.86528611 0.22045003, + -0.52544278 -0.82449156 0.2100559, + -0.51616585 -0.82816982 0.21842095, + -0.59126914 -0.77980918 0.20566605, + -0.57540989 -0.7876128 0.22038494, + -0.64871192 -0.73288393 0.20507097, + -0.62875873 -0.74454767 0.22430189, + -0.69971365 -0.68405569 0.2060789, + -0.67531508 -0.70052606 0.23067904, + -0.7441088 -0.6345408 0.20894995, + -0.72660279 -0.6482138 0.22774394, + -0.79199284 -0.57601291 0.20237696, + -0.79656887 -0.57161093 0.19682197, + -0.8528803 -0.49366117 0.16998206, + -0.85298717 -0.49353012 0.16982605, + -0.89980644 -0.41254777 0.14195991, + -0.8983779 -0.41477394 0.14449799, + -0.93588322 -0.33269909 0.11590503, + -0.93445539 -0.33556315 0.11912406, + -0.96302938 -0.25387409 0.090124227, + -0.96199799 -0.256643 0.093242802, + -0.98199373 -0.17755796 0.064509585, + -0.98138112 -0.17992401 0.067220308, + -0.99378151 -0.10430595 0.038969081, + -0.99353689 -0.10590398 0.040851798, + -0.99934453 -0.033774886 0.013028493, + -0.99931479 -0.034364793 0.013751896, + -0.99936098 0.033186901 -0.0132805, + -0.99933678 0.033661094 -0.013891296, + -0.99430853 0.098482452 -0.040641781, + -0.99424475 0.098892175 -0.04120189, + -0.98490298 0.159793 -0.066575304, + -0.98459864 0.16094995 -0.068269275, + -0.97131479 0.21891794 -0.092857175, + -0.97052985 0.22098097 -0.096120588, + -0.95347178 0.27646095 -0.12025297, + -0.9520731 0.27918103 -0.12495901, + -0.93169844 0.33153814 -0.14839308, + -0.92937934 0.33499512 -0.15502407, + -0.90575802 0.38460901 -0.177984, + -0.90230685 0.38860095 -0.18663199, + -0.87542713 0.43570605 -0.20925502, + -0.87065983 0.43997189 -0.21994594, + -0.84082133 0.48418218 -0.24204808, + -0.84500015 0.48121107 -0.23326103, + -0.8174141 0.51836103 -0.25126904, + -0.83093441 0.51026124 -0.22176911, + -0.80341089 0.54607892 -0.23733696, + -0.81540132 0.5398342 -0.20904507, + -0.78717387 0.57511592 -0.22270797, + -0.79776418 0.57043511 -0.19538705, + -0.76848483 0.60534286 -0.20734295, + -0.7778511 0.60195106 -0.18056202, + -0.74765301 0.63608903 -0.19080301, + -0.75586355 0.63376963 -0.16433589, + -0.72438806 0.66732305 -0.17303701, + -0.73142606 0.66589904 -0.14695002, + -0.69824898 0.699036 -0.154263, + -0.70416623 0.69833022 -0.12839304, + -0.669038 0.73097599 -0.134396, + -0.67389804 0.73081803 -0.10847302, + -0.63720375 0.7623437 -0.11315196, + -0.64103937 0.76256245 -0.086989149, + -0.60268575 0.79283673 -0.090442471, + -0.60552192 0.7932629 -0.063851692, + -0.56521094 0.8222869 -0.066187792, + -0.56706518 0.82274628 -0.039059516, + -0.5245958 0.85039371 -0.040371984, + -0.525536 0.85070199 -0.010862, + -0.53602713 0.84408516 -0.013972904, + -0.53607917 0.84416729 0.00090149132, + -0.53605598 0.84418201 0.00090149097, + -0.53600395 0.84409988 -0.013970798, + -0.53611022 0.84403241 -0.013969807, + -0.56862807 0.8225261 -0.010629801, + -0.56766903 0.82231814 -0.039302904, + -0.60853291 0.79262382 -0.037883591, + -0.60666114 0.79235518 -0.064308114, + -0.64545178 0.7612977 -0.061787378, + -0.64262438 0.76115549 -0.08761505, + -0.67965925 0.72871625 -0.083881028, + -0.67588174 0.72886974 -0.10923696, + -0.711236 0.695189 -0.10419, + -0.70650506 0.69580305 -0.12926202, + -0.73981094 0.66149694 -0.12288898, + -0.73411018 0.6627292 -0.14789303, + -0.76553434 0.6279493 -0.14013205, + -0.75882787 0.62996596 -0.16529699, + -0.78886402 0.59444499 -0.155977, + -0.78111315 0.59742707 -0.18150301, + -0.80998731 0.56112319 -0.17047405, + -0.80125517 0.5652281 -0.19623305, + -0.82890302 0.52845103 -0.183465, + -0.81913573 0.5338788 -0.20973793, + -0.84580898 0.49654299 -0.19507, + -0.83489186 0.50355893 -0.22222497, + -0.86123186 0.46494994 -0.20518596, + -0.84913915 0.47381011 -0.23338106, + -0.87550485 0.43347794 -0.21351397, + -0.87158227 0.43687016 -0.22246107, + -0.89943075 0.3894749 -0.19832696, + -0.9030683 0.38553315 -0.18929307, + -0.92751056 0.33553484 -0.16474393, + -0.92996597 0.33207801 -0.157758, + -0.95097923 0.27933607 -0.13270202, + -0.95248437 0.27655309 -0.12764004, + -0.96997935 0.22080408 -0.10191004, + -0.97077924 0.21879506 -0.098571524, + -0.98435777 0.16063195 -0.072367884, + -0.98472285 0.15929899 -0.070319094, + -0.99419612 0.098420717 -0.043445602, + -0.99428612 0.097861014 -0.042641703, + -0.9993369 0.033379596 -0.014544698, + -0.99934065 0.033309888 -0.014450395, + -0.99929327 -0.034485307 0.014960304, + -0.99931735 -0.03403151 0.014375506, + -0.99326462 -0.10673596 0.045086984, + -0.99354249 -0.10501505 0.04295712, + -0.98067021 -0.18110204 0.074080713, + -0.98132485 -0.17869999 0.071188696, + -0.96063536 -0.2580871 0.10281403, + -0.96172488 -0.25530598 0.099518888, + -0.93220335 -0.33722112 0.13144904, + -0.93371886 -0.33433196 0.12802799, + -0.8950789 -0.41641995 0.15946199, + -0.89684486 -0.41380495 0.15631598, + -0.84888768 -0.49446982 0.18678693, + -0.85025215 -0.49287212 0.18479304, + -0.79316539 -0.5702433 0.2138021, + -0.79212987 -0.57120192 0.21507797, + -0.72667724 -0.64291322 0.24208009, + -0.71954823 -0.64802325 0.24963209, + -0.64795965 -0.71076161 0.27379984, + -0.66653854 -0.70014954 0.25596282, + -0.59337765 -0.75598854 0.27637681, + -0.61865008 -0.74377304 0.25312802, + -0.54427701 -0.794173 0.27028099, + -0.5639149 -0.78622085 0.25269893, + -0.48898211 -0.83045316 0.26691607, + -0.50338584 -0.82580268 0.25426891, + -0.42935193 -0.86314785 0.26576796, + -0.43640891 -0.8614738 0.25963494, + -0.36412796 -0.89172989 0.26875398, + -0.3640911 -0.89173526 0.26878607, + -0.29549003 -0.91469711 0.27570802, + -0.28839493 -0.91505575 0.28195995, + -0.22508106 -0.93113822 0.28691506, + -0.21326497 -0.93054891 0.29765198, + -0.15769202 -0.94054413 0.30084902, + -0.14332797 -0.93835276 0.31456491, + -0.09626466 -0.94373864 0.31637087, + -0.081994221 -0.94007325 0.3309671, + -0.043776006 -0.94234514 0.33176702, + -0.031743489 -0.93798667 0.34521487, + -0.0023232903 -0.93845713 0.34538803, + 0.0066796979 -0.93423063 0.35660687, + 0.028389391 -0.93387467 0.35647187, + 0.034583513 -0.93027937 0.36521813, + 0.04923822 -0.92970735 0.36499313, + 0.052003227 -0.92777842 0.36949018, + 0.060671106 -0.92732412 0.36930904, + 0.056448407 -0.93075812 0.36125204, + 0.062182523 -0.93044037 0.36112911, + 0.058817621 -0.93359834 0.35346112, + 0.061624594 -0.93343991 0.35340098, + 0.058509573 -0.93685758 0.34478182, + 0.058160376 -0.93687665 0.34478888, + 0.054639481 -0.94145066 0.33269387, + 0.044120003 -0.94194114 0.33286703, + 0.049699217 -0.93292433 0.35662612, + 0.052210469 -0.93280447 0.35658079, + 0.055623986 -0.92819577 0.36791092, + 0.055366214 -0.92820925 0.36791608, + 0.059017271 -0.9240576 0.37766981, + 0.056333594 -0.92420089 0.37772894, + 0.060966998 -0.91968 0.387907, + 0.055568706 -0.9199701 0.38803005, + 0.055467781 -0.92005461 0.38784385, + 0.044897903 -0.92054415 0.38805005, + 0.042049788 -0.92256278 0.38354892, + 0.025612295 -0.92307675 0.38376191, + 0.020553894 -0.92606777 0.3767969, + -0.0028313294 -0.92625976 0.37687492, + -0.010743096 -0.93007165 0.36722088, + -0.041399203 -0.92932814 0.36692703, + -0.051773991 -0.93322986 0.35552996, + -0.090776175 -0.93062478 0.3545379, + -0.10205699 -0.93371791 0.34315497, + -0.14922705 -0.92810935 0.34109312, + -0.15936995 -0.92989165 0.33151588, + -0.21418408 -0.92007136 0.32801512, + -0.22116406 -0.92063522 0.3217411, + -0.28300792 -0.90541869 0.31642288, + -0.28441796 -0.90540487 0.31519598, + -0.35095909 -0.88433522 0.30786207, + -0.34609312 -0.88479728 0.31201512, + -0.41633978 -0.85745656 0.30237284, + -0.40392107 -0.85961813 0.31289703, + -0.47653517 -0.82612932 0.30070713, + -0.45868483 -0.83056468 0.31586489, + -0.53281289 -0.7909658 0.30080494, + -0.50798273 -0.79888552 0.32207981, + -0.58289403 -0.75360799 0.30382499, + -0.56415612 -0.76101518 0.32028708, + -0.63890707 -0.70904607 0.29841504, + -0.63387406 -0.71156508 0.30311504, + -0.72897208 -0.62978303 0.26827803, + -0.71675324 -0.63790023 0.28168809, + -0.71061701 -0.634996 0.302991, + -0.77806264 -0.56695271 0.27052388, + -0.77650118 -0.5681631 0.27246407, + -0.83703482 -0.49335387 0.23658994, + -0.83495229 -0.49540618 0.23964009, + -0.88669974 -0.41620892 0.20132996, + -0.88450229 -0.41896313 0.20524508, + -0.92666191 -0.33756596 0.16536899, + -0.9245671 -0.34095404 0.17007701, + -0.95728248 -0.25874913 0.12907106, + -0.95510721 -0.26342905 0.13555603, + -0.98016673 -0.17621295 0.090676181, + -0.97930551 -0.17889991 0.094633855, + -0.99342334 -0.10121103 0.05353862, + -0.99303436 -0.10325003 0.05676432, + -0.99931401 -0.032452401 0.0178416, + -0.99926823 -0.033162907 0.019057203, + -0.99932438 0.03186661 -0.018312208, + -0.9993521 0.031440903 -0.017521001, + -0.99442178 0.092136174 -0.051344387, + -0.99510264 0.08852987 -0.043968286, + -0.98702586 0.14380299 -0.071419589, + -0.98834002 0.139375 -0.061307099, + -0.97796726 0.19108905 -0.084054425, + -0.97980189 0.18650198 -0.072147295, + -0.96748334 0.23589909 -0.091256529, + -0.9697119 0.23147596 -0.077960089, + -0.95578891 0.27867296 -0.093856089, + -0.95826262 0.27462292 -0.079467572, + -0.94271034 0.32046512 -0.092733033, + -0.94526267 0.31694889 -0.077600271, + -0.92795426 0.36200207 -0.088630825, + -0.93046659 0.35906583 -0.072826065, + -0.9112857 0.40355784 -0.08184997, + -0.91365486 0.40120494 -0.065339394, + -0.89266557 0.44485879 -0.072448663, + -0.89478689 0.44307294 -0.055160392, + -0.87182218 0.48607013 -0.060513414, + -0.87359118 0.48481613 -0.04232911, + -0.84829456 0.52751774 -0.046057276, + -0.84959602 0.52675003 -0.0268532, + -0.85001171 0.52606481 -0.027129991, + -0.87537044 0.48281124 -0.024899311, + -0.8742218 0.48364088 -0.042753588, + -0.89709121 0.44012913 -0.038907107, + -0.89556146 0.44143972 -0.055682566, + -0.91629523 0.39735508 -0.05012181, + -0.91450685 0.39916593 -0.065907292, + -0.93327177 0.35437292 -0.058511283, + -0.93133622 0.3566891 -0.073388517, + -0.94807655 0.31151685 -0.064094469, + -0.94609827 0.31432009 -0.078108616, + -0.96094298 0.26857799 -0.066741601, + -0.95902586 0.27182397 -0.079881392, + -0.97210586 0.22502697 -0.066128992, + -0.97036749 0.22861511 -0.07824444, + -0.98172355 0.18005891 -0.061625872, + -0.98031187 0.18375099 -0.072277993, + -0.98966378 0.13345397 -0.052493688, + -0.98868054 0.13694794 -0.061286271, + -0.99576545 0.083911635 -0.03755182, + -0.99526721 0.086724222 -0.043843612, + -0.99945635 0.029425111 -0.014875906, + -0.99937725 0.030684607 -0.017422503, + -0.99933589 -0.031687696 0.017992098, + -0.99930263 -0.03218909 0.018924793, + -0.99305767 -0.10140196 0.059616677, + -0.99342799 -0.099571101 0.056448098, + -0.97975224 -0.17417204 0.098740123, + -0.98063922 -0.17153305 0.094462521, + -0.9571051 -0.25380102 0.13976702, + -0.95826399 -0.25140899 0.13610201, + -0.92073661 -0.34313086 0.18575591, + -0.92386585 -0.33838996 0.17878498, + -0.88030076 -0.41946891 0.22162195, + -0.88300329 -0.41628414 0.21682407, + -0.8299467 -0.49475381 0.25769591, + -0.83226788 -0.49260694 0.25429997, + -0.77039129 -0.56653517 0.29246411, + -0.77233386 -0.56512797 0.29005298, + -0.70336556 -0.63239664 0.32457882, + -0.71820098 -0.62382799 0.308263, + -0.62114197 -0.70259792 0.34718698, + -0.63725895 -0.69551092 0.33191198, + -0.56239611 -0.74624819 0.3561241, + -0.55644703 -0.74819499 0.36134601, + -0.48169187 -0.78912884 0.3811149, + -0.46764189 -0.7919898 0.39250892, + -0.39597094 -0.82276291 0.40775993, + -0.41179994 -0.82103986 0.39536595, + -0.34398621 -0.84599745 0.40738425, + -0.36424118 -0.84508139 0.39136419, + -0.29921016 -0.86584544 0.40098017, + -0.31236196 -0.86606187 0.39034194, + -0.25083902 -0.88253212 0.39776507, + -0.25910297 -0.8832249 0.39086995, + -0.20182709 -0.89563543 0.39636219, + -0.20405702 -0.89598614 0.39442307, + -0.15234199 -0.90456086 0.39819795, + -0.15056095 -0.90413868 0.39983085, + -0.10490495 -0.90951759 0.40220982, + -0.10037196 -0.90805459 0.4066478, + -0.061384421 -0.91094232 0.40794116, + -0.055629991 -0.90855086 0.41405395, + -0.023462189 -0.90970957 0.41458181, + -0.018345891 -0.90707058 0.42057878, + 0.0068525383 -0.90720177 0.4206399, + 0.010522703 -0.90491325 0.42546609, + 0.029675797 -0.90456486 0.42530194, + 0.031342112 -0.90333033 0.42779914, + 0.044667713 -0.90287232 0.42758214, + 0.044373102 -0.9031291 0.42707005, + 0.05258438 -0.90276873 0.42689985, + 0.051165074 -0.9042266 0.42397678, + 0.055028673 -0.90404058 0.42388979, + 0.052252583 -0.90741068 0.41698384, + 0.052371506 -0.90740514 0.41698107, + 0.04780139 -0.91400278 0.40288192, + 0.045870278 -0.91408557 0.40291882, + 0.042293411 -0.92037922 0.38873309, + 0.032420203 -0.92071915 0.38887706, + 0.036838185 -0.91055572 0.41174185, + 0.0246852 -0.90236503 0.43026501, + 0.028680796 -0.90226889 0.43021894, + 0.023052195 -0.92088175 0.38915992, + 0.018385792 -0.92097062 0.38919786, + 0.015125704 -0.93806422 0.34613109, + 0.0066223498 -0.938151 0.346163, + 0.0059938375 -0.94756663 0.31950188, + -0.0059815184 -0.94756675 0.31950191, + -0.0065999278 -0.93813866 0.34619689, + -0.015197598 -0.93805087 0.34616396, + -0.018449407 -0.92099434 0.38913915, + -0.023044208 -0.92090636 0.38910216, + -0.028671889 -0.9022997 0.43015486, + -0.029475585 -0.9022786 0.43014479, + -0.035221618 -0.9051044 0.4237282, + -0.039153095 -0.9049719 0.42366594, + -0.032420203 -0.92071915 0.38887706, + -0.042325988 -0.92037779 0.38873291, + -0.046336986 -0.91330272 0.40463686, + -0.048714694 -0.91319889 0.40459195, + -0.051837999 -0.90869302 0.41423401, + -0.05120787 -0.90872246 0.41424775, + -0.054321375 -0.90496659 0.4220008, + -0.050002307 -0.9051711 0.42209607, + -0.05265389 -0.90245175 0.42756093, + -0.044587385 -0.9028067 0.42772886, + -0.044927604 -0.90250909 0.42832106, + -0.031751588 -0.90296572 0.42853785, + -0.029959792 -0.90429676 0.42585191, + -0.011078704 -0.90464729 0.42601714, + -0.0076542771 -0.90678871 0.42151585, + 0.017706903 -0.90667313 0.42146206, + 0.022540411 -0.90917844 0.41579622, + 0.054357 -0.90806502 0.41528699, + 0.059911784 -0.91038978 0.4093909, + 0.098850325 -0.90756124 0.40811908, + 0.103526 -0.90908498 0.403543, + 0.14884701 -0.90381414 0.40120405, + 0.15087295 -0.90429968 0.39934886, + 0.202499 -0.89581901 0.39560401, + 0.20107305 -0.89559221 0.39684308, + 0.25817302 -0.88327014 0.39138305, + 0.25168902 -0.88272715 0.39679405, + 0.3133201 -0.86616319 0.38934809, + 0.300529 -0.86597502 0.399712, + 0.36571997 -0.8450489 0.39005294, + 0.345146 -0.84601903 0.40635699, + 0.41305384 -0.82092172 0.39430186, + 0.39949405 -0.82244414 0.40495706, + 0.47108775 -0.79135865 0.38965082, + 0.48146689 -0.78921884 0.38121292, + 0.55643892 -0.74817991 0.36138996, + 0.55931991 -0.74724495 0.35886797, + 0.63425964 -0.69691658 0.3346968, + 0.63654023 -0.69588423 0.33250812, + 0.70944494 -0.63589793 0.30384496, + 0.70981592 -0.63567495 0.30344498, + 0.77775985 -0.5672459 0.27077994, + 0.77690786 -0.56790692 0.27183798, + 0.83743918 -0.49296612 0.23596606, + 0.83553183 -0.49485087 0.23876594, + 0.8871184 -0.41568422 0.20056809, + 0.88489312 -0.41848207 0.20454103, + 0.92694962 -0.33707687 0.16475295, + 0.92485142 -0.34047914 0.16948107, + 0.95742309 -0.25844103 0.12864402, + 0.95500875 -0.26363695 0.13584498, + 0.98012435 -0.17635006 0.090867929, + 0.9793005 -0.17891809 0.094651945, + 0.99342251 -0.10121596 0.053545475, + 0.99305224 -0.10315802 0.056618314, + 0.99931562 -0.032428388 0.017798394, + 0.99926865 -0.033157587 0.019045992, + 0.99932474 0.031860493 -0.018300897, + 0.99935687 0.031364396 -0.017378798, + 0.99445689 0.091970392 -0.050959993, + 0.99512738 0.088401228 -0.043665815, + 0.98709053 0.14359993 -0.070931166, + 0.98836833 0.13928005 -0.061067022, + 0.9780159 0.19097997 -0.083734691, + 0.97981888 0.18646398 -0.072014295, + 0.9674955 0.23590589 -0.091109157, + 0.96969366 0.23153891 -0.078000069, + 0.95576435 0.27874207 -0.093901739, + 0.95821553 0.27473089 -0.079661064, + 0.94264525 0.32059109 -0.092958622, + 0.94519734 0.31708112 -0.077856831, + 0.92788512 0.36211002 -0.088913411, + 0.9304201 0.35915202 -0.072995208, + 0.91123211 0.40364105 -0.082037106, + 0.91364479 0.40124491 -0.065236486, + 0.89264411 0.44492006 -0.072337404, + 0.89480358 0.44309479 -0.054712575, + 0.87180209 0.48616606 -0.060031008, + 0.87355071 0.48491782 -0.041997787, + 0.84823114 0.52765107 -0.045698904, + 0.84947985 0.52691495 -0.027287297, + 0.82162321 0.56926811 -0.029480608, + 0.82234102 0.56892401 -0.0089902896, + 0.84375143 0.53673422 -8.8755442e-005, + 0.84373617 0.53675812 -8.762232e-005, + 0.8436774 0.53672123 -0.011782406, + 0.84369284 0.53669685 -0.011781897, + 0.81645203 0.57735598 -0.0081341499, + 0.81647915 0.57737505 7.9093908e-005, + 0.81638509 0.57750803 7.9093807e-005, + 0.81632531 0.57746619 -0.012080905, + 0.81635088 0.57742995 -0.012080198, + 0.81641042 0.57747227 8.4107647e-005, + 0.79983413 0.60020804 -0.0039601303, + 0.78703821 0.61690414 -0.0004964621, + 0.78709567 0.61683071 -0.00050021178, + 0.7870363 0.61678421 -0.012296804, + 0.78697866 0.61685771 -0.012298094, + 0.75592536 0.65457529 -0.010392505, + 0.75596589 0.65461093 0.00038610093, + 0.75588518 0.65470415 0.0003861021, + 0.75582588 0.65465295 -0.012523798, + 0.75584215 0.65463418 -0.012523503, + 0.75590086 0.65468591 0.00038891894, + 0.73387474 0.67927378 -0.0038729587, + 0.85730779 0.51478887 -0.0039761988, + 0.8690272 0.49476412 -0.00030181807, + 0.8690576 0.49471077 -0.00029469185, + 0.8690027 0.49467883 -0.011278796, + 0.8689723 0.49473217 -0.011279903, + 0.85055882 0.52581888 -0.0080223279, + 0.84990388 0.52621591 -0.027569296, + 0.87527072 0.48297083 -0.025303591, + 0.87416899 0.48376599 -0.042415202, + 0.8970719 0.44019595 -0.038595095, + 0.89556068 0.44149885 -0.055225182, + 0.91631091 0.39737093 -0.049705394, + 0.9144901 0.39922205 -0.065801211, + 0.93326461 0.35440788 -0.058414776, + 0.93129289 0.35676697 -0.073558792, + 0.94804102 0.31159401 -0.064245, + 0.94604355 0.31441987 -0.078369163, + 0.96090347 0.26866412 -0.066964731, + 0.95898664 0.27190492 -0.080077171, + 0.97207636 0.22510608 -0.066294722, + 0.97035402 0.22865801 -0.078286, + 0.98171741 0.18008189 -0.061654761, + 0.98032779 0.18371795 -0.072146282, + 0.98967302 0.133424 -0.0523961, + 0.98870701 0.13686299 -0.061049901, + 0.99577647 0.083847441 -0.037401419, + 0.99529153 0.086594358 -0.043545779, + 0.99945939 0.029374512 -0.014771606, + 0.99938178 0.030617192 -0.017283997, + 0.99934113 -0.031606104 0.017842302, + 0.9993031 -0.032182004 0.018913701, + 0.99306613 -0.10135002 0.059564307, + 0.99344623 -0.099469021 0.056306716, + 0.97979724 -0.17404304 0.09852092, + 0.98063499 -0.17154901 0.094477497, + 0.95710033 -0.25381109 0.13978204, + 0.95817798 -0.25158799 0.13637599, + 0.92056227 -0.34339109 0.18613905, + 0.92416024 -0.33793709 0.17811905, + 0.88068086 -0.41906294 0.22087897, + 0.88340813 -0.41583905 0.21602803, + 0.83061314 -0.49414805 0.25670904, + 0.83285111 -0.49207106 0.25342703, + 0.77113873 -0.56601083 0.2915079, + 0.77269346 -0.56488156 0.2895748, + 0.70389408 -0.63209105 0.32402802, + 0.7038188 -0.63213283 0.32410991, + 0.63031894 -0.69082493 0.35420197, + 0.62875205 -0.69147807 0.35570902, + 0.55338788 -0.74066883 0.3810139, + 0.55005407 -0.74164408 0.38393307, + 0.47508088 -0.78144079 0.40453491, + 0.47132313 -0.78212219 0.4076021, + 0.39951995 -0.81295091 0.42366794, + 0.38853091 -0.81378984 0.43219191, + 0.32248309 -0.83599216 0.44398412, + 0.33395299 -0.836097 0.43522099, + 0.27237502 -0.85348409 0.44427106, + 0.2897999 -0.85473073 0.43064085, + 0.23142509 -0.8688103 0.43773416, + 0.24190395 -0.87020081 0.42922392, + 0.18752401 -0.88092703 0.43451399, + 0.19275196 -0.88197875 0.43006992, + 0.14337201 -0.88954812 0.43376106, + 0.14441797 -0.88983679 0.43282092, + 0.10058098 -0.89470387 0.43518794, + 0.09932778 -0.89425677 0.4363929, + 0.061103992 -0.89702189 0.43774194, + 0.058134377 -0.89570171 0.44083884, + 0.026350195 -0.89690775 0.44143188, + 0.023165692 -0.8951847 0.44509286, + -0.0026190097 -0.89542186 0.44521093, + -0.0049275784 -0.89392978 0.44817987, + -0.024539791 -0.89367169 0.44804984, + -0.025568904 -0.8928861 0.44955605, + -0.039880089 -0.89246774 0.44934487, + -0.0394703 -0.89283502 0.44865099, + -0.04870699 -0.89247078 0.44846788, + -0.046712201 -0.89456999 0.44448, + -0.051751118 -0.89434731 0.44437015, + -0.048288282 -0.89863873 0.43602386, + -0.049746383 -0.89857471 0.43599185, + -0.046191096 -0.90383488 0.42538095, + -0.037279081 -0.90417159 0.42553979, + -0.043172397 -0.8933199 0.44734293, + -0.043976706 -0.89328814 0.44732806, + -0.047810212 -0.88746321 0.45839211, + -0.045672823 -0.88755244 0.4584372, + -0.048602089 -0.88382775 0.46528089, + -0.042745519 -0.88406444 0.46540621, + -0.044703379 -0.88195556 0.46920776, + -0.034474913 -0.88231331 0.46939817, + -0.035477407 -0.88139224 0.47105113, + -0.020198107 -0.88176727 0.47125217, + -0.020032695 -0.88189775 0.47101489, + 0.00010290695 -0.88207459 0.47110975, + 0.0012630196 -0.88285178 0.46964988, + 0.027073 -0.88252902 0.46947801, + 0.028238807 -0.88319021 0.46816412, + 0.059580892 -0.88197291 0.46751893, + 0.059913069 -0.88213056 0.46717879, + 0.096832335 -0.8795653 0.46582019, + 0.095437124 -0.87902021 0.46713513, + 0.13754095 -0.8746587 0.46481681, + 0.13325801 -0.8733111 0.46858305, + 0.17994706 -0.8667863 0.46508119, + 0.17136501 -0.86468011 0.47218907, + 0.22246297 -0.85566986 0.46726793, + 0.20757693 -0.85293871 0.47896484, + 0.26236892 -0.84138471 0.47247681, + 0.25285295 -0.84022582 0.47967288, + 0.31213993 -0.82505482 0.47101289, + 0.32297713 -0.8255083 0.46284118, + 0.38925508 -0.80346018 0.45048013, + 0.3934271 -0.80323917 0.44723812, + 0.46499094 -0.77349788 0.43067893, + 0.46947494 -0.77281487 0.42702493, + 0.54432493 -0.73424095 0.40570995, + 0.54733896 -0.73345393 0.40306994, + 0.62277514 -0.68568218 0.37681708, + 0.62397796 -0.68522292 0.37566093, + 0.69807518 -0.62786019 0.3442131, + 0.6972782 -0.62827319 0.34507409, + 0.7670123 -0.56238818 0.30888811, + 0.76501685 -0.56373894 0.31136397, + 0.82798719 -0.49085411 0.27110806, + 0.82481098 -0.49360901 0.27574801, + 0.87919974 -0.41594991 0.23236494, + 0.87474501 -0.42085499 0.24021301, + 0.92599738 -0.32788011 0.18714605, + 0.92530698 -0.328888 0.188785, + 0.95982134 -0.24336809 0.13969605, + 0.95865834 -0.24567509 0.14359005, + 0.98093462 -0.16778193 0.098063961, + 0.98007375 -0.17021395 0.10238498, + 0.99338812 -0.098379016 0.059175406, + 0.99379587 -0.096404389 0.055460494, + 0.99936676 -0.030843593 0.017743995, + 0.99944878 -0.029550593 0.015129697, + 0.99947786 0.028761996 -0.014725998, + 0.99953353 0.027810987 -0.012621795, + 0.99590266 0.082347371 -0.037372686, + 0.99626625 0.080177523 -0.032020207, + 0.98994178 0.13138497 -0.052470587, + 0.99068153 0.12863295 -0.044762976, + 0.98212665 0.17776494 -0.061860677, + 0.98321003 0.174821 -0.0523034, + 0.97260851 0.2226959 -0.066626869, + 0.97394711 0.21984403 -0.055638008, + 0.96152854 0.26630887 -0.067397572, + 0.96302152 0.26371387 -0.055177074, + 0.9487195 0.30941886 -0.064740174, + 0.950266 0.30717701 -0.051350102, + 0.9339509 0.35250998 -0.058928192, + 0.93543333 0.35069612 -0.044460416, + 0.91694689 0.39584094 -0.050183792, + 0.91821778 0.39452392 -0.035028894, + 0.8975969 0.43908995 -0.038985796, + 0.89854556 0.4382638 -0.023251988, + 0.87565821 0.4822531 -0.025585905, + 0.87624288 0.48181695 -0.007133069, + 0.8921333 0.45164615 -0.010673404, + 0.89218402 0.45167199 0.00025275, + 0.89226103 0.45152 0.00025274901, + 0.89221013 0.45149407 -0.010686201, + 0.89220113 0.45151207 -0.010686501, + 0.89225191 0.45153794 0.00025345996, + 0.90569532 0.42391115 -0.0039236615, + 0.94448376 0.3285439 -0.0030595392, + 0.94883925 0.3157571 -0.0012636804, + 0.94880462 0.31574488 -0.0086497674, + 0.94877636 0.31583011 -0.0086514931, + 0.93853903 0.34514099 -0.0047142599, + 0.93818724 0.3456021 -0.019075304, + 0.95392627 0.29958507 -0.016535403, + 0.95342565 0.30034789 -0.027761891, + 0.96680599 0.25442699 -0.0235174, + 0.96621066 0.25552991 -0.033783089, + 0.97741634 0.20950007 -0.02769761, + 0.97682154 0.21086289 -0.036829483, + 0.98599499 0.164288 -0.0286947, + 0.98549926 0.16575405 -0.036288507, + 0.99255937 0.11894505 -0.02604061, + 0.99221975 0.12033997 -0.031909794, + 0.99716234 0.072767422 -0.019295307, + 0.99699867 0.073865272 -0.023185892, + 0.9996649 0.024699597 -0.0077530793, + 0.99964076 0.025172595 -0.0092045683, + 0.99962854 -0.025596088 0.0093594156, + 0.99959588 -0.026205596 0.011018199, + 0.99613166 -0.081004672 0.034058489, + 0.99571747 -0.083382934 0.039927118, + 0.9874599 -0.14238799 0.068181194, + 0.98581725 -0.14754003 0.079976521, + 0.97052675 -0.21186796 0.11484697, + 0.96578747 -0.22124511 0.13529706, + 0.93991637 -0.29126108 0.17811306, + 0.93455762 -0.29850888 0.19363493, + 0.89607829 -0.37240711 0.24157108, + 0.89649367 -0.37198889 0.24067292, + 0.8446961 -0.44939107 0.29075104, + 0.84217173 -0.45133984 0.29502389, + 0.77296513 -0.53105909 0.34713304, + 0.763955 -0.536129 0.35907999, + 0.67354107 -0.61413008 0.41132307, + 0.67660105 -0.61293805 0.40806606, + 0.60069686 -0.66548485 0.44304988, + 0.60229033 -0.66505241 0.44153327, + 0.52609897 -0.70849591 0.47037596, + 0.52535224 -0.70861936 0.47102425, + 0.45087212 -0.74335021 0.49411011, + 0.44850713 -0.74350816 0.49602112, + 0.37751007 -0.77031612 0.51390606, + 0.37332004 -0.77020711 0.51712006, + 0.30851689 -0.78973073 0.53022879, + 0.30385885 -0.78920066 0.53369677, + 0.24505591 -0.80311072 0.5431028, + 0.24052197 -0.80221391 0.54644495, + 0.18844196 -0.81166983 0.55288488, + 0.18570291 -0.81090665 0.55492777, + 0.14028497 -0.81710082 0.55916589, + 0.13370606 -0.81472939 0.5642153, + 0.095213681 -0.81837589 0.56674093, + 0.10083696 -0.82083571 0.5621928, + 0.066803887 -0.82319784 0.56381088, + 0.076150432 -0.8279283 0.55564016, + 0.044982076 -0.82949853 0.55669463, + 0.051225301 -0.83311403 0.55072403, + 0.02356991 -0.83397728 0.55129516, + 0.027669404 -0.83669811 0.54696506, + 0.003835059 -0.83701283 0.54716986, + 0.0070028608 -0.83942211 0.54343504, + -0.012739396 -0.83937472 0.5434038, + -0.0098499302 -0.841896 0.53955001, + -0.02562261 -0.84166032 0.53939921, + -0.022704598 -0.84459388 0.53492594, + -0.034624603 -0.8443051 0.53474307, + -0.031554911 -0.84788829 0.52923518, + -0.039530884 -0.84764773 0.5290848, + -0.03611638 -0.85232759 0.52175975, + -0.040744189 -0.85217583 0.52166688, + -0.037055004 -0.85820913 0.51196104, + -0.038144898 -0.85817391 0.51193994, + -0.03458751 -0.86531931 0.50002617, + -0.032570198 -0.86537802 0.50006002, + -0.020486105 -0.85532415 0.5176881, + -0.02576559 -0.85521972 0.5176248, + -0.014894596 -0.79920584 0.60087287, + -0.022284906 -0.79909617 0.60079014, + 0.014828497 -0.79941082 0.60060185, + 0.022214903 -0.79930115 0.60052007, + 0.015761299 -0.8254959 0.56418794, + 0.014747002 -0.82550913 0.56419605, + 0.010830396 -0.85105067 0.52497184, + 0.0054621887 -0.85108781 0.52499491, + 0.0041425587 -0.87580472 0.48264781, + -0.0037738991 -0.87580574 0.48264888, + -0.0050676395 -0.8509829 0.52516896, + -0.010781094 -0.85094458 0.52514476, + -0.014664603 -0.82549417 0.56422013, + -0.01580799 -0.82547951 0.56421065, + -0.017621405 -0.82857132 0.55960619, + -0.023955196 -0.82846189 0.55953294, + -0.017746102 -0.85252512 0.52238506, + -0.015705502 -0.85255414 0.52240306, + -0.011905896 -0.87623173 0.48174283, + -0.0053859283 -0.87628073 0.48177081, + -0.0041505499 -0.89886302 0.43821001, + 0.0042477488 -0.89886272 0.43820986, + 0.0055050515 -0.87620622 0.48190513, + 0.012101297 -0.87615478 0.48187789, + 0.015880005 -0.85270029 0.52215916, + 0.017951103 -0.85267019 0.5221411, + 0.024198795 -0.8285858 0.55933887, + 0.017595103 -0.82870018 0.55941612, + -0.53241092 -0.66499496 0.52375597, + -0.43249786 -0.70831978 0.55787879, + -0.42608207 -0.7081902 0.56295711, + -0.35646287 -0.73138076 0.58139181, + -0.35530397 -0.73125494 0.58225894, + -0.29205102 -0.74819309 0.59574604, + -0.289305 -0.74767101 0.59773803, + -0.23232809 -0.7597003 0.60735422, + -0.22974902 -0.75900412 0.60920304, + -0.17901801 -0.76726699 0.61583602, + -0.17682409 -0.76650137 0.61742127, + -0.13246304 -0.77191031 0.62177825, + -0.13157406 -0.77152938 0.62243932, + -0.093219571 -0.77490669 0.62516373, + -0.092403673 -0.77449173 0.62579876, + -0.059891138 -0.77642345 0.62735933, + -0.058149915 -0.77539116 0.62879819, + -0.030742789 -0.7763387 0.62956578, + -0.028251713 -0.77463335 0.63177931, + -0.0064664586 -0.77492684 0.63201785, + -0.013211994 -0.78017265 0.62542468, + 0.0058658998 -0.78022701 0.62546903, + -0.0014892496 -0.78664184 0.61740786, + 0.015086904 -0.7865532 0.61733812, + 0.0092335613 -0.79229909 0.61006308, + 0.023356602 -0.79211712 0.60992205, + 0.018032698 -0.79804885 0.60232294, + 0.029398883 -0.7978335 0.60216063, + 0.024607411 -0.80396134 0.5941723, + 0.033006497 -0.80376691 0.59402794, + 0.028579196 -0.8103599 0.58523494, + 0.034083299 -0.81022 0.58513403, + 0.029891508 -0.81763315 0.57496309, + 0.032504588 -0.81756669 0.57491583, + 0.028650604 -0.8259111 0.56307209, + 0.022177499 -0.82604688 0.56316495, + 0.027267801 -0.81165099 0.58350599, + 0.027069209 -0.81165528 0.58350927, + 0.031119507 -0.80266321 0.5956201, + 0.028248893 -0.80273181 0.59567088, + 0.032752912 -0.79454428 0.60632223, + 0.027122101 -0.79467797 0.60642499, + 0.032045402 -0.78711998 0.61596698, + 0.023891803 -0.78730011 0.61610705, + 0.029179193 -0.78030682 0.62471586, + 0.018651396 -0.78050381 0.62487286, + 0.02454659 -0.77369165 0.63308668, + 0.011343 -0.77387488 0.63323694, + 0.018356608 -0.76670331 0.64173925, + 0.0033156604 -0.76682812 0.64184403, + 0.0098931296 -0.76083499 0.64886999, + -0.0077407449 -0.76084948 0.64888233, + -0.008292079 -0.76129389 0.64835393, + -0.030745 -0.76095998 0.64806998, + -0.03104372 -0.76117146 0.64780736, + -0.058442194 -0.76023686 0.64701194, + -0.057973914 -0.75994819 0.64739317, + -0.090213604 -0.75812411 0.64584005, + -0.090216473 -0.75812572 0.64583778, + -0.12792397 -0.7549758 0.64315385, + -0.12931995 -0.75560772 0.64213175, + -0.17307009 -0.75050735 0.6377973, + -0.17506999 -0.7512539 0.63637096, + -0.22521186 -0.74343556 0.62974864, + -0.22729108 -0.74404824 0.62827623, + -0.28404793 -0.73257482 0.61858785, + -0.28558803 -0.73290807 0.61748308, + -0.34814698 -0.71691495 0.60400891, + -0.35525009 -0.71786016 0.59872711, + -0.42430586 -0.69539577 0.5799908, + -0.46091989 -0.69635081 0.5501349, + -0.53203988 -0.66439682 0.5248909, + -0.56352192 -0.66108692 0.49538594, + -0.65209502 -0.60669899 0.45462999, + -0.66913676 -0.60244477 0.43510485, + -0.74345684 -0.54216689 0.39156991, + -0.75203532 -0.53880316 0.37965015, + -0.81262869 -0.47639781 0.33567789, + -0.82358772 -0.47032881 0.31700787, + -0.88030672 -0.39338985 0.26514992, + -0.96772754 0.25198987 -0.0021002791, + -0.96751398 0.252426 -0.0140658, + -0.9784289 0.20626397 -0.011493599, + -0.97816211 0.20689303 -0.019857801, + -0.98689985 0.16059598 -0.015414198, + -0.98664302 0.161382 -0.0221675, + -0.99320126 0.11532703 -0.015841404, + -0.99301255 0.11613595 -0.020940691, + -0.99747324 0.069916517 -0.012606703, + -0.99737936 0.070580423 -0.015900506, + -0.99971014 0.023487203 -0.0052912403, + -0.99969625 0.023778906 -0.0064874012, + -0.9996891 -0.024054503 0.006562571, + -0.99967015 -0.024437904 0.0079092309, + -0.99687612 -0.075144105 0.024320103, + -0.99663574 -0.076655783 0.029002793, + -0.99025637 -0.13024604 0.049278919, + -0.98933887 -0.13345799 0.058288991, + -0.97807688 -0.19083597 0.08334969, + -0.97557622 -0.19650805 0.098161325, + -0.9574495 -0.25818089 0.12896894, + -0.95157689 -0.26730296 0.15182398, + -0.92418259 -0.33211786 0.18863791, + -0.91174877 -0.3454949 0.22214293, + -0.87143898 -0.41258001 0.265277, + -0.85955018 -0.42159408 0.28884605, + -0.80516118 -0.48924413 0.33519509, + -0.80065 -0.49174401 0.34226799, + -0.73179626 -0.55936718 0.38933614, + -0.72069061 -0.56373066 0.40350077, + -0.63573205 -0.62768805 0.44928005, + -0.61318988 -0.63300985 0.47254288, + -0.51160198 -0.68853301 0.51398998, + -0.5084691 -0.68884617 0.51667213, + -0.43443686 -0.72054279 0.54044682, + -0.43389621 -0.72054636 0.54087621, + -0.36385104 -0.74493408 0.55918306, + -0.36182502 -0.74477005 0.56071407, + -0.29760489 -0.76269972 0.57421285, + -0.29471588 -0.76222467 0.57632983, + -0.23720297 -0.77488786 0.58590394, + -0.23442511 -0.77420735 0.58791828, + -0.18308298 -0.7829389 0.59454793, + -0.18107298 -0.78228688 0.59601992, + -0.13631497 -0.78801084 0.6003809, + -0.13452898 -0.78728986 0.60172796, + -0.095605023 -0.79087317 0.60446614, + -0.092363775 -0.7893008 0.6070199, + -0.059800476 -0.79127067 0.60853475, + -0.054928094 -0.7884829 0.61259896, + -0.028463496 -0.78935486 0.61327696, + -0.035241403 -0.79380912 0.60714507, + -0.0119929 -0.79424602 0.60747802, + -0.019794798 -0.80001986 0.59964693, + 0.0011020302 -0.80017614 0.59976405, + -0.0048990981 -0.80517668 0.59301478, + 0.013083894 -0.80511767 0.59297073, + 0.0079416698 -0.80996603 0.58642298, + 0.022914806 -0.80977917 0.58628714, + 0.018426199 -0.81460387 0.57972497, + 0.030228803 -0.8143701 0.57955807, + 0.025992295 -0.81961781 0.57232088, + 0.034646407 -0.81940216 0.57217109, + 0.030572999 -0.82529199 0.563878, + 0.035972107 -0.82514316 0.56377715, + 0.032000192 -0.83197683 0.55388689, + 0.034390815 -0.83191043 0.55384326, + 0.030588688 -0.83992171 0.54184484, + 0.029958095 -0.83993787 0.54185492, + 0.025070289 -0.85307556 0.52118474, + 0.032633007 -0.85288918 0.52107114, + 0.03620778 -0.84554261 0.53267878, + 0.034422606 -0.84559619 0.5327121, + 0.038183104 -0.8393001 0.54232603, + 0.03309178 -0.83945251 0.54242468, + 0.036810704 -0.83422911 0.55018806, + 0.028315209 -0.83446032 0.55034018, + 0.031896591 -0.83016485 0.55660486, + 0.019837195 -0.83042383 0.55677891, + 0.023556404 -0.82656711 0.56234509, + 0.0078996606 -0.82677114 0.56248307, + 0.0119646 -0.82309198 0.56778198, + -0.0071534216 -0.82312918 0.5678091, + -0.0022107398 -0.81919986 0.57350391, + -0.024625694 -0.81895381 0.57333088, + -0.018583298 -0.81471986 0.57955694, + -0.044274673 -0.81406152 0.57908863, + -0.035605099 -0.80869401 0.58715099, + -0.064049885 -0.80754584 0.58631688, + -0.056827385 -0.80360281 0.59244686, + -0.088423595 -0.8017509 0.59108096, + -0.095795535 -0.80518728 0.58523226, + -0.13477097 -0.8015278 0.58257186, + -0.13950898 -0.80333084 0.57896191, + -0.18489 -0.79727697 0.57459998, + -0.18752196 -0.79806489 0.57264996, + -0.23948103 -0.78883612 0.56602705, + -0.24209692 -0.78941071 0.5641098, + -0.30041581 -0.77603149 0.55454963, + -0.30316696 -0.7764129 0.55251491, + -0.36777797 -0.75765389 0.53916591, + -0.37064898 -0.75780791 0.53697896, + -0.44088694 -0.73234296 0.51893395, + -0.44259906 -0.73228109 0.51756203, + -0.5167163 -0.6991564 0.49415031, + -0.51645386 -0.6991908 0.49437588, + -0.59306973 -0.65741473 0.46483782, + -0.59348613 -0.65731716 0.46444413, + -0.69127923 -0.59013826 0.41697714, + -0.70628142 -0.58435535 0.39961925, + -0.78503317 -0.51132214 0.34967509, + -0.79098755 -0.5079717 0.3410328, + -0.85208929 -0.43454814 0.29173911, + -0.85364169 -0.43338084 0.28892392, + -0.9004187 -0.36196089 0.24130991, + -0.90844488 -0.35388497 0.22247097, + -0.94167286 -0.28490797 0.17910798, + -0.94989938 -0.2731491 0.15192406, + -0.97136986 -0.20761897 0.11547699, + -0.97480601 -0.200316 0.098116197, + -0.98780614 -0.13981801 0.068483807, + -0.98903477 -0.13573498 0.058191184, + -0.99623466 -0.079683572 0.034161288, + -0.99655133 -0.077776127 0.028918412, + -0.99963766 -0.025230091 0.0093809459, + -0.99966288 -0.024739496 0.0078755189, + -0.99967223 0.024396706 -0.0077663921, + -0.99969065 0.024022091 -0.0064506074, + -0.99721533 0.07202442 -0.019340608, + -0.99733955 0.071165361 -0.015787393, + -0.99267262 0.11796696 -0.02616979, + -0.99292725 0.11689503 -0.020760806, + -0.98615777 0.16325496 -0.028994393, + -0.98651952 0.16216493 -0.02194869, + -0.97760653 0.20853989 -0.028225288, + -0.97802174 0.20757596 -0.019639395, + -0.96700925 0.25360906 -0.023994705, + -0.96739674 0.25288394 -0.013901196, + -0.95411855 0.29897785 -0.016434992, + -0.95440447 0.29850414 -0.0027344814, + -0.96402186 0.26574796 -0.0063207392, + -0.96404099 0.265753 0.00060169498, + -0.96398801 0.26594499 0.00060169498, + -0.96396887 0.26593998 -0.0063165692, + -0.96400422 0.26581207 -0.0063144816, + -0.96402335 0.26581708 0.00059989822, + -0.97589475 0.21818195 -0.0051036286, + -0.97589242 0.21818087 -0.0055636466, + -0.97588533 0.21821308 -0.0055641821, + -0.97589946 0.21821611 -0.0014623808, + -0.98542339 0.17011806 0.0007738173, + -0.98541254 0.17011593 -0.0047620577, + -0.97865838 0.20548807 -0.0015760306, + -0.97851038 0.20586908 -0.011634003, + -0.98714978 0.15954295 -0.0090159886, + -0.98698527 0.16005404 -0.015585204, + -0.99339867 0.11417297 -0.011117596, + -0.99326497 0.114755 -0.015998101, + -0.99757373 0.068951488 -0.0096125482, + -0.99750423 0.069452211 -0.012714403, + -0.9997251 0.023064602 -0.0042223507, + -0.99971461 0.023289593 -0.0053290981, + -0.99970925 -0.023508705 0.0053792414, + -0.99969476 -0.023806594 0.0066008386, + -0.99712342 -0.073038653 0.02025139, + -0.99694276 -0.074218087 0.024431594, + -0.99118853 -0.12581694 0.041417383, + -0.99049437 -0.12835805 0.049448118, + -0.98054385 -0.18317798 0.070566393, + -0.9786765 -0.18765192 0.08354006, + -0.96301365 -0.24616091 0.10958796, + -0.95873737 -0.25327808 0.12912405, + -0.93554926 -0.3146641 0.16041905, + -0.92664576 -0.32514992 0.18869296, + -0.89317667 -0.38895485 0.22571993, + -0.87963915 -0.40024406 0.25698203, + -0.83928472 -0.45750785 0.29374787, + -0.82381052 -0.46649772 0.32204983, + -0.77548617 -0.51957715 0.35869309, + -0.76089013 -0.52536309 0.38084105, + -0.69601274 -0.58134884 0.42142585, + -0.68246382 -0.58480287 0.43846187, + -0.60502195 -0.63703996 0.47762793, + -0.58151799 -0.639956 0.50228798, + -0.49170512 -0.68497419 0.53762114, + -0.45431694 -0.68453395 0.57009596, + -0.3869651 -0.70855016 0.59009713, + -0.34722719 -0.70310438 0.62054628, + -0.28499401 -0.71866101 0.63427502, + -0.27804899 -0.71700102 0.63921702, + -0.22208004 -0.72779506 0.64884108, + -0.22044 -0.72727102 0.64998698, + -0.17118689 -0.73460656 0.6565426, + -0.16930395 -0.73385781 0.65786684, + -0.12617701 -0.73865604 0.66216809, + -0.12495006 -0.73807037 0.66305327, + -0.087846726 -0.74102426 0.66570723, + -0.087344803 -0.74074399 0.666085, + -0.055455808 -0.74244106 0.66761208, + -0.056656186 -0.74321383 0.66665083, + -0.029514093 -0.74408484 0.66743284, + -0.031196799 -0.74531698 0.66597998, + -0.0087449811 -0.74565208 0.66627806, + -0.0097638201 -0.746499 0.66531497, + 0.0085234996 -0.74650699 0.66532302, + 0.0073815663 -0.74758363 0.66412669, + 0.021454299 -0.74743193 0.66399193, + 0.014818398 -0.75448591 0.65614897, + 0.026546691 -0.75430268 0.65598977, + 0.019989602 -0.76216513 0.64707404, + 0.029585093 -0.76198381 0.64691985, + 0.02385659 -0.76982367 0.63781071, + 0.031612206 -0.76965821 0.6376732, + 0.026342304 -0.77800709 0.62770307, + 0.03169189 -0.77788669 0.62760478, + 0.026932592 -0.78679872 0.61662173, + 0.029628389 -0.78673869 0.61657476, + 0.025459297 -0.79626888 0.60440695, + 0.019778799 -0.79637098 0.60448498, + 0.025092389 -0.78051066 0.62463868, + 0.012749705 -0.76747328 0.64095426, + 0.020538298 -0.76737386 0.64087093, + 0.013855197 -0.79599184 0.60514885, + 0.013745098 -0.79599285 0.60514992, + 0.0096922321 -0.82371718 0.56691813, + 0.00505713 -0.82374501 0.56693798, + 0.0036960291 -0.8505218 0.52592689, + -0.00363024 -0.85052198 0.52592701, + -0.0049740896 -0.82370287 0.56699991, + -0.0095328605 -0.8236751 0.56698203, + -0.013565497 -0.7958318 0.60536587, + -0.014025697 -0.79582679 0.60536188, + -0.020668698 -0.76726091 0.64100194, + -0.012868302 -0.7673611 0.64108604, + 0.55924016 -0.64372426 0.52236921, + 0.47620595 -0.68280393 0.55408192, + 0.44636494 -0.67995292 0.58174092, + 0.386758 -0.70072001 0.59950799, + 0.34971702 -0.69293404 0.63050807, + 0.29439297 -0.70686096 0.64317995, + 0.24734098 -0.69135892 0.67885596, + 0.1705751 -0.70307243 0.69035745, + 0.16229893 -0.69941366 0.69604564, + 0.12029105 -0.70366424 0.70027626, + 0.11958704 -0.70329422 0.70076823, + 0.083287537 -0.70591635 0.70338136, + 0.083331332 -0.70594323 0.70334923, + 0.051881582 -0.70745277 0.70485377, + 0.052308328 -0.70774943 0.7045244, + 0.026215097 -0.70847595 0.70524794, + 0.027610496 -0.70957595 0.70408791, + 0.0056519513 -0.70983517 0.70434517, + 0.0077703721 -0.71172118 0.70241916, + -0.010259097 -0.71170479 0.70240378, + -0.0068204585 -0.71515381 0.69893384, + -0.020941092 -0.71501374 0.69879675, + -0.016330693 -0.72022265 0.69355065, + -0.027692493 -0.72004282 0.69337684, + -0.02345551 -0.72546124 0.68786323, + -0.0315874 -0.725299 0.68770897, + -0.026085794 -0.73333782 0.67936385, + -0.032487389 -0.73319978 0.67923677, + -0.026676394 -0.74300784 0.66875082, + -0.030978588 -0.74291575 0.66866773, + -0.025835296 -0.75315291 0.65733796, + -0.028251017 -0.75310349 0.65729541, + -0.023888912 -0.76367635 0.64515728, + -0.018389303 -0.76376516 0.6452322, + -0.02369659 -0.74694377 0.66446477, + -0.023321202 -0.74695003 0.66447103, + -0.027967397 -0.73536593 0.67709297, + -0.025847791 -0.73540777 0.67713177, + -0.031101296 -0.72463393 0.68843192, + -0.027618608 -0.7247082 0.68850219, + -0.032854203 -0.71560705 0.69773006, + -0.027059095 -0.7157318 0.69785082, + -0.031852812 -0.70852423 0.70496726, + -0.023417989 -0.70868963 0.70513165, + -0.028608603 -0.70185304 0.71174705, + -0.017282907 -0.70203537 0.71193236, + -0.0215174 -0.69710302 0.71664798, + -0.0074724099 -0.697245 0.71679401, + -0.010580003 -0.69403225 0.71986622, + 0.007357562 -0.69405216 0.7198872, + 0.0048651011 -0.69176316 0.72210819, + 0.026644999 -0.69152498 0.721861, + 0.025049103 -0.69022506 0.72316104, + 0.050915498 -0.68954599 0.72245002, + 0.050334711 -0.68912816 0.72288918, + 0.08094316 -0.68773866 0.72143161, + 0.080565959 -0.68749964 0.72170162, + 0.116592 -0.68503797 0.71911699, + 0.12455397 -0.6893838 0.71360785, + 0.19315703 -0.68171006 0.70566404, + 0.24066003 -0.70217705 0.67009705, + 0.29049999 -0.69224101 0.66061503, + 0.3285698 -0.70404559 0.62957263, + 0.38357592 -0.6884138 0.61559391, + 0.41600606 -0.69479805 0.58668107, + 0.47392705 -0.67279506 0.56810206, + 0.50030106 -0.67505604 0.54221606, + 0.55967134 -0.64610237 0.5189603, + 0.58093983 -0.64553875 0.49577081, + 0.64982402 -0.60282099 0.462964, + 0.67371792 -0.59932095 0.43234095, + 0.72634482 -0.55742586 0.40211892, + 0.74904102 -0.550807 0.36816999, + 0.79663002 -0.50253999 0.335908, + 0.81296772 -0.49497381 0.30673188, + 0.85449773 -0.44154686 0.27362391, + 0.86556768 -0.43418184 0.24955691, + 0.89998072 -0.37794685 0.21723492, + 0.90937644 -0.36924917 0.19154508, + 0.93765062 -0.30853689 0.16005094, + 0.94404125 -0.30040506 0.13617302, + 0.96406674 -0.24196194 0.10967997, + 0.96720976 -0.23641394 0.092809878, + 0.98101753 -0.18050791 0.070862763, + 0.98241478 -0.17700195 0.059427187, + 0.9913699 -0.12427699 0.041724898, + 0.99189025 -0.12230103 0.034586206, + 0.99717402 -0.072291702 0.0204437, + 0.99731135 -0.071369819 0.016629405, + 0.99971354 -0.023310289 0.0054313773, + 0.99972451 -0.023076689 0.0042821281, + 0.9997285 0.022907488 -0.0042507383, + 0.99973649 0.022734512 -0.0031876517, + 0.99759835 0.068593524 -0.0096176537, + 0.99764675 0.068236984 -0.0066787284, + 0.99344414 0.11377501 -0.011135801, + 0.99352551 0.11341595 -0.0066229668, + 0.98719513 0.15924601 -0.0092992606, + 0.60572386 -0.63697082 0.47682989, + 0.68291318 -0.58479512 0.43777213, + 0.69605124 -0.5814352 0.42124316, + 0.76106298 -0.52530402 0.380577, + 0.77683979 -0.51901489 0.35657191, + 0.82493711 -0.46587405 0.32006302, + 0.8405512 -0.45671913 0.29134405, + 0.88069469 -0.39934984 0.2547479, + 0.89073527 -0.39104414 0.2316791, + 0.92988479 -0.31647691 0.18750095, + 0.92461425 -0.33164409 0.18735205, + 0.95187235 -0.26685709 0.15075307, + 0.9575935 -0.25793087 0.12839894, + 0.97565699 -0.19632199 0.097729698, + 0.97810864 -0.19074893 0.083176672, + 0.98935288 -0.13340499 0.058171492, + 0.99025655 -0.13023993 0.049290776, + 0.99663562 -0.076654471 0.029010689, + 0.9968735 -0.075159438 0.024378411, + 0.99966979 -0.024442995 0.007928228, + 0.99968886 -0.024060596 0.0065850192, + 0.9996959 0.023784297 -0.0065094093, + 0.99971002 0.023490399 -0.0053039002, + 0.99737811 0.070589907 -0.015938502, + 0.99747366 0.069913775 -0.012584295, + 0.99301338 0.11613604 -0.020904208, + 0.99320567 0.11530896 -0.015696095, + 0.98664898 0.161373 -0.0219664, + 0.98690248 0.16059408 -0.015269708, + 0.97816133 0.20691407 -0.019674007, + 0.96770722 0.25205907 -0.0030206607, + 0.9674989 0.25246897 -0.014326698, + 0.97841555 0.20631489 -0.011707595, + 0.97864574 0.20554195 -0.0022585096, + 0.97850001 0.205906 -0.0118529, + 0.98714387 0.15956998 -0.0091856094, + 0.98698699 0.16005699 -0.0154399, + 0.99340045 0.11416806 -0.011013306, + 0.99326837 0.11474604 -0.015851606, + 0.99757546 0.068939626 -0.0095237345, + 0.99750465 0.069451079 -0.012691795, + 0.9997251 0.023063201 -0.0042146905, + 0.99971449 0.023292311 -0.0053417725, + 0.99970901 -0.023511801 0.0053921002, + 0.99969453 -0.023812089 0.0066231769, + 0.99712098 -0.073054597 0.0203197, + 0.99694037 -0.074230827 0.024489509, + 0.99118167 -0.12583895 0.041515484, + 0.99049449 -0.12835306 0.049459822, + 0.98054546 -0.18316409 0.070581235, + 0.97870636 -0.18757308 0.083368927, + 0.96306974 -0.24604394 0.10935698, + 0.95887566 -0.2530399 0.12856196, + 0.93576515 -0.31437504 0.15972501, + 0.92906958 -0.32241386 0.18132591, + 0.8995477 -0.38073984 0.21412893, + 0.89113772 -0.38806584 0.2351139, + 0.85405082 -0.44490388 0.26955095, + 0.84091055 -0.45314178 0.29585785, + 0.79627681 -0.50652885 0.3307139, + 0.77701271 -0.51475281 0.36232689, + 0.72622615 -0.56215811 0.39569408, + 0.7063002 -0.56742913 0.42327809, + 0.63865906 -0.61678708 0.46009606, + 0.62032676 -0.61925977 0.48136482, + 0.54153085 -0.66373974 0.51593983, + 0.5133872 -0.66408223 0.54353321, + 0.44978088 -0.69115281 0.56568986, + 0.4151001 -0.68742418 0.59593612, + 0.35424721 -0.7065984 0.61255836, + 0.30893114 -0.69626635 0.64790028, + 0.224427 -0.71340197 0.663845, + 0.21626887 -0.71062458 0.66950756, + 0.16750805 -0.71756619 0.67604721, + 0.16650607 -0.71714324 0.67674321, + 0.12358197 -0.72172081 0.68106282, + 0.12246796 -0.72116274 0.68185478, + 0.085862711 -0.72394907 0.68448907, + 0.08505518 -0.72347784 0.6850878, + 0.053387683 -0.72507375 0.68659878, + 0.053565394 -0.72519296 0.68645895, + 0.027279887 -0.72596467 0.68719071, + 0.028235096 -0.72669291 0.68638194, + 0.0061631384 -0.72696882 0.68664283, + 0.0086034592 -0.72907394 0.68438095, + -0.0095176408 -0.72906804 0.68437505, + -0.0052865613 -0.7331782 0.68001616, + -0.020018995 -0.73304182 0.67988884, + -0.016604993 -0.73678076 0.67592776, + -0.027706901 -0.73659998 0.67576098, + -0.022168597 -0.74346894 0.66840297, + -0.030873297 -0.74329692 0.66824895, + -0.024714312 -0.75201339 0.65868431, + -0.031888403 -0.75186014 0.65855104, + -0.0263968 -0.76084298 0.648399, + -0.031177197 -0.7607379 0.64830995, + -0.026333394 -0.77009881 0.63738084, + -0.029145693 -0.77003884 0.63733083, + -0.0248073 -0.78025299 0.62497199, + -0.025077291 -0.78024769 0.62496775, + -0.019749705 -0.7962212 0.6046831, + -0.02587959 -0.79610968 0.60459876, + -0.030100204 -0.78644609 0.61692506, + -0.027243404 -0.78651112 0.61697507, + -0.031904105 -0.77776414 0.62774605, + -0.026776897 -0.77788091 0.62784094, + -0.031850211 -0.76983631 0.63744622, + -0.024011197 -0.77000487 0.63758594, + -0.029726099 -0.762182 0.64668, + -0.020016992 -0.7623657 0.64683676, + -0.02646981 -0.75463033 0.65561622, + -0.014630596 -0.75481385 0.65577585, + -0.020132503 -0.74897707 0.66229004, + -0.0059041777 -0.74911577 0.66241276, + -0.0080374591 -0.74710995 0.66465193, + 0.010516203 -0.7470932 0.66463619, + 0.0070414389 -0.74419892 0.66792095, + 0.029276589 -0.74389875 0.66765076, + 0.028007699 -0.74296498 0.66874403, + 0.054735199 -0.74214202 0.66800398, + 0.054777119 -0.74216926 0.66797024, + 0.086370654 -0.74050766 0.6664747, + 0.087786399 -0.74129999 0.66540802, + 0.12496296 -0.73833978 0.66275078, + 0.12666796 -0.73915279 0.66151977, + 0.17020206 -0.73428226 0.65716124, + 0.17205006 -0.73501521 0.65585923, + 0.22171786 -0.72757059 0.64921665, + 0.2228311 -0.72792536 0.64843732, + 0.27855298 -0.71714592 0.63883495, + 0.28590414 -0.71889734 0.63359731, + 0.37820205 -0.69448906 0.61208504, + 0.41988394 -0.69964796 0.57809192, + 0.48540729 -0.67398542 0.55688733, + 0.51675481 -0.67397475 0.52794182, + 0.58250672 -0.63988173 0.50123578, + 0.58219618 -0.63903224 0.50267816, + 0.49028707 -0.68502104 0.53885508, + 0.45320684 -0.68452978 0.57098383, + 0.3551358 -0.71786457 0.59878963, + 0.34912091 -0.71706682 0.60326588, + 0.28619602 -0.73320806 0.61684507, + 0.28521606 -0.73299718 0.61754912, + 0.22864486 -0.74450457 0.62724364, + 0.22588703 -0.74369508 0.62920004, + 0.17593502 -0.75151914 0.63581908, + 0.1730791 -0.75045347 0.63785833, + 0.12928404 -0.75555831 0.64219725, + 0.12721704 -0.75462031 0.64371121, + 0.089259893 -0.75776488 0.64639395, + 0.088194244 -0.75719434 0.64720827, + 0.056101907 -0.75895911 0.64871705, + 0.056060009 -0.75893313 0.64875108, + 0.029147608 -0.7598052 0.64949715, + 0.031450395 -0.76143587 0.64747691, + 0.008989091 -0.76178211 0.64777106, + 0.0098069273 -0.76243985 0.64698482, + -0.0084978072 -0.76244873 0.64699274, + -0.0032550006 -0.76721311 0.64138407, + -0.018174099 -0.76709086 0.64128095, + -0.011437804 -0.77397728 0.63311023, + -0.024518706 -0.77379519 0.63296115, + -0.018661704 -0.78056818 0.6247921, + -0.029268097 -0.78036988 0.62463295, + -0.024247495 -0.78701991 0.61645097, + -0.032381184 -0.78683865 0.61630869, + -0.027596092 -0.7942028 0.60702586, + -0.032928687 -0.79407465 0.60692769, + -0.028375996 -0.80237889 0.59613997, + -0.031367898 -0.80230689 0.59608692, + -0.027321113 -0.81131738 0.58396727, + -0.027211895 -0.81131983 0.58396888, + -0.0220381 -0.82601303 0.56322002, + -0.028920608 -0.82586819 0.56312114, + -0.032856792 -0.81733584 0.57522386, + -0.030125389 -0.81740671 0.5752728, + -0.034310896 -0.8099879 0.58544195, + -0.028885689 -0.81012672 0.58554274, + -0.033471499 -0.80328101 0.59465897, + -0.025156403 -0.80347711 0.59480405, + -0.029761512 -0.79757428 0.60248625, + -0.018412307 -0.79779232 0.60265124, + -0.0233844 -0.79224497 0.60975498, + -0.0093997363 -0.79242671 0.60989475, + -0.015182404 -0.78674918 0.61708611, + 0.0017416498 -0.78683889 0.61715597, + -0.005728588 -0.78032273 0.62535077, + 0.013202791 -0.78026748 0.62530655, + 0.0084419167 -0.77657467 0.6299687, + 0.030682681 -0.77623653 0.62969464, + 0.031375192 -0.77670884 0.62907779, + 0.058778714 -0.77574819 0.62829918, + 0.057531476 -0.77500671 0.62932879, + 0.089803293 -0.77315587 0.62782592, + 0.091229677 -0.77388585 0.62671983, + 0.12914595 -0.77061868 0.62407374, + 0.13184997 -0.7717818 0.62206787, + 0.17621902 -0.76639509 0.61772609, + 0.17913306 -0.76741332 0.61562026, + 0.2299269 -0.75913167 0.60897672, + 0.233041 -0.75997102 0.60674202, + 0.29011208 -0.74787825 0.59708726, + 0.29315999 -0.74845397 0.59487301, + 0.35648996 -0.73141593 0.58133096, + 0.357449 -0.73151898 0.580612, + 0.42710716 -0.70823121 0.56212819, + 0.43077484 -0.70830679 0.55922681, + 0.53236622 -0.6643973 0.52455926, + 0.56338495 -0.66113096 0.49548295, + 0.65217316 -0.60661709 0.45462713, + 0.66977698 -0.60221601 0.43443599, + 0.74385399 -0.54202402 0.391013, + 0.75221598 -0.53873903 0.379383, + 0.81277329 -0.47632518 0.33543113, + 0.82470942 -0.46968523 0.31504014, + 0.86833417 -0.4119021 0.27628306, + 0.88034624 -0.4025211 0.25093305, + 0.91518211 -0.34202302 0.21321803, + 0.91582012 -0.33589402 0.22011103, + 0.8680774 -0.41521922 0.27209312, + 0.859662 -0.421518 0.28862399, + 0.8053121 -0.48916706 0.33494502, + 0.8009901 -0.49156505 0.34172902, + 0.73222107 -0.55921406 0.38875705, + 0.72068107 -0.56375408 0.40348506, + 0.63571966 -0.62771362 0.44926172, + 0.61259687 -0.63316184 0.47310787, + 0.51093227 -0.68861634 0.51454425, + 0.50949615 -0.68876022 0.51577419, + 0.43546706 -0.72056305 0.53959006, + 0.43513578 -0.72056562 0.53985375, + 0.3650471 -0.74507415 0.55821609, + 0.36274189 -0.74489075 0.55996084, + 0.29844901 -0.76290399 0.57350302, + 0.29501814 -0.76234335 0.57601827, + 0.23743297 -0.7750389 0.58561093, + 0.2335339 -0.77408272 0.58843678, + 0.18247499 -0.78272986 0.59500992, + 0.1788591 -0.78155047 0.59765238, + 0.13397506 -0.78719836 0.60197127, + 0.13147403 -0.78618115 0.60384911, + 0.093056075 -0.7896238 0.60649389, + 0.092884526 -0.78954017 0.60662913, + 0.060336776 -0.79152369 0.60815275, + 0.057736106 -0.79004115 0.61032903, + 0.030794697 -0.79098588 0.61105895, + 0.035601109 -0.79413319 0.60670012, + 0.0119964 -0.79457998 0.607041, + 0.019954 -0.80046302 0.59904999, + -0.00087232509 -0.80062211 0.59916908, + 0.0048276004 -0.80536914 0.59275407, + -0.013252498 -0.80530781 0.59270889, + -0.0085588526 -0.80973732 0.58673024, + -0.023300594 -0.80954683 0.58659285, + -0.01891451 -0.81427139 0.58017629, + -0.030854104 -0.8140291 0.58000404, + -0.026571088 -0.81934357 0.57268667, + -0.034937792 -0.8191328 0.57253885, + -0.030978704 -0.82487011 0.56447303, + -0.036060195 -0.82472986 0.56437594, + -0.0320765 -0.83160597 0.55443901, + -0.0343551 -0.83154303 0.55439699, + -0.030534185 -0.83962357 0.54230976, + -0.029804699 -0.83964199 0.54232198, + -0.02488151 -0.85292929 0.52143317, + -0.032463208 -0.85274416 0.52131909, + -0.036117811 -0.84520829 0.53321517, + -0.034633897 -0.84525287 0.53324294, + -0.038344793 -0.8390258 0.54273885, + -0.03335309 -0.8391757 0.54283684, + -0.037192486 -0.83377069 0.55085683, + -0.028619893 -0.83400583 0.55101287, + -0.032302495 -0.82957387 0.55746192, + -0.020370301 -0.829835 0.55763698, + -0.023982296 -0.82607687 0.56304693, + -0.0086305179 -0.82628381 0.5631879, + -0.012533305 -0.8227424 0.56827629, + 0.006553391 -0.82278913 0.56830907, + 0.0021767397 -0.81930488 0.57335395, + 0.024682799 -0.81905699 0.57318097, + 0.018798899 -0.8149339 0.57924896, + 0.04439871 -0.81427419 0.57878011, + 0.035997495 -0.80907786 0.58659792, + 0.064584918 -0.80791217 0.58575314, + 0.059518777 -0.80515969 0.59006375, + 0.09160579 -0.80319786 0.58862692, + 0.096204787 -0.80533189 0.58496594, + 0.13514996 -0.80166173 0.58229983, + 0.13648498 -0.80217189 0.58128494, + 0.18161505 -0.7962833 0.57701719, + 0.18540506 -0.79743028 0.57422119, + 0.23697905 -0.7883842 0.56770712, + 0.24128596 -0.78933787 0.56455892, + 0.29962206 -0.77600217 0.55502009, + 0.30352002 -0.77654314 0.55213803, + 0.36819392 -0.75773585 0.53876686, + 0.37159687 -0.75791669 0.53616983, + 0.44188479 -0.73234564 0.51808077, + 0.44383994 -0.73227292 0.51650995, + 0.51795304 -0.69901603 0.49305305, + 0.5174771 -0.69907916 0.49346313, + 0.59380573 -0.65734172 0.46400079, + 0.59275687 -0.65758783 0.46499187, + 0.69086325 -0.59031224 0.41742015, + 0.70626199 -0.58438301 0.39961299, + 0.78502017 -0.5113461 0.3496691, + 0.79135329 -0.50777817 0.34047213, + 0.85236382 -0.4343479 0.29123494, + 0.85376167 -0.43329486 0.2886979, + 0.90050232 -0.36188212 0.24111609, + 0.90915412 -0.35314304 0.22074603, + 0.94215512 -0.28421804 0.17766201, + 0.95022655 -0.27261388 0.15083493, + 0.97153735 -0.20727508 0.11468305, + 0.97489047 -0.20011909 0.097678244, + 0.98784924 -0.13966604 0.068170816, + 0.98905164 -0.13566296 0.058072876, + 0.99623901 -0.079656303 0.034098201, + 0.99655122 -0.077774912 0.028926408, + 0.99963766 -0.025230691 0.0093839066, + 0.99966264 -0.02474539 0.0078946576, + 0.99967188 0.024402697 -0.0077853189, + 0.99969035 0.024028908 -0.0064726225, + 0.99721277 0.072042987 -0.019406097, + 0.99733812 0.071177207 -0.015825203, + 0.99266899 0.117984 -0.0262319, + 0.99292827 0.11689303 -0.020724406, + 0.98615837 0.16326006 -0.028945211, + 0.98652691 0.16214699 -0.021748997, + 0.97761351 0.2085409 -0.027971987, + 0.97802365 0.20758392 -0.019458592, + 0.96700752 0.25363588 -0.023775389, + 0.96737713 0.25294504 -0.014155902, + 0.95409513 0.29903603 -0.016735302, + 0.95437276 0.29859295 -0.0038467192, + 0.96314573 0.26886794 -0.007767078, + 0.96317452 0.26887587 0.00072052167, + 0.96317345 0.26888013 0.00072052237, + 0.96314466 0.2688719 -0.007766997, + 0.96315074 0.26884994 -0.0077665383, + 0.96317953 0.26885787 0.00072021165, + 0.97518313 0.22135402 -0.0045073302, + 0.97517014 0.22135103 -0.0068519111, + 0.97517765 0.22131793 -0.0068512177, + 0.97519875 0.22132294 -0.0018602995, + 0.98488849 0.17318809 0.00084531243, + 0.98487163 0.17318495 -0.0058959275, + 0.98491865 0.17291795 -0.0058902279, + 0.98493534 0.17292106 0.0008475323, + 0.98488152 0.17322691 0.0008475316, + 0.99219501 0.124642 -0.0036758599, + 0.9917171 0.12840201 -0.0031744705, + 0.02542161 -0.53266817 0.84594232, + 0.016158804 -0.53277111 0.84610516, + 0.0013178405 -0.57205331 0.8202154, + -0.0068322015 -0.57204014 0.82019717, + -0.021092398 -0.60264993 0.79772687, + -0.033948995 -0.60243595 0.79744488, + -0.050326418 -0.63160622 0.77365428, + -0.067830294 -0.63095093 0.77285188, + -0.086029649 -0.65818059 0.74792856, + -0.10792401 -0.65677106 0.74632704, + -0.12744506 -0.68151927 0.72061735, + -0.15345794 -0.67898375 0.71793574, + -0.17370012 -0.7008065 0.69188046, + -0.20363992 -0.69671273 0.68783873, + -0.22593389 -0.71708661 0.65934873, + -0.26016799 -0.71077102 0.65354198, + -0.28546807 -0.7301262 0.62082511, + -0.32376111 -0.72079426 0.61289024, + -0.34959999 -0.73701298 0.578439, + -0.39146084 -0.72387266 0.56812572, + -0.41641307 -0.73633707 0.53329909, + -0.46119794 -0.71861792 0.52046597, + -0.48450994 -0.72740191 0.48593894, + -0.53107923 -0.70456535 0.47068325, + -0.552145 -0.70997697 0.437114, + -0.59870714 -0.68206316 0.4199281, + -0.61710626 -0.68460727 0.38793415, + -0.66238749 -0.65179145 0.36933827, + -0.6778937 -0.65207469 0.33949786, + -0.72112781 -0.61450386 0.3199369, + -0.73374075 -0.61315876 0.29267889, + -0.77406913 -0.57134908 0.27272204, + -0.78397 -0.568973 0.248316, + -0.82033128 -0.5241462 0.22875208, + -0.82781416 -0.52126813 0.20737204, + -0.86882818 -0.46004611 0.18301705, + -0.93199676 -0.35450891 0.075533688, + -0.93417901 -0.352256 0.056791499, + -0.95160925 -0.30339307 0.04891371, + -0.95274001 -0.301898 0.0338239, + -0.96679503 -0.25396401 0.028453499, + -0.96729952 -0.25310689 0.016387893, + -0.97859746 -0.2056921 0.0061544427, + -0.97846955 -0.2059599 0.013335194, + -0.98725426 -0.15907605 0.0048785009, + -0.98718137 -0.15928006 0.010140903, + -0.97837436 -0.20642407 0.013142405, + -0.97804397 -0.207146 0.022814499, + -0.96655446 -0.25492013 0.028076213, + -0.96575886 -0.25624597 0.040593997, + -0.9511295 -0.30498916 0.048315823, + -0.94951349 -0.30707914 0.064239033, + -0.93113935 -0.35693711 0.074668929, + -0.9281714 -0.35991517 0.094652347, + -0.90024221 -0.41459608 0.13294403, + -0.90536177 -0.4106769 0.10800198, + -0.90676326 -0.40726408 0.10916203, + -0.9106046 -0.40420583 0.086122252, + -0.91170174 -0.40150291 0.087151378, + -0.91452861 -0.39917883 0.065526567, + -0.93482578 -0.3504169 0.057522185, + -0.93635166 -0.34880388 0.039767385, + -0.9530791 -0.30077302 0.034291405, + -0.95379555 -0.29980686 0.01974339, + -0.96744138 -0.2525481 0.016631206, + -0.96764112 -0.25222203 0.0074011311, + -0.97554713 -0.21978404 0.0016991802, + -0.97554803 -0.219785 0.000748355, + -0.97569877 -0.21911494 0.00074835483, + -0.97569788 -0.21911398 0.0016782997, + -0.97554487 -0.21979398 0.0016912398, + -0.97554576 -0.21979494 0.00075088383, + -0.98379302 -0.179279 -0.00322786, + -0.985147 -0.17165799 -0.0043597398, + -0.98515612 -0.17165901 0.00083558209, + -0.98516226 -0.17162405 0.00083491515, + -0.98516077 -0.17162296 -0.0019631195, + -0.99237537 -0.12324905 0.00085794629, + -0.99237579 -0.12324897 0.00017377696, + -0.99239498 -0.123094 0.00017091401, + -0.99239463 -0.12309396 0.00086141971, + -0.99239022 -0.12313003 0.00086142024, + -0.99239051 -0.12312994 0.00016903091, + -0.99358267 -0.11305296 0.0035470987, + -0.99354762 -0.11319397 0.0070916875, + -0.98712575 -0.15963295 0.010001097, + -0.9869315 -0.16020292 0.017352393, + -0.97788477 -0.20792796 0.022521695, + -0.97736412 -0.20904604 0.032544103, + -0.96541286 -0.25762296 0.040106595, + -0.96427649 -0.25947911 0.053306527, + -0.94886714 -0.30921802 0.063524805, + -0.94666547 -0.31199214 0.080532834, + -0.92708063 -0.36296487 0.093690172, + -0.9231174 -0.36680418 0.11536505, + -0.89850289 -0.41874495 0.13170098, + -0.89171076 -0.42369491 0.15916796, + -0.86140573 -0.47547382 0.17861894, + -0.85290056 -0.48004177 0.20523289, + -0.81941891 -0.52704793 0.22532897, + -0.8108598 -0.53017288 0.24783695, + -0.773022 -0.57468802 0.268646, + -0.76179087 -0.57717395 0.29418498, + -0.71996063 -0.61832869 0.31516084, + -0.70570123 -0.61959225 0.34364411, + -0.66113019 -0.65611321 0.36389908, + -0.64369673 -0.6554867 0.39495781, + -0.59738123 -0.68690121 0.41388714, + -0.57685012 -0.68370515 0.44698012, + -0.52968979 -0.70993763 0.46413079, + -0.50632983 -0.70353079 0.49867281, + -0.45973578 -0.72451067 0.51354378, + -0.43407491 -0.71439284 0.54883689, + -0.38990492 -0.73023582 0.56100786, + -0.36277303 -0.71620005 0.59619904, + -0.32206589 -0.72760475 0.60569376, + -0.29491511 -0.71008223 0.63938123, + -0.25829211 -0.71791738 0.64643627, + -0.234212 -0.69912398 0.67555201, + -0.20145808 -0.70438224 0.68063223, + -0.17960891 -0.68412971 0.70689964, + -0.15078197 -0.68748784 0.71036983, + -0.129207 -0.66393298 0.73654503, + -0.10474498 -0.6658628 0.73868483, + -0.084108077 -0.63935483 0.76429784, + -0.064185075 -0.64030576 0.76543373, + -0.045115799 -0.61138397 0.79004699, + -0.02991269 -0.61173278 0.79049867, + -0.012846905 -0.5808962 0.81387627, + -0.0025484799 -0.58094198 0.813941, + 0.015622804 -0.54119015 0.84075516, + 0.028237293 -0.54103988 0.84052283, + 0.027102713 -0.54404324 0.83861941, + 0.021940794 -0.54411191 0.83872581, + 0.017838499 -0.54747492 0.83663189, + 0.025843604 -0.54738003 0.83648515, + 0.017229103 -0.58304507 0.81225711, + 0.019185292 -0.58302373 0.81222862, + 0.012683698 -0.61943191 0.78494787, + 0.012077794 -0.61943668 0.78495365, + 0.0079752756 -0.65609461 0.75463653, + 0.0041197706 -0.65611005 0.75465411, + 0.0027017407 -0.69246018 0.72145116, + -0.0025777193 -0.69245982 0.72145182, + -0.0039772694 -0.65607196 0.75468791, + -0.0078947796 -0.656057 0.75467002, + -0.011985107 -0.61930835 0.78505647, + -0.013173698 -0.61929888 0.78504485, + -0.0196319 -0.58312798 0.81214303, + -0.0173073 -0.58315301 0.81217802, + -0.017834902 -0.54753304 0.8365941, + -0.025928397 -0.54743594 0.83644587, + 0.02512219 -0.59459776 0.80363071, + 0.038928095 -0.62384397 0.78057885, + 0.054121807 -0.62340206 0.78002614, + 0.069880396 -0.65111995 0.75575089, + 0.089494973 -0.65009677 0.75456268, + 0.10684605 -0.67574227 0.72935337, + 0.13049099 -0.67382193 0.72727996, + 0.14876696 -0.69672281 0.70174479, + 0.17618006 -0.69354224 0.69854122, + 0.197402 -0.71611899 0.66948199, + 0.22909392 -0.71106476 0.66475779, + 0.2527051 -0.73223525 0.63243324, + 0.28896308 -0.72451323 0.62576425, + 0.31294814 -0.74239737 0.59237629, + 0.35290396 -0.73136795 0.58357495, + 0.37655908 -0.74576318 0.54958212, + 0.41947216 -0.73077023 0.53853315, + 0.44208714 -0.74164921 0.5044952, + 0.48724282 -0.72204876 0.49116182, + 0.50819194 -0.72956896 0.45767894, + 0.5545572 -0.70491922 0.44221616, + 0.57333803 -0.70941603 0.40989307, + 0.61915487 -0.67993385 0.39285791, + 0.63544494 -0.68190593 0.36223498, + 0.67961198 -0.64784002 0.344138, + 0.69326419 -0.64785719 0.3156991, + 0.73514992 -0.60940093 0.29695997, + 0.74620682 -0.60803288 0.27105594, + 0.78510898 -0.56569302 0.25218099, + 0.79372227 -0.56347817 0.22912307, + 0.82870591 -0.51846093 0.21081898, + 0.83516312 -0.51586807 0.19074303, + 0.86602712 -0.46896607 0.17340101, + 0.87069017 -0.46634513 0.15627204, + 0.90383714 -0.40570405 0.13595101, + 0.0070915157 -0.57047766 0.82128251, + 0.0011908594 -0.57049167 0.82130253, + 0.012788497 -0.52060688 0.85370082, + 0.015740296 -0.52058488 0.85366482, + 0.012803097 -0.53850389 0.84252584, + 0.011772199 -0.53850996 0.84253687, + 0.0078451894 -0.57734597 0.81646186, + 0.00391735 -0.57735902 0.81648099, + 0.0025395206 -0.61675614 0.7871502, + -0.0027228794 -0.6167559 0.78714985, + -0.0040878919 -0.57739133 0.81645739, + -0.0079487618 -0.57737809 0.8164382, + -0.011868294 -0.53854579 0.84251261, + -0.012847007 -0.53853929 0.84250247, + -0.015797406 -0.52053815 0.85369229, + -0.012843207 -0.52056026 0.85372841, + -0.0012375499 -0.57051694 0.82128489, + 0.0094002541 -0.57049167 0.82124954, + 0.021929992 -0.61089379 0.79140872, + 0.033248112 -0.61070323 0.7911613, + 0.044194587 -0.63849175 0.76835871, + 0.059549116 -0.63798219 0.7677452, + 0.072381184 -0.6645568 0.74372381, + 0.091745324 -0.66349417 0.74253517, + 0.106043 -0.68811399 0.717812, + 0.12918505 -0.68621725 0.71583325, + 0.14605007 -0.71061724 0.68825322, + 0.17320305 -0.7074632 0.68519819, + 0.19228303 -0.73077506 0.65497708, + 0.22367094 -0.72580481 0.65052181, + 0.24385697 -0.74661392 0.61895192, + 0.27939093 -0.73919785 0.61280286, + 0.30013412 -0.75712132 0.58024716, + 0.33945885 -0.74658364 0.57217169, + 0.36020896 -0.7614069 0.53898895, + 0.40225881 -0.74724966 0.52896678, + 0.42238101 -0.75888503 0.49566901, + 0.46639073 -0.74060059 0.4837257, + 0.48532429 -0.74914539 0.45082328, + 0.53058302 -0.72626698 0.43705601, + 0.54785997 -0.73195994 0.40507293, + 0.59340727 -0.70425236 0.38973919, + 0.60869986 -0.70746285 0.35913891, + 0.65291804 -0.67538708 0.34285602, + 0.66598195 -0.67657793 0.31418198, + 0.70803803 -0.64048606 0.29742202, + 0.71884501 -0.64016998 0.27100599, + 0.7583012 -0.60032713 0.25413907, + 0.76685739 -0.5990023 0.2304911, + 0.80328184 -0.5558669 0.21389295, + 0.80984038 -0.55397326 0.19306009, + 0.84244961 -0.50876474 0.17730491, + 0.8473261 -0.50665003 0.15919901, + 0.87611032 -0.45993918 0.14452204, + 0.8796227 -0.45784986 0.12898596, + 0.90382242 -0.41187522 0.11603405, + 0.90145558 -0.41366878 0.12749894, + 0.87544513 -0.46187705 0.14235702, + 0.87139469 -0.46422184 0.15864894, + 0.84162486 -0.51104295 0.17464998, + 0.836025 -0.513385 0.193644, + 0.80228472 -0.55853081 0.21067193, + 0.79474866 -0.56059176 0.2326189, + 0.7571497 -0.60335875 0.2503649, + 0.74738783 -0.6047219 0.27517793, + 0.70672464 -0.64395171 0.29302984, + 0.69457585 -0.64412582 0.32041591, + 0.65146792 -0.67927396 0.33789998, + 0.63687384 -0.67772985 0.36752391, + 0.59182477 -0.70858377 0.38425586, + 0.57487494 -0.70478296 0.41569194, + 0.52888113 -0.73101521 0.4311631, + 0.50984097 -0.72446895 0.46390393, + 0.46456587 -0.74574983 0.47753087, + 0.44385505 -0.73610407 0.51102203, + 0.40029693 -0.75276887 0.52259094, + 0.37846291 -0.73982179 0.55626386, + 0.33733696 -0.7524249 0.56573892, + 0.31501201 -0.736139 0.59905499, + 0.27709699 -0.74525601 0.60647398, + 0.25494707 -0.72576916 0.63895315, + 0.22120097 -0.73197895 0.64441997, + 0.19982204 -0.7095862 0.67569119, + 0.170587 -0.71357697 0.67949098, + 0.15148804 -0.68992418 0.7078532, + 0.12633698 -0.69238681 0.71037984, + 0.11000606 -0.66850442 0.7355274, + 0.088508807 -0.66994709 0.73711407, + 0.073423833 -0.64371222 0.76173729, + 0.056027584 -0.64444083 0.76259881, + 0.042722195 -0.61659193 0.78612286, + 0.029588796 -0.61688495 0.78649688, + 0.020903392 -0.59465575 0.80370867, + -0.0037604382 -0.57635671 0.81718957, + 0.00021505603 -0.57636106 0.81719512, + -0.0151553 -0.52585697 0.850438, + -0.021198502 -0.52580005 0.85034412, + -0.017364601 -0.54227901 0.84001899, + -0.019308198 -0.54225993 0.83998889, + -0.012981007 -0.5794543 0.81490141, + -0.011892704 -0.57946217 0.81491232, + -0.0078961384 -0.61724186 0.78673381, + -0.0037494691 -0.61725688 0.78675282, + -0.0023750409 -0.65532625 0.7553423, + 0.0024364004 -0.65532619 0.75534219, + 0.0038306001 -0.61738598 0.78665102, + 0.0079897838 -0.61737132 0.78663135, + 0.012012898 -0.57954895 0.8148489, + 0.012881706 -0.57954228 0.81484044, + 0.019238099 -0.54220802 0.84002399, + 0.017287895 -0.5422278 0.84005368, + 0.021105802 -0.52582306 0.85033214, + 0.015072795 -0.52588081 0.85042471, + 0.0033699495 -0.56451792 0.82541388, + -0.0028277985 -0.56451863 0.82541555, + -0.014430895 -0.59467775 0.80383468, + -0.025157591 -0.59455174 0.80366373, + -0.038935382 -0.62372869 0.78067064, + -0.054120209 -0.62328708 0.78011811, + -0.069852784 -0.65095484 0.75589579, + -0.089435399 -0.64993399 0.75471002, + -0.10678197 -0.67557484 0.72951782, + -0.13039 -0.67365903 0.727449, + -0.14877605 -0.69670022 0.70176524, + -0.17618595 -0.69351983 0.69856185, + -0.19659193 -0.71524477 0.67065376, + -0.22808793 -0.71025175 0.66597176, + -0.25134012 -0.73114735 0.6342333, + -0.28742 -0.72352201 0.62761903, + -0.31159487 -0.74160177 0.59408379, + -0.3513999 -0.7306838 0.58533686, + -0.37528986 -0.74527174 0.5511148, + -0.41808715 -0.73039621 0.54011518, + -0.44094706 -0.74143308 0.50580907, + -0.48607805 -0.72192305 0.49249905, + -0.50727117 -0.72956026 0.45871317, + -0.55361974 -0.70499563 0.44326779, + -0.57263619 -0.70956826 0.41061014, + -0.61849231 -0.68012428 0.39357117, + -0.63495404 -0.68212807 0.36267704, + -0.67918909 -0.64805806 0.34456202, + -0.69297582 -0.64807981 0.3158749, + -0.73492366 -0.60959673 0.29711786, + -0.74608165 -0.60821468 0.27099288, + -0.78501898 -0.56584698 0.25211599, + -0.7937243 -0.56360215 0.22881107, + -0.82870698 -0.51857603 0.21053199, + -0.83520228 -0.51595819 0.19032708, + -0.86607581 -0.46901989 0.17301196, + -0.87246889 -0.46533194 0.14921199, + -0.87903959 -0.4512668 0.15377793, + -0.84168619 -0.51110613 0.17416905, + -0.83606881 -0.51346487 0.19324295, + -0.80230719 -0.55865711 0.21025105, + -0.79474521 -0.56073409 0.23228706, + -0.75710988 -0.60354996 0.25002396, + -0.747253 -0.60493398 0.275078, + -0.70657325 -0.64416826 0.29291913, + -0.69428897 -0.64434695 0.32059297, + -0.65114427 -0.67949426 0.33808112, + -0.63639021 -0.67793024 0.36799213, + -0.59129786 -0.7087658 0.38473091, + -0.57417881 -0.70491475 0.41642985, + -0.52816433 -0.73109943 0.43189827, + -0.50891691 -0.72446293 0.46492693, + -0.46359879 -0.74569666 0.47855276, + -0.44269699 -0.73593402 0.51226997, + -0.39921793 -0.75250089 0.52380097, + -0.37716985 -0.73939276 0.55771083, + -0.33616292 -0.75189483 0.56714088, + -0.31363004 -0.73541504 0.60066706, + -0.27586892 -0.74443775 0.60803676, + -0.25355294 -0.72475582 0.64065582, + -0.2200191 -0.73088038 0.64606929, + -0.19897602 -0.70880008 0.67676508, + -0.16993293 -0.71274263 0.68052971, + -0.15149598 -0.68989897 0.70787597, + -0.12637001 -0.69235903 0.71040106, + -0.10994396 -0.66833478 0.73569077, + -0.088432193 -0.66977692 0.73727793, + -0.073375769 -0.64359277 0.76184273, + -0.056038901 -0.644319 0.76270097, + -0.042732984 -0.61647278 0.78621572, + -0.029624192 -0.6167649 0.7865898, + -0.018345097 -0.58781987 0.80878383, + -0.014804695 -0.58785379 0.80883169, + -0.021986205 -0.61082011 0.79146415, + -0.033256486 -0.61062968 0.79121763, + -0.044196595 -0.63839394 0.76843989, + -0.059548493 -0.63788396 0.76782686, + -0.072354808 -0.66440505 0.74386203, + -0.091658346 -0.66334659 0.74267757, + -0.10605302 -0.68813217 0.71779317, + -0.12919503 -0.68623519 0.71581417, + -0.14549302 -0.70982504 0.68918806, + -0.17251399 -0.70670193 0.68615693, + -0.19131292 -0.72970575 0.65645176, + -0.22244413 -0.72481143 0.65204841, + -0.24277012 -0.74580634 0.62035131, + -0.27812296 -0.73847294 0.61425191, + -0.29902503 -0.75657111 0.58153605, + -0.33826104 -0.74611104 0.57349604, + -0.35917708 -0.7610842 0.54013211, + -0.40116924 -0.74700439 0.53013933, + -0.42145276 -0.75875854 0.49665171, + -0.46542001 -0.74055201 0.484734, + -0.4845663 -0.74921143 0.45152828, + -0.52985913 -0.72637016 0.43776211, + -0.54731607 -0.73213208 0.40549707, + -0.59286994 -0.70446396 0.39017394, + -0.60831308 -0.70770907 0.35930902, + -0.65258944 -0.6756224 0.3430182, + -0.66578573 -0.67682272 0.31407085, + -0.7078858 -0.64070582 0.29731095, + -0.71877795 -0.64037895 0.27068996, + -0.75827187 -0.60049492 0.25382996, + -0.76687735 -0.59915233 0.2300341, + -0.80330312 -0.55600005 0.21346703, + -0.80987781 -0.55409086 0.19256495, + -0.84251416 -0.50882214 0.17683305, + -0.84737498 -0.50670499 0.15876301, + -0.87615991 -0.45997095 0.14411998, + -0.88097727 -0.45702615 0.12250005, + -0.85859287 -0.49453494 0.13510498, + -0.88269079 -0.45334089 0.12385097, + -0.88748312 -0.45035306 0.097754918, + -0.86586231 -0.48848018 0.10802604, + -0.8888309 -0.44742495 0.098946989, + -0.89236474 -0.44513887 0.074407682, + -0.91535175 -0.39714491 0.066385187, + -0.91732979 -0.39547491 0.045886889, + -0.93679959 -0.34753484 0.040324282, + -0.93776625 -0.34649009 0.023220705, + -0.95399803 -0.299142 0.020047599, + -0.9542895 -0.29876116 0.008568584, + -0.96358764 -0.2673409 -0.0052622883, + -0.96359766 -0.26734391 0.0025974091, + -0.96359938 -0.2673381 0.002597281, + -0.96360189 -0.26733798 -0.0013623099, + -0.96014434 -0.2794871 -0.0031430111, + -0.92631412 -0.37673205 -0.0039039005, + -0.91402441 -0.40565917 0.00030664416, + -0.91393667 -0.40585685 0.00030664389, + -0.91397923 -0.40576109 0.00030320705, + -0.91396421 -0.4057551 0.0056875716, + -0.91392159 -0.40585083 0.0056895474, + -0.91400969 -0.40565285 0.0056605083, + -0.89924055 -0.43728879 0.012035795, + -0.89856887 -0.43773896 0.030960096, + -0.87473071 -0.48340183 0.03418969, + -0.8728267 -0.48441184 0.059319578, + -0.84927511 -0.52403605 0.06417191, + 0.85207415 -0.52202308 0.038230103, + 0.87528986 -0.48230693 0.035321496, + 0.87608171 -0.48191983 0.015299395, + 0.87142271 -0.49053282 -0.00027135291, + 0.87136799 -0.490502 0.0112089, + 0.87131572 -0.49059483 0.011211396, + 0.8713702 -0.49062613 -0.00026725806, + 0.89436924 -0.44725811 -0.0079968022, + 0.89435577 -0.44725087 0.009715748, + 0.89435875 -0.44724488 0.0097155878, + 0.89437222 -0.44725212 -0.0079981219, + 0.88268244 -0.46996972 -0.00021701786, + 0.93389934 -0.35747311 0.0067181122, + 0.93392026 -0.35748109 -0.00052070414, + 0.93389839 -0.35753819 -0.00052847521, + 0.93387741 -0.35753018 0.0067195734, + 0.92002302 -0.39166099 0.0126213, + 0.91951925 -0.39206707 0.027711507, + 0.89816326 -0.43856812 0.030998308, + 0.89666528 -0.43959415 0.052425619, + 0.8752023 -0.48035318 0.05728652, + -0.0044913692 -0.64613384 0.76321083, + -0.0032850895 -0.60973191 0.79260087, + 0.0032392305 -0.60973203 0.79260111, + 0.0048428108 -0.6579842 0.75301617, + 0.017245201 -0.65789407 0.75291312, + 0.02087909 -0.69348067 0.72017264, + 0.036896721 -0.6931594 0.71983939, + 0.041065503 -0.71707606 0.69578403, + 0.060487591 -0.71636695 0.69509697, + 0.0663592 -0.73987198 0.66946697, + 0.089355305 -0.73854005 0.66826206, + 0.096798576 -0.76104283 0.64143884, + 0.12322508 -0.75880647 0.63955337, + 0.13214503 -0.78015119 0.61147511, + 0.16193296 -0.77666581 0.60874289, + 0.17213209 -0.79653335 0.57957327, + 0.20535897 -0.7913689 0.57581496, + 0.21664102 -0.80954313 0.54562503, + 0.25311804 -0.8022331 0.54069704, + 0.2652221 -0.81849831 0.5096252, + 0.30428705 -0.80864519 0.50349009, + 0.31687191 -0.82280183 0.47179389, + 0.35806596 -0.80998689 0.46444595, + 0.37076712 -0.82191527 0.43242013, + 0.41381904 -0.80566114 0.42386806, + 0.42622691 -0.81528485 0.3919709, + 0.47056523 -0.79523134 0.38232917, + 0.48218787 -0.80253184 0.3513369, + 0.52649516 -0.77881527 0.34095412, + 0.53703898 -0.78402299 0.31128299, + 0.58072573 -0.75664365 0.30041286, + 0.59003723 -0.76007229 0.2722981, + 0.63283426 -0.72892225 0.26113808, + 0.64080691 -0.73089492 0.23485997, + 0.68206179 -0.6962328 0.22372194, + 0.68871534 -0.69708735 0.19935009, + 0.72750705 -0.65965605 0.18864603, + 0.73288238 -0.65971029 0.16633007, + 0.7689119 -0.61995393 0.15630598, + 0.77312654 -0.61948663 0.13605793, + 0.80646884 -0.57751191 0.12683897, + 0.80965102 -0.576756 0.10871, + 0.84023571 -0.53283882 0.10043296, + 0.84251285 -0.53198886 0.08461678, + 0.86990511 -0.48709607 0.077476308, + 0.87133318 -0.48636013 0.065055415, + 0.84491372 -0.53018081 0.070916779, + 0.84306782 -0.53088689 0.08599858, + 0.8130191 -0.57474506 0.093103208, + 0.81037784 -0.57539791 0.11047697, + 0.77763289 -0.61744094 0.11854898, + 0.774032 -0.61787498 0.138221, + 0.73861718 -0.65786517 0.14716703, + 0.73396093 -0.65786195 0.16887599, + 0.69579619 -0.69568318 0.17858504, + 0.68997592 -0.69498897 0.20229597, + 0.64928108 -0.73024207 0.21255703, + 0.64223915 -0.7285642 0.23816606, + 0.59992993 -0.76045185 0.24858998, + 0.59165609 -0.7574811 0.27598104, + 0.54826915 -0.78577328 0.2862891, + 0.53882623 -0.78119934 0.31526816, + 0.49457493 -0.80597585 0.32526696, + 0.48412377 -0.79951364 0.35553083, + 0.43959087 -0.82071084 0.36495692, + 0.42831492 -0.81208283 0.3963179, + 0.38473395 -0.82951587 0.40482494, + 0.37297398 -0.81859988 0.43678895, + 0.33092815 -0.83255243 0.44423321, + 0.31916198 -0.81945086 0.47606295, + 0.27899197 -0.83033991 0.48238894, + 0.26758802 -0.81515211 0.51373506, + 0.22973096 -0.82337588 0.51891792, + 0.21904008 -0.8062883 0.54947317, + 0.18422002 -0.81221211 0.55351108, + 0.17451501 -0.79344511 0.58308607, + 0.14292201 -0.7975381 0.58609408, + 0.13442305 -0.77734232 0.61454827, + 0.10602999 -0.78003991 0.61668092, + 0.098889187 -0.75859791 0.64401096, + 0.073839009 -0.76025313 0.64541703, + 0.068201296 -0.73783392 0.67152792, + 0.046600509 -0.73875219 0.67236418, + 0.042528197 -0.71554697 0.69726896, + 0.024271995 -0.71598381 0.69769484, + 0.0218472 -0.69252402 0.72106397, + 0.006843002 -0.69267321 0.72121918, + 0.0056664012 -0.6575942 0.75335115, + 0.0074123009 -0.65758705 0.75334209, + -0.8127979 -0.57491195 0.093999185, + -0.81017435 -0.57555127 0.11116805, + -0.77739412 -0.61759907 0.11928902, + -0.77385211 -0.61802006 0.13857901, + -0.73842192 -0.65799993 0.14754398, + -0.73382902 -0.657996 0.168927, + -0.69563216 -0.69583321 0.17864004, + -0.68987209 -0.69515008 0.20209603, + -0.64915997 -0.73041093 0.21234697, + -0.64217472 -0.72875464 0.23775688, + -0.59982902 -0.76066899 0.248169, + -0.59158206 -0.75772011 0.27548304, + -0.54810894 -0.78606689 0.28578898, + -0.53867322 -0.78151035 0.31475815, + -0.49437007 -0.80631113 0.32474703, + -0.48387629 -0.79983747 0.3551392, + -0.43929499 -0.82104701 0.364557, + -0.42796195 -0.81238788 0.39607394, + -0.3843199 -0.8298288 0.4045769, + -0.37248009 -0.81884819 0.43674508, + -0.3303839 -0.83279485 0.44418389, + -0.31853691 -0.81960583 0.47621489, + -0.27839509 -0.83046228 0.48252317, + -0.26692894 -0.81518984 0.51401788, + -0.22903992 -0.82339573 0.5191918, + -0.21831207 -0.80624431 0.54982716, + -0.18351902 -0.81214112 0.55384809, + -0.17377606 -0.79329032 0.58351725, + -0.14226897 -0.79735285 0.58650488, + -0.13374206 -0.77707833 0.61503029, + -0.10548998 -0.77974784 0.61714286, + -0.098354504 -0.75830901 0.64443302, + -0.073376484 -0.75994885 0.64582783, + -0.067736767 -0.73751265 0.67192769, + -0.04630851 -0.73841721 0.6727522, + -0.042251613 -0.71528816 0.69755119, + -0.024190506 -0.71571815 0.69797015, + -0.021781605 -0.69240916 0.72117621, + -0.0068655922 -0.69255722 0.72133023, + -0.0060902699 -0.66959 0.742706, + -0.018412896 -0.66948885 0.74259382, + -0.020860413 -0.69331944 0.72032839, + -0.036740094 -0.69300193 0.71999896, + -0.040875427 -0.71672744 0.69615442, + -0.060146131 -0.71602833 0.69547534, + -0.065992892 -0.73944294 0.66997695, + -0.088860154 -0.73812664 0.66878468, + -0.096318662 -0.76068968 0.64192975, + -0.12259605 -0.75847828 0.64006323, + -0.13151297 -0.77982682 0.6120249, + -0.16118494 -0.77637368 0.60931379, + -0.171426 -0.79633498 0.580055, + -0.20463495 -0.7911948 0.57631189, + -0.21595505 -0.80944115 0.5460481, + -0.25236416 -0.80217046 0.54114228, + -0.26455104 -0.81855112 0.50988907, + -0.30359897 -0.80872887 0.50377095, + -0.31624508 -0.8229562 0.47194511, + -0.35748002 -0.81015509 0.46460405, + -0.37027103 -0.82216412 0.43237206, + -0.41338322 -0.80590838 0.42382321, + -0.4258728 -0.81558758 0.39172581, + -0.47024819 -0.79553229 0.38209316, + -0.48193419 -0.80286127 0.35093212, + -0.52630806 -0.77911711 0.34055302, + -0.53688723 -0.78432834 0.31077516, + -0.58064216 -0.75690728 0.29991013, + -0.58995402 -0.76032299 0.27177799, + -0.63276327 -0.72916222 0.26064008, + -0.64071983 -0.7311188 0.23439994, + -0.68200803 -0.696428 0.223278, + -0.68859935 -0.69726634 0.1991251, + -0.72743392 -0.65979993 0.18842497, + -0.73274696 -0.65984893 0.16637698, + -0.76880229 -0.62007922 0.15634906, + -0.7729528 -0.61962086 0.13643298, + -0.80631882 -0.57764387 0.12719098, + -0.80944914 -0.57690704 0.10940901, + -0.83913487 -0.53439796 0.10134798, + -0.83672702 -0.535254 0.11572, + -0.80552536 -0.5791803 0.12521607, + -0.80185485 -0.5800119 0.14357898, + -0.76782387 -0.62188995 0.15394598, + -0.76300913 -0.62237906 0.17453201, + -0.72627503 -0.66187203 0.185607, + -0.72016627 -0.66176021 0.20840807, + -0.68067294 -0.69875497 0.22005898, + -0.67314625 -0.69772923 0.24504709, + -0.63123882 -0.7317698 0.25700295, + -0.62222201 -0.72946602 0.28411099, + -0.57894468 -0.75977463 0.29591486, + -0.56846607 -0.75582713 0.32491803, + -0.52444792 -0.78222686 0.33626696, + -0.51261413 -0.7762742 0.36691308, + -0.46823087 -0.79886484 0.37759092, + -0.45528516 -0.79060131 0.40946916, + -0.41122606 -0.8094151 0.41921407, + -0.39767584 -0.79875869 0.45148486, + -0.35519391 -0.81378984 0.45998189, + -0.34147808 -0.80075318 0.49212512, + -0.30122587 -0.81239372 0.49927881, + -0.28769195 -0.79700583 0.53105086, + -0.24994092 -0.8057757 0.53689384, + -0.23706509 -0.78830427 0.56778216, + -0.20218804 -0.79467618 0.57237214, + -0.19021991 -0.77522063 0.60236973, + -0.15878895 -0.77961981 0.60578787, + -0.14805798 -0.75854188 0.63458097, + -0.12030499 -0.7614249 0.63699192, + -0.11096397 -0.73888981 0.66462684, + -0.086764053 -0.74067765 0.66623473, + -0.079015896 -0.71706992 0.69250792, + -0.058348794 -0.71809292 0.69349694, + -0.052371781 -0.69399577 0.71807176, + -0.035343193 -0.69451481 0.71860981, + -0.0311509 -0.67030799 0.74142897, + -0.017392397 -0.67053181 0.74167681, + -0.014897208 -0.64606929 0.76313335, + -0.013755701 -0.64727306 0.76213413, + -0.010018699 -0.61017293 0.79220486, + -0.0023483408 -0.61020225 0.79224229, + -0.00071851321 -0.56038016 0.82823527, + 0.00064489921 -0.56038016 0.82823527, + 0.00226476 -0.61022103 0.79222798, + 0.010007204 -0.61019224 0.79219031, + 0.014947892 -0.65903968 0.75195962, + 0.0148748 -0.65904099 0.75195998, + 0.95311499 -0.300695 0.033975702, + 0.93640512 -0.34870204 0.039399903, + 0.93489778 -0.35030591 0.057025883, + 0.91462022 -0.39906108 0.064962715, + 0.91174829 -0.40143016 0.086998932, + 0.91065401 -0.404127 0.085969299, + 0.93203586 -0.35443497 0.075398296, + 0.93425399 -0.352137 0.056294002, + 0.95166373 -0.30329093 0.04848529, + 0.95278025 -0.30180606 0.033511907, + 0.96681875 -0.25390294 0.028192792, + 0.96729946 -0.25308713 0.016693708, + 0.97846866 -0.20594792 0.013584395, + 0.97859102 -0.205699 0.0068999901, + 0.97624135 -0.21668507 0.00063633325, + 0.97623676 -0.21668395 0.0031393394, + 0.97627562 -0.21650892 0.0031350688, + 0.97628021 -0.21651004 0.0006356822, + 0.97623563 -0.21671093 0.00063568278, + 0.97623098 -0.21671 0.0031423999, + 0.96763152 -0.25222588 0.0084396563, + 0.96744186 -0.25252596 0.016937697, + 0.95379835 -0.29977411 0.020106807, + 0.95427787 -0.29875797 0.0098700989, + 0.9540019 -0.29910496 0.020412298, + 0.93777412 -0.34644002 0.023642704, + 0.93685198 -0.34743601 0.039957602, + 0.91739714 -0.39536706 0.045470003, + 0.915443 -0.397028 0.065825202, + 0.89547473 -0.43911788 0.072803386, + 0.89151812 -0.44569206 0.080956809, + 0.86696661 -0.49034277 0.089067258, + 0.86464202 -0.49150199 0.104019, + 0.83616215 -0.53659713 0.11356203, + 0.832932 -0.53773201 0.130647, + 0.8010729 -0.58164597 0.14131598, + 0.79674768 -0.5825808 0.16060095, + 0.76202667 -0.62425971 0.17209092, + 0.75642884 -0.62476689 0.19360195, + 0.71896118 -0.6639052 0.20573005, + 0.71194422 -0.66369826 0.22943409, + 0.67175597 -0.70011991 0.24202497, + 0.66317761 -0.69885159 0.26795885, + 0.62070167 -0.7320776 0.28069884, + 0.610542 -0.72936398 0.308653, + 0.56686085 -0.75867683 0.32105792, + 0.55513507 -0.75412011 0.35089603, + 0.51097184 -0.77935869 0.36263987, + 0.49789676 -0.77262366 0.39389282, + 0.45363405 -0.79396212 0.40477207, + 0.43962905 -0.78485513 0.43672505, + 0.39602482 -0.80238461 0.44647878, + 0.38149583 -0.79078865 0.47865877, + 0.33982602 -0.80457711 0.48700505, + 0.32520908 -0.79051518 0.51896513, + 0.28602198 -0.80103189 0.52586997, + 0.27174395 -0.78462881 0.55723691, + 0.23533803 -0.79241014 0.56276304, + 0.22173193 -0.77378368 0.59337479, + 0.18844491 -0.77931964 0.59761971, + 0.17591009 -0.75877738 0.6271463, + 0.14624 -0.76251 0.63023198, + 0.13498199 -0.74023092 0.65866393, + 0.10913104 -0.74260622 0.66077721, + 0.099401437 -0.71896923 0.68789726, + 0.0771567 -0.72039402 0.68926001, + 0.069158189 -0.69585592 0.71484393, + 0.0506007 -0.69663298 0.71564102, + 0.044464123 -0.67172128 0.73946834, + 0.031400703 -0.67205507 0.73983508, + 0.035348199 -0.69483602 0.71829897, + 0.052551292 -0.69430995 0.71775496, + 0.058569402 -0.71857101 0.69298297, + 0.079419203 -0.71753299 0.69198197, + 0.087184876 -0.74118084 0.66561985, + 0.111546 -0.739371 0.66399401, + 0.12086503 -0.76184016 0.6363892, + 0.14877097 -0.7589258 0.63395482, + 0.15949304 -0.7799722 0.60514909, + 0.19097391 -0.77554464 0.60171372, + 0.20288397 -0.79489189 0.57182592, + 0.23784703 -0.78847909 0.56721205, + 0.25067306 -0.80587119 0.53640914, + 0.28845203 -0.79706609 0.53054804, + 0.30189398 -0.81234288 0.49895793, + 0.34213996 -0.80067587 0.49179095, + 0.35577399 -0.81363302 0.459811, + 0.39822286 -0.79858673 0.45130685, + 0.41166693 -0.8091619 0.41926995, + 0.4556922 -0.79034138 0.40951821, + 0.46855283 -0.79855871 0.37783885, + 0.51286584 -0.77599072 0.36716089, + 0.52463681 -0.78192472 0.33667487, + 0.5686059 -0.75554985 0.32531792, + 0.57904106 -0.75949413 0.29644603, + 0.62228692 -0.72920996 0.28462598, + 0.6313132 -0.73152918 0.25750506, + 0.67316216 -0.69754016 0.24554107, + 0.68071693 -0.69858092 0.22047497, + 0.72018343 -0.66161543 0.20880812, + 0.726345 -0.66173601 0.185818, + 0.76306754 -0.62225163 0.1747309, + 0.76793611 -0.62176108 0.15390702, + 0.80194187 -0.57989997 0.14354499, + 0.80567271 -0.57905382 0.12485296, + 0.83685768 -0.53512281 0.11538096, + 0.83960843 -0.53412521 0.098833844, + 0.86750215 -0.48913011 0.090507925, + 0.86942631 -0.48814818 0.076218732, + 0.89415622 -0.44239512 0.069074914, + 0.89595187 -0.44113594 0.051664792, + 0.91797924 -0.3939361 0.046136912, + 0.91917539 -0.39290214 0.027288409, + 0.93804598 -0.345678 0.0240086, + 0.93842733 -0.34529412 0.011238404, + 0.95026821 -0.31138507 0.0054619415, + 0.9502821 -0.31139004 0.00040469805, + 0.95034277 -0.31120494 0.00040469892, + 0.95032853 -0.31120086 0.0054431474, + 0.95031023 -0.31125706 0.0054445714, + 0.95032436 -0.31126112 0.00040597015, + 0.96439689 -0.26439396 -0.0058686589, + 0.96440464 -0.26439592 0.0042895088, + 0.96443677 -0.26427895 0.0042865989, + 0.96444523 -0.26428106 -0.0010086203, + 0.9601441 -0.27948704 -0.0032364305, + 0.92631388 -0.37673193 -0.0039558997, + 0.91524887 -0.40288895 0.00010190999, + 0.91521841 -0.40287519 0.0081782639, + 0.91523731 -0.40283215 0.0081771323, + 0.91526777 -0.40284592 0.00010035797, + 0.9150449 -0.40335193 0.00010035998, + 0.91501391 -0.40333793 0.0082540587, + 0.89923579 -0.43723992 0.014012297, + 0.89859521 -0.43764713 0.031490408, + 0.87477714 -0.48327607 0.034773603, + 0.87345582 -0.48402789 0.052838787, + 0.84686887 -0.52866095 0.057711191, + 0.84540755 -0.52923071 0.072118059, + 0.81580299 -0.57303399 0.078087203, + 0.8136642 -0.5735811 0.09463232, + 0.78143227 -0.61566722 0.10157604, + 0.77844167 -0.61605573 0.12043194, + 0.74361378 -0.65618879 0.12827696, + 0.73961681 -0.65622282 0.14946097, + 0.70203978 -0.69435579 0.15814593, + 0.69698292 -0.69379693 0.18127498, + 0.65682119 -0.72955519 0.19061804, + 0.65064174 -0.72813475 0.21560393, + 0.60879487 -0.76068079 0.22524095, + 0.60146999 -0.75811303 0.25198901, + 0.55836612 -0.78724515 0.26167205, + 0.54995888 -0.78324682 0.28994793, + 0.50583994 -0.80897588 0.29947296, + 0.49642888 -0.80324483 0.32917491, + 0.45175713 -0.82551116 0.33830008, + 0.44158307 -0.81782711 0.36900303, + 0.39760092 -0.83636582 0.3773669, + 0.38685519 -0.82650441 0.40894222, + 0.34409717 -0.84155643 0.4163892, + 0.33314398 -0.82948089 0.44830394, + 0.29200304 -0.84139413 0.45474207, + 0.28129098 -0.8272509 0.48634493, + 0.24217394 -0.83639783 0.49172187, + 0.23206286 -0.82036054 0.52264273, + 0.19571796 -0.82707381 0.52691889, + 0.18650502 -0.80938214 0.55688107, + 0.15323301 -0.81410801 0.56013203, + 0.14511596 -0.7949447 0.58907074, + 0.114889 -0.79812902 0.59143102, + 0.10806196 -0.77775669 0.61920679, + 0.081025794 -0.7797659 0.62080592, + 0.075610086 -0.75836682 0.6474278, + 0.051964827 -0.75951636 0.64840931, + 0.048041008 -0.73730004 0.67385507, + 0.027629999 -0.73787099 0.67437601, + 0.025256701 -0.71504402 0.698623, + 0.0080127344 -0.71524942 0.69882339, + 0.0072352816 -0.69231617 0.72155815, + -0.007129882 -0.69231617 0.72155917, + -0.0079051368 -0.71513778 0.69893879, + -0.025009809 -0.71493626 0.69874221, + -0.02737291 -0.73765826 0.67461926, + -0.047617707 -0.73709804 0.67410606, + -0.051535219 -0.75928432 0.64871526, + -0.075066306 -0.75814915 0.64774609, + -0.080481678 -0.77955782 0.62113786, + -0.10742898 -0.77756882 0.61955291, + -0.11427099 -0.7979939 0.59173292, + -0.14439693 -0.79483765 0.58939171, + -0.15252601 -0.814035 0.560431, + -0.18578699 -0.80933189 0.55719393, + -0.19503197 -0.82708788 0.52715093, + -0.231355 -0.82040298 0.52288997, + -0.24151906 -0.83652717 0.49182412, + -0.28068006 -0.82739419 0.48645413, + -0.29145002 -0.84161013 0.45469707, + -0.332609 -0.829714 0.44826999, + -0.34364188 -0.84187073 0.41612986, + -0.38643891 -0.82682282 0.40869191, + -0.3972249 -0.83670682 0.37700692, + -0.44130516 -0.81814027 0.36864111, + -0.45151493 -0.82583886 0.33782297, + -0.49624723 -0.80354935 0.32870516, + -0.50565398 -0.80926299 0.29901099, + -0.54982197 -0.78351003 0.289496, + -0.55821413 -0.78748816 0.26126507, + -0.60137886 -0.75831884 0.25158694, + -0.6086551 -0.76085919 0.22501606, + -0.65052009 -0.72830707 0.21538903, + -0.65664124 -0.72970825 0.19065207, + -0.69681197 -0.693959 0.18131199, + -0.70180362 -0.69451165 0.15850893, + -0.73940921 -0.65637815 0.14980602, + -0.74333501 -0.65635097 0.12906, + -0.77820301 -0.61621302 0.121168, + -0.78117585 -0.61583793 0.10250799, + -0.813434 -0.57376301 0.095504798, + -0.81560284 -0.57321787 0.078825377, + -0.84460282 -0.53040189 0.072937489, + -0.8428852 -0.5310421 0.08682622, + -0.84471631 -0.52734816 0.091423333, + -0.86896002 -0.487609 0.0845339, + -0.87196517 -0.48606512 0.058458313, + -0.89657068 -0.43973184 0.052885883, + -0.89813799 -0.43865699 0.030468199, + -0.91950274 -0.3921389 0.027237095, + -0.9200331 -0.39169106 0.010834701, + -0.93275923 -0.36047208 0.0044848612, + -0.93278044 -0.36041719 0.0044837622, + -0.93278939 -0.36042112 -0.00082284131, + -0.93276811 -0.36047602 -0.00083027012, + -0.94931465 -0.31432688 0.00056290085, + -0.94935465 -0.31420588 0.00056290085, + -0.94932353 -0.31429985 0.00056503073, + -0.94931787 -0.31429797 0.0034989596, + -0.94934911 -0.31420404 0.0034971004, + -0.94930899 -0.314325 0.0035087899, + -0.93844324 -0.34529808 0.0096782818, + -0.93804109 -0.34572002 0.023590904, + -0.91915977 -0.39297092 0.026815094, + -0.91790825 -0.3940531 0.04654691, + -0.89585477 -0.44127887 0.052125391, + -0.8933807 -0.44292885 0.07539957, + -0.86774111 -0.48996806 0.083407104, + -0.86453581 -0.49162087 0.10433998, + -0.83603382 -0.5367229 0.11391197, + -0.83285588 -0.53783792 0.13069598, + -0.80099082 -0.58174688 0.14136598, + -0.79672402 -0.58267301 0.160384, + -0.761958 -0.62440401 0.17187101, + -0.75640911 -0.62491405 0.19320403, + -0.71893406 -0.66406506 0.20530804, + -0.71194208 -0.66386908 0.22894603, + -0.6717338 -0.70031685 0.24151593, + -0.66316259 -0.69906259 0.26744485, + -0.62063211 -0.73233718 0.28017506, + -0.61044431 -0.72962838 0.30822116, + -0.56670588 -0.75897783 0.32061991, + -0.55493277 -0.75441366 0.35058483, + -0.51069379 -0.77968562 0.36232883, + -0.49750817 -0.77290028 0.39384115, + -0.45322084 -0.79422969 0.40470985, + -0.43910593 -0.78505391 0.43689394, + -0.39546993 -0.8025679 0.44664094, + -0.38084501 -0.79089397 0.47900301, + -0.33916309 -0.80465519 0.48733813, + -0.32444599 -0.79048997 0.519481, + -0.2852599 -0.80097473 0.52637082, + -0.27090004 -0.7844671 0.55787504, + -0.23457812 -0.79220039 0.56337529, + -0.22090392 -0.77346569 0.59409773, + -0.18771499 -0.77895999 0.59831798, + -0.17512698 -0.75831187 0.62792796, + -0.14561391 -0.76200551 0.63098663, + -0.13433899 -0.73967195 0.65942293, + -0.108628 -0.74202102 0.66151702, + -0.098902181 -0.71837282 0.68859184, + -0.076877169 -0.71977574 0.68993676, + -0.068953484 -0.6954568 0.7152518, + -0.050498806 -0.69622707 0.71604306, + -0.04446651 -0.67174119 0.73945016, + -0.029538803 -0.67211306 0.73985904, + -0.025242388 -0.64712769 0.76196367, + -0.023467794 -0.64917982 0.7602728, + -0.036262598 -0.64893192 0.75998187, + -0.042448785 -0.67422974 0.73730075, + -0.058754809 -0.67367208 0.73669106, + -0.06674017 -0.69836462 0.71262366, + -0.08652027 -0.69730073 0.71153778, + -0.096491143 -0.72174037 0.68540531, + -0.12003101 -0.71988106 0.68364006, + -0.13181101 -0.74341708 0.65571105, + -0.15930404 -0.74038321 0.65303516, + -0.17256099 -0.7623319 0.62375695, + -0.203899 -0.75768298 0.61995298, + -0.21834804 -0.77768415 0.58951813, + -0.25314301 -0.77095598 0.58441901, + -0.26842892 -0.78873068 0.55303681, + -0.30633602 -0.77941614 0.54650605, + -0.32206392 -0.79475182 0.51443589, + -0.36284092 -0.7822718 0.50635689, + -0.37859192 -0.79503781 0.47390187, + -0.42166525 -0.77887845 0.46427026, + -0.43698826 -0.78902346 0.43183726, + -0.48109511 -0.76902419 0.42089108, + -0.49553999 -0.77662897 0.38895699, + -0.53993887 -0.75259382 0.37691993, + -0.55312288 -0.75785983 0.3459819, + -0.59730113 -0.72958416 0.33307409, + -0.6088019 -0.73277181 0.30398294, + -0.65195757 -0.70038158 0.29054582, + -0.66168696 -0.70191294 0.26360697, + -0.70265204 -0.66610807 0.25016004, + -0.71064395 -0.66641593 0.22555497, + -0.74892515 -0.6276772 0.21244405, + -0.75529337 -0.62715727 0.19027808, + -0.79085129 -0.58564723 0.17768405, + -0.79578698 -0.58462602 0.15791, + -0.82839531 -0.54076517 0.14606306, + -0.83209532 -0.53950417 0.12865704, + -0.86016673 -0.49610183 0.11830596, + -0.85746813 -0.49736905 0.13180502, + -0.82757568 -0.54262382 0.14379795, + -0.82328486 -0.54403895 0.16193698, + -0.7898562 -0.58780509 0.17496404, + -0.78417218 -0.58891809 0.19557504, + -0.74775684 -0.63013381 0.20926295, + -0.74045539 -0.63064736 0.23240013, + -0.70130503 -0.66888905 0.24649303, + -0.6922012 -0.66843319 0.27213007, + -0.65043396 -0.70349693 0.28640497, + -0.63939703 -0.70162803 0.31446701, + -0.59561938 -0.73301041 0.32853222, + -0.58267897 -0.72926301 0.358693, + -0.53809595 -0.75634587 0.37201297, + -0.52357697 -0.75036502 0.40350899, + -0.47909805 -0.77307314 0.41572005, + -0.46333382 -0.76457667 0.44804484, + -0.41952014 -0.7831803 0.45894617, + -0.402931 -0.77199101 0.491606, + -0.36055401 -0.78675902 0.50101, + -0.34361598 -0.77281487 0.53355896, + -0.30393004 -0.78399414 0.54127604, + -0.28711995 -0.76738381 0.5733099, + -0.250631 -0.77554601 0.57940698, + -0.234386 -0.756432 0.61063403, + -0.20131503 -0.76217711 0.61527103, + -0.18606009 -0.74083138 0.64540732, + -0.156688 -0.74468398 0.64876401, + -0.14277208 -0.72141439 0.67762631, + -0.11747804 -0.72383422 0.67989922, + -0.1054 -0.69948101 0.70683599, + -0.08403784 -0.70091033 0.70828134, + -0.074040204 -0.67621309 0.73297608, + -0.056313116 -0.6769982 0.73382717, + -0.048138581 -0.65152675 0.75709671, + -0.033927593 -0.6519078 0.7575388, + -0.02758161 -0.62574822 0.77953732, + -0.019487493 -0.62586778 0.77968568, + -0.002630021 -0.61168224 0.79109931, + -0.0071748602 -0.61166799 0.79108202, + -0.0021363006 -0.56098515 0.82782316, + 0.00042542908 -0.5609861 0.82782519, + 0.0019304497 -0.51399195 0.85779285, + -0.0020066593 -0.51399183 0.85779268, + -0.0005084569 -0.56099087 0.82782185, + 0.0020538403 -0.56099004 0.82782012, + 0.00709019 -0.61172599 0.79103798, + 0.017024396 -0.6116519 0.7909438, + 0.023406712 -0.64927036 0.76019746, + 0.036237802 -0.64902204 0.75990611, + 0.042407211 -0.67425716 0.73727816, + 0.058739286 -0.67369884 0.73666781, + 0.066875309 -0.69885409 0.71213108, + 0.086791076 -0.69777882 0.71103585, + 0.096878842 -0.72249061 0.68455958, + 0.12062199 -0.72060496 0.68277293, + 0.13238096 -0.74408174 0.65484178, + 0.16006994 -0.74100876 0.65213776, + 0.17329189 -0.76287752 0.62288666, + 0.20477 -0.758183 0.61905402, + 0.21914203 -0.77805614 0.58873206, + 0.25401303 -0.7712841 0.58360803, + 0.26923299 -0.78896099 0.55231702, + 0.30717081 -0.77960551 0.54576671, + 0.3227981 -0.79482919 0.51385611, + 0.363601 -0.782305 0.50576001, + 0.37922686 -0.79496169 0.47352183, + 0.42230377 -0.77876753 0.46387574, + 0.43750811 -0.78883219 0.43166009, + 0.48159289 -0.76881385 0.42070591, + 0.49592507 -0.77636212 0.38899904, + 0.54026687 -0.75233781 0.3769609, + 0.55332863 -0.75756353 0.34630179, + 0.59746712 -0.72930616 0.33338508, + 0.60891104 -0.73249006 0.30444303, + 0.65201926 -0.70013726 0.29099607, + 0.66171771 -0.70167565 0.26416087, + 0.70265108 -0.66590804 0.25069502, + 0.71065593 -0.66622996 0.22606596, + 0.74891543 -0.62752336 0.21293214, + 0.75531363 -0.62701172 0.19067691, + 0.79084086 -0.58554494 0.17806698, + 0.79581732 -0.58452225 0.15814106, + 0.82841611 -0.54067504 0.14627801, + 0.83217186 -0.53939795 0.12860699, + 0.86131012 -0.49422607 0.11783701, + 0.86404514 -0.49289507 0.10237502, + 0.88981158 -0.44679278 0.092799053, + 0.8909567 -0.44378585 0.096178465, + 0.036955599 -0.62896597 0.77655399, + 0.045388188 -0.65546679 0.7538588, + 0.06117063 -0.65491432 0.75322336, + 0.071363576 -0.68030375 0.72944778, + 0.090670824 -0.67923319 0.72830015, + 0.10304802 -0.70439917 0.70228416, + 0.12630001 -0.70249802 0.70038903, + 0.14078397 -0.7269398 0.67211485, + 0.16825895 -0.7237848 0.66919684, + 0.18426901 -0.74641109 0.63946503, + 0.21563508 -0.74154925 0.63530022, + 0.23276106 -0.76192516 0.60439414, + 0.26778495 -0.75483084 0.59876686, + 0.28562319 -0.77268147 0.56690633, + 0.32412896 -0.76274091 0.55961293, + 0.34218803 -0.77782714 0.52715504, + 0.38374186 -0.76442373 0.51807183, + 0.4015311 -0.77663916 0.48539111, + 0.44489399 -0.75945699 0.47465199, + 0.46192989 -0.76884782 0.44214687, + 0.50635988 -0.74752784 0.42988592, + 0.52214593 -0.75423187 0.39811793, + 0.56702912 -0.72844517 0.38450709, + 0.58124501 -0.73275 0.353881, + 0.62562096 -0.70249194 0.33926898, + 0.637981 -0.70475298 0.31032801, + 0.68052483 -0.67059082 0.29528594, + 0.69083959 -0.67124957 0.26863486, + 0.73089194 -0.63363492 0.25358197, + 0.73922491 -0.63316393 0.22945596, + 0.77655089 -0.59235692 0.21466698, + 0.78309488 -0.59116691 0.19309098, + 0.81741881 -0.54757488 0.17885296, + 0.82239819 -0.54600114 0.15982504, + 0.85310286 -0.50073093 0.14657399, + 0.85678184 -0.49903387 0.12996197, + 0.88388222 -0.45261312 0.11787203, + 0.88614827 -0.45121315 0.10558404, + 0.86066431 -0.49578017 0.11601304, + 0.8574847 -0.49728781 0.13200295, + 0.82759714 -0.54253405 0.14401302, + 0.82326716 -0.54395515 0.16230804, + 0.78985071 -0.58769476 0.17535894, + 0.78413898 -0.58880299 0.196054, + 0.74775165 -0.62997371 0.2097629, + 0.74044102 -0.630476 0.23291001, + 0.70130336 -0.6686933 0.24702811, + 0.69222426 -0.66822422 0.27258408, + 0.65050143 -0.7032454 0.28686917, + 0.63953096 -0.70137691 0.31475496, + 0.59578127 -0.73274422 0.32883212, + 0.58295292 -0.72902292 0.35873598, + 0.53842294 -0.75609189 0.37205598, + 0.52401209 -0.75015211 0.40334007, + 0.47960129 -0.77285445 0.41554624, + 0.46395782 -0.76442671 0.44765484, + 0.42016476 -0.78305751 0.45856574, + 0.40370286 -0.7719627 0.49101683, + 0.36132491 -0.78677082 0.50043589, + 0.34451291 -0.77294481 0.53279185, + 0.30476588 -0.78417969 0.54053682, + 0.28807783 -0.76770651 0.57239664, + 0.25147012 -0.77593035 0.57852829, + 0.23532487 -0.75695765 0.60962069, + 0.20214307 -0.76275128 0.61428726, + 0.18694098 -0.74150795 0.64437497, + 0.15739401 -0.74540699 0.647762, + 0.14351501 -0.72222799 0.67660201, + 0.11798395 -0.72468579 0.67890376, + 0.10574802 -0.7000342 0.70623618, + 0.08424487 -0.70147878 0.70769376, + 0.074037112 -0.67626315 0.73293018, + 0.056279201 -0.67704999 0.73378199, + 0.048116889 -0.65161783 0.75701982, + 0.033902112 -0.65199822 0.75746232, + 0.02835081 -0.62914324 0.77677232, + 0.009518669 -0.61422193 0.78907585, + 0.0124273 -0.61420202 0.789051, + 0.0038360804 -0.56285304 0.8265481, + -0.0013243903 -0.56285709 0.82655317, + -0.0060005127 -0.51469326 0.85735339, + -0.00329304 -0.5147 0.857364, + -0.0026249001 -0.53558701 0.84447598, + 0.0025850001 -0.53558707 0.8444761, + 0.0032540387 -0.5147208 0.85735172, + 0.0059220926 -0.51471424 0.85734141, + 0.0012412796 -0.56285191 0.8265568, + -0.0038576515 -0.56284815 0.82655132, + -0.010414497 -0.60219288 0.7982828, + -0.018504899 -0.60212296 0.79818887, + -0.025000297 -0.62914497 0.77688587, + -0.036955692 -0.62891179 0.7765978, + -0.04538849 -0.65540582 0.75391179, + -0.061146937 -0.65485442 0.75327748, + -0.071352594 -0.68027693 0.72947395, + -0.090681709 -0.67920506 0.72832507, + -0.10275405 -0.70375937 0.70296836, + -0.12583706 -0.70188034 0.70109135, + -0.14011493 -0.72600162 0.67326772, + -0.16739802 -0.72288805 0.67038107, + -0.18345609 -0.74561334 0.64062828, + -0.21463896 -0.74080896 0.63649994, + -0.23186094 -0.7613278 0.60549188, + -0.26676697 -0.75429291 0.59989792, + -0.28470808 -0.77227527 0.56791919, + -0.32311496 -0.76240289 0.56065893, + -0.34132212 -0.77763432 0.52800018, + -0.3828271 -0.76429218 0.51894212, + -0.40077484 -0.77663273 0.48602581, + -0.44413295 -0.75949585 0.47530195, + -0.46131593 -0.76897585 0.44256493, + -0.50576472 -0.74768561 0.43031174, + -0.52170485 -0.75445682 0.39826992, + -0.56660306 -0.72869104 0.38466907, + -0.58095008 -0.73303205 0.35378104, + -0.62536907 -0.70276308 0.33917204, + -0.63783199 -0.705033 0.30999801, + -0.68044281 -0.67081982 0.29495493, + -0.69080895 -0.67147094 0.26815996, + -0.73088825 -0.63382226 0.25312409, + -0.73923576 -0.63333875 0.22893792, + -0.77659571 -0.59247875 0.21416792, + -0.78312802 -0.59127897 0.19261301, + -0.81746203 -0.54765701 0.17840301, + -0.82241571 -0.54608279 0.15945494, + -0.85169441 -0.50303227 0.14688507, + -0.8481679 -0.50459892 0.16121799, + -0.8165459 -0.54989594 0.17569098, + -0.81084234 -0.55163324 0.19553909, + -0.7755028 -0.59506488 0.21093395, + -0.76800716 -0.59634215 0.23354006, + -0.72962719 -0.63675719 0.24936806, + -0.72007263 -0.63718271 0.27476087, + -0.67902243 -0.67411441 0.29068619, + -0.66723984 -0.67321283 0.3187089, + -0.62379962 -0.7064206 0.33443078, + -0.60990793 -0.70369893 0.36444497, + -0.56487972 -0.73273665 0.37948382, + -0.54904389 -0.72773081 0.41104591, + -0.50390285 -0.75208181 0.42479992, + -0.48642913 -0.74442416 0.45740512, + -0.44212994 -0.76421785 0.46956593, + -0.42344207 -0.75365412 0.50269508, + -0.38068107 -0.76928014 0.51311809, + -0.36131296 -0.75569791 0.54623592, + -0.32080808 -0.76761121 0.55484712, + -0.30130288 -0.75101769 0.58752775, + -0.26431501 -0.75960898 0.59424901, + -0.24519597 -0.74016494 0.62612695, + -0.21206805 -0.74610519 0.63115317, + -0.19385909 -0.72412133 0.66186631, + -0.16474195 -0.72803885 0.66544682, + -0.14817694 -0.70432276 0.69424278, + -0.12314197 -0.7067638 0.69664985, + -0.10896798 -0.68258792 0.72263396, + -0.087827995 -0.68402296 0.72415394, + -0.075536557 -0.65880656 0.7485106, + -0.058137868 -0.65957659 0.7493856, + -0.047541209 -0.63294709 0.77273411, + -0.0339498 -0.63329798 0.77316302, + -0.025290284 -0.60583466 0.79518855, + -0.015683003 -0.60595405 0.79534513, + -0.00621869 -0.56597197 0.82440102, + 0.0015371003 -0.5659821 0.82441616, + 0.0095742112 -0.51689208 0.85599715, + 0.0097291293 -0.51689094 0.85599589, + 0.0078350529 -0.5363422 0.84396428, + 0.0040298519 -0.53635424 0.84398341, + 0.0026822002 -0.57672906 0.81693113, + -0.0027894094 -0.57672888 0.81693083, + -0.0041285409 -0.53638512 0.84396321, + -0.0079221493 -0.53637296 0.84394389, + -0.0098189702 -0.51687598 0.856004, + -0.0096824691 -0.51687694 0.85600489, + -0.0016403904 -0.56603414 0.82438016, + 0.0061292299 -0.56602401 0.82436597, + 0.015594502 -0.60603905 0.79528213, + 0.025226988 -0.60591972 0.79512566, + 0.033897601 -0.63342899 0.773058, + 0.047518592 -0.63307697 0.7726289, + 0.058116186 -0.6597088 0.7492708, + 0.075575083 -0.65893584 0.74839282, + 0.087816581 -0.68404984 0.7241298, + 0.10893502 -0.68261617 0.7226122, + 0.12353306 -0.70750934 0.69582337, + 0.14877492 -0.70503563 0.69339067, + 0.16555294 -0.72902775 0.66416174, + 0.194894 -0.72505301 0.660541, + 0.2130301 -0.74691135 0.62987429, + 0.24631497 -0.74090594 0.62480992, + 0.26531094 -0.76019084 0.5930599, + 0.30243295 -0.75152379 0.58629888, + 0.32180709 -0.76797718 0.55376112, + 0.36235502 -0.75600111 0.54512507, + 0.38157484 -0.76945573 0.51218981, + 0.42438 -0.75376099 0.50174302, + 0.44288012 -0.76420218 0.46888411, + 0.48718894 -0.74435592 0.45670694, + 0.50449514 -0.75193018 0.4243651, + 0.54958504 -0.72756606 0.41061407, + 0.56529164 -0.73252559 0.37927777, + 0.61028373 -0.70347977 0.36423889, + 0.62404126 -0.70617723 0.33449411, + 0.66742259 -0.67299861 0.31877881, + 0.67909992 -0.67389995 0.29100198, + 0.72013444 -0.63698334 0.27506119, + 0.7296322 -0.63657117 0.24982806, + 0.76798266 -0.59619969 0.23398389, + 0.77546185 -0.59493697 0.21144497, + 0.81079912 -0.55152708 0.19601703, + 0.81651086 -0.54979694 0.17616299, + 0.84812069 -0.50453681 0.16165994, + 0.85236013 -0.50263804 0.14435102, + 0.88025409 -0.45606807 0.13097602, + 0.88329786 -0.45421293 0.11608399, + 0.90771312 -0.40652505 0.10389601, + 0.90850478 -0.40407291 0.10650898, + 0.92815924 -0.35989109 0.094862819, + 0.93117887 -0.35686296 0.074530691, + 0.94953448 -0.30703816 0.06412483, + 0.95117837 -0.30490613 0.047876619, + 0.96579391 -0.25617197 0.040224396, + 0.96657866 -0.25485691 0.027814891, + 0.97805977 -0.20709495 0.022602195, + 0.97837436 -0.20640807 0.013393804, + 0.98718077 -0.15927096 0.010335097, + 0.98725176 -0.15907696 0.0053362688, + 0.99279678 -0.11980497 0.0011591098, + 0.99275434 -0.12015604 0.0011674204, + 0.99277222 -0.12000803 0.0011742802, + 0.99277264 -0.12000795 0.00079577271, + 0.99275476 -0.12015597 0.00079577282, + 0.99279714 -0.11980502 0.00080359512, + 0.98568839 -0.16856989 -0.0015709291, + 0.98568761 -0.16856994 0.0020389294, + 0.98570967 -0.16844094 0.0020358292, + 0.98569965 -0.16843894 -0.004949098, + 0.98379266 -0.17927894 -0.0033397188, + 0.9970125 -0.07716734 -0.0033618517, + 0.99746197 -0.071084902 -0.004069, + 0.99747014 -0.071085505 0.00048139307, + 0.99358237 -0.11305103 0.0036763314, + 0.9935469 -0.11319198 0.0072263093, + 0.98712355 -0.15963493 0.010191196, + 0.98693866 -0.16017695 0.017187294, + 0.97789955 -0.2078819 0.02230599, + 0.97738576 -0.20899096 0.032248393, + 0.96545148 -0.25753513 0.03973892, + 0.96429515 -0.25942904 0.053211506, + 0.94889188 -0.30916497 0.063412793, + 0.94665277 -0.31198493 0.080709077, + 0.92706221 -0.36295909 0.093896024, + 0.92306888 -0.36681798 0.11570799, + 0.89845729 -0.41872314 0.13208105, + 0.89330727 -0.42254514 0.15315907, + 0.8652916 -0.47126576 0.17081892, + 0.85990328 -0.47419617 0.18895608, + 0.82781488 -0.52114993 0.20766596, + 0.82040012 -0.52399606 0.22884902, + 0.78406888 -0.56879395 0.24841397, + 0.77426612 -0.57114506 0.27259004, + 0.73397326 -0.61294621 0.29254112, + 0.72150695 -0.61427993 0.31951198, + 0.67831415 -0.65186417 0.33906209, + 0.66301006 -0.65159607 0.36856502, + 0.61775315 -0.68446416 0.3871561, + 0.59958124 -0.68197227 0.41882715, + 0.55306864 -0.70994061 0.43600374, + 0.53224123 -0.70462233 0.46928325, + 0.48566294 -0.72755492 0.48455694, + 0.46263281 -0.71891767 0.51877576, + 0.417781 -0.73675603 0.53164798, + 0.39308518 -0.72447336 0.5662353, + 0.35108596 -0.73774195 0.57660693, + 0.32550204 -0.72174305 0.61084807, + 0.28698099 -0.73120397 0.61885601, + 0.26129103 -0.71160406 0.65218604, + 0.22690913 -0.71798539 0.65803444, + 0.20361388 -0.69671559 0.68784356, + 0.1736989 -0.7008056 0.6918816, + 0.15361807 -0.67915827 0.71773636, + 0.12754105 -0.68170321 0.72042626, + 0.108031 -0.65697402 0.74613303, + 0.086073026 -0.65838915 0.74774015, + 0.06782762 -0.63108921 0.77273929, + 0.050318278 -0.63174468 0.77354163, + 0.033905305 -0.60250306 0.79739612, + 0.021045802 -0.60271609 0.79767811, + 0.0067763757 -0.57207465 0.8201735, + -0.0013950799 -0.57208693 0.82019186, + -0.016256401 -0.53274107 0.84612215, + -0.0254985 -0.53263801 0.84595901, + -0.022010399 -0.54410893 0.83872586, + -0.027305704 -0.54403806 0.83861613, + -0.0284271 -0.54106998 0.84049702, + -0.015704703 -0.54122204 0.84073311, + 0.0024734887 -0.58100462 0.81389654, + 0.012776195 -0.58095884 0.8138327, + 0.029855404 -0.61182809 0.79042715, + 0.045093488 -0.61147887 0.78997481, + 0.064185582 -0.64044183 0.76531982, + 0.084190406 -0.63948607 0.76417911, + 0.104865 -0.66604 0.73850799, + 0.12933901 -0.66410804 0.73636407, + 0.15093809 -0.68768442 0.71014643, + 0.17978096 -0.68431979 0.70667183, + 0.20142899 -0.70438403 0.68063903, + 0.23418203 -0.69912708 0.67555904, + 0.2594001 -0.71878827 0.64502323, + 0.29621905 -0.71086216 0.63791019, + 0.32379097 -0.72859496 0.60357994, + 0.36466187 -0.71705276 0.59401774, + 0.39151418 -0.73087734 0.55904824, + 0.435826 -0.71487999 0.54681098, + 0.461164 -0.72481501 0.51183099, + 0.50779217 -0.70371121 0.49692819, + 0.53084886 -0.7099908 0.46272287, + 0.57798308 -0.68367004 0.44556805, + 0.59825695 -0.68679494 0.41279694, + 0.64453971 -0.65531069 0.39387381, + 0.66175461 -0.65590757 0.36313379, + 0.70626098 -0.61936498 0.34290299, + 0.72033918 -0.61810613 0.31473207, + 0.76210499 -0.57696402 0.29378301, + 0.77321488 -0.57449996 0.26849297, + 0.81101811 -0.52999705 0.24769503, + 0.81948602 -0.52690601 0.225417, + 0.85294646 -0.4799237 0.20531788, + 0.8591429 -0.47667494 0.18615699, + 0.88835174 -0.4277049 0.16703196, + 0.89270073 -0.42462686 0.15092194, + 0.91769826 -0.37433708 0.13304803, + 0.91953766 -0.36703488 0.14048396, + 0.88771278 -0.42997792 0.16457495, + 0.88269114 -0.43342206 0.18166402, + 0.85216427 -0.48259819 0.20227507, + 0.84506416 -0.48617312 0.22249106, + 0.81009483 -0.53312391 0.24397793, + 0.80044883 -0.5364539 0.26739293, + 0.76106632 -0.58055216 0.28937408, + 0.74846405 -0.58310807 0.31589004, + 0.70512778 -0.62347078 0.33775589, + 0.68920779 -0.6246019 0.36723992, + 0.64334416 -0.65995717 0.3880271, + 0.62400723 -0.65893525 0.42002314, + 0.57674873 -0.68887365 0.43910578, + 0.55412692 -0.68497992 0.47301793, + 0.50651717 -0.70949924 0.48995018, + 0.48094013 -0.70207018 0.52516115, + 0.43449506 -0.72122508 0.53948903, + 0.40675405 -0.70984107 0.57504505, + 0.36323011 -0.72395325 0.58647722, + 0.33403897 -0.70838296 0.62178093, + 0.29464903 -0.71818805 0.63038707, + 0.2678099 -0.70046675 0.66153175, + 0.23234008 -0.70712823 0.66782326, + 0.20935197 -0.68889993 0.69396591, + 0.17747501 -0.69332802 0.69842601, + 0.15396605 -0.67124122 0.72507226, + 0.12652694 -0.67388171 0.72792464, + 0.10353001 -0.64841908 0.75421113, + 0.080844402 -0.64978802 0.755804, + 0.059024628 -0.62134427 0.78131133, + 0.041269213 -0.62189913 0.78200918, + 0.021262895 -0.59107286 0.80633783, + 0.0085482579 -0.59118485 0.80649084, + -0.013142298 -0.55118597 0.83427888, + -0.029404411 -0.55099517 0.83399028, + -0.028669603 -0.55260503 0.83295012, + -0.031993203 -0.55254906 0.83286613, + -0.02734529 -0.56462181 0.82489669, + -0.028584987 -0.56460267 0.82486761, + -0.022097811 -0.58504832 0.81069738, + -0.0273562 -0.58497202 0.810592, + -0.032057688 -0.57304782 0.81889468, + -0.028829111 -0.5731042 0.81897527, + -0.033593096 -0.56287092 0.82586187, + -0.028481808 -0.56296015 0.82599318, + -0.028628893 -0.56268889 0.82617283, + -0.008002284 -0.56290132 0.8264854, + 0.017260801 -0.60266703 0.79780614, + 0.032634493 -0.60243589 0.79749984, + 0.055565726 -0.63283628 0.77228934, + 0.076191597 -0.63197303 0.771236, + 0.10063598 -0.65948182 0.74495381, + 0.12641001 -0.65752906 0.74274904, + 0.15161407 -0.68158329 0.71586138, + 0.18233901 -0.67799509 0.71209204, + 0.20749207 -0.69824123 0.68513227, + 0.24235909 -0.69249523 0.67949426, + 0.26634803 -0.70864707 0.65335906, + 0.30469102 -0.70024705 0.64561409, + 0.33279508 -0.71573019 0.61398512, + 0.375121 -0.70356899 0.60355198, + 0.40559608 -0.7166692 0.5673421, + 0.45163289 -0.69953883 0.55378085, + 0.47982913 -0.70827121 0.51779914, + 0.52772683 -0.68570977 0.50130481, + 0.55302793 -0.69055092 0.46615395, + 0.60117394 -0.66233397 0.44710594, + 0.62291193 -0.66390091 0.41378295, + 0.67012703 -0.62991607 0.39260107, + 0.68813819 -0.62898916 0.36171609, + 0.73310721 -0.58957523 0.33905011, + 0.74745375 -0.58695173 0.31112787, + 0.78853387 -0.54337293 0.28802797, + 0.79952866 -0.53980476 0.26337188, + 0.83613873 -0.49297181 0.24052191, + 0.84426612 -0.48905507 0.21918003, + 0.87626499 -0.43969101 0.19705699, + 0.88203079 -0.43586892 0.17899695, + 0.90941525 -0.3847121 0.15798904, + 0.91115457 -0.37730682 0.16564092, + 0.87559313 -0.44230404 0.19417503, + 0.86898082 -0.44652689 0.21327496, + 0.83533788 -0.49605793 0.23693296, + 0.82603216 -0.50033009 0.25950107, + 0.78763467 -0.54695177 0.28368184, + 0.77504885 -0.55076194 0.30977497, + 0.7321496 -0.59368163 0.33391479, + 0.71581101 -0.59632403 0.36333501, + 0.66914904 -0.63461107 0.38666305, + 0.64872009 -0.63524008 0.41908506, + 0.60021871 -0.66763473 0.44045579, + 0.57574493 -0.66536993 0.47518495, + 0.52680016 -0.69170326 0.49399218, + 0.49864012 -0.68574017 0.53020614, + 0.45072812 -0.7061922 0.54601914, + 0.41947094 -0.69586796 0.58293396, + 0.37418309 -0.71088219 0.59551114, + 0.34516317 -0.69787937 0.62755632, + 0.30361584 -0.70847666 0.63708568, + 0.27906704 -0.69463706 0.66302407, + 0.24097399 -0.70205897 0.67010802, + 0.21451297 -0.68394393 0.69728392, + 0.18053502 -0.68873906 0.70217204, + 0.15339501 -0.66651309 0.72954106, + 0.12407006 -0.66928428 0.73257434, + 0.096930288 -0.64291793 0.75977689, + 0.073300995 -0.64422196 0.76131791, + 0.047507383 -0.61465174 0.78736669, + 0.029119203 -0.61508608 0.78792214, + 0.00019766192 -0.57585084 0.81755471, + -0.024546094 -0.57567686 0.81730884, + -0.025282504 -0.57451403 0.81810415, + -0.033141706 -0.57438213 0.81791615, + -0.028294396 -0.58316493 0.81186086, + -0.033673704 -0.58306807 0.81172514, + -0.028875014 -0.59313327 0.80458635, + -0.031978011 -0.59307724 0.8045103, + -0.027352696 -0.60453492 0.7961089, + -0.028549917 -0.60451436 0.7960825, + -0.017937509 -0.58832532 0.80842537, + -0.026083605 -0.58822012 0.80828017, + -0.017362203 -0.62265712 0.7823022, + -0.019491104 -0.6226331 0.78227121, + -0.012867101 -0.65794504 0.75295609, + -0.011831293 -0.65795356 0.75296551, + -0.0077075409 -0.69309705 0.72080308, + -0.0040487987 -0.69311178 0.72081876, + -0.0026377791 -0.72779876 0.68578577, + 0.0024482703 -0.72779906 0.68578607, + 0.0038736209 -0.69297916 0.72094721, + 0.0078487629 -0.69296324 0.72093022, + 0.011967792 -0.65801859 0.7529065, + 0.012614698 -0.65801293 0.7529009, + 0.019219108 -0.62288123 0.78208029, + 0.017119402 -0.62290508 0.7821101, + 0.025949609 -0.58808023 0.80838633, + 0.0178254 -0.58818501 0.80852997, + 0.032360006 -0.58173811 0.81273216, + -0.0046933494 -0.58203691 0.81314886, + -0.029164096 -0.61510092 0.78790885, + -0.047554292 -0.61466694 0.78735191, + -0.073269129 -0.64414024 0.76139027, + -0.096944913 -0.64283407 0.75984609, + -0.12394805 -0.66906726 0.73279321, + -0.153202 -0.66630697 0.72977, + -0.18033905 -0.68853623 0.70242125, + -0.21424605 -0.68375915 0.6975472, + -0.24068497 -0.70186692 0.67041296, + -0.27878803 -0.69445407 0.66333306, + -0.30363911 -0.70846725 0.63708526, + -0.34518519 -0.69786936 0.62755531, + -0.37264898 -0.71020293 0.59728092, + -0.41780078 -0.69532967 0.58477271, + -0.44853494 -0.70556092 0.54863495, + -0.49638078 -0.68530369 0.53288376, + -0.52500391 -0.69144982 0.49625388, + -0.57389218 -0.66531521 0.47749719, + -0.59877527 -0.66768521 0.44234014, + -0.64736497 -0.63539201 0.420946, + -0.66812623 -0.63480121 0.38811713, + -0.71482426 -0.59662724 0.36477712, + -0.73143005 -0.59397507 0.33496803, + -0.77444863 -0.55105078 0.31076086, + -0.78720886 -0.54720694 0.28437096, + -0.825665 -0.50059903 0.26014999, + -0.83511257 -0.49627176 0.23727888, + -0.88481271 -0.42518586 0.19058692, + -0.84414285 -0.48921895 0.21928898, + -0.83591473 -0.49318081 0.24087191, + -0.79925573 -0.5400238 0.26375091, + -0.78810591 -0.54363191 0.28870997, + -0.74695623 -0.58720225 0.31184912, + -0.73239237 -0.58984327 0.34012714, + -0.68738282 -0.62918383 0.36281192, + -0.66910332 -0.63009131 0.39406317, + -0.62179726 -0.66401225 0.41527814, + -0.59972614 -0.66237319 0.44898811, + -0.55158079 -0.69044763 0.46801779, + -0.52591908 -0.68547404 0.50352204, + -0.47805583 -0.70787477 0.51997679, + -0.44943011 -0.69892818 0.55633813, + -0.40352106 -0.71587104 0.56982404, + -0.37357602 -0.70292509 0.60525805, + -0.33140102 -0.71496707 0.61562604, + -0.30470803 -0.70023507 0.64561903, + -0.26633701 -0.70864201 0.65336901, + -0.24207506 -0.6923002 0.67979419, + -0.20728092 -0.69802576 0.68541574, + -0.18214996 -0.67778981 0.71233582, + -0.15149492 -0.68136573 0.71609366, + -0.12629406 -0.65731031 0.74296236, + -0.10053794 -0.6592586 0.74516457, + -0.076171972 -0.63183779 0.77134871, + -0.055574406 -0.63269907 0.77240109, + -0.032691307 -0.60237014 0.79754716, + -0.017335694 -0.60260177 0.79785371, + 0.0078786407 -0.56292105 0.82647312, + 0.028281193 -0.56271386 0.82616782, + 0.028419901 -0.56245703 0.82633799, + 0.033768401 -0.56236398 0.82620001, + 0.028849017 -0.57293135 0.81909549, + 0.031731002 -0.57288104 0.81902415, + 0.027040195 -0.58478189 0.81073982, + 0.022056108 -0.58485323 0.8108393, + 0.028531307 -0.56445414 0.8249712, + 0.027028603 -0.56447709 0.82500613, + 0.031689487 -0.55236679 0.83299869, + 0.028996792 -0.55241185 0.83306682, + 0.029574307 -0.55114812 0.83388317, + 0.012980097 -0.5513429 0.83417779, + -0.0086142085 -0.59114987 0.80651581, + -0.021319499 -0.59103799 0.80636197, + -0.041293189 -0.62180489 0.7820828, + -0.059018701 -0.62125099 0.78138602, + -0.080774359 -0.64960873 0.75596565, + -0.103423 -0.64824301 0.75437701, + -0.126398 -0.67368299 0.728131, + -0.15384701 -0.67104506 0.72527903, + -0.177311 -0.69309598 0.69869798, + -0.20914397 -0.68867993 0.69424695, + -0.2323779 -0.70710766 0.66783172, + -0.26779595 -0.70045584 0.66154879, + -0.29336011 -0.71735823 0.63193125, + -0.33263615 -0.70764333 0.62337327, + -0.36136103 -0.72303104 0.58876508, + -0.4046621 -0.70910418 0.57742512, + -0.43275678 -0.72070765 0.54157376, + -0.47915587 -0.7016958 0.5272879, + -0.50506788 -0.70928383 0.49175489, + -0.55267102 -0.684892 0.47484499, + -0.57562405 -0.68888909 0.44055507, + -0.62288386 -0.65906584 0.42148292, + -0.6425032 -0.66013515 0.38911608, + -0.68844521 -0.62481922 0.36829913, + -0.70457 -0.62369502 0.338505, + -0.74796695 -0.58335495 0.31661096, + -0.76074898 -0.58077401 0.289763, + -0.80017412 -0.53667909 0.26776302, + -0.80993181 -0.53331387 0.24410394, + -0.8449412 -0.48633611 0.22260205, + -0.85211587 -0.48272195 0.20218296, + -0.88266587 -0.43351194 0.18157199, + -0.88954878 -0.4286949 0.15787196, + -0.91646713 -0.37546006 0.13826701, + -0.92174125 -0.37056908 0.11433203, + -0.94289553 -0.31828386 0.098200053, + -0.94583774 -0.3146939 0.079741277, + -0.96226865 -0.26376492 0.066836275, + -0.96381652 -0.26129788 0.052736573, + -0.97639221 -0.21173604 0.04273361, + -0.97713578 -0.21016896 0.032167993, + -0.98653048 -0.16169508 0.02474861, + -0.98683637 -0.16081207 0.017135305, + -0.99342334 -0.11385503 0.012131805, + -0.99351954 -0.11344595 0.0069964766, + -0.99771386 -0.067548096 0.0020575698, + -0.99770153 -0.067633972 0.0041711582, + -0.99975288 -0.022231597 -0.00014090698, + -0.99975061 -0.022292893 0.0013540696, + -0.99769163 -0.067782976 0.0041171284, + -0.9976579 -0.068027593 0.0071346392, + -0.99337566 -0.11428496 0.011985996, + -0.99322438 -0.11491805 0.017300006, + -0.98639411 -0.16256602 0.024472803, + -0.9859581 -0.16380201 0.032490104, + -0.97608638 -0.21322908 0.042294014, + -0.97507387 -0.21531397 0.053579792, + -0.96167839 -0.2660661 0.066209324, + -0.9596085 -0.26926813 0.081525534, + -0.94185889 -0.32159197 0.097367287, + -0.93793887 -0.32618797 0.11777999, + -0.91475421 -0.37999809 0.13720903, + -0.90773726 -0.3861641 0.16398305, + -0.87785631 -0.44082513 0.18719406, + -0.86881417 -0.44670513 0.21358004, + -0.87075543 -0.4382892 0.22290711, + -0.8248772 -0.50388813 0.25627005, + -0.8140229 -0.50859195 0.28053698, + -0.77359211 -0.55487007 0.30606303, + -0.75891709 -0.55894303 0.33410704, + -0.71395224 -0.60100824 0.35925111, + -0.69495362 -0.60360569 0.39076781, + -0.64652568 -0.6404047 0.41459179, + -0.62295127 -0.64054531 0.44903621, + -0.57312369 -0.6710127 0.47039476, + -0.54512882 -0.66772276 0.5069328, + -0.49568906 -0.69173408 0.52516305, + -0.46468699 -0.68440801 0.56182897, + -0.41715607 -0.70246303 0.57665104, + -0.38940385 -0.69274473 0.60701674, + -0.34448579 -0.70607561 0.61869764, + -0.3193419 -0.69448781 0.64475381, + -0.27789 -0.703996 0.65358001, + -0.25059408 -0.68830425 0.68076426, + -0.21303004 -0.6946702 0.68706018, + -0.18423501 -0.67456001 0.71486098, + -0.15154198 -0.67838097 0.71891195, + -0.12247495 -0.65409678 0.74642974, + -0.09467712 -0.65609819 0.7487132, + -0.066121012 -0.62780619 0.77555621, + -0.044632688 -0.62855583 0.77648282, + -0.016560499 -0.59570593 0.80303186, + -0.0011805505 -0.59578729 0.80314136, + 0.017796895 -0.56970185 0.82165873, + 0.028366003 -0.56956303 0.8214581, + 0.025391506 -0.5742771 0.81826717, + 0.033190019 -0.57414538 0.81808048, + 0.028345104 -0.58292407 0.8120321, + 0.033661805 -0.58282804 0.81189811, + 0.028708296 -0.59321392 0.80453289, + 0.031819399 -0.59315801 0.80445701, + 0.027167706 -0.60467315 0.7960102, + 0.028616913 -0.60464829 0.79597837, + 0.021948002 -0.62464404 0.78060114, + 0.027218901 -0.62456298 0.78049999, + 0.032012906 -0.6129961 0.78943717, + 0.028718913 -0.61305732 0.78951633, + 0.033598095 -0.60307992 0.79697287, + 0.027999992 -0.60318375 0.79711068, + 0.033035699 -0.59428197 0.80357802, + 0.025258396 -0.59441596 0.80376089, + 0.029798303 -0.58738607 0.80875814, + 0.019637901 -0.58753407 0.80896109, + 0.021643702 -0.58479106 0.81089514, + 0.0079313405 -0.58490908 0.81106013, + -0.013754798 -0.61075795 0.79169786, + -0.03288018 -0.61048561 0.79134452, + -0.064073183 -0.64213181 0.76391184, + -0.089336909 -0.64088106 0.76242411, + -0.12100397 -0.66792381 0.73432684, + -0.15212807 -0.66503632 0.73115236, + -0.183258 -0.68724102 0.70293403, + -0.219891 -0.68197 0.69754201, + -0.24995092 -0.69961274 0.66937774, + -0.29146108 -0.69117624 0.66130626, + -0.31890199 -0.70409203 0.63447303, + -0.364234 -0.69184899 0.62344098, + -0.38904691 -0.7008208 0.59790689, + -0.43687099 -0.68431699 0.58382702, + -0.46427688 -0.69128782 0.5536859, + -0.51401097 -0.66950697 0.53623992, + -0.54459894 -0.67380697 0.49939594, + -0.59545785 -0.64543885 0.47837088, + -0.62229091 -0.64592183 0.44219789, + -0.67245603 -0.61072999 0.41810501, + -0.69420135 -0.60828727 0.38480017, + -0.74121904 -0.56728506 0.35886204, + -0.75812888 -0.56301492 0.32902098, + -0.80070591 -0.51721495 0.30225596, + -0.81326288 -0.51209992 0.27632797, + -0.85080487 -0.46245193 0.24953797, + -0.86273986 -0.45533994 0.21987598, + -0.89638722 -0.3991701 0.19275205, + -0.90560222 -0.39157709 0.16294804, + -0.93141323 -0.3360301 0.13983303, + -0.93664265 -0.33018988 0.11694095, + -0.95610338 -0.27621809 0.097826339, + -0.95886433 -0.2721011 0.080871232, + -0.9733265 -0.2199169 0.065361373, + -0.97468048 -0.21720611 0.053100027, + -0.98518175 -0.16660696 0.040730089, + -0.98577553 -0.16495992 0.032169685, + -0.99294037 -0.11642204 0.022704108, + -0.9931559 -0.11553598 0.017114798, + -0.99758822 -0.068660617 0.010171003, + -0.99764115 -0.068282411 0.0070522209, + -0.99974591 -0.022421299 0.0023156798, + -0.99974954 -0.022341289 0.0013370494, + -0.99975061 0.022291793 -0.0013340896, + -0.99975109 0.022284202 -0.0011501901, + -0.99971747 0.023764411 -0.00058134727, + -0.99973321 0.023092305 -0.00056955009, + -0.99967939 -0.025311384 0.00062428066, + -0.99967927 -0.025311405 0.0009001682, + -0.99967825 -0.025348905 0.0009001682, + -0.99967849 -0.025348911 -0.00062733027, + -0.99967486 -0.025490396 -0.00062480994, + -0.99967462 -0.02549039 0.0008920707, + -0.99723238 -0.074301228 -0.002641781, + -0.99723577 -0.074301489 -0.00034498092, + -0.99723625 -0.074295014 -0.00034509809, + -0.99723011 -0.074294508 -0.0035303705, + -0.99701309 -0.07716731 -0.0031963105, + -0.99966449 0.025738712 -0.0029279315, + -0.99971187 0.023764296 -0.0033854996, + -0.99971378 0.023680694 -0.0033936293, + -0.9997189 0.023680797 -0.0011743698, + -0.9973501 0.072750106 -0.00052839809, + -0.99734986 0.072750092 0.00087720086, + -0.99735725 0.072648816 0.00087720121, + -0.99735421 0.072648615 -0.0025891208, + -0.99734014 0.072842509 -0.0025924302, + -0.99734312 0.07284271 0.00086972211, + -0.99258077 0.12156897 -0.0020793595, + -0.99257588 0.12156899 -0.0037685996, + -0.9925831 0.12151001 -0.0037676105, + -0.99258125 0.12151003 -0.0042145108, + -0.99171674 0.12840196 -0.0032956293, + -0.85730779 0.51478887 -0.0039736889, + -0.8706128 0.49196887 -4.1197491e-005, + -0.8705762 0.49194911 -0.0091200015, + -0.8506887 0.52563083 -0.0064028776, + -0.84539115 0.5340631 -0.009513692, + -0.8454293 0.53408718 -0.00034629513, + -0.84549081 0.53398991 -0.00035087491, + -0.84545261 0.53396577 -0.0095121954, + -0.81808686 0.57505393 -0.006852319, + -0.81810617 0.5750671 0.00028712105, + -0.81820971 0.57491982 0.00028712087, + -0.81817091 0.57489294 -0.0097194491, + -0.81821382 0.5748319 -0.0097185085, + -0.81825256 0.57485873 0.00029569786, + -0.79983467 0.60020769 -0.0039106482, + -0.62061214 -0.78411019 -0.0034188309, + -0.61491162 -0.78858453 -0.0042678178, + -0.61490566 -0.78857654 0.0061698961, + -0.65284902 -0.75739402 0.0119339, + -0.65289503 -0.75744814 0.00076249411, + -0.65291226 -0.7574333 0.00076249329, + -0.65299493 -0.75736189 0.00075838389, + -0.68925422 -0.72451824 -0.0014307605, + -0.68923515 -0.72449815 0.007577552, + -0.72394723 -0.68982226 0.0067514423, + -0.72396374 -0.68983775 0.00058712077, + -0.69793767 -0.71614861 -0.0037448981, + -0.76786673 -0.64059776 -0.0038917686, + -0.78819531 -0.61542523 0.00036907016, + -0.78819084 -0.61542189 0.0033296593, + -0.78804535 -0.61560827 0.0033314317, + -0.78804964 -0.61561167 0.00034196384, + -0.78806669 -0.61558974 0.00034196489, + -0.7880162 -0.6155501 0.011340603, + -0.7921102 -0.61030811 0.0092485016, + -0.79182291 -0.61035097 0.022096798, + -0.75915533 -0.65048331 0.023549711, + -0.75834328 -0.65052825 0.041575413, + -0.72318316 -0.68925017 0.044050112, + -0.72181219 -0.68915421 0.063669316, + -0.68414718 -0.72625118 0.067096613, + -0.68212879 -0.72586876 0.088401273, + -0.64260119 -0.7605812 0.092628926, + -0.63986808 -0.75973612 0.11562801, + -0.59867579 -0.79187268 0.12051895, + -0.59518379 -0.79036272 0.14519995, + -0.5522849 -0.81993383 0.15063196, + -0.5480147 -0.81752753 0.1769989, + -0.50356495 -0.84439391 0.18281499, + -0.49855593 -0.84084886 0.21074897, + -0.45361412 -0.86445916 0.21666704, + -0.44801578 -0.85960561 0.24568288, + -0.402933 -0.87999302 0.25150999, + -0.3968901 -0.87366116 0.28141505, + -0.351946 -0.89094102 0.28698099, + -0.345651 -0.88300699 0.31752801, + -0.30117705 -0.89731526 0.32267308, + -0.29486006 -0.88771427 0.3535831, + -0.25181592 -0.89908069 0.35810989, + -0.24571203 -0.88781309 0.38911906, + -0.20445704 -0.89654422 0.39294508, + -0.19877507 -0.8836143 0.42392716, + -0.15957506 -0.89005232 0.42701614, + -0.15454397 -0.87554777 0.45774689, + -0.11751196 -0.88005471 0.46010283, + -0.11335999 -0.86417389 0.49025795, + -0.07909546 -0.86705559 0.49189276, + -0.076020353 -0.85019046 0.52095771, + -0.044450913 -0.85181516 0.52195311, + -0.042562205 -0.83422112 0.54978508, + -0.013546303 -0.83490115 0.55023313, + -0.012911597 -0.8167848 0.5767979, + 0.013581402 -0.81677812 0.57679206, + 0.014217107 -0.83491445 0.55019623, + 0.043227624 -0.83421844 0.54973722, + 0.045114711 -0.85180116 0.52191913, + 0.076704204 -0.85015714 0.52091205, + 0.079774708 -0.8670001 0.49188107, + 0.11397702 -0.86410409 0.49023807, + 0.11811805 -0.87994629 0.46015519, + 0.15514807 -0.87541944 0.4577882, + 0.16015296 -0.88985878 0.42720291, + 0.19931696 -0.88340688 0.42410493, + 0.20497796 -0.89630377 0.39322191, + 0.24616504 -0.88756913 0.38938907, + 0.25226611 -0.89884442 0.35838619, + 0.29521894 -0.88748574 0.35385692, + 0.30153093 -0.89709377 0.3229579, + 0.34595597 -0.88278687 0.31780797, + 0.35227317 -0.89076239 0.28713414, + 0.39719009 -0.87347716 0.28156307, + 0.40326583 -0.87985057 0.25147489, + 0.44829807 -0.8594681 0.24564902, + 0.45395306 -0.86437315 0.21630003, + 0.49891993 -0.84072489 0.21038197, + 0.50398707 -0.84430712 0.18205102, + 0.54842484 -0.81741369 0.17625295, + 0.55271107 -0.81981909 0.14969002, + 0.59561431 -0.79020637 0.14428307, + 0.59908313 -0.79169518 0.11965903, + 0.64027303 -0.75952113 0.11479601, + 0.64295018 -0.76034015 0.092184521, + 0.68244517 -0.72562319 0.08797542, + 0.68439776 -0.72599179 0.067348175, + 0.72200644 -0.68892843 0.06390994, + 0.72331619 -0.6890282 0.045320012, + 0.75844401 -0.65033299 0.042774901, + 0.75921953 -0.65031159 0.026084386, + 0.7918399 -0.61023796 0.024476996, + 0.7921468 -0.61021489 0.011889197, + 0.78997272 -0.61300379 0.013018295, + 0.79003954 -0.61305565 0.00051308068, + 0.81910872 -0.57363784 -0.00071152375, + 0.81906313 -0.57370305 -0.00070836005, + 0.81904489 -0.57368994 0.0067224391, + 0.81909031 -0.57362521 0.0067214225, + 0.846187 -0.53273201 0.0128153, + 0.84630871 -0.53253883 0.012809996, + 0.82482219 -0.56513911 0.016918603, + -0.79056585 -0.6112169 0.037676293, + -0.78944314 -0.61139208 0.054583307, + -0.75626719 -0.65167117 0.058179215, + -0.75455689 -0.65172893 0.07676769, + -0.71876574 -0.69047874 0.081331968, + -0.71635377 -0.69027674 0.10176096, + -0.67804515 -0.72716117 0.10719802, + -0.67484325 -0.72651625 0.12946305, + -0.63464421 -0.76081932 0.13557604, + -0.63057697 -0.75951588 0.15971299, + -0.58878011 -0.79099417 0.16633205, + -0.58382565 -0.78879255 0.19223388, + -0.54040498 -0.81747901 0.19922499, + -0.53461677 -0.81414157 0.22662389, + -0.48994184 -0.83982569 0.2337729, + -0.48340613 -0.83511215 0.26250005, + -0.4385289 -0.85735983 0.26949295, + -0.43140593 -0.85108286 0.29924396, + -0.38678899 -0.86996001 0.30588201, + -0.37927216 -0.86196929 0.33639511, + -0.33518893 -0.87768078 0.34252691, + -0.32748908 -0.86784518 0.3736251, + -0.28433895 -0.88058376 0.37910891, + -0.27675512 -0.8689124 0.4103632, + -0.23545709 -0.87880832 0.41503716, + -0.22820093 -0.86525369 0.44638586, + -0.189209 -0.87265003 0.45020199, + -0.18257402 -0.85737514 0.48122206, + -0.14596197 -0.86269283 0.48420689, + -0.14026104 -0.8460713 0.51428616, + -0.10623304 -0.84968328 0.51648116, + -0.10166202 -0.83201009 0.54536605, + -0.070631079 -0.83425468 0.54683679, + -0.067285903 -0.81571102 0.57453299, + -0.039154004 -0.81693715 0.57539606, + -0.037112694 -0.79772985 0.60187191, + -0.011804001 -0.79822409 0.60224503, + -0.011120103 -0.77852732 0.62751222, + 0.011677005 -0.77852237 0.62750828, + 0.012363403 -0.79827815 0.60216212, + 0.037730299 -0.79777098 0.60177898, + 0.039774187 -0.81698972 0.57527882, + 0.067926899 -0.81574798 0.57440501, + 0.071269892 -0.83427089 0.54672897, + 0.10231598 -0.83200788 0.54524696, + 0.10688002 -0.84965515 0.51639414, + 0.14094599 -0.84601891 0.51418495, + 0.14661698 -0.86256087 0.48424393, + 0.18322794 -0.85722172 0.48124683, + 0.18983604 -0.87244618 0.45033312, + 0.22876211 -0.86504143 0.4465102, + 0.23598894 -0.87855375 0.4152739, + 0.2771779 -0.8686657 0.41059986, + 0.28474995 -0.88033074 0.37938792, + 0.3278501 -0.8675912 0.37389809, + 0.33552191 -0.87740475 0.34290791, + 0.3795549 -0.86169881 0.33676893, + 0.38708785 -0.86971873 0.30618989, + 0.431633 -0.85086 0.29955, + 0.43878099 -0.85716897 0.26969001, + 0.48365787 -0.83490783 0.26268595, + 0.49022812 -0.83965218 0.23379606, + 0.53490001 -0.81395102 0.22664, + 0.54076207 -0.81733412 0.19885004, + 0.58412713 -0.78865719 0.19187304, + 0.58915496 -0.79088587 0.16551699, + 0.63093883 -0.75938082 0.15892395, + 0.63502401 -0.76067901 0.134581, + 0.67521703 -0.72633904 0.12850502, + 0.67838722 -0.72696626 0.10635204, + 0.71668637 -0.69005036 0.10095204, + 0.71904594 -0.69023895 0.080889791, + 0.75478911 -0.65150905 0.076351009, + 0.75643814 -0.65145105 0.058420707, + 0.78958219 -0.61119211 0.054810315, + 0.79065055 -0.61103362 0.038855277, + 0.82141757 -0.56917769 0.03619368, + 0.8220126 -0.5690257 0.022473888, + 0.79165953 -0.61048663 0.024111385, + 0.79096532 -0.61058426 0.039506815, + 0.75810766 -0.6507687 0.042106882, + 0.75691372 -0.65081078 0.059387676, + 0.72150165 -0.68954766 0.06292247, + 0.71969396 -0.68940991 0.082187191, + 0.68173409 -0.72645605 0.086603709, + 0.67920017 -0.72597015 0.10795602, + 0.63937998 -0.76052803 0.113095, + 0.63603115 -0.75948715 0.13654204, + 0.59454495 -0.79137486 0.14227499, + 0.59032708 -0.78953713 0.16776502, + 0.54718906 -0.81873012 0.17396902, + 0.54209709 -0.81583315 0.20136304, + 0.49752706 -0.84217513 0.20786503, + 0.49171123 -0.83801943 0.23652412, + 0.44679806 -0.86099809 0.24301003, + 0.44041285 -0.85540873 0.27260292, + 0.39560592 -0.87505978 0.27886593, + 0.38882083 -0.86788857 0.30917284, + 0.34427798 -0.88442487 0.31506398, + 0.33730587 -0.87556571 0.34584588, + 0.29351106 -0.88910824 0.3511951, + 0.28657985 -0.87849659 0.38225082, + 0.24446706 -0.88913423 0.3868801, + 0.237818 -0.87677699 0.41797701, + 0.19768597 -0.88486087 0.42183095, + 0.19155991 -0.87082958 0.4527258, + 0.15362293 -0.87672859 0.45579278, + 0.14823505 -0.86110032 0.48634619, + 0.11267702 -0.86517513 0.48864707, + 0.10831901 -0.8484121 0.51813507, + 0.075646929 -0.85098827 0.51970816, + 0.072440282 -0.83330685 0.54804391, + 0.042522717 -0.83474642 0.54899025, + 0.04055969 -0.81637383 0.57609791, + 0.0133083 -0.81697398 0.57652098, + 0.012648308 -0.79806447 0.60243934, + -0.012008798 -0.79807091 0.60244393, + -0.012667902 -0.8169601 0.57655507, + -0.039870396 -0.81637585 0.57614297, + -0.041835997 -0.8347649 0.54901493, + -0.071738392 -0.83334386 0.54807997, + -0.074947588 -0.85103381 0.51973486, + -0.10763198 -0.84847581 0.51817387, + -0.112005 -0.86528897 0.48859999, + -0.14758198 -0.86123288 0.48630995, + -0.15298198 -0.87688786 0.45570195, + -0.19096592 -0.87100267 0.45264384, + -0.19712108 -0.88508743 0.42162022, + -0.23730797 -0.8770119 0.41777393, + -0.24398409 -0.8894043 0.38656414, + -0.28614897 -0.87877089 0.38194293, + -0.29309502 -0.8893891 0.35083103, + -0.33698398 -0.87583286 0.34548298, + -0.3439481 -0.88466722 0.31474409, + -0.38851994 -0.8681339 0.30886197, + -0.39528093 -0.87526691 0.27867696, + -0.4401668 -0.85559559 0.27241388, + -0.44651005 -0.86114013 0.24303603, + -0.4914543 -0.83816248 0.23655114, + -0.49719617 -0.84226429 0.20829508, + -0.54176682 -0.81594771 0.20178692, + -0.54680294 -0.81881887 0.17476298, + -0.58993322 -0.7896663 0.16854106, + -0.59413695 -0.7915079 0.14323598, + -0.63562071 -0.75966263 0.13747394, + -0.63899368 -0.76072264 0.11396595, + -0.67885321 -0.72617024 0.10878903, + -0.68144029 -0.72667533 0.087075941, + -0.71941996 -0.68964195 0.082638294, + -0.72129583 -0.68978679 0.062661082, + -0.756742 -0.65103298 0.0591406, + -0.75799268 -0.65098077 0.040879287, + -0.79089272 -0.61075175 0.038353086, + -0.79162037 -0.61062831 0.021686211, + -0.82199085 -0.56914186 0.020212794, + -0.82136601 -0.56932098 0.035093799, + -0.8242619 -0.56469095 0.041429695, + -0.84939879 -0.52633691 0.038615793, + -0.85040081 -0.52594787 0.014044296, + -0.8435244 -0.53684962 0.016094988, + -0.84363389 -0.53691894 2.4934696e-005, + -0.84458411 -0.53542304 2.4931303e-005, + -0.84454614 -0.53539908 0.0094767408, + -0.84457016 -0.53536111 0.009475912, + -0.84460813 -0.53538507 3.0058503e-005, + -0.82967281 -0.55823588 -0.003963999, + -0.88268256 -0.46996975 -4.0929881e-005, + -0.86978883 -0.49335489 -0.0082656182, + -0.86979568 -0.49334282 -0.0082618268, + -0.89294428 -0.45016715 -0.00037987615, + -0.89297813 -0.45010006 -0.00037107407, + -0.89295626 -0.45009011 0.0069436417, + -0.89292288 -0.45015594 0.0069450391, + -0.87608558 -0.48197675 0.013133493, + -0.8752566 -0.48240876 0.034751985, + -0.84878099 -0.52737802 0.037991501, + -0.84713686 -0.52808493 0.059037093, + -0.8179031 -0.57179403 0.063923508, + -0.81616086 -0.57224393 0.080115095, + -0.7843492 -0.61432815 0.086006925, + -0.78189212 -0.61465603 0.10412902, + -0.74754226 -0.65488327 0.11094404, + -0.74423575 -0.65493077 0.13106796, + -0.70717782 -0.6932888 0.13874497, + -0.70289916 -0.69284719 0.16092105, + -0.66324103 -0.72900099 0.169319, + -0.65791923 -0.72782326 0.19343108, + -0.6164819 -0.76095384 0.20223595, + -0.6101017 -0.75877464 0.2281159, + -0.56727785 -0.78865671 0.23709992, + -0.55983812 -0.78519017 0.26468405, + -0.51583594 -0.81180388 0.27365598, + -0.50744122 -0.80677533 0.30268314, + -0.46263 -0.83005601 0.31141701, + -0.45343801 -0.82321 0.34164199, + -0.40906495 -0.84280688 0.34977496, + -0.39928585 -0.8339417 0.38093585, + -0.35591379 -0.85003448 0.38828677, + -0.34581608 -0.83901918 0.4200691, + -0.30374604 -0.85194111 0.42653805, + -0.29367793 -0.83876979 0.45849589, + -0.25330499 -0.84884501 0.464003, + -0.2437411 -0.83379227 0.49535918, + -0.205999 -0.84128201 0.499809, + -0.197207 -0.824516 0.530361, + -0.16238299 -0.82986987 0.53380495, + -0.15462299 -0.8116619 0.56329095, + -0.12274396 -0.81532973 0.56583685, + -0.11620098 -0.79591286 0.59415495, + -0.087326504 -0.79828012 0.59592205, + -0.082132541 -0.77786738 0.62303829, + -0.05658618 -0.77925372 0.62414879, + -0.052818298 -0.758039 0.65006697, + -0.030468693 -0.75874585 0.65067381, + -0.0281852 -0.736911 0.67540199, + -0.0088891014 -0.73717517 0.67564321, + -0.0081297625 -0.71494025 0.69913822, + 0.0083658295 -0.71493894 0.69913691, + 0.0091295261 -0.73728079 0.67552477, + 0.028565196 -0.73701096 0.67527694, + 0.030856105 -0.7589041 0.65047103, + 0.053336874 -0.75818467 0.64985472, + 0.057107028 -0.77941233 0.62390327, + 0.082740352 -0.77800947 0.62278038, + 0.087933607 -0.79841113 0.59565705, + 0.11683901 -0.79602611 0.59387803, + 0.12338007 -0.81543046 0.56555337, + 0.15532891 -0.81173551 0.56299067, + 0.163057 -0.82986701 0.53360403, + 0.19790304 -0.8244881 0.53014505, + 0.20664811 -0.84116542 0.49973723, + 0.24440494 -0.83364981 0.49527189, + 0.25393289 -0.84864759 0.46402079, + 0.29421493 -0.8385728 0.45851189, + 0.30422902 -0.85168213 0.42671105, + 0.34622291 -0.8387658 0.42023993, + 0.3562772 -0.8497445 0.38858825, + 0.39962685 -0.8336457 0.38122585, + 0.40936416 -0.84248531 0.35019913, + 0.45365179 -0.82291657 0.34206486, + 0.46284482 -0.8297767 0.31184188, + 0.50760609 -0.8065151 0.30310002, + 0.51600289 -0.81155682 0.27407393, + 0.55998802 -0.78494698 0.26508799, + 0.56747121 -0.78844428 0.23734409, + 0.61024624 -0.75858629 0.22835608, + 0.61669427 -0.76079333 0.20219208, + 0.658095 -0.72767502 0.193391, + 0.66349095 -0.72886992 0.16890399, + 0.7031188 -0.69271582 0.16052596, + 0.70746422 -0.69315726 0.13794005, + 0.74451822 -0.65476322 0.13029905, + 0.74784076 -0.65470475 0.10998196, + 0.78215814 -0.61447006 0.10322402, + 0.78458631 -0.61413527 0.085219428, + 0.81636161 -0.57205969 0.079380766, + 0.81806058 -0.57161373 0.063517369, + 0.84726769 -0.52791685 0.058661778, + 0.848324 -0.52750498 0.0456613, + 0.8198275 -0.57047737 0.049381129, + 0.81852901 -0.57082403 0.064577103, + 0.7871471 -0.61285603 0.069332205, + 0.7852158 -0.61313486 0.086613275, + 0.75134701 -0.65341997 0.092303999, + 0.74864477 -0.65348774 0.11173496, + 0.71207207 -0.69206303 0.11833002, + 0.70844895 -0.69172597 0.14005499, + 0.66930932 -0.72820735 0.14744207, + 0.66466391 -0.72721893 0.17138998, + 0.62369531 -0.76082337 0.17931008, + 0.61804777 -0.75893569 0.20502092, + 0.57560688 -0.78942883 0.21325795, + 0.56899697 -0.78639287 0.24047597, + 0.52516991 -0.81379783 0.24885695, + 0.51767009 -0.8093552 0.27742007, + 0.47294283 -0.83348972 0.28569192, + 0.46468282 -0.82739472 0.31541687, + 0.42012891 -0.84793985 0.32324892, + 0.41131008 -0.84001219 0.3538411, + 0.3674691 -0.85709816 0.3610391, + 0.35832399 -0.84719998 0.39224499, + 0.31553686 -0.86109859 0.39867982, + 0.30632594 -0.8491438 0.43025491, + 0.26499006 -0.86013716 0.43582609, + 0.25604895 -0.84616882 0.46737289, + 0.21703798 -0.8544839 0.47196594, + 0.20875303 -0.83878911 0.50284708, + 0.172443 -0.84483701 0.50647199, + 0.16508301 -0.82767397 0.53637999, + 0.13151105 -0.83189929 0.53911817, + 0.12526602 -0.81348109 0.56794107, + 0.094503015 -0.81627011 0.56988806, + 0.089529604 -0.79684103 0.59751898, + 0.062014479 -0.79851371 0.59877378, + 0.058389325 -0.77821535 0.62527728, + 0.033966299 -0.77909499 0.62598503, + 0.031757094 -0.75810581 0.65135783, + 0.010259097 -0.75844884 0.6516518, + 0.0095202541 -0.73694956 0.67588061, + -0.0091521107 -0.73695207 0.67588305, + -0.0098870276 -0.75836784 0.65175182, + -0.031272795 -0.75803387 0.65146494, + -0.033473693 -0.7789678 0.6261698, + -0.057822015 -0.77810019 0.6254732, + -0.061443299 -0.798383 0.59900701, + -0.088906102 -0.796727 0.59776402, + -0.093886815 -0.81618613 0.57011008, + -0.12459201 -0.8134191 0.56817806, + -0.13085295 -0.83188671 0.53929782, + -0.16440302 -0.8276841 0.53657305, + -0.17179196 -0.84491581 0.50656188, + -0.20812304 -0.8388862 0.50294614, + -0.2164399 -0.8546356 0.47196576, + -0.25544095 -0.84634483 0.46738687, + -0.2644411 -0.86039728 0.43564615, + -0.30584207 -0.84940618 0.4300811, + -0.31509584 -0.86140859 0.39835882, + -0.35795182 -0.8475036 0.39192882, + -0.3671239 -0.8574158 0.36063591, + -0.41102493 -0.84031886 0.35344398, + -0.41985521 -0.84824139 0.32281315, + -0.46446595 -0.82767987 0.31498796, + -0.47270995 -0.83374989 0.28531796, + -0.51752704 -0.80957514 0.27704504, + -0.52499002 -0.81398499 0.248624, + -0.56881702 -0.78658998 0.24025699, + -0.57536697 -0.78959203 0.213301, + -0.61783707 -0.75909615 0.20506203, + -0.62341094 -0.76095891 0.17972298, + -0.66440701 -0.72736001 0.17178699, + -0.66898584 -0.72833985 0.14825296, + -0.7081508 -0.69187385 0.14082997, + -0.71175617 -0.69222015 0.11930803, + -0.74833393 -0.65368396 0.11266599, + -0.75106567 -0.65362573 0.093133755, + -0.78497618 -0.61333114 0.08739242, + -0.78695387 -0.61305392 0.06977459, + -0.81837428 -0.57099921 0.064988121, + -0.8196578 -0.57066286 0.050049189, + -0.78901398 -0.61202598 0.053676799, + -0.78747714 -0.61225206 0.070903905, + -0.75397921 -0.65253717 0.075569317, + -0.75177169 -0.65259778 0.094632864, + -0.71560895 -0.69127095 0.10024098, + -0.7126298 -0.69100285 0.12113597, + -0.67390484 -0.7277208 0.12757197, + -0.67004275 -0.72691977 0.15043394, + -0.62944883 -0.7609188 0.15746996, + -0.62464523 -0.75934732 0.18223606, + -0.58252192 -0.79037291 0.18968096, + -0.57678413 -0.78778416 0.21613905, + -0.53316706 -0.81586009 0.22384202, + -0.52656984 -0.81200969 0.2517229, + -0.48178595 -0.83699387 0.25946796, + -0.474433 -0.83163798 0.28860301, + -0.42964101 -0.853091 0.29604799, + -0.42169595 -0.84602886 0.32620198, + -0.37740806 -0.8640461 0.33314803, + -0.36907604 -0.85511911 0.36408004, + -0.32554689 -0.86995667 0.3703979, + -0.31710804 -0.85910112 0.40173107, + -0.2747981 -0.87097931 0.40728515, + -0.26649487 -0.85811257 0.43888879, + -0.22627997 -0.86721689 0.44354495, + -0.21844496 -0.85248083 0.47492987, + -0.18072991 -0.85919261 0.47866976, + -0.17371206 -0.84293127 0.50920618, + -0.13855003 -0.84768915 0.51208115, + -0.13257901 -0.8301791 0.54150307, + -0.10016704 -0.83336031 0.54357821, + -0.095383786 -0.81477386 0.57187897, + -0.066118091 -0.81671488 0.57324094, + -0.062635995 -0.79731387 0.60030591, + -0.036348276 -0.79835451 0.60108966, + -0.034229603 -0.77832413 0.62692904, + -0.010855 -0.7787351 0.62725908, + -0.010144199 -0.75815886 0.65199095, + 0.010619499 -0.75815487 0.65198797, + 0.011332899 -0.7787919 0.62717992, + 0.034818392 -0.77836984 0.62683982, + 0.036940191 -0.79841679 0.60097086, + 0.063301302 -0.79736 0.60017502, + 0.066779882 -0.81673485 0.57313585, + 0.096087985 -0.81477386 0.57176095, + 0.10086104 -0.83332229 0.54350817, + 0.13331103 -0.83011717 0.54141814, + 0.13927199 -0.8476029 0.51202792, + 0.17438391 -0.84282959 0.50914478, + 0.18138094 -0.85904372 0.47869083, + 0.21905193 -0.85231769 0.47494283, + 0.22685207 -0.86699528 0.44368616, + 0.26701608 -0.85788232 0.43902215, + 0.27526906 -0.87068319 0.40760008, + 0.31753996 -0.85879886 0.40203595, + 0.32596186 -0.86964661 0.37076083, + 0.36939913 -0.85482532 0.36444211, + 0.37771586 -0.8637507 0.33356488, + 0.42195508 -0.84574217 0.32661009, + 0.42990795 -0.85282588 0.29642397, + 0.47466189 -0.83137983 0.28896993, + 0.48205301 -0.83677399 0.25968099, + 0.52674121 -0.8118313 0.2519401, + 0.53340405 -0.8157261 0.22376603, + 0.57700533 -0.78764337 0.2160621, + 0.58280408 -0.79026109 0.18928003, + 0.624937 -0.759202 0.181841, + 0.62980598 -0.76078898 0.15666699, + 0.6703828 -0.72676581 0.14966097, + 0.67426395 -0.72756094 0.12658298, + 0.71296 -0.69082701 0.120192, + 0.71591437 -0.69108033 0.099371746, + 0.75205427 -0.65239125 0.093808539, + 0.7542063 -0.65232426 0.07514023, + 0.78768599 -0.61203003 0.070498802, + 0.78916311 -0.61181206 0.053923909, + 0.82020891 -0.56985492 0.050225891, + 0.82114768 -0.5696038 0.035607889, + 0.84975868 -0.5261448 0.032891087, + 0.85041779 -0.52586186 0.016090596, + 0.84620416 -0.53257513 0.017387304, + 0.84633183 -0.53265589 0.00023593094, + 0.8462562 -0.53277612 0.00023593106, + 0.84637833 -0.53258216 0.00026217208, + 0.82967287 -0.55823594 -0.0039262897, + 0.69793826 -0.71614921 -0.0035350011, + 0.69157004 -0.72229505 -0.0045597306, + 0.69154221 -0.72226518 0.010117003, + 0.691531 -0.72227597 0.0101172, + 0.69156498 -0.72231197 -0.00182327, + 0.65532696 -0.75534487 0.00083642389, + 0.65529728 -0.75531036 0.0095797544, + 0.65522128 -0.75537634 0.0095808245, + 0.65525085 -0.75541085 0.00084023684, + 0.6553002 -0.75536817 0.00084023719, + 0.61743623 -0.78661227 -0.0037215315, + 0.62061208 -0.78411114 -0.0032478406, + 0.2546649 -0.96702164 -0.0038567185, + 0.22211507 -0.97502035 0.00041317815, + 0.22210693 -0.97498876 0.008082578, + 0.22208592 -0.97499365 0.0080826571, + 0.22209311 -0.97502548 0.00041480121, + 0.22195707 -0.97505635 0.00041480115, + 0.22185303 -0.97459811 0.030658403, + 0.20547095 -0.97846276 0.019808695, + 0.20520093 -0.97769666 0.044742886, + 0.15871096 -0.98629278 0.045136288, + 0.15823504 -0.98456424 0.074799418, + 0.11246801 -0.99080014 0.075273208, + 0.11194903 -0.98810124 0.10546802, + 0.066870503 -0.99212599 0.105898, + 0.066449784 -0.98842275 0.13639997, + 0.022057205 -0.99037123 0.13666902, + 0.021882297 -0.98565888 0.16732499, + -0.021252608 -0.98567235 0.16732706, + -0.021425407 -0.99038035 0.13670304, + -0.065728173 -0.98846555 0.13643894, + -0.066146784 -0.99218476 0.10580198, + -0.11127995 -0.98818654 0.10537595, + -0.11179895 -0.9909035 0.074907564, + -0.15772898 -0.9846729 0.07443659, + -0.158208 -0.98642099 0.044089399, + -0.20491703 -0.97780311 0.043704305, + -0.20519897 -0.97858387 0.016340397, + -0.21892197 -0.97541088 0.025430197, + -0.21899305 -0.97572625 0.0005737741, + -0.21895708 -0.97573435 0.00057377422, + -0.21905793 -0.97571164 0.00056614081, + -0.25466502 -0.96702212 -0.0037548405, + -0.15389703 -0.98807925 -0.003899331, + -0.12233499 -0.99248886 0.00032403597, + -0.12233002 -0.99245411 0.0083854105, + -0.12234601 -0.99245214 0.008385391, + -0.12235 -0.99248701 0.000322482, + -0.12227194 -0.99249655 0.00032248185, + -0.12224501 -0.9922781 0.020985102, + -0.11271704 -0.99347335 0.017480105, + -0.11255803 -0.99262923 0.04492151, + -0.066982798 -0.99673402 0.045107301, + -0.06677448 -0.99489564 0.075655669, + -0.021740088 -0.99688554 0.07580696, + -0.021638101 -0.99409813 0.10630502, + 0.022299692 -0.99408364 0.10630296, + 0.022404198 -0.99685991 0.075949393, + 0.067353502 -0.99484599 0.075795896, + 0.067563027 -0.99666947 0.045665022, + 0.11290703 -0.99256426 0.04547691, + 0.11305897 -0.99337876 0.020403994, + 0.12533605 -0.99180138 0.02491851, + 0.12537506 -0.99210948 0.00012096906, + 0.12552199 -0.99209088 0.00012096899, + 0.12551698 -0.99205387 0.0086383894, + 0.125453 -0.99206197 0.0086385198, + 0.12545702 -0.99209911 0.00012746002, + 0.153897 -0.98807901 -0.0039516301, + 0.10280795 0.99469352 -0.003915648, + 0.071956687 0.99740773 0.00026847795, + 0.071947075 0.99727464 -0.016333895, + 0.11242895 0.99355352 -0.014528194, + 0.12076201 0.99254113 -0.016694501, + 0.12077902 0.99267912 -0.00077198411, + 0.12076104 0.99268138 -0.0007729893, + 0.12074404 0.99254334 -0.016694505, + 0.169322 0.98546797 -0.0135269, + 0.16933702 0.98555809 0.00053772307, + 0.169314 0.98556203 0.00053772301, + 0.16929002 0.98542112 -0.016913401, + 0.16930299 0.98541886 -0.016913299, + 0.16932696 0.98555976 0.0005366499, + 0.20454805 0.97884923 -0.003782881, + 0.30412212 0.95262635 -0.0035832615, + 0.26509103 0.96422315 0.00072643004, + 0.265053 0.96408498 -0.016945601, + 0.29804888 0.95445365 -0.013599595, + 0.29742298 0.95371085 -0.044443198, + 0.34326813 0.93821937 -0.043721315, + 0.34190887 0.93690467 -0.072854877, + 0.38716599 0.91923499 -0.0714809, + 0.38488606 0.91745514 -0.10069201, + 0.42867184 0.89806771 -0.098563761, + 0.42532015 0.89596027 -0.12789804, + 0.46745589 0.87514478 -0.12492597, + 0.46294788 0.87289184 -0.15407497, + 0.50367302 0.850743 -0.150166, + 0.49790683 0.84851873 -0.17917794, + 0.53725493 0.8252219 -0.17425798, + 0.5301162 0.82319927 -0.20327307, + 0.56748885 0.79937071 -0.19738993, + 0.55884188 0.79771382 -0.22660194, + 0.594491 0.77350003 -0.219723, + 0.58422786 0.77239084 -0.24917895, + 0.61862022 0.74774224 -0.24122709, + 0.60659885 0.74737281 -0.27105695, + 0.6399278 0.72239184 -0.26199695, + 0.62585396 0.72296596 -0.29262096, + 0.65769953 0.69825351 -0.28261879, + 0.64117932 0.70000637 -0.31445214, + 0.67184097 0.67565495 -0.30351296, + 0.6673612 0.67649817 -0.31141505, + 0.70184106 0.64706606 -0.29786703, + 0.71258402 0.64377099 -0.278896, + 0.74588275 0.61118776 -0.26477993, + 0.7549969 0.60698897 -0.24808097, + 0.78636533 0.57184428 -0.2337171, + 0.79398012 0.56707704 -0.21913303, + 0.8232879 0.52946794 -0.20459896, + 0.82939559 0.52453178 -0.19227391, + 0.85684532 0.48407617 -0.17744406, + 0.86165071 0.47919682 -0.16711794, + 0.88702273 0.43597391 -0.15204397, + 0.89055175 0.43152991 -0.14387298, + 0.91355973 0.3858259 -0.12863497, + 0.91608822 0.38189408 -0.12222703, + 0.93656486 0.33381397 -0.10683899, + 0.93917674 0.32873392 -0.099403478, + 0.95700324 0.27766106 -0.083959922, + 0.95893151 0.27283487 -0.077533662, + 0.97383952 0.2185819 -0.062116269, + 0.9749611 0.21481302 -0.057501007, + 0.98651087 0.15812899 -0.042327695, + 0.98706377 0.15544397 -0.03927229, + 0.99506599 0.096192896 -0.024302701, + 0.99525774 0.094607875 -0.022611795, + 0.9994489 0.032285195 -0.0077163391, + 0.99946898 0.031777699 -0.0072047501, + 0.99943167 -0.032876387 0.007453857, + 0.99945015 -0.032410502 0.0070065008, + 0.99458152 -0.10161195 0.021966388, + 0.99471962 -0.10047496 0.020918092, + 0.98417938 -0.17345606 0.036112312, + 0.9844501 -0.17215301 0.034947902, + 0.96713197 -0.249192 0.0505872, + 0.97079951 -0.23660688 0.039566081, + 0.94792664 -0.31412688 0.052529182, + 0.95447814 -0.29599202 0.036882102, + 0.9269079 -0.37240896 0.046403997, + 0.93447179 -0.35466191 0.031262394, + 0.90172511 -0.43064007 0.037959702, + 0.91015613 -0.41360006 0.023470504, + 0.87160188 -0.48942694 0.027773496, + 0.88000643 -0.47471923 0.015181308, + 0.83485729 -0.5501852 0.017594706, + 0.84229183 -0.53896588 0.0077707381, + 0.79010665 -0.61290568 0.0088367853, + 0.79456389 -0.60716993 0.0035848296, + 0.73454076 -0.67855275 0.0040062787, + 0.73390216 -0.67923915 0.0046853409, + 0.66560578 -0.74628574 0.0051478283, + 0.6569953 -0.75377333 0.013525606, + 0.58139819 -0.8134883 0.014597106, + 0.56251264 -0.82617754 0.031782281, + 0.48316512 -0.87488216 0.033655908, + 0.45286679 -0.88954759 0.060139369, + 0.37459409 -0.92507726 0.062541515, + 0.33690184 -0.93671656 0.095179759, + 0.26521596 -0.95924985 0.097469382, + 0.2306959 -0.96454966 0.12815395, + 0.16951507 -0.97694248 0.12980007, + 0.13368805 -0.97743434 0.16355306, + 0.085441932 -0.98268133 0.16443007, + 0.061075829 -0.97999948 0.18939608, + 0.023795288 -0.98155451 0.18969591, + 0.021970792 -0.98119164 0.19178192, + -0.0092666335 -0.98138636 0.19182007, + -0.019885106 -0.97844625 0.20554204, + -0.04286541 -0.97774023 0.20539404, + -0.04788401 -0.97592223 0.21279804, + -0.064579032 -0.97500348 0.2125981, + -0.067044362 -0.97391438 0.21678486, + -0.078430675 -0.97310376 0.21660495, + -0.081427425 -0.97152221 0.22251806, + -0.075575128 -0.97197133 0.22262107, + -0.038571604 -0.98962212 0.13842101, + -0.03709108 -0.98967755 0.13842894, + 0.050033309 -0.99430513 -0.094095312, + 0.039449204 -0.99477714 -0.094140016, + 0.11652396 -0.93337363 -0.33946389, + 0.094919048 -0.93553239 -0.34024915, + 0.15793304 -0.79668516 -0.58339512, + 0.12618001 -0.80036211 -0.58608806, + 0.16533604 -0.60968411 -0.77520919, + 0.12662698 -0.61321592 -0.77969986, + 0.14817005 -0.37287611 -0.91597432, + 0.10518698 -0.37494591 -0.92105979, + 0.11229903 -0.13513103 -0.98444325, + 0.12069401 -0.14249702 -0.98240912, + 0.11786001 -0.14253801 -0.98274714, + 0.15864508 -0.10010905 -0.98224747, + 0.14815801 -0.37279803 -0.91600811, + 0.19190304 -0.36995208 -0.90901524, + 0.16494896 -0.60590488 -0.77824885, + 0.20456795 -0.6013279 -0.77237082, + 0.15789999 -0.79124385 -0.59076291, + 0.190781 -0.786578 -0.58727998, + 0.11772303 -0.92848122 -0.35222709, + 0.14138098 -0.92559087 -0.35113096, + 0.053566806 -0.9921031 -0.11341102, + 0.059901331 -0.99174547 -0.11337005, + 0.16369702 -0.91649014 -0.36503303, + 0.14358397 -0.91939574 -0.3661899, + 0.22604696 -0.7736479 -0.59192193, + 0.191175 -0.77955699 -0.59644198, + 0.24443103 -0.59026206 -0.76931411, + 0.20421797 -0.59589791 -0.77665991, + 0.23597312 -0.36417219 -0.90094143, + 0.19163205 -0.3678101 -0.90994126, + 0.20492108 -0.091626726 -0.97448033, + 0.21681599 0.0026046401 -0.97620898, + 0.21468908 -0.13977905 -0.96662837, + 0.21835297 -0.13968499 -0.96582091, + 0.220515 0.00265957 -0.97538, + 0.21612503 0.0026596703 -0.97636211, + 0.26428393 -0.0039990884 -0.96443665, + 0.2795369 -0.012949395 -0.96004766, + 0.37664691 -0.015940497 -0.92621976, + 0.40300286 0.00038632084 -0.91519868, + 0.40005201 -0.120811 -0.90849501, + 0.4004139 -0.12079397 -0.90833777, + 0.40336791 0.00043844187 -0.91503775, + 0.39740714 0.00043841015 -0.91764235, + 0.39408395 -0.12903799 -0.90997088, + 0.43640709 -0.065648817 -0.89735126, + 0.44440988 -0.11216497 -0.88877374, + 0.44723314 -0.00050209515 -0.89441729, + 0.44799486 -0.00090545067 -0.8940357, + 0.44517004 -0.11212701 -0.88839811, + 0.48126793 -0.062382493 -0.87435091, + 0.48783094 -0.10351498 -0.86677891, + 0.49046582 -0.0011323796 -0.87145972, + 0.49107412 -0.0010251602 -0.87111717, + 0.48843718 -0.10348204 -0.86644131, + 0.53124309 -0.051707506 -0.84564012, + 0.53195506 0.00094308011 -0.84677213, + 0.5327729 0.00094307779 -0.84625781, + 0.53274888 0.00095601875 -0.84627283, + 0.53028589 -0.096065581 -0.84235883, + 0.56829095 -0.058662191 -0.8207339, + 0.54801184 -0.27404392 -0.79030567, + 0.59053427 -0.26439312 -0.76247334, + 0.55105811 -0.43937713 -0.7094242, + 0.59396493 -0.42359394 -0.68393993, + 0.53385019 -0.58416623 -0.61135423, + 0.57769769 -0.5639047 -0.5901497, + 0.4639858 -0.75271565 -0.46705079, + 0.46604079 -0.74693763 -0.47422576, + 0.34005103 -0.87845212 -0.33568904, + 0.36426997 -0.86993891 -0.33243597, + 0.21568495 -0.95992178 -0.17896995, + 0.23729794 -0.95498079 -0.17804895, + 0.10789903 -0.99275821 -0.052811112, + 0.10245996 -0.99333262 -0.052841581, + 0.19965109 -0.96805447 -0.15169108, + 0.180227 -0.97176701 -0.152273, + 0.33153513 -0.88888431 -0.31617913, + 0.30847001 -0.89622498 -0.31878999, + 0.44749928 -0.7549755 -0.47932929, + 0.40949491 -0.79004484 -0.45622689, + 0.52879816 -0.60148627 -0.59882122, + 0.49882883 -0.61420876 -0.61148775, + 0.38730609 -0.79467517 -0.46742412, + 0.41099 -0.78578699 -0.46219701, + 0.27937993 -0.91127479 -0.30253094, + 0.300964 -0.90506297 -0.30046901, + 0.14815398 -0.98084879 -0.12643597, + 0.16575295 -0.97807467 -0.12607895, + 0.04644471 -0.99892026 0.0011167702, + 0.044149615 -0.99902433 0.0011168903, + 0.13473098 -0.98577988 -0.10042699, + 0.11903098 -0.98777789 -0.10062999, + 0.27220803 -0.91943914 -0.28378603, + 0.25165305 -0.92477024 -0.28543106, + 0.38448599 -0.80323499 -0.45495501, + 0.36193904 -0.81112814 -0.45942506, + 0.47082087 -0.64001483 -0.60721385, + 0.45094407 -0.64750403 -0.61431909, + 0.33721596 -0.82609791 -0.45149493, + 0.35948503 -0.81883514 -0.44752607, + 0.225954 -0.93647999 -0.268235, + 0.24511303 -0.93201613 -0.26695603, + 0.093090557 -0.99276954 -0.075781859, + 0.107046 -0.99137002 -0.0756751, + 0.020598894 -0.99944574 0.026150994, + 0.031277593 -0.99916875 0.026143795, + 0.034816992 -0.99914676 0.022215795, + 0.079250239 -0.9966085 0.022159411, + 0.10655794 -0.99429041 -0.0056454269, + 0.16392401 -0.98645711 -0.0056009605, + 0.19910797 -0.97923589 -0.038120497, + 0.26867101 -0.96250302 -0.0374691, + 0.31737912 -0.94497335 -0.079347126, + 0.39734799 -0.91444999 -0.076784097, + 0.41442591 -0.90554374 -0.090783074, + 0.49777517 -0.86298031 -0.08651603, + 0.536448 -0.83569002 -0.117668, + 0.59908813 -0.79286218 -0.11163803, + 0.65914583 -0.73457885 -0.16099896, + 0.71674198 -0.68116999 -0.14929301, + 0.74526083 -0.64357281 -0.17435695, + 0.80567586 -0.57174593 -0.15489699, + 0.81808972 -0.5501858 -0.16740593, + 0.86604971 -0.47830683 -0.14553496, + 0.87225097 -0.46451801 -0.15297499, + 0.90920877 -0.39544892 -0.13022897, + 0.91073686 -0.39115995 -0.13248499, + 0.93890113 -0.32599604 -0.11041401, + 0.93815678 -0.32859191 -0.10903798, + 0.95957488 -0.26712996 -0.088642895, + 0.95810974 -0.27343494 -0.08520028, + 0.97436422 -0.21479104 -0.066927515, + 0.97287863 -0.22273992 -0.062403079, + 0.98500752 -0.16611493 -0.046538979, + 0.98387003 -0.173914 -0.041877698, + 0.9924379 -0.11933699 -0.028735695, + 0.99172539 -0.12601304 -0.024528209, + 0.99724662 -0.072789781 -0.014168396, + 0.9969461 -0.077289306 -0.011171101, + 0.99968964 -0.024653891 -0.0035633789, + 0.99965113 -0.026304604 -0.0023996702, + 0.99967277 0.025476795 0.0023241495, + 0.99962777 0.027264895 0.00098791381, + 0.99677914 0.08014331 0.0029039101, + 0.99628466 0.086102374 -0.0018254393, + 0.99020326 0.13960204 -0.0029596707, + 0.98885125 0.14853503 -0.010520902, + 0.9792065 0.20235892 -0.014333294, + 0.97842211 0.20587203 -0.017519202, + 0.96592909 0.25787503 -0.021944502, + 0.96481848 0.26166311 -0.025649114, + 0.94991064 0.31103089 -0.030488389, + 0.94802934 0.31614813 -0.03592781, + 0.93074036 0.36334211 -0.041291114, + 0.92802978 0.36936191 -0.048296187, + 0.90843588 0.41449594 -0.054197792, + 0.90478468 0.42120785 -0.06283848, + 0.88297528 0.46428117 -0.069264524, + 0.87825191 0.47151294 -0.079680592, + 0.85460269 0.51202279 -0.086526372, + 0.84870028 0.51955718 -0.098834336, + 0.82338297 0.55748898 -0.10605, + 0.81620979 0.5650779 -0.12036897, + 0.78911185 0.60077095 -0.12797199, + 0.78109014 0.60771406 -0.14346401, + 0.75232786 0.64116496 -0.15136099, + 0.74419594 0.64681393 -0.16674599, + 0.71411425 0.67786622 -0.17475206, + 0.70482618 0.6828692 -0.19211905, + 0.67353427 0.71153235 -0.20018309, + 0.66317421 0.71557325 -0.21944207, + 0.63054401 0.74204499 -0.22756, + 0.61922705 0.74481606 -0.24861003, + 0.58539873 0.7690357 -0.25669491, + 0.57319403 0.77025598 -0.27956101, + 0.5388878 0.79183668 -0.28739291, + 0.52605093 0.79124188 -0.31177998, + 0.49144319 0.8102743 -0.3192791, + 0.47813812 0.80765319 -0.34508008, + 0.44332087 0.82427782 -0.35218292, + 0.44524786 0.82491368 -0.34824088, + 0.4130761 0.83899915 -0.3541871, + 0.4263368 0.8448956 -0.32309186, + 0.39265686 0.85901868 -0.32849288, + 0.40365493 0.86506486 -0.29786798, + 0.3681621 0.87910622 -0.30270305, + 0.37719294 0.88517588 -0.27237698, + 0.33995411 0.89885032 -0.2765851, + 0.34725204 0.90482813 -0.24637803, + 0.30809787 0.91793364 -0.24994691, + 0.31386504 0.92371112 -0.21965103, + 0.2731691 0.93587035 -0.22254308, + 0.27757895 0.94126874 -0.19225796, + 0.23577589 0.9521485 -0.19448091, + 0.23898891 0.95704466 -0.16416395, + 0.19590098 0.96650785 -0.16578698, + 0.19810708 0.97079235 -0.13533604, + 0.15385492 0.97862953 -0.13642894, + 0.15523499 0.98219287 -0.10582598, + 0.11043503 0.98816425 -0.10646902, + 0.11117101 0.99089509 -0.075947404, + 0.066302076 0.99488163 -0.07625287, + 0.0665944 0.99673003 -0.045765899, + 0.021986302 0.9987061 -0.045856602, + 0.022032911 0.99963647 -0.015542908, + 0.023180988 0.99961042 -0.01554249, + 0.023183189 0.99970353 -0.0074441661, + -0.026116196 0.99965888 -6.4459993e-005, + -0.026112905 0.99953026 -0.016048204, + -0.025917405 0.99953526 -0.016048303, + -0.07591784 0.99701548 -0.014026706, + -0.075925261 0.99711353 6.0097969e-005, + -0.10280804 0.99469334 -0.0039622113, + -0.12401196 0.99228066 -0.00046628484, + -0.12390795 0.99229366 -0.00047202283, + -0.12389202 0.99215913 -0.016466102, + -0.12399503 0.99214625 -0.016465904, + -0.17239891 0.98495054 -0.012291995, + -0.17241198 0.98502487 0.00037551695, + -0.17241894 0.98502362 0.00037551686, + -0.17239505 0.98489022 -0.016471503, + -0.17239699 0.98488986 -0.016471498, + -0.17242008 0.9850235 0.00037541517, + -0.20454797 0.97884887 -0.0038764095, + -0.22054604 0.97537613 -0.00094495114, + -0.22055903 0.97537315 -0.00094389613, + -0.22052993 0.97524363 -0.016323095, + -0.22051689 0.97524655 -0.016323192, + -0.26797795 0.96336377 -0.010867897, + -0.26799291 0.96342063 0.00061276177, + -0.26814905 0.96337724 0.00061276217, + -0.26811403 0.96325213 -0.016131202, + -0.26803502 0.96327412 -0.016131502, + -0.29856411 0.95430934 -0.012375805, + -0.2979221 0.95356739 -0.044178713, + -0.3438409 0.93802178 -0.043458488, + -0.34245804 0.9366861 -0.073087007, + -0.3876071 0.91903126 -0.071709514, + -0.38531384 0.91723561 -0.10105396, + -0.42894492 0.89789778 -0.098923676, + -0.4256269 0.89580274 -0.12798098, + -0.46770099 0.87500203 -0.125009, + -0.4632428 0.87276858 -0.15388693, + -0.50398982 0.85058868 -0.14997694, + -0.49826512 0.84837818 -0.17884704, + -0.53764421 0.82503831 -0.17392705, + -0.53050971 0.82301754 -0.20298187, + -0.56794095 0.79912388 -0.19708897, + -0.55925208 0.79745811 -0.22649004, + -0.59484023 0.77326131 -0.21961807, + -0.58450174 0.77213973 -0.2493149, + -0.61876297 0.74757391 -0.24138297, + -0.60657406 0.74719208 -0.27161002, + -0.63981837 0.72228539 -0.26255715, + -0.62552601 0.722848 -0.293612, + -0.65731901 0.69821203 -0.28360501, + -0.64059901 0.69994497 -0.31576899, + -0.67115998 0.67573202 -0.30484501, + -0.66749024 0.67641723 -0.31131411, + -0.70187908 0.64705503 -0.29780102, + -0.71237063 0.64384073 -0.27927989, + -0.74565685 0.61129689 -0.26516393, + -0.75476134 0.60711128 -0.24849811, + -0.7861228 0.57200891 -0.23412994, + -0.79372585 0.56725889 -0.21958295, + -0.8231011 0.52960104 -0.20500603, + -0.82934928 0.52455819 -0.19240208, + -0.8567611 0.48417205 -0.17758901, + -0.86172843 0.47912824 -0.16691408, + -0.88710201 0.43588099 -0.151848, + -0.89077699 0.43124601 -0.14332899, + -0.91373622 0.38557008 -0.12814803, + -0.91606086 0.38195094 -0.12225398, + -0.93657386 0.33378896 -0.10683799, + -0.93906921 0.32894009 -0.099737421, + -0.95690852 0.27789587 -0.084260464, + -0.95882577 0.27310693 -0.077882282, + -0.97376454 0.21883389 -0.062405169, + -0.97488666 0.21507092 -0.057796877, + -0.98646945 0.15832807 -0.042548317, + -0.98703253 0.15559892 -0.039441582, + -0.99505335 0.096296735 -0.024409609, + -0.99525434 0.094637834 -0.022639807, + -0.99944854 0.032294385 -0.0077256663, + -0.99947011 0.031749506 -0.007176321, + -0.99943286 -0.032845397 0.0074240291, + -0.99945277 -0.032342393 0.0069410983, + -0.99460977 -0.10138097 0.021757694, + -0.99473876 -0.10031497 0.020774994, + -0.98423898 -0.173169 0.0358629, + -0.98441637 -0.17231506 0.03509941, + -0.96705836 -0.24943309 0.050807718, + -0.97063679 -0.23718694 0.040081389, + -0.94762099 -0.31493199 0.0532194, + -0.95414776 -0.29695195 0.037703592, + -0.92639261 -0.37355989 0.047430482, + -0.93416113 -0.35541904 0.031941503, + -0.90124625 -0.43156809 0.038785107, + -0.91011912 -0.41367605 0.023569005, + -0.87157118 -0.48947513 0.027887607, + -0.88034356 -0.47410777 0.014735593, + -0.83533573 -0.54947484 0.017077994, + -0.84298587 -0.53789091 0.006942559, + -0.79099482 -0.61177188 0.0078961486, + -0.79559714 -0.60582107 0.0024563803, + -0.73582941 -0.6771614 0.0027456416, + -0.73527825 -0.67775726 0.0033327611, + -0.66721874 -0.74485278 0.0036626887, + -0.65853894 -0.75244886 0.012130698, + -0.58311099 -0.81228697 0.0130954, + -0.56417984 -0.82509369 0.030357089, + -0.48489505 -0.87398112 0.032155804, + -0.4554998 -0.88835156 0.057891473, + -0.37719899 -0.92417198 0.0602258, + -0.33950588 -0.93600267 0.092922971, + -0.26767102 -0.9587971 0.095185913, + -0.2250969 -0.96521753 0.13299094, + -0.16445498 -0.97715288 0.13463598, + -0.12518504 -0.97720337 0.17147106, + -0.078118563 -0.98194152 0.17230292, + -0.068927988 -0.98093176 0.18171896, + -0.030380011 -0.98281634 0.18206906, + -0.021983795 -0.98121178 0.19167696, + 0.0091857361 -0.98140764 0.19171493, + 0.020586208 -0.97824138 0.20644608, + 0.043480314 -0.97752339 0.20629507, + 0.047784712 -0.97596127 0.21264105, + 0.064450301 -0.97504598 0.212442, + 0.067108102 -0.97387201 0.216956, + 0.078481093 -0.97306186 0.21677497, + 0.083666027 -0.97029334 0.22700408, + 0.077334017 -0.97079122 0.22712106, + 0.041854788 -0.98834574 0.14635897, + 0.039727882 -0.98843151 0.14637193, + -0.054940317 -0.99281436 -0.10630704, + -0.16426393 -0.91616273 -0.36559987, + -0.14962101 -0.91832411 -0.36646202, + -0.23983197 -0.75989789 -0.60418195, + -0.22130908 -0.77979231 -0.58561623, + -0.28812802 -0.56949306 -0.76984411, + -0.24616906 -0.57641214 -0.77919817, + -0.28215593 -0.34129792 -0.89660674, + -0.25111195 -0.090737276 -0.96369576, + -0.23699594 -0.34561691 -0.90795475, + -0.20452897 -0.096058182 -0.97413588, + -0.19247103 -0.35436204 -0.91508609, + -0.23754898 -0.35077697 -0.90582889, + -0.2057101 -0.58928728 -0.78129637, + -0.24638185 -0.58360267 -0.77375954, + -0.19279104 -0.77633721 -0.60011011, + -0.21939893 -0.77190268 -0.59668279, + -0.13602194 -0.92319256 -0.35946283, + -0.15009902 -0.92129624 -0.3587251, + -0.054954972 -0.9923445 -0.11059995, + -0.059102107 -0.99210912 -0.11057401, + -0.07268469 -0.98916686 -0.12753798, + 0.03559408 -0.99181855 0.12259294, + 0.039414715 -0.99167633 0.12257504, + -0.082516149 -0.98777241 -0.13227493, + -0.072973207 -0.98851013 -0.13237302, + -0.17916304 -0.91047221 -0.37274808, + -0.16396394 -0.91292173 -0.3737509, + -0.25689399 -0.756473 -0.60145998, + -0.2582711 -0.76441431 -0.59073424, + -0.33103991 -0.55345589 -0.76426381, + -0.28814796 -0.56164896 -0.7755779, + -0.32759112 -0.33064711 -0.88507432, + -0.28166485 -0.33578885 -0.89883858, + -0.29746112 -0.086104631 -0.95084333, + -0.26503491 -0.15271494 -0.95206863, + -0.26817894 0.0028997294 -0.96336478, + -0.2705971 0.002899671 -0.96268839, + -0.26748106 -0.15135103 -0.95160222, + -0.26561394 -0.15141597 -0.95211476, + -0.26871094 0.0027940292 -0.96321678, + -0.22075494 -0.018295696 -0.97515774, + -0.21809793 -0.15573093 -0.96342164, + -0.21867797 -0.15571399 -0.9632929, + -0.22137192 -0.0073574572 -0.97516167, + -0.17369999 0.0033634296 -0.98479289, + -0.17157902 -0.15579802 -0.97277313, + -0.16904208 -0.15585308 -0.97320849, + -0.17113298 0.0034487494 -0.98524189, + -0.17322601 0.0034487206 -0.9848761, + -0.17109302 -0.15647501 -0.97275013, + -0.15798508 -0.099778444 -0.98238748, + -0.14827499 -0.36196998 -0.92032188, + -0.19307391 -0.35912883 -0.91309857, + -0.16607699 -0.60042197 -0.7822479, + -0.20612893 -0.59580177 -0.77622873, + -0.15900095 -0.78913879 -0.59327787, + -0.19235504 -0.78438014 -0.58970106, + -0.11838197 -0.92833674 -0.35238692, + -0.13670902 -0.9261331 -0.35155103, + -0.044291589 -0.99477875 -0.091942579, + -0.039150681 -0.99499249 -0.091962256, + -0.11727397 -0.93293577 -0.34040791, + -0.09552452 -0.93512225 -0.3412061, + -0.15904096 -0.79447281 -0.58610487, + -0.12722893 -0.79817551 -0.58883667, + -0.16657801 -0.60535705 -0.77832812, + -0.12746598 -0.60892695 -0.78291786, + -0.14892097 -0.36636692 -0.91847575, + -0.11236299 -0.10564799 -0.9880349, + -0.10525 -0.36844099 -0.92367399, + -0.022183407 -0.11980704 -0.99254936, + -0.02076989 -0.37641183 -0.92621958, + -0.39137793 0.92015487 -0.011760498, + -0.39058194 0.91956586 -0.042946097, + -0.43553206 0.89919311 -0.041994605, + -0.43389115 0.89817631 -0.070836723, + -0.47732094 0.87600887 -0.069088392, + -0.47470087 0.87472683 -0.097530581, + -0.51679683 0.85083568 -0.09486676, + -0.5131163 0.84946245 -0.12298507, + -0.5538801 0.82400519 -0.11929903, + -0.54905778 0.82271558 -0.14722292, + -0.58781189 0.7963478 -0.14250398, + -0.58175796 0.7953099 -0.17041099, + -0.61872089 0.76817483 -0.16459596, + -0.61131811 0.76755619 -0.19273704, + -0.64682406 0.73967606 -0.18573602, + -0.63794816 0.73966318 -0.21429105, + -0.67215884 0.71116281 -0.20603396, + -0.66176325 0.71195322 -0.23493008, + -0.69436681 0.68337685 -0.22550094, + -0.68230224 0.68517125 -0.25495908, + -0.7135756 0.65659356 -0.24432485, + -0.69955194 0.65963495 -0.27478898, + -0.73005497 0.63084 -0.26279399, + -0.71385407 0.63539404 -0.29442602, + -0.74407393 0.60618097 -0.28088897, + -0.73987693 0.60772794 -0.28852898, + -0.77318585 0.57289189 -0.27198994, + -0.7815538 0.56870389 -0.25641695, + -0.812751 0.53112102 -0.239471, + -0.81965387 0.52646095 -0.22584596, + -0.84886569 0.48579481 -0.20839992, + -0.85426486 0.48107794 -0.19696598, + -0.8812539 0.43740195 -0.17908399, + -0.88532531 0.43289414 -0.16971105, + -0.90962887 0.38676193 -0.15162599, + -0.91260475 0.38261992 -0.14406396, + -0.93418211 0.33391201 -0.12572402, + -0.93611223 0.33052608 -0.12019403, + -0.95489049 0.27907911 -0.10148504, + -0.95587242 0.27687582 -0.098221943, + -0.97184145 0.2220761 -0.078781635, + -0.97294611 0.21876404 -0.074285507, + -0.98538965 0.16127095 -0.054762583, + -0.98605078 0.15839295 -0.05114219, + -0.99467033 0.098118536 -0.031680711, + -0.99489933 0.096410736 -0.02967051, + -0.99940652 0.032922786 -0.010131995, + -0.99943078 0.032366391 -0.0095136678, + -0.99939013 -0.033501703 0.0098473607, + -0.99941349 -0.032963917 0.0092781642, + -0.9942199 -0.10334699 0.029088596, + -0.99442166 -0.10181996 0.02753569, + -0.98329014 -0.17573301 0.047524106, + -0.98376524 -0.17361404 0.045433212, + -0.96570897 -0.251169 0.065728702, + -0.96620566 -0.24963792 0.06424538, + -0.939933 -0.330587 0.085078098, + -0.93977523 -0.33094609 0.08542452, + -0.90431821 -0.41331208 0.10668502, + -0.91334611 -0.39694005 0.090760611, + -0.8717894 -0.47755623 0.10919406, + -0.88582075 -0.45567489 0.087647177, + -0.83918846 -0.5340513 0.10272306, + -0.85333973 -0.51466483 0.083255872, + -0.80116701 -0.59076101 0.0955659, + -0.81518728 -0.57391018 0.078082733, + -0.75759089 -0.64677095 0.08799579, + -0.76925611 -0.63456208 0.074673705, + -0.70577061 -0.70358557 0.082796045, + -0.71335822 -0.69679624 0.074800327, + -0.64384276 -0.76078671 0.081669569, + -0.64495492 -0.75996089 0.080576994, + -0.57004493 -0.81703389 0.086628295, + -0.5630967 -0.82113159 0.093085252, + -0.48538512 -0.86873621 0.098481819, + -0.46907488 -0.87588978 0.11307397, + -0.39203706 -0.91237813 0.11778402, + -0.36737803 -0.91954613 0.13952902, + -0.29466686 -0.94478554 0.14335893, + -0.265111 -0.94916099 0.169734, + -0.20105192 -0.96428365 0.17243893, + -0.17046902 -0.96467412 0.20085903, + -0.11765994 -0.97220355 0.20242591, + -0.088517442 -0.96883249 0.2313621, + -0.047782417 -0.97153938 0.23200908, + -0.024662288 -0.96606553 0.25711688, + 0.0050567104 -0.9663471 0.25719202, + 0.0073616374 -0.96558166 0.25999591, + 0.030892396 -0.9651469 0.25987896, + 0.032872193 -0.96433675 0.26262894, + 0.051177207 -0.96359414 0.26242602, + 0.054516513 -0.96194124 0.26776305, + 0.066864595 -0.96121788 0.26756197, + 0.066296183 -0.96155077 0.26650494, + 0.074408814 -0.96099925 0.26635307, + 0.0732489 -0.96178699 0.26381901, + 0.077334069 -0.96148962 0.2637369, + 0.078533106 -0.96053112 0.26685703, + 0.069827206 -0.96115512 0.26703003, + 0.04263531 -0.98217422 0.18307404, + 0.037868004 -0.9823631 0.18310902, + -0.027572209 -0.99762338 -0.063146122, + -0.020244505 -0.99779826 -0.063157216, + -0.074918494 -0.9439429 -0.32149497, + -0.055990219 -0.94511837 -0.32189512, + -0.097311303 -0.80920398 -0.579413, + -0.068204083 -0.8111698 -0.5808199, + -0.090666726 -0.61939025 -0.77983028, + -0.053585988 -0.62105787 -0.7819308, + -0.063083395 -0.37574393 -0.9245739, + -0.066458195 -0.13832998 -0.98815387, + -0.062407199 -0.372188 -0.92605698, + -0.10565203 -0.37082812 -0.92267233, + -0.090007119 -0.61574709 -0.78278619, + -0.12806295 -0.61316574 -0.77950472, + -0.096859388 -0.80604988 -0.58386797, + -0.12760097 -0.8032378 -0.58183086, + -0.074847996 -0.94096786 -0.33011696, + -0.095036283 -0.93934387 -0.32954696, + -0.028510904 -0.9966951 -0.076065406, + -0.037151009 -0.99641222 -0.076043814, + 0.040215082 -0.98522252 0.16649093, + 0.043821409 -0.98507321 0.16646504, + 0.075018965 -0.96572351 0.24849588, + 0.082702801 -0.96513498 0.248344, + 0.079901062 -0.9669705 0.24204089, + 0.072466061 -0.96752155 0.24217889, + 0.072000794 -0.96777886 0.24128798, + 0.059969008 -0.9685511 0.24148002, + 0.058584973 -0.96920151 0.23919888, + 0.041284475 -0.97004139 0.23940586, + 0.034505986 -0.97265154 0.22969189, + 0.010393696 -0.97317863 0.22981592, + 0.0055523487 -0.97463375 0.22373694, + -0.024798306 -0.97434926 0.22367106, + -0.0303187 -0.975582 0.21753301, + -0.06794899 -0.97377491 0.21712998, + -0.098884739 -0.97755039 0.18605706, + -0.149115 -0.97138202 0.184883, + -0.18545105 -0.97098625 0.15097603, + -0.24827194 -0.95718879 0.14883097, + -0.28346407 -0.95175827 0.11749203, + -0.35603487 -0.92743266 0.11448896, + -0.3869639 -0.91794276 0.087407276, + -0.46475512 -0.88145226 0.083932623, + -0.48754171 -0.87077147 0.063718364, + -0.56601834 -0.82219446 0.060163837, + -0.57890832 -0.81396341 0.048257824, + -0.65395516 -0.75520718 0.044774313, + -0.65751284 -0.75231183 0.041275088, + -0.72614509 -0.68650907 0.037664905, + -0.72282284 -0.68980384 0.04120319, + -0.78421915 -0.61938006 0.036996704, + -0.77618414 -0.62879807 0.046381503, + -0.83070803 -0.55519998 0.040952701, + -0.82017809 -0.56950104 0.054558508, + -0.86845589 -0.49350694 0.047278192, + -0.8568753 -0.51153719 0.063988224, + -0.8991757 -0.43420386 0.05431458, + -0.8882677 -0.45363286 0.072095878, + -0.9250651 -0.37510106 0.059614807, + -0.91502571 -0.39569986 0.078419767, + -0.94678509 -0.31572604 0.062570505, + -0.94073635 -0.33049312 0.076089531, + -0.96665162 -0.24956591 0.057457477, + -0.96651912 -0.24998903 0.057847507, + -0.98415387 -0.17275198 0.039974898, + -0.98383921 -0.17421505 0.041348413, + -0.99460465 -0.10093396 0.023955692, + -0.99442464 -0.10236096 0.025337191, + -0.99943411 -0.032651402 0.0080821505, + -0.999412 -0.0331861 0.00862101, + -0.99945098 0.0320687 -0.0083307298, + -0.99942821 0.032618608 -0.0089127021, + -0.99508178 0.095554478 -0.026109295, + -0.99486834 0.097230136 -0.027986409, + -0.98655885 0.15703098 -0.045199297, + -0.98595434 0.15981106 -0.048523918, + -0.97395939 0.21694307 -0.065871023, + -0.97273678 0.22081894 -0.070866682, + -0.95726264 0.27538592 -0.088378772, + -0.95550251 0.27953589 -0.094204955, + -0.93713778 0.33068591 -0.11144297, + -0.93554461 0.33362186 -0.11598594, + -0.91453612 0.38207304 -0.13283102, + -0.91179198 0.38611999 -0.13981, + -0.88817197 0.43206 -0.156444, + -0.88424802 0.436703 -0.165517, + -0.85809809 0.48015505 -0.18198602, + -0.852947 0.48501399 -0.192984, + -0.82467359 0.52553576 -0.20910689, + -0.81813312 0.53037608 -0.22217003, + -0.78790832 0.56797415 -0.23792009, + -0.7798745 0.57248467 -0.25309485, + -0.74757963 0.60745573 -0.26855588, + -0.73811483 0.61123788 -0.28561294, + -0.70383316 0.64357215 -0.30072206, + -0.70781833 0.64247727 -0.29362616, + -0.67739272 0.66905969 -0.30577484, + -0.69398379 0.66589582 -0.27380493, + -0.66304719 0.69233519 -0.28467605, + -0.67729008 0.69052309 -0.25388202, + -0.64501995 0.71722496 -0.26369998, + -0.65722382 0.71651185 -0.23381095, + -0.62346071 0.74328166 -0.24254689, + -0.63390476 0.74344873 -0.21318692, + -0.59895325 0.76976132 -0.22073208, + -0.60779673 0.77060664 -0.19169891, + -0.5714522 0.79636431 -0.19810708, + -0.57876801 0.79768699 -0.169479, + -0.54062301 0.82289702 -0.174835, + -0.54655397 0.82452589 -0.14640999, + -0.50644785 0.84898984 -0.15075397, + -0.51112014 0.85076118 -0.12231803, + -0.46964476 0.8738696 -0.12564094, + -0.47316793 0.87561488 -0.097008385, + -0.43037179 0.89716256 -0.099395558, + -0.43284392 0.89870977 -0.070475787, + -0.38857993 0.9185949 -0.072035089, + -0.39010215 0.91977733 -0.042779814, + -0.34432104 0.93783814 -0.043619804, + -0.34504512 0.93850833 -0.012084804, + -0.36111701 0.93238902 -0.0156617, + -0.36116108 0.93250322 0.00077717419, + -0.36122099 0.93247998 0.00077717402, + -0.36117688 0.93236566 -0.015668394, + -0.36116892 0.93236876 -0.015668396, + -0.361213 0.93248302 0.00077759102, + -0.40649399 0.91364402 -0.0041613402, + -0.40645009 0.91354525 -0.015283504, + -0.40644315 0.91354829 -0.015283505, + -0.43689793 0.89943886 -0.011402799, + -0.43603975 0.89893848 -0.042176273, + -0.48011607 0.87624115 -0.041111402, + -0.47837812 0.87540221 -0.069465011, + -0.52107894 0.85083389 -0.067515396, + -0.5183478 0.84983069 -0.095411859, + -0.55969304 0.82352614 -0.092458606, + -0.55590612 0.8225382 -0.11999703, + -0.59522402 0.79514301 -0.116, + -0.59031814 0.79434121 -0.14334103, + -0.62780219 0.76600116 -0.13822703, + -0.62170672 0.76555467 -0.16554992, + -0.65764803 0.73630601 -0.159225, + -0.65026474 0.73639178 -0.18676995, + -0.6848262 0.70634216 -0.17914805, + -0.67604619 0.70715517 -0.20710704, + -0.70890397 0.67687297 -0.19823797, + -0.69869834 0.67859328 -0.22656511, + -0.73010606 0.64816207 -0.21640503, + -0.71834618 0.65099621 -0.24532206, + -0.74878937 0.62023032 -0.23372811, + -0.73522305 0.62445009 -0.26364604, + -0.76530802 0.59297901 -0.250359, + -0.74973392 0.59886694 -0.28152698, + -0.77905202 0.56739098 -0.26673099, + -0.77473688 0.56941897 -0.27485397, + -0.80704713 0.53177804 -0.25668502, + -0.81420809 0.52739406 -0.24273603, + -0.84442931 0.48660117 -0.22396107, + -0.8501488 0.48199189 -0.21196896, + -0.87800431 0.43815416 -0.19269007, + -0.88231224 0.43370008 -0.18283704, + -0.90737867 0.38730386 -0.16327794, + -0.91045171 0.38327584 -0.15549093, + -0.9326731 0.33426303 -0.13560702, + -0.93477237 0.33077011 -0.12958305, + -0.95403612 0.27904204 -0.10931902, + -0.95527101 0.27639401 -0.105184, + -0.97152674 0.22143695 -0.08426968, + -0.97205937 0.21991308 -0.082090229, + -0.98491114 0.16213301 -0.060522009, + -0.98549378 0.15973096 -0.057341985, + -0.99444926 0.099029824 -0.035550907, + -0.99470365 0.09723106 -0.033326689, + -0.99938333 0.033218011 -0.011385804, + -0.9994095 0.032647215 -0.010719805, + -0.99936712 -0.033797104 0.011097401, + -0.99939185 -0.033253796 0.010493799, + -0.99400723 -0.10424702 0.032896906, + -0.99421853 -0.10272194 0.031267684, + -0.98268074 -0.17727596 0.053961489, + -0.98322111 -0.17497501 0.051575609, + -0.96457303 -0.253052 0.074589901, + -0.9654215 -0.25054413 0.072035939, + -0.93856913 -0.33165503 0.095356815, + -0.93914187 -0.33039597 0.094080187, + -0.90337211 -0.41246206 0.11744802, + -0.90240878 -0.41408792 0.11911997, + -0.85661787 -0.49584293 0.14263798, + -0.86880517 -0.47912711 0.12495903, + -0.81697482 -0.5580079 0.14553097, + -0.8351621 -0.53632808 0.12188701, + -0.77868211 -0.61181808 0.13904302, + -0.79570282 -0.59393489 0.11873697, + -0.73454195 -0.66539693 0.13302298, + -0.75036311 -0.65085006 0.11554001, + -0.68454432 -0.71774936 0.12741606, + -0.69629294 -0.70843893 0.11528399, + -0.62554318 -0.77006018 0.12531203, + -0.63179505 -0.7659111 0.11922801, + -0.55679011 -0.82076818 0.12776703, + -0.5553019 -0.82155985 0.12914798, + -0.47835594 -0.86751288 0.13637099, + -0.46836078 -0.87150156 0.14533792, + -0.3922199 -0.90734076 0.15131497, + -0.37405089 -0.91217571 0.16739593, + -0.30170503 -0.93774211 0.17208701, + -0.27750194 -0.94099474 0.19370496, + -0.2128129 -0.95702654 0.19700491, + -0.18669796 -0.95719779 0.22116993, + -0.13225998 -0.96576989 0.22314997, + -0.10735004 -0.96288735 0.24763709, + -0.064003207 -0.96649814 0.24856603, + -0.041869882 -0.96132851 0.27220288, + -0.0092158355 -0.9621315 0.27242988, + 0.0070568076 -0.95648265 0.29170388, + 0.029812707 -0.95608121 0.29158205, + 0.029815992 -0.95607978 0.29158595, + 0.047587879 -0.95542151 0.29138485, + 0.047471106 -0.95548213 0.29120502, + 0.060887106 -0.95478612 0.29099202, + 0.061519876 -0.95439762 0.29213089, + 0.070072025 -0.95385838 0.29196611, + 0.068062082 -0.95529479 0.28771394, + 0.072797664 -0.95497453 0.28761786, + 0.070544019 -0.95683634 0.28193608, + 0.071809292 -0.95674986 0.28190997, + 0.071794063 -0.95676452 0.28186384, + 0.062134821 -0.95738637 0.28204709, + 0.039080303 -0.9797141 0.19655304, + 0.033429597 -0.9799149 0.19659397, + -0.020027895 -0.99840873 -0.052715488, + -0.013859302 -0.9985131 -0.052721009, + -0.0563953 -0.94743401 -0.314942, + -0.038940717 -0.94822437 -0.31520513, + -0.068731189 -0.81363583 -0.57729787, + -0.040418584 -0.81489772 -0.57819384, + -0.054007191 -0.62295896 -0.78038788, + -0.017606704 -0.6237731 -0.78140718, + -0.020774895 -0.37643591 -0.92620975, + 0.020414108 -0.37643918 -0.92621642, + 0.022484193 -0.13188796 -0.99100965, + 0.020979507 -0.37912816 -0.92510635, + 0.062646024 -0.37846714 -0.92349237, + 0.053198691 -0.62213194 -0.7811029, + 0.089992493 -0.62048596 -0.77903688, + 0.067555301 -0.81249201 -0.579045, + 0.09644448 -0.81055582 -0.57766587, + 0.055462115 -0.94534826 -0.32131109, + 0.074342832 -0.94418538 -0.32091612, + 0.020084606 -0.99773526 -0.064195111, + 0.027525714 -0.99755847 -0.064183727, + -0.03668898 -0.9834345 0.17751192, + -0.041005012 -0.98326921 0.17748305, + -0.068807311 -0.96224123 0.26335806, + -0.077230036 -0.9616465 0.26319513, + -0.07741116 -0.96150255 0.26366687, + -0.0733466 -0.96179903 0.26374799, + -0.074501902 -0.96101499 0.26627001, + -0.066420518 -0.96156526 0.26642206, + -0.066606179 -0.96145666 0.26676691, + -0.053921383 -0.96219462 0.26697192, + -0.05122041 -0.96353024 0.26265207, + -0.032934703 -0.9642731 0.26285502, + -0.035076015 -0.96338248 0.26582712, + -0.012556194 -0.96389955 0.26596987, + 0.00021899493 -0.96813864 0.25041491, + 0.030898215 -0.96767646 0.25029513, + 0.051495198 -0.97233099 0.227861, + 0.092941754 -0.96940851 0.22717589, + 0.11606397 -0.97202677 0.20418896, + 0.16857699 -0.9646349 0.20263597, + 0.19895604 -0.96435922 0.17443605, + 0.26283097 -0.94943488 0.17173599, + 0.29294604 -0.94508612 0.14489602, + 0.36553091 -0.92004877 0.14105797, + 0.39000091 -0.91302574 0.11951297, + 0.467114 -0.87671798 0.114761, + 0.48335311 -0.86966521 0.10026103, + 0.56109124 -0.82230741 0.094800942, + 0.568142 -0.818183 0.088267803, + 0.64322829 -0.76125735 0.082126535, + 0.642277 -0.76195902 0.083058797, + 0.71204203 -0.69800204 0.07608711, + 0.70483834 -0.70441735 0.083661035, + 0.76846951 -0.63542062 0.075466454, + 0.7575649 -0.64681393 0.087903991, + 0.81516701 -0.57394999 0.078001603, + 0.80202717 -0.58977914 0.094408222, + 0.8540023 -0.51372916 0.082234733, + 0.8402319 -0.53269094 0.10124598, + 0.88661557 -0.45437279 0.086360253, + 0.87248689 -0.47651893 0.10814998, + 0.91383833 -0.39600715 0.089877233, + 0.90465027 -0.41272616 0.10613704, + 0.93998301 -0.33046901 0.084983401, + 0.93972498 -0.331056 0.085550301, + 0.96608126 -0.25002506 0.064610414, + 0.96549863 -0.2518149 0.066344477, + 0.98366851 -0.17404991 0.045856178, + 0.98324102 -0.175951 0.047732402, + 0.99440587 -0.10194199 0.027654996, + 0.99422187 -0.10333298 0.029069996, + 0.99941379 -0.032957893 0.0092717884, + 0.99939197 -0.033461399 0.0098047704, + 0.99943227 0.032331806 -0.0094737718, + 0.99940854 0.032878485 -0.010081295, + 0.99491578 0.096285477 -0.029523293, + 0.99468774 0.097990975 -0.031530794, + 0.98609334 0.15820406 -0.05090582, + 0.98542202 0.16113199 -0.054588299, + 0.97300154 0.21859489 -0.07405556, + 0.97184277 0.22207195 -0.078776576, + 0.95588863 0.2768279 -0.09820006, + 0.95476514 0.27934504 -0.10193101, + 0.93595475 0.33078691 -0.12070097, + 0.93413001 0.33398199 -0.125925, + 0.91254956 0.38266981 -0.14428192, + 0.90972072 0.38660586 -0.15147294, + 0.88539755 0.4328008 -0.16957192, + 0.88141876 0.43721092 -0.17873895, + 0.85444009 0.48091406 -0.19660603, + 0.84906119 0.48562011 -0.20801005, + 0.81992388 0.52622992 -0.22540396, + 0.81298715 0.53091908 -0.23911703, + 0.78173786 0.56859893 -0.25608796, + 0.77314889 0.57289994 -0.27207798, + 0.739838 0.607732 -0.28862, + 0.74483293 0.60588396 -0.27951497, + 0.71453059 0.63526165 -0.29306781, + 0.7305522 0.63071716 -0.26170507, + 0.69994497 0.65966398 -0.273716, + 0.71372199 0.65665299 -0.243737, + 0.68232727 0.68535727 -0.25439113, + 0.69423926 0.68357122 -0.22530508, + 0.66155827 0.71220535 -0.23474312, + 0.67186177 0.71141678 -0.20612593, + 0.63759494 0.73993891 -0.21438996, + 0.64641804 0.73994708 -0.18607001, + 0.61095792 0.76776087 -0.19306397, + 0.61836475 0.76838368 -0.16495894, + 0.58145505 0.79545414 -0.17077102, + 0.58755422 0.79650128 -0.14270905, + 0.548787 0.82285899 -0.147431, + 0.55366963 0.82416052 -0.11920293, + 0.51285285 0.84963572 -0.12288696, + 0.51657581 0.8510167 -0.094445266, + 0.47433087 0.87497485 -0.09710408, + 0.47693512 0.87624127 -0.068806417, + 0.43340284 0.8984347 -0.070549078, + 0.39092395 0.92032689 -0.013296098, + 0.39014986 0.91973364 -0.043278184, + 0.43500894 0.89943087 -0.042322896, + 0.43645978 0.89962858 -0.013085893, + 0.43562716 0.89912128 -0.042544115, + 0.47961593 0.87649786 -0.041473597, + 0.48114994 0.87654287 -0.012936899, + 0.48027319 0.87612629 -0.041717313, + 0.5235672 0.85102028 -0.040521916, + 0.52513313 0.85092318 -0.012845103, + 0.52422804 0.85060114 -0.040776804, + 0.5666461 0.82301617 -0.039454412, + 0.56826597 0.82274598 -0.0127606, + 0.56734502 0.82252097 -0.039736301, + 0.60816211 0.79288816 -0.038304806, + 0.60634464 0.7926265 -0.063948266, + 0.64522129 0.76152134 -0.061438829, + 0.64241701 0.76138902 -0.087104499, + 0.67956519 0.72886115 -0.083383225, + 0.67573321 0.72902524 -0.10911804, + 0.71113402 0.69531101 -0.104072, + 0.70633036 0.69593638 -0.12949906, + 0.73962915 0.66165715 -0.12312003, + 0.73388016 0.66289616 -0.14828603, + 0.76531088 0.62813693 -0.14051099, + 0.7585997 0.63014877 -0.16564694, + 0.7886377 0.59465575 -0.15631694, + 0.78095186 0.59760696 -0.18160398, + 0.809865 0.56127298 -0.170562, + 0.80123073 0.56533283 -0.19603093, + 0.82888812 0.52854109 -0.18327302, + 0.81928003 0.53389198 -0.20914, + 0.84599769 0.49645483 -0.19447492, + 0.83530784 0.50335389 -0.22112393, + 0.86166871 0.46461582 -0.20410593, + 0.84973985 0.47340387 -0.23201494, + 0.87607175 0.4329769 -0.21220095, + 0.87155384 0.43689391 -0.22252594, + 0.89940625 0.38950109 -0.19838704, + 0.90320659 0.38537982 -0.18894491, + 0.92762214 0.33538002 -0.16443102, + 0.93007988 0.33191496 -0.15742898, + 0.95106989 0.27916598 -0.13240999, + 0.95256275 0.27640194 -0.12738197, + 0.97003245 0.22066911 -0.10169705, + 0.97047991 0.21683197 -0.10560598, + 0.95147073 0.27666995 -0.13474897, + 0.94984788 0.27952296 -0.14019999, + 0.92819089 0.33261096 -0.16682799, + 0.92548335 0.33620811 -0.17448406, + 0.90012324 0.38666508 -0.20067005, + 0.90410972 0.38245484 -0.19056192, + 0.87957656 0.4258258 -0.2121729, + 0.8898989 0.41656795 -0.18587899, + 0.86505485 0.45813689 -0.20442796, + 0.87450081 0.45070988 -0.17918995, + 0.8492673 0.49061117 -0.19505307, + 0.85791284 0.48469788 -0.17045096, + 0.83202714 0.52331907 -0.18403302, + 0.83991009 0.51868707 -0.15973401, + 0.81283927 0.55668819 -0.17143705, + 0.81995344 0.55316824 -0.14724608, + 0.79140687 0.59071994 -0.15724199, + 0.79769486 0.58818191 -0.13313499, + 0.7678358 0.6248399 -0.14143297, + 0.77329129 0.62312025 -0.11722604, + 0.74184304 0.65901303 -0.12397902, + 0.74645221 0.65796125 -0.099478737, + 0.71298796 0.69329697 -0.10482098, + 0.71670693 0.69277292 -0.079980396, + 0.6810112 0.72744119 -0.083982825, + 0.6837644 0.72730041 -0.059165034, + 0.6462577 0.76060665 -0.061874371, + 0.648063 0.76068503 -0.037050501, + 0.60884494 0.79234987 -0.038592797, + 0.60973388 0.79248685 -0.013755596, + 0.61366773 0.78946763 -0.012363194, + 0.61371464 0.78952754 0.00078709354, + 0.57413399 0.81875098 -0.0041251499, + 0.57407498 0.81866801 -0.0148535, + 0.57419717 0.8185823 -0.014852006, + 0.57425892 0.81867087 -0.0021583198, + 0.53340483 0.84585971 0.00088199071, + 0.53334081 0.84575868 -0.015483694, + 0.53336596 0.84574288 -0.015483499, + 0.53336406 0.84574413 -0.015483302, + 0.53342801 0.84584498 0.00088085898, + 0.49130005 0.87098414 -0.0032999006, + 0.49124011 0.87087917 -0.015895603, + 0.49121588 0.87089282 -0.015895797, + 0.49127612 0.87099916 -0.0028535007, + 0.44800207 0.89403212 0.00090074411, + 0.447943 0.893915 -0.016220501, + 0.4479818 0.89389557 -0.016220093, + 0.44794786 0.89391267 -0.016216895, + 0.44800684 0.89402968 0.00089896563, + 0.40356886 0.91494572 -0.0025678691, + 0.40351486 0.91482371 -0.016531995, + 0.40355909 0.91480422 -0.016531704, + 0.40361205 0.91492313 -0.0036278705, + 0.35822204 0.93363613 0.00085023814, + 0.35817096 0.93350488 -0.016800798, + 0.35814789 0.93351364 -0.016800994, + 0.34451181 0.93865752 -0.015283792, + 0.34383997 0.93800086 -0.043913297, + 0.38954991 0.91999775 -0.043070387, + 0.38805699 0.918836 -0.071779102, + 0.43245816 0.89891529 -0.070223026, + 0.43000007 0.89738411 -0.099003918, + 0.47291711 0.87579322 -0.096621923, + 0.46935713 0.87403816 -0.12554403, + 0.5108692 0.85092533 -0.12222405, + 0.50614315 0.84913731 -0.15094706, + 0.54623497 0.82470286 -0.14660299, + 0.54026198 0.823062 -0.175174, + 0.57839012 0.79788917 -0.16981705, + 0.57106489 0.79656285 -0.19842495, + 0.60740077 0.77083969 -0.19201693, + 0.59860873 0.76999873 -0.22083792, + 0.63357997 0.74369496 -0.21329397, + 0.62322903 0.74353403 -0.242369, + 0.6570527 0.71672761 -0.2336309, + 0.64501238 0.71744543 -0.26311815, + 0.67731702 0.69070601 -0.25331199, + 0.6632818 0.69252384 -0.28366894, + 0.6944592 0.66583818 -0.27273807, + 0.67804223 0.66900724 -0.30444711, + 0.70858705 0.64224803 -0.29227003, + 0.70380425 0.64356822 -0.30079812, + 0.73806894 0.61125493 -0.28569496, + 0.74779564 0.60736471 -0.26815987, + 0.7800442 0.57241511 -0.25272906, + 0.78812391 0.56786793 -0.23745897, + 0.81839269 0.53017384 -0.22169593, + 0.82487214 0.52537006 -0.20874003, + 0.85312903 0.484833 -0.192634, + 0.858181 0.48006201 -0.18184, + 0.88432175 0.4366059 -0.16537896, + 0.88809812 0.43213806 -0.15664801, + 0.91172814 0.38620305 -0.13999702, + 0.91436213 0.38232407 -0.13330501, + 0.93537575 0.3339389 -0.11643497, + 0.93712723 0.33071509 -0.11144603, + 0.95551902 0.27948701 -0.094183303, + 0.95735776 0.27514794 -0.088088877, + 0.97279334 0.22064307 -0.070639022, + 0.974033 0.21670499 -0.065563798, + 0.98599714 0.15961702 -0.048291907, + 0.98659962 0.15683994 -0.044970386, + 0.99488503 0.097100899 -0.0278416, + 0.99509412 0.095455714 -0.025998704, + 0.99942964 0.03258219 -0.0088741975, + 0.99945134 0.032061312 -0.0083229728, + 0.99941236 -0.033178013 0.0086128628, + 0.99943274 -0.032685094 0.0081160981, + 0.99441046 -0.10247205 0.025445012, + 0.99457479 -0.10117298 0.024187595, + 0.98374826 -0.17463204 0.041749511, + 0.98409766 -0.17301294 0.040229086, + 0.96638799 -0.25040799 0.058224998, + 0.96675134 -0.24924909 0.057157118, + 0.9409011 -0.33011302 0.075700611, + 0.94709849 -0.31493384 0.061813969, + 0.91552269 -0.39473486 0.077477068, + 0.92558676 -0.3739799 0.058551285, + 0.88905489 -0.45229095 0.07081189, + 0.89966023 -0.4333061 0.053454012, + 0.85753328 -0.51055819 0.062984124, + 0.86846185 -0.49350488 0.047191489, + 0.82018483 -0.56950086 0.054458588, + 0.83016312 -0.55596805 0.041577604, + 0.7754817 -0.62961179 0.047084883, + 0.78324789 -0.62054497 0.038034897, + 0.72163206 -0.69098008 0.042352103, + 0.72474492 -0.68790996 0.039047096, + 0.65587419 -0.75365716 0.04277901, + 0.65222698 -0.75660503 0.046356101, + 0.57699317 -0.8152203 0.049947418, + 0.56419688 -0.82332879 0.061739184, + 0.48566481 -0.87169772 0.065366179, + 0.46299222 -0.88223439 0.085444741, + 0.38513595 -0.91856188 0.088962995, + 0.35342696 -0.92815787 0.11667199, + 0.28111407 -0.95218122 0.11969103, + 0.24583408 -0.95746833 0.15106305, + 0.18337998 -0.97103089 0.15320198, + 0.15425992 -0.97141755 0.18042091, + 0.10324004 -0.97793233 0.18163106, + 0.075365297 -0.97484899 0.209737, + 0.036502492 -0.97697777 0.21019496, + 0.018451203 -0.97295213 0.23026903, + -0.010866503 -0.97306025 0.23029506, + -0.010470003 -0.97318226 0.22979707, + -0.034581512 -0.97265333 0.22967309, + -0.040682785 -0.97031164 0.2384119, + -0.058021974 -0.9694795 0.23820788, + -0.060106378 -0.96850163 0.24164391, + -0.072069891 -0.96773291 0.24145196, + -0.072412409 -0.96754313 0.24210903, + -0.079974569 -0.96698266 0.24196792, + -0.0810977 -0.96625298 0.244496, + -0.073686987 -0.96681076 0.24463694, + -0.041484803 -0.98625612 0.15993102, + -0.038435381 -0.98637652 0.15994993, + 0.037355095 -0.99627686 -0.077697992, + 0.028528396 -0.99656689 -0.07772059, + 0.094435699 -0.93955898 -0.329106, + 0.074280374 -0.94116962 -0.32966989, + 0.12652002 -0.8050102 -0.57961309, + 0.096045896 -0.80778003 -0.58160698, + 0.12708798 -0.61646795 -0.77705586, + 0.089722119 -0.61900014 -0.78024918, + 0.10541102 -0.37627006 -0.92049414, + 0.062488001 -0.377639 -0.92384201, + 0.066943973 -0.11880294 -0.99065852, + 0.070757195 -0.13945699 -0.98769689, + 0.071452588 -0.0089659085 -0.99740374, + 0.017807703 0.004526481 -0.99983126, + 0.017656699 -0.13005298 -0.99134988, + 0.021676205 -0.13004403 -0.99127126, + 0.021861689 0.0035988383 -0.99975455, + 0.0226468 0.00359884 -0.99973702, + 0.022448802 -0.13199502 -0.99099612, + 0.020938993 -0.13199896 -0.99102867, + 0.0211237 0.00312811 -0.99977201, + -0.027092787 -0.013141293 -0.99954653, + -0.026814491 -0.14354396 -0.98928064, + -0.024922106 -0.14355002 -0.98932922, + -0.075782232 -0.10331704 -0.99175733, + -0.076189391 0.0036114596 -0.99708688, + -0.075374387 0.0036114592 -0.99714875, + -0.07451427 -0.15067793 -0.98577064, + -0.075890571 -0.15066494 -0.98566765, + -0.076766528 0.0033966212 -0.99704337, + -0.12441798 -0.0099633392 -0.99217987, + -0.12295006 -0.15346408 -0.98047549, + -0.12389006 -0.15344907 -0.98035949, + -0.12536199 -0.0143715 -0.99200702, + -0.12836103 -0.012773503 -0.99164522, + 0.077207386 -0.013421497 -0.99692476, + 0.070451483 -0.016561097 -0.99737775, + 0.069772474 -0.13946596 -0.98776567, + 0.11903706 -0.10570105 -0.98724747, + 0.11970696 0.0030240088 -0.99280465, + 0.12193801 0.0030240505 -0.99253315, + 0.11907499 0.0032793996 -0.99287987, + 0.16856696 -0.0063595688 -0.98566973, + 0.166876 -0.14140099 -0.97578597, + 0.16657995 -0.14140695 -0.97583562, + 0.16823801 -0.019873302 -0.98554611, + 0.179187 -0.013383 -0.983724, + -0.60016102 -0.0155575 0.79972798, + -0.57469815 0.0013878505 0.81836432, + -0.5746941 0.0040753311 0.81835818, + -0.61091292 0.012061998 0.79160589, + -0.61080772 0.027430987 0.79130363, + -0.57226473 0.028411087 0.81957656, + -0.57221889 0.034717094 0.8193658, + -0.53615189 0.035733894 0.84336483, + -0.536134 0.033747599 0.843458, + -0.59318072 0.032185886 0.80442566, + -0.59345186 0.037917692 0.80397582, + -0.64768404 0.035893902 0.7610631, + -0.64764363 0.035422176 0.76111954, + -0.60683078 0.036951084 0.79397172, + -0.60632992 0.031123497 0.79460388, + -0.54965907 0.032696005 0.8347491, + -0.54940492 0.027521696 0.83510286, + -0.49210212 0.028673908 0.87006515, + -0.49198306 0.020212801 0.87037009, + -0.4397321 0.015678603 0.89799225, + -0.43978584 0.00021612292 0.8981027, + -0.44921607 0.00021593603 0.89342314, + -0.44915515 0.016449705 0.89330232, + -0.44832784 0.016458094 0.89371771, + -0.44838879 8.1961465e-005 0.89383858, + -0.42377084 -0.015796995 0.90563172, + -0.12836005 -0.013161205 0.99164033, + -0.22968695 -0.012921398 0.97317874, + -0.32857704 -0.012605802 0.9443931, + -0.3127681 -0.0037178008 0.94982225, + -0.312756 0.0094009601 0.94978702, + -0.31314498 0.0093995789 0.94965887, + -0.31306785 -0.024075389 0.94942552, + -0.35897213 0.0013704305 0.93334734, + -0.35895488 0.009785166 0.93330365, + -0.35844019 0.0097876042 0.93350142, + -0.35845712 0.0013088705 0.93354535, + -0.36085412 0.0013090004 0.93262136, + -0.36083701 0.0099362899 0.932576, + -0.40048286 0.013974295 0.91619772, + -0.40056714 0.019340107 0.91606331, + -0.45901206 0.018752502 0.88823211, + -0.45922011 0.023021005 0.88802421, + -0.51729727 0.022178311 0.8555184, + -0.51774484 0.027445491 0.85509473, + -0.56535989 0.026460994 0.8244198, + -0.56754816 0.050755817 0.8217743, + -0.61420304 0.048648007 0.78764713, + -0.61745608 0.08824341 0.78164011, + -0.66124272 0.084156163 0.74543667, + -0.66385823 0.12340105 0.73760724, + -0.70524085 0.11698297 0.6992498, + -0.70707518 0.15473104 0.6900022, + -0.74567509 0.14579701 0.65016305, + -0.74671882 0.18206495 0.63973683, + -0.7824558 0.17044996 0.59892386, + -0.78275615 0.19721004 0.59025514, + -0.74989867 0.20963989 0.62745768, + -0.74938583 0.17394996 0.63887584, + -0.71100402 0.184736 0.67848802, + -0.70970523 0.14714706 0.68896025, + -0.66854727 0.15532808 0.72726738, + -0.6664682 0.11627703 0.7364102, + -0.62286496 0.12201498 0.77275586, + -0.62004411 0.081492126 0.78032321, + -0.57358509 0.08508382 0.81471521, + -0.57018971 0.044320479 0.82031655, + -0.5224309 0.046001989 0.85143983, + -0.52031714 0.022214705 0.85368419, + -0.47125012 0.022943806 0.88170123, + -0.47085223 0.018100809 0.88202643, + -0.4119519 0.018695697 0.91101378, + -0.41177884 0.014979295 0.91116071, + -0.36392391 0.015310396 0.93130279, + -0.36389998 0.014767698 0.93132091, + -0.42283899 0.0143676 0.90609097, + -0.42317399 0.018672099 0.90585601, + -0.47379187 0.018148396 0.88044977, + -0.47579613 0.04143161 0.87857926, + -0.5250628 0.040089384 0.8501187, + -0.52848816 0.081512533 0.84501833, + -0.57634193 0.078465693 0.81343287, + -0.57932192 0.12023699 0.80618191, + -0.62562764 0.11507693 0.77158755, + -0.62791002 0.15535501 0.76262301, + -0.67133093 0.14794399 0.72624195, + -0.67286742 0.1868061 0.71578842, + -0.71381974 0.17684793 0.67763275, + -0.71457005 0.21381703 0.66608703, + -0.75275731 0.20120408 0.62679625, + -0.7528348 0.22969994 0.61682886, + -0.72047925 0.24200809 0.64987826, + -0.72025526 0.2650201 0.64109021, + -0.68600094 0.27796796 0.67241096, + -0.68549007 0.30310902 0.66198808, + -0.64848667 0.31690684 0.69212365, + -0.64764506 0.34353802 0.68010104, + -0.60809511 0.35793108 0.7085942, + -0.60685432 0.38648519 0.69451934, + -0.56497794 0.40121493 0.72098994, + -0.56331104 0.43125707 0.70476806, + -0.51904297 0.44613394 0.72908092, + -0.51699305 0.47682205 0.71088606, + -0.47014523 0.49163923 0.73297638, + -0.46770895 0.52331495 0.71231294, + -0.41864607 0.53768307 0.73186904, + -0.41588995 0.56989092 0.70870292, + -0.36484483 0.58345968 0.72557765, + -0.36185712 0.61609024 0.69963723, + -0.30970094 0.6283828 0.71359682, + -0.30666798 0.66045094 0.68538994, + -0.25300691 0.67130876 0.69665778, + -0.25008997 0.70273596 0.66604596, + -0.19544391 0.71180266 0.6746397, + -0.19281307 0.74255925 0.64142722, + -0.13845798 0.74947095 0.64739692, + -0.13631 0.77914 0.61185002, + -0.081819981 0.78384382 0.6155439, + -0.080416992 0.81162387 0.57861894, + -0.026721699 0.81397003 0.58029199, + -0.026211008 0.8401953 0.54165018, + 0.026790706 0.84018219 0.54164213, + 0.027304497 0.8139379 0.58030993, + 0.080986604 0.81156713 0.57861906, + 0.082389027 0.7838273 0.61548924, + 0.13685803 0.77910119 0.61177713, + 0.13900499 0.74945092 0.64730293, + 0.19356096 0.74248582 0.64128685, + 0.19619703 0.71179408 0.67443007, + 0.25058398 0.70274293 0.66585296, + 0.25349692 0.67134279 0.69644678, + 0.30709288 0.66047674 0.68517476, + 0.31014588 0.62818378 0.71357876, + 0.36223987 0.61589074 0.69961476, + 0.3652232 0.58327937 0.72553241, + 0.41624299 0.569704 0.708646, + 0.4189758 0.53776175 0.73162264, + 0.46818694 0.52332991 0.71198791, + 0.47063223 0.49165624 0.73265237, + 0.51723486 0.47689688 0.7106598, + 0.51930392 0.44594294 0.72901195, + 0.56337315 0.43113008 0.7047962, + 0.56503505 0.40108407 0.72101808, + 0.60705626 0.38630116 0.69444525, + 0.60827696 0.35832298 0.70823991, + 0.64795297 0.34385601 0.67964703, + 0.64881265 0.31700182 0.69177461, + 0.68563503 0.30325302 0.66177207, + 0.68614721 0.27847409 0.67205226, + 0.72050798 0.26545301 0.64062703, + 0.72074616 0.24221505 0.6495052, + 0.75282919 0.22999106 0.61672711, + 0.75276601 0.20194601 0.62654698, + 0.71470064 0.2145669 0.66570568, + 0.71395779 0.17702994 0.67743975, + 0.6731838 0.18696296 0.71544981, + 0.67168492 0.14856899 0.72578692, + 0.62795097 0.15607199 0.76244289, + 0.62570995 0.11613698 0.77136189, + 0.57961184 0.12132295 0.80581069, + 0.5766902 0.079992533 0.81303728, + 0.52840424 0.08312884 0.84491342, + 0.52498114 0.04150781 0.85010117, + 0.47591689 0.042891689 0.87844378, + 0.47379681 0.018175794 0.88044667, + 0.4231762 0.018700309 0.9058544, + 0.42283899 0.0143657 0.90609097, + 0.36390087 0.014765695 0.93132067, + 0.36375412 0.011394204 0.93142533, + 0.30573693 0.011646397 0.95204479, + 0.305673 0.0073715001 0.95210803, + 0.25464001 0.00748685 0.96700698, + 0.25464106 0.0078028119 0.96700424, + 0.21959098 0.00046339995 0.9755919, + 0.2195901 0.0030685815 0.97558749, + 0.22031406 0.0030685707 0.97542423, + 0.21988192 0.0030621488 0.97552162, + 0.17188808 -0.017308008 0.98496449, + 0.17191395 -0.0005239009 0.98511177, + 0.17143199 -0.00052366394 0.98519588, + 0.17142595 -0.0078470977 0.98516577, + 0.123702 0.0032862399 0.99231398, + 0.12370305 8.6855631e-005 0.99231935, + 0.12213396 8.7155473e-005 0.99251366, + 0.12213299 0.0034259695 0.99250787, + 0.123465 0.00342598 0.99234301, + 0.12346597 2.2312595e-005 0.99234879, + 0.11594696 0.0018643494 0.99325365, + 0.11594897 0.0021708496 0.99325275, + 0.16803999 0.0021545098 0.98577785, + 0.16807204 0.0035645009 0.98576826, + 0.22387607 0.0035241612 0.97461134, + 0.22399493 0.0060212477 0.97457165, + 0.27611506 0.0059380615 0.96110624, + 0.27745607 0.028573509 0.96031338, + 0.3302649 0.028072292 0.94347078, + 0.33303508 0.071387514 0.94020826, + 0.38579193 0.069848396 0.91993791, + 0.388549 0.114343 0.91430598, + 0.44114912 0.11136503 0.89049727, + 0.4435862 0.15474507 0.88277143, + 0.49510783 0.15001394 0.85578269, + 0.49710888 0.19272195 0.8460148, + 0.54679799 0.185965 0.816351, + 0.54822385 0.22767293 0.80474579, + 0.59648108 0.21849804 0.77231413, + 0.59722304 0.25909102 0.75907612, + 0.6433478 0.24729994 0.72453183, + 0.64340806 0.28073102 0.71219105, + 0.60358965 0.29238182 0.74174958, + 0.60325813 0.32116109 0.73002416, + 0.56146979 0.33322188 0.75743967, + 0.56078118 0.3634901 0.74390823, + 0.51652402 0.375918 0.76934302, + 0.51544827 0.40783224 0.75364846, + 0.46879011 0.42039108 0.7768572, + 0.46735117 0.45314014 0.75910932, + 0.41816086 0.46559581 0.77997571, + 0.41635391 0.49976388 0.75952983, + 0.36567202 0.51160407 0.77752513, + 0.36360404 0.54598606 0.7547791, + 0.31120303 0.55699909 0.77000314, + 0.30900589 0.59116977 0.74500579, + 0.25500304 0.60104108 0.7574451, + 0.25275707 0.63564819 0.72942817, + 0.19796903 0.64397705 0.73898709, + 0.19589108 0.67778128 0.70868838, + 0.14080505 0.68428624 0.71549022, + 0.139084 0.71693599 0.68312401, + 0.083678395 0.72143394 0.68740892, + 0.082509123 0.75298619 0.65284318, + 0.028062291 0.7552647 0.65481877, + 0.02761119 0.7856217 0.61809075, + -0.027028397 0.78563386 0.61810094, + -0.027479904 0.7552591 0.65485007, + -0.081972674 0.75300169 0.65289277, + -0.083142824 0.72142518 0.68748319, + -0.13831602 0.71697307 0.68324107, + -0.14002804 0.68429923 0.71563023, + -0.19541296 0.67778492 0.70881695, + -0.19749303 0.64395905 0.73913008, + -0.25234997 0.63563794 0.72957796, + -0.25458303 0.60123807 0.75743014, + -0.30835804 0.59142709 0.74507004, + -0.31057999 0.55673701 0.77044398, + -0.36305708 0.54573715 0.7552222, + -0.3651 0.511572 0.77781498, + -0.41605586 0.49968681 0.75974369, + -0.41784507 0.46583506 0.78000212, + -0.46707389 0.45337489 0.75913984, + -0.46853566 0.42001972 0.77721149, + -0.51502615 0.40753016 0.75410032, + -0.51608115 0.37588716 0.76965529, + -0.56037587 0.36346692 0.74422485, + -0.56106186 0.3328329 0.75791281, + -0.602907 0.320786 0.730479, + -0.60322392 0.29193997 0.74222094, + -0.64309019 0.28030705 0.71264517, + -0.64301521 0.24715605 0.72487617, + -0.59685993 0.25893196 0.75941586, + -0.5960961 0.21810904 0.77272117, + -0.54823077 0.22718589 0.80487865, + -0.54678118 0.18530506 0.81651229, + -0.49684581 0.19206892 0.84631771, + -0.49483481 0.14951594 0.85602772, + -0.44329295 0.15422899 0.8830089, + -0.44084388 0.11082397 0.89071578, + -0.38821393 0.11378498 0.91451788, + -0.38543886 0.069016777 0.92014867, + -0.33266008 0.070536114 0.94040525, + -0.32991701 0.027579701 0.94360697, + -0.27742389 0.028068688 0.96033752, + -0.2761139 0.0059333476 0.96110666, + -0.223994 0.00601647 0.974572, + -0.16805305 0.0027441008 0.98577422, + -0.16807204 0.003564741 0.98576826, + -0.22387607 0.0035243912 0.97461134, + -0.21752296 0.0044797896 0.97604489, + -0.21755596 0.0055964086 0.97603178, + -0.27446905 0.0055135512 0.96158022, + -0.26641804 0.0065891407 0.96383512, + -0.2664749 0.0082428874 0.96380663, + -0.32413808 0.0080903918 0.94597524, + -0.3243551 0.011443303 0.94586623, + -0.37627181 0.011208294 0.92644161, + -0.37798086 0.033894788 0.92519265, + -0.430121 0.0330512 0.90216601, + -0.43336815 0.07560233 0.89804029, + -0.48402682 0.073407367 0.87196869, + -0.487041 0.116621 0.86555803, + -0.53674608 0.11266401 0.83618814, + -0.53925413 0.15486003 0.82778215, + -0.58718812 0.14884803 0.7956472, + -0.58908099 0.190072 0.785402, + -0.63516831 0.18167509 0.75070333, + -0.63633895 0.22137097 0.73896396, + -0.67966318 0.21049905 0.70267218, + -0.68007201 0.24908 0.68953699, + -0.71769863 0.23658088 0.65493369, + -0.71744883 0.20597996 0.66546184, + -0.67681092 0.21767397 0.70323896, + -0.67582893 0.17915398 0.71495396, + -0.63239682 0.18828996 0.75141281, + -0.63067627 0.14858808 0.76168835, + -0.58429497 0.155384 0.79652703, + -0.58188486 0.11430197 0.80519885, + -0.5338611 0.11884203 0.83717918, + -0.53083676 0.076308362 0.84403157, + -0.48133975 0.078924961 0.87297356, + -0.47797093 0.036908995 0.8775999, + -0.42756709 0.037985109 0.90318525, + -0.42564207 0.014337102 0.90477812, + -0.37414992 0.014693196 0.92725176, + -0.37388489 0.011015496 0.92740965, + -0.31523311 0.011271404 0.94894737, + -0.3151471 0.0091060223 0.94899923, + -0.26480201 0.0066351499 0.96428001, + -0.26480705 0.0024884306 0.96429825, + -0.267048 0.0024883801 0.96368003, + -0.26704288 0.0066650668 0.96366155, + -0.2657631 0.0066678124 0.96401536, + -0.26576799 0.0024167399 0.96403402, + -0.21826503 -0.020309802 0.97567815, + -0.21830803 0.0043649403 0.97587013, + -0.218483 0.0043647299 0.97583097, + -0.21848097 -0.005975639 0.97582287, + -0.17112106 0.0030476011 0.98524535, + -0.16970599 0.0030946196 0.9854899, + -0.16970593 0.0025138687 0.98549151, + -0.17112096 0.0025130594 0.98524678, + -0.16983795 0.0025254793 0.98546875, + -0.16983804 0.0030476006 0.98546726, + -0.12170202 -0.016708503 0.9924261, + -0.12171899 0.0011818699 0.9925639, + -0.12159994 0.0011818894 0.99257851, + -0.12159596 -0.0083419476 0.99254465, + -0.072574385 0.003526069 0.99735677, + -0.072574802 0.00032202399 0.99736297, + -0.11951195 0.0014493496 0.99283165, + -0.11952097 0.0019508295 0.99282974, + -0.17322604 0.0019352104 0.98488021, + -0.17329891 0.0038848482 0.98486155, + -0.22556703 0.0038428705 0.9742201, + -0.22663897 0.025464097 0.97364587, + -0.27928805 0.025104105 0.95987922, + -0.28170684 0.068397671 0.9570595, + -0.3346709 0.067173988 0.93993777, + -0.33718884 0.11194595 0.93475759, + -0.39071608 0.10945803 0.91398025, + -0.39304087 0.15333194 0.90664673, + -0.44603795 0.14924498 0.88248289, + -0.44804499 0.19275101 0.87298501, + -0.49962613 0.18676405 0.84586817, + -0.50114512 0.22962306 0.83434218, + -0.55110896 0.22141597 0.80452091, + -0.55199498 0.26290199 0.791318, + -0.60005111 0.25221905 0.75916016, + -0.600263 0.28742501 0.74637198, + -0.55830508 0.29814604 0.77421212, + -0.55808514 0.3286621 0.76192015, + -0.51375103 0.33981404 0.78777313, + -0.51316619 0.37212911 0.77342129, + -0.46672112 0.38345209 0.79695415, + -0.46576795 0.41673094 0.78063786, + -0.41666016 0.42810616 0.8019473, + -0.41533208 0.46307811 0.7829802, + -0.36431298 0.47407693 0.80157787, + -0.36271691 0.50915086 0.78051382, + -0.31043789 0.51936382 0.79617172, + -0.30863389 0.55489683 0.7725507, + -0.25483608 0.56411618 0.78538632, + -0.25295198 0.59979594 0.7591179, + -0.19807796 0.60767388 0.7690888, + -0.19627507 0.64294624 0.74033523, + -0.140581 0.649189 0.74752301, + -0.13906905 0.68354326 0.71653926, + -0.083527565 0.68783861 0.72104162, + -0.082490869 0.72093475 0.68807578, + -0.027593497 0.72312492 0.69016594, + -0.027194994 0.7550528 0.65509981, + 0.027753396 0.7550419 0.65508896, + 0.028151697 0.72313392 0.69013393, + 0.08300098 0.72092479 0.68802482, + 0.08404389 0.68760991 0.72119993, + 0.13955095 0.68329877 0.71667874, + 0.14105096 0.6492058 0.74741983, + 0.19673093 0.64294678 0.74021375, + 0.19853091 0.60771871 0.76893663, + 0.25359097 0.59979194 0.75890785, + 0.25548601 0.56411201 0.78517801, + 0.30900595 0.55492085 0.77238482, + 0.31080896 0.51942992 0.79598391, + 0.3632701 0.50916213 0.78024918, + 0.36487702 0.47406206 0.80133009, + 0.41584507 0.46305406 0.78272212, + 0.41717094 0.42842394 0.80151188, + 0.46601087 0.4170869 0.78030282, + 0.46697801 0.383522 0.79676998, + 0.5135982 0.37214211 0.77312827, + 0.51419091 0.33986497 0.7874639, + 0.55828893 0.32875898 0.76172888, + 0.55851394 0.29830298 0.77400088, + 0.60044289 0.28757694 0.74616879, + 0.60024595 0.25272796 0.75883687, + 0.55219406 0.26344004 0.79100013, + 0.55131209 0.22148003 0.80436414, + 0.50136608 0.22969303 0.83419013, + 0.49988323 0.1874321 0.84556842, + 0.44830212 0.19344604 0.8726992, + 0.44630885 0.14981294 0.88224971, + 0.3933461 0.15391703 0.90641522, + 0.3910329 0.11005697 0.91377276, + 0.33755285 0.11255895 0.93455261, + 0.33504811 0.068023026 0.93974239, + 0.28176609 0.069270723 0.95697933, + 0.27931896 0.025604596 0.95985687, + 0.22666606 0.025971906 0.97362626, + 0.22556703 0.0038454004 0.9742201, + 0.17329891 0.0038874082 0.98486155, + 0.17322604 0.0019351104 0.98488021, + 0.11952097 0.0019507295 0.99282974, + 0.11950599 0.0010833299 0.9928329, + 0.069034502 0.00073425 0.99761403, + 0.06903597 0.0010885495 0.99761355, + 0.022797801 -0.000410259 0.99974, + 0.022799101 0.00043490401 0.99974, + 0.071232475 0.00043391186 0.99745965, + 0.071235918 0.00076164718 0.99745923, + 0.12341499 0.0007577489 0.99235487, + 0.12345301 0.0021674903 0.99234813, + 0.17461799 0.0021506397 0.98463386, + 0.17546694 0.023759291 0.98419863, + 0.22830811 0.023496311 0.97330546, + 0.23037592 0.067444175 0.97076166, + 0.28354895 0.066463888 0.95665175, + 0.28576696 0.11138499 0.95180386, + 0.33954903 0.10932702 0.9342131, + 0.3416771 0.15357803 0.92718422, + 0.39560881 0.15008092 0.90607357, + 0.3975139 0.19416195 0.89681876, + 0.45087215 0.18887107 0.87237728, + 0.45237011 0.23202406 0.86111915, + 0.50403708 0.22470103 0.83394015, + 0.50500512 0.26760006 0.82058519, + 0.55502278 0.25790089 0.79084563, + 0.55533415 0.29374912 0.77802032, + 0.50843674 0.30415884 0.80559266, + 0.50803268 0.26206884 0.82050151, + 0.45603007 0.27077803 0.84777111, + 0.45502013 0.22739705 0.86095721, + 0.40152919 0.2338741 0.88548142, + 0.40006492 0.18990995 0.89659476, + 0.34568891 0.19443996 0.91798276, + 0.34392503 0.14999801 0.92693913, + 0.2896581 0.15289506 0.94483936, + 0.28776798 0.10832699 0.95155388, + 0.23374191 0.10997897 0.96605867, + 0.23188089 0.06520167 0.9705565, + 0.17848998 0.065952189 0.98172885, + 0.17684299 0.021788998 0.98399788, + 0.12473303 0.021965105 0.99194723, + 0.12414798 0.0012909799 0.9922629, + 0.073444836 0.0012975306 0.99729848, + 0.073425487 0.00010906497 0.99730074, + -0.024479909 -5.4849017e-005 0.99970037, + -0.022740507 -5.4840919e-005 0.99974138, + -0.022738298 -0.013895499 0.99964488, + -0.025736194 -0.012721797 0.99958777, + -0.02116769 -0.010335496 0.99972254, + -0.023914712 -0.011184006 0.99965149, + -0.023916196 -0.00021850297 0.9997139, + -0.021168899 -0.00021850897 0.99977589, + 0.0253751 2.17875e-005 0.99967802, + 0.025374889 0.0036021783 0.99967152, + 0.025635496 0.0036021795 0.9996649, + 0.025635704 -0.00075865909 0.9996711, + 0.025459386 -0.00075865863 0.99967551, + 0.025459206 0.003642071 0.99966925, + 0.073921196 -0.010392899 0.99720991, + 0.073925167 -0.00054869585 0.99726367, + 0.074661486 -0.00054872991 0.99720877, + 0.074654132 -0.014130205 0.99710935, + 0.077212773 -0.012937895 0.99693066, + 0.64049977 -0.015263194 -0.76780671, + 0.65118468 -0.0048747975 -0.75890362, + 0.64997584 -0.061097383 -0.75749481, + 0.68600631 -0.058793329 -0.72521633, + 0.68719226 0.0028012509 -0.72647023, + 0.6875 0.00280127 -0.726179, + 0.72249722 -0.018503608 -0.69112623, + 0.72136897 -0.058838591 -0.69004697, + 0.72102606 -0.058865607 -0.69040304, + 0.72225863 -0.0073876963 -0.69158363, + 0.75573486 0.0033967996 -0.65486896, + 0.75443012 -0.058837008 -0.65373808, + 0.75426614 -0.058850706 -0.65392607, + 0.75557113 0.0033589303 -0.65505809, + 0.75536633 0.003358931 -0.65529424, + 0.7863791 -0.014793701 -0.61756706, + 0.78520215 -0.056647107 -0.61664307, + 0.78530979 -0.056637786 -0.61650687, + 0.78653318 -0.009995603 -0.61746711, + 0.81611013 0.0036205905 -0.57788503, + 0.8159765 0.0027201583 -0.57807863, + 0.8159743 0.0035541612 -0.5780772, + 0.81585139 0.0035541474 -0.57825059, + 0.81457818 -0.055959716 -0.57734811, + 0.82218319 -0.04080971 -0.56775814, + 0.81379086 -0.15033399 -0.56137693, + 0.84373313 -0.13885002 -0.51849306, + 0.82962215 -0.22986606 -0.50881112, + 0.85923982 -0.21061796 -0.46620488, + 0.84197873 -0.2891759 -0.45546585, + 0.8718093 -0.26255608 -0.41353714, + 0.84094381 -0.3685399 -0.39622191, + 0.87629998 -0.328114 -0.35275999, + 0.84241718 -0.42216608 -0.3348271, + 0.88178402 -0.369537 -0.29308599, + 0.88351101 -0.36465201 -0.294002, + 0.92081457 -0.30361086 -0.24478789, + 0.92818123 -0.27578005 -0.24985006, + 0.95359564 -0.22313492 -0.20215392, + 0.95735025 -0.20257704 -0.20601705, + 0.97645301 -0.151255 -0.153823, + 0.97690088 -0.14733799 -0.15477799, + 0.98735678 -0.10929198 -0.11481197, + 0.98725122 -0.11061403 -0.11445403, + 0.99406564 -0.07559707 -0.078221269, + 0.9940359 -0.07616239 -0.078051195, + 0.99802625 -0.043857511 -0.04494511, + 0.99797702 -0.045512799 -0.044390701, + 0.99979502 -0.0144952 -0.0141378, + 0.99978834 -0.015190406 -0.013879305, + 0.99980152 0.014708892 0.013439293, + 0.99979311 0.015577402 0.013082102, + 0.99820501 0.045862202 0.0385154, + 0.99811113 0.048959509 0.037111502, + 0.99498791 0.07968919 0.060404792, + 0.9946835 0.085385464 0.057568375, + 0.98997778 0.11709497 0.078947477, + 0.98927921 0.12577704 0.074208014, + 0.98285455 0.15880293 0.093693458, + 0.98151761 0.17065294 0.086606473, + 0.97330976 0.20464896 0.10385998, + 0.97099251 0.21992089 0.093852252, + 0.96075565 0.25513491 0.10887996, + 0.95706815 0.27366304 0.095546812, + 0.94452226 0.31009105 0.10826502, + 0.93887126 0.33207208 0.090823621, + 0.92368579 0.3695769 0.10108098, + 0.92394322 0.36941108 0.09931992, + 0.90314728 0.41460714 0.11147204, + 0.89946967 0.42489386 0.10207596, + 0.87848902 0.46454501 0.111602, + 0.87370783 0.47600788 0.10025598, + 0.8500827 0.51534283 0.10854096, + 0.84411681 0.52763289 0.095238179, + 0.81780261 0.5663467 0.10222594, + 0.81039768 0.5794518 0.086552173, + 0.7817958 0.6166929 0.092114776, + 0.77318388 0.62977695 0.074616194, + 0.74245405 0.66524404 0.078818411, + 0.73600465 0.6737507 0.066008069, + 0.70322484 0.70757979 0.069322385, + 0.69782609 0.71386606 0.058599409, + 0.66659993 0.74291694 0.060984194, + 0.65820009 0.75157011 0.043762103, + 0.62580097 0.77866387 0.045339696, + 0.40069515 0.91619933 -0.0047147418, + 0.44917378 0.89343256 -0.0045975777, + 0.45337993 0.89129388 0.0064649889, + 0.49319687 0.8698948 0.0063097687, + 0.49734694 0.86739486 0.016498398, + 0.53668082 0.8436327 0.016046394, + 0.54066998 0.840855 0.025276899, + 0.57875806 0.81513113 0.024503604, + 0.58249921 0.81217128 0.032748513, + 0.61936593 0.7844649 0.031631295, + 0.62046289 0.78403282 0.017846096, + 0.57951188 0.81475282 0.018545296, + 0.57571387 0.81758779 0.010189397, + 0.53764492 0.84310585 0.010507399, + 0.5336172 0.8457253 0.0012072105, + 0.49433795 0.86926889 0.0012408199, + 0.49016669 0.87158245 -0.0089731943, + 0.45045215 0.8927533 -0.0091911741, + 0.44617301 0.894714 -0.020410599, + 0.40612495 0.91357988 -0.020840999, + 0.39896807 0.91604412 -0.041081604, + 0.36122897 0.93154091 -0.041776497, + 0.35171613 0.93337637 -0.071445122, + 0.3135131 0.94681424 -0.072473712, + 0.30467713 0.94684935 -0.10319003, + 0.26668891 0.95810962 -0.10441697, + 0.25870395 0.95634079 -0.13595797, + 0.22112507 0.96553725 -0.13726503, + 0.21412508 0.96198833 -0.16949606, + 0.17668507 0.96933633 -0.17079106, + 0.17076601 0.96403211 -0.20366903, + 0.13372901 0.9696151 -0.20484903, + 0.12904105 0.96265638 -0.23799409, + 0.092682645 0.96659446 -0.23896712, + 0.089278623 0.95807326 -0.27225906, + 0.053949274 0.96051353 -0.27295288, + 0.051879101 0.95050102 -0.30636001, + 0.017510597 0.95163679 -0.30672595, + 0.016817803 0.94026309 -0.34003302, + -0.016748106 0.94026434 -0.34003311, + -0.017439695 0.95163167 -0.30674589, + -0.05173678 0.95050162 -0.30638188, + -0.053804282 0.96050966 -0.27299491, + -0.089134745 0.95807445 -0.27230212, + -0.092539772 0.96660262 -0.23898891, + -0.12883006 0.96267849 -0.23801912, + -0.13353203 0.96965921 -0.20476905, + -0.17064701 0.96407014 -0.20358904, + -0.17658302 0.96938813 -0.17060201, + -0.2140709 0.96203351 -0.16930793, + -0.22102894 0.96555978 -0.13726097, + -0.25859702 0.95637012 -0.13595502, + -0.26654902 0.95813012 -0.10458702, + -0.30450296 0.9468869 -0.10335898, + -0.31332514 0.9468565 -0.072733738, + -0.34816197 0.93468088 -0.071798392, + -0.65013117 0.75966418 -0.015488704, + -0.61046201 0.79188102 -0.016145499, + -0.60677892 0.79451185 -0.023878196, + -0.5698871 0.82135218 -0.024684906, + -0.56590718 0.82379329 -0.033372011, + -0.5279448 0.84858268 -0.034376189, + -0.52373809 0.8507421 -0.044005305, + -0.48470494 0.87350988 -0.045182995, + -0.48035076 0.87530357 -0.055737674, + -0.44107911 0.89565426 -0.057033613, + -0.43667886 0.89700872 -0.06846118, + -0.39708686 0.91511971 -0.069843374, + -0.39273292 0.91598177 -0.082086578, + -0.35283908 0.93194926 -0.083517626, + -0.34588498 0.93239391 -0.10490599, + -0.30824897 0.94534087 -0.10636298, + -0.29938513 0.94426036 -0.13689804, + -0.26197696 0.95508885 -0.13846798, + -0.25400198 0.95220488 -0.16967298, + -0.21686999 0.96106201 -0.171252, + -0.20977597 0.9563179 -0.20359297, + -0.17294005 0.96334326 -0.20508905, + -0.16698796 0.95685077 -0.23780595, + -0.13061506 0.96216345 -0.23912612, + -0.12591694 0.95402753 -0.27198589, + -0.090389505 0.95774513 -0.27304602, + -0.086980842 0.94804949 -0.30600116, + -0.052371908 0.95035011 -0.30674404, + -0.050287608 0.93917513 -0.33973703, + -0.016902598 0.94023091 -0.34011796, + -0.0162053 0.92776299 -0.37281799, + 0.016239706 0.92776233 -0.37281811, + 0.016937802 0.9402371 -0.34009904, + 0.050359793 0.93917888 -0.33971596, + 0.05244742 0.95036536 -0.30668411, + 0.087088719 0.94805926 -0.30594006, + 0.0904985 0.957753 -0.272982, + 0.12599798 0.95403475 -0.27192295, + 0.13071297 0.96217376 -0.23903094, + 0.16708802 0.95685714 -0.23771003, + 0.173024 0.96331602 -0.205146, + 0.20989503 0.95628011 -0.20364803, + 0.21695608 0.96100533 -0.17146106, + 0.25397906 0.95217323 -0.16988504, + 0.26201987 0.95508355 -0.13842294, + 0.29945797 0.94424391 -0.13685198, + 0.30836889 0.94532561 -0.10615096, + 0.34603879 0.93236047 -0.10469494, + 0.35567898 0.93160188 -0.074902795, + 0.39301714 0.91657329 -0.073694527, + 0.40315109 0.91402227 -0.045083612, + 0.44006285 0.89687669 -0.044237886, + 0.43683192 0.89861178 -0.040923089, + 0.48389113 0.87422216 -0.039812412, + 0.48818782 0.87224472 -0.029357089, + 0.52730697 0.84919399 -0.028581301, + 0.53144187 0.84687984 -0.019082796, + 0.56944788 0.82181883 -0.018518096, + 0.57124507 0.82012212 -0.032844905, + 0.52826172 0.84840155 -0.033977482, + 0.52405101 0.85056901 -0.043622401, + 0.48502913 0.8733502 -0.044790812, + 0.48067188 0.87515074 -0.055369284, + 0.44132689 0.89555573 -0.056660283, + 0.4337641 0.89779824 -0.076204218, + 0.39721686 0.9144367 -0.077616371, + 0.38695091 0.91593975 -0.10641098, + 0.35002887 0.93048066 -0.10809996, + 0.34031686 0.9301486 -0.13786994, + 0.30311298 0.94265586 -0.13972299, + 0.29414186 0.94046152 -0.17033093, + 0.25717992 0.95089364 -0.17221995, + 0.249071 0.94683802 -0.203621, + 0.21252607 0.95531434 -0.20544407, + 0.20541592 0.94943166 -0.23745291, + 0.16928498 0.95611787 -0.23912597, + 0.16332693 0.94849366 -0.2714479, + 0.12758493 0.95354652 -0.27289388, + 0.12285796 0.94426364 -0.30540487, + 0.088111907 0.94777113 -0.30653903, + 0.084670231 0.93686134 -0.33929613, + 0.050996911 0.93901426 -0.34007609, + 0.04891922 0.92674237 -0.37249911, + 0.016383093 0.92772859 -0.37289581, + 0.016352903 0.92716223 -0.3743031, + -0.016315892 0.92716259 -0.37430382, + -0.016346093 0.92772961 -0.37289482, + -0.048885509 0.92674422 -0.37249908, + -0.050960191 0.93900174 -0.3401159, + -0.084634967 0.93684965 -0.33933687, + -0.088070333 0.94774234 -0.30664012, + -0.12270802 0.94424909 -0.30551004, + -0.12744503 0.95355725 -0.27292207, + -0.16306502 0.94852912 -0.27148202, + -0.16903998 0.9561609 -0.23912697, + -0.20525795 0.94946575 -0.23745294, + -0.21238193 0.95536166 -0.20537293, + -0.24896502 0.94688112 -0.20355003, + -0.25712389 0.95095754 -0.17195091, + -0.29412907 0.94051427 -0.17006205, + -0.30301306 0.94268423 -0.13974804, + -0.34029484 0.93015361 -0.13788994, + -0.34992397 0.93049085 -0.10835098, + -0.38674101 0.915999 -0.106664, + -0.39411184 0.91501772 -0.086129971, + -0.433516 0.89718002 -0.084450997, + -0.43795812 0.89603025 -0.072956018, + -0.47708789 0.87595677 -0.071321584, + -0.4814887 0.87434846 -0.060689963, + -0.5204398 0.85184872 -0.059128176, + -0.52469885 0.8498528 -0.04941019, + -0.56260568 0.82533157 -0.047984477, + -0.56665468 0.82302356 -0.039173681, + -0.60353893 0.7964319 -0.037907995, + -0.60729164 0.7939105 -0.030051081, + -0.64339864 0.76498353 -0.028956084, + -0.6500513 0.75973535 -0.015350208, + -0.68169773 0.73148465 -0.014779393, + -0.69106817 0.72277915 0.003900961, + -0.69082481 0.72300881 0.004388799, + -0.6529302 0.75740421 0.0045975908, + -0.64960974 0.76026469 -0.0021820592, + -0.6135903 0.78962135 -0.0022663111, + -0.60994697 0.79237986 -0.0099360291, + -0.57305998 0.81944901 -0.0102755, + -0.569139 0.822025 -0.018858399, + -0.53112364 0.84707141 -0.019432986, + -0.52698308 0.84938312 -0.028936304, + -0.48788807 0.8724001 -0.029720403, + -0.48357013 0.87438118 -0.04021721, + -0.44415089 0.89500576 -0.041165888, + -0.43979821 0.89656043 -0.052507427, + -0.40005684 0.91492271 -0.05358278, + -0.39572304 0.91600811 -0.06582091, + -0.35297698 0.93322587 -0.067058094, + -0.35835803 0.93222612 -0.050339509, + -0.39866191 0.91576374 -0.049450491, + -0.40294594 0.91446286 -0.037312295, + -0.44285214 0.89584929 -0.036552817, + -0.44714913 0.89410126 -0.025314106, + -0.48675093 0.87319088 -0.024722096, + -0.49100211 0.87104017 -0.014352203, + -0.53016287 0.84778082 -0.013968896, + -0.5342657 0.84530455 -0.0045246272, + -0.57230687 0.82002783 -0.0043893289, + -0.57617283 0.81731772 0.0040874388, + -0.61307377 0.7900157 0.0039508985, + -0.61668497 0.78712499 0.0115734, + -0.65265793 0.75757086 0.011138899, + -0.65591121 0.75462818 0.017798504, + -0.69080198 0.72284299 0.0170488, + -0.69662893 0.71685392 0.028784595, + -0.72650105 0.68661207 0.027570203, + -0.73415375 0.67764175 0.042660084, + -0.76235938 0.64587528 0.040660318, + -0.7669149 0.63983595 0.049511492, + -0.79668301 0.60259598 0.046629801, + -0.80120009 0.59581208 0.055555809, + -0.82914019 0.55662614 0.051902011, + -0.83583784 0.5450359 0.065657787, + -0.86113632 0.50472516 0.060801722, + -0.86685669 0.49314183 0.073284172, + -0.88945103 0.452066 0.06718, + -0.89390498 0.44148099 0.077643298, + -0.91398412 0.39961705 0.070280708, + -0.91738063 0.39009386 0.07899037, + -0.9350121 0.34756202 0.07037811, + -0.93953955 0.33209985 0.08351656, + -0.93967986 0.33199796 0.082335696, + -0.92103422 0.37803009 0.09375152, + -0.91794926 0.38737109 0.085515819, + -0.89862591 0.42840093 0.094573386, + -0.894548 0.43889299 0.084598199, + -0.87276816 0.47931212 0.092389122, + -0.86755699 0.49077201 0.080546498, + -0.8431254 0.53061825 0.087086245, + -0.83659202 0.54292297 0.073133498, + -0.80946529 0.58191216 0.078385532, + -0.801952 0.59404403 0.063124798, + -0.77261972 0.63131475 0.067085281, + -0.76739913 0.63865006 0.056787107, + -0.73623621 0.67406523 0.059936222, + -0.73113406 0.68040305 0.049946409, + -0.70142984 0.7108258 0.05217969, + -0.69323337 0.71982539 0.035763919, + -0.66184402 0.74871802 0.0371994, + -0.65563494 0.75468385 0.024395397, + -0.61972904 0.78440613 0.025356203, + -0.61616689 0.78741384 0.017826596, + -0.57926589 0.81492984 0.018449496, + -0.57542115 0.81779629 0.0099933539, + -0.53736681 0.84328568 0.010304797, + -0.53330785 0.84592068 0.00093598966, + -0.49404806 0.86943412 0.00096200709, + -0.48985711 0.87175316 -0.0092931818, + -0.45014411 0.89290524 -0.0095186718, + -0.4458662 0.89485943 -0.020737208, + -0.40581208 0.91371125 -0.021174006, + -0.40157309 0.91522425 -0.033221208, + -0.36103901 0.93193698 -0.033827901, + -0.35692188 0.93296665 -0.046689685, + -0.315896 0.94760799 -0.047422402, + -0.30951789 0.94834167 -0.069617979, + -0.27104697 0.95998287 -0.070472591, + -0.26312301 0.95935601 -0.101992, + -0.22498597 0.96890187 -0.10300699, + -0.21805704 0.9665311 -0.13516201, + -0.18011005 0.97416735 -0.13622904, + -0.17425896 0.97007877 -0.16905895, + -0.13642795 0.97594064 -0.17007995, + -0.13173205 0.97014338 -0.20363808, + -0.094736934 0.97427034 -0.20450507, + -0.09133631 0.9668951 -0.23826803, + -0.055141218 0.96947634 -0.23890409, + -0.053083092 0.96066791 -0.27257898, + -0.017836101 0.96187115 -0.27292103, + -0.017141793 0.9516905 -0.30657986, + 0.017247595 0.95168865 -0.30657989, + 0.017942706 0.96186435 -0.2729381, + 0.053325281 0.96065062 -0.2725929, + 0.055374581 0.96946865 -0.23888092, + 0.091476671 0.96688765 -0.23824391, + 0.094870239 0.97424537 -0.20456207, + 0.13189101 0.97011012 -0.20369403, + 0.13657604 0.97589433 -0.17022707, + 0.17429896 0.97004575 -0.16920696, + 0.18017602 0.97415411 -0.13623701, + 0.21815507 0.96650833 -0.13516705, + 0.22511707 0.96888733 -0.10285804, + 0.26328999 0.95932603 -0.101843, + 0.27123091 0.95994765 -0.070244476, + 0.30974597 0.94828385 -0.06939099, + 0.31851813 0.94712538 -0.038728915, + 0.3571761 0.93325722 -0.038161807, + 0.36654589 0.93035865 -0.0087642074, + 0.40469217 0.91441244 -0.0086139934, + 0.41171205 0.91124314 0.011368101, + 0.45208922 0.8919034 0.011126806, + 0.45626789 0.88956678 0.022146495, + 0.49620283 0.86793768 0.021607993, + 0.50030613 0.86526817 0.031697609, + 0.53970802 0.84128797 0.0308192, + 0.54363692 0.83836991 0.039933898, + 0.58175093 0.81244588 0.038699098, + 0.58843225 0.80677229 0.053535517, + 0.6218583 0.78141135 0.051852625, + 0.63062292 0.77288789 0.07042069, + 0.66292572 0.74559665 0.067934074, + 0.66878504 0.73915309 0.079870209, + 0.70323694 0.70684093 0.076378591, + 0.71034104 0.69798505 0.090732805, + 0.74279302 0.66393501 0.086306497, + 0.75210989 0.65055794 0.10538098, + 0.78220487 0.61500496 0.099621788, + 0.79033983 0.60142887 0.11681697, + 0.81822515 0.56435108 0.10961501, + 0.82493043 0.55137825 0.12438606, + 0.85051221 0.51306212 0.11574203, + 0.85601246 0.50072873 0.12850392, + 0.87891209 0.46201205 0.11856802, + 0.8832649 0.45068794 0.12931898, + 0.90354812 0.41186705 0.11818001, + 0.90696687 0.40151295 0.12727298, + 0.924914 0.362405 0.114877, + 0.92946488 0.34585997 0.12835899, + 0.94362777 0.31032595 0.11517097, + 0.94830197 0.289184 0.130752, + 0.9600541 0.25496402 0.11528002, + 0.96314234 0.23695809 0.12731004, + 0.97278237 0.20412508 0.10967004, + 0.97468865 0.18957493 0.11850496, + 0.98248512 0.15800901 0.098773412, + 0.98359078 0.14669096 0.10502798, + 0.98974437 0.11614905 0.083160132, + 0.99031538 0.10798503 0.087262027, + 0.99486262 0.078738667 0.063628078, + 0.99511313 0.073377207 0.066073209, + 0.99815738 0.045091115 0.040602714, + 0.99823201 0.042301401 0.0417541, + 0.99979621 0.014369803 0.014183904, + 0.99980289 0.013595698 0.014471798, + 0.99978966 -0.014043695 -0.014948694, + 0.99979538 -0.013381905 -0.015169405, + 0.99797875 -0.04203999 -0.047655489, + 0.99800235 -0.041179914 -0.047911119, + 0.99395835 -0.071543321 -0.083237633, + 0.994048 -0.069707602 -0.083722398, + 0.98719233 -0.10207903 -0.12260205, + 0.98698825 -0.10476802 -0.12197503, + 0.97404748 -0.14747907 -0.17170207, + 0.97233254 -0.16078992 -0.16945793, + 0.94949991 -0.21596897 -0.22761197, + 0.94904011 -0.21824703 -0.22735703, + 0.925286 -0.262647 -0.27361, + 0.93578875 -0.21590695 -0.27871794, + 0.91105425 -0.25248206 -0.32593408, + 0.92468941 -0.18554009 -0.33245215, + 0.90151411 -0.21089503 -0.37788305, + 0.91072112 -0.15533601 -0.38269806, + 0.88699526 -0.17367305 -0.4278751, + 0.89531887 -0.10595199 -0.43264094, + 0.87071884 -0.11697897 -0.47766587, + 0.87646925 0.00088254624 -0.48145711, + 0.86750782 -0.050476991 -0.49485588, + 0.86860985 0.0035659291 -0.49548388, + 0.86859381 0.0035659291 -0.49551189, + 0.86749071 -0.050516482 -0.49488181, + 0.86766142 -0.050499722 -0.49458423, + 0.8687641 0.0036193104 -0.49521306, + 0.84320509 -0.012866502 -0.53743804, + 0.84203291 -0.054251794 -0.53669095, + 0.84207588 -0.054247793 -0.53662395, + 0.8432591 -0.011790502 -0.53737807, + 0.84369683 -0.012174597 -0.53668189, + 0.89443868 -0.011573796 -0.44704086, + 0.891846 -0.0089352699 -0.45225099, + 0.89090031 -0.04688812 -0.45177215, + 0.8909061 -0.046887506 -0.45176107, + 0.89177102 -0.0161146 -0.4522, + 0.91301358 0.0031669587 -0.40791678, + 0.91214025 -0.04382981 -0.4075281, + 0.91211289 -0.043832798 -0.40758893, + 0.91298586 0.0031550096 -0.40797895, + 0.91309577 0.0031550394 -0.4077329, + 0.93194824 -0.0064523313 -0.36253408, + 0.93186367 -0.0063535278 -0.36275288, + 0.93109363 -0.041141186 -0.36245289, + 0.93117923 -0.04113121 -0.36223409, + 0.92033023 0.0073170117 -0.39107409, + 0.91704988 -0.086983494 -0.38916993, + 0.93638843 -0.076555535 -0.34251416, + 0.93208265 -0.12383095 -0.34042287, + 0.94990414 -0.10684001 -0.29371303, + 0.94579297 -0.14249 -0.291843, + 0.96199113 -0.11981201 -0.24539404, + 0.95705754 -0.15771693 -0.24324088, + 0.97250938 -0.12668805 -0.19538608, + 0.97003734 -0.14613506 -0.19409308, + 0.98285389 -0.11090598 -0.14730299, + 0.98307014 -0.10874902 -0.14746802, + 0.99282289 -0.070980392 -0.096251987, + 0.99314278 -0.065056086 -0.097134076, + 0.99790812 -0.035975005 -0.053713609, + 0.99792689 -0.035182297 -0.053890791, + 0.99979055 -0.011187894 -0.017137093, + 0.99978626 -0.011804903 -0.016977204, + 0.99979991 0.0114189 0.016422099, + 0.99979633 0.011952205 0.016264405, + 0.99823421 0.035175908 0.04786671, + 0.99818343 0.037638977 0.047042869, + 0.9951871 0.061220709 0.076516211, + 0.99502653 0.065771572 0.07480906, + 0.99062365 0.090207569 0.10260297, + 0.99025297 0.0973434 0.099616401, + 0.98440588 0.12294499 0.12581599, + 0.98366433 0.13326004 0.12102205, + 0.97638911 0.15991502 0.14522901, + 0.97510189 0.17332299 0.13833098, + 0.96622711 0.20140903 0.16074702, + 0.96412688 0.21816097 0.15121199, + 0.95347834 0.24776509 0.17173105, + 0.95138234 0.2611461 0.16332306, + 0.93773276 0.29450494 0.18418495, + 0.93615079 0.30287594 0.17857195, + 0.92054677 0.3364999 0.19839695, + 0.91838765 0.34633487 0.19135393, + 0.90066803 0.380319 0.21013001, + 0.8978467 0.39145884 0.20157193, + 0.87777829 0.42591816 0.21931508, + 0.87423742 0.4381012 0.2092281, + 0.85163981 0.47295889 0.22587495, + 0.84716833 0.48641217 0.21379708, + 0.82230711 0.52094305 0.22897503, + 0.81684721 0.53534114 0.21487305, + 0.78959918 0.56946415 0.22856906, + 0.78310019 0.58451313 0.21236405, + 0.7532118 0.61823887 0.22461694, + 0.74565083 0.63361579 0.20624195, + 0.71316218 0.66657621 0.21697004, + 0.70449018 0.68204618 0.19623104, + 0.66996074 0.71345478 0.20526792, + 0.66025585 0.72860283 0.18220896, + 0.62388498 0.75816798 0.189602, + 0.61326587 0.77261084 0.16424796, + 0.57511592 0.80018985 0.17011099, + 0.56381893 0.8134709 0.14273499, + 0.52392286 0.83894885 0.14720596, + 0.51499307 0.8480581 0.12481902, + 0.47449893 0.87087387 0.12817699, + 0.46770406 0.87699109 0.11018001, + 0.42944992 0.89604676 0.11257397, + 0.42344108 0.90091926 0.09509062, + 0.38143301 0.91929001 0.097029597, + 0.37770009 0.92200822 0.085108824, + 0.33492288 0.93825662 0.086608671, + 0.33029312 0.94127333 0.070078425, + 0.32522291 0.94339079 0.065145582, + 0.28836793 0.95524478 0.065964185, + 0.28075007 0.95914721 0.034872308, + 0.24030299 0.97005701 0.035269, + 0.23356906 0.97233522 0.0031246208, + 0.19308807 0.98117638 0.0031530312, + 0.18738101 0.98183215 -0.029901205, + 0.14694408 0.9886865 -0.030110015, + 0.14237303 0.98774421 -0.063963518, + 0.10255095 0.99264854 -0.064281069, + 0.099217959 0.99016351 -0.098651253, + 0.060125414 0.99327326 -0.098961122, + 0.058101773 0.98931855 -0.13368994, + 0.0196626 0.99080098 -0.133891, + 0.018982101 0.9854511 -0.16889602, + -0.01890911 0.98545247 -0.16889608, + -0.019589107 0.99080235 -0.13389204, + -0.058029722 0.98932236 -0.13369304, + -0.06005073 0.9932735 -0.099003948, + -0.099072374 0.99017376 -0.098694876, + -0.10239904 0.99265736 -0.064388521, + -0.14221697 0.98775977 -0.064070784, + -0.14678296 0.98870575 -0.030261492, + -0.18711698 0.98187786 -0.030052496, + -0.19282492 0.98122853 0.0030026587, + -0.23324297 0.9724139 0.0029756795, + -0.23997694 0.97014177 0.035158291, + -0.27615699 0.960482 0.0348083, + -0.5938561 0.80061215 0.079718821, + -0.55164301 0.82997602 0.0826426, + -0.54815984 0.83304667 0.074524768, + -0.50856489 0.85759884 0.076721184, + -0.50469613 0.86068219 0.067141518, + -0.46444401 0.88292003 0.068876296, + -0.46037179 0.88582557 0.058059674, + -0.41954991 0.90578878 0.059368186, + -0.4154681 0.90836126 0.04760471, + -0.37394908 0.92617822 0.048538413, + -0.36996099 0.92835402 0.0358845, + -0.32782903 0.94403213 0.036490504, + -0.32404584 0.94576055 0.023047689, + -0.28189209 0.95916134 0.023374308, + -0.27625993 0.96108276 0.00063249882, + -0.23635088 0.97166753 0.00063946471, + -0.22954603 0.9727841 -0.031619903, + -0.18974598 0.9813149 -0.031897195, + -0.1839781 0.98077649 -0.065035433, + -0.14434193 0.98735952 -0.065471873, + -0.13975796 0.98520565 -0.099184662, + -0.10061704 0.98992133 -0.099659637, + -0.097281434 0.98622537 -0.13377604, + -0.058847807 0.9892081 -0.13418001, + -0.056799125 0.98402047 -0.16875307, + -0.019082099 0.98543203 -0.16899601, + -0.018386992 0.97880763 -0.20395492, + 0.018532097 0.97880489 -0.20395496, + 0.019227402 0.98542213 -0.16903701, + 0.05693328 0.98400563 -0.16879395, + 0.058970399 0.98919702 -0.13420799, + 0.097348884 0.98621488 -0.13380398, + 0.100695 0.98992199 -0.099574097, + 0.13987593 0.98519754 -0.099098854, + 0.14446598 0.98734987 -0.065343395, + 0.18420509 0.98074245 -0.064906128, + 0.18997909 0.9812755 -0.031724315, + 0.22981103 0.97272712 -0.031447902, + 0.23661809 0.97160238 0.0008315923, + 0.27656311 0.9609955 0.00082251441, + 0.28424907 0.95821524 0.032032706, + 0.32429498 0.94542789 0.031605195, + 0.33042896 0.94232291 0.053330392, + 0.37277892 0.92643774 0.05243139, + 0.37672883 0.92404056 0.064995266, + 0.41842699 0.906012 0.0637272, + 0.42243901 0.90325701 0.075313397, + 0.46335912 0.88310623 0.073633216, + 0.46719205 0.88017315 0.083826207, + 0.50753492 0.85774988 0.081690595, + 0.5137248 0.8524437 0.09709046, + 0.55007112 0.82975316 0.094506122, + 0.55678183 0.82333767 0.11004096, + 0.59493011 0.79669321 0.10648002, + 0.60352468 0.78737265 0.12570694, + 0.64025098 0.75855899 0.121107, + 0.65113121 0.74496126 0.14512405, + 0.68627793 0.71391892 0.13907698, + 0.69617206 0.69958806 0.16100001, + 0.72955322 0.66650224 0.15338506, + 0.7383008 0.65189785 0.17303495, + 0.76914185 0.61768895 0.16395499, + 0.77669001 0.60321999 0.18132401, + 0.80498409 0.56818205 0.17079201, + 0.81137663 0.55413878 0.18600591, + 0.83731484 0.51830089 0.17397696, + 0.84259552 0.50500071 0.1871019, + 0.86625731 0.46847817 0.17357007, + 0.87053484 0.45609888 0.18477796, + 0.89156228 0.41975915 0.17005606, + 0.89489931 0.40863514 0.17936707, + 0.91347712 0.37257802 0.16354002, + 0.91605842 0.36262617 0.17128707, + 0.9324559 0.32667398 0.15430498, + 0.93437433 0.31805813 0.16057307, + 0.94870812 0.28222603 0.14248301, + 0.94840914 0.28919902 0.12993902, + 0.93234378 0.3298119 0.14818597, + 0.93024659 0.33851084 0.14160393, + 0.91337222 0.37558809 0.15711404, + 0.91054589 0.38563693 0.14896399, + 0.89147091 0.42264193 0.16325898, + 0.88778198 0.433956 0.15338001, + 0.86619061 0.47115076 0.16652593, + 0.8615464 0.48348624 0.15485108, + 0.8372888 0.52070588 0.16677195, + 0.8315599 0.53391695 0.15310399, + 0.80501586 0.57026994 0.16352898, + 0.79814368 0.58405179 0.14781794, + 0.76924711 0.61942106 0.15676902, + 0.76112831 0.63357526 0.13880305, + 0.72974676 0.66787773 0.14631794, + 0.72034407 0.68208003 0.12598102, + 0.68655884 0.71498084 0.13205796, + 0.67607409 0.72862607 0.10967202, + 0.64066267 0.75926954 0.11428493, + 0.63243717 0.76855719 0.096659921, + 0.59566307 0.79695612 0.10023201, + 0.58917189 0.8034218 0.085964374, + 0.554362 0.82755202 0.088546298, + 0.54824603 0.83301502 0.074244998, + 0.50869089 0.85754985 0.076431684, + 0.5049209 0.86055285 0.067109883, + 0.46466112 0.88280827 0.068845518, + 0.46062589 0.88568878 0.058130585, + 0.41982478 0.90565658 0.059441172, + 0.4157452 0.90823042 0.047681224, + 0.37423813 0.92605734 0.048617117, + 0.36908391 0.92883474 0.032296494, + 0.41305014 0.91015828 0.031647112, + 0.417144 0.907803 0.043412901, + 0.45783713 0.88802129 0.042466916, + 0.46193779 0.88530761 0.053327575, + 0.50207323 0.86326039 0.051999625, + 0.50607473 0.86026645 0.061886061, + 0.5455761 0.8359012 0.060133316, + 0.5492121 0.83286315 0.068593018, + 0.58735824 0.80659628 0.066429719, + 0.58905011 0.80638218 0.052609012, + 0.54653788 0.83565784 0.05451899, + 0.54267073 0.83871055 0.045533273, + 0.50321794 0.86288887 0.046845995, + 0.49916011 0.86572617 0.036843207, + 0.45912513 0.88756824 0.037772708, + 0.45498201 0.89009702 0.02681, + 0.41444695 0.90966088 0.027399296, + 0.41032192 0.91180778 0.015571896, + 0.36919808 0.92921525 0.015869204, + 0.36453703 0.93077111 0.027893804, + 0.32810989 0.94421566 0.02829669, + 0.31958699 0.94755501 -0.00192461, + 0.28003496 0.95998788 -0.0019498698, + 0.27226487 0.96164453 -0.033342086, + 0.23284897 0.97192889 -0.033698697, + 0.22597294 0.97188777 -0.066108987, + 0.186753 0.980142 -0.0666705, + 0.18095101 0.9784171 -0.099783815, + 0.141921 0.98477 -0.100432, + 0.13730705 0.98140937 -0.13409905, + 0.098827437 0.98594338 -0.13471805, + 0.095461838 0.98101133 -0.16883107, + 0.057826094 0.98386288 -0.16932198, + 0.055765994 0.97740591 -0.20388196, + 0.018899204 0.97875422 -0.20416404, + 0.018208995 0.97094476 -0.23860994, + -0.018029097 0.97094786 -0.23861097, + -0.018718198 0.97876185 -0.20414397, + -0.055657808 0.9774161 -0.20386302, + -0.057717472 0.98387355 -0.16929692, + -0.095493287 0.98101288 -0.16880399, + -0.098841578 0.98593879 -0.13474096, + -0.13723502 0.98141611 -0.13412301, + -0.141837 0.98477101 -0.10054, + -0.18079706 0.97843438 -0.099893138, + -0.18658909 0.98016149 -0.066843331, + -0.22580597 0.97191489 -0.066280894, + -0.23266989 0.97196352 -0.033933986, + -0.27201504 0.96170712 -0.033576004, + -0.27978808 0.96005934 -0.0021823607, + -0.31553096 0.94891286 -0.0021570297, + -0.62598932 0.77852434 0.045136921, + -0.5852887 0.80946565 0.046930779, + -0.58155704 0.81258512 0.038689002, + -0.54342192 0.83850986 0.039923295, + -0.53945196 0.84145588 0.030716496, + -0.50002795 0.86543286 0.031591795, + -0.49590304 0.8681131 0.021445202, + -0.45598578 0.88971561 0.021978788, + -0.45177922 0.89206344 0.010883906, + -0.41140205 0.91138613 0.011119701, + -0.4072428 0.91331959 -0.00077665265, + -0.36630812 0.93049335 -0.0007912583, + -0.36223218 0.93198842 -0.013614806, + -0.32076314 0.9470585 -0.013834907, + -0.31598088 0.94827062 -0.03064099, + -0.35959491 0.93262178 -0.030135293, + -0.36367902 0.93136311 -0.017329002, + -0.40442291 0.91441375 -0.017013697, + -0.40864208 0.91268122 -0.0049835914, + -0.44885188 0.89359277 -0.0048793592, + -0.45307413 0.89145124 0.0062184515, + -0.49289483 0.87006772 0.0060692779, + -0.49706012 0.86756319 0.016287904, + -0.53640121 0.84381443 0.015842108, + -0.54042178 0.84101856 0.025141289, + -0.57851303 0.81530899 0.024372799, + -0.58231115 0.81230628 0.03274541, + -0.61920899 0.78458899 0.031628098, + -0.62574095 0.77869987 0.045548696, + -0.65815276 0.75159973 0.043963484, + -0.66681504 0.74266106 0.061744306, + -0.69807696 0.71356094 0.059324991, + -0.70369709 0.70699203 0.07051751, + -0.73650074 0.67309678 0.067136675, + -0.74242204 0.66526806 0.078917608, + -0.77318865 0.62976068 0.074705459, + -0.78146487 0.61720395 0.091498293, + -0.81007189 0.57999194 0.085981689, + -0.81735414 0.56715006 0.10135601, + -0.84370542 0.52843422 0.094437547, + -0.84966117 0.51621914 0.10767402, + -0.87332273 0.47687882 0.099468261, + -0.87811571 0.46544182 0.11079996, + -0.89914227 0.42575908 0.10135302, + -0.90288532 0.41533616 0.11087804, + -0.9214974 0.37524319 0.10017505, + -0.92436665 0.36585587 0.10814697, + -0.94066685 0.32541198 0.096191585, + -0.94444287 0.31039998 0.10807198, + -0.9445675 0.31036285 0.10708395, + -0.92735773 0.3537139 0.12204097, + -0.92472923 0.3630161 0.11443503, + -0.90675056 0.40215883 0.12677394, + -0.90329188 0.41259193 0.11760799, + -0.88294649 0.45148975 0.12869492, + -0.87855029 0.46287718 0.11787304, + -0.85561514 0.50160408 0.12773502, + -0.85010201 0.51391202 0.114983, + -0.82450283 0.55220491 0.12355097, + -0.81778312 0.56515008 0.10879402, + -0.7898981 0.60218203 0.11592201, + -0.78187984 0.61551487 0.099021778, + -0.75175691 0.65106893 0.10474198, + -0.74276322 0.66396326 0.086345233, + -0.71031326 0.69800824 0.090772629, + -0.70372093 0.70624292 0.077445693, + -0.66923505 0.73862308 0.080996506, + -0.6631788 0.74530685 0.068640083, + -0.63082409 0.77265614 0.071158804, + -0.62491608 0.77849311 0.058553707, + -0.58803511 0.80655718 0.060664617, + -0.58453113 0.80964416 0.052911609, + -0.54637796 0.83575588 0.054617994, + -0.54245424 0.83885241 0.04549922, + -0.5029639 0.86303884 0.046811089, + -0.49887887 0.86589283 0.036734991, + -0.45884687 0.88771677 0.037660792, + -0.4546898 0.89025056 0.026667386, + -0.41414693 0.9098019 0.027253097, + -0.409998 0.91195703 0.0153618, + -0.36889181 0.92934048 0.01565459, + -0.36486199 0.93105698 0.0029360701, + -0.32075009 0.94715923 0.0029868507, + -0.32550016 0.94533545 0.01976651, + -0.36742792 0.92984879 0.019442696, + -0.37142187 0.92790961 0.032084487, + -0.41275585 0.91029769 0.031475488, + -0.416875 0.90793103 0.043317799, + -0.45754984 0.8881737 0.042375185, + -0.46167579 0.88544559 0.053306073, + -0.50181222 0.86341339 0.051979724, + -0.50584996 0.86039388 0.061952192, + -0.54541308 0.83600312 0.060195908, + -0.54913491 0.83289284 0.068851486, + -0.58727676 0.80663472 0.066680878, + -0.59343088 0.80086184 0.080375075, + -0.62691915 0.77519017 0.077798717, + -0.63335365 0.76844752 0.091387048, + -0.66900975 0.73805279 0.087772571, + -0.67620492 0.72951996 0.10270099, + -0.71041602 0.69691002 0.098109797, + -0.72004795 0.68379194 0.11815099, + -0.75195867 0.64958471 0.11223995, + -0.76061064 0.63593173 0.13062294, + -0.79014117 0.60039014 0.12332303, + -0.79756218 0.58686513 0.13958503, + -0.82478648 0.55009836 0.13084008, + -0.83100516 0.53702211 0.14504403, + -0.85592014 0.49922007 0.13483402, + -0.86102682 0.48681387 0.14712296, + -0.88325912 0.44883606 0.13564502, + -0.8873384 0.43736121 0.14610207, + -0.90704972 0.39933184 0.13339795, + -0.91022474 0.3889479 0.14216296, + -0.92762798 0.35080701 0.128222, + -0.92998457 0.34178585 0.13531893, + -0.94517052 0.30364487 0.12021794, + -0.94827634 0.2892431 0.13080704, + -0.94839466 0.2892589 0.12991096, + -0.93229675 0.32994592 0.14818397, + -0.93017435 0.33874112 0.14152804, + -0.91330177 0.37580192 0.15701196, + -0.91042376 0.38601592 0.14872897, + -0.89130068 0.42309484 0.16301493, + -0.8875379 0.43460295 0.15295999, + -0.86592269 0.47180882 0.16605493, + -0.86121428 0.48426917 0.15425105, + -0.83694184 0.52147686 0.16610296, + -0.83116072 0.53475183 0.15235594, + -0.80458283 0.57111287 0.16271596, + -0.79766518 0.58492315 0.14695303, + -0.76876134 0.6202603 0.15583107, + -0.76064301 0.63435102 0.137917, + -0.72928584 0.66858983 0.14536098, + -0.72001392 0.68254292 0.12535998, + -0.68621707 0.71543008 0.13140002, + -0.67605484 0.72863483 0.10973197, + -0.64061171 0.75930262 0.11435094, + -0.63288724 0.76804429 0.097784437, + -0.59606075 0.79650968 0.10140897, + -0.59226269 0.80035967 0.093001954, + -0.55402911 0.82693321 0.096089825, + -0.55067998 0.83003402 0.088289604, + -0.5110628 0.85472172 0.090915568, + -0.50742191 0.85779691 0.081899494, + -0.4670108 0.88024861 0.08404316, + -0.46312511 0.88322324 0.073702313, + -0.42216307 0.9033801 0.075384304, + -0.41812614 0.90615129 0.063720524, + -0.3764641 0.92414922 0.064986117, + -0.37248904 0.92655909 0.052347209, + -0.33011708 0.94243723 0.053244311, + -0.3263531 0.94440824 0.03983511, + -0.28181508 0.95861638 0.040434416, + -0.28597996 0.95651489 0.057399392, + -0.32865298 0.94275486 0.056573693, + -0.33240303 0.94053912 0.069961004, + -0.37502193 0.9244619 0.068765193, + -0.37894484 0.92184466 0.081260473, + -0.42077091 0.90366274 0.079657681, + -0.42464486 0.90078872 0.090864569, + -0.46571288 0.88046777 0.08881478, + -0.46943781 0.8774277 0.09873616, + -0.50990593 0.85483485 0.096193887, + -0.51336908 0.85174811 0.10477301, + -0.55308288 0.82689381 0.10171498, + -0.55714995 0.8229329 0.11119998, + -0.59534776 0.79623169 0.10759196, + -0.60347211 0.7874012 0.12578103, + -0.64020479 0.7585867 0.12117796, + -0.65078276 0.74538475 0.14451095, + -0.68593615 0.71436018 0.13849603, + -0.69574201 0.700203 0.160184, + -0.72908998 0.66718203 0.15263, + -0.73780376 0.65269077 0.17216393, + -0.76865691 0.61850595 0.16314699, + -0.7762081 0.60409307 0.18047902, + -0.80455583 0.56902486 0.17000195, + -0.81098187 0.55497092 0.18524499, + -0.83697212 0.51909107 0.17326902, + -0.84232211 0.50567305 0.18651602, + -0.8659907 0.46916282 0.17304994, + -0.87034369 0.45660785 0.18442094, + -0.89139199 0.42025 0.169736, + -0.89481121 0.40887609 0.17925805, + -0.91340613 0.37279603 0.16343902, + -0.91599923 0.36281008 0.17121404, + -0.93240666 0.32684487 0.15424094, + -0.93436724 0.31804308 0.16064404, + -0.94869167 0.28224191 0.14256096, + -0.9512679 0.26825196 0.15208599, + -0.96240014 0.23630004 0.13397102, + -0.96494174 0.21899894 0.14466096, + -0.97413498 0.188546 0.124545, + -0.97571689 0.17446099 0.13243799, + -0.98320538 0.14536305 0.11034904, + -0.98410785 0.13460499 0.11581598, + -0.99007034 0.10655904 0.09168423, + -0.99053645 0.098828241 0.095240146, + -0.99497879 0.072067387 0.069450885, + -0.99517936 0.067120224 0.071505219, + -0.99818325 0.041236512 0.043930512, + -0.99824375 0.038649894 0.044895489, + -0.99979746 0.013131007 0.015252908, + -0.99980265 0.012450895 0.015479594, + -0.99978936 -0.012865005 -0.015994405, + -0.99979275 -0.012429697 -0.016123196, + -0.99795187 -0.039056897 -0.050662491, + -0.99800497 -0.036911201 -0.051221501, + -0.99396086 -0.06415499 -0.089027591, + -0.99383551 -0.066898674 -0.088405453, + -0.98557621 -0.10211902 -0.13494903, + -0.98475367 -0.11155696 -0.13347396, + -0.96931612 -0.15764202 -0.18861403, + -0.96854913 -0.16283701 -0.18814003, + -0.95056474 -0.20321795 -0.23479594, + -0.9555611 -0.17502701 -0.23721004, + -0.93522465 -0.21021193 -0.2848959, + -0.94548148 -0.14919508 -0.28949216, + -0.92600298 -0.172943 -0.33557299, + -0.93317562 -0.11917996 -0.33908588, + -0.91260171 -0.13556996 -0.38571885, + -0.9184739 -0.071850196 -0.38889995, + -0.89682114 -0.080373108 -0.43503106, + -0.89896524 -0.038745008 -0.43630308, + -0.89414376 -0.00035940891 -0.44777989, + -0.8941381 0.0035968705 -0.44777706, + -0.8938874 0.0035968616 -0.44827721, + -0.89252412 -0.055329006 -0.44759306, + -0.89271969 -0.05529698 -0.44720685, + -0.89408171 0.0036680587 -0.44788885, + -0.87092602 -0.0113958 -0.49128199, + -0.86944783 -0.059342187 -0.49044788, + -0.86961627 -0.059316821 -0.49015218, + -0.87107301 -0.0133211 -0.490973, + -0.87021083 -0.012501597 -0.49252087, + -0.95252979 -0.014874596 0.30408195, + -0.96334773 0.0023932396 0.26824495, + -0.96334147 0.0043463819 0.26824313, + -0.96338552 0.0043386379 0.26808488, + -0.9633919 0.0024352898 0.26808596, + -0.96338302 0.00243529 0.26811799, + -0.97538924 -0.0038178109 0.22045706, + -0.97535688 -0.0037699896 0.22060098, + -0.97535938 0.0029808511 0.22060208, + -0.97861046 0.019742109 0.2047731, + -0.97815853 0.037289683 0.20448789, + -0.96755546 0.045326624 0.24856012, + -0.96656048 0.065902829 0.24782611, + -0.95512521 0.076121815 0.28625405, + -0.95539767 0.071059279 0.28664592, + -0.94538552 0.078429766 0.31637785, + -0.94562012 0.069822505 0.31769103, + -0.93492526 0.076170214 0.34657308, + -0.93491358 0.081911162 0.34529281, + -0.95019686 0.071933992 0.30323496, + -0.95018077 0.074678883 0.30262095, + -0.95955378 0.067449786 0.27332595, + -0.95930499 0.075425901 0.27211201, + -0.96811098 0.066918299 0.241419, + -0.96790302 0.070866004 0.241126, + -0.97759688 0.059350893 0.20194498, + -0.97844666 0.040098485 0.20256892, + -0.98691875 0.031305894 0.15814996, + -0.98727489 0.014140198 0.15839298, + -0.98476046 0.023916911 0.17226408, + -0.98504114 0.0014926703 0.17231302, + -0.98502165 0.0014926594 0.17242394, + -0.98502213 0.0012383402 0.17242402, + -0.98503977 0.0012325797 0.17232296, + -0.98503935 0.0015275106 0.17232306, + -0.97873914 -0.015531502 0.20452003, + -0.99457479 -0.015856896 0.10280798, + -0.99718326 0.00029500405 0.075003013, + -0.99718165 -0.0018072593 0.075002871, + -0.99717253 -0.0017992092 0.075123765, + -0.99717426 0.00023888606 0.075123914, + -0.9972015 0.00023889288 0.074760862, + -0.99714434 0.010706903 0.07475663, + -0.99965525 -0.0028920607 0.026099505, + -0.9996559 -0.0028940998 0.026070897, + -0.99966013 -0.00026882804 0.026071103, + -0.99965936 -0.00026653608 0.026099609, + -0.9992891 -0.029752905 -0.023152502, + -0.99772638 -0.0043849214 -0.067251824, + -0.99762887 -0.015178299 -0.067127891, + -0.99974477 -0.0049822987 -0.022034794, + -0.99973273 -0.0071096281 -0.021999195, + -0.99973577 0.0070683584 0.021871494, + -0.99972123 0.0090089515 0.021826105, + -0.99751288 0.026892297 0.065152094, + -0.99752522 0.026379406 0.065173618, + -0.94289166 0.15617993 0.29421589, + -0.95459467 0.13967995 0.26313192, + -0.95529366 0.12251796 0.26907891, + -0.96552813 0.10786501 0.23689803, + -0.96592921 0.094262324 0.24103005, + -0.97483164 0.081199668 0.20762892, + -0.97506911 0.069798805 0.21063803, + -0.98272491 0.058214292 0.17567798, + -0.98267847 0.060523529 0.17515709, + -0.98849136 0.049405817 0.14298205, + -0.98832715 0.054652907 0.14220601, + -0.99335563 0.041285686 0.10742496, + -0.99327946 0.043424621 0.10728605, + -0.99324387 0.041256197 0.10846399, + -0.99748635 0.025191909 0.066230625, + -0.99759567 0.019988092 0.066358678, + -0.99973565 0.0066314177 0.022015693, + -0.99974614 0.0046407706 0.022048902, + -0.999744 -0.0046601398 -0.022141, + -0.99974525 -0.0043862811 -0.022144005, + -0.99973178 -0.0031406393 -0.022947295, + -0.99972677 -0.0031570494 -0.023162594, + -0.99975026 0.0029030507 0.022160305, + -0.99974537 0.0043551913 0.022144508, + -0.99767262 0.013158095 0.066903874, + -0.99759173 0.018640095 0.066807382, + -0.99331814 0.031015905 0.11116301, + -0.99304247 0.039497919 0.11093505, + -0.98699635 0.053916018 0.15143105, + -0.98706549 0.052325074 0.15153793, + -0.9806655 0.06387037 0.18497491, + -0.98087889 0.057516094 0.18592599, + -0.97389954 0.067079671 0.21684089, + -0.97394198 0.064615302 0.217398, + -0.96472991 0.074998394 0.25233197, + -0.96450245 0.088833444 0.24868412, + -0.95399511 0.10085902 0.28234902, + -0.95357287 0.11752798 0.27728298, + -0.94172466 0.13127296 0.30971289, + -0.94128478 0.14440797 0.30517095, + -0.92678636 0.16065106 0.33949712, + -0.92643487 0.16888998 0.33644396, + -0.91023886 0.18577199 0.37007296, + -0.90975457 0.1955599 0.36620083, + -0.89158332 0.21332307 0.39946514, + -0.890917 0.22489101 0.394577, + -0.87068915 0.24354306 0.42730209, + -0.86977786 0.25707898 0.42118493, + -0.84759402 0.27646101 0.452939, + -0.84639812 0.29168704 0.44556606, + -0.82205915 0.31187105 0.47639811, + -0.8205002 0.32895708 0.46751112, + -0.79377681 0.34999692 0.49741387, + -0.79178488 0.36885998 0.48684594, + -0.76249886 0.39071393 0.51569194, + -0.7600047 0.41123885 0.50326484, + -0.72832525 0.43358415 0.5306102, + -0.72532016 0.45527312 0.5163691, + -0.69117075 0.47794381 0.54208183, + -0.687549 0.501086 0.52553701, + -0.65076894 0.52395391 0.54951996, + -0.646559 0.54797298 0.53074199, + -0.60677779 0.5709638 0.55301082, + -0.60198808 0.59562606 0.53182703, + -0.56003624 0.61797631 0.55178326, + -0.55470204 0.64303106 0.52803105, + -0.51063412 0.66447616 0.54564112, + -0.50482309 0.68965006 0.51916903, + -0.45852289 0.7099908 0.53448087, + -0.45245713 0.73456818 0.50566012, + -0.40416494 0.7534309 0.51864493, + -0.3980121 0.77714318 0.48747811, + -0.34864697 0.79397887 0.49803895, + -0.34254304 0.8167721 0.46427107, + -0.29248795 0.83134884 0.47255689, + -0.28673694 0.85265779 0.43675691, + -0.236296 0.86482602 0.44299001, + -0.23110506 0.88452524 0.4052231, + -0.18038405 0.89422327 0.40966615, + -0.17605101 0.91197199 0.37055799, + -0.12599401 0.9190591 0.37343803, + -0.12269503 0.93491125 0.33299708, + -0.07386373 0.93945533 0.33461612, + -0.071759775 0.95338464 0.29310089, + -0.023914995 0.95557576 0.29377395, + -0.023199795 0.96735078 0.25237694, + 0.023381792 0.96734667 0.2523759, + 0.024098296 0.95550686 0.29398298, + 0.071907617 0.95331025 0.29330707, + 0.073987491 0.9394049 0.33472997, + 0.12312502 0.9348191 0.33309704, + 0.12643805 0.91892934 0.37360713, + 0.17638806 0.91183931 0.37072411, + 0.18073399 0.89398998 0.41002101, + 0.2314869 0.8842696 0.40556282, + 0.23666593 0.86455482 0.44332188, + 0.28716102 0.85235614 0.43706706, + 0.29290605 0.83099616 0.47291812, + 0.343126 0.81634998 0.46458301, + 0.34914681 0.79383963 0.49791077, + 0.39848515 0.77698731 0.48734018, + 0.40465924 0.75317848 0.51862627, + 0.45289993 0.73431194 0.50563592, + 0.45895207 0.70976603 0.53441107, + 0.50520301 0.689426 0.51909697, + 0.51099396 0.66432697 0.54548591, + 0.55502009 0.64288217 0.52787811, + 0.56035018 0.61783826 0.55161917, + 0.60225815 0.59549314 0.53167009, + 0.60704106 0.57085907 0.55283004, + 0.64677221 0.54788113 0.53057712, + 0.65094525 0.52409118 0.54918015, + 0.68770283 0.50121689 0.52521086, + 0.69135708 0.47788507 0.54189605, + 0.72547764 0.45521981 0.51619476, + 0.72848165 0.43354079 0.53043073, + 0.76012897 0.41120601 0.50310397, + 0.76260167 0.39088285 0.51541179, + 0.79186732 0.36902311 0.48658818, + 0.79386419 0.35016209 0.49715811, + 0.82057256 0.32911384 0.4672738, + 0.82213616 0.31202707 0.47616312, + 0.84645391 0.29184097 0.44535893, + 0.8476541 0.27661103 0.45273507, + 0.86982387 0.25722298 0.42100194, + 0.8707211 0.24397103 0.42699307, + 0.89094198 0.225288 0.39429399, + 0.89160877 0.21382296 0.39914092, + 0.90976924 0.19602405 0.3659161, + 0.91026628 0.18608107 0.36985013, + 0.92778802 0.16769201 0.33329999, + 0.92700315 0.18354401 0.32707304, + 0.91094011 0.20188802 0.35976303, + 0.91034061 0.21160689 0.35567182, + 0.89225215 0.23087204 0.38805205, + 0.89142501 0.24251001 0.382819, + 0.87129813 0.26262403 0.41457006, + 0.87018681 0.27614695 0.40806592, + 0.84807402 0.29697099 0.43883801, + 0.84659618 0.31251609 0.43082309, + 0.8223784 0.33406916 0.46053421, + 0.82050812 0.35113803 0.45107505, + 0.79378819 0.3735961 0.47992313, + 0.79149789 0.39187795 0.46900195, + 0.76205385 0.41517991 0.49688989, + 0.75916111 0.43547806 0.48377007, + 0.72757715 0.45897713 0.50987411, + 0.72409081 0.48056087 0.49472588, + 0.68979859 0.50445771 0.51932669, + 0.6857236 0.52694869 0.50210369, + 0.64896315 0.55080914 0.5248391, + 0.64424294 0.57419592 0.50522292, + 0.60449189 0.59806287 0.52622288, + 0.59919697 0.621831 0.50427097, + 0.55714494 0.64498794 0.52304894, + 0.55122298 0.66931301 0.49816999, + 0.50736475 0.69127166 0.51451379, + 0.50109917 0.71503723 0.48746419, + 0.45492887 0.73580784 0.50162387, + 0.44837388 0.75909984 0.47194088, + 0.40039501 0.77820498 0.48381901, + 0.39382923 0.80036348 0.45201427, + 0.34486297 0.81731588 0.46158895, + 0.33830208 0.83869618 0.42677909, + 0.2889511 0.85322928 0.43417415, + 0.28287598 0.87274086 0.39787495, + 0.23290494 0.88488173 0.4034099, + 0.22745495 0.90272778 0.3651669, + 0.17756906 0.91229427 0.36903712, + 0.17302802 0.92815912 0.32951802, + 0.12394901 0.9351061 0.33198404, + 0.12049104 0.94904834 0.29118609, + 0.072498284 0.95349777 0.29255095, + 0.070354581 0.96529162 0.25151992, + 0.023627389 0.96741951 0.25207388, + 0.02287681 0.97734946 0.2103921, + -0.022731895 0.97735274 0.21039195, + -0.023483194 0.96743476 0.25202894, + -0.070139013 0.96531826 0.25147805, + -0.072281621 0.95355034 0.29243311, + -0.12021003 0.94911826 0.29107407, + -0.12365903 0.93524623 0.33169708, + -0.17258495 0.92833775 0.32924691, + -0.17714496 0.91239375 0.36899492, + -0.22698306 0.90285826 0.36513808, + -0.232408 0.88508803 0.40324399, + -0.282206 0.87301701 0.39774501, + -0.28829896 0.8534199 0.43423295, + -0.33784002 0.83885914 0.42682505, + -0.3443211 0.81775916 0.46120811, + -0.39328009 0.80083215 0.45166212, + -0.39994317 0.77837437 0.48392025, + -0.44795206 0.7592811 0.47205007, + -0.45449001 0.73606402 0.50164598, + -0.50068724 0.71530336 0.48749724, + -0.50697196 0.69148391 0.51461595, + -0.55102295 0.66944492 0.49821395, + -0.55692786 0.6452328 0.52297789, + -0.59887171 0.62214768 0.50426674, + -0.60421473 0.59818268 0.52640474, + -0.64400202 0.57431197 0.50539798, + -0.64873284 0.55087286 0.5250569, + -0.68563807 0.52693206 0.50223804, + -0.68971622 0.50443417 0.51945919, + -0.72383791 0.48067093 0.49498895, + -0.72734958 0.45889473 0.51027268, + -0.75907034 0.4353182 0.48405623, + -0.76193321 0.41520709 0.49705213, + -0.7913903 0.39190716 0.46915919, + -0.79370368 0.37341487 0.48020381, + -0.82044983 0.35095692 0.45132187, + -0.82231158 0.33391684 0.46076378, + -0.84654516 0.31236905 0.43103009, + -0.84802014 0.29681003 0.43905106, + -0.87014133 0.2759971 0.40826416, + -0.87125069 0.26245791 0.41477486, + -0.89143729 0.24230209 0.38292214, + -0.8922649 0.23061897 0.38817295, + -0.91031432 0.21141708 0.35585213, + -0.91092777 0.20140296 0.36006591, + -0.92702961 0.18305892 0.32726985, + -0.92746139 0.17494106 0.33047113, + -0.94296426 0.15574703 0.29421306, + -0.94224674 0.16963695 0.28878093, + -0.94362366 0.18063994 0.2773869, + -0.95515311 0.16159101 0.24813503, + -0.95616555 0.14385892 0.25505289, + -0.96621627 0.12661803 0.22448605, + -0.96682137 0.11243804 0.22937809, + -0.97550899 0.096815802 0.19750699, + -0.97585154 0.086067453 0.20076391, + -0.98327833 0.071754426 0.16737705, + -0.98348725 0.062760815 0.16974704, + -0.98965263 0.049758483 0.13457996, + -0.98961174 0.051734887 0.13413496, + -0.99413002 0.0389334 0.100944, + -0.99402511 0.042910505 0.10036401, + -0.9975729 0.027373297 0.064023696, + -0.99754113 0.028691404 0.063941211, + -0.99972349 0.0096271047 0.021454809, + -0.99972373 0.0095995385 0.021455895, + -0.99971461 -0.0097572459 -0.021808393, + -0.99973261 -0.0075382474 -0.021860393, + -0.99750578 -0.023010693 -0.066729486, + -0.99763399 -0.0160309 -0.066854, + -0.99330199 -0.026943101 -0.112362, + -0.99362314 -0.0051652105 -0.11263402, + -0.99250448 -0.018443009 -0.12080906, + -0.99266863 -0.0030732388 -0.12082896, + -0.99267924 -0.0030928208 -0.12074103, + -0.99251527 -0.018434804 -0.12072103, + -0.98559076 -0.0051629185 -0.16906896, + -0.98560154 0.0021237291 -0.16907093, + -0.98556024 0.0021237005 -0.16931204, + -0.9787451 -0.015125101 -0.20452203, + -0.98552126 0.0020443304 -0.16954005, + -0.98521179 -0.025137894 -0.16948695, + -0.97767478 -0.010330597 -0.20986995, + -0.97557062 -0.032611288 -0.21725193, + -0.97607636 -0.0052367421 -0.21736507, + -0.97602224 -0.0051556015 -0.21761005, + -0.97551554 -0.032627486 -0.2174969, + -0.96411586 0.015261198 -0.26504296, + -0.96422386 0.0029316195 -0.26507297, + -0.96425164 0.0029316188 -0.26497191, + -0.95253688 -0.014363798 -0.30408397, + -0.964261 0.00294053 -0.264938, + -0.96357638 -0.037790716 -0.26475009, + -0.95444697 -0.00059285498 -0.29837999, + -0.94919902 -0.042771898 -0.31175601, + -0.95004123 -0.0075976318 -0.31203207, + -0.94998038 -0.0075200428 -0.31221911, + -0.94913733 -0.042785317 -0.31194213, + -0.93359166 0.011347196 -0.35815889, + -0.93364638 0.0033985111 -0.35818011, + -0.93358886 0.0033985095 -0.35832998, + -0.9325099 -0.048182491 -0.35791597, + -0.93256766 -0.048171081 -0.35776687, + -0.9336459 0.0034300496 -0.35818097, + -0.9148643 -0.014466505 -0.40350214, + -0.9137339 -0.051750794 -0.40300393, + -0.91361487 -0.051772092 -0.40327093, + -0.91479522 -0.010130903 -0.4037911, + -0.9162659 -0.011756798 -0.40039793, + -0.99988055 -0.015458393 0, + -0.99973589 -0.0012792099 -0.022947399, + -0.99974602 -0.00131509 -0.0225005, + -0.99973714 -0.0044152206 -0.022500303, + -0.99737614 -0.0035449704 -0.072307907, + -0.99738175 0.0010912998 -0.072308287, + -0.99740964 0.0010912496 -0.071922176, + -0.99734336 -0.011587304 -0.071917422, + -0.99734426 -0.011586203 -0.071904615, + -0.99741054 0.0010972095 -0.071909361, + -0.99457777 -0.015670497 -0.10280798, + -0.4508118 0.8926186 0.0008744126, + -0.45076215 0.89252031 -0.014865106, + 0 -1 0, + 0.99842674 0.056072284 0, + 0.99842674 -0.056072284 0, + 0.9609201 0.27682602 0, + 0.98587126 0.16750504 0, + 0.9238739 0.38269693 0, + 0.66635692 0.74563295 0, + 0.74563295 0.66635692 0, + -0.99842674 0.056072284 0, + -0.98587126 0.16750504 0, + -0.9609201 0.27682602 0, + -0.9238739 0.38269693 0, + 0 0 -1, + -0.87522501 0.48371601 0, + -0.056072284 0.99842674 0, + -0.16750504 0.98587126 0, + -0.27682602 0.9609201 0, + -0.38269693 0.9238739 0, + 0.87522501 -0.48371601 0, + 0.81556481 -0.57866585 0, + 0.48371601 -0.87522501 0, + 0.57866585 -0.81556481 0, + 0.38269693 -0.9238739 0, + -0.27682602 -0.9609201 0, + -0.38269693 -0.9238739 0, + 0.66635692 -0.74563295 0, + 0.27682602 -0.9609201 0, + -0.16750504 -0.98587126 0, + -0.48371601 -0.87522501 0, + -0.57866585 -0.81556481 0, + 0.056072284 0.99842674 0, + -0.48371601 0.87522501 0, + -0.74563295 0.66635692 0, + -0.66635692 0.74563295 0, + -0.57866585 0.81556481 0, + 0.48371601 0.87522501 0, + 0.38269693 0.9238739 0, + 0.57866585 0.81556481 0, + 0.81556481 0.57866585 0, + 0.87522501 0.48371601 0, + -0.9238739 -0.38269693 0, + -0.9609201 -0.27682602 0, + 0.9609201 -0.27682602 0, + 0.9238739 -0.38269693 0, + 0.98587126 -0.16750504 0, + -0.98587126 -0.16750504 0, + -0.99842674 -0.056072284 0, + -0.81556481 0.57866585 0, + -0.66635692 -0.74563295 0, + -0.74563295 -0.66635692 0, + -0.81556481 -0.57866585 0, + -0.87522501 -0.48371601 0, + 0.74563295 -0.66635692 0, + 0.16750504 -0.98587126 0, + -0.056072284 -0.99842674 0, + 0.056072284 -0.99842674 0, + 0.16750504 0.98587126 0, + 0.27682602 0.9609201 0, + 0.024670089 0.00043713779 0.99969554, + -0.024670089 0.00043706279 0.99969554, + -0.0239159 0.000109491 0.99971402, + 0.021810694 0.99684078 -0.076372586, + 0.53740281 -0.84328872 0.0078913374, + -0.075101294 0.99717587 6.0073791e-005, + -0.075091295 0.99704289 -0.016333299, + 0.0239159 0.000109491 0.99971402 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 3, 4, -1, + 1, 4, 5, -1, 5, 6, 1, -1, + 6, 5, 7, -1, 7, 8, 6, -1, + 8, 7, 9, -1, 9, 10, 8, -1, + 10, 9, 11, -1, 11, 12, 10, -1, + 12, 11, 13, -1, 13, 14, 12, -1, + 14, 13, 15, -1, 15, 16, 14, -1, + 16, 15, 17, -1, 17, 18, 16, -1, + 18, 17, 19, -1, 19, 20, 18, -1, + 20, 19, 21, -1, 21, 22, 20, -1, + 22, 21, 23, -1, 23, 24, 22, -1, + 24, 23, 25, -1, 25, 26, 24, -1, + 26, 25, 27, -1, 27, 28, 26, -1, + 28, 27, 29, -1, 29, 30, 28, -1, + 30, 29, 31, -1, 31, 32, 30, -1, + 32, 31, 33, -1, 33, 34, 32, -1, + 34, 33, 35, -1, 35, 36, 34, -1, + 37, 38, 39, -1, 38, 37, 40, -1, + 40, 41, 38, -1, 41, 40, 42, -1, + 42, 43, 41, -1, 43, 42, 44, -1, + 44, 45, 43, -1, 45, 44, 46, -1, + 46, 47, 45, -1, 47, 46, 48, -1, + 48, 49, 47, -1, 49, 48, 50, -1, + 50, 51, 49, -1, 51, 50, 52, -1, + 52, 53, 51, -1, 53, 52, 54, -1, + 54, 55, 53, -1, 55, 54, 56, -1, + 56, 57, 55, -1, 57, 56, 58, -1, + 58, 59, 57, -1, 59, 58, 60, -1, + 60, 61, 59, -1, 61, 60, 62, -1, + 62, 63, 61, -1, 63, 62, 64, -1, + 64, 65, 63, -1, 65, 64, 66, -1, + 66, 67, 65, -1, 67, 66, 68, -1, + 68, 69, 67, -1, 69, 68, 70, -1, + 70, 36, 69, -1, 71, 69, 36, -1, + 36, 35, 71, -1, 72, 73, 74, -1, + 74, 75, 72, -1, 75, 74, 76, -1, + 76, 77, 75, -1, 77, 76, 78, -1, + 78, 79, 77, -1, 79, 78, 80, -1, + 80, 81, 79, -1, 81, 80, 82, -1, + 82, 83, 81, -1, 83, 82, 84, -1, + 84, 85, 83, -1, 85, 84, 86, -1, + 86, 87, 85, -1, 87, 86, 88, -1, + 88, 89, 87, -1, 89, 88, 90, -1, + 90, 91, 89, -1, 92, 93, 91, -1, + 91, 90, 92, -1, 94, 95, 96, -1, + 96, 97, 94, -1, 97, 96, 98, -1, + 98, 99, 97, -1, 99, 98, 100, -1, + 100, 101, 99, -1, 101, 100, 102, -1, + 102, 103, 101, -1, 103, 102, 104, -1, + 104, 105, 103, -1, 105, 104, 106, -1, + 106, 107, 105, -1, 107, 106, 108, -1, + 108, 109, 107, -1, 109, 108, 110, -1, + 110, 111, 109, -1, 111, 110, 112, -1, + 111, 112, 113, -1, 113, 114, 111, -1, + 114, 113, 115, -1, 115, 116, 114, -1, + 116, 115, 117, -1, 117, 118, 116, -1, + 118, 117, 119, -1, 119, 120, 118, -1, + 120, 119, 121, -1, 121, 122, 120, -1, + 122, 121, 123, -1, 123, 124, 122, -1, + 124, 123, 125, -1, 125, 126, 124, -1, + 125, 127, 126, -1, 128, 129, 130, -1, + 131, 132, 133, -1, 133, 134, 131, -1, + 134, 133, 135, -1, 135, 136, 134, -1, + 136, 135, 137, -1, 137, 138, 136, -1, + 138, 137, 139, -1, 139, 140, 138, -1, + 140, 139, 141, -1, 141, 142, 140, -1, + 142, 141, 128, -1, 128, 130, 142, -1, + 143, 144, 145, -1, 146, 147, 143, -1, + 148, 149, 150, -1, 151, 152, 153, -1, + 152, 151, 154, -1, 152, 154, 155, -1, + 152, 155, 156, -1, 156, 153, 152, -1, + 156, 157, 153, -1, 156, 158, 157, -1, + 158, 156, 155, -1, 155, 159, 158, -1, + 155, 160, 159, -1, 160, 155, 154, -1, + 154, 161, 160, -1, 154, 162, 161, -1, + 162, 154, 151, -1, 151, 163, 162, -1, + 151, 153, 163, -1, 164, 165, 166, -1, + 166, 167, 164, -1, 167, 166, 168, -1, + 168, 169, 167, -1, 169, 168, 170, -1, + 170, 171, 169, -1, 170, 172, 171, -1, + 170, 173, 172, -1, 173, 170, 168, -1, + 168, 174, 173, -1, 174, 168, 166, -1, + 166, 175, 174, -1, 175, 166, 165, -1, + 175, 165, 176, -1, 176, 177, 175, -1, + 177, 176, 178, -1, 178, 179, 177, -1, + 179, 178, 180, -1, 179, 180, 163, -1, + 179, 163, 153, -1, 153, 177, 179, -1, + 177, 153, 157, -1, 157, 175, 177, -1, + 157, 174, 175, -1, 174, 157, 158, -1, + 158, 173, 174, -1, 173, 158, 159, -1, + 159, 172, 173, -1, 159, 181, 172, -1, + 181, 159, 160, -1, 160, 182, 181, -1, + 182, 160, 161, -1, 161, 183, 182, -1, + 161, 184, 183, -1, 184, 161, 162, -1, + 162, 185, 184, -1, 185, 162, 163, -1, + 163, 186, 185, -1, 186, 163, 180, -1, + 180, 187, 186, -1, 180, 188, 187, -1, + 188, 180, 178, -1, 178, 189, 188, -1, + 189, 178, 176, -1, 176, 190, 189, -1, + 190, 176, 165, -1, 165, 191, 190, -1, + 165, 164, 191, -1, 192, 191, 164, -1, + 164, 193, 192, -1, 193, 164, 167, -1, + 167, 194, 193, -1, 194, 167, 169, -1, + 169, 195, 194, -1, 195, 169, 171, -1, + 171, 196, 195, -1, 171, 197, 196, -1, + 197, 171, 172, -1, 172, 198, 197, -1, + 198, 172, 181, -1, 181, 199, 198, -1, + 199, 181, 182, -1, 182, 200, 199, -1, + 200, 182, 183, -1, 183, 201, 200, -1, + 183, 202, 201, -1, 202, 183, 184, -1, + 184, 203, 202, -1, 203, 184, 185, -1, + 185, 204, 203, -1, 204, 185, 186, -1, + 186, 205, 204, -1, 205, 186, 187, -1, + 187, 206, 205, -1, 187, 207, 206, -1, + 207, 187, 188, -1, 188, 208, 207, -1, + 208, 188, 189, -1, 189, 209, 208, -1, + 209, 189, 190, -1, 190, 210, 209, -1, + 210, 190, 191, -1, 191, 211, 210, -1, + 191, 192, 211, -1, 212, 211, 192, -1, + 192, 213, 212, -1, 213, 192, 193, -1, + 193, 214, 213, -1, 214, 193, 194, -1, + 194, 215, 214, -1, 215, 194, 195, -1, + 195, 216, 215, -1, 216, 195, 196, -1, + 196, 217, 216, -1, 196, 218, 217, -1, + 218, 196, 197, -1, 197, 219, 218, -1, + 219, 197, 198, -1, 198, 220, 219, -1, + 220, 198, 199, -1, 199, 221, 220, -1, + 221, 199, 200, -1, 200, 222, 221, -1, + 222, 200, 201, -1, 201, 223, 222, -1, + 201, 224, 223, -1, 224, 201, 202, -1, + 202, 225, 224, -1, 225, 202, 203, -1, + 203, 226, 225, -1, 226, 203, 204, -1, + 204, 227, 226, -1, 227, 204, 205, -1, + 205, 228, 227, -1, 228, 205, 206, -1, + 206, 229, 228, -1, 206, 230, 229, -1, + 230, 206, 207, -1, 207, 231, 230, -1, + 231, 207, 208, -1, 208, 232, 231, -1, + 232, 208, 209, -1, 209, 233, 232, -1, + 233, 209, 210, -1, 210, 234, 233, -1, + 234, 210, 211, -1, 211, 235, 234, -1, + 211, 212, 235, -1, 236, 235, 212, -1, + 212, 237, 236, -1, 237, 212, 213, -1, + 213, 238, 237, -1, 238, 213, 214, -1, + 214, 239, 238, -1, 239, 214, 215, -1, + 215, 240, 239, -1, 240, 215, 216, -1, + 216, 241, 240, -1, 241, 216, 217, -1, + 217, 242, 241, -1, 217, 243, 242, -1, + 243, 217, 218, -1, 218, 244, 243, -1, + 244, 218, 219, -1, 219, 245, 244, -1, + 245, 219, 220, -1, 220, 246, 245, -1, + 246, 220, 221, -1, 221, 247, 246, -1, + 247, 221, 222, -1, 222, 248, 247, -1, + 248, 222, 223, -1, 223, 249, 248, -1, + 223, 250, 249, -1, 250, 223, 224, -1, + 224, 251, 250, -1, 251, 224, 225, -1, + 225, 252, 251, -1, 252, 225, 226, -1, + 226, 253, 252, -1, 253, 226, 227, -1, + 227, 254, 253, -1, 254, 227, 228, -1, + 228, 255, 254, -1, 255, 228, 229, -1, + 229, 256, 255, -1, 229, 257, 256, -1, + 257, 229, 230, -1, 230, 258, 257, -1, + 258, 230, 231, -1, 231, 259, 258, -1, + 259, 231, 232, -1, 232, 260, 259, -1, + 260, 232, 233, -1, 233, 261, 260, -1, + 261, 233, 234, -1, 234, 262, 261, -1, + 262, 234, 235, -1, 235, 263, 262, -1, + 235, 236, 263, -1, 264, 263, 236, -1, + 236, 265, 264, -1, 265, 236, 237, -1, + 237, 266, 265, -1, 266, 237, 238, -1, + 238, 267, 266, -1, 267, 238, 239, -1, + 239, 268, 267, -1, 268, 239, 240, -1, + 240, 269, 268, -1, 269, 240, 241, -1, + 241, 270, 269, -1, 270, 241, 242, -1, + 242, 271, 270, -1, 242, 272, 271, -1, + 272, 242, 243, -1, 243, 273, 272, -1, + 273, 243, 244, -1, 244, 274, 273, -1, + 274, 244, 245, -1, 245, 275, 274, -1, + 275, 245, 246, -1, 246, 276, 275, -1, + 276, 246, 247, -1, 247, 277, 276, -1, + 277, 247, 248, -1, 248, 278, 277, -1, + 278, 248, 249, -1, 249, 279, 278, -1, + 249, 280, 279, -1, 280, 249, 250, -1, + 250, 281, 280, -1, 281, 250, 251, -1, + 251, 282, 281, -1, 282, 251, 252, -1, + 252, 283, 282, -1, 283, 252, 253, -1, + 253, 284, 283, -1, 284, 253, 254, -1, + 254, 285, 284, -1, 285, 254, 255, -1, + 255, 286, 285, -1, 286, 255, 256, -1, + 256, 287, 286, -1, 256, 288, 287, -1, + 288, 256, 257, -1, 257, 289, 288, -1, + 289, 257, 258, -1, 258, 290, 289, -1, + 290, 258, 259, -1, 259, 291, 290, -1, + 291, 259, 260, -1, 260, 292, 291, -1, + 292, 260, 261, -1, 261, 293, 292, -1, + 293, 261, 262, -1, 262, 294, 293, -1, + 294, 262, 263, -1, 263, 295, 294, -1, + 263, 264, 295, -1, 296, 295, 264, -1, + 264, 297, 296, -1, 297, 264, 265, -1, + 265, 298, 297, -1, 298, 265, 266, -1, + 266, 299, 298, -1, 299, 266, 267, -1, + 267, 300, 299, -1, 300, 267, 268, -1, + 268, 301, 300, -1, 301, 268, 269, -1, + 269, 302, 301, -1, 302, 269, 270, -1, + 270, 303, 302, -1, 303, 270, 271, -1, + 271, 304, 303, -1, 271, 305, 304, -1, + 305, 271, 272, -1, 272, 306, 305, -1, + 306, 272, 273, -1, 273, 307, 306, -1, + 307, 273, 274, -1, 274, 308, 307, -1, + 308, 274, 275, -1, 275, 309, 308, -1, + 309, 275, 276, -1, 276, 310, 309, -1, + 310, 276, 277, -1, 277, 311, 310, -1, + 311, 277, 278, -1, 278, 312, 311, -1, + 312, 278, 279, -1, 279, 313, 312, -1, + 279, 314, 313, -1, 314, 279, 280, -1, + 280, 315, 314, -1, 315, 280, 281, -1, + 281, 316, 315, -1, 316, 281, 282, -1, + 282, 317, 316, -1, 317, 282, 283, -1, + 283, 318, 317, -1, 318, 283, 284, -1, + 284, 319, 318, -1, 319, 284, 285, -1, + 285, 320, 319, -1, 320, 285, 286, -1, + 286, 321, 320, -1, 321, 286, 287, -1, + 287, 322, 321, -1, 287, 323, 322, -1, + 323, 287, 288, -1, 288, 324, 323, -1, + 324, 288, 289, -1, 289, 325, 324, -1, + 325, 289, 290, -1, 290, 326, 325, -1, + 326, 290, 291, -1, 291, 327, 326, -1, + 327, 291, 292, -1, 292, 328, 327, -1, + 328, 292, 293, -1, 293, 329, 328, -1, + 329, 293, 294, -1, 294, 330, 329, -1, + 330, 294, 295, -1, 296, 331, 332, -1, + 331, 296, 297, -1, 297, 333, 331, -1, + 333, 297, 298, -1, 298, 334, 333, -1, + 334, 298, 299, -1, 299, 335, 334, -1, + 335, 299, 300, -1, 300, 336, 335, -1, + 336, 300, 301, -1, 301, 337, 336, -1, + 337, 301, 302, -1, 302, 338, 337, -1, + 338, 302, 303, -1, 303, 339, 338, -1, + 339, 303, 304, -1, 304, 340, 339, -1, + 304, 341, 340, -1, 341, 304, 305, -1, + 305, 342, 341, -1, 342, 305, 306, -1, + 306, 343, 342, -1, 343, 306, 307, -1, + 307, 344, 343, -1, 344, 307, 308, -1, + 308, 345, 344, -1, 345, 308, 309, -1, + 309, 346, 345, -1, 346, 309, 310, -1, + 310, 347, 346, -1, 347, 310, 311, -1, + 311, 348, 347, -1, 348, 311, 312, -1, + 312, 349, 348, -1, 349, 312, 313, -1, + 313, 350, 349, -1, 313, 351, 350, -1, + 351, 313, 314, -1, 314, 352, 351, -1, + 352, 314, 315, -1, 315, 353, 352, -1, + 353, 315, 316, -1, 316, 354, 353, -1, + 354, 316, 317, -1, 317, 355, 354, -1, + 355, 317, 318, -1, 318, 356, 355, -1, + 356, 318, 319, -1, 319, 357, 356, -1, + 357, 319, 320, -1, 320, 358, 357, -1, + 358, 320, 321, -1, 321, 359, 358, -1, + 359, 321, 322, -1, 322, 360, 359, -1, + 322, 361, 360, -1, 361, 322, 323, -1, + 323, 362, 361, -1, 362, 323, 324, -1, + 324, 363, 362, -1, 363, 324, 325, -1, + 325, 364, 363, -1, 364, 325, 326, -1, + 326, 365, 364, -1, 365, 326, 327, -1, + 327, 366, 365, -1, 366, 327, 328, -1, + 328, 367, 366, -1, 367, 328, 329, -1, + 329, 368, 367, -1, 368, 329, 330, -1, + 330, 369, 368, -1, 370, 371, 369, -1, + 370, 332, 371, -1, 332, 372, 373, -1, + 372, 332, 331, -1, 331, 374, 372, -1, + 374, 331, 333, -1, 333, 375, 374, -1, + 375, 333, 334, -1, 334, 376, 375, -1, + 376, 334, 335, -1, 335, 377, 376, -1, + 377, 335, 336, -1, 336, 378, 377, -1, + 378, 336, 337, -1, 337, 379, 378, -1, + 379, 337, 338, -1, 338, 380, 379, -1, + 380, 338, 339, -1, 339, 381, 380, -1, + 381, 339, 340, -1, 381, 340, 382, -1, + 381, 382, 383, -1, 383, 380, 381, -1, + 380, 383, 384, -1, 384, 379, 380, -1, + 379, 384, 385, -1, 385, 378, 379, -1, + 378, 385, 386, -1, 386, 377, 378, -1, + 377, 386, 387, -1, 387, 376, 377, -1, + 376, 387, 388, -1, 388, 375, 376, -1, + 375, 388, 389, -1, 389, 374, 375, -1, + 374, 389, 390, -1, 390, 372, 374, -1, + 372, 390, 150, -1, 150, 373, 372, -1, + 150, 149, 373, -1, 391, 373, 149, -1, + 149, 392, 391, -1, 149, 148, 392, -1, + 393, 394, 395, -1, 396, 397, 398, -1, + 396, 398, 399, -1, 395, 399, 398, -1, + 398, 400, 395, -1, 400, 398, 401, -1, + 401, 402, 400, -1, 402, 401, 403, -1, + 403, 404, 402, -1, 404, 403, 405, -1, + 405, 406, 404, -1, 406, 405, 407, -1, + 407, 408, 406, -1, 408, 407, 409, -1, + 409, 410, 408, -1, 410, 409, 411, -1, + 411, 412, 410, -1, 412, 411, 413, -1, + 413, 414, 412, -1, 414, 413, 415, -1, + 415, 416, 414, -1, 416, 415, 417, -1, + 417, 418, 416, -1, 418, 417, 419, -1, + 418, 419, 420, -1, 418, 420, 421, -1, + 421, 416, 418, -1, 416, 421, 422, -1, + 422, 414, 416, -1, 414, 422, 423, -1, + 423, 412, 414, -1, 412, 423, 424, -1, + 424, 410, 412, -1, 410, 424, 425, -1, + 425, 408, 410, -1, 408, 425, 426, -1, + 426, 406, 408, -1, 406, 426, 427, -1, + 427, 404, 406, -1, 404, 427, 428, -1, + 428, 402, 404, -1, 402, 428, 429, -1, + 429, 400, 402, -1, 400, 429, 430, -1, + 430, 395, 400, -1, 430, 393, 395, -1, + 430, 431, 393, -1, 431, 430, 429, -1, + 429, 432, 431, -1, 432, 429, 428, -1, + 428, 433, 432, -1, 433, 428, 427, -1, + 427, 434, 433, -1, 434, 427, 426, -1, + 426, 435, 434, -1, 435, 426, 425, -1, + 425, 436, 435, -1, 436, 425, 424, -1, + 424, 437, 436, -1, 437, 424, 423, -1, + 423, 438, 437, -1, 438, 423, 422, -1, + 422, 439, 438, -1, 439, 422, 421, -1, + 421, 440, 439, -1, 440, 421, 420, -1, + 440, 420, 441, -1, 441, 442, 440, -1, + 442, 441, 443, -1, 443, 444, 442, -1, + 444, 443, 445, -1, 445, 446, 444, -1, + 446, 445, 447, -1, 447, 448, 446, -1, + 448, 447, 449, -1, 449, 450, 448, -1, + 450, 449, 451, -1, 451, 452, 450, -1, + 452, 451, 453, -1, 453, 454, 452, -1, + 454, 453, 455, -1, 455, 456, 454, -1, + 456, 455, 457, -1, 457, 458, 456, -1, + 458, 457, 459, -1, 459, 460, 458, -1, + 460, 459, 461, -1, 461, 462, 460, -1, + 462, 461, 463, -1, 463, 464, 462, -1, + 464, 463, 465, -1, 465, 466, 464, -1, + 466, 465, 467, -1, 466, 467, 468, -1, + 468, 469, 466, -1, 469, 468, 470, -1, + 470, 471, 469, -1, 471, 470, 472, -1, + 472, 473, 471, -1, 473, 472, 474, -1, + 474, 475, 473, -1, 475, 474, 476, -1, + 476, 477, 475, -1, 477, 476, 478, -1, + 478, 479, 477, -1, 479, 478, 480, -1, + 480, 481, 479, -1, 481, 480, 482, -1, + 482, 483, 481, -1, 483, 482, 484, -1, + 484, 485, 483, -1, 485, 484, 486, -1, + 486, 487, 485, -1, 487, 486, 488, -1, + 488, 489, 487, -1, 489, 488, 490, -1, + 490, 491, 489, -1, 491, 490, 492, -1, + 492, 493, 491, -1, 494, 495, 496, -1, + 496, 497, 494, -1, 497, 496, 498, -1, + 498, 499, 497, -1, 499, 498, 500, -1, + 500, 501, 499, -1, 501, 500, 502, -1, + 502, 503, 501, -1, 503, 502, 504, -1, + 504, 505, 503, -1, 505, 504, 506, -1, + 506, 507, 505, -1, 507, 506, 508, -1, + 508, 509, 507, -1, 509, 508, 493, -1, + 493, 510, 509, -1, 493, 492, 510, -1, + 511, 512, 513, -1, 514, 515, 516, -1, + 516, 515, 517, -1, 518, 519, 520, -1, + 521, 522, 523, -1, 524, 525, 526, -1, + 527, 528, 529, -1, 528, 527, 530, -1, + 531, 530, 527, -1, 527, 532, 531, -1, + 527, 529, 532, -1, 533, 529, 534, -1, + 533, 532, 529, -1, 533, 531, 532, -1, + 533, 534, 531, -1, 535, 531, 534, -1, + 536, 537, 538, -1, 537, 536, 535, -1, + 537, 535, 534, -1, 534, 538, 537, -1, + 538, 534, 529, -1, 539, 540, 541, -1, + 542, 543, 544, -1, 543, 542, 545, -1, + 543, 545, 546, -1, 547, 546, 545, -1, + 547, 548, 546, -1, 549, 550, 551, -1, + 551, 552, 549, -1, 552, 551, 553, -1, + 553, 554, 552, -1, 554, 553, 555, -1, + 555, 556, 554, -1, 556, 555, 557, -1, + 557, 558, 556, -1, 558, 557, 559, -1, + 559, 560, 558, -1, 560, 559, 561, -1, + 561, 562, 560, -1, 562, 561, 563, -1, + 563, 564, 562, -1, 564, 563, 565, -1, + 565, 566, 564, -1, 566, 565, 567, -1, + 567, 568, 566, -1, 568, 567, 569, -1, + 569, 570, 568, -1, 570, 569, 571, -1, + 571, 572, 570, -1, 572, 571, 573, -1, + 573, 574, 572, -1, 574, 573, 575, -1, + 575, 576, 574, -1, 576, 575, 577, -1, + 577, 578, 576, -1, 578, 577, 579, -1, + 579, 580, 578, -1, 580, 579, 581, -1, + 581, 582, 580, -1, 582, 581, 583, -1, + 583, 584, 582, -1, 584, 583, 585, -1, + 585, 586, 584, -1, 586, 585, 587, -1, + 587, 588, 586, -1, 588, 587, 589, -1, + 589, 590, 588, -1, 590, 589, 591, -1, + 591, 592, 590, -1, 592, 591, 593, -1, + 593, 594, 592, -1, 594, 593, 595, -1, + 595, 596, 594, -1, 596, 595, 597, -1, + 597, 598, 596, -1, 598, 597, 599, -1, + 599, 600, 598, -1, 600, 599, 601, -1, + 601, 602, 600, -1, 602, 601, 603, -1, + 603, 604, 602, -1, 604, 603, 605, -1, + 605, 606, 604, -1, 606, 605, 607, -1, + 607, 608, 606, -1, 608, 607, 609, -1, + 609, 610, 608, -1, 610, 609, 611, -1, + 611, 612, 610, -1, 612, 611, 613, -1, + 613, 614, 612, -1, 614, 613, 615, -1, + 615, 616, 614, -1, 616, 615, 617, -1, + 617, 618, 616, -1, 618, 617, 619, -1, + 619, 620, 618, -1, 620, 619, 621, -1, + 621, 622, 620, -1, 622, 621, 623, -1, + 623, 624, 622, -1, 624, 623, 625, -1, + 625, 626, 624, -1, 626, 625, 627, -1, + 627, 628, 626, -1, 628, 627, 629, -1, + 629, 630, 628, -1, 631, 629, 632, -1, + 632, 633, 631, -1, 633, 632, 634, -1, + 634, 635, 633, -1, 635, 634, 636, -1, + 636, 637, 635, -1, 637, 636, 638, -1, + 638, 639, 637, -1, 639, 638, 640, -1, + 640, 641, 639, -1, 641, 640, 642, -1, + 642, 643, 641, -1, 643, 642, 644, -1, + 644, 645, 643, -1, 645, 644, 646, -1, + 646, 647, 645, -1, 647, 646, 648, -1, + 648, 649, 647, -1, 649, 648, 650, -1, + 650, 651, 649, -1, 651, 650, 652, -1, + 652, 653, 651, -1, 653, 652, 654, -1, + 654, 655, 653, -1, 655, 654, 656, -1, + 656, 657, 655, -1, 657, 656, 658, -1, + 658, 659, 657, -1, 659, 658, 660, -1, + 660, 661, 659, -1, 661, 660, 662, -1, + 662, 663, 661, -1, 663, 662, 664, -1, + 664, 665, 663, -1, 665, 664, 666, -1, + 666, 667, 665, -1, 667, 666, 668, -1, + 668, 669, 667, -1, 669, 668, 670, -1, + 670, 671, 669, -1, 671, 670, 672, -1, + 672, 673, 671, -1, 673, 672, 674, -1, + 674, 675, 673, -1, 675, 674, 676, -1, + 676, 677, 675, -1, 677, 676, 678, -1, + 678, 679, 677, -1, 679, 678, 680, -1, + 680, 681, 679, -1, 681, 680, 682, -1, + 682, 683, 681, -1, 683, 682, 684, -1, + 684, 685, 683, -1, 685, 684, 686, -1, + 686, 687, 685, -1, 687, 686, 688, -1, + 688, 689, 687, -1, 689, 688, 690, -1, + 690, 691, 689, -1, 691, 690, 692, -1, + 692, 693, 691, -1, 693, 692, 694, -1, + 694, 695, 693, -1, 695, 694, 696, -1, + 696, 697, 695, -1, 697, 696, 698, -1, + 698, 699, 697, -1, 699, 698, 700, -1, + 700, 701, 699, -1, 701, 700, 702, -1, + 702, 703, 701, -1, 703, 702, 704, -1, + 704, 705, 703, -1, 705, 704, 706, -1, + 706, 707, 705, -1, 707, 706, 708, -1, + 708, 709, 707, -1, 709, 708, 710, -1, + 710, 711, 709, -1, 711, 710, 712, -1, + 712, 713, 711, -1, 713, 712, 714, -1, + 714, 715, 713, -1, 715, 714, 716, -1, + 716, 717, 715, -1, 717, 716, 718, -1, + 718, 719, 717, -1, 719, 718, 720, -1, + 720, 721, 719, -1, 722, 723, 724, -1, + 722, 724, 721, -1, 721, 720, 722, -1, + 725, 722, 720, -1, 722, 725, 726, -1, + 726, 723, 722, -1, 727, 728, 723, -1, + 723, 726, 727, -1, 729, 730, 731, -1, + 732, 731, 730, -1, 733, 734, 735, -1, + 735, 736, 733, -1, 736, 735, 737, -1, + 737, 738, 736, -1, 738, 737, 739, -1, + 739, 740, 738, -1, 740, 739, 741, -1, + 741, 742, 740, -1, 743, 744, 745, -1, + 745, 746, 743, -1, 746, 745, 742, -1, + 742, 741, 746, -1, 741, 747, 746, -1, + 747, 741, 739, -1, 739, 748, 747, -1, + 748, 739, 737, -1, 737, 749, 748, -1, + 749, 737, 735, -1, 735, 750, 749, -1, + 750, 735, 734, -1, 734, 751, 750, -1, + 751, 734, 752, -1, 752, 753, 751, -1, + 753, 752, 754, -1, 754, 755, 753, -1, + 755, 754, 756, -1, 756, 757, 755, -1, + 758, 759, 760, -1, 760, 761, 758, -1, + 762, 763, 764, -1, 764, 765, 762, -1, + 765, 764, 766, -1, 766, 764, 767, -1, + 766, 767, 768, -1, 768, 769, 766, -1, + 769, 768, 761, -1, 761, 760, 769, -1, + 770, 769, 760, -1, 760, 771, 770, -1, + 771, 760, 759, -1, 759, 772, 771, -1, + 773, 774, 731, -1, 773, 731, 772, -1, + 772, 759, 773, -1, 775, 776, 777, -1, + 773, 777, 776, -1, 777, 773, 759, -1, + 759, 758, 777, -1, 778, 779, 780, -1, + 780, 779, 777, -1, 780, 777, 758, -1, + 758, 781, 780, -1, 781, 758, 761, -1, + 761, 782, 781, -1, 782, 761, 768, -1, + 768, 783, 782, -1, 783, 768, 767, -1, + 767, 784, 783, -1, 785, 786, 787, -1, + 787, 788, 785, -1, 788, 787, 789, -1, + 789, 790, 788, -1, 790, 789, 791, -1, + 791, 792, 790, -1, 792, 791, 784, -1, + 784, 793, 792, -1, 793, 784, 767, -1, + 793, 767, 764, -1, 793, 764, 763, -1, + 763, 792, 793, -1, 792, 763, 794, -1, + 794, 790, 792, -1, 790, 794, 795, -1, + 795, 788, 790, -1, 788, 795, 796, -1, + 796, 785, 788, -1, 785, 796, 797, -1, + 797, 786, 785, -1, 786, 797, 798, -1, + 798, 799, 786, -1, 799, 798, 800, -1, + 800, 801, 799, -1, 801, 800, 802, -1, + 802, 803, 801, -1, 803, 802, 804, -1, + 804, 805, 803, -1, 805, 804, 806, -1, + 806, 807, 805, -1, 807, 806, 808, -1, + 808, 809, 807, -1, 809, 808, 810, -1, + 810, 811, 809, -1, 811, 810, 812, -1, + 812, 813, 811, -1, 813, 812, 814, -1, + 814, 815, 813, -1, 815, 814, 816, -1, + 816, 817, 815, -1, 817, 816, 818, -1, + 818, 819, 817, -1, 819, 818, 820, -1, + 820, 821, 819, -1, 821, 820, 822, -1, + 822, 823, 821, -1, 823, 822, 824, -1, + 824, 825, 823, -1, 826, 827, 828, -1, + 827, 826, 829, -1, 829, 830, 827, -1, + 830, 829, 831, -1, 831, 832, 830, -1, + 832, 831, 833, -1, 833, 834, 832, -1, + 834, 833, 835, -1, 835, 836, 834, -1, + 836, 835, 837, -1, 837, 838, 836, -1, + 838, 837, 839, -1, 839, 840, 838, -1, + 840, 839, 841, -1, 841, 842, 840, -1, + 842, 841, 843, -1, 843, 844, 842, -1, + 844, 843, 845, -1, 845, 846, 844, -1, + 846, 845, 847, -1, 847, 848, 846, -1, + 848, 847, 849, -1, 849, 850, 848, -1, + 850, 849, 851, -1, 851, 852, 850, -1, + 852, 851, 853, -1, 853, 854, 852, -1, + 853, 855, 854, -1, 855, 853, 856, -1, + 856, 857, 855, -1, 857, 856, 858, -1, + 858, 859, 857, -1, 859, 858, 860, -1, + 860, 861, 859, -1, 861, 860, 862, -1, + 862, 863, 861, -1, 863, 862, 864, -1, + 864, 865, 863, -1, 865, 864, 866, -1, + 866, 867, 865, -1, 867, 866, 868, -1, + 868, 869, 867, -1, 869, 868, 870, -1, + 870, 871, 869, -1, 871, 870, 872, -1, + 872, 873, 871, -1, 873, 872, 874, -1, + 874, 875, 873, -1, 875, 874, 876, -1, + 876, 877, 875, -1, 877, 876, 878, -1, + 878, 879, 877, -1, 879, 878, 880, -1, + 880, 881, 879, -1, 881, 880, 882, -1, + 882, 883, 881, -1, 883, 882, 884, -1, + 884, 885, 883, -1, 885, 884, 886, -1, + 886, 887, 885, -1, 887, 886, 888, -1, + 888, 889, 887, -1, 889, 888, 890, -1, + 890, 891, 889, -1, 891, 890, 892, -1, + 892, 893, 891, -1, 893, 892, 894, -1, + 894, 895, 893, -1, 895, 894, 896, -1, + 896, 897, 895, -1, 897, 896, 898, -1, + 898, 899, 897, -1, 899, 898, 825, -1, + 825, 824, 899, -1, 899, 824, 900, -1, + 900, 897, 899, -1, 897, 900, 901, -1, + 901, 895, 897, -1, 895, 901, 902, -1, + 902, 893, 895, -1, 893, 902, 903, -1, + 903, 891, 893, -1, 891, 903, 904, -1, + 904, 889, 891, -1, 889, 904, 905, -1, + 905, 887, 889, -1, 887, 905, 906, -1, + 906, 885, 887, -1, 885, 906, 907, -1, + 907, 883, 885, -1, 883, 907, 908, -1, + 908, 881, 883, -1, 881, 908, 909, -1, + 909, 879, 881, -1, 879, 909, 910, -1, + 910, 877, 879, -1, 877, 910, 911, -1, + 911, 875, 877, -1, 875, 911, 912, -1, + 912, 873, 875, -1, 873, 912, 913, -1, + 913, 871, 873, -1, 871, 913, 914, -1, + 914, 869, 871, -1, 869, 914, 915, -1, + 915, 867, 869, -1, 867, 915, 916, -1, + 916, 865, 867, -1, 865, 916, 917, -1, + 917, 863, 865, -1, 863, 917, 918, -1, + 918, 861, 863, -1, 861, 918, 919, -1, + 919, 859, 861, -1, 859, 919, 920, -1, + 920, 857, 859, -1, 857, 920, 921, -1, + 921, 855, 857, -1, 855, 921, 922, -1, + 922, 854, 855, -1, 854, 922, 923, -1, + 854, 923, 924, -1, 924, 852, 854, -1, + 852, 924, 925, -1, 925, 850, 852, -1, + 850, 925, 926, -1, 926, 848, 850, -1, + 848, 926, 927, -1, 927, 846, 848, -1, + 846, 927, 928, -1, 928, 844, 846, -1, + 844, 928, 929, -1, 929, 842, 844, -1, + 842, 929, 930, -1, 930, 840, 842, -1, + 840, 930, 931, -1, 931, 838, 840, -1, + 838, 931, 932, -1, 932, 836, 838, -1, + 836, 932, 933, -1, 933, 834, 836, -1, + 834, 933, 934, -1, 934, 832, 834, -1, + 832, 934, 935, -1, 935, 830, 832, -1, + 830, 935, 936, -1, 936, 827, 830, -1, + 827, 936, 937, -1, 937, 828, 827, -1, + 828, 937, 757, -1, 757, 756, 828, -1, + 938, 828, 756, -1, 828, 938, 939, -1, + 939, 826, 828, -1, 826, 939, 940, -1, + 940, 829, 826, -1, 829, 940, 941, -1, + 941, 831, 829, -1, 831, 941, 942, -1, + 942, 833, 831, -1, 833, 942, 943, -1, + 943, 835, 833, -1, 835, 943, 944, -1, + 944, 837, 835, -1, 837, 944, 945, -1, + 945, 839, 837, -1, 839, 945, 946, -1, + 946, 841, 839, -1, 841, 946, 947, -1, + 947, 843, 841, -1, 843, 947, 948, -1, + 948, 845, 843, -1, 845, 948, 949, -1, + 949, 847, 845, -1, 847, 949, 950, -1, + 950, 849, 847, -1, 849, 950, 951, -1, + 951, 851, 849, -1, 851, 951, 952, -1, + 952, 853, 851, -1, 952, 856, 853, -1, + 856, 952, 953, -1, 953, 858, 856, -1, + 858, 953, 954, -1, 954, 860, 858, -1, + 860, 954, 955, -1, 955, 862, 860, -1, + 862, 955, 956, -1, 956, 864, 862, -1, + 864, 956, 957, -1, 957, 866, 864, -1, + 866, 957, 958, -1, 958, 868, 866, -1, + 868, 958, 959, -1, 959, 870, 868, -1, + 870, 959, 960, -1, 960, 872, 870, -1, + 872, 960, 961, -1, 961, 874, 872, -1, + 874, 961, 962, -1, 962, 876, 874, -1, + 876, 962, 963, -1, 963, 878, 876, -1, + 878, 963, 964, -1, 964, 880, 878, -1, + 880, 964, 965, -1, 965, 882, 880, -1, + 882, 965, 966, -1, 966, 884, 882, -1, + 884, 966, 967, -1, 967, 886, 884, -1, + 886, 967, 968, -1, 968, 888, 886, -1, + 888, 968, 969, -1, 969, 890, 888, -1, + 890, 969, 970, -1, 970, 892, 890, -1, + 892, 970, 971, -1, 971, 894, 892, -1, + 894, 971, 972, -1, 972, 896, 894, -1, + 896, 972, 973, -1, 973, 898, 896, -1, + 898, 973, 974, -1, 974, 825, 898, -1, + 825, 974, 975, -1, 975, 823, 825, -1, + 976, 823, 975, -1, 975, 977, 976, -1, + 977, 975, 974, -1, 974, 978, 977, -1, + 978, 974, 973, -1, 973, 979, 978, -1, + 979, 973, 972, -1, 972, 980, 979, -1, + 981, 982, 983, -1, 983, 984, 981, -1, + 984, 983, 985, -1, 985, 986, 984, -1, + 986, 985, 987, -1, 987, 988, 986, -1, + 989, 986, 988, -1, 988, 990, 989, -1, + 990, 988, 991, -1, 991, 992, 990, -1, + 992, 991, 993, -1, 993, 994, 992, -1, + 994, 993, 995, -1, 995, 996, 994, -1, + 996, 995, 997, -1, 997, 998, 996, -1, + 998, 997, 980, -1, 980, 972, 998, -1, + 998, 972, 971, -1, 971, 996, 998, -1, + 996, 971, 970, -1, 970, 994, 996, -1, + 994, 970, 969, -1, 969, 992, 994, -1, + 992, 969, 968, -1, 968, 990, 992, -1, + 990, 968, 967, -1, 967, 989, 990, -1, + 989, 967, 966, -1, 966, 999, 989, -1, + 1000, 1001, 1002, -1, 1001, 1000, 1003, -1, + 1003, 1004, 1001, -1, 1004, 1003, 1005, -1, + 1005, 1006, 1004, -1, 1006, 1005, 1007, -1, + 1007, 1008, 1006, -1, 1008, 1007, 1009, -1, + 1010, 1009, 1011, -1, 1009, 1010, 1012, -1, + 1012, 1008, 1009, -1, 1008, 1012, 1013, -1, + 1013, 1006, 1008, -1, 1006, 1013, 1014, -1, + 1014, 1004, 1006, -1, 1004, 1014, 1015, -1, + 1015, 1001, 1004, -1, 1001, 1015, 1016, -1, + 1016, 1002, 1001, -1, 1002, 1016, 1017, -1, + 1017, 1018, 1002, -1, 1018, 1017, 1019, -1, + 1019, 1020, 1018, -1, 1020, 1019, 1021, -1, + 1021, 1022, 1020, -1, 1022, 1021, 1023, -1, + 1023, 1024, 1022, -1, 1024, 1023, 1025, -1, + 1025, 1026, 1024, -1, 1026, 1025, 1027, -1, + 1027, 1028, 1026, -1, 1028, 1027, 1029, -1, + 1029, 1030, 1028, -1, 1030, 1029, 1031, -1, + 1031, 1032, 1030, -1, 1032, 1031, 1033, -1, + 1033, 1034, 1032, -1, 1034, 1033, 1035, -1, + 1035, 1036, 1034, -1, 1035, 1037, 1036, -1, + 1037, 1035, 1038, -1, 1038, 1039, 1037, -1, + 1039, 1038, 1040, -1, 1040, 1041, 1039, -1, + 1041, 1040, 1042, -1, 1042, 1043, 1041, -1, + 1043, 1042, 1044, -1, 1044, 1045, 1043, -1, + 1045, 1044, 1046, -1, 1046, 1047, 1045, -1, + 1047, 1046, 1048, -1, 1048, 1049, 1047, -1, + 1049, 1048, 1050, -1, 1050, 1051, 1049, -1, + 1051, 1050, 1052, -1, 1052, 1053, 1051, -1, + 1053, 1052, 1054, -1, 1054, 1055, 1053, -1, + 1055, 1054, 1056, -1, 1056, 1057, 1055, -1, + 1057, 1056, 1058, -1, 1058, 1059, 1057, -1, + 1059, 1058, 1060, -1, 1060, 1061, 1059, -1, + 1061, 1060, 999, -1, 999, 966, 1061, -1, + 1061, 966, 965, -1, 965, 1059, 1061, -1, + 1059, 965, 964, -1, 964, 1057, 1059, -1, + 1057, 964, 963, -1, 963, 1055, 1057, -1, + 1055, 963, 962, -1, 962, 1053, 1055, -1, + 1053, 962, 961, -1, 961, 1051, 1053, -1, + 1051, 961, 960, -1, 960, 1049, 1051, -1, + 1049, 960, 959, -1, 959, 1047, 1049, -1, + 1047, 959, 958, -1, 958, 1045, 1047, -1, + 1045, 958, 957, -1, 957, 1043, 1045, -1, + 1043, 957, 956, -1, 956, 1041, 1043, -1, + 1041, 956, 955, -1, 955, 1039, 1041, -1, + 1039, 955, 954, -1, 954, 1037, 1039, -1, + 1037, 954, 953, -1, 953, 1036, 1037, -1, + 1036, 953, 952, -1, 1036, 952, 951, -1, + 951, 1034, 1036, -1, 1034, 951, 950, -1, + 950, 1032, 1034, -1, 1032, 950, 949, -1, + 949, 1030, 1032, -1, 1030, 949, 948, -1, + 948, 1028, 1030, -1, 1028, 948, 947, -1, + 947, 1026, 1028, -1, 1026, 947, 946, -1, + 946, 1024, 1026, -1, 1024, 946, 945, -1, + 945, 1022, 1024, -1, 1022, 945, 944, -1, + 944, 1020, 1022, -1, 1020, 944, 943, -1, + 943, 1018, 1020, -1, 1018, 943, 942, -1, + 942, 1002, 1018, -1, 1002, 942, 941, -1, + 941, 1000, 1002, -1, 1000, 941, 940, -1, + 940, 1003, 1000, -1, 1003, 940, 939, -1, + 939, 1005, 1003, -1, 1005, 939, 938, -1, + 938, 1007, 1005, -1, 1007, 938, 756, -1, + 756, 1009, 1007, -1, 1009, 756, 754, -1, + 754, 1011, 1009, -1, 1011, 754, 752, -1, + 752, 1062, 1011, -1, 1062, 752, 734, -1, + 734, 733, 1062, -1, 1063, 1062, 733, -1, + 733, 1064, 1063, -1, 1064, 733, 736, -1, + 736, 1065, 1064, -1, 1065, 736, 738, -1, + 738, 1066, 1065, -1, 1066, 738, 740, -1, + 740, 1067, 1066, -1, 1067, 740, 742, -1, + 742, 1068, 1067, -1, 1068, 742, 745, -1, + 745, 1069, 1068, -1, 1069, 745, 744, -1, + 744, 1070, 1069, -1, 1070, 744, 1071, -1, + 1072, 1073, 1074, -1, 1072, 1075, 1073, -1, + 1075, 1072, 1076, -1, 1076, 1077, 1075, -1, + 1077, 1076, 1078, -1, 1078, 1079, 1077, -1, + 1079, 1078, 1080, -1, 1080, 1081, 1079, -1, + 1081, 1080, 1082, -1, 1082, 1083, 1081, -1, + 1083, 1082, 1084, -1, 1084, 1085, 1083, -1, + 1085, 1084, 1086, -1, 1086, 1087, 1085, -1, + 1087, 1086, 1088, -1, 1088, 1089, 1087, -1, + 1089, 1088, 1090, -1, 1090, 1091, 1089, -1, + 1091, 1090, 1092, -1, 1092, 1093, 1091, -1, + 1093, 1092, 1094, -1, 1094, 1095, 1093, -1, + 1095, 1094, 1096, -1, 1096, 1097, 1095, -1, + 1097, 1096, 1098, -1, 1098, 1099, 1097, -1, + 1099, 1098, 1100, -1, 1100, 1101, 1099, -1, + 1101, 1100, 1102, -1, 1102, 1103, 1101, -1, + 1103, 1102, 1104, -1, 1104, 1105, 1103, -1, + 1105, 1104, 1106, -1, 1106, 1107, 1105, -1, + 1107, 1106, 1108, -1, 1108, 1109, 1107, -1, + 1110, 1111, 1112, -1, 1112, 1113, 1110, -1, + 1113, 1112, 1114, -1, 1114, 1115, 1113, -1, + 1115, 1114, 1116, -1, 1116, 1117, 1115, -1, + 1117, 1116, 1118, -1, 1118, 1119, 1117, -1, + 1119, 1120, 1121, -1, 1119, 1118, 1120, -1, + 1122, 1123, 1124, -1, 1124, 1125, 1122, -1, + 1125, 1124, 1126, -1, 1126, 1127, 1125, -1, + 1128, 1129, 1130, -1, 1129, 1128, 1127, -1, + 1127, 1126, 1129, -1, 1126, 1131, 1129, -1, + 1131, 1126, 1124, -1, 1124, 1132, 1131, -1, + 1132, 1124, 1123, -1, 1123, 1133, 1132, -1, + 1133, 1123, 1134, -1, 1134, 1135, 1133, -1, + 1135, 1134, 1136, -1, 1136, 1137, 1135, -1, + 1137, 1136, 1138, -1, 1138, 1139, 1137, -1, + 1139, 1138, 1140, -1, 1140, 1141, 1139, -1, + 1141, 1140, 1142, -1, 1141, 1142, 1143, -1, + 1144, 1143, 1142, -1, 1143, 1144, 1145, -1, + 1146, 1120, 1147, -1, 1147, 1145, 1146, -1, + 1147, 1148, 1145, -1, 1148, 1143, 1145, -1, + 1148, 1141, 1143, -1, 1148, 1147, 1141, -1, + 1141, 1147, 1120, -1, 1120, 1139, 1141, -1, + 1139, 1120, 1118, -1, 1118, 1137, 1139, -1, + 1137, 1118, 1116, -1, 1116, 1135, 1137, -1, + 1135, 1116, 1114, -1, 1114, 1133, 1135, -1, + 1133, 1114, 1112, -1, 1112, 1132, 1133, -1, + 1132, 1112, 1111, -1, 1111, 1131, 1132, -1, + 1131, 1111, 1149, -1, 1149, 1129, 1131, -1, + 1129, 1149, 1150, -1, 1150, 1130, 1129, -1, + 1130, 1150, 1151, -1, 1151, 1152, 1130, -1, + 1152, 1151, 1153, -1, 1153, 1154, 1152, -1, + 1154, 1153, 1155, -1, 1155, 1156, 1154, -1, + 1156, 1155, 1157, -1, 1157, 1158, 1156, -1, + 1158, 1157, 1159, -1, 1159, 1160, 1158, -1, + 1160, 1159, 1161, -1, 1161, 1162, 1160, -1, + 1162, 1161, 1163, -1, 1163, 1164, 1162, -1, + 1164, 1163, 1165, -1, 1165, 1166, 1164, -1, + 1166, 1165, 1167, -1, 1167, 1168, 1166, -1, + 1168, 1167, 1169, -1, 1169, 1170, 1168, -1, + 1170, 1169, 1171, -1, 1171, 1172, 1170, -1, + 1172, 1171, 1173, -1, 1173, 1174, 1172, -1, + 1175, 1071, 1174, -1, 1174, 1173, 1175, -1, + 1109, 1175, 1173, -1, 1173, 1107, 1109, -1, + 1107, 1173, 1171, -1, 1171, 1105, 1107, -1, + 1105, 1171, 1169, -1, 1169, 1103, 1105, -1, + 1103, 1169, 1167, -1, 1167, 1101, 1103, -1, + 1101, 1167, 1165, -1, 1165, 1099, 1101, -1, + 1099, 1165, 1163, -1, 1163, 1097, 1099, -1, + 1097, 1163, 1161, -1, 1161, 1095, 1097, -1, + 1095, 1161, 1159, -1, 1159, 1093, 1095, -1, + 1093, 1159, 1157, -1, 1157, 1091, 1093, -1, + 1091, 1157, 1155, -1, 1155, 1089, 1091, -1, + 1089, 1155, 1153, -1, 1153, 1087, 1089, -1, + 1087, 1153, 1151, -1, 1151, 1085, 1087, -1, + 1085, 1151, 1150, -1, 1150, 1083, 1085, -1, + 1083, 1150, 1149, -1, 1149, 1081, 1083, -1, + 1081, 1149, 1111, -1, 1111, 1110, 1081, -1, + 1110, 1079, 1081, -1, 1079, 1110, 1113, -1, + 1113, 1077, 1079, -1, 1077, 1113, 1115, -1, + 1115, 1075, 1077, -1, 1075, 1115, 1117, -1, + 1117, 1073, 1075, -1, 1073, 1117, 1119, -1, + 1119, 1176, 1073, -1, 1177, 1073, 1176, -1, + 1176, 1178, 1177, -1, 1176, 1179, 1178, -1, + 1179, 1176, 1119, -1, 1179, 1119, 1121, -1, + 1121, 1178, 1179, -1, 1121, 1180, 1178, -1, + 1180, 1121, 1120, -1, 1180, 1120, 1146, -1, + 1146, 1145, 1180, -1, 1145, 1178, 1180, -1, + 1181, 1182, 1183, -1, 1181, 1184, 1182, -1, + 1185, 1184, 1181, -1, 1181, 1183, 1185, -1, + 1186, 1187, 1188, -1, 1187, 1186, 1189, -1, + 1189, 1190, 1187, -1, 1190, 1189, 1191, -1, + 1191, 1192, 1190, -1, 1192, 1191, 1193, -1, + 1193, 1194, 1192, -1, 1194, 1193, 1195, -1, + 1195, 1196, 1194, -1, 1196, 1195, 1197, -1, + 1197, 1198, 1196, -1, 1198, 1197, 1199, -1, + 1199, 1200, 1198, -1, 1200, 1199, 1201, -1, + 1201, 1202, 1200, -1, 1202, 1201, 1203, -1, + 1203, 1204, 1202, -1, 1204, 1203, 1205, -1, + 1205, 1206, 1204, -1, 1206, 1205, 1207, -1, + 1207, 1208, 1206, -1, 1208, 1207, 1209, -1, + 1209, 1210, 1208, -1, 1210, 1209, 1211, -1, + 1211, 1212, 1210, -1, 1212, 1211, 1213, -1, + 1213, 1214, 1212, -1, 1214, 1213, 1215, -1, + 1215, 1216, 1214, -1, 1216, 1215, 1217, -1, + 1217, 1218, 1216, -1, 1218, 1217, 1219, -1, + 1219, 1220, 1218, -1, 1220, 1219, 1221, -1, + 1221, 1222, 1220, -1, 1222, 1221, 1223, -1, + 1223, 1224, 1222, -1, 1224, 1223, 1225, -1, + 1225, 1226, 1224, -1, 1226, 1225, 1227, -1, + 1227, 1228, 1226, -1, 1228, 1227, 1229, -1, + 1229, 1230, 1228, -1, 1230, 1229, 1231, -1, + 1230, 1231, 1232, -1, 1232, 1233, 1230, -1, + 1233, 1232, 1234, -1, 1234, 1235, 1233, -1, + 1235, 1234, 1236, -1, 1236, 1237, 1235, -1, + 1237, 1236, 1238, -1, 1238, 1239, 1237, -1, + 1239, 1238, 1240, -1, 1240, 1241, 1239, -1, + 1241, 1240, 1242, -1, 1242, 1243, 1241, -1, + 1243, 1242, 1244, -1, 1244, 1245, 1243, -1, + 1245, 1244, 1246, -1, 1246, 1247, 1245, -1, + 1247, 1246, 1248, -1, 1248, 1249, 1247, -1, + 1249, 1248, 1250, -1, 1250, 1251, 1249, -1, + 1251, 1250, 1252, -1, 1252, 1253, 1251, -1, + 1253, 1252, 1254, -1, 1254, 1255, 1253, -1, + 1255, 1254, 1256, -1, 1256, 1257, 1255, -1, + 1257, 1256, 1258, -1, 1258, 1259, 1257, -1, + 1259, 1258, 1260, -1, 1260, 1261, 1259, -1, + 1261, 1260, 1262, -1, 1262, 1263, 1261, -1, + 1263, 1262, 1264, -1, 1264, 1265, 1263, -1, + 1265, 1264, 1266, -1, 1266, 1267, 1265, -1, + 1267, 1266, 1268, -1, 1268, 1269, 1267, -1, + 1269, 1268, 1270, -1, 1270, 1271, 1269, -1, + 1271, 1270, 1272, -1, 1272, 1273, 1271, -1, + 1273, 1272, 1274, -1, 1274, 1275, 1273, -1, + 1276, 1277, 1275, -1, 1275, 1274, 1276, -1, + 1278, 1276, 1274, -1, 1274, 1279, 1278, -1, + 1279, 1274, 1272, -1, 1272, 1280, 1279, -1, + 1280, 1272, 1270, -1, 1270, 1281, 1280, -1, + 1281, 1270, 1268, -1, 1268, 1282, 1281, -1, + 1282, 1268, 1266, -1, 1266, 1283, 1282, -1, + 1283, 1266, 1264, -1, 1264, 1284, 1283, -1, + 1284, 1264, 1262, -1, 1262, 1285, 1284, -1, + 1285, 1262, 1260, -1, 1260, 1286, 1285, -1, + 1286, 1260, 1258, -1, 1258, 1287, 1286, -1, + 1287, 1258, 1256, -1, 1256, 1288, 1287, -1, + 1288, 1256, 1254, -1, 1254, 1289, 1288, -1, + 1289, 1254, 1252, -1, 1252, 1290, 1289, -1, + 1290, 1252, 1250, -1, 1250, 1291, 1290, -1, + 1291, 1250, 1248, -1, 1248, 1292, 1291, -1, + 1292, 1248, 1246, -1, 1246, 1293, 1292, -1, + 1293, 1246, 1244, -1, 1244, 1294, 1293, -1, + 1294, 1244, 1242, -1, 1242, 1295, 1294, -1, + 1295, 1242, 1240, -1, 1240, 1296, 1295, -1, + 1296, 1240, 1238, -1, 1238, 1297, 1296, -1, + 1297, 1238, 1236, -1, 1236, 1298, 1297, -1, + 1298, 1236, 1234, -1, 1234, 1299, 1298, -1, + 1299, 1234, 1232, -1, 1232, 1300, 1299, -1, + 1300, 1232, 1231, -1, 1231, 1301, 1300, -1, + 1231, 1302, 1301, -1, 1302, 1231, 1229, -1, + 1229, 1303, 1302, -1, 1303, 1229, 1227, -1, + 1227, 1304, 1303, -1, 1304, 1227, 1225, -1, + 1225, 1305, 1304, -1, 1305, 1225, 1223, -1, + 1223, 1306, 1305, -1, 1306, 1223, 1221, -1, + 1221, 1307, 1306, -1, 1307, 1221, 1219, -1, + 1219, 1308, 1307, -1, 1308, 1219, 1217, -1, + 1217, 1309, 1308, -1, 1309, 1217, 1215, -1, + 1215, 1310, 1309, -1, 1310, 1215, 1213, -1, + 1213, 1311, 1310, -1, 1311, 1213, 1211, -1, + 1211, 1312, 1311, -1, 1312, 1211, 1209, -1, + 1209, 1313, 1312, -1, 1313, 1209, 1207, -1, + 1207, 1314, 1313, -1, 1314, 1207, 1205, -1, + 1205, 1315, 1314, -1, 1315, 1205, 1203, -1, + 1203, 1316, 1315, -1, 1316, 1203, 1201, -1, + 1201, 1317, 1316, -1, 1317, 1201, 1199, -1, + 1199, 1318, 1317, -1, 1318, 1199, 1197, -1, + 1197, 1319, 1318, -1, 1319, 1197, 1195, -1, + 1195, 1320, 1319, -1, 1320, 1195, 1193, -1, + 1193, 1321, 1320, -1, 1321, 1193, 1191, -1, + 1191, 1322, 1321, -1, 1322, 1191, 1189, -1, + 1189, 1323, 1322, -1, 1323, 1189, 1186, -1, + 1186, 1324, 1323, -1, 1186, 1188, 1324, -1, + 1325, 1324, 1188, -1, 1325, 1326, 1324, -1, + 1326, 1325, 1327, -1, 1327, 1328, 1326, -1, + 1328, 1327, 1329, -1, 1329, 1330, 1328, -1, + 1330, 1329, 1331, -1, 1331, 1332, 1330, -1, + 1332, 1331, 1333, -1, 1333, 1334, 1332, -1, + 1334, 1333, 1335, -1, 1335, 1336, 1334, -1, + 1336, 1335, 1337, -1, 1337, 1338, 1336, -1, + 1338, 1337, 1339, -1, 1339, 1340, 1338, -1, + 1340, 1339, 1341, -1, 1341, 1342, 1340, -1, + 1342, 1341, 1343, -1, 1343, 1344, 1342, -1, + 1344, 1343, 1345, -1, 1345, 1346, 1344, -1, + 1347, 1348, 1349, -1, 1349, 1348, 1350, -1, + 1349, 1350, 1346, -1, 1346, 1345, 1349, -1, + 1351, 1352, 1353, -1, 1354, 1355, 1356, -1, + 1354, 1356, 1357, -1, 1357, 1358, 1354, -1, + 1358, 1357, 1359, -1, 1359, 1360, 1358, -1, + 1360, 1359, 1361, -1, 1361, 1362, 1360, -1, + 1363, 1364, 1365, -1, 1363, 1366, 1364, -1, + 1363, 1367, 1366, -1, 1363, 1365, 1367, -1, + 1367, 1368, 1369, -1, 1370, 1371, 1368, -1, + 1370, 1368, 1372, -1, 1372, 1373, 1370, -1, + 1374, 1375, 1376, -1, 1377, 1378, 1379, -1, + 1379, 1380, 1377, -1, 1380, 1379, 1381, -1, + 1381, 1382, 1380, -1, 1382, 1381, 1383, -1, + 1383, 1384, 1382, -1, 1384, 1383, 1385, -1, + 1385, 1386, 1384, -1, 1387, 1376, 1386, -1, + 1386, 1385, 1387, -1, 1388, 1389, 1390, -1, + 1389, 1388, 1391, -1, 1389, 1391, 1392, -1, + 1392, 1393, 1389, -1, 1393, 1392, 1394, -1, + 1394, 1395, 1393, -1, 1395, 1394, 1396, -1, + 1396, 1397, 1395, -1, 1397, 1396, 1398, -1, + 1398, 1399, 1397, -1, 1399, 1398, 1400, -1, + 1401, 1400, 1398, -1, 1400, 1401, 1402, -1, + 1403, 1404, 1405, -1, 1403, 1402, 1404, -1, + 1403, 1406, 1402, -1, 1403, 1405, 1406, -1, + 1406, 1405, 1407, -1, 1407, 1402, 1406, -1, + 1407, 1408, 1402, -1, 1408, 1400, 1402, -1, + 1408, 1399, 1400, -1, 1408, 1407, 1399, -1, + 1399, 1407, 1405, -1, 1399, 1405, 1409, -1, + 1409, 1397, 1399, -1, 1397, 1409, 1410, -1, + 1410, 1395, 1397, -1, 1395, 1410, 1411, -1, + 1411, 1393, 1395, -1, 1393, 1411, 1412, -1, + 1412, 1389, 1393, -1, 1412, 1390, 1389, -1, + 1412, 1413, 1390, -1, 1413, 1412, 1411, -1, + 1411, 1414, 1413, -1, 1414, 1411, 1410, -1, + 1410, 1415, 1414, -1, 1415, 1410, 1409, -1, + 1409, 1416, 1415, -1, 1416, 1409, 1405, -1, + 1405, 1417, 1416, -1, 1417, 1405, 1404, -1, + 1418, 1417, 1404, -1, 1418, 1419, 1417, -1, + 1387, 1417, 1419, -1, 1417, 1387, 1385, -1, + 1385, 1416, 1417, -1, 1416, 1385, 1383, -1, + 1383, 1415, 1416, -1, 1415, 1383, 1381, -1, + 1381, 1414, 1415, -1, 1414, 1381, 1379, -1, + 1379, 1413, 1414, -1, 1413, 1379, 1378, -1, + 1378, 1390, 1413, -1, 1378, 1420, 1390, -1, + 1378, 1377, 1420, -1, 1421, 1422, 1423, -1, + 1424, 1425, 1426, -1, 1424, 1427, 1425, -1, + 1424, 1428, 1427, -1, 1424, 1426, 1428, -1, + 1426, 1429, 1430, -1, 1352, 1428, 1426, -1, + 1431, 1432, 1433, -1, 1432, 1431, 1352, -1, + 1431, 1428, 1352, -1, 1431, 1433, 1428, -1, + 1433, 1427, 1428, -1, 1427, 1433, 1434, -1, + 1434, 1435, 1427, -1, 1435, 1434, 1436, -1, + 1436, 1437, 1435, -1, 1437, 1436, 1438, -1, + 1438, 1439, 1437, -1, 1439, 1438, 1440, -1, + 1440, 1441, 1439, -1, 1441, 1440, 1442, -1, + 1442, 1443, 1441, -1, 1443, 1442, 1444, -1, + 1444, 1445, 1443, -1, 1445, 1444, 1422, -1, + 1422, 1421, 1445, -1, 1421, 1446, 1420, -1, + 1420, 1445, 1421, -1, 1445, 1420, 1377, -1, + 1377, 1443, 1445, -1, 1443, 1377, 1380, -1, + 1380, 1441, 1443, -1, 1441, 1380, 1382, -1, + 1382, 1439, 1441, -1, 1439, 1382, 1384, -1, + 1384, 1437, 1439, -1, 1437, 1384, 1386, -1, + 1386, 1435, 1437, -1, 1435, 1386, 1376, -1, + 1376, 1427, 1435, -1, 1427, 1376, 1375, -1, + 1375, 1425, 1427, -1, 1375, 1426, 1425, -1, + 1375, 1374, 1426, -1, 1374, 1429, 1426, -1, + 1374, 1376, 1429, -1, 1376, 1387, 1429, -1, + 1447, 1429, 1387, -1, 1447, 1430, 1429, -1, + 1447, 1448, 1430, -1, 1447, 1387, 1448, -1, + 1448, 1387, 1419, -1, 1419, 1430, 1448, -1, + 1419, 1418, 1430, -1, 1418, 1404, 1430, -1, + 1430, 1404, 1402, -1, 1449, 1402, 1401, -1, + 1450, 1449, 1401, -1, 1401, 1398, 1450, -1, + 1398, 1451, 1450, -1, 1451, 1398, 1396, -1, + 1396, 1452, 1451, -1, 1452, 1396, 1394, -1, + 1394, 1453, 1452, -1, 1453, 1394, 1392, -1, + 1392, 1454, 1453, -1, 1454, 1392, 1391, -1, + 1391, 1455, 1454, -1, 1391, 1456, 1455, -1, + 1456, 1391, 1388, -1, 1388, 1457, 1456, -1, + 1388, 1390, 1457, -1, 1458, 1457, 1390, -1, + 1458, 1390, 1420, -1, 1458, 1420, 1446, -1, + 1446, 1459, 1458, -1, 1460, 1461, 1462, -1, + 1460, 1373, 1463, -1, 1373, 1460, 1464, -1, + 1464, 1465, 1373, -1, 1465, 1464, 1466, -1, + 1466, 1467, 1465, -1, 1466, 1468, 1467, -1, + 1466, 1469, 1468, -1, 1469, 1466, 1464, -1, + 1464, 1470, 1469, -1, 1470, 1464, 1460, -1, + 1460, 1462, 1470, -1, 1471, 1472, 1473, -1, + 1471, 1474, 1472, -1, 1475, 1462, 1476, -1, + 1477, 1476, 1462, -1, 1476, 1477, 1472, -1, + 1476, 1472, 1474, -1, 1474, 1475, 1476, -1, + 1474, 1471, 1475, -1, 1471, 1473, 1475, -1, + 1478, 1475, 1473, -1, 1475, 1478, 1479, -1, + 1479, 1462, 1475, -1, 1462, 1479, 1480, -1, + 1480, 1470, 1462, -1, 1470, 1480, 1481, -1, + 1481, 1469, 1470, -1, 1469, 1481, 1482, -1, + 1482, 1468, 1469, -1, 1482, 1483, 1468, -1, + 1483, 1482, 1484, -1, 1484, 1485, 1483, -1, + 1485, 1484, 1486, -1, 1486, 1487, 1485, -1, + 1487, 1486, 1488, -1, 1488, 1459, 1487, -1, + 1488, 1458, 1459, -1, 1488, 1457, 1458, -1, + 1457, 1488, 1486, -1, 1486, 1456, 1457, -1, + 1456, 1486, 1484, -1, 1484, 1455, 1456, -1, + 1455, 1484, 1482, -1, 1455, 1482, 1481, -1, + 1481, 1454, 1455, -1, 1454, 1481, 1480, -1, + 1480, 1453, 1454, -1, 1453, 1480, 1479, -1, + 1479, 1452, 1453, -1, 1452, 1479, 1478, -1, + 1478, 1451, 1452, -1, 1451, 1478, 1489, -1, + 1490, 1451, 1489, -1, 1490, 1491, 1451, -1, + 1491, 1450, 1451, -1, 1491, 1449, 1450, -1, + 1491, 1490, 1449, -1, 1490, 1489, 1449, -1, + 1489, 1492, 1449, -1, 1492, 1489, 1478, -1, + 1492, 1478, 1473, -1, 1492, 1473, 1472, -1, + 1472, 1449, 1492, -1, 1493, 1472, 1477, -1, + 1477, 1494, 1493, -1, 1477, 1462, 1494, -1, + 1494, 1462, 1461, -1, 1461, 1493, 1494, -1, + 1461, 1495, 1493, -1, 1495, 1461, 1460, -1, + 1495, 1460, 1463, -1, 1463, 1493, 1495, -1, + 1463, 1496, 1493, -1, 1496, 1463, 1373, -1, + 1496, 1373, 1372, -1, 1372, 1368, 1496, -1, + 1368, 1493, 1496, -1, 1497, 1367, 1365, -1, + 1498, 1497, 1365, -1, 1499, 1500, 1501, -1, + 1499, 1501, 1502, -1, 1502, 1503, 1499, -1, + 1503, 1502, 1504, -1, 1503, 1504, 1505, -1, + 1503, 1505, 1506, -1, 1506, 1499, 1503, -1, + 1506, 1507, 1499, -1, 1508, 1497, 1509, -1, + 1508, 1507, 1497, -1, 1508, 1499, 1507, -1, + 1508, 1509, 1499, -1, 1509, 1500, 1499, -1, + 1500, 1509, 1497, -1, 1500, 1497, 1498, -1, + 1498, 1501, 1500, -1, 1498, 1365, 1501, -1, + 1501, 1365, 1364, -1, 1501, 1364, 1510, -1, + 1510, 1502, 1501, -1, 1502, 1510, 1511, -1, + 1511, 1504, 1502, -1, 1511, 1512, 1504, -1, + 1512, 1511, 1513, -1, 1513, 1514, 1512, -1, + 1514, 1513, 1515, -1, 1515, 1516, 1514, -1, + 1516, 1515, 1517, -1, 1517, 1518, 1516, -1, + 1518, 1517, 1519, -1, 1519, 1520, 1518, -1, + 1520, 1519, 1521, -1, 1521, 1522, 1520, -1, + 1522, 1521, 1523, -1, 1523, 1524, 1522, -1, + 1525, 1522, 1524, -1, 1522, 1525, 1526, -1, + 1526, 1520, 1522, -1, 1520, 1526, 1527, -1, + 1527, 1518, 1520, -1, 1518, 1527, 1528, -1, + 1528, 1516, 1518, -1, 1516, 1528, 1529, -1, + 1529, 1514, 1516, -1, 1514, 1529, 1530, -1, + 1530, 1512, 1514, -1, 1512, 1530, 1531, -1, + 1531, 1504, 1512, -1, 1504, 1531, 1532, -1, + 1532, 1505, 1504, -1, 1505, 1532, 1533, -1, + 1505, 1533, 1534, -1, 1534, 1506, 1505, -1, + 1534, 1535, 1506, -1, 1536, 1537, 1538, -1, + 1539, 1537, 1536, -1, 1536, 1534, 1539, -1, + 1536, 1538, 1534, -1, 1538, 1535, 1534, -1, + 1535, 1538, 1537, -1, 1535, 1537, 1540, -1, + 1540, 1506, 1535, -1, 1540, 1507, 1506, -1, + 1540, 1537, 1507, -1, 1537, 1497, 1507, -1, + 1537, 1539, 1541, -1, 1542, 1541, 1539, -1, + 1542, 1543, 1541, -1, 1542, 1544, 1543, -1, + 1542, 1539, 1544, -1, 1544, 1539, 1534, -1, + 1544, 1534, 1533, -1, 1533, 1545, 1544, -1, + 1533, 1546, 1545, -1, 1546, 1533, 1532, -1, + 1532, 1547, 1546, -1, 1547, 1532, 1531, -1, + 1531, 1548, 1547, -1, 1548, 1531, 1530, -1, + 1530, 1549, 1548, -1, 1549, 1530, 1529, -1, + 1529, 1550, 1549, -1, 1550, 1529, 1528, -1, + 1528, 1551, 1550, -1, 1551, 1528, 1527, -1, + 1527, 1552, 1551, -1, 1552, 1527, 1526, -1, + 1526, 1553, 1552, -1, 1553, 1526, 1525, -1, + 1525, 1554, 1553, -1, 1525, 1524, 1554, -1, + 1555, 1556, 1557, -1, 1557, 1558, 1555, -1, + 1559, 1558, 1557, -1, 1560, 1558, 1561, -1, + 1558, 1560, 1562, -1, 1563, 1564, 1565, -1, + 1563, 1566, 1564, -1, 1566, 1563, 1567, -1, + 1567, 1568, 1566, -1, 1568, 1567, 1569, -1, + 1569, 1570, 1568, -1, 1570, 1569, 1571, -1, + 1571, 1572, 1570, -1, 1572, 1571, 1573, -1, + 1573, 1574, 1572, -1, 1574, 1573, 1575, -1, + 1575, 1576, 1574, -1, 1575, 1577, 1576, -1, + 1577, 1575, 1578, -1, 1578, 1579, 1577, -1, + 1579, 1580, 1581, -1, 1579, 1578, 1580, -1, + 1582, 1583, 1580, -1, 1580, 1584, 1582, -1, + 1584, 1580, 1578, -1, 1578, 1585, 1584, -1, + 1585, 1578, 1575, -1, 1585, 1575, 1573, -1, + 1573, 1586, 1585, -1, 1586, 1573, 1571, -1, + 1571, 1587, 1586, -1, 1587, 1571, 1569, -1, + 1569, 1588, 1587, -1, 1588, 1569, 1567, -1, + 1567, 1589, 1588, -1, 1589, 1567, 1563, -1, + 1563, 1565, 1589, -1, 1590, 1591, 1592, -1, + 1593, 1592, 1591, -1, 1591, 1594, 1593, -1, + 1595, 1596, 1597, -1, 1596, 1598, 1599, -1, + 1599, 1597, 1596, -1, 1600, 1597, 1599, -1, + 1600, 1599, 1601, -1, 1601, 1602, 1600, -1, + 1601, 1603, 1602, -1, 1604, 1605, 1606, -1, + 1605, 1607, 1606, -1, 1608, 1606, 1607, -1, + 1608, 1609, 1606, -1, 1610, 1611, 1612, -1, + 1613, 1614, 1611, -1, 1614, 1613, 1615, -1, + 1613, 1616, 1615, -1, 1613, 1611, 1616, -1, + 1617, 1616, 1611, -1, 1611, 1610, 1617, -1, + 1618, 1619, 1617, -1, 1617, 1620, 1618, -1, + 1620, 1617, 1610, -1, 1610, 1621, 1620, -1, + 1621, 1610, 1612, -1, 1612, 1622, 1621, -1, + 1622, 1612, 1623, -1, 1623, 1624, 1622, -1, + 1624, 1623, 1625, -1, 1625, 1626, 1624, -1, + 1626, 1625, 1627, -1, 1627, 1628, 1626, -1, + 1628, 1627, 1629, -1, 1629, 1630, 1628, -1, + 1631, 1632, 1633, -1, 1631, 1633, 1630, -1, + 1630, 1629, 1631, -1, 1631, 1634, 1635, -1, + 1634, 1631, 1629, -1, 1634, 1629, 1636, -1, + 1636, 1637, 1634, -1, 1636, 1638, 1637, -1, + 1638, 1636, 1639, -1, 1639, 1640, 1638, -1, + 1640, 1639, 1641, -1, 1641, 1642, 1640, -1, + 1642, 1641, 1609, -1, 1609, 1608, 1642, -1, + 1643, 1644, 1645, -1, 1644, 1643, 1602, -1, + 1643, 1646, 1602, -1, 1643, 1645, 1646, -1, + 1608, 1646, 1645, -1, 1645, 1642, 1608, -1, + 1642, 1645, 1647, -1, 1647, 1640, 1642, -1, + 1640, 1647, 1648, -1, 1648, 1638, 1640, -1, + 1638, 1648, 1649, -1, 1649, 1637, 1638, -1, + 1649, 1650, 1637, -1, 1649, 1651, 1650, -1, + 1651, 1649, 1648, -1, 1648, 1652, 1651, -1, + 1652, 1648, 1647, -1, 1647, 1653, 1652, -1, + 1653, 1647, 1645, -1, 1645, 1644, 1653, -1, + 1654, 1653, 1644, -1, 1654, 1644, 1602, -1, + 1654, 1602, 1603, -1, 1603, 1653, 1654, -1, + 1603, 1601, 1653, -1, 1653, 1601, 1599, -1, + 1599, 1652, 1653, -1, 1652, 1599, 1598, -1, + 1598, 1651, 1652, -1, 1651, 1598, 1655, -1, + 1655, 1650, 1651, -1, 1650, 1655, 1656, -1, + 1650, 1656, 1657, -1, 1657, 1637, 1650, -1, + 1637, 1657, 1658, -1, 1658, 1634, 1637, -1, + 1658, 1635, 1634, -1, 1658, 1659, 1635, -1, + 1659, 1658, 1657, -1, 1657, 1660, 1659, -1, + 1660, 1657, 1656, -1, 1656, 1661, 1660, -1, + 1656, 1662, 1661, -1, 1662, 1656, 1655, -1, + 1655, 1663, 1662, -1, 1663, 1655, 1598, -1, + 1598, 1596, 1663, -1, 1596, 1664, 1593, -1, + 1593, 1663, 1596, -1, 1663, 1593, 1594, -1, + 1594, 1662, 1663, -1, 1662, 1594, 1665, -1, + 1665, 1661, 1662, -1, 1661, 1665, 1666, -1, + 1661, 1666, 1667, -1, 1667, 1660, 1661, -1, + 1660, 1667, 1668, -1, 1668, 1659, 1660, -1, + 1659, 1668, 1669, -1, 1669, 1635, 1659, -1, + 1669, 1565, 1635, -1, 1669, 1589, 1565, -1, + 1589, 1669, 1668, -1, 1668, 1588, 1589, -1, + 1588, 1668, 1667, -1, 1667, 1587, 1588, -1, + 1587, 1667, 1666, -1, 1666, 1586, 1587, -1, + 1666, 1670, 1586, -1, 1670, 1666, 1665, -1, + 1665, 1671, 1670, -1, 1671, 1665, 1594, -1, + 1594, 1591, 1671, -1, 1591, 1672, 1673, -1, + 1673, 1671, 1591, -1, 1671, 1673, 1674, -1, + 1674, 1670, 1671, -1, 1670, 1674, 1675, -1, + 1675, 1586, 1670, -1, 1675, 1585, 1586, -1, + 1675, 1584, 1585, -1, 1584, 1675, 1674, -1, + 1674, 1582, 1584, -1, 1582, 1674, 1673, -1, + 1582, 1673, 1676, -1, 1677, 1676, 1673, -1, + 1676, 1677, 1562, -1, 1676, 1562, 1678, -1, + 1678, 1582, 1676, -1, 1678, 1583, 1582, -1, + 1678, 1562, 1583, -1, 1583, 1562, 1560, -1, + 1560, 1580, 1583, -1, 1560, 1561, 1580, -1, + 1561, 1581, 1580, -1, 1581, 1561, 1558, -1, + 1581, 1558, 1559, -1, 1559, 1579, 1581, -1, + 1559, 1557, 1579, -1, 1579, 1557, 1556, -1, + 1556, 1577, 1579, -1, 1577, 1556, 1679, -1, + 1679, 1576, 1577, -1, 1576, 1679, 1680, -1, + 1576, 1680, 1681, -1, 1681, 1574, 1576, -1, + 1574, 1681, 1682, -1, 1682, 1572, 1574, -1, + 1572, 1682, 1683, -1, 1683, 1570, 1572, -1, + 1570, 1683, 1684, -1, 1684, 1568, 1570, -1, + 1568, 1684, 1685, -1, 1685, 1566, 1568, -1, + 1566, 1685, 1686, -1, 1686, 1564, 1566, -1, + 1686, 1687, 1564, -1, 1687, 1686, 1688, -1, + 1688, 1689, 1687, -1, 1689, 1688, 1690, -1, + 1690, 1691, 1689, -1, 1691, 1690, 1692, -1, + 1692, 1693, 1691, -1, 1693, 1692, 1694, -1, + 1694, 1695, 1693, -1, 1695, 1694, 1696, -1, + 1696, 1697, 1695, -1, 1697, 1696, 1698, -1, + 1698, 1699, 1697, -1, 1699, 1698, 1700, -1, + 1700, 1701, 1699, -1, 1701, 1700, 1702, -1, + 1702, 1703, 1701, -1, 1703, 1702, 1704, -1, + 1704, 1705, 1703, -1, 1705, 1704, 1706, -1, + 1706, 1707, 1705, -1, 1707, 1706, 1708, -1, + 1708, 1709, 1707, -1, 1709, 1708, 1710, -1, + 1710, 1711, 1709, -1, 1711, 1710, 1712, -1, + 1712, 1713, 1711, -1, 1713, 1712, 1714, -1, + 1714, 1715, 1713, -1, 1715, 1714, 1716, -1, + 1716, 1717, 1715, -1, 1717, 1716, 1718, -1, + 1718, 1719, 1717, -1, 1719, 1718, 1720, -1, + 1720, 1721, 1719, -1, 1721, 1720, 1722, -1, + 1722, 1723, 1721, -1, 1723, 1722, 1724, -1, + 1724, 1725, 1723, -1, 1724, 1726, 1725, -1, + 1726, 1724, 1727, -1, 1727, 1728, 1726, -1, + 1728, 1727, 1729, -1, 1729, 1730, 1728, -1, + 1730, 1729, 1731, -1, 1731, 1732, 1730, -1, + 1732, 1731, 1733, -1, 1733, 1734, 1732, -1, + 1734, 1733, 1735, -1, 1735, 1736, 1734, -1, + 1736, 1735, 1737, -1, 1737, 1738, 1736, -1, + 1738, 1737, 1739, -1, 1739, 1740, 1738, -1, + 1740, 1739, 1741, -1, 1741, 1742, 1740, -1, + 1742, 1741, 1743, -1, 1743, 1744, 1742, -1, + 1744, 1743, 1745, -1, 1745, 1746, 1744, -1, + 1746, 1745, 1747, -1, 1747, 1748, 1746, -1, + 1748, 1747, 1749, -1, 1749, 1750, 1748, -1, + 1750, 1749, 1751, -1, 1751, 1752, 1750, -1, + 1752, 1751, 1753, -1, 1753, 1754, 1752, -1, + 1754, 1753, 1755, -1, 1755, 1756, 1754, -1, + 1756, 1755, 1757, -1, 1757, 1758, 1756, -1, + 1758, 1757, 1759, -1, 1759, 1760, 1758, -1, + 1760, 1759, 1554, -1, 1554, 1761, 1760, -1, + 1761, 1554, 1524, -1, 1524, 1762, 1761, -1, + 1524, 1523, 1762, -1, 1763, 1764, 1765, -1, + 1764, 1763, 1766, -1, 1766, 1767, 1764, -1, + 1767, 1766, 1768, -1, 1768, 1769, 1767, -1, + 1768, 1770, 1769, -1, 1770, 1768, 1771, -1, + 1771, 1772, 1770, -1, 1772, 1771, 1773, -1, + 1773, 1774, 1772, -1, 1774, 1773, 1775, -1, + 1775, 1776, 1774, -1, 1776, 1775, 1777, -1, + 1777, 1778, 1776, -1, 1778, 1777, 1779, -1, + 1779, 1780, 1778, -1, 1780, 1779, 1781, -1, + 1780, 1781, 1762, -1, 1780, 1762, 1523, -1, + 1523, 1778, 1780, -1, 1778, 1523, 1521, -1, + 1521, 1776, 1778, -1, 1776, 1521, 1519, -1, + 1519, 1774, 1776, -1, 1774, 1519, 1517, -1, + 1517, 1772, 1774, -1, 1772, 1517, 1515, -1, + 1515, 1770, 1772, -1, 1770, 1515, 1513, -1, + 1513, 1769, 1770, -1, 1769, 1513, 1511, -1, + 1769, 1511, 1510, -1, 1510, 1767, 1769, -1, + 1767, 1510, 1364, -1, 1364, 1764, 1767, -1, + 1364, 1782, 1764, -1, 1782, 1364, 1366, -1, + 1782, 1366, 1367, -1, 1782, 1367, 1369, -1, + 1369, 1764, 1782, -1, 1369, 1765, 1764, -1, + 1765, 1369, 1368, -1, 1765, 1368, 1371, -1, + 1371, 1763, 1765, -1, 1371, 1370, 1763, -1, + 1763, 1370, 1373, -1, 1763, 1373, 1465, -1, + 1465, 1766, 1763, -1, 1766, 1465, 1467, -1, + 1467, 1768, 1766, -1, 1467, 1771, 1768, -1, + 1771, 1467, 1468, -1, 1468, 1773, 1771, -1, + 1773, 1468, 1483, -1, 1483, 1775, 1773, -1, + 1775, 1483, 1485, -1, 1485, 1777, 1775, -1, + 1777, 1485, 1487, -1, 1487, 1779, 1777, -1, + 1779, 1487, 1459, -1, 1459, 1781, 1779, -1, + 1781, 1459, 1446, -1, 1781, 1446, 1783, -1, + 1783, 1762, 1781, -1, 1762, 1783, 1784, -1, + 1784, 1761, 1762, -1, 1761, 1784, 1785, -1, + 1785, 1760, 1761, -1, 1760, 1785, 1786, -1, + 1786, 1758, 1760, -1, 1758, 1786, 1787, -1, + 1787, 1756, 1758, -1, 1756, 1787, 1788, -1, + 1788, 1754, 1756, -1, 1754, 1788, 1789, -1, + 1789, 1752, 1754, -1, 1752, 1789, 1790, -1, + 1790, 1750, 1752, -1, 1750, 1790, 1791, -1, + 1791, 1748, 1750, -1, 1748, 1791, 1792, -1, + 1792, 1746, 1748, -1, 1746, 1792, 1793, -1, + 1793, 1744, 1746, -1, 1744, 1793, 1794, -1, + 1794, 1742, 1744, -1, 1742, 1794, 1795, -1, + 1795, 1740, 1742, -1, 1740, 1795, 1796, -1, + 1796, 1738, 1740, -1, 1738, 1796, 1797, -1, + 1797, 1736, 1738, -1, 1736, 1797, 1798, -1, + 1798, 1734, 1736, -1, 1734, 1798, 1799, -1, + 1799, 1732, 1734, -1, 1732, 1799, 1800, -1, + 1800, 1730, 1732, -1, 1730, 1800, 1801, -1, + 1801, 1728, 1730, -1, 1728, 1801, 1802, -1, + 1802, 1726, 1728, -1, 1726, 1802, 1803, -1, + 1803, 1725, 1726, -1, 1725, 1803, 1804, -1, + 1725, 1804, 1805, -1, 1805, 1723, 1725, -1, + 1723, 1805, 1806, -1, 1806, 1721, 1723, -1, + 1721, 1806, 1807, -1, 1807, 1719, 1721, -1, + 1719, 1807, 1808, -1, 1808, 1717, 1719, -1, + 1717, 1808, 1809, -1, 1809, 1715, 1717, -1, + 1715, 1809, 1810, -1, 1810, 1713, 1715, -1, + 1713, 1810, 1811, -1, 1811, 1711, 1713, -1, + 1711, 1811, 1812, -1, 1812, 1709, 1711, -1, + 1709, 1812, 1813, -1, 1813, 1707, 1709, -1, + 1707, 1813, 1814, -1, 1814, 1705, 1707, -1, + 1705, 1814, 1815, -1, 1815, 1703, 1705, -1, + 1703, 1815, 1816, -1, 1816, 1701, 1703, -1, + 1701, 1816, 1817, -1, 1817, 1699, 1701, -1, + 1699, 1817, 1818, -1, 1818, 1697, 1699, -1, + 1697, 1818, 1819, -1, 1819, 1695, 1697, -1, + 1695, 1819, 1820, -1, 1820, 1693, 1695, -1, + 1693, 1820, 1821, -1, 1821, 1691, 1693, -1, + 1691, 1821, 1822, -1, 1822, 1689, 1691, -1, + 1689, 1822, 1823, -1, 1823, 1687, 1689, -1, + 1687, 1823, 1824, -1, 1824, 1564, 1687, -1, + 1564, 1824, 1825, -1, 1825, 1565, 1564, -1, + 1565, 1825, 1826, -1, 1826, 1635, 1565, -1, + 1826, 1631, 1635, -1, 1826, 1632, 1631, -1, + 1632, 1826, 1825, -1, 1825, 1827, 1632, -1, + 1827, 1825, 1824, -1, 1824, 1828, 1827, -1, + 1828, 1824, 1823, -1, 1823, 1829, 1828, -1, + 1829, 1823, 1822, -1, 1822, 1830, 1829, -1, + 1830, 1822, 1821, -1, 1821, 1831, 1830, -1, + 1831, 1821, 1820, -1, 1820, 1832, 1831, -1, + 1832, 1820, 1819, -1, 1819, 1833, 1832, -1, + 1833, 1819, 1818, -1, 1818, 1834, 1833, -1, + 1834, 1818, 1817, -1, 1817, 1835, 1834, -1, + 1835, 1817, 1816, -1, 1816, 1836, 1835, -1, + 1836, 1816, 1815, -1, 1815, 1837, 1836, -1, + 1837, 1815, 1814, -1, 1814, 1838, 1837, -1, + 1838, 1814, 1813, -1, 1813, 1839, 1838, -1, + 1839, 1813, 1812, -1, 1812, 1840, 1839, -1, + 1840, 1812, 1811, -1, 1811, 1841, 1840, -1, + 1841, 1811, 1810, -1, 1810, 1842, 1841, -1, + 1842, 1810, 1809, -1, 1809, 1843, 1842, -1, + 1843, 1809, 1808, -1, 1808, 1844, 1843, -1, + 1844, 1808, 1807, -1, 1807, 1845, 1844, -1, + 1845, 1807, 1806, -1, 1806, 1846, 1845, -1, + 1846, 1806, 1805, -1, 1805, 1847, 1846, -1, + 1847, 1805, 1804, -1, 1804, 1848, 1847, -1, + 1804, 1849, 1848, -1, 1849, 1804, 1803, -1, + 1803, 1850, 1849, -1, 1850, 1803, 1802, -1, + 1802, 1851, 1850, -1, 1851, 1802, 1801, -1, + 1801, 1852, 1851, -1, 1852, 1801, 1800, -1, + 1800, 1853, 1852, -1, 1853, 1800, 1799, -1, + 1799, 1854, 1853, -1, 1854, 1799, 1798, -1, + 1798, 1855, 1854, -1, 1855, 1798, 1797, -1, + 1797, 1856, 1855, -1, 1856, 1797, 1796, -1, + 1796, 1857, 1856, -1, 1857, 1796, 1795, -1, + 1795, 1858, 1857, -1, 1858, 1795, 1794, -1, + 1794, 1859, 1858, -1, 1859, 1794, 1793, -1, + 1793, 1860, 1859, -1, 1860, 1793, 1792, -1, + 1792, 1861, 1860, -1, 1861, 1792, 1791, -1, + 1791, 1862, 1861, -1, 1862, 1791, 1790, -1, + 1790, 1863, 1862, -1, 1863, 1790, 1789, -1, + 1789, 1864, 1863, -1, 1864, 1789, 1788, -1, + 1788, 1865, 1864, -1, 1865, 1788, 1787, -1, + 1787, 1866, 1865, -1, 1866, 1787, 1786, -1, + 1786, 1867, 1866, -1, 1867, 1786, 1785, -1, + 1785, 1868, 1867, -1, 1868, 1785, 1784, -1, + 1784, 1869, 1868, -1, 1869, 1784, 1783, -1, + 1783, 1870, 1869, -1, 1870, 1783, 1446, -1, + 1446, 1421, 1870, -1, 1421, 1423, 1870, -1, + 1871, 1870, 1423, -1, 1871, 1869, 1870, -1, + 1869, 1871, 1872, -1, 1872, 1868, 1869, -1, + 1868, 1872, 1873, -1, 1873, 1867, 1868, -1, + 1867, 1873, 1874, -1, 1874, 1866, 1867, -1, + 1866, 1874, 1875, -1, 1875, 1865, 1866, -1, + 1865, 1875, 1876, -1, 1876, 1864, 1865, -1, + 1864, 1876, 1877, -1, 1877, 1863, 1864, -1, + 1863, 1877, 1878, -1, 1878, 1862, 1863, -1, + 1862, 1878, 1879, -1, 1879, 1861, 1862, -1, + 1861, 1879, 1880, -1, 1880, 1860, 1861, -1, + 1860, 1880, 1881, -1, 1881, 1859, 1860, -1, + 1859, 1881, 1882, -1, 1882, 1858, 1859, -1, + 1858, 1882, 1883, -1, 1883, 1857, 1858, -1, + 1857, 1883, 1884, -1, 1884, 1856, 1857, -1, + 1856, 1884, 1885, -1, 1885, 1855, 1856, -1, + 1855, 1885, 1886, -1, 1886, 1854, 1855, -1, + 1854, 1886, 1887, -1, 1887, 1853, 1854, -1, + 1853, 1887, 1888, -1, 1888, 1852, 1853, -1, + 1852, 1888, 1889, -1, 1889, 1851, 1852, -1, + 1851, 1889, 1890, -1, 1890, 1850, 1851, -1, + 1850, 1890, 1891, -1, 1891, 1849, 1850, -1, + 1849, 1891, 1892, -1, 1892, 1848, 1849, -1, + 1848, 1892, 1893, -1, 1848, 1893, 1894, -1, + 1894, 1847, 1848, -1, 1847, 1894, 1895, -1, + 1895, 1846, 1847, -1, 1846, 1895, 1896, -1, + 1896, 1845, 1846, -1, 1845, 1896, 1897, -1, + 1897, 1844, 1845, -1, 1844, 1897, 1898, -1, + 1898, 1843, 1844, -1, 1843, 1898, 1899, -1, + 1899, 1842, 1843, -1, 1842, 1899, 1900, -1, + 1900, 1841, 1842, -1, 1841, 1900, 1901, -1, + 1901, 1840, 1841, -1, 1840, 1901, 1902, -1, + 1902, 1839, 1840, -1, 1839, 1902, 1903, -1, + 1903, 1838, 1839, -1, 1838, 1903, 1904, -1, + 1904, 1837, 1838, -1, 1837, 1904, 1905, -1, + 1905, 1836, 1837, -1, 1836, 1905, 1906, -1, + 1906, 1835, 1836, -1, 1835, 1906, 1907, -1, + 1907, 1834, 1835, -1, 1834, 1907, 1908, -1, + 1908, 1833, 1834, -1, 1833, 1908, 1909, -1, + 1909, 1832, 1833, -1, 1832, 1909, 1910, -1, + 1910, 1831, 1832, -1, 1831, 1910, 1911, -1, + 1911, 1830, 1831, -1, 1830, 1911, 1912, -1, + 1912, 1829, 1830, -1, 1829, 1912, 1913, -1, + 1913, 1828, 1829, -1, 1828, 1913, 1914, -1, + 1914, 1827, 1828, -1, 1827, 1914, 1915, -1, + 1915, 1632, 1827, -1, 1915, 1633, 1632, -1, + 1915, 1916, 1633, -1, 1916, 1915, 1914, -1, + 1914, 1917, 1916, -1, 1917, 1914, 1913, -1, + 1913, 1918, 1917, -1, 1918, 1913, 1912, -1, + 1912, 1919, 1918, -1, 1919, 1912, 1911, -1, + 1911, 1920, 1919, -1, 1920, 1911, 1910, -1, + 1910, 1921, 1920, -1, 1921, 1910, 1909, -1, + 1909, 1922, 1921, -1, 1922, 1909, 1908, -1, + 1908, 1923, 1922, -1, 1923, 1908, 1907, -1, + 1907, 1924, 1923, -1, 1924, 1907, 1906, -1, + 1906, 1925, 1924, -1, 1925, 1906, 1905, -1, + 1905, 1926, 1925, -1, 1926, 1905, 1904, -1, + 1904, 1927, 1926, -1, 1927, 1904, 1903, -1, + 1903, 1928, 1927, -1, 1928, 1903, 1902, -1, + 1902, 1929, 1928, -1, 1929, 1902, 1901, -1, + 1901, 1930, 1929, -1, 1930, 1901, 1900, -1, + 1900, 1931, 1930, -1, 1931, 1900, 1899, -1, + 1899, 1932, 1931, -1, 1932, 1899, 1898, -1, + 1898, 1933, 1932, -1, 1933, 1898, 1897, -1, + 1897, 1934, 1933, -1, 1934, 1897, 1896, -1, + 1896, 1935, 1934, -1, 1935, 1896, 1895, -1, + 1895, 1936, 1935, -1, 1936, 1895, 1894, -1, + 1894, 1937, 1936, -1, 1937, 1894, 1893, -1, + 1893, 1938, 1937, -1, 1893, 1939, 1938, -1, + 1939, 1893, 1892, -1, 1892, 1940, 1939, -1, + 1940, 1892, 1891, -1, 1891, 1941, 1940, -1, + 1941, 1891, 1890, -1, 1890, 1942, 1941, -1, + 1942, 1890, 1889, -1, 1889, 1943, 1942, -1, + 1943, 1889, 1888, -1, 1888, 1944, 1943, -1, + 1944, 1888, 1887, -1, 1887, 1945, 1944, -1, + 1945, 1887, 1886, -1, 1886, 1946, 1945, -1, + 1946, 1886, 1885, -1, 1885, 1947, 1946, -1, + 1947, 1885, 1884, -1, 1884, 1948, 1947, -1, + 1948, 1884, 1883, -1, 1883, 1949, 1948, -1, + 1949, 1883, 1882, -1, 1882, 1950, 1949, -1, + 1950, 1882, 1881, -1, 1881, 1951, 1950, -1, + 1951, 1881, 1880, -1, 1880, 1952, 1951, -1, + 1952, 1880, 1879, -1, 1879, 1953, 1952, -1, + 1953, 1879, 1878, -1, 1878, 1954, 1953, -1, + 1954, 1878, 1877, -1, 1877, 1955, 1954, -1, + 1955, 1877, 1876, -1, 1876, 1956, 1955, -1, + 1956, 1876, 1875, -1, 1875, 1957, 1956, -1, + 1957, 1875, 1874, -1, 1874, 1958, 1957, -1, + 1958, 1874, 1873, -1, 1873, 1959, 1958, -1, + 1959, 1873, 1872, -1, 1872, 1960, 1959, -1, + 1960, 1872, 1871, -1, 1871, 1423, 1960, -1, + 1423, 1961, 1960, -1, 1423, 1962, 1961, -1, + 1962, 1423, 1422, -1, 1422, 1963, 1962, -1, + 1963, 1422, 1444, -1, 1444, 1964, 1963, -1, + 1964, 1444, 1442, -1, 1442, 1965, 1964, -1, + 1965, 1442, 1440, -1, 1440, 1966, 1965, -1, + 1966, 1440, 1438, -1, 1438, 1362, 1966, -1, + 1362, 1438, 1436, -1, 1436, 1360, 1362, -1, + 1360, 1436, 1434, -1, 1434, 1358, 1360, -1, + 1358, 1434, 1433, -1, 1433, 1354, 1358, -1, + 1354, 1433, 1432, -1, 1432, 1355, 1354, -1, + 1432, 1352, 1355, -1, 1355, 1352, 1351, -1, + 1351, 1356, 1355, -1, 1351, 1353, 1356, -1, + 1356, 1353, 1349, -1, 1356, 1349, 1345, -1, + 1345, 1357, 1356, -1, 1357, 1345, 1343, -1, + 1343, 1359, 1357, -1, 1359, 1343, 1341, -1, + 1341, 1361, 1359, -1, 1361, 1341, 1339, -1, + 1339, 1362, 1361, -1, 1362, 1339, 1337, -1, + 1337, 1966, 1362, -1, 1966, 1337, 1335, -1, + 1335, 1965, 1966, -1, 1965, 1335, 1333, -1, + 1333, 1964, 1965, -1, 1964, 1333, 1331, -1, + 1331, 1963, 1964, -1, 1963, 1331, 1329, -1, + 1329, 1962, 1963, -1, 1962, 1329, 1327, -1, + 1327, 1961, 1962, -1, 1961, 1327, 1325, -1, + 1961, 1325, 1967, -1, 1968, 1969, 1970, -1, + 1970, 1971, 1968, -1, 1971, 1970, 1972, -1, + 1972, 1973, 1971, -1, 1973, 1972, 1974, -1, + 1974, 1975, 1973, -1, 1975, 1974, 1976, -1, + 1976, 1977, 1975, -1, 1977, 1976, 1978, -1, + 1978, 1979, 1977, -1, 1979, 1978, 1980, -1, + 1980, 1981, 1979, -1, 1981, 1980, 1982, -1, + 1982, 1983, 1981, -1, 1983, 1982, 1984, -1, + 1984, 1985, 1983, -1, 1985, 1984, 1986, -1, + 1986, 1987, 1985, -1, 1987, 1986, 1988, -1, + 1988, 1989, 1987, -1, 1989, 1988, 1990, -1, + 1990, 1991, 1989, -1, 1991, 1990, 1992, -1, + 1992, 1993, 1991, -1, 1993, 1992, 1994, -1, + 1994, 1995, 1993, -1, 1995, 1994, 1996, -1, + 1996, 1997, 1995, -1, 1997, 1996, 1998, -1, + 1998, 1999, 1997, -1, 1999, 1998, 2000, -1, + 2000, 2001, 1999, -1, 2001, 2000, 2002, -1, + 2002, 2003, 2001, -1, 2003, 2002, 2004, -1, + 2004, 2005, 2003, -1, 2005, 2004, 2006, -1, + 2006, 2007, 2005, -1, 2007, 2006, 2008, -1, + 2008, 2009, 2007, -1, 2009, 2008, 2010, -1, + 2010, 2011, 2009, -1, 2011, 2010, 2012, -1, + 2012, 2013, 2011, -1, 2013, 2012, 2014, -1, + 2014, 2015, 2013, -1, 2014, 2016, 2015, -1, + 2016, 2014, 2017, -1, 2017, 2018, 2016, -1, + 2018, 2017, 2019, -1, 2019, 2020, 2018, -1, + 2020, 2019, 2021, -1, 2021, 2022, 2020, -1, + 2022, 2021, 2023, -1, 2023, 2024, 2022, -1, + 2024, 2023, 2025, -1, 2025, 2026, 2024, -1, + 2026, 2025, 2027, -1, 2027, 2028, 2026, -1, + 2028, 2027, 2029, -1, 2029, 2030, 2028, -1, + 2030, 2029, 2031, -1, 2031, 2032, 2030, -1, + 2032, 2031, 2033, -1, 2033, 2034, 2032, -1, + 2034, 2033, 2035, -1, 2035, 2036, 2034, -1, + 2036, 2035, 2037, -1, 2037, 2038, 2036, -1, + 2038, 2037, 2039, -1, 2039, 2040, 2038, -1, + 2040, 2039, 2041, -1, 2041, 2042, 2040, -1, + 2042, 2041, 2043, -1, 2043, 2044, 2042, -1, + 2044, 2043, 2045, -1, 2045, 2046, 2044, -1, + 2046, 2045, 2047, -1, 2047, 2048, 2046, -1, + 2048, 2047, 2049, -1, 2049, 2050, 2048, -1, + 2050, 2049, 2051, -1, 2051, 2052, 2050, -1, + 2052, 2051, 2053, -1, 2053, 2054, 2052, -1, + 2054, 2053, 2055, -1, 2055, 2056, 2054, -1, + 2056, 2055, 2057, -1, 2057, 2058, 2056, -1, + 2058, 2057, 1967, -1, 2058, 1967, 1325, -1, + 2058, 1325, 1188, -1, 1188, 2056, 2058, -1, + 2056, 1188, 1187, -1, 1187, 2054, 2056, -1, + 2054, 1187, 1190, -1, 1190, 2052, 2054, -1, + 2052, 1190, 1192, -1, 1192, 2050, 2052, -1, + 2050, 1192, 1194, -1, 1194, 2048, 2050, -1, + 2048, 1194, 1196, -1, 1196, 2046, 2048, -1, + 2046, 1196, 1198, -1, 1198, 2044, 2046, -1, + 2044, 1198, 1200, -1, 1200, 2042, 2044, -1, + 2042, 1200, 1202, -1, 1202, 2040, 2042, -1, + 2040, 1202, 1204, -1, 1204, 2038, 2040, -1, + 2038, 1204, 1206, -1, 1206, 2036, 2038, -1, + 2036, 1206, 1208, -1, 1208, 2034, 2036, -1, + 2034, 1208, 1210, -1, 1210, 2032, 2034, -1, + 2032, 1210, 1212, -1, 1212, 2030, 2032, -1, + 2030, 1212, 1214, -1, 1214, 2028, 2030, -1, + 2028, 1214, 1216, -1, 1216, 2026, 2028, -1, + 2026, 1216, 1218, -1, 1218, 2024, 2026, -1, + 2024, 1218, 1220, -1, 1220, 2022, 2024, -1, + 2022, 1220, 1222, -1, 1222, 2020, 2022, -1, + 2020, 1222, 1224, -1, 1224, 2018, 2020, -1, + 2018, 1224, 1226, -1, 1226, 2016, 2018, -1, + 2016, 1226, 1228, -1, 1228, 2015, 2016, -1, + 2015, 1228, 1230, -1, 2015, 1230, 1233, -1, + 1233, 2013, 2015, -1, 2013, 1233, 1235, -1, + 1235, 2011, 2013, -1, 2011, 1235, 1237, -1, + 1237, 2009, 2011, -1, 2009, 1237, 1239, -1, + 1239, 2007, 2009, -1, 2007, 1239, 1241, -1, + 1241, 2005, 2007, -1, 2005, 1241, 1243, -1, + 1243, 2003, 2005, -1, 2003, 1243, 1245, -1, + 1245, 2001, 2003, -1, 2001, 1245, 1247, -1, + 1247, 1999, 2001, -1, 1999, 1247, 1249, -1, + 1249, 1997, 1999, -1, 1997, 1249, 1251, -1, + 1251, 1995, 1997, -1, 1995, 1251, 1253, -1, + 1253, 1993, 1995, -1, 1993, 1253, 1255, -1, + 1255, 1991, 1993, -1, 1991, 1255, 1257, -1, + 1257, 1989, 1991, -1, 1989, 1257, 1259, -1, + 1259, 1987, 1989, -1, 1987, 1259, 1261, -1, + 1261, 1985, 1987, -1, 1985, 1261, 1263, -1, + 1263, 1983, 1985, -1, 1983, 1263, 1265, -1, + 1265, 1981, 1983, -1, 1981, 1265, 1267, -1, + 1267, 1979, 1981, -1, 1979, 1267, 1269, -1, + 1269, 1977, 1979, -1, 1977, 1269, 1271, -1, + 1271, 1975, 1977, -1, 1975, 1271, 1273, -1, + 1273, 1973, 1975, -1, 1973, 1273, 1275, -1, + 1275, 1971, 1973, -1, 1971, 1275, 1277, -1, + 1277, 1968, 1971, -1, 1277, 2059, 1968, -1, + 1277, 1276, 2059, -1, 1276, 1278, 2059, -1, + 2060, 2061, 2062, -1, 2063, 2064, 2065, -1, + 2065, 2066, 2063, -1, 2066, 2065, 2060, -1, + 2060, 2062, 2066, -1, 2067, 2068, 2069, -1, + 2068, 2067, 2070, -1, 2070, 2071, 2068, -1, + 2071, 2070, 2072, -1, 2072, 2073, 2071, -1, + 2073, 2072, 2074, -1, 2074, 2075, 2073, -1, + 2075, 2074, 2076, -1, 2076, 2077, 2075, -1, + 2077, 2076, 2078, -1, 2078, 2079, 2077, -1, + 2079, 2078, 2080, -1, 2080, 2081, 2079, -1, + 2081, 2080, 2082, -1, 2082, 2083, 2081, -1, + 2083, 2082, 2084, -1, 2084, 2085, 2083, -1, + 2085, 2084, 2086, -1, 2086, 2087, 2085, -1, + 2087, 2086, 2088, -1, 2088, 2089, 2087, -1, + 2089, 2088, 2090, -1, 2090, 2091, 2089, -1, + 2091, 2090, 2092, -1, 2092, 2093, 2091, -1, + 2093, 2092, 2094, -1, 2094, 2095, 2093, -1, + 2095, 2094, 2096, -1, 2097, 2098, 2099, -1, + 2099, 2100, 2097, -1, 2100, 2099, 2101, -1, + 2101, 2102, 2100, -1, 2102, 2101, 2103, -1, + 2103, 2104, 2102, -1, 2104, 2103, 2105, -1, + 2105, 2106, 2104, -1, 2106, 2105, 2107, -1, + 2107, 2108, 2106, -1, 2108, 2107, 2109, -1, + 2109, 2110, 2108, -1, 2110, 2109, 2111, -1, + 2111, 2112, 2110, -1, 2112, 2111, 2113, -1, + 2113, 2114, 2112, -1, 2114, 2113, 2115, -1, + 2115, 2116, 2114, -1, 2116, 2115, 2117, -1, + 2117, 2118, 2116, -1, 2118, 2117, 2119, -1, + 2119, 2120, 2118, -1, 2120, 2119, 2121, -1, + 2121, 2122, 2120, -1, 2122, 2121, 2123, -1, + 2123, 2124, 2122, -1, 2124, 2123, 2125, -1, + 2125, 2126, 2124, -1, 2126, 2125, 2127, -1, + 2127, 2128, 2126, -1, 2128, 2127, 2129, -1, + 2129, 2130, 2128, -1, 2130, 2129, 2131, -1, + 2131, 2132, 2130, -1, 2132, 2131, 2133, -1, + 2133, 2134, 2132, -1, 2134, 2133, 2135, -1, + 2135, 2136, 2134, -1, 2136, 2135, 2137, -1, + 2137, 2138, 2136, -1, 2138, 2137, 2139, -1, + 2139, 2140, 2138, -1, 2140, 2139, 2141, -1, + 2141, 2142, 2140, -1, 2142, 2141, 2143, -1, + 2143, 2144, 2142, -1, 2144, 2143, 2145, -1, + 2144, 2145, 2146, -1, 2146, 2147, 2144, -1, + 2147, 2146, 2148, -1, 2148, 2149, 2147, -1, + 2149, 2148, 2150, -1, 2150, 2151, 2149, -1, + 2151, 2150, 2152, -1, 2152, 2153, 2151, -1, + 2153, 2152, 2154, -1, 2154, 2155, 2153, -1, + 2156, 2157, 2158, -1, 2158, 2159, 2156, -1, + 2159, 2158, 2160, -1, 2160, 2161, 2159, -1, + 2161, 2160, 2162, -1, 2162, 2163, 2161, -1, + 2163, 2162, 2164, -1, 2164, 2165, 2163, -1, + 2165, 2164, 2166, -1, 2166, 2167, 2165, -1, + 2167, 2166, 2168, -1, 2168, 2169, 2167, -1, + 2169, 2168, 2170, -1, 2170, 2171, 2169, -1, + 2171, 2170, 2172, -1, 2172, 2173, 2171, -1, + 2173, 2172, 2174, -1, 2174, 2175, 2173, -1, + 2175, 2174, 2176, -1, 2176, 2177, 2175, -1, + 2177, 2176, 2178, -1, 2178, 2179, 2177, -1, + 2179, 2178, 2180, -1, 2180, 2181, 2179, -1, + 2181, 2180, 2182, -1, 2182, 2183, 2181, -1, + 2183, 2182, 2184, -1, 2184, 2185, 2183, -1, + 2185, 2184, 2186, -1, 2186, 2187, 2185, -1, + 2187, 2186, 2188, -1, 2188, 2189, 2187, -1, + 2189, 2188, 2190, -1, 2190, 2191, 2189, -1, + 2191, 2190, 2192, -1, 2192, 2193, 2191, -1, + 2193, 2192, 2155, -1, 2155, 2154, 2193, -1, + 2194, 2193, 2154, -1, 2154, 2195, 2194, -1, + 2195, 2154, 2152, -1, 2152, 2196, 2195, -1, + 2196, 2152, 2150, -1, 2150, 2197, 2196, -1, + 2197, 2150, 2148, -1, 2148, 2198, 2197, -1, + 2198, 2148, 2146, -1, 2146, 2199, 2198, -1, + 2199, 2146, 2145, -1, 2145, 2200, 2199, -1, + 2145, 2201, 2200, -1, 2201, 2145, 2143, -1, + 2143, 2202, 2201, -1, 2202, 2143, 2141, -1, + 2141, 2203, 2202, -1, 2203, 2141, 2139, -1, + 2139, 2204, 2203, -1, 2204, 2139, 2137, -1, + 2137, 2205, 2204, -1, 2205, 2137, 2135, -1, + 2135, 2206, 2205, -1, 2206, 2135, 2133, -1, + 2133, 2207, 2206, -1, 2207, 2133, 2131, -1, + 2131, 2208, 2207, -1, 2208, 2131, 2129, -1, + 2129, 2209, 2208, -1, 2209, 2129, 2127, -1, + 2127, 2210, 2209, -1, 2210, 2127, 2125, -1, + 2125, 2211, 2210, -1, 2211, 2125, 2123, -1, + 2123, 2212, 2211, -1, 2212, 2123, 2121, -1, + 2121, 2213, 2212, -1, 2213, 2121, 2119, -1, + 2119, 2214, 2213, -1, 2214, 2119, 2117, -1, + 2117, 2215, 2214, -1, 2215, 2117, 2115, -1, + 2115, 2216, 2215, -1, 2216, 2115, 2113, -1, + 2113, 2217, 2216, -1, 2217, 2113, 2111, -1, + 2111, 2218, 2217, -1, 2218, 2111, 2109, -1, + 2109, 2219, 2218, -1, 2219, 2109, 2107, -1, + 2107, 2220, 2219, -1, 2220, 2107, 2105, -1, + 2105, 2221, 2220, -1, 2221, 2105, 2103, -1, + 2103, 2222, 2221, -1, 2222, 2103, 2101, -1, + 2101, 2223, 2222, -1, 2223, 2101, 2099, -1, + 2099, 2224, 2223, -1, 2224, 2099, 2098, -1, + 2098, 2225, 2224, -1, 2226, 2227, 2228, -1, + 2228, 2229, 2226, -1, 2229, 2228, 2230, -1, + 2230, 2231, 2229, -1, 2231, 2230, 2232, -1, + 2232, 2233, 2231, -1, 2233, 2232, 2234, -1, + 2234, 2235, 2233, -1, 2235, 2234, 2236, -1, + 2236, 2237, 2235, -1, 2237, 2236, 2238, -1, + 2238, 2239, 2237, -1, 2239, 2238, 2240, -1, + 2240, 2241, 2239, -1, 2241, 2240, 2242, -1, + 2242, 2243, 2241, -1, 2243, 2242, 2244, -1, + 2244, 2245, 2243, -1, 2245, 2244, 2246, -1, + 2246, 2247, 2245, -1, 2247, 2246, 2248, -1, + 2248, 2249, 2247, -1, 2249, 2248, 2250, -1, + 2250, 2251, 2249, -1, 2251, 2250, 2225, -1, + 2225, 2252, 2251, -1, 2252, 2225, 2098, -1, + 2098, 2097, 2252, -1, 2253, 2252, 2097, -1, + 2097, 2254, 2253, -1, 2254, 2097, 2100, -1, + 2100, 2255, 2254, -1, 2255, 2100, 2102, -1, + 2102, 2256, 2255, -1, 2256, 2102, 2104, -1, + 2104, 2257, 2256, -1, 2257, 2104, 2106, -1, + 2106, 2258, 2257, -1, 2258, 2106, 2108, -1, + 2108, 2259, 2258, -1, 2259, 2108, 2110, -1, + 2110, 2260, 2259, -1, 2260, 2110, 2112, -1, + 2112, 2261, 2260, -1, 2261, 2112, 2114, -1, + 2114, 2262, 2261, -1, 2262, 2114, 2116, -1, + 2116, 2263, 2262, -1, 2263, 2116, 2118, -1, + 2118, 2264, 2263, -1, 2264, 2118, 2120, -1, + 2120, 2265, 2264, -1, 2265, 2120, 2122, -1, + 2122, 2266, 2265, -1, 2266, 2122, 2124, -1, + 2124, 2267, 2266, -1, 2267, 2124, 2126, -1, + 2126, 2268, 2267, -1, 2268, 2126, 2128, -1, + 2128, 2269, 2268, -1, 2269, 2128, 2130, -1, + 2130, 2270, 2269, -1, 2270, 2130, 2132, -1, + 2132, 2271, 2270, -1, 2271, 2132, 2134, -1, + 2134, 2272, 2271, -1, 2272, 2134, 2136, -1, + 2136, 2273, 2272, -1, 2273, 2136, 2138, -1, + 2138, 2274, 2273, -1, 2274, 2138, 2140, -1, + 2140, 2275, 2274, -1, 2275, 2140, 2142, -1, + 2142, 2276, 2275, -1, 2276, 2142, 2144, -1, + 2276, 2144, 2147, -1, 2147, 2277, 2276, -1, + 2277, 2147, 2149, -1, 2149, 2278, 2277, -1, + 2278, 2149, 2151, -1, 2151, 2279, 2278, -1, + 2279, 2151, 2153, -1, 2153, 2280, 2279, -1, + 2280, 2153, 2155, -1, 2155, 2281, 2280, -1, + 2281, 2155, 2192, -1, 2192, 2282, 2281, -1, + 2282, 2192, 2190, -1, 2190, 2283, 2282, -1, + 2283, 2190, 2188, -1, 2188, 2284, 2283, -1, + 2284, 2188, 2186, -1, 2186, 2285, 2284, -1, + 2285, 2186, 2184, -1, 2184, 2286, 2285, -1, + 2286, 2184, 2182, -1, 2182, 2287, 2286, -1, + 2287, 2182, 2180, -1, 2180, 2288, 2287, -1, + 2288, 2180, 2178, -1, 2178, 2289, 2288, -1, + 2289, 2178, 2176, -1, 2176, 2290, 2289, -1, + 2290, 2176, 2174, -1, 2174, 2291, 2290, -1, + 2291, 2174, 2172, -1, 2172, 2292, 2291, -1, + 2292, 2172, 2170, -1, 2170, 2293, 2292, -1, + 2293, 2170, 2168, -1, 2168, 2294, 2293, -1, + 2294, 2168, 2166, -1, 2166, 2295, 2294, -1, + 2295, 2166, 2164, -1, 2164, 2296, 2295, -1, + 2296, 2164, 2162, -1, 2162, 2297, 2296, -1, + 2297, 2162, 2160, -1, 2160, 2298, 2297, -1, + 2298, 2160, 2158, -1, 2158, 2299, 2298, -1, + 2299, 2158, 2157, -1, 2157, 2300, 2299, -1, + 2300, 2157, 2301, -1, 2302, 2303, 2304, -1, + 2304, 2305, 2302, -1, 2306, 2307, 2308, -1, + 2308, 2307, 2305, -1, 2305, 2304, 2308, -1, + 2308, 2309, 2310, -1, 2309, 2308, 2304, -1, + 2304, 2311, 2309, -1, 2311, 2304, 2303, -1, + 2303, 2312, 2311, -1, 2312, 2303, 2313, -1, + 2313, 2314, 2312, -1, 2314, 2313, 2315, -1, + 2315, 2316, 2314, -1, 2316, 2315, 2317, -1, + 2317, 2318, 2316, -1, 2318, 2317, 2319, -1, + 2319, 2320, 2318, -1, 2320, 2319, 2321, -1, + 2321, 2322, 2320, -1, 2322, 2321, 2323, -1, + 2323, 2324, 2322, -1, 2324, 2323, 2325, -1, + 2325, 2326, 2324, -1, 2326, 2325, 2327, -1, + 2327, 2328, 2326, -1, 2328, 2327, 2329, -1, + 2329, 2330, 2328, -1, 2330, 2329, 2331, -1, + 2331, 2332, 2330, -1, 2332, 2331, 2301, -1, + 2301, 2333, 2332, -1, 2333, 2301, 2157, -1, + 2157, 2156, 2333, -1, 2156, 2334, 2333, -1, + 2334, 2156, 2159, -1, 2159, 2335, 2334, -1, + 2335, 2159, 2161, -1, 2161, 2336, 2335, -1, + 2336, 2161, 2163, -1, 2163, 2337, 2336, -1, + 2337, 2163, 2165, -1, 2165, 2338, 2337, -1, + 2338, 2165, 2167, -1, 2167, 2339, 2338, -1, + 2339, 2167, 2169, -1, 2169, 2340, 2339, -1, + 2340, 2169, 2171, -1, 2171, 2341, 2340, -1, + 2341, 2171, 2173, -1, 2173, 2342, 2341, -1, + 2342, 2173, 2175, -1, 2175, 2343, 2342, -1, + 2343, 2175, 2177, -1, 2177, 2344, 2343, -1, + 2344, 2177, 2179, -1, 2179, 2345, 2344, -1, + 2345, 2179, 2181, -1, 2181, 2346, 2345, -1, + 2346, 2181, 2183, -1, 2183, 2347, 2346, -1, + 2347, 2183, 2185, -1, 2185, 2348, 2347, -1, + 2348, 2185, 2187, -1, 2187, 2349, 2348, -1, + 2349, 2187, 2189, -1, 2189, 2350, 2349, -1, + 2350, 2189, 2191, -1, 2191, 2351, 2350, -1, + 2351, 2191, 2193, -1, 2193, 2194, 2351, -1, + 2352, 2351, 2194, -1, 2352, 2353, 2351, -1, + 2354, 2355, 2356, -1, 2355, 2354, 2357, -1, + 2357, 2358, 2355, -1, 2358, 2357, 2359, -1, + 2359, 2360, 2358, -1, 2360, 2359, 2361, -1, + 2361, 2362, 2360, -1, 2362, 2361, 2363, -1, + 2363, 2364, 2362, -1, 2364, 2363, 2365, -1, + 2365, 2366, 2364, -1, 2366, 2365, 2367, -1, + 2367, 2368, 2366, -1, 2368, 2367, 2369, -1, + 2369, 2370, 2368, -1, 2370, 2369, 2371, -1, + 2371, 2372, 2370, -1, 2372, 2371, 2373, -1, + 2373, 2374, 2372, -1, 2374, 2373, 2375, -1, + 2375, 2376, 2374, -1, 2376, 2375, 2377, -1, + 2377, 2378, 2376, -1, 2378, 2377, 2379, -1, + 2379, 2380, 2378, -1, 2380, 2379, 2381, -1, + 2381, 2382, 2380, -1, 2382, 2381, 2383, -1, + 2383, 2384, 2382, -1, 2384, 2383, 2385, -1, + 2385, 2386, 2384, -1, 2386, 2385, 2387, -1, + 2387, 2353, 2386, -1, 2387, 2351, 2353, -1, + 2387, 2350, 2351, -1, 2350, 2387, 2385, -1, + 2385, 2349, 2350, -1, 2349, 2385, 2383, -1, + 2383, 2348, 2349, -1, 2348, 2383, 2381, -1, + 2381, 2347, 2348, -1, 2347, 2381, 2379, -1, + 2379, 2346, 2347, -1, 2346, 2379, 2377, -1, + 2377, 2345, 2346, -1, 2345, 2377, 2375, -1, + 2375, 2344, 2345, -1, 2344, 2375, 2373, -1, + 2373, 2343, 2344, -1, 2343, 2373, 2371, -1, + 2371, 2342, 2343, -1, 2342, 2371, 2369, -1, + 2369, 2341, 2342, -1, 2341, 2369, 2367, -1, + 2367, 2340, 2341, -1, 2340, 2367, 2365, -1, + 2365, 2339, 2340, -1, 2339, 2365, 2363, -1, + 2363, 2338, 2339, -1, 2338, 2363, 2361, -1, + 2361, 2337, 2338, -1, 2337, 2361, 2359, -1, + 2359, 2336, 2337, -1, 2336, 2359, 2357, -1, + 2357, 2335, 2336, -1, 2335, 2357, 2354, -1, + 2354, 2334, 2335, -1, 2334, 2354, 2356, -1, + 2356, 2333, 2334, -1, 2333, 2356, 2388, -1, + 2388, 2332, 2333, -1, 2332, 2388, 2389, -1, + 2389, 2330, 2332, -1, 2330, 2389, 2390, -1, + 2390, 2328, 2330, -1, 2328, 2390, 2391, -1, + 2391, 2326, 2328, -1, 2326, 2391, 2392, -1, + 2392, 2324, 2326, -1, 2324, 2392, 2393, -1, + 2393, 2322, 2324, -1, 2322, 2393, 2394, -1, + 2394, 2320, 2322, -1, 2320, 2394, 2395, -1, + 2395, 2318, 2320, -1, 2318, 2395, 2396, -1, + 2396, 2316, 2318, -1, 2316, 2396, 2397, -1, + 2397, 2314, 2316, -1, 2314, 2397, 2398, -1, + 2398, 2312, 2314, -1, 2312, 2398, 2399, -1, + 2399, 2311, 2312, -1, 2311, 2399, 2400, -1, + 2400, 2309, 2311, -1, 2309, 2400, 2401, -1, + 2401, 2310, 2309, -1, 2402, 2403, 2310, -1, + 2310, 2401, 2402, -1, 2402, 2404, 2405, -1, + 2402, 2406, 2404, -1, 2406, 2402, 2401, -1, + 2401, 2407, 2406, -1, 2407, 2401, 2400, -1, + 2400, 2408, 2407, -1, 2408, 2400, 2399, -1, + 2399, 2409, 2408, -1, 2409, 2399, 2398, -1, + 2398, 2410, 2409, -1, 2410, 2398, 2397, -1, + 2397, 2411, 2410, -1, 2411, 2397, 2396, -1, + 2396, 2412, 2411, -1, 2412, 2396, 2395, -1, + 2395, 2413, 2412, -1, 2413, 2395, 2394, -1, + 2394, 2414, 2413, -1, 2414, 2394, 2393, -1, + 2393, 2415, 2414, -1, 2415, 2393, 2392, -1, + 2392, 2416, 2415, -1, 2416, 2392, 2391, -1, + 2391, 2417, 2416, -1, 2417, 2391, 2390, -1, + 2390, 2418, 2417, -1, 2418, 2390, 2389, -1, + 2389, 2419, 2418, -1, 2419, 2389, 2388, -1, + 2388, 2420, 2419, -1, 2420, 2388, 2356, -1, + 2356, 2096, 2420, -1, 2096, 2356, 2355, -1, + 2355, 2095, 2096, -1, 2095, 2355, 2358, -1, + 2358, 2093, 2095, -1, 2093, 2358, 2360, -1, + 2360, 2091, 2093, -1, 2091, 2360, 2362, -1, + 2362, 2089, 2091, -1, 2089, 2362, 2364, -1, + 2364, 2087, 2089, -1, 2087, 2364, 2366, -1, + 2366, 2085, 2087, -1, 2085, 2366, 2368, -1, + 2368, 2083, 2085, -1, 2083, 2368, 2370, -1, + 2370, 2081, 2083, -1, 2081, 2370, 2372, -1, + 2372, 2079, 2081, -1, 2079, 2372, 2374, -1, + 2374, 2077, 2079, -1, 2077, 2374, 2376, -1, + 2376, 2075, 2077, -1, 2075, 2376, 2378, -1, + 2378, 2073, 2075, -1, 2073, 2378, 2380, -1, + 2380, 2071, 2073, -1, 2071, 2380, 2382, -1, + 2382, 2068, 2071, -1, 2068, 2382, 2384, -1, + 2384, 2069, 2068, -1, 2069, 2384, 2386, -1, + 2386, 2421, 2069, -1, 2421, 2386, 2353, -1, + 2353, 2422, 2421, -1, 2422, 2353, 2352, -1, + 2352, 2423, 2422, -1, 2352, 2194, 2423, -1, + 2424, 2423, 2194, -1, 2424, 2194, 2195, -1, + 2195, 2425, 2424, -1, 2425, 2195, 2196, -1, + 2196, 2426, 2425, -1, 2426, 2196, 2197, -1, + 2197, 2427, 2426, -1, 2427, 2197, 2198, -1, + 2198, 2428, 2427, -1, 2428, 2198, 2199, -1, + 2199, 2429, 2428, -1, 2429, 2199, 2200, -1, + 2200, 2430, 2429, -1, 2200, 2431, 2430, -1, + 2431, 2200, 2201, -1, 2201, 2432, 2431, -1, + 2432, 2201, 2202, -1, 2202, 2433, 2432, -1, + 2433, 2202, 2203, -1, 2203, 2434, 2433, -1, + 2434, 2203, 2204, -1, 2204, 2435, 2434, -1, + 2435, 2204, 2205, -1, 2205, 2436, 2435, -1, + 2436, 2205, 2206, -1, 2206, 2437, 2436, -1, + 2437, 2206, 2207, -1, 2437, 2207, 2438, -1, + 2439, 2440, 2441, -1, 2441, 2442, 2439, -1, + 2442, 2441, 2443, -1, 2443, 2444, 2442, -1, + 2444, 2443, 2445, -1, 2445, 2446, 2444, -1, + 2446, 2445, 2447, -1, 2447, 2448, 2446, -1, + 2448, 2447, 2449, -1, 2449, 2450, 2448, -1, + 2450, 2449, 2451, -1, 2451, 2452, 2450, -1, + 2452, 2451, 2453, -1, 2453, 2454, 2452, -1, + 2454, 2453, 2455, -1, 2455, 2456, 2454, -1, + 2456, 2455, 2457, -1, 2457, 2458, 2456, -1, + 2458, 2457, 2459, -1, 2459, 2460, 2458, -1, + 2460, 2459, 2461, -1, 2461, 2462, 2460, -1, + 2462, 2461, 2463, -1, 2463, 2464, 2462, -1, + 2464, 2463, 2465, -1, 2465, 2466, 2464, -1, + 2466, 2465, 2467, -1, 2467, 2468, 2466, -1, + 2468, 2467, 2469, -1, 2469, 2470, 2468, -1, + 2470, 2469, 2471, -1, 2471, 2472, 2470, -1, + 2472, 2471, 2438, -1, 2472, 2438, 2207, -1, + 2472, 2207, 2208, -1, 2208, 2470, 2472, -1, + 2470, 2208, 2209, -1, 2209, 2468, 2470, -1, + 2468, 2209, 2210, -1, 2210, 2466, 2468, -1, + 2466, 2210, 2211, -1, 2211, 2464, 2466, -1, + 2464, 2211, 2212, -1, 2212, 2462, 2464, -1, + 2462, 2212, 2213, -1, 2213, 2460, 2462, -1, + 2460, 2213, 2214, -1, 2214, 2458, 2460, -1, + 2458, 2214, 2215, -1, 2215, 2456, 2458, -1, + 2456, 2215, 2216, -1, 2216, 2454, 2456, -1, + 2454, 2216, 2217, -1, 2217, 2452, 2454, -1, + 2452, 2217, 2218, -1, 2218, 2450, 2452, -1, + 2450, 2218, 2219, -1, 2219, 2448, 2450, -1, + 2448, 2219, 2220, -1, 2220, 2446, 2448, -1, + 2446, 2220, 2221, -1, 2221, 2444, 2446, -1, + 2444, 2221, 2222, -1, 2222, 2442, 2444, -1, + 2442, 2222, 2223, -1, 2223, 2439, 2442, -1, + 2439, 2223, 2224, -1, 2224, 2440, 2439, -1, + 2440, 2224, 2225, -1, 2225, 2473, 2440, -1, + 2473, 2225, 2250, -1, 2250, 2474, 2473, -1, + 2474, 2250, 2248, -1, 2248, 2475, 2474, -1, + 2475, 2248, 2246, -1, 2246, 2476, 2475, -1, + 2476, 2246, 2244, -1, 2244, 2477, 2476, -1, + 2477, 2244, 2242, -1, 2242, 2478, 2477, -1, + 2478, 2242, 2240, -1, 2240, 2479, 2478, -1, + 2479, 2240, 2238, -1, 2238, 2480, 2479, -1, + 2480, 2238, 2236, -1, 2236, 2481, 2480, -1, + 2481, 2236, 2234, -1, 2234, 2482, 2481, -1, + 2482, 2234, 2232, -1, 2232, 2483, 2482, -1, + 2483, 2232, 2230, -1, 2230, 2484, 2483, -1, + 2484, 2230, 2228, -1, 2228, 2485, 2484, -1, + 2485, 2228, 2227, -1, 2227, 2486, 2485, -1, + 2487, 2488, 2489, -1, 2487, 2489, 2486, -1, + 2486, 2227, 2487, -1, 2487, 2490, 2491, -1, + 2490, 2487, 2227, -1, 2227, 2226, 2490, -1, + 2062, 2492, 2490, -1, 2062, 2490, 2226, -1, + 2226, 2066, 2062, -1, 2066, 2226, 2229, -1, + 2229, 2063, 2066, -1, 2063, 2229, 2231, -1, + 2231, 2064, 2063, -1, 2064, 2231, 2233, -1, + 2233, 2493, 2064, -1, 2493, 2233, 2235, -1, + 2235, 2494, 2493, -1, 2494, 2235, 2237, -1, + 2237, 2495, 2494, -1, 2495, 2237, 2239, -1, + 2239, 2496, 2495, -1, 2496, 2239, 2241, -1, + 2241, 2497, 2496, -1, 2497, 2241, 2243, -1, + 2243, 2498, 2497, -1, 2498, 2243, 2245, -1, + 2245, 2499, 2498, -1, 2499, 2245, 2247, -1, + 2247, 2500, 2499, -1, 2500, 2247, 2249, -1, + 2249, 2501, 2500, -1, 2501, 2249, 2251, -1, + 2251, 2502, 2501, -1, 2502, 2251, 2252, -1, + 2252, 2253, 2502, -1, 2503, 2502, 2253, -1, + 2253, 2504, 2503, -1, 2504, 2253, 2254, -1, + 2254, 2505, 2504, -1, 2505, 2254, 2255, -1, + 2255, 2506, 2505, -1, 2506, 2255, 2256, -1, + 2256, 2507, 2506, -1, 2507, 2256, 2257, -1, + 2257, 2508, 2507, -1, 2508, 2257, 2258, -1, + 2258, 2509, 2508, -1, 2509, 2258, 2259, -1, + 2259, 2510, 2509, -1, 2510, 2259, 2260, -1, + 2260, 2511, 2510, -1, 2511, 2260, 2261, -1, + 2261, 2512, 2511, -1, 2512, 2261, 2262, -1, + 2262, 2513, 2512, -1, 2513, 2262, 2263, -1, + 2263, 2514, 2513, -1, 2514, 2263, 2264, -1, + 2264, 2515, 2514, -1, 2515, 2264, 2265, -1, + 2265, 2516, 2515, -1, 2516, 2265, 2266, -1, + 2266, 2517, 2516, -1, 2517, 2266, 2267, -1, + 2267, 2518, 2517, -1, 2518, 2267, 2268, -1, + 2268, 2519, 2518, -1, 2519, 2268, 2269, -1, + 2269, 2520, 2519, -1, 2520, 2269, 2270, -1, + 2270, 2521, 2520, -1, 2521, 2270, 2271, -1, + 2271, 2522, 2521, -1, 2522, 2271, 2272, -1, + 2272, 2523, 2522, -1, 2523, 2272, 2273, -1, + 2273, 2524, 2523, -1, 2524, 2273, 2274, -1, + 2274, 2525, 2524, -1, 2525, 2274, 2275, -1, + 2275, 2526, 2525, -1, 2526, 2275, 2276, -1, + 2526, 2276, 2277, -1, 2277, 2527, 2526, -1, + 2527, 2277, 2278, -1, 2278, 2528, 2527, -1, + 2528, 2278, 2279, -1, 2279, 2529, 2528, -1, + 2529, 2279, 2280, -1, 2280, 2530, 2529, -1, + 2530, 2280, 2281, -1, 2281, 2531, 2530, -1, + 2531, 2281, 2282, -1, 2282, 2532, 2531, -1, + 2532, 2282, 2283, -1, 2283, 2533, 2532, -1, + 2533, 2283, 2284, -1, 2284, 2534, 2533, -1, + 2534, 2284, 2285, -1, 2285, 2535, 2534, -1, + 2535, 2285, 2286, -1, 2286, 2536, 2535, -1, + 2536, 2286, 2287, -1, 2287, 2537, 2536, -1, + 2537, 2287, 2288, -1, 2288, 2538, 2537, -1, + 2538, 2288, 2289, -1, 2289, 2539, 2538, -1, + 2539, 2289, 2290, -1, 2290, 2540, 2539, -1, + 2540, 2290, 2291, -1, 2291, 2541, 2540, -1, + 2541, 2291, 2292, -1, 2292, 2542, 2541, -1, + 2542, 2292, 2293, -1, 2293, 2543, 2542, -1, + 2543, 2293, 2294, -1, 2294, 2544, 2543, -1, + 2544, 2294, 2295, -1, 2295, 2545, 2544, -1, + 2545, 2295, 2296, -1, 2296, 2546, 2545, -1, + 2546, 2296, 2297, -1, 2297, 2547, 2546, -1, + 2547, 2297, 2298, -1, 2298, 2548, 2547, -1, + 2548, 2298, 2299, -1, 2299, 2549, 2548, -1, + 2549, 2299, 2300, -1, 2300, 2550, 2549, -1, + 2550, 2300, 2301, -1, 2301, 2551, 2550, -1, + 2551, 2301, 2331, -1, 2331, 2552, 2551, -1, + 2552, 2331, 2329, -1, 2329, 2553, 2552, -1, + 2553, 2329, 2327, -1, 2327, 2554, 2553, -1, + 2554, 2327, 2325, -1, 2325, 2555, 2554, -1, + 2555, 2325, 2323, -1, 2323, 2556, 2555, -1, + 2556, 2323, 2321, -1, 2321, 2557, 2556, -1, + 2557, 2321, 2319, -1, 2319, 2558, 2557, -1, + 2558, 2319, 2317, -1, 2317, 2559, 2558, -1, + 2559, 2317, 2315, -1, 2315, 2560, 2559, -1, + 2560, 2315, 2313, -1, 2313, 2561, 2560, -1, + 2561, 2313, 2303, -1, 2303, 2302, 2561, -1, + 2562, 2563, 2302, -1, 2564, 2302, 2563, -1, + 2564, 2561, 2302, -1, 2561, 2564, 2565, -1, + 2565, 2560, 2561, -1, 2560, 2565, 2566, -1, + 2566, 2559, 2560, -1, 2559, 2566, 2567, -1, + 2567, 2558, 2559, -1, 2558, 2567, 2568, -1, + 2568, 2557, 2558, -1, 2557, 2568, 2569, -1, + 2569, 2556, 2557, -1, 2556, 2569, 2570, -1, + 2570, 2555, 2556, -1, 2555, 2570, 2571, -1, + 2571, 2554, 2555, -1, 2554, 2571, 2572, -1, + 2572, 2553, 2554, -1, 2553, 2572, 2573, -1, + 2573, 2552, 2553, -1, 2552, 2573, 2574, -1, + 2574, 2551, 2552, -1, 2551, 2574, 2059, -1, + 2059, 2550, 2551, -1, 2550, 2059, 1278, -1, + 1278, 2549, 2550, -1, 2549, 1278, 1279, -1, + 1279, 2548, 2549, -1, 2548, 1279, 1280, -1, + 1280, 2547, 2548, -1, 2547, 1280, 1281, -1, + 1281, 2546, 2547, -1, 2546, 1281, 1282, -1, + 1282, 2545, 2546, -1, 2545, 1282, 1283, -1, + 1283, 2544, 2545, -1, 2544, 1283, 1284, -1, + 1284, 2543, 2544, -1, 2543, 1284, 1285, -1, + 1285, 2542, 2543, -1, 2542, 1285, 1286, -1, + 1286, 2541, 2542, -1, 2541, 1286, 1287, -1, + 1287, 2540, 2541, -1, 2540, 1287, 1288, -1, + 1288, 2539, 2540, -1, 2539, 1288, 1289, -1, + 1289, 2538, 2539, -1, 2538, 1289, 1290, -1, + 1290, 2537, 2538, -1, 2537, 1290, 1291, -1, + 1291, 2536, 2537, -1, 2536, 1291, 1292, -1, + 1292, 2535, 2536, -1, 2535, 1292, 1293, -1, + 1293, 2534, 2535, -1, 2534, 1293, 1294, -1, + 1294, 2533, 2534, -1, 2533, 1294, 1295, -1, + 1295, 2532, 2533, -1, 2532, 1295, 1296, -1, + 1296, 2531, 2532, -1, 2531, 1296, 1297, -1, + 1297, 2530, 2531, -1, 2530, 1297, 1298, -1, + 1298, 2529, 2530, -1, 2529, 1298, 1299, -1, + 1299, 2528, 2529, -1, 2528, 1299, 1300, -1, + 1300, 2527, 2528, -1, 2527, 1300, 1301, -1, + 1301, 2526, 2527, -1, 1301, 2525, 2526, -1, + 2525, 1301, 1302, -1, 1302, 2524, 2525, -1, + 2524, 1302, 1303, -1, 1303, 2523, 2524, -1, + 2523, 1303, 1304, -1, 1304, 2522, 2523, -1, + 2522, 1304, 1305, -1, 1305, 2521, 2522, -1, + 2521, 1305, 1306, -1, 1306, 2520, 2521, -1, + 2520, 1306, 1307, -1, 1307, 2519, 2520, -1, + 2519, 1307, 1308, -1, 1308, 2518, 2519, -1, + 2518, 1308, 1309, -1, 1309, 2517, 2518, -1, + 2517, 1309, 1310, -1, 1310, 2516, 2517, -1, + 2516, 1310, 1311, -1, 1311, 2515, 2516, -1, + 2515, 1311, 1312, -1, 1312, 2514, 2515, -1, + 2514, 1312, 1313, -1, 1313, 2513, 2514, -1, + 2513, 1313, 1314, -1, 1314, 2512, 2513, -1, + 2512, 1314, 1315, -1, 1315, 2511, 2512, -1, + 2511, 1315, 1316, -1, 1316, 2510, 2511, -1, + 2510, 1316, 1317, -1, 1317, 2509, 2510, -1, + 2509, 1317, 1318, -1, 1318, 2508, 2509, -1, + 2508, 1318, 1319, -1, 1319, 2507, 2508, -1, + 2507, 1319, 1320, -1, 1320, 2506, 2507, -1, + 2506, 1320, 1321, -1, 1321, 2505, 2506, -1, + 2505, 1321, 1322, -1, 1322, 2504, 2505, -1, + 2504, 1322, 1323, -1, 1323, 2503, 2504, -1, + 2503, 1323, 1324, -1, 1324, 2502, 2503, -1, + 2502, 1324, 1326, -1, 1326, 2501, 2502, -1, + 2501, 1326, 1328, -1, 1328, 2500, 2501, -1, + 2500, 1328, 1330, -1, 1330, 2499, 2500, -1, + 2499, 1330, 1332, -1, 1332, 2498, 2499, -1, + 2498, 1332, 1334, -1, 1334, 2497, 2498, -1, + 2497, 1334, 1336, -1, 1336, 2496, 2497, -1, + 2496, 1336, 1338, -1, 1338, 2495, 2496, -1, + 2495, 1338, 1340, -1, 1340, 2494, 2495, -1, + 2494, 1340, 1342, -1, 1342, 2493, 2494, -1, + 2493, 1342, 1344, -1, 1344, 2064, 2493, -1, + 2064, 1344, 1346, -1, 1346, 2065, 2064, -1, + 2065, 1346, 1350, -1, 1350, 2060, 2065, -1, + 1350, 2575, 2060, -1, 2576, 2577, 2578, -1, + 2576, 2575, 2577, -1, 2576, 2060, 2575, -1, + 2576, 2578, 2060, -1, 2578, 2061, 2060, -1, + 2061, 2578, 2577, -1, 2061, 2577, 2579, -1, + 2579, 2062, 2061, -1, 2579, 2492, 2062, -1, + 2579, 2577, 2492, -1, 2577, 2580, 2492, -1, + 2581, 2582, 2580, -1, 2582, 2492, 2580, -1, + 2582, 2490, 2492, -1, 2582, 2581, 2490, -1, + 2581, 2491, 2490, -1, 2491, 2581, 2580, -1, + 2491, 2580, 2583, -1, 2583, 2487, 2491, -1, + 2583, 2488, 2487, -1, 2583, 2580, 2488, -1, + 2580, 2584, 2488, -1, 2585, 2577, 2575, -1, + 2586, 2585, 2575, -1, 2586, 2575, 1350, -1, + 2586, 1350, 1348, -1, 1348, 2585, 2586, -1, + 1348, 1347, 2585, -1, 1347, 2587, 2585, -1, + 2587, 1347, 1349, -1, 2587, 1349, 1353, -1, + 1353, 2585, 2587, -1, 2585, 1353, 1352, -1, + 2588, 2589, 2590, -1, 2591, 2592, 2593, -1, + 2591, 2593, 2594, -1, 2595, 2594, 2593, -1, + 2596, 2595, 2593, -1, 2596, 2597, 2595, -1, + 2597, 2596, 2598, -1, 2598, 2599, 2597, -1, + 2599, 2598, 2600, -1, 2600, 2601, 2599, -1, + 2601, 2600, 2602, -1, 2602, 2603, 2601, -1, + 2603, 2602, 2604, -1, 2604, 2605, 2603, -1, + 2605, 2604, 2606, -1, 2606, 2607, 2605, -1, + 2607, 2606, 2608, -1, 2608, 2609, 2607, -1, + 2609, 2608, 2610, -1, 2610, 2611, 2609, -1, + 2611, 2610, 2612, -1, 2612, 2613, 2611, -1, + 2613, 2612, 2614, -1, 2614, 2615, 2613, -1, + 2614, 2616, 2615, -1, 2614, 2617, 2616, -1, + 2617, 2614, 2612, -1, 2612, 2618, 2617, -1, + 2618, 2612, 2610, -1, 2610, 2619, 2618, -1, + 2619, 2610, 2608, -1, 2608, 2620, 2619, -1, + 2620, 2608, 2606, -1, 2606, 2621, 2620, -1, + 2621, 2606, 2604, -1, 2604, 2622, 2621, -1, + 2622, 2604, 2602, -1, 2602, 2623, 2622, -1, + 2623, 2602, 2600, -1, 2600, 2624, 2623, -1, + 2624, 2600, 2598, -1, 2598, 2625, 2624, -1, + 2625, 2598, 2596, -1, 2596, 2593, 2625, -1, + 2626, 2627, 2628, -1, 2626, 2629, 2627, -1, + 2626, 2630, 2629, -1, 2626, 2628, 2630, -1, + 2630, 2628, 2631, -1, 2630, 2631, 2625, -1, + 2630, 2625, 2593, -1, 2593, 2629, 2630, -1, + 2629, 2593, 2592, -1, 2592, 2627, 2629, -1, + 2592, 2591, 2627, -1, 2591, 2594, 2627, -1, + 2594, 2632, 2627, -1, 2632, 2594, 2595, -1, + 2632, 2595, 2633, -1, 2633, 2588, 2632, -1, + 2588, 2627, 2632, -1, 1541, 2628, 2627, -1, + 2634, 2628, 1541, -1, 2634, 2631, 2628, -1, + 2634, 2635, 2631, -1, 2635, 2634, 1541, -1, + 2635, 1541, 1543, -1, 1543, 2631, 2635, -1, + 2631, 1543, 1544, -1, 2631, 1544, 1545, -1, + 1545, 2625, 2631, -1, 1545, 2624, 2625, -1, + 2624, 1545, 1546, -1, 1546, 2623, 2624, -1, + 2623, 1546, 1547, -1, 1547, 2622, 2623, -1, + 2622, 1547, 1548, -1, 1548, 2621, 2622, -1, + 2621, 1548, 1549, -1, 1549, 2620, 2621, -1, + 2620, 1549, 1550, -1, 1550, 2619, 2620, -1, + 2619, 1550, 1551, -1, 1551, 2618, 2619, -1, + 2618, 1551, 1552, -1, 1552, 2617, 2618, -1, + 2617, 1552, 1553, -1, 1553, 2616, 2617, -1, + 2616, 1553, 1554, -1, 2616, 1554, 1759, -1, + 1759, 2615, 2616, -1, 2615, 1759, 1757, -1, + 1757, 2636, 2615, -1, 2636, 1757, 1755, -1, + 1755, 2637, 2636, -1, 2637, 1755, 1753, -1, + 1753, 2638, 2637, -1, 2638, 1753, 1751, -1, + 1751, 2639, 2638, -1, 2639, 1751, 1749, -1, + 1749, 2640, 2639, -1, 2640, 1749, 1747, -1, + 1747, 2641, 2640, -1, 2641, 1747, 1745, -1, + 1745, 2642, 2641, -1, 2642, 1745, 1743, -1, + 1743, 2643, 2642, -1, 2643, 1743, 1741, -1, + 1741, 2644, 2643, -1, 2644, 1741, 1739, -1, + 1739, 2645, 2644, -1, 2645, 1739, 1737, -1, + 1737, 2646, 2645, -1, 2646, 1737, 1735, -1, + 1735, 2647, 2646, -1, 2647, 1735, 1733, -1, + 1733, 2648, 2647, -1, 2648, 1733, 1731, -1, + 1731, 2649, 2648, -1, 2649, 1731, 1729, -1, + 1729, 2650, 2649, -1, 2650, 1729, 1727, -1, + 1727, 2651, 2650, -1, 2651, 1727, 1724, -1, + 2651, 1724, 1722, -1, 1722, 2652, 2651, -1, + 2652, 1722, 1720, -1, 1720, 2653, 2652, -1, + 2653, 1720, 1718, -1, 1718, 2654, 2653, -1, + 2654, 1718, 1716, -1, 1716, 2655, 2654, -1, + 2655, 1716, 1714, -1, 1714, 2656, 2655, -1, + 2656, 1714, 1712, -1, 1712, 2657, 2656, -1, + 2657, 1712, 1710, -1, 1710, 2658, 2657, -1, + 2658, 1710, 1708, -1, 1708, 2659, 2658, -1, + 2659, 1708, 1706, -1, 1706, 2660, 2659, -1, + 2660, 1706, 1704, -1, 1704, 2661, 2660, -1, + 2661, 1704, 1702, -1, 1702, 2662, 2661, -1, + 2662, 1702, 1700, -1, 1700, 2663, 2662, -1, + 2663, 1700, 1698, -1, 1698, 2664, 2663, -1, + 2664, 1698, 1696, -1, 1696, 2665, 2664, -1, + 2665, 1696, 1694, -1, 1694, 2666, 2665, -1, + 2666, 1694, 1692, -1, 1692, 2667, 2666, -1, + 2667, 1692, 1690, -1, 1690, 2668, 2667, -1, + 2668, 1690, 1688, -1, 2668, 1688, 2669, -1, + 2669, 2670, 2668, -1, 2670, 2669, 2671, -1, + 2671, 2672, 2670, -1, 2672, 2671, 2673, -1, + 2673, 2674, 2672, -1, 2674, 2673, 2675, -1, + 2675, 2676, 2674, -1, 2677, 2678, 2679, -1, + 2677, 2680, 2678, -1, 2677, 2681, 2680, -1, + 2677, 2679, 2681, -1, 2679, 2682, 2681, -1, + 2682, 2679, 2683, -1, 2683, 2684, 2682, -1, + 2684, 2683, 2685, -1, 2685, 2686, 2684, -1, + 2686, 2685, 2687, -1, 2687, 2688, 2686, -1, + 2688, 2687, 2676, -1, 2676, 2675, 2688, -1, + 2675, 2689, 2688, -1, 2675, 2690, 2689, -1, + 2690, 2675, 2673, -1, 2673, 2691, 2690, -1, + 2691, 2673, 2671, -1, 2671, 2692, 2691, -1, + 2692, 2671, 2669, -1, 2669, 2693, 2692, -1, + 2693, 2669, 1688, -1, 2693, 1688, 1686, -1, + 2693, 1686, 1685, -1, 1685, 2692, 2693, -1, + 2692, 1685, 1684, -1, 1684, 2691, 2692, -1, + 2691, 1684, 1683, -1, 1683, 2690, 2691, -1, + 2690, 1683, 1682, -1, 1682, 2689, 2690, -1, + 2689, 1682, 1681, -1, 1681, 2694, 2689, -1, + 2694, 1681, 1680, -1, 1680, 2695, 2694, -1, + 1680, 2696, 2695, -1, 2696, 1680, 1679, -1, + 1679, 1183, 2696, -1, 1183, 1679, 1556, -1, + 1183, 1556, 2697, -1, 2697, 1185, 1183, -1, + 2697, 1184, 1185, -1, 2697, 2698, 1184, -1, + 2698, 2697, 1556, -1, 2698, 1556, 1555, -1, + 1555, 1184, 2698, -1, 1184, 1555, 1558, -1, + 2699, 2700, 2701, -1, 2702, 2703, 2704, -1, + 2705, 2706, 2707, -1, 2708, 2706, 2705, -1, + 2705, 2709, 2708, -1, 2705, 2707, 2709, -1, + 2709, 2707, 2710, -1, 2710, 2711, 2709, -1, + 2711, 2710, 2703, -1, 2703, 2702, 2711, -1, + 2712, 2711, 2702, -1, 2711, 2712, 2713, -1, + 2713, 2709, 2711, -1, 2709, 2713, 2714, -1, + 2714, 2708, 2709, -1, 2708, 2714, 2715, -1, + 2715, 2706, 2708, -1, 2715, 2716, 2706, -1, + 2716, 2715, 2714, -1, 2716, 2714, 2717, -1, + 2717, 2706, 2716, -1, 2717, 2718, 2706, -1, + 2719, 2720, 2721, -1, 2720, 2706, 2718, -1, + 2718, 2722, 2720, -1, 2718, 2723, 2722, -1, + 2718, 2717, 2723, -1, 2723, 2717, 2714, -1, + 2714, 2724, 2723, -1, 2724, 2714, 2713, -1, + 2713, 2725, 2724, -1, 2725, 2713, 2712, -1, + 2726, 2727, 2728, -1, 2728, 2729, 2726, -1, + 2730, 2731, 2732, -1, 2730, 2733, 2731, -1, + 2734, 2735, 2736, -1, 2736, 2737, 2734, -1, + 2737, 2736, 2738, -1, 2738, 2739, 2737, -1, + 2739, 2738, 2740, -1, 2740, 2741, 2739, -1, + 2741, 2740, 2733, -1, 2733, 2730, 2741, -1, + 2742, 2730, 2743, -1, 2742, 2741, 2730, -1, + 2741, 2742, 2744, -1, 2744, 2739, 2741, -1, + 2739, 2744, 2745, -1, 2745, 2737, 2739, -1, + 2737, 2745, 2746, -1, 2746, 2734, 2737, -1, + 2747, 2748, 2734, -1, 2734, 2746, 2747, -1, + 2749, 2750, 2751, -1, 2751, 2752, 2749, -1, + 2753, 2754, 2755, -1, 2753, 2756, 2754, -1, + 2753, 2757, 2756, -1, 2753, 2755, 2757, -1, + 2757, 2755, 2749, -1, 2749, 2758, 2757, -1, + 2758, 2749, 2752, -1, 2752, 2759, 2758, -1, + 2759, 2760, 2761, -1, 2759, 2752, 2760, -1, + 2760, 2762, 2763, -1, 2760, 2764, 2762, -1, + 2764, 2760, 2752, -1, 2752, 2751, 2764, -1, + 2751, 2765, 2747, -1, 2747, 2764, 2751, -1, + 2764, 2747, 2746, -1, 2746, 2762, 2764, -1, + 2762, 2746, 2745, -1, 2745, 2766, 2762, -1, + 2766, 2745, 2744, -1, 2766, 2744, 2767, -1, + 2768, 2769, 2770, -1, 2770, 2771, 2768, -1, + 2772, 2773, 2774, -1, 2772, 2774, 2775, -1, + 2776, 2775, 2774, -1, 2776, 2777, 2775, -1, + 2778, 2779, 2780, -1, 2779, 2778, 2781, -1, + 2781, 2782, 2779, -1, 2782, 2781, 2783, -1, + 2783, 2784, 2782, -1, 2784, 2783, 2785, -1, + 2785, 2786, 2784, -1, 2786, 2785, 2787, -1, + 2787, 2788, 2786, -1, 2788, 2787, 2789, -1, + 2789, 2790, 2788, -1, 2790, 2789, 2777, -1, + 2777, 2776, 2790, -1, 2791, 2776, 2792, -1, + 2791, 2790, 2776, -1, 2790, 2791, 2793, -1, + 2793, 2788, 2790, -1, 2788, 2793, 2794, -1, + 2794, 2786, 2788, -1, 2786, 2794, 2795, -1, + 2795, 2784, 2786, -1, 2784, 2795, 2796, -1, + 2796, 2782, 2784, -1, 2782, 2796, 2797, -1, + 2797, 2779, 2782, -1, 2779, 2797, 2798, -1, + 2798, 2780, 2779, -1, 2780, 2798, 2799, -1, + 2799, 2800, 2780, -1, 2800, 2799, 2801, -1, + 2801, 2802, 2800, -1, 2802, 2801, 2803, -1, + 2803, 2804, 2802, -1, 2804, 2803, 2805, -1, + 2805, 2806, 2804, -1, 2806, 2805, 2807, -1, + 2807, 2808, 2806, -1, 2808, 2807, 2809, -1, + 2809, 2810, 2808, -1, 2810, 2809, 2811, -1, + 2811, 2812, 2810, -1, 2812, 2811, 2813, -1, + 2813, 2814, 2812, -1, 2814, 2813, 2815, -1, + 2815, 2816, 2814, -1, 2816, 2815, 2817, -1, + 2817, 2818, 2816, -1, 2818, 2817, 2819, -1, + 2819, 2820, 2818, -1, 2820, 2819, 2821, -1, + 2821, 2822, 2820, -1, 2822, 2821, 2823, -1, + 2823, 2824, 2822, -1, 2824, 2823, 2825, -1, + 2825, 2826, 2824, -1, 2826, 2825, 2827, -1, + 2827, 2828, 2826, -1, 2828, 2827, 2829, -1, + 2829, 2830, 2828, -1, 2830, 2829, 2831, -1, + 2831, 2832, 2830, -1, 2832, 2831, 2833, -1, + 2833, 2834, 2832, -1, 2834, 2833, 2835, -1, + 2835, 2836, 2834, -1, 2836, 2835, 2837, -1, + 2837, 2838, 2836, -1, 2838, 2837, 2839, -1, + 2839, 2840, 2838, -1, 2840, 2839, 2841, -1, + 2841, 2842, 2840, -1, 2842, 2841, 2843, -1, + 2843, 2844, 2842, -1, 2844, 2843, 2845, -1, + 2845, 2846, 2844, -1, 2846, 2845, 2847, -1, + 2847, 2848, 2846, -1, 2848, 2847, 2849, -1, + 2849, 2850, 2848, -1, 2850, 2849, 2851, -1, + 2851, 2852, 2850, -1, 2852, 2851, 2853, -1, + 2853, 2854, 2852, -1, 2854, 2853, 2855, -1, + 2855, 2856, 2854, -1, 2856, 2855, 2857, -1, + 2857, 2858, 2856, -1, 2858, 2857, 2859, -1, + 2859, 2860, 2858, -1, 2860, 2859, 2861, -1, + 2861, 2862, 2860, -1, 2862, 2861, 2863, -1, + 2863, 2864, 2862, -1, 2864, 2863, 2865, -1, + 2865, 2866, 2864, -1, 2866, 2865, 2867, -1, + 2867, 2868, 2866, -1, 2868, 2867, 2869, -1, + 2869, 2870, 2868, -1, 2870, 2869, 2871, -1, + 2871, 2872, 2870, -1, 2872, 2871, 2873, -1, + 2873, 2874, 2872, -1, 2874, 2873, 2875, -1, + 2875, 2771, 2874, -1, 2771, 2875, 2876, -1, + 2876, 2768, 2771, -1, 2877, 2878, 2768, -1, + 2768, 2876, 2877, -1, 2879, 2880, 2877, -1, + 2877, 2881, 2879, -1, 2881, 2877, 2876, -1, + 2876, 2882, 2881, -1, 2882, 2876, 2875, -1, + 2875, 2883, 2882, -1, 2883, 2875, 2873, -1, + 2873, 2884, 2883, -1, 2884, 2873, 2871, -1, + 2871, 2885, 2884, -1, 2885, 2871, 2869, -1, + 2869, 2886, 2885, -1, 2886, 2869, 2867, -1, + 2867, 2887, 2886, -1, 2887, 2867, 2865, -1, + 2865, 2888, 2887, -1, 2888, 2865, 2863, -1, + 2863, 2889, 2888, -1, 2889, 2863, 2861, -1, + 2861, 2890, 2889, -1, 2890, 2861, 2859, -1, + 2859, 2891, 2890, -1, 2891, 2859, 2857, -1, + 2857, 2892, 2891, -1, 2892, 2857, 2855, -1, + 2855, 2893, 2892, -1, 2893, 2855, 2853, -1, + 2853, 2894, 2893, -1, 2894, 2853, 2851, -1, + 2851, 2895, 2894, -1, 2895, 2851, 2849, -1, + 2849, 2896, 2895, -1, 2896, 2849, 2847, -1, + 2847, 2897, 2896, -1, 2897, 2847, 2845, -1, + 2845, 2898, 2897, -1, 2898, 2845, 2843, -1, + 2843, 2899, 2898, -1, 2899, 2843, 2841, -1, + 2841, 2900, 2899, -1, 2900, 2841, 2839, -1, + 2839, 2901, 2900, -1, 2901, 2839, 2837, -1, + 2837, 2902, 2901, -1, 2902, 2837, 2835, -1, + 2835, 2903, 2902, -1, 2903, 2835, 2833, -1, + 2833, 2904, 2903, -1, 2904, 2833, 2831, -1, + 2831, 2905, 2904, -1, 2905, 2831, 2829, -1, + 2829, 2906, 2905, -1, 2906, 2829, 2827, -1, + 2827, 2907, 2906, -1, 2907, 2827, 2825, -1, + 2825, 2908, 2907, -1, 2908, 2825, 2823, -1, + 2823, 2909, 2908, -1, 2909, 2823, 2821, -1, + 2821, 2910, 2909, -1, 2910, 2821, 2819, -1, + 2819, 2911, 2910, -1, 2911, 2819, 2817, -1, + 2817, 2912, 2911, -1, 2912, 2817, 2815, -1, + 2815, 2913, 2912, -1, 2913, 2815, 2813, -1, + 2813, 2914, 2913, -1, 2914, 2813, 2811, -1, + 2811, 2915, 2914, -1, 2915, 2811, 2809, -1, + 2809, 2916, 2915, -1, 2916, 2809, 2807, -1, + 2807, 2917, 2916, -1, 2917, 2807, 2805, -1, + 2805, 2918, 2917, -1, 2918, 2805, 2803, -1, + 2803, 2919, 2918, -1, 2919, 2803, 2801, -1, + 2801, 2920, 2919, -1, 2920, 2801, 2799, -1, + 2799, 2921, 2920, -1, 2921, 2799, 2798, -1, + 2798, 2922, 2921, -1, 2922, 2798, 2797, -1, + 2797, 2923, 2922, -1, 2923, 2797, 2796, -1, + 2796, 2924, 2923, -1, 2924, 2796, 2795, -1, + 2795, 2925, 2924, -1, 2925, 2795, 2794, -1, + 2794, 2926, 2925, -1, 2926, 2794, 2793, -1, + 2793, 2927, 2926, -1, 2927, 2793, 2791, -1, + 2927, 2791, 2928, -1, 2929, 2930, 2931, -1, + 2930, 2929, 2932, -1, 2932, 2928, 2930, -1, + 2928, 2932, 2933, -1, 2933, 2927, 2928, -1, + 2933, 2934, 2927, -1, 2933, 2935, 2934, -1, + 2935, 2933, 2932, -1, 2932, 2767, 2935, -1, + 2767, 2932, 2929, -1, 2929, 2766, 2767, -1, + 2929, 2931, 2766, -1, 2936, 2766, 2931, -1, + 2936, 2762, 2766, -1, 2936, 2763, 2762, -1, + 2936, 2937, 2763, -1, 2937, 2936, 2931, -1, + 2931, 2938, 2937, -1, 2938, 2931, 2930, -1, + 2930, 2939, 2938, -1, 2939, 2930, 2928, -1, + 2939, 2928, 2791, -1, 2939, 2791, 2792, -1, + 2792, 2938, 2939, -1, 2938, 2792, 2940, -1, + 2940, 2937, 2938, -1, 2937, 2940, 2941, -1, + 2941, 2763, 2937, -1, 2763, 2941, 2942, -1, + 2942, 2760, 2763, -1, 2942, 2761, 2760, -1, + 2942, 2943, 2761, -1, 2943, 2942, 2941, -1, + 2941, 2944, 2943, -1, 2944, 2941, 2940, -1, + 2940, 2945, 2944, -1, 2945, 2940, 2792, -1, + 2945, 2792, 2776, -1, 2945, 2776, 2774, -1, + 2774, 2944, 2945, -1, 2944, 2774, 2773, -1, + 2773, 2943, 2944, -1, 2943, 2773, 2946, -1, + 2946, 2761, 2943, -1, 2761, 2946, 2947, -1, + 2947, 2759, 2761, -1, 2947, 2948, 2759, -1, + 2947, 2949, 2948, -1, 2949, 2947, 2946, -1, + 2946, 2950, 2949, -1, 2950, 2946, 2773, -1, + 2773, 2772, 2950, -1, 2772, 2951, 2950, -1, + 2772, 2775, 2951, -1, 2951, 2952, 2953, -1, + 2951, 2954, 2952, -1, 2954, 2951, 2775, -1, + 2775, 2955, 2954, -1, 2955, 2775, 2777, -1, + 2777, 2956, 2955, -1, 2956, 2777, 2789, -1, + 2789, 2957, 2956, -1, 2957, 2789, 2787, -1, + 2787, 2958, 2957, -1, 2958, 2787, 2785, -1, + 2785, 2959, 2958, -1, 2959, 2785, 2783, -1, + 2783, 2960, 2959, -1, 2960, 2783, 2781, -1, + 2781, 2961, 2960, -1, 2961, 2781, 2778, -1, + 2778, 2962, 2961, -1, 2962, 2778, 2780, -1, + 2780, 2963, 2962, -1, 2963, 2780, 2800, -1, + 2800, 2964, 2963, -1, 2964, 2800, 2802, -1, + 2802, 2965, 2964, -1, 2965, 2802, 2804, -1, + 2804, 2966, 2965, -1, 2966, 2804, 2806, -1, + 2806, 2967, 2966, -1, 2967, 2806, 2808, -1, + 2808, 2968, 2967, -1, 2968, 2808, 2810, -1, + 2810, 2969, 2968, -1, 2969, 2810, 2812, -1, + 2812, 2970, 2969, -1, 2970, 2812, 2814, -1, + 2814, 2971, 2970, -1, 2971, 2814, 2816, -1, + 2816, 2972, 2971, -1, 2972, 2816, 2818, -1, + 2818, 2973, 2972, -1, 2973, 2818, 2820, -1, + 2820, 2974, 2973, -1, 2974, 2820, 2822, -1, + 2822, 2975, 2974, -1, 2975, 2822, 2824, -1, + 2824, 2976, 2975, -1, 2976, 2824, 2826, -1, + 2826, 2977, 2976, -1, 2977, 2826, 2828, -1, + 2828, 2978, 2977, -1, 2978, 2828, 2830, -1, + 2830, 2979, 2978, -1, 2979, 2830, 2832, -1, + 2832, 2980, 2979, -1, 2980, 2832, 2834, -1, + 2834, 2981, 2980, -1, 2981, 2834, 2836, -1, + 2836, 2982, 2981, -1, 2982, 2836, 2838, -1, + 2838, 2983, 2982, -1, 2983, 2838, 2840, -1, + 2840, 2984, 2983, -1, 2984, 2840, 2842, -1, + 2842, 2985, 2984, -1, 2985, 2842, 2844, -1, + 2844, 2986, 2985, -1, 2986, 2844, 2846, -1, + 2846, 2987, 2986, -1, 2987, 2846, 2848, -1, + 2848, 2988, 2987, -1, 2988, 2848, 2850, -1, + 2850, 2989, 2988, -1, 2989, 2850, 2852, -1, + 2852, 2990, 2989, -1, 2990, 2852, 2854, -1, + 2854, 2991, 2990, -1, 2991, 2854, 2856, -1, + 2856, 2992, 2991, -1, 2992, 2856, 2858, -1, + 2858, 2993, 2992, -1, 2993, 2858, 2860, -1, + 2860, 2994, 2993, -1, 2994, 2860, 2862, -1, + 2862, 2995, 2994, -1, 2995, 2862, 2864, -1, + 2864, 2996, 2995, -1, 2996, 2864, 2866, -1, + 2866, 2997, 2996, -1, 2997, 2866, 2868, -1, + 2868, 2998, 2997, -1, 2998, 2868, 2870, -1, + 2870, 2999, 2998, -1, 2999, 2870, 2872, -1, + 2872, 3000, 2999, -1, 3000, 2872, 2874, -1, + 2874, 3001, 3000, -1, 3001, 2874, 2771, -1, + 2771, 2770, 3001, -1, 2770, 3002, 2726, -1, + 2726, 3001, 2770, -1, 3001, 2726, 2729, -1, + 2729, 3000, 3001, -1, 3000, 2729, 3003, -1, + 3003, 2999, 3000, -1, 2999, 3003, 3004, -1, + 3004, 2998, 2999, -1, 2998, 3004, 3005, -1, + 3005, 2997, 2998, -1, 2997, 3005, 3006, -1, + 3006, 2996, 2997, -1, 2996, 3006, 3007, -1, + 3007, 2995, 2996, -1, 2995, 3007, 3008, -1, + 3008, 2994, 2995, -1, 2994, 3008, 3009, -1, + 3009, 2993, 2994, -1, 2993, 3009, 3010, -1, + 3010, 2992, 2993, -1, 2992, 3010, 3011, -1, + 3011, 2991, 2992, -1, 2991, 3011, 3012, -1, + 3012, 2990, 2991, -1, 2990, 3012, 3013, -1, + 3013, 2989, 2990, -1, 2989, 3013, 3014, -1, + 3014, 2988, 2989, -1, 2988, 3014, 3015, -1, + 3015, 2987, 2988, -1, 2987, 3015, 3016, -1, + 3016, 2986, 2987, -1, 2986, 3016, 3017, -1, + 3017, 2985, 2986, -1, 2985, 3017, 3018, -1, + 3018, 2984, 2985, -1, 2984, 3018, 3019, -1, + 3019, 2983, 2984, -1, 2983, 3019, 3020, -1, + 3020, 2982, 2983, -1, 2982, 3020, 3021, -1, + 3021, 2981, 2982, -1, 2981, 3021, 3022, -1, + 3022, 2980, 2981, -1, 2980, 3022, 3023, -1, + 3023, 2979, 2980, -1, 2979, 3023, 3024, -1, + 3024, 2978, 2979, -1, 2978, 3024, 3025, -1, + 3025, 2977, 2978, -1, 2977, 3025, 3026, -1, + 3026, 2976, 2977, -1, 2976, 3026, 3027, -1, + 3027, 2975, 2976, -1, 2975, 3027, 3028, -1, + 3028, 2974, 2975, -1, 2974, 3028, 3029, -1, + 3029, 2973, 2974, -1, 2973, 3029, 3030, -1, + 3030, 2972, 2973, -1, 2972, 3030, 3031, -1, + 3031, 2971, 2972, -1, 2971, 3031, 3032, -1, + 3032, 2970, 2971, -1, 2970, 3032, 3033, -1, + 3033, 2969, 2970, -1, 2969, 3033, 3034, -1, + 3034, 2968, 2969, -1, 2968, 3034, 3035, -1, + 3035, 2967, 2968, -1, 2967, 3035, 3036, -1, + 3036, 2966, 2967, -1, 2966, 3036, 3037, -1, + 3037, 2965, 2966, -1, 2965, 3037, 3038, -1, + 3038, 2964, 2965, -1, 2964, 3038, 3039, -1, + 3039, 2963, 2964, -1, 2963, 3039, 3040, -1, + 3040, 2962, 2963, -1, 2962, 3040, 3041, -1, + 3041, 2961, 2962, -1, 2961, 3041, 3042, -1, + 3042, 2960, 2961, -1, 2960, 3042, 3043, -1, + 3043, 2959, 2960, -1, 2959, 3043, 3044, -1, + 3044, 2958, 2959, -1, 2958, 3044, 3045, -1, + 3045, 2957, 2958, -1, 2957, 3045, 3046, -1, + 3046, 2956, 2957, -1, 2956, 3046, 3047, -1, + 3047, 2955, 2956, -1, 2955, 3047, 3048, -1, + 3048, 2954, 2955, -1, 2954, 3048, 3049, -1, + 3049, 2952, 2954, -1, 2952, 3050, 3051, -1, + 2952, 3049, 3050, -1, 3050, 3052, 3053, -1, + 3050, 3054, 3052, -1, 3054, 3050, 3049, -1, + 3049, 3055, 3054, -1, 3055, 3049, 3048, -1, + 3048, 3056, 3055, -1, 3056, 3048, 3047, -1, + 3047, 3057, 3056, -1, 3057, 3047, 3046, -1, + 3046, 3058, 3057, -1, 3058, 3046, 3045, -1, + 3045, 3059, 3058, -1, 3059, 3045, 3044, -1, + 3044, 3060, 3059, -1, 3060, 3044, 3043, -1, + 3043, 3061, 3060, -1, 3061, 3043, 3042, -1, + 3042, 3062, 3061, -1, 3062, 3042, 3041, -1, + 3041, 3063, 3062, -1, 3063, 3041, 3040, -1, + 3040, 3064, 3063, -1, 3064, 3040, 3039, -1, + 3039, 3065, 3064, -1, 3065, 3039, 3038, -1, + 3038, 3066, 3065, -1, 3066, 3038, 3037, -1, + 3037, 3067, 3066, -1, 3067, 3037, 3036, -1, + 3036, 3068, 3067, -1, 3068, 3036, 3035, -1, + 3035, 3069, 3068, -1, 3069, 3035, 3034, -1, + 3034, 3070, 3069, -1, 3070, 3034, 3033, -1, + 3033, 3071, 3070, -1, 3071, 3033, 3032, -1, + 3032, 3072, 3071, -1, 3072, 3032, 3031, -1, + 3031, 3073, 3072, -1, 3073, 3031, 3030, -1, + 3030, 3074, 3073, -1, 3074, 3030, 3029, -1, + 3029, 3075, 3074, -1, 3075, 3029, 3028, -1, + 3028, 3076, 3075, -1, 3076, 3028, 3027, -1, + 3027, 3077, 3076, -1, 3077, 3027, 3026, -1, + 3026, 3078, 3077, -1, 3078, 3026, 3025, -1, + 3025, 3079, 3078, -1, 3079, 3025, 3024, -1, + 3024, 3080, 3079, -1, 3080, 3024, 3023, -1, + 3023, 3081, 3080, -1, 3081, 3023, 3022, -1, + 3022, 3082, 3081, -1, 3082, 3022, 3021, -1, + 3021, 3083, 3082, -1, 3083, 3021, 3020, -1, + 3020, 3084, 3083, -1, 3084, 3020, 3019, -1, + 3019, 3085, 3084, -1, 3085, 3019, 3018, -1, + 3018, 3086, 3085, -1, 3086, 3018, 3017, -1, + 3017, 3087, 3086, -1, 3087, 3017, 3016, -1, + 3016, 3088, 3087, -1, 3088, 3016, 3015, -1, + 3015, 3089, 3088, -1, 3089, 3015, 3014, -1, + 3014, 3090, 3089, -1, 3090, 3014, 3013, -1, + 3013, 3091, 3090, -1, 3091, 3013, 3012, -1, + 3012, 3092, 3091, -1, 3092, 3012, 3011, -1, + 3011, 3093, 3092, -1, 3093, 3011, 3010, -1, + 3010, 3094, 3093, -1, 3094, 3010, 3009, -1, + 3009, 3095, 3094, -1, 3095, 3009, 3008, -1, + 3008, 3096, 3095, -1, 3096, 3008, 3007, -1, + 3007, 3097, 3096, -1, 3097, 3007, 3006, -1, + 3006, 3098, 3097, -1, 3098, 3006, 3005, -1, + 3005, 3099, 3098, -1, 3099, 3005, 3004, -1, + 3004, 3100, 3099, -1, 3100, 3004, 3003, -1, + 3003, 3101, 3100, -1, 3101, 3003, 2729, -1, + 2729, 2728, 3101, -1, 3102, 2728, 3103, -1, + 3102, 3101, 2728, -1, 3101, 3102, 3104, -1, + 3104, 3100, 3101, -1, 3100, 3104, 3105, -1, + 3105, 3099, 3100, -1, 3099, 3105, 3106, -1, + 3106, 3098, 3099, -1, 3098, 3106, 3107, -1, + 3107, 3097, 3098, -1, 3097, 3107, 3108, -1, + 3108, 3096, 3097, -1, 3096, 3108, 3109, -1, + 3109, 3095, 3096, -1, 3095, 3109, 3110, -1, + 3110, 3094, 3095, -1, 3094, 3110, 3111, -1, + 3111, 3093, 3094, -1, 3093, 3111, 3112, -1, + 3112, 3092, 3093, -1, 3092, 3112, 3113, -1, + 3113, 3091, 3092, -1, 3091, 3113, 3114, -1, + 3114, 3090, 3091, -1, 3090, 3114, 3115, -1, + 3115, 3089, 3090, -1, 3089, 3115, 3116, -1, + 3116, 3088, 3089, -1, 3088, 3116, 3117, -1, + 3117, 3087, 3088, -1, 3087, 3117, 3118, -1, + 3118, 3086, 3087, -1, 3086, 3118, 3119, -1, + 3119, 3085, 3086, -1, 3085, 3119, 3120, -1, + 3120, 3084, 3085, -1, 3084, 3120, 3121, -1, + 3121, 3083, 3084, -1, 3083, 3121, 3122, -1, + 3122, 3082, 3083, -1, 3082, 3122, 3123, -1, + 3123, 3081, 3082, -1, 3081, 3123, 3124, -1, + 3124, 3080, 3081, -1, 3080, 3124, 3125, -1, + 3125, 3079, 3080, -1, 3079, 3125, 3126, -1, + 3126, 3078, 3079, -1, 3078, 3126, 3127, -1, + 3127, 3077, 3078, -1, 3077, 3127, 3128, -1, + 3128, 3076, 3077, -1, 3076, 3128, 3129, -1, + 3129, 3075, 3076, -1, 3075, 3129, 3130, -1, + 3130, 3074, 3075, -1, 3074, 3130, 3131, -1, + 3131, 3073, 3074, -1, 3073, 3131, 3132, -1, + 3132, 3072, 3073, -1, 3072, 3132, 3133, -1, + 3133, 3071, 3072, -1, 3071, 3133, 3134, -1, + 3134, 3070, 3071, -1, 3070, 3134, 3135, -1, + 3135, 3069, 3070, -1, 3069, 3135, 3136, -1, + 3136, 3068, 3069, -1, 3068, 3136, 3137, -1, + 3137, 3067, 3068, -1, 3067, 3137, 3138, -1, + 3138, 3066, 3067, -1, 3066, 3138, 3139, -1, + 3139, 3065, 3066, -1, 3065, 3139, 3140, -1, + 3140, 3064, 3065, -1, 3064, 3140, 3141, -1, + 3141, 3063, 3064, -1, 3063, 3141, 3142, -1, + 3142, 3062, 3063, -1, 3062, 3142, 3143, -1, + 3143, 3061, 3062, -1, 3061, 3143, 3144, -1, + 3144, 3060, 3061, -1, 3060, 3144, 3145, -1, + 3145, 3059, 3060, -1, 3059, 3145, 3146, -1, + 3146, 3058, 3059, -1, 3058, 3146, 3147, -1, + 3147, 3057, 3058, -1, 3057, 3147, 3148, -1, + 3148, 3056, 3057, -1, 3056, 3148, 3149, -1, + 3149, 3055, 3056, -1, 3055, 3149, 3150, -1, + 3150, 3054, 3055, -1, 3054, 3150, 3151, -1, + 3151, 3052, 3054, -1, 3052, 3151, 3152, -1, + 3052, 3152, 3153, -1, 3154, 3155, 2725, -1, + 3154, 3156, 3155, -1, 3156, 3154, 3157, -1, + 3157, 3153, 3156, -1, 3153, 3157, 3158, -1, + 3158, 3052, 3153, -1, 3158, 3053, 3052, -1, + 3158, 3159, 3053, -1, 3159, 3158, 3157, -1, + 3157, 3160, 3159, -1, 3160, 3157, 3154, -1, + 3154, 2725, 3160, -1, 2725, 2712, 3160, -1, + 3161, 3160, 2712, -1, 3161, 3159, 3160, -1, + 3159, 3161, 3162, -1, 3162, 3053, 3159, -1, + 3053, 3162, 3163, -1, 3163, 3050, 3053, -1, + 3163, 3051, 3050, -1, 3163, 3164, 3051, -1, + 3164, 3163, 3162, -1, 3162, 3165, 3164, -1, + 3165, 3162, 3161, -1, 3161, 2712, 3165, -1, + 2712, 2702, 3165, -1, 3166, 3165, 2702, -1, + 3166, 3164, 3165, -1, 3164, 3166, 3167, -1, + 3167, 3051, 3164, -1, 3051, 3167, 3168, -1, + 3168, 2952, 3051, -1, 3168, 2953, 2952, -1, + 3168, 3169, 2953, -1, 3169, 3168, 3167, -1, + 3167, 3170, 3169, -1, 3170, 3167, 3166, -1, + 3166, 2702, 3170, -1, 2702, 2704, 3170, -1, + 3171, 3170, 2704, -1, 3171, 3169, 3170, -1, + 3169, 3171, 3172, -1, 3172, 2953, 3169, -1, + 2953, 3172, 3173, -1, 3173, 2951, 2953, -1, + 3173, 2950, 2951, -1, 3173, 2949, 2950, -1, + 2949, 3173, 3172, -1, 3172, 2948, 2949, -1, + 2948, 3172, 3171, -1, 3171, 2704, 2948, -1, + 2704, 2759, 2948, -1, 2704, 2758, 2759, -1, + 2758, 2704, 2703, -1, 2703, 2757, 2758, -1, + 2757, 2703, 2710, -1, 2710, 2756, 2757, -1, + 2756, 2710, 3174, -1, 3174, 2754, 2756, -1, + 3174, 3175, 2754, -1, 3175, 3174, 2710, -1, + 3175, 2710, 2707, -1, 2707, 2754, 3175, -1, + 2754, 2707, 2706, -1, 2701, 2755, 2754, -1, + 2755, 2701, 2700, -1, 2700, 2749, 2755, -1, + 2700, 2699, 2749, -1, 2699, 2750, 2749, -1, + 2750, 2699, 2701, -1, 2750, 2701, 3176, -1, + 3176, 2751, 2750, -1, 3176, 2765, 2751, -1, + 2765, 3176, 2701, -1, 2701, 3177, 2765, -1, + 3178, 3179, 3177, -1, 3179, 2765, 3177, -1, + 3179, 2747, 2765, -1, 3179, 3178, 2747, -1, + 3178, 2748, 2747, -1, 2748, 3178, 3177, -1, + 2748, 3177, 3180, -1, 3180, 2734, 2748, -1, + 3180, 2735, 2734, -1, 2735, 3180, 3177, -1, + 3177, 3181, 2735, -1, 3182, 3183, 3184, -1, + 1562, 3185, 3182, -1, 3185, 1562, 1677, -1, + 3185, 1677, 1673, -1, 3185, 1673, 1672, -1, + 1672, 3182, 3185, -1, 3186, 3182, 1672, -1, + 3186, 1672, 1591, -1, 3186, 1591, 1590, -1, + 1590, 3182, 3186, -1, 1590, 1592, 3182, -1, + 1592, 3183, 3182, -1, 3183, 1592, 1593, -1, + 3183, 1593, 1664, -1, 1664, 3184, 3183, -1, + 1664, 3187, 3184, -1, 3187, 1664, 1596, -1, + 3187, 1596, 1595, -1, 1595, 3184, 3187, -1, + 1595, 1597, 3184, -1, 1597, 1600, 3184, -1, + 3184, 1600, 1602, -1, 3181, 1145, 1144, -1, + 1144, 3188, 3181, -1, 1144, 1142, 3188, -1, + 3188, 1142, 3189, -1, 3189, 3181, 3188, -1, + 3189, 3190, 3181, -1, 3190, 3191, 3181, -1, + 3191, 2735, 3181, -1, 3191, 2736, 2735, -1, + 3191, 3190, 2736, -1, 3190, 3189, 2736, -1, + 2736, 3189, 1142, -1, 1142, 2738, 2736, -1, + 2738, 1142, 1140, -1, 1140, 2740, 2738, -1, + 2740, 1140, 1138, -1, 1138, 2733, 2740, -1, + 2733, 1138, 1136, -1, 1136, 2731, 2733, -1, + 2731, 1136, 1134, -1, 1134, 3192, 2731, -1, + 3192, 1134, 1123, -1, 1123, 1122, 3192, -1, + 3193, 3192, 1122, -1, 3192, 3193, 3194, -1, + 3194, 2731, 3192, -1, 3194, 2732, 2731, -1, + 3194, 3195, 2732, -1, 3195, 3194, 3193, -1, + 3193, 3196, 3195, -1, 3196, 3193, 1122, -1, + 1122, 3197, 3196, -1, 3197, 1122, 1125, -1, + 1125, 3198, 3197, -1, 3198, 1125, 1127, -1, + 1127, 3199, 3198, -1, 3199, 1127, 1128, -1, + 1128, 3200, 3199, -1, 3200, 1128, 1130, -1, + 1130, 3201, 3200, -1, 3201, 1130, 1152, -1, + 1152, 3202, 3201, -1, 3202, 1152, 1154, -1, + 1154, 3203, 3202, -1, 3203, 1154, 1156, -1, + 1156, 3204, 3203, -1, 3204, 1156, 1158, -1, + 1158, 3205, 3204, -1, 3205, 1158, 1160, -1, + 1160, 3206, 3205, -1, 3206, 1160, 1162, -1, + 1162, 3207, 3206, -1, 3207, 1162, 1164, -1, + 1164, 3208, 3207, -1, 3208, 1164, 1166, -1, + 1166, 3209, 3208, -1, 3209, 1166, 1168, -1, + 1168, 3210, 3209, -1, 3210, 1168, 1170, -1, + 1170, 3211, 3210, -1, 3211, 1170, 1172, -1, + 1172, 3212, 3211, -1, 3212, 1172, 1174, -1, + 1174, 3213, 3212, -1, 3213, 1174, 1071, -1, + 1071, 3214, 3213, -1, 3214, 1071, 744, -1, + 744, 743, 3214, -1, 743, 3215, 3214, -1, + 3215, 743, 746, -1, 746, 3216, 3215, -1, + 3216, 746, 747, -1, 747, 3217, 3216, -1, + 3217, 747, 748, -1, 748, 3218, 3217, -1, + 3218, 748, 749, -1, 749, 3219, 3218, -1, + 3219, 749, 750, -1, 750, 3220, 3219, -1, + 3220, 750, 751, -1, 751, 3221, 3220, -1, + 3221, 751, 753, -1, 753, 3222, 3221, -1, + 3222, 753, 755, -1, 755, 3223, 3222, -1, + 3223, 755, 757, -1, 757, 3224, 3223, -1, + 3224, 757, 937, -1, 937, 3225, 3224, -1, + 3225, 937, 936, -1, 936, 3226, 3225, -1, + 3226, 936, 935, -1, 935, 3227, 3226, -1, + 3227, 935, 934, -1, 934, 3228, 3227, -1, + 3228, 934, 933, -1, 933, 3229, 3228, -1, + 3229, 933, 932, -1, 932, 3230, 3229, -1, + 3230, 932, 931, -1, 931, 3231, 3230, -1, + 3231, 931, 930, -1, 930, 3232, 3231, -1, + 3232, 930, 929, -1, 929, 3233, 3232, -1, + 3233, 929, 928, -1, 928, 3234, 3233, -1, + 3234, 928, 927, -1, 927, 3235, 3234, -1, + 3235, 927, 926, -1, 926, 3236, 3235, -1, + 3236, 926, 925, -1, 925, 3237, 3236, -1, + 3237, 925, 924, -1, 924, 3238, 3237, -1, + 3238, 924, 923, -1, 923, 3239, 3238, -1, + 923, 3240, 3239, -1, 3240, 923, 922, -1, + 922, 3241, 3240, -1, 3241, 922, 921, -1, + 921, 3242, 3241, -1, 3242, 921, 920, -1, + 920, 3243, 3242, -1, 3243, 920, 919, -1, + 919, 3244, 3243, -1, 3244, 919, 918, -1, + 918, 3245, 3244, -1, 3245, 918, 917, -1, + 917, 3246, 3245, -1, 3246, 917, 916, -1, + 916, 3247, 3246, -1, 3247, 916, 915, -1, + 915, 3248, 3247, -1, 3248, 915, 914, -1, + 914, 3249, 3248, -1, 3249, 914, 913, -1, + 913, 3250, 3249, -1, 3250, 913, 912, -1, + 912, 3251, 3250, -1, 3251, 912, 911, -1, + 911, 3252, 3251, -1, 3252, 911, 910, -1, + 910, 3253, 3252, -1, 3253, 910, 909, -1, + 909, 3254, 3253, -1, 3254, 909, 908, -1, + 908, 3255, 3254, -1, 3255, 908, 907, -1, + 907, 3256, 3255, -1, 3256, 907, 906, -1, + 906, 3257, 3256, -1, 3257, 906, 905, -1, + 905, 3258, 3257, -1, 3258, 905, 904, -1, + 904, 3259, 3258, -1, 3259, 904, 903, -1, + 903, 3260, 3259, -1, 3260, 903, 902, -1, + 902, 3261, 3260, -1, 3261, 902, 901, -1, + 901, 3262, 3261, -1, 3262, 901, 900, -1, + 900, 3263, 3262, -1, 3263, 900, 824, -1, + 824, 3264, 3263, -1, 3264, 824, 822, -1, + 822, 3265, 3264, -1, 3265, 822, 820, -1, + 820, 3266, 3265, -1, 3266, 820, 818, -1, + 818, 3267, 3266, -1, 3267, 818, 816, -1, + 816, 3268, 3267, -1, 3268, 816, 814, -1, + 814, 3269, 3268, -1, 3269, 814, 812, -1, + 812, 3270, 3269, -1, 3270, 812, 810, -1, + 810, 3271, 3270, -1, 3271, 810, 808, -1, + 808, 3272, 3271, -1, 3272, 808, 806, -1, + 806, 3273, 3272, -1, 3273, 806, 804, -1, + 804, 3274, 3273, -1, 3274, 804, 802, -1, + 802, 3275, 3274, -1, 3275, 802, 800, -1, + 800, 3276, 3275, -1, 3276, 800, 798, -1, + 798, 3277, 3276, -1, 3277, 798, 797, -1, + 797, 3278, 3277, -1, 3278, 797, 796, -1, + 796, 3279, 3278, -1, 3279, 796, 795, -1, + 795, 3280, 3279, -1, 3280, 795, 794, -1, + 794, 3281, 3280, -1, 3281, 794, 763, -1, + 763, 762, 3281, -1, 762, 3282, 3281, -1, + 3282, 762, 765, -1, 765, 3283, 3282, -1, + 765, 766, 3283, -1, 3284, 3283, 766, -1, + 3284, 766, 769, -1, 769, 770, 3284, -1, + 3285, 3286, 3284, -1, 3285, 3284, 770, -1, + 770, 3287, 3285, -1, 3287, 770, 771, -1, + 771, 3288, 3287, -1, 3288, 771, 772, -1, + 772, 3289, 3288, -1, 3289, 772, 731, -1, + 731, 732, 3289, -1, 3290, 3291, 3292, -1, + 3291, 3290, 3293, -1, 3290, 3294, 3293, -1, + 3290, 3292, 3294, -1, 3292, 732, 3294, -1, + 732, 3292, 3295, -1, 3295, 3289, 732, -1, + 3289, 3295, 3296, -1, 3296, 3288, 3289, -1, + 3288, 3296, 3297, -1, 3297, 3287, 3288, -1, + 3287, 3297, 3298, -1, 3298, 3285, 3287, -1, + 3298, 3299, 3285, -1, 3300, 3301, 3302, -1, + 3301, 3300, 3303, -1, 3303, 3304, 3301, -1, + 3304, 3303, 3299, -1, 3299, 3305, 3304, -1, + 3305, 3299, 3298, -1, 3305, 3298, 727, -1, + 3305, 727, 726, -1, 726, 3304, 3305, -1, + 3304, 726, 725, -1, 725, 3301, 3304, -1, + 3301, 725, 720, -1, 720, 3302, 3301, -1, + 3302, 720, 718, -1, 718, 3306, 3302, -1, + 3306, 718, 716, -1, 716, 3307, 3306, -1, + 3307, 716, 714, -1, 714, 3308, 3307, -1, + 3308, 714, 712, -1, 712, 3309, 3308, -1, + 3309, 712, 710, -1, 710, 3310, 3309, -1, + 3310, 710, 708, -1, 708, 3311, 3310, -1, + 3311, 708, 706, -1, 706, 3312, 3311, -1, + 3312, 706, 704, -1, 704, 3313, 3312, -1, + 3313, 704, 702, -1, 702, 3314, 3313, -1, + 3314, 702, 700, -1, 700, 3315, 3314, -1, + 3315, 700, 698, -1, 698, 3316, 3315, -1, + 3316, 698, 696, -1, 696, 3317, 3316, -1, + 3317, 696, 694, -1, 694, 3318, 3317, -1, + 3318, 694, 692, -1, 692, 3319, 3318, -1, + 3319, 692, 690, -1, 690, 3320, 3319, -1, + 3320, 690, 688, -1, 688, 3321, 3320, -1, + 3321, 688, 686, -1, 686, 3322, 3321, -1, + 3322, 686, 684, -1, 684, 3323, 3322, -1, + 3323, 684, 682, -1, 682, 3324, 3323, -1, + 3324, 682, 680, -1, 680, 3325, 3324, -1, + 3325, 680, 678, -1, 678, 3326, 3325, -1, + 3326, 678, 676, -1, 676, 3327, 3326, -1, + 3327, 676, 674, -1, 674, 3328, 3327, -1, + 3328, 674, 672, -1, 672, 3329, 3328, -1, + 3329, 672, 670, -1, 670, 3330, 3329, -1, + 3330, 670, 668, -1, 668, 3331, 3330, -1, + 3331, 668, 666, -1, 666, 3332, 3331, -1, + 3332, 666, 664, -1, 664, 3333, 3332, -1, + 3333, 664, 662, -1, 662, 3334, 3333, -1, + 3334, 662, 660, -1, 660, 3335, 3334, -1, + 3335, 660, 658, -1, 658, 3336, 3335, -1, + 3336, 658, 656, -1, 656, 3337, 3336, -1, + 3337, 656, 654, -1, 654, 3338, 3337, -1, + 3338, 654, 652, -1, 652, 3339, 3338, -1, + 3339, 652, 650, -1, 650, 3340, 3339, -1, + 3340, 650, 648, -1, 648, 3341, 3340, -1, + 3341, 648, 646, -1, 646, 3342, 3341, -1, + 3342, 646, 644, -1, 644, 3343, 3342, -1, + 3343, 644, 642, -1, 642, 3344, 3343, -1, + 3344, 642, 640, -1, 640, 3345, 3344, -1, + 3345, 640, 638, -1, 638, 3346, 3345, -1, + 3346, 638, 636, -1, 636, 3347, 3346, -1, + 3347, 636, 634, -1, 634, 3348, 3347, -1, + 3348, 634, 632, -1, 632, 3349, 3348, -1, + 3349, 632, 629, -1, 3349, 629, 627, -1, + 627, 3350, 3349, -1, 3350, 627, 625, -1, + 625, 3351, 3350, -1, 3351, 625, 623, -1, + 623, 3352, 3351, -1, 3352, 623, 621, -1, + 621, 3353, 3352, -1, 3353, 621, 619, -1, + 619, 3354, 3353, -1, 3354, 619, 617, -1, + 617, 3355, 3354, -1, 3355, 617, 615, -1, + 615, 3356, 3355, -1, 3356, 615, 613, -1, + 613, 3357, 3356, -1, 3357, 613, 611, -1, + 611, 3358, 3357, -1, 3358, 611, 609, -1, + 609, 3359, 3358, -1, 3359, 609, 607, -1, + 607, 3360, 3359, -1, 3360, 607, 605, -1, + 605, 3361, 3360, -1, 3361, 605, 603, -1, + 603, 3362, 3361, -1, 3362, 603, 601, -1, + 601, 3363, 3362, -1, 3363, 601, 599, -1, + 599, 3364, 3363, -1, 3364, 599, 597, -1, + 597, 3365, 3364, -1, 3365, 597, 595, -1, + 595, 3366, 3365, -1, 3366, 595, 593, -1, + 593, 3367, 3366, -1, 3367, 593, 591, -1, + 591, 3368, 3367, -1, 3368, 591, 589, -1, + 589, 3369, 3368, -1, 3369, 589, 587, -1, + 587, 3370, 3369, -1, 3370, 587, 585, -1, + 585, 3371, 3370, -1, 3371, 585, 583, -1, + 583, 3372, 3371, -1, 3372, 583, 581, -1, + 581, 3373, 3372, -1, 3373, 581, 579, -1, + 579, 3374, 3373, -1, 3374, 579, 577, -1, + 577, 3375, 3374, -1, 3375, 577, 575, -1, + 575, 3376, 3375, -1, 3376, 575, 573, -1, + 573, 3377, 3376, -1, 3377, 573, 571, -1, + 571, 3378, 3377, -1, 3378, 571, 569, -1, + 569, 3379, 3378, -1, 3379, 569, 567, -1, + 567, 3380, 3379, -1, 3380, 567, 565, -1, + 565, 3381, 3380, -1, 3381, 565, 563, -1, + 563, 3382, 3381, -1, 3382, 563, 561, -1, + 561, 3383, 3382, -1, 3383, 561, 559, -1, + 559, 3384, 3383, -1, 3384, 559, 557, -1, + 557, 3385, 3384, -1, 3385, 557, 555, -1, + 555, 3386, 3385, -1, 3386, 555, 553, -1, + 553, 3387, 3386, -1, 3387, 553, 551, -1, + 551, 3388, 3387, -1, 3388, 551, 550, -1, + 550, 3389, 3388, -1, 3389, 550, 3390, -1, + 3390, 3391, 3389, -1, 3391, 3390, 3392, -1, + 3392, 3393, 3391, -1, 3393, 3392, 3394, -1, + 3394, 3395, 3393, -1, 3395, 3394, 3396, -1, + 3396, 3397, 3395, -1, 3397, 3396, 548, -1, + 548, 547, 3397, -1, 3398, 547, 3399, -1, + 3398, 3397, 547, -1, 3397, 3398, 3400, -1, + 3400, 3395, 3397, -1, 3395, 3400, 3401, -1, + 3401, 3393, 3395, -1, 3393, 3401, 3402, -1, + 3402, 3391, 3393, -1, 3391, 3402, 3403, -1, + 3403, 3389, 3391, -1, 3389, 3403, 3404, -1, + 3404, 3388, 3389, -1, 3388, 3404, 3405, -1, + 3405, 3387, 3388, -1, 3387, 3405, 3406, -1, + 3406, 3386, 3387, -1, 3386, 3406, 3407, -1, + 3407, 3385, 3386, -1, 3385, 3407, 3408, -1, + 3408, 3384, 3385, -1, 3384, 3408, 3409, -1, + 3409, 3383, 3384, -1, 3383, 3409, 3410, -1, + 3410, 3382, 3383, -1, 3382, 3410, 3411, -1, + 3411, 3381, 3382, -1, 3381, 3411, 3412, -1, + 3412, 3380, 3381, -1, 3380, 3412, 3413, -1, + 3413, 3379, 3380, -1, 3379, 3413, 3414, -1, + 3414, 3378, 3379, -1, 3378, 3414, 3415, -1, + 3415, 3377, 3378, -1, 3377, 3415, 3416, -1, + 3416, 3376, 3377, -1, 3376, 3416, 3417, -1, + 3417, 3375, 3376, -1, 3375, 3417, 3418, -1, + 3418, 3374, 3375, -1, 3374, 3418, 3419, -1, + 3419, 3373, 3374, -1, 3373, 3419, 3420, -1, + 3420, 3372, 3373, -1, 3372, 3420, 3421, -1, + 3421, 3371, 3372, -1, 3371, 3421, 3422, -1, + 3422, 3370, 3371, -1, 3370, 3422, 3423, -1, + 3423, 3369, 3370, -1, 3369, 3423, 3424, -1, + 3424, 3368, 3369, -1, 3368, 3424, 3425, -1, + 3425, 3367, 3368, -1, 3367, 3425, 3426, -1, + 3426, 3366, 3367, -1, 3366, 3426, 3427, -1, + 3427, 3365, 3366, -1, 3365, 3427, 3428, -1, + 3428, 3364, 3365, -1, 3364, 3428, 3429, -1, + 3429, 3363, 3364, -1, 3363, 3429, 3430, -1, + 3430, 3362, 3363, -1, 3362, 3430, 3431, -1, + 3431, 3361, 3362, -1, 3361, 3431, 3432, -1, + 3432, 3360, 3361, -1, 3360, 3432, 3433, -1, + 3433, 3359, 3360, -1, 3359, 3433, 3434, -1, + 3434, 3358, 3359, -1, 3358, 3434, 3435, -1, + 3435, 3357, 3358, -1, 3357, 3435, 3436, -1, + 3436, 3356, 3357, -1, 3356, 3436, 3437, -1, + 3437, 3355, 3356, -1, 3355, 3437, 3438, -1, + 3438, 3354, 3355, -1, 3354, 3438, 3439, -1, + 3439, 3353, 3354, -1, 3353, 3439, 3440, -1, + 3440, 3352, 3353, -1, 3352, 3440, 3441, -1, + 3441, 3351, 3352, -1, 3351, 3441, 3442, -1, + 3442, 3350, 3351, -1, 3350, 3442, 3443, -1, + 3443, 3349, 3350, -1, 3443, 3348, 3349, -1, + 3348, 3443, 3444, -1, 3444, 3347, 3348, -1, + 3347, 3444, 3445, -1, 3445, 3346, 3347, -1, + 3346, 3445, 3446, -1, 3446, 3345, 3346, -1, + 3345, 3446, 3447, -1, 3447, 3344, 3345, -1, + 3344, 3447, 3448, -1, 3448, 3343, 3344, -1, + 3343, 3448, 3449, -1, 3449, 3342, 3343, -1, + 3342, 3449, 3450, -1, 3450, 3341, 3342, -1, + 3341, 3450, 3451, -1, 3451, 3340, 3341, -1, + 3340, 3451, 3452, -1, 3452, 3339, 3340, -1, + 3339, 3452, 3453, -1, 3453, 3338, 3339, -1, + 3338, 3453, 3454, -1, 3454, 3337, 3338, -1, + 3337, 3454, 3455, -1, 3455, 3336, 3337, -1, + 3336, 3455, 3456, -1, 3456, 3335, 3336, -1, + 3335, 3456, 3457, -1, 3457, 3334, 3335, -1, + 3334, 3457, 3458, -1, 3458, 3333, 3334, -1, + 3333, 3458, 3459, -1, 3459, 3332, 3333, -1, + 3332, 3459, 3460, -1, 3460, 3331, 3332, -1, + 3331, 3460, 3461, -1, 3461, 3330, 3331, -1, + 3330, 3461, 3462, -1, 3462, 3329, 3330, -1, + 3329, 3462, 3463, -1, 3463, 3328, 3329, -1, + 3328, 3463, 3464, -1, 3464, 3327, 3328, -1, + 3327, 3464, 3465, -1, 3465, 3326, 3327, -1, + 3326, 3465, 3466, -1, 3466, 3325, 3326, -1, + 3325, 3466, 3467, -1, 3467, 3324, 3325, -1, + 3324, 3467, 3468, -1, 3468, 3323, 3324, -1, + 3323, 3468, 3469, -1, 3469, 3322, 3323, -1, + 3322, 3469, 3470, -1, 3470, 3321, 3322, -1, + 3321, 3470, 3471, -1, 3471, 3320, 3321, -1, + 3320, 3471, 3472, -1, 3472, 3319, 3320, -1, + 3319, 3472, 3473, -1, 3473, 3318, 3319, -1, + 3318, 3473, 3474, -1, 3474, 3317, 3318, -1, + 3317, 3474, 3475, -1, 3475, 3316, 3317, -1, + 3316, 3475, 3476, -1, 3476, 3315, 3316, -1, + 3315, 3476, 3477, -1, 3477, 3314, 3315, -1, + 3314, 3477, 3478, -1, 3478, 3313, 3314, -1, + 3313, 3478, 3479, -1, 3479, 3312, 3313, -1, + 3312, 3479, 3480, -1, 3480, 3311, 3312, -1, + 3311, 3480, 3481, -1, 3481, 3310, 3311, -1, + 3310, 3481, 3482, -1, 3482, 3309, 3310, -1, + 3309, 3482, 3483, -1, 3483, 3308, 3309, -1, + 3308, 3483, 3484, -1, 3484, 3307, 3308, -1, + 3307, 3484, 3485, -1, 3485, 3306, 3307, -1, + 3306, 3485, 541, -1, 541, 3302, 3306, -1, + 3302, 541, 540, -1, 540, 3300, 3302, -1, + 3300, 540, 3486, -1, 3486, 3303, 3300, -1, + 3303, 3486, 3487, -1, 3487, 3299, 3303, -1, + 3487, 3285, 3299, -1, 3487, 3286, 3285, -1, + 3286, 3487, 3486, -1, 3486, 3488, 3286, -1, + 3488, 3486, 540, -1, 540, 539, 3488, -1, + 3488, 539, 3489, -1, 3489, 3286, 3488, -1, + 3489, 3284, 3286, -1, 3489, 3283, 3284, -1, + 3283, 3489, 539, -1, 539, 3282, 3283, -1, + 3282, 539, 541, -1, 541, 3281, 3282, -1, + 3281, 541, 3485, -1, 3485, 3280, 3281, -1, + 3280, 3485, 3484, -1, 3484, 3279, 3280, -1, + 3279, 3484, 3483, -1, 3483, 3278, 3279, -1, + 3278, 3483, 3482, -1, 3482, 3277, 3278, -1, + 3277, 3482, 3481, -1, 3481, 3276, 3277, -1, + 3276, 3481, 3480, -1, 3480, 3275, 3276, -1, + 3275, 3480, 3479, -1, 3479, 3274, 3275, -1, + 3274, 3479, 3478, -1, 3478, 3273, 3274, -1, + 3273, 3478, 3477, -1, 3477, 3272, 3273, -1, + 3272, 3477, 3476, -1, 3476, 3271, 3272, -1, + 3271, 3476, 3475, -1, 3475, 3270, 3271, -1, + 3270, 3475, 3474, -1, 3474, 3269, 3270, -1, + 3269, 3474, 3473, -1, 3473, 3268, 3269, -1, + 3268, 3473, 3472, -1, 3472, 3267, 3268, -1, + 3267, 3472, 3471, -1, 3471, 3266, 3267, -1, + 3266, 3471, 3470, -1, 3470, 3265, 3266, -1, + 3265, 3470, 3469, -1, 3469, 3264, 3265, -1, + 3264, 3469, 3468, -1, 3468, 3263, 3264, -1, + 3263, 3468, 3467, -1, 3467, 3262, 3263, -1, + 3262, 3467, 3466, -1, 3466, 3261, 3262, -1, + 3261, 3466, 3465, -1, 3465, 3260, 3261, -1, + 3260, 3465, 3464, -1, 3464, 3259, 3260, -1, + 3259, 3464, 3463, -1, 3463, 3258, 3259, -1, + 3258, 3463, 3462, -1, 3462, 3257, 3258, -1, + 3257, 3462, 3461, -1, 3461, 3256, 3257, -1, + 3256, 3461, 3460, -1, 3460, 3255, 3256, -1, + 3255, 3460, 3459, -1, 3459, 3254, 3255, -1, + 3254, 3459, 3458, -1, 3458, 3253, 3254, -1, + 3253, 3458, 3457, -1, 3457, 3252, 3253, -1, + 3252, 3457, 3456, -1, 3456, 3251, 3252, -1, + 3251, 3456, 3455, -1, 3455, 3250, 3251, -1, + 3250, 3455, 3454, -1, 3454, 3249, 3250, -1, + 3249, 3454, 3453, -1, 3453, 3248, 3249, -1, + 3248, 3453, 3452, -1, 3452, 3247, 3248, -1, + 3247, 3452, 3451, -1, 3451, 3246, 3247, -1, + 3246, 3451, 3450, -1, 3450, 3245, 3246, -1, + 3245, 3450, 3449, -1, 3449, 3244, 3245, -1, + 3244, 3449, 3448, -1, 3448, 3243, 3244, -1, + 3243, 3448, 3447, -1, 3447, 3242, 3243, -1, + 3242, 3447, 3446, -1, 3446, 3241, 3242, -1, + 3241, 3446, 3445, -1, 3445, 3240, 3241, -1, + 3240, 3445, 3444, -1, 3444, 3239, 3240, -1, + 3239, 3444, 3443, -1, 3239, 3443, 3442, -1, + 3442, 3238, 3239, -1, 3238, 3442, 3441, -1, + 3441, 3237, 3238, -1, 3237, 3441, 3440, -1, + 3440, 3236, 3237, -1, 3236, 3440, 3439, -1, + 3439, 3235, 3236, -1, 3235, 3439, 3438, -1, + 3438, 3234, 3235, -1, 3234, 3438, 3437, -1, + 3437, 3233, 3234, -1, 3233, 3437, 3436, -1, + 3436, 3232, 3233, -1, 3232, 3436, 3435, -1, + 3435, 3231, 3232, -1, 3231, 3435, 3434, -1, + 3434, 3230, 3231, -1, 3230, 3434, 3433, -1, + 3433, 3229, 3230, -1, 3229, 3433, 3432, -1, + 3432, 3228, 3229, -1, 3228, 3432, 3431, -1, + 3431, 3227, 3228, -1, 3227, 3431, 3430, -1, + 3430, 3226, 3227, -1, 3226, 3430, 3429, -1, + 3429, 3225, 3226, -1, 3225, 3429, 3428, -1, + 3428, 3224, 3225, -1, 3224, 3428, 3427, -1, + 3427, 3223, 3224, -1, 3223, 3427, 3426, -1, + 3426, 3222, 3223, -1, 3222, 3426, 3425, -1, + 3425, 3221, 3222, -1, 3221, 3425, 3424, -1, + 3424, 3220, 3221, -1, 3220, 3424, 3423, -1, + 3423, 3219, 3220, -1, 3219, 3423, 3422, -1, + 3422, 3218, 3219, -1, 3218, 3422, 3421, -1, + 3421, 3217, 3218, -1, 3217, 3421, 3420, -1, + 3420, 3216, 3217, -1, 3216, 3420, 3419, -1, + 3419, 3215, 3216, -1, 3215, 3419, 3418, -1, + 3418, 3214, 3215, -1, 3214, 3418, 3417, -1, + 3417, 3213, 3214, -1, 3213, 3417, 3416, -1, + 3416, 3212, 3213, -1, 3212, 3416, 3415, -1, + 3415, 3211, 3212, -1, 3211, 3415, 3414, -1, + 3414, 3210, 3211, -1, 3210, 3414, 3413, -1, + 3413, 3209, 3210, -1, 3209, 3413, 3412, -1, + 3412, 3208, 3209, -1, 3208, 3412, 3411, -1, + 3411, 3207, 3208, -1, 3207, 3411, 3410, -1, + 3410, 3206, 3207, -1, 3206, 3410, 3409, -1, + 3409, 3205, 3206, -1, 3205, 3409, 3408, -1, + 3408, 3204, 3205, -1, 3204, 3408, 3407, -1, + 3407, 3203, 3204, -1, 3203, 3407, 3406, -1, + 3406, 3202, 3203, -1, 3202, 3406, 3405, -1, + 3405, 3201, 3202, -1, 3201, 3405, 3404, -1, + 3404, 3200, 3201, -1, 3200, 3404, 3403, -1, + 3403, 3199, 3200, -1, 3199, 3403, 3402, -1, + 3402, 3198, 3199, -1, 3198, 3402, 3401, -1, + 3401, 3197, 3198, -1, 3197, 3401, 3400, -1, + 3400, 3196, 3197, -1, 3196, 3400, 3398, -1, + 3398, 3195, 3196, -1, 3195, 3398, 3399, -1, + 3399, 2732, 3195, -1, 2732, 3399, 3490, -1, + 3490, 2730, 2732, -1, 3490, 2743, 2730, -1, + 3490, 3491, 2743, -1, 3491, 3490, 3399, -1, + 3491, 3399, 547, -1, 3491, 547, 545, -1, + 545, 2743, 3491, -1, 2743, 545, 542, -1, + 542, 2742, 2743, -1, 542, 544, 2742, -1, + 3492, 2742, 544, -1, 3492, 2744, 2742, -1, + 3492, 2767, 2744, -1, 3492, 2935, 2767, -1, + 2935, 3492, 544, -1, 544, 2934, 2935, -1, + 2934, 544, 543, -1, 543, 546, 2934, -1, + 546, 2927, 2934, -1, 546, 2926, 2927, -1, + 2926, 546, 548, -1, 548, 2925, 2926, -1, + 2925, 548, 3396, -1, 3396, 2924, 2925, -1, + 2924, 3396, 3394, -1, 3394, 2923, 2924, -1, + 2923, 3394, 3392, -1, 3392, 2922, 2923, -1, + 2922, 3392, 3390, -1, 3390, 2921, 2922, -1, + 2921, 3390, 550, -1, 550, 549, 2921, -1, + 549, 2920, 2921, -1, 2920, 549, 552, -1, + 552, 2919, 2920, -1, 2919, 552, 554, -1, + 554, 2918, 2919, -1, 2918, 554, 556, -1, + 556, 2917, 2918, -1, 2917, 556, 558, -1, + 558, 2916, 2917, -1, 2916, 558, 560, -1, + 560, 2915, 2916, -1, 2915, 560, 562, -1, + 562, 2914, 2915, -1, 2914, 562, 564, -1, + 564, 2913, 2914, -1, 2913, 564, 566, -1, + 566, 2912, 2913, -1, 2912, 566, 568, -1, + 568, 2911, 2912, -1, 2911, 568, 570, -1, + 570, 2910, 2911, -1, 2910, 570, 572, -1, + 572, 2909, 2910, -1, 2909, 572, 574, -1, + 574, 2908, 2909, -1, 2908, 574, 576, -1, + 576, 2907, 2908, -1, 2907, 576, 578, -1, + 578, 2906, 2907, -1, 2906, 578, 580, -1, + 580, 2905, 2906, -1, 2905, 580, 582, -1, + 582, 2904, 2905, -1, 2904, 582, 584, -1, + 584, 2903, 2904, -1, 2903, 584, 586, -1, + 586, 2902, 2903, -1, 2902, 586, 588, -1, + 588, 2901, 2902, -1, 2901, 588, 590, -1, + 590, 2900, 2901, -1, 2900, 590, 592, -1, + 592, 2899, 2900, -1, 2899, 592, 594, -1, + 594, 2898, 2899, -1, 2898, 594, 596, -1, + 596, 2897, 2898, -1, 2897, 596, 598, -1, + 598, 2896, 2897, -1, 2896, 598, 600, -1, + 600, 2895, 2896, -1, 2895, 600, 602, -1, + 602, 2894, 2895, -1, 2894, 602, 604, -1, + 604, 2893, 2894, -1, 2893, 604, 606, -1, + 606, 2892, 2893, -1, 2892, 606, 608, -1, + 608, 2891, 2892, -1, 2891, 608, 610, -1, + 610, 2890, 2891, -1, 2890, 610, 612, -1, + 612, 2889, 2890, -1, 2889, 612, 614, -1, + 614, 2888, 2889, -1, 2888, 614, 616, -1, + 616, 2887, 2888, -1, 2887, 616, 618, -1, + 618, 2886, 2887, -1, 2886, 618, 620, -1, + 620, 2885, 2886, -1, 2885, 620, 622, -1, + 622, 2884, 2885, -1, 2884, 622, 624, -1, + 624, 2883, 2884, -1, 2883, 624, 626, -1, + 626, 2882, 2883, -1, 2882, 626, 628, -1, + 628, 2881, 2882, -1, 2881, 628, 630, -1, + 630, 2879, 2881, -1, 630, 3493, 2879, -1, + 631, 3494, 3493, -1, 3494, 631, 633, -1, + 633, 3495, 3494, -1, 3495, 633, 635, -1, + 635, 3496, 3495, -1, 3496, 635, 637, -1, + 637, 3497, 3496, -1, 3497, 637, 639, -1, + 639, 3498, 3497, -1, 3498, 639, 641, -1, + 641, 3499, 3498, -1, 3499, 641, 643, -1, + 643, 3500, 3499, -1, 3500, 643, 645, -1, + 645, 3501, 3500, -1, 3501, 645, 647, -1, + 647, 3502, 3501, -1, 3502, 647, 649, -1, + 649, 3503, 3502, -1, 3503, 649, 651, -1, + 651, 3504, 3503, -1, 3504, 651, 653, -1, + 653, 3505, 3504, -1, 3505, 653, 655, -1, + 655, 3506, 3505, -1, 3506, 655, 657, -1, + 657, 3507, 3506, -1, 3507, 657, 659, -1, + 659, 3508, 3507, -1, 3508, 659, 661, -1, + 661, 3509, 3508, -1, 3509, 661, 663, -1, + 663, 3510, 3509, -1, 3510, 663, 665, -1, + 665, 3511, 3510, -1, 3511, 665, 667, -1, + 667, 3512, 3511, -1, 3512, 667, 669, -1, + 669, 3513, 3512, -1, 3513, 669, 671, -1, + 671, 3514, 3513, -1, 3514, 671, 673, -1, + 673, 3515, 3514, -1, 3515, 673, 675, -1, + 675, 3516, 3515, -1, 3516, 675, 677, -1, + 677, 3517, 3516, -1, 3517, 677, 679, -1, + 679, 3518, 3517, -1, 3518, 679, 681, -1, + 681, 3519, 3518, -1, 3519, 681, 683, -1, + 683, 3520, 3519, -1, 3520, 683, 685, -1, + 685, 3521, 3520, -1, 3521, 685, 687, -1, + 687, 3522, 3521, -1, 3522, 687, 689, -1, + 689, 3523, 3522, -1, 3523, 689, 691, -1, + 691, 3524, 3523, -1, 3524, 691, 693, -1, + 693, 3525, 3524, -1, 3525, 693, 695, -1, + 695, 3526, 3525, -1, 3526, 695, 697, -1, + 697, 3527, 3526, -1, 3527, 697, 699, -1, + 699, 3528, 3527, -1, 3528, 699, 701, -1, + 701, 3529, 3528, -1, 3529, 701, 703, -1, + 703, 3530, 3529, -1, 3530, 703, 705, -1, + 705, 3531, 3530, -1, 3531, 705, 707, -1, + 707, 3532, 3531, -1, 3532, 707, 709, -1, + 709, 3533, 3532, -1, 3533, 709, 711, -1, + 711, 3534, 3533, -1, 3535, 3536, 3537, -1, + 3535, 3537, 3538, -1, 3538, 3539, 3535, -1, + 3539, 3538, 3540, -1, 3540, 3541, 3539, -1, + 3541, 3540, 3542, -1, 3542, 3543, 3541, -1, + 3543, 3542, 3544, -1, 3544, 3545, 3543, -1, + 3545, 3544, 3546, -1, 3546, 3547, 3545, -1, + 3547, 3546, 3548, -1, 3548, 3549, 3547, -1, + 3549, 3548, 3534, -1, 3534, 711, 3549, -1, + 3549, 711, 713, -1, 713, 3547, 3549, -1, + 3547, 713, 715, -1, 715, 3545, 3547, -1, + 3545, 715, 717, -1, 717, 3543, 3545, -1, + 3543, 717, 719, -1, 719, 3541, 3543, -1, + 3541, 719, 721, -1, 721, 3539, 3541, -1, + 3539, 721, 724, -1, 724, 3535, 3539, -1, + 724, 3550, 3535, -1, 3551, 3552, 3553, -1, + 3551, 3553, 3554, -1, 3551, 3554, 3555, -1, + 3551, 3555, 3556, -1, 3556, 3552, 3551, -1, + 3552, 3556, 3550, -1, 3550, 3557, 3552, -1, + 3557, 3550, 724, -1, 3557, 724, 723, -1, + 3557, 723, 728, -1, 728, 3552, 3557, -1, + 728, 3553, 3552, -1, 728, 727, 3553, -1, + 3553, 727, 3298, -1, 3553, 3298, 3297, -1, + 3297, 3554, 3553, -1, 3554, 3297, 3296, -1, + 3296, 3558, 3554, -1, 3558, 3296, 3295, -1, + 3295, 3559, 3558, -1, 3559, 3295, 3292, -1, + 3292, 3560, 3559, -1, 3560, 3292, 3291, -1, + 3561, 3560, 3291, -1, 3291, 3293, 3561, -1, + 3562, 3561, 3293, -1, 3562, 3560, 3561, -1, + 3562, 3563, 3560, -1, 3562, 3293, 3563, -1, + 3564, 3563, 3293, -1, 3565, 3566, 3564, -1, + 3567, 3568, 3569, -1, 3570, 3571, 3567, -1, + 3567, 3569, 3570, -1, 3570, 3569, 3572, -1, + 3572, 3571, 3570, -1, 3572, 3573, 3571, -1, + 3572, 3569, 3573, -1, 3574, 3575, 3576, -1, + 3574, 3577, 3575, -1, 3574, 3578, 3577, -1, + 3574, 3576, 3578, -1, 3579, 3578, 3576, -1, + 3580, 3581, 3582, -1, 3580, 3579, 3581, -1, + 3580, 3583, 3579, -1, 3580, 3582, 3583, -1, + 3584, 3583, 3582, -1, 3584, 3582, 3585, -1, + 3584, 3585, 3586, -1, 3586, 3587, 3584, -1, + 3588, 3584, 3587, -1, 3588, 3583, 3584, -1, + 3588, 3579, 3583, -1, 3588, 3587, 3579, -1, + 3587, 3578, 3579, -1, 3587, 3586, 3578, -1, + 3586, 3577, 3578, -1, 3586, 3589, 3577, -1, + 3589, 3586, 3585, -1, 3585, 3590, 3589, -1, + 3585, 3591, 3590, -1, 3591, 3585, 3582, -1, + 3582, 3592, 3591, -1, 3582, 3581, 3592, -1, + 3593, 3592, 3581, -1, 3593, 3594, 3592, -1, + 3593, 3595, 3594, -1, 3593, 3581, 3595, -1, + 3595, 3581, 3579, -1, 3596, 3597, 3598, -1, + 3596, 3599, 3597, -1, 3596, 3600, 3599, -1, + 3596, 3598, 3600, -1, 3601, 3600, 3598, -1, + 3601, 3602, 3600, -1, 3602, 3601, 3603, -1, + 3603, 3604, 3602, -1, 3604, 3603, 3605, -1, + 3605, 3606, 3604, -1, 3606, 3605, 3607, -1, + 3607, 3608, 3606, -1, 3607, 3609, 3608, -1, + 3609, 3607, 3610, -1, 3610, 3611, 3609, -1, + 3611, 3610, 3612, -1, 3612, 3613, 3611, -1, + 3613, 3612, 3614, -1, 3614, 3615, 3613, -1, + 3614, 3616, 3615, -1, 3617, 3616, 3618, -1, + 3617, 3615, 3616, -1, 3617, 3619, 3615, -1, + 3617, 3618, 3619, -1, 3620, 3621, 3622, -1, + 3620, 3623, 3621, -1, 3624, 3625, 3626, -1, + 3627, 3625, 3628, -1, 3627, 3626, 3625, -1, + 3627, 3629, 3626, -1, 3629, 3627, 3628, -1, + 3630, 3631, 3632, -1, 3633, 3634, 3635, -1, + 3634, 3633, 3636, -1, 3636, 3637, 3634, -1, + 3637, 3636, 3638, -1, 3638, 3639, 3637, -1, + 3639, 3638, 3640, -1, 3640, 3641, 3639, -1, + 3641, 3640, 3642, -1, 3642, 3643, 3641, -1, + 3643, 3642, 3644, -1, 3644, 3645, 3643, -1, + 3645, 3644, 3646, -1, 3646, 3647, 3645, -1, + 3647, 3646, 3648, -1, 3648, 3649, 3647, -1, + 3649, 3648, 3650, -1, 3650, 3651, 3649, -1, + 3651, 3650, 3652, -1, 3652, 3653, 3651, -1, + 3653, 3652, 3654, -1, 3654, 3655, 3653, -1, + 3655, 3654, 3656, -1, 3656, 3657, 3655, -1, + 3657, 3656, 3658, -1, 3658, 3659, 3657, -1, + 3659, 3658, 3660, -1, 3660, 3661, 3659, -1, + 3661, 3660, 3662, -1, 3662, 3663, 3661, -1, + 3663, 3662, 3664, -1, 3664, 3665, 3663, -1, + 3666, 3667, 3665, -1, 3665, 3664, 3666, -1, + 3668, 3669, 3670, -1, 3671, 3672, 3673, -1, + 3674, 3675, 3676, -1, 3676, 3677, 3674, -1, + 3677, 3676, 3678, -1, 3678, 3679, 3677, -1, + 3679, 3678, 3680, -1, 3680, 3681, 3679, -1, + 3681, 3680, 3682, -1, 3682, 3683, 3681, -1, + 3683, 3682, 3684, -1, 3684, 3685, 3683, -1, + 3685, 3684, 3686, -1, 3686, 3687, 3685, -1, + 3687, 3686, 3688, -1, 3688, 3689, 3687, -1, + 3690, 3687, 3689, -1, 3689, 3691, 3690, -1, + 3691, 3689, 3692, -1, 3692, 3693, 3691, -1, + 3693, 3692, 3694, -1, 3694, 3695, 3693, -1, + 3695, 3694, 3696, -1, 3696, 3697, 3695, -1, + 3697, 3696, 3698, -1, 3698, 3699, 3697, -1, + 3699, 3698, 3700, -1, 3700, 3701, 3699, -1, + 3701, 3700, 3702, -1, 3702, 3703, 3701, -1, + 3703, 3702, 3704, -1, 3704, 3705, 3703, -1, + 3705, 3704, 3673, -1, 3673, 3706, 3705, -1, + 3673, 3672, 3706, -1, 3707, 3708, 3709, -1, + 3706, 3709, 3708, -1, 3710, 3709, 3706, -1, + 3710, 3706, 3672, -1, 3672, 3711, 3710, -1, + 3672, 3671, 3711, -1, 3712, 3713, 3714, -1, + 3714, 3715, 3712, -1, 3715, 3714, 3716, -1, + 3716, 3717, 3715, -1, 3717, 3716, 3718, -1, + 3718, 3719, 3717, -1, 3719, 3718, 3720, -1, + 3720, 3721, 3719, -1, 3721, 3720, 3722, -1, + 3722, 3723, 3721, -1, 3723, 3722, 3724, -1, + 3724, 3725, 3723, -1, 3725, 3724, 3726, -1, + 3727, 3726, 3724, -1, 3726, 3727, 3728, -1, + 3729, 3730, 3711, -1, 3711, 3730, 3728, -1, + 3731, 3730, 3732, -1, 3731, 3728, 3730, -1, + 3733, 3728, 3731, -1, 3733, 3731, 3732, -1, + 3733, 3732, 3734, -1, 3734, 3728, 3733, -1, + 3734, 3735, 3728, -1, 3735, 3726, 3728, -1, + 3735, 3725, 3726, -1, 3735, 3734, 3725, -1, + 3725, 3734, 3732, -1, 3725, 3732, 3736, -1, + 3736, 3723, 3725, -1, 3723, 3736, 3737, -1, + 3737, 3721, 3723, -1, 3721, 3737, 3738, -1, + 3738, 3719, 3721, -1, 3719, 3738, 3739, -1, + 3739, 3717, 3719, -1, 3717, 3739, 3740, -1, + 3740, 3715, 3717, -1, 3715, 3740, 3741, -1, + 3741, 3712, 3715, -1, 3742, 3743, 3712, -1, + 3712, 3741, 3742, -1, 3744, 3745, 3746, -1, + 3747, 3748, 3749, -1, 3747, 3750, 3748, -1, + 3750, 3747, 3751, -1, 3751, 3752, 3750, -1, + 3752, 3751, 3753, -1, 3753, 3754, 3752, -1, + 3754, 3753, 3755, -1, 3755, 3756, 3754, -1, + 3756, 3755, 3757, -1, 3756, 3757, 3758, -1, + 3758, 3759, 3756, -1, 3759, 3758, 3760, -1, + 3760, 3761, 3759, -1, 3761, 3760, 3744, -1, + 3744, 3746, 3761, -1, 3762, 3763, 3764, -1, + 3762, 3764, 3765, -1, 3765, 3746, 3762, -1, + 3746, 3765, 3766, -1, 3766, 3761, 3746, -1, + 3761, 3766, 3767, -1, 3767, 3759, 3761, -1, + 3759, 3767, 3768, -1, 3768, 3756, 3759, -1, + 3768, 3754, 3756, -1, 3754, 3768, 3769, -1, + 3769, 3752, 3754, -1, 3752, 3769, 3770, -1, + 3770, 3750, 3752, -1, 3750, 3770, 3771, -1, + 3771, 3748, 3750, -1, 3748, 3771, 3772, -1, + 3748, 3772, 3773, -1, 3774, 3773, 3772, -1, + 3774, 3775, 3773, -1, 3775, 3774, 3776, -1, + 3776, 3777, 3775, -1, 3777, 3776, 3778, -1, + 3778, 3779, 3777, -1, 3779, 3778, 3780, -1, + 3780, 3781, 3779, -1, 3781, 3780, 3782, -1, + 3782, 3783, 3781, -1, 3783, 3782, 3784, -1, + 3784, 3785, 3783, -1, 3785, 3784, 3786, -1, + 3786, 3787, 3785, -1, 3787, 3786, 3788, -1, + 3788, 3789, 3787, -1, 3789, 3788, 3790, -1, + 3790, 3791, 3789, -1, 3791, 3790, 3792, -1, + 3792, 3793, 3791, -1, 3793, 3792, 3794, -1, + 3794, 3795, 3793, -1, 3795, 3794, 3796, -1, + 3796, 3797, 3795, -1, 3797, 3796, 3798, -1, + 3798, 3799, 3797, -1, 3799, 3798, 3800, -1, + 3800, 3801, 3799, -1, 3801, 3800, 3802, -1, + 3802, 3803, 3801, -1, 3803, 3802, 3804, -1, + 3804, 3805, 3803, -1, 3805, 3804, 3806, -1, + 3806, 3807, 3805, -1, 3807, 3806, 3808, -1, + 3808, 3809, 3807, -1, 3809, 3808, 3810, -1, + 3810, 3811, 3809, -1, 3811, 3810, 3812, -1, + 3812, 3813, 3811, -1, 3813, 3812, 3742, -1, + 3742, 3814, 3813, -1, 3814, 3742, 3741, -1, + 3741, 3815, 3814, -1, 3815, 3741, 3740, -1, + 3740, 3816, 3815, -1, 3816, 3740, 3739, -1, + 3739, 3817, 3816, -1, 3817, 3739, 3738, -1, + 3738, 3818, 3817, -1, 3818, 3738, 3737, -1, + 3737, 3819, 3818, -1, 3819, 3737, 3736, -1, + 3736, 3820, 3819, -1, 3820, 3736, 3732, -1, + 3732, 3821, 3820, -1, 3821, 3732, 3730, -1, + 3730, 3729, 3821, -1, 3729, 3822, 3821, -1, + 3822, 3729, 3711, -1, 3822, 3711, 3671, -1, + 3671, 3673, 3822, -1, 3673, 3821, 3822, -1, + 3821, 3673, 3704, -1, 3704, 3820, 3821, -1, + 3820, 3704, 3702, -1, 3702, 3819, 3820, -1, + 3819, 3702, 3700, -1, 3700, 3818, 3819, -1, + 3818, 3700, 3698, -1, 3698, 3817, 3818, -1, + 3817, 3698, 3696, -1, 3696, 3816, 3817, -1, + 3816, 3696, 3694, -1, 3694, 3815, 3816, -1, + 3815, 3694, 3692, -1, 3692, 3814, 3815, -1, + 3814, 3692, 3689, -1, 3689, 3813, 3814, -1, + 3813, 3689, 3688, -1, 3688, 3811, 3813, -1, + 3811, 3688, 3686, -1, 3686, 3809, 3811, -1, + 3809, 3686, 3684, -1, 3684, 3807, 3809, -1, + 3807, 3684, 3682, -1, 3682, 3805, 3807, -1, + 3805, 3682, 3680, -1, 3680, 3803, 3805, -1, + 3803, 3680, 3678, -1, 3678, 3801, 3803, -1, + 3801, 3678, 3676, -1, 3676, 3799, 3801, -1, + 3799, 3676, 3675, -1, 3675, 3797, 3799, -1, + 3797, 3675, 3823, -1, 3823, 3795, 3797, -1, + 3795, 3823, 3824, -1, 3824, 3793, 3795, -1, + 3793, 3824, 3825, -1, 3825, 3791, 3793, -1, + 3791, 3825, 3826, -1, 3826, 3789, 3791, -1, + 3789, 3826, 3827, -1, 3827, 3787, 3789, -1, + 3787, 3827, 3828, -1, 3828, 3785, 3787, -1, + 3785, 3828, 3829, -1, 3829, 3783, 3785, -1, + 3783, 3829, 3830, -1, 3830, 3781, 3783, -1, + 3781, 3830, 3831, -1, 3831, 3779, 3781, -1, + 3779, 3831, 3832, -1, 3832, 3777, 3779, -1, + 3777, 3832, 3833, -1, 3833, 3775, 3777, -1, + 3775, 3833, 3834, -1, 3834, 3773, 3775, -1, + 3773, 3834, 3835, -1, 3835, 3748, 3773, -1, + 3835, 3749, 3748, -1, 3835, 3836, 3749, -1, + 3836, 3835, 3834, -1, 3834, 3837, 3836, -1, + 3837, 3834, 3833, -1, 3833, 3838, 3837, -1, + 3838, 3833, 3832, -1, 3832, 3839, 3838, -1, + 3839, 3832, 3831, -1, 3831, 3840, 3839, -1, + 3840, 3831, 3830, -1, 3830, 3841, 3840, -1, + 3841, 3830, 3829, -1, 3829, 3842, 3841, -1, + 3842, 3829, 3828, -1, 3828, 3843, 3842, -1, + 3843, 3828, 3827, -1, 3827, 3844, 3843, -1, + 3844, 3827, 3826, -1, 3826, 3845, 3844, -1, + 3845, 3826, 3825, -1, 3825, 3846, 3845, -1, + 3846, 3825, 3824, -1, 3824, 3847, 3846, -1, + 3847, 3824, 3823, -1, 3823, 3848, 3847, -1, + 3848, 3823, 3675, -1, 3675, 3674, 3848, -1, + 3848, 3674, 3849, -1, 3849, 3847, 3848, -1, + 3847, 3849, 3850, -1, 3850, 3846, 3847, -1, + 3846, 3850, 3851, -1, 3851, 3845, 3846, -1, + 3845, 3851, 3852, -1, 3852, 3844, 3845, -1, + 3844, 3852, 3853, -1, 3853, 3843, 3844, -1, + 3843, 3853, 3854, -1, 3854, 3842, 3843, -1, + 3842, 3854, 3855, -1, 3855, 3841, 3842, -1, + 3841, 3855, 3856, -1, 3856, 3840, 3841, -1, + 3840, 3856, 3857, -1, 3857, 3839, 3840, -1, + 3839, 3857, 3858, -1, 3858, 3838, 3839, -1, + 3838, 3858, 3859, -1, 3859, 3837, 3838, -1, + 3837, 3859, 3860, -1, 3860, 3836, 3837, -1, + 3836, 3860, 3861, -1, 3861, 3749, 3836, -1, + 3749, 3861, 3862, -1, 3862, 3747, 3749, -1, + 3862, 3863, 3747, -1, 3862, 3864, 3863, -1, + 3864, 3862, 3861, -1, 3861, 3865, 3864, -1, + 3865, 3861, 3860, -1, 3860, 3866, 3865, -1, + 3866, 3860, 3859, -1, 3859, 3867, 3866, -1, + 3867, 3859, 3858, -1, 3858, 3868, 3867, -1, + 3868, 3858, 3857, -1, 3857, 3869, 3868, -1, + 3869, 3857, 3856, -1, 3856, 3870, 3869, -1, + 3870, 3856, 3855, -1, 3855, 3871, 3870, -1, + 3871, 3855, 3854, -1, 3854, 3872, 3871, -1, + 3872, 3854, 3853, -1, 3853, 3873, 3872, -1, + 3873, 3853, 3852, -1, 3852, 3874, 3873, -1, + 3874, 3852, 3851, -1, 3851, 3875, 3874, -1, + 3875, 3851, 3850, -1, 3850, 3876, 3875, -1, + 3876, 3850, 3849, -1, 3849, 3877, 3876, -1, + 3877, 3849, 3674, -1, 3674, 3878, 3877, -1, + 3878, 3674, 3677, -1, 3677, 3879, 3878, -1, + 3879, 3677, 3679, -1, 3679, 3880, 3879, -1, + 3880, 3679, 3681, -1, 3681, 3881, 3880, -1, + 3881, 3681, 3683, -1, 3683, 3882, 3881, -1, + 3882, 3683, 3685, -1, 3685, 3883, 3882, -1, + 3883, 3685, 3687, -1, 3687, 3690, 3883, -1, + 3883, 3690, 3884, -1, 3884, 3882, 3883, -1, + 3882, 3884, 3885, -1, 3885, 3881, 3882, -1, + 3881, 3885, 3886, -1, 3886, 3880, 3881, -1, + 3880, 3886, 3887, -1, 3887, 3879, 3880, -1, + 3879, 3887, 3888, -1, 3888, 3878, 3879, -1, + 3878, 3888, 3889, -1, 3889, 3877, 3878, -1, + 3877, 3889, 3890, -1, 3890, 3876, 3877, -1, + 3876, 3890, 3891, -1, 3891, 3875, 3876, -1, + 3875, 3891, 3892, -1, 3892, 3874, 3875, -1, + 3874, 3892, 3893, -1, 3893, 3873, 3874, -1, + 3873, 3893, 3894, -1, 3894, 3872, 3873, -1, + 3872, 3894, 3895, -1, 3895, 3871, 3872, -1, + 3871, 3895, 3896, -1, 3896, 3870, 3871, -1, + 3870, 3896, 3897, -1, 3897, 3869, 3870, -1, + 3869, 3897, 3898, -1, 3898, 3868, 3869, -1, + 3868, 3898, 3899, -1, 3899, 3867, 3868, -1, + 3867, 3899, 3900, -1, 3900, 3866, 3867, -1, + 3866, 3900, 3901, -1, 3901, 3865, 3866, -1, + 3865, 3901, 3902, -1, 3902, 3864, 3865, -1, + 3864, 3902, 3903, -1, 3903, 3863, 3864, -1, + 3863, 3903, 3669, -1, 3669, 3668, 3863, -1, + 3668, 3747, 3863, -1, 3668, 3751, 3747, -1, + 3668, 3670, 3751, -1, 3904, 3751, 3670, -1, + 3904, 3753, 3751, -1, 3753, 3904, 3905, -1, + 3905, 3755, 3753, -1, 3755, 3905, 3906, -1, + 3906, 3757, 3755, -1, 3757, 3906, 3907, -1, + 3757, 3907, 3908, -1, 3908, 3758, 3757, -1, + 3758, 3908, 3909, -1, 3909, 3760, 3758, -1, + 3760, 3909, 3910, -1, 3910, 3744, 3760, -1, + 3910, 3911, 3744, -1, 3912, 3913, 3914, -1, + 3913, 3912, 3915, -1, 3915, 3916, 3913, -1, + 3916, 3915, 3917, -1, 3917, 3918, 3916, -1, + 3918, 3917, 3919, -1, 3919, 3920, 3918, -1, + 3920, 3919, 3921, -1, 3921, 3922, 3920, -1, + 3922, 3921, 3923, -1, 3923, 3924, 3922, -1, + 3924, 3923, 3925, -1, 3925, 3926, 3924, -1, + 3926, 3925, 3927, -1, 3927, 3928, 3926, -1, + 3928, 3927, 3929, -1, 3929, 3930, 3928, -1, + 3930, 3929, 3931, -1, 3931, 3932, 3930, -1, + 3932, 3931, 3933, -1, 3933, 3934, 3932, -1, + 3934, 3933, 3935, -1, 3935, 3936, 3934, -1, + 3937, 3938, 3936, -1, 3936, 3935, 3937, -1, + 3939, 3940, 3941, -1, 3940, 3939, 3942, -1, + 3942, 3943, 3940, -1, 3943, 3942, 3944, -1, + 3944, 3945, 3943, -1, 3945, 3944, 3946, -1, + 3946, 3947, 3945, -1, 3947, 3946, 3948, -1, + 3948, 3949, 3947, -1, 3949, 3948, 3950, -1, + 3950, 3951, 3949, -1, 3951, 3950, 3952, -1, + 3952, 3953, 3951, -1, 3953, 3952, 3954, -1, + 3954, 3955, 3953, -1, 3955, 3954, 3956, -1, + 3956, 3957, 3955, -1, 3957, 3956, 3958, -1, + 3958, 3959, 3957, -1, 3959, 3958, 3960, -1, + 3960, 3961, 3959, -1, 3961, 3960, 3962, -1, + 3962, 3963, 3961, -1, 3963, 3962, 3964, -1, + 3964, 3965, 3963, -1, 3965, 3964, 3966, -1, + 3965, 3966, 3937, -1, 3965, 3937, 3935, -1, + 3935, 3963, 3965, -1, 3963, 3935, 3933, -1, + 3933, 3961, 3963, -1, 3961, 3933, 3931, -1, + 3931, 3959, 3961, -1, 3959, 3931, 3929, -1, + 3929, 3957, 3959, -1, 3957, 3929, 3927, -1, + 3927, 3955, 3957, -1, 3955, 3927, 3925, -1, + 3925, 3953, 3955, -1, 3953, 3925, 3923, -1, + 3923, 3951, 3953, -1, 3951, 3923, 3921, -1, + 3921, 3949, 3951, -1, 3949, 3921, 3919, -1, + 3919, 3947, 3949, -1, 3947, 3919, 3917, -1, + 3917, 3945, 3947, -1, 3945, 3917, 3915, -1, + 3915, 3943, 3945, -1, 3943, 3915, 3912, -1, + 3912, 3940, 3943, -1, 3940, 3912, 3914, -1, + 3914, 3941, 3940, -1, 3941, 3914, 3967, -1, + 3967, 3968, 3941, -1, 3968, 3967, 3969, -1, + 3969, 3970, 3968, -1, 3970, 3969, 3971, -1, + 3971, 3972, 3970, -1, 3972, 3971, 3973, -1, + 3973, 3974, 3972, -1, 3975, 3976, 3977, -1, + 3976, 3975, 3974, -1, 3974, 3973, 3976, -1, + 3978, 3976, 3973, -1, 3973, 3979, 3978, -1, + 3979, 3973, 3971, -1, 3971, 3980, 3979, -1, + 3980, 3971, 3969, -1, 3969, 3981, 3980, -1, + 3981, 3969, 3967, -1, 3967, 3982, 3981, -1, + 3982, 3967, 3914, -1, 3914, 3983, 3982, -1, + 3983, 3914, 3913, -1, 3913, 3984, 3983, -1, + 3984, 3913, 3916, -1, 3916, 3985, 3984, -1, + 3985, 3916, 3918, -1, 3918, 3986, 3985, -1, + 3986, 3918, 3920, -1, 3920, 3987, 3986, -1, + 3987, 3920, 3922, -1, 3922, 3988, 3987, -1, + 3988, 3922, 3924, -1, 3924, 3989, 3988, -1, + 3989, 3924, 3926, -1, 3926, 3990, 3989, -1, + 3990, 3926, 3928, -1, 3928, 3991, 3990, -1, + 3991, 3928, 3930, -1, 3930, 3992, 3991, -1, + 3992, 3930, 3932, -1, 3932, 3993, 3992, -1, + 3993, 3932, 3934, -1, 3934, 3994, 3993, -1, + 3994, 3934, 3936, -1, 3936, 3995, 3994, -1, + 3995, 3936, 3938, -1, 3938, 3996, 3995, -1, + 3996, 3938, 3997, -1, 3997, 3998, 3996, -1, + 3998, 3997, 3999, -1, 3999, 3911, 3998, -1, + 3999, 3744, 3911, -1, 3999, 3745, 3744, -1, + 3745, 3999, 3997, -1, 3997, 4000, 3745, -1, + 4000, 3997, 3938, -1, 3938, 3937, 4000, -1, + 4000, 3937, 3966, -1, 4000, 3966, 4001, -1, + 4001, 3745, 4000, -1, 4001, 3746, 3745, -1, + 4001, 3762, 3746, -1, 3762, 4001, 3966, -1, + 3966, 3763, 3762, -1, 3763, 3966, 3964, -1, + 3964, 4002, 3763, -1, 4002, 3964, 3962, -1, + 3962, 4003, 4002, -1, 4003, 3962, 3960, -1, + 3960, 4004, 4003, -1, 4004, 3960, 3958, -1, + 3958, 4005, 4004, -1, 4005, 3958, 3956, -1, + 3956, 4006, 4005, -1, 4006, 3956, 3954, -1, + 3954, 4007, 4006, -1, 4007, 3954, 3952, -1, + 3952, 4008, 4007, -1, 4008, 3952, 3950, -1, + 3950, 4009, 4008, -1, 4009, 3950, 3948, -1, + 3948, 4010, 4009, -1, 4010, 3948, 3946, -1, + 3946, 4011, 4010, -1, 4011, 3946, 3944, -1, + 3944, 4012, 4011, -1, 4012, 3944, 3942, -1, + 3942, 4013, 4012, -1, 4013, 3942, 3939, -1, + 3939, 4014, 4013, -1, 4014, 3939, 3941, -1, + 3941, 4015, 4014, -1, 4015, 3941, 3968, -1, + 3968, 4016, 4015, -1, 4016, 3968, 3970, -1, + 3970, 4017, 4016, -1, 4017, 3970, 3972, -1, + 3972, 4018, 4017, -1, 4018, 3972, 3974, -1, + 3974, 4019, 4018, -1, 4019, 3974, 3975, -1, + 3975, 4020, 4019, -1, 4020, 3975, 3977, -1, + 3977, 4021, 4020, -1, 4021, 3977, 4022, -1, + 4022, 4023, 4021, -1, 4023, 4022, 4024, -1, + 4024, 4025, 4023, -1, 4025, 4024, 4026, -1, + 4026, 4027, 4025, -1, 4027, 4026, 4028, -1, + 4028, 4029, 4027, -1, 4029, 4028, 4030, -1, + 4030, 4031, 4029, -1, 4031, 4030, 4032, -1, + 4032, 4033, 4031, -1, 4033, 4032, 4034, -1, + 4034, 4035, 4033, -1, 4035, 4034, 4036, -1, + 4036, 4037, 4035, -1, 4038, 4039, 4037, -1, + 4037, 4036, 4038, -1, 4038, 4040, 4041, -1, + 4038, 4042, 4040, -1, 4042, 4038, 4036, -1, + 4036, 4043, 4042, -1, 4043, 4036, 4034, -1, + 4034, 4044, 4043, -1, 4044, 4034, 4032, -1, + 4032, 4045, 4044, -1, 4045, 4032, 4030, -1, + 4030, 4046, 4045, -1, 4046, 4030, 4028, -1, + 4028, 4047, 4046, -1, 4047, 4028, 4026, -1, + 4026, 4048, 4047, -1, 4048, 4026, 4024, -1, + 4024, 4049, 4048, -1, 4049, 4024, 4022, -1, + 4022, 4050, 4049, -1, 4050, 4022, 3977, -1, + 3977, 4051, 4050, -1, 4051, 3977, 3976, -1, + 3976, 3978, 4051, -1, 3978, 4052, 4051, -1, + 4052, 3978, 3979, -1, 3979, 4053, 4052, -1, + 4053, 3979, 3980, -1, 3980, 4054, 4053, -1, + 4054, 3980, 3981, -1, 3981, 4055, 4054, -1, + 4055, 3981, 3982, -1, 3982, 4056, 4055, -1, + 4056, 3982, 3983, -1, 3983, 4057, 4056, -1, + 4057, 3983, 3984, -1, 3984, 4058, 4057, -1, + 4058, 3984, 3985, -1, 3985, 4059, 4058, -1, + 4059, 3985, 3986, -1, 3986, 4060, 4059, -1, + 4060, 3986, 3987, -1, 3987, 4061, 4060, -1, + 4061, 3987, 3988, -1, 3988, 4062, 4061, -1, + 4062, 3988, 3989, -1, 3989, 4063, 4062, -1, + 4063, 3989, 3990, -1, 3990, 4064, 4063, -1, + 4064, 3990, 3991, -1, 3991, 4065, 4064, -1, + 4065, 3991, 3992, -1, 3992, 4066, 4065, -1, + 4066, 3992, 3993, -1, 3993, 4067, 4066, -1, + 4067, 3993, 3994, -1, 3994, 4068, 4067, -1, + 4068, 3994, 3995, -1, 3995, 4069, 4068, -1, + 4069, 3995, 3996, -1, 3996, 4070, 4069, -1, + 4070, 3996, 3998, -1, 3998, 4071, 4070, -1, + 4071, 3998, 3911, -1, 3911, 4072, 4071, -1, + 4072, 3911, 3910, -1, 4072, 3910, 3666, -1, + 4072, 3666, 3664, -1, 3664, 4071, 4072, -1, + 4071, 3664, 3662, -1, 3662, 4070, 4071, -1, + 4070, 3662, 3660, -1, 3660, 4069, 4070, -1, + 4069, 3660, 3658, -1, 3658, 4068, 4069, -1, + 4068, 3658, 3656, -1, 3656, 4067, 4068, -1, + 4067, 3656, 3654, -1, 3654, 4066, 4067, -1, + 4066, 3654, 3652, -1, 3652, 4065, 4066, -1, + 4065, 3652, 3650, -1, 3650, 4064, 4065, -1, + 4064, 3650, 3648, -1, 3648, 4063, 4064, -1, + 4063, 3648, 3646, -1, 3646, 4062, 4063, -1, + 4062, 3646, 3644, -1, 3644, 4061, 4062, -1, + 4061, 3644, 3642, -1, 3642, 4060, 4061, -1, + 4060, 3642, 3640, -1, 3640, 4059, 4060, -1, + 4059, 3640, 3638, -1, 3638, 4058, 4059, -1, + 4058, 3638, 3636, -1, 3636, 4057, 4058, -1, + 4057, 3636, 3633, -1, 3633, 4056, 4057, -1, + 4056, 3633, 3635, -1, 3635, 4055, 4056, -1, + 4055, 3635, 4073, -1, 4073, 4054, 4055, -1, + 4054, 4073, 4074, -1, 4074, 4053, 4054, -1, + 4053, 4074, 4075, -1, 4075, 4052, 4053, -1, + 4052, 4075, 4076, -1, 4076, 4051, 4052, -1, + 4051, 4076, 4077, -1, 4077, 4050, 4051, -1, + 4050, 4077, 4078, -1, 4078, 4049, 4050, -1, + 4049, 4078, 4079, -1, 4079, 4048, 4049, -1, + 4048, 4079, 4080, -1, 4080, 4047, 4048, -1, + 4047, 4080, 4081, -1, 4081, 4046, 4047, -1, + 4046, 4081, 4082, -1, 4082, 4045, 4046, -1, + 4045, 4082, 4083, -1, 4083, 4044, 4045, -1, + 4044, 4083, 4084, -1, 4084, 4043, 4044, -1, + 4043, 4084, 4085, -1, 4085, 4042, 4043, -1, + 4042, 4085, 4086, -1, 4086, 4040, 4042, -1, + 4040, 4086, 4087, -1, 4040, 4087, 4088, -1, + 4089, 4090, 4087, -1, 4090, 4088, 4087, -1, + 4090, 4091, 4088, -1, 4090, 4089, 4091, -1, + 4092, 4093, 4094, -1, 4095, 4096, 4097, -1, + 4095, 4098, 4096, -1, 4091, 4099, 4100, -1, + 4101, 4102, 4103, -1, 4104, 4105, 4106, -1, + 4106, 4107, 4104, -1, 4107, 4106, 4108, -1, + 4108, 4109, 4107, -1, 4109, 4108, 4110, -1, + 4110, 4111, 4109, -1, 4111, 4110, 4112, -1, + 4112, 4113, 4111, -1, 4113, 4112, 4114, -1, + 4114, 4115, 4113, -1, 4115, 4114, 4116, -1, + 4116, 4117, 4115, -1, 4117, 4116, 4118, -1, + 4118, 4119, 4117, -1, 4119, 4118, 4120, -1, + 4120, 4121, 4119, -1, 4121, 4120, 4122, -1, + 4122, 4123, 4121, -1, 4123, 4122, 4124, -1, + 4124, 4125, 4123, -1, 4125, 4124, 4126, -1, + 4126, 4127, 4125, -1, 4127, 4126, 4128, -1, + 4128, 4129, 4127, -1, 4129, 4128, 4130, -1, + 4130, 4131, 4129, -1, 4131, 4130, 4132, -1, + 4132, 4133, 4131, -1, 4133, 4132, 4134, -1, + 4134, 4135, 4133, -1, 4135, 4134, 4136, -1, + 4136, 4137, 4135, -1, 4137, 4136, 4138, -1, + 4138, 4139, 4137, -1, 4139, 4138, 4140, -1, + 4140, 4141, 4139, -1, 4141, 4140, 4142, -1, + 4143, 4144, 4145, -1, 4145, 4146, 4143, -1, + 4146, 4145, 4147, -1, 4147, 4148, 4146, -1, + 4148, 4147, 4149, -1, 4149, 4150, 4148, -1, + 4150, 4149, 4151, -1, 4151, 4152, 4150, -1, + 4152, 4151, 4153, -1, 4153, 4154, 4152, -1, + 4154, 4153, 4155, -1, 4155, 4156, 4154, -1, + 4156, 4155, 4157, -1, 4157, 4158, 4156, -1, + 4158, 4157, 4159, -1, 4159, 4160, 4158, -1, + 4160, 4159, 4161, -1, 4161, 4162, 4160, -1, + 4162, 4161, 4163, -1, 4163, 4164, 4162, -1, + 4164, 4163, 4165, -1, 4165, 4166, 4164, -1, + 4166, 4165, 4167, -1, 4167, 4168, 4166, -1, + 4168, 4167, 4169, -1, 4169, 4170, 4168, -1, + 4170, 4169, 4171, -1, 4171, 4172, 4170, -1, + 4172, 4171, 4173, -1, 4173, 4174, 4172, -1, + 4174, 4173, 4175, -1, 4175, 4176, 4174, -1, + 4176, 4175, 4177, -1, 4177, 4178, 4176, -1, + 4179, 4180, 4178, -1, 4179, 4181, 4180, -1, + 4179, 4182, 4181, -1, 4179, 4178, 4182, -1, + 4178, 4183, 4182, -1, 4178, 4177, 4183, -1, + 4184, 4183, 4177, -1, 4177, 4185, 4184, -1, + 4185, 4177, 4175, -1, 4175, 4186, 4185, -1, + 4186, 4175, 4173, -1, 4173, 4187, 4186, -1, + 4187, 4173, 4171, -1, 4171, 4188, 4187, -1, + 4188, 4171, 4169, -1, 4169, 4189, 4188, -1, + 4189, 4169, 4167, -1, 4167, 4190, 4189, -1, + 4190, 4167, 4165, -1, 4165, 4191, 4190, -1, + 4191, 4165, 4163, -1, 4163, 4192, 4191, -1, + 4192, 4163, 4161, -1, 4161, 4193, 4192, -1, + 4193, 4161, 4159, -1, 4159, 4194, 4193, -1, + 4194, 4159, 4157, -1, 4157, 4195, 4194, -1, + 4195, 4157, 4155, -1, 4155, 4196, 4195, -1, + 4196, 4155, 4153, -1, 4153, 4197, 4196, -1, + 4197, 4153, 4151, -1, 4151, 4198, 4197, -1, + 4198, 4151, 4149, -1, 4149, 4199, 4198, -1, + 4199, 4149, 4147, -1, 4147, 4200, 4199, -1, + 4200, 4147, 4145, -1, 4145, 4201, 4200, -1, + 4201, 4145, 4144, -1, 4144, 4202, 4201, -1, + 4202, 4144, 4142, -1, 4203, 4142, 4144, -1, + 4142, 4203, 4204, -1, 4204, 4141, 4142, -1, + 4141, 4204, 4205, -1, 4205, 4139, 4141, -1, + 4139, 4205, 4206, -1, 4206, 4137, 4139, -1, + 4137, 4206, 4207, -1, 4207, 4135, 4137, -1, + 4135, 4207, 4208, -1, 4208, 4133, 4135, -1, + 4133, 4208, 4209, -1, 4209, 4131, 4133, -1, + 4131, 4209, 4210, -1, 4210, 4129, 4131, -1, + 4129, 4210, 4211, -1, 4211, 4127, 4129, -1, + 4127, 4211, 4212, -1, 4212, 4125, 4127, -1, + 4125, 4212, 4213, -1, 4213, 4123, 4125, -1, + 4123, 4213, 4214, -1, 4214, 4121, 4123, -1, + 4121, 4214, 4215, -1, 4215, 4119, 4121, -1, + 4119, 4215, 4216, -1, 4216, 4117, 4119, -1, + 4117, 4216, 4217, -1, 4217, 4115, 4117, -1, + 4115, 4217, 4218, -1, 4218, 4113, 4115, -1, + 4113, 4218, 4219, -1, 4219, 4111, 4113, -1, + 4111, 4219, 4220, -1, 4220, 4109, 4111, -1, + 4109, 4220, 4102, -1, 4102, 4107, 4109, -1, + 4107, 4102, 4101, -1, 4101, 4104, 4107, -1, + 4101, 4221, 4104, -1, 4101, 4103, 4221, -1, + 4222, 4223, 4224, -1, 4222, 4224, 4225, -1, + 4225, 4226, 4222, -1, 4226, 4225, 4227, -1, + 4227, 4228, 4226, -1, 4228, 4227, 4229, -1, + 4229, 4230, 4228, -1, 4229, 4231, 4230, -1, + 4231, 4229, 4232, -1, 4232, 4233, 4231, -1, + 4233, 4232, 4234, -1, 4234, 4235, 4233, -1, + 4236, 4237, 4238, -1, 4239, 4240, 4237, -1, + 4241, 4242, 4237, -1, 4241, 4237, 4240, -1, + 4240, 4243, 4241, -1, 4240, 4239, 4243, -1, + 4244, 4245, 4235, -1, 4244, 4246, 4245, -1, + 4246, 4244, 4247, -1, 4247, 4248, 4246, -1, + 4248, 4247, 4249, -1, 4249, 4250, 4248, -1, + 4250, 4249, 4251, -1, 4251, 4252, 4250, -1, + 4252, 4251, 4253, -1, 4253, 4254, 4252, -1, + 4254, 4253, 4255, -1, 4255, 4256, 4254, -1, + 4256, 4255, 4257, -1, 4257, 4258, 4256, -1, + 4258, 4257, 4259, -1, 4259, 4260, 4258, -1, + 4260, 4259, 4261, -1, 4261, 4262, 4260, -1, + 4262, 4261, 4263, -1, 4263, 4264, 4262, -1, + 4264, 4263, 4265, -1, 4265, 4266, 4264, -1, + 4266, 4265, 4267, -1, 4267, 4268, 4266, -1, + 4268, 4267, 4269, -1, 4269, 4270, 4268, -1, + 4270, 4269, 4271, -1, 4271, 4272, 4270, -1, + 4272, 4271, 4273, -1, 4273, 4274, 4272, -1, + 4274, 4273, 4275, -1, 4275, 4276, 4274, -1, + 4276, 4275, 4277, -1, 4277, 4278, 4276, -1, + 4278, 4277, 4279, -1, 4279, 4280, 4278, -1, + 4280, 4279, 4281, -1, 4281, 4282, 4280, -1, + 4282, 4281, 4283, -1, 4283, 4284, 4282, -1, + 4284, 4283, 4285, -1, 4285, 4286, 4284, -1, + 4286, 4285, 4287, -1, 4287, 4288, 4286, -1, + 4288, 4287, 4289, -1, 4289, 4290, 4288, -1, + 4290, 4289, 4291, -1, 4291, 4292, 4290, -1, + 4292, 4291, 4293, -1, 4293, 4294, 4292, -1, + 4294, 4293, 4295, -1, 4295, 4296, 4294, -1, + 4296, 4295, 4297, -1, 4297, 4298, 4296, -1, + 4298, 4297, 4299, -1, 4299, 4300, 4298, -1, + 4300, 4299, 4301, -1, 4301, 4302, 4300, -1, + 4302, 4301, 4303, -1, 4303, 4304, 4302, -1, + 4304, 4303, 4305, -1, 4305, 4306, 4304, -1, + 4306, 4305, 4307, -1, 4307, 4308, 4306, -1, + 4308, 4307, 4309, -1, 4309, 4310, 4308, -1, + 4310, 4309, 4311, -1, 4311, 4312, 4310, -1, + 4312, 4311, 4313, -1, 4313, 4314, 4312, -1, + 4314, 4313, 4315, -1, 4315, 4316, 4314, -1, + 4316, 4315, 4243, -1, 4243, 4317, 4316, -1, + 4243, 4318, 4317, -1, 4318, 4243, 4239, -1, + 4239, 4237, 4318, -1, 4318, 4237, 4236, -1, + 4236, 4317, 4318, -1, 4236, 4238, 4317, -1, + 4317, 4238, 4319, -1, 4317, 4319, 4320, -1, + 4320, 4316, 4317, -1, 4316, 4320, 4321, -1, + 4321, 4314, 4316, -1, 4314, 4321, 4322, -1, + 4322, 4312, 4314, -1, 4312, 4322, 4323, -1, + 4323, 4310, 4312, -1, 4310, 4323, 4324, -1, + 4324, 4308, 4310, -1, 4308, 4324, 4325, -1, + 4325, 4306, 4308, -1, 4306, 4325, 4326, -1, + 4326, 4304, 4306, -1, 4304, 4326, 4327, -1, + 4327, 4302, 4304, -1, 4302, 4327, 4328, -1, + 4328, 4300, 4302, -1, 4300, 4328, 4329, -1, + 4329, 4298, 4300, -1, 4298, 4329, 4330, -1, + 4330, 4296, 4298, -1, 4296, 4330, 4331, -1, + 4331, 4294, 4296, -1, 4294, 4331, 4332, -1, + 4332, 4292, 4294, -1, 4292, 4332, 4333, -1, + 4333, 4290, 4292, -1, 4290, 4333, 4334, -1, + 4334, 4288, 4290, -1, 4288, 4334, 4335, -1, + 4335, 4286, 4288, -1, 4286, 4335, 4336, -1, + 4336, 4284, 4286, -1, 4284, 4336, 4337, -1, + 4337, 4282, 4284, -1, 4282, 4337, 4338, -1, + 4338, 4280, 4282, -1, 4280, 4338, 4339, -1, + 4339, 4278, 4280, -1, 4278, 4339, 4340, -1, + 4340, 4276, 4278, -1, 4276, 4340, 4341, -1, + 4341, 4274, 4276, -1, 4274, 4341, 4342, -1, + 4342, 4272, 4274, -1, 4272, 4342, 4343, -1, + 4343, 4270, 4272, -1, 4270, 4343, 4344, -1, + 4344, 4268, 4270, -1, 4268, 4344, 4345, -1, + 4345, 4266, 4268, -1, 4266, 4345, 4346, -1, + 4346, 4264, 4266, -1, 4264, 4346, 4347, -1, + 4347, 4262, 4264, -1, 4262, 4347, 4348, -1, + 4348, 4260, 4262, -1, 4260, 4348, 4349, -1, + 4349, 4258, 4260, -1, 4258, 4349, 4350, -1, + 4350, 4256, 4258, -1, 4256, 4350, 4351, -1, + 4351, 4254, 4256, -1, 4254, 4351, 4352, -1, + 4352, 4252, 4254, -1, 4252, 4352, 4353, -1, + 4353, 4250, 4252, -1, 4250, 4353, 4354, -1, + 4354, 4248, 4250, -1, 4248, 4354, 4355, -1, + 4355, 4246, 4248, -1, 4246, 4355, 4356, -1, + 4356, 4245, 4246, -1, 4245, 4356, 4357, -1, + 4357, 4358, 4245, -1, 4358, 4235, 4245, -1, + 4358, 4233, 4235, -1, 4233, 4358, 4359, -1, + 4359, 4231, 4233, -1, 4231, 4359, 4360, -1, + 4360, 4230, 4231, -1, 4230, 4360, 4361, -1, + 4230, 4361, 4362, -1, 4362, 4228, 4230, -1, + 4228, 4362, 4363, -1, 4363, 4226, 4228, -1, + 4226, 4363, 4221, -1, 4221, 4222, 4226, -1, + 4222, 4221, 4103, -1, 4103, 4223, 4222, -1, + 4223, 4103, 4364, -1, 4364, 4365, 4223, -1, + 4365, 4364, 4366, -1, 4366, 4367, 4365, -1, + 4367, 4366, 4368, -1, 4368, 4369, 4367, -1, + 4369, 4368, 4370, -1, 4370, 4371, 4369, -1, + 4371, 4370, 4372, -1, 4372, 4373, 4371, -1, + 4373, 4372, 4374, -1, 4374, 4375, 4373, -1, + 4375, 4374, 4376, -1, 4376, 4377, 4375, -1, + 4377, 4376, 4378, -1, 4378, 4379, 4377, -1, + 4379, 4378, 4380, -1, 4380, 4381, 4379, -1, + 4381, 4380, 4382, -1, 4382, 4383, 4381, -1, + 4383, 4382, 4384, -1, 4384, 4385, 4383, -1, + 4385, 4384, 4386, -1, 4386, 4387, 4385, -1, + 4387, 4386, 4388, -1, 4388, 4389, 4387, -1, + 4389, 4388, 4390, -1, 4390, 4391, 4389, -1, + 4391, 4390, 4392, -1, 4392, 4393, 4391, -1, + 4393, 4392, 4394, -1, 4394, 4395, 4393, -1, + 4395, 4394, 4396, -1, 4396, 4397, 4395, -1, + 4397, 4396, 4398, -1, 4398, 4399, 4397, -1, + 4399, 4398, 4400, -1, 4400, 4401, 4399, -1, + 4402, 4403, 4404, -1, 4402, 4405, 4403, -1, + 4405, 4402, 4406, -1, 4406, 4407, 4405, -1, + 4407, 4406, 4408, -1, 4408, 4409, 4407, -1, + 4409, 4408, 4410, -1, 4410, 4411, 4409, -1, + 4411, 4410, 4412, -1, 4412, 4413, 4411, -1, + 4413, 4412, 4414, -1, 4414, 4415, 4413, -1, + 4415, 4414, 4416, -1, 4416, 4417, 4415, -1, + 4417, 4416, 4418, -1, 4418, 4419, 4417, -1, + 4419, 4418, 4420, -1, 4420, 4421, 4419, -1, + 4421, 4420, 4422, -1, 4422, 4423, 4421, -1, + 4423, 4422, 4424, -1, 4424, 4425, 4423, -1, + 4425, 4424, 4426, -1, 4426, 4427, 4425, -1, + 4427, 4426, 4428, -1, 4428, 4429, 4427, -1, + 4429, 4428, 4430, -1, 4430, 4431, 4429, -1, + 4431, 4430, 4432, -1, 4432, 4433, 4431, -1, + 4433, 4432, 4434, -1, 4434, 4435, 4433, -1, + 4435, 4434, 4401, -1, 4401, 4400, 4435, -1, + 4400, 4436, 4435, -1, 4436, 4400, 4398, -1, + 4398, 4437, 4436, -1, 4437, 4398, 4396, -1, + 4396, 4438, 4437, -1, 4438, 4396, 4394, -1, + 4394, 4439, 4438, -1, 4439, 4394, 4392, -1, + 4392, 4440, 4439, -1, 4440, 4392, 4390, -1, + 4390, 4441, 4440, -1, 4441, 4390, 4388, -1, + 4388, 4442, 4441, -1, 4442, 4388, 4386, -1, + 4386, 4443, 4442, -1, 4443, 4386, 4384, -1, + 4384, 4444, 4443, -1, 4444, 4384, 4382, -1, + 4382, 4445, 4444, -1, 4445, 4382, 4380, -1, + 4380, 4446, 4445, -1, 4446, 4380, 4378, -1, + 4378, 4447, 4446, -1, 4447, 4378, 4376, -1, + 4376, 4448, 4447, -1, 4448, 4376, 4374, -1, + 4374, 4449, 4448, -1, 4449, 4374, 4372, -1, + 4372, 4450, 4449, -1, 4450, 4372, 4370, -1, + 4370, 4451, 4450, -1, 4451, 4370, 4368, -1, + 4368, 4452, 4451, -1, 4452, 4368, 4366, -1, + 4366, 4453, 4452, -1, 4453, 4366, 4364, -1, + 4364, 4454, 4453, -1, 4454, 4364, 4103, -1, + 4454, 4103, 4102, -1, 4454, 4102, 4220, -1, + 4220, 4453, 4454, -1, 4453, 4220, 4219, -1, + 4219, 4452, 4453, -1, 4452, 4219, 4218, -1, + 4218, 4451, 4452, -1, 4451, 4218, 4217, -1, + 4217, 4450, 4451, -1, 4450, 4217, 4216, -1, + 4216, 4449, 4450, -1, 4449, 4216, 4215, -1, + 4215, 4448, 4449, -1, 4448, 4215, 4214, -1, + 4214, 4447, 4448, -1, 4447, 4214, 4213, -1, + 4213, 4446, 4447, -1, 4446, 4213, 4212, -1, + 4212, 4445, 4446, -1, 4445, 4212, 4211, -1, + 4211, 4444, 4445, -1, 4444, 4211, 4210, -1, + 4210, 4443, 4444, -1, 4443, 4210, 4209, -1, + 4209, 4442, 4443, -1, 4442, 4209, 4208, -1, + 4208, 4441, 4442, -1, 4441, 4208, 4207, -1, + 4207, 4440, 4441, -1, 4440, 4207, 4206, -1, + 4206, 4439, 4440, -1, 4439, 4206, 4205, -1, + 4205, 4438, 4439, -1, 4438, 4205, 4204, -1, + 4204, 4437, 4438, -1, 4437, 4204, 4203, -1, + 4203, 4436, 4437, -1, 4436, 4203, 4144, -1, + 4144, 4143, 4436, -1, 4143, 4435, 4436, -1, + 4435, 4143, 4146, -1, 4146, 4433, 4435, -1, + 4433, 4146, 4148, -1, 4148, 4431, 4433, -1, + 4431, 4148, 4150, -1, 4150, 4429, 4431, -1, + 4429, 4150, 4152, -1, 4152, 4427, 4429, -1, + 4427, 4152, 4154, -1, 4154, 4425, 4427, -1, + 4425, 4154, 4156, -1, 4156, 4423, 4425, -1, + 4423, 4156, 4158, -1, 4158, 4421, 4423, -1, + 4421, 4158, 4160, -1, 4160, 4419, 4421, -1, + 4419, 4160, 4162, -1, 4162, 4417, 4419, -1, + 4417, 4162, 4164, -1, 4164, 4415, 4417, -1, + 4415, 4164, 4166, -1, 4166, 4413, 4415, -1, + 4413, 4166, 4168, -1, 4168, 4411, 4413, -1, + 4411, 4168, 4170, -1, 4170, 4409, 4411, -1, + 4409, 4170, 4172, -1, 4172, 4407, 4409, -1, + 4407, 4172, 4174, -1, 4174, 4405, 4407, -1, + 4405, 4174, 4176, -1, 4176, 4403, 4405, -1, + 4403, 4176, 4178, -1, 4403, 4178, 4180, -1, + 4180, 4455, 4403, -1, 4455, 4180, 4181, -1, + 4455, 4181, 4456, -1, 4456, 4403, 4455, -1, + 4456, 4404, 4403, -1, 4404, 4456, 4181, -1, + 4404, 4181, 4457, -1, 4457, 4402, 4404, -1, + 4457, 4458, 4402, -1, 4457, 4100, 4458, -1, + 4100, 4457, 4181, -1, 4098, 4181, 4182, -1, + 4459, 4098, 4182, -1, 4459, 4182, 4183, -1, + 4459, 4183, 4460, -1, 4460, 4098, 4459, -1, + 4460, 4096, 4098, -1, 4096, 4460, 4183, -1, + 4183, 4097, 4096, -1, 4183, 4184, 4097, -1, + 4461, 4462, 4463, -1, 4464, 4465, 4461, -1, + 4464, 4461, 4466, -1, 4466, 4467, 4464, -1, + 4467, 4466, 4468, -1, 4468, 4469, 4467, -1, + 4469, 4468, 4470, -1, 4470, 4471, 4469, -1, + 4471, 4470, 4472, -1, 4472, 4473, 4471, -1, + 4473, 4472, 4474, -1, 4474, 4475, 4473, -1, + 4475, 4474, 4476, -1, 4476, 4477, 4475, -1, + 4477, 4476, 4478, -1, 4478, 4479, 4477, -1, + 4479, 4478, 4480, -1, 4480, 4481, 4479, -1, + 4481, 4480, 4482, -1, 4482, 4483, 4481, -1, + 4483, 4482, 4484, -1, 4484, 4485, 4483, -1, + 4485, 4484, 4486, -1, 4486, 4487, 4485, -1, + 4487, 4486, 4488, -1, 4488, 4489, 4487, -1, + 4489, 4488, 4490, -1, 4490, 4491, 4489, -1, + 4491, 4490, 4492, -1, 4492, 4493, 4491, -1, + 4493, 4492, 4494, -1, 4494, 4495, 4493, -1, + 4495, 4494, 4496, -1, 4496, 4497, 4495, -1, + 4497, 4496, 4498, -1, 4498, 4499, 4497, -1, + 4499, 4498, 4500, -1, 4500, 4501, 4499, -1, + 4501, 4500, 4502, -1, 4502, 4503, 4501, -1, + 4503, 4502, 4504, -1, 4504, 4505, 4503, -1, + 4506, 4507, 4508, -1, 4507, 4506, 4509, -1, + 4509, 4510, 4507, -1, 4510, 4509, 4511, -1, + 4511, 4512, 4510, -1, 4512, 4511, 4513, -1, + 4513, 4514, 4512, -1, 4514, 4513, 4515, -1, + 4515, 4516, 4514, -1, 4516, 4515, 4517, -1, + 4517, 4518, 4516, -1, 4518, 4517, 4519, -1, + 4519, 4520, 4518, -1, 4520, 4519, 4521, -1, + 4521, 4522, 4520, -1, 4522, 4521, 4523, -1, + 4523, 4524, 4522, -1, 4524, 4523, 4525, -1, + 4525, 4526, 4524, -1, 4526, 4525, 4527, -1, + 4527, 4528, 4526, -1, 4528, 4527, 4529, -1, + 4529, 4530, 4528, -1, 4530, 4529, 4531, -1, + 4531, 4532, 4530, -1, 4532, 4531, 4533, -1, + 4533, 4534, 4532, -1, 4534, 4533, 4535, -1, + 4535, 4536, 4534, -1, 4536, 4535, 4537, -1, + 4537, 4538, 4536, -1, 4538, 4537, 4539, -1, + 4539, 4540, 4538, -1, 4540, 4539, 4541, -1, + 4541, 4542, 4540, -1, 4542, 4541, 4543, -1, + 4543, 4544, 4542, -1, 4545, 4546, 4544, -1, + 4545, 4544, 4547, -1, 4547, 4548, 4545, -1, + 4548, 4547, 4549, -1, 4549, 4550, 4548, -1, + 4550, 4549, 4551, -1, 4551, 4552, 4550, -1, + 4552, 4551, 4553, -1, 4553, 4554, 4552, -1, + 4553, 4555, 4554, -1, 4555, 4553, 4556, -1, + 4556, 4557, 4555, -1, 4557, 4556, 4558, -1, + 4558, 4559, 4557, -1, 4559, 4558, 4560, -1, + 4560, 4561, 4559, -1, 4562, 4563, 4564, -1, + 4564, 4565, 4562, -1, 4565, 4564, 4566, -1, + 4566, 4567, 4565, -1, 4567, 4566, 4568, -1, + 4568, 4569, 4567, -1, 4569, 4568, 4570, -1, + 4570, 4571, 4569, -1, 4571, 4570, 4572, -1, + 4572, 4573, 4571, -1, 4573, 4572, 4574, -1, + 4574, 4575, 4573, -1, 4575, 4574, 4576, -1, + 4576, 4577, 4575, -1, 4577, 4576, 4578, -1, + 4578, 4579, 4577, -1, 4579, 4578, 4580, -1, + 4580, 4581, 4579, -1, 4581, 4580, 4582, -1, + 4582, 4583, 4581, -1, 4583, 4582, 4584, -1, + 4584, 4585, 4583, -1, 4585, 4584, 4586, -1, + 4586, 4587, 4585, -1, 4587, 4586, 4588, -1, + 4588, 4589, 4587, -1, 4589, 4588, 4590, -1, + 4590, 4591, 4589, -1, 4591, 4590, 4592, -1, + 4592, 4593, 4591, -1, 4593, 4592, 4594, -1, + 4594, 4595, 4593, -1, 4595, 4594, 4596, -1, + 4596, 4597, 4595, -1, 4597, 4596, 4598, -1, + 4598, 4599, 4597, -1, 4599, 4598, 4600, -1, + 4600, 4601, 4599, -1, 4601, 4600, 4602, -1, + 4602, 4603, 4601, -1, 4603, 4602, 4561, -1, + 4561, 4560, 4603, -1, 4560, 4604, 4603, -1, + 4560, 4605, 4604, -1, 4605, 4560, 4558, -1, + 4558, 4606, 4605, -1, 4606, 4558, 4556, -1, + 4556, 4607, 4606, -1, 4607, 4556, 4553, -1, + 4607, 4553, 4551, -1, 4551, 4608, 4607, -1, + 4608, 4551, 4549, -1, 4549, 4609, 4608, -1, + 4609, 4549, 4547, -1, 4547, 4610, 4609, -1, + 4610, 4547, 4544, -1, 4544, 4543, 4610, -1, + 4610, 4543, 4611, -1, 4610, 4611, 4612, -1, + 4612, 4609, 4610, -1, 4609, 4612, 4613, -1, + 4613, 4608, 4609, -1, 4608, 4613, 4614, -1, + 4614, 4607, 4608, -1, 4614, 4606, 4607, -1, + 4606, 4614, 4615, -1, 4615, 4605, 4606, -1, + 4605, 4615, 4616, -1, 4616, 4604, 4605, -1, + 4604, 4616, 4617, -1, 4604, 4617, 4618, -1, + 4619, 4505, 4620, -1, 4620, 4621, 4619, -1, + 4621, 4620, 4622, -1, 4622, 4623, 4621, -1, + 4623, 4622, 4624, -1, 4624, 4625, 4623, -1, + 4625, 4624, 4626, -1, 4626, 4627, 4625, -1, + 4627, 4626, 4628, -1, 4628, 4629, 4627, -1, + 4629, 4628, 4630, -1, 4630, 4631, 4629, -1, + 4631, 4630, 4632, -1, 4632, 4633, 4631, -1, + 4633, 4632, 4634, -1, 4634, 4635, 4633, -1, + 4635, 4634, 4636, -1, 4636, 4637, 4635, -1, + 4637, 4636, 4638, -1, 4638, 4639, 4637, -1, + 4639, 4638, 4640, -1, 4640, 4641, 4639, -1, + 4641, 4640, 4642, -1, 4642, 4643, 4641, -1, + 4643, 4642, 4644, -1, 4644, 4645, 4643, -1, + 4645, 4644, 4646, -1, 4646, 4647, 4645, -1, + 4647, 4646, 4648, -1, 4648, 4649, 4647, -1, + 4649, 4648, 4650, -1, 4650, 4651, 4649, -1, + 4651, 4650, 4652, -1, 4652, 4653, 4651, -1, + 4653, 4652, 4654, -1, 4654, 4655, 4653, -1, + 4655, 4654, 4656, -1, 4656, 4657, 4655, -1, + 4657, 4656, 4658, -1, 4658, 4618, 4657, -1, + 4618, 4658, 4659, -1, 4659, 4604, 4618, -1, + 4659, 4603, 4604, -1, 4659, 4601, 4603, -1, + 4601, 4659, 4658, -1, 4658, 4599, 4601, -1, + 4599, 4658, 4656, -1, 4656, 4597, 4599, -1, + 4597, 4656, 4654, -1, 4654, 4595, 4597, -1, + 4595, 4654, 4652, -1, 4652, 4593, 4595, -1, + 4593, 4652, 4650, -1, 4650, 4591, 4593, -1, + 4591, 4650, 4648, -1, 4648, 4589, 4591, -1, + 4589, 4648, 4646, -1, 4646, 4587, 4589, -1, + 4587, 4646, 4644, -1, 4644, 4585, 4587, -1, + 4585, 4644, 4642, -1, 4642, 4583, 4585, -1, + 4583, 4642, 4640, -1, 4640, 4581, 4583, -1, + 4581, 4640, 4638, -1, 4638, 4579, 4581, -1, + 4579, 4638, 4636, -1, 4636, 4577, 4579, -1, + 4577, 4636, 4634, -1, 4634, 4575, 4577, -1, + 4575, 4634, 4632, -1, 4632, 4573, 4575, -1, + 4573, 4632, 4630, -1, 4630, 4571, 4573, -1, + 4571, 4630, 4628, -1, 4628, 4569, 4571, -1, + 4569, 4628, 4626, -1, 4626, 4567, 4569, -1, + 4567, 4626, 4624, -1, 4624, 4565, 4567, -1, + 4565, 4624, 4622, -1, 4622, 4562, 4565, -1, + 4562, 4622, 4620, -1, 4620, 4563, 4562, -1, + 4563, 4620, 4505, -1, 4505, 4504, 4563, -1, + 4660, 4563, 4504, -1, 4504, 4661, 4660, -1, + 4661, 4504, 4502, -1, 4502, 4662, 4661, -1, + 4662, 4502, 4500, -1, 4500, 4663, 4662, -1, + 4663, 4500, 4498, -1, 4498, 4664, 4663, -1, + 4664, 4498, 4496, -1, 4496, 4665, 4664, -1, + 4665, 4496, 4494, -1, 4494, 4666, 4665, -1, + 4666, 4494, 4492, -1, 4492, 4667, 4666, -1, + 4667, 4492, 4490, -1, 4490, 4668, 4667, -1, + 4668, 4490, 4488, -1, 4488, 4669, 4668, -1, + 4669, 4488, 4486, -1, 4486, 4670, 4669, -1, + 4670, 4486, 4484, -1, 4484, 4671, 4670, -1, + 4671, 4484, 4482, -1, 4482, 4672, 4671, -1, + 4672, 4482, 4480, -1, 4480, 4673, 4672, -1, + 4673, 4480, 4478, -1, 4478, 4674, 4673, -1, + 4674, 4478, 4476, -1, 4476, 4675, 4674, -1, + 4675, 4476, 4474, -1, 4474, 4676, 4675, -1, + 4676, 4474, 4472, -1, 4472, 4677, 4676, -1, + 4677, 4472, 4470, -1, 4470, 4678, 4677, -1, + 4678, 4470, 4468, -1, 4468, 4679, 4678, -1, + 4679, 4468, 4466, -1, 4466, 4680, 4679, -1, + 4680, 4466, 4461, -1, 4461, 4463, 4680, -1, + 4681, 4682, 4683, -1, 4684, 4685, 4683, -1, + 4684, 4683, 4686, -1, 4686, 4687, 4684, -1, + 4687, 4686, 4688, -1, 4688, 4689, 4687, -1, + 4689, 4688, 4690, -1, 4690, 4691, 4689, -1, + 4691, 4690, 4692, -1, 4692, 4693, 4691, -1, + 4693, 4692, 4694, -1, 4694, 4695, 4693, -1, + 4695, 4694, 4696, -1, 4696, 4697, 4695, -1, + 4697, 4696, 4698, -1, 4698, 4699, 4697, -1, + 4699, 4698, 4700, -1, 4700, 4701, 4699, -1, + 4701, 4700, 4702, -1, 4702, 4703, 4701, -1, + 4703, 4702, 4704, -1, 4704, 4705, 4703, -1, + 4705, 4704, 4706, -1, 4706, 4707, 4705, -1, + 4707, 4706, 4708, -1, 4708, 4709, 4707, -1, + 4709, 4708, 4710, -1, 4710, 4711, 4709, -1, + 4712, 4713, 4714, -1, 4714, 4715, 4712, -1, + 4715, 4714, 4716, -1, 4716, 4717, 4715, -1, + 4718, 4715, 4717, -1, 4717, 4719, 4718, -1, + 4719, 4717, 4720, -1, 4720, 4721, 4719, -1, + 4721, 4720, 4722, -1, 4722, 4723, 4721, -1, + 4723, 4722, 4724, -1, 4724, 4725, 4723, -1, + 4725, 4724, 4726, -1, 4726, 4727, 4725, -1, + 4727, 4726, 4728, -1, 4728, 4729, 4727, -1, + 4729, 4728, 4730, -1, 4730, 4731, 4729, -1, + 4731, 4730, 4732, -1, 4732, 4733, 4731, -1, + 4733, 4732, 4734, -1, 4734, 4735, 4733, -1, + 4735, 4734, 4736, -1, 4736, 4737, 4735, -1, + 4737, 4736, 4738, -1, 4738, 4739, 4737, -1, + 4739, 4738, 4740, -1, 4740, 4741, 4739, -1, + 4741, 4740, 4742, -1, 4742, 4743, 4741, -1, + 4743, 4742, 4744, -1, 4744, 4745, 4743, -1, + 4745, 4744, 4746, -1, 4746, 4747, 4745, -1, + 4747, 4746, 4748, -1, 4748, 4749, 4747, -1, + 4750, 4751, 4752, -1, 4752, 4753, 4750, -1, + 4753, 4752, 4754, -1, 4754, 4755, 4753, -1, + 4755, 4754, 4756, -1, 4756, 4757, 4755, -1, + 4757, 4756, 4758, -1, 4758, 4759, 4757, -1, + 4759, 4758, 4760, -1, 4760, 4761, 4759, -1, + 4761, 4760, 4762, -1, 4762, 4763, 4761, -1, + 4763, 4762, 4764, -1, 4764, 4765, 4763, -1, + 4765, 4764, 4766, -1, 4766, 4767, 4765, -1, + 4767, 4766, 4768, -1, 4768, 4769, 4767, -1, + 4769, 4768, 4770, -1, 4770, 4771, 4769, -1, + 4771, 4770, 4772, -1, 4772, 4773, 4771, -1, + 4773, 4772, 4774, -1, 4774, 4775, 4773, -1, + 4775, 4774, 4776, -1, 4776, 4777, 4775, -1, + 4777, 4776, 4778, -1, 4778, 4779, 4777, -1, + 4779, 4778, 4780, -1, 4780, 4781, 4779, -1, + 4781, 4780, 4782, -1, 4782, 4783, 4781, -1, + 4783, 4782, 4784, -1, 4784, 4785, 4783, -1, + 4785, 4784, 4786, -1, 4786, 4787, 4785, -1, + 4787, 4786, 4788, -1, 4788, 4789, 4787, -1, + 4789, 4788, 4790, -1, 4790, 4791, 4789, -1, + 4791, 4790, 4792, -1, 4792, 4793, 4791, -1, + 4793, 4792, 4794, -1, 4794, 4795, 4793, -1, + 4795, 4794, 4796, -1, 4796, 4797, 4795, -1, + 4797, 4796, 4798, -1, 4798, 4799, 4797, -1, + 4799, 4798, 4800, -1, 4800, 4801, 4799, -1, + 4802, 4803, 4804, -1, 4805, 4806, 4807, -1, + 4805, 4808, 4806, -1, 4808, 4805, 4809, -1, + 4809, 4810, 4808, -1, 4810, 4809, 4811, -1, + 4811, 4812, 4810, -1, 4812, 4811, 4813, -1, + 4813, 4814, 4812, -1, 4814, 4813, 4815, -1, + 4815, 4816, 4814, -1, 4816, 4815, 4817, -1, + 4817, 4818, 4816, -1, 4818, 4817, 4819, -1, + 4819, 4820, 4818, -1, 4820, 4819, 4821, -1, + 4821, 4822, 4820, -1, 4822, 4821, 4823, -1, + 4823, 4824, 4822, -1, 4824, 4823, 4825, -1, + 4825, 4826, 4824, -1, 4826, 4825, 4827, -1, + 4827, 4828, 4826, -1, 4828, 4827, 4829, -1, + 4829, 4830, 4828, -1, 4829, 4831, 4830, -1, + 4831, 4829, 4832, -1, 4832, 4833, 4831, -1, + 4833, 4832, 4834, -1, 4834, 4835, 4833, -1, + 4835, 4834, 4836, -1, 4836, 4837, 4835, -1, + 4837, 4836, 4838, -1, 4838, 4839, 4837, -1, + 4839, 4838, 4840, -1, 4840, 4841, 4839, -1, + 4841, 4840, 4842, -1, 4842, 4843, 4841, -1, + 4843, 4842, 4844, -1, 4844, 4845, 4843, -1, + 4845, 4844, 4846, -1, 4846, 4847, 4845, -1, + 4847, 4846, 4848, -1, 4848, 4849, 4847, -1, + 4849, 4848, 4850, -1, 4850, 4851, 4849, -1, + 4851, 4850, 4802, -1, 4802, 4804, 4851, -1, + 4852, 4853, 4854, -1, 4855, 4856, 4857, -1, + 4857, 4858, 4855, -1, 4859, 4858, 4857, -1, + 4859, 4857, 4860, -1, 4857, 4861, 4860, -1, + 4857, 4862, 4861, -1, 4862, 4857, 4856, -1, + 4856, 4863, 4862, -1, 4863, 4856, 4864, -1, + 4864, 4865, 4863, -1, 4865, 4864, 4866, -1, + 4866, 4867, 4865, -1, 4867, 4866, 4868, -1, + 4868, 4869, 4867, -1, 4869, 4868, 4870, -1, + 4870, 4871, 4869, -1, 4871, 4870, 4872, -1, + 4872, 4873, 4871, -1, 4873, 4872, 4874, -1, + 4874, 4875, 4873, -1, 4875, 4874, 4876, -1, + 4876, 4877, 4875, -1, 4877, 4876, 4878, -1, + 4878, 4879, 4877, -1, 4879, 4878, 4880, -1, + 4880, 4881, 4879, -1, 4881, 4880, 4882, -1, + 4882, 4883, 4881, -1, 4883, 4882, 4884, -1, + 4884, 4885, 4883, -1, 4885, 4884, 4886, -1, + 4886, 4887, 4885, -1, 4887, 4886, 4888, -1, + 4888, 4889, 4887, -1, 4889, 4888, 4890, -1, + 4890, 4891, 4889, -1, 4890, 4892, 4891, -1, + 4892, 4890, 4893, -1, 4893, 4894, 4892, -1, + 4894, 4893, 4895, -1, 4895, 4896, 4894, -1, + 4896, 4895, 4897, -1, 4897, 4898, 4896, -1, + 4898, 4897, 4899, -1, 4899, 4900, 4898, -1, + 4900, 4899, 4901, -1, 4901, 4902, 4900, -1, + 4902, 4901, 4903, -1, 4903, 4904, 4902, -1, + 4904, 4903, 4905, -1, 4905, 4906, 4904, -1, + 4906, 4905, 4907, -1, 4907, 4908, 4906, -1, + 4908, 4907, 4909, -1, 4909, 4910, 4908, -1, + 4910, 4909, 4911, -1, 4911, 4912, 4910, -1, + 4912, 4911, 4913, -1, 4913, 4914, 4912, -1, + 4914, 4913, 4915, -1, 4915, 4916, 4914, -1, + 4916, 4915, 4917, -1, 4917, 4918, 4916, -1, + 4918, 4917, 4919, -1, 4919, 4920, 4918, -1, + 4920, 4921, 4922, -1, 4922, 4918, 4920, -1, + 4918, 4922, 4923, -1, 4923, 4916, 4918, -1, + 4916, 4923, 4924, -1, 4924, 4914, 4916, -1, + 4914, 4924, 4925, -1, 4925, 4912, 4914, -1, + 4912, 4925, 4926, -1, 4926, 4910, 4912, -1, + 4910, 4926, 4927, -1, 4927, 4908, 4910, -1, + 4908, 4927, 4928, -1, 4928, 4906, 4908, -1, + 4906, 4928, 4929, -1, 4929, 4904, 4906, -1, + 4904, 4929, 4930, -1, 4930, 4902, 4904, -1, + 4902, 4930, 4931, -1, 4931, 4900, 4902, -1, + 4900, 4931, 4932, -1, 4932, 4898, 4900, -1, + 4898, 4932, 4933, -1, 4933, 4896, 4898, -1, + 4896, 4933, 4934, -1, 4934, 4894, 4896, -1, + 4894, 4934, 4935, -1, 4935, 4892, 4894, -1, + 4892, 4935, 4936, -1, 4936, 4891, 4892, -1, + 4891, 4936, 4937, -1, 4891, 4937, 4938, -1, + 4938, 4889, 4891, -1, 4889, 4938, 4939, -1, + 4939, 4887, 4889, -1, 4887, 4939, 4940, -1, + 4940, 4885, 4887, -1, 4885, 4940, 4941, -1, + 4941, 4883, 4885, -1, 4883, 4941, 4942, -1, + 4942, 4881, 4883, -1, 4881, 4942, 4943, -1, + 4943, 4879, 4881, -1, 4879, 4943, 4944, -1, + 4944, 4877, 4879, -1, 4877, 4944, 4945, -1, + 4945, 4875, 4877, -1, 4875, 4945, 4946, -1, + 4946, 4873, 4875, -1, 4873, 4946, 4947, -1, + 4947, 4871, 4873, -1, 4871, 4947, 4948, -1, + 4948, 4869, 4871, -1, 4869, 4948, 4949, -1, + 4949, 4867, 4869, -1, 4867, 4949, 4950, -1, + 4950, 4865, 4867, -1, 4865, 4950, 4951, -1, + 4951, 4863, 4865, -1, 4863, 4951, 4952, -1, + 4952, 4862, 4863, -1, 4862, 4952, 4953, -1, + 4953, 4861, 4862, -1, 4861, 4953, 4854, -1, + 4854, 4954, 4861, -1, 4954, 4854, 4853, -1, + 4954, 4853, 4955, -1, 4853, 4852, 4955, -1, + 4852, 4956, 4955, -1, 4852, 4854, 4956, -1, + 4957, 4956, 4854, -1, 4854, 4958, 4957, -1, + 4958, 4854, 4953, -1, 4953, 4959, 4958, -1, + 4959, 4953, 4952, -1, 4952, 4960, 4959, -1, + 4960, 4952, 4951, -1, 4951, 4961, 4960, -1, + 4961, 4951, 4950, -1, 4950, 4962, 4961, -1, + 4962, 4950, 4949, -1, 4949, 4963, 4962, -1, + 4963, 4949, 4948, -1, 4948, 4964, 4963, -1, + 4964, 4948, 4947, -1, 4947, 4965, 4964, -1, + 4965, 4947, 4946, -1, 4946, 4966, 4965, -1, + 4966, 4946, 4945, -1, 4945, 4967, 4966, -1, + 4967, 4945, 4944, -1, 4944, 4968, 4967, -1, + 4968, 4944, 4943, -1, 4943, 4969, 4968, -1, + 4969, 4943, 4942, -1, 4942, 4970, 4969, -1, + 4970, 4942, 4941, -1, 4941, 4971, 4970, -1, + 4971, 4941, 4940, -1, 4940, 4972, 4971, -1, + 4972, 4940, 4939, -1, 4939, 4973, 4972, -1, + 4973, 4939, 4938, -1, 4938, 4974, 4973, -1, + 4974, 4938, 4937, -1, 4937, 4975, 4974, -1, + 4937, 4976, 4975, -1, 4976, 4937, 4936, -1, + 4936, 4977, 4976, -1, 4977, 4936, 4935, -1, + 4935, 4978, 4977, -1, 4978, 4935, 4934, -1, + 4934, 4979, 4978, -1, 4979, 4934, 4933, -1, + 4933, 4980, 4979, -1, 4980, 4933, 4932, -1, + 4932, 4981, 4980, -1, 4981, 4932, 4931, -1, + 4931, 4982, 4981, -1, 4982, 4931, 4930, -1, + 4930, 4983, 4982, -1, 4983, 4930, 4929, -1, + 4929, 4984, 4983, -1, 4984, 4929, 4928, -1, + 4928, 4985, 4984, -1, 4985, 4928, 4927, -1, + 4927, 4986, 4985, -1, 4986, 4927, 4926, -1, + 4926, 4987, 4986, -1, 4987, 4926, 4925, -1, + 4925, 4988, 4987, -1, 4988, 4925, 4924, -1, + 4924, 4989, 4988, -1, 4989, 4924, 4923, -1, + 4923, 4990, 4989, -1, 4990, 4923, 4922, -1, + 4922, 4991, 4990, -1, 4991, 4922, 4921, -1, + 4921, 4992, 4991, -1, 4992, 4921, 4993, -1, + 4993, 4994, 4992, -1, 4995, 4996, 4997, -1, + 4998, 4999, 4994, -1, 4999, 4998, 4995, -1, + 4998, 4996, 4995, -1, 4998, 4994, 4996, -1, + 4994, 4993, 4996, -1, 5000, 4996, 4993, -1, + 5000, 4997, 4996, -1, 5001, 5002, 5003, -1, + 5002, 5001, 4997, -1, 5002, 4997, 5000, -1, + 5000, 4993, 5002, -1, 4993, 5003, 5002, -1, + 5003, 4993, 4921, -1, 4921, 4920, 5003, -1, + 5004, 5005, 5003, -1, 5004, 5003, 4920, -1, + 4920, 4919, 5004, -1, 5006, 5007, 5008, -1, + 5008, 5009, 5006, -1, 5008, 5010, 5009, -1, + 5010, 5011, 5009, -1, 5004, 5009, 5011, -1, + 5009, 5004, 4919, -1, 4919, 5012, 5009, -1, + 5012, 4919, 4917, -1, 4917, 5013, 5012, -1, + 5013, 4917, 4915, -1, 4915, 5014, 5013, -1, + 5014, 4915, 4913, -1, 4913, 5015, 5014, -1, + 5015, 4913, 4911, -1, 4911, 5016, 5015, -1, + 5016, 4911, 4909, -1, 4909, 5017, 5016, -1, + 5017, 4909, 4907, -1, 4907, 5018, 5017, -1, + 5018, 4907, 4905, -1, 4905, 5019, 5018, -1, + 5019, 4905, 4903, -1, 4903, 5020, 5019, -1, + 5020, 4903, 4901, -1, 4901, 5021, 5020, -1, + 5021, 4901, 4899, -1, 4899, 5022, 5021, -1, + 5022, 4899, 4897, -1, 4897, 5023, 5022, -1, + 5023, 4897, 4895, -1, 4895, 5024, 5023, -1, + 5024, 4895, 4893, -1, 4893, 5025, 5024, -1, + 5025, 4893, 4890, -1, 5025, 4890, 4888, -1, + 4888, 5026, 5025, -1, 5026, 4888, 4886, -1, + 4886, 5027, 5026, -1, 5027, 4886, 4884, -1, + 4884, 5028, 5027, -1, 5028, 4884, 4882, -1, + 4882, 5029, 5028, -1, 5029, 4882, 4880, -1, + 4880, 5030, 5029, -1, 5030, 4880, 4878, -1, + 4878, 5031, 5030, -1, 5031, 4878, 4876, -1, + 4876, 5032, 5031, -1, 5032, 4876, 4874, -1, + 4874, 5033, 5032, -1, 5033, 4874, 4872, -1, + 4872, 5034, 5033, -1, 5034, 4872, 4870, -1, + 4870, 5035, 5034, -1, 5035, 4870, 4868, -1, + 4868, 5036, 5035, -1, 5036, 4868, 4866, -1, + 4866, 5037, 5036, -1, 5037, 4866, 4864, -1, + 4864, 5038, 5037, -1, 5038, 4864, 4856, -1, + 4856, 4855, 5038, -1, 5039, 5040, 4855, -1, + 5040, 5039, 5041, -1, 5042, 5043, 5044, -1, + 5043, 5042, 5041, -1, 5042, 5040, 5041, -1, + 5042, 5044, 5040, -1, 5044, 4855, 5040, -1, + 5044, 5038, 4855, -1, 5038, 5044, 5045, -1, + 5045, 5037, 5038, -1, 5037, 5045, 5046, -1, + 5046, 5036, 5037, -1, 5036, 5046, 5047, -1, + 5047, 5035, 5036, -1, 5035, 5047, 5048, -1, + 5048, 5034, 5035, -1, 5034, 5048, 5049, -1, + 5049, 5033, 5034, -1, 5033, 5049, 5050, -1, + 5050, 5032, 5033, -1, 5032, 5050, 5051, -1, + 5051, 5031, 5032, -1, 5031, 5051, 5052, -1, + 5052, 5030, 5031, -1, 5030, 5052, 5053, -1, + 5053, 5029, 5030, -1, 5029, 5053, 5054, -1, + 5054, 5028, 5029, -1, 5028, 5054, 5055, -1, + 5055, 5027, 5028, -1, 5027, 5055, 5056, -1, + 5056, 5026, 5027, -1, 5026, 5056, 5057, -1, + 5057, 5025, 5026, -1, 5057, 5024, 5025, -1, + 5024, 5057, 5058, -1, 5058, 5023, 5024, -1, + 5023, 5058, 5059, -1, 5059, 5022, 5023, -1, + 5022, 5059, 5060, -1, 5060, 5021, 5022, -1, + 5021, 5060, 5061, -1, 5061, 5020, 5021, -1, + 5020, 5061, 5062, -1, 5062, 5019, 5020, -1, + 5019, 5062, 5063, -1, 5063, 5018, 5019, -1, + 5018, 5063, 5064, -1, 5064, 5017, 5018, -1, + 5017, 5064, 5065, -1, 5065, 5016, 5017, -1, + 5016, 5065, 5066, -1, 5066, 5015, 5016, -1, + 5015, 5066, 5067, -1, 5067, 5014, 5015, -1, + 5014, 5067, 5068, -1, 5068, 5013, 5014, -1, + 5013, 5068, 5069, -1, 5069, 5012, 5013, -1, + 5012, 5069, 5070, -1, 5070, 5009, 5012, -1, + 5070, 5006, 5009, -1, 5071, 5006, 5070, -1, + 5071, 5007, 5006, -1, 5072, 5073, 4804, -1, + 5073, 5072, 5007, -1, 5073, 5007, 5071, -1, + 5071, 5070, 5073, -1, 5070, 4804, 5073, -1, + 4804, 5070, 5069, -1, 5069, 4851, 4804, -1, + 4851, 5069, 5068, -1, 5068, 4849, 4851, -1, + 4849, 5068, 5067, -1, 5067, 4847, 4849, -1, + 4847, 5067, 5066, -1, 5066, 4845, 4847, -1, + 4845, 5066, 5065, -1, 5065, 4843, 4845, -1, + 4843, 5065, 5064, -1, 5064, 4841, 4843, -1, + 4841, 5064, 5063, -1, 5063, 4839, 4841, -1, + 4839, 5063, 5062, -1, 5062, 4837, 4839, -1, + 4837, 5062, 5061, -1, 5061, 4835, 4837, -1, + 4835, 5061, 5060, -1, 5060, 4833, 4835, -1, + 4833, 5060, 5059, -1, 5059, 4831, 4833, -1, + 4831, 5059, 5058, -1, 5058, 4830, 4831, -1, + 4830, 5058, 5057, -1, 4830, 5057, 5056, -1, + 5056, 4828, 4830, -1, 4828, 5056, 5055, -1, + 5055, 4826, 4828, -1, 4826, 5055, 5054, -1, + 5054, 4824, 4826, -1, 4824, 5054, 5053, -1, + 5053, 4822, 4824, -1, 4822, 5053, 5052, -1, + 5052, 4820, 4822, -1, 4820, 5052, 5051, -1, + 5051, 4818, 4820, -1, 4818, 5051, 5050, -1, + 5050, 4816, 4818, -1, 4816, 5050, 5049, -1, + 5049, 4814, 4816, -1, 4814, 5049, 5048, -1, + 5048, 4812, 4814, -1, 4812, 5048, 5047, -1, + 5047, 4810, 4812, -1, 4810, 5047, 5046, -1, + 5046, 4808, 4810, -1, 4808, 5046, 5045, -1, + 5045, 4806, 4808, -1, 4806, 5045, 5044, -1, + 5044, 5043, 4806, -1, 5074, 4806, 5043, -1, + 5043, 5041, 5074, -1, 5041, 5075, 5076, -1, + 5076, 5074, 5041, -1, 5076, 4806, 5074, -1, + 5076, 4807, 4806, -1, 4807, 5076, 5075, -1, + 5077, 5078, 5075, -1, 5078, 4807, 5075, -1, + 5078, 4805, 4807, -1, 5078, 5077, 4805, -1, + 5077, 5079, 4805, -1, 5077, 5075, 5079, -1, + 5080, 5081, 5082, -1, 5083, 5084, 5085, -1, + 5086, 5084, 5083, -1, 5084, 5086, 5087, -1, + 5084, 5087, 5088, -1, 5088, 5085, 5084, -1, + 5089, 5085, 5088, -1, 5090, 5091, 5092, -1, + 5092, 5093, 5090, -1, 5093, 5092, 5094, -1, + 5094, 5095, 5093, -1, 5095, 5094, 5096, -1, + 5096, 5097, 5095, -1, 5097, 5096, 5098, -1, + 5098, 5099, 5097, -1, 5099, 5098, 5100, -1, + 5100, 5101, 5099, -1, 5101, 5100, 5102, -1, + 5102, 5103, 5101, -1, 5103, 5102, 5104, -1, + 5104, 5105, 5103, -1, 5104, 5106, 5105, -1, + 5106, 5104, 5107, -1, 5107, 5108, 5106, -1, + 5108, 5107, 5109, -1, 5109, 5110, 5108, -1, + 5110, 5109, 5111, -1, 5111, 5112, 5110, -1, + 5112, 5111, 5113, -1, 5113, 5114, 5112, -1, + 5114, 5113, 5115, -1, 5115, 5116, 5114, -1, + 5116, 5115, 5117, -1, 5117, 5118, 5116, -1, + 5119, 5120, 5121, -1, 5119, 5085, 5120, -1, + 5119, 5122, 5085, -1, 5119, 5121, 5122, -1, + 5123, 5122, 5121, -1, 5123, 5121, 5118, -1, + 5118, 5117, 5123, -1, 5124, 5125, 5126, -1, + 5125, 5127, 5126, -1, 5123, 5126, 5127, -1, + 5126, 5123, 5117, -1, 5117, 5128, 5126, -1, + 5128, 5117, 5115, -1, 5115, 5129, 5128, -1, + 5129, 5115, 5113, -1, 5113, 5130, 5129, -1, + 5130, 5113, 5111, -1, 5111, 5131, 5130, -1, + 5131, 5111, 5109, -1, 5109, 5132, 5131, -1, + 5132, 5109, 5107, -1, 5107, 5133, 5132, -1, + 5133, 5107, 5104, -1, 5133, 5104, 5102, -1, + 5102, 5134, 5133, -1, 5134, 5102, 5100, -1, + 5100, 5135, 5134, -1, 5135, 5100, 5098, -1, + 5098, 5136, 5135, -1, 5136, 5098, 5096, -1, + 5096, 5137, 5136, -1, 5137, 5096, 5094, -1, + 5094, 5138, 5137, -1, 5138, 5094, 5092, -1, + 5092, 5139, 5138, -1, 5139, 5092, 5091, -1, + 5091, 5140, 5139, -1, 5141, 5140, 5091, -1, + 5141, 5091, 5142, -1, 5091, 5143, 5142, -1, + 5091, 5090, 5143, -1, 5143, 5144, 5145, -1, + 5143, 5146, 5144, -1, 5146, 5143, 5090, -1, + 5090, 5147, 5146, -1, 5147, 5090, 5093, -1, + 5093, 5148, 5147, -1, 5148, 5093, 5095, -1, + 5095, 5149, 5148, -1, 5149, 5095, 5097, -1, + 5097, 5150, 5149, -1, 5150, 5097, 5099, -1, + 5099, 5151, 5150, -1, 5151, 5099, 5101, -1, + 5101, 5152, 5151, -1, 5152, 5101, 5103, -1, + 5103, 5153, 5152, -1, 5153, 5103, 5105, -1, + 5105, 5154, 5153, -1, 5105, 5155, 5154, -1, + 5155, 5105, 5106, -1, 5106, 5156, 5155, -1, + 5156, 5106, 5108, -1, 5108, 5157, 5156, -1, + 5157, 5108, 5110, -1, 5110, 5158, 5157, -1, + 5158, 5110, 5112, -1, 5112, 5159, 5158, -1, + 5159, 5112, 5114, -1, 5114, 5160, 5159, -1, + 5160, 5114, 5116, -1, 5116, 5161, 5160, -1, + 5161, 5116, 5118, -1, 5118, 5162, 5161, -1, + 5162, 5118, 5121, -1, 5121, 5163, 5162, -1, + 5121, 5120, 5163, -1, 5164, 5163, 5120, -1, + 5164, 5120, 5085, -1, 5164, 5085, 5089, -1, + 5089, 5163, 5164, -1, 5089, 5088, 5163, -1, + 5163, 5088, 5087, -1, 5163, 5087, 5165, -1, + 5165, 5162, 5163, -1, 5162, 5165, 5166, -1, + 5166, 5161, 5162, -1, 5161, 5166, 5167, -1, + 5167, 5160, 5161, -1, 5160, 5167, 5168, -1, + 5168, 5159, 5160, -1, 5159, 5168, 5169, -1, + 5169, 5158, 5159, -1, 5158, 5169, 5170, -1, + 5170, 5157, 5158, -1, 5157, 5170, 5171, -1, + 5171, 5156, 5157, -1, 5156, 5171, 5172, -1, + 5172, 5155, 5156, -1, 5155, 5172, 5173, -1, + 5173, 5154, 5155, -1, 5154, 5173, 5174, -1, + 5154, 5174, 5175, -1, 5175, 5153, 5154, -1, + 5153, 5175, 5176, -1, 5176, 5152, 5153, -1, + 5152, 5176, 5177, -1, 5177, 5151, 5152, -1, + 5151, 5177, 5178, -1, 5178, 5150, 5151, -1, + 5150, 5178, 5179, -1, 5179, 5149, 5150, -1, + 5149, 5179, 5180, -1, 5180, 5148, 5149, -1, + 5148, 5180, 5181, -1, 5181, 5147, 5148, -1, + 5147, 5181, 5182, -1, 5182, 5146, 5147, -1, + 5146, 5182, 5183, -1, 5183, 5144, 5146, -1, + 5144, 5183, 5082, -1, 5144, 5082, 5081, -1, + 5184, 5144, 5081, -1, 5184, 5185, 5144, -1, + 5185, 5145, 5144, -1, 5185, 5186, 5145, -1, + 5185, 5184, 5186, -1, 5184, 5081, 5186, -1, + 5081, 5080, 5186, -1, 5075, 5186, 5080, -1, + 5080, 5079, 5075, -1, 5080, 5082, 5079, -1, + 5082, 4805, 5079, -1, 5082, 4809, 4805, -1, + 4809, 5082, 5183, -1, 5183, 4811, 4809, -1, + 4811, 5183, 5182, -1, 5182, 4813, 4811, -1, + 4813, 5182, 5181, -1, 5181, 4815, 4813, -1, + 4815, 5181, 5180, -1, 5180, 4817, 4815, -1, + 4817, 5180, 5179, -1, 5179, 4819, 4817, -1, + 4819, 5179, 5178, -1, 5178, 4821, 4819, -1, + 4821, 5178, 5177, -1, 5177, 4823, 4821, -1, + 4823, 5177, 5176, -1, 5176, 4825, 4823, -1, + 4825, 5176, 5175, -1, 5175, 4827, 4825, -1, + 4827, 5175, 5174, -1, 5174, 4829, 4827, -1, + 5174, 4832, 4829, -1, 4832, 5174, 5173, -1, + 5173, 4834, 4832, -1, 4834, 5173, 5172, -1, + 5172, 4836, 4834, -1, 4836, 5172, 5171, -1, + 5171, 4838, 4836, -1, 4838, 5171, 5170, -1, + 5170, 4840, 4838, -1, 4840, 5170, 5169, -1, + 5169, 4842, 4840, -1, 4842, 5169, 5168, -1, + 5168, 4844, 4842, -1, 4844, 5168, 5167, -1, + 5167, 4846, 4844, -1, 4846, 5167, 5166, -1, + 5166, 4848, 4846, -1, 4848, 5166, 5165, -1, + 5165, 4850, 4848, -1, 4850, 5165, 5087, -1, + 5087, 4802, 4850, -1, 5087, 5086, 4802, -1, + 5187, 4802, 5086, -1, 5187, 5086, 5083, -1, + 5187, 5083, 5188, -1, 5188, 4802, 5187, -1, + 5188, 4803, 4802, -1, 5188, 5083, 4803, -1, + 4803, 5083, 5189, -1, 5189, 5007, 5072, -1, + 5007, 5189, 5083, -1, 5190, 5085, 5122, -1, + 5122, 5191, 5190, -1, 5191, 5122, 5123, -1, + 5191, 5123, 5127, -1, 5127, 5190, 5191, -1, + 5127, 5125, 5190, -1, 5125, 5124, 5190, -1, + 5124, 5192, 5190, -1, 5124, 5126, 5192, -1, + 5193, 5192, 5126, -1, 5193, 5126, 5128, -1, + 5128, 5194, 5193, -1, 5194, 5128, 5129, -1, + 5129, 5195, 5194, -1, 5195, 5129, 5130, -1, + 5130, 5196, 5195, -1, 5196, 5130, 5131, -1, + 5131, 5197, 5196, -1, 5197, 5131, 5132, -1, + 5132, 5198, 5197, -1, 5198, 5132, 5133, -1, + 5198, 5133, 5134, -1, 5134, 5199, 5198, -1, + 5199, 5134, 5135, -1, 5135, 5200, 5199, -1, + 5200, 5135, 5136, -1, 5136, 5201, 5200, -1, + 5201, 5136, 5137, -1, 5137, 5202, 5201, -1, + 5202, 5137, 5138, -1, 5138, 5203, 5202, -1, + 5203, 5138, 5139, -1, 5204, 5205, 5203, -1, + 5204, 5203, 5206, -1, 5203, 5139, 5206, -1, + 5207, 5206, 5139, -1, 5207, 5208, 5206, -1, + 5207, 5209, 5208, -1, 5207, 5139, 5209, -1, + 5209, 5139, 5140, -1, 5140, 5208, 5209, -1, + 5140, 5141, 5208, -1, 5141, 5142, 5208, -1, + 5142, 5210, 5208, -1, 5210, 5142, 5143, -1, + 5210, 5143, 5145, -1, 5210, 5145, 5186, -1, + 5186, 5208, 5210, -1, 5211, 5212, 5213, -1, + 5212, 5211, 5214, -1, 5215, 5216, 5217, -1, + 5218, 5217, 5216, -1, 5219, 5220, 5221, -1, + 5219, 5221, 5222, -1, 5222, 5223, 5219, -1, + 5223, 5222, 5217, -1, 5217, 5218, 5223, -1, + 5224, 5225, 5226, -1, 5226, 5227, 5224, -1, + 5228, 5229, 5230, -1, 5230, 5231, 5228, -1, + 5230, 5232, 5231, -1, 5233, 5232, 5230, -1, + 5232, 5233, 5234, -1, 5234, 5235, 5232, -1, + 5235, 5234, 5227, -1, 5227, 5236, 5235, -1, + 5236, 5227, 5226, -1, 5226, 5237, 5236, -1, + 5237, 5226, 5225, -1, 5225, 5238, 5237, -1, + 5238, 5225, 5239, -1, 5240, 5241, 5242, -1, + 5242, 5243, 5240, -1, 5243, 5242, 5244, -1, + 5244, 5245, 5243, -1, 5245, 5244, 5246, -1, + 5246, 5247, 5245, -1, 5247, 5246, 5248, -1, + 5248, 5249, 5247, -1, 5249, 5248, 5250, -1, + 5250, 5251, 5249, -1, 5251, 5250, 5252, -1, + 5252, 5253, 5251, -1, 5253, 5252, 5254, -1, + 5254, 5255, 5253, -1, 5255, 5254, 5256, -1, + 5256, 5257, 5255, -1, 5257, 5256, 5258, -1, + 5258, 5259, 5257, -1, 5259, 5258, 5260, -1, + 5260, 5261, 5259, -1, 5261, 5260, 5262, -1, + 5262, 5263, 5261, -1, 5263, 5262, 5264, -1, + 5264, 5265, 5263, -1, 5265, 5264, 5266, -1, + 5266, 5267, 5265, -1, 5267, 5266, 5268, -1, + 5268, 5269, 5267, -1, 5269, 5268, 5270, -1, + 5270, 5271, 5269, -1, 5271, 5270, 5272, -1, + 5272, 5273, 5271, -1, 5273, 5272, 5274, -1, + 5274, 5275, 5273, -1, 5275, 5274, 5276, -1, + 5276, 5277, 5275, -1, 5277, 5276, 5278, -1, + 5278, 5279, 5277, -1, 5279, 5278, 5280, -1, + 5280, 5281, 5279, -1, 5281, 5280, 5282, -1, + 5282, 5283, 5281, -1, 5283, 5282, 5284, -1, + 5284, 5285, 5283, -1, 5285, 5284, 5286, -1, + 5286, 5287, 5285, -1, 5287, 5286, 5288, -1, + 5288, 5289, 5287, -1, 5289, 5288, 5290, -1, + 5290, 5291, 5289, -1, 5291, 5290, 5292, -1, + 5292, 5293, 5291, -1, 5293, 5292, 5294, -1, + 5294, 5295, 5293, -1, 5295, 5294, 5296, -1, + 5296, 5297, 5295, -1, 5297, 5296, 5298, -1, + 5298, 5299, 5297, -1, 5299, 5298, 5300, -1, + 5300, 5301, 5299, -1, 5301, 5300, 5302, -1, + 5302, 5303, 5301, -1, 5303, 5302, 5304, -1, + 5304, 5305, 5303, -1, 5305, 5304, 5306, -1, + 5306, 5307, 5305, -1, 5307, 5306, 5308, -1, + 5308, 5309, 5307, -1, 5309, 5308, 5310, -1, + 5310, 5311, 5309, -1, 5311, 5310, 5312, -1, + 5312, 5313, 5311, -1, 5313, 5312, 5314, -1, + 5314, 5315, 5313, -1, 5315, 5314, 5316, -1, + 5316, 5317, 5315, -1, 5317, 5316, 5318, -1, + 5318, 5319, 5317, -1, 5319, 5318, 5320, -1, + 5320, 5321, 5319, -1, 5321, 5320, 5322, -1, + 5322, 5323, 5321, -1, 5324, 5214, 5323, -1, + 5323, 5322, 5324, -1, 5324, 5325, 5326, -1, + 5325, 5324, 5322, -1, 5322, 5327, 5325, -1, + 5327, 5322, 5320, -1, 5320, 5328, 5327, -1, + 5328, 5320, 5318, -1, 5318, 5329, 5328, -1, + 5329, 5318, 5316, -1, 5316, 5330, 5329, -1, + 5330, 5316, 5314, -1, 5314, 5331, 5330, -1, + 5331, 5314, 5312, -1, 5312, 5332, 5331, -1, + 5332, 5312, 5310, -1, 5310, 5333, 5332, -1, + 5333, 5310, 5308, -1, 5308, 5334, 5333, -1, + 5334, 5308, 5306, -1, 5306, 5335, 5334, -1, + 5335, 5306, 5304, -1, 5304, 5336, 5335, -1, + 5336, 5304, 5302, -1, 5302, 5337, 5336, -1, + 5337, 5302, 5300, -1, 5300, 5338, 5337, -1, + 5338, 5300, 5298, -1, 5298, 5339, 5338, -1, + 5339, 5298, 5296, -1, 5296, 5340, 5339, -1, + 5340, 5296, 5294, -1, 5294, 5341, 5340, -1, + 5341, 5294, 5292, -1, 5292, 5342, 5341, -1, + 5342, 5292, 5290, -1, 5290, 5343, 5342, -1, + 5343, 5290, 5288, -1, 5288, 5344, 5343, -1, + 5344, 5288, 5286, -1, 5286, 5345, 5344, -1, + 5345, 5286, 5284, -1, 5284, 5346, 5345, -1, + 5346, 5284, 5282, -1, 5282, 5347, 5346, -1, + 5347, 5282, 5280, -1, 5280, 5348, 5347, -1, + 5348, 5280, 5278, -1, 5278, 5349, 5348, -1, + 5349, 5278, 5276, -1, 5276, 5350, 5349, -1, + 5350, 5276, 5274, -1, 5274, 5351, 5350, -1, + 5351, 5274, 5272, -1, 5272, 5352, 5351, -1, + 5352, 5272, 5270, -1, 5270, 5353, 5352, -1, + 5353, 5270, 5268, -1, 5268, 5354, 5353, -1, + 5354, 5268, 5266, -1, 5266, 5355, 5354, -1, + 5355, 5266, 5264, -1, 5264, 5356, 5355, -1, + 5356, 5264, 5262, -1, 5262, 5357, 5356, -1, + 5357, 5262, 5260, -1, 5260, 5358, 5357, -1, + 5358, 5260, 5258, -1, 5258, 5359, 5358, -1, + 5359, 5258, 5256, -1, 5256, 5360, 5359, -1, + 5360, 5256, 5254, -1, 5254, 5361, 5360, -1, + 5361, 5254, 5252, -1, 5252, 5362, 5361, -1, + 5362, 5252, 5250, -1, 5250, 5363, 5362, -1, + 5363, 5250, 5248, -1, 5248, 5364, 5363, -1, + 5364, 5248, 5246, -1, 5246, 5365, 5364, -1, + 5365, 5246, 5244, -1, 5244, 5366, 5365, -1, + 5366, 5244, 5242, -1, 5242, 5367, 5366, -1, + 5367, 5242, 5241, -1, 5241, 5368, 5367, -1, + 5368, 5241, 5369, -1, 5369, 5370, 5368, -1, + 5370, 5369, 5371, -1, 5371, 5372, 5370, -1, + 5372, 5371, 5373, -1, 5373, 5374, 5372, -1, + 5374, 5373, 5375, -1, 5375, 5376, 5374, -1, + 5376, 5375, 5239, -1, 5239, 5377, 5376, -1, + 5377, 5239, 5225, -1, 5225, 5224, 5377, -1, + 5224, 5378, 5377, -1, 5379, 5380, 5381, -1, + 5379, 5381, 5378, -1, 5378, 5224, 5379, -1, + 5379, 5224, 5227, -1, 5227, 5380, 5379, -1, + 5380, 5227, 5234, -1, 5234, 5382, 5380, -1, + 5382, 5234, 5233, -1, 5233, 5383, 5382, -1, + 5233, 5230, 5383, -1, 5384, 5383, 5230, -1, + 5384, 5230, 5229, -1, 5229, 5385, 5384, -1, + 5386, 5387, 5388, -1, 5386, 5388, 5389, -1, + 5389, 5390, 5386, -1, 5391, 5392, 5393, -1, + 5392, 5391, 5390, -1, 5390, 5389, 5392, -1, + 5394, 5395, 5396, -1, 5395, 5397, 5392, -1, + 5392, 5396, 5395, -1, 5396, 5392, 5389, -1, + 5389, 5385, 5396, -1, 5385, 5389, 5388, -1, + 5388, 5384, 5385, -1, 5388, 5398, 5384, -1, + 5399, 5400, 5401, -1, 5401, 5402, 5399, -1, + 5402, 5401, 5403, -1, 5403, 5398, 5402, -1, + 5403, 5384, 5398, -1, 5403, 5383, 5384, -1, + 5383, 5403, 5401, -1, 5401, 5382, 5383, -1, + 5382, 5401, 5400, -1, 5400, 5380, 5382, -1, + 5400, 5381, 5380, -1, 5400, 5399, 5381, -1, + 5381, 5399, 5404, -1, 5381, 5404, 5405, -1, + 5405, 5378, 5381, -1, 5378, 5405, 5406, -1, + 5406, 5377, 5378, -1, 5377, 5406, 5407, -1, + 5407, 5376, 5377, -1, 5376, 5407, 5408, -1, + 5408, 5374, 5376, -1, 5374, 5408, 5409, -1, + 5409, 5372, 5374, -1, 5372, 5409, 5410, -1, + 5410, 5370, 5372, -1, 5370, 5410, 5411, -1, + 5411, 5368, 5370, -1, 5368, 5411, 5412, -1, + 5412, 5367, 5368, -1, 5367, 5412, 5413, -1, + 5413, 5366, 5367, -1, 5366, 5413, 5414, -1, + 5414, 5365, 5366, -1, 5365, 5414, 5415, -1, + 5415, 5364, 5365, -1, 5364, 5415, 5416, -1, + 5416, 5363, 5364, -1, 5363, 5416, 5417, -1, + 5417, 5362, 5363, -1, 5362, 5417, 5418, -1, + 5418, 5361, 5362, -1, 5361, 5418, 5419, -1, + 5419, 5360, 5361, -1, 5360, 5419, 5420, -1, + 5420, 5359, 5360, -1, 5359, 5420, 5421, -1, + 5421, 5358, 5359, -1, 5358, 5421, 5422, -1, + 5422, 5357, 5358, -1, 5357, 5422, 5423, -1, + 5423, 5356, 5357, -1, 5356, 5423, 5424, -1, + 5424, 5355, 5356, -1, 5355, 5424, 5425, -1, + 5425, 5354, 5355, -1, 5354, 5425, 5426, -1, + 5426, 5353, 5354, -1, 5353, 5426, 5427, -1, + 5427, 5352, 5353, -1, 5352, 5427, 5428, -1, + 5428, 5351, 5352, -1, 5351, 5428, 5429, -1, + 5429, 5350, 5351, -1, 5350, 5429, 5430, -1, + 5430, 5349, 5350, -1, 5349, 5430, 5431, -1, + 5431, 5348, 5349, -1, 5348, 5431, 5432, -1, + 5432, 5347, 5348, -1, 5347, 5432, 5433, -1, + 5433, 5346, 5347, -1, 5346, 5433, 5434, -1, + 5434, 5345, 5346, -1, 5345, 5434, 5435, -1, + 5435, 5344, 5345, -1, 5344, 5435, 5436, -1, + 5436, 5343, 5344, -1, 5343, 5436, 5437, -1, + 5437, 5342, 5343, -1, 5342, 5437, 5438, -1, + 5438, 5341, 5342, -1, 5341, 5438, 5439, -1, + 5439, 5340, 5341, -1, 5340, 5439, 5440, -1, + 5440, 5339, 5340, -1, 5339, 5440, 5441, -1, + 5441, 5338, 5339, -1, 5338, 5441, 5442, -1, + 5442, 5337, 5338, -1, 5337, 5442, 5443, -1, + 5443, 5336, 5337, -1, 5336, 5443, 5444, -1, + 5444, 5335, 5336, -1, 5335, 5444, 5445, -1, + 5445, 5334, 5335, -1, 5334, 5445, 5446, -1, + 5446, 5333, 5334, -1, 5333, 5446, 5447, -1, + 5447, 5332, 5333, -1, 5332, 5447, 5448, -1, + 5448, 5331, 5332, -1, 5331, 5448, 5449, -1, + 5449, 5330, 5331, -1, 5330, 5449, 5450, -1, + 5450, 5329, 5330, -1, 5329, 5450, 5451, -1, + 5451, 5328, 5329, -1, 5328, 5451, 5452, -1, + 5452, 5327, 5328, -1, 5327, 5452, 5453, -1, + 5453, 5325, 5327, -1, 5325, 5453, 5454, -1, + 5455, 5454, 5453, -1, 5455, 5456, 5454, -1, + 5457, 5456, 5455, -1, 5455, 5453, 5457, -1, + 5457, 5453, 5458, -1, 5458, 5456, 5457, -1, + 5458, 5459, 5456, -1, 5459, 5458, 5460, -1, + 5460, 5458, 5453, -1, 5460, 5453, 5452, -1, + 5452, 5461, 5460, -1, 5461, 5452, 5451, -1, + 5451, 5462, 5461, -1, 5462, 5451, 5450, -1, + 5450, 5463, 5462, -1, 5463, 5450, 5449, -1, + 5449, 5464, 5463, -1, 5464, 5449, 5448, -1, + 5448, 5465, 5464, -1, 5465, 5448, 5447, -1, + 5447, 5466, 5465, -1, 5466, 5447, 5446, -1, + 5446, 5467, 5466, -1, 5467, 5446, 5445, -1, + 5445, 5468, 5467, -1, 5468, 5445, 5444, -1, + 5444, 5469, 5468, -1, 5469, 5444, 5443, -1, + 5443, 5470, 5469, -1, 5470, 5443, 5442, -1, + 5442, 5471, 5470, -1, 5471, 5442, 5441, -1, + 5441, 5472, 5471, -1, 5472, 5441, 5440, -1, + 5440, 5473, 5472, -1, 5473, 5440, 5439, -1, + 5439, 5474, 5473, -1, 5474, 5439, 5438, -1, + 5438, 5475, 5474, -1, 5475, 5438, 5437, -1, + 5437, 5476, 5475, -1, 5476, 5437, 5436, -1, + 5436, 5477, 5476, -1, 5477, 5436, 5435, -1, + 5435, 5478, 5477, -1, 5478, 5435, 5434, -1, + 5434, 5479, 5478, -1, 5479, 5434, 5433, -1, + 5433, 5480, 5479, -1, 5480, 5433, 5432, -1, + 5432, 5481, 5480, -1, 5481, 5432, 5431, -1, + 5431, 5482, 5481, -1, 5482, 5431, 5430, -1, + 5430, 5483, 5482, -1, 5483, 5430, 5429, -1, + 5429, 5484, 5483, -1, 5484, 5429, 5428, -1, + 5428, 5485, 5484, -1, 5485, 5428, 5427, -1, + 5427, 5486, 5485, -1, 5486, 5427, 5426, -1, + 5426, 5487, 5486, -1, 5487, 5426, 5425, -1, + 5425, 5488, 5487, -1, 5488, 5425, 5424, -1, + 5424, 5489, 5488, -1, 5489, 5424, 5423, -1, + 5423, 5490, 5489, -1, 5490, 5423, 5422, -1, + 5422, 5491, 5490, -1, 5491, 5422, 5421, -1, + 5421, 5492, 5491, -1, 5492, 5421, 5420, -1, + 5420, 5493, 5492, -1, 5493, 5420, 5419, -1, + 5419, 5494, 5493, -1, 5494, 5419, 5418, -1, + 5418, 5495, 5494, -1, 5495, 5418, 5417, -1, + 5417, 5496, 5495, -1, 5496, 5417, 5416, -1, + 5416, 5497, 5496, -1, 5497, 5416, 5415, -1, + 5415, 5498, 5497, -1, 5498, 5415, 5414, -1, + 5414, 5499, 5498, -1, 5499, 5414, 5413, -1, + 5413, 5500, 5499, -1, 5500, 5413, 5412, -1, + 5412, 5501, 5500, -1, 5501, 5412, 5411, -1, + 5411, 5502, 5501, -1, 5502, 5411, 5410, -1, + 5410, 5503, 5502, -1, 5503, 5410, 5409, -1, + 5409, 5504, 5503, -1, 5504, 5409, 5408, -1, + 5408, 5505, 5504, -1, 5505, 5408, 5407, -1, + 5407, 5506, 5505, -1, 5506, 5407, 5406, -1, + 5406, 5507, 5506, -1, 5507, 5406, 5405, -1, + 5405, 5508, 5507, -1, 5508, 5405, 5404, -1, + 5404, 5509, 5508, -1, 5510, 5511, 5512, -1, + 5510, 5512, 5509, -1, 5509, 5404, 5510, -1, + 5513, 5514, 5510, -1, 5513, 5510, 5404, -1, + 5513, 5404, 5399, -1, 5513, 5399, 5402, -1, + 5402, 5514, 5513, -1, 5514, 5402, 5398, -1, + 5398, 5515, 5514, -1, 5515, 5398, 5388, -1, + 5515, 5388, 5387, -1, 5515, 5387, 5516, -1, + 5516, 5514, 5515, -1, 5516, 5510, 5514, -1, + 5516, 5511, 5510, -1, 5511, 5516, 5387, -1, + 5387, 5517, 5511, -1, 5517, 5387, 5386, -1, + 5386, 5518, 5517, -1, 5518, 5386, 5390, -1, + 5390, 5519, 5518, -1, 5519, 5390, 5391, -1, + 5391, 5520, 5519, -1, 5521, 5522, 5520, -1, + 5520, 5391, 5521, -1, 5523, 5521, 5391, -1, + 5523, 5391, 5393, -1, 5393, 5524, 5523, -1, + 5393, 5525, 5524, -1, 5525, 5393, 5392, -1, + 5525, 5392, 5397, -1, 5397, 5524, 5525, -1, + 5397, 5395, 5524, -1, 5395, 5394, 5524, -1, + 5394, 5526, 5524, -1, 5394, 5396, 5526, -1, + 5396, 5527, 5526, -1, 5527, 5396, 5385, -1, + 5385, 5229, 5527, -1, 5528, 5527, 5229, -1, + 5229, 5228, 5528, -1, 5218, 5528, 5228, -1, + 5228, 5223, 5218, -1, 5223, 5228, 5231, -1, + 5231, 5219, 5223, -1, 5231, 5529, 5219, -1, + 5530, 5531, 5532, -1, 5531, 5530, 5533, -1, + 5533, 5534, 5531, -1, 5534, 5533, 5535, -1, + 5535, 5536, 5534, -1, 5536, 5535, 5537, -1, + 5537, 5538, 5536, -1, 5538, 5537, 5529, -1, + 5529, 5539, 5538, -1, 5539, 5529, 5231, -1, + 5539, 5231, 5232, -1, 5539, 5232, 5235, -1, + 5235, 5538, 5539, -1, 5538, 5235, 5236, -1, + 5236, 5536, 5538, -1, 5536, 5236, 5237, -1, + 5237, 5534, 5536, -1, 5534, 5237, 5238, -1, + 5238, 5531, 5534, -1, 5531, 5238, 5239, -1, + 5239, 5532, 5531, -1, 5532, 5239, 5375, -1, + 5375, 5540, 5532, -1, 5540, 5375, 5373, -1, + 5373, 5541, 5540, -1, 5541, 5373, 5371, -1, + 5371, 5542, 5541, -1, 5542, 5371, 5369, -1, + 5369, 5543, 5542, -1, 5543, 5369, 5241, -1, + 5241, 5240, 5543, -1, 5544, 5543, 5240, -1, + 5240, 5545, 5544, -1, 5545, 5240, 5243, -1, + 5243, 5546, 5545, -1, 5546, 5243, 5245, -1, + 5245, 5547, 5546, -1, 5547, 5245, 5247, -1, + 5247, 5548, 5547, -1, 5548, 5247, 5249, -1, + 5249, 5549, 5548, -1, 5549, 5249, 5251, -1, + 5251, 5550, 5549, -1, 5550, 5251, 5253, -1, + 5253, 5551, 5550, -1, 5551, 5253, 5255, -1, + 5255, 5552, 5551, -1, 5552, 5255, 5257, -1, + 5257, 5553, 5552, -1, 5553, 5257, 5259, -1, + 5259, 5554, 5553, -1, 5554, 5259, 5261, -1, + 5261, 5555, 5554, -1, 5555, 5261, 5263, -1, + 5263, 5556, 5555, -1, 5556, 5263, 5265, -1, + 5265, 5557, 5556, -1, 5557, 5265, 5267, -1, + 5267, 5558, 5557, -1, 5558, 5267, 5269, -1, + 5269, 5559, 5558, -1, 5559, 5269, 5271, -1, + 5271, 5560, 5559, -1, 5560, 5271, 5273, -1, + 5273, 5561, 5560, -1, 5561, 5273, 5275, -1, + 5275, 5562, 5561, -1, 5562, 5275, 5277, -1, + 5277, 5563, 5562, -1, 5563, 5277, 5279, -1, + 5279, 5564, 5563, -1, 5564, 5279, 5281, -1, + 5281, 5565, 5564, -1, 5565, 5281, 5283, -1, + 5283, 5566, 5565, -1, 5566, 5283, 5285, -1, + 5285, 5567, 5566, -1, 5567, 5285, 5287, -1, + 5287, 5568, 5567, -1, 5568, 5287, 5289, -1, + 5289, 5569, 5568, -1, 5569, 5289, 5291, -1, + 5291, 5570, 5569, -1, 5570, 5291, 5293, -1, + 5293, 5571, 5570, -1, 5571, 5293, 5295, -1, + 5295, 5572, 5571, -1, 5572, 5295, 5297, -1, + 5297, 5573, 5572, -1, 5573, 5297, 5299, -1, + 5299, 5574, 5573, -1, 5574, 5299, 5301, -1, + 5301, 5575, 5574, -1, 5575, 5301, 5303, -1, + 5303, 5576, 5575, -1, 5576, 5303, 5305, -1, + 5305, 5577, 5576, -1, 5577, 5305, 5307, -1, + 5307, 5578, 5577, -1, 5578, 5307, 5309, -1, + 5309, 5579, 5578, -1, 5579, 5309, 5311, -1, + 5311, 5580, 5579, -1, 5580, 5311, 5313, -1, + 5313, 5581, 5580, -1, 5581, 5313, 5315, -1, + 5315, 5582, 5581, -1, 5582, 5315, 5317, -1, + 5317, 5583, 5582, -1, 5583, 5317, 5319, -1, + 5319, 5584, 5583, -1, 5584, 5319, 5321, -1, + 5321, 5585, 5584, -1, 5585, 5321, 5323, -1, + 5323, 5586, 5585, -1, 5586, 5323, 5214, -1, + 5214, 5587, 5586, -1, 5587, 5214, 5211, -1, + 5588, 5587, 5211, -1, 5211, 5213, 5588, -1, + 5588, 5213, 5589, -1, 5589, 5587, 5588, -1, + 5589, 5590, 5587, -1, 5590, 5589, 5213, -1, + 5213, 525, 5590, -1, 5591, 5592, 5593, -1, + 5591, 5594, 5592, -1, 5591, 5595, 5594, -1, + 5591, 5593, 5595, -1, 5596, 5597, 5593, -1, + 5597, 5595, 5593, -1, 5598, 5599, 5600, -1, + 5598, 5601, 5599, -1, 5602, 5603, 5604, -1, + 5604, 5605, 5602, -1, 5606, 5607, 5608, -1, + 5607, 5606, 5609, -1, 5609, 5610, 5607, -1, + 5610, 5609, 5611, -1, 5611, 5612, 5610, -1, + 5612, 5611, 5613, -1, 5613, 5614, 5612, -1, + 5614, 5613, 5615, -1, 5615, 5616, 5614, -1, + 5616, 5615, 5617, -1, 5617, 5618, 5616, -1, + 5618, 5617, 5619, -1, 5619, 5620, 5618, -1, + 5620, 5619, 5621, -1, 5621, 5622, 5620, -1, + 5622, 5621, 5623, -1, 5623, 5624, 5622, -1, + 5624, 5623, 5625, -1, 5625, 5626, 5624, -1, + 5626, 5625, 5627, -1, 5627, 5628, 5626, -1, + 5628, 5627, 5629, -1, 5629, 5605, 5628, -1, + 5605, 5629, 5630, -1, 5630, 5602, 5605, -1, + 5602, 5630, 5631, -1, 5602, 5631, 5632, -1, + 5633, 5632, 5631, -1, 5634, 5633, 5631, -1, + 5634, 5631, 5635, -1, 5635, 5636, 5634, -1, + 5635, 5637, 5636, -1, 5638, 5639, 5640, -1, + 5639, 5638, 5641, -1, 5641, 5642, 5639, -1, + 5642, 5641, 5643, -1, 5643, 5644, 5642, -1, + 5644, 5643, 5645, -1, 5645, 5646, 5644, -1, + 5646, 5645, 5647, -1, 5647, 5648, 5646, -1, + 5648, 5647, 5649, -1, 5649, 5650, 5648, -1, + 5650, 5649, 5651, -1, 5651, 5652, 5650, -1, + 5652, 5651, 5653, -1, 5653, 5654, 5652, -1, + 5654, 5653, 5655, -1, 5655, 5656, 5654, -1, + 5656, 5655, 5657, -1, 5657, 5658, 5656, -1, + 5658, 5657, 5659, -1, 5659, 5660, 5658, -1, + 5660, 5659, 5661, -1, 5661, 5662, 5660, -1, + 5662, 5661, 5663, -1, 5663, 5664, 5662, -1, + 5664, 5663, 5665, -1, 5665, 5666, 5664, -1, + 5666, 5665, 5667, -1, 5667, 5668, 5666, -1, + 5668, 5667, 5669, -1, 5668, 5669, 5670, -1, + 5671, 5672, 5636, -1, 5636, 5672, 5673, -1, + 5674, 5675, 5673, -1, 5674, 5673, 5672, -1, + 5672, 5669, 5674, -1, 5672, 5671, 5669, -1, + 5671, 5670, 5669, -1, 5670, 5671, 5636, -1, + 5670, 5636, 5637, -1, 5637, 5668, 5670, -1, + 5637, 5635, 5668, -1, 5668, 5635, 5631, -1, + 5631, 5666, 5668, -1, 5666, 5631, 5630, -1, + 5630, 5664, 5666, -1, 5664, 5630, 5629, -1, + 5629, 5662, 5664, -1, 5662, 5629, 5627, -1, + 5627, 5660, 5662, -1, 5660, 5627, 5625, -1, + 5625, 5658, 5660, -1, 5658, 5625, 5623, -1, + 5623, 5656, 5658, -1, 5656, 5623, 5621, -1, + 5621, 5654, 5656, -1, 5654, 5621, 5619, -1, + 5619, 5652, 5654, -1, 5652, 5619, 5617, -1, + 5617, 5650, 5652, -1, 5650, 5617, 5615, -1, + 5615, 5648, 5650, -1, 5648, 5615, 5613, -1, + 5613, 5646, 5648, -1, 5646, 5613, 5611, -1, + 5611, 5644, 5646, -1, 5644, 5611, 5609, -1, + 5609, 5642, 5644, -1, 5642, 5609, 5606, -1, + 5606, 5639, 5642, -1, 5639, 5606, 5608, -1, + 5608, 5640, 5639, -1, 5640, 5608, 5676, -1, + 5676, 5677, 5640, -1, 5677, 5676, 5678, -1, + 5679, 5680, 5681, -1, 5680, 5679, 5678, -1, + 5678, 5682, 5680, -1, 5682, 5678, 5676, -1, + 5676, 5683, 5682, -1, 5683, 5676, 5608, -1, + 5608, 5684, 5683, -1, 5684, 5608, 5607, -1, + 5607, 5685, 5684, -1, 5685, 5607, 5610, -1, + 5610, 5686, 5685, -1, 5686, 5610, 5612, -1, + 5612, 5687, 5686, -1, 5687, 5612, 5614, -1, + 5614, 5688, 5687, -1, 5688, 5614, 5616, -1, + 5616, 5689, 5688, -1, 5689, 5616, 5618, -1, + 5618, 5690, 5689, -1, 5690, 5618, 5620, -1, + 5620, 5691, 5690, -1, 5691, 5620, 5622, -1, + 5622, 5692, 5691, -1, 5692, 5622, 5624, -1, + 5624, 5693, 5692, -1, 5693, 5624, 5626, -1, + 5626, 5694, 5693, -1, 5694, 5626, 5628, -1, + 5628, 5695, 5694, -1, 5695, 5628, 5605, -1, + 5605, 5604, 5695, -1, 5696, 5697, 5604, -1, + 5698, 5604, 5697, -1, 5698, 5695, 5604, -1, + 5695, 5698, 5699, -1, 5699, 5694, 5695, -1, + 5694, 5699, 5700, -1, 5700, 5693, 5694, -1, + 5693, 5700, 5701, -1, 5701, 5692, 5693, -1, + 5692, 5701, 5702, -1, 5702, 5691, 5692, -1, + 5691, 5702, 5703, -1, 5703, 5690, 5691, -1, + 5690, 5703, 5704, -1, 5704, 5689, 5690, -1, + 5689, 5704, 5705, -1, 5705, 5688, 5689, -1, + 5688, 5705, 5706, -1, 5706, 5687, 5688, -1, + 5687, 5706, 5707, -1, 5707, 5686, 5687, -1, + 5686, 5707, 5708, -1, 5708, 5685, 5686, -1, + 5685, 5708, 5709, -1, 5709, 5684, 5685, -1, + 5684, 5709, 5710, -1, 5710, 5683, 5684, -1, + 5683, 5710, 5711, -1, 5711, 5682, 5683, -1, + 5682, 5711, 5712, -1, 5712, 5680, 5682, -1, + 5680, 5712, 5713, -1, 5713, 5681, 5680, -1, + 5681, 5713, 5714, -1, 5714, 5715, 5681, -1, + 5715, 5714, 5716, -1, 5716, 5717, 5715, -1, + 5717, 5716, 5718, -1, 5718, 5719, 5717, -1, + 5719, 5718, 5720, -1, 5720, 5721, 5719, -1, + 5721, 5720, 5722, -1, 5722, 5723, 5721, -1, + 5723, 5722, 5724, -1, 5724, 5725, 5723, -1, + 5726, 5727, 5728, -1, 5727, 5726, 5725, -1, + 5725, 5724, 5727, -1, 5729, 5727, 5724, -1, + 5724, 5730, 5729, -1, 5730, 5724, 5722, -1, + 5722, 5731, 5730, -1, 5731, 5722, 5720, -1, + 5720, 5732, 5731, -1, 5732, 5720, 5718, -1, + 5718, 5733, 5732, -1, 5733, 5718, 5716, -1, + 5716, 5734, 5733, -1, 5734, 5716, 5714, -1, + 5714, 5735, 5734, -1, 5735, 5714, 5713, -1, + 5713, 5736, 5735, -1, 5736, 5713, 5712, -1, + 5712, 5737, 5736, -1, 5737, 5712, 5711, -1, + 5711, 5738, 5737, -1, 5738, 5711, 5710, -1, + 5710, 5739, 5738, -1, 5739, 5710, 5709, -1, + 5709, 5740, 5739, -1, 5740, 5709, 5708, -1, + 5708, 5741, 5740, -1, 5741, 5708, 5707, -1, + 5707, 5742, 5741, -1, 5742, 5707, 5706, -1, + 5706, 5743, 5742, -1, 5743, 5706, 5705, -1, + 5705, 5744, 5743, -1, 5744, 5705, 5704, -1, + 5704, 5745, 5744, -1, 5745, 5704, 5703, -1, + 5703, 5746, 5745, -1, 5746, 5703, 5702, -1, + 5702, 5747, 5746, -1, 5747, 5702, 5701, -1, + 5701, 5748, 5747, -1, 5748, 5701, 5700, -1, + 5700, 5601, 5748, -1, 5601, 5700, 5699, -1, + 5699, 5599, 5601, -1, 5599, 5699, 5698, -1, + 5599, 5698, 5749, -1, 5750, 5749, 5698, -1, + 5750, 5751, 5749, -1, 5752, 5751, 5750, -1, + 5750, 5698, 5752, -1, 5752, 5698, 5697, -1, + 5697, 5751, 5752, -1, 5697, 5696, 5751, -1, + 5751, 5753, 5754, -1, 5753, 5751, 5696, -1, + 5696, 5604, 5753, -1, 5753, 5604, 5603, -1, + 5603, 5754, 5753, -1, 5603, 5755, 5754, -1, + 5755, 5603, 5602, -1, 5755, 5602, 5632, -1, + 5632, 5754, 5755, -1, 5632, 5633, 5754, -1, + 5633, 5634, 5754, -1, 5754, 5634, 5636, -1, + 5756, 5757, 5758, -1, 5756, 5758, 5759, -1, + 5759, 5760, 5756, -1, 5759, 5761, 5760, -1, + 5761, 5759, 5673, -1, 5673, 5759, 5758, -1, + 5758, 5762, 5595, -1, 5763, 5762, 5758, -1, + 5757, 5756, 5764, -1, 5764, 5756, 5760, -1, + 5760, 5765, 5764, -1, 5765, 5760, 5766, -1, + 5766, 5767, 5765, -1, 5767, 5766, 5768, -1, + 5768, 5769, 5767, -1, 5769, 5768, 5770, -1, + 5770, 5771, 5769, -1, 5771, 5770, 5772, -1, + 5772, 5773, 5771, -1, 5773, 5772, 5774, -1, + 5774, 5775, 5773, -1, 5775, 5774, 5776, -1, + 5776, 5777, 5775, -1, 5777, 5776, 5778, -1, + 5778, 5779, 5777, -1, 5779, 5778, 5780, -1, + 5780, 5781, 5779, -1, 5781, 5780, 5782, -1, + 5782, 5783, 5781, -1, 5783, 5782, 5784, -1, + 5784, 5785, 5783, -1, 5785, 5784, 5786, -1, + 5786, 5787, 5785, -1, 5787, 5786, 5788, -1, + 5788, 5789, 5787, -1, 5789, 5788, 5790, -1, + 5790, 5791, 5789, -1, 5791, 5790, 5792, -1, + 5792, 5793, 5791, -1, 5793, 5792, 5794, -1, + 5794, 5795, 5793, -1, 5795, 5794, 5796, -1, + 5796, 5797, 5795, -1, 5797, 5796, 5798, -1, + 5798, 5799, 5797, -1, 5799, 5798, 5800, -1, + 5800, 5801, 5799, -1, 5801, 5800, 5802, -1, + 5802, 5803, 5801, -1, 5803, 5802, 5804, -1, + 5804, 5805, 5803, -1, 5805, 5804, 5806, -1, + 5806, 5807, 5805, -1, 5807, 5806, 5808, -1, + 5808, 5809, 5807, -1, 5809, 5808, 5810, -1, + 5810, 5811, 5809, -1, 5811, 5810, 5812, -1, + 5812, 5813, 5811, -1, 5813, 5812, 5814, -1, + 5814, 5815, 5813, -1, 5815, 5814, 5816, -1, + 5816, 5817, 5815, -1, 5817, 5816, 5818, -1, + 5818, 5819, 5817, -1, 5819, 5818, 5820, -1, + 5820, 5821, 5819, -1, 5821, 5820, 5822, -1, + 5822, 5823, 5821, -1, 5823, 5822, 5824, -1, + 5824, 5825, 5823, -1, 5825, 5824, 5826, -1, + 5826, 5827, 5825, -1, 5827, 5826, 5828, -1, + 5828, 5829, 5827, -1, 5829, 5828, 5830, -1, + 5830, 5831, 5829, -1, 5831, 5830, 5832, -1, + 5832, 5833, 5831, -1, 5833, 5832, 5834, -1, + 5834, 5835, 5833, -1, 5835, 5834, 5836, -1, + 5836, 5837, 5835, -1, 5837, 5836, 5838, -1, + 5838, 5839, 5837, -1, 5839, 5838, 5840, -1, + 5840, 5841, 5839, -1, 5841, 5840, 5842, -1, + 5842, 5843, 5841, -1, 5843, 5842, 5844, -1, + 5844, 5845, 5843, -1, 5845, 5844, 5846, -1, + 5846, 5847, 5845, -1, 5847, 5846, 5848, -1, + 5848, 5849, 5847, -1, 5849, 5848, 5850, -1, + 5850, 5851, 5849, -1, 5851, 5850, 5852, -1, + 5852, 5853, 5851, -1, 5853, 5852, 5854, -1, + 5854, 5855, 5853, -1, 5855, 5854, 5856, -1, + 5856, 5857, 5855, -1, 5857, 5856, 5858, -1, + 5858, 5859, 5857, -1, 5859, 5858, 5860, -1, + 5860, 5861, 5859, -1, 5861, 5860, 5862, -1, + 5862, 5863, 5861, -1, 5863, 5862, 5864, -1, + 5864, 5865, 5863, -1, 5865, 5864, 5866, -1, + 5866, 5867, 5865, -1, 5867, 5866, 5868, -1, + 5868, 5869, 5867, -1, 5869, 5868, 4801, -1, + 4801, 5870, 5869, -1, 4801, 4800, 5870, -1, + 5871, 5870, 4800, -1, 4800, 5872, 5871, -1, + 5872, 4800, 4798, -1, 4798, 5873, 5872, -1, + 5873, 4798, 4796, -1, 4796, 5874, 5873, -1, + 5874, 4796, 4794, -1, 4794, 5875, 5874, -1, + 5875, 4794, 4792, -1, 4792, 5876, 5875, -1, + 5876, 4792, 4790, -1, 4790, 5877, 5876, -1, + 5877, 4790, 4788, -1, 4788, 5878, 5877, -1, + 5878, 4788, 4786, -1, 4786, 5879, 5878, -1, + 5879, 4786, 4784, -1, 4784, 5880, 5879, -1, + 5880, 4784, 4782, -1, 4782, 5881, 5880, -1, + 5881, 4782, 4780, -1, 4780, 5882, 5881, -1, + 5882, 4780, 4778, -1, 4778, 5883, 5882, -1, + 5883, 4778, 4776, -1, 4776, 5884, 5883, -1, + 5884, 4776, 4774, -1, 4774, 5885, 5884, -1, + 5885, 4774, 4772, -1, 4772, 5886, 5885, -1, + 5886, 4772, 4770, -1, 4770, 5887, 5886, -1, + 5887, 4770, 4768, -1, 4768, 5888, 5887, -1, + 5888, 4768, 4766, -1, 4766, 5889, 5888, -1, + 5889, 4766, 4764, -1, 4764, 5890, 5889, -1, + 5890, 4764, 4762, -1, 4762, 5891, 5890, -1, + 5891, 4762, 4760, -1, 4760, 5892, 5891, -1, + 5892, 4760, 4758, -1, 4758, 5893, 5892, -1, + 5893, 4758, 4756, -1, 4756, 5894, 5893, -1, + 5894, 4756, 4754, -1, 4754, 5895, 5894, -1, + 5895, 4754, 4752, -1, 4752, 5896, 5895, -1, + 5896, 4752, 4751, -1, 4751, 5897, 5896, -1, + 5897, 4751, 5898, -1, 5898, 5899, 5897, -1, + 5899, 5898, 5900, -1, 5900, 5901, 5899, -1, + 5901, 5900, 5902, -1, 5902, 5903, 5901, -1, + 5903, 5902, 5904, -1, 5904, 5905, 5903, -1, + 5905, 5904, 5906, -1, 5906, 5907, 5905, -1, + 5907, 5906, 5908, -1, 5908, 5909, 5907, -1, + 5909, 5908, 5910, -1, 5910, 5911, 5909, -1, + 5911, 5910, 5912, -1, 5912, 5913, 5911, -1, + 5913, 5912, 5914, -1, 5914, 5915, 5913, -1, + 5915, 5914, 5916, -1, 5916, 5917, 5915, -1, + 5917, 5916, 5918, -1, 5918, 5919, 5917, -1, + 5919, 5918, 5920, -1, 5920, 5921, 5919, -1, + 5921, 5920, 5922, -1, 5922, 5923, 5921, -1, + 5923, 5922, 5924, -1, 5924, 5925, 5923, -1, + 5925, 5924, 5926, -1, 5926, 5927, 5925, -1, + 5927, 5926, 5928, -1, 5928, 5929, 5927, -1, + 5929, 5928, 5930, -1, 5930, 5931, 5929, -1, + 5931, 5930, 5932, -1, 5932, 5933, 5931, -1, + 5933, 5932, 5934, -1, 5934, 5935, 5933, -1, + 5935, 5934, 5936, -1, 5936, 5937, 5935, -1, + 5937, 5936, 5938, -1, 5938, 5939, 5937, -1, + 5939, 5938, 5940, -1, 5940, 5941, 5939, -1, + 5941, 5940, 5942, -1, 5942, 5943, 5941, -1, + 5943, 5942, 5944, -1, 5944, 5945, 5943, -1, + 5945, 5944, 5946, -1, 5946, 5947, 5945, -1, + 5947, 5946, 5948, -1, 5948, 5949, 5947, -1, + 5950, 5951, 5949, -1, 5949, 5948, 5950, -1, + 4749, 5950, 5948, -1, 5948, 4747, 4749, -1, + 4747, 5948, 5946, -1, 5946, 4745, 4747, -1, + 4745, 5946, 5944, -1, 5944, 4743, 4745, -1, + 4743, 5944, 5942, -1, 5942, 4741, 4743, -1, + 4741, 5942, 5940, -1, 5940, 4739, 4741, -1, + 4739, 5940, 5938, -1, 5938, 4737, 4739, -1, + 4737, 5938, 5936, -1, 5936, 4735, 4737, -1, + 4735, 5936, 5934, -1, 5934, 4733, 4735, -1, + 4733, 5934, 5932, -1, 5932, 4731, 4733, -1, + 4731, 5932, 5930, -1, 5930, 4729, 4731, -1, + 4729, 5930, 5928, -1, 5928, 4727, 4729, -1, + 4727, 5928, 5926, -1, 5926, 4725, 4727, -1, + 4725, 5926, 5924, -1, 5924, 4723, 4725, -1, + 4723, 5924, 5922, -1, 5922, 4721, 4723, -1, + 4721, 5922, 5920, -1, 5920, 4719, 4721, -1, + 4719, 5920, 5918, -1, 5918, 4718, 4719, -1, + 4718, 5918, 5916, -1, 5916, 4715, 4718, -1, + 4715, 5916, 5914, -1, 5914, 4712, 4715, -1, + 4712, 5914, 5912, -1, 5912, 4713, 4712, -1, + 4713, 5912, 5910, -1, 5910, 5952, 4713, -1, + 5952, 5910, 5908, -1, 5908, 5953, 5952, -1, + 5953, 5908, 5906, -1, 5906, 5954, 5953, -1, + 5954, 5906, 5904, -1, 5904, 5955, 5954, -1, + 5955, 5904, 5902, -1, 5902, 5956, 5955, -1, + 5956, 5902, 5900, -1, 5900, 5957, 5956, -1, + 5957, 5900, 5898, -1, 5898, 5958, 5957, -1, + 5958, 5898, 4751, -1, 4751, 4750, 5958, -1, + 5958, 4750, 5959, -1, 5959, 5957, 5958, -1, + 5957, 5959, 5960, -1, 5960, 5956, 5957, -1, + 5956, 5960, 5961, -1, 5961, 5955, 5956, -1, + 5955, 5961, 5962, -1, 5962, 5954, 5955, -1, + 5954, 5962, 5963, -1, 5963, 5953, 5954, -1, + 5953, 5963, 5964, -1, 5964, 5952, 5953, -1, + 5952, 5964, 5965, -1, 5965, 4713, 5952, -1, + 4713, 5965, 5966, -1, 5966, 4714, 4713, -1, + 4714, 5966, 5967, -1, 5967, 4716, 4714, -1, + 4716, 5967, 4711, -1, 4711, 5968, 4716, -1, + 5968, 4711, 4710, -1, 4710, 5969, 5968, -1, + 5969, 4710, 4708, -1, 4708, 5970, 5969, -1, + 5970, 4708, 4706, -1, 4706, 5971, 5970, -1, + 5971, 4706, 4704, -1, 4704, 5972, 5971, -1, + 5972, 4704, 4702, -1, 4702, 5973, 5972, -1, + 5973, 4702, 4700, -1, 4700, 5974, 5973, -1, + 5974, 4700, 4698, -1, 4698, 5975, 5974, -1, + 5975, 4698, 4696, -1, 4696, 5976, 5975, -1, + 5976, 4696, 4694, -1, 4694, 5977, 5976, -1, + 5977, 4694, 4692, -1, 4692, 5978, 5977, -1, + 5978, 4692, 4690, -1, 4690, 5979, 5978, -1, + 5979, 4690, 4688, -1, 4688, 5980, 5979, -1, + 5980, 4688, 4686, -1, 4686, 5981, 5980, -1, + 5981, 4686, 4683, -1, 4683, 5982, 5981, -1, + 5982, 4683, 4682, -1, 5983, 5984, 5985, -1, + 5984, 5983, 5982, -1, 5984, 5982, 4682, -1, + 4682, 5985, 5984, -1, 4682, 4681, 5985, -1, + 523, 520, 5986, -1, 520, 3569, 5987, -1, + 5985, 523, 5988, -1, 5989, 5985, 4681, -1, + 5990, 5989, 4681, -1, 4681, 4683, 5990, -1, + 5990, 4683, 4685, -1, 4685, 5989, 5990, -1, + 4685, 5991, 5989, -1, 5991, 4685, 4684, -1, + 5992, 5991, 4684, -1, 5992, 5989, 5991, -1, + 5992, 5993, 5989, -1, 5992, 4684, 5993, -1, + 4463, 5993, 4684, -1, 4463, 4684, 4687, -1, + 4687, 4680, 4463, -1, 4680, 4687, 4689, -1, + 4689, 4679, 4680, -1, 4679, 4689, 4691, -1, + 4691, 4678, 4679, -1, 4678, 4691, 4693, -1, + 4693, 4677, 4678, -1, 4677, 4693, 4695, -1, + 4695, 4676, 4677, -1, 4676, 4695, 4697, -1, + 4697, 4675, 4676, -1, 4675, 4697, 4699, -1, + 4699, 4674, 4675, -1, 4674, 4699, 4701, -1, + 4701, 4673, 4674, -1, 4673, 4701, 4703, -1, + 4703, 4672, 4673, -1, 4672, 4703, 4705, -1, + 4705, 4671, 4672, -1, 4671, 4705, 4707, -1, + 4707, 4670, 4671, -1, 4670, 4707, 4709, -1, + 4709, 4669, 4670, -1, 4669, 4709, 4711, -1, + 4711, 4668, 4669, -1, 4668, 4711, 5967, -1, + 5967, 4667, 4668, -1, 4667, 5967, 5966, -1, + 5966, 4666, 4667, -1, 4666, 5966, 5965, -1, + 5965, 4665, 4666, -1, 4665, 5965, 5964, -1, + 5964, 4664, 4665, -1, 4664, 5964, 5963, -1, + 5963, 4663, 4664, -1, 4663, 5963, 5962, -1, + 5962, 4662, 4663, -1, 4662, 5962, 5961, -1, + 5961, 4661, 4662, -1, 4661, 5961, 5960, -1, + 5960, 4660, 4661, -1, 4660, 5960, 5959, -1, + 5959, 4563, 4660, -1, 4563, 5959, 4750, -1, + 4750, 4564, 4563, -1, 4564, 4750, 4753, -1, + 4753, 4566, 4564, -1, 4566, 4753, 4755, -1, + 4755, 4568, 4566, -1, 4568, 4755, 4757, -1, + 4757, 4570, 4568, -1, 4570, 4757, 4759, -1, + 4759, 4572, 4570, -1, 4572, 4759, 4761, -1, + 4761, 4574, 4572, -1, 4574, 4761, 4763, -1, + 4763, 4576, 4574, -1, 4576, 4763, 4765, -1, + 4765, 4578, 4576, -1, 4578, 4765, 4767, -1, + 4767, 4580, 4578, -1, 4580, 4767, 4769, -1, + 4769, 4582, 4580, -1, 4582, 4769, 4771, -1, + 4771, 4584, 4582, -1, 4584, 4771, 4773, -1, + 4773, 4586, 4584, -1, 4586, 4773, 4775, -1, + 4775, 4588, 4586, -1, 4588, 4775, 4777, -1, + 4777, 4590, 4588, -1, 4590, 4777, 4779, -1, + 4779, 4592, 4590, -1, 4592, 4779, 4781, -1, + 4781, 4594, 4592, -1, 4594, 4781, 4783, -1, + 4783, 4596, 4594, -1, 4596, 4783, 4785, -1, + 4785, 4598, 4596, -1, 4598, 4785, 4787, -1, + 4787, 4600, 4598, -1, 4600, 4787, 4789, -1, + 4789, 4602, 4600, -1, 4602, 4789, 4791, -1, + 4791, 4561, 4602, -1, 4561, 4791, 4793, -1, + 4793, 4559, 4561, -1, 4559, 4793, 4795, -1, + 4795, 4557, 4559, -1, 4557, 4795, 4797, -1, + 4797, 4555, 4557, -1, 4555, 4797, 4799, -1, + 4799, 4554, 4555, -1, 4554, 4799, 4801, -1, + 4554, 4801, 5868, -1, 5868, 4552, 4554, -1, + 4552, 5868, 5866, -1, 5866, 4550, 4552, -1, + 4550, 5866, 5864, -1, 5864, 4548, 4550, -1, + 4548, 5864, 5862, -1, 5862, 4545, 4548, -1, + 4545, 5862, 5860, -1, 5860, 4546, 4545, -1, + 4546, 5860, 5858, -1, 5858, 5994, 4546, -1, + 5994, 5858, 5856, -1, 5856, 5995, 5994, -1, + 5995, 5856, 5854, -1, 5854, 5996, 5995, -1, + 5996, 5854, 5852, -1, 5852, 5997, 5996, -1, + 5997, 5852, 5850, -1, 5850, 5998, 5997, -1, + 5998, 5850, 5848, -1, 5848, 5999, 5998, -1, + 5999, 5848, 5846, -1, 5846, 6000, 5999, -1, + 6000, 5846, 5844, -1, 5844, 6001, 6000, -1, + 6001, 5844, 5842, -1, 5842, 6002, 6001, -1, + 6002, 5842, 5840, -1, 5840, 6003, 6002, -1, + 6003, 5840, 5838, -1, 5838, 6004, 6003, -1, + 6004, 5838, 5836, -1, 5836, 6005, 6004, -1, + 6005, 5836, 5834, -1, 5834, 6006, 6005, -1, + 6006, 5834, 5832, -1, 5832, 6007, 6006, -1, + 6007, 5832, 5830, -1, 5830, 6008, 6007, -1, + 6008, 5830, 5828, -1, 5828, 6009, 6008, -1, + 6009, 5828, 5826, -1, 5826, 6010, 6009, -1, + 6010, 5826, 5824, -1, 5824, 6011, 6010, -1, + 6011, 5824, 5822, -1, 5822, 6012, 6011, -1, + 6012, 5822, 5820, -1, 5820, 6013, 6012, -1, + 6013, 5820, 5818, -1, 5818, 6014, 6013, -1, + 6014, 5818, 5816, -1, 5816, 6015, 6014, -1, + 6015, 5816, 5814, -1, 5814, 6016, 6015, -1, + 6016, 5814, 5812, -1, 5812, 6017, 6016, -1, + 6017, 5812, 5810, -1, 5810, 6018, 6017, -1, + 6018, 5810, 5808, -1, 5808, 6019, 6018, -1, + 6019, 5808, 5806, -1, 5806, 6020, 6019, -1, + 6020, 5806, 5804, -1, 5804, 6021, 6020, -1, + 6021, 5804, 5802, -1, 5802, 6022, 6021, -1, + 6022, 5802, 5800, -1, 5800, 6023, 6022, -1, + 6023, 5800, 5798, -1, 5798, 6024, 6023, -1, + 6024, 5798, 5796, -1, 5796, 6025, 6024, -1, + 6025, 5796, 5794, -1, 5794, 6026, 6025, -1, + 6026, 5794, 5792, -1, 5792, 6027, 6026, -1, + 6027, 5792, 5790, -1, 5790, 6028, 6027, -1, + 6028, 5790, 5788, -1, 5788, 6029, 6028, -1, + 6029, 5788, 5786, -1, 5786, 6030, 6029, -1, + 6030, 5786, 5784, -1, 5784, 6031, 6030, -1, + 6031, 5784, 5782, -1, 5782, 6032, 6031, -1, + 6032, 5782, 5780, -1, 5780, 6033, 6032, -1, + 6033, 5780, 5778, -1, 5778, 6034, 6033, -1, + 6034, 5778, 5776, -1, 5776, 6035, 6034, -1, + 6035, 5776, 5774, -1, 5774, 6036, 6035, -1, + 6036, 5774, 5772, -1, 5772, 6037, 6036, -1, + 6037, 5772, 5770, -1, 5770, 6038, 6037, -1, + 6038, 5770, 5768, -1, 5768, 6039, 6038, -1, + 6039, 5768, 5766, -1, 5766, 6040, 6039, -1, + 6040, 5766, 5760, -1, 5760, 5761, 6040, -1, + 6041, 6040, 5761, -1, 6041, 5761, 5673, -1, + 6041, 5673, 5675, -1, 5675, 6040, 6041, -1, + 5675, 5674, 6040, -1, 6040, 5674, 5669, -1, + 5669, 6039, 6040, -1, 6039, 5669, 5667, -1, + 5667, 6038, 6039, -1, 6038, 5667, 5665, -1, + 5665, 6037, 6038, -1, 6037, 5665, 5663, -1, + 5663, 6036, 6037, -1, 6036, 5663, 5661, -1, + 5661, 6035, 6036, -1, 6035, 5661, 5659, -1, + 5659, 6034, 6035, -1, 6034, 5659, 5657, -1, + 5657, 6033, 6034, -1, 6033, 5657, 5655, -1, + 5655, 6032, 6033, -1, 6032, 5655, 5653, -1, + 5653, 6031, 6032, -1, 6031, 5653, 5651, -1, + 5651, 6030, 6031, -1, 6030, 5651, 5649, -1, + 5649, 6029, 6030, -1, 6029, 5649, 5647, -1, + 5647, 6028, 6029, -1, 6028, 5647, 5645, -1, + 5645, 6027, 6028, -1, 6027, 5645, 5643, -1, + 5643, 6026, 6027, -1, 6026, 5643, 5641, -1, + 5641, 6025, 6026, -1, 6025, 5641, 5638, -1, + 5638, 6024, 6025, -1, 6024, 5638, 5640, -1, + 5640, 6023, 6024, -1, 6023, 5640, 5677, -1, + 5677, 6022, 6023, -1, 6022, 5677, 5678, -1, + 5678, 6021, 6022, -1, 6021, 5678, 5679, -1, + 5679, 6020, 6021, -1, 6020, 5679, 5681, -1, + 5681, 6019, 6020, -1, 6019, 5681, 5715, -1, + 5715, 6018, 6019, -1, 6018, 5715, 5717, -1, + 5717, 6017, 6018, -1, 6017, 5717, 5719, -1, + 5719, 6016, 6017, -1, 6016, 5719, 5721, -1, + 5721, 6015, 6016, -1, 6015, 5721, 5723, -1, + 5723, 6014, 6015, -1, 6014, 5723, 5725, -1, + 5725, 6013, 6014, -1, 6013, 5725, 5726, -1, + 5726, 6012, 6013, -1, 6012, 5726, 5728, -1, + 5728, 6011, 6012, -1, 6011, 5728, 6042, -1, + 6042, 6010, 6011, -1, 6010, 6042, 6043, -1, + 6043, 6009, 6010, -1, 6009, 6043, 6044, -1, + 6044, 6008, 6009, -1, 6008, 6044, 6045, -1, + 6045, 6007, 6008, -1, 6007, 6045, 6046, -1, + 6046, 6006, 6007, -1, 6006, 6046, 6047, -1, + 6047, 6005, 6006, -1, 6005, 6047, 6048, -1, + 6048, 6004, 6005, -1, 6004, 6048, 6049, -1, + 6049, 6003, 6004, -1, 6003, 6049, 6050, -1, + 6050, 6002, 6003, -1, 6002, 6050, 6051, -1, + 6051, 6001, 6002, -1, 6001, 6051, 6052, -1, + 6052, 6000, 6001, -1, 6000, 6052, 6053, -1, + 6053, 5999, 6000, -1, 5999, 6053, 6054, -1, + 6054, 5998, 5999, -1, 5998, 6054, 6055, -1, + 6055, 5997, 5998, -1, 5997, 6055, 6056, -1, + 6056, 5996, 5997, -1, 5996, 6056, 6057, -1, + 6057, 5995, 5996, -1, 5995, 6057, 6058, -1, + 6058, 5994, 5995, -1, 5994, 6058, 6059, -1, + 6059, 4546, 5994, -1, 6059, 4544, 4546, -1, + 6059, 4542, 4544, -1, 4542, 6059, 6058, -1, + 6058, 4540, 4542, -1, 4540, 6058, 6057, -1, + 6057, 4538, 4540, -1, 4538, 6057, 6056, -1, + 6056, 4536, 4538, -1, 4536, 6056, 6055, -1, + 6055, 4534, 4536, -1, 4534, 6055, 6054, -1, + 6054, 4532, 4534, -1, 4532, 6054, 6053, -1, + 6053, 4530, 4532, -1, 4530, 6053, 6052, -1, + 6052, 4528, 4530, -1, 4528, 6052, 6051, -1, + 6051, 4526, 4528, -1, 4526, 6051, 6050, -1, + 6050, 4524, 4526, -1, 4524, 6050, 6049, -1, + 6049, 4522, 4524, -1, 4522, 6049, 6048, -1, + 6048, 4520, 4522, -1, 4520, 6048, 6047, -1, + 6047, 4518, 4520, -1, 4518, 6047, 6046, -1, + 6046, 4516, 4518, -1, 4516, 6046, 6045, -1, + 6045, 4514, 4516, -1, 4514, 6045, 6044, -1, + 6044, 4512, 4514, -1, 4512, 6044, 6043, -1, + 6043, 4510, 4512, -1, 4510, 6043, 6042, -1, + 6042, 4507, 4510, -1, 4507, 6042, 5728, -1, + 5728, 4508, 4507, -1, 4508, 5728, 5727, -1, + 5727, 5729, 4508, -1, 5729, 6060, 4508, -1, + 6060, 5729, 5730, -1, 5730, 6061, 6060, -1, + 6061, 5730, 5731, -1, 5731, 6062, 6061, -1, + 6062, 5731, 5732, -1, 5732, 6063, 6062, -1, + 6063, 5732, 5733, -1, 5733, 6064, 6063, -1, + 6064, 5733, 5734, -1, 5734, 6065, 6064, -1, + 6065, 5734, 5735, -1, 5735, 6066, 6065, -1, + 6066, 5735, 5736, -1, 5736, 6067, 6066, -1, + 6067, 5736, 5737, -1, 5737, 6068, 6067, -1, + 6068, 5737, 5738, -1, 5738, 6069, 6068, -1, + 6069, 5738, 5739, -1, 5739, 6070, 6069, -1, + 6070, 5739, 5740, -1, 5740, 6071, 6070, -1, + 6071, 5740, 5741, -1, 5741, 6072, 6071, -1, + 6072, 5741, 5742, -1, 5742, 6073, 6072, -1, + 6073, 5742, 5743, -1, 5743, 6074, 6073, -1, + 6074, 5743, 5744, -1, 5744, 6075, 6074, -1, + 6075, 5744, 5745, -1, 5745, 6076, 6075, -1, + 6076, 5745, 5746, -1, 5746, 6077, 6076, -1, + 6077, 5746, 5747, -1, 5747, 6078, 6077, -1, + 6078, 5747, 5748, -1, 5748, 6079, 6078, -1, + 6079, 5748, 5601, -1, 5601, 5598, 6079, -1, + 4097, 6079, 5598, -1, 6079, 4097, 4184, -1, + 4184, 6078, 6079, -1, 6078, 4184, 4185, -1, + 4185, 6077, 6078, -1, 6077, 4185, 4186, -1, + 4186, 6076, 6077, -1, 6076, 4186, 4187, -1, + 4187, 6075, 6076, -1, 6075, 4187, 4188, -1, + 4188, 6074, 6075, -1, 6074, 4188, 4189, -1, + 4189, 6073, 6074, -1, 6073, 4189, 4190, -1, + 4190, 6072, 6073, -1, 6072, 4190, 4191, -1, + 4191, 6071, 6072, -1, 6071, 4191, 4192, -1, + 4192, 6070, 6071, -1, 6070, 4192, 4193, -1, + 4193, 6069, 6070, -1, 6069, 4193, 4194, -1, + 4194, 6068, 6069, -1, 6068, 4194, 4195, -1, + 4195, 6067, 6068, -1, 6067, 4195, 4196, -1, + 4196, 6066, 6067, -1, 6066, 4196, 4197, -1, + 4197, 6065, 6066, -1, 6065, 4197, 4198, -1, + 4198, 6064, 6065, -1, 6064, 4198, 4199, -1, + 4199, 6063, 6064, -1, 6063, 4199, 4200, -1, + 4200, 6062, 6063, -1, 6062, 4200, 4201, -1, + 4201, 6061, 6062, -1, 6061, 4201, 4202, -1, + 4202, 6060, 6061, -1, 6060, 4202, 4142, -1, + 4142, 4508, 6060, -1, 4508, 4142, 4140, -1, + 4140, 4506, 4508, -1, 4506, 4140, 4138, -1, + 4138, 4509, 4506, -1, 4509, 4138, 4136, -1, + 4136, 4511, 4509, -1, 4511, 4136, 4134, -1, + 4134, 4513, 4511, -1, 4513, 4134, 4132, -1, + 4132, 4515, 4513, -1, 4515, 4132, 4130, -1, + 4130, 4517, 4515, -1, 4517, 4130, 4128, -1, + 4128, 4519, 4517, -1, 4519, 4128, 4126, -1, + 4126, 4521, 4519, -1, 4521, 4126, 4124, -1, + 4124, 4523, 4521, -1, 4523, 4124, 4122, -1, + 4122, 4525, 4523, -1, 4525, 4122, 4120, -1, + 4120, 4527, 4525, -1, 4527, 4120, 4118, -1, + 4118, 4529, 4527, -1, 4529, 4118, 4116, -1, + 4116, 4531, 4529, -1, 4531, 4116, 4114, -1, + 4114, 4533, 4531, -1, 4533, 4114, 4112, -1, + 4112, 4535, 4533, -1, 4535, 4112, 4110, -1, + 4110, 4537, 4535, -1, 4537, 4110, 4108, -1, + 4108, 4539, 4537, -1, 4539, 4108, 4106, -1, + 4106, 4541, 4539, -1, 4541, 4106, 4105, -1, + 4105, 4543, 4541, -1, 4105, 4611, 4543, -1, + 4105, 4104, 4611, -1, 4611, 4104, 4221, -1, + 4611, 4221, 4363, -1, 4363, 4612, 4611, -1, + 4612, 4363, 4362, -1, 4362, 4613, 4612, -1, + 4613, 4362, 4361, -1, 4361, 4614, 4613, -1, + 4361, 4615, 4614, -1, 4615, 4361, 4360, -1, + 4360, 4616, 4615, -1, 4616, 4360, 4359, -1, + 4359, 4617, 4616, -1, 4617, 4359, 4358, -1, + 4358, 4357, 4617, -1, 6080, 4357, 6081, -1, + 6080, 4617, 4357, -1, 6080, 4618, 4617, -1, + 6080, 4657, 4618, -1, 4657, 6080, 6081, -1, + 6081, 4655, 4657, -1, 4655, 6081, 6082, -1, + 6082, 4653, 4655, -1, 4653, 6082, 6083, -1, + 6083, 4651, 4653, -1, 4651, 6083, 6084, -1, + 6084, 4649, 4651, -1, 4649, 6084, 6085, -1, + 6085, 4647, 4649, -1, 4647, 6085, 6086, -1, + 6086, 4645, 4647, -1, 4645, 6086, 6087, -1, + 6087, 4643, 4645, -1, 4643, 6087, 6088, -1, + 6088, 4641, 4643, -1, 4641, 6088, 6089, -1, + 6089, 4639, 4641, -1, 4639, 6089, 6090, -1, + 6090, 4637, 4639, -1, 4637, 6090, 6091, -1, + 6091, 4635, 4637, -1, 4635, 6091, 6092, -1, + 6092, 4633, 4635, -1, 4633, 6092, 6093, -1, + 6093, 4631, 4633, -1, 4631, 6093, 6094, -1, + 6094, 4629, 4631, -1, 4629, 6094, 6095, -1, + 6095, 4627, 4629, -1, 4627, 6095, 6096, -1, + 6096, 4625, 4627, -1, 4625, 6096, 6097, -1, + 6097, 4623, 4625, -1, 4623, 6097, 6098, -1, + 6098, 4621, 4623, -1, 4621, 6098, 6099, -1, + 6099, 4619, 4621, -1, 4619, 6099, 6100, -1, + 6100, 4505, 4619, -1, 4505, 6100, 6101, -1, + 6101, 4503, 4505, -1, 4503, 6101, 6102, -1, + 6102, 4501, 4503, -1, 4501, 6102, 6103, -1, + 6103, 4499, 4501, -1, 4499, 6103, 6104, -1, + 6104, 4497, 4499, -1, 4497, 6104, 6105, -1, + 6105, 4495, 4497, -1, 4495, 6105, 6106, -1, + 6106, 4493, 4495, -1, 4493, 6106, 6107, -1, + 6107, 4491, 4493, -1, 4491, 6107, 6108, -1, + 6108, 4489, 4491, -1, 4489, 6108, 6109, -1, + 6109, 4487, 4489, -1, 4487, 6109, 6110, -1, + 6110, 4485, 4487, -1, 4485, 6110, 6111, -1, + 6111, 4483, 4485, -1, 4483, 6111, 6112, -1, + 6112, 4481, 4483, -1, 4481, 6112, 6113, -1, + 6113, 4479, 4481, -1, 4479, 6113, 6114, -1, + 6114, 4477, 4479, -1, 4477, 6114, 6115, -1, + 6115, 4475, 4477, -1, 4475, 6115, 6116, -1, + 6116, 4473, 4475, -1, 4473, 6116, 6117, -1, + 6117, 4471, 4473, -1, 4471, 6117, 6118, -1, + 6118, 4469, 4471, -1, 4469, 6118, 6119, -1, + 6119, 4467, 4469, -1, 4467, 6119, 6120, -1, + 6120, 4464, 4467, -1, 6120, 6121, 4464, -1, + 6122, 6123, 6124, -1, 6125, 6123, 6122, -1, + 6122, 6120, 6125, -1, 6122, 6124, 6120, -1, + 6124, 6121, 6120, -1, 6121, 6124, 6123, -1, + 6121, 6123, 6126, -1, 6126, 4464, 6121, -1, + 6126, 4465, 4464, -1, 6126, 6123, 4465, -1, + 6123, 6127, 4465, -1, 6128, 6129, 6127, -1, + 6129, 4465, 6127, -1, 6129, 4461, 4465, -1, + 6129, 6128, 4461, -1, 6128, 4462, 4461, -1, + 4462, 6128, 6127, -1, 4462, 6127, 6130, -1, + 6130, 4463, 4462, -1, 6130, 5993, 4463, -1, + 5993, 6130, 6127, -1, 6127, 5989, 5993, -1, + 6123, 6125, 6131, -1, 6132, 6131, 6125, -1, + 6133, 6131, 6132, -1, 6132, 6134, 6133, -1, + 6132, 6125, 6134, -1, 6134, 6125, 6120, -1, + 6134, 6120, 6119, -1, 6119, 6135, 6134, -1, + 6135, 6119, 6118, -1, 6118, 6136, 6135, -1, + 6136, 6118, 6117, -1, 6117, 6137, 6136, -1, + 6137, 6117, 6116, -1, 6116, 6138, 6137, -1, + 6138, 6116, 6115, -1, 6115, 6139, 6138, -1, + 6139, 6115, 6114, -1, 6114, 6140, 6139, -1, + 6140, 6114, 6113, -1, 6113, 6141, 6140, -1, + 6141, 6113, 6112, -1, 6112, 6142, 6141, -1, + 6142, 6112, 6111, -1, 6111, 6143, 6142, -1, + 6143, 6111, 6110, -1, 6110, 6144, 6143, -1, + 6144, 6110, 6109, -1, 6109, 6145, 6144, -1, + 6145, 6109, 6108, -1, 6108, 6146, 6145, -1, + 6146, 6108, 6107, -1, 6107, 6147, 6146, -1, + 6147, 6107, 6106, -1, 6106, 6148, 6147, -1, + 6148, 6106, 6105, -1, 6105, 6149, 6148, -1, + 6149, 6105, 6104, -1, 6104, 6150, 6149, -1, + 6150, 6104, 6103, -1, 6103, 6151, 6150, -1, + 6151, 6103, 6102, -1, 6102, 6152, 6151, -1, + 6152, 6102, 6101, -1, 6101, 6153, 6152, -1, + 6153, 6101, 6100, -1, 6100, 6154, 6153, -1, + 6154, 6100, 6099, -1, 6099, 6155, 6154, -1, + 6155, 6099, 6098, -1, 6098, 6156, 6155, -1, + 6156, 6098, 6097, -1, 6097, 6157, 6156, -1, + 6157, 6097, 6096, -1, 6096, 6158, 6157, -1, + 6158, 6096, 6095, -1, 6095, 6159, 6158, -1, + 6159, 6095, 6094, -1, 6094, 6160, 6159, -1, + 6160, 6094, 6093, -1, 6093, 6161, 6160, -1, + 6161, 6093, 6092, -1, 6092, 6162, 6161, -1, + 6162, 6092, 6091, -1, 6091, 6163, 6162, -1, + 6163, 6091, 6090, -1, 6090, 6164, 6163, -1, + 6164, 6090, 6089, -1, 6089, 6165, 6164, -1, + 6165, 6089, 6088, -1, 6088, 6166, 6165, -1, + 6166, 6088, 6087, -1, 6087, 6167, 6166, -1, + 6167, 6087, 6086, -1, 6086, 6168, 6167, -1, + 6168, 6086, 6085, -1, 6085, 6169, 6168, -1, + 6169, 6085, 6084, -1, 6084, 6170, 6169, -1, + 6170, 6084, 6083, -1, 6083, 6171, 6170, -1, + 6171, 6083, 6082, -1, 6082, 6172, 6171, -1, + 6172, 6082, 6081, -1, 6172, 6081, 4357, -1, + 6172, 4357, 4356, -1, 4356, 6171, 6172, -1, + 6171, 4356, 4355, -1, 4355, 6170, 6171, -1, + 6170, 4355, 4354, -1, 4354, 6169, 6170, -1, + 6169, 4354, 4353, -1, 4353, 6168, 6169, -1, + 6168, 4353, 4352, -1, 4352, 6167, 6168, -1, + 6167, 4352, 4351, -1, 4351, 6166, 6167, -1, + 6166, 4351, 4350, -1, 4350, 6165, 6166, -1, + 6165, 4350, 4349, -1, 4349, 6164, 6165, -1, + 6164, 4349, 4348, -1, 4348, 6163, 6164, -1, + 6163, 4348, 4347, -1, 4347, 6162, 6163, -1, + 6162, 4347, 4346, -1, 4346, 6161, 6162, -1, + 6161, 4346, 4345, -1, 4345, 6160, 6161, -1, + 6160, 4345, 4344, -1, 4344, 6159, 6160, -1, + 6159, 4344, 4343, -1, 4343, 6158, 6159, -1, + 6158, 4343, 4342, -1, 4342, 6157, 6158, -1, + 6157, 4342, 4341, -1, 4341, 6156, 6157, -1, + 6156, 4341, 4340, -1, 4340, 6155, 6156, -1, + 6155, 4340, 4339, -1, 4339, 6154, 6155, -1, + 6154, 4339, 4338, -1, 4338, 6153, 6154, -1, + 6153, 4338, 4337, -1, 4337, 6152, 6153, -1, + 6152, 4337, 4336, -1, 4336, 6151, 6152, -1, + 6151, 4336, 4335, -1, 4335, 6150, 6151, -1, + 6150, 4335, 4334, -1, 4334, 6149, 6150, -1, + 6149, 4334, 4333, -1, 4333, 6148, 6149, -1, + 6148, 4333, 4332, -1, 4332, 6147, 6148, -1, + 6147, 4332, 4331, -1, 4331, 6146, 6147, -1, + 6146, 4331, 4330, -1, 4330, 6145, 6146, -1, + 6145, 4330, 4329, -1, 4329, 6144, 6145, -1, + 6144, 4329, 4328, -1, 4328, 6143, 6144, -1, + 6143, 4328, 4327, -1, 4327, 6142, 6143, -1, + 6142, 4327, 4326, -1, 4326, 6141, 6142, -1, + 6141, 4326, 4325, -1, 4325, 6140, 6141, -1, + 6140, 4325, 4324, -1, 4324, 6139, 6140, -1, + 6139, 4324, 4323, -1, 4323, 6138, 6139, -1, + 6138, 4323, 4322, -1, 4322, 6137, 6138, -1, + 6137, 4322, 4321, -1, 4321, 6136, 6137, -1, + 6136, 4321, 4320, -1, 4320, 6135, 6136, -1, + 6135, 4320, 4319, -1, 4319, 6134, 6135, -1, + 4319, 6133, 6134, -1, 6133, 4319, 6173, -1, + 6173, 6131, 6133, -1, 6173, 6174, 6131, -1, + 6174, 6173, 4319, -1, 6174, 4319, 4238, -1, + 4238, 6131, 6174, -1, 6131, 4238, 4237, -1, + 4093, 4237, 4242, -1, 6175, 4093, 4242, -1, + 4242, 6176, 6175, -1, 4242, 4241, 6176, -1, + 6176, 4241, 4243, -1, 6176, 4243, 4315, -1, + 4315, 6177, 6176, -1, 6177, 4315, 4313, -1, + 4313, 6178, 6177, -1, 6178, 4313, 4311, -1, + 4311, 6179, 6178, -1, 6179, 4311, 4309, -1, + 4309, 6180, 6179, -1, 6180, 4309, 4307, -1, + 4307, 6181, 6180, -1, 6181, 4307, 4305, -1, + 4305, 6182, 6181, -1, 6182, 4305, 4303, -1, + 4303, 6183, 6182, -1, 6183, 4303, 4301, -1, + 4301, 6184, 6183, -1, 6184, 4301, 4299, -1, + 4299, 6185, 6184, -1, 6185, 4299, 4297, -1, + 4297, 6186, 6185, -1, 6186, 4297, 4295, -1, + 4295, 6187, 6186, -1, 6187, 4295, 4293, -1, + 4293, 6188, 6187, -1, 6188, 4293, 4291, -1, + 4291, 6189, 6188, -1, 6189, 4291, 4289, -1, + 4289, 6190, 6189, -1, 6190, 4289, 4287, -1, + 4287, 6191, 6190, -1, 6191, 4287, 4285, -1, + 4285, 6192, 6191, -1, 6192, 4285, 4283, -1, + 4283, 6193, 6192, -1, 6193, 4283, 4281, -1, + 4281, 6194, 6193, -1, 6194, 4281, 4279, -1, + 4279, 6195, 6194, -1, 6195, 4279, 4277, -1, + 4277, 6196, 6195, -1, 6196, 4277, 4275, -1, + 4275, 6197, 6196, -1, 6197, 4275, 4273, -1, + 4273, 6198, 6197, -1, 6198, 4273, 4271, -1, + 4271, 6199, 6198, -1, 6199, 4271, 4269, -1, + 4269, 6200, 6199, -1, 6200, 4269, 4267, -1, + 4267, 6201, 6200, -1, 6201, 4267, 4265, -1, + 4265, 6202, 6201, -1, 6202, 4265, 4263, -1, + 4263, 6203, 6202, -1, 6203, 4263, 4261, -1, + 4261, 6204, 6203, -1, 6204, 4261, 4259, -1, + 4259, 6205, 6204, -1, 6205, 4259, 4257, -1, + 4257, 6206, 6205, -1, 6206, 4257, 4255, -1, + 4255, 6207, 6206, -1, 6207, 4255, 4253, -1, + 4253, 6208, 6207, -1, 6208, 4253, 4251, -1, + 4251, 6209, 6208, -1, 6209, 4251, 4249, -1, + 4249, 6210, 6209, -1, 6210, 4249, 4247, -1, + 4247, 6211, 6210, -1, 6211, 4247, 4244, -1, + 4244, 4235, 6211, -1, 4235, 6212, 6211, -1, + 4235, 4234, 6212, -1, 6213, 6214, 6215, -1, + 6213, 6216, 6214, -1, 6217, 6218, 6219, -1, + 6217, 6219, 6220, -1, 6220, 6221, 6217, -1, + 6221, 6220, 6222, -1, 6222, 6223, 6221, -1, + 6223, 6222, 6224, -1, 6224, 6225, 6223, -1, + 6224, 6226, 6225, -1, 6226, 6224, 6227, -1, + 6227, 6228, 6226, -1, 6228, 6227, 6216, -1, + 6216, 6213, 6228, -1, 6212, 6213, 6229, -1, + 6212, 6228, 6213, -1, 6228, 6212, 4234, -1, + 4234, 6226, 6228, -1, 6226, 4234, 4232, -1, + 4232, 6225, 6226, -1, 6225, 4232, 4229, -1, + 6225, 4229, 4227, -1, 4227, 6223, 6225, -1, + 6223, 4227, 4225, -1, 4225, 6221, 6223, -1, + 6221, 4225, 4224, -1, 4224, 6217, 6221, -1, + 4224, 6230, 6217, -1, 6231, 6232, 6233, -1, + 6232, 6231, 6234, -1, 6234, 6235, 6232, -1, + 6235, 6234, 6236, -1, 6236, 6237, 6235, -1, + 6237, 6236, 6238, -1, 6238, 6239, 6237, -1, + 6239, 6238, 6240, -1, 6240, 6241, 6239, -1, + 6241, 6240, 6242, -1, 6242, 6243, 6241, -1, + 6243, 6242, 6244, -1, 6244, 6245, 6243, -1, + 6245, 6244, 6246, -1, 6246, 6247, 6245, -1, + 6247, 6246, 6248, -1, 6248, 6249, 6247, -1, + 6249, 6248, 6250, -1, 6250, 6251, 6249, -1, + 6251, 6250, 6252, -1, 6252, 6253, 6251, -1, + 6253, 6252, 6254, -1, 6254, 6255, 6253, -1, + 6255, 6254, 6256, -1, 6256, 6257, 6255, -1, + 6257, 6256, 6258, -1, 6258, 6259, 6257, -1, + 6259, 6258, 6260, -1, 6260, 6261, 6259, -1, + 6261, 6260, 6262, -1, 6262, 6263, 6261, -1, + 6263, 6262, 6264, -1, 6264, 6265, 6263, -1, + 6265, 6264, 6266, -1, 6266, 6230, 6265, -1, + 6266, 6217, 6230, -1, 6266, 6218, 6217, -1, + 6218, 6266, 6264, -1, 6264, 6267, 6218, -1, + 6267, 6264, 6262, -1, 6262, 6268, 6267, -1, + 6268, 6262, 6260, -1, 6260, 6269, 6268, -1, + 6269, 6260, 6258, -1, 6258, 6270, 6269, -1, + 6270, 6258, 6256, -1, 6256, 6271, 6270, -1, + 6271, 6256, 6254, -1, 6254, 6272, 6271, -1, + 6272, 6254, 6252, -1, 6252, 6273, 6272, -1, + 6273, 6252, 6250, -1, 6250, 6274, 6273, -1, + 6274, 6250, 6248, -1, 6248, 6275, 6274, -1, + 6275, 6248, 6246, -1, 6246, 6276, 6275, -1, + 6276, 6246, 6244, -1, 6244, 6277, 6276, -1, + 6277, 6244, 6242, -1, 6242, 6278, 6277, -1, + 6278, 6242, 6240, -1, 6240, 6279, 6278, -1, + 6279, 6240, 6238, -1, 6238, 6280, 6279, -1, + 6280, 6238, 6236, -1, 6236, 6281, 6280, -1, + 6281, 6236, 6234, -1, 6234, 6282, 6281, -1, + 6282, 6234, 6231, -1, 6231, 6283, 6282, -1, + 6283, 6231, 6233, -1, 6233, 6284, 6283, -1, + 6284, 6233, 6285, -1, 6285, 6286, 6284, -1, + 6286, 6285, 6287, -1, 6287, 6288, 6286, -1, + 6288, 6287, 6289, -1, 6289, 6290, 6288, -1, + 6290, 6289, 6291, -1, 6292, 6293, 6294, -1, + 6292, 6295, 6293, -1, 6295, 6292, 6296, -1, + 6296, 6297, 6295, -1, 6297, 6296, 6298, -1, + 6298, 6299, 6297, -1, 6299, 6298, 6300, -1, + 6300, 6301, 6299, -1, 6301, 6300, 6302, -1, + 6302, 6303, 6301, -1, 6303, 6302, 6304, -1, + 6304, 6305, 6303, -1, 6305, 6304, 6306, -1, + 6306, 6307, 6305, -1, 6307, 6306, 6308, -1, + 6308, 6309, 6307, -1, 6309, 6308, 6310, -1, + 6310, 6311, 6309, -1, 6311, 6310, 6312, -1, + 6312, 6313, 6311, -1, 6313, 6312, 6314, -1, + 6314, 6315, 6313, -1, 6315, 6314, 6291, -1, + 6291, 6316, 6315, -1, 6316, 6291, 6289, -1, + 6289, 6317, 6316, -1, 6317, 6289, 6287, -1, + 6287, 6318, 6317, -1, 6287, 6285, 6318, -1, + 6319, 6318, 6285, -1, 6319, 6285, 6233, -1, + 6233, 6320, 6319, -1, 6320, 6233, 6232, -1, + 6232, 6321, 6320, -1, 6321, 6232, 6235, -1, + 6235, 6322, 6321, -1, 6322, 6235, 6237, -1, + 6237, 6323, 6322, -1, 6323, 6237, 6239, -1, + 6239, 6324, 6323, -1, 6324, 6239, 6241, -1, + 6241, 6325, 6324, -1, 6325, 6241, 6243, -1, + 6243, 6326, 6325, -1, 6326, 6243, 6245, -1, + 6245, 6327, 6326, -1, 6327, 6245, 6247, -1, + 6247, 6328, 6327, -1, 6328, 6247, 6249, -1, + 6249, 6329, 6328, -1, 6329, 6249, 6251, -1, + 6251, 6330, 6329, -1, 6330, 6251, 6253, -1, + 6253, 6331, 6330, -1, 6331, 6253, 6255, -1, + 6255, 6332, 6331, -1, 6332, 6255, 6257, -1, + 6257, 6333, 6332, -1, 6333, 6257, 6259, -1, + 6259, 6334, 6333, -1, 6334, 6259, 6261, -1, + 6261, 6335, 6334, -1, 6335, 6261, 6263, -1, + 6263, 6336, 6335, -1, 6336, 6263, 6265, -1, + 6265, 6337, 6336, -1, 6337, 6265, 6230, -1, + 6230, 6338, 6337, -1, 6338, 6230, 4224, -1, + 6338, 4224, 4223, -1, 6338, 4223, 4365, -1, + 4365, 6337, 6338, -1, 6337, 4365, 4367, -1, + 4367, 6336, 6337, -1, 6336, 4367, 4369, -1, + 4369, 6335, 6336, -1, 6335, 4369, 4371, -1, + 4371, 6334, 6335, -1, 6334, 4371, 4373, -1, + 4373, 6333, 6334, -1, 6333, 4373, 4375, -1, + 4375, 6332, 6333, -1, 6332, 4375, 4377, -1, + 4377, 6331, 6332, -1, 6331, 4377, 4379, -1, + 4379, 6330, 6331, -1, 6330, 4379, 4381, -1, + 4381, 6329, 6330, -1, 6329, 4381, 4383, -1, + 4383, 6328, 6329, -1, 6328, 4383, 4385, -1, + 4385, 6327, 6328, -1, 6327, 4385, 4387, -1, + 4387, 6326, 6327, -1, 6326, 4387, 4389, -1, + 4389, 6325, 6326, -1, 6325, 4389, 4391, -1, + 4391, 6324, 6325, -1, 6324, 4391, 4393, -1, + 4393, 6323, 6324, -1, 6323, 4393, 4395, -1, + 4395, 6322, 6323, -1, 6322, 4395, 4397, -1, + 4397, 6321, 6322, -1, 6321, 4397, 4399, -1, + 4399, 6320, 6321, -1, 6320, 4399, 4401, -1, + 4401, 6319, 6320, -1, 6319, 4401, 4434, -1, + 4434, 6318, 6319, -1, 6318, 4434, 4432, -1, + 4432, 6317, 6318, -1, 6317, 4432, 4430, -1, + 4430, 6316, 6317, -1, 6316, 4430, 4428, -1, + 4428, 6315, 6316, -1, 6315, 4428, 4426, -1, + 4426, 6313, 6315, -1, 6313, 4426, 4424, -1, + 4424, 6311, 6313, -1, 6311, 4424, 4422, -1, + 4422, 6309, 6311, -1, 6309, 4422, 4420, -1, + 4420, 6307, 6309, -1, 6307, 4420, 4418, -1, + 4418, 6305, 6307, -1, 6305, 4418, 4416, -1, + 4416, 6303, 6305, -1, 6303, 4416, 4414, -1, + 4414, 6301, 6303, -1, 6301, 4414, 4412, -1, + 4412, 6299, 6301, -1, 6299, 4412, 4410, -1, + 4410, 6297, 6299, -1, 6297, 4410, 4408, -1, + 4408, 6295, 6297, -1, 6295, 4408, 4406, -1, + 4406, 6293, 6295, -1, 6293, 4406, 4402, -1, + 6293, 4402, 4458, -1, 4458, 6339, 6293, -1, + 6339, 4458, 4100, -1, 6339, 4100, 6340, -1, + 6340, 6293, 6339, -1, 6340, 6294, 6293, -1, + 6340, 4100, 6294, -1, 6294, 4100, 4099, -1, + 4099, 6292, 6294, -1, 4099, 6341, 6292, -1, + 4099, 4091, 6341, -1, 6341, 4091, 4089, -1, + 4089, 4087, 6341, -1, 4087, 6292, 6341, -1, + 4087, 6296, 6292, -1, 6296, 4087, 4086, -1, + 4086, 6298, 6296, -1, 6298, 4086, 4085, -1, + 4085, 6300, 6298, -1, 6300, 4085, 4084, -1, + 4084, 6302, 6300, -1, 6302, 4084, 4083, -1, + 4083, 6304, 6302, -1, 6304, 4083, 4082, -1, + 4082, 6306, 6304, -1, 6306, 4082, 4081, -1, + 4081, 6308, 6306, -1, 6308, 4081, 4080, -1, + 4080, 6310, 6308, -1, 6310, 4080, 4079, -1, + 4079, 6312, 6310, -1, 6312, 4079, 4078, -1, + 4078, 6314, 6312, -1, 6314, 4078, 4077, -1, + 4077, 6291, 6314, -1, 6291, 4077, 4076, -1, + 4076, 6290, 6291, -1, 6290, 4076, 4075, -1, + 4075, 6288, 6290, -1, 6288, 4075, 4074, -1, + 4074, 6286, 6288, -1, 6286, 4074, 4073, -1, + 4073, 6284, 6286, -1, 6284, 4073, 3635, -1, + 3635, 6283, 6284, -1, 6283, 3635, 3634, -1, + 3634, 6282, 6283, -1, 6282, 3634, 3637, -1, + 3637, 6281, 6282, -1, 6281, 3637, 3639, -1, + 3639, 6280, 6281, -1, 6280, 3639, 3641, -1, + 3641, 6279, 6280, -1, 6279, 3641, 3643, -1, + 3643, 6278, 6279, -1, 6278, 3643, 3645, -1, + 3645, 6277, 6278, -1, 6277, 3645, 3647, -1, + 3647, 6276, 6277, -1, 6276, 3647, 3649, -1, + 3649, 6275, 6276, -1, 6275, 3649, 3651, -1, + 3651, 6274, 6275, -1, 6274, 3651, 3653, -1, + 3653, 6273, 6274, -1, 6273, 3653, 3655, -1, + 3655, 6272, 6273, -1, 6272, 3655, 3657, -1, + 3657, 6271, 6272, -1, 6271, 3657, 3659, -1, + 3659, 6270, 6271, -1, 6270, 3659, 3661, -1, + 3661, 6269, 6270, -1, 6269, 3661, 3663, -1, + 3663, 6268, 6269, -1, 6268, 3663, 3665, -1, + 3665, 6267, 6268, -1, 6267, 3665, 3667, -1, + 3667, 6218, 6267, -1, 3667, 6219, 6218, -1, + 3667, 3666, 6219, -1, 6219, 3666, 3910, -1, + 6219, 3910, 3909, -1, 3909, 6220, 6219, -1, + 6220, 3909, 3908, -1, 3908, 6222, 6220, -1, + 6222, 3908, 3907, -1, 3907, 6224, 6222, -1, + 3907, 6227, 6224, -1, 6227, 3907, 3906, -1, + 3906, 6216, 6227, -1, 6216, 3906, 3905, -1, + 3905, 6214, 6216, -1, 6214, 3905, 3904, -1, + 6214, 3904, 6342, -1, 6343, 6344, 6345, -1, + 6345, 6346, 6343, -1, 6346, 6345, 6347, -1, + 6347, 6348, 6346, -1, 6348, 6347, 6349, -1, + 6349, 6350, 6348, -1, 6350, 6349, 6351, -1, + 6351, 6352, 6350, -1, 6352, 6351, 6353, -1, + 6353, 6354, 6352, -1, 6354, 6353, 6355, -1, + 6355, 6356, 6354, -1, 6356, 6355, 6357, -1, + 6357, 6358, 6356, -1, 6358, 6357, 6359, -1, + 6359, 6360, 6358, -1, 6360, 6359, 6361, -1, + 6361, 6362, 6360, -1, 6362, 6361, 6363, -1, + 6363, 6364, 6362, -1, 6364, 6363, 6365, -1, + 6365, 6366, 6364, -1, 6366, 6365, 6367, -1, + 6367, 6368, 6366, -1, 6368, 6367, 6369, -1, + 6369, 6370, 6368, -1, 6370, 6369, 6371, -1, + 6371, 6372, 6370, -1, 6372, 6371, 6373, -1, + 6373, 6374, 6372, -1, 6374, 6373, 6375, -1, + 6375, 6376, 6374, -1, 6376, 6375, 6342, -1, + 6376, 6342, 3904, -1, 6376, 3904, 3670, -1, + 3670, 6374, 6376, -1, 6374, 3670, 3669, -1, + 3669, 6372, 6374, -1, 6372, 3669, 3903, -1, + 3903, 6370, 6372, -1, 6370, 3903, 3902, -1, + 3902, 6368, 6370, -1, 6368, 3902, 3901, -1, + 3901, 6366, 6368, -1, 6366, 3901, 3900, -1, + 3900, 6364, 6366, -1, 6364, 3900, 3899, -1, + 3899, 6362, 6364, -1, 6362, 3899, 3898, -1, + 3898, 6360, 6362, -1, 6360, 3898, 3897, -1, + 3897, 6358, 6360, -1, 6358, 3897, 3896, -1, + 3896, 6356, 6358, -1, 6356, 3896, 3895, -1, + 3895, 6354, 6356, -1, 6354, 3895, 3894, -1, + 3894, 6352, 6354, -1, 6352, 3894, 3893, -1, + 3893, 6350, 6352, -1, 6350, 3893, 3892, -1, + 3892, 6348, 6350, -1, 6348, 3892, 3891, -1, + 3891, 6346, 6348, -1, 6346, 3891, 3890, -1, + 3890, 6343, 6346, -1, 6343, 3890, 3889, -1, + 3889, 6344, 6343, -1, 6344, 3889, 3888, -1, + 3888, 6377, 6344, -1, 6377, 3888, 3887, -1, + 3887, 6378, 6377, -1, 6378, 3887, 3886, -1, + 3886, 6379, 6378, -1, 6379, 3886, 3885, -1, + 3885, 6380, 6379, -1, 6380, 3885, 3884, -1, + 3884, 6381, 6380, -1, 6381, 3884, 3690, -1, + 3690, 6382, 6381, -1, 6382, 3690, 3691, -1, + 3691, 6383, 6382, -1, 6383, 3691, 3693, -1, + 3693, 6384, 6383, -1, 6384, 3693, 3695, -1, + 3695, 6385, 6384, -1, 6385, 3695, 3697, -1, + 3697, 6386, 6385, -1, 6386, 3697, 3699, -1, + 3699, 6387, 6386, -1, 6387, 3699, 3701, -1, + 3701, 6388, 6387, -1, 6388, 3701, 3703, -1, + 3703, 6389, 6388, -1, 6389, 3703, 3705, -1, + 3705, 6390, 6389, -1, 6390, 3705, 3706, -1, + 3706, 3708, 6390, -1, 6391, 6392, 6393, -1, + 6393, 6394, 6391, -1, 6394, 6393, 6395, -1, + 6395, 6396, 6394, -1, 6396, 6395, 6397, -1, + 6397, 6398, 6396, -1, 6398, 6397, 6399, -1, + 6399, 6400, 6398, -1, 6400, 6399, 6401, -1, + 6401, 6402, 6400, -1, 6403, 6400, 6402, -1, + 6402, 6404, 6403, -1, 6404, 6402, 6405, -1, + 6405, 6406, 6404, -1, 6406, 6405, 6407, -1, + 6407, 6408, 6406, -1, 6408, 6407, 6409, -1, + 6409, 6410, 6408, -1, 6410, 6409, 6411, -1, + 6411, 6412, 6410, -1, 6412, 6411, 6413, -1, + 6413, 6414, 6412, -1, 6414, 6413, 6415, -1, + 6415, 6416, 6414, -1, 6416, 6415, 6417, -1, + 6417, 6418, 6416, -1, 6418, 6417, 6419, -1, + 6419, 6420, 6418, -1, 6420, 6419, 6421, -1, + 6421, 6422, 6420, -1, 6423, 6424, 6425, -1, + 6423, 6425, 6422, -1, 6422, 6421, 6423, -1, + 3708, 6426, 6423, -1, 3708, 6423, 6421, -1, + 6421, 6390, 3708, -1, 6390, 6421, 6419, -1, + 6419, 6389, 6390, -1, 6389, 6419, 6417, -1, + 6417, 6388, 6389, -1, 6388, 6417, 6415, -1, + 6415, 6387, 6388, -1, 6387, 6415, 6413, -1, + 6413, 6386, 6387, -1, 6386, 6413, 6411, -1, + 6411, 6385, 6386, -1, 6385, 6411, 6409, -1, + 6409, 6384, 6385, -1, 6384, 6409, 6407, -1, + 6407, 6383, 6384, -1, 6383, 6407, 6405, -1, + 6405, 6382, 6383, -1, 6382, 6405, 6402, -1, + 6402, 6381, 6382, -1, 6381, 6402, 6401, -1, + 6401, 6380, 6381, -1, 6380, 6401, 6399, -1, + 6399, 6379, 6380, -1, 6379, 6399, 6397, -1, + 6397, 6378, 6379, -1, 6378, 6397, 6395, -1, + 6395, 6377, 6378, -1, 6377, 6395, 6393, -1, + 6393, 6344, 6377, -1, 6344, 6393, 6392, -1, + 6392, 6345, 6344, -1, 6345, 6392, 6427, -1, + 6427, 6347, 6345, -1, 6347, 6427, 6428, -1, + 6428, 6349, 6347, -1, 6349, 6428, 6429, -1, + 6429, 6351, 6349, -1, 6351, 6429, 6430, -1, + 6430, 6353, 6351, -1, 6353, 6430, 6431, -1, + 6431, 6355, 6353, -1, 6355, 6431, 6432, -1, + 6432, 6357, 6355, -1, 6357, 6432, 6433, -1, + 6433, 6359, 6357, -1, 6359, 6433, 6434, -1, + 6434, 6361, 6359, -1, 6361, 6434, 6435, -1, + 6435, 6363, 6361, -1, 6363, 6435, 6436, -1, + 6436, 6365, 6363, -1, 6365, 6436, 6437, -1, + 6437, 6367, 6365, -1, 6367, 6437, 6438, -1, + 6438, 6369, 6367, -1, 6369, 6438, 6439, -1, + 6439, 6371, 6369, -1, 6371, 6439, 6440, -1, + 6440, 6373, 6371, -1, 6373, 6440, 6441, -1, + 6441, 6375, 6373, -1, 6375, 6441, 6442, -1, + 6442, 6342, 6375, -1, 6342, 6442, 6443, -1, + 6443, 6214, 6342, -1, 6443, 6215, 6214, -1, + 6443, 6444, 6215, -1, 6444, 6443, 6442, -1, + 6442, 6445, 6444, -1, 6445, 6442, 6441, -1, + 6441, 6446, 6445, -1, 6446, 6441, 6440, -1, + 6440, 6447, 6446, -1, 6447, 6440, 6439, -1, + 6439, 6448, 6447, -1, 6448, 6439, 6438, -1, + 6438, 6449, 6448, -1, 6449, 6438, 6437, -1, + 6437, 6450, 6449, -1, 6450, 6437, 6436, -1, + 6436, 6451, 6450, -1, 6451, 6436, 6435, -1, + 6435, 6452, 6451, -1, 6452, 6435, 6434, -1, + 6434, 6453, 6452, -1, 6453, 6434, 6433, -1, + 6433, 6454, 6453, -1, 6454, 6433, 6432, -1, + 6432, 6455, 6454, -1, 6455, 6432, 6431, -1, + 6431, 6456, 6455, -1, 6456, 6431, 6430, -1, + 6430, 6457, 6456, -1, 6457, 6430, 6429, -1, + 6429, 6458, 6457, -1, 6458, 6429, 6428, -1, + 6428, 6459, 6458, -1, 6459, 6428, 6427, -1, + 6427, 6460, 6459, -1, 6460, 6427, 6392, -1, + 6392, 6391, 6460, -1, 6460, 6391, 6461, -1, + 6461, 6459, 6460, -1, 6459, 6461, 6462, -1, + 6462, 6458, 6459, -1, 6458, 6462, 6463, -1, + 6463, 6457, 6458, -1, 6457, 6463, 6464, -1, + 6464, 6456, 6457, -1, 6456, 6464, 6465, -1, + 6465, 6455, 6456, -1, 6455, 6465, 6466, -1, + 6466, 6454, 6455, -1, 6454, 6466, 6467, -1, + 6467, 6453, 6454, -1, 6453, 6467, 6468, -1, + 6468, 6452, 6453, -1, 6452, 6468, 6469, -1, + 6469, 6451, 6452, -1, 6451, 6469, 6470, -1, + 6470, 6450, 6451, -1, 6450, 6470, 6471, -1, + 6471, 6449, 6450, -1, 6449, 6471, 6472, -1, + 6472, 6448, 6449, -1, 6448, 6472, 6473, -1, + 6473, 6447, 6448, -1, 6447, 6473, 6474, -1, + 6474, 6446, 6447, -1, 6446, 6474, 6475, -1, + 6475, 6445, 6446, -1, 6445, 6475, 6476, -1, + 6476, 6444, 6445, -1, 6444, 6476, 6477, -1, + 6477, 6215, 6444, -1, 6215, 6477, 6478, -1, + 6478, 6213, 6215, -1, 6478, 6229, 6213, -1, + 6478, 6479, 6229, -1, 6479, 6478, 6477, -1, + 6477, 6480, 6479, -1, 6480, 6477, 6476, -1, + 6476, 6481, 6480, -1, 6481, 6476, 6475, -1, + 6475, 6482, 6481, -1, 6482, 6475, 6474, -1, + 6474, 6483, 6482, -1, 6483, 6474, 6473, -1, + 6473, 6484, 6483, -1, 6484, 6473, 6472, -1, + 6472, 6485, 6484, -1, 6485, 6472, 6471, -1, + 6471, 6486, 6485, -1, 6486, 6471, 6470, -1, + 6470, 6487, 6486, -1, 6487, 6470, 6469, -1, + 6469, 6488, 6487, -1, 6488, 6469, 6468, -1, + 6468, 6489, 6488, -1, 6489, 6468, 6467, -1, + 6467, 6490, 6489, -1, 6490, 6467, 6466, -1, + 6466, 6491, 6490, -1, 6491, 6466, 6465, -1, + 6465, 6492, 6491, -1, 6492, 6465, 6464, -1, + 6464, 6493, 6492, -1, 6493, 6464, 6463, -1, + 6463, 6494, 6493, -1, 6494, 6463, 6462, -1, + 6462, 6495, 6494, -1, 6495, 6462, 6461, -1, + 6461, 6496, 6495, -1, 6496, 6461, 6391, -1, + 6391, 6497, 6496, -1, 6497, 6391, 6394, -1, + 6394, 6498, 6497, -1, 6498, 6394, 6396, -1, + 6396, 6499, 6498, -1, 6499, 6396, 6398, -1, + 6398, 6500, 6499, -1, 6500, 6398, 6400, -1, + 6400, 6403, 6500, -1, 6500, 6403, 6501, -1, + 6501, 6499, 6500, -1, 6499, 6501, 6502, -1, + 6502, 6498, 6499, -1, 6498, 6502, 6503, -1, + 6503, 6497, 6498, -1, 6497, 6503, 6504, -1, + 6504, 6496, 6497, -1, 6496, 6504, 6505, -1, + 6505, 6495, 6496, -1, 6495, 6505, 6506, -1, + 6506, 6494, 6495, -1, 6494, 6506, 6507, -1, + 6507, 6493, 6494, -1, 6493, 6507, 6508, -1, + 6508, 6492, 6493, -1, 6492, 6508, 6509, -1, + 6509, 6491, 6492, -1, 6491, 6509, 6510, -1, + 6510, 6490, 6491, -1, 6490, 6510, 6511, -1, + 6511, 6489, 6490, -1, 6489, 6511, 6512, -1, + 6512, 6488, 6489, -1, 6488, 6512, 6513, -1, + 6513, 6487, 6488, -1, 6487, 6513, 6514, -1, + 6514, 6486, 6487, -1, 6486, 6514, 6515, -1, + 6515, 6485, 6486, -1, 6485, 6515, 6516, -1, + 6516, 6484, 6485, -1, 6484, 6516, 6517, -1, + 6517, 6483, 6484, -1, 6483, 6517, 6518, -1, + 6518, 6482, 6483, -1, 6482, 6518, 6519, -1, + 6519, 6481, 6482, -1, 6481, 6519, 6520, -1, + 6520, 6480, 6481, -1, 6480, 6520, 6521, -1, + 6521, 6479, 6480, -1, 6479, 6521, 6522, -1, + 6522, 6229, 6479, -1, 6229, 6522, 6523, -1, + 6523, 6212, 6229, -1, 6523, 6211, 6212, -1, + 6523, 6210, 6211, -1, 6210, 6523, 6522, -1, + 6522, 6209, 6210, -1, 6209, 6522, 6521, -1, + 6521, 6208, 6209, -1, 6208, 6521, 6520, -1, + 6520, 6207, 6208, -1, 6207, 6520, 6519, -1, + 6519, 6206, 6207, -1, 6206, 6519, 6518, -1, + 6518, 6205, 6206, -1, 6205, 6518, 6517, -1, + 6517, 6204, 6205, -1, 6204, 6517, 6516, -1, + 6516, 6203, 6204, -1, 6203, 6516, 6515, -1, + 6515, 6202, 6203, -1, 6202, 6515, 6514, -1, + 6514, 6201, 6202, -1, 6201, 6514, 6513, -1, + 6513, 6200, 6201, -1, 6200, 6513, 6512, -1, + 6512, 6199, 6200, -1, 6199, 6512, 6511, -1, + 6511, 6198, 6199, -1, 6198, 6511, 6510, -1, + 6510, 6197, 6198, -1, 6197, 6510, 6509, -1, + 6509, 6196, 6197, -1, 6196, 6509, 6508, -1, + 6508, 6195, 6196, -1, 6195, 6508, 6507, -1, + 6507, 6194, 6195, -1, 6194, 6507, 6506, -1, + 6506, 6193, 6194, -1, 6193, 6506, 6505, -1, + 6505, 6192, 6193, -1, 6192, 6505, 6504, -1, + 6504, 6191, 6192, -1, 6191, 6504, 6503, -1, + 6503, 6190, 6191, -1, 6190, 6503, 6502, -1, + 6502, 6189, 6190, -1, 6189, 6502, 6501, -1, + 6501, 6188, 6189, -1, 6188, 6501, 6403, -1, + 6403, 6187, 6188, -1, 6187, 6403, 6404, -1, + 6404, 6186, 6187, -1, 6186, 6404, 6406, -1, + 6406, 6185, 6186, -1, 6185, 6406, 6408, -1, + 6408, 6184, 6185, -1, 6184, 6408, 6410, -1, + 6410, 6183, 6184, -1, 6183, 6410, 6412, -1, + 6412, 6182, 6183, -1, 6182, 6412, 6414, -1, + 6414, 6181, 6182, -1, 6181, 6414, 6416, -1, + 6416, 6180, 6181, -1, 6180, 6416, 6418, -1, + 6418, 6179, 6180, -1, 6179, 6418, 6420, -1, + 6420, 6178, 6179, -1, 6178, 6420, 6422, -1, + 6422, 6177, 6178, -1, 6177, 6422, 6425, -1, + 6425, 6176, 6177, -1, 6425, 6175, 6176, -1, + 6175, 6425, 6524, -1, 6524, 4093, 6175, -1, + 6524, 6525, 4093, -1, 6525, 6524, 6425, -1, + 6525, 6425, 6424, -1, 6424, 4093, 6525, -1, + 6424, 4094, 4093, -1, 4094, 6424, 6423, -1, + 4094, 6423, 6426, -1, 6426, 4092, 4094, -1, + 6426, 6526, 4092, -1, 6526, 6426, 3708, -1, + 6526, 3708, 3707, -1, 3707, 4092, 6526, -1, + 3707, 3709, 4092, -1, 3709, 3710, 4092, -1, + 4092, 3710, 3711, -1, 6527, 6528, 6529, -1, + 6528, 6527, 6530, -1, 6530, 6531, 6528, -1, + 6531, 6530, 6532, -1, 6532, 6533, 6531, -1, + 6533, 6532, 6534, -1, 6534, 6535, 6533, -1, + 6535, 6534, 6536, -1, 6536, 6537, 6535, -1, + 6537, 6536, 6538, -1, 6538, 6539, 6537, -1, + 6539, 6538, 6540, -1, 6540, 6541, 6539, -1, + 6541, 6540, 6542, -1, 6542, 6543, 6541, -1, + 6543, 6542, 6544, -1, 6544, 6545, 6543, -1, + 6545, 6544, 6546, -1, 6546, 6547, 6545, -1, + 6547, 6546, 6548, -1, 6548, 6549, 6547, -1, + 6549, 6548, 6550, -1, 6550, 6551, 6549, -1, + 6551, 6550, 6552, -1, 6552, 6553, 6551, -1, + 6553, 6552, 6554, -1, 6554, 6555, 6553, -1, + 6555, 6554, 6556, -1, 6556, 6557, 6555, -1, + 6557, 6556, 6558, -1, 6558, 6559, 6557, -1, + 6559, 6558, 6560, -1, 6560, 6561, 6559, -1, + 6561, 6560, 6562, -1, 6562, 6563, 6561, -1, + 6563, 6562, 6564, -1, 6565, 6566, 6567, -1, + 6567, 6568, 6565, -1, 6568, 6567, 6569, -1, + 6569, 6570, 6568, -1, 6570, 6569, 6571, -1, + 6571, 6572, 6570, -1, 6573, 6574, 6572, -1, + 6572, 6571, 6573, -1, 6575, 6576, 6573, -1, + 6573, 6577, 6575, -1, 6577, 6573, 6571, -1, + 6571, 6578, 6577, -1, 6578, 6571, 6569, -1, + 6569, 6579, 6578, -1, 6579, 6569, 6567, -1, + 6567, 6580, 6579, -1, 6580, 6567, 6566, -1, + 6566, 6581, 6580, -1, 6582, 6564, 6581, -1, + 6581, 6566, 6582, -1, 6583, 6582, 6566, -1, + 6566, 6565, 6583, -1, 6584, 6583, 6565, -1, + 6565, 6585, 6584, -1, 6585, 6565, 6568, -1, + 6568, 6586, 6585, -1, 6586, 6568, 6570, -1, + 6570, 6587, 6586, -1, 6587, 6570, 6572, -1, + 6572, 6588, 6587, -1, 6589, 6588, 6572, -1, + 6589, 6590, 6588, -1, 6589, 6591, 6590, -1, + 6591, 6589, 6572, -1, 6591, 6572, 6574, -1, + 6574, 6590, 6591, -1, 6590, 6592, 6593, -1, + 6592, 6590, 6574, -1, 6592, 6574, 6573, -1, + 6592, 6573, 6576, -1, 6576, 6593, 6592, -1, + 6594, 6593, 6576, -1, 6594, 6576, 6575, -1, + 6594, 6575, 6595, -1, 6595, 6593, 6594, -1, + 6595, 6596, 6593, -1, 6595, 6575, 6596, -1, + 6597, 6596, 6575, -1, 6575, 6598, 6597, -1, + 6598, 6575, 6577, -1, 6577, 6599, 6598, -1, + 6599, 6577, 6578, -1, 6578, 6600, 6599, -1, + 6600, 6578, 6579, -1, 6579, 6601, 6600, -1, + 6601, 6579, 6580, -1, 6580, 6602, 6601, -1, + 6602, 6580, 6581, -1, 6581, 6603, 6602, -1, + 6603, 6581, 6564, -1, 6564, 6604, 6603, -1, + 6604, 6564, 6562, -1, 6562, 6605, 6604, -1, + 6605, 6562, 6560, -1, 6560, 6606, 6605, -1, + 6606, 6560, 6558, -1, 6558, 6607, 6606, -1, + 6607, 6558, 6556, -1, 6556, 6608, 6607, -1, + 6608, 6556, 6554, -1, 6554, 6609, 6608, -1, + 6609, 6554, 6552, -1, 6552, 6610, 6609, -1, + 6610, 6552, 6550, -1, 6550, 6611, 6610, -1, + 6611, 6550, 6548, -1, 6548, 6612, 6611, -1, + 6612, 6548, 6546, -1, 6546, 6613, 6612, -1, + 6613, 6546, 6544, -1, 6544, 6614, 6613, -1, + 6614, 6544, 6542, -1, 6542, 6615, 6614, -1, + 6615, 6542, 6540, -1, 6540, 6616, 6615, -1, + 6616, 6540, 6538, -1, 6538, 6617, 6616, -1, + 6617, 6538, 6536, -1, 6536, 6618, 6617, -1, + 6618, 6536, 6534, -1, 6534, 6619, 6618, -1, + 6619, 6534, 6532, -1, 6532, 6620, 6619, -1, + 6620, 6532, 6530, -1, 6530, 6621, 6620, -1, + 6621, 6530, 6527, -1, 6527, 6622, 6621, -1, + 6527, 6529, 6622, -1, 6623, 6622, 6529, -1, + 6623, 6529, 6624, -1, 6624, 6625, 6623, -1, + 6625, 6624, 6626, -1, 6626, 6627, 6625, -1, + 6627, 6626, 6628, -1, 6628, 6629, 6627, -1, + 6629, 6628, 6630, -1, 6630, 6631, 6629, -1, + 6630, 6632, 6631, -1, 6632, 6630, 6633, -1, + 6633, 6634, 6632, -1, 6634, 6633, 6635, -1, + 6635, 6636, 6634, -1, 6636, 6635, 6637, -1, + 6637, 6638, 6636, -1, 6638, 6639, 6640, -1, + 6638, 6637, 6639, -1, 6641, 6642, 6643, -1, + 6642, 6641, 6644, -1, 6644, 6645, 6642, -1, + 6645, 6644, 6646, -1, 6646, 6647, 6645, -1, + 6647, 6646, 6648, -1, 6648, 6649, 6647, -1, + 6649, 6648, 6650, -1, 6650, 6651, 6649, -1, + 6651, 6650, 6652, -1, 6652, 6653, 6651, -1, + 6653, 6652, 6654, -1, 6654, 6655, 6653, -1, + 6655, 6654, 6656, -1, 6656, 6657, 6655, -1, + 6657, 6656, 6658, -1, 6658, 6659, 6657, -1, + 6659, 6658, 6660, -1, 6660, 6661, 6659, -1, + 6661, 6660, 6662, -1, 6662, 6663, 6661, -1, + 6663, 6662, 6664, -1, 6664, 6665, 6663, -1, + 6665, 6664, 6666, -1, 6666, 6667, 6665, -1, + 6667, 6666, 6668, -1, 6668, 6669, 6667, -1, + 6669, 6668, 6670, -1, 6670, 6671, 6669, -1, + 6671, 6670, 6672, -1, 6672, 6673, 6671, -1, + 6673, 6672, 6674, -1, 6674, 6675, 6673, -1, + 6675, 6674, 6676, -1, 6676, 6677, 6675, -1, + 6678, 6679, 6680, -1, 6678, 6680, 6681, -1, + 6681, 6682, 6678, -1, 6682, 6681, 6683, -1, + 6683, 6684, 6682, -1, 6684, 6683, 6685, -1, + 6685, 6686, 6684, -1, 6686, 6685, 6687, -1, + 6687, 6688, 6686, -1, 6687, 6689, 6688, -1, + 6689, 6687, 6690, -1, 6690, 6691, 6689, -1, + 6691, 6690, 6692, -1, 6692, 6693, 6691, -1, + 6693, 6692, 6694, -1, 6694, 6695, 6693, -1, + 6695, 6694, 6696, -1, 6696, 6697, 6695, -1, + 6697, 6696, 6698, -1, 6698, 6699, 6697, -1, + 6699, 6698, 6700, -1, 6700, 6701, 6699, -1, + 6701, 6700, 6702, -1, 6702, 6703, 6701, -1, + 6703, 6702, 6704, -1, 6704, 6705, 6703, -1, + 6705, 6704, 6706, -1, 6706, 6707, 6705, -1, + 6707, 6706, 6708, -1, 6708, 6709, 6707, -1, + 6709, 6708, 6710, -1, 6710, 6711, 6709, -1, + 6711, 6710, 6712, -1, 6712, 6713, 6711, -1, + 6713, 6712, 6714, -1, 6714, 6715, 6713, -1, + 6715, 6714, 6716, -1, 6716, 6717, 6715, -1, + 6717, 6716, 6718, -1, 6718, 6719, 6717, -1, + 6719, 6718, 6720, -1, 6720, 6721, 6719, -1, + 6721, 6720, 6722, -1, 6722, 6723, 6721, -1, + 6723, 6722, 6724, -1, 6724, 6725, 6723, -1, + 6725, 6724, 6726, -1, 6726, 6727, 6725, -1, + 6727, 6726, 6728, -1, 6728, 6729, 6727, -1, + 6729, 6728, 6730, -1, 6730, 6731, 6729, -1, + 6731, 6730, 6732, -1, 6732, 6733, 6731, -1, + 6733, 6732, 6734, -1, 6733, 6734, 6677, -1, + 6733, 6677, 6676, -1, 6676, 6731, 6733, -1, + 6731, 6676, 6674, -1, 6674, 6729, 6731, -1, + 6729, 6674, 6672, -1, 6672, 6727, 6729, -1, + 6727, 6672, 6670, -1, 6670, 6725, 6727, -1, + 6725, 6670, 6668, -1, 6668, 6723, 6725, -1, + 6723, 6668, 6666, -1, 6666, 6721, 6723, -1, + 6721, 6666, 6664, -1, 6664, 6719, 6721, -1, + 6719, 6664, 6662, -1, 6662, 6717, 6719, -1, + 6717, 6662, 6660, -1, 6660, 6715, 6717, -1, + 6715, 6660, 6658, -1, 6658, 6713, 6715, -1, + 6713, 6658, 6656, -1, 6656, 6711, 6713, -1, + 6711, 6656, 6654, -1, 6654, 6709, 6711, -1, + 6709, 6654, 6652, -1, 6652, 6707, 6709, -1, + 6707, 6652, 6650, -1, 6650, 6705, 6707, -1, + 6705, 6650, 6648, -1, 6648, 6703, 6705, -1, + 6703, 6648, 6646, -1, 6646, 6701, 6703, -1, + 6701, 6646, 6644, -1, 6644, 6699, 6701, -1, + 6699, 6644, 6641, -1, 6641, 6697, 6699, -1, + 6641, 6643, 6697, -1, 6735, 6697, 6643, -1, + 6735, 6695, 6697, -1, 6695, 6735, 6639, -1, + 6639, 6693, 6695, -1, 6693, 6639, 6637, -1, + 6637, 6691, 6693, -1, 6691, 6637, 6635, -1, + 6635, 6689, 6691, -1, 6689, 6635, 6633, -1, + 6633, 6688, 6689, -1, 6688, 6633, 6630, -1, + 6688, 6630, 6628, -1, 6628, 6686, 6688, -1, + 6686, 6628, 6626, -1, 6626, 6684, 6686, -1, + 6684, 6626, 6624, -1, 6624, 6682, 6684, -1, + 6682, 6624, 6529, -1, 6529, 6678, 6682, -1, + 6678, 6529, 6528, -1, 6528, 6679, 6678, -1, + 6679, 6528, 6531, -1, 6531, 6736, 6679, -1, + 6736, 6531, 6533, -1, 6533, 6737, 6736, -1, + 6737, 6533, 6535, -1, 6535, 6738, 6737, -1, + 6738, 6535, 6537, -1, 6537, 6739, 6738, -1, + 6739, 6537, 6539, -1, 6539, 6740, 6739, -1, + 6740, 6539, 6541, -1, 6541, 6741, 6740, -1, + 6741, 6541, 6543, -1, 6543, 6742, 6741, -1, + 6742, 6543, 6545, -1, 6545, 6743, 6742, -1, + 6743, 6545, 6547, -1, 6547, 6744, 6743, -1, + 6744, 6547, 6549, -1, 6549, 6745, 6744, -1, + 6745, 6549, 6551, -1, 6551, 6746, 6745, -1, + 6746, 6551, 6553, -1, 6553, 6747, 6746, -1, + 6747, 6553, 6555, -1, 6555, 6748, 6747, -1, + 6748, 6555, 6557, -1, 6557, 6749, 6748, -1, + 6749, 6557, 6559, -1, 6559, 6750, 6749, -1, + 6750, 6559, 6561, -1, 6561, 6751, 6750, -1, + 6751, 6561, 6563, -1, 6563, 6752, 6751, -1, + 6752, 6563, 6564, -1, 6564, 6582, 6752, -1, + 6753, 6752, 6582, -1, 6752, 6753, 6754, -1, + 6754, 6751, 6752, -1, 6751, 6754, 6755, -1, + 6755, 6750, 6751, -1, 6750, 6755, 6756, -1, + 6756, 6749, 6750, -1, 6749, 6756, 6757, -1, + 6757, 6748, 6749, -1, 6748, 6757, 6758, -1, + 6758, 6747, 6748, -1, 6747, 6758, 6759, -1, + 6759, 6746, 6747, -1, 6746, 6759, 6760, -1, + 6760, 6745, 6746, -1, 6745, 6760, 6761, -1, + 6761, 6744, 6745, -1, 6744, 6761, 6762, -1, + 6762, 6743, 6744, -1, 6743, 6762, 6763, -1, + 6763, 6742, 6743, -1, 6742, 6763, 6764, -1, + 6764, 6741, 6742, -1, 6741, 6764, 6765, -1, + 6765, 6740, 6741, -1, 6740, 6765, 6766, -1, + 6766, 6739, 6740, -1, 6739, 6766, 6767, -1, + 6767, 6738, 6739, -1, 6738, 6767, 6768, -1, + 6768, 6737, 6738, -1, 6737, 6768, 6769, -1, + 6769, 6736, 6737, -1, 6736, 6769, 6770, -1, + 6770, 6679, 6736, -1, 6770, 6680, 6679, -1, + 6770, 6771, 6680, -1, 6771, 6770, 6769, -1, + 6769, 6772, 6771, -1, 6772, 6769, 6768, -1, + 6768, 6773, 6772, -1, 6773, 6768, 6767, -1, + 6767, 6774, 6773, -1, 6774, 6767, 6766, -1, + 6766, 6775, 6774, -1, 6775, 6766, 6765, -1, + 6765, 6776, 6775, -1, 6776, 6765, 6764, -1, + 6764, 6777, 6776, -1, 6777, 6764, 6763, -1, + 6763, 6778, 6777, -1, 6778, 6763, 6762, -1, + 6762, 6779, 6778, -1, 6779, 6762, 6761, -1, + 6761, 6780, 6779, -1, 6780, 6761, 6760, -1, + 6760, 6781, 6780, -1, 6781, 6760, 6759, -1, + 6759, 6782, 6781, -1, 6782, 6759, 6758, -1, + 6758, 6783, 6782, -1, 6783, 6758, 6757, -1, + 6757, 6784, 6783, -1, 6784, 6757, 6756, -1, + 6756, 6785, 6784, -1, 6785, 6756, 6755, -1, + 6755, 6786, 6785, -1, 6786, 6755, 6754, -1, + 6754, 6787, 6786, -1, 6787, 6754, 6753, -1, + 6753, 6788, 6787, -1, 6788, 6753, 6582, -1, + 6582, 6583, 6788, -1, 6789, 6790, 6788, -1, + 6789, 6788, 6583, -1, 6583, 6584, 6789, -1, + 6791, 6792, 6789, -1, 6791, 6789, 6584, -1, + 6584, 6793, 6791, -1, 6793, 6584, 6585, -1, + 6585, 6794, 6793, -1, 6794, 6585, 6586, -1, + 6586, 6795, 6794, -1, 6795, 6586, 6587, -1, + 6587, 6796, 6795, -1, 6796, 6797, 6798, -1, + 6797, 6796, 6587, -1, 6797, 6587, 6588, -1, + 6797, 6588, 6590, -1, 6590, 6798, 6797, -1, + 6799, 6800, 6798, -1, 6801, 6799, 6802, -1, + 6801, 6803, 6799, -1, 6803, 6800, 6799, -1, + 6803, 6804, 6800, -1, 6803, 6801, 6804, -1, + 6801, 6802, 6804, -1, 6804, 6802, 6805, -1, + 6805, 6806, 6804, -1, 6806, 6805, 6807, -1, + 6807, 6808, 6806, -1, 6807, 6809, 6808, -1, + 6810, 6811, 6812, -1, 6810, 6813, 6811, -1, + 6813, 6810, 6814, -1, 6815, 6816, 6817, -1, + 6815, 6810, 6816, -1, 6815, 6814, 6810, -1, + 6814, 6815, 6817, -1, 6818, 6814, 6817, -1, + 6818, 6813, 6814, -1, 6818, 6819, 6813, -1, + 6819, 6818, 6817, -1, 6817, 6820, 6819, -1, + 6821, 6822, 6823, -1, 6821, 6824, 6822, -1, + 6821, 6825, 6824, -1, 6821, 6823, 6825, -1, + 6823, 6826, 6825, -1, 6826, 6823, 6827, -1, + 6827, 6828, 6826, -1, 6828, 6827, 6829, -1, + 6828, 6829, 6830, -1, 6831, 6832, 6833, -1, + 6833, 6834, 6831, -1, 6833, 6835, 6834, -1, + 6835, 6833, 6836, -1, 6836, 6837, 6835, -1, + 6837, 6836, 6838, -1, 6838, 6839, 6837, -1, + 6839, 6838, 6840, -1, 6840, 6841, 6839, -1, + 6841, 6840, 6842, -1, 6842, 6843, 6841, -1, + 6843, 6842, 6844, -1, 6844, 6845, 6843, -1, + 6845, 6844, 6846, -1, 6846, 6847, 6845, -1, + 6847, 6846, 6848, -1, 6848, 6849, 6847, -1, + 6849, 6848, 6850, -1, 6850, 6851, 6849, -1, + 6851, 6850, 6852, -1, 6852, 6853, 6851, -1, + 6853, 6852, 6854, -1, 6854, 6855, 6853, -1, + 6855, 6854, 6856, -1, 6856, 6857, 6855, -1, + 6857, 6856, 6858, -1, 6858, 6859, 6857, -1, + 6859, 6858, 6860, -1, 6860, 6861, 6859, -1, + 6861, 6860, 6862, -1, 6862, 6863, 6861, -1, + 6863, 6862, 6864, -1, 6864, 6865, 6863, -1, + 6865, 6864, 6866, -1, 6866, 6867, 6865, -1, + 6867, 6866, 6868, -1, 6868, 6869, 6867, -1, + 6869, 6868, 6870, -1, 6870, 6871, 6869, -1, + 6871, 6870, 6872, -1, 6872, 6873, 6871, -1, + 6873, 6872, 6874, -1, 6874, 6875, 6873, -1, + 6875, 6874, 6876, -1, 6876, 6829, 6875, -1, + 6876, 6830, 6829, -1, 6876, 6877, 6830, -1, + 6877, 6876, 6874, -1, 6874, 6878, 6877, -1, + 6878, 6874, 6872, -1, 6872, 6879, 6878, -1, + 6879, 6872, 6870, -1, 6870, 6880, 6879, -1, + 6880, 6870, 6868, -1, 6868, 6881, 6880, -1, + 6881, 6868, 6866, -1, 6866, 6882, 6881, -1, + 6882, 6866, 6864, -1, 6864, 6883, 6882, -1, + 6883, 6864, 6862, -1, 6862, 6884, 6883, -1, + 6884, 6862, 6860, -1, 6860, 6885, 6884, -1, + 6885, 6860, 6858, -1, 6858, 6886, 6885, -1, + 6886, 6858, 6856, -1, 6856, 6887, 6886, -1, + 6887, 6856, 6854, -1, 6854, 6888, 6887, -1, + 6888, 6854, 6852, -1, 6852, 6889, 6888, -1, + 6889, 6852, 6850, -1, 6850, 6890, 6889, -1, + 6890, 6850, 6848, -1, 6848, 6891, 6890, -1, + 6891, 6848, 6846, -1, 6846, 6892, 6891, -1, + 6892, 6846, 6844, -1, 6844, 6893, 6892, -1, + 6893, 6844, 6842, -1, 6842, 6894, 6893, -1, + 6894, 6842, 6840, -1, 6840, 6895, 6894, -1, + 6895, 6840, 6838, -1, 6838, 6896, 6895, -1, + 6896, 6838, 6836, -1, 6836, 6897, 6896, -1, + 6897, 6836, 6833, -1, 6833, 6832, 6897, -1, + 6898, 6899, 6900, -1, 6900, 6901, 6898, -1, + 6901, 6900, 6902, -1, 6902, 6903, 6901, -1, + 6903, 6902, 6904, -1, 6904, 6905, 6903, -1, + 6905, 6904, 6906, -1, 6906, 6907, 6905, -1, + 6907, 6906, 6908, -1, 6908, 6909, 6907, -1, + 6909, 6908, 6910, -1, 6910, 6911, 6909, -1, + 6911, 6910, 6912, -1, 6912, 6913, 6911, -1, + 6913, 6912, 6914, -1, 6914, 6915, 6913, -1, + 6915, 6914, 6916, -1, 6916, 6917, 6915, -1, + 6917, 6916, 6918, -1, 6918, 6919, 6917, -1, + 6919, 6918, 6920, -1, 6920, 6921, 6919, -1, + 6921, 6920, 6922, -1, 6922, 6923, 6921, -1, + 6923, 6922, 6924, -1, 6924, 6925, 6923, -1, + 6925, 6924, 6926, -1, 6926, 6927, 6925, -1, + 6927, 6926, 6928, -1, 6928, 6929, 6927, -1, + 6929, 6928, 6930, -1, 6930, 6931, 6929, -1, + 6931, 6930, 6932, -1, 6932, 6933, 6931, -1, + 6933, 6932, 6934, -1, 6934, 6935, 6933, -1, + 6935, 6934, 6936, -1, 6936, 6937, 6935, -1, + 6937, 6936, 6897, -1, 6937, 6897, 6832, -1, + 6937, 6832, 6938, -1, 6938, 6935, 6937, -1, + 6935, 6938, 6939, -1, 6939, 6933, 6935, -1, + 6933, 6939, 6940, -1, 6940, 6931, 6933, -1, + 6931, 6940, 6941, -1, 6941, 6929, 6931, -1, + 6929, 6941, 6942, -1, 6942, 6927, 6929, -1, + 6927, 6942, 6943, -1, 6943, 6925, 6927, -1, + 6925, 6943, 6944, -1, 6944, 6923, 6925, -1, + 6923, 6944, 6945, -1, 6945, 6921, 6923, -1, + 6921, 6945, 6946, -1, 6946, 6919, 6921, -1, + 6919, 6946, 6947, -1, 6947, 6917, 6919, -1, + 6917, 6947, 6948, -1, 6948, 6915, 6917, -1, + 6915, 6948, 6949, -1, 6949, 6913, 6915, -1, + 6913, 6949, 6950, -1, 6950, 6911, 6913, -1, + 6911, 6950, 6951, -1, 6951, 6909, 6911, -1, + 6909, 6951, 6952, -1, 6952, 6907, 6909, -1, + 6907, 6952, 6953, -1, 6953, 6905, 6907, -1, + 6905, 6953, 6954, -1, 6954, 6903, 6905, -1, + 6903, 6954, 6955, -1, 6955, 6901, 6903, -1, + 6901, 6955, 6956, -1, 6956, 6898, 6901, -1, + 6956, 6957, 6898, -1, 6956, 6958, 6957, -1, + 6958, 6956, 6955, -1, 6955, 6959, 6958, -1, + 6959, 6955, 6954, -1, 6954, 6960, 6959, -1, + 6960, 6954, 6953, -1, 6953, 6961, 6960, -1, + 6961, 6953, 6952, -1, 6952, 6962, 6961, -1, + 6962, 6952, 6951, -1, 6951, 6963, 6962, -1, + 6963, 6951, 6950, -1, 6950, 6964, 6963, -1, + 6964, 6950, 6949, -1, 6949, 6965, 6964, -1, + 6965, 6949, 6948, -1, 6948, 6966, 6965, -1, + 6966, 6948, 6947, -1, 6947, 6967, 6966, -1, + 6967, 6947, 6946, -1, 6946, 6968, 6967, -1, + 6968, 6946, 6945, -1, 6945, 6969, 6968, -1, + 6969, 6945, 6944, -1, 6944, 6970, 6969, -1, + 6970, 6944, 6943, -1, 6943, 6971, 6970, -1, + 6971, 6943, 6942, -1, 6942, 6972, 6971, -1, + 6972, 6942, 6941, -1, 6941, 6973, 6972, -1, + 6973, 6941, 6940, -1, 6940, 6974, 6973, -1, + 6974, 6940, 6939, -1, 6939, 6975, 6974, -1, + 6975, 6939, 6938, -1, 6938, 6976, 6975, -1, + 6976, 6938, 6832, -1, 6832, 6831, 6976, -1, + 6977, 6976, 6831, -1, 6831, 6978, 6977, -1, + 6978, 6831, 6834, -1, 6834, 6979, 6978, -1, + 6834, 6980, 6979, -1, 6980, 6834, 6835, -1, + 6835, 6981, 6980, -1, 6981, 6835, 6837, -1, + 6981, 6837, 6982, -1, 6983, 6984, 6985, -1, + 6985, 6986, 6983, -1, 6986, 6985, 6987, -1, + 6987, 6988, 6986, -1, 6988, 6987, 6989, -1, + 6990, 6989, 6987, -1, 6987, 6991, 6990, -1, + 6991, 6987, 6985, -1, 6985, 6992, 6991, -1, + 6992, 6985, 6984, -1, 6984, 6993, 6992, -1, + 6993, 6984, 6994, -1, 6994, 6995, 6993, -1, + 6995, 6994, 6996, -1, 6996, 6997, 6998, -1, + 6997, 6996, 6994, -1, 6997, 6994, 6999, -1, + 6999, 6998, 6997, -1, 6999, 7000, 6998, -1, + 6999, 6994, 7000, -1, 6994, 7001, 7000, -1, + 7001, 6994, 6984, -1, 6984, 6983, 7001, -1, + 7001, 7002, 7003, -1, 7002, 7001, 6983, -1, + 6983, 7004, 7002, -1, 7004, 6983, 6986, -1, + 6986, 7005, 7004, -1, 7005, 6986, 6988, -1, + 7005, 6988, 7006, -1, 7007, 7006, 6988, -1, + 7007, 7008, 7006, -1, 7008, 7007, 7009, -1, + 7009, 7010, 7008, -1, 7010, 7009, 7011, -1, + 7011, 7012, 7010, -1, 7012, 7011, 7013, -1, + 7013, 7014, 7012, -1, 7014, 7013, 7015, -1, + 7015, 7016, 7014, -1, 7016, 7015, 7017, -1, + 7017, 7018, 7016, -1, 7018, 7017, 7019, -1, + 7019, 7020, 7018, -1, 7020, 7019, 7021, -1, + 7021, 7022, 7020, -1, 7022, 7021, 7023, -1, + 7023, 7024, 7022, -1, 7024, 7023, 7025, -1, + 7025, 7026, 7024, -1, 7026, 7025, 7027, -1, + 7027, 7028, 7026, -1, 7028, 7027, 7029, -1, + 7029, 7030, 7028, -1, 7030, 7029, 7031, -1, + 7031, 7032, 7030, -1, 7032, 7031, 7033, -1, + 7033, 7034, 7032, -1, 7034, 7033, 7035, -1, + 7035, 7036, 7034, -1, 7036, 7035, 7037, -1, + 7037, 7038, 7036, -1, 7038, 7037, 7039, -1, + 7039, 7040, 7038, -1, 7040, 7039, 7041, -1, + 7041, 7042, 7040, -1, 7042, 7041, 7043, -1, + 7043, 7044, 7042, -1, 7044, 7043, 6982, -1, + 7044, 6982, 6837, -1, 7044, 6837, 6839, -1, + 6839, 7042, 7044, -1, 7042, 6839, 6841, -1, + 6841, 7040, 7042, -1, 7040, 6841, 6843, -1, + 6843, 7038, 7040, -1, 7038, 6843, 6845, -1, + 6845, 7036, 7038, -1, 7036, 6845, 6847, -1, + 6847, 7034, 7036, -1, 7034, 6847, 6849, -1, + 6849, 7032, 7034, -1, 7032, 6849, 6851, -1, + 6851, 7030, 7032, -1, 7030, 6851, 6853, -1, + 6853, 7028, 7030, -1, 7028, 6853, 6855, -1, + 6855, 7026, 7028, -1, 7026, 6855, 6857, -1, + 6857, 7024, 7026, -1, 7024, 6857, 6859, -1, + 6859, 7022, 7024, -1, 7022, 6859, 6861, -1, + 6861, 7020, 7022, -1, 7020, 6861, 6863, -1, + 6863, 7018, 7020, -1, 7018, 6863, 6865, -1, + 6865, 7016, 7018, -1, 7016, 6865, 6867, -1, + 6867, 7014, 7016, -1, 7014, 6867, 6869, -1, + 6869, 7012, 7014, -1, 7012, 6869, 6871, -1, + 6871, 7010, 7012, -1, 7010, 6871, 6873, -1, + 6873, 7008, 7010, -1, 7008, 6873, 6875, -1, + 6875, 7006, 7008, -1, 7006, 6875, 6829, -1, + 6829, 7005, 7006, -1, 7005, 6829, 6827, -1, + 6827, 7004, 7005, -1, 7004, 6827, 6823, -1, + 6823, 7002, 7004, -1, 7002, 6823, 6822, -1, + 7045, 7002, 6822, -1, 7045, 6822, 6824, -1, + 7045, 6824, 7046, -1, 7046, 7002, 7045, -1, + 7046, 7003, 7002, -1, 7003, 7046, 6824, -1, + 7003, 6824, 7047, -1, 7047, 7001, 7003, -1, + 7047, 7000, 7001, -1, 7047, 6998, 7000, -1, + 6998, 7047, 6824, -1, 6820, 6824, 6825, -1, + 6825, 7048, 6820, -1, 7048, 6825, 6826, -1, + 7048, 6826, 7049, -1, 7049, 6820, 7048, -1, + 7049, 6819, 6820, -1, 7049, 6826, 6819, -1, + 6826, 6813, 6819, -1, 6813, 6826, 6828, -1, + 6828, 6811, 6813, -1, 6811, 6828, 6830, -1, + 6830, 7050, 6811, -1, 7050, 6830, 6877, -1, + 6877, 7051, 7050, -1, 7051, 6877, 6878, -1, + 6878, 7052, 7051, -1, 7052, 6878, 6879, -1, + 6879, 7053, 7052, -1, 7053, 6879, 6880, -1, + 6880, 7054, 7053, -1, 7054, 6880, 6881, -1, + 6881, 7055, 7054, -1, 7055, 6881, 6882, -1, + 6882, 7056, 7055, -1, 7056, 6882, 6883, -1, + 6883, 7057, 7056, -1, 7057, 6883, 6884, -1, + 6884, 7058, 7057, -1, 7058, 6884, 6885, -1, + 6885, 7059, 7058, -1, 7059, 6885, 6886, -1, + 6886, 7060, 7059, -1, 7060, 6886, 6887, -1, + 6887, 7061, 7060, -1, 7061, 6887, 6888, -1, + 6888, 7062, 7061, -1, 7062, 6888, 6889, -1, + 6889, 7063, 7062, -1, 7063, 6889, 6890, -1, + 6890, 7064, 7063, -1, 7064, 6890, 6891, -1, + 6891, 7065, 7064, -1, 7065, 6891, 6892, -1, + 6892, 7066, 7065, -1, 7066, 6892, 6893, -1, + 6893, 7067, 7066, -1, 7067, 6893, 6894, -1, + 6894, 7068, 7067, -1, 7068, 6894, 6895, -1, + 6895, 7069, 7068, -1, 7069, 6895, 6896, -1, + 6896, 7070, 7069, -1, 7070, 6896, 6897, -1, + 7070, 6897, 6936, -1, 6936, 7071, 7070, -1, + 7071, 6936, 6934, -1, 6934, 7072, 7071, -1, + 7072, 6934, 6932, -1, 6932, 7073, 7072, -1, + 7073, 6932, 6930, -1, 6930, 7074, 7073, -1, + 7074, 6930, 6928, -1, 6928, 7075, 7074, -1, + 7075, 6928, 6926, -1, 6926, 7076, 7075, -1, + 7076, 6926, 6924, -1, 6924, 7077, 7076, -1, + 7077, 6924, 6922, -1, 6922, 7078, 7077, -1, + 7078, 6922, 6920, -1, 6920, 7079, 7078, -1, + 7079, 6920, 6918, -1, 6918, 7080, 7079, -1, + 7080, 6918, 6916, -1, 6916, 7081, 7080, -1, + 7081, 6916, 6914, -1, 6914, 7082, 7081, -1, + 7082, 6914, 6912, -1, 6912, 7083, 7082, -1, + 7083, 6912, 6910, -1, 6910, 7084, 7083, -1, + 7084, 6910, 6908, -1, 6908, 7085, 7084, -1, + 7085, 6908, 6906, -1, 6906, 7086, 7085, -1, + 7086, 6906, 6904, -1, 6904, 7087, 7086, -1, + 7087, 6904, 6902, -1, 6902, 7088, 7087, -1, + 7088, 6902, 6900, -1, 6900, 7089, 7088, -1, + 7089, 6900, 6899, -1, 6899, 6809, 7089, -1, + 6899, 6808, 6809, -1, 6899, 6898, 6808, -1, + 6808, 6898, 6957, -1, 6808, 6957, 7090, -1, + 7090, 6806, 6808, -1, 6806, 7090, 7091, -1, + 7091, 6804, 6806, -1, 6804, 7091, 7092, -1, + 7092, 6800, 6804, -1, 7093, 7092, 7094, -1, + 7093, 6800, 7092, -1, 7093, 6798, 6800, -1, + 7093, 7094, 6798, -1, 7095, 6798, 7094, -1, + 7095, 7096, 6798, -1, 7096, 6796, 6798, -1, + 7096, 6795, 6796, -1, 7096, 7095, 6795, -1, + 7095, 7094, 6795, -1, 6795, 7094, 7092, -1, + 7092, 6794, 6795, -1, 6794, 7092, 7091, -1, + 7091, 6793, 6794, -1, 6793, 7091, 7090, -1, + 7090, 6791, 6793, -1, 6791, 7090, 6957, -1, + 6957, 6792, 6791, -1, 6792, 6957, 6958, -1, + 6958, 7097, 6792, -1, 7097, 6958, 6959, -1, + 6959, 7098, 7097, -1, 7098, 6959, 6960, -1, + 6960, 7099, 7098, -1, 7099, 6960, 6961, -1, + 6961, 7100, 7099, -1, 7100, 6961, 6962, -1, + 6962, 7101, 7100, -1, 7101, 6962, 6963, -1, + 6963, 7102, 7101, -1, 7102, 6963, 6964, -1, + 6964, 7103, 7102, -1, 7103, 6964, 6965, -1, + 6965, 7104, 7103, -1, 7104, 6965, 6966, -1, + 6966, 7105, 7104, -1, 7105, 6966, 6967, -1, + 6967, 7106, 7105, -1, 7106, 6967, 6968, -1, + 6968, 7107, 7106, -1, 7107, 6968, 6969, -1, + 6969, 7108, 7107, -1, 7108, 6969, 6970, -1, + 6970, 7109, 7108, -1, 7109, 6970, 6971, -1, + 6971, 7110, 7109, -1, 7110, 6971, 6972, -1, + 6972, 7111, 7110, -1, 7111, 6972, 6973, -1, + 6973, 7112, 7111, -1, 7112, 6973, 6974, -1, + 6974, 7113, 7112, -1, 7113, 6974, 6975, -1, + 6975, 7114, 7113, -1, 7114, 6975, 6976, -1, + 6976, 6977, 7114, -1, 7115, 7114, 6977, -1, + 7114, 7115, 7116, -1, 7116, 7113, 7114, -1, + 7113, 7116, 7117, -1, 7117, 7112, 7113, -1, + 7112, 7117, 7118, -1, 7118, 7111, 7112, -1, + 7111, 7118, 7119, -1, 7119, 7110, 7111, -1, + 7110, 7119, 7120, -1, 7120, 7109, 7110, -1, + 7109, 7120, 7121, -1, 7121, 7108, 7109, -1, + 7108, 7121, 7122, -1, 7122, 7107, 7108, -1, + 7107, 7122, 7123, -1, 7123, 7106, 7107, -1, + 7106, 7123, 7124, -1, 7124, 7105, 7106, -1, + 7105, 7124, 7125, -1, 7125, 7104, 7105, -1, + 7104, 7125, 7126, -1, 7126, 7103, 7104, -1, + 7103, 7126, 7127, -1, 7127, 7102, 7103, -1, + 7102, 7127, 7128, -1, 7128, 7101, 7102, -1, + 7101, 7128, 7129, -1, 7129, 7100, 7101, -1, + 7100, 7129, 7130, -1, 7130, 7099, 7100, -1, + 7099, 7130, 7131, -1, 7131, 7098, 7099, -1, + 7098, 7131, 7132, -1, 7132, 7097, 7098, -1, + 7097, 7132, 7133, -1, 7133, 6792, 7097, -1, + 7133, 6789, 6792, -1, 7133, 6790, 6789, -1, + 6790, 7133, 7132, -1, 7132, 7134, 6790, -1, + 7134, 7132, 7131, -1, 7131, 7135, 7134, -1, + 7135, 7131, 7130, -1, 7130, 7136, 7135, -1, + 7136, 7130, 7129, -1, 7129, 7137, 7136, -1, + 7137, 7129, 7128, -1, 7128, 7138, 7137, -1, + 7138, 7128, 7127, -1, 7127, 7139, 7138, -1, + 7139, 7127, 7126, -1, 7126, 7140, 7139, -1, + 7140, 7126, 7125, -1, 7125, 7141, 7140, -1, + 7141, 7125, 7124, -1, 7124, 7142, 7141, -1, + 7142, 7124, 7123, -1, 7123, 7143, 7142, -1, + 7143, 7123, 7122, -1, 7122, 7144, 7143, -1, + 7144, 7122, 7121, -1, 7121, 7145, 7144, -1, + 7145, 7121, 7120, -1, 7120, 7146, 7145, -1, + 7146, 7120, 7119, -1, 7119, 7147, 7146, -1, + 7147, 7119, 7118, -1, 7118, 7148, 7147, -1, + 7148, 7118, 7117, -1, 7117, 7149, 7148, -1, + 7149, 7117, 7116, -1, 7116, 7150, 7149, -1, + 7150, 7116, 7115, -1, 7115, 7151, 7150, -1, + 7115, 6977, 7151, -1, 7152, 7151, 6977, -1, + 7152, 6977, 6978, -1, 6978, 7153, 7152, -1, + 7153, 6978, 6979, -1, 6979, 7154, 7153, -1, + 6979, 7155, 7154, -1, 7155, 6979, 6980, -1, + 6980, 7156, 7155, -1, 7156, 6980, 6981, -1, + 6981, 7157, 7156, -1, 7157, 6981, 6982, -1, + 6982, 7158, 7157, -1, 7158, 6982, 7043, -1, + 7043, 7159, 7158, -1, 7159, 7043, 7041, -1, + 7041, 7160, 7159, -1, 7160, 7041, 7039, -1, + 7039, 7161, 7160, -1, 7161, 7039, 7037, -1, + 7037, 7162, 7161, -1, 7162, 7037, 7035, -1, + 7035, 7163, 7162, -1, 7163, 7035, 7033, -1, + 7033, 7164, 7163, -1, 7164, 7033, 7031, -1, + 7031, 7165, 7164, -1, 7165, 7031, 7029, -1, + 7029, 7166, 7165, -1, 7166, 7029, 7027, -1, + 7027, 7167, 7166, -1, 7167, 7027, 7025, -1, + 7025, 7168, 7167, -1, 7168, 7025, 7023, -1, + 7023, 7169, 7168, -1, 7169, 7023, 7021, -1, + 7021, 7170, 7169, -1, 7170, 7021, 7019, -1, + 7019, 7171, 7170, -1, 7171, 7019, 7017, -1, + 7017, 7172, 7171, -1, 7172, 7017, 7015, -1, + 7015, 7173, 7172, -1, 7173, 7015, 7013, -1, + 7013, 7174, 7173, -1, 7174, 7013, 7011, -1, + 7011, 7175, 7174, -1, 7175, 7011, 7009, -1, + 7009, 7176, 7175, -1, 7176, 7009, 7007, -1, + 7007, 6988, 7176, -1, 6988, 6989, 7176, -1, + 7177, 7178, 7179, -1, 7178, 7177, 7180, -1, + 7180, 7181, 7178, -1, 7181, 7180, 7182, -1, + 7182, 7183, 7181, -1, 7183, 7182, 7184, -1, + 7184, 7185, 7183, -1, 7185, 7184, 7186, -1, + 7186, 7187, 7185, -1, 7187, 7186, 7188, -1, + 7188, 7189, 7187, -1, 7189, 7188, 7190, -1, + 7190, 7191, 7189, -1, 7191, 7190, 7192, -1, + 7192, 7193, 7191, -1, 7193, 7192, 7194, -1, + 7194, 7195, 7193, -1, 7195, 7194, 7196, -1, + 7196, 7197, 7195, -1, 7197, 7196, 7198, -1, + 7198, 7199, 7197, -1, 7199, 7198, 7200, -1, + 7200, 7201, 7199, -1, 7201, 7200, 7202, -1, + 7202, 7203, 7201, -1, 7203, 7202, 7204, -1, + 7204, 7205, 7203, -1, 7205, 7204, 7206, -1, + 7206, 7207, 7205, -1, 7207, 7206, 7208, -1, + 7208, 7209, 7207, -1, 7209, 7208, 7210, -1, + 7210, 7211, 7209, -1, 7211, 7210, 7212, -1, + 7212, 7213, 7211, -1, 7213, 7212, 7214, -1, + 7214, 6989, 7213, -1, 7214, 7176, 6989, -1, + 7214, 7175, 7176, -1, 7175, 7214, 7212, -1, + 7212, 7174, 7175, -1, 7174, 7212, 7210, -1, + 7210, 7173, 7174, -1, 7173, 7210, 7208, -1, + 7208, 7172, 7173, -1, 7172, 7208, 7206, -1, + 7206, 7171, 7172, -1, 7171, 7206, 7204, -1, + 7204, 7170, 7171, -1, 7170, 7204, 7202, -1, + 7202, 7169, 7170, -1, 7169, 7202, 7200, -1, + 7200, 7168, 7169, -1, 7168, 7200, 7198, -1, + 7198, 7167, 7168, -1, 7167, 7198, 7196, -1, + 7196, 7166, 7167, -1, 7166, 7196, 7194, -1, + 7194, 7165, 7166, -1, 7165, 7194, 7192, -1, + 7192, 7164, 7165, -1, 7164, 7192, 7190, -1, + 7190, 7163, 7164, -1, 7163, 7190, 7188, -1, + 7188, 7162, 7163, -1, 7162, 7188, 7186, -1, + 7186, 7161, 7162, -1, 7161, 7186, 7184, -1, + 7184, 7160, 7161, -1, 7160, 7184, 7182, -1, + 7182, 7159, 7160, -1, 7159, 7182, 7180, -1, + 7180, 7158, 7159, -1, 7158, 7180, 7177, -1, + 7177, 7157, 7158, -1, 7177, 7179, 7157, -1, + 7215, 7157, 7179, -1, 7215, 7156, 7157, -1, + 7156, 7215, 7216, -1, 7216, 7155, 7156, -1, + 7155, 7216, 7217, -1, 7217, 7154, 7155, -1, + 7154, 7217, 7218, -1, 7154, 7218, 7219, -1, + 7219, 7153, 7154, -1, 7153, 7219, 7220, -1, + 7220, 7152, 7153, -1, 7152, 7220, 7221, -1, + 7221, 7151, 7152, -1, 7151, 7221, 7222, -1, + 7222, 7150, 7151, -1, 7150, 7222, 7223, -1, + 7223, 7149, 7150, -1, 7149, 7223, 7224, -1, + 7224, 7148, 7149, -1, 7148, 7224, 7225, -1, + 7225, 7147, 7148, -1, 7147, 7225, 7226, -1, + 7226, 7146, 7147, -1, 7146, 7226, 7227, -1, + 7227, 7145, 7146, -1, 7145, 7227, 7228, -1, + 7228, 7144, 7145, -1, 7144, 7228, 7229, -1, + 7229, 7143, 7144, -1, 7143, 7229, 7230, -1, + 7230, 7142, 7143, -1, 7142, 7230, 7231, -1, + 7231, 7141, 7142, -1, 7141, 7231, 7232, -1, + 7232, 7140, 7141, -1, 7140, 7232, 7233, -1, + 7233, 7139, 7140, -1, 7139, 7233, 7234, -1, + 7234, 7138, 7139, -1, 7138, 7234, 7235, -1, + 7235, 7137, 7138, -1, 7137, 7235, 7236, -1, + 7236, 7136, 7137, -1, 7136, 7236, 7237, -1, + 7237, 7135, 7136, -1, 7135, 7237, 7238, -1, + 7238, 7134, 7135, -1, 7134, 7238, 7239, -1, + 7239, 6790, 7134, -1, 7239, 6788, 6790, -1, + 7239, 6787, 6788, -1, 6787, 7239, 7238, -1, + 7238, 6786, 6787, -1, 6786, 7238, 7237, -1, + 7237, 6785, 6786, -1, 6785, 7237, 7236, -1, + 7236, 6784, 6785, -1, 6784, 7236, 7235, -1, + 7235, 6783, 6784, -1, 6783, 7235, 7234, -1, + 7234, 6782, 6783, -1, 6782, 7234, 7233, -1, + 7233, 6781, 6782, -1, 6781, 7233, 7232, -1, + 7232, 6780, 6781, -1, 6780, 7232, 7231, -1, + 7231, 6779, 6780, -1, 6779, 7231, 7230, -1, + 7230, 6778, 6779, -1, 6778, 7230, 7229, -1, + 7229, 6777, 6778, -1, 6777, 7229, 7228, -1, + 7228, 6776, 6777, -1, 6776, 7228, 7227, -1, + 7227, 6775, 6776, -1, 6775, 7227, 7226, -1, + 7226, 6774, 6775, -1, 6774, 7226, 7225, -1, + 7225, 6773, 6774, -1, 6773, 7225, 7224, -1, + 7224, 6772, 6773, -1, 6772, 7224, 7223, -1, + 7223, 6771, 6772, -1, 6771, 7223, 7222, -1, + 7222, 6680, 6771, -1, 6680, 7222, 7221, -1, + 7221, 6681, 6680, -1, 6681, 7221, 7220, -1, + 7220, 6683, 6681, -1, 6683, 7220, 7219, -1, + 7219, 6685, 6683, -1, 6685, 7219, 7218, -1, + 7218, 6687, 6685, -1, 7218, 6690, 6687, -1, + 6690, 7218, 7217, -1, 7217, 6692, 6690, -1, + 6692, 7217, 7216, -1, 7216, 6694, 6692, -1, + 6694, 7216, 7215, -1, 7215, 6696, 6694, -1, + 6696, 7215, 7179, -1, 7179, 6698, 6696, -1, + 6698, 7179, 7178, -1, 7178, 6700, 6698, -1, + 6700, 7178, 7181, -1, 7181, 6702, 6700, -1, + 6702, 7181, 7183, -1, 7183, 6704, 6702, -1, + 6704, 7183, 7185, -1, 7185, 6706, 6704, -1, + 6706, 7185, 7187, -1, 7187, 6708, 6706, -1, + 6708, 7187, 7189, -1, 7189, 6710, 6708, -1, + 6710, 7189, 7191, -1, 7191, 6712, 6710, -1, + 6712, 7191, 7193, -1, 7193, 6714, 6712, -1, + 6714, 7193, 7195, -1, 7195, 6716, 6714, -1, + 6716, 7195, 7197, -1, 7197, 6718, 6716, -1, + 6718, 7197, 7199, -1, 7199, 6720, 6718, -1, + 6720, 7199, 7201, -1, 7201, 6722, 6720, -1, + 6722, 7201, 7203, -1, 7203, 6724, 6722, -1, + 6724, 7203, 7205, -1, 7205, 6726, 6724, -1, + 6726, 7205, 7207, -1, 7207, 6728, 6726, -1, + 6728, 7207, 7209, -1, 7209, 6730, 6728, -1, + 6730, 7209, 7211, -1, 7211, 6732, 6730, -1, + 6732, 7211, 7213, -1, 7213, 6734, 6732, -1, + 6734, 7213, 6989, -1, 6989, 6990, 6734, -1, + 6990, 6677, 6734, -1, 6990, 7240, 6677, -1, + 7240, 6990, 6991, -1, 6991, 7241, 7240, -1, + 7241, 6991, 6992, -1, 6992, 7242, 7241, -1, + 7242, 6992, 6993, -1, 6993, 7243, 7242, -1, + 7243, 6993, 6995, -1, 6995, 7244, 7243, -1, + 7244, 6995, 7245, -1, 7246, 7244, 7245, -1, + 7246, 7247, 7244, -1, 7247, 7248, 7244, -1, + 7247, 7249, 7248, -1, 7247, 7246, 7249, -1, + 7246, 7245, 7249, -1, 7245, 7250, 7249, -1, + 7250, 7245, 6995, -1, 7250, 6995, 6996, -1, + 7250, 6996, 6998, -1, 6998, 7249, 7250, -1, + 7249, 3728, 3727, -1, 3727, 7248, 7249, -1, + 3727, 3724, 7248, -1, 3724, 7244, 7248, -1, + 7244, 3724, 3722, -1, 3722, 7243, 7244, -1, + 7243, 3722, 3720, -1, 3720, 7242, 7243, -1, + 7242, 3720, 3718, -1, 3718, 7241, 7242, -1, + 7241, 3718, 3716, -1, 3716, 7240, 7241, -1, + 7240, 3716, 3714, -1, 3714, 6677, 7240, -1, + 6677, 3714, 3713, -1, 3713, 6675, 6677, -1, + 6675, 3713, 7251, -1, 7251, 6673, 6675, -1, + 6673, 7251, 7252, -1, 7252, 6671, 6673, -1, + 6671, 7252, 7253, -1, 7253, 6669, 6671, -1, + 6669, 7253, 7254, -1, 7254, 6667, 6669, -1, + 6667, 7254, 7255, -1, 7255, 6665, 6667, -1, + 6665, 7255, 7256, -1, 7256, 6663, 6665, -1, + 6663, 7256, 7257, -1, 7257, 6661, 6663, -1, + 6661, 7257, 7258, -1, 7258, 6659, 6661, -1, + 6659, 7258, 7259, -1, 7259, 6657, 6659, -1, + 6657, 7259, 7260, -1, 7260, 6655, 6657, -1, + 6655, 7260, 7261, -1, 7261, 6653, 6655, -1, + 6653, 7261, 7262, -1, 7262, 6651, 6653, -1, + 6651, 7262, 7263, -1, 7263, 6649, 6651, -1, + 6649, 7263, 7264, -1, 7264, 6647, 6649, -1, + 6647, 7264, 7265, -1, 7265, 6645, 6647, -1, + 6645, 7265, 7266, -1, 7266, 6642, 6645, -1, + 6642, 7266, 7267, -1, 7267, 6643, 6642, -1, + 6643, 7267, 7268, -1, 7268, 6735, 6643, -1, + 6735, 7268, 7269, -1, 7269, 6639, 6735, -1, + 7269, 6640, 6639, -1, 7269, 7270, 6640, -1, + 7270, 7269, 7268, -1, 7268, 7271, 7270, -1, + 7271, 7268, 7267, -1, 7267, 7272, 7271, -1, + 7272, 7267, 7266, -1, 7266, 7273, 7272, -1, + 7273, 7266, 7265, -1, 7265, 7274, 7273, -1, + 7274, 7265, 7264, -1, 7264, 7275, 7274, -1, + 7275, 7264, 7263, -1, 7263, 7276, 7275, -1, + 7276, 7263, 7262, -1, 7262, 7277, 7276, -1, + 7277, 7262, 7261, -1, 7261, 7278, 7277, -1, + 7278, 7261, 7260, -1, 7260, 7279, 7278, -1, + 7279, 7260, 7259, -1, 7259, 7280, 7279, -1, + 7280, 7259, 7258, -1, 7258, 7281, 7280, -1, + 7281, 7258, 7257, -1, 7257, 7282, 7281, -1, + 7282, 7257, 7256, -1, 7256, 7283, 7282, -1, + 7283, 7256, 7255, -1, 7255, 7284, 7283, -1, + 7284, 7255, 7254, -1, 7254, 7285, 7284, -1, + 7285, 7254, 7253, -1, 7253, 7286, 7285, -1, + 7286, 7253, 7252, -1, 7252, 7287, 7286, -1, + 7287, 7252, 7251, -1, 7251, 7288, 7287, -1, + 7288, 7251, 3713, -1, 3713, 3712, 7288, -1, + 7288, 3712, 3743, -1, 3743, 7287, 7288, -1, + 7287, 3743, 7289, -1, 7289, 7286, 7287, -1, + 7286, 7289, 7290, -1, 7290, 7285, 7286, -1, + 7285, 7290, 7291, -1, 7291, 7284, 7285, -1, + 7284, 7291, 7292, -1, 7292, 7283, 7284, -1, + 7283, 7292, 7293, -1, 7293, 7282, 7283, -1, + 7282, 7293, 7294, -1, 7294, 7281, 7282, -1, + 7281, 7294, 7295, -1, 7295, 7280, 7281, -1, + 7280, 7295, 7296, -1, 7296, 7279, 7280, -1, + 7279, 7296, 7297, -1, 7297, 7278, 7279, -1, + 7278, 7297, 7298, -1, 7298, 7277, 7278, -1, + 7277, 7298, 7299, -1, 7299, 7276, 7277, -1, + 7276, 7299, 7300, -1, 7300, 7275, 7276, -1, + 7275, 7300, 7301, -1, 7301, 7274, 7275, -1, + 7274, 7301, 7302, -1, 7302, 7273, 7274, -1, + 7273, 7302, 7303, -1, 7303, 7272, 7273, -1, + 7272, 7303, 7304, -1, 7304, 7271, 7272, -1, + 7271, 7304, 7305, -1, 7305, 7270, 7271, -1, + 7270, 7305, 7306, -1, 7306, 6640, 7270, -1, + 6640, 7306, 7307, -1, 7307, 6638, 6640, -1, + 7307, 7308, 6638, -1, 7307, 7309, 7308, -1, + 7309, 7307, 7306, -1, 7306, 7310, 7309, -1, + 7310, 7306, 7305, -1, 7305, 7311, 7310, -1, + 7311, 7305, 7304, -1, 7304, 7312, 7311, -1, + 7312, 7304, 7303, -1, 7303, 7313, 7312, -1, + 7313, 7303, 7302, -1, 7302, 7314, 7313, -1, + 7314, 7302, 7301, -1, 7301, 7315, 7314, -1, + 7315, 7301, 7300, -1, 7300, 7316, 7315, -1, + 7316, 7300, 7299, -1, 7299, 7317, 7316, -1, + 7317, 7299, 7298, -1, 7298, 7318, 7317, -1, + 7318, 7298, 7297, -1, 7297, 7319, 7318, -1, + 7319, 7297, 7296, -1, 7296, 7320, 7319, -1, + 7320, 7296, 7295, -1, 7295, 7321, 7320, -1, + 7321, 7295, 7294, -1, 7294, 7322, 7321, -1, + 7322, 7294, 7293, -1, 7293, 7323, 7322, -1, + 7323, 7293, 7292, -1, 7292, 7324, 7323, -1, + 7324, 7292, 7291, -1, 7291, 7325, 7324, -1, + 7325, 7291, 7290, -1, 7290, 7326, 7325, -1, + 7326, 7290, 7289, -1, 7289, 7327, 7326, -1, + 7327, 7289, 3743, -1, 3743, 3742, 7327, -1, + 7327, 3742, 3812, -1, 3812, 7326, 7327, -1, + 7326, 3812, 3810, -1, 3810, 7325, 7326, -1, + 7325, 3810, 3808, -1, 3808, 7324, 7325, -1, + 7324, 3808, 3806, -1, 3806, 7323, 7324, -1, + 7323, 3806, 3804, -1, 3804, 7322, 7323, -1, + 7322, 3804, 3802, -1, 3802, 7321, 7322, -1, + 7321, 3802, 3800, -1, 3800, 7320, 7321, -1, + 7320, 3800, 3798, -1, 3798, 7319, 7320, -1, + 7319, 3798, 3796, -1, 3796, 7318, 7319, -1, + 7318, 3796, 3794, -1, 3794, 7317, 7318, -1, + 7317, 3794, 3792, -1, 3792, 7316, 7317, -1, + 7316, 3792, 3790, -1, 3790, 7315, 7316, -1, + 7315, 3790, 3788, -1, 3788, 7314, 7315, -1, + 7314, 3788, 3786, -1, 3786, 7313, 7314, -1, + 7313, 3786, 3784, -1, 3784, 7312, 7313, -1, + 7312, 3784, 3782, -1, 3782, 7311, 7312, -1, + 7311, 3782, 3780, -1, 3780, 7310, 7311, -1, + 7310, 3780, 3778, -1, 3778, 7309, 7310, -1, + 7309, 3778, 3776, -1, 3776, 7308, 7309, -1, + 7308, 3776, 3774, -1, 3774, 3772, 7308, -1, + 3772, 6638, 7308, -1, 3772, 6636, 6638, -1, + 6636, 3772, 3771, -1, 3771, 6634, 6636, -1, + 6634, 3771, 3770, -1, 3770, 6632, 6634, -1, + 6632, 3770, 3769, -1, 3769, 6631, 6632, -1, + 6631, 3769, 3768, -1, 6631, 3768, 3767, -1, + 3767, 6629, 6631, -1, 6629, 3767, 3766, -1, + 3766, 6627, 6629, -1, 6627, 3766, 3765, -1, + 3765, 6625, 6627, -1, 6625, 3765, 3764, -1, + 3764, 6623, 6625, -1, 3764, 7328, 6623, -1, + 7329, 7330, 7331, -1, 7330, 7329, 7332, -1, + 7332, 7333, 7330, -1, 7333, 7332, 7334, -1, + 7334, 7335, 7333, -1, 7335, 7334, 7336, -1, + 7336, 7337, 7335, -1, 7337, 7336, 7338, -1, + 7338, 7339, 7337, -1, 7339, 7338, 7340, -1, + 7340, 7341, 7339, -1, 7341, 7340, 7342, -1, + 7342, 7343, 7341, -1, 7343, 7342, 7344, -1, + 7344, 7345, 7343, -1, 7345, 7344, 7346, -1, + 7346, 7347, 7345, -1, 7347, 7346, 7348, -1, + 7348, 7349, 7347, -1, 7349, 7348, 7350, -1, + 7350, 7351, 7349, -1, 7351, 7350, 7352, -1, + 7352, 7353, 7351, -1, 7353, 7352, 7354, -1, + 7354, 7355, 7353, -1, 7355, 7354, 7356, -1, + 7356, 7357, 7355, -1, 7357, 7356, 7358, -1, + 7358, 7359, 7357, -1, 7360, 7359, 7361, -1, + 7359, 7360, 7362, -1, 7362, 7357, 7359, -1, + 7357, 7362, 7363, -1, 7363, 7355, 7357, -1, + 7355, 7363, 7364, -1, 7364, 7353, 7355, -1, + 7353, 7364, 7365, -1, 7365, 7351, 7353, -1, + 7351, 7365, 7366, -1, 7366, 7349, 7351, -1, + 7349, 7366, 7367, -1, 7367, 7347, 7349, -1, + 7347, 7367, 7368, -1, 7368, 7345, 7347, -1, + 7345, 7368, 7369, -1, 7369, 7343, 7345, -1, + 7343, 7369, 7370, -1, 7370, 7341, 7343, -1, + 7341, 7370, 7371, -1, 7371, 7339, 7341, -1, + 7339, 7371, 7372, -1, 7372, 7337, 7339, -1, + 7337, 7372, 7373, -1, 7373, 7335, 7337, -1, + 7335, 7373, 7374, -1, 7374, 7333, 7335, -1, + 7333, 7374, 7375, -1, 7375, 7330, 7333, -1, + 7330, 7375, 7376, -1, 7376, 7331, 7330, -1, + 7331, 7376, 7377, -1, 7377, 7378, 7331, -1, + 7378, 7377, 7379, -1, 7379, 7380, 7378, -1, + 7380, 7379, 7381, -1, 7381, 7328, 7380, -1, + 7381, 6623, 7328, -1, 7381, 6622, 6623, -1, + 6622, 7381, 7379, -1, 7379, 6621, 6622, -1, + 6621, 7379, 7377, -1, 7377, 6620, 6621, -1, + 6620, 7377, 7376, -1, 7376, 6619, 6620, -1, + 6619, 7376, 7375, -1, 7375, 6618, 6619, -1, + 6618, 7375, 7374, -1, 7374, 6617, 6618, -1, + 6617, 7374, 7373, -1, 7373, 6616, 6617, -1, + 6616, 7373, 7372, -1, 7372, 6615, 6616, -1, + 6615, 7372, 7371, -1, 7371, 6614, 6615, -1, + 6614, 7371, 7370, -1, 7370, 6613, 6614, -1, + 6613, 7370, 7369, -1, 7369, 6612, 6613, -1, + 6612, 7369, 7368, -1, 7368, 6611, 6612, -1, + 6611, 7368, 7367, -1, 7367, 6610, 6611, -1, + 6610, 7367, 7366, -1, 7366, 6609, 6610, -1, + 6609, 7366, 7365, -1, 7365, 6608, 6609, -1, + 6608, 7365, 7364, -1, 7364, 6607, 6608, -1, + 6607, 7364, 7363, -1, 7363, 6606, 6607, -1, + 6606, 7363, 7362, -1, 7362, 6605, 6606, -1, + 6605, 7362, 7360, -1, 7360, 6604, 6605, -1, + 6604, 7360, 7361, -1, 7361, 6603, 6604, -1, + 6603, 7361, 7382, -1, 7382, 6602, 6603, -1, + 6602, 7382, 7383, -1, 7383, 6601, 6602, -1, + 6601, 7383, 7384, -1, 7384, 6600, 6601, -1, + 6600, 7384, 7385, -1, 7385, 6599, 6600, -1, + 6599, 7385, 7386, -1, 7386, 6598, 6599, -1, + 6598, 7386, 7387, -1, 7387, 6597, 6598, -1, + 7388, 7389, 6597, -1, 6597, 7387, 7388, -1, + 7388, 7390, 7391, -1, 7388, 7392, 7390, -1, + 7392, 7388, 7387, -1, 7387, 7393, 7392, -1, + 7393, 7387, 7386, -1, 7386, 7394, 7393, -1, + 7394, 7386, 7385, -1, 7385, 7395, 7394, -1, + 7395, 7385, 7384, -1, 7384, 7396, 7395, -1, + 7396, 7384, 7383, -1, 7383, 7397, 7396, -1, + 7397, 7383, 7382, -1, 7382, 7398, 7397, -1, + 7398, 7382, 7361, -1, 7361, 7399, 7398, -1, + 7399, 7361, 7359, -1, 7359, 7358, 7399, -1, + 7358, 7400, 7399, -1, 7400, 7358, 7356, -1, + 7356, 7401, 7400, -1, 7401, 7356, 7354, -1, + 7354, 7402, 7401, -1, 7402, 7354, 7352, -1, + 7352, 7403, 7402, -1, 7403, 7352, 7350, -1, + 7350, 7404, 7403, -1, 7404, 7350, 7348, -1, + 7348, 7405, 7404, -1, 7405, 7348, 7346, -1, + 7346, 7406, 7405, -1, 7406, 7346, 7344, -1, + 7344, 7407, 7406, -1, 7407, 7344, 7342, -1, + 7342, 7408, 7407, -1, 7408, 7342, 7340, -1, + 7340, 7409, 7408, -1, 7409, 7340, 7338, -1, + 7338, 7410, 7409, -1, 7410, 7338, 7336, -1, + 7336, 7411, 7410, -1, 7411, 7336, 7334, -1, + 7334, 7412, 7411, -1, 7412, 7334, 7332, -1, + 7332, 7413, 7412, -1, 7413, 7332, 7329, -1, + 7329, 7414, 7413, -1, 7414, 7329, 7331, -1, + 7331, 7415, 7414, -1, 7415, 7331, 7378, -1, + 7378, 7416, 7415, -1, 7416, 7378, 7380, -1, + 7380, 7417, 7416, -1, 7417, 7380, 7328, -1, + 7328, 7418, 7417, -1, 7418, 7328, 3764, -1, + 7418, 3764, 3763, -1, 7418, 3763, 4002, -1, + 4002, 7417, 7418, -1, 7417, 4002, 4003, -1, + 4003, 7416, 7417, -1, 7416, 4003, 4004, -1, + 4004, 7415, 7416, -1, 7415, 4004, 4005, -1, + 4005, 7414, 7415, -1, 7414, 4005, 4006, -1, + 4006, 7413, 7414, -1, 7413, 4006, 4007, -1, + 4007, 7412, 7413, -1, 7412, 4007, 4008, -1, + 4008, 7411, 7412, -1, 7411, 4008, 4009, -1, + 4009, 7410, 7411, -1, 7410, 4009, 4010, -1, + 4010, 7409, 7410, -1, 7409, 4010, 4011, -1, + 4011, 7408, 7409, -1, 7408, 4011, 4012, -1, + 4012, 7407, 7408, -1, 7407, 4012, 4013, -1, + 4013, 7406, 7407, -1, 7406, 4013, 4014, -1, + 4014, 7405, 7406, -1, 7405, 4014, 4015, -1, + 4015, 7404, 7405, -1, 7404, 4015, 4016, -1, + 4016, 7403, 7404, -1, 7403, 4016, 4017, -1, + 4017, 7402, 7403, -1, 7402, 4017, 4018, -1, + 4018, 7401, 7402, -1, 7401, 4018, 4019, -1, + 4019, 7400, 7401, -1, 7400, 4019, 4020, -1, + 4020, 7399, 7400, -1, 7399, 4020, 4021, -1, + 4021, 7398, 7399, -1, 7398, 4021, 4023, -1, + 4023, 7397, 7398, -1, 7397, 4023, 4025, -1, + 4025, 7396, 7397, -1, 7396, 4025, 4027, -1, + 4027, 7395, 7396, -1, 7395, 4027, 4029, -1, + 4029, 7394, 7395, -1, 7394, 4029, 4031, -1, + 4031, 7393, 7394, -1, 7393, 4031, 4033, -1, + 4033, 7392, 7393, -1, 7392, 4033, 4035, -1, + 4035, 7390, 7392, -1, 7390, 4035, 4037, -1, + 4037, 7419, 7390, -1, 3631, 7390, 7419, -1, + 3631, 3630, 7390, -1, 3630, 7391, 7390, -1, + 7391, 3630, 3632, -1, 7391, 3632, 7420, -1, + 7420, 7388, 7391, -1, 7420, 7389, 7388, -1, + 7420, 3632, 7389, -1, 7389, 3632, 7421, -1, + 7421, 6597, 7389, -1, 7421, 6596, 6597, -1, + 7421, 6593, 6596, -1, 6593, 7421, 3632, -1, + 7422, 3632, 3631, -1, 3631, 7419, 7422, -1, + 7423, 7422, 7419, -1, 7419, 4037, 7423, -1, + 7423, 4037, 4039, -1, 4039, 7422, 7423, -1, + 4039, 7424, 7422, -1, 7424, 4039, 4038, -1, + 7424, 4038, 4041, -1, 4041, 7422, 7424, -1, + 4041, 7425, 7422, -1, 7425, 4041, 4040, -1, + 7425, 4040, 4088, -1, 4088, 4091, 7425, -1, + 4091, 7422, 7425, -1, 4098, 7426, 7427, -1, + 7426, 4098, 4095, -1, 4095, 4097, 7426, -1, + 4097, 5598, 7426, -1, 7428, 7426, 5598, -1, + 7428, 7427, 7426, -1, 7429, 7427, 7428, -1, + 7428, 5598, 7429, -1, 7429, 5598, 5600, -1, + 5600, 7427, 7429, -1, 5600, 7430, 7427, -1, + 7430, 5600, 5599, -1, 7430, 5599, 5749, -1, + 5749, 7427, 7430, -1, 7427, 5749, 5751, -1, + 7431, 5041, 5039, -1, 5039, 7432, 7431, -1, + 5039, 4855, 7432, -1, 7432, 4855, 4858, -1, + 4858, 7431, 7432, -1, 4858, 4859, 7431, -1, + 4859, 4860, 7431, -1, 4860, 7433, 7431, -1, + 7433, 4860, 4861, -1, 7433, 4861, 4954, -1, + 4954, 4955, 7433, -1, 4955, 7431, 7433, -1, + 3628, 4955, 4956, -1, 7434, 3628, 4956, -1, + 7434, 4956, 4957, -1, 7434, 4957, 7435, -1, + 7435, 3628, 7434, -1, 7435, 3629, 3628, -1, + 7435, 3626, 3629, -1, 3626, 7435, 4957, -1, + 4957, 7436, 3626, -1, 7436, 4957, 4958, -1, + 4958, 7437, 7436, -1, 7437, 4958, 4959, -1, + 4959, 7438, 7437, -1, 7438, 4959, 4960, -1, + 4960, 7439, 7438, -1, 7439, 4960, 4961, -1, + 4961, 7440, 7439, -1, 7440, 4961, 4962, -1, + 4962, 7441, 7440, -1, 7441, 4962, 4963, -1, + 4963, 7442, 7441, -1, 7442, 4963, 4964, -1, + 4964, 7443, 7442, -1, 7443, 4964, 4965, -1, + 4965, 7444, 7443, -1, 7444, 4965, 4966, -1, + 4966, 7445, 7444, -1, 7445, 4966, 4967, -1, + 4967, 7446, 7445, -1, 7446, 4967, 4968, -1, + 4968, 7447, 7446, -1, 7447, 4968, 4969, -1, + 4969, 7448, 7447, -1, 7448, 4969, 4970, -1, + 4970, 7449, 7448, -1, 7449, 4970, 4971, -1, + 4971, 7450, 7449, -1, 7450, 4971, 4972, -1, + 4972, 7451, 7450, -1, 7451, 4972, 4973, -1, + 4973, 7452, 7451, -1, 7452, 4973, 4974, -1, + 4974, 7453, 7452, -1, 7453, 4974, 4975, -1, + 4975, 7454, 7453, -1, 4975, 7455, 7454, -1, + 7455, 4975, 4976, -1, 4976, 7456, 7455, -1, + 7456, 4976, 4977, -1, 4977, 7457, 7456, -1, + 7457, 4977, 4978, -1, 4978, 7458, 7457, -1, + 7458, 4978, 4979, -1, 4979, 7459, 7458, -1, + 7459, 4979, 4980, -1, 4980, 7460, 7459, -1, + 7460, 4980, 4981, -1, 4981, 7461, 7460, -1, + 7461, 4981, 4982, -1, 4982, 7462, 7461, -1, + 7462, 4982, 4983, -1, 4983, 7463, 7462, -1, + 7463, 4983, 4984, -1, 4984, 7464, 7463, -1, + 7464, 4984, 4985, -1, 4985, 7465, 7464, -1, + 7465, 4985, 4986, -1, 4986, 7466, 7465, -1, + 7466, 4986, 4987, -1, 4987, 7467, 7466, -1, + 7467, 4987, 4988, -1, 4988, 7468, 7467, -1, + 7468, 4988, 4989, -1, 4989, 7469, 7468, -1, + 7469, 4989, 4990, -1, 4990, 7470, 7469, -1, + 7470, 4990, 4991, -1, 4991, 7471, 7470, -1, + 7471, 4991, 4992, -1, 4992, 7472, 7471, -1, + 7472, 4992, 4994, -1, 4994, 7473, 7472, -1, + 7473, 4994, 4999, -1, 4999, 7474, 7473, -1, + 4999, 4995, 7474, -1, 7475, 4995, 7476, -1, + 7475, 7474, 4995, -1, 7475, 7473, 7474, -1, + 7475, 7476, 7473, -1, 7477, 7478, 7479, -1, + 7477, 7479, 7476, -1, 7479, 7473, 7476, -1, + 7480, 7481, 7482, -1, 7482, 7483, 7480, -1, + 7483, 7482, 7484, -1, 7484, 7485, 7483, -1, + 7485, 7484, 7486, -1, 7486, 7487, 7485, -1, + 7487, 7486, 7488, -1, 7488, 7489, 7487, -1, + 7489, 7488, 7490, -1, 7490, 7491, 7489, -1, + 7491, 7490, 7492, -1, 7492, 7493, 7491, -1, + 7493, 7492, 7494, -1, 7494, 7495, 7493, -1, + 7495, 7494, 7496, -1, 7496, 7497, 7495, -1, + 7497, 7496, 7498, -1, 7498, 7499, 7497, -1, + 7499, 7498, 7500, -1, 7500, 7501, 7499, -1, + 7501, 7500, 7502, -1, 7502, 7503, 7501, -1, + 7503, 7502, 7504, -1, 7504, 7505, 7503, -1, + 7505, 7504, 7506, -1, 7506, 7507, 7505, -1, + 7507, 7506, 7508, -1, 7508, 7509, 7507, -1, + 7509, 7508, 7510, -1, 7510, 7511, 7509, -1, + 7511, 7510, 7512, -1, 7512, 7513, 7511, -1, + 7513, 7512, 7514, -1, 7514, 7515, 7513, -1, + 7515, 7514, 7516, -1, 7516, 7517, 7515, -1, + 7517, 7516, 7518, -1, 7518, 7519, 7517, -1, + 7518, 7520, 7519, -1, 7520, 7518, 7521, -1, + 7521, 7522, 7520, -1, 7522, 7521, 7523, -1, + 7523, 7524, 7522, -1, 7524, 7523, 7525, -1, + 7525, 7526, 7524, -1, 7526, 7525, 7527, -1, + 7527, 7528, 7526, -1, 7528, 7527, 7529, -1, + 7529, 7530, 7528, -1, 7530, 7529, 7531, -1, + 7531, 7532, 7530, -1, 7532, 7531, 7533, -1, + 7533, 7534, 7532, -1, 7534, 7533, 7535, -1, + 7535, 7536, 7534, -1, 7536, 7535, 7537, -1, + 7537, 7538, 7536, -1, 7538, 7537, 7539, -1, + 7539, 7540, 7538, -1, 7540, 7539, 7541, -1, + 7541, 7542, 7540, -1, 7542, 7541, 7543, -1, + 7543, 7544, 7542, -1, 7544, 7543, 7545, -1, + 7545, 7546, 7544, -1, 7546, 7545, 7547, -1, + 7547, 7548, 7546, -1, 7548, 7547, 7549, -1, + 7549, 7550, 7548, -1, 7550, 7549, 7551, -1, + 7551, 7552, 7550, -1, 7552, 7551, 7553, -1, + 7553, 7554, 7552, -1, 7554, 7553, 7555, -1, + 7555, 7556, 7554, -1, 7556, 7555, 7557, -1, + 7557, 7479, 7556, -1, 7557, 7473, 7479, -1, + 7557, 7472, 7473, -1, 7472, 7557, 7555, -1, + 7555, 7471, 7472, -1, 7471, 7555, 7553, -1, + 7553, 7470, 7471, -1, 7470, 7553, 7551, -1, + 7551, 7469, 7470, -1, 7469, 7551, 7549, -1, + 7549, 7468, 7469, -1, 7468, 7549, 7547, -1, + 7547, 7467, 7468, -1, 7467, 7547, 7545, -1, + 7545, 7466, 7467, -1, 7466, 7545, 7543, -1, + 7543, 7465, 7466, -1, 7465, 7543, 7541, -1, + 7541, 7464, 7465, -1, 7464, 7541, 7539, -1, + 7539, 7463, 7464, -1, 7463, 7539, 7537, -1, + 7537, 7462, 7463, -1, 7462, 7537, 7535, -1, + 7535, 7461, 7462, -1, 7461, 7535, 7533, -1, + 7533, 7460, 7461, -1, 7460, 7533, 7531, -1, + 7531, 7459, 7460, -1, 7459, 7531, 7529, -1, + 7529, 7458, 7459, -1, 7458, 7529, 7527, -1, + 7527, 7457, 7458, -1, 7457, 7527, 7525, -1, + 7525, 7456, 7457, -1, 7456, 7525, 7523, -1, + 7523, 7455, 7456, -1, 7455, 7523, 7521, -1, + 7521, 7454, 7455, -1, 7454, 7521, 7518, -1, + 7454, 7518, 7516, -1, 7516, 7453, 7454, -1, + 7453, 7516, 7514, -1, 7514, 7452, 7453, -1, + 7452, 7514, 7512, -1, 7512, 7451, 7452, -1, + 7451, 7512, 7510, -1, 7510, 7450, 7451, -1, + 7450, 7510, 7508, -1, 7508, 7449, 7450, -1, + 7449, 7508, 7506, -1, 7506, 7448, 7449, -1, + 7448, 7506, 7504, -1, 7504, 7447, 7448, -1, + 7447, 7504, 7502, -1, 7502, 7446, 7447, -1, + 7446, 7502, 7500, -1, 7500, 7445, 7446, -1, + 7445, 7500, 7498, -1, 7498, 7444, 7445, -1, + 7444, 7498, 7496, -1, 7496, 7443, 7444, -1, + 7443, 7496, 7494, -1, 7494, 7442, 7443, -1, + 7442, 7494, 7492, -1, 7492, 7441, 7442, -1, + 7441, 7492, 7490, -1, 7490, 7440, 7441, -1, + 7440, 7490, 7488, -1, 7488, 7439, 7440, -1, + 7439, 7488, 7486, -1, 7486, 7438, 7439, -1, + 7438, 7486, 7484, -1, 7484, 7437, 7438, -1, + 7437, 7484, 7482, -1, 7482, 7436, 7437, -1, + 7436, 7482, 7481, -1, 7481, 3626, 7436, -1, + 7481, 3624, 3626, -1, 7481, 7480, 3624, -1, + 3624, 7480, 7558, -1, 3624, 7558, 3621, -1, + 3621, 7559, 3624, -1, 7559, 3621, 3623, -1, + 7559, 3623, 7560, -1, 7559, 7560, 7561, -1, + 7561, 3624, 7559, -1, 7561, 3625, 3624, -1, + 3625, 7561, 7560, -1, 7560, 3628, 3625, -1, + 6799, 7560, 3623, -1, 3623, 3620, 6799, -1, + 3620, 3622, 6799, -1, 7562, 6799, 3622, -1, + 7562, 6802, 6799, -1, 7562, 6805, 6802, -1, + 7562, 3622, 6805, -1, 6805, 3622, 3621, -1, + 3621, 6807, 6805, -1, 6807, 3621, 7558, -1, + 7558, 6809, 6807, -1, 6809, 7558, 7563, -1, + 7563, 7089, 6809, -1, 7089, 7563, 7564, -1, + 7564, 7088, 7089, -1, 7088, 7564, 7565, -1, + 7565, 7087, 7088, -1, 7087, 7565, 7566, -1, + 7566, 7086, 7087, -1, 7086, 7566, 7567, -1, + 7567, 7085, 7086, -1, 7085, 7567, 7568, -1, + 7568, 7084, 7085, -1, 7084, 7568, 7569, -1, + 7569, 7083, 7084, -1, 7083, 7569, 7570, -1, + 7570, 7082, 7083, -1, 7082, 7570, 7571, -1, + 7571, 7081, 7082, -1, 7081, 7571, 7572, -1, + 7572, 7080, 7081, -1, 7080, 7572, 7573, -1, + 7573, 7079, 7080, -1, 7079, 7573, 7574, -1, + 7574, 7078, 7079, -1, 7078, 7574, 7575, -1, + 7575, 7077, 7078, -1, 7077, 7575, 7576, -1, + 7576, 7076, 7077, -1, 7076, 7576, 7577, -1, + 7577, 7075, 7076, -1, 7075, 7577, 7578, -1, + 7578, 7074, 7075, -1, 7074, 7578, 7579, -1, + 7579, 7073, 7074, -1, 7073, 7579, 7580, -1, + 7580, 7072, 7073, -1, 7072, 7580, 7581, -1, + 7581, 7071, 7072, -1, 7071, 7581, 7582, -1, + 7582, 7070, 7071, -1, 7582, 7069, 7070, -1, + 7069, 7582, 7583, -1, 7583, 7068, 7069, -1, + 7068, 7583, 7584, -1, 7584, 7067, 7068, -1, + 7067, 7584, 7585, -1, 7585, 7066, 7067, -1, + 7066, 7585, 7586, -1, 7586, 7065, 7066, -1, + 7065, 7586, 7587, -1, 7587, 7064, 7065, -1, + 7064, 7587, 7588, -1, 7588, 7063, 7064, -1, + 7063, 7588, 7589, -1, 7589, 7062, 7063, -1, + 7062, 7589, 7590, -1, 7590, 7061, 7062, -1, + 7061, 7590, 7591, -1, 7591, 7060, 7061, -1, + 7060, 7591, 7592, -1, 7592, 7059, 7060, -1, + 7059, 7592, 7593, -1, 7593, 7058, 7059, -1, + 7058, 7593, 7594, -1, 7594, 7057, 7058, -1, + 7057, 7594, 7595, -1, 7595, 7056, 7057, -1, + 7056, 7595, 7596, -1, 7596, 7055, 7056, -1, + 7055, 7596, 7597, -1, 7597, 7054, 7055, -1, + 7054, 7597, 7598, -1, 7598, 7053, 7054, -1, + 7053, 7598, 7599, -1, 7599, 7052, 7053, -1, + 7052, 7599, 7600, -1, 7600, 7051, 7052, -1, + 7051, 7600, 7601, -1, 7601, 7050, 7051, -1, + 7050, 7601, 7602, -1, 7602, 6811, 7050, -1, + 7602, 6812, 6811, -1, 7602, 7603, 6812, -1, + 7603, 7602, 7601, -1, 7601, 7604, 7603, -1, + 7604, 7601, 7600, -1, 7600, 7605, 7604, -1, + 7605, 7600, 7599, -1, 7599, 7606, 7605, -1, + 7606, 7599, 7598, -1, 7598, 7607, 7606, -1, + 7607, 7598, 7597, -1, 7597, 7608, 7607, -1, + 7608, 7597, 7596, -1, 7596, 7609, 7608, -1, + 7609, 7596, 7595, -1, 7595, 7610, 7609, -1, + 7610, 7595, 7594, -1, 7594, 7611, 7610, -1, + 7611, 7594, 7593, -1, 7593, 7612, 7611, -1, + 7612, 7593, 7592, -1, 7592, 7613, 7612, -1, + 7613, 7592, 7591, -1, 7591, 7614, 7613, -1, + 7614, 7591, 7590, -1, 7590, 7615, 7614, -1, + 7615, 7590, 7589, -1, 7589, 7616, 7615, -1, + 7616, 7589, 7588, -1, 7588, 7617, 7616, -1, + 7617, 7588, 7587, -1, 7587, 7618, 7617, -1, + 7618, 7587, 7586, -1, 7586, 7619, 7618, -1, + 7619, 7586, 7585, -1, 7585, 7620, 7619, -1, + 7620, 7585, 7584, -1, 7584, 7621, 7620, -1, + 7621, 7584, 7583, -1, 7583, 7622, 7621, -1, + 7622, 7583, 7582, -1, 7622, 7582, 7581, -1, + 7581, 7623, 7622, -1, 7623, 7581, 7580, -1, + 7580, 7624, 7623, -1, 7624, 7580, 7579, -1, + 7579, 7625, 7624, -1, 7625, 7579, 7578, -1, + 7578, 7626, 7625, -1, 7626, 7578, 7577, -1, + 7577, 7627, 7626, -1, 7627, 7577, 7576, -1, + 7576, 7628, 7627, -1, 7628, 7576, 7575, -1, + 7575, 7629, 7628, -1, 7629, 7575, 7574, -1, + 7574, 7630, 7629, -1, 7630, 7574, 7573, -1, + 7573, 7631, 7630, -1, 7631, 7573, 7572, -1, + 7572, 7632, 7631, -1, 7632, 7572, 7571, -1, + 7571, 7633, 7632, -1, 7633, 7571, 7570, -1, + 7570, 7634, 7633, -1, 7634, 7570, 7569, -1, + 7569, 7635, 7634, -1, 7635, 7569, 7568, -1, + 7568, 7636, 7635, -1, 7636, 7568, 7567, -1, + 7567, 7637, 7636, -1, 7637, 7567, 7566, -1, + 7566, 7638, 7637, -1, 7638, 7566, 7565, -1, + 7565, 7639, 7638, -1, 7639, 7565, 7564, -1, + 7564, 7640, 7639, -1, 7640, 7564, 7563, -1, + 7563, 7641, 7640, -1, 7641, 7563, 7558, -1, + 7641, 7558, 7480, -1, 7641, 7480, 7483, -1, + 7483, 7640, 7641, -1, 7640, 7483, 7485, -1, + 7485, 7639, 7640, -1, 7639, 7485, 7487, -1, + 7487, 7638, 7639, -1, 7638, 7487, 7489, -1, + 7489, 7637, 7638, -1, 7637, 7489, 7491, -1, + 7491, 7636, 7637, -1, 7636, 7491, 7493, -1, + 7493, 7635, 7636, -1, 7635, 7493, 7495, -1, + 7495, 7634, 7635, -1, 7634, 7495, 7497, -1, + 7497, 7633, 7634, -1, 7633, 7497, 7499, -1, + 7499, 7632, 7633, -1, 7632, 7499, 7501, -1, + 7501, 7631, 7632, -1, 7631, 7501, 7503, -1, + 7503, 7630, 7631, -1, 7630, 7503, 7505, -1, + 7505, 7629, 7630, -1, 7629, 7505, 7507, -1, + 7507, 7628, 7629, -1, 7628, 7507, 7509, -1, + 7509, 7627, 7628, -1, 7627, 7509, 7511, -1, + 7511, 7626, 7627, -1, 7626, 7511, 7513, -1, + 7513, 7625, 7626, -1, 7625, 7513, 7515, -1, + 7515, 7624, 7625, -1, 7624, 7515, 7517, -1, + 7517, 7623, 7624, -1, 7623, 7517, 7519, -1, + 7519, 7622, 7623, -1, 7519, 7621, 7622, -1, + 7621, 7519, 7520, -1, 7520, 7620, 7621, -1, + 7620, 7520, 7522, -1, 7522, 7619, 7620, -1, + 7619, 7522, 7524, -1, 7524, 7618, 7619, -1, + 7618, 7524, 7526, -1, 7526, 7617, 7618, -1, + 7617, 7526, 7528, -1, 7528, 7616, 7617, -1, + 7616, 7528, 7530, -1, 7530, 7615, 7616, -1, + 7615, 7530, 7532, -1, 7532, 7614, 7615, -1, + 7614, 7532, 7534, -1, 7534, 7613, 7614, -1, + 7613, 7534, 7536, -1, 7536, 7612, 7613, -1, + 7612, 7536, 7538, -1, 7538, 7611, 7612, -1, + 7611, 7538, 7540, -1, 7540, 7610, 7611, -1, + 7610, 7540, 7542, -1, 7542, 7609, 7610, -1, + 7609, 7542, 7544, -1, 7544, 7608, 7609, -1, + 7608, 7544, 7546, -1, 7546, 7607, 7608, -1, + 7607, 7546, 7548, -1, 7548, 7606, 7607, -1, + 7606, 7548, 7550, -1, 7550, 7605, 7606, -1, + 7605, 7550, 7552, -1, 7552, 7604, 7605, -1, + 7604, 7552, 7554, -1, 7554, 7603, 7604, -1, + 7603, 7554, 7556, -1, 7556, 6812, 7603, -1, + 6812, 7556, 7479, -1, 7479, 6810, 6812, -1, + 6810, 7479, 7478, -1, 7478, 6816, 6810, -1, + 7478, 6817, 6816, -1, 7478, 7477, 6817, -1, + 7477, 7476, 6817, -1, 6817, 7476, 4995, -1, + 4997, 7642, 7643, -1, 7642, 4997, 5001, -1, + 7642, 5001, 5003, -1, 7642, 5003, 5005, -1, + 5005, 7643, 7642, -1, 7644, 7643, 5005, -1, + 7644, 5005, 5004, -1, 7644, 5004, 5011, -1, + 5011, 7643, 7644, -1, 5011, 5010, 7643, -1, + 5010, 5008, 7643, -1, 7643, 5008, 5007, -1, + 3618, 5190, 5192, -1, 5192, 7645, 3618, -1, + 7645, 5192, 5193, -1, 7645, 5193, 7646, -1, + 7646, 3618, 7645, -1, 7646, 3619, 3618, -1, + 7646, 3615, 3619, -1, 3615, 7646, 5193, -1, + 3615, 5193, 5194, -1, 5194, 3613, 3615, -1, + 3613, 5194, 5195, -1, 5195, 3611, 3613, -1, + 3611, 5195, 5196, -1, 5196, 3609, 3611, -1, + 3609, 5196, 5197, -1, 5197, 3608, 3609, -1, + 3608, 5197, 5198, -1, 3608, 5198, 5199, -1, + 5199, 3606, 3608, -1, 3606, 5199, 5200, -1, + 5200, 3604, 3606, -1, 3604, 5200, 5201, -1, + 5201, 3602, 3604, -1, 3602, 5201, 5202, -1, + 5202, 3600, 3602, -1, 3600, 5202, 5203, -1, + 3600, 5203, 5205, -1, 5205, 3599, 3600, -1, + 5205, 3597, 3599, -1, 5205, 5204, 3597, -1, + 5204, 5206, 3597, -1, 3597, 5206, 5208, -1, + 3576, 3598, 3597, -1, 7647, 3598, 3576, -1, + 7647, 3601, 3598, -1, 7647, 7648, 3601, -1, + 7648, 7647, 3576, -1, 7648, 3576, 3575, -1, + 7648, 3575, 3577, -1, 3577, 3601, 7648, -1, + 3577, 3603, 3601, -1, 3603, 3577, 3589, -1, + 3589, 3605, 3603, -1, 3605, 3589, 3590, -1, + 3590, 3607, 3605, -1, 3590, 3610, 3607, -1, + 3610, 3590, 3591, -1, 3591, 3612, 3610, -1, + 3612, 3591, 3592, -1, 3592, 3614, 3612, -1, + 3592, 7649, 3614, -1, 7649, 3592, 3594, -1, + 7649, 3594, 3595, -1, 7649, 3595, 7650, -1, + 7650, 3614, 7649, -1, 7650, 3616, 3614, -1, + 3616, 7650, 3595, -1, 3595, 3618, 3616, -1, + 5213, 7651, 7652, -1, 7651, 5213, 5212, -1, + 5212, 5214, 7651, -1, 5214, 5324, 7651, -1, + 7653, 7651, 5324, -1, 7653, 7652, 7651, -1, + 7654, 7652, 7653, -1, 7653, 5324, 7654, -1, + 7654, 5324, 5326, -1, 5326, 7652, 7654, -1, + 5326, 7655, 7652, -1, 7655, 5326, 5325, -1, + 7655, 5325, 5454, -1, 5454, 7652, 7655, -1, + 7652, 5454, 5456, -1, 5456, 3573, 3569, -1, + 3573, 5456, 5459, -1, 5459, 5460, 3573, -1, + 5460, 3571, 3573, -1, 3571, 5460, 5461, -1, + 5461, 7656, 3571, -1, 7656, 5461, 5462, -1, + 5462, 7657, 7656, -1, 7657, 5462, 5463, -1, + 5463, 7658, 7657, -1, 7658, 5463, 5464, -1, + 5464, 7659, 7658, -1, 7659, 5464, 5465, -1, + 5465, 7660, 7659, -1, 7660, 5465, 5466, -1, + 5466, 7661, 7660, -1, 7661, 5466, 5467, -1, + 5467, 7662, 7661, -1, 7662, 5467, 5468, -1, + 5468, 7663, 7662, -1, 7663, 5468, 5469, -1, + 5469, 7664, 7663, -1, 7664, 5469, 5470, -1, + 5470, 7665, 7664, -1, 7665, 5470, 5471, -1, + 5471, 7666, 7665, -1, 7666, 5471, 5472, -1, + 5472, 7667, 7666, -1, 7667, 5472, 5473, -1, + 5473, 7668, 7667, -1, 7668, 5473, 5474, -1, + 5474, 7669, 7668, -1, 7669, 5474, 5475, -1, + 5475, 7670, 7669, -1, 7670, 5475, 5476, -1, + 5476, 7671, 7670, -1, 7671, 5476, 5477, -1, + 5477, 7672, 7671, -1, 7672, 5477, 5478, -1, + 5478, 7673, 7672, -1, 7673, 5478, 5479, -1, + 5479, 7674, 7673, -1, 7674, 5479, 5480, -1, + 5480, 7675, 7674, -1, 7675, 5480, 5481, -1, + 5481, 7676, 7675, -1, 7676, 5481, 5482, -1, + 5482, 7677, 7676, -1, 7677, 5482, 5483, -1, + 5483, 7678, 7677, -1, 7678, 5483, 5484, -1, + 5484, 7679, 7678, -1, 7679, 5484, 5485, -1, + 5485, 7680, 7679, -1, 7680, 5485, 5486, -1, + 5486, 7681, 7680, -1, 7681, 5486, 5487, -1, + 5487, 7682, 7681, -1, 7682, 5487, 5488, -1, + 5488, 7683, 7682, -1, 7683, 5488, 5489, -1, + 5489, 7684, 7683, -1, 7684, 5489, 5490, -1, + 5490, 7685, 7684, -1, 7685, 5490, 5491, -1, + 5491, 7686, 7685, -1, 7686, 5491, 5492, -1, + 5492, 7687, 7686, -1, 7687, 5492, 5493, -1, + 5493, 7688, 7687, -1, 7688, 5493, 5494, -1, + 5494, 7689, 7688, -1, 7689, 5494, 5495, -1, + 5495, 7690, 7689, -1, 7690, 5495, 5496, -1, + 5496, 7691, 7690, -1, 7691, 5496, 5497, -1, + 5497, 7692, 7691, -1, 7692, 5497, 5498, -1, + 5498, 7693, 7692, -1, 7693, 5498, 5499, -1, + 5499, 7694, 7693, -1, 7694, 5499, 5500, -1, + 5500, 7695, 7694, -1, 7695, 5500, 5501, -1, + 5501, 7696, 7695, -1, 7696, 5501, 5502, -1, + 5502, 7697, 7696, -1, 7697, 5502, 5503, -1, + 5503, 7698, 7697, -1, 7698, 5503, 5504, -1, + 5504, 7699, 7698, -1, 7699, 5504, 5505, -1, + 5505, 7700, 7699, -1, 7700, 5505, 5506, -1, + 5506, 7701, 7700, -1, 7701, 5506, 5507, -1, + 5507, 7702, 7701, -1, 7702, 5507, 5508, -1, + 5508, 7703, 7702, -1, 7703, 5508, 5509, -1, + 5509, 7704, 7703, -1, 7704, 5509, 5512, -1, + 5512, 7705, 7704, -1, 7705, 5512, 7706, -1, + 7706, 7707, 7705, -1, 7707, 7706, 7708, -1, + 7708, 7709, 7707, -1, 7709, 7708, 7710, -1, + 7710, 7711, 7709, -1, 7711, 7710, 7712, -1, + 7712, 7713, 7711, -1, 7713, 7712, 7714, -1, + 7714, 7715, 7713, -1, 7714, 7716, 7715, -1, + 7717, 7716, 7714, -1, 7717, 7714, 7718, -1, + 7714, 7719, 7718, -1, 7719, 7714, 7712, -1, + 7712, 7720, 7719, -1, 7720, 7712, 7710, -1, + 7710, 7721, 7720, -1, 7721, 7710, 7708, -1, + 7708, 7722, 7721, -1, 7722, 7708, 7706, -1, + 7706, 7723, 7722, -1, 7723, 7706, 5512, -1, + 7723, 5512, 5511, -1, 7723, 5511, 5517, -1, + 5517, 7722, 7723, -1, 7722, 5517, 5518, -1, + 5518, 7721, 7722, -1, 7721, 5518, 5519, -1, + 5519, 7720, 7721, -1, 7720, 5519, 5520, -1, + 5520, 7719, 7720, -1, 7719, 5520, 7724, -1, + 7724, 7725, 7726, -1, 7725, 7724, 5520, -1, + 7725, 5520, 5522, -1, 5522, 7726, 7725, -1, + 5522, 5521, 7726, -1, 5521, 5523, 7726, -1, + 7726, 5523, 5524, -1, 3565, 5524, 5526, -1, + 5526, 7727, 3565, -1, 7727, 5526, 5527, -1, + 7727, 5527, 7728, -1, 7728, 3565, 7727, -1, + 7728, 7729, 3565, -1, 7729, 7728, 5527, -1, + 5527, 5528, 7729, -1, 7730, 7729, 5528, -1, + 7730, 3565, 7729, -1, 7730, 3566, 3565, -1, + 7730, 5528, 3566, -1, 5528, 5218, 3566, -1, + 7731, 3566, 5218, -1, 7731, 3564, 3566, -1, + 7731, 7732, 3564, -1, 7731, 5218, 7732, -1, + 7732, 5218, 5216, -1, 5216, 3564, 7732, -1, + 5216, 5215, 3564, -1, 5215, 3563, 3564, -1, + 5215, 5217, 3563, -1, 5217, 3560, 3563, -1, + 3560, 5217, 5222, -1, 5222, 3559, 3560, -1, + 3559, 5222, 5221, -1, 5221, 3558, 3559, -1, + 3558, 5221, 7733, -1, 7733, 3554, 3558, -1, + 7733, 3555, 3554, -1, 7734, 3555, 7733, -1, + 3555, 7734, 7735, -1, 7735, 3556, 3555, -1, + 3556, 7735, 7736, -1, 7736, 3550, 3556, -1, + 7736, 3535, 3550, -1, 7736, 3536, 3535, -1, + 3536, 7736, 7735, -1, 7735, 7737, 3536, -1, + 7737, 7735, 7734, -1, 7734, 7738, 7737, -1, + 7734, 7733, 7738, -1, 7739, 7738, 7733, -1, + 7739, 7733, 5221, -1, 7739, 5221, 5220, -1, + 7739, 5220, 7740, -1, 7740, 7738, 7739, -1, + 7738, 7740, 7741, -1, 7741, 7737, 7738, -1, + 7737, 7741, 7742, -1, 7742, 3536, 7737, -1, + 7742, 3537, 3536, -1, 7742, 7743, 3537, -1, + 7743, 7742, 7741, -1, 7741, 7744, 7743, -1, + 7744, 7741, 7740, -1, 7740, 7745, 7744, -1, + 7745, 7740, 5220, -1, 5220, 7746, 7745, -1, + 7746, 5220, 5219, -1, 7746, 5219, 5529, -1, + 7746, 5529, 5537, -1, 5537, 7745, 7746, -1, + 7745, 5537, 5535, -1, 5535, 7744, 7745, -1, + 7744, 5535, 5533, -1, 5533, 7743, 7744, -1, + 7743, 5533, 5530, -1, 5530, 3537, 7743, -1, + 3537, 5530, 5532, -1, 5532, 3538, 3537, -1, + 3538, 5532, 5540, -1, 5540, 3540, 3538, -1, + 3540, 5540, 5541, -1, 5541, 3542, 3540, -1, + 3542, 5541, 5542, -1, 5542, 3544, 3542, -1, + 3544, 5542, 5543, -1, 5543, 3546, 3544, -1, + 3546, 5543, 5544, -1, 5544, 3548, 3546, -1, + 3548, 5544, 5545, -1, 5545, 3534, 3548, -1, + 3534, 5545, 5546, -1, 5546, 3533, 3534, -1, + 3533, 5546, 5547, -1, 5547, 3532, 3533, -1, + 3532, 5547, 5548, -1, 5548, 3531, 3532, -1, + 3531, 5548, 5549, -1, 5549, 3530, 3531, -1, + 3530, 5549, 5550, -1, 5550, 3529, 3530, -1, + 3529, 5550, 5551, -1, 5551, 3528, 3529, -1, + 3528, 5551, 5552, -1, 5552, 3527, 3528, -1, + 3527, 5552, 5553, -1, 5553, 3526, 3527, -1, + 3526, 5553, 5554, -1, 5554, 3525, 3526, -1, + 3525, 5554, 5555, -1, 5555, 3524, 3525, -1, + 3524, 5555, 5556, -1, 5556, 3523, 3524, -1, + 3523, 5556, 5557, -1, 5557, 3522, 3523, -1, + 3522, 5557, 5558, -1, 5558, 3521, 3522, -1, + 3521, 5558, 5559, -1, 5559, 3520, 3521, -1, + 3520, 5559, 5560, -1, 5560, 3519, 3520, -1, + 3519, 5560, 5561, -1, 5561, 3518, 3519, -1, + 3518, 5561, 5562, -1, 5562, 3517, 3518, -1, + 3517, 5562, 5563, -1, 5563, 3516, 3517, -1, + 3516, 5563, 5564, -1, 5564, 3515, 3516, -1, + 3515, 5564, 5565, -1, 5565, 3514, 3515, -1, + 3514, 5565, 5566, -1, 5566, 3513, 3514, -1, + 3513, 5566, 5567, -1, 5567, 3512, 3513, -1, + 3512, 5567, 5568, -1, 5568, 3511, 3512, -1, + 3511, 5568, 5569, -1, 5569, 3510, 3511, -1, + 3510, 5569, 5570, -1, 5570, 3509, 3510, -1, + 3509, 5570, 5571, -1, 5571, 3508, 3509, -1, + 3508, 5571, 5572, -1, 5572, 3507, 3508, -1, + 3507, 5572, 5573, -1, 5573, 3506, 3507, -1, + 3506, 5573, 5574, -1, 5574, 3505, 3506, -1, + 3505, 5574, 5575, -1, 5575, 3504, 3505, -1, + 3504, 5575, 5576, -1, 5576, 3503, 3504, -1, + 3503, 5576, 5577, -1, 5577, 3502, 3503, -1, + 3502, 5577, 5578, -1, 5578, 3501, 3502, -1, + 3501, 5578, 5579, -1, 5579, 3500, 3501, -1, + 3500, 5579, 5580, -1, 5580, 3499, 3500, -1, + 3499, 5580, 5581, -1, 5581, 3498, 3499, -1, + 3498, 5581, 5582, -1, 5582, 3497, 3498, -1, + 3497, 5582, 5583, -1, 5583, 3496, 3497, -1, + 3496, 5583, 5584, -1, 5584, 3495, 3496, -1, + 3495, 5584, 5585, -1, 5585, 3494, 3495, -1, + 3494, 5585, 5586, -1, 5586, 3493, 3494, -1, + 3493, 5586, 5587, -1, 5587, 2879, 3493, -1, + 2879, 5587, 5590, -1, 5590, 2880, 2879, -1, + 2880, 5590, 525, -1, 2880, 525, 524, -1, + 524, 2877, 2880, -1, 524, 526, 2877, -1, + 526, 2878, 2877, -1, 2878, 526, 525, -1, + 525, 7747, 2769, -1, 7748, 7749, 7747, -1, + 7749, 2769, 7747, -1, 7749, 2770, 2769, -1, + 7749, 7748, 2770, -1, 7748, 3002, 2770, -1, + 3002, 7748, 7747, -1, 3002, 7747, 7750, -1, + 7750, 2726, 3002, -1, 7750, 2727, 2726, -1, + 2727, 7750, 7747, -1, 7747, 5597, 2727, -1, + 7751, 5597, 7752, -1, 7751, 2727, 5597, -1, + 7751, 2728, 2727, -1, 7751, 7752, 2728, -1, + 7752, 3103, 2728, -1, 3103, 7752, 5597, -1, + 3103, 5597, 5596, -1, 5596, 3102, 3103, -1, + 5596, 5593, 3102, -1, 3102, 5593, 5592, -1, + 5592, 3104, 3102, -1, 3104, 5592, 7753, -1, + 7753, 3105, 3104, -1, 3105, 7753, 7754, -1, + 7754, 3106, 3105, -1, 3106, 7754, 7755, -1, + 7755, 3107, 3106, -1, 3107, 7755, 7756, -1, + 7756, 3108, 3107, -1, 3108, 7756, 7757, -1, + 7757, 3109, 3108, -1, 3109, 7757, 7758, -1, + 7758, 3110, 3109, -1, 3110, 7758, 7759, -1, + 7759, 3111, 3110, -1, 3111, 7759, 7760, -1, + 7760, 3112, 3111, -1, 3112, 7760, 7761, -1, + 7761, 3113, 3112, -1, 3113, 7761, 7762, -1, + 7762, 3114, 3113, -1, 3114, 7762, 7763, -1, + 7763, 3115, 3114, -1, 3115, 7763, 7764, -1, + 7764, 3116, 3115, -1, 3116, 7764, 7765, -1, + 7765, 3117, 3116, -1, 3117, 7765, 7766, -1, + 7766, 3118, 3117, -1, 3118, 7766, 7767, -1, + 7767, 3119, 3118, -1, 3119, 7767, 7768, -1, + 7768, 3120, 3119, -1, 3120, 7768, 7769, -1, + 7769, 3121, 3120, -1, 3121, 7769, 7770, -1, + 7770, 3122, 3121, -1, 3122, 7770, 7771, -1, + 7771, 3123, 3122, -1, 3123, 7771, 7772, -1, + 7772, 3124, 3123, -1, 3124, 7772, 7773, -1, + 7773, 3125, 3124, -1, 3125, 7773, 7774, -1, + 7774, 3126, 3125, -1, 3126, 7774, 7775, -1, + 7775, 3127, 3126, -1, 3127, 7775, 7776, -1, + 7776, 3128, 3127, -1, 3128, 7776, 7777, -1, + 7777, 3129, 3128, -1, 3129, 7777, 7778, -1, + 7778, 3130, 3129, -1, 3130, 7778, 7779, -1, + 7779, 3131, 3130, -1, 3131, 7779, 7780, -1, + 7780, 3132, 3131, -1, 3132, 7780, 7781, -1, + 7781, 3133, 3132, -1, 3133, 7781, 7782, -1, + 7782, 3134, 3133, -1, 3134, 7782, 7783, -1, + 7783, 3135, 3134, -1, 3135, 7783, 7784, -1, + 7784, 3136, 3135, -1, 3136, 7784, 7785, -1, + 7785, 3137, 3136, -1, 3137, 7785, 7786, -1, + 7786, 3138, 3137, -1, 3138, 7786, 7787, -1, + 7787, 3139, 3138, -1, 3139, 7787, 7788, -1, + 7788, 3140, 3139, -1, 3140, 7788, 7789, -1, + 7789, 3141, 3140, -1, 3141, 7789, 7790, -1, + 7790, 3142, 3141, -1, 3142, 7790, 7791, -1, + 7791, 3143, 3142, -1, 3143, 7791, 7792, -1, + 7792, 3144, 3143, -1, 3144, 7792, 7793, -1, + 7793, 3145, 3144, -1, 3145, 7793, 7794, -1, + 7794, 3146, 3145, -1, 3146, 7794, 7795, -1, + 7795, 3147, 3146, -1, 3147, 7795, 7796, -1, + 7796, 3148, 3147, -1, 3148, 7796, 7797, -1, + 7797, 3149, 3148, -1, 3149, 7797, 7798, -1, + 7798, 3150, 3149, -1, 3150, 7798, 7799, -1, + 7799, 3151, 3150, -1, 3151, 7799, 7800, -1, + 7800, 3152, 3151, -1, 3152, 7800, 7801, -1, + 7801, 7802, 3152, -1, 7802, 7801, 7803, -1, + 7802, 7803, 7804, -1, 7805, 7806, 7807, -1, + 7806, 7805, 7808, -1, 7806, 7808, 7809, -1, + 7810, 7809, 7808, -1, 7810, 7811, 7809, -1, + 7811, 7810, 7812, -1, 7812, 7813, 7811, -1, + 7814, 7815, 7813, -1, 7813, 7812, 7814, -1, + 7816, 7817, 7814, -1, 7814, 7818, 7816, -1, + 7818, 7814, 7812, -1, 7812, 7819, 7818, -1, + 7819, 7812, 7810, -1, 7810, 7820, 7819, -1, + 7820, 7810, 7808, -1, 7808, 7804, 7820, -1, + 7804, 7808, 7805, -1, 7805, 7802, 7804, -1, + 7805, 7807, 7802, -1, 7821, 7802, 7807, -1, + 7821, 3152, 7802, -1, 7821, 3153, 3152, -1, + 7821, 3156, 3153, -1, 3156, 7821, 7807, -1, + 7807, 3155, 3156, -1, 3155, 7807, 7806, -1, + 7806, 7809, 3155, -1, 7809, 2725, 3155, -1, + 7809, 2724, 2725, -1, 2724, 7809, 7811, -1, + 7811, 2723, 2724, -1, 2723, 7811, 7813, -1, + 7813, 2722, 2723, -1, 2722, 7813, 7822, -1, + 7822, 2720, 2722, -1, 7822, 7823, 2720, -1, + 7823, 7822, 7813, -1, 7823, 7813, 7815, -1, + 7815, 2720, 7823, -1, 7815, 2721, 2720, -1, + 2721, 7815, 7814, -1, 2721, 7814, 7817, -1, + 7817, 2719, 2721, -1, 7817, 7824, 2719, -1, + 7824, 7817, 7816, -1, 7824, 7816, 7825, -1, + 7825, 2719, 7824, -1, 7825, 7826, 2719, -1, + 7825, 7816, 7826, -1, 7827, 7826, 7816, -1, + 7816, 7828, 7827, -1, 7828, 7816, 7818, -1, + 7818, 7829, 7828, -1, 7829, 7818, 7819, -1, + 7819, 7830, 7829, -1, 7830, 7819, 7820, -1, + 7820, 7831, 7830, -1, 7831, 7820, 7804, -1, + 7831, 7804, 7803, -1, 7831, 7803, 7832, -1, + 7832, 7830, 7831, -1, 7830, 7832, 7833, -1, + 7833, 7829, 7830, -1, 7829, 7833, 7834, -1, + 7834, 7828, 7829, -1, 7828, 7834, 7835, -1, + 7835, 7827, 7828, -1, 7836, 7837, 7827, -1, + 7827, 7835, 7836, -1, 7838, 7839, 7840, -1, + 7840, 7841, 7838, -1, 7842, 7843, 7844, -1, + 7844, 7845, 7842, -1, 7845, 7844, 7846, -1, + 7846, 7847, 7845, -1, 7847, 7846, 7848, -1, + 7848, 7849, 7847, -1, 7849, 7848, 7850, -1, + 7850, 7851, 7849, -1, 7851, 7850, 7852, -1, + 7852, 7853, 7851, -1, 7853, 7852, 7854, -1, + 7854, 7855, 7853, -1, 7855, 7854, 7856, -1, + 7856, 7857, 7855, -1, 7857, 7856, 7858, -1, + 7858, 7859, 7857, -1, 7859, 7858, 7860, -1, + 7860, 7861, 7859, -1, 7861, 7860, 7862, -1, + 7862, 7863, 7861, -1, 7863, 7862, 7864, -1, + 7864, 7865, 7863, -1, 7865, 7864, 7866, -1, + 7866, 7867, 7865, -1, 7867, 7866, 7868, -1, + 7868, 7869, 7867, -1, 7869, 7868, 7870, -1, + 7870, 7871, 7869, -1, 7871, 7870, 7872, -1, + 7872, 7873, 7871, -1, 7873, 7872, 7874, -1, + 7874, 7875, 7873, -1, 7875, 7874, 7876, -1, + 7876, 7877, 7875, -1, 7877, 7876, 7878, -1, + 7878, 7879, 7877, -1, 7879, 7878, 7880, -1, + 7880, 7881, 7879, -1, 7881, 7880, 7882, -1, + 7882, 7883, 7881, -1, 7883, 7882, 7884, -1, + 7884, 7885, 7883, -1, 7885, 7884, 7886, -1, + 7886, 7887, 7885, -1, 7887, 7886, 7888, -1, + 7888, 7889, 7887, -1, 7889, 7888, 7890, -1, + 7890, 7891, 7889, -1, 7891, 7890, 7892, -1, + 7892, 7893, 7891, -1, 7893, 7892, 7894, -1, + 7894, 7895, 7893, -1, 7895, 7894, 7896, -1, + 7896, 7897, 7895, -1, 7897, 7896, 7898, -1, + 7898, 7899, 7897, -1, 7899, 7898, 7900, -1, + 7900, 7901, 7899, -1, 7901, 7900, 7902, -1, + 7902, 7903, 7901, -1, 7903, 7902, 7904, -1, + 7904, 7905, 7903, -1, 7905, 7904, 7906, -1, + 7906, 7907, 7905, -1, 7907, 7906, 7908, -1, + 7908, 7909, 7907, -1, 7909, 7908, 7910, -1, + 7910, 7911, 7909, -1, 7911, 7910, 7912, -1, + 7912, 7913, 7911, -1, 7913, 7912, 7914, -1, + 7914, 7915, 7913, -1, 7915, 7914, 7916, -1, + 7916, 7917, 7915, -1, 7917, 7916, 7918, -1, + 7918, 7919, 7917, -1, 7919, 7918, 7920, -1, + 7920, 7921, 7919, -1, 7921, 7920, 7922, -1, + 7922, 7923, 7921, -1, 7923, 7922, 7924, -1, + 7924, 7925, 7923, -1, 7925, 7924, 7926, -1, + 7926, 7927, 7925, -1, 7927, 7926, 7928, -1, + 7928, 7929, 7927, -1, 7929, 7928, 7930, -1, + 7930, 7931, 7929, -1, 7931, 7930, 7932, -1, + 7932, 7933, 7931, -1, 7933, 7932, 7934, -1, + 7934, 7935, 7933, -1, 7935, 7934, 7936, -1, + 7936, 7937, 7935, -1, 7937, 7936, 7938, -1, + 7938, 7939, 7937, -1, 7939, 7938, 7940, -1, + 7940, 7941, 7939, -1, 7941, 7940, 7942, -1, + 7942, 7943, 7941, -1, 7943, 7942, 7944, -1, + 7944, 7945, 7943, -1, 7945, 7944, 7946, -1, + 7946, 7947, 7945, -1, 7947, 7946, 7948, -1, + 7948, 7949, 7947, -1, 7949, 7948, 7950, -1, + 7950, 7951, 7949, -1, 7951, 7950, 7841, -1, + 7841, 7840, 7951, -1, 7836, 7840, 7952, -1, + 7836, 7951, 7840, -1, 7951, 7836, 7835, -1, + 7835, 7949, 7951, -1, 7949, 7835, 7834, -1, + 7834, 7947, 7949, -1, 7947, 7834, 7833, -1, + 7833, 7945, 7947, -1, 7945, 7833, 7832, -1, + 7832, 7943, 7945, -1, 7943, 7832, 7803, -1, + 7803, 7941, 7943, -1, 7941, 7803, 7801, -1, + 7801, 7939, 7941, -1, 7939, 7801, 7800, -1, + 7800, 7937, 7939, -1, 7937, 7800, 7799, -1, + 7799, 7935, 7937, -1, 7935, 7799, 7798, -1, + 7798, 7933, 7935, -1, 7933, 7798, 7797, -1, + 7797, 7931, 7933, -1, 7931, 7797, 7796, -1, + 7796, 7929, 7931, -1, 7929, 7796, 7795, -1, + 7795, 7927, 7929, -1, 7927, 7795, 7794, -1, + 7794, 7925, 7927, -1, 7925, 7794, 7793, -1, + 7793, 7923, 7925, -1, 7923, 7793, 7792, -1, + 7792, 7921, 7923, -1, 7921, 7792, 7791, -1, + 7791, 7919, 7921, -1, 7919, 7791, 7790, -1, + 7790, 7917, 7919, -1, 7917, 7790, 7789, -1, + 7789, 7915, 7917, -1, 7915, 7789, 7788, -1, + 7788, 7913, 7915, -1, 7913, 7788, 7787, -1, + 7787, 7911, 7913, -1, 7911, 7787, 7786, -1, + 7786, 7909, 7911, -1, 7909, 7786, 7785, -1, + 7785, 7907, 7909, -1, 7907, 7785, 7784, -1, + 7784, 7905, 7907, -1, 7905, 7784, 7783, -1, + 7783, 7903, 7905, -1, 7903, 7783, 7782, -1, + 7782, 7901, 7903, -1, 7901, 7782, 7781, -1, + 7781, 7899, 7901, -1, 7899, 7781, 7780, -1, + 7780, 7897, 7899, -1, 7897, 7780, 7779, -1, + 7779, 7895, 7897, -1, 7895, 7779, 7778, -1, + 7778, 7893, 7895, -1, 7893, 7778, 7777, -1, + 7777, 7891, 7893, -1, 7891, 7777, 7776, -1, + 7776, 7889, 7891, -1, 7889, 7776, 7775, -1, + 7775, 7887, 7889, -1, 7887, 7775, 7774, -1, + 7774, 7885, 7887, -1, 7885, 7774, 7773, -1, + 7773, 7883, 7885, -1, 7883, 7773, 7772, -1, + 7772, 7881, 7883, -1, 7881, 7772, 7771, -1, + 7771, 7879, 7881, -1, 7879, 7771, 7770, -1, + 7770, 7877, 7879, -1, 7877, 7770, 7769, -1, + 7769, 7875, 7877, -1, 7875, 7769, 7768, -1, + 7768, 7873, 7875, -1, 7873, 7768, 7767, -1, + 7767, 7871, 7873, -1, 7871, 7767, 7766, -1, + 7766, 7869, 7871, -1, 7869, 7766, 7765, -1, + 7765, 7867, 7869, -1, 7867, 7765, 7764, -1, + 7764, 7865, 7867, -1, 7865, 7764, 7763, -1, + 7763, 7863, 7865, -1, 7863, 7763, 7762, -1, + 7762, 7861, 7863, -1, 7861, 7762, 7761, -1, + 7761, 7859, 7861, -1, 7859, 7761, 7760, -1, + 7760, 7857, 7859, -1, 7857, 7760, 7759, -1, + 7759, 7855, 7857, -1, 7855, 7759, 7758, -1, + 7758, 7853, 7855, -1, 7853, 7758, 7757, -1, + 7757, 7851, 7853, -1, 7851, 7757, 7756, -1, + 7756, 7849, 7851, -1, 7849, 7756, 7755, -1, + 7755, 7847, 7849, -1, 7847, 7755, 7754, -1, + 7754, 7845, 7847, -1, 7845, 7754, 7753, -1, + 7753, 7842, 7845, -1, 7842, 7753, 5592, -1, + 5592, 5594, 7842, -1, 7953, 7842, 5594, -1, + 7953, 5594, 5595, -1, 7953, 5595, 7954, -1, + 7954, 7842, 7953, -1, 7954, 7843, 7842, -1, + 7954, 5595, 7843, -1, 7843, 5595, 5762, -1, + 5762, 7844, 7843, -1, 5762, 5763, 7844, -1, + 7844, 5763, 5764, -1, 5764, 7846, 7844, -1, + 7846, 5764, 5765, -1, 5765, 7848, 7846, -1, + 7848, 5765, 5767, -1, 5767, 7850, 7848, -1, + 7850, 5767, 5769, -1, 5769, 7852, 7850, -1, + 7852, 5769, 5771, -1, 5771, 7854, 7852, -1, + 7854, 5771, 5773, -1, 5773, 7856, 7854, -1, + 7856, 5773, 5775, -1, 5775, 7858, 7856, -1, + 7858, 5775, 5777, -1, 5777, 7860, 7858, -1, + 7860, 5777, 5779, -1, 5779, 7862, 7860, -1, + 7862, 5779, 5781, -1, 5781, 7864, 7862, -1, + 7864, 5781, 5783, -1, 5783, 7866, 7864, -1, + 7866, 5783, 5785, -1, 5785, 7868, 7866, -1, + 7868, 5785, 5787, -1, 5787, 7870, 7868, -1, + 7870, 5787, 5789, -1, 5789, 7872, 7870, -1, + 7872, 5789, 5791, -1, 5791, 7874, 7872, -1, + 7874, 5791, 5793, -1, 5793, 7876, 7874, -1, + 7876, 5793, 5795, -1, 5795, 7878, 7876, -1, + 7878, 5795, 5797, -1, 5797, 7880, 7878, -1, + 7880, 5797, 5799, -1, 5799, 7882, 7880, -1, + 7882, 5799, 5801, -1, 5801, 7884, 7882, -1, + 7884, 5801, 5803, -1, 5803, 7886, 7884, -1, + 7886, 5803, 5805, -1, 5805, 7888, 7886, -1, + 7888, 5805, 5807, -1, 5807, 7890, 7888, -1, + 7890, 5807, 5809, -1, 5809, 7892, 7890, -1, + 7892, 5809, 5811, -1, 5811, 7894, 7892, -1, + 7894, 5811, 5813, -1, 5813, 7896, 7894, -1, + 7896, 5813, 5815, -1, 5815, 7898, 7896, -1, + 7898, 5815, 5817, -1, 5817, 7900, 7898, -1, + 7900, 5817, 5819, -1, 5819, 7902, 7900, -1, + 7902, 5819, 5821, -1, 5821, 7904, 7902, -1, + 7904, 5821, 5823, -1, 5823, 7906, 7904, -1, + 7906, 5823, 5825, -1, 5825, 7908, 7906, -1, + 7908, 5825, 5827, -1, 5827, 7910, 7908, -1, + 7910, 5827, 5829, -1, 5829, 7912, 7910, -1, + 7912, 5829, 5831, -1, 5831, 7914, 7912, -1, + 7914, 5831, 5833, -1, 5833, 7916, 7914, -1, + 7916, 5833, 5835, -1, 5835, 7918, 7916, -1, + 7918, 5835, 5837, -1, 5837, 7920, 7918, -1, + 7920, 5837, 5839, -1, 5839, 7922, 7920, -1, + 7922, 5839, 5841, -1, 5841, 7924, 7922, -1, + 7924, 5841, 5843, -1, 5843, 7926, 7924, -1, + 7926, 5843, 5845, -1, 5845, 7928, 7926, -1, + 7928, 5845, 5847, -1, 5847, 7930, 7928, -1, + 7930, 5847, 5849, -1, 5849, 7932, 7930, -1, + 7932, 5849, 5851, -1, 5851, 7934, 7932, -1, + 7934, 5851, 5853, -1, 5853, 7936, 7934, -1, + 7936, 5853, 5855, -1, 5855, 7938, 7936, -1, + 7938, 5855, 5857, -1, 5857, 7940, 7938, -1, + 7940, 5857, 5859, -1, 5859, 7942, 7940, -1, + 7942, 5859, 5861, -1, 5861, 7944, 7942, -1, + 7944, 5861, 5863, -1, 5863, 7946, 7944, -1, + 7946, 5863, 5865, -1, 5865, 7948, 7946, -1, + 7948, 5865, 5867, -1, 5867, 7950, 7948, -1, + 7950, 5867, 5869, -1, 5869, 7841, 7950, -1, + 7841, 5869, 5870, -1, 5870, 7838, 7841, -1, + 5870, 5871, 7838, -1, 7955, 7956, 7838, -1, + 7955, 7838, 5871, -1, 5871, 7957, 7955, -1, + 7957, 5871, 5872, -1, 5872, 7958, 7957, -1, + 7958, 5872, 5873, -1, 5873, 7959, 7958, -1, + 7959, 5873, 5874, -1, 5874, 7960, 7959, -1, + 7960, 5874, 5875, -1, 5875, 7961, 7960, -1, + 7961, 5875, 5876, -1, 5876, 7962, 7961, -1, + 7962, 5876, 5877, -1, 5877, 7963, 7962, -1, + 7963, 5877, 5878, -1, 5878, 7964, 7963, -1, + 7964, 5878, 5879, -1, 5879, 7965, 7964, -1, + 7965, 5879, 5880, -1, 5880, 7966, 7965, -1, + 7966, 5880, 5881, -1, 5881, 7967, 7966, -1, + 7967, 5881, 5882, -1, 5882, 7968, 7967, -1, + 7968, 5882, 5883, -1, 5883, 7969, 7968, -1, + 7969, 5883, 5884, -1, 5884, 7970, 7969, -1, + 7970, 5884, 5885, -1, 5885, 7971, 7970, -1, + 7971, 5885, 5886, -1, 5886, 7972, 7971, -1, + 7972, 5886, 5887, -1, 5887, 7973, 7972, -1, + 7973, 5887, 5888, -1, 5888, 7974, 7973, -1, + 7974, 5888, 5889, -1, 5889, 7975, 7974, -1, + 7975, 5889, 5890, -1, 5890, 7976, 7975, -1, + 7976, 5890, 5891, -1, 5891, 7977, 7976, -1, + 7977, 5891, 5892, -1, 5892, 7978, 7977, -1, + 7978, 5892, 5893, -1, 5893, 7979, 7978, -1, + 7979, 5893, 5894, -1, 5894, 7980, 7979, -1, + 7980, 5894, 5895, -1, 5895, 7981, 7980, -1, + 7981, 5895, 5896, -1, 5896, 7982, 7981, -1, + 7982, 5896, 5897, -1, 5897, 7983, 7982, -1, + 7983, 5897, 5899, -1, 5899, 7984, 7983, -1, + 7984, 5899, 5901, -1, 5901, 7985, 7984, -1, + 7985, 5901, 5903, -1, 5903, 7986, 7985, -1, + 7986, 5903, 5905, -1, 5905, 7987, 7986, -1, + 7987, 5905, 5907, -1, 5907, 7988, 7987, -1, + 7988, 5907, 5909, -1, 5909, 7989, 7988, -1, + 7989, 5909, 5911, -1, 5911, 7990, 7989, -1, + 7990, 5911, 5913, -1, 5913, 7991, 7990, -1, + 7991, 5913, 5915, -1, 5915, 7992, 7991, -1, + 7992, 5915, 5917, -1, 5917, 7993, 7992, -1, + 7993, 5917, 5919, -1, 5919, 7994, 7993, -1, + 7994, 5919, 5921, -1, 5921, 7995, 7994, -1, + 7995, 5921, 5923, -1, 5923, 7996, 7995, -1, + 7996, 5923, 5925, -1, 5925, 7997, 7996, -1, + 7997, 5925, 5927, -1, 5927, 7998, 7997, -1, + 7998, 5927, 5929, -1, 5929, 7999, 7998, -1, + 7999, 5929, 5931, -1, 5931, 8000, 7999, -1, + 8000, 5931, 5933, -1, 5933, 8001, 8000, -1, + 8001, 5933, 5935, -1, 5935, 8002, 8001, -1, + 8002, 5935, 5937, -1, 5937, 8003, 8002, -1, + 8003, 5937, 5939, -1, 5939, 8004, 8003, -1, + 8004, 5939, 5941, -1, 5941, 8005, 8004, -1, + 8005, 5941, 5943, -1, 5943, 8006, 8005, -1, + 8006, 5943, 5945, -1, 5945, 8007, 8006, -1, + 8007, 5945, 5947, -1, 5947, 8008, 8007, -1, + 8008, 5947, 5949, -1, 5949, 8009, 8008, -1, + 8009, 5949, 5951, -1, 5951, 8010, 8009, -1, + 8011, 8012, 8013, -1, 8012, 8011, 8010, -1, + 8010, 5951, 8012, -1, 8012, 8014, 8015, -1, + 8014, 8012, 5951, -1, 5951, 5950, 8014, -1, + 8014, 8016, 8017, -1, 8016, 8014, 5950, -1, + 5950, 4749, 8016, -1, 8016, 8018, 8019, -1, + 8018, 8016, 4749, -1, 4749, 4748, 8018, -1, + 8018, 8020, 8021, -1, 8020, 8018, 4748, -1, + 4748, 8022, 8020, -1, 8022, 4748, 4746, -1, + 4746, 8023, 8022, -1, 8023, 4746, 4744, -1, + 4744, 8024, 8023, -1, 8024, 4744, 4742, -1, + 4742, 8025, 8024, -1, 8025, 4742, 4740, -1, + 4740, 8026, 8025, -1, 8026, 4740, 4738, -1, + 4738, 8027, 8026, -1, 8027, 4738, 4736, -1, + 4736, 8028, 8027, -1, 8028, 4736, 4734, -1, + 4734, 8029, 8028, -1, 8029, 4734, 4732, -1, + 4732, 8030, 8029, -1, 8030, 4732, 4730, -1, + 4730, 8031, 8030, -1, 8031, 4730, 4728, -1, + 4728, 8032, 8031, -1, 8032, 4728, 4726, -1, + 4726, 8033, 8032, -1, 8033, 4726, 4724, -1, + 4724, 8034, 8033, -1, 8034, 4724, 4722, -1, + 4722, 8035, 8034, -1, 8035, 4722, 4720, -1, + 4720, 8036, 8035, -1, 8036, 4720, 4717, -1, + 4717, 4716, 8036, -1, 8036, 4716, 5968, -1, + 5968, 8035, 8036, -1, 8035, 5968, 5969, -1, + 5969, 8034, 8035, -1, 8034, 5969, 5970, -1, + 5970, 8033, 8034, -1, 8033, 5970, 5971, -1, + 5971, 8032, 8033, -1, 8032, 5971, 5972, -1, + 5972, 8031, 8032, -1, 8031, 5972, 5973, -1, + 5973, 8030, 8031, -1, 8030, 5973, 5974, -1, + 5974, 8029, 8030, -1, 8029, 5974, 5975, -1, + 5975, 8028, 8029, -1, 8028, 5975, 5976, -1, + 5976, 8027, 8028, -1, 8027, 5976, 5977, -1, + 5977, 8026, 8027, -1, 8026, 5977, 5978, -1, + 5978, 8025, 8026, -1, 8025, 5978, 5979, -1, + 5979, 8024, 8025, -1, 8024, 5979, 5980, -1, + 5980, 8023, 8024, -1, 8023, 5980, 5981, -1, + 5981, 8022, 8023, -1, 8022, 5981, 5982, -1, + 5982, 8020, 8022, -1, 5982, 5983, 8020, -1, + 8037, 8020, 5983, -1, 5983, 5985, 8037, -1, + 8037, 5985, 5988, -1, 5988, 8020, 8037, -1, + 5988, 8021, 8020, -1, 8021, 5988, 523, -1, + 8021, 523, 522, -1, 522, 8018, 8021, -1, + 522, 521, 8018, -1, 521, 8019, 8018, -1, + 521, 523, 8019, -1, 8019, 523, 5986, -1, + 5986, 8016, 8019, -1, 5986, 8017, 8016, -1, + 8017, 5986, 520, -1, 8017, 520, 519, -1, + 519, 8014, 8017, -1, 519, 518, 8014, -1, + 518, 8015, 8014, -1, 518, 520, 8015, -1, + 8015, 520, 5987, -1, 5987, 8012, 8015, -1, + 5987, 8013, 8012, -1, 8013, 5987, 3569, -1, + 8013, 3569, 3568, -1, 3568, 8011, 8013, -1, + 3568, 3567, 8011, -1, 8011, 3567, 3571, -1, + 8011, 3571, 7656, -1, 7656, 8010, 8011, -1, + 8010, 7656, 7657, -1, 7657, 8009, 8010, -1, + 8009, 7657, 7658, -1, 7658, 8008, 8009, -1, + 8008, 7658, 7659, -1, 7659, 8007, 8008, -1, + 8007, 7659, 7660, -1, 7660, 8006, 8007, -1, + 8006, 7660, 7661, -1, 7661, 8005, 8006, -1, + 8005, 7661, 7662, -1, 7662, 8004, 8005, -1, + 8004, 7662, 7663, -1, 7663, 8003, 8004, -1, + 8003, 7663, 7664, -1, 7664, 8002, 8003, -1, + 8002, 7664, 7665, -1, 7665, 8001, 8002, -1, + 8001, 7665, 7666, -1, 7666, 8000, 8001, -1, + 8000, 7666, 7667, -1, 7667, 7999, 8000, -1, + 7999, 7667, 7668, -1, 7668, 7998, 7999, -1, + 7998, 7668, 7669, -1, 7669, 7997, 7998, -1, + 7997, 7669, 7670, -1, 7670, 7996, 7997, -1, + 7996, 7670, 7671, -1, 7671, 7995, 7996, -1, + 7995, 7671, 7672, -1, 7672, 7994, 7995, -1, + 7994, 7672, 7673, -1, 7673, 7993, 7994, -1, + 7993, 7673, 7674, -1, 7674, 7992, 7993, -1, + 7992, 7674, 7675, -1, 7675, 7991, 7992, -1, + 7991, 7675, 7676, -1, 7676, 7990, 7991, -1, + 7990, 7676, 7677, -1, 7677, 7989, 7990, -1, + 7989, 7677, 7678, -1, 7678, 7988, 7989, -1, + 7988, 7678, 7679, -1, 7679, 7987, 7988, -1, + 7987, 7679, 7680, -1, 7680, 7986, 7987, -1, + 7986, 7680, 7681, -1, 7681, 7985, 7986, -1, + 7985, 7681, 7682, -1, 7682, 7984, 7985, -1, + 7984, 7682, 7683, -1, 7683, 7983, 7984, -1, + 7983, 7683, 7684, -1, 7684, 7982, 7983, -1, + 7982, 7684, 7685, -1, 7685, 7981, 7982, -1, + 7981, 7685, 7686, -1, 7686, 7980, 7981, -1, + 7980, 7686, 7687, -1, 7687, 7979, 7980, -1, + 7979, 7687, 7688, -1, 7688, 7978, 7979, -1, + 7978, 7688, 7689, -1, 7689, 7977, 7978, -1, + 7977, 7689, 7690, -1, 7690, 7976, 7977, -1, + 7976, 7690, 7691, -1, 7691, 7975, 7976, -1, + 7975, 7691, 7692, -1, 7692, 7974, 7975, -1, + 7974, 7692, 7693, -1, 7693, 7973, 7974, -1, + 7973, 7693, 7694, -1, 7694, 7972, 7973, -1, + 7972, 7694, 7695, -1, 7695, 7971, 7972, -1, + 7971, 7695, 7696, -1, 7696, 7970, 7971, -1, + 7970, 7696, 7697, -1, 7697, 7969, 7970, -1, + 7969, 7697, 7698, -1, 7698, 7968, 7969, -1, + 7968, 7698, 7699, -1, 7699, 7967, 7968, -1, + 7967, 7699, 7700, -1, 7700, 7966, 7967, -1, + 7966, 7700, 7701, -1, 7701, 7965, 7966, -1, + 7965, 7701, 7702, -1, 7702, 7964, 7965, -1, + 7964, 7702, 7703, -1, 7703, 7963, 7964, -1, + 7963, 7703, 7704, -1, 7704, 7962, 7963, -1, + 7962, 7704, 7705, -1, 7705, 7961, 7962, -1, + 7961, 7705, 7707, -1, 7707, 7960, 7961, -1, + 7960, 7707, 7709, -1, 7709, 7959, 7960, -1, + 7959, 7709, 7711, -1, 7711, 7958, 7959, -1, + 7958, 7711, 7713, -1, 7713, 7957, 7958, -1, + 7957, 7713, 7715, -1, 7715, 7955, 7957, -1, + 7955, 7715, 8038, -1, 8039, 8038, 7715, -1, + 8038, 8039, 517, -1, 8040, 8038, 517, -1, + 8040, 7955, 8038, -1, 8040, 7956, 7955, -1, + 7956, 8040, 517, -1, 7956, 517, 8041, -1, + 8041, 7838, 7956, -1, 8041, 7839, 7838, -1, + 7839, 8041, 517, -1, 7839, 517, 515, -1, + 515, 7840, 7839, -1, 515, 514, 7840, -1, + 514, 7952, 7840, -1, 7952, 514, 516, -1, + 7952, 516, 8042, -1, 8042, 7836, 7952, -1, + 8042, 7837, 7836, -1, 7837, 8042, 516, -1, + 7837, 516, 8043, -1, 8043, 7827, 7837, -1, + 8043, 7826, 7827, -1, 8043, 2719, 7826, -1, + 2719, 8043, 516, -1, 8044, 517, 8039, -1, + 8039, 8045, 8044, -1, 8039, 7715, 8045, -1, + 8045, 7715, 7716, -1, 7716, 8044, 8045, -1, + 7716, 7717, 8044, -1, 7717, 7718, 8044, -1, + 7718, 8046, 8044, -1, 8046, 7718, 7719, -1, + 8046, 7719, 7724, -1, 8046, 7724, 7726, -1, + 7726, 8044, 8046, -1, 529, 1182, 1184, -1, + 1182, 529, 528, -1, 528, 530, 1182, -1, + 530, 1183, 1182, -1, 530, 2696, 1183, -1, + 2696, 530, 531, -1, 531, 2695, 2696, -1, + 2695, 531, 535, -1, 2695, 535, 8047, -1, + 8047, 2694, 2695, -1, 2694, 8047, 8048, -1, + 8048, 2689, 2694, -1, 8048, 2688, 2689, -1, + 8048, 2686, 2688, -1, 2686, 8048, 8047, -1, + 8047, 2684, 2686, -1, 2684, 8047, 535, -1, + 535, 2682, 2684, -1, 2682, 535, 536, -1, + 8049, 2682, 536, -1, 8049, 536, 538, -1, + 8049, 538, 8050, -1, 8050, 2682, 8049, -1, + 8050, 2681, 2682, -1, 8050, 538, 2681, -1, + 538, 2680, 2681, -1, 8051, 392, 8052, -1, + 8051, 8053, 8054, -1, 8054, 8055, 2680, -1, + 8056, 8055, 8054, -1, 8055, 8056, 511, -1, + 8055, 511, 513, -1, 513, 2680, 8055, -1, + 8057, 2680, 513, -1, 8057, 513, 512, -1, + 8057, 512, 8058, -1, 8058, 2680, 8057, -1, + 8058, 2678, 2680, -1, 8058, 512, 2678, -1, + 512, 2679, 2678, -1, 2679, 512, 8059, -1, + 8059, 2683, 2679, -1, 2683, 8059, 8060, -1, + 8060, 2685, 2683, -1, 2685, 8060, 8061, -1, + 8061, 2687, 2685, -1, 2687, 8061, 8062, -1, + 8062, 2676, 2687, -1, 2676, 8062, 8063, -1, + 8063, 2674, 2676, -1, 2674, 8063, 8064, -1, + 8064, 2672, 2674, -1, 2672, 8064, 8065, -1, + 8065, 2670, 2672, -1, 2670, 8065, 8066, -1, + 8066, 2668, 2670, -1, 8066, 2667, 2668, -1, + 8066, 8067, 2667, -1, 8067, 8066, 8065, -1, + 8065, 8068, 8067, -1, 8068, 8065, 8064, -1, + 8064, 8069, 8068, -1, 8069, 8064, 8063, -1, + 8063, 8070, 8069, -1, 8070, 8063, 8062, -1, + 8062, 8071, 8070, -1, 8071, 8062, 8061, -1, + 8061, 8072, 8071, -1, 8072, 8061, 8060, -1, + 8060, 8073, 8072, -1, 8073, 8060, 8059, -1, + 8059, 8074, 8073, -1, 8074, 8059, 512, -1, + 8074, 512, 511, -1, 8074, 511, 8075, -1, + 8075, 8073, 8074, -1, 8073, 8075, 8076, -1, + 8076, 8072, 8073, -1, 8072, 8076, 8077, -1, + 8077, 8071, 8072, -1, 8071, 8077, 8078, -1, + 8078, 8070, 8071, -1, 8070, 8078, 8079, -1, + 8079, 8069, 8070, -1, 8069, 8079, 8080, -1, + 8080, 8068, 8069, -1, 8068, 8080, 8081, -1, + 8081, 8067, 8068, -1, 8067, 8081, 8082, -1, + 8082, 2667, 8067, -1, 8082, 2666, 2667, -1, + 2666, 8082, 510, -1, 510, 2665, 2666, -1, + 2665, 510, 492, -1, 492, 2664, 2665, -1, + 2664, 492, 490, -1, 490, 2663, 2664, -1, + 2663, 490, 488, -1, 488, 2662, 2663, -1, + 2662, 488, 486, -1, 486, 2661, 2662, -1, + 2661, 486, 484, -1, 484, 2660, 2661, -1, + 2660, 484, 482, -1, 482, 2659, 2660, -1, + 2659, 482, 480, -1, 480, 2658, 2659, -1, + 2658, 480, 478, -1, 478, 2657, 2658, -1, + 2657, 478, 476, -1, 476, 2656, 2657, -1, + 2656, 476, 474, -1, 474, 2655, 2656, -1, + 2655, 474, 472, -1, 472, 2654, 2655, -1, + 2654, 472, 470, -1, 470, 2653, 2654, -1, + 2653, 470, 468, -1, 468, 2652, 2653, -1, + 2652, 468, 467, -1, 467, 2651, 2652, -1, + 467, 2650, 2651, -1, 2650, 467, 465, -1, + 465, 2649, 2650, -1, 2649, 465, 463, -1, + 463, 2648, 2649, -1, 2648, 463, 461, -1, + 461, 2647, 2648, -1, 2647, 461, 459, -1, + 459, 2646, 2647, -1, 2646, 459, 457, -1, + 457, 2645, 2646, -1, 2645, 457, 455, -1, + 455, 2644, 2645, -1, 2644, 455, 453, -1, + 453, 2643, 2644, -1, 2643, 453, 451, -1, + 451, 2642, 2643, -1, 2642, 451, 449, -1, + 449, 2641, 2642, -1, 2641, 449, 447, -1, + 447, 2640, 2641, -1, 2640, 447, 445, -1, + 445, 2639, 2640, -1, 2639, 445, 443, -1, + 443, 2638, 2639, -1, 2638, 443, 441, -1, + 441, 2637, 2638, -1, 2637, 441, 420, -1, + 420, 2636, 2637, -1, 2636, 420, 419, -1, + 419, 2615, 2636, -1, 419, 2613, 2615, -1, + 2613, 419, 417, -1, 417, 2611, 2613, -1, + 2611, 417, 415, -1, 415, 2609, 2611, -1, + 2609, 415, 413, -1, 413, 2607, 2609, -1, + 2607, 413, 411, -1, 411, 2605, 2607, -1, + 2605, 411, 409, -1, 409, 2603, 2605, -1, + 2603, 409, 407, -1, 407, 2601, 2603, -1, + 2601, 407, 405, -1, 405, 2599, 2601, -1, + 2599, 405, 403, -1, 403, 2597, 2599, -1, + 2597, 403, 401, -1, 401, 2595, 2597, -1, + 2595, 401, 398, -1, 398, 2633, 2595, -1, + 2633, 398, 397, -1, 397, 2588, 2633, -1, + 397, 396, 2588, -1, 396, 399, 2588, -1, + 399, 2589, 2588, -1, 2589, 399, 395, -1, + 2589, 395, 394, -1, 394, 2590, 2589, -1, + 8083, 2590, 394, -1, 8083, 394, 393, -1, + 8083, 393, 8084, -1, 8084, 2590, 8083, -1, + 8084, 8085, 2590, -1, 8084, 393, 8085, -1, + 8086, 8085, 393, -1, 393, 8087, 8086, -1, + 8087, 393, 431, -1, 431, 8088, 8087, -1, + 8088, 431, 432, -1, 432, 8089, 8088, -1, + 8089, 432, 433, -1, 433, 8090, 8089, -1, + 8090, 433, 434, -1, 434, 8091, 8090, -1, + 8091, 434, 435, -1, 435, 8092, 8091, -1, + 8092, 435, 436, -1, 436, 8093, 8092, -1, + 8093, 436, 437, -1, 437, 8094, 8093, -1, + 8094, 437, 438, -1, 438, 8095, 8094, -1, + 8095, 438, 439, -1, 439, 8096, 8095, -1, + 8096, 439, 440, -1, 8096, 440, 442, -1, + 442, 8097, 8096, -1, 8097, 442, 444, -1, + 444, 8098, 8097, -1, 8098, 444, 446, -1, + 446, 8099, 8098, -1, 8099, 446, 448, -1, + 448, 8100, 8099, -1, 8100, 448, 450, -1, + 450, 8101, 8100, -1, 8101, 450, 452, -1, + 452, 8102, 8101, -1, 8102, 452, 454, -1, + 454, 8103, 8102, -1, 8103, 454, 456, -1, + 456, 8104, 8103, -1, 8104, 456, 458, -1, + 458, 8105, 8104, -1, 8105, 458, 460, -1, + 460, 8106, 8105, -1, 8106, 460, 462, -1, + 462, 8107, 8106, -1, 8107, 462, 464, -1, + 464, 8108, 8107, -1, 8108, 464, 466, -1, + 8108, 466, 469, -1, 469, 8109, 8108, -1, + 8109, 469, 471, -1, 471, 8110, 8109, -1, + 8110, 471, 473, -1, 473, 8111, 8110, -1, + 8111, 473, 475, -1, 475, 8112, 8111, -1, + 8112, 475, 477, -1, 477, 8113, 8112, -1, + 8113, 477, 479, -1, 479, 8114, 8113, -1, + 8114, 479, 481, -1, 481, 8115, 8114, -1, + 8115, 481, 483, -1, 483, 8116, 8115, -1, + 8116, 483, 485, -1, 485, 8117, 8116, -1, + 8117, 485, 487, -1, 487, 8118, 8117, -1, + 8118, 487, 489, -1, 489, 8119, 8118, -1, + 8119, 489, 491, -1, 491, 8120, 8119, -1, + 8120, 491, 493, -1, 8120, 493, 508, -1, + 508, 8121, 8120, -1, 8121, 508, 506, -1, + 506, 8122, 8121, -1, 8122, 506, 504, -1, + 504, 8123, 8122, -1, 8123, 504, 502, -1, + 502, 8124, 8123, -1, 8124, 502, 500, -1, + 500, 8125, 8124, -1, 8125, 500, 498, -1, + 498, 8126, 8125, -1, 8126, 498, 496, -1, + 496, 8127, 8126, -1, 8127, 496, 495, -1, + 495, 8128, 8127, -1, 8129, 8130, 8131, -1, + 8130, 8129, 8128, -1, 8128, 495, 8130, -1, + 8130, 8132, 8133, -1, 8132, 8130, 495, -1, + 495, 494, 8132, -1, 8132, 8134, 8135, -1, + 8134, 8132, 494, -1, 494, 8136, 8134, -1, + 8136, 494, 497, -1, 497, 8137, 8136, -1, + 8137, 497, 499, -1, 499, 8138, 8137, -1, + 8138, 499, 501, -1, 501, 8139, 8138, -1, + 8139, 501, 503, -1, 503, 8140, 8139, -1, + 8140, 503, 505, -1, 505, 8141, 8140, -1, + 8141, 505, 507, -1, 507, 8142, 8141, -1, + 8142, 507, 509, -1, 509, 8143, 8142, -1, + 8143, 509, 510, -1, 8143, 510, 8082, -1, + 8143, 8082, 8081, -1, 8081, 8142, 8143, -1, + 8142, 8081, 8080, -1, 8080, 8141, 8142, -1, + 8141, 8080, 8079, -1, 8079, 8140, 8141, -1, + 8140, 8079, 8078, -1, 8078, 8139, 8140, -1, + 8139, 8078, 8077, -1, 8077, 8138, 8139, -1, + 8138, 8077, 8076, -1, 8076, 8137, 8138, -1, + 8137, 8076, 8075, -1, 8075, 8136, 8137, -1, + 8136, 8075, 511, -1, 511, 8134, 8136, -1, + 8134, 511, 8056, -1, 8144, 8134, 8056, -1, + 8144, 8056, 8054, -1, 8144, 8054, 8145, -1, + 8145, 8134, 8144, -1, 8145, 8135, 8134, -1, + 8145, 8054, 8135, -1, 8135, 8054, 8053, -1, + 8053, 8132, 8135, -1, 8053, 8133, 8132, -1, + 8053, 8051, 8133, -1, 8146, 8147, 8051, -1, + 8147, 8133, 8051, -1, 8147, 8130, 8133, -1, + 8147, 8146, 8130, -1, 8146, 8131, 8130, -1, + 8146, 8051, 8131, -1, 8131, 8051, 8052, -1, + 8052, 8129, 8131, -1, 8052, 8148, 8129, -1, + 8148, 8052, 392, -1, 8148, 392, 148, -1, + 148, 150, 8148, -1, 150, 8129, 8148, -1, + 8129, 150, 390, -1, 390, 8128, 8129, -1, + 8128, 390, 389, -1, 389, 8127, 8128, -1, + 8127, 389, 388, -1, 388, 8126, 8127, -1, + 8126, 388, 387, -1, 387, 8125, 8126, -1, + 8125, 387, 386, -1, 386, 8124, 8125, -1, + 8124, 386, 385, -1, 385, 8123, 8124, -1, + 8123, 385, 384, -1, 384, 8122, 8123, -1, + 8122, 384, 383, -1, 383, 8121, 8122, -1, + 8121, 383, 382, -1, 382, 8120, 8121, -1, + 382, 8119, 8120, -1, 8119, 382, 340, -1, + 340, 8118, 8119, -1, 8118, 340, 341, -1, + 341, 8117, 8118, -1, 8117, 341, 342, -1, + 342, 8116, 8117, -1, 8116, 342, 343, -1, + 343, 8115, 8116, -1, 8115, 343, 344, -1, + 344, 8114, 8115, -1, 8114, 344, 345, -1, + 345, 8113, 8114, -1, 8113, 345, 346, -1, + 346, 8112, 8113, -1, 8112, 346, 347, -1, + 347, 8111, 8112, -1, 8111, 347, 348, -1, + 348, 8110, 8111, -1, 8110, 348, 349, -1, + 349, 8109, 8110, -1, 8109, 349, 350, -1, + 350, 8108, 8109, -1, 350, 8107, 8108, -1, + 8107, 350, 351, -1, 351, 8106, 8107, -1, + 8106, 351, 352, -1, 352, 8105, 8106, -1, + 8105, 352, 353, -1, 353, 8104, 8105, -1, + 8104, 353, 354, -1, 354, 8103, 8104, -1, + 8103, 354, 355, -1, 355, 8102, 8103, -1, + 8102, 355, 356, -1, 356, 8101, 8102, -1, + 8101, 356, 357, -1, 357, 8100, 8101, -1, + 8100, 357, 358, -1, 358, 8099, 8100, -1, + 8099, 358, 359, -1, 359, 8098, 8099, -1, + 8098, 359, 360, -1, 360, 8097, 8098, -1, + 8097, 360, 8149, -1, 8149, 8096, 8097, -1, + 8149, 8095, 8096, -1, 8095, 8149, 8150, -1, + 8150, 8094, 8095, -1, 8094, 8150, 8151, -1, + 8151, 8093, 8094, -1, 8093, 8151, 8152, -1, + 8152, 8092, 8093, -1, 8092, 8152, 8153, -1, + 8153, 8091, 8092, -1, 8091, 8153, 8154, -1, + 8154, 8090, 8091, -1, 8090, 8154, 8155, -1, + 8155, 8089, 8090, -1, 8089, 8155, 8156, -1, + 8156, 8088, 8089, -1, 8088, 8156, 8157, -1, + 8157, 8087, 8088, -1, 8087, 8157, 8158, -1, + 8158, 8086, 8087, -1, 8159, 8160, 8086, -1, + 8086, 8158, 8159, -1, 8159, 8161, 8162, -1, + 8159, 8163, 8161, -1, 8163, 8159, 8158, -1, + 8158, 8164, 8163, -1, 8164, 8158, 8157, -1, + 8157, 8165, 8164, -1, 8165, 8157, 8156, -1, + 8156, 8166, 8165, -1, 8166, 8156, 8155, -1, + 8155, 8167, 8166, -1, 8167, 8155, 8154, -1, + 8154, 8168, 8167, -1, 8168, 8154, 8153, -1, + 8153, 8169, 8168, -1, 8169, 8153, 8152, -1, + 8152, 8170, 8169, -1, 8170, 8152, 8151, -1, + 8151, 8171, 8170, -1, 8171, 8151, 8150, -1, + 8150, 8172, 8171, -1, 8172, 8150, 8149, -1, + 8172, 8149, 360, -1, 8172, 360, 361, -1, + 361, 8171, 8172, -1, 8171, 361, 362, -1, + 362, 8170, 8171, -1, 8170, 362, 363, -1, + 363, 8169, 8170, -1, 8169, 363, 364, -1, + 364, 8168, 8169, -1, 8168, 364, 365, -1, + 365, 8167, 8168, -1, 8167, 365, 366, -1, + 366, 8166, 8167, -1, 8166, 366, 367, -1, + 367, 8165, 8166, -1, 8165, 367, 368, -1, + 368, 8164, 8165, -1, 8164, 368, 369, -1, + 369, 8163, 8164, -1, 373, 8173, 8161, -1, + 8173, 373, 391, -1, 391, 392, 8173, -1, + 392, 8174, 8173, -1, 8175, 8174, 8176, -1, + 8175, 8173, 8174, -1, 8175, 8161, 8173, -1, + 8175, 8176, 8161, -1, 8176, 8162, 8161, -1, + 8162, 8176, 8174, -1, 8162, 8174, 8177, -1, + 8177, 8159, 8162, -1, 8177, 8160, 8159, -1, + 8177, 8174, 8160, -1, 8160, 8174, 8178, -1, + 8178, 8086, 8160, -1, 8178, 8085, 8086, -1, + 8178, 2590, 8085, -1, 2590, 8178, 8174, -1, + 3293, 3294, 146, -1, 8179, 146, 3294, -1, + 8179, 3294, 732, -1, 8179, 732, 730, -1, + 730, 146, 8179, -1, 730, 729, 146, -1, + 729, 147, 146, -1, 147, 729, 731, -1, + 147, 731, 774, -1, 774, 143, 147, -1, + 774, 8180, 143, -1, 8180, 774, 773, -1, + 8180, 773, 776, -1, 776, 143, 8180, -1, + 776, 775, 143, -1, 775, 144, 143, -1, + 144, 775, 777, -1, 144, 777, 779, -1, + 779, 145, 144, -1, 779, 778, 145, -1, + 8181, 8182, 130, -1, 8182, 8181, 145, -1, + 8182, 145, 778, -1, 778, 780, 8182, -1, + 780, 130, 8182, -1, 130, 780, 781, -1, + 781, 142, 130, -1, 142, 781, 782, -1, + 782, 140, 142, -1, 140, 782, 783, -1, + 783, 138, 140, -1, 138, 783, 784, -1, + 784, 136, 138, -1, 136, 784, 791, -1, + 791, 134, 136, -1, 134, 791, 789, -1, + 789, 131, 134, -1, 131, 789, 787, -1, + 787, 132, 131, -1, 132, 787, 786, -1, + 786, 8183, 132, -1, 8183, 786, 799, -1, + 799, 8184, 8183, -1, 8184, 799, 801, -1, + 801, 8185, 8184, -1, 8185, 801, 803, -1, + 803, 8186, 8185, -1, 8186, 803, 805, -1, + 805, 8187, 8186, -1, 8187, 805, 807, -1, + 807, 8188, 8187, -1, 8188, 807, 809, -1, + 809, 8189, 8188, -1, 8189, 809, 811, -1, + 811, 8190, 8189, -1, 8190, 811, 813, -1, + 813, 8191, 8190, -1, 8191, 813, 815, -1, + 815, 8192, 8191, -1, 8192, 815, 817, -1, + 817, 8193, 8192, -1, 8193, 817, 819, -1, + 819, 8194, 8193, -1, 8194, 819, 821, -1, + 821, 8195, 8194, -1, 8195, 821, 823, -1, + 823, 976, 8195, -1, 8196, 8195, 976, -1, + 976, 8197, 8196, -1, 8197, 976, 977, -1, + 977, 8198, 8197, -1, 8198, 977, 978, -1, + 978, 8199, 8198, -1, 8199, 978, 979, -1, + 979, 8200, 8199, -1, 8200, 979, 980, -1, + 980, 8201, 8200, -1, 8201, 980, 997, -1, + 997, 8202, 8201, -1, 8202, 997, 995, -1, + 995, 8203, 8202, -1, 8203, 995, 993, -1, + 993, 8204, 8203, -1, 8204, 993, 991, -1, + 991, 8205, 8204, -1, 8206, 8207, 8208, -1, + 8208, 8209, 8206, -1, 8209, 8208, 8210, -1, + 8210, 8211, 8209, -1, 8211, 8210, 8212, -1, + 8212, 8213, 8211, -1, 8213, 8212, 8214, -1, + 8214, 8215, 8213, -1, 8215, 8214, 8205, -1, + 8205, 991, 8215, -1, 8215, 991, 988, -1, + 988, 8213, 8215, -1, 8213, 988, 987, -1, + 987, 8211, 8213, -1, 8211, 987, 985, -1, + 985, 8209, 8211, -1, 8209, 985, 983, -1, + 983, 8206, 8209, -1, 8206, 983, 982, -1, + 982, 8207, 8206, -1, 8207, 982, 8216, -1, + 8216, 8217, 8207, -1, 8217, 8216, 8218, -1, + 8218, 8219, 8217, -1, 8219, 8218, 8220, -1, + 8220, 8221, 8219, -1, 8221, 8220, 8222, -1, + 8222, 8223, 8221, -1, 8223, 8222, 8224, -1, + 8224, 8225, 8223, -1, 8225, 8224, 8226, -1, + 8226, 8227, 8225, -1, 8227, 8226, 8228, -1, + 8228, 8229, 8227, -1, 8229, 8228, 8230, -1, + 8230, 8231, 8229, -1, 8231, 8230, 8232, -1, + 8232, 8233, 8231, -1, 8233, 8232, 8234, -1, + 8233, 8234, 8235, -1, 8235, 8236, 8233, -1, + 8236, 8235, 8237, -1, 8237, 8238, 8236, -1, + 8238, 8237, 8239, -1, 8239, 8240, 8238, -1, + 8240, 8239, 8241, -1, 8241, 8242, 8240, -1, + 8242, 8241, 8243, -1, 8243, 8244, 8242, -1, + 8244, 8243, 8245, -1, 8245, 8246, 8244, -1, + 8246, 8245, 8247, -1, 8247, 8248, 8246, -1, + 8248, 8247, 8249, -1, 8249, 8250, 8248, -1, + 8249, 8251, 8250, -1, 8252, 8253, 8254, -1, + 8253, 8252, 8255, -1, 8255, 8256, 8253, -1, + 8256, 8255, 8257, -1, 8257, 8258, 8256, -1, + 8258, 8257, 8259, -1, 8259, 8260, 8258, -1, + 8260, 8259, 8261, -1, 8261, 8262, 8260, -1, + 8262, 8261, 8263, -1, 8263, 8264, 8262, -1, + 8264, 8263, 8251, -1, 8251, 8265, 8264, -1, + 8265, 8251, 8249, -1, 8249, 8266, 8265, -1, + 8266, 8249, 8247, -1, 8247, 8267, 8266, -1, + 8267, 8247, 8245, -1, 8245, 8268, 8267, -1, + 8268, 8245, 8243, -1, 8243, 8269, 8268, -1, + 8269, 8243, 8241, -1, 8241, 8270, 8269, -1, + 8270, 8241, 8239, -1, 8239, 8271, 8270, -1, + 8271, 8239, 8237, -1, 8237, 8272, 8271, -1, + 8272, 8237, 8235, -1, 8235, 8273, 8272, -1, + 8273, 8235, 8234, -1, 8234, 8274, 8273, -1, + 8234, 8275, 8274, -1, 8275, 8234, 8232, -1, + 8232, 8276, 8275, -1, 8276, 8232, 8230, -1, + 8230, 8277, 8276, -1, 8277, 8230, 8228, -1, + 8228, 8278, 8277, -1, 8278, 8228, 8226, -1, + 8226, 8279, 8278, -1, 8279, 8226, 8224, -1, + 8224, 8280, 8279, -1, 8280, 8224, 8222, -1, + 8222, 8281, 8280, -1, 8281, 8222, 8220, -1, + 8220, 8282, 8281, -1, 8282, 8220, 8218, -1, + 8218, 8283, 8282, -1, 8283, 8218, 8216, -1, + 8216, 8284, 8283, -1, 8284, 8216, 982, -1, + 982, 981, 8284, -1, 8285, 8284, 981, -1, + 981, 8286, 8285, -1, 8286, 981, 984, -1, + 984, 8287, 8286, -1, 8287, 984, 986, -1, + 986, 989, 8287, -1, 8287, 989, 999, -1, + 999, 8286, 8287, -1, 8286, 999, 1060, -1, + 1060, 8285, 8286, -1, 8285, 1060, 1058, -1, + 1058, 8284, 8285, -1, 8284, 1058, 1056, -1, + 1056, 8283, 8284, -1, 8283, 1056, 1054, -1, + 1054, 8282, 8283, -1, 8282, 1054, 1052, -1, + 1052, 8281, 8282, -1, 8281, 1052, 1050, -1, + 1050, 8280, 8281, -1, 8280, 1050, 1048, -1, + 1048, 8279, 8280, -1, 8279, 1048, 1046, -1, + 1046, 8278, 8279, -1, 8278, 1046, 1044, -1, + 1044, 8277, 8278, -1, 8277, 1044, 1042, -1, + 1042, 8276, 8277, -1, 8276, 1042, 1040, -1, + 1040, 8275, 8276, -1, 8275, 1040, 1038, -1, + 1038, 8274, 8275, -1, 8274, 1038, 1035, -1, + 8274, 1035, 1033, -1, 1033, 8273, 8274, -1, + 8273, 1033, 1031, -1, 1031, 8272, 8273, -1, + 8272, 1031, 1029, -1, 1029, 8271, 8272, -1, + 8271, 1029, 1027, -1, 1027, 8270, 8271, -1, + 8270, 1027, 1025, -1, 1025, 8269, 8270, -1, + 8269, 1025, 1023, -1, 1023, 8268, 8269, -1, + 8268, 1023, 1021, -1, 1021, 8267, 8268, -1, + 8267, 1021, 1019, -1, 1019, 8266, 8267, -1, + 8266, 1019, 1017, -1, 1017, 8265, 8266, -1, + 8265, 1017, 1016, -1, 1016, 8264, 8265, -1, + 8264, 1016, 1015, -1, 1015, 8262, 8264, -1, + 8262, 1015, 1014, -1, 1014, 8260, 8262, -1, + 8260, 1014, 1013, -1, 1013, 8258, 8260, -1, + 8258, 1013, 1012, -1, 1012, 8256, 8258, -1, + 8256, 1012, 1010, -1, 1010, 8253, 8256, -1, + 8253, 1010, 1011, -1, 1011, 8254, 8253, -1, + 8254, 1011, 1062, -1, 1062, 1063, 8254, -1, + 8288, 8254, 1063, -1, 8254, 8288, 8289, -1, + 8289, 8252, 8254, -1, 8252, 8289, 8290, -1, + 8290, 8255, 8252, -1, 8255, 8290, 8291, -1, + 8291, 8257, 8255, -1, 8257, 8291, 8292, -1, + 8292, 8259, 8257, -1, 8259, 8292, 8293, -1, + 8293, 8261, 8259, -1, 8261, 8293, 8294, -1, + 8294, 8263, 8261, -1, 8263, 8294, 8295, -1, + 8295, 8251, 8263, -1, 8295, 8250, 8251, -1, + 8295, 8296, 8250, -1, 8296, 8295, 8294, -1, + 8294, 8297, 8296, -1, 8297, 8294, 8293, -1, + 8293, 8298, 8297, -1, 8298, 8293, 8292, -1, + 8292, 8299, 8298, -1, 8299, 8292, 8291, -1, + 8291, 8300, 8299, -1, 8300, 8291, 8290, -1, + 8290, 8301, 8300, -1, 8301, 8290, 8289, -1, + 8289, 8302, 8301, -1, 8302, 8289, 8288, -1, + 8288, 8303, 8302, -1, 8303, 8288, 1063, -1, + 1063, 8304, 8303, -1, 8304, 1063, 1064, -1, + 1064, 8305, 8304, -1, 8305, 1064, 1065, -1, + 1065, 8306, 8305, -1, 8306, 1065, 1066, -1, + 1066, 8307, 8306, -1, 8307, 1066, 1067, -1, + 1067, 8308, 8307, -1, 8308, 1067, 1068, -1, + 1068, 8309, 8308, -1, 8309, 1068, 1069, -1, + 1069, 8310, 8309, -1, 8310, 1069, 1070, -1, + 1070, 8311, 8310, -1, 8311, 1070, 1071, -1, + 1071, 1175, 8311, -1, 8312, 8311, 1175, -1, + 8311, 8312, 8313, -1, 8313, 8310, 8311, -1, + 8310, 8313, 8314, -1, 8314, 8309, 8310, -1, + 8309, 8314, 8315, -1, 8315, 8308, 8309, -1, + 8308, 8315, 8316, -1, 8316, 8307, 8308, -1, + 8307, 8316, 8317, -1, 8317, 8306, 8307, -1, + 8306, 8317, 8318, -1, 8318, 8305, 8306, -1, + 8305, 8318, 8319, -1, 8319, 8304, 8305, -1, + 8304, 8319, 8320, -1, 8320, 8303, 8304, -1, + 8303, 8320, 8321, -1, 8321, 8302, 8303, -1, + 8302, 8321, 8322, -1, 8322, 8301, 8302, -1, + 8301, 8322, 8323, -1, 8323, 8300, 8301, -1, + 8300, 8323, 8324, -1, 8324, 8299, 8300, -1, + 8299, 8324, 8325, -1, 8325, 8298, 8299, -1, + 8298, 8325, 8326, -1, 8326, 8297, 8298, -1, + 8297, 8326, 8327, -1, 8327, 8296, 8297, -1, + 8296, 8327, 127, -1, 127, 8250, 8296, -1, + 8250, 127, 125, -1, 125, 8248, 8250, -1, + 8248, 125, 123, -1, 123, 8246, 8248, -1, + 8246, 123, 121, -1, 121, 8244, 8246, -1, + 8244, 121, 119, -1, 119, 8242, 8244, -1, + 8242, 119, 117, -1, 117, 8240, 8242, -1, + 8240, 117, 115, -1, 115, 8238, 8240, -1, + 8238, 115, 113, -1, 113, 8236, 8238, -1, + 8236, 113, 112, -1, 112, 8233, 8236, -1, + 112, 8231, 8233, -1, 8231, 112, 110, -1, + 110, 8229, 8231, -1, 8229, 110, 108, -1, + 108, 8227, 8229, -1, 8227, 108, 106, -1, + 106, 8225, 8227, -1, 8225, 106, 104, -1, + 104, 8223, 8225, -1, 8223, 104, 102, -1, + 102, 8221, 8223, -1, 8221, 102, 100, -1, + 100, 8219, 8221, -1, 8219, 100, 98, -1, + 98, 8217, 8219, -1, 8217, 98, 96, -1, + 96, 8207, 8217, -1, 8207, 96, 95, -1, + 95, 8208, 8207, -1, 8208, 95, 8328, -1, + 8328, 8210, 8208, -1, 8210, 8328, 8329, -1, + 8329, 8212, 8210, -1, 8212, 8329, 8330, -1, + 8330, 8214, 8212, -1, 8214, 8330, 8331, -1, + 8331, 8205, 8214, -1, 8205, 8331, 92, -1, + 92, 8204, 8205, -1, 8204, 92, 90, -1, + 90, 8203, 8204, -1, 8203, 90, 88, -1, + 88, 8202, 8203, -1, 8202, 88, 86, -1, + 86, 8201, 8202, -1, 8201, 86, 84, -1, + 84, 8200, 8201, -1, 8200, 84, 82, -1, + 82, 8199, 8200, -1, 8199, 82, 80, -1, + 80, 8198, 8199, -1, 8198, 80, 78, -1, + 78, 8197, 8198, -1, 8197, 78, 76, -1, + 76, 8196, 8197, -1, 8196, 76, 74, -1, + 74, 8195, 8196, -1, 8195, 74, 73, -1, + 73, 8194, 8195, -1, 8194, 73, 71, -1, + 71, 8193, 8194, -1, 8193, 71, 35, -1, + 35, 8192, 8193, -1, 8192, 35, 33, -1, + 33, 8191, 8192, -1, 8191, 33, 31, -1, + 31, 8190, 8191, -1, 8190, 31, 29, -1, + 29, 8189, 8190, -1, 8189, 29, 27, -1, + 27, 8188, 8189, -1, 8188, 27, 25, -1, + 25, 8187, 8188, -1, 8187, 25, 23, -1, + 23, 8186, 8187, -1, 8186, 23, 21, -1, + 21, 8185, 8186, -1, 8185, 21, 19, -1, + 19, 8184, 8185, -1, 8184, 19, 17, -1, + 17, 8183, 8184, -1, 8183, 17, 15, -1, + 15, 132, 8183, -1, 132, 15, 13, -1, + 13, 133, 132, -1, 133, 13, 11, -1, + 11, 135, 133, -1, 135, 11, 9, -1, + 9, 137, 135, -1, 137, 9, 7, -1, + 7, 139, 137, -1, 139, 7, 5, -1, + 5, 141, 139, -1, 141, 5, 4, -1, + 4, 128, 141, -1, 4, 8332, 128, -1, + 8333, 128, 8332, -1, 8333, 8332, 8334, -1, + 8333, 8334, 8335, -1, 8335, 128, 8333, -1, + 8335, 129, 128, -1, 8335, 8334, 129, -1, + 129, 8334, 8336, -1, 8336, 130, 129, -1, + 8336, 8181, 130, -1, 8336, 145, 8181, -1, + 145, 8336, 8334, -1, 8334, 8337, 2584, -1, + 8337, 8334, 8332, -1, 8337, 8332, 4, -1, + 8337, 4, 3, -1, 3, 2584, 8337, -1, + 8338, 2584, 3, -1, 8338, 3, 1, -1, + 8338, 1, 0, -1, 0, 2584, 8338, -1, + 0, 2, 2584, -1, 8339, 2584, 2, -1, + 8339, 2488, 2584, -1, 8339, 2489, 2488, -1, + 8339, 2, 2489, -1, 2489, 2, 1, -1, + 2489, 1, 6, -1, 6, 2486, 2489, -1, + 2486, 6, 8, -1, 8, 2485, 2486, -1, + 2485, 8, 10, -1, 10, 2484, 2485, -1, + 2484, 10, 12, -1, 12, 2483, 2484, -1, + 2483, 12, 14, -1, 14, 2482, 2483, -1, + 2482, 14, 16, -1, 16, 2481, 2482, -1, + 2481, 16, 18, -1, 18, 2480, 2481, -1, + 2480, 18, 20, -1, 20, 2479, 2480, -1, + 2479, 20, 22, -1, 22, 2478, 2479, -1, + 2478, 22, 24, -1, 24, 2477, 2478, -1, + 2477, 24, 26, -1, 26, 2476, 2477, -1, + 2476, 26, 28, -1, 28, 2475, 2476, -1, + 2475, 28, 30, -1, 30, 2474, 2475, -1, + 2474, 30, 32, -1, 32, 2473, 2474, -1, + 2473, 32, 34, -1, 34, 2440, 2473, -1, + 2440, 34, 36, -1, 36, 2441, 2440, -1, + 2441, 36, 70, -1, 70, 2443, 2441, -1, + 2443, 70, 68, -1, 68, 2445, 2443, -1, + 2445, 68, 66, -1, 66, 2447, 2445, -1, + 2447, 66, 64, -1, 64, 2449, 2447, -1, + 2449, 64, 62, -1, 62, 2451, 2449, -1, + 2451, 62, 60, -1, 60, 2453, 2451, -1, + 2453, 60, 58, -1, 58, 2455, 2453, -1, + 2455, 58, 56, -1, 56, 2457, 2455, -1, + 2457, 56, 54, -1, 54, 2459, 2457, -1, + 2459, 54, 52, -1, 52, 2461, 2459, -1, + 2461, 52, 50, -1, 50, 2463, 2461, -1, + 2463, 50, 48, -1, 48, 2465, 2463, -1, + 2465, 48, 46, -1, 46, 2467, 2465, -1, + 2467, 46, 44, -1, 44, 2469, 2467, -1, + 2469, 44, 42, -1, 42, 2471, 2469, -1, + 2471, 42, 40, -1, 40, 2438, 2471, -1, + 2438, 40, 37, -1, 37, 2437, 2438, -1, + 37, 39, 2437, -1, 8340, 2437, 39, -1, + 8340, 2436, 2437, -1, 2436, 8340, 8341, -1, + 8341, 2435, 2436, -1, 2435, 8341, 8342, -1, + 8342, 2434, 2435, -1, 2434, 8342, 8343, -1, + 8343, 2433, 2434, -1, 2433, 8343, 8344, -1, + 8344, 2432, 2433, -1, 2432, 8344, 8345, -1, + 8345, 2431, 2432, -1, 2431, 8345, 8346, -1, + 8346, 2430, 2431, -1, 2430, 8346, 8347, -1, + 2430, 8347, 8348, -1, 8348, 2429, 2430, -1, + 2429, 8348, 8349, -1, 8349, 2428, 2429, -1, + 2428, 8349, 8350, -1, 8350, 2427, 2428, -1, + 2427, 8350, 8351, -1, 8351, 2426, 2427, -1, + 2426, 8351, 8352, -1, 8352, 2425, 2426, -1, + 2425, 8352, 8353, -1, 8353, 2424, 2425, -1, + 8353, 8354, 2424, -1, 8355, 8356, 8357, -1, + 8356, 8355, 8358, -1, 8358, 8359, 8356, -1, + 8359, 8358, 8360, -1, 8360, 8361, 8359, -1, + 8361, 8360, 8362, -1, 8362, 8363, 8361, -1, + 8363, 8362, 8364, -1, 8364, 8365, 8363, -1, + 8365, 8364, 8366, -1, 8366, 8367, 8365, -1, + 8367, 8366, 8354, -1, 8354, 8368, 8367, -1, + 8368, 8354, 8353, -1, 8353, 8369, 8368, -1, + 8369, 8353, 8352, -1, 8352, 8370, 8369, -1, + 8370, 8352, 8351, -1, 8351, 8371, 8370, -1, + 8371, 8351, 8350, -1, 8350, 8372, 8371, -1, + 8372, 8350, 8349, -1, 8349, 8373, 8372, -1, + 8373, 8349, 8348, -1, 8348, 8374, 8373, -1, + 8374, 8348, 8347, -1, 8347, 8375, 8374, -1, + 8347, 8376, 8375, -1, 8376, 8347, 8346, -1, + 8346, 8377, 8376, -1, 8377, 8346, 8345, -1, + 8345, 8378, 8377, -1, 8378, 8345, 8344, -1, + 8344, 8379, 8378, -1, 8379, 8344, 8343, -1, + 8343, 8380, 8379, -1, 8380, 8343, 8342, -1, + 8342, 8381, 8380, -1, 8381, 8342, 8341, -1, + 8341, 8382, 8381, -1, 8382, 8341, 8340, -1, + 8340, 8383, 8382, -1, 8383, 8340, 39, -1, + 39, 8384, 8383, -1, 8384, 39, 38, -1, + 38, 8385, 8384, -1, 8385, 38, 41, -1, + 41, 8386, 8385, -1, 8386, 41, 43, -1, + 43, 8387, 8386, -1, 8387, 43, 45, -1, + 45, 8388, 8387, -1, 8388, 45, 47, -1, + 47, 8389, 8388, -1, 8389, 47, 49, -1, + 49, 8390, 8389, -1, 8390, 49, 51, -1, + 51, 8391, 8390, -1, 8391, 51, 53, -1, + 53, 8392, 8391, -1, 8392, 53, 55, -1, + 55, 8393, 8392, -1, 8393, 55, 57, -1, + 57, 8394, 8393, -1, 8394, 57, 59, -1, + 59, 8395, 8394, -1, 8395, 59, 61, -1, + 61, 8396, 8395, -1, 8396, 61, 63, -1, + 63, 8397, 8396, -1, 8397, 63, 65, -1, + 65, 8398, 8397, -1, 8398, 65, 67, -1, + 67, 8399, 8398, -1, 8399, 67, 69, -1, + 69, 71, 8399, -1, 8399, 71, 73, -1, + 73, 8398, 8399, -1, 8398, 73, 72, -1, + 72, 8397, 8398, -1, 8397, 72, 75, -1, + 75, 8396, 8397, -1, 8396, 75, 77, -1, + 77, 8395, 8396, -1, 8395, 77, 79, -1, + 79, 8394, 8395, -1, 8394, 79, 81, -1, + 81, 8393, 8394, -1, 8393, 81, 83, -1, + 83, 8392, 8393, -1, 8392, 83, 85, -1, + 85, 8391, 8392, -1, 8391, 85, 87, -1, + 87, 8390, 8391, -1, 8390, 87, 89, -1, + 89, 8389, 8390, -1, 8389, 89, 91, -1, + 91, 8388, 8389, -1, 8388, 91, 93, -1, + 93, 8387, 8388, -1, 8387, 93, 8400, -1, + 8400, 8386, 8387, -1, 8386, 8400, 8401, -1, + 8401, 8385, 8386, -1, 8385, 8401, 8402, -1, + 8402, 8384, 8385, -1, 8384, 8402, 8403, -1, + 8403, 8383, 8384, -1, 8403, 8404, 8383, -1, + 8403, 8405, 8404, -1, 8405, 8403, 8402, -1, + 8402, 8406, 8405, -1, 8406, 8402, 8401, -1, + 8401, 8407, 8406, -1, 8407, 8401, 8400, -1, + 8400, 8408, 8407, -1, 8408, 8400, 93, -1, + 93, 92, 8408, -1, 8408, 92, 8331, -1, + 8331, 8407, 8408, -1, 8407, 8331, 8330, -1, + 8330, 8406, 8407, -1, 8406, 8330, 8329, -1, + 8329, 8405, 8406, -1, 8405, 8329, 8328, -1, + 8328, 8404, 8405, -1, 8404, 8328, 95, -1, + 95, 94, 8404, -1, 94, 8383, 8404, -1, + 94, 8382, 8383, -1, 8382, 94, 97, -1, + 97, 8381, 8382, -1, 8381, 97, 99, -1, + 99, 8380, 8381, -1, 8380, 99, 101, -1, + 101, 8379, 8380, -1, 8379, 101, 103, -1, + 103, 8378, 8379, -1, 8378, 103, 105, -1, + 105, 8377, 8378, -1, 8377, 105, 107, -1, + 107, 8376, 8377, -1, 8376, 107, 109, -1, + 109, 8375, 8376, -1, 8375, 109, 111, -1, + 8375, 111, 114, -1, 114, 8374, 8375, -1, + 8374, 114, 116, -1, 116, 8373, 8374, -1, + 8373, 116, 118, -1, 118, 8372, 8373, -1, + 8372, 118, 120, -1, 120, 8371, 8372, -1, + 8371, 120, 122, -1, 122, 8370, 8371, -1, + 8370, 122, 124, -1, 124, 8369, 8370, -1, + 8369, 124, 126, -1, 126, 8368, 8369, -1, + 126, 8409, 8368, -1, 8410, 8411, 8412, -1, + 8411, 8410, 8413, -1, 8413, 8414, 8411, -1, + 8414, 8413, 8415, -1, 8415, 8416, 8414, -1, + 8416, 8415, 8417, -1, 8417, 8418, 8416, -1, + 8418, 8417, 8419, -1, 8419, 8420, 8418, -1, + 8420, 8419, 8421, -1, 8421, 8422, 8420, -1, + 8422, 8421, 8409, -1, 8409, 8423, 8422, -1, + 8423, 8409, 126, -1, 8423, 126, 127, -1, + 8423, 127, 8327, -1, 8327, 8422, 8423, -1, + 8422, 8327, 8326, -1, 8326, 8420, 8422, -1, + 8420, 8326, 8325, -1, 8325, 8418, 8420, -1, + 8418, 8325, 8324, -1, 8324, 8416, 8418, -1, + 8416, 8324, 8323, -1, 8323, 8414, 8416, -1, + 8414, 8323, 8322, -1, 8322, 8411, 8414, -1, + 8411, 8322, 8321, -1, 8321, 8412, 8411, -1, + 8412, 8321, 8320, -1, 8320, 8424, 8412, -1, + 8424, 8320, 8319, -1, 8319, 8425, 8424, -1, + 8425, 8319, 8318, -1, 8318, 8426, 8425, -1, + 8426, 8318, 8317, -1, 8317, 8427, 8426, -1, + 8427, 8317, 8316, -1, 8316, 8428, 8427, -1, + 8428, 8316, 8315, -1, 8315, 8429, 8428, -1, + 8429, 8315, 8314, -1, 8314, 8430, 8429, -1, + 8430, 8314, 8313, -1, 8313, 8431, 8430, -1, + 8431, 8313, 8312, -1, 8312, 8432, 8431, -1, + 8432, 8312, 1175, -1, 1175, 1109, 8432, -1, + 8433, 8432, 1109, -1, 8432, 8433, 8434, -1, + 8434, 8431, 8432, -1, 8431, 8434, 8435, -1, + 8435, 8430, 8431, -1, 8430, 8435, 8436, -1, + 8436, 8429, 8430, -1, 8429, 8436, 8437, -1, + 8437, 8428, 8429, -1, 8428, 8437, 8438, -1, + 8438, 8427, 8428, -1, 8427, 8438, 8439, -1, + 8439, 8426, 8427, -1, 8426, 8439, 8440, -1, + 8440, 8425, 8426, -1, 8425, 8440, 8441, -1, + 8441, 8424, 8425, -1, 8424, 8441, 8442, -1, + 8442, 8412, 8424, -1, 8412, 8442, 8443, -1, + 8443, 8410, 8412, -1, 8410, 8443, 8444, -1, + 8444, 8413, 8410, -1, 8413, 8444, 8445, -1, + 8445, 8415, 8413, -1, 8415, 8445, 8446, -1, + 8446, 8417, 8415, -1, 8417, 8446, 8447, -1, + 8447, 8419, 8417, -1, 8419, 8447, 8448, -1, + 8448, 8421, 8419, -1, 8421, 8448, 8449, -1, + 8449, 8409, 8421, -1, 8449, 8368, 8409, -1, + 8449, 8367, 8368, -1, 8367, 8449, 8448, -1, + 8448, 8365, 8367, -1, 8365, 8448, 8447, -1, + 8447, 8363, 8365, -1, 8363, 8447, 8446, -1, + 8446, 8361, 8363, -1, 8361, 8446, 8445, -1, + 8445, 8359, 8361, -1, 8359, 8445, 8444, -1, + 8444, 8356, 8359, -1, 8356, 8444, 8443, -1, + 8443, 8357, 8356, -1, 8357, 8443, 8442, -1, + 8442, 8450, 8357, -1, 8450, 8442, 8441, -1, + 8441, 8451, 8450, -1, 8451, 8441, 8440, -1, + 8440, 8452, 8451, -1, 8452, 8440, 8439, -1, + 8439, 8453, 8452, -1, 8453, 8439, 8438, -1, + 8438, 8454, 8453, -1, 8454, 8438, 8437, -1, + 8437, 8455, 8454, -1, 8455, 8437, 8436, -1, + 8436, 8456, 8455, -1, 8456, 8436, 8435, -1, + 8435, 8457, 8456, -1, 8457, 8435, 8434, -1, + 8434, 8458, 8457, -1, 8458, 8434, 8433, -1, + 8433, 8459, 8458, -1, 8459, 8433, 1109, -1, + 1109, 1108, 8459, -1, 8460, 8459, 1108, -1, + 8459, 8460, 8461, -1, 8461, 8458, 8459, -1, + 8458, 8461, 8462, -1, 8462, 8457, 8458, -1, + 8457, 8462, 8463, -1, 8463, 8456, 8457, -1, + 8456, 8463, 8464, -1, 8464, 8455, 8456, -1, + 8455, 8464, 8465, -1, 8465, 8454, 8455, -1, + 8454, 8465, 8466, -1, 8466, 8453, 8454, -1, + 8453, 8466, 8467, -1, 8467, 8452, 8453, -1, + 8452, 8467, 8468, -1, 8468, 8451, 8452, -1, + 8451, 8468, 8469, -1, 8469, 8450, 8451, -1, + 8450, 8469, 8470, -1, 8470, 8357, 8450, -1, + 8357, 8470, 8471, -1, 8471, 8355, 8357, -1, + 8355, 8471, 8472, -1, 8472, 8358, 8355, -1, + 8358, 8472, 8473, -1, 8473, 8360, 8358, -1, + 8360, 8473, 8474, -1, 8474, 8362, 8360, -1, + 8362, 8474, 8475, -1, 8475, 8364, 8362, -1, + 8364, 8475, 8476, -1, 8476, 8366, 8364, -1, + 8366, 8476, 8477, -1, 8477, 8354, 8366, -1, + 8477, 2424, 8354, -1, 8477, 2423, 2424, -1, + 2423, 8477, 8476, -1, 8476, 2422, 2423, -1, + 2422, 8476, 8475, -1, 8475, 2421, 2422, -1, + 2421, 8475, 8474, -1, 8474, 2069, 2421, -1, + 2069, 8474, 8473, -1, 8473, 2067, 2069, -1, + 2067, 8473, 8472, -1, 8472, 2070, 2067, -1, + 2070, 8472, 8471, -1, 8471, 2072, 2070, -1, + 2072, 8471, 8470, -1, 8470, 2074, 2072, -1, + 2074, 8470, 8469, -1, 8469, 2076, 2074, -1, + 2076, 8469, 8468, -1, 8468, 2078, 2076, -1, + 2078, 8468, 8467, -1, 8467, 2080, 2078, -1, + 2080, 8467, 8466, -1, 8466, 2082, 2080, -1, + 2082, 8466, 8465, -1, 8465, 2084, 2082, -1, + 2084, 8465, 8464, -1, 8464, 2086, 2084, -1, + 2086, 8464, 8463, -1, 8463, 2088, 2086, -1, + 2088, 8463, 8462, -1, 8462, 2090, 2088, -1, + 2090, 8462, 8461, -1, 8461, 2092, 2090, -1, + 2092, 8461, 8460, -1, 8460, 2094, 2092, -1, + 2094, 8460, 1108, -1, 1108, 2096, 2094, -1, + 2096, 1108, 1106, -1, 1106, 2420, 2096, -1, + 2420, 1106, 1104, -1, 1104, 2419, 2420, -1, + 2419, 1104, 1102, -1, 1102, 2418, 2419, -1, + 2418, 1102, 1100, -1, 1100, 2417, 2418, -1, + 2417, 1100, 1098, -1, 1098, 2416, 2417, -1, + 2416, 1098, 1096, -1, 1096, 2415, 2416, -1, + 2415, 1096, 1094, -1, 1094, 2414, 2415, -1, + 2414, 1094, 1092, -1, 1092, 2413, 2414, -1, + 2413, 1092, 1090, -1, 1090, 2412, 2413, -1, + 2412, 1090, 1088, -1, 1088, 2411, 2412, -1, + 2411, 1088, 1086, -1, 1086, 2410, 2411, -1, + 2410, 1086, 1084, -1, 1084, 2409, 2410, -1, + 2409, 1084, 1082, -1, 1082, 2408, 2409, -1, + 2408, 1082, 1080, -1, 1080, 2407, 2408, -1, + 2407, 1080, 1078, -1, 1078, 2406, 2407, -1, + 2406, 1078, 1076, -1, 1076, 2404, 2406, -1, + 2404, 1076, 1072, -1, 1072, 8478, 2404, -1, + 8479, 2404, 8478, -1, 8478, 8480, 8479, -1, + 8478, 8481, 8480, -1, 8481, 8478, 1072, -1, + 8481, 1072, 1074, -1, 1074, 8480, 8481, -1, + 1074, 8482, 8480, -1, 8482, 1074, 1073, -1, + 8482, 1073, 1177, -1, 8482, 1177, 1178, -1, + 1178, 8480, 8482, -1, 8483, 1602, 1646, -1, + 8484, 8483, 1646, -1, 8484, 1646, 1608, -1, + 8484, 1608, 1607, -1, 1607, 8483, 8484, -1, + 1607, 1605, 8483, -1, 1605, 1604, 8483, -1, + 1604, 8485, 8483, -1, 1604, 1606, 8485, -1, + 8486, 8485, 1606, -1, 1606, 8487, 8486, -1, + 8487, 1606, 1609, -1, 1609, 8488, 8487, -1, + 8488, 1609, 1641, -1, 1641, 8489, 8488, -1, + 8489, 1641, 1639, -1, 1639, 8490, 8489, -1, + 8490, 1639, 1636, -1, 8490, 1636, 1629, -1, + 8490, 1629, 1627, -1, 1627, 8489, 8490, -1, + 8489, 1627, 1625, -1, 1625, 8488, 8489, -1, + 8488, 1625, 1623, -1, 1623, 8487, 8488, -1, + 8487, 1623, 1612, -1, 1612, 8486, 8487, -1, + 8486, 1612, 1611, -1, 1611, 8491, 8486, -1, + 8491, 1611, 1614, -1, 8491, 1614, 1615, -1, + 8491, 1615, 8492, -1, 8492, 8486, 8491, -1, + 8492, 8485, 8486, -1, 8485, 8492, 1615, -1, + 1615, 8483, 8485, -1, 8493, 1615, 1616, -1, + 8494, 8493, 1616, -1, 8494, 1616, 1617, -1, + 8494, 1617, 1619, -1, 1619, 8493, 8494, -1, + 1619, 8495, 8493, -1, 1619, 1618, 8495, -1, + 8496, 1618, 8497, -1, 8496, 8495, 1618, -1, + 8496, 8493, 8495, -1, 8496, 8497, 8493, -1, + 8497, 8498, 8493, -1, 8499, 8500, 8501, -1, + 8499, 8502, 8500, -1, 8502, 8499, 8503, -1, + 8503, 8504, 8502, -1, 8504, 8503, 8505, -1, + 8505, 8506, 8504, -1, 8506, 8505, 8507, -1, + 8507, 8508, 8506, -1, 8509, 8510, 8511, -1, + 8509, 8511, 8512, -1, 8512, 8513, 8509, -1, + 8513, 8512, 8514, -1, 8514, 8515, 8513, -1, + 8515, 8514, 8516, -1, 8516, 8517, 8515, -1, + 8517, 8516, 8518, -1, 8518, 8519, 8517, -1, + 8519, 8518, 8520, -1, 8520, 8521, 8519, -1, + 8521, 8520, 8508, -1, 8508, 8507, 8521, -1, + 8507, 8522, 8521, -1, 8522, 8507, 8505, -1, + 8505, 8523, 8522, -1, 8523, 8505, 8503, -1, + 8503, 8524, 8523, -1, 8524, 8503, 8499, -1, + 8499, 8525, 8524, -1, 8498, 8524, 8525, -1, + 8498, 8497, 8524, -1, 8524, 8497, 1618, -1, + 1618, 8523, 8524, -1, 8523, 1618, 1620, -1, + 1620, 8522, 8523, -1, 8522, 1620, 1621, -1, + 1621, 8521, 8522, -1, 8521, 1621, 1622, -1, + 1622, 8519, 8521, -1, 8519, 1622, 1624, -1, + 1624, 8517, 8519, -1, 8517, 1624, 1626, -1, + 1626, 8515, 8517, -1, 8515, 1626, 1628, -1, + 1628, 8513, 8515, -1, 8513, 1628, 1630, -1, + 1630, 8509, 8513, -1, 8509, 1630, 1633, -1, + 1633, 8510, 8509, -1, 8510, 1633, 1916, -1, + 1916, 8526, 8510, -1, 8526, 1916, 1917, -1, + 1917, 8527, 8526, -1, 8527, 1917, 1918, -1, + 1918, 8528, 8527, -1, 8528, 1918, 1919, -1, + 1919, 8529, 8528, -1, 8529, 1919, 1920, -1, + 1920, 8530, 8529, -1, 8530, 1920, 1921, -1, + 1921, 8531, 8530, -1, 8531, 1921, 1922, -1, + 1922, 8532, 8531, -1, 8532, 1922, 1923, -1, + 1923, 8533, 8532, -1, 8533, 1923, 1924, -1, + 1924, 8534, 8533, -1, 8534, 1924, 1925, -1, + 1925, 8535, 8534, -1, 8535, 1925, 1926, -1, + 1926, 8536, 8535, -1, 8536, 1926, 1927, -1, + 1927, 8537, 8536, -1, 8537, 1927, 1928, -1, + 1928, 8538, 8537, -1, 8538, 1928, 1929, -1, + 1929, 8539, 8538, -1, 8539, 1929, 1930, -1, + 1930, 8540, 8539, -1, 8540, 1930, 1931, -1, + 1931, 8541, 8540, -1, 8541, 1931, 1932, -1, + 1932, 8542, 8541, -1, 8542, 1932, 1933, -1, + 1933, 8543, 8542, -1, 8543, 1933, 1934, -1, + 1934, 8544, 8543, -1, 8544, 1934, 1935, -1, + 1935, 8545, 8544, -1, 8545, 1935, 1936, -1, + 1936, 8546, 8545, -1, 8546, 1936, 1937, -1, + 1937, 8547, 8546, -1, 8547, 1937, 1938, -1, + 1938, 8548, 8547, -1, 1938, 8549, 8548, -1, + 8549, 1938, 1939, -1, 1939, 8550, 8549, -1, + 8550, 1939, 1940, -1, 1940, 8551, 8550, -1, + 8551, 1940, 1941, -1, 1941, 8552, 8551, -1, + 8552, 1941, 1942, -1, 1942, 8553, 8552, -1, + 8553, 1942, 1943, -1, 1943, 8554, 8553, -1, + 8554, 1943, 1944, -1, 1944, 8555, 8554, -1, + 8555, 1944, 1945, -1, 1945, 8556, 8555, -1, + 8556, 1945, 1946, -1, 1946, 8557, 8556, -1, + 8557, 1946, 1947, -1, 1947, 8558, 8557, -1, + 8558, 1947, 1948, -1, 1948, 8559, 8558, -1, + 8559, 1948, 1949, -1, 1949, 8560, 8559, -1, + 8560, 1949, 1950, -1, 1950, 8561, 8560, -1, + 8561, 1950, 1951, -1, 1951, 8562, 8561, -1, + 8562, 1951, 1952, -1, 1952, 8563, 8562, -1, + 8563, 1952, 1953, -1, 1953, 8564, 8563, -1, + 8564, 1953, 1954, -1, 1954, 8565, 8564, -1, + 8565, 1954, 1955, -1, 1955, 8566, 8565, -1, + 8566, 1955, 1956, -1, 1956, 8567, 8566, -1, + 8567, 1956, 1957, -1, 1957, 8568, 8567, -1, + 8568, 1957, 1958, -1, 1958, 8569, 8568, -1, + 8569, 1958, 1959, -1, 1959, 8570, 8569, -1, + 8570, 1959, 1960, -1, 8570, 1960, 1961, -1, + 8570, 1961, 1967, -1, 1967, 8569, 8570, -1, + 8569, 1967, 2057, -1, 2057, 8568, 8569, -1, + 8568, 2057, 2055, -1, 2055, 8567, 8568, -1, + 8567, 2055, 2053, -1, 2053, 8566, 8567, -1, + 8566, 2053, 2051, -1, 2051, 8565, 8566, -1, + 8565, 2051, 2049, -1, 2049, 8564, 8565, -1, + 8564, 2049, 2047, -1, 2047, 8563, 8564, -1, + 8563, 2047, 2045, -1, 2045, 8562, 8563, -1, + 8562, 2045, 2043, -1, 2043, 8561, 8562, -1, + 8561, 2043, 2041, -1, 2041, 8560, 8561, -1, + 8560, 2041, 2039, -1, 2039, 8559, 8560, -1, + 8559, 2039, 2037, -1, 2037, 8558, 8559, -1, + 8558, 2037, 2035, -1, 2035, 8557, 8558, -1, + 8557, 2035, 2033, -1, 2033, 8556, 8557, -1, + 8556, 2033, 2031, -1, 2031, 8555, 8556, -1, + 8555, 2031, 2029, -1, 2029, 8554, 8555, -1, + 8554, 2029, 2027, -1, 2027, 8553, 8554, -1, + 8553, 2027, 2025, -1, 2025, 8552, 8553, -1, + 8552, 2025, 2023, -1, 2023, 8551, 8552, -1, + 8551, 2023, 2021, -1, 2021, 8550, 8551, -1, + 8550, 2021, 2019, -1, 2019, 8549, 8550, -1, + 8549, 2019, 2017, -1, 2017, 8548, 8549, -1, + 8548, 2017, 2014, -1, 8548, 2014, 2012, -1, + 2012, 8547, 8548, -1, 8547, 2012, 2010, -1, + 2010, 8546, 8547, -1, 8546, 2010, 2008, -1, + 2008, 8545, 8546, -1, 8545, 2008, 2006, -1, + 2006, 8544, 8545, -1, 8544, 2006, 2004, -1, + 2004, 8543, 8544, -1, 8543, 2004, 2002, -1, + 2002, 8542, 8543, -1, 8542, 2002, 2000, -1, + 2000, 8541, 8542, -1, 8541, 2000, 1998, -1, + 1998, 8540, 8541, -1, 8540, 1998, 1996, -1, + 1996, 8539, 8540, -1, 8539, 1996, 1994, -1, + 1994, 8538, 8539, -1, 8538, 1994, 1992, -1, + 1992, 8537, 8538, -1, 8537, 1992, 1990, -1, + 1990, 8536, 8537, -1, 8536, 1990, 1988, -1, + 1988, 8535, 8536, -1, 8535, 1988, 1986, -1, + 1986, 8534, 8535, -1, 8534, 1986, 1984, -1, + 1984, 8533, 8534, -1, 8533, 1984, 1982, -1, + 1982, 8532, 8533, -1, 8532, 1982, 1980, -1, + 1980, 8531, 8532, -1, 8531, 1980, 1978, -1, + 1978, 8530, 8531, -1, 8530, 1978, 1976, -1, + 1976, 8529, 8530, -1, 8529, 1976, 1974, -1, + 1974, 8528, 8529, -1, 8528, 1974, 1972, -1, + 1972, 8527, 8528, -1, 8527, 1972, 1970, -1, + 1970, 8526, 8527, -1, 8526, 1970, 1969, -1, + 1969, 8510, 8526, -1, 1969, 8511, 8510, -1, + 1969, 1968, 8511, -1, 8511, 1968, 2059, -1, + 8511, 2059, 2574, -1, 2574, 8512, 8511, -1, + 8512, 2574, 2573, -1, 2573, 8514, 8512, -1, + 8514, 2573, 2572, -1, 2572, 8516, 8514, -1, + 8516, 2572, 2571, -1, 2571, 8518, 8516, -1, + 8518, 2571, 2570, -1, 2570, 8520, 8518, -1, + 8520, 2570, 2569, -1, 2569, 8508, 8520, -1, + 8508, 2569, 2568, -1, 2568, 8506, 8508, -1, + 8506, 2568, 2567, -1, 2567, 8504, 8506, -1, + 8504, 2567, 2566, -1, 2566, 8502, 8504, -1, + 8502, 2566, 2565, -1, 2565, 8500, 8502, -1, + 8500, 2565, 2564, -1, 8500, 2564, 8571, -1, + 8572, 8571, 2564, -1, 8572, 8573, 8571, -1, + 8574, 8573, 8572, -1, 8572, 2564, 8574, -1, + 8574, 2564, 2563, -1, 2563, 8573, 8574, -1, + 2563, 2562, 8573, -1, 8573, 8575, 8576, -1, + 8575, 8573, 2562, -1, 2562, 2302, 8575, -1, + 2302, 2305, 8575, -1, 8577, 8575, 2305, -1, + 8577, 8576, 8575, -1, 8578, 8576, 8577, -1, + 8577, 2305, 8578, -1, 8578, 2305, 2307, -1, + 2307, 8576, 8578, -1, 2307, 2306, 8576, -1, + 8576, 8579, 8580, -1, 8579, 8576, 2306, -1, + 2306, 2308, 8579, -1, 2308, 2310, 8579, -1, + 8581, 8579, 2310, -1, 8581, 8580, 8579, -1, + 8582, 8580, 8581, -1, 8581, 2310, 8582, -1, + 8582, 2310, 2403, -1, 2403, 8580, 8582, -1, + 2403, 8583, 8580, -1, 8583, 2403, 2402, -1, + 8583, 2402, 2405, -1, 2405, 8580, 8583, -1, + 2405, 8584, 8580, -1, 8584, 2405, 2404, -1, + 8584, 2404, 8479, -1, 8479, 8480, 8584, -1, + 8480, 8580, 8584, -1, 8585, 8493, 8498, -1, + 8498, 8525, 8585, -1, 8586, 8585, 8525, -1, + 8525, 8499, 8586, -1, 8586, 8499, 8501, -1, + 8501, 8585, 8586, -1, 8501, 8587, 8585, -1, + 8587, 8501, 8500, -1, 8587, 8500, 8571, -1, + 8571, 8585, 8587, -1, 8585, 8571, 8573, -1, + 5763, 5758, 8588, -1, 8588, 5758, 5757, -1, + 5763, 8588, 5764, -1, 5764, 8588, 5757, -1, + 1472, 1493, 1449, -1, 1449, 1493, 1402, -1, + 1402, 1493, 1430, -1, 1430, 1493, 1426, -1, + 1426, 1493, 1352, -1, 1352, 1493, 1368, -1, + 1352, 1368, 1367, -1, 1367, 1497, 1352, -1, + 1352, 1497, 1537, -1, 1352, 1537, 1541, -1, + 1541, 2627, 1352, -1, 1352, 2627, 2588, -1, + 1352, 2588, 2590, -1, 1352, 2590, 2585, -1, + 2585, 2590, 2577, -1, 2577, 2590, 2580, -1, + 2580, 2590, 2584, -1, 2584, 2590, 8334, -1, + 8334, 2590, 145, -1, 145, 2590, 143, -1, + 143, 2590, 146, -1, 146, 2590, 3293, -1, + 3293, 2590, 8174, -1, 3293, 8174, 392, -1, + 392, 8051, 3293, -1, 3293, 8051, 8054, -1, + 3293, 8054, 2680, -1, 2680, 538, 3293, -1, + 3293, 538, 529, -1, 3293, 529, 3564, -1, + 3564, 529, 3565, -1, 3565, 529, 5524, -1, + 5524, 529, 7726, -1, 7726, 529, 8044, -1, + 8044, 529, 1184, -1, 8044, 1184, 517, -1, + 517, 1184, 516, -1, 516, 1184, 2719, -1, + 2719, 1184, 2720, -1, 2720, 1184, 2706, -1, + 2706, 1184, 2754, -1, 2754, 1184, 2701, -1, + 2701, 1184, 3177, -1, 3177, 1184, 3181, -1, + 3181, 1184, 1558, -1, 3181, 1558, 1562, -1, + 1562, 3182, 3181, -1, 3181, 3182, 3184, -1, + 3181, 3184, 1602, -1, 3181, 1602, 1145, -1, + 1145, 1602, 1178, -1, 1178, 1602, 8480, -1, + 8480, 1602, 8483, -1, 8480, 8483, 1615, -1, + 1615, 8493, 8480, -1, 8480, 8493, 8580, -1, + 8493, 8585, 8580, -1, 8580, 8585, 8576, -1, + 8585, 8573, 8576, -1, 8589, 8590, 8591, -1, + 8591, 8590, 8592, -1, 8591, 8593, 8589, -1, + 8589, 8593, 8594, -1, 8595, 8596, 8597, -1, + 8597, 8596, 8598, -1, 8597, 8592, 8595, -1, + 8595, 8592, 8590, -1, 8596, 8599, 8598, -1, + 8598, 8599, 8600, -1, 8601, 8602, 8603, -1, + 8603, 8602, 8604, -1, 8603, 8605, 8601, -1, + 8601, 8605, 8606, -1, 8607, 8608, 8609, -1, + 8609, 8608, 8610, -1, 8609, 8611, 8607, -1, + 8607, 8611, 8612, -1, 8613, 8612, 8614, -1, + 8614, 8612, 8611, -1, 8614, 8615, 8613, -1, + 8613, 8615, 8616, -1, 8612, 8613, 8607, -1, + 8607, 8613, 8616, -1, 8607, 8616, 8617, -1, + 8607, 8617, 8608, -1, 8608, 8617, 8618, -1, + 8618, 8617, 8619, -1, 8619, 8617, 8620, -1, + 8620, 8617, 8621, -1, 8621, 8617, 8622, -1, + 8622, 8617, 8623, -1, 8623, 8617, 8624, -1, + 8624, 8617, 8625, -1, 8625, 8617, 8626, -1, + 8617, 8627, 8626, -1, 8626, 8627, 8628, -1, + 8626, 8628, 8629, -1, 8629, 8630, 8626, -1, + 8626, 8630, 8631, -1, 8626, 8631, 8632, -1, + 8632, 8633, 8626, -1, 8626, 8633, 8634, -1, + 8626, 8634, 8635, -1, 8626, 8635, 8636, -1, + 8636, 8635, 8637, -1, 8637, 8635, 8638, -1, + 8638, 8635, 8639, -1, 8639, 8635, 8640, -1, + 8640, 8635, 8641, -1, 8641, 8635, 8642, -1, + 8642, 8635, 8643, -1, 8642, 8643, 8644, -1, + 8644, 8645, 8642, -1, 8642, 8645, 8646, -1, + 8642, 8646, 8647, -1, 8647, 8602, 8642, -1, + 8642, 8602, 8601, -1, 8642, 8601, 8606, -1, + 8606, 8648, 8642, -1, 8642, 8648, 8599, -1, + 8642, 8599, 8596, -1, 8596, 8595, 8642, -1, + 8642, 8595, 8590, -1, 8642, 8590, 8589, -1, + 8589, 8594, 8642, -1, 8642, 8594, 8649, -1, + 8642, 8649, 8650, -1, 8650, 8651, 8642, -1, + 8642, 8651, 8652, -1, 8642, 8652, 8653, -1, + 8653, 8654, 8642, -1, 8642, 8654, 8655, -1, + 8655, 8654, 8656, -1, 8656, 8654, 8657, -1, + 8656, 8657, 8658, -1, 8615, 8659, 8616, -1, + 8616, 8659, 8617, -1, 8660, 8661, 8634, -1, + 8634, 8661, 8635, -1, 8634, 8633, 8660, -1, + 8660, 8633, 8662, -1, 8633, 8632, 8662, -1, + 8662, 8632, 8663, -1, 8632, 8631, 8663, -1, + 8663, 8631, 8664, -1, 8652, 8651, 8665, -1, + 8665, 8651, 8666, -1, 8665, 8667, 8652, -1, + 8652, 8667, 8653, -1, 8668, 8669, 8658, -1, + 8658, 8669, 8656, -1, 8658, 8657, 8668, -1, + 8668, 8657, 8670, -1, 8669, 8671, 8656, -1, + 8656, 8671, 8655, -1, 8637, 8638, 8672, -1, + 8672, 8638, 8673, -1, 8672, 8674, 8637, -1, + 8637, 8674, 8636, -1, 8657, 8654, 8670, -1, + 8670, 8654, 8675, -1, 8671, 8676, 8655, -1, + 8655, 8676, 8642, -1, 8638, 8639, 8673, -1, + 8673, 8639, 8677, -1, 8674, 8678, 8636, -1, + 8636, 8678, 8626, -1, 8678, 8679, 8626, -1, + 8626, 8679, 8625, -1, 8661, 8680, 8635, -1, + 8635, 8680, 8643, -1, 8631, 8630, 8664, -1, + 8664, 8630, 8681, -1, 8628, 8627, 8682, -1, + 8682, 8627, 8683, -1, 8682, 8684, 8628, -1, + 8628, 8684, 8629, -1, 8684, 8681, 8629, -1, + 8629, 8681, 8630, -1, 8685, 8686, 8646, -1, + 8646, 8686, 8647, -1, 8646, 8645, 8685, -1, + 8685, 8645, 8687, -1, 8686, 8604, 8647, -1, + 8647, 8604, 8602, -1, 8605, 8688, 8606, -1, + 8606, 8688, 8648, -1, 8688, 8600, 8648, -1, + 8648, 8600, 8599, -1, 8620, 8621, 8689, -1, + 8689, 8621, 8690, -1, 8689, 8691, 8620, -1, + 8620, 8691, 8619, -1, 8650, 8649, 8692, -1, + 8692, 8649, 8693, -1, 8692, 8666, 8650, -1, + 8650, 8666, 8651, -1, 8649, 8594, 8693, -1, + 8693, 8594, 8593, -1, 8691, 8694, 8619, -1, + 8619, 8694, 8618, -1, 8694, 8610, 8618, -1, + 8618, 8610, 8608, -1, 8659, 8683, 8617, -1, + 8617, 8683, 8627, -1, 8679, 8695, 8625, -1, + 8625, 8695, 8624, -1, 8695, 8696, 8624, -1, + 8624, 8696, 8623, -1, 8696, 8697, 8623, -1, + 8623, 8697, 8622, -1, 8697, 8690, 8622, -1, + 8622, 8690, 8621, -1, 8667, 8675, 8653, -1, + 8653, 8675, 8654, -1, 8676, 8698, 8642, -1, + 8642, 8698, 8641, -1, 8639, 8640, 8677, -1, + 8677, 8640, 8699, -1, 8640, 8641, 8699, -1, + 8699, 8641, 8698, -1, 8680, 8700, 8643, -1, + 8643, 8700, 8644, -1, 8700, 8687, 8644, -1, + 8644, 8687, 8645, -1, 295, 370, 330, -1, + 330, 370, 369, -1, 295, 296, 370, -1, + 370, 296, 332, -1, 332, 373, 371, -1, + 371, 373, 8161, -1, 629, 631, 630, -1, + 630, 631, 3493, -1, 4803, 5189, 4804, -1, + 4804, 5189, 5072, -1, 2878, 525, 8701, -1, + 8701, 525, 2769, -1, 2878, 8701, 2768, -1, + 2768, 8701, 2769, -1, 369, 371, 8163, -1, + 8163, 371, 8161, -1, 3595, 3579, 8699, -1, + 8699, 3579, 3576, -1, 8699, 3576, 8677, -1, + 8677, 3576, 3597, -1, 8677, 3597, 8673, -1, + 8673, 3597, 5208, -1, 8673, 5208, 8672, -1, + 8672, 5208, 5186, -1, 8672, 5186, 8674, -1, + 8674, 5186, 5075, -1, 8674, 5075, 8678, -1, + 8678, 5075, 5041, -1, 8678, 5041, 8679, -1, + 8679, 5041, 7431, -1, 8679, 7431, 8695, -1, + 8695, 7431, 4955, -1, 8695, 4955, 8696, -1, + 8696, 4955, 3628, -1, 8696, 3628, 8697, -1, + 8697, 3628, 7560, -1, 8697, 7560, 8690, -1, + 8690, 7560, 6799, -1, 8690, 6799, 8689, -1, + 8689, 6799, 6798, -1, 8689, 6798, 6590, -1, + 8689, 6590, 8691, -1, 8691, 6590, 6593, -1, + 8691, 6593, 8694, -1, 8694, 6593, 3632, -1, + 8694, 3632, 8610, -1, 8610, 3632, 7422, -1, + 8610, 7422, 8609, -1, 8609, 7422, 4091, -1, + 8609, 4091, 8611, -1, 8611, 4091, 4100, -1, + 8611, 4100, 8614, -1, 8614, 4100, 4181, -1, + 8614, 4181, 8615, -1, 8615, 4181, 4098, -1, + 8615, 4098, 8659, -1, 8659, 4098, 7427, -1, + 8659, 7427, 8683, -1, 8683, 7427, 5751, -1, + 8683, 5751, 8682, -1, 8682, 5751, 5754, -1, + 8682, 5754, 8684, -1, 8684, 5754, 5636, -1, + 8684, 5636, 5673, -1, 8684, 5673, 8681, -1, + 8681, 5673, 5758, -1, 8681, 5758, 8664, -1, + 8664, 5758, 5595, -1, 8664, 5595, 8663, -1, + 8663, 5595, 5597, -1, 8663, 5597, 8662, -1, + 8662, 5597, 7747, -1, 8662, 7747, 8660, -1, + 8660, 7747, 525, -1, 8660, 525, 8661, -1, + 8661, 525, 5213, -1, 8661, 5213, 8680, -1, + 8680, 5213, 7652, -1, 8680, 7652, 8700, -1, + 8700, 7652, 5456, -1, 8700, 5456, 8687, -1, + 8687, 5456, 3569, -1, 8687, 3569, 8685, -1, + 8685, 3569, 520, -1, 8685, 520, 8686, -1, + 8686, 520, 523, -1, 8686, 523, 8604, -1, + 8604, 523, 5985, -1, 8604, 5985, 5989, -1, + 8604, 5989, 8603, -1, 8603, 5989, 6127, -1, + 8603, 6127, 8605, -1, 8605, 6127, 6123, -1, + 8605, 6123, 8688, -1, 8688, 6123, 6131, -1, + 8688, 6131, 8600, -1, 8600, 6131, 4237, -1, + 8600, 4237, 8598, -1, 8598, 4237, 4093, -1, + 8598, 4093, 8597, -1, 8597, 4093, 4092, -1, + 8597, 4092, 8592, -1, 8592, 4092, 3711, -1, + 8592, 3711, 8591, -1, 8591, 3711, 3728, -1, + 8591, 3728, 8593, -1, 8593, 3728, 7249, -1, + 8593, 7249, 8693, -1, 8693, 7249, 6998, -1, + 8693, 6998, 8692, -1, 8692, 6998, 6824, -1, + 8692, 6824, 6820, -1, 8692, 6820, 8666, -1, + 8666, 6820, 6817, -1, 8666, 6817, 8665, -1, + 8665, 6817, 4995, -1, 8665, 4995, 8667, -1, + 8667, 4995, 4997, -1, 8667, 4997, 8675, -1, + 8675, 4997, 7643, -1, 8675, 7643, 8670, -1, + 8670, 7643, 5007, -1, 8670, 5007, 8668, -1, + 8668, 5007, 5083, -1, 8668, 5083, 8669, -1, + 8669, 5083, 5085, -1, 8669, 5085, 8671, -1, + 8671, 5085, 5190, -1, 8671, 5190, 8676, -1, + 8676, 5190, 3618, -1, 8676, 3618, 8698, -1, + 8698, 3618, 3595, -1, 8698, 3595, 8699, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5712, 5712, 5712, -1, 5713, 5713, 5713, -1, + 5714, 5714, 5714, -1, 5715, 5715, 5715, -1, + 5716, 5716, 5716, -1, 5717, 5717, 5717, -1, + 5718, 5718, 5718, -1, 5719, 5719, 5719, -1, + 5720, 5720, 5720, -1, 5721, 5721, 5721, -1, + 5722, 5722, 5722, -1, 5723, 5723, 5723, -1, + 5724, 5724, 5724, -1, 5725, 5725, 5725, -1, + 5726, 5726, 5726, -1, 5727, 5727, 5727, -1, + 5728, 5728, 5728, -1, 5729, 5729, 5729, -1, + 5730, 5730, 5730, -1, 5731, 5731, 5731, -1, + 5732, 5732, 5732, -1, 5733, 5733, 5733, -1, + 5734, 5734, 5734, -1, 5735, 5735, 5735, -1, + 5736, 5736, 5736, -1, 5737, 5737, 5737, -1, + 5738, 5738, 5738, -1, 5739, 5739, 5739, -1, + 5740, 5740, 5740, -1, 5741, 5741, 5741, -1, + 5742, 5742, 5742, -1, 5743, 5743, 5743, -1, + 5744, 5744, 5744, -1, 5745, 5745, 5745, -1, + 5746, 5746, 5746, -1, 5747, 5747, 5747, -1, + 5748, 5748, 5748, -1, 5749, 5749, 5749, -1, + 5750, 5750, 5750, -1, 5751, 5751, 5751, -1, + 5752, 5752, 5752, -1, 5753, 5753, 5753, -1, + 5754, 5754, 5754, -1, 5755, 5755, 5755, -1, + 5756, 5756, 5756, -1, 5757, 5757, 5757, -1, + 5758, 5758, 5758, -1, 5759, 5759, 5759, -1, + 5760, 5760, 5760, -1, 5761, 5761, 5761, -1, + 5762, 5762, 5762, -1, 5763, 5763, 5763, -1, + 5764, 5764, 5764, -1, 5765, 5765, 5765, -1, + 5766, 5766, 5766, -1, 5767, 5767, 5767, -1, + 5768, 5768, 5768, -1, 5769, 5769, 5769, -1, + 5770, 5770, 5770, -1, 5771, 5771, 5771, -1, + 5772, 5772, 5772, -1, 5773, 5773, 5773, -1, + 5774, 5774, 5774, -1, 5775, 5775, 5775, -1, + 5776, 5776, 5776, -1, 5777, 5777, 5777, -1, + 5778, 5778, 5778, -1, 5779, 5779, 5779, -1, + 5780, 5780, 5780, -1, 5781, 5781, 5781, -1, + 5782, 5782, 5782, -1, 5783, 5783, 5783, -1, + 5784, 5784, 5784, -1, 5785, 5785, 5785, -1, + 5786, 5786, 5786, -1, 5787, 5787, 5787, -1, + 5788, 5788, 5788, -1, 5789, 5789, 5789, -1, + 5790, 5790, 5790, -1, 5791, 5791, 5791, -1, + 5792, 5792, 5792, -1, 5793, 5793, 5793, -1, + 5794, 5794, 5794, -1, 5795, 5795, 5795, -1, + 5796, 5796, 5796, -1, 5797, 5797, 5797, -1, + 5798, 5798, 5798, -1, 5799, 5799, 5799, -1, + 5800, 5800, 5800, -1, 5801, 5801, 5801, -1, + 5802, 5802, 5802, -1, 5803, 5803, 5803, -1, + 5804, 5804, 5804, -1, 5805, 5805, 5805, -1, + 5806, 5806, 5806, -1, 5807, 5807, 5807, -1, + 5808, 5808, 5808, -1, 5809, 5809, 5809, -1, + 5810, 5810, 5810, -1, 5811, 5811, 5811, -1, + 5812, 5812, 5812, -1, 5813, 5813, 5813, -1, + 5814, 5814, 5814, -1, 5815, 5815, 5815, -1, + 5816, 5816, 5816, -1, 5817, 5817, 5817, -1, + 5818, 5818, 5818, -1, 5819, 5819, 5819, -1, + 5820, 5820, 5820, -1, 5821, 5821, 5821, -1, + 5822, 5822, 5822, -1, 5823, 5823, 5823, -1, + 5824, 5824, 5824, -1, 5825, 5825, 5825, -1, + 5826, 5826, 5826, -1, 5827, 5827, 5827, -1, + 5828, 5828, 5828, -1, 5829, 5829, 5829, -1, + 5830, 5830, 5830, -1, 5831, 5831, 5831, -1, + 5832, 5832, 5832, -1, 5833, 5833, 5833, -1, + 5834, 5834, 5834, -1, 5835, 5835, 5835, -1, + 5836, 5836, 5836, -1, 5837, 5837, 5837, -1, + 5838, 5838, 5838, -1, 5839, 5839, 5839, -1, + 5840, 5840, 5840, -1, 5841, 5841, 5841, -1, + 5842, 5842, 5842, -1, 5843, 5843, 5843, -1, + 5844, 5844, 5844, -1, 5845, 5845, 5845, -1, + 5846, 5846, 5846, -1, 5847, 5847, 5847, -1, + 5848, 5848, 5848, -1, 5849, 5849, 5849, -1, + 5850, 5850, 5850, -1, 5851, 5851, 5851, -1, + 5852, 5852, 5852, -1, 5853, 5853, 5853, -1, + 5854, 5854, 5854, -1, 5855, 5855, 5855, -1, + 5856, 5856, 5856, -1, 5857, 5857, 5857, -1, + 5858, 5858, 5858, -1, 5859, 5859, 5859, -1, + 5860, 5860, 5860, -1, 5861, 5861, 5861, -1, + 5862, 5862, 5862, -1, 5863, 5863, 5863, -1, + 5864, 5864, 5864, -1, 5865, 5865, 5865, -1, + 5866, 5866, 5866, -1, 5867, 5867, 5867, -1, + 5868, 5868, 5868, -1, 5869, 5869, 5869, -1, + 5870, 5870, 5870, -1, 5871, 5871, 5871, -1, + 5872, 5872, 5872, -1, 5873, 5873, 5873, -1, + 5874, 5874, 5874, -1, 5875, 5875, 5875, -1, + 5876, 5876, 5876, -1, 5877, 5877, 5877, -1, + 5878, 5878, 5878, -1, 5879, 5879, 5879, -1, + 5880, 5880, 5880, -1, 5881, 5881, 5881, -1, + 5882, 5882, 5882, -1, 5883, 5883, 5883, -1, + 5884, 5884, 5884, -1, 5885, 5885, 5885, -1, + 5886, 5886, 5886, -1, 5887, 5887, 5887, -1, + 5888, 5888, 5888, -1, 5889, 5889, 5889, -1, + 5890, 5890, 5890, -1, 5891, 5891, 5891, -1, + 5892, 5892, 5892, -1, 5893, 5893, 5893, -1, + 5894, 5894, 5894, -1, 5895, 5895, 5895, -1, + 5896, 5896, 5896, -1, 5897, 5897, 5897, -1, + 5898, 5898, 5898, -1, 5899, 5899, 5899, -1, + 5900, 5900, 5900, -1, 5901, 5901, 5901, -1, + 5902, 5902, 5902, -1, 5903, 5903, 5903, -1, + 5904, 5904, 5904, -1, 5905, 5905, 5905, -1, + 5906, 5906, 5906, -1, 5907, 5907, 5907, -1, + 5908, 5908, 5908, -1, 5909, 5909, 5909, -1, + 5910, 5910, 5910, -1, 5911, 5911, 5911, -1, + 5912, 5912, 5912, -1, 5913, 5913, 5913, -1, + 5914, 5914, 5914, -1, 5915, 5915, 5915, -1, + 5916, 5916, 5916, -1, 5917, 5917, 5917, -1, + 5918, 5918, 5918, -1, 5919, 5919, 5919, -1, + 5920, 5920, 5920, -1, 5921, 5921, 5921, -1, + 5922, 5922, 5922, -1, 5923, 5923, 5923, -1, + 5924, 5924, 5924, -1, 5925, 5925, 5925, -1, + 5926, 5926, 5926, -1, 5927, 5927, 5927, -1, + 5928, 5928, 5928, -1, 5929, 5929, 5929, -1, + 5930, 5930, 5930, -1, 5931, 5931, 5931, -1, + 5932, 5932, 5932, -1, 5933, 5933, 5933, -1, + 5934, 5934, 5934, -1, 5935, 5935, 5935, -1, + 5936, 5936, 5936, -1, 5937, 5937, 5937, -1, + 5938, 5938, 5938, -1, 5939, 5939, 5939, -1, + 5940, 5940, 5940, -1, 5941, 5941, 5941, -1, + 5942, 5942, 5942, -1, 5943, 5943, 5943, -1, + 5944, 5944, 5944, -1, 5945, 5945, 5945, -1, + 5946, 5946, 5946, -1, 5947, 5947, 5947, -1, + 5948, 5948, 5948, -1, 5949, 5949, 5949, -1, + 5950, 5950, 5950, -1, 5951, 5951, 5951, -1, + 5952, 5952, 5952, -1, 5953, 5953, 5953, -1, + 5954, 5954, 5954, -1, 5955, 5955, 5955, -1, + 5956, 5956, 5956, -1, 5957, 5957, 5957, -1, + 5958, 5958, 5958, -1, 5959, 5959, 5959, -1, + 5960, 5960, 5960, -1, 5961, 5961, 5961, -1, + 5962, 5962, 5962, -1, 5963, 5963, 5963, -1, + 5964, 5964, 5964, -1, 5965, 5965, 5965, -1, + 5966, 5966, 5966, -1, 5967, 5967, 5967, -1, + 5968, 5968, 5968, -1, 5969, 5969, 5969, -1, + 5970, 5970, 5970, -1, 5971, 5971, 5971, -1, + 5972, 5972, 5972, -1, 5973, 5973, 5973, -1, + 5974, 5974, 5974, -1, 5975, 5975, 5975, -1, + 5976, 5976, 5976, -1, 5977, 5977, 5977, -1, + 5978, 5978, 5978, -1, 5979, 5979, 5979, -1, + 5980, 5980, 5980, -1, 5981, 5981, 5981, -1, + 5982, 5982, 5982, -1, 5983, 5983, 5983, -1, + 5984, 5984, 5984, -1, 5985, 5985, 5985, -1, + 5986, 5986, 5986, -1, 5987, 5987, 5987, -1, + 5988, 5988, 5988, -1, 5989, 5989, 5989, -1, + 5990, 5990, 5990, -1, 5991, 5991, 5991, -1, + 5992, 5992, 5992, -1, 5993, 5993, 5993, -1, + 5994, 5994, 5994, -1, 5995, 5995, 5995, -1, + 5996, 5996, 5996, -1, 5997, 5997, 5997, -1, + 5998, 5998, 5998, -1, 5999, 5999, 5999, -1, + 6000, 6000, 6000, -1, 6001, 6001, 6001, -1, + 6002, 6002, 6002, -1, 6003, 6003, 6003, -1, + 6004, 6004, 6004, -1, 6005, 6005, 6005, -1, + 6006, 6006, 6006, -1, 6007, 6007, 6007, -1, + 6008, 6008, 6008, -1, 6009, 6009, 6009, -1, + 6010, 6010, 6010, -1, 6011, 6011, 6011, -1, + 6012, 6012, 6012, -1, 6013, 6013, 6013, -1, + 6014, 6014, 6014, -1, 6015, 6015, 6015, -1, + 6016, 6016, 6016, -1, 6017, 6017, 6017, -1, + 6018, 6018, 6018, -1, 6019, 6019, 6019, -1, + 6020, 6020, 6020, -1, 6021, 6021, 6021, -1, + 6022, 6022, 6022, -1, 6023, 6023, 6023, -1, + 6024, 6024, 6024, -1, 6025, 6025, 6025, -1, + 6026, 6026, 6026, -1, 6027, 6027, 6027, -1, + 6028, 6028, 6028, -1, 6029, 6029, 6029, -1, + 6030, 6030, 6030, -1, 6031, 6031, 6031, -1, + 6032, 6032, 6032, -1, 6033, 6033, 6033, -1, + 6034, 6034, 6034, -1, 6035, 6035, 6035, -1, + 6036, 6036, 6036, -1, 6037, 6037, 6037, -1, + 6038, 6038, 6038, -1, 6039, 6039, 6039, -1, + 6040, 6040, 6040, -1, 6041, 6041, 6041, -1, + 6042, 6042, 6042, -1, 6043, 6043, 6043, -1, + 6044, 6044, 6044, -1, 6045, 6045, 6045, -1, + 6046, 6046, 6046, -1, 6047, 6047, 6047, -1, + 6048, 6048, 6048, -1, 6049, 6049, 6049, -1, + 6050, 6050, 6050, -1, 6051, 6051, 6051, -1, + 6052, 6052, 6052, -1, 6053, 6053, 6053, -1, + 6054, 6054, 6054, -1, 6055, 6055, 6055, -1, + 6056, 6056, 6056, -1, 6057, 6057, 6057, -1, + 6058, 6058, 6058, -1, 6059, 6059, 6059, -1, + 6060, 6060, 6060, -1, 6061, 6061, 6061, -1, + 6062, 6062, 6062, -1, 6063, 6063, 6063, -1, + 6064, 6064, 6064, -1, 6065, 6065, 6065, -1, + 6066, 6066, 6066, -1, 6067, 6067, 6067, -1, + 6068, 6068, 6068, -1, 6069, 6069, 6069, -1, + 6070, 6070, 6070, -1, 6071, 6071, 6071, -1, + 6072, 6072, 6072, -1, 6073, 6073, 6073, -1, + 6074, 6074, 6074, -1, 6075, 6075, 6075, -1, + 6076, 6076, 6076, -1, 6077, 6077, 6077, -1, + 6078, 6078, 6078, -1, 6079, 6079, 6079, -1, + 6080, 6080, 6080, -1, 6081, 6081, 6081, -1, + 6082, 6082, 6082, -1, 6083, 6083, 6083, -1, + 6084, 6084, 6084, -1, 6085, 6085, 6085, -1, + 6086, 6086, 6086, -1, 6087, 6087, 6087, -1, + 6088, 6088, 6088, -1, 6089, 6089, 6089, -1, + 6090, 6090, 6090, -1, 6091, 6091, 6091, -1, + 6092, 6092, 6092, -1, 6093, 6093, 6093, -1, + 6094, 6094, 6094, -1, 6095, 6095, 6095, -1, + 6096, 6096, 6096, -1, 6097, 6097, 6097, -1, + 6098, 6098, 6098, -1, 6099, 6099, 6099, -1, + 6100, 6100, 6100, -1, 6101, 6101, 6101, -1, + 6102, 6102, 6102, -1, 6103, 6103, 6103, -1, + 6104, 6104, 6104, -1, 6105, 6105, 6105, -1, + 6106, 6106, 6106, -1, 6107, 6107, 6107, -1, + 6108, 6108, 6108, -1, 6109, 6109, 6109, -1, + 6110, 6110, 6110, -1, 6111, 6111, 6111, -1, + 6112, 6112, 6112, -1, 6113, 6113, 6113, -1, + 6114, 6114, 6114, -1, 6115, 6115, 6115, -1, + 6116, 6116, 6116, -1, 6117, 6117, 6117, -1, + 6118, 6118, 6118, -1, 6119, 6119, 6119, -1, + 6120, 6120, 6120, -1, 6121, 6121, 6121, -1, + 6122, 6122, 6122, -1, 6123, 6123, 6123, -1, + 6124, 6124, 6124, -1, 6125, 6125, 6125, -1, + 6126, 6126, 6126, -1, 6127, 6127, 6127, -1, + 6128, 6128, 6128, -1, 6129, 6129, 6129, -1, + 6130, 6130, 6130, -1, 6131, 6131, 6131, -1, + 6132, 6132, 6132, -1, 6133, 6133, 6133, -1, + 6134, 6134, 6134, -1, 6135, 6135, 6135, -1, + 6136, 6136, 6136, -1, 6137, 6137, 6137, -1, + 6138, 6138, 6138, -1, 6139, 6139, 6139, -1, + 6140, 6140, 6140, -1, 6141, 6141, 6141, -1, + 6142, 6142, 6142, -1, 6143, 6143, 6143, -1, + 6144, 6144, 6144, -1, 6145, 6145, 6145, -1, + 6146, 6146, 6146, -1, 6147, 6147, 6147, -1, + 6148, 6148, 6148, -1, 6149, 6149, 6149, -1, + 6150, 6150, 6150, -1, 6151, 6151, 6151, -1, + 6152, 6152, 6152, -1, 6153, 6153, 6153, -1, + 6154, 6154, 6154, -1, 6155, 6155, 6155, -1, + 6156, 6156, 6156, -1, 6157, 6157, 6157, -1, + 6158, 6158, 6158, -1, 6159, 6159, 6159, -1, + 6160, 6160, 6160, -1, 6161, 6161, 6161, -1, + 6162, 6162, 6162, -1, 6163, 6163, 6163, -1, + 6164, 6164, 6164, -1, 6165, 6165, 6165, -1, + 6166, 6166, 6166, -1, 6167, 6167, 6167, -1, + 6168, 6168, 6168, -1, 6169, 6169, 6169, -1, + 6170, 6170, 6170, -1, 6171, 6171, 6171, -1, + 6172, 6172, 6172, -1, 6173, 6173, 6173, -1, + 6174, 6174, 6174, -1, 6175, 6175, 6175, -1, + 6176, 6176, 6176, -1, 6177, 6177, 6177, -1, + 6178, 6178, 6178, -1, 6179, 6179, 6179, -1, + 6180, 6180, 6180, -1, 6181, 6181, 6181, -1, + 6182, 6182, 6182, -1, 6183, 6183, 6183, -1, + 6184, 6184, 6184, -1, 6185, 6185, 6185, -1, + 6186, 6186, 6186, -1, 6187, 6187, 6187, -1, + 6188, 6188, 6188, -1, 6189, 6189, 6189, -1, + 6190, 6190, 6190, -1, 6191, 6191, 6191, -1, + 6192, 6192, 6192, -1, 6193, 6193, 6193, -1, + 6194, 6194, 6194, -1, 6195, 6195, 6195, -1, + 6196, 6196, 6196, -1, 6197, 6197, 6197, -1, + 6198, 6198, 6198, -1, 6199, 6199, 6199, -1, + 6200, 6200, 6200, -1, 6201, 6201, 6201, -1, + 6202, 6202, 6202, -1, 6203, 6203, 6203, -1, + 6204, 6204, 6204, -1, 6205, 6205, 6205, -1, + 6206, 6206, 6206, -1, 6207, 6207, 6207, -1, + 6208, 6208, 6208, -1, 6209, 6209, 6209, -1, + 6210, 6210, 6210, -1, 6211, 6211, 6211, -1, + 6212, 6212, 6212, -1, 6213, 6213, 6213, -1, + 6214, 6214, 6214, -1, 6215, 6215, 6215, -1, + 6216, 6216, 6216, -1, 6217, 6217, 6217, -1, + 6218, 6218, 6218, -1, 6219, 6219, 6219, -1, + 6220, 6220, 6220, -1, 6221, 6221, 6221, -1, + 6222, 6222, 6222, -1, 6223, 6223, 6223, -1, + 6224, 6224, 6224, -1, 6225, 6225, 6225, -1, + 6226, 6226, 6226, -1, 6227, 6227, 6227, -1, + 6228, 6228, 6228, -1, 6229, 6229, 6229, -1, + 6230, 6230, 6230, -1, 6231, 6231, 6231, -1, + 6232, 6232, 6232, -1, 6233, 6233, 6233, -1, + 6234, 6234, 6234, -1, 6235, 6235, 6235, -1, + 6236, 6236, 6236, -1, 6237, 6237, 6237, -1, + 6238, 6238, 6238, -1, 6239, 6239, 6239, -1, + 6240, 6240, 6240, -1, 6241, 6241, 6241, -1, + 6242, 6242, 6242, -1, 6243, 6243, 6243, -1, + 6244, 6244, 6244, -1, 6245, 6245, 6245, -1, + 6246, 6246, 6246, -1, 6247, 6247, 6247, -1, + 6248, 6248, 6248, -1, 6249, 6249, 6249, -1, + 6250, 6250, 6250, -1, 6251, 6251, 6251, -1, + 6252, 6252, 6252, -1, 6253, 6253, 6253, -1, + 6254, 6254, 6254, -1, 6255, 6255, 6255, -1, + 6256, 6256, 6256, -1, 6257, 6257, 6257, -1, + 6258, 6258, 6258, -1, 6259, 6259, 6259, -1, + 6260, 6260, 6260, -1, 6261, 6261, 6261, -1, + 6262, 6262, 6262, -1, 6263, 6263, 6263, -1, + 6264, 6264, 6264, -1, 6265, 6265, 6265, -1, + 6266, 6266, 6266, -1, 6267, 6267, 6267, -1, + 6268, 6268, 6268, -1, 6269, 6269, 6269, -1, + 6270, 6270, 6270, -1, 6271, 6271, 6271, -1, + 6272, 6272, 6272, -1, 6273, 6273, 6273, -1, + 6274, 6274, 6274, -1, 6275, 6275, 6275, -1, + 6276, 6276, 6276, -1, 6277, 6277, 6277, -1, + 6278, 6278, 6278, -1, 6279, 6279, 6279, -1, + 6280, 6280, 6280, -1, 6281, 6281, 6281, -1, + 6282, 6282, 6282, -1, 6283, 6283, 6283, -1, + 6284, 6284, 6284, -1, 6285, 6285, 6285, -1, + 6286, 6286, 6286, -1, 6287, 6287, 6287, -1, + 6288, 6288, 6288, -1, 6289, 6289, 6289, -1, + 6290, 6290, 6290, -1, 6291, 6291, 6291, -1, + 6292, 6292, 6292, -1, 6293, 6293, 6293, -1, + 6294, 6294, 6294, -1, 6295, 6295, 6295, -1, + 6296, 6296, 6296, -1, 6297, 6297, 6297, -1, + 6298, 6298, 6298, -1, 6299, 6299, 6299, -1, + 6300, 6300, 6300, -1, 6301, 6301, 6301, -1, + 6302, 6302, 6302, -1, 6303, 6303, 6303, -1, + 6304, 6304, 6304, -1, 6305, 6305, 6305, -1, + 6306, 6306, 6306, -1, 6307, 6307, 6307, -1, + 6308, 6308, 6308, -1, 6309, 6309, 6309, -1, + 6310, 6310, 6310, -1, 6311, 6311, 6311, -1, + 6312, 6312, 6312, -1, 6313, 6313, 6313, -1, + 6314, 6314, 6314, -1, 6315, 6315, 6315, -1, + 6316, 6316, 6316, -1, 6317, 6317, 6317, -1, + 6318, 6318, 6318, -1, 6319, 6319, 6319, -1, + 6320, 6320, 6320, -1, 6321, 6321, 6321, -1, + 6322, 6322, 6322, -1, 6323, 6323, 6323, -1, + 6324, 6324, 6324, -1, 6325, 6325, 6325, -1, + 6326, 6326, 6326, -1, 6327, 6327, 6327, -1, + 6328, 6328, 6328, -1, 6329, 6329, 6329, -1, + 6330, 6330, 6330, -1, 6331, 6331, 6331, -1, + 6332, 6332, 6332, -1, 6333, 6333, 6333, -1, + 6334, 6334, 6334, -1, 6335, 6335, 6335, -1, + 6336, 6336, 6336, -1, 6337, 6337, 6337, -1, + 6338, 6338, 6338, -1, 6339, 6339, 6339, -1, + 6340, 6340, 6340, -1, 6341, 6341, 6341, -1, + 6342, 6342, 6342, -1, 6343, 6343, 6343, -1, + 6344, 6344, 6344, -1, 6345, 6345, 6345, -1, + 6346, 6346, 6346, -1, 6347, 6347, 6347, -1, + 6348, 6348, 6348, -1, 6349, 6349, 6349, -1, + 6350, 6350, 6350, -1, 6351, 6351, 6351, -1, + 6352, 6352, 6352, -1, 6353, 6353, 6353, -1, + 6354, 6354, 6354, -1, 6355, 6355, 6355, -1, + 6356, 6356, 6356, -1, 6357, 6357, 6357, -1, + 6358, 6358, 6358, -1, 6359, 6359, 6359, -1, + 6360, 6360, 6360, -1, 6361, 6361, 6361, -1, + 6362, 6362, 6362, -1, 6363, 6363, 6363, -1, + 6364, 6364, 6364, -1, 6365, 6365, 6365, -1, + 6366, 6366, 6366, -1, 6367, 6367, 6367, -1, + 6368, 6368, 6368, -1, 6369, 6369, 6369, -1, + 6370, 6370, 6370, -1, 6371, 6371, 6371, -1, + 6372, 6372, 6372, -1, 6373, 6373, 6373, -1, + 6374, 6374, 6374, -1, 6375, 6375, 6375, -1, + 6376, 6376, 6376, -1, 6377, 6377, 6377, -1, + 6378, 6378, 6378, -1, 6379, 6379, 6379, -1, + 6380, 6380, 6380, -1, 6381, 6381, 6381, -1, + 6382, 6382, 6382, -1, 6383, 6383, 6383, -1, + 6384, 6384, 6384, -1, 6385, 6385, 6385, -1, + 6386, 6386, 6386, -1, 6387, 6387, 6387, -1, + 6388, 6388, 6388, -1, 6389, 6389, 6389, -1, + 6390, 6390, 6390, -1, 6391, 6391, 6391, -1, + 6392, 6392, 6392, -1, 6393, 6393, 6393, -1, + 6394, 6394, 6394, -1, 6395, 6395, 6395, -1, + 6396, 6396, 6396, -1, 6397, 6397, 6397, -1, + 6398, 6398, 6398, -1, 6399, 6399, 6399, -1, + 6400, 6400, 6400, -1, 6401, 6401, 6401, -1, + 6402, 6402, 6402, -1, 6403, 6403, 6403, -1, + 6404, 6404, 6404, -1, 6405, 6405, 6405, -1, + 6406, 6406, 6406, -1, 6407, 6407, 6407, -1, + 6408, 6408, 6408, -1, 6409, 6409, 6409, -1, + 6410, 6410, 6410, -1, 6411, 6411, 6411, -1, + 6412, 6412, 6412, -1, 6413, 6413, 6413, -1, + 6414, 6414, 6414, -1, 6415, 6415, 6415, -1, + 6416, 6416, 6416, -1, 6417, 6417, 6417, -1, + 6418, 6418, 6418, -1, 6419, 6419, 6419, -1, + 6420, 6420, 6420, -1, 6421, 6421, 6421, -1, + 6422, 6422, 6422, -1, 6423, 6423, 6423, -1, + 6424, 6424, 6424, -1, 6425, 6425, 6425, -1, + 6426, 6426, 6426, -1, 6427, 6427, 6427, -1, + 6428, 6428, 6428, -1, 6429, 6429, 6429, -1, + 6430, 6430, 6430, -1, 6431, 6431, 6431, -1, + 6432, 6432, 6432, -1, 6433, 6433, 6433, -1, + 6434, 6434, 6434, -1, 6435, 6435, 6435, -1, + 6436, 6436, 6436, -1, 6437, 6437, 6437, -1, + 6438, 6438, 6438, -1, 6439, 6439, 6439, -1, + 6440, 6440, 6440, -1, 6441, 6441, 6441, -1, + 6442, 6442, 6442, -1, 6443, 6443, 6443, -1, + 6444, 6444, 6444, -1, 6445, 6445, 6445, -1, + 6446, 6446, 6446, -1, 6447, 6447, 6447, -1, + 6448, 6448, 6448, -1, 6449, 6449, 6449, -1, + 6450, 6450, 6450, -1, 6451, 6451, 6451, -1, + 6452, 6452, 6452, -1, 6453, 6453, 6453, -1, + 6454, 6454, 6454, -1, 6455, 6455, 6455, -1, + 6456, 6456, 6456, -1, 6457, 6457, 6457, -1, + 6458, 6458, 6458, -1, 6459, 6459, 6459, -1, + 6460, 6460, 6460, -1, 6461, 6461, 6461, -1, + 6462, 6462, 6462, -1, 6463, 6463, 6463, -1, + 6464, 6464, 6464, -1, 6465, 6465, 6465, -1, + 6466, 6466, 6466, -1, 6467, 6467, 6467, -1, + 6468, 6468, 6468, -1, 6469, 6469, 6469, -1, + 6470, 6470, 6470, -1, 6471, 6471, 6471, -1, + 6472, 6472, 6472, -1, 6473, 6473, 6473, -1, + 6474, 6474, 6474, -1, 6475, 6475, 6475, -1, + 6476, 6476, 6476, -1, 6477, 6477, 6477, -1, + 6478, 6478, 6478, -1, 6479, 6479, 6479, -1, + 6480, 6480, 6480, -1, 6481, 6481, 6481, -1, + 6482, 6482, 6482, -1, 6483, 6483, 6483, -1, + 6484, 6484, 6484, -1, 6485, 6485, 6485, -1, + 6486, 6486, 6486, -1, 6487, 6487, 6487, -1, + 6488, 6488, 6488, -1, 6489, 6489, 6489, -1, + 6490, 6490, 6490, -1, 6491, 6491, 6491, -1, + 6492, 6492, 6492, -1, 6493, 6493, 6493, -1, + 6494, 6494, 6494, -1, 6495, 6495, 6495, -1, + 6496, 6496, 6496, -1, 6497, 6497, 6497, -1, + 6498, 6498, 6498, -1, 6499, 6499, 6499, -1, + 6500, 6500, 6500, -1, 6501, 6501, 6501, -1, + 6502, 6502, 6502, -1, 6503, 6503, 6503, -1, + 6504, 6504, 6504, -1, 6505, 6505, 6505, -1, + 6506, 6506, 6506, -1, 6507, 6507, 6507, -1, + 6508, 6508, 6508, -1, 6509, 6509, 6509, -1, + 6510, 6510, 6510, -1, 6511, 6511, 6511, -1, + 6512, 6512, 6512, -1, 6513, 6513, 6513, -1, + 6514, 6514, 6514, -1, 6515, 6515, 6515, -1, + 6516, 6516, 6516, -1, 6517, 6517, 6517, -1, + 6518, 6518, 6518, -1, 6519, 6519, 6519, -1, + 6520, 6520, 6520, -1, 6521, 6521, 6521, -1, + 6522, 6522, 6522, -1, 6523, 6523, 6523, -1, + 6524, 6524, 6524, -1, 6525, 6525, 6525, -1, + 6526, 6526, 6526, -1, 6527, 6527, 6527, -1, + 6528, 6528, 6528, -1, 6529, 6529, 6529, -1, + 6530, 6530, 6530, -1, 6531, 6531, 6531, -1, + 6532, 6532, 6532, -1, 6533, 6533, 6533, -1, + 6534, 6534, 6534, -1, 6535, 6535, 6535, -1, + 6536, 6536, 6536, -1, 6537, 6537, 6537, -1, + 6538, 6538, 6538, -1, 6539, 6539, 6539, -1, + 6540, 6540, 6540, -1, 6541, 6541, 6541, -1, + 6542, 6542, 6542, -1, 6543, 6543, 6543, -1, + 6544, 6544, 6544, -1, 6545, 6545, 6545, -1, + 6546, 6546, 6546, -1, 6547, 6547, 6547, -1, + 6548, 6548, 6548, -1, 6549, 6549, 6549, -1, + 6550, 6550, 6550, -1, 6551, 6551, 6551, -1, + 6552, 6552, 6552, -1, 6553, 6553, 6553, -1, + 6554, 6554, 6554, -1, 6555, 6555, 6555, -1, + 6556, 6556, 6556, -1, 6557, 6557, 6557, -1, + 6558, 6558, 6558, -1, 6559, 6559, 6559, -1, + 6560, 6560, 6560, -1, 6561, 6561, 6561, -1, + 6562, 6562, 6562, -1, 6563, 6563, 6563, -1, + 6564, 6564, 6564, -1, 6565, 6565, 6565, -1, + 6566, 6566, 6566, -1, 6567, 6567, 6567, -1, + 6568, 6568, 6568, -1, 6569, 6569, 6569, -1, + 6570, 6570, 6570, -1, 6571, 6571, 6571, -1, + 6572, 6572, 6572, -1, 6573, 6573, 6573, -1, + 6574, 6574, 6574, -1, 6575, 6575, 6575, -1, + 6576, 6576, 6576, -1, 6577, 6577, 6577, -1, + 6578, 6578, 6578, -1, 6579, 6579, 6579, -1, + 6580, 6580, 6580, -1, 6581, 6581, 6581, -1, + 6582, 6582, 6582, -1, 6583, 6583, 6583, -1, + 6584, 6584, 6584, -1, 6585, 6585, 6585, -1, + 6586, 6586, 6586, -1, 6587, 6587, 6587, -1, + 6588, 6588, 6588, -1, 6589, 6589, 6589, -1, + 6590, 6590, 6590, -1, 6591, 6591, 6591, -1, + 6592, 6592, 6592, -1, 6593, 6593, 6593, -1, + 6594, 6594, 6594, -1, 6595, 6595, 6595, -1, + 6596, 6596, 6596, -1, 6597, 6597, 6597, -1, + 6598, 6598, 6598, -1, 6599, 6599, 6599, -1, + 6600, 6600, 6600, -1, 6601, 6601, 6601, -1, + 6602, 6602, 6602, -1, 6603, 6603, 6603, -1, + 6604, 6604, 6604, -1, 6605, 6605, 6605, -1, + 6606, 6606, 6606, -1, 6607, 6607, 6607, -1, + 6608, 6608, 6608, -1, 6609, 6609, 6609, -1, + 6610, 6610, 6610, -1, 6611, 6611, 6611, -1, + 6612, 6612, 6612, -1, 6613, 6613, 6613, -1, + 6614, 6614, 6614, -1, 6615, 6615, 6615, -1, + 6616, 6616, 6616, -1, 6617, 6617, 6617, -1, + 6618, 6618, 6618, -1, 6619, 6619, 6619, -1, + 6620, 6620, 6620, -1, 6621, 6621, 6621, -1, + 6622, 6622, 6622, -1, 6623, 6623, 6623, -1, + 6624, 6624, 6624, -1, 6625, 6625, 6625, -1, + 6626, 6626, 6626, -1, 6627, 6627, 6627, -1, + 6628, 6628, 6628, -1, 6629, 6629, 6629, -1, + 6630, 6630, 6630, -1, 6631, 6631, 6631, -1, + 6632, 6632, 6632, -1, 6633, 6633, 6633, -1, + 6634, 6634, 6634, -1, 6635, 6635, 6635, -1, + 6636, 6636, 6636, -1, 6637, 6637, 6637, -1, + 6638, 6638, 6638, -1, 6639, 6639, 6639, -1, + 6640, 6640, 6640, -1, 6641, 6641, 6641, -1, + 6642, 6642, 6642, -1, 6643, 6643, 6643, -1, + 6644, 6644, 6644, -1, 6645, 6645, 6645, -1, + 6646, 6646, 6646, -1, 6647, 6647, 6647, -1, + 6648, 6648, 6648, -1, 6649, 6649, 6649, -1, + 6650, 6650, 6650, -1, 6651, 6651, 6651, -1, + 6652, 6652, 6652, -1, 6653, 6653, 6653, -1, + 6654, 6654, 6654, -1, 6655, 6655, 6655, -1, + 6656, 6656, 6656, -1, 6657, 6657, 6657, -1, + 6658, 6658, 6658, -1, 6659, 6659, 6659, -1, + 6660, 6660, 6660, -1, 6661, 6661, 6661, -1, + 6662, 6662, 6662, -1, 6663, 6663, 6663, -1, + 6664, 6664, 6664, -1, 6665, 6665, 6665, -1, + 6666, 6666, 6666, -1, 6667, 6667, 6667, -1, + 6668, 6668, 6668, -1, 6669, 6669, 6669, -1, + 6670, 6670, 6670, -1, 6671, 6671, 6671, -1, + 6672, 6672, 6672, -1, 6673, 6673, 6673, -1, + 6674, 6674, 6674, -1, 6675, 6675, 6675, -1, + 6676, 6676, 6676, -1, 6677, 6677, 6677, -1, + 6678, 6678, 6678, -1, 6679, 6679, 6679, -1, + 6680, 6680, 6680, -1, 6681, 6681, 6681, -1, + 6682, 6682, 6682, -1, 6683, 6683, 6683, -1, + 6684, 6684, 6684, -1, 6685, 6685, 6685, -1, + 6686, 6686, 6686, -1, 6687, 6687, 6687, -1, + 6688, 6688, 6688, -1, 6689, 6689, 6689, -1, + 6690, 6690, 6690, -1, 6691, 6691, 6691, -1, + 6692, 6692, 6692, -1, 6693, 6693, 6693, -1, + 6694, 6694, 6694, -1, 6695, 6695, 6695, -1, + 6696, 6696, 6696, -1, 6697, 6697, 6697, -1, + 6698, 6698, 6698, -1, 6699, 6699, 6699, -1, + 6700, 6700, 6700, -1, 6701, 6701, 6701, -1, + 6702, 6702, 6702, -1, 6703, 6703, 6703, -1, + 6704, 6704, 6704, -1, 6705, 6705, 6705, -1, + 6706, 6706, 6706, -1, 6707, 6707, 6707, -1, + 6708, 6708, 6708, -1, 6709, 6709, 6709, -1, + 6710, 6710, 6710, -1, 6711, 6711, 6711, -1, + 6712, 6712, 6712, -1, 6713, 6713, 6713, -1, + 6714, 6714, 6714, -1, 6715, 6715, 6715, -1, + 6716, 6716, 6716, -1, 6717, 6717, 6717, -1, + 6718, 6718, 6718, -1, 6719, 6719, 6719, -1, + 6720, 6720, 6720, -1, 6721, 6721, 6721, -1, + 6722, 6722, 6722, -1, 6723, 6723, 6723, -1, + 6724, 6724, 6724, -1, 6725, 6725, 6725, -1, + 6726, 6726, 6726, -1, 6727, 6727, 6727, -1, + 6728, 6728, 6728, -1, 6729, 6729, 6729, -1, + 6730, 6730, 6730, -1, 6731, 6731, 6731, -1, + 6732, 6732, 6732, -1, 6733, 6733, 6733, -1, + 6734, 6734, 6734, -1, 6735, 6735, 6735, -1, + 6736, 6736, 6736, -1, 6737, 6737, 6737, -1, + 6738, 6738, 6738, -1, 6739, 6739, 6739, -1, + 6740, 6740, 6740, -1, 6741, 6741, 6741, -1, + 6742, 6742, 6742, -1, 6743, 6743, 6743, -1, + 6744, 6744, 6744, -1, 6745, 6745, 6745, -1, + 6746, 6746, 6746, -1, 6747, 6747, 6747, -1, + 6748, 6748, 6748, -1, 6749, 6749, 6749, -1, + 6750, 6750, 6750, -1, 6751, 6751, 6751, -1, + 6752, 6752, 6752, -1, 6753, 6753, 6753, -1, + 6754, 6754, 6754, -1, 6755, 6755, 6755, -1, + 6756, 6756, 6756, -1, 6757, 6757, 6757, -1, + 6758, 6758, 6758, -1, 6759, 6759, 6759, -1, + 6760, 6760, 6760, -1, 6761, 6761, 6761, -1, + 6762, 6762, 6762, -1, 6763, 6763, 6763, -1, + 6764, 6764, 6764, -1, 6765, 6765, 6765, -1, + 6766, 6766, 6766, -1, 6767, 6767, 6767, -1, + 6768, 6768, 6768, -1, 6769, 6769, 6769, -1, + 6770, 6770, 6770, -1, 6771, 6771, 6771, -1, + 6772, 6772, 6772, -1, 6773, 6773, 6773, -1, + 6774, 6774, 6774, -1, 6775, 6775, 6775, -1, + 6776, 6776, 6776, -1, 6777, 6777, 6777, -1, + 6778, 6778, 6778, -1, 6779, 6779, 6779, -1, + 6780, 6780, 6780, -1, 6781, 6781, 6781, -1, + 6782, 6782, 6782, -1, 6783, 6783, 6783, -1, + 6784, 6784, 6784, -1, 6785, 6785, 6785, -1, + 6786, 6786, 6786, -1, 6787, 6787, 6787, -1, + 6788, 6788, 6788, -1, 6789, 6789, 6789, -1, + 6790, 6790, 6790, -1, 6791, 6791, 6791, -1, + 6792, 6792, 6792, -1, 6793, 6793, 6793, -1, + 6794, 6794, 6794, -1, 6795, 6795, 6795, -1, + 6796, 6796, 6796, -1, 6797, 6797, 6797, -1, + 6798, 6798, 6798, -1, 6799, 6799, 6799, -1, + 6800, 6800, 6800, -1, 6801, 6801, 6801, -1, + 6802, 6802, 6802, -1, 6803, 6803, 6803, -1, + 6804, 6804, 6804, -1, 6805, 6805, 6805, -1, + 6806, 6806, 6806, -1, 6807, 6807, 6807, -1, + 6808, 6808, 6808, -1, 6809, 6809, 6809, -1, + 6810, 6810, 6810, -1, 6811, 6811, 6811, -1, + 6812, 6812, 6812, -1, 6813, 6813, 6813, -1, + 6814, 6814, 6814, -1, 6815, 6815, 6815, -1, + 6816, 6816, 6816, -1, 6817, 6817, 6817, -1, + 6818, 6818, 6818, -1, 6819, 6819, 6819, -1, + 6820, 6820, 6820, -1, 6821, 6821, 6821, -1, + 6822, 6822, 6822, -1, 6823, 6823, 6823, -1, + 6824, 6824, 6824, -1, 6825, 6825, 6825, -1, + 6826, 6826, 6826, -1, 6827, 6827, 6827, -1, + 6828, 6828, 6828, -1, 6829, 6829, 6829, -1, + 6830, 6830, 6830, -1, 6831, 6831, 6831, -1, + 6832, 6832, 6832, -1, 6833, 6833, 6833, -1, + 6834, 6834, 6834, -1, 6835, 6835, 6835, -1, + 6836, 6836, 6836, -1, 6837, 6837, 6837, -1, + 6838, 6838, 6838, -1, 6839, 6839, 6839, -1, + 6840, 6840, 6840, -1, 6841, 6841, 6841, -1, + 6842, 6842, 6842, -1, 6843, 6843, 6843, -1, + 6844, 6844, 6844, -1, 6845, 6845, 6845, -1, + 6846, 6846, 6846, -1, 6847, 6847, 6847, -1, + 6848, 6848, 6848, -1, 6849, 6849, 6849, -1, + 6850, 6850, 6850, -1, 6851, 6851, 6851, -1, + 6852, 6852, 6852, -1, 6853, 6853, 6853, -1, + 6854, 6854, 6854, -1, 6855, 6855, 6855, -1, + 6856, 6856, 6856, -1, 6857, 6857, 6857, -1, + 6858, 6858, 6858, -1, 6859, 6859, 6859, -1, + 6860, 6860, 6860, -1, 6861, 6861, 6861, -1, + 6862, 6862, 6862, -1, 6863, 6863, 6863, -1, + 6864, 6864, 6864, -1, 6865, 6865, 6865, -1, + 6866, 6866, 6866, -1, 6867, 6867, 6867, -1, + 6868, 6868, 6868, -1, 6869, 6869, 6869, -1, + 6870, 6870, 6870, -1, 6871, 6871, 6871, -1, + 6872, 6872, 6872, -1, 6873, 6873, 6873, -1, + 6874, 6874, 6874, -1, 6875, 6875, 6875, -1, + 6876, 6876, 6876, -1, 6877, 6877, 6877, -1, + 6878, 6878, 6878, -1, 6879, 6879, 6879, -1, + 6880, 6880, 6880, -1, 6881, 6881, 6881, -1, + 6882, 6882, 6882, -1, 6883, 6883, 6883, -1, + 6884, 6884, 6884, -1, 6885, 6885, 6885, -1, + 6886, 6886, 6886, -1, 6887, 6887, 6887, -1, + 6888, 6888, 6888, -1, 6889, 6889, 6889, -1, + 6890, 6890, 6890, -1, 6891, 6891, 6891, -1, + 6892, 6892, 6892, -1, 6893, 6893, 6893, -1, + 6894, 6894, 6894, -1, 6895, 6895, 6895, -1, + 6896, 6896, 6896, -1, 6897, 6897, 6897, -1, + 6898, 6898, 6898, -1, 6899, 6899, 6899, -1, + 6900, 6900, 6900, -1, 6901, 6901, 6901, -1, + 6902, 6902, 6902, -1, 6903, 6903, 6903, -1, + 6904, 6904, 6904, -1, 6905, 6905, 6905, -1, + 6906, 6906, 6906, -1, 6907, 6907, 6907, -1, + 6908, 6908, 6908, -1, 6909, 6909, 6909, -1, + 6910, 6910, 6910, -1, 6911, 6911, 6911, -1, + 6912, 6912, 6912, -1, 6913, 6913, 6913, -1, + 6914, 6914, 6914, -1, 6915, 6915, 6915, -1, + 6916, 6916, 6916, -1, 6917, 6917, 6917, -1, + 6918, 6918, 6918, -1, 6919, 6919, 6919, -1, + 6920, 6920, 6920, -1, 6921, 6921, 6921, -1, + 6922, 6922, 6922, -1, 6923, 6923, 6923, -1, + 6924, 6924, 6924, -1, 6925, 6925, 6925, -1, + 6926, 6926, 6926, -1, 6927, 6927, 6927, -1, + 6928, 6928, 6928, -1, 6929, 6929, 6929, -1, + 6930, 6930, 6930, -1, 6931, 6931, 6931, -1, + 6932, 6932, 6932, -1, 6933, 6933, 6933, -1, + 6934, 6934, 6934, -1, 6935, 6935, 6935, -1, + 6936, 6936, 6936, -1, 6937, 6937, 6937, -1, + 6938, 6938, 6938, -1, 6939, 6939, 6939, -1, + 6940, 6940, 6940, -1, 6941, 6941, 6941, -1, + 6942, 6942, 6942, -1, 6943, 6943, 6943, -1, + 6944, 6944, 6944, -1, 6945, 6945, 6945, -1, + 6946, 6946, 6946, -1, 6947, 6947, 6947, -1, + 6948, 6948, 6948, -1, 6949, 6949, 6949, -1, + 6950, 6950, 6950, -1, 6951, 6951, 6951, -1, + 6952, 6952, 6952, -1, 6953, 6953, 6953, -1, + 6954, 6954, 6954, -1, 6955, 6955, 6955, -1, + 6956, 6956, 6956, -1, 6957, 6957, 6957, -1, + 6958, 6958, 6958, -1, 6959, 6959, 6959, -1, + 6960, 6960, 6960, -1, 6961, 6961, 6961, -1, + 6962, 6962, 6962, -1, 6963, 6963, 6963, -1, + 6964, 6964, 6964, -1, 6965, 6965, 6965, -1, + 6966, 6966, 6966, -1, 6967, 6967, 6967, -1, + 6968, 6968, 6968, -1, 6969, 6969, 6969, -1, + 6970, 6970, 6970, -1, 6971, 6971, 6971, -1, + 6972, 6972, 6972, -1, 6973, 6973, 6973, -1, + 6974, 6974, 6974, -1, 6975, 6975, 6975, -1, + 6976, 6976, 6976, -1, 6977, 6977, 6977, -1, + 6978, 6978, 6978, -1, 6979, 6979, 6979, -1, + 6980, 6980, 6980, -1, 6981, 6981, 6981, -1, + 6982, 6982, 6982, -1, 6983, 6983, 6983, -1, + 6984, 6984, 6984, -1, 6985, 6985, 6985, -1, + 6986, 6986, 6986, -1, 6987, 6987, 6987, -1, + 6988, 6988, 6988, -1, 6989, 6989, 6989, -1, + 6990, 6990, 6990, -1, 6991, 6991, 6991, -1, + 6992, 6992, 6992, -1, 6993, 6993, 6993, -1, + 6994, 6994, 6994, -1, 6995, 6995, 6995, -1, + 6996, 6996, 6996, -1, 6997, 6997, 6997, -1, + 6998, 6998, 6998, -1, 6999, 6999, 6999, -1, + 7000, 7000, 7000, -1, 7001, 7001, 7001, -1, + 7002, 7002, 7002, -1, 7003, 7003, 7003, -1, + 7004, 7004, 7004, -1, 7005, 7005, 7005, -1, + 7006, 7006, 7006, -1, 7007, 7007, 7007, -1, + 7008, 7008, 7008, -1, 7009, 7009, 7009, -1, + 7010, 7010, 7010, -1, 7011, 7011, 7011, -1, + 7012, 7012, 7012, -1, 7013, 7013, 7013, -1, + 7014, 7014, 7014, -1, 7015, 7015, 7015, -1, + 7016, 7016, 7016, -1, 7017, 7017, 7017, -1, + 7018, 7018, 7018, -1, 7019, 7019, 7019, -1, + 7020, 7020, 7020, -1, 7021, 7021, 7021, -1, + 7022, 7022, 7022, -1, 7023, 7023, 7023, -1, + 7024, 7024, 7024, -1, 7025, 7025, 7025, -1, + 7026, 7026, 7026, -1, 7027, 7027, 7027, -1, + 7028, 7028, 7028, -1, 7029, 7029, 7029, -1, + 7030, 7030, 7030, -1, 7031, 7031, 7031, -1, + 7032, 7032, 7032, -1, 7033, 7033, 7033, -1, + 7034, 7034, 7034, -1, 7035, 7035, 7035, -1, + 7036, 7036, 7036, -1, 7037, 7037, 7037, -1, + 7038, 7038, 7038, -1, 7039, 7039, 7039, -1, + 7040, 7040, 7040, -1, 7041, 7041, 7041, -1, + 7042, 7042, 7042, -1, 7043, 7043, 7043, -1, + 7044, 7044, 7044, -1, 7045, 7045, 7045, -1, + 7046, 7046, 7046, -1, 7047, 7047, 7047, -1, + 7048, 7048, 7048, -1, 7049, 7049, 7049, -1, + 7050, 7050, 7050, -1, 7051, 7051, 7051, -1, + 7052, 7052, 7052, -1, 7053, 7053, 7053, -1, + 7054, 7054, 7054, -1, 7055, 7055, 7055, -1, + 7056, 7056, 7056, -1, 7057, 7057, 7057, -1, + 7058, 7058, 7058, -1, 7059, 7059, 7059, -1, + 7060, 7060, 7060, -1, 7061, 7061, 7061, -1, + 7062, 7062, 7062, -1, 7063, 7063, 7063, -1, + 7064, 7064, 7064, -1, 7065, 7065, 7065, -1, + 7066, 7066, 7066, -1, 7067, 7067, 7067, -1, + 7068, 7068, 7068, -1, 7069, 7069, 7069, -1, + 7070, 7070, 7070, -1, 7071, 7071, 7071, -1, + 7072, 7072, 7072, -1, 7073, 7073, 7073, -1, + 7074, 7074, 7074, -1, 7075, 7075, 7075, -1, + 7076, 7076, 7076, -1, 7077, 7077, 7077, -1, + 7078, 7078, 7078, -1, 7079, 7079, 7079, -1, + 7080, 7080, 7080, -1, 7081, 7081, 7081, -1, + 7082, 7082, 7082, -1, 7083, 7083, 7083, -1, + 7084, 7084, 7084, -1, 7085, 7085, 7085, -1, + 7086, 7086, 7086, -1, 7087, 7087, 7087, -1, + 7088, 7088, 7088, -1, 7089, 7089, 7089, -1, + 7090, 7090, 7090, -1, 7091, 7091, 7091, -1, + 7092, 7092, 7092, -1, 7093, 7093, 7093, -1, + 7094, 7094, 7094, -1, 7095, 7095, 7095, -1, + 7096, 7096, 7096, -1, 7097, 7097, 7097, -1, + 7098, 7098, 7098, -1, 7099, 7099, 7099, -1, + 7100, 7100, 7100, -1, 7101, 7101, 7101, -1, + 7102, 7102, 7102, -1, 7103, 7103, 7103, -1, + 7104, 7104, 7104, -1, 7105, 7105, 7105, -1, + 7106, 7106, 7106, -1, 7107, 7107, 7107, -1, + 7108, 7108, 7108, -1, 7109, 7109, 7109, -1, + 7110, 7110, 7110, -1, 7111, 7111, 7111, -1, + 7112, 7112, 7112, -1, 7113, 7113, 7113, -1, + 7114, 7114, 7114, -1, 7115, 7115, 7115, -1, + 7116, 7116, 7116, -1, 7117, 7117, 7117, -1, + 7118, 7118, 7118, -1, 7119, 7119, 7119, -1, + 7120, 7120, 7120, -1, 7121, 7121, 7121, -1, + 7122, 7122, 7122, -1, 7123, 7123, 7123, -1, + 7124, 7124, 7124, -1, 7125, 7125, 7125, -1, + 7126, 7126, 7126, -1, 7127, 7127, 7127, -1, + 7128, 7128, 7128, -1, 7129, 7129, 7129, -1, + 7130, 7130, 7130, -1, 7131, 7131, 7131, -1, + 7132, 7132, 7132, -1, 7133, 7133, 7133, -1, + 7134, 7134, 7134, -1, 7135, 7135, 7135, -1, + 7136, 7136, 7136, -1, 7137, 7137, 7137, -1, + 7138, 7138, 7138, -1, 7139, 7139, 7139, -1, + 7140, 7140, 7140, -1, 7141, 7141, 7141, -1, + 7142, 7142, 7142, -1, 7143, 7143, 7143, -1, + 7144, 7144, 7144, -1, 7145, 7145, 7145, -1, + 7146, 7146, 7146, -1, 7147, 7147, 7147, -1, + 7148, 7148, 7148, -1, 7149, 7149, 7149, -1, + 7150, 7150, 7150, -1, 7151, 7151, 7151, -1, + 7152, 7152, 7152, -1, 7153, 7153, 7153, -1, + 7154, 7154, 7154, -1, 7155, 7155, 7155, -1, + 7156, 7156, 7156, -1, 7157, 7157, 7157, -1, + 7158, 7158, 7158, -1, 7159, 7159, 7159, -1, + 7160, 7160, 7160, -1, 7161, 7161, 7161, -1, + 7162, 7162, 7162, -1, 7163, 7163, 7163, -1, + 7164, 7164, 7164, -1, 7165, 7165, 7165, -1, + 7166, 7166, 7166, -1, 7167, 7167, 7167, -1, + 7168, 7168, 7168, -1, 7169, 7169, 7169, -1, + 7170, 7170, 7170, -1, 7171, 7171, 7171, -1, + 7172, 7172, 7172, -1, 7173, 7173, 7173, -1, + 7174, 7174, 7174, -1, 7175, 7175, 7175, -1, + 7176, 7176, 7176, -1, 7177, 7177, 7177, -1, + 7178, 7178, 7178, -1, 7179, 7179, 7179, -1, + 7180, 7180, 7180, -1, 7181, 7181, 7181, -1, + 7182, 7182, 7182, -1, 7183, 7183, 7183, -1, + 7184, 7184, 7184, -1, 7185, 7185, 7185, -1, + 7186, 7186, 7186, -1, 7187, 7187, 7187, -1, + 7188, 7188, 7188, -1, 7189, 7189, 7189, -1, + 7190, 7190, 7190, -1, 7191, 7191, 7191, -1, + 7192, 7192, 7192, -1, 7193, 7193, 7193, -1, + 7194, 7194, 7194, -1, 7195, 7195, 7195, -1, + 7196, 7196, 7196, -1, 7197, 7197, 7197, -1, + 7198, 7198, 7198, -1, 7199, 7199, 7199, -1, + 7200, 7200, 7200, -1, 7201, 7201, 7201, -1, + 7202, 7202, 7202, -1, 7203, 7203, 7203, -1, + 7204, 7204, 7204, -1, 7205, 7205, 7205, -1, + 7206, 7206, 7206, -1, 7207, 7207, 7207, -1, + 7208, 7208, 7208, -1, 7209, 7209, 7209, -1, + 7210, 7210, 7210, -1, 7211, 7211, 7211, -1, + 7212, 7212, 7212, -1, 7213, 7213, 7213, -1, + 7214, 7214, 7214, -1, 7215, 7215, 7215, -1, + 7216, 7216, 7216, -1, 7217, 7217, 7217, -1, + 7218, 7218, 7218, -1, 7219, 7219, 7219, -1, + 7220, 7220, 7220, -1, 7221, 7221, 7221, -1, + 7222, 7222, 7222, -1, 7223, 7223, 7223, -1, + 7224, 7224, 7224, -1, 7225, 7225, 7225, -1, + 7226, 7226, 7226, -1, 7227, 7227, 7227, -1, + 7228, 7228, 7228, -1, 7229, 7229, 7229, -1, + 7230, 7230, 7230, -1, 7231, 7231, 7231, -1, + 7232, 7232, 7232, -1, 7233, 7233, 7233, -1, + 7234, 7234, 7234, -1, 7235, 7235, 7235, -1, + 7236, 7236, 7236, -1, 7237, 7237, 7237, -1, + 7238, 7238, 7238, -1, 7239, 7239, 7239, -1, + 7240, 7240, 7240, -1, 7241, 7241, 7241, -1, + 7242, 7242, 7242, -1, 7243, 7243, 7243, -1, + 7244, 7244, 7244, -1, 7245, 7245, 7245, -1, + 7246, 7246, 7246, -1, 7247, 7247, 7247, -1, + 7248, 7248, 7248, -1, 7249, 7249, 7249, -1, + 7250, 7250, 7250, -1, 7251, 7251, 7251, -1, + 7252, 7252, 7252, -1, 7253, 7253, 7253, -1, + 7254, 7254, 7254, -1, 7255, 7255, 7255, -1, + 7256, 7256, 7256, -1, 7257, 7257, 7257, -1, + 7258, 7258, 7258, -1, 7259, 7259, 7259, -1, + 7260, 7260, 7260, -1, 7261, 7261, 7261, -1, + 7262, 7262, 7262, -1, 7263, 7263, 7263, -1, + 7264, 7264, 7264, -1, 7265, 7265, 7265, -1, + 7266, 7266, 7266, -1, 7267, 7267, 7267, -1, + 7268, 7268, 7268, -1, 7269, 7269, 7269, -1, + 7270, 7270, 7270, -1, 7271, 7271, 7271, -1, + 7272, 7272, 7272, -1, 7273, 7273, 7273, -1, + 7274, 7274, 7274, -1, 7275, 7275, 7275, -1, + 7276, 7276, 7276, -1, 7277, 7277, 7277, -1, + 7278, 7278, 7278, -1, 7279, 7279, 7279, -1, + 7280, 7280, 7280, -1, 7281, 7281, 7281, -1, + 7282, 7282, 7282, -1, 7283, 7283, 7283, -1, + 7284, 7284, 7284, -1, 7285, 7285, 7285, -1, + 7286, 7286, 7286, -1, 7287, 7287, 7287, -1, + 7288, 7288, 7288, -1, 7289, 7289, 7289, -1, + 7290, 7290, 7290, -1, 7291, 7291, 7291, -1, + 7292, 7292, 7292, -1, 7293, 7293, 7293, -1, + 7294, 7294, 7294, -1, 7295, 7295, 7295, -1, + 7296, 7296, 7296, -1, 7297, 7297, 7297, -1, + 7298, 7298, 7298, -1, 7299, 7299, 7299, -1, + 7300, 7300, 7300, -1, 7301, 7301, 7301, -1, + 7302, 7302, 7302, -1, 7303, 7303, 7303, -1, + 7304, 7304, 7304, -1, 7305, 7305, 7305, -1, + 7306, 7306, 7306, -1, 7307, 7307, 7307, -1, + 7308, 7308, 7308, -1, 7309, 7309, 7309, -1, + 7310, 7310, 7310, -1, 7311, 7311, 7311, -1, + 7312, 7312, 7312, -1, 7313, 7313, 7313, -1, + 7314, 7314, 7314, -1, 7315, 7315, 7315, -1, + 7316, 7316, 7316, -1, 7317, 7317, 7317, -1, + 7318, 7318, 7318, -1, 7319, 7319, 7319, -1, + 7320, 7320, 7320, -1, 7321, 7321, 7321, -1, + 7322, 7322, 7322, -1, 7323, 7323, 7323, -1, + 7324, 7324, 7324, -1, 7325, 7325, 7325, -1, + 7326, 7326, 7326, -1, 7327, 7327, 7327, -1, + 7328, 7328, 7328, -1, 7329, 7329, 7329, -1, + 7330, 7330, 7330, -1, 7331, 7331, 7331, -1, + 7332, 7332, 7332, -1, 7333, 7333, 7333, -1, + 7334, 7334, 7334, -1, 7335, 7335, 7335, -1, + 7336, 7336, 7336, -1, 7337, 7337, 7337, -1, + 7338, 7338, 7338, -1, 7339, 7339, 7339, -1, + 7340, 7340, 7340, -1, 7341, 7341, 7341, -1, + 7342, 7342, 7342, -1, 7343, 7343, 7343, -1, + 7344, 7344, 7344, -1, 7345, 7345, 7345, -1, + 7346, 7346, 7346, -1, 7347, 7347, 7347, -1, + 7348, 7348, 7348, -1, 7349, 7349, 7349, -1, + 7350, 7350, 7350, -1, 7351, 7351, 7351, -1, + 7352, 7352, 7352, -1, 7353, 7353, 7353, -1, + 7354, 7354, 7354, -1, 7355, 7355, 7355, -1, + 7356, 7356, 7356, -1, 7357, 7357, 7357, -1, + 7358, 7358, 7358, -1, 7359, 7359, 7359, -1, + 7360, 7360, 7360, -1, 7361, 7361, 7361, -1, + 7362, 7362, 7362, -1, 7363, 7363, 7363, -1, + 7364, 7364, 7364, -1, 7365, 7365, 7365, -1, + 7366, 7366, 7366, -1, 7367, 7367, 7367, -1, + 7368, 7368, 7368, -1, 7369, 7369, 7369, -1, + 7370, 7370, 7370, -1, 7371, 7371, 7371, -1, + 7372, 7372, 7372, -1, 7373, 7373, 7373, -1, + 7374, 7374, 7374, -1, 7375, 7375, 7375, -1, + 7376, 7376, 7376, -1, 7377, 7377, 7377, -1, + 7378, 7378, 7378, -1, 7379, 7379, 7379, -1, + 7380, 7380, 7380, -1, 7381, 7381, 7381, -1, + 7382, 7382, 7382, -1, 7383, 7383, 7383, -1, + 7384, 7384, 7384, -1, 7385, 7385, 7385, -1, + 7386, 7386, 7386, -1, 7387, 7387, 7387, -1, + 7388, 7388, 7388, -1, 7389, 7389, 7389, -1, + 7390, 7390, 7390, -1, 7391, 7391, 7391, -1, + 7392, 7392, 7392, -1, 7393, 7393, 7393, -1, + 7394, 7394, 7394, -1, 7395, 7395, 7395, -1, + 7396, 7396, 7396, -1, 7397, 7397, 7397, -1, + 7398, 7398, 7398, -1, 7399, 7399, 7399, -1, + 7400, 7400, 7400, -1, 7401, 7401, 7401, -1, + 7402, 7402, 7402, -1, 7403, 7403, 7403, -1, + 7404, 7404, 7404, -1, 7405, 7405, 7405, -1, + 7406, 7406, 7406, -1, 7407, 7407, 7407, -1, + 7408, 7408, 7408, -1, 7409, 7409, 7409, -1, + 7410, 7410, 7410, -1, 7411, 7411, 7411, -1, + 7412, 7412, 7412, -1, 7413, 7413, 7413, -1, + 7414, 7414, 7414, -1, 7415, 7415, 7415, -1, + 7416, 7416, 7416, -1, 7417, 7417, 7417, -1, + 7418, 7418, 7418, -1, 7419, 7419, 7419, -1, + 7420, 7420, 7420, -1, 7421, 7421, 7421, -1, + 7422, 7422, 7422, -1, 7423, 7423, 7423, -1, + 7424, 7424, 7424, -1, 7425, 7425, 7425, -1, + 7426, 7426, 7426, -1, 7427, 7427, 7427, -1, + 7428, 7428, 7428, -1, 7429, 7429, 7429, -1, + 7430, 7430, 7430, -1, 7431, 7431, 7431, -1, + 7432, 7432, 7432, -1, 7433, 7433, 7433, -1, + 7434, 7434, 7434, -1, 7435, 7435, 7435, -1, + 7436, 7436, 7436, -1, 7437, 7437, 7437, -1, + 7438, 7438, 7438, -1, 7439, 7439, 7439, -1, + 7440, 7440, 7440, -1, 7441, 7441, 7441, -1, + 7442, 7442, 7442, -1, 7443, 7443, 7443, -1, + 7444, 7444, 7444, -1, 7445, 7445, 7445, -1, + 7446, 7446, 7446, -1, 7447, 7447, 7447, -1, + 7448, 7448, 7448, -1, 7449, 7449, 7449, -1, + 7450, 7450, 7450, -1, 7451, 7451, 7451, -1, + 7452, 7452, 7452, -1, 7453, 7453, 7453, -1, + 7454, 7454, 7454, -1, 7455, 7455, 7455, -1, + 7456, 7456, 7456, -1, 7457, 7457, 7457, -1, + 7458, 7458, 7458, -1, 7459, 7459, 7459, -1, + 7460, 7460, 7460, -1, 7461, 7461, 7461, -1, + 7462, 7462, 7462, -1, 7463, 7463, 7463, -1, + 7464, 7464, 7464, -1, 7465, 7465, 7465, -1, + 7466, 7466, 7466, -1, 7467, 7467, 7467, -1, + 7468, 7468, 7468, -1, 7469, 7469, 7469, -1, + 7470, 7470, 7470, -1, 7471, 7471, 7471, -1, + 7472, 7472, 7472, -1, 7473, 7473, 7473, -1, + 7474, 7474, 7474, -1, 7475, 7475, 7475, -1, + 7476, 7476, 7476, -1, 7477, 7477, 7477, -1, + 7478, 7478, 7478, -1, 7479, 7479, 7479, -1, + 7480, 7480, 7480, -1, 7481, 7481, 7481, -1, + 7482, 7482, 7482, -1, 7483, 7483, 7483, -1, + 7484, 7484, 7484, -1, 7485, 7485, 7485, -1, + 7486, 7486, 7486, -1, 7487, 7487, 7487, -1, + 7488, 7488, 7488, -1, 7489, 7489, 7489, -1, + 7490, 7490, 7490, -1, 7491, 7491, 7491, -1, + 7492, 7492, 7492, -1, 7493, 7493, 7493, -1, + 7494, 7494, 7494, -1, 7495, 7495, 7495, -1, + 7496, 7496, 7496, -1, 7497, 7497, 7497, -1, + 7498, 7498, 7498, -1, 7499, 7499, 7499, -1, + 7500, 7500, 7500, -1, 7501, 7501, 7501, -1, + 7502, 7502, 7502, -1, 7503, 7503, 7503, -1, + 7504, 7504, 7504, -1, 7505, 7505, 7505, -1, + 7506, 7506, 7506, -1, 7507, 7507, 7507, -1, + 7508, 7508, 7508, -1, 7509, 7509, 7509, -1, + 7510, 7510, 7510, -1, 7511, 7511, 7511, -1, + 7512, 7512, 7512, -1, 7513, 7513, 7513, -1, + 7514, 7514, 7514, -1, 7515, 7515, 7515, -1, + 7516, 7516, 7516, -1, 7517, 7517, 7517, -1, + 7518, 7518, 7518, -1, 7519, 7519, 7519, -1, + 7520, 7520, 7520, -1, 7521, 7521, 7521, -1, + 7522, 7522, 7522, -1, 7523, 7523, 7523, -1, + 7524, 7524, 7524, -1, 7525, 7525, 7525, -1, + 7526, 7526, 7526, -1, 7527, 7527, 7527, -1, + 7528, 7528, 7528, -1, 7529, 7529, 7529, -1, + 7530, 7530, 7530, -1, 7531, 7531, 7531, -1, + 7532, 7532, 7532, -1, 7533, 7533, 7533, -1, + 7534, 7534, 7534, -1, 7535, 7535, 7535, -1, + 7536, 7536, 7536, -1, 7537, 7537, 7537, -1, + 7538, 7538, 7538, -1, 7539, 7539, 7539, -1, + 7540, 7540, 7540, -1, 7541, 7541, 7541, -1, + 7542, 7542, 7542, -1, 7543, 7543, 7543, -1, + 7544, 7544, 7544, -1, 7545, 7545, 7545, -1, + 7546, 7546, 7546, -1, 7547, 7547, 7547, -1, + 7548, 7548, 7548, -1, 7549, 7549, 7549, -1, + 7550, 7550, 7550, -1, 7551, 7551, 7551, -1, + 7552, 7552, 7552, -1, 7553, 7553, 7553, -1, + 7554, 7554, 7554, -1, 7555, 7555, 7555, -1, + 7556, 7556, 7556, -1, 7557, 7557, 7557, -1, + 7558, 7558, 7558, -1, 7559, 7559, 7559, -1, + 7560, 7560, 7560, -1, 7561, 7561, 7561, -1, + 7562, 7562, 7562, -1, 7563, 7563, 7563, -1, + 7564, 7564, 7564, -1, 7565, 7565, 7565, -1, + 7566, 7566, 7566, -1, 7567, 7567, 7567, -1, + 7568, 7568, 7568, -1, 7569, 7569, 7569, -1, + 7570, 7570, 7570, -1, 7571, 7571, 7571, -1, + 7572, 7572, 7572, -1, 7573, 7573, 7573, -1, + 7574, 7574, 7574, -1, 7575, 7575, 7575, -1, + 7576, 7576, 7576, -1, 7577, 7577, 7577, -1, + 7578, 7578, 7578, -1, 7579, 7579, 7579, -1, + 7580, 7580, 7580, -1, 7581, 7581, 7581, -1, + 7582, 7582, 7582, -1, 7583, 7583, 7583, -1, + 7584, 7584, 7584, -1, 7585, 7585, 7585, -1, + 7586, 7586, 7586, -1, 7587, 7587, 7587, -1, + 7588, 7588, 7588, -1, 7589, 7589, 7589, -1, + 7590, 7590, 7590, -1, 7591, 7591, 7591, -1, + 7592, 7592, 7592, -1, 7593, 7593, 7593, -1, + 7594, 7594, 7594, -1, 7595, 7595, 7595, -1, + 7596, 7596, 7596, -1, 7597, 7597, 7597, -1, + 7598, 7598, 7598, -1, 7599, 7599, 7599, -1, + 7600, 7600, 7600, -1, 7601, 7601, 7601, -1, + 7602, 7602, 7602, -1, 7603, 7603, 7603, -1, + 7604, 7604, 7604, -1, 7605, 7605, 7605, -1, + 7606, 7606, 7606, -1, 7607, 7607, 7607, -1, + 7608, 7608, 7608, -1, 7609, 7609, 7609, -1, + 7610, 7610, 7610, -1, 7611, 7611, 7611, -1, + 7612, 7612, 7612, -1, 7613, 7613, 7613, -1, + 7614, 7614, 7614, -1, 7615, 7615, 7615, -1, + 7616, 7616, 7616, -1, 7617, 7617, 7617, -1, + 7618, 7618, 7618, -1, 7619, 7619, 7619, -1, + 7620, 7620, 7620, -1, 7621, 7621, 7621, -1, + 7622, 7622, 7622, -1, 7623, 7623, 7623, -1, + 7624, 7624, 7624, -1, 7625, 7625, 7625, -1, + 7626, 7626, 7626, -1, 7627, 7627, 7627, -1, + 7628, 7628, 7628, -1, 7629, 7629, 7629, -1, + 7630, 7630, 7630, -1, 7631, 7631, 7631, -1, + 7632, 7632, 7632, -1, 7633, 7633, 7633, -1, + 7634, 7634, 7634, -1, 7635, 7635, 7635, -1, + 7636, 7636, 7636, -1, 7637, 7637, 7637, -1, + 7638, 7638, 7638, -1, 7639, 7639, 7639, -1, + 7640, 7640, 7640, -1, 7641, 7641, 7641, -1, + 7642, 7642, 7642, -1, 7643, 7643, 7643, -1, + 7644, 7644, 7644, -1, 7645, 7645, 7645, -1, + 7646, 7646, 7646, -1, 7647, 7647, 7647, -1, + 7648, 7648, 7648, -1, 7649, 7649, 7649, -1, + 7650, 7650, 7650, -1, 7651, 7651, 7651, -1, + 7652, 7652, 7652, -1, 7653, 7653, 7653, -1, + 7654, 7654, 7654, -1, 7655, 7655, 7655, -1, + 7656, 7656, 7656, -1, 7657, 7657, 7657, -1, + 7658, 7658, 7658, -1, 7659, 7659, 7659, -1, + 7660, 7660, 7660, -1, 7661, 7661, 7661, -1, + 7662, 7662, 7662, -1, 7663, 7663, 7663, -1, + 7664, 7664, 7664, -1, 7665, 7665, 7665, -1, + 7666, 7666, 7666, -1, 7667, 7667, 7667, -1, + 7668, 7668, 7668, -1, 7669, 7669, 7669, -1, + 7670, 7670, 7670, -1, 7671, 7671, 7671, -1, + 7672, 7672, 7672, -1, 7673, 7673, 7673, -1, + 7674, 7674, 7674, -1, 7675, 7675, 7675, -1, + 7676, 7676, 7676, -1, 7677, 7677, 7677, -1, + 7678, 7678, 7678, -1, 7679, 7679, 7679, -1, + 7680, 7680, 7680, -1, 7681, 7681, 7681, -1, + 7682, 7682, 7682, -1, 7683, 7683, 7683, -1, + 7684, 7684, 7684, -1, 7685, 7685, 7685, -1, + 7686, 7686, 7686, -1, 7687, 7687, 7687, -1, + 7688, 7688, 7688, -1, 7689, 7689, 7689, -1, + 7690, 7690, 7690, -1, 7691, 7691, 7691, -1, + 7692, 7692, 7692, -1, 7693, 7693, 7693, -1, + 7694, 7694, 7694, -1, 7695, 7695, 7695, -1, + 7696, 7696, 7696, -1, 7697, 7697, 7697, -1, + 7698, 7698, 7698, -1, 7699, 7699, 7699, -1, + 7700, 7700, 7700, -1, 7701, 7701, 7701, -1, + 7702, 7702, 7702, -1, 7703, 7703, 7703, -1, + 7704, 7704, 7704, -1, 7705, 7705, 7705, -1, + 7706, 7706, 7706, -1, 7707, 7707, 7707, -1, + 7708, 7708, 7708, -1, 7709, 7709, 7709, -1, + 7710, 7710, 7710, -1, 7711, 7711, 7711, -1, + 7712, 7712, 7712, -1, 7713, 7713, 7713, -1, + 7714, 7714, 7714, -1, 7715, 7715, 7715, -1, + 7716, 7716, 7716, -1, 7717, 7717, 7717, -1, + 7718, 7718, 7718, -1, 7719, 7719, 7719, -1, + 7720, 7720, 7720, -1, 7721, 7721, 7721, -1, + 7722, 7722, 7722, -1, 7723, 7723, 7723, -1, + 7724, 7724, 7724, -1, 7725, 7725, 7725, -1, + 7726, 7726, 7726, -1, 7727, 7727, 7727, -1, + 7728, 7728, 7728, -1, 7729, 7729, 7729, -1, + 7730, 7730, 7730, -1, 7731, 7731, 7731, -1, + 7732, 7732, 7732, -1, 7733, 7733, 7733, -1, + 7734, 7734, 7734, -1, 7735, 7735, 7735, -1, + 7736, 7736, 7736, -1, 7737, 7737, 7737, -1, + 7738, 7738, 7738, -1, 7739, 7739, 7739, -1, + 7740, 7740, 7740, -1, 7741, 7741, 7741, -1, + 7742, 7742, 7742, -1, 7743, 7743, 7743, -1, + 7744, 7744, 7744, -1, 7745, 7745, 7745, -1, + 7746, 7746, 7746, -1, 7747, 7747, 7747, -1, + 7748, 7748, 7748, -1, 7749, 7749, 7749, -1, + 7750, 7750, 7750, -1, 7751, 7751, 7751, -1, + 7752, 7752, 7752, -1, 7753, 7753, 7753, -1, + 7754, 7754, 7754, -1, 7755, 7755, 7755, -1, + 7756, 7756, 7756, -1, 7757, 7757, 7757, -1, + 7758, 7758, 7758, -1, 7759, 7759, 7759, -1, + 7760, 7760, 7760, -1, 7761, 7761, 7761, -1, + 7762, 7762, 7762, -1, 7763, 7763, 7763, -1, + 7764, 7764, 7764, -1, 7765, 7765, 7765, -1, + 7766, 7766, 7766, -1, 7767, 7767, 7767, -1, + 7768, 7768, 7768, -1, 7769, 7769, 7769, -1, + 7770, 7770, 7770, -1, 7771, 7771, 7771, -1, + 7772, 7772, 7772, -1, 7773, 7773, 7773, -1, + 7774, 7774, 7774, -1, 7775, 7775, 7775, -1, + 7776, 7776, 7776, -1, 7777, 7777, 7777, -1, + 7778, 7778, 7778, -1, 7779, 7779, 7779, -1, + 7780, 7780, 7780, -1, 7781, 7781, 7781, -1, + 7782, 7782, 7782, -1, 7783, 7783, 7783, -1, + 7784, 7784, 7784, -1, 7785, 7785, 7785, -1, + 7786, 7786, 7786, -1, 7787, 7787, 7787, -1, + 7788, 7788, 7788, -1, 7789, 7789, 7789, -1, + 7790, 7790, 7790, -1, 7791, 7791, 7791, -1, + 7792, 7792, 7792, -1, 7793, 7793, 7793, -1, + 7794, 7794, 7794, -1, 7795, 7795, 7795, -1, + 7796, 7796, 7796, -1, 7797, 7797, 7797, -1, + 7798, 7798, 7798, -1, 7799, 7799, 7799, -1, + 7800, 7800, 7800, -1, 7801, 7801, 7801, -1, + 7802, 7802, 7802, -1, 7803, 7803, 7803, -1, + 7804, 7804, 7804, -1, 7805, 7805, 7805, -1, + 7806, 7806, 7806, -1, 7807, 7807, 7807, -1, + 7808, 7808, 7808, -1, 7809, 7809, 7809, -1, + 7810, 7810, 7810, -1, 7811, 7811, 7811, -1, + 7812, 7812, 7812, -1, 7813, 7813, 7813, -1, + 7814, 7814, 7814, -1, 7815, 7815, 7815, -1, + 7816, 7816, 7816, -1, 7817, 7817, 7817, -1, + 7818, 7818, 7818, -1, 7819, 7819, 7819, -1, + 7820, 7820, 7820, -1, 7821, 7821, 7821, -1, + 7822, 7822, 7822, -1, 7823, 7823, 7823, -1, + 7824, 7824, 7824, -1, 7825, 7825, 7825, -1, + 7826, 7826, 7826, -1, 7827, 7827, 7827, -1, + 7828, 7828, 7828, -1, 7829, 7829, 7829, -1, + 7830, 7830, 7830, -1, 7831, 7831, 7831, -1, + 7832, 7832, 7832, -1, 7833, 7833, 7833, -1, + 7834, 7834, 7834, -1, 7835, 7835, 7835, -1, + 7836, 7836, 7836, -1, 7837, 7837, 7837, -1, + 7838, 7838, 7838, -1, 7839, 7839, 7839, -1, + 7840, 7840, 7840, -1, 7841, 7841, 7841, -1, + 7842, 7842, 7842, -1, 7843, 7843, 7843, -1, + 7844, 7844, 7844, -1, 7845, 7845, 7845, -1, + 7846, 7846, 7846, -1, 7847, 7847, 7847, -1, + 7848, 7848, 7848, -1, 7849, 7849, 7849, -1, + 7850, 7850, 7850, -1, 7851, 7851, 7851, -1, + 7852, 7852, 7852, -1, 7853, 7853, 7853, -1, + 7854, 7854, 7854, -1, 7855, 7855, 7855, -1, + 7856, 7856, 7856, -1, 7857, 7857, 7857, -1, + 7858, 7858, 7858, -1, 7859, 7859, 7859, -1, + 7860, 7860, 7860, -1, 7861, 7861, 7861, -1, + 7862, 7862, 7862, -1, 7863, 7863, 7863, -1, + 7864, 7864, 7864, -1, 7865, 7865, 7865, -1, + 7866, 7866, 7866, -1, 7867, 7867, 7867, -1, + 7868, 7868, 7868, -1, 7869, 7869, 7869, -1, + 7870, 7870, 7870, -1, 7871, 7871, 7871, -1, + 7872, 7872, 7872, -1, 7873, 7873, 7873, -1, + 7874, 7874, 7874, -1, 7875, 7875, 7875, -1, + 7876, 7876, 7876, -1, 7877, 7877, 7877, -1, + 7878, 7878, 7878, -1, 7879, 7879, 7879, -1, + 7880, 7880, 7880, -1, 7881, 7881, 7881, -1, + 7882, 7882, 7882, -1, 7883, 7883, 7883, -1, + 7884, 7884, 7884, -1, 7885, 7885, 7885, -1, + 7886, 7886, 7886, -1, 7887, 7887, 7887, -1, + 7888, 7888, 7888, -1, 7889, 7889, 7889, -1, + 7890, 7890, 7890, -1, 7891, 7891, 7891, -1, + 7892, 7892, 7892, -1, 7893, 7893, 7893, -1, + 7894, 7894, 7894, -1, 7895, 7895, 7895, -1, + 7896, 7896, 7896, -1, 7897, 7897, 7897, -1, + 7898, 7898, 7898, -1, 7899, 7899, 7899, -1, + 7900, 7900, 7900, -1, 7901, 7901, 7901, -1, + 7902, 7902, 7902, -1, 7903, 7903, 7903, -1, + 7904, 7904, 7904, -1, 7905, 7905, 7905, -1, + 7906, 7906, 7906, -1, 7907, 7907, 7907, -1, + 7908, 7908, 7908, -1, 7909, 7909, 7909, -1, + 7910, 7910, 7910, -1, 7911, 7911, 7911, -1, + 7912, 7912, 7912, -1, 7913, 7913, 7913, -1, + 7914, 7914, 7914, -1, 7915, 7915, 7915, -1, + 7916, 7916, 7916, -1, 7917, 7917, 7917, -1, + 7918, 7918, 7918, -1, 7919, 7919, 7919, -1, + 7920, 7920, 7920, -1, 7921, 7921, 7921, -1, + 7922, 7922, 7922, -1, 7923, 7923, 7923, -1, + 7924, 7924, 7924, -1, 7925, 7925, 7925, -1, + 7926, 7926, 7926, -1, 7927, 7927, 7927, -1, + 7928, 7928, 7928, -1, 7929, 7929, 7929, -1, + 7930, 7930, 7930, -1, 7931, 7931, 7931, -1, + 7932, 7932, 7932, -1, 7933, 7933, 7933, -1, + 7934, 7934, 7934, -1, 7935, 7935, 7935, -1, + 7936, 7936, 7936, -1, 7937, 7937, 7937, -1, + 7938, 7938, 7938, -1, 7939, 7939, 7939, -1, + 7940, 7940, 7940, -1, 7941, 7941, 7941, -1, + 7942, 7942, 7942, -1, 7943, 7943, 7943, -1, + 7944, 7944, 7944, -1, 7945, 7945, 7945, -1, + 7946, 7946, 7946, -1, 7947, 7947, 7947, -1, + 7948, 7948, 7948, -1, 7949, 7949, 7949, -1, + 7950, 7950, 7950, -1, 7951, 7951, 7951, -1, + 7952, 7952, 7952, -1, 7953, 7953, 7953, -1, + 7954, 7954, 7954, -1, 7955, 7955, 7955, -1, + 7956, 7956, 7956, -1, 7957, 7957, 7957, -1, + 7958, 7958, 7958, -1, 7959, 7959, 7959, -1, + 7960, 7960, 7960, -1, 7961, 7961, 7961, -1, + 7962, 7962, 7962, -1, 7963, 7963, 7963, -1, + 7964, 7964, 7964, -1, 7965, 7965, 7965, -1, + 7966, 7966, 7966, -1, 7967, 7967, 7967, -1, + 7968, 7968, 7968, -1, 7969, 7969, 7969, -1, + 7970, 7970, 7970, -1, 7971, 7971, 7971, -1, + 7972, 7972, 7972, -1, 7973, 7973, 7973, -1, + 7974, 7974, 7974, -1, 7975, 7975, 7975, -1, + 7976, 7976, 7976, -1, 7977, 7977, 7977, -1, + 7978, 7978, 7978, -1, 7979, 7979, 7979, -1, + 7980, 7980, 7980, -1, 7981, 7981, 7981, -1, + 7982, 7982, 7982, -1, 7983, 7983, 7983, -1, + 7984, 7984, 7984, -1, 7985, 7985, 7985, -1, + 7986, 7986, 7986, -1, 7987, 7987, 7987, -1, + 7988, 7988, 7988, -1, 7989, 7989, 7989, -1, + 7990, 7990, 7990, -1, 7991, 7991, 7991, -1, + 7992, 7992, 7992, -1, 7993, 7993, 7993, -1, + 7994, 7994, 7994, -1, 7995, 7995, 7995, -1, + 7996, 7996, 7996, -1, 7997, 7997, 7997, -1, + 7998, 7998, 7998, -1, 7999, 7999, 7999, -1, + 8000, 8000, 8000, -1, 8001, 8001, 8001, -1, + 8002, 8002, 8002, -1, 8003, 8003, 8003, -1, + 8004, 8004, 8004, -1, 8005, 8005, 8005, -1, + 8006, 8006, 8006, -1, 8007, 8007, 8007, -1, + 8008, 8008, 8008, -1, 8009, 8009, 8009, -1, + 8010, 8010, 8010, -1, 8011, 8011, 8011, -1, + 8012, 8012, 8012, -1, 8013, 8013, 8013, -1, + 8014, 8014, 8014, -1, 8015, 8015, 8015, -1, + 8016, 8016, 8016, -1, 8017, 8017, 8017, -1, + 8018, 8018, 8018, -1, 8019, 8019, 8019, -1, + 8020, 8020, 8020, -1, 8021, 8021, 8021, -1, + 8022, 8022, 8022, -1, 8023, 8023, 8023, -1, + 8024, 8024, 8024, -1, 8025, 8025, 8025, -1, + 8026, 8026, 8026, -1, 8027, 8027, 8027, -1, + 8028, 8028, 8028, -1, 8029, 8029, 8029, -1, + 8030, 8030, 8030, -1, 8031, 8031, 8031, -1, + 8032, 8032, 8032, -1, 8033, 8033, 8033, -1, + 8034, 8034, 8034, -1, 8035, 8035, 8035, -1, + 8036, 8036, 8036, -1, 8037, 8037, 8037, -1, + 8038, 8038, 8038, -1, 8039, 8039, 8039, -1, + 8040, 8040, 8040, -1, 8041, 8041, 8041, -1, + 8042, 8042, 8042, -1, 8043, 8043, 8043, -1, + 8044, 8044, 8044, -1, 8045, 8045, 8045, -1, + 8046, 8046, 8046, -1, 8047, 8047, 8047, -1, + 8048, 8048, 8048, -1, 8049, 8049, 8049, -1, + 8050, 8050, 8050, -1, 8051, 8051, 8051, -1, + 8052, 8052, 8052, -1, 8053, 8053, 8053, -1, + 8054, 8054, 8054, -1, 8055, 8055, 8055, -1, + 8056, 8056, 8056, -1, 8057, 8057, 8057, -1, + 8058, 8058, 8058, -1, 8059, 8059, 8059, -1, + 8060, 8060, 8060, -1, 8061, 8061, 8061, -1, + 8062, 8062, 8062, -1, 8063, 8063, 8063, -1, + 8064, 8064, 8064, -1, 8065, 8065, 8065, -1, + 8066, 8066, 8066, -1, 8067, 8067, 8067, -1, + 8068, 8068, 8068, -1, 8069, 8069, 8069, -1, + 8070, 8070, 8070, -1, 8071, 8071, 8071, -1, + 8072, 8072, 8072, -1, 8073, 8073, 8073, -1, + 8074, 8074, 8074, -1, 8075, 8075, 8075, -1, + 8076, 8076, 8076, -1, 8077, 8077, 8077, -1, + 8078, 8078, 8078, -1, 8079, 8079, 8079, -1, + 8080, 8080, 8080, -1, 8081, 8081, 8081, -1, + 8082, 8082, 8082, -1, 8083, 8083, 8083, -1, + 8084, 8084, 8084, -1, 8085, 8085, 8085, -1, + 8086, 8086, 8086, -1, 8087, 8087, 8087, -1, + 8088, 8088, 8088, -1, 8089, 8089, 8089, -1, + 8090, 8090, 8090, -1, 8091, 8091, 8091, -1, + 8092, 8092, 8092, -1, 8093, 8093, 8093, -1, + 8094, 8094, 8094, -1, 8095, 8095, 8095, -1, + 8096, 8096, 8096, -1, 8097, 8097, 8097, -1, + 8098, 8098, 8098, -1, 8099, 8099, 8099, -1, + 8100, 8100, 8100, -1, 8101, 8101, 8101, -1, + 8102, 8102, 8102, -1, 8103, 8103, 8103, -1, + 8104, 8104, 8104, -1, 8105, 8105, 8105, -1, + 8106, 8106, 8106, -1, 8107, 8107, 8107, -1, + 8108, 8108, 8108, -1, 8109, 8109, 8109, -1, + 8110, 8110, 8110, -1, 8111, 8111, 8111, -1, + 8112, 8112, 8112, -1, 8113, 8113, 8113, -1, + 8114, 8114, 8114, -1, 8115, 8115, 8115, -1, + 8116, 8116, 8116, -1, 8117, 8117, 8117, -1, + 8118, 8118, 8118, -1, 8119, 8119, 8119, -1, + 8120, 8120, 8120, -1, 8121, 8121, 8121, -1, + 8122, 8122, 8122, -1, 8123, 8123, 8123, -1, + 8124, 8124, 8124, -1, 8125, 8125, 8125, -1, + 8126, 8126, 8126, -1, 8127, 8127, 8127, -1, + 8128, 8128, 8128, -1, 8129, 8129, 8129, -1, + 8130, 8130, 8130, -1, 8131, 8131, 8131, -1, + 8132, 8132, 8132, -1, 8133, 8133, 8133, -1, + 8134, 8134, 8134, -1, 8135, 8135, 8135, -1, + 8136, 8136, 8136, -1, 8137, 8137, 8137, -1, + 8138, 8138, 8138, -1, 8139, 8139, 8139, -1, + 8140, 8140, 8140, -1, 8141, 8141, 8141, -1, + 8142, 8142, 8142, -1, 8143, 8143, 8143, -1, + 8144, 8144, 8144, -1, 8145, 8145, 8145, -1, + 8146, 8146, 8146, -1, 8147, 8147, 8147, -1, + 8148, 8148, 8148, -1, 8149, 8149, 8149, -1, + 8150, 8150, 8150, -1, 8151, 8151, 8151, -1, + 8152, 8152, 8152, -1, 8153, 8153, 8153, -1, + 8154, 8154, 8154, -1, 8155, 8155, 8155, -1, + 8156, 8156, 8156, -1, 8157, 8157, 8157, -1, + 8158, 8158, 8158, -1, 8159, 8159, 8159, -1, + 8160, 8160, 8160, -1, 8161, 8161, 8161, -1, + 8162, 8162, 8162, -1, 8163, 8163, 8163, -1, + 8164, 8164, 8164, -1, 8165, 8165, 8165, -1, + 8166, 8166, 8166, -1, 8167, 8167, 8167, -1, + 8168, 8168, 8168, -1, 8169, 8169, 8169, -1, + 8170, 8170, 8170, -1, 8171, 8171, 8171, -1, + 8172, 8172, 8172, -1, 8173, 8173, 8173, -1, + 8174, 8174, 8174, -1, 8175, 8175, 8175, -1, + 8176, 8176, 8176, -1, 8177, 8177, 8177, -1, + 8178, 8178, 8178, -1, 8179, 8179, 8179, -1, + 8180, 8180, 8180, -1, 8181, 8181, 8181, -1, + 8182, 8182, 8182, -1, 8183, 8183, 8183, -1, + 8184, 8184, 8184, -1, 8185, 8185, 8185, -1, + 8186, 8186, 8186, -1, 8187, 8187, 8187, -1, + 8188, 8188, 8188, -1, 8189, 8189, 8189, -1, + 8190, 8190, 8190, -1, 8191, 8191, 8191, -1, + 8192, 8192, 8192, -1, 8193, 8193, 8193, -1, + 8194, 8194, 8194, -1, 8195, 8195, 8195, -1, + 8196, 8196, 8196, -1, 8197, 8197, 8197, -1, + 8198, 8198, 8198, -1, 8199, 8199, 8199, -1, + 8200, 8200, 8200, -1, 8201, 8201, 8201, -1, + 8202, 8202, 8202, -1, 8203, 8203, 8203, -1, + 8204, 8204, 8204, -1, 8205, 8205, 8205, -1, + 8206, 8206, 8206, -1, 8207, 8207, 8207, -1, + 8208, 8208, 8208, -1, 8209, 8209, 8209, -1, + 8210, 8210, 8210, -1, 8211, 8211, 8211, -1, + 8212, 8212, 8212, -1, 8213, 8213, 8213, -1, + 8214, 8214, 8214, -1, 8215, 8215, 8215, -1, + 8216, 8216, 8216, -1, 8217, 8217, 8217, -1, + 8218, 8218, 8218, -1, 8219, 8219, 8219, -1, + 8220, 8220, 8220, -1, 8221, 8221, 8221, -1, + 8222, 8222, 8222, -1, 8223, 8223, 8223, -1, + 8224, 8224, 8224, -1, 8225, 8225, 8225, -1, + 8226, 8226, 8226, -1, 8227, 8227, 8227, -1, + 8228, 8228, 8228, -1, 8229, 8229, 8229, -1, + 8230, 8230, 8230, -1, 8231, 8231, 8231, -1, + 8232, 8232, 8232, -1, 8233, 8233, 8233, -1, + 8234, 8234, 8234, -1, 8235, 8235, 8235, -1, + 8236, 8236, 8236, -1, 8237, 8237, 8237, -1, + 8238, 8238, 8238, -1, 8239, 8239, 8239, -1, + 8240, 8240, 8240, -1, 8241, 8241, 8241, -1, + 8242, 8242, 8242, -1, 8243, 8243, 8243, -1, + 8244, 8244, 8244, -1, 8245, 8245, 8245, -1, + 8246, 8246, 8246, -1, 8247, 8247, 8247, -1, + 8248, 8248, 8248, -1, 8249, 8249, 8249, -1, + 8250, 8250, 8250, -1, 8251, 8251, 8251, -1, + 8252, 8252, 8252, -1, 8253, 8253, 8253, -1, + 8254, 8254, 8254, -1, 8255, 8255, 8255, -1, + 8256, 8256, 8256, -1, 8257, 8257, 8257, -1, + 8258, 8258, 8258, -1, 8259, 8259, 8259, -1, + 8260, 8260, 8260, -1, 8261, 8261, 8261, -1, + 8262, 8262, 8262, -1, 8263, 8263, 8263, -1, + 8264, 8264, 8264, -1, 8265, 8265, 8265, -1, + 8266, 8266, 8266, -1, 8267, 8267, 8267, -1, + 8268, 8268, 8268, -1, 8269, 8269, 8269, -1, + 8270, 8270, 8270, -1, 8271, 8271, 8271, -1, + 8272, 8272, 8272, -1, 8273, 8273, 8273, -1, + 8274, 8274, 8274, -1, 8275, 8275, 8275, -1, + 8276, 8276, 8276, -1, 8277, 8277, 8277, -1, + 8278, 8278, 8278, -1, 8279, 8279, 8279, -1, + 8280, 8280, 8280, -1, 8281, 8281, 8281, -1, + 8282, 8282, 8282, -1, 8283, 8283, 8283, -1, + 8284, 8284, 8284, -1, 8285, 8285, 8285, -1, + 8286, 8286, 8286, -1, 8287, 8287, 8287, -1, + 8288, 8288, 8288, -1, 8289, 8289, 8289, -1, + 8290, 8290, 8290, -1, 8291, 8291, 8291, -1, + 8292, 8292, 8292, -1, 8293, 8293, 8293, -1, + 8294, 8294, 8294, -1, 8295, 8295, 8295, -1, + 8296, 8296, 8296, -1, 8297, 8297, 8297, -1, + 8298, 8298, 8298, -1, 8299, 8299, 8299, -1, + 8300, 8300, 8300, -1, 8301, 8301, 8301, -1, + 8302, 8302, 8302, -1, 8303, 8303, 8303, -1, + 8304, 8304, 8304, -1, 8305, 8305, 8305, -1, + 8306, 8306, 8306, -1, 8307, 8307, 8307, -1, + 8308, 8308, 8308, -1, 8309, 8309, 8309, -1, + 8310, 8310, 8310, -1, 8311, 8311, 8311, -1, + 8312, 8312, 8312, -1, 8313, 8313, 8313, -1, + 8314, 8314, 8314, -1, 8315, 8315, 8315, -1, + 8316, 8316, 8316, -1, 8317, 8317, 8317, -1, + 8318, 8318, 8318, -1, 8319, 8319, 8319, -1, + 8320, 8320, 8320, -1, 8321, 8321, 8321, -1, + 8322, 8322, 8322, -1, 8323, 8323, 8323, -1, + 8324, 8324, 8324, -1, 8325, 8325, 8325, -1, + 8326, 8326, 8326, -1, 8327, 8327, 8327, -1, + 8328, 8328, 8328, -1, 8329, 8329, 8329, -1, + 8330, 8330, 8330, -1, 8331, 8331, 8331, -1, + 8332, 8332, 8332, -1, 8333, 8333, 8333, -1, + 8334, 8334, 8334, -1, 8335, 8335, 8335, -1, + 8336, 8336, 8336, -1, 8337, 8337, 8337, -1, + 8338, 8338, 8338, -1, 8339, 8339, 8339, -1, + 8340, 8340, 8340, -1, 8341, 8341, 8341, -1, + 8342, 8342, 8342, -1, 8343, 8343, 8343, -1, + 8344, 8344, 8344, -1, 8345, 8345, 8345, -1, + 8346, 8346, 8346, -1, 8347, 8347, 8347, -1, + 8348, 8348, 8348, -1, 8349, 8349, 8349, -1, + 8350, 8350, 8350, -1, 8351, 8351, 8351, -1, + 8352, 8352, 8352, -1, 8353, 8353, 8353, -1, + 8354, 8354, 8354, -1, 8355, 8355, 8355, -1, + 8356, 8356, 8356, -1, 8357, 8357, 8357, -1, + 8358, 8358, 8358, -1, 8359, 8359, 8359, -1, + 8360, 8360, 8360, -1, 8361, 8361, 8361, -1, + 8362, 8362, 8362, -1, 8363, 8363, 8363, -1, + 8364, 8364, 8364, -1, 8365, 8365, 8365, -1, + 8366, 8366, 8366, -1, 8367, 8367, 8367, -1, + 8368, 8368, 8368, -1, 8369, 8369, 8369, -1, + 8370, 8370, 8370, -1, 8371, 8371, 8371, -1, + 8372, 8372, 8372, -1, 8373, 8373, 8373, -1, + 8374, 8374, 8374, -1, 8375, 8375, 8375, -1, + 8376, 8376, 8376, -1, 8377, 8377, 8377, -1, + 8378, 8378, 8378, -1, 8379, 8379, 8379, -1, + 8380, 8380, 8380, -1, 8381, 8381, 8381, -1, + 8382, 8382, 8382, -1, 8383, 8383, 8383, -1, + 8384, 8384, 8384, -1, 8385, 8385, 8385, -1, + 8386, 8386, 8386, -1, 8387, 8387, 8387, -1, + 8388, 8388, 8388, -1, 8389, 8389, 8389, -1, + 8390, 8390, 8390, -1, 8391, 8391, 8391, -1, + 8392, 8392, 8392, -1, 8393, 8393, 8393, -1, + 8394, 8394, 8394, -1, 8395, 8395, 8395, -1, + 8396, 8396, 8396, -1, 8397, 8397, 8397, -1, + 8398, 8398, 8398, -1, 8399, 8399, 8399, -1, + 8400, 8400, 8400, -1, 8401, 8401, 8401, -1, + 8402, 8402, 8402, -1, 8403, 8403, 8403, -1, + 8404, 8404, 8404, -1, 8405, 8405, 8405, -1, + 8406, 8406, 8406, -1, 8407, 8407, 8407, -1, + 8408, 8408, 8408, -1, 8409, 8409, 8409, -1, + 8410, 8410, 8410, -1, 8411, 8411, 8411, -1, + 8412, 8412, 8412, -1, 8413, 8413, 8413, -1, + 8414, 8414, 8414, -1, 8415, 8415, 8415, -1, + 8416, 8416, 8416, -1, 8417, 8417, 8417, -1, + 8418, 8418, 8418, -1, 8419, 8419, 8419, -1, + 8420, 8420, 8420, -1, 8421, 8421, 8421, -1, + 8422, 8422, 8422, -1, 8423, 8423, 8423, -1, + 8424, 8424, 8424, -1, 8425, 8425, 8425, -1, + 8426, 8426, 8426, -1, 8427, 8427, 8427, -1, + 8428, 8428, 8428, -1, 8429, 8429, 8429, -1, + 8430, 8430, 8430, -1, 8431, 8431, 8431, -1, + 8432, 8432, 8432, -1, 8433, 8433, 8433, -1, + 8434, 8434, 8434, -1, 8435, 8435, 8435, -1, + 8436, 8436, 8436, -1, 8437, 8437, 8437, -1, + 8438, 8438, 8438, -1, 8439, 8439, 8439, -1, + 8440, 8440, 8440, -1, 8441, 8441, 8441, -1, + 8442, 8442, 8442, -1, 8443, 8443, 8443, -1, + 8444, 8444, 8444, -1, 8445, 8445, 8445, -1, + 8446, 8446, 8446, -1, 8447, 8447, 8447, -1, + 8448, 8448, 8448, -1, 8449, 8449, 8449, -1, + 8450, 8450, 8450, -1, 8451, 8451, 8451, -1, + 8452, 8452, 8452, -1, 8453, 8453, 8453, -1, + 8454, 8454, 8454, -1, 8455, 8455, 8455, -1, + 8456, 8456, 8456, -1, 8457, 8457, 8457, -1, + 8458, 8458, 8458, -1, 8459, 8459, 8459, -1, + 8460, 8460, 8460, -1, 8461, 8461, 8461, -1, + 8462, 8462, 8462, -1, 8463, 8463, 8463, -1, + 8464, 8464, 8464, -1, 8465, 8465, 8465, -1, + 8466, 8466, 8466, -1, 8467, 8467, 8467, -1, + 8468, 8468, 8468, -1, 8469, 8469, 8469, -1, + 8470, 8470, 8470, -1, 8471, 8471, 8471, -1, + 8472, 8472, 8472, -1, 8473, 8473, 8473, -1, + 8474, 8474, 8474, -1, 8475, 8475, 8475, -1, + 8476, 8476, 8476, -1, 8477, 8477, 8477, -1, + 8478, 8478, 8478, -1, 8479, 8479, 8479, -1, + 8480, 8480, 8480, -1, 8481, 8481, 8481, -1, + 8482, 8482, 8482, -1, 8483, 8483, 8483, -1, + 8484, 8484, 8484, -1, 8485, 8485, 8485, -1, + 8486, 8486, 8486, -1, 8487, 8487, 8487, -1, + 8488, 8488, 8488, -1, 8489, 8489, 8489, -1, + 8490, 8490, 8490, -1, 8491, 8491, 8491, -1, + 8492, 8492, 8492, -1, 8493, 8493, 8493, -1, + 8494, 8494, 8494, -1, 8495, 8495, 8495, -1, + 8496, 8496, 8496, -1, 8497, 8497, 8497, -1, + 8498, 8498, 8498, -1, 8499, 8499, 8499, -1, + 8500, 8500, 8500, -1, 8501, 8501, 8501, -1, + 8502, 8502, 8502, -1, 8503, 8503, 8503, -1, + 8504, 8504, 8504, -1, 8505, 8505, 8505, -1, + 8506, 8506, 8506, -1, 8507, 8507, 8507, -1, + 8508, 8508, 8508, -1, 8509, 8509, 8509, -1, + 8510, 8510, 8510, -1, 8511, 8511, 8511, -1, + 8512, 8512, 8512, -1, 8513, 8513, 8513, -1, + 8514, 8514, 8514, -1, 8515, 8515, 8515, -1, + 8516, 8516, 8516, -1, 8517, 8517, 8517, -1, + 8518, 8518, 8518, -1, 8519, 8519, 8519, -1, + 8520, 8520, 8520, -1, 8521, 8521, 8521, -1, + 8522, 8522, 8522, -1, 8523, 8523, 8523, -1, + 8524, 8524, 8524, -1, 8525, 8525, 8525, -1, + 8526, 8526, 8526, -1, 8527, 8527, 8527, -1, + 8528, 8528, 8528, -1, 8529, 8529, 8529, -1, + 8530, 8530, 8530, -1, 8531, 8531, 8531, -1, + 8532, 8532, 8532, -1, 8533, 8533, 8533, -1, + 8534, 8534, 8534, -1, 8535, 8535, 8535, -1, + 8536, 8536, 8536, -1, 8537, 8537, 8537, -1, + 8538, 8538, 8538, -1, 8539, 8539, 8539, -1, + 8540, 8540, 8540, -1, 8541, 8541, 8541, -1, + 8542, 8542, 8542, -1, 8543, 8543, 8543, -1, + 8544, 8544, 8544, -1, 8545, 8545, 8545, -1, + 8546, 8546, 8546, -1, 8547, 8547, 8547, -1, + 8548, 8548, 8548, -1, 8549, 8549, 8549, -1, + 8550, 8550, 8550, -1, 8551, 8551, 8551, -1, + 8552, 8552, 8552, -1, 8553, 8553, 8553, -1, + 8554, 8554, 8554, -1, 8555, 8555, 8555, -1, + 8556, 8556, 8556, -1, 8557, 8557, 8557, -1, + 8558, 8558, 8558, -1, 8559, 8559, 8559, -1, + 8560, 8560, 8560, -1, 8561, 8561, 8561, -1, + 8562, 8562, 8562, -1, 8563, 8563, 8563, -1, + 8564, 8564, 8564, -1, 8565, 8565, 8565, -1, + 8566, 8566, 8566, -1, 8567, 8567, 8567, -1, + 8568, 8568, 8568, -1, 8569, 8569, 8569, -1, + 8570, 8570, 8570, -1, 8571, 8571, 8571, -1, + 8572, 8572, 8572, -1, 8573, 8573, 8573, -1, + 8574, 8574, 8574, -1, 8575, 8575, 8575, -1, + 8576, 8576, 8576, -1, 8577, 8577, 8577, -1, + 8578, 8578, 8578, -1, 8579, 8579, 8579, -1, + 8580, 8580, 8580, -1, 8581, 8581, 8581, -1, + 8582, 8582, 8582, -1, 8583, 8583, 8583, -1, + 8584, 8584, 8584, -1, 8585, 8585, 8585, -1, + 8586, 8586, 8586, -1, 8587, 8587, 8587, -1, + 8588, 8588, 8588, -1, 8589, 8589, 8589, -1, + 8590, 8590, 8590, -1, 8591, 8591, 8591, -1, + 8592, 8592, 8592, -1, 8593, 8593, 8593, -1, + 8594, 8594, 8594, -1, 8595, 8595, 8595, -1, + 8596, 8596, 8596, -1, 8597, 8597, 8597, -1, + 8598, 8598, 8598, -1, 8599, 8599, 8599, -1, + 8600, 8600, 8600, -1, 8601, 8601, 8601, -1, + 8602, 8602, 8602, -1, 8603, 8603, 8603, -1, + 8604, 8604, 8604, -1, 8605, 8605, 8605, -1, + 8606, 8606, 8606, -1, 8607, 8607, 8607, -1, + 8608, 8608, 8608, -1, 8609, 8609, 8609, -1, + 8610, 8610, 8610, -1, 8611, 8611, 8611, -1, + 8612, 8612, 8612, -1, 8613, 8613, 8613, -1, + 8614, 8614, 8614, -1, 8615, 8615, 8615, -1, + 8616, 8616, 8616, -1, 8617, 8617, 8617, -1, + 8618, 8618, 8618, -1, 8619, 8619, 8619, -1, + 8620, 8620, 8620, -1, 8621, 8621, 8621, -1, + 8622, 8622, 8622, -1, 8623, 8623, 8623, -1, + 8624, 8624, 8624, -1, 8625, 8625, 8625, -1, + 8626, 8626, 8626, -1, 8627, 8627, 8627, -1, + 8628, 8628, 8628, -1, 8629, 8629, 8629, -1, + 8630, 8630, 8630, -1, 8631, 8631, 8631, -1, + 8632, 8632, 8632, -1, 8633, 8633, 8633, -1, + 8634, 8634, 8634, -1, 8635, 8635, 8635, -1, + 8636, 8636, 8636, -1, 8637, 8637, 8637, -1, + 8638, 8638, 8638, -1, 8639, 8639, 8639, -1, + 8640, 8640, 8640, -1, 8641, 8641, 8641, -1, + 8642, 8642, 8642, -1, 8643, 8643, 8643, -1, + 8644, 8644, 8644, -1, 8645, 8645, 8645, -1, + 8646, 8646, 8646, -1, 8647, 8647, 8647, -1, + 8648, 8648, 8648, -1, 8649, 8649, 8649, -1, + 8650, 8650, 8650, -1, 8651, 8651, 8651, -1, + 8652, 8652, 8652, -1, 8653, 8653, 8653, -1, + 8654, 8654, 8654, -1, 8655, 8655, 8655, -1, + 8656, 8656, 8656, -1, 8657, 8657, 8657, -1, + 8658, 8658, 8658, -1, 8659, 8659, 8659, -1, + 8660, 8660, 8660, -1, 8661, 8661, 8661, -1, + 8662, 8662, 8662, -1, 8663, 8663, 8663, -1, + 8664, 8664, 8664, -1, 8665, 8665, 8665, -1, + 8666, 8666, 8666, -1, 8667, 8667, 8667, -1, + 8668, 8668, 8668, -1, 8669, 8669, 8669, -1, + 8670, 8670, 8670, -1, 8671, 8671, 8671, -1, + 8672, 8672, 8672, -1, 8673, 8673, 8673, -1, + 8674, 8674, 8674, -1, 8675, 8675, 8675, -1, + 8676, 8676, 8676, -1, 8677, 8677, 8677, -1, + 8678, 8678, 8678, -1, 8679, 8679, 8679, -1, + 8680, 8680, 8680, -1, 8681, 8681, 8681, -1, + 8682, 8682, 8682, -1, 8683, 8683, 8683, -1, + 8684, 8684, 8684, -1, 8685, 8685, 8685, -1, + 8686, 8686, 8686, -1, 8687, 8687, 8687, -1, + 8688, 8688, 8688, -1, 8689, 8689, 8689, -1, + 8690, 8690, 8690, -1, 8691, 8691, 8691, -1, + 8692, 8692, 8692, -1, 8693, 8693, 8693, -1, + 8694, 8694, 8694, -1, 8695, 8695, 8695, -1, + 8696, 8696, 8696, -1, 8697, 8697, 8697, -1, + 8698, 8698, 8698, -1, 8699, 8699, 8699, -1, + 8700, 8700, 8700, -1, 8701, 8701, 8701, -1, + 8702, 8702, 8702, -1, 8703, 8703, 8703, -1, + 8704, 8704, 8704, -1, 8705, 8705, 8705, -1, + 8706, 8706, 8706, -1, 8707, 8707, 8707, -1, + 8708, 8708, 8708, -1, 8709, 8709, 8709, -1, + 8710, 8710, 8710, -1, 8711, 8711, 8711, -1, + 8712, 8712, 8712, -1, 8713, 8713, 8713, -1, + 8714, 8714, 8714, -1, 8715, 8715, 8715, -1, + 8716, 8716, 8716, -1, 8717, 8717, 8717, -1, + 8718, 8718, 8718, -1, 8719, 8719, 8719, -1, + 8720, 8720, 8720, -1, 8721, 8721, 8721, -1, + 8722, 8722, 8722, -1, 8723, 8723, 8723, -1, + 8724, 8724, 8724, -1, 8725, 8725, 8725, -1, + 8726, 8726, 8726, -1, 8727, 8727, 8727, -1, + 8728, 8728, 8728, -1, 8729, 8729, 8729, -1, + 8730, 8730, 8730, -1, 8731, 8731, 8731, -1, + 8732, 8732, 8732, -1, 8733, 8733, 8733, -1, + 8734, 8734, 8734, -1, 8735, 8735, 8735, -1, + 8736, 8736, 8736, -1, 8737, 8737, 8737, -1, + 8738, 8738, 8738, -1, 8739, 8739, 8739, -1, + 8740, 8740, 8740, -1, 8741, 8741, 8741, -1, + 8742, 8742, 8742, -1, 8743, 8743, 8743, -1, + 8744, 8744, 8744, -1, 8745, 8745, 8745, -1, + 8746, 8746, 8746, -1, 8747, 8747, 8747, -1, + 8748, 8748, 8748, -1, 8749, 8749, 8749, -1, + 8750, 8750, 8750, -1, 8751, 8751, 8751, -1, + 8752, 8752, 8752, -1, 8753, 8753, 8753, -1, + 8754, 8754, 8754, -1, 8755, 8755, 8755, -1, + 8756, 8756, 8756, -1, 8757, 8757, 8757, -1, + 8758, 8758, 8758, -1, 8759, 8759, 8759, -1, + 8760, 8760, 8760, -1, 8761, 8761, 8761, -1, + 8762, 8762, 8762, -1, 8763, 8763, 8763, -1, + 8764, 8764, 8764, -1, 8765, 8765, 8765, -1, + 8766, 8766, 8766, -1, 8767, 8767, 8767, -1, + 8768, 8768, 8768, -1, 8769, 8769, 8769, -1, + 8770, 8770, 8770, -1, 8771, 8771, 8771, -1, + 8772, 8772, 8772, -1, 8773, 8773, 8773, -1, + 8774, 8774, 8774, -1, 8775, 8775, 8775, -1, + 8776, 8776, 8776, -1, 8777, 8777, 8777, -1, + 8778, 8778, 8778, -1, 8779, 8779, 8779, -1, + 8780, 8780, 8780, -1, 8781, 8781, 8781, -1, + 8782, 8782, 8782, -1, 8783, 8783, 8783, -1, + 8784, 8784, 8784, -1, 8785, 8785, 8785, -1, + 8786, 8786, 8786, -1, 8787, 8787, 8787, -1, + 8788, 8788, 8788, -1, 8789, 8789, 8789, -1, + 8790, 8790, 8790, -1, 8791, 8791, 8791, -1, + 8792, 8792, 8792, -1, 8793, 8793, 8793, -1, + 8794, 8794, 8794, -1, 8795, 8795, 8795, -1, + 8796, 8796, 8796, -1, 8797, 8797, 8797, -1, + 8798, 8798, 8798, -1, 8799, 8799, 8799, -1, + 8800, 8800, 8800, -1, 8801, 8801, 8801, -1, + 8802, 8802, 8802, -1, 8803, 8803, 8803, -1, + 8804, 8804, 8804, -1, 8805, 8805, 8805, -1, + 8806, 8806, 8806, -1, 8807, 8807, 8807, -1, + 8808, 8808, 8808, -1, 8809, 8809, 8809, -1, + 8810, 8810, 8810, -1, 8811, 8811, 8811, -1, + 8812, 8812, 8812, -1, 8813, 8813, 8813, -1, + 8814, 8814, 8814, -1, 8815, 8815, 8815, -1, + 8816, 8816, 8816, -1, 8817, 8817, 8817, -1, + 8818, 8818, 8818, -1, 8819, 8819, 8819, -1, + 8820, 8820, 8820, -1, 8821, 8821, 8821, -1, + 8822, 8822, 8822, -1, 8823, 8823, 8823, -1, + 8824, 8824, 8824, -1, 8825, 8825, 8825, -1, + 8826, 8826, 8826, -1, 8827, 8827, 8827, -1, + 8828, 8828, 8828, -1, 8829, 8829, 8829, -1, + 8830, 8830, 8830, -1, 8831, 8831, 8831, -1, + 8832, 8832, 8832, -1, 8833, 8833, 8833, -1, + 8834, 8834, 8834, -1, 8835, 8835, 8835, -1, + 8836, 8836, 8836, -1, 8837, 8837, 8837, -1, + 8838, 8838, 8838, -1, 8839, 8839, 8839, -1, + 8840, 8840, 8840, -1, 8841, 8841, 8841, -1, + 8842, 8842, 8842, -1, 8843, 8843, 8843, -1, + 8844, 8844, 8844, -1, 8845, 8845, 8845, -1, + 8846, 8846, 8846, -1, 8847, 8847, 8847, -1, + 8848, 8848, 8848, -1, 8849, 8849, 8849, -1, + 8850, 8850, 8850, -1, 8851, 8851, 8851, -1, + 8852, 8852, 8852, -1, 8853, 8853, 8853, -1, + 8854, 8854, 8854, -1, 8855, 8855, 8855, -1, + 8856, 8856, 8856, -1, 8857, 8857, 8857, -1, + 8858, 8858, 8858, -1, 8859, 8859, 8859, -1, + 8860, 8860, 8860, -1, 8861, 8861, 8861, -1, + 8862, 8862, 8862, -1, 8863, 8863, 8863, -1, + 8864, 8864, 8864, -1, 8865, 8865, 8865, -1, + 8866, 8866, 8866, -1, 8867, 8867, 8867, -1, + 8868, 8868, 8868, -1, 8869, 8869, 8869, -1, + 8870, 8870, 8870, -1, 8871, 8871, 8871, -1, + 8872, 8872, 8872, -1, 8873, 8873, 8873, -1, + 8874, 8874, 8874, -1, 8875, 8875, 8875, -1, + 8876, 8876, 8876, -1, 8877, 8877, 8877, -1, + 8878, 8878, 8878, -1, 8879, 8879, 8879, -1, + 8880, 8880, 8880, -1, 8881, 8881, 8881, -1, + 8882, 8882, 8882, -1, 8883, 8883, 8883, -1, + 8884, 8884, 8884, -1, 8885, 8885, 8885, -1, + 8886, 8886, 8886, -1, 8887, 8887, 8887, -1, + 8888, 8888, 8888, -1, 8889, 8889, 8889, -1, + 8890, 8890, 8890, -1, 8891, 8891, 8891, -1, + 8892, 8892, 8892, -1, 8893, 8893, 8893, -1, + 8894, 8894, 8894, -1, 8895, 8895, 8895, -1, + 8896, 8896, 8896, -1, 8897, 8897, 8897, -1, + 8898, 8898, 8898, -1, 8899, 8899, 8899, -1, + 8900, 8900, 8900, -1, 8901, 8901, 8901, -1, + 8902, 8902, 8902, -1, 8903, 8903, 8903, -1, + 8904, 8904, 8904, -1, 8905, 8905, 8905, -1, + 8906, 8906, 8906, -1, 8907, 8907, 8907, -1, + 8908, 8908, 8908, -1, 8909, 8909, 8909, -1, + 8910, 8910, 8910, -1, 8911, 8911, 8911, -1, + 8912, 8912, 8912, -1, 8913, 8913, 8913, -1, + 8914, 8914, 8914, -1, 8915, 8915, 8915, -1, + 8916, 8916, 8916, -1, 8917, 8917, 8917, -1, + 8918, 8918, 8918, -1, 8919, 8919, 8919, -1, + 8920, 8920, 8920, -1, 8921, 8921, 8921, -1, + 8922, 8922, 8922, -1, 8923, 8923, 8923, -1, + 8924, 8924, 8924, -1, 8925, 8925, 8925, -1, + 8926, 8926, 8926, -1, 8927, 8927, 8927, -1, + 8928, 8928, 8928, -1, 8929, 8929, 8929, -1, + 8930, 8930, 8930, -1, 8931, 8931, 8931, -1, + 8932, 8932, 8932, -1, 8933, 8933, 8933, -1, + 8934, 8934, 8934, -1, 8935, 8935, 8935, -1, + 8936, 8936, 8936, -1, 8937, 8937, 8937, -1, + 8938, 8938, 8938, -1, 8939, 8939, 8939, -1, + 8940, 8940, 8940, -1, 8941, 8941, 8941, -1, + 8942, 8942, 8942, -1, 8943, 8943, 8943, -1, + 8944, 8944, 8944, -1, 8945, 8945, 8945, -1, + 8946, 8946, 8946, -1, 8947, 8947, 8947, -1, + 8948, 8948, 8948, -1, 8949, 8949, 8949, -1, + 8950, 8950, 8950, -1, 8951, 8951, 8951, -1, + 8952, 8952, 8952, -1, 8953, 8953, 8953, -1, + 8954, 8954, 8954, -1, 8955, 8955, 8955, -1, + 8956, 8956, 8956, -1, 8957, 8957, 8957, -1, + 8958, 8958, 8958, -1, 8959, 8959, 8959, -1, + 8960, 8960, 8960, -1, 8961, 8961, 8961, -1, + 8962, 8962, 8962, -1, 8963, 8963, 8963, -1, + 8964, 8964, 8964, -1, 8965, 8965, 8965, -1, + 8966, 8966, 8966, -1, 8967, 8967, 8967, -1, + 8968, 8968, 8968, -1, 8969, 8969, 8969, -1, + 8970, 8970, 8970, -1, 8971, 8971, 8971, -1, + 8972, 8972, 8972, -1, 8973, 8973, 8973, -1, + 8974, 8974, 8974, -1, 8975, 8975, 8975, -1, + 8976, 8976, 8976, -1, 8977, 8977, 8977, -1, + 8978, 8978, 8978, -1, 8979, 8979, 8979, -1, + 8980, 8980, 8980, -1, 8981, 8981, 8981, -1, + 8982, 8982, 8982, -1, 8983, 8983, 8983, -1, + 8984, 8984, 8984, -1, 8985, 8985, 8985, -1, + 8986, 8986, 8986, -1, 8987, 8987, 8987, -1, + 8988, 8988, 8988, -1, 8989, 8989, 8989, -1, + 8990, 8990, 8990, -1, 8991, 8991, 8991, -1, + 8992, 8992, 8992, -1, 8993, 8993, 8993, -1, + 8994, 8994, 8994, -1, 8995, 8995, 8995, -1, + 8996, 8996, 8996, -1, 8997, 8997, 8997, -1, + 8998, 8998, 8998, -1, 8999, 8999, 8999, -1, + 9000, 9000, 9000, -1, 9001, 9001, 9001, -1, + 9002, 9002, 9002, -1, 9003, 9003, 9003, -1, + 9004, 9004, 9004, -1, 9005, 9005, 9005, -1, + 9006, 9006, 9006, -1, 9007, 9007, 9007, -1, + 9008, 9008, 9008, -1, 9009, 9009, 9009, -1, + 9010, 9010, 9010, -1, 9011, 9011, 9011, -1, + 9012, 9012, 9012, -1, 9013, 9013, 9013, -1, + 9014, 9014, 9014, -1, 9015, 9015, 9015, -1, + 9016, 9016, 9016, -1, 9017, 9017, 9017, -1, + 9018, 9018, 9018, -1, 9019, 9019, 9019, -1, + 9020, 9020, 9020, -1, 9021, 9021, 9021, -1, + 9022, 9022, 9022, -1, 9023, 9023, 9023, -1, + 9024, 9024, 9024, -1, 9025, 9025, 9025, -1, + 9026, 9026, 9026, -1, 9027, 9027, 9027, -1, + 9028, 9028, 9028, -1, 9029, 9029, 9029, -1, + 9030, 9030, 9030, -1, 9031, 9031, 9031, -1, + 9032, 9032, 9032, -1, 9033, 9033, 9033, -1, + 9034, 9034, 9034, -1, 9035, 9035, 9035, -1, + 9036, 9036, 9036, -1, 9037, 9037, 9037, -1, + 9038, 9038, 9038, -1, 9039, 9039, 9039, -1, + 9040, 9040, 9040, -1, 9041, 9041, 9041, -1, + 9042, 9042, 9042, -1, 9043, 9043, 9043, -1, + 9044, 9044, 9044, -1, 9045, 9045, 9045, -1, + 9046, 9046, 9046, -1, 9047, 9047, 9047, -1, + 9048, 9048, 9048, -1, 9049, 9049, 9049, -1, + 9050, 9050, 9050, -1, 9051, 9051, 9051, -1, + 9052, 9052, 9052, -1, 9053, 9053, 9053, -1, + 9054, 9054, 9054, -1, 9055, 9055, 9055, -1, + 9056, 9056, 9056, -1, 9057, 9057, 9057, -1, + 9058, 9058, 9058, -1, 9059, 9059, 9059, -1, + 9060, 9060, 9060, -1, 9061, 9061, 9061, -1, + 9062, 9062, 9062, -1, 9063, 9063, 9063, -1, + 9064, 9064, 9064, -1, 9065, 9065, 9065, -1, + 9066, 9066, 9066, -1, 9067, 9067, 9067, -1, + 9068, 9068, 9068, -1, 9069, 9069, 9069, -1, + 9070, 9070, 9070, -1, 9071, 9071, 9071, -1, + 9072, 9072, 9072, -1, 9073, 9073, 9073, -1, + 9074, 9074, 9074, -1, 9075, 9075, 9075, -1, + 9076, 9076, 9076, -1, 9077, 9077, 9077, -1, + 9078, 9078, 9078, -1, 9079, 9079, 9079, -1, + 9080, 9080, 9080, -1, 9081, 9081, 9081, -1, + 9082, 9082, 9082, -1, 9083, 9083, 9083, -1, + 9084, 9084, 9084, -1, 9085, 9085, 9085, -1, + 9086, 9086, 9086, -1, 9087, 9087, 9087, -1, + 9088, 9088, 9088, -1, 9089, 9089, 9089, -1, + 9090, 9090, 9090, -1, 9091, 9091, 9091, -1, + 9092, 9092, 9092, -1, 9093, 9093, 9093, -1, + 9094, 9094, 9094, -1, 9095, 9095, 9095, -1, + 9096, 9096, 9096, -1, 9097, 9097, 9097, -1, + 9098, 9098, 9098, -1, 9099, 9099, 9099, -1, + 9100, 9100, 9100, -1, 9101, 9101, 9101, -1, + 9102, 9102, 9102, -1, 9103, 9103, 9103, -1, + 9104, 9104, 9104, -1, 9105, 9105, 9105, -1, + 9106, 9106, 9106, -1, 9107, 9107, 9107, -1, + 9108, 9108, 9108, -1, 9109, 9109, 9109, -1, + 9110, 9110, 9110, -1, 9111, 9111, 9111, -1, + 9112, 9112, 9112, -1, 9113, 9113, 9113, -1, + 9114, 9114, 9114, -1, 9115, 9115, 9115, -1, + 9116, 9116, 9116, -1, 9117, 9117, 9117, -1, + 9118, 9118, 9118, -1, 9119, 9119, 9119, -1, + 9120, 9120, 9120, -1, 9121, 9121, 9121, -1, + 9122, 9122, 9122, -1, 9123, 9123, 9123, -1, + 9124, 9124, 9124, -1, 9125, 9125, 9125, -1, + 9126, 9126, 9126, -1, 9127, 9127, 9127, -1, + 9128, 9128, 9128, -1, 9129, 9129, 9129, -1, + 9130, 9130, 9130, -1, 9131, 9131, 9131, -1, + 9132, 9132, 9132, -1, 9133, 9133, 9133, -1, + 9134, 9134, 9134, -1, 9135, 9135, 9135, -1, + 9136, 9136, 9136, -1, 9137, 9137, 9137, -1, + 9138, 9138, 9138, -1, 9139, 9139, 9139, -1, + 9140, 9140, 9140, -1, 9141, 9141, 9141, -1, + 9142, 9142, 9142, -1, 9143, 9143, 9143, -1, + 9144, 9144, 9144, -1, 9145, 9145, 9145, -1, + 9146, 9146, 9146, -1, 9147, 9147, 9147, -1, + 9148, 9148, 9148, -1, 9149, 9149, 9149, -1, + 9150, 9150, 9150, -1, 9151, 9151, 9151, -1, + 9152, 9152, 9152, -1, 9153, 9153, 9153, -1, + 9154, 9154, 9154, -1, 9155, 9155, 9155, -1, + 9156, 9156, 9156, -1, 9157, 9157, 9157, -1, + 9158, 9158, 9158, -1, 9159, 9159, 9159, -1, + 9160, 9160, 9160, -1, 9161, 9161, 9161, -1, + 9162, 9162, 9162, -1, 9163, 9163, 9163, -1, + 9164, 9164, 9164, -1, 9165, 9165, 9165, -1, + 9166, 9166, 9166, -1, 9167, 9167, 9167, -1, + 9168, 9168, 9168, -1, 9169, 9169, 9169, -1, + 9170, 9170, 9170, -1, 9171, 9171, 9171, -1, + 9172, 9172, 9172, -1, 9173, 9173, 9173, -1, + 9174, 9174, 9174, -1, 9175, 9175, 9175, -1, + 9176, 9176, 9176, -1, 9177, 9177, 9177, -1, + 9178, 9178, 9178, -1, 9179, 9179, 9179, -1, + 9180, 9180, 9180, -1, 9181, 9181, 9181, -1, + 9182, 9182, 9182, -1, 9183, 9183, 9183, -1, + 9184, 9184, 9184, -1, 9185, 9185, 9185, -1, + 9186, 9186, 9186, -1, 9187, 9187, 9187, -1, + 9188, 9188, 9188, -1, 9189, 9189, 9189, -1, + 9190, 9190, 9190, -1, 9191, 9191, 9191, -1, + 9192, 9192, 9192, -1, 9193, 9193, 9193, -1, + 9194, 9194, 9194, -1, 9195, 9195, 9195, -1, + 9196, 9196, 9196, -1, 9197, 9197, 9197, -1, + 9198, 9198, 9198, -1, 9199, 9199, 9199, -1, + 9200, 9200, 9200, -1, 9201, 9201, 9201, -1, + 9202, 9202, 9202, -1, 9203, 9203, 9203, -1, + 9204, 9204, 9204, -1, 9205, 9205, 9205, -1, + 9206, 9206, 9206, -1, 9207, 9207, 9207, -1, + 9208, 9208, 9208, -1, 9209, 9209, 9209, -1, + 9210, 9210, 9210, -1, 9211, 9211, 9211, -1, + 9212, 9212, 9212, -1, 9213, 9213, 9213, -1, + 9214, 9214, 9214, -1, 9215, 9215, 9215, -1, + 9216, 9216, 9216, -1, 9217, 9217, 9217, -1, + 9218, 9218, 9218, -1, 9219, 9219, 9219, -1, + 9220, 9220, 9220, -1, 9221, 9221, 9221, -1, + 9222, 9222, 9222, -1, 9223, 9223, 9223, -1, + 9224, 9224, 9224, -1, 9225, 9225, 9225, -1, + 9226, 9226, 9226, -1, 9227, 9227, 9227, -1, + 9228, 9228, 9228, -1, 9229, 9229, 9229, -1, + 9230, 9230, 9230, -1, 9231, 9231, 9231, -1, + 9232, 9232, 9232, -1, 9233, 9233, 9233, -1, + 9234, 9234, 9234, -1, 9235, 9235, 9235, -1, + 9236, 9236, 9236, -1, 9237, 9237, 9237, -1, + 9238, 9238, 9238, -1, 9239, 9239, 9239, -1, + 9240, 9240, 9240, -1, 9241, 9241, 9241, -1, + 9242, 9242, 9242, -1, 9243, 9243, 9243, -1, + 9244, 9244, 9244, -1, 9245, 9245, 9245, -1, + 9246, 9246, 9246, -1, 9247, 9247, 9247, -1, + 9248, 9248, 9248, -1, 9249, 9249, 9249, -1, + 9250, 9250, 9250, -1, 9251, 9251, 9251, -1, + 9252, 9252, 9252, -1, 9253, 9253, 9253, -1, + 9254, 9254, 9254, -1, 9255, 9255, 9255, -1, + 9256, 9256, 9256, -1, 9257, 9257, 9257, -1, + 9258, 9258, 9258, -1, 9259, 9259, 9259, -1, + 9260, 9260, 9260, -1, 9261, 9261, 9261, -1, + 9262, 9262, 9262, -1, 9263, 9263, 9263, -1, + 9264, 9264, 9264, -1, 9265, 9265, 9265, -1, + 9266, 9266, 9266, -1, 9267, 9267, 9267, -1, + 9268, 9268, 9268, -1, 9269, 9269, 9269, -1, + 9270, 9270, 9270, -1, 9271, 9271, 9271, -1, + 9272, 9272, 9272, -1, 9273, 9273, 9273, -1, + 9274, 9274, 9274, -1, 9275, 9275, 9275, -1, + 9276, 9276, 9276, -1, 9277, 9277, 9277, -1, + 9278, 9278, 9278, -1, 9279, 9279, 9279, -1, + 9280, 9280, 9280, -1, 9281, 9281, 9281, -1, + 9282, 9282, 9282, -1, 9283, 9283, 9283, -1, + 9284, 9284, 9284, -1, 9285, 9285, 9285, -1, + 9286, 9286, 9286, -1, 9287, 9287, 9287, -1, + 9288, 9288, 9288, -1, 9289, 9289, 9289, -1, + 9290, 9290, 9290, -1, 9291, 9291, 9291, -1, + 9292, 9292, 9292, -1, 9293, 9293, 9293, -1, + 9294, 9294, 9294, -1, 9295, 9295, 9295, -1, + 9296, 9296, 9296, -1, 9297, 9297, 9297, -1, + 9298, 9298, 9298, -1, 9299, 9299, 9299, -1, + 9300, 9300, 9300, -1, 9301, 9301, 9301, -1, + 9302, 9302, 9302, -1, 9303, 9303, 9303, -1, + 9304, 9304, 9304, -1, 9305, 9305, 9305, -1, + 9306, 9306, 9306, -1, 9307, 9307, 9307, -1, + 9308, 9308, 9308, -1, 9309, 9309, 9309, -1, + 9310, 9310, 9310, -1, 9311, 9311, 9311, -1, + 9312, 9312, 9312, -1, 9313, 9313, 9313, -1, + 9314, 9314, 9314, -1, 9315, 9315, 9315, -1, + 9316, 9316, 9316, -1, 9317, 9317, 9317, -1, + 9318, 9318, 9318, -1, 9319, 9319, 9319, -1, + 9320, 9320, 9320, -1, 9321, 9321, 9321, -1, + 9322, 9322, 9322, -1, 9323, 9323, 9323, -1, + 9324, 9324, 9324, -1, 9325, 9325, 9325, -1, + 9326, 9326, 9326, -1, 9327, 9327, 9327, -1, + 9328, 9328, 9328, -1, 9329, 9329, 9329, -1, + 9330, 9330, 9330, -1, 9331, 9331, 9331, -1, + 9332, 9332, 9332, -1, 9333, 9333, 9333, -1, + 9334, 9334, 9334, -1, 9335, 9335, 9335, -1, + 9336, 9336, 9336, -1, 9337, 9337, 9337, -1, + 9338, 9338, 9338, -1, 9339, 9339, 9339, -1, + 9340, 9340, 9340, -1, 9341, 9341, 9341, -1, + 9342, 9342, 9342, -1, 9343, 9343, 9343, -1, + 9344, 9344, 9344, -1, 9345, 9345, 9345, -1, + 9346, 9346, 9346, -1, 9347, 9347, 9347, -1, + 9348, 9348, 9348, -1, 9349, 9349, 9349, -1, + 9350, 9350, 9350, -1, 9351, 9351, 9351, -1, + 9352, 9352, 9352, -1, 9353, 9353, 9353, -1, + 9354, 9354, 9354, -1, 9355, 9355, 9355, -1, + 9356, 9356, 9356, -1, 9357, 9357, 9357, -1, + 9358, 9358, 9358, -1, 9359, 9359, 9359, -1, + 9360, 9360, 9360, -1, 9361, 9361, 9361, -1, + 9362, 9362, 9362, -1, 9363, 9363, 9363, -1, + 9364, 9364, 9364, -1, 9365, 9365, 9365, -1, + 9366, 9366, 9366, -1, 9367, 9367, 9367, -1, + 9368, 9368, 9368, -1, 9369, 9369, 9369, -1, + 9370, 9370, 9370, -1, 9371, 9371, 9371, -1, + 9372, 9372, 9372, -1, 9373, 9373, 9373, -1, + 9374, 9374, 9374, -1, 9375, 9375, 9375, -1, + 9376, 9376, 9376, -1, 9377, 9377, 9377, -1, + 9378, 9378, 9378, -1, 9379, 9379, 9379, -1, + 9380, 9380, 9380, -1, 9381, 9381, 9381, -1, + 9382, 9382, 9382, -1, 9383, 9383, 9383, -1, + 9384, 9384, 9384, -1, 9385, 9385, 9385, -1, + 9386, 9386, 9386, -1, 9387, 9387, 9387, -1, + 9388, 9388, 9388, -1, 9389, 9389, 9389, -1, + 9390, 9390, 9390, -1, 9391, 9391, 9391, -1, + 9392, 9392, 9392, -1, 9393, 9393, 9393, -1, + 9394, 9394, 9394, -1, 9395, 9395, 9395, -1, + 9396, 9396, 9396, -1, 9397, 9397, 9397, -1, + 9398, 9398, 9398, -1, 9399, 9399, 9399, -1, + 9400, 9400, 9400, -1, 9401, 9401, 9401, -1, + 9402, 9402, 9402, -1, 9403, 9403, 9403, -1, + 9404, 9404, 9404, -1, 9405, 9405, 9405, -1, + 9406, 9406, 9406, -1, 9407, 9407, 9407, -1, + 9408, 9408, 9408, -1, 9409, 9409, 9409, -1, + 9410, 9410, 9410, -1, 9411, 9411, 9411, -1, + 9412, 9412, 9412, -1, 9413, 9413, 9413, -1, + 9414, 9414, 9414, -1, 9415, 9415, 9415, -1, + 9416, 9416, 9416, -1, 9417, 9417, 9417, -1, + 9418, 9418, 9418, -1, 9419, 9419, 9419, -1, + 9420, 9420, 9420, -1, 9421, 9421, 9421, -1, + 9422, 9422, 9422, -1, 9423, 9423, 9423, -1, + 9424, 9424, 9424, -1, 9425, 9425, 9425, -1, + 9426, 9426, 9426, -1, 9427, 9427, 9427, -1, + 9428, 9428, 9428, -1, 9429, 9429, 9429, -1, + 9430, 9430, 9430, -1, 9431, 9431, 9431, -1, + 9432, 9432, 9432, -1, 9433, 9433, 9433, -1, + 9434, 9434, 9434, -1, 9435, 9435, 9435, -1, + 9436, 9436, 9436, -1, 9437, 9437, 9437, -1, + 9438, 9438, 9438, -1, 9439, 9439, 9439, -1, + 9440, 9440, 9440, -1, 9441, 9441, 9441, -1, + 9442, 9442, 9442, -1, 9443, 9443, 9443, -1, + 9444, 9444, 9444, -1, 9445, 9445, 9445, -1, + 9446, 9446, 9446, -1, 9447, 9447, 9447, -1, + 9448, 9448, 9448, -1, 9449, 9449, 9449, -1, + 9450, 9450, 9450, -1, 9451, 9451, 9451, -1, + 9452, 9452, 9452, -1, 9453, 9453, 9453, -1, + 9454, 9454, 9454, -1, 9455, 9455, 9455, -1, + 9456, 9456, 9456, -1, 9457, 9457, 9457, -1, + 9458, 9458, 9458, -1, 9459, 9459, 9459, -1, + 9460, 9460, 9460, -1, 9461, 9461, 9461, -1, + 9462, 9462, 9462, -1, 9463, 9463, 9463, -1, + 9464, 9464, 9464, -1, 9465, 9465, 9465, -1, + 9466, 9466, 9466, -1, 9467, 9467, 9467, -1, + 9468, 9468, 9468, -1, 9469, 9469, 9469, -1, + 9470, 9470, 9470, -1, 9471, 9471, 9471, -1, + 9472, 9472, 9472, -1, 9473, 9473, 9473, -1, + 9474, 9474, 9474, -1, 9475, 9475, 9475, -1, + 9476, 9476, 9476, -1, 9477, 9477, 9477, -1, + 9478, 9478, 9478, -1, 9479, 9479, 9479, -1, + 9480, 9480, 9480, -1, 9481, 9481, 9481, -1, + 9482, 9482, 9482, -1, 9483, 9483, 9483, -1, + 9484, 9484, 9484, -1, 9485, 9485, 9485, -1, + 9486, 9486, 9486, -1, 9487, 9487, 9487, -1, + 9488, 9488, 9488, -1, 9489, 9489, 9489, -1, + 9490, 9490, 9490, -1, 9491, 9491, 9491, -1, + 9492, 9492, 9492, -1, 9493, 9493, 9493, -1, + 9494, 9494, 9494, -1, 9495, 9495, 9495, -1, + 9496, 9496, 9496, -1, 9497, 9497, 9497, -1, + 9498, 9498, 9498, -1, 9499, 9499, 9499, -1, + 9500, 9500, 9500, -1, 9501, 9501, 9501, -1, + 9502, 9502, 9502, -1, 9503, 9503, 9503, -1, + 9504, 9504, 9504, -1, 9505, 9505, 9505, -1, + 9506, 9506, 9506, -1, 9507, 9507, 9507, -1, + 9508, 9508, 9508, -1, 9509, 9509, 9509, -1, + 9510, 9510, 9510, -1, 9511, 9511, 9511, -1, + 9512, 9512, 9512, -1, 9513, 9513, 9513, -1, + 9514, 9514, 9514, -1, 9515, 9515, 9515, -1, + 9516, 9516, 9516, -1, 9517, 9517, 9517, -1, + 9518, 9518, 9518, -1, 9519, 9519, 9519, -1, + 9520, 9520, 9520, -1, 9521, 9521, 9521, -1, + 9522, 9522, 9522, -1, 9523, 9523, 9523, -1, + 9524, 9524, 9524, -1, 9525, 9525, 9525, -1, + 9526, 9526, 9526, -1, 9527, 9527, 9527, -1, + 9528, 9528, 9528, -1, 9529, 9529, 9529, -1, + 9530, 9530, 9530, -1, 9531, 9531, 9531, -1, + 9532, 9532, 9532, -1, 9533, 9533, 9533, -1, + 9534, 9534, 9534, -1, 9535, 9535, 9535, -1, + 9536, 9536, 9536, -1, 9537, 9537, 9537, -1, + 9538, 9538, 9538, -1, 9539, 9539, 9539, -1, + 9540, 9540, 9540, -1, 9541, 9541, 9541, -1, + 9542, 9542, 9542, -1, 9543, 9543, 9543, -1, + 9544, 9544, 9544, -1, 9545, 9545, 9545, -1, + 9546, 9546, 9546, -1, 9547, 9547, 9547, -1, + 9548, 9548, 9548, -1, 9549, 9549, 9549, -1, + 9550, 9550, 9550, -1, 9551, 9551, 9551, -1, + 9552, 9552, 9552, -1, 9553, 9553, 9553, -1, + 9554, 9554, 9554, -1, 9555, 9555, 9555, -1, + 9556, 9556, 9556, -1, 9557, 9557, 9557, -1, + 9558, 9558, 9558, -1, 9559, 9559, 9559, -1, + 9560, 9560, 9560, -1, 9561, 9561, 9561, -1, + 9562, 9562, 9562, -1, 9563, 9563, 9563, -1, + 9564, 9564, 9564, -1, 9565, 9565, 9565, -1, + 9566, 9566, 9566, -1, 9567, 9567, 9567, -1, + 9568, 9568, 9568, -1, 9569, 9569, 9569, -1, + 9570, 9570, 9570, -1, 9571, 9571, 9571, -1, + 9572, 9572, 9572, -1, 9573, 9573, 9573, -1, + 9574, 9574, 9574, -1, 9575, 9575, 9575, -1, + 9576, 9576, 9576, -1, 9577, 9577, 9577, -1, + 9578, 9578, 9578, -1, 9579, 9579, 9579, -1, + 9580, 9580, 9580, -1, 9581, 9581, 9581, -1, + 9582, 9582, 9582, -1, 9583, 9583, 9583, -1, + 9584, 9584, 9584, -1, 9585, 9585, 9585, -1, + 9586, 9586, 9586, -1, 9587, 9587, 9587, -1, + 9588, 9588, 9588, -1, 9589, 9589, 9589, -1, + 9590, 9590, 9590, -1, 9591, 9591, 9591, -1, + 9592, 9592, 9592, -1, 9593, 9593, 9593, -1, + 9594, 9594, 9594, -1, 9595, 9595, 9595, -1, + 9596, 9596, 9596, -1, 9597, 9597, 9597, -1, + 9598, 9598, 9598, -1, 9599, 9599, 9599, -1, + 9600, 9600, 9600, -1, 9601, 9601, 9601, -1, + 9602, 9602, 9602, -1, 9603, 9603, 9603, -1, + 9604, 9604, 9604, -1, 9605, 9605, 9605, -1, + 9606, 9606, 9606, -1, 9607, 9607, 9607, -1, + 9608, 9608, 9608, -1, 9609, 9609, 9609, -1, + 9610, 9610, 9610, -1, 9611, 9611, 9611, -1, + 9612, 9612, 9612, -1, 9613, 9613, 9613, -1, + 9614, 9614, 9614, -1, 9615, 9615, 9615, -1, + 9616, 9616, 9616, -1, 9617, 9617, 9617, -1, + 9618, 9618, 9618, -1, 9619, 9619, 9619, -1, + 9620, 9620, 9620, -1, 9621, 9621, 9621, -1, + 9622, 9622, 9622, -1, 9623, 9623, 9623, -1, + 9624, 9624, 9624, -1, 9625, 9625, 9625, -1, + 9626, 9626, 9626, -1, 9627, 9627, 9627, -1, + 9628, 9628, 9628, -1, 9629, 9629, 9629, -1, + 9630, 9630, 9630, -1, 9631, 9631, 9631, -1, + 9632, 9632, 9632, -1, 9633, 9633, 9633, -1, + 9634, 9634, 9634, -1, 9635, 9635, 9635, -1, + 9636, 9636, 9636, -1, 9637, 9637, 9637, -1, + 9638, 9638, 9638, -1, 9639, 9639, 9639, -1, + 9640, 9640, 9640, -1, 9641, 9641, 9641, -1, + 9642, 9642, 9642, -1, 9643, 9643, 9643, -1, + 9644, 9644, 9644, -1, 9645, 9645, 9645, -1, + 9646, 9646, 9646, -1, 9647, 9647, 9647, -1, + 9648, 9648, 9648, -1, 9649, 9649, 9649, -1, + 9650, 9650, 9650, -1, 9651, 9651, 9651, -1, + 9652, 9652, 9652, -1, 9653, 9653, 9653, -1, + 9654, 9654, 9654, -1, 9655, 9655, 9655, -1, + 9656, 9656, 9656, -1, 9657, 9657, 9657, -1, + 9658, 9658, 9658, -1, 9659, 9659, 9659, -1, + 9660, 9660, 9660, -1, 9661, 9661, 9661, -1, + 9662, 9662, 9662, -1, 9663, 9663, 9663, -1, + 9664, 9664, 9664, -1, 9665, 9665, 9665, -1, + 9666, 9666, 9666, -1, 9667, 9667, 9667, -1, + 9668, 9668, 9668, -1, 9669, 9669, 9669, -1, + 9670, 9670, 9670, -1, 9671, 9671, 9671, -1, + 9672, 9672, 9672, -1, 9673, 9673, 9673, -1, + 9674, 9674, 9674, -1, 9675, 9675, 9675, -1, + 9676, 9676, 9676, -1, 9677, 9677, 9677, -1, + 9678, 9678, 9678, -1, 9679, 9679, 9679, -1, + 9680, 9680, 9680, -1, 9681, 9681, 9681, -1, + 9682, 9682, 9682, -1, 9683, 9683, 9683, -1, + 9684, 9684, 9684, -1, 9685, 9685, 9685, -1, + 9686, 9686, 9686, -1, 9687, 9687, 9687, -1, + 9688, 9688, 9688, -1, 9689, 9689, 9689, -1, + 9690, 9690, 9690, -1, 9691, 9691, 9691, -1, + 9692, 9692, 9692, -1, 9693, 9693, 9693, -1, + 9694, 9694, 9694, -1, 9695, 9695, 9695, -1, + 9696, 9696, 9696, -1, 9697, 9697, 9697, -1, + 9698, 9698, 9698, -1, 9699, 9699, 9699, -1, + 9700, 9700, 9700, -1, 9701, 9701, 9701, -1, + 9702, 9702, 9702, -1, 9703, 9703, 9703, -1, + 9704, 9704, 9704, -1, 9705, 9705, 9705, -1, + 9706, 9706, 9706, -1, 9707, 9707, 9707, -1, + 9708, 9708, 9708, -1, 9709, 9709, 9709, -1, + 9710, 9710, 9710, -1, 9711, 9711, 9711, -1, + 9712, 9712, 9712, -1, 9713, 9713, 9713, -1, + 9714, 9714, 9714, -1, 9715, 9715, 9715, -1, + 9716, 9716, 9716, -1, 9717, 9717, 9717, -1, + 9718, 9718, 9718, -1, 9719, 9719, 9719, -1, + 9720, 9720, 9720, -1, 9721, 9721, 9721, -1, + 9722, 9722, 9722, -1, 9723, 9723, 9723, -1, + 9724, 9724, 9724, -1, 9725, 9725, 9725, -1, + 9726, 9726, 9726, -1, 9727, 9727, 9727, -1, + 9728, 9728, 9728, -1, 9729, 9729, 9729, -1, + 9730, 9730, 9730, -1, 9731, 9731, 9731, -1, + 9732, 9732, 9732, -1, 9733, 9733, 9733, -1, + 9734, 9734, 9734, -1, 9735, 9735, 9735, -1, + 9736, 9736, 9736, -1, 9737, 9737, 9737, -1, + 9738, 9738, 9738, -1, 9739, 9739, 9739, -1, + 9740, 9740, 9740, -1, 9741, 9741, 9741, -1, + 9742, 9742, 9742, -1, 9743, 9743, 9743, -1, + 9744, 9744, 9744, -1, 9745, 9745, 9745, -1, + 9746, 9746, 9746, -1, 9747, 9747, 9747, -1, + 9748, 9748, 9748, -1, 9749, 9749, 9749, -1, + 9750, 9750, 9750, -1, 9751, 9751, 9751, -1, + 9752, 9752, 9752, -1, 9753, 9753, 9753, -1, + 9754, 9754, 9754, -1, 9755, 9755, 9755, -1, + 9756, 9756, 9756, -1, 9757, 9757, 9757, -1, + 9758, 9758, 9758, -1, 9759, 9759, 9759, -1, + 9760, 9760, 9760, -1, 9761, 9761, 9761, -1, + 9762, 9762, 9762, -1, 9763, 9763, 9763, -1, + 9764, 9764, 9764, -1, 9765, 9765, 9765, -1, + 9766, 9766, 9766, -1, 9767, 9767, 9767, -1, + 9768, 9768, 9768, -1, 9769, 9769, 9769, -1, + 9770, 9770, 9770, -1, 9771, 9771, 9771, -1, + 9772, 9772, 9772, -1, 9773, 9773, 9773, -1, + 9774, 9774, 9774, -1, 9775, 9775, 9775, -1, + 9776, 9776, 9776, -1, 9777, 9777, 9777, -1, + 9778, 9778, 9778, -1, 9779, 9779, 9779, -1, + 9780, 9780, 9780, -1, 9781, 9781, 9781, -1, + 9782, 9782, 9782, -1, 9783, 9783, 9783, -1, + 9784, 9784, 9784, -1, 9785, 9785, 9785, -1, + 9786, 9786, 9786, -1, 9787, 9787, 9787, -1, + 9788, 9788, 9788, -1, 9789, 9789, 9789, -1, + 9790, 9790, 9790, -1, 9791, 9791, 9791, -1, + 9792, 9792, 9792, -1, 9793, 9793, 9793, -1, + 9794, 9794, 9794, -1, 9795, 9795, 9795, -1, + 9796, 9796, 9796, -1, 9797, 9797, 9797, -1, + 9798, 9798, 9798, -1, 9799, 9799, 9799, -1, + 9800, 9800, 9800, -1, 9801, 9801, 9801, -1, + 9802, 9802, 9802, -1, 9803, 9803, 9803, -1, + 9804, 9804, 9804, -1, 9805, 9805, 9805, -1, + 9806, 9806, 9806, -1, 9807, 9807, 9807, -1, + 9808, 9808, 9808, -1, 9809, 9809, 9809, -1, + 9810, 9810, 9810, -1, 9811, 9811, 9811, -1, + 9812, 9812, 9812, -1, 9813, 9813, 9813, -1, + 9814, 9814, 9814, -1, 9815, 9815, 9815, -1, + 9816, 9816, 9816, -1, 9817, 9817, 9817, -1, + 9818, 9818, 9818, -1, 9819, 9819, 9819, -1, + 9820, 9820, 9820, -1, 9821, 9821, 9821, -1, + 9822, 9822, 9822, -1, 9823, 9823, 9823, -1, + 9824, 9824, 9824, -1, 9825, 9825, 9825, -1, + 9826, 9826, 9826, -1, 9827, 9827, 9827, -1, + 9828, 9828, 9828, -1, 9829, 9829, 9829, -1, + 9830, 9830, 9830, -1, 9831, 9831, 9831, -1, + 9832, 9832, 9832, -1, 9833, 9833, 9833, -1, + 9834, 9834, 9834, -1, 9835, 9835, 9835, -1, + 9836, 9836, 9836, -1, 9837, 9837, 9837, -1, + 9838, 9838, 9838, -1, 9839, 9839, 9839, -1, + 9840, 9840, 9840, -1, 9841, 9841, 9841, -1, + 9842, 9842, 9842, -1, 9843, 9843, 9843, -1, + 9844, 9844, 9844, -1, 9845, 9845, 9845, -1, + 9846, 9846, 9846, -1, 9847, 9847, 9847, -1, + 9848, 9848, 9848, -1, 9849, 9849, 9849, -1, + 9850, 9850, 9850, -1, 9851, 9851, 9851, -1, + 9852, 9852, 9852, -1, 9853, 9853, 9853, -1, + 9854, 9854, 9854, -1, 9855, 9855, 9855, -1, + 9856, 9856, 9856, -1, 9857, 9857, 9857, -1, + 9858, 9858, 9858, -1, 9859, 9859, 9859, -1, + 9860, 9860, 9860, -1, 9861, 9861, 9861, -1, + 9862, 9862, 9862, -1, 9863, 9863, 9863, -1, + 9864, 9864, 9864, -1, 9865, 9865, 9865, -1, + 9866, 9866, 9866, -1, 9867, 9867, 9867, -1, + 9868, 9868, 9868, -1, 9869, 9869, 9869, -1, + 9870, 9870, 9870, -1, 9871, 9871, 9871, -1, + 9872, 9872, 9872, -1, 9873, 9873, 9873, -1, + 9874, 9874, 9874, -1, 9875, 9875, 9875, -1, + 9876, 9876, 9876, -1, 9877, 9877, 9877, -1, + 9878, 9878, 9878, -1, 9879, 9879, 9879, -1, + 9880, 9880, 9880, -1, 9881, 9881, 9881, -1, + 9882, 9882, 9882, -1, 9883, 9883, 9883, -1, + 9884, 9884, 9884, -1, 9885, 9885, 9885, -1, + 9886, 9886, 9886, -1, 9887, 9887, 9887, -1, + 9888, 9888, 9888, -1, 9889, 9889, 9889, -1, + 9890, 9890, 9890, -1, 9891, 9891, 9891, -1, + 9892, 9892, 9892, -1, 9893, 9893, 9893, -1, + 9894, 9894, 9894, -1, 9895, 9895, 9895, -1, + 9896, 9896, 9896, -1, 9897, 9897, 9897, -1, + 9898, 9898, 9898, -1, 9899, 9899, 9899, -1, + 9900, 9900, 9900, -1, 9901, 9901, 9901, -1, + 9902, 9902, 9902, -1, 9903, 9903, 9903, -1, + 9904, 9904, 9904, -1, 9905, 9905, 9905, -1, + 9906, 9906, 9906, -1, 9907, 9907, 9907, -1, + 9908, 9908, 9908, -1, 9909, 9909, 9909, -1, + 9910, 9910, 9910, -1, 9911, 9911, 9911, -1, + 9912, 9912, 9912, -1, 9913, 9913, 9913, -1, + 9914, 9914, 9914, -1, 9915, 9915, 9915, -1, + 9916, 9916, 9916, -1, 9917, 9917, 9917, -1, + 9918, 9918, 9918, -1, 9919, 9919, 9919, -1, + 9920, 9920, 9920, -1, 9921, 9921, 9921, -1, + 9922, 9922, 9922, -1, 9923, 9923, 9923, -1, + 9924, 9924, 9924, -1, 9925, 9925, 9925, -1, + 9926, 9926, 9926, -1, 9927, 9927, 9927, -1, + 9928, 9928, 9928, -1, 9929, 9929, 9929, -1, + 9930, 9930, 9930, -1, 9931, 9931, 9931, -1, + 9932, 9932, 9932, -1, 9933, 9933, 9933, -1, + 9934, 9934, 9934, -1, 9935, 9935, 9935, -1, + 9936, 9936, 9936, -1, 9937, 9937, 9937, -1, + 9938, 9938, 9938, -1, 9939, 9939, 9939, -1, + 9940, 9940, 9940, -1, 9941, 9941, 9941, -1, + 9942, 9942, 9942, -1, 9943, 9943, 9943, -1, + 9944, 9944, 9944, -1, 9945, 9945, 9945, -1, + 9946, 9946, 9946, -1, 9947, 9947, 9947, -1, + 9948, 9948, 9948, -1, 9949, 9949, 9949, -1, + 9950, 9950, 9950, -1, 9951, 9951, 9951, -1, + 9952, 9952, 9952, -1, 9953, 9953, 9953, -1, + 9954, 9954, 9954, -1, 9955, 9955, 9955, -1, + 9956, 9956, 9956, -1, 9957, 9957, 9957, -1, + 9958, 9958, 9958, -1, 9959, 9959, 9959, -1, + 9960, 9960, 9960, -1, 9961, 9961, 9961, -1, + 9962, 9962, 9962, -1, 9963, 9963, 9963, -1, + 9964, 9964, 9964, -1, 9965, 9965, 9965, -1, + 9966, 9966, 9966, -1, 9967, 9967, 9967, -1, + 9968, 9968, 9968, -1, 9969, 9969, 9969, -1, + 9970, 9970, 9970, -1, 9971, 9971, 9971, -1, + 9972, 9972, 9972, -1, 9973, 9973, 9973, -1, + 9974, 9974, 9974, -1, 9975, 9975, 9975, -1, + 9976, 9976, 9976, -1, 9977, 9977, 9977, -1, + 9978, 9978, 9978, -1, 9979, 9979, 9979, -1, + 9980, 9980, 9980, -1, 9981, 9981, 9981, -1, + 9982, 9982, 9982, -1, 9983, 9983, 9983, -1, + 9984, 9984, 9984, -1, 9985, 9985, 9985, -1, + 9986, 9986, 9986, -1, 9987, 9987, 9987, -1, + 9988, 9988, 9988, -1, 9989, 9989, 9989, -1, + 9990, 9990, 9990, -1, 9991, 9991, 9991, -1, + 9992, 9992, 9992, -1, 9993, 9993, 9993, -1, + 9994, 9994, 9994, -1, 9995, 9995, 9995, -1, + 9996, 9996, 9996, -1, 9997, 9997, 9997, -1, + 9998, 9998, 9998, -1, 9999, 9999, 9999, -1, + 10000, 10000, 10000, -1, 10001, 10001, 10001, -1, + 10002, 10002, 10002, -1, 10003, 10003, 10003, -1, + 10004, 10004, 10004, -1, 10005, 10005, 10005, -1, + 10006, 10006, 10006, -1, 10007, 10007, 10007, -1, + 10008, 10008, 10008, -1, 10009, 10009, 10009, -1, + 10010, 10010, 10010, -1, 10011, 10011, 10011, -1, + 10012, 10012, 10012, -1, 10013, 10013, 10013, -1, + 10014, 10014, 10014, -1, 10015, 10015, 10015, -1, + 10016, 10016, 10016, -1, 10017, 10017, 10017, -1, + 10018, 10018, 10018, -1, 10019, 10019, 10019, -1, + 10020, 10020, 10020, -1, 10021, 10021, 10021, -1, + 10022, 10022, 10022, -1, 10023, 10023, 10023, -1, + 10024, 10024, 10024, -1, 10025, 10025, 10025, -1, + 10026, 10026, 10026, -1, 10027, 10027, 10027, -1, + 10028, 10028, 10028, -1, 10029, 10029, 10029, -1, + 10030, 10030, 10030, -1, 10031, 10031, 10031, -1, + 10032, 10032, 10032, -1, 10033, 10033, 10033, -1, + 10034, 10034, 10034, -1, 10035, 10035, 10035, -1, + 10036, 10036, 10036, -1, 10037, 10037, 10037, -1, + 10038, 10038, 10038, -1, 10039, 10039, 10039, -1, + 10040, 10040, 10040, -1, 10041, 10041, 10041, -1, + 10042, 10042, 10042, -1, 10043, 10043, 10043, -1, + 10044, 10044, 10044, -1, 10045, 10045, 10045, -1, + 10046, 10046, 10046, -1, 10047, 10047, 10047, -1, + 10048, 10048, 10048, -1, 10049, 10049, 10049, -1, + 10050, 10050, 10050, -1, 10051, 10051, 10051, -1, + 10052, 10052, 10052, -1, 10053, 10053, 10053, -1, + 10054, 10054, 10054, -1, 10055, 10055, 10055, -1, + 10056, 10056, 10056, -1, 10057, 10057, 10057, -1, + 10058, 10058, 10058, -1, 10059, 10059, 10059, -1, + 10060, 10060, 10060, -1, 10061, 10061, 10061, -1, + 10062, 10062, 10062, -1, 10063, 10063, 10063, -1, + 10064, 10064, 10064, -1, 10065, 10065, 10065, -1, + 10066, 10066, 10066, -1, 10067, 10067, 10067, -1, + 10068, 10068, 10068, -1, 10069, 10069, 10069, -1, + 10070, 10070, 10070, -1, 10071, 10071, 10071, -1, + 10072, 10072, 10072, -1, 10073, 10073, 10073, -1, + 10074, 10074, 10074, -1, 10075, 10075, 10075, -1, + 10076, 10076, 10076, -1, 10077, 10077, 10077, -1, + 10078, 10078, 10078, -1, 10079, 10079, 10079, -1, + 10080, 10080, 10080, -1, 10081, 10081, 10081, -1, + 10082, 10082, 10082, -1, 10083, 10083, 10083, -1, + 10084, 10084, 10084, -1, 10085, 10085, 10085, -1, + 10086, 10086, 10086, -1, 10087, 10087, 10087, -1, + 10088, 10088, 10088, -1, 10089, 10089, 10089, -1, + 10090, 10090, 10090, -1, 10091, 10091, 10091, -1, + 10092, 10092, 10092, -1, 10093, 10093, 10093, -1, + 10094, 10094, 10094, -1, 10095, 10095, 10095, -1, + 10096, 10096, 10096, -1, 10097, 10097, 10097, -1, + 10098, 10098, 10098, -1, 10099, 10099, 10099, -1, + 10100, 10100, 10100, -1, 10101, 10101, 10101, -1, + 10102, 10102, 10102, -1, 10103, 10103, 10103, -1, + 10104, 10104, 10104, -1, 10105, 10105, 10105, -1, + 10106, 10106, 10106, -1, 10107, 10107, 10107, -1, + 10108, 10108, 10108, -1, 10109, 10109, 10109, -1, + 10110, 10110, 10110, -1, 10111, 10111, 10111, -1, + 10112, 10112, 10112, -1, 10113, 10113, 10113, -1, + 10114, 10114, 10114, -1, 10115, 10115, 10115, -1, + 10116, 10116, 10116, -1, 10117, 10117, 10117, -1, + 10118, 10118, 10118, -1, 10119, 10119, 10119, -1, + 10120, 10120, 10120, -1, 10121, 10121, 10121, -1, + 10122, 10122, 10122, -1, 10123, 10123, 10123, -1, + 10124, 10124, 10124, -1, 10125, 10125, 10125, -1, + 10126, 10126, 10126, -1, 10127, 10127, 10127, -1, + 10128, 10128, 10128, -1, 10129, 10129, 10129, -1, + 10130, 10130, 10130, -1, 10131, 10131, 10131, -1, + 10132, 10132, 10132, -1, 10133, 10133, 10133, -1, + 10134, 10134, 10134, -1, 10135, 10135, 10135, -1, + 10136, 10136, 10136, -1, 10137, 10137, 10137, -1, + 10138, 10138, 10138, -1, 10139, 10139, 10139, -1, + 10140, 10140, 10140, -1, 10141, 10141, 10141, -1, + 10142, 10142, 10142, -1, 10143, 10143, 10143, -1, + 10144, 10144, 10144, -1, 10145, 10145, 10145, -1, + 10146, 10146, 10146, -1, 10147, 10147, 10147, -1, + 10148, 10148, 10148, -1, 10149, 10149, 10149, -1, + 10150, 10150, 10150, -1, 10151, 10151, 10151, -1, + 10152, 10152, 10152, -1, 10153, 10153, 10153, -1, + 10154, 10154, 10154, -1, 10155, 10155, 10155, -1, + 10156, 10156, 10156, -1, 10157, 10157, 10157, -1, + 10158, 10158, 10158, -1, 10159, 10159, 10159, -1, + 10160, 10160, 10160, -1, 10161, 10161, 10161, -1, + 10162, 10162, 10162, -1, 10163, 10163, 10163, -1, + 10164, 10164, 10164, -1, 10165, 10165, 10165, -1, + 10166, 10166, 10166, -1, 10167, 10167, 10167, -1, + 10168, 10168, 10168, -1, 10169, 10169, 10169, -1, + 10170, 10170, 10170, -1, 10171, 10171, 10171, -1, + 10172, 10172, 10172, -1, 10173, 10173, 10173, -1, + 10174, 10174, 10174, -1, 10175, 10175, 10175, -1, + 10176, 10176, 10176, -1, 10177, 10177, 10177, -1, + 10178, 10178, 10178, -1, 10179, 10179, 10179, -1, + 10180, 10180, 10180, -1, 10181, 10181, 10181, -1, + 10182, 10182, 10182, -1, 10183, 10183, 10183, -1, + 10184, 10184, 10184, -1, 10185, 10185, 10185, -1, + 10186, 10186, 10186, -1, 10187, 10187, 10187, -1, + 10188, 10188, 10188, -1, 10189, 10189, 10189, -1, + 10190, 10190, 10190, -1, 10191, 10191, 10191, -1, + 10192, 10192, 10192, -1, 10193, 10193, 10193, -1, + 10194, 10194, 10194, -1, 10195, 10195, 10195, -1, + 10196, 10196, 10196, -1, 10197, 10197, 10197, -1, + 10198, 10198, 10198, -1, 10199, 10199, 10199, -1, + 10200, 10200, 10200, -1, 10201, 10201, 10201, -1, + 10202, 10202, 10202, -1, 10203, 10203, 10203, -1, + 10204, 10204, 10204, -1, 10205, 10205, 10205, -1, + 10206, 10206, 10206, -1, 10207, 10207, 10207, -1, + 10208, 10208, 10208, -1, 10209, 10209, 10209, -1, + 10210, 10210, 10210, -1, 10211, 10211, 10211, -1, + 10212, 10212, 10212, -1, 10213, 10213, 10213, -1, + 10214, 10214, 10214, -1, 10215, 10215, 10215, -1, + 10216, 10216, 10216, -1, 10217, 10217, 10217, -1, + 10218, 10218, 10218, -1, 10219, 10219, 10219, -1, + 10220, 10220, 10220, -1, 10221, 10221, 10221, -1, + 10222, 10222, 10222, -1, 10223, 10223, 10223, -1, + 10224, 10224, 10224, -1, 10225, 10225, 10225, -1, + 10226, 10226, 10226, -1, 10227, 10227, 10227, -1, + 10228, 10228, 10228, -1, 10229, 10229, 10229, -1, + 10230, 10230, 10230, -1, 10231, 10231, 10231, -1, + 10232, 10232, 10232, -1, 10233, 10233, 10233, -1, + 10234, 10234, 10234, -1, 10235, 10235, 10235, -1, + 10236, 10236, 10236, -1, 10237, 10237, 10237, -1, + 10238, 10238, 10238, -1, 10239, 10239, 10239, -1, + 10240, 10240, 10240, -1, 10241, 10241, 10241, -1, + 10242, 10242, 10242, -1, 10243, 10243, 10243, -1, + 10244, 10244, 10244, -1, 10245, 10245, 10245, -1, + 10246, 10246, 10246, -1, 10247, 10247, 10247, -1, + 10248, 10248, 10248, -1, 10249, 10249, 10249, -1, + 10250, 10250, 10250, -1, 10251, 10251, 10251, -1, + 10252, 10252, 10252, -1, 10253, 10253, 10253, -1, + 10254, 10254, 10254, -1, 10255, 10255, 10255, -1, + 10256, 10256, 10256, -1, 10257, 10257, 10257, -1, + 10258, 10258, 10258, -1, 10259, 10259, 10259, -1, + 10260, 10260, 10260, -1, 10261, 10261, 10261, -1, + 10262, 10262, 10262, -1, 10263, 10263, 10263, -1, + 10264, 10264, 10264, -1, 10265, 10265, 10265, -1, + 10266, 10266, 10266, -1, 10267, 10267, 10267, -1, + 10268, 10268, 10268, -1, 10269, 10269, 10269, -1, + 10270, 10270, 10270, -1, 10271, 10271, 10271, -1, + 10272, 10272, 10272, -1, 10273, 10273, 10273, -1, + 10274, 10274, 10274, -1, 10275, 10275, 10275, -1, + 10276, 10276, 10276, -1, 10277, 10277, 10277, -1, + 10278, 10278, 10278, -1, 10279, 10279, 10279, -1, + 10280, 10280, 10280, -1, 10281, 10281, 10281, -1, + 10282, 10282, 10282, -1, 10283, 10283, 10283, -1, + 10284, 10284, 10284, -1, 10285, 10285, 10285, -1, + 10286, 10286, 10286, -1, 10287, 10287, 10287, -1, + 10288, 10288, 10288, -1, 10289, 10289, 10289, -1, + 10290, 10290, 10290, -1, 10291, 10291, 10291, -1, + 10292, 10292, 10292, -1, 10293, 10293, 10293, -1, + 10294, 10294, 10294, -1, 10295, 10295, 10295, -1, + 10296, 10296, 10296, -1, 10297, 10297, 10297, -1, + 10298, 10298, 10298, -1, 10299, 10299, 10299, -1, + 10300, 10300, 10300, -1, 10301, 10301, 10301, -1, + 10302, 10302, 10302, -1, 10303, 10303, 10303, -1, + 10304, 10304, 10304, -1, 10305, 10305, 10305, -1, + 10306, 10306, 10306, -1, 10307, 10307, 10307, -1, + 10308, 10308, 10308, -1, 10309, 10309, 10309, -1, + 10310, 10310, 10310, -1, 10311, 10311, 10311, -1, + 10312, 10312, 10312, -1, 10313, 10313, 10313, -1, + 10314, 10314, 10314, -1, 10315, 10315, 10315, -1, + 10316, 10316, 10316, -1, 10317, 10317, 10317, -1, + 10318, 10318, 10318, -1, 10319, 10319, 10319, -1, + 10320, 10320, 10320, -1, 10321, 10321, 10321, -1, + 10322, 10322, 10322, -1, 10323, 10323, 10323, -1, + 10324, 10324, 10324, -1, 10325, 10325, 10325, -1, + 10326, 10326, 10326, -1, 10327, 10327, 10327, -1, + 10328, 10328, 10328, -1, 10329, 10329, 10329, -1, + 10330, 10330, 10330, -1, 10331, 10331, 10331, -1, + 10332, 10332, 10332, -1, 10333, 10333, 10333, -1, + 10334, 10334, 10334, -1, 10335, 10335, 10335, -1, + 10336, 10336, 10336, -1, 10337, 10337, 10337, -1, + 10338, 10338, 10338, -1, 10339, 10339, 10339, -1, + 10340, 10340, 10340, -1, 10341, 10341, 10341, -1, + 10342, 10342, 10342, -1, 10343, 10343, 10343, -1, + 10344, 10344, 10344, -1, 10345, 10345, 10345, -1, + 10346, 10346, 10346, -1, 10347, 10347, 10347, -1, + 10348, 10348, 10348, -1, 10349, 10349, 10349, -1, + 10350, 10350, 10350, -1, 10351, 10351, 10351, -1, + 10352, 10352, 10352, -1, 10353, 10353, 10353, -1, + 10354, 10354, 10354, -1, 10355, 10355, 10355, -1, + 10356, 10356, 10356, -1, 10357, 10357, 10357, -1, + 10358, 10358, 10358, -1, 10359, 10359, 10359, -1, + 10360, 10360, 10360, -1, 10361, 10361, 10361, -1, + 10362, 10362, 10362, -1, 10363, 10363, 10363, -1, + 10364, 10364, 10364, -1, 10365, 10365, 10365, -1, + 10366, 10366, 10366, -1, 10367, 10367, 10367, -1, + 10368, 10368, 10368, -1, 10369, 10369, 10369, -1, + 10370, 10370, 10370, -1, 10371, 10371, 10371, -1, + 10372, 10372, 10372, -1, 10373, 10373, 10373, -1, + 10374, 10374, 10374, -1, 10375, 10375, 10375, -1, + 10376, 10376, 10376, -1, 10377, 10377, 10377, -1, + 10378, 10378, 10378, -1, 10379, 10379, 10379, -1, + 10380, 10380, 10380, -1, 10381, 10381, 10381, -1, + 10382, 10382, 10382, -1, 10383, 10383, 10383, -1, + 10384, 10384, 10384, -1, 10385, 10385, 10385, -1, + 10386, 10386, 10386, -1, 10387, 10387, 10387, -1, + 10388, 10388, 10388, -1, 10389, 10389, 10389, -1, + 10390, 10390, 10390, -1, 10391, 10391, 10391, -1, + 10392, 10392, 10392, -1, 10393, 10393, 10393, -1, + 10394, 10394, 10394, -1, 10395, 10395, 10395, -1, + 10396, 10396, 10396, -1, 10397, 10397, 10397, -1, + 10398, 10398, 10398, -1, 10399, 10399, 10399, -1, + 10400, 10400, 10400, -1, 10401, 10401, 10401, -1, + 10402, 10402, 10402, -1, 10403, 10403, 10403, -1, + 10404, 10404, 10404, -1, 10405, 10405, 10405, -1, + 10406, 10406, 10406, -1, 10407, 10407, 10407, -1, + 10408, 10408, 10408, -1, 10409, 10409, 10409, -1, + 10410, 10410, 10410, -1, 10411, 10411, 10411, -1, + 10412, 10412, 10412, -1, 10413, 10413, 10413, -1, + 10414, 10414, 10414, -1, 10415, 10415, 10415, -1, + 10416, 10416, 10416, -1, 10417, 10417, 10417, -1, + 10418, 10418, 10418, -1, 10419, 10419, 10419, -1, + 10420, 10420, 10420, -1, 10421, 10421, 10421, -1, + 10422, 10422, 10422, -1, 10423, 10423, 10423, -1, + 10424, 10424, 10424, -1, 10425, 10425, 10425, -1, + 10426, 10426, 10426, -1, 10427, 10427, 10427, -1, + 10428, 10428, 10428, -1, 10429, 10429, 10429, -1, + 10430, 10430, 10430, -1, 10431, 10431, 10431, -1, + 10432, 10432, 10432, -1, 10433, 10433, 10433, -1, + 10434, 10434, 10434, -1, 10435, 10435, 10435, -1, + 10436, 10436, 10436, -1, 10437, 10437, 10437, -1, + 10438, 10438, 10438, -1, 10439, 10439, 10439, -1, + 10440, 10440, 10440, -1, 10441, 10441, 10441, -1, + 10442, 10442, 10442, -1, 10443, 10443, 10443, -1, + 10444, 10444, 10444, -1, 10445, 10445, 10445, -1, + 10446, 10446, 10446, -1, 10447, 10447, 10447, -1, + 10448, 10448, 10448, -1, 10449, 10449, 10449, -1, + 10450, 10450, 10450, -1, 10451, 10451, 10451, -1, + 10452, 10452, 10452, -1, 10453, 10453, 10453, -1, + 10454, 10454, 10454, -1, 10455, 10455, 10455, -1, + 10456, 10456, 10456, -1, 10457, 10457, 10457, -1, + 10458, 10458, 10458, -1, 10459, 10459, 10459, -1, + 10460, 10460, 10460, -1, 10461, 10461, 10461, -1, + 10462, 10462, 10462, -1, 10463, 10463, 10463, -1, + 10464, 10464, 10464, -1, 10465, 10465, 10465, -1, + 10466, 10466, 10466, -1, 10467, 10467, 10467, -1, + 10468, 10468, 10468, -1, 10469, 10469, 10469, -1, + 10470, 10470, 10470, -1, 10471, 10471, 10471, -1, + 10472, 10472, 10472, -1, 10473, 10473, 10473, -1, + 10474, 10474, 10474, -1, 10475, 10475, 10475, -1, + 10476, 10476, 10476, -1, 10477, 10477, 10477, -1, + 10478, 10478, 10478, -1, 10479, 10479, 10479, -1, + 10480, 10480, 10480, -1, 10481, 10481, 10481, -1, + 10482, 10482, 10482, -1, 10483, 10483, 10483, -1, + 10484, 10484, 10484, -1, 10485, 10485, 10485, -1, + 10486, 10486, 10486, -1, 10487, 10487, 10487, -1, + 10488, 10488, 10488, -1, 10489, 10489, 10489, -1, + 10490, 10490, 10490, -1, 10491, 10491, 10491, -1, + 10492, 10492, 10492, -1, 10493, 10493, 10493, -1, + 10494, 10494, 10494, -1, 10495, 10495, 10495, -1, + 10496, 10496, 10496, -1, 10497, 10497, 10497, -1, + 10498, 10498, 10498, -1, 10499, 10499, 10499, -1, + 10500, 10500, 10500, -1, 10501, 10501, 10501, -1, + 10502, 10502, 10502, -1, 10503, 10503, 10503, -1, + 10504, 10504, 10504, -1, 10505, 10505, 10505, -1, + 10506, 10506, 10506, -1, 10507, 10507, 10507, -1, + 10508, 10508, 10508, -1, 10509, 10509, 10509, -1, + 10510, 10510, 10510, -1, 10511, 10511, 10511, -1, + 10512, 10512, 10512, -1, 10513, 10513, 10513, -1, + 10514, 10514, 10514, -1, 10515, 10515, 10515, -1, + 10516, 10516, 10516, -1, 10517, 10517, 10517, -1, + 10518, 10518, 10518, -1, 10519, 10519, 10519, -1, + 10520, 10520, 10520, -1, 10521, 10521, 10521, -1, + 10522, 10522, 10522, -1, 10523, 10523, 10523, -1, + 10524, 10524, 10524, -1, 10525, 10525, 10525, -1, + 10526, 10526, 10526, -1, 10527, 10527, 10527, -1, + 10528, 10528, 10528, -1, 10529, 10529, 10529, -1, + 10530, 10530, 10530, -1, 10531, 10531, 10531, -1, + 10532, 10532, 10532, -1, 10533, 10533, 10533, -1, + 10534, 10534, 10534, -1, 10535, 10535, 10535, -1, + 10536, 10536, 10536, -1, 10537, 10537, 10537, -1, + 10538, 10538, 10538, -1, 10539, 10539, 10539, -1, + 10540, 10540, 10540, -1, 10541, 10541, 10541, -1, + 10542, 10542, 10542, -1, 10543, 10543, 10543, -1, + 10544, 10544, 10544, -1, 10545, 10545, 10545, -1, + 10546, 10546, 10546, -1, 10547, 10547, 10547, -1, + 10548, 10548, 10548, -1, 10549, 10549, 10549, -1, + 10550, 10550, 10550, -1, 10551, 10551, 10551, -1, + 10552, 10552, 10552, -1, 10553, 10553, 10553, -1, + 10554, 10554, 10554, -1, 10555, 10555, 10555, -1, + 10556, 10556, 10556, -1, 10557, 10557, 10557, -1, + 10558, 10558, 10558, -1, 10559, 10559, 10559, -1, + 10560, 10560, 10560, -1, 10561, 10561, 10561, -1, + 10562, 10562, 10562, -1, 10563, 10563, 10563, -1, + 10564, 10564, 10564, -1, 10565, 10565, 10565, -1, + 10566, 10566, 10566, -1, 10567, 10567, 10567, -1, + 10568, 10568, 10568, -1, 10569, 10569, 10569, -1, + 10570, 10570, 10570, -1, 10571, 10571, 10571, -1, + 10572, 10572, 10572, -1, 10573, 10573, 10573, -1, + 10574, 10574, 10574, -1, 10575, 10575, 10575, -1, + 10576, 10576, 10576, -1, 10577, 10577, 10577, -1, + 10578, 10578, 10578, -1, 10579, 10579, 10579, -1, + 10580, 10580, 10580, -1, 10581, 10581, 10581, -1, + 10582, 10582, 10582, -1, 10583, 10583, 10583, -1, + 10584, 10584, 10584, -1, 10585, 10585, 10585, -1, + 10586, 10586, 10586, -1, 10587, 10587, 10587, -1, + 10588, 10588, 10588, -1, 10589, 10589, 10589, -1, + 10590, 10590, 10590, -1, 10591, 10591, 10591, -1, + 10592, 10592, 10592, -1, 10593, 10593, 10593, -1, + 10594, 10594, 10594, -1, 10595, 10595, 10595, -1, + 10596, 10596, 10596, -1, 10597, 10597, 10597, -1, + 10598, 10598, 10598, -1, 10599, 10599, 10599, -1, + 10600, 10600, 10600, -1, 10601, 10601, 10601, -1, + 10602, 10602, 10602, -1, 10603, 10603, 10603, -1, + 10604, 10604, 10604, -1, 10605, 10605, 10605, -1, + 10606, 10606, 10606, -1, 10607, 10607, 10607, -1, + 10608, 10608, 10608, -1, 10609, 10609, 10609, -1, + 10610, 10610, 10610, -1, 10611, 10611, 10611, -1, + 10612, 10612, 10612, -1, 10613, 10613, 10613, -1, + 10614, 10614, 10614, -1, 10615, 10615, 10615, -1, + 10616, 10616, 10616, -1, 10617, 10617, 10617, -1, + 10618, 10618, 10618, -1, 10619, 10619, 10619, -1, + 10620, 10620, 10620, -1, 10621, 10621, 10621, -1, + 10622, 10622, 10622, -1, 10623, 10623, 10623, -1, + 10624, 10624, 10624, -1, 10625, 10625, 10625, -1, + 10626, 10626, 10626, -1, 10627, 10627, 10627, -1, + 10628, 10628, 10628, -1, 10629, 10629, 10629, -1, + 10630, 10630, 10630, -1, 10631, 10631, 10631, -1, + 10632, 10632, 10632, -1, 10633, 10633, 10633, -1, + 10634, 10634, 10634, -1, 10635, 10635, 10635, -1, + 10636, 10636, 10636, -1, 10637, 10637, 10637, -1, + 10638, 10638, 10638, -1, 10639, 10639, 10639, -1, + 10640, 10640, 10640, -1, 10641, 10641, 10641, -1, + 10642, 10642, 10642, -1, 10643, 10643, 10643, -1, + 10644, 10644, 10644, -1, 10645, 10645, 10645, -1, + 10646, 10646, 10646, -1, 10647, 10647, 10647, -1, + 10648, 10648, 10648, -1, 10649, 10649, 10649, -1, + 10650, 10650, 10650, -1, 10651, 10651, 10651, -1, + 10652, 10652, 10652, -1, 10653, 10653, 10653, -1, + 10654, 10654, 10654, -1, 10655, 10655, 10655, -1, + 10656, 10656, 10656, -1, 10657, 10657, 10657, -1, + 10658, 10658, 10658, -1, 10659, 10659, 10659, -1, + 10660, 10660, 10660, -1, 10661, 10661, 10661, -1, + 10662, 10662, 10662, -1, 10663, 10663, 10663, -1, + 10664, 10664, 10664, -1, 10665, 10665, 10665, -1, + 10666, 10666, 10666, -1, 10667, 10667, 10667, -1, + 10668, 10668, 10668, -1, 10669, 10669, 10669, -1, + 10670, 10670, 10670, -1, 10671, 10671, 10671, -1, + 10672, 10672, 10672, -1, 10673, 10673, 10673, -1, + 10674, 10674, 10674, -1, 10675, 10675, 10675, -1, + 10676, 10676, 10676, -1, 10677, 10677, 10677, -1, + 10678, 10678, 10678, -1, 10679, 10679, 10679, -1, + 10680, 10680, 10680, -1, 10681, 10681, 10681, -1, + 10682, 10682, 10682, -1, 10683, 10683, 10683, -1, + 10684, 10684, 10684, -1, 10685, 10685, 10685, -1, + 10686, 10686, 10686, -1, 10687, 10687, 10687, -1, + 10688, 10688, 10688, -1, 10689, 10689, 10689, -1, + 10690, 10690, 10690, -1, 10691, 10691, 10691, -1, + 10692, 10692, 10692, -1, 10693, 10693, 10693, -1, + 10694, 10694, 10694, -1, 10695, 10695, 10695, -1, + 10696, 10696, 10696, -1, 10697, 10697, 10697, -1, + 10698, 10698, 10698, -1, 10699, 10699, 10699, -1, + 10700, 10700, 10700, -1, 10701, 10701, 10701, -1, + 10702, 10702, 10702, -1, 10703, 10703, 10703, -1, + 10704, 10704, 10704, -1, 10705, 10705, 10705, -1, + 10706, 10706, 10706, -1, 10707, 10707, 10707, -1, + 10708, 10708, 10708, -1, 10709, 10709, 10709, -1, + 10710, 10710, 10710, -1, 10711, 10711, 10711, -1, + 10712, 10712, 10712, -1, 10713, 10713, 10713, -1, + 10714, 10714, 10714, -1, 10715, 10715, 10715, -1, + 10716, 10716, 10716, -1, 10717, 10717, 10717, -1, + 10718, 10718, 10718, -1, 10719, 10719, 10719, -1, + 10720, 10720, 10720, -1, 10721, 10721, 10721, -1, + 10722, 10722, 10722, -1, 10723, 10723, 10723, -1, + 10724, 10724, 10724, -1, 10725, 10725, 10725, -1, + 10726, 10726, 10726, -1, 10727, 10727, 10727, -1, + 10728, 10728, 10728, -1, 10729, 10729, 10729, -1, + 10730, 10730, 10730, -1, 10731, 10731, 10731, -1, + 10732, 10732, 10732, -1, 10733, 10733, 10733, -1, + 10734, 10734, 10734, -1, 10735, 10735, 10735, -1, + 10736, 10736, 10736, -1, 10737, 10737, 10737, -1, + 10738, 10738, 10738, -1, 10739, 10739, 10739, -1, + 10740, 10740, 10740, -1, 10741, 10741, 10741, -1, + 10742, 10742, 10742, -1, 10743, 10743, 10743, -1, + 10744, 10744, 10744, -1, 10745, 10745, 10745, -1, + 10746, 10746, 10746, -1, 10747, 10747, 10747, -1, + 10748, 10748, 10748, -1, 10749, 10749, 10749, -1, + 10750, 10750, 10750, -1, 10751, 10751, 10751, -1, + 10752, 10752, 10752, -1, 10753, 10753, 10753, -1, + 10754, 10754, 10754, -1, 10755, 10755, 10755, -1, + 10756, 10756, 10756, -1, 10757, 10757, 10757, -1, + 10758, 10758, 10758, -1, 10759, 10759, 10759, -1, + 10760, 10760, 10760, -1, 10761, 10761, 10761, -1, + 10762, 10762, 10762, -1, 10763, 10763, 10763, -1, + 10764, 10764, 10764, -1, 10765, 10765, 10765, -1, + 10766, 10766, 10766, -1, 10767, 10767, 10767, -1, + 10768, 10768, 10768, -1, 10769, 10769, 10769, -1, + 10770, 10770, 10770, -1, 10771, 10771, 10771, -1, + 10772, 10772, 10772, -1, 10773, 10773, 10773, -1, + 10774, 10774, 10774, -1, 10775, 10775, 10775, -1, + 10776, 10776, 10776, -1, 10777, 10777, 10777, -1, + 10778, 10778, 10778, -1, 10779, 10779, 10779, -1, + 10780, 10780, 10780, -1, 10781, 10781, 10781, -1, + 10782, 10782, 10782, -1, 10783, 10783, 10783, -1, + 10784, 10784, 10784, -1, 10785, 10785, 10785, -1, + 10786, 10786, 10786, -1, 10787, 10787, 10787, -1, + 10788, 10788, 10788, -1, 10789, 10789, 10789, -1, + 10790, 10790, 10790, -1, 10791, 10791, 10791, -1, + 10792, 10792, 10792, -1, 10793, 10793, 10793, -1, + 10794, 10794, 10794, -1, 10795, 10795, 10795, -1, + 10796, 10796, 10796, -1, 10797, 10797, 10797, -1, + 10798, 10798, 10798, -1, 10799, 10799, 10799, -1, + 10800, 10800, 10800, -1, 10801, 10801, 10801, -1, + 10802, 10802, 10802, -1, 10803, 10803, 10803, -1, + 10804, 10804, 10804, -1, 10805, 10805, 10805, -1, + 10806, 10806, 10806, -1, 10807, 10807, 10807, -1, + 10808, 10808, 10808, -1, 10809, 10809, 10809, -1, + 10810, 10810, 10810, -1, 10811, 10811, 10811, -1, + 10812, 10812, 10812, -1, 10813, 10813, 10813, -1, + 10814, 10814, 10814, -1, 10815, 10815, 10815, -1, + 10816, 10816, 10816, -1, 10817, 10817, 10817, -1, + 10818, 10818, 10818, -1, 10819, 10819, 10819, -1, + 10820, 10820, 10820, -1, 10821, 10821, 10821, -1, + 10822, 10822, 10822, -1, 10823, 10823, 10823, -1, + 10824, 10824, 10824, -1, 10825, 10825, 10825, -1, + 10826, 10826, 10826, -1, 10827, 10827, 10827, -1, + 10828, 10828, 10828, -1, 10829, 10829, 10829, -1, + 10830, 10830, 10830, -1, 10831, 10831, 10831, -1, + 10832, 10832, 10832, -1, 10833, 10833, 10833, -1, + 10834, 10834, 10834, -1, 10835, 10835, 10835, -1, + 10836, 10836, 10836, -1, 10837, 10837, 10837, -1, + 10838, 10838, 10838, -1, 10839, 10839, 10839, -1, + 10840, 10840, 10840, -1, 10841, 10841, 10841, -1, + 10842, 10842, 10842, -1, 10843, 10843, 10843, -1, + 10844, 10844, 10844, -1, 10845, 10845, 10845, -1, + 10846, 10846, 10846, -1, 10847, 10847, 10847, -1, + 10848, 10848, 10848, -1, 10849, 10849, 10849, -1, + 10850, 10850, 10850, -1, 10851, 10851, 10851, -1, + 10852, 10852, 10852, -1, 10853, 10853, 10853, -1, + 10854, 10854, 10854, -1, 10855, 10855, 10855, -1, + 10856, 10856, 10856, -1, 10857, 10857, 10857, -1, + 10858, 10858, 10858, -1, 10859, 10859, 10859, -1, + 10860, 10860, 10860, -1, 10861, 10861, 10861, -1, + 10862, 10862, 10862, -1, 10863, 10863, 10863, -1, + 10864, 10864, 10864, -1, 10865, 10865, 10865, -1, + 10866, 10866, 10866, -1, 10867, 10867, 10867, -1, + 10868, 10868, 10868, -1, 10869, 10869, 10869, -1, + 10870, 10870, 10870, -1, 10871, 10871, 10871, -1, + 10872, 10872, 10872, -1, 10873, 10873, 10873, -1, + 10874, 10874, 10874, -1, 10875, 10875, 10875, -1, + 10876, 10876, 10876, -1, 10877, 10877, 10877, -1, + 10878, 10878, 10878, -1, 10879, 10879, 10879, -1, + 10880, 10880, 10880, -1, 10881, 10881, 10881, -1, + 10882, 10882, 10882, -1, 10883, 10883, 10883, -1, + 10884, 10884, 10884, -1, 10885, 10885, 10885, -1, + 10886, 10886, 10886, -1, 10887, 10887, 10887, -1, + 10888, 10888, 10888, -1, 10889, 10889, 10889, -1, + 10890, 10890, 10890, -1, 10891, 10891, 10891, -1, + 10892, 10892, 10892, -1, 10893, 10893, 10893, -1, + 10894, 10894, 10894, -1, 10895, 10895, 10895, -1, + 10896, 10896, 10896, -1, 10897, 10897, 10897, -1, + 10898, 10898, 10898, -1, 10899, 10899, 10899, -1, + 10900, 10900, 10900, -1, 10901, 10901, 10901, -1, + 10902, 10902, 10902, -1, 10903, 10903, 10903, -1, + 10904, 10904, 10904, -1, 10905, 10905, 10905, -1, + 10906, 10906, 10906, -1, 10907, 10907, 10907, -1, + 10908, 10908, 10908, -1, 10909, 10909, 10909, -1, + 10910, 10910, 10910, -1, 10911, 10911, 10911, -1, + 10912, 10912, 10912, -1, 10913, 10913, 10913, -1, + 10914, 10914, 10914, -1, 10915, 10915, 10915, -1, + 10916, 10916, 10916, -1, 10917, 10917, 10917, -1, + 10918, 10918, 10918, -1, 10919, 10919, 10919, -1, + 10920, 10920, 10920, -1, 10921, 10921, 10921, -1, + 10922, 10922, 10922, -1, 10923, 10923, 10923, -1, + 10924, 10924, 10924, -1, 10925, 10925, 10925, -1, + 10926, 10926, 10926, -1, 10927, 10927, 10927, -1, + 10928, 10928, 10928, -1, 10929, 10929, 10929, -1, + 10930, 10930, 10930, -1, 10931, 10931, 10931, -1, + 10932, 10932, 10932, -1, 10933, 10933, 10933, -1, + 10934, 10934, 10934, -1, 10935, 10935, 10935, -1, + 10936, 10936, 10936, -1, 10937, 10937, 10937, -1, + 10938, 10938, 10938, -1, 10939, 10939, 10939, -1, + 10940, 10940, 10940, -1, 10941, 10941, 10941, -1, + 10942, 10942, 10942, -1, 10943, 10943, 10943, -1, + 10944, 10944, 10944, -1, 10945, 10945, 10945, -1, + 10946, 10946, 10946, -1, 10947, 10947, 10947, -1, + 10948, 10948, 10948, -1, 10949, 10949, 10949, -1, + 10950, 10950, 10950, -1, 10951, 10951, 10951, -1, + 10952, 10952, 10952, -1, 10953, 10953, 10953, -1, + 10954, 10954, 10954, -1, 10955, 10955, 10955, -1, + 10956, 10956, 10956, -1, 10957, 10957, 10957, -1, + 10958, 10958, 10958, -1, 10959, 10959, 10959, -1, + 10960, 10960, 10960, -1, 10961, 10961, 10961, -1, + 10962, 10962, 10962, -1, 10963, 10963, 10963, -1, + 10964, 10964, 10964, -1, 10965, 10965, 10965, -1, + 10966, 10966, 10966, -1, 10967, 10967, 10967, -1, + 10968, 10968, 10968, -1, 10969, 10969, 10969, -1, + 10970, 10970, 10970, -1, 10971, 10971, 10971, -1, + 10972, 10972, 10972, -1, 10973, 10973, 10973, -1, + 10974, 10974, 10974, -1, 10975, 10975, 10975, -1, + 10976, 10976, 10976, -1, 10977, 10977, 10977, -1, + 10978, 10978, 10978, -1, 10979, 10979, 10979, -1, + 10980, 10980, 10980, -1, 10981, 10981, 10981, -1, + 10982, 10982, 10982, -1, 10983, 10983, 10983, -1, + 10984, 10984, 10984, -1, 10985, 10985, 10985, -1, + 10986, 10986, 10986, -1, 10987, 10987, 10987, -1, + 10988, 10988, 10988, -1, 10989, 10989, 10989, -1, + 10990, 10990, 10990, -1, 10991, 10991, 10991, -1, + 10992, 10992, 10992, -1, 10993, 10993, 10993, -1, + 10994, 10994, 10994, -1, 10995, 10995, 10995, -1, + 10996, 10996, 10996, -1, 10997, 10997, 10997, -1, + 10998, 10998, 10998, -1, 10999, 10999, 10999, -1, + 11000, 11000, 11000, -1, 11001, 11001, 11001, -1, + 11002, 11002, 11002, -1, 11003, 11003, 11003, -1, + 11004, 11004, 11004, -1, 11005, 11005, 11005, -1, + 11006, 11006, 11006, -1, 11007, 11007, 11007, -1, + 11008, 11008, 11008, -1, 11009, 11009, 11009, -1, + 11010, 11010, 11010, -1, 11011, 11011, 11011, -1, + 11012, 11012, 11012, -1, 11013, 11013, 11013, -1, + 11014, 11014, 11014, -1, 11015, 11015, 11015, -1, + 11016, 11016, 11016, -1, 11017, 11017, 11017, -1, + 11018, 11018, 11018, -1, 11019, 11019, 11019, -1, + 11020, 11020, 11020, -1, 11021, 11021, 11021, -1, + 11022, 11022, 11022, -1, 11023, 11023, 11023, -1, + 11024, 11024, 11024, -1, 11025, 11025, 11025, -1, + 11026, 11026, 11026, -1, 11027, 11027, 11027, -1, + 11028, 11028, 11028, -1, 11029, 11029, 11029, -1, + 11030, 11030, 11030, -1, 11031, 11031, 11031, -1, + 11032, 11032, 11032, -1, 11033, 11033, 11033, -1, + 11034, 11034, 11034, -1, 11035, 11035, 11035, -1, + 11036, 11036, 11036, -1, 11037, 11037, 11037, -1, + 11038, 11038, 11038, -1, 11039, 11039, 11039, -1, + 11040, 11040, 11040, -1, 11041, 11041, 11041, -1, + 11042, 11042, 11042, -1, 11043, 11043, 11043, -1, + 11044, 11044, 11044, -1, 11045, 11045, 11045, -1, + 11046, 11046, 11046, -1, 11047, 11047, 11047, -1, + 11048, 11048, 11048, -1, 11049, 11049, 11049, -1, + 11050, 11050, 11050, -1, 11051, 11051, 11051, -1, + 11052, 11052, 11052, -1, 11053, 11053, 11053, -1, + 11054, 11054, 11054, -1, 11055, 11055, 11055, -1, + 11056, 11056, 11056, -1, 11057, 11057, 11057, -1, + 11058, 11058, 11058, -1, 11059, 11059, 11059, -1, + 11060, 11060, 11060, -1, 11061, 11061, 11061, -1, + 11062, 11062, 11062, -1, 11063, 11063, 11063, -1, + 11064, 11064, 11064, -1, 11065, 11065, 11065, -1, + 11066, 11066, 11066, -1, 11067, 11067, 11067, -1, + 11068, 11068, 11068, -1, 11069, 11069, 11069, -1, + 11070, 11070, 11070, -1, 11071, 11071, 11071, -1, + 11072, 11072, 11072, -1, 11073, 11073, 11073, -1, + 11074, 11074, 11074, -1, 11075, 11075, 11075, -1, + 11076, 11076, 11076, -1, 11077, 11077, 11077, -1, + 11078, 11078, 11078, -1, 11079, 11079, 11079, -1, + 11080, 11080, 11080, -1, 11081, 11081, 11081, -1, + 11082, 11082, 11082, -1, 11083, 11083, 11083, -1, + 11084, 11084, 11084, -1, 11085, 11085, 11085, -1, + 11086, 11086, 11086, -1, 11087, 11087, 11087, -1, + 11088, 11088, 11088, -1, 11089, 11089, 11089, -1, + 11090, 11090, 11090, -1, 11091, 11091, 11091, -1, + 11092, 11092, 11092, -1, 11093, 11093, 11093, -1, + 11094, 11094, 11094, -1, 11095, 11095, 11095, -1, + 11096, 11096, 11096, -1, 11097, 11097, 11097, -1, + 11098, 11098, 11098, -1, 11099, 11099, 11099, -1, + 11100, 11100, 11100, -1, 11101, 11101, 11101, -1, + 11102, 11102, 11102, -1, 11103, 11103, 11103, -1, + 11104, 11104, 11104, -1, 11105, 11105, 11105, -1, + 11106, 11106, 11106, -1, 11107, 11107, 11107, -1, + 11108, 11108, 11108, -1, 11109, 11109, 11109, -1, + 11110, 11110, 11110, -1, 11111, 11111, 11111, -1, + 11112, 11112, 11112, -1, 11113, 11113, 11113, -1, + 11114, 11114, 11114, -1, 11115, 11115, 11115, -1, + 11116, 11116, 11116, -1, 11117, 11117, 11117, -1, + 11118, 11118, 11118, -1, 11119, 11119, 11119, -1, + 11120, 11120, 11120, -1, 11121, 11121, 11121, -1, + 11122, 11122, 11122, -1, 11123, 11123, 11123, -1, + 11124, 11124, 11124, -1, 11125, 11125, 11125, -1, + 11126, 11126, 11126, -1, 11127, 11127, 11127, -1, + 11128, 11128, 11128, -1, 11129, 11129, 11129, -1, + 11130, 11130, 11130, -1, 11131, 11131, 11131, -1, + 11132, 11132, 11132, -1, 11133, 11133, 11133, -1, + 11134, 11134, 11134, -1, 11135, 11135, 11135, -1, + 11136, 11136, 11136, -1, 11137, 11137, 11137, -1, + 11138, 11138, 11138, -1, 11139, 11139, 11139, -1, + 11140, 11140, 11140, -1, 11141, 11141, 11141, -1, + 11142, 11142, 11142, -1, 11143, 11143, 11143, -1, + 11144, 11144, 11144, -1, 11145, 11145, 11145, -1, + 11146, 11146, 11146, -1, 11147, 11147, 11147, -1, + 11148, 11148, 11148, -1, 11149, 11149, 11149, -1, + 11150, 11150, 11150, -1, 11151, 11151, 11151, -1, + 11152, 11152, 11152, -1, 11153, 11153, 11153, -1, + 11154, 11154, 11154, -1, 11155, 11155, 11155, -1, + 11156, 11156, 11156, -1, 11157, 11157, 11157, -1, + 11158, 11158, 11158, -1, 11159, 11159, 11159, -1, + 11160, 11160, 11160, -1, 11161, 11161, 11161, -1, + 11162, 11162, 11162, -1, 11163, 11163, 11163, -1, + 11164, 11164, 11164, -1, 11165, 11165, 11165, -1, + 11166, 11166, 11166, -1, 11167, 11167, 11167, -1, + 11168, 11168, 11168, -1, 11169, 11169, 11169, -1, + 11170, 11170, 11170, -1, 11171, 11171, 11171, -1, + 11172, 11172, 11172, -1, 11173, 11173, 11173, -1, + 11174, 11174, 11174, -1, 11175, 11175, 11175, -1, + 11176, 11176, 11176, -1, 11177, 11177, 11177, -1, + 11178, 11178, 11178, -1, 11179, 11179, 11179, -1, + 11180, 11180, 11180, -1, 11181, 11181, 11181, -1, + 11182, 11182, 11182, -1, 11183, 11183, 11183, -1, + 11184, 11184, 11184, -1, 11185, 11185, 11185, -1, + 11186, 11186, 11186, -1, 11187, 11187, 11187, -1, + 11188, 11188, 11188, -1, 11189, 11189, 11189, -1, + 11190, 11190, 11190, -1, 11191, 11191, 11191, -1, + 11192, 11192, 11192, -1, 11193, 11193, 11193, -1, + 11194, 11194, 11194, -1, 11195, 11195, 11195, -1, + 11196, 11196, 11196, -1, 11197, 11197, 11197, -1, + 11198, 11198, 11198, -1, 11199, 11199, 11199, -1, + 11200, 11200, 11200, -1, 11201, 11201, 11201, -1, + 11202, 11202, 11202, -1, 11203, 11203, 11203, -1, + 11204, 11204, 11204, -1, 11205, 11205, 11205, -1, + 11206, 11206, 11206, -1, 11207, 11207, 11207, -1, + 11208, 11208, 11208, -1, 11209, 11209, 11209, -1, + 11210, 11210, 11210, -1, 11211, 11211, 11211, -1, + 11212, 11212, 11212, -1, 11213, 11213, 11213, -1, + 11214, 11214, 11214, -1, 11215, 11215, 11215, -1, + 11216, 11216, 11216, -1, 11217, 11217, 11217, -1, + 11218, 11218, 11218, -1, 11219, 11219, 11219, -1, + 11220, 11220, 11220, -1, 11221, 11221, 11221, -1, + 11222, 11222, 11222, -1, 11223, 11223, 11223, -1, + 11224, 11224, 11224, -1, 11225, 11225, 11225, -1, + 11226, 11226, 11226, -1, 11227, 11227, 11227, -1, + 11228, 11228, 11228, -1, 11229, 11229, 11229, -1, + 11230, 11230, 11230, -1, 11231, 11231, 11231, -1, + 11232, 11232, 11232, -1, 11233, 11233, 11233, -1, + 11234, 11234, 11234, -1, 11235, 11235, 11235, -1, + 11236, 11236, 11236, -1, 11237, 11237, 11237, -1, + 11238, 11238, 11238, -1, 11239, 11239, 11239, -1, + 11240, 11240, 11240, -1, 11241, 11241, 11241, -1, + 11242, 11242, 11242, -1, 11243, 11243, 11243, -1, + 11244, 11244, 11244, -1, 11245, 11245, 11245, -1, + 11246, 11246, 11246, -1, 11247, 11247, 11247, -1, + 11248, 11248, 11248, -1, 11249, 11249, 11249, -1, + 11250, 11250, 11250, -1, 11251, 11251, 11251, -1, + 11252, 11252, 11252, -1, 11253, 11253, 11253, -1, + 11254, 11254, 11254, -1, 11255, 11255, 11255, -1, + 11256, 11256, 11256, -1, 11257, 11257, 11257, -1, + 11258, 11258, 11258, -1, 11259, 11259, 11259, -1, + 11260, 11260, 11260, -1, 11261, 11261, 11261, -1, + 11262, 11262, 11262, -1, 11263, 11263, 11263, -1, + 11264, 11264, 11264, -1, 11265, 11265, 11265, -1, + 11266, 11266, 11266, -1, 11267, 11267, 11267, -1, + 11268, 11268, 11268, -1, 11269, 11269, 11269, -1, + 11270, 11270, 11270, -1, 11271, 11271, 11271, -1, + 11272, 11272, 11272, -1, 11273, 11273, 11273, -1, + 11274, 11274, 11274, -1, 11275, 11275, 11275, -1, + 11276, 11276, 11276, -1, 11277, 11277, 11277, -1, + 11278, 11278, 11278, -1, 11279, 11279, 11279, -1, + 11280, 11280, 11280, -1, 11281, 11281, 11281, -1, + 11282, 11282, 11282, -1, 11283, 11283, 11283, -1, + 11284, 11284, 11284, -1, 11285, 11285, 11285, -1, + 11286, 11286, 11286, -1, 11287, 11287, 11287, -1, + 11288, 11288, 11288, -1, 11289, 11289, 11289, -1, + 11290, 11290, 11290, -1, 11291, 11291, 11291, -1, + 11292, 11292, 11292, -1, 11293, 11293, 11293, -1, + 11294, 11294, 11294, -1, 11295, 11295, 11295, -1, + 11296, 11296, 11296, -1, 11297, 11297, 11297, -1, + 11298, 11298, 11298, -1, 11299, 11299, 11299, -1, + 11300, 11300, 11300, -1, 11301, 11301, 11301, -1, + 11302, 11302, 11302, -1, 11303, 11303, 11303, -1, + 11304, 11304, 11304, -1, 11305, 11305, 11305, -1, + 11306, 11306, 11306, -1, 11307, 11307, 11307, -1, + 11308, 11308, 11308, -1, 11309, 11309, 11309, -1, + 11310, 11310, 11310, -1, 11311, 11311, 11311, -1, + 11312, 11312, 11312, -1, 11313, 11313, 11313, -1, + 11314, 11314, 11314, -1, 11315, 11315, 11315, -1, + 11316, 11316, 11316, -1, 11317, 11317, 11317, -1, + 11318, 11318, 11318, -1, 11319, 11319, 11319, -1, + 11320, 11320, 11320, -1, 11321, 11321, 11321, -1, + 11322, 11322, 11322, -1, 11323, 11323, 11323, -1, + 11324, 11324, 11324, -1, 11325, 11325, 11325, -1, + 11326, 11326, 11326, -1, 11327, 11327, 11327, -1, + 11328, 11328, 11328, -1, 11329, 11329, 11329, -1, + 11330, 11330, 11330, -1, 11331, 11331, 11331, -1, + 11332, 11332, 11332, -1, 11333, 11333, 11333, -1, + 11334, 11334, 11334, -1, 11335, 11335, 11335, -1, + 11336, 11336, 11336, -1, 11337, 11337, 11337, -1, + 11338, 11338, 11338, -1, 11339, 11339, 11339, -1, + 11340, 11340, 11340, -1, 11341, 11341, 11341, -1, + 11342, 11342, 11342, -1, 11343, 11343, 11343, -1, + 11344, 11344, 11344, -1, 11345, 11345, 11345, -1, + 11346, 11346, 11346, -1, 11347, 11347, 11347, -1, + 11348, 11348, 11348, -1, 11349, 11349, 11349, -1, + 11350, 11350, 11350, -1, 11351, 11351, 11351, -1, + 11352, 11352, 11352, -1, 11353, 11353, 11353, -1, + 11354, 11354, 11354, -1, 11355, 11355, 11355, -1, + 11356, 11356, 11356, -1, 11357, 11357, 11357, -1, + 11358, 11358, 11358, -1, 11359, 11359, 11359, -1, + 11360, 11360, 11360, -1, 11361, 11361, 11361, -1, + 11362, 11362, 11362, -1, 11363, 11363, 11363, -1, + 11364, 11364, 11364, -1, 11365, 11365, 11365, -1, + 11366, 11366, 11366, -1, 11367, 11367, 11367, -1, + 11368, 11368, 11368, -1, 11369, 11369, 11369, -1, + 11370, 11370, 11370, -1, 11371, 11371, 11371, -1, + 11372, 11372, 11372, -1, 11373, 11373, 11373, -1, + 11374, 11374, 11374, -1, 11375, 11375, 11375, -1, + 11376, 11376, 11376, -1, 11377, 11377, 11377, -1, + 11378, 11378, 11378, -1, 11379, 11379, 11379, -1, + 11380, 11380, 11380, -1, 11381, 11381, 11381, -1, + 11382, 11382, 11382, -1, 11383, 11383, 11383, -1, + 11384, 11384, 11384, -1, 11385, 11385, 11385, -1, + 11386, 11386, 11386, -1, 11387, 11387, 11387, -1, + 11388, 11388, 11388, -1, 11389, 11389, 11389, -1, + 11390, 11390, 11390, -1, 11391, 11391, 11391, -1, + 11392, 11392, 11392, -1, 11393, 11393, 11393, -1, + 11394, 11394, 11394, -1, 11395, 11395, 11395, -1, + 11396, 11396, 11396, -1, 11397, 11397, 11397, -1, + 11398, 11398, 11398, -1, 11399, 11399, 11399, -1, + 11400, 11400, 11400, -1, 11401, 11401, 11401, -1, + 11402, 11402, 11402, -1, 11403, 11403, 11403, -1, + 11404, 11404, 11404, -1, 11405, 11405, 11405, -1, + 11406, 11406, 11406, -1, 11407, 11407, 11407, -1, + 11408, 11408, 11408, -1, 11409, 11409, 11409, -1, + 11410, 11410, 11410, -1, 11411, 11411, 11411, -1, + 11412, 11412, 11412, -1, 11413, 11413, 11413, -1, + 11414, 11414, 11414, -1, 11415, 11415, 11415, -1, + 11416, 11416, 11416, -1, 11417, 11417, 11417, -1, + 11418, 11418, 11418, -1, 11419, 11419, 11419, -1, + 11420, 11420, 11420, -1, 11421, 11421, 11421, -1, + 11422, 11422, 11422, -1, 11423, 11423, 11423, -1, + 11424, 11424, 11424, -1, 11425, 11425, 11425, -1, + 11426, 11426, 11426, -1, 11427, 11427, 11427, -1, + 11428, 11428, 11428, -1, 11429, 11429, 11429, -1, + 11430, 11430, 11430, -1, 11431, 11431, 11431, -1, + 11432, 11432, 11432, -1, 11433, 11433, 11433, -1, + 11434, 11434, 11434, -1, 11435, 11435, 11435, -1, + 11436, 11436, 11436, -1, 11437, 11437, 11437, -1, + 11438, 11438, 11438, -1, 11439, 11439, 11439, -1, + 11440, 11440, 11440, -1, 11441, 11441, 11441, -1, + 11442, 11442, 11442, -1, 11443, 11443, 11443, -1, + 11444, 11444, 11444, -1, 11445, 11445, 11445, -1, + 11446, 11446, 11446, -1, 11447, 11447, 11447, -1, + 11448, 11448, 11448, -1, 11449, 11449, 11449, -1, + 11450, 11450, 11450, -1, 11451, 11451, 11451, -1, + 11452, 11452, 11452, -1, 11453, 11453, 11453, -1, + 11454, 11454, 11454, -1, 11455, 11455, 11455, -1, + 11456, 11456, 11456, -1, 11457, 11457, 11457, -1, + 11458, 11458, 11458, -1, 11459, 11459, 11459, -1, + 11460, 11460, 11460, -1, 11461, 11461, 11461, -1, + 11462, 11462, 11462, -1, 11463, 11463, 11463, -1, + 11464, 11464, 11464, -1, 11465, 11465, 11465, -1, + 11466, 11466, 11466, -1, 11467, 11467, 11467, -1, + 11468, 11468, 11468, -1, 11469, 11469, 11469, -1, + 11470, 11470, 11470, -1, 11471, 11471, 11471, -1, + 11472, 11472, 11472, -1, 11473, 11473, 11473, -1, + 11474, 11474, 11474, -1, 11475, 11475, 11475, -1, + 11476, 11476, 11476, -1, 11477, 11477, 11477, -1, + 11478, 11478, 11478, -1, 11479, 11479, 11479, -1, + 11480, 11480, 11480, -1, 11481, 11481, 11481, -1, + 11482, 11482, 11482, -1, 11483, 11483, 11483, -1, + 11484, 11484, 11484, -1, 11485, 11485, 11485, -1, + 11486, 11486, 11486, -1, 11487, 11487, 11487, -1, + 11488, 11488, 11488, -1, 11489, 11489, 11489, -1, + 11490, 11490, 11490, -1, 11491, 11491, 11491, -1, + 11492, 11492, 11492, -1, 11493, 11493, 11493, -1, + 11494, 11494, 11494, -1, 11495, 11495, 11495, -1, + 11496, 11496, 11496, -1, 11497, 11497, 11497, -1, + 11498, 11498, 11498, -1, 11499, 11499, 11499, -1, + 11500, 11500, 11500, -1, 11501, 11501, 11501, -1, + 11502, 11502, 11502, -1, 11503, 11503, 11503, -1, + 11504, 11504, 11504, -1, 11505, 11505, 11505, -1, + 11506, 11506, 11506, -1, 11507, 11507, 11507, -1, + 11508, 11508, 11508, -1, 11509, 11509, 11509, -1, + 11510, 11510, 11510, -1, 11511, 11511, 11511, -1, + 11512, 11512, 11512, -1, 11513, 11513, 11513, -1, + 11514, 11514, 11514, -1, 11515, 11515, 11515, -1, + 11516, 11516, 11516, -1, 11517, 11517, 11517, -1, + 11518, 11518, 11518, -1, 11519, 11519, 11519, -1, + 11520, 11520, 11520, -1, 11521, 11521, 11521, -1, + 11522, 11522, 11522, -1, 11523, 11523, 11523, -1, + 11524, 11524, 11524, -1, 11525, 11525, 11525, -1, + 11526, 11526, 11526, -1, 11527, 11527, 11527, -1, + 11528, 11528, 11528, -1, 11529, 11529, 11529, -1, + 11530, 11530, 11530, -1, 11531, 11531, 11531, -1, + 11532, 11532, 11532, -1, 11533, 11533, 11533, -1, + 11534, 11534, 11534, -1, 11535, 11535, 11535, -1, + 11536, 11536, 11536, -1, 11537, 11537, 11537, -1, + 11538, 11538, 11538, -1, 11539, 11539, 11539, -1, + 11540, 11540, 11540, -1, 11541, 11541, 11541, -1, + 11542, 11542, 11542, -1, 11543, 11543, 11543, -1, + 11544, 11544, 11544, -1, 11545, 11545, 11545, -1, + 11546, 11546, 11546, -1, 11547, 11547, 11547, -1, + 11548, 11548, 11548, -1, 11549, 11549, 11549, -1, + 11550, 11550, 11550, -1, 11551, 11551, 11551, -1, + 11552, 11552, 11552, -1, 11553, 11553, 11553, -1, + 11554, 11554, 11554, -1, 11555, 11555, 11555, -1, + 11556, 11556, 11556, -1, 11557, 11557, 11557, -1, + 11558, 11558, 11558, -1, 11559, 11559, 11559, -1, + 11560, 11560, 11560, -1, 11561, 11561, 11561, -1, + 11562, 11562, 11562, -1, 11563, 11563, 11563, -1, + 11564, 11564, 11564, -1, 11565, 11565, 11565, -1, + 11566, 11566, 11566, -1, 11567, 11567, 11567, -1, + 11568, 11568, 11568, -1, 11569, 11569, 11569, -1, + 11570, 11570, 11570, -1, 11571, 11571, 11571, -1, + 11572, 11572, 11572, -1, 11573, 11573, 11573, -1, + 11574, 11574, 11574, -1, 11575, 11575, 11575, -1, + 11576, 11576, 11576, -1, 11577, 11577, 11577, -1, + 11578, 11578, 11578, -1, 11579, 11579, 11579, -1, + 11580, 11580, 11580, -1, 11581, 11581, 11581, -1, + 11582, 11582, 11582, -1, 11583, 11583, 11583, -1, + 11584, 11584, 11584, -1, 11585, 11585, 11585, -1, + 11586, 11586, 11586, -1, 11587, 11587, 11587, -1, + 11588, 11588, 11588, -1, 11589, 11589, 11589, -1, + 11590, 11590, 11590, -1, 11591, 11591, 11591, -1, + 11592, 11592, 11592, -1, 11593, 11593, 11593, -1, + 11594, 11594, 11594, -1, 11595, 11595, 11595, -1, + 11596, 11596, 11596, -1, 11597, 11597, 11597, -1, + 11598, 11598, 11598, -1, 11599, 11599, 11599, -1, + 11600, 11600, 11600, -1, 11601, 11601, 11601, -1, + 11602, 11602, 11602, -1, 11603, 11603, 11603, -1, + 11604, 11604, 11604, -1, 11605, 11605, 11605, -1, + 11606, 11606, 11606, -1, 11607, 11607, 11607, -1, + 11608, 11608, 11608, -1, 11609, 11609, 11609, -1, + 11610, 11610, 11610, -1, 11611, 11611, 11611, -1, + 11612, 11612, 11612, -1, 11613, 11613, 11613, -1, + 11614, 11614, 11614, -1, 11615, 11615, 11615, -1, + 11616, 11616, 11616, -1, 11617, 11617, 11617, -1, + 11618, 11618, 11618, -1, 11619, 11619, 11619, -1, + 11620, 11620, 11620, -1, 11621, 11621, 11621, -1, + 11622, 11622, 11622, -1, 11623, 11623, 11623, -1, + 11624, 11624, 11624, -1, 11625, 11625, 11625, -1, + 11626, 11626, 11626, -1, 11627, 11627, 11627, -1, + 11628, 11628, 11628, -1, 11629, 11629, 11629, -1, + 11630, 11630, 11630, -1, 11631, 11631, 11631, -1, + 11632, 11632, 11632, -1, 11633, 11633, 11633, -1, + 11634, 11634, 11634, -1, 11635, 11635, 11635, -1, + 11636, 11636, 11636, -1, 11637, 11637, 11637, -1, + 11638, 11638, 11638, -1, 11639, 11639, 11639, -1, + 11640, 11640, 11640, -1, 11641, 11641, 11641, -1, + 11642, 11642, 11642, -1, 11643, 11643, 11643, -1, + 11644, 11644, 11644, -1, 11645, 11645, 11645, -1, + 11646, 11646, 11646, -1, 11647, 11647, 11647, -1, + 11648, 11648, 11648, -1, 11649, 11649, 11649, -1, + 11650, 11650, 11650, -1, 11651, 11651, 11651, -1, + 11652, 11652, 11652, -1, 11653, 11653, 11653, -1, + 11654, 11654, 11654, -1, 11655, 11655, 11655, -1, + 11656, 11656, 11656, -1, 11657, 11657, 11657, -1, + 11658, 11658, 11658, -1, 11659, 11659, 11659, -1, + 11660, 11660, 11660, -1, 11661, 11661, 11661, -1, + 11662, 11662, 11662, -1, 11663, 11663, 11663, -1, + 11664, 11664, 11664, -1, 11665, 11665, 11665, -1, + 11666, 11666, 11666, -1, 11667, 11667, 11667, -1, + 11668, 11668, 11668, -1, 11669, 11669, 11669, -1, + 11670, 11670, 11670, -1, 11671, 11671, 11671, -1, + 11672, 11672, 11672, -1, 11673, 11673, 11673, -1, + 11674, 11674, 11674, -1, 11675, 11675, 11675, -1, + 11676, 11676, 11676, -1, 11677, 11677, 11677, -1, + 11678, 11678, 11678, -1, 11679, 11679, 11679, -1, + 11680, 11680, 11680, -1, 11681, 11681, 11681, -1, + 11682, 11682, 11682, -1, 11683, 11683, 11683, -1, + 11684, 11684, 11684, -1, 11685, 11685, 11685, -1, + 11686, 11686, 11686, -1, 11687, 11687, 11687, -1, + 11688, 11688, 11688, -1, 11689, 11689, 11689, -1, + 11690, 11690, 11690, -1, 11691, 11691, 11691, -1, + 11692, 11692, 11692, -1, 11693, 11693, 11693, -1, + 11694, 11694, 11694, -1, 11695, 11695, 11695, -1, + 11696, 11696, 11696, -1, 11697, 11697, 11697, -1, + 11698, 11698, 11698, -1, 11699, 11699, 11699, -1, + 11700, 11700, 11700, -1, 11701, 11701, 11701, -1, + 11702, 11702, 11702, -1, 11703, 11703, 11703, -1, + 11704, 11704, 11704, -1, 11705, 11705, 11705, -1, + 11706, 11706, 11706, -1, 11707, 11707, 11707, -1, + 11708, 11708, 11708, -1, 11709, 11709, 11709, -1, + 11710, 11710, 11710, -1, 11711, 11711, 11711, -1, + 11712, 11712, 11712, -1, 11713, 11713, 11713, -1, + 11714, 11714, 11714, -1, 11715, 11715, 11715, -1, + 11716, 11716, 11716, -1, 11717, 11717, 11717, -1, + 11718, 11718, 11718, -1, 11719, 11719, 11719, -1, + 11720, 11720, 11720, -1, 11721, 11721, 11721, -1, + 11722, 11722, 11722, -1, 11723, 11723, 11723, -1, + 11724, 11724, 11724, -1, 11725, 11725, 11725, -1, + 11726, 11726, 11726, -1, 11727, 11727, 11727, -1, + 11728, 11728, 11728, -1, 11729, 11729, 11729, -1, + 11730, 11730, 11730, -1, 11731, 11731, 11731, -1, + 11732, 11732, 11732, -1, 11733, 11733, 11733, -1, + 11734, 11734, 11734, -1, 11735, 11735, 11735, -1, + 11736, 11736, 11736, -1, 11737, 11737, 11737, -1, + 11738, 11738, 11738, -1, 11739, 11739, 11739, -1, + 11740, 11740, 11740, -1, 11741, 11741, 11741, -1, + 11742, 11742, 11742, -1, 11743, 11743, 11743, -1, + 11744, 11744, 11744, -1, 11745, 11745, 11745, -1, + 11746, 11746, 11746, -1, 11747, 11747, 11747, -1, + 11748, 11748, 11748, -1, 11749, 11749, 11749, -1, + 11750, 11750, 11750, -1, 11751, 11751, 11751, -1, + 11752, 11752, 11752, -1, 11753, 11753, 11753, -1, + 11754, 11754, 11754, -1, 11755, 11755, 11755, -1, + 11756, 11756, 11756, -1, 11757, 11757, 11757, -1, + 11758, 11758, 11758, -1, 11759, 11759, 11759, -1, + 11760, 11760, 11760, -1, 11761, 11761, 11761, -1, + 11762, 11762, 11762, -1, 11763, 11763, 11763, -1, + 11764, 11764, 11764, -1, 11765, 11765, 11765, -1, + 11766, 11766, 11766, -1, 11767, 11767, 11767, -1, + 11768, 11768, 11768, -1, 11769, 11769, 11769, -1, + 11770, 11770, 11770, -1, 11771, 11771, 11771, -1, + 11772, 11772, 11772, -1, 11773, 11773, 11773, -1, + 11774, 11774, 11774, -1, 11775, 11775, 11775, -1, + 11776, 11776, 11776, -1, 11777, 11777, 11777, -1, + 11778, 11778, 11778, -1, 11779, 11779, 11779, -1, + 11780, 11780, 11780, -1, 11781, 11781, 11781, -1, + 11782, 11782, 11782, -1, 11783, 11783, 11783, -1, + 11784, 11784, 11784, -1, 11785, 11785, 11785, -1, + 11786, 11786, 11786, -1, 11787, 11787, 11787, -1, + 11788, 11788, 11788, -1, 11789, 11789, 11789, -1, + 11790, 11790, 11790, -1, 11791, 11791, 11791, -1, + 11792, 11792, 11792, -1, 11793, 11793, 11793, -1, + 11794, 11794, 11794, -1, 11795, 11795, 11795, -1, + 11796, 11796, 11796, -1, 11797, 11797, 11797, -1, + 11798, 11798, 11798, -1, 11799, 11799, 11799, -1, + 11800, 11800, 11800, -1, 11801, 11801, 11801, -1, + 11802, 11802, 11802, -1, 11803, 11803, 11803, -1, + 11804, 11804, 11804, -1, 11805, 11805, 11805, -1, + 11806, 11806, 11806, -1, 11807, 11807, 11807, -1, + 11808, 11808, 11808, -1, 11809, 11809, 11809, -1, + 11810, 11810, 11810, -1, 11811, 11811, 11811, -1, + 11812, 11812, 11812, -1, 11813, 11813, 11813, -1, + 11814, 11814, 11814, -1, 11815, 11815, 11815, -1, + 11816, 11816, 11816, -1, 11817, 11817, 11817, -1, + 11818, 11818, 11818, -1, 11819, 11819, 11819, -1, + 11820, 11820, 11820, -1, 11821, 11821, 11821, -1, + 11822, 11822, 11822, -1, 11823, 11823, 11823, -1, + 11824, 11824, 11824, -1, 11825, 11825, 11825, -1, + 11826, 11826, 11826, -1, 11827, 11827, 11827, -1, + 11828, 11828, 11828, -1, 11829, 11829, 11829, -1, + 11830, 11830, 11830, -1, 11831, 11831, 11831, -1, + 11832, 11832, 11832, -1, 11833, 11833, 11833, -1, + 11834, 11834, 11834, -1, 11835, 11835, 11835, -1, + 11836, 11836, 11836, -1, 11837, 11837, 11837, -1, + 11838, 11838, 11838, -1, 11839, 11839, 11839, -1, + 11840, 11840, 11840, -1, 11841, 11841, 11841, -1, + 11842, 11842, 11842, -1, 11843, 11843, 11843, -1, + 11844, 11844, 11844, -1, 11845, 11845, 11845, -1, + 11846, 11846, 11846, -1, 11847, 11847, 11847, -1, + 11848, 11848, 11848, -1, 11849, 11849, 11849, -1, + 11850, 11850, 11850, -1, 11851, 11851, 11851, -1, + 11852, 11852, 11852, -1, 11853, 11853, 11853, -1, + 11854, 11854, 11854, -1, 11855, 11855, 11855, -1, + 11856, 11856, 11856, -1, 11857, 11857, 11857, -1, + 11858, 11858, 11858, -1, 11859, 11859, 11859, -1, + 11860, 11860, 11860, -1, 11861, 11861, 11861, -1, + 11862, 11862, 11862, -1, 11863, 11863, 11863, -1, + 11864, 11864, 11864, -1, 11865, 11865, 11865, -1, + 11866, 11866, 11866, -1, 11867, 11867, 11867, -1, + 11868, 11868, 11868, -1, 11869, 11869, 11869, -1, + 11870, 11870, 11870, -1, 11871, 11871, 11871, -1, + 11872, 11872, 11872, -1, 11873, 11873, 11873, -1, + 11874, 11874, 11874, -1, 11875, 11875, 11875, -1, + 11876, 11876, 11876, -1, 11877, 11877, 11877, -1, + 11878, 11878, 11878, -1, 11879, 11879, 11879, -1, + 11880, 11880, 11880, -1, 11881, 11881, 11881, -1, + 11882, 11882, 11882, -1, 11883, 11883, 11883, -1, + 11884, 11884, 11884, -1, 11885, 11885, 11885, -1, + 11886, 11886, 11886, -1, 11887, 11887, 11887, -1, + 11888, 11888, 11888, -1, 11889, 11889, 11889, -1, + 11890, 11890, 11890, -1, 11891, 11891, 11891, -1, + 11892, 11892, 11892, -1, 11893, 11893, 11893, -1, + 11894, 11894, 11894, -1, 11895, 11895, 11895, -1, + 11896, 11896, 11896, -1, 11897, 11897, 11897, -1, + 11898, 11898, 11898, -1, 11899, 11899, 11899, -1, + 11900, 11900, 11900, -1, 11901, 11901, 11901, -1, + 11902, 11902, 11902, -1, 11903, 11903, 11903, -1, + 11904, 11904, 11904, -1, 11905, 11905, 11905, -1, + 11906, 11906, 11906, -1, 11907, 11907, 11907, -1, + 11908, 11908, 11908, -1, 11909, 11909, 11909, -1, + 11910, 11910, 11910, -1, 11911, 11911, 11911, -1, + 11912, 11912, 11912, -1, 11913, 11913, 11913, -1, + 11914, 11914, 11914, -1, 11915, 11915, 11915, -1, + 11916, 11916, 11916, -1, 11917, 11917, 11917, -1, + 11918, 11918, 11918, -1, 11919, 11919, 11919, -1, + 11920, 11920, 11920, -1, 11921, 11921, 11921, -1, + 11922, 11922, 11922, -1, 11923, 11923, 11923, -1, + 11924, 11924, 11924, -1, 11925, 11925, 11925, -1, + 11926, 11926, 11926, -1, 11927, 11927, 11927, -1, + 11928, 11928, 11928, -1, 11929, 11929, 11929, -1, + 11930, 11930, 11930, -1, 11931, 11931, 11931, -1, + 11932, 11932, 11932, -1, 11933, 11933, 11933, -1, + 11934, 11934, 11934, -1, 11935, 11935, 11935, -1, + 11936, 11936, 11936, -1, 11937, 11937, 11937, -1, + 11938, 11938, 11938, -1, 11939, 11939, 11939, -1, + 11940, 11940, 11940, -1, 11941, 11941, 11941, -1, + 11942, 11942, 11942, -1, 11943, 11943, 11943, -1, + 11944, 11944, 11944, -1, 11945, 11945, 11945, -1, + 11946, 11946, 11946, -1, 11947, 11947, 11947, -1, + 11948, 11948, 11948, -1, 11949, 11949, 11949, -1, + 11950, 11950, 11950, -1, 11951, 11951, 11951, -1, + 11952, 11952, 11952, -1, 11953, 11953, 11953, -1, + 11954, 11954, 11954, -1, 11955, 11955, 11955, -1, + 11956, 11956, 11956, -1, 11957, 11957, 11957, -1, + 11958, 11958, 11958, -1, 11959, 11959, 11959, -1, + 11960, 11960, 11960, -1, 11961, 11961, 11961, -1, + 11962, 11962, 11962, -1, 11963, 11963, 11963, -1, + 11964, 11964, 11964, -1, 11965, 11965, 11965, -1, + 11966, 11966, 11966, -1, 11967, 11967, 11967, -1, + 11968, 11968, 11968, -1, 11969, 11969, 11969, -1, + 11970, 11970, 11970, -1, 11971, 11971, 11971, -1, + 11972, 11972, 11972, -1, 11973, 11973, 11973, -1, + 11974, 11974, 11974, -1, 11975, 11975, 11975, -1, + 11976, 11976, 11976, -1, 11977, 11977, 11977, -1, + 11978, 11978, 11978, -1, 11979, 11979, 11979, -1, + 11980, 11980, 11980, -1, 11981, 11981, 11981, -1, + 11982, 11982, 11982, -1, 11983, 11983, 11983, -1, + 11984, 11984, 11984, -1, 11985, 11985, 11985, -1, + 11986, 11986, 11986, -1, 11987, 11987, 11987, -1, + 11988, 11988, 11988, -1, 11989, 11989, 11989, -1, + 11990, 11990, 11990, -1, 11991, 11991, 11991, -1, + 11992, 11992, 11992, -1, 11993, 11993, 11993, -1, + 11994, 11994, 11994, -1, 11995, 11995, 11995, -1, + 11996, 11996, 11996, -1, 11997, 11997, 11997, -1, + 11998, 11998, 11998, -1, 11999, 11999, 11999, -1, + 12000, 12000, 12000, -1, 12001, 12001, 12001, -1, + 12002, 12002, 12002, -1, 12003, 12003, 12003, -1, + 12004, 12004, 12004, -1, 12005, 12005, 12005, -1, + 12006, 12006, 12006, -1, 12007, 12007, 12007, -1, + 12008, 12008, 12008, -1, 12009, 12009, 12009, -1, + 12010, 12010, 12010, -1, 12011, 12011, 12011, -1, + 12012, 12012, 12012, -1, 12013, 12013, 12013, -1, + 12014, 12014, 12014, -1, 12015, 12015, 12015, -1, + 12016, 12016, 12016, -1, 12017, 12017, 12017, -1, + 12018, 12018, 12018, -1, 12019, 12019, 12019, -1, + 12020, 12020, 12020, -1, 12021, 12021, 12021, -1, + 12022, 12022, 12022, -1, 12023, 12023, 12023, -1, + 12024, 12024, 12024, -1, 12025, 12025, 12025, -1, + 12026, 12026, 12026, -1, 12027, 12027, 12027, -1, + 12028, 12028, 12028, -1, 12029, 12029, 12029, -1, + 12030, 12030, 12030, -1, 12031, 12031, 12031, -1, + 12032, 12032, 12032, -1, 12033, 12033, 12033, -1, + 12034, 12034, 12034, -1, 12035, 12035, 12035, -1, + 12036, 12036, 12036, -1, 12037, 12037, 12037, -1, + 12038, 12038, 12038, -1, 12039, 12039, 12039, -1, + 12040, 12040, 12040, -1, 12041, 12041, 12041, -1, + 12042, 12042, 12042, -1, 12043, 12043, 12043, -1, + 12044, 12044, 12044, -1, 12045, 12045, 12045, -1, + 12046, 12046, 12046, -1, 12047, 12047, 12047, -1, + 12048, 12048, 12048, -1, 12049, 12049, 12049, -1, + 12050, 12050, 12050, -1, 12051, 12051, 12051, -1, + 12052, 12052, 12052, -1, 12053, 12053, 12053, -1, + 12054, 12054, 12054, -1, 12055, 12055, 12055, -1, + 12056, 12056, 12056, -1, 12057, 12057, 12057, -1, + 12058, 12058, 12058, -1, 12059, 12059, 12059, -1, + 12060, 12060, 12060, -1, 12061, 12061, 12061, -1, + 12062, 12062, 12062, -1, 12063, 12063, 12063, -1, + 12064, 12064, 12064, -1, 12065, 12065, 12065, -1, + 12066, 12066, 12066, -1, 12067, 12067, 12067, -1, + 12068, 12068, 12068, -1, 12069, 12069, 12069, -1, + 12070, 12070, 12070, -1, 12071, 12071, 12071, -1, + 12072, 12072, 12072, -1, 12073, 12073, 12073, -1, + 12074, 12074, 12074, -1, 12075, 12075, 12075, -1, + 12076, 12076, 12076, -1, 12077, 12077, 12077, -1, + 12078, 12078, 12078, -1, 12079, 12079, 12079, -1, + 12080, 12080, 12080, -1, 12081, 12081, 12081, -1, + 12082, 12082, 12082, -1, 12083, 12083, 12083, -1, + 12084, 12084, 12084, -1, 12085, 12085, 12085, -1, + 12086, 12086, 12086, -1, 12087, 12087, 12087, -1, + 12088, 12088, 12088, -1, 12089, 12089, 12089, -1, + 12090, 12090, 12090, -1, 12091, 12091, 12091, -1, + 12092, 12092, 12092, -1, 12093, 12093, 12093, -1, + 12094, 12094, 12094, -1, 12095, 12095, 12095, -1, + 12096, 12096, 12096, -1, 12097, 12097, 12097, -1, + 12098, 12098, 12098, -1, 12099, 12099, 12099, -1, + 12100, 12100, 12100, -1, 12101, 12101, 12101, -1, + 12102, 12102, 12102, -1, 12103, 12103, 12103, -1, + 12104, 12104, 12104, -1, 12105, 12105, 12105, -1, + 12106, 12106, 12106, -1, 12107, 12107, 12107, -1, + 12108, 12108, 12108, -1, 12109, 12109, 12109, -1, + 12110, 12110, 12110, -1, 12111, 12111, 12111, -1, + 12112, 12112, 12112, -1, 12113, 12113, 12113, -1, + 12114, 12114, 12114, -1, 12115, 12115, 12115, -1, + 12116, 12116, 12116, -1, 12117, 12117, 12117, -1, + 12118, 12118, 12118, -1, 12119, 12119, 12119, -1, + 12120, 12120, 12120, -1, 12121, 12121, 12121, -1, + 12122, 12122, 12122, -1, 12123, 12123, 12123, -1, + 12124, 12124, 12124, -1, 12125, 12125, 12125, -1, + 12126, 12126, 12126, -1, 12127, 12127, 12127, -1, + 12128, 12128, 12128, -1, 12129, 12129, 12129, -1, + 12130, 12130, 12130, -1, 12131, 12131, 12131, -1, + 12132, 12132, 12132, -1, 12133, 12133, 12133, -1, + 12134, 12134, 12134, -1, 12135, 12135, 12135, -1, + 12136, 12136, 12136, -1, 12137, 12137, 12137, -1, + 12138, 12138, 12138, -1, 12139, 12139, 12139, -1, + 12140, 12140, 12140, -1, 12141, 12141, 12141, -1, + 12142, 12142, 12142, -1, 12143, 12143, 12143, -1, + 12144, 12144, 12144, -1, 12145, 12145, 12145, -1, + 12146, 12146, 12146, -1, 12147, 12147, 12147, -1, + 12148, 12148, 12148, -1, 12149, 12149, 12149, -1, + 12150, 12150, 12150, -1, 12151, 12151, 12151, -1, + 12152, 12152, 12152, -1, 12153, 12153, 12153, -1, + 12154, 12154, 12154, -1, 12155, 12155, 12155, -1, + 12156, 12156, 12156, -1, 12157, 12157, 12157, -1, + 12158, 12158, 12158, -1, 12159, 12159, 12159, -1, + 12160, 12160, 12160, -1, 12161, 12161, 12161, -1, + 12162, 12162, 12162, -1, 12163, 12163, 12163, -1, + 12164, 12164, 12164, -1, 12165, 12165, 12165, -1, + 12166, 12166, 12166, -1, 12167, 12167, 12167, -1, + 12168, 12168, 12168, -1, 12169, 12169, 12169, -1, + 12170, 12170, 12170, -1, 12171, 12171, 12171, -1, + 12172, 12172, 12172, -1, 12173, 12173, 12173, -1, + 12174, 12174, 12174, -1, 12175, 12175, 12175, -1, + 12176, 12176, 12176, -1, 12177, 12177, 12177, -1, + 12178, 12178, 12178, -1, 12179, 12179, 12179, -1, + 12180, 12180, 12180, -1, 12181, 12181, 12181, -1, + 12182, 12182, 12182, -1, 12183, 12183, 12183, -1, + 12184, 12184, 12184, -1, 12185, 12185, 12185, -1, + 12186, 12186, 12186, -1, 12187, 12187, 12187, -1, + 12188, 12188, 12188, -1, 12189, 12189, 12189, -1, + 12190, 12190, 12190, -1, 12191, 12191, 12191, -1, + 12192, 12192, 12192, -1, 12193, 12193, 12193, -1, + 12194, 12194, 12194, -1, 12195, 12195, 12195, -1, + 12196, 12196, 12196, -1, 12197, 12197, 12197, -1, + 12198, 12198, 12198, -1, 12199, 12199, 12199, -1, + 12200, 12200, 12200, -1, 12201, 12201, 12201, -1, + 12202, 12202, 12202, -1, 12203, 12203, 12203, -1, + 12204, 12204, 12204, -1, 12205, 12205, 12205, -1, + 12206, 12206, 12206, -1, 12207, 12207, 12207, -1, + 12208, 12208, 12208, -1, 12209, 12209, 12209, -1, + 12210, 12210, 12210, -1, 12211, 12211, 12211, -1, + 12212, 12212, 12212, -1, 12213, 12213, 12213, -1, + 12214, 12214, 12214, -1, 12215, 12215, 12215, -1, + 12216, 12216, 12216, -1, 12217, 12217, 12217, -1, + 12218, 12218, 12218, -1, 12219, 12219, 12219, -1, + 12220, 12220, 12220, -1, 12221, 12221, 12221, -1, + 12222, 12222, 12222, -1, 12223, 12223, 12223, -1, + 12224, 12224, 12224, -1, 12225, 12225, 12225, -1, + 12226, 12226, 12226, -1, 12227, 12227, 12227, -1, + 12228, 12228, 12228, -1, 12229, 12229, 12229, -1, + 12230, 12230, 12230, -1, 12231, 12231, 12231, -1, + 12232, 12232, 12232, -1, 12233, 12233, 12233, -1, + 12234, 12234, 12234, -1, 12235, 12235, 12235, -1, + 12236, 12236, 12236, -1, 12237, 12237, 12237, -1, + 12238, 12238, 12238, -1, 12239, 12239, 12239, -1, + 12240, 12240, 12240, -1, 12241, 12241, 12241, -1, + 12242, 12242, 12242, -1, 12243, 12243, 12243, -1, + 12244, 12244, 12244, -1, 12245, 12245, 12245, -1, + 12246, 12246, 12246, -1, 12247, 12247, 12247, -1, + 12248, 12248, 12248, -1, 12249, 12249, 12249, -1, + 12250, 12250, 12250, -1, 12251, 12251, 12251, -1, + 12252, 12252, 12252, -1, 12253, 12253, 12253, -1, + 12254, 12254, 12254, -1, 12255, 12255, 12255, -1, + 12256, 12256, 12256, -1, 12257, 12257, 12257, -1, + 12258, 12258, 12258, -1, 12259, 12259, 12259, -1, + 12260, 12260, 12260, -1, 12261, 12261, 12261, -1, + 12262, 12262, 12262, -1, 12263, 12263, 12263, -1, + 12264, 12264, 12264, -1, 12265, 12265, 12265, -1, + 12266, 12266, 12266, -1, 12267, 12267, 12267, -1, + 12268, 12268, 12268, -1, 12269, 12269, 12269, -1, + 12270, 12270, 12270, -1, 12271, 12271, 12271, -1, + 12272, 12272, 12272, -1, 12273, 12273, 12273, -1, + 12274, 12274, 12274, -1, 12275, 12275, 12275, -1, + 12276, 12276, 12276, -1, 12277, 12277, 12277, -1, + 12278, 12278, 12278, -1, 12279, 12279, 12279, -1, + 12280, 12280, 12280, -1, 12281, 12281, 12281, -1, + 12282, 12282, 12282, -1, 12283, 12283, 12283, -1, + 12284, 12284, 12284, -1, 12285, 12285, 12285, -1, + 12286, 12286, 12286, -1, 12287, 12287, 12287, -1, + 12288, 12288, 12288, -1, 12289, 12289, 12289, -1, + 12290, 12290, 12290, -1, 12291, 12291, 12291, -1, + 12292, 12292, 12292, -1, 12293, 12293, 12293, -1, + 12294, 12294, 12294, -1, 12295, 12295, 12295, -1, + 12296, 12296, 12296, -1, 12297, 12297, 12297, -1, + 12298, 12298, 12298, -1, 12299, 12299, 12299, -1, + 12300, 12300, 12300, -1, 12301, 12301, 12301, -1, + 12302, 12302, 12302, -1, 12303, 12303, 12303, -1, + 12304, 12304, 12304, -1, 12305, 12305, 12305, -1, + 12306, 12306, 12306, -1, 12307, 12307, 12307, -1, + 12308, 12308, 12308, -1, 12309, 12309, 12309, -1, + 12310, 12310, 12310, -1, 12311, 12311, 12311, -1, + 12312, 12312, 12312, -1, 12313, 12313, 12313, -1, + 12314, 12314, 12314, -1, 12315, 12315, 12315, -1, + 12316, 12316, 12316, -1, 12317, 12317, 12317, -1, + 12318, 12318, 12318, -1, 12319, 12319, 12319, -1, + 12320, 12320, 12320, -1, 12321, 12321, 12321, -1, + 12322, 12322, 12322, -1, 12323, 12323, 12323, -1, + 12324, 12324, 12324, -1, 12325, 12325, 12325, -1, + 12326, 12326, 12326, -1, 12327, 12327, 12327, -1, + 12328, 12328, 12328, -1, 12329, 12329, 12329, -1, + 12330, 12330, 12330, -1, 12331, 12331, 12331, -1, + 12332, 12332, 12332, -1, 12333, 12333, 12333, -1, + 12334, 12334, 12334, -1, 12335, 12335, 12335, -1, + 12336, 12336, 12336, -1, 12337, 12337, 12337, -1, + 12338, 12338, 12338, -1, 12339, 12339, 12339, -1, + 12340, 12340, 12340, -1, 12341, 12341, 12341, -1, + 12342, 12342, 12342, -1, 12343, 12343, 12343, -1, + 12344, 12344, 12344, -1, 12345, 12345, 12345, -1, + 12346, 12346, 12346, -1, 12347, 12347, 12347, -1, + 12348, 12348, 12348, -1, 12349, 12349, 12349, -1, + 12350, 12350, 12350, -1, 12351, 12351, 12351, -1, + 12352, 12352, 12352, -1, 12353, 12353, 12353, -1, + 12354, 12354, 12354, -1, 12355, 12355, 12355, -1, + 12356, 12356, 12356, -1, 12357, 12357, 12357, -1, + 12358, 12358, 12358, -1, 12359, 12359, 12359, -1, + 12360, 12360, 12360, -1, 12361, 12361, 12361, -1, + 12362, 12362, 12362, -1, 12363, 12363, 12363, -1, + 12364, 12364, 12364, -1, 12365, 12365, 12365, -1, + 12366, 12366, 12366, -1, 12367, 12367, 12367, -1, + 12368, 12368, 12368, -1, 12369, 12369, 12369, -1, + 12370, 12370, 12370, -1, 12371, 12371, 12371, -1, + 12372, 12372, 12372, -1, 12373, 12373, 12373, -1, + 12374, 12374, 12374, -1, 12375, 12375, 12375, -1, + 12376, 12376, 12376, -1, 12377, 12377, 12377, -1, + 12378, 12378, 12378, -1, 12379, 12379, 12379, -1, + 12380, 12380, 12380, -1, 12381, 12381, 12381, -1, + 12382, 12382, 12382, -1, 12383, 12383, 12383, -1, + 12384, 12384, 12384, -1, 12385, 12385, 12385, -1, + 12386, 12386, 12386, -1, 12387, 12387, 12387, -1, + 12388, 12388, 12388, -1, 12389, 12389, 12389, -1, + 12390, 12390, 12390, -1, 12391, 12391, 12391, -1, + 12392, 12392, 12392, -1, 12393, 12393, 12393, -1, + 12394, 12394, 12394, -1, 12395, 12395, 12395, -1, + 12396, 12396, 12396, -1, 12397, 12397, 12397, -1, + 12398, 12398, 12398, -1, 12399, 12399, 12399, -1, + 12400, 12400, 12400, -1, 12401, 12401, 12401, -1, + 12402, 12402, 12402, -1, 12403, 12403, 12403, -1, + 12404, 12404, 12404, -1, 12405, 12405, 12405, -1, + 12406, 12406, 12406, -1, 12407, 12407, 12407, -1, + 12408, 12408, 12408, -1, 12409, 12409, 12409, -1, + 12410, 12410, 12410, -1, 12411, 12411, 12411, -1, + 12412, 12412, 12412, -1, 12413, 12413, 12413, -1, + 12414, 12414, 12414, -1, 12415, 12415, 12415, -1, + 12416, 12416, 12416, -1, 12417, 12417, 12417, -1, + 12418, 12418, 12418, -1, 12419, 12419, 12419, -1, + 12420, 12420, 12420, -1, 12421, 12421, 12421, -1, + 12422, 12422, 12422, -1, 12423, 12423, 12423, -1, + 12424, 12424, 12424, -1, 12425, 12425, 12425, -1, + 12426, 12426, 12426, -1, 12427, 12427, 12427, -1, + 12428, 12428, 12428, -1, 12429, 12429, 12429, -1, + 12430, 12430, 12430, -1, 12431, 12431, 12431, -1, + 12432, 12432, 12432, -1, 12433, 12433, 12433, -1, + 12434, 12434, 12434, -1, 12435, 12435, 12435, -1, + 12436, 12436, 12436, -1, 12437, 12437, 12437, -1, + 12438, 12438, 12438, -1, 12439, 12439, 12439, -1, + 12440, 12440, 12440, -1, 12441, 12441, 12441, -1, + 12442, 12442, 12442, -1, 12443, 12443, 12443, -1, + 12444, 12444, 12444, -1, 12445, 12445, 12445, -1, + 12446, 12446, 12446, -1, 12447, 12447, 12447, -1, + 12448, 12448, 12448, -1, 12449, 12449, 12449, -1, + 12450, 12450, 12450, -1, 12451, 12451, 12451, -1, + 12452, 12452, 12452, -1, 12453, 12453, 12453, -1, + 12454, 12454, 12454, -1, 12455, 12455, 12455, -1, + 12456, 12456, 12456, -1, 12457, 12457, 12457, -1, + 12458, 12458, 12458, -1, 12459, 12459, 12459, -1, + 12460, 12460, 12460, -1, 12461, 12461, 12461, -1, + 12462, 12462, 12462, -1, 12463, 12463, 12463, -1, + 12464, 12464, 12464, -1, 12465, 12465, 12465, -1, + 12466, 12466, 12466, -1, 12467, 12467, 12467, -1, + 12468, 12468, 12468, -1, 12469, 12469, 12469, -1, + 12470, 12470, 12470, -1, 12471, 12471, 12471, -1, + 12472, 12472, 12472, -1, 12473, 12473, 12473, -1, + 12474, 12474, 12474, -1, 12475, 12475, 12475, -1, + 12476, 12476, 12476, -1, 12477, 12477, 12477, -1, + 12478, 12478, 12478, -1, 12479, 12479, 12479, -1, + 12480, 12480, 12480, -1, 12481, 12481, 12481, -1, + 12482, 12482, 12482, -1, 12483, 12483, 12483, -1, + 12484, 12484, 12484, -1, 12485, 12485, 12485, -1, + 12486, 12486, 12486, -1, 12487, 12487, 12487, -1, + 12488, 12488, 12488, -1, 12489, 12489, 12489, -1, + 12490, 12490, 12490, -1, 12491, 12491, 12491, -1, + 12492, 12492, 12492, -1, 12493, 12493, 12493, -1, + 12494, 12494, 12494, -1, 12495, 12495, 12495, -1, + 12496, 12496, 12496, -1, 12497, 12497, 12497, -1, + 12498, 12498, 12498, -1, 12499, 12499, 12499, -1, + 12500, 12500, 12500, -1, 12501, 12501, 12501, -1, + 12502, 12502, 12502, -1, 12503, 12503, 12503, -1, + 12504, 12504, 12504, -1, 12505, 12505, 12505, -1, + 12506, 12506, 12506, -1, 12507, 12507, 12507, -1, + 12508, 12508, 12508, -1, 12509, 12509, 12509, -1, + 12510, 12510, 12510, -1, 12511, 12511, 12511, -1, + 12512, 12512, 12512, -1, 12513, 12513, 12513, -1, + 12514, 12514, 12514, -1, 12515, 12515, 12515, -1, + 12516, 12516, 12516, -1, 12517, 12517, 12517, -1, + 12518, 12518, 12518, -1, 12519, 12519, 12519, -1, + 12520, 12520, 12520, -1, 12521, 12521, 12521, -1, + 12522, 12522, 12522, -1, 12523, 12523, 12523, -1, + 12524, 12524, 12524, -1, 12525, 12525, 12525, -1, + 12526, 12526, 12526, -1, 12527, 12527, 12527, -1, + 12528, 12528, 12528, -1, 12529, 12529, 12529, -1, + 12530, 12530, 12530, -1, 12531, 12531, 12531, -1, + 12532, 12532, 12532, -1, 12533, 12533, 12533, -1, + 12534, 12534, 12534, -1, 12535, 12535, 12535, -1, + 12536, 12536, 12536, -1, 12537, 12537, 12537, -1, + 12538, 12538, 12538, -1, 12539, 12539, 12539, -1, + 12540, 12540, 12540, -1, 12541, 12541, 12541, -1, + 12542, 12542, 12542, -1, 12543, 12543, 12543, -1, + 12544, 12544, 12544, -1, 12545, 12545, 12545, -1, + 12546, 12546, 12546, -1, 12547, 12547, 12547, -1, + 12548, 12548, 12548, -1, 12549, 12549, 12549, -1, + 12550, 12550, 12550, -1, 12551, 12551, 12551, -1, + 12552, 12552, 12552, -1, 12553, 12553, 12553, -1, + 12554, 12554, 12554, -1, 12555, 12555, 12555, -1, + 12556, 12556, 12556, -1, 12557, 12557, 12557, -1, + 12558, 12558, 12558, -1, 12559, 12559, 12559, -1, + 12560, 12560, 12560, -1, 12561, 12561, 12561, -1, + 12562, 12562, 12562, -1, 12563, 12563, 12563, -1, + 12564, 12564, 12564, -1, 12565, 12565, 12565, -1, + 12566, 12566, 12566, -1, 12567, 12567, 12567, -1, + 12568, 12568, 12568, -1, 12569, 12569, 12569, -1, + 12570, 12570, 12570, -1, 12571, 12571, 12571, -1, + 12572, 12572, 12572, -1, 12573, 12573, 12573, -1, + 12574, 12574, 12574, -1, 12575, 12575, 12575, -1, + 12576, 12576, 12576, -1, 12577, 12577, 12577, -1, + 12578, 12578, 12578, -1, 12579, 12579, 12579, -1, + 12580, 12580, 12580, -1, 12581, 12581, 12581, -1, + 12582, 12582, 12582, -1, 12583, 12583, 12583, -1, + 12584, 12584, 12584, -1, 12585, 12585, 12585, -1, + 12586, 12586, 12586, -1, 12587, 12587, 12587, -1, + 12588, 12588, 12588, -1, 12589, 12589, 12589, -1, + 12590, 12590, 12590, -1, 12591, 12591, 12591, -1, + 12592, 12592, 12592, -1, 12593, 12593, 12593, -1, + 12594, 12594, 12594, -1, 12595, 12595, 12595, -1, + 12596, 12596, 12596, -1, 12597, 12597, 12597, -1, + 12598, 12598, 12598, -1, 12599, 12599, 12599, -1, + 12600, 12600, 12600, -1, 12601, 12601, 12601, -1, + 12602, 12602, 12602, -1, 12603, 12603, 12603, -1, + 12604, 12604, 12604, -1, 12605, 12605, 12605, -1, + 12606, 12606, 12606, -1, 12607, 12607, 12607, -1, + 12608, 12608, 12608, -1, 12609, 12609, 12609, -1, + 12610, 12610, 12610, -1, 12611, 12611, 12611, -1, + 12612, 12612, 12612, -1, 12613, 12613, 12613, -1, + 12614, 12614, 12614, -1, 12615, 12615, 12615, -1, + 12616, 12616, 12616, -1, 12617, 12617, 12617, -1, + 12618, 12618, 12618, -1, 12619, 12619, 12619, -1, + 12620, 12620, 12620, -1, 12621, 12621, 12621, -1, + 12622, 12622, 12622, -1, 12623, 12623, 12623, -1, + 12624, 12624, 12624, -1, 12625, 12625, 12625, -1, + 12626, 12626, 12626, -1, 12627, 12627, 12627, -1, + 12628, 12628, 12628, -1, 12629, 12629, 12629, -1, + 12630, 12630, 12630, -1, 12631, 12631, 12631, -1, + 12632, 12632, 12632, -1, 12633, 12633, 12633, -1, + 12634, 12634, 12634, -1, 12635, 12635, 12635, -1, + 12636, 12636, 12636, -1, 12637, 12637, 12637, -1, + 12638, 12638, 12638, -1, 12639, 12639, 12639, -1, + 12640, 12640, 12640, -1, 12641, 12641, 12641, -1, + 12642, 12642, 12642, -1, 12643, 12643, 12643, -1, + 12644, 12644, 12644, -1, 12645, 12645, 12645, -1, + 12646, 12646, 12646, -1, 12647, 12647, 12647, -1, + 12648, 12648, 12648, -1, 12649, 12649, 12649, -1, + 12650, 12650, 12650, -1, 12651, 12651, 12651, -1, + 12652, 12652, 12652, -1, 12653, 12653, 12653, -1, + 12654, 12654, 12654, -1, 12655, 12655, 12655, -1, + 12656, 12656, 12656, -1, 12657, 12657, 12657, -1, + 12658, 12658, 12658, -1, 12659, 12659, 12659, -1, + 12660, 12660, 12660, -1, 12661, 12661, 12661, -1, + 12662, 12662, 12662, -1, 12663, 12663, 12663, -1, + 12664, 12664, 12664, -1, 12665, 12665, 12665, -1, + 12666, 12666, 12666, -1, 12667, 12667, 12667, -1, + 12668, 12668, 12668, -1, 12669, 12669, 12669, -1, + 12670, 12670, 12670, -1, 12671, 12671, 12671, -1, + 12672, 12672, 12672, -1, 12673, 12673, 12673, -1, + 12674, 12674, 12674, -1, 12675, 12675, 12675, -1, + 12676, 12676, 12676, -1, 12677, 12677, 12677, -1, + 12678, 12678, 12678, -1, 12679, 12679, 12679, -1, + 12680, 12680, 12680, -1, 12681, 12681, 12681, -1, + 12682, 12682, 12682, -1, 12683, 12683, 12683, -1, + 12684, 12684, 12684, -1, 12685, 12685, 12685, -1, + 12686, 12686, 12686, -1, 12687, 12687, 12687, -1, + 12688, 12688, 12688, -1, 12689, 12689, 12689, -1, + 12690, 12690, 12690, -1, 12691, 12691, 12691, -1, + 12692, 12692, 12692, -1, 12693, 12693, 12693, -1, + 12694, 12694, 12694, -1, 12695, 12695, 12695, -1, + 12696, 12696, 12696, -1, 12697, 12697, 12697, -1, + 12698, 12698, 12698, -1, 12699, 12699, 12699, -1, + 12700, 12700, 12700, -1, 12701, 12701, 12701, -1, + 12702, 12702, 12702, -1, 12703, 12703, 12703, -1, + 12704, 12704, 12704, -1, 12705, 12705, 12705, -1, + 12706, 12706, 12706, -1, 12707, 12707, 12707, -1, + 12708, 12708, 12708, -1, 12709, 12709, 12709, -1, + 12710, 12710, 12710, -1, 12711, 12711, 12711, -1, + 12712, 12712, 12712, -1, 12713, 12713, 12713, -1, + 12714, 12714, 12714, -1, 12715, 12715, 12715, -1, + 12716, 12716, 12716, -1, 12717, 12717, 12717, -1, + 12718, 12718, 12718, -1, 12719, 12719, 12719, -1, + 12720, 12720, 12720, -1, 12721, 12721, 12721, -1, + 12722, 12722, 12722, -1, 12723, 12723, 12723, -1, + 12724, 12724, 12724, -1, 12725, 12725, 12725, -1, + 12726, 12726, 12726, -1, 12727, 12727, 12727, -1, + 12728, 12728, 12728, -1, 12729, 12729, 12729, -1, + 12730, 12730, 12730, -1, 12731, 12731, 12731, -1, + 12732, 12732, 12732, -1, 12733, 12733, 12733, -1, + 12734, 12734, 12734, -1, 12735, 12735, 12735, -1, + 12736, 12736, 12736, -1, 12737, 12737, 12737, -1, + 12738, 12738, 12738, -1, 12739, 12739, 12739, -1, + 12740, 12740, 12740, -1, 12741, 12741, 12741, -1, + 12742, 12742, 12742, -1, 12743, 12743, 12743, -1, + 12744, 12744, 12744, -1, 12745, 12745, 12745, -1, + 12746, 12746, 12746, -1, 12747, 12747, 12747, -1, + 12748, 12748, 12748, -1, 12749, 12749, 12749, -1, + 12750, 12750, 12750, -1, 12751, 12751, 12751, -1, + 12752, 12752, 12752, -1, 12753, 12753, 12753, -1, + 12754, 12754, 12754, -1, 12755, 12755, 12755, -1, + 12756, 12756, 12756, -1, 12757, 12757, 12757, -1, + 12758, 12758, 12758, -1, 12759, 12759, 12759, -1, + 12760, 12760, 12760, -1, 12761, 12761, 12761, -1, + 12762, 12762, 12762, -1, 12763, 12763, 12763, -1, + 12764, 12764, 12764, -1, 12765, 12765, 12765, -1, + 12766, 12766, 12766, -1, 12767, 12767, 12767, -1, + 12768, 12768, 12768, -1, 12769, 12769, 12769, -1, + 12770, 12770, 12770, -1, 12771, 12771, 12771, -1, + 12772, 12772, 12772, -1, 12773, 12773, 12773, -1, + 12774, 12774, 12774, -1, 12775, 12775, 12775, -1, + 12776, 12776, 12776, -1, 12777, 12777, 12777, -1, + 12778, 12778, 12778, -1, 12779, 12779, 12779, -1, + 12780, 12780, 12780, -1, 12781, 12781, 12781, -1, + 12782, 12782, 12782, -1, 12783, 12783, 12783, -1, + 12784, 12784, 12784, -1, 12785, 12785, 12785, -1, + 12786, 12786, 12786, -1, 12787, 12787, 12787, -1, + 12788, 12788, 12788, -1, 12789, 12789, 12789, -1, + 12790, 12790, 12790, -1, 12791, 12791, 12791, -1, + 12792, 12792, 12792, -1, 12793, 12793, 12793, -1, + 12794, 12794, 12794, -1, 12795, 12795, 12795, -1, + 12796, 12796, 12796, -1, 12797, 12797, 12797, -1, + 12798, 12798, 12798, -1, 12799, 12799, 12799, -1, + 12800, 12800, 12800, -1, 12801, 12801, 12801, -1, + 12802, 12802, 12802, -1, 12803, 12803, 12803, -1, + 12804, 12804, 12804, -1, 12805, 12805, 12805, -1, + 12806, 12806, 12806, -1, 12807, 12807, 12807, -1, + 12808, 12808, 12808, -1, 12809, 12809, 12809, -1, + 12810, 12810, 12810, -1, 12811, 12811, 12811, -1, + 12812, 12812, 12812, -1, 12813, 12813, 12813, -1, + 12814, 12814, 12814, -1, 12815, 12815, 12815, -1, + 12816, 12816, 12816, -1, 12817, 12817, 12817, -1, + 12818, 12818, 12818, -1, 12819, 12819, 12819, -1, + 12820, 12820, 12820, -1, 12821, 12821, 12821, -1, + 12822, 12822, 12822, -1, 12823, 12823, 12823, -1, + 12824, 12824, 12824, -1, 12825, 12825, 12825, -1, + 12826, 12826, 12826, -1, 12827, 12827, 12827, -1, + 12828, 12828, 12828, -1, 12829, 12829, 12829, -1, + 12830, 12830, 12830, -1, 12831, 12831, 12831, -1, + 12832, 12832, 12832, -1, 12833, 12833, 12833, -1, + 12834, 12834, 12834, -1, 12835, 12835, 12835, -1, + 12836, 12836, 12836, -1, 12837, 12837, 12837, -1, + 12838, 12838, 12838, -1, 12839, 12839, 12839, -1, + 12840, 12840, 12840, -1, 12841, 12841, 12841, -1, + 12842, 12842, 12842, -1, 12843, 12843, 12843, -1, + 12844, 12844, 12844, -1, 12845, 12845, 12845, -1, + 12846, 12846, 12846, -1, 12847, 12847, 12847, -1, + 12848, 12848, 12848, -1, 12849, 12849, 12849, -1, + 12850, 12850, 12850, -1, 12851, 12851, 12851, -1, + 12852, 12852, 12852, -1, 12853, 12853, 12853, -1, + 12854, 12854, 12854, -1, 12855, 12855, 12855, -1, + 12856, 12856, 12856, -1, 12857, 12857, 12857, -1, + 12858, 12858, 12858, -1, 12859, 12859, 12859, -1, + 12860, 12860, 12860, -1, 12861, 12861, 12861, -1, + 12862, 12862, 12862, -1, 12863, 12863, 12863, -1, + 12864, 12864, 12864, -1, 12865, 12865, 12865, -1, + 12866, 12866, 12866, -1, 12867, 12867, 12867, -1, + 12868, 12868, 12868, -1, 12869, 12869, 12869, -1, + 12870, 12870, 12870, -1, 12871, 12871, 12871, -1, + 12872, 12872, 12872, -1, 12873, 12873, 12873, -1, + 12874, 12874, 12874, -1, 12875, 12875, 12875, -1, + 12876, 12876, 12876, -1, 12877, 12877, 12877, -1, + 12878, 12878, 12878, -1, 12879, 12879, 12879, -1, + 12880, 12880, 12880, -1, 12881, 12881, 12881, -1, + 12882, 12882, 12882, -1, 12883, 12883, 12883, -1, + 12884, 12884, 12884, -1, 12885, 12885, 12885, -1, + 12886, 12886, 12886, -1, 12887, 12887, 12887, -1, + 12888, 12888, 12888, -1, 12889, 12889, 12889, -1, + 12890, 12890, 12890, -1, 12891, 12891, 12891, -1, + 12892, 12892, 12892, -1, 12893, 12893, 12893, -1, + 12894, 12894, 12894, -1, 12895, 12895, 12895, -1, + 12896, 12896, 12896, -1, 12897, 12897, 12897, -1, + 12898, 12898, 12898, -1, 12899, 12899, 12899, -1, + 12900, 12900, 12900, -1, 12901, 12901, 12901, -1, + 12902, 12902, 12902, -1, 12903, 12903, 12903, -1, + 12904, 12904, 12904, -1, 12905, 12905, 12905, -1, + 12906, 12906, 12906, -1, 12907, 12907, 12907, -1, + 12908, 12908, 12908, -1, 12909, 12909, 12909, -1, + 12910, 12910, 12910, -1, 12911, 12911, 12911, -1, + 12912, 12912, 12912, -1, 12913, 12913, 12913, -1, + 12914, 12914, 12914, -1, 12915, 12915, 12915, -1, + 12916, 12916, 12916, -1, 12917, 12917, 12917, -1, + 12918, 12918, 12918, -1, 12919, 12919, 12919, -1, + 12920, 12920, 12920, -1, 12921, 12921, 12921, -1, + 12922, 12922, 12922, -1, 12923, 12923, 12923, -1, + 12924, 12924, 12924, -1, 12925, 12925, 12925, -1, + 12926, 12926, 12926, -1, 12927, 12927, 12927, -1, + 12928, 12928, 12928, -1, 12929, 12929, 12929, -1, + 12930, 12930, 12930, -1, 12931, 12931, 12931, -1, + 12932, 12932, 12932, -1, 12933, 12933, 12933, -1, + 12934, 12934, 12934, -1, 12935, 12935, 12935, -1, + 12936, 12936, 12936, -1, 12937, 12937, 12937, -1, + 12938, 12938, 12938, -1, 12939, 12939, 12939, -1, + 12940, 12940, 12940, -1, 12941, 12941, 12941, -1, + 12942, 12942, 12942, -1, 12943, 12943, 12943, -1, + 12944, 12944, 12944, -1, 12945, 12945, 12945, -1, + 12946, 12946, 12946, -1, 12947, 12947, 12947, -1, + 12948, 12948, 12948, -1, 12949, 12949, 12949, -1, + 12950, 12950, 12950, -1, 12951, 12951, 12951, -1, + 12952, 12952, 12952, -1, 12953, 12953, 12953, -1, + 12954, 12954, 12954, -1, 12955, 12955, 12955, -1, + 12956, 12956, 12956, -1, 12957, 12957, 12957, -1, + 12958, 12958, 12958, -1, 12959, 12959, 12959, -1, + 12960, 12960, 12960, -1, 12961, 12961, 12961, -1, + 12962, 12962, 12962, -1, 12963, 12963, 12963, -1, + 12964, 12964, 12964, -1, 12965, 12965, 12965, -1, + 12966, 12966, 12966, -1, 12967, 12967, 12967, -1, + 12968, 12968, 12968, -1, 12969, 12969, 12969, -1, + 12970, 12970, 12970, -1, 12971, 12971, 12971, -1, + 12972, 12972, 12972, -1, 12973, 12973, 12973, -1, + 12974, 12974, 12974, -1, 12975, 12975, 12975, -1, + 12976, 12976, 12976, -1, 12977, 12977, 12977, -1, + 12978, 12978, 12978, -1, 12979, 12979, 12979, -1, + 12980, 12980, 12980, -1, 12981, 12981, 12981, -1, + 12982, 12982, 12982, -1, 12983, 12983, 12983, -1, + 12984, 12984, 12984, -1, 12985, 12985, 12985, -1, + 12986, 12986, 12986, -1, 12987, 12987, 12987, -1, + 12988, 12988, 12988, -1, 12989, 12989, 12989, -1, + 12990, 12990, 12990, -1, 12991, 12991, 12991, -1, + 12992, 12992, 12992, -1, 12993, 12993, 12993, -1, + 12994, 12994, 12994, -1, 12995, 12995, 12995, -1, + 12996, 12996, 12996, -1, 12997, 12997, 12997, -1, + 12998, 12998, 12998, -1, 12999, 12999, 12999, -1, + 13000, 13000, 13000, -1, 13001, 13001, 13001, -1, + 13002, 13002, 13002, -1, 13003, 13003, 13003, -1, + 13004, 13004, 13004, -1, 13005, 13005, 13005, -1, + 13006, 13006, 13006, -1, 13007, 13007, 13007, -1, + 13008, 13008, 13008, -1, 13009, 13009, 13009, -1, + 13010, 13010, 13010, -1, 13011, 13011, 13011, -1, + 13012, 13012, 13012, -1, 13013, 13013, 13013, -1, + 13014, 13014, 13014, -1, 13015, 13015, 13015, -1, + 13016, 13016, 13016, -1, 13017, 13017, 13017, -1, + 13018, 13018, 13018, -1, 13019, 13019, 13019, -1, + 13020, 13020, 13020, -1, 13021, 13021, 13021, -1, + 13022, 13022, 13022, -1, 13023, 13023, 13023, -1, + 13024, 13024, 13024, -1, 13025, 13025, 13025, -1, + 13026, 13026, 13026, -1, 13027, 13027, 13027, -1, + 13028, 13028, 13028, -1, 13029, 13029, 13029, -1, + 13030, 13030, 13030, -1, 13031, 13031, 13031, -1, + 13032, 13032, 13032, -1, 13033, 13033, 13033, -1, + 13034, 13034, 13034, -1, 13035, 13035, 13035, -1, + 13036, 13036, 13036, -1, 13037, 13037, 13037, -1, + 13038, 13038, 13038, -1, 13039, 13039, 13039, -1, + 13040, 13040, 13040, -1, 13041, 13041, 13041, -1, + 13042, 13042, 13042, -1, 13043, 13043, 13043, -1, + 13044, 13044, 13044, -1, 13045, 13045, 13045, -1, + 13046, 13046, 13046, -1, 13047, 13047, 13047, -1, + 13048, 13048, 13048, -1, 13049, 13049, 13049, -1, + 13050, 13050, 13050, -1, 13051, 13051, 13051, -1, + 13052, 13052, 13052, -1, 13053, 13053, 13053, -1, + 13054, 13054, 13054, -1, 13055, 13055, 13055, -1, + 13056, 13056, 13056, -1, 13057, 13057, 13057, -1, + 13058, 13058, 13058, -1, 13059, 13059, 13059, -1, + 13060, 13060, 13060, -1, 13061, 13061, 13061, -1, + 13062, 13062, 13062, -1, 13063, 13063, 13063, -1, + 13064, 13064, 13064, -1, 13065, 13065, 13065, -1, + 13066, 13066, 13066, -1, 13067, 13067, 13067, -1, + 13068, 13068, 13068, -1, 13069, 13069, 13069, -1, + 13070, 13070, 13070, -1, 13071, 13071, 13071, -1, + 13072, 13072, 13072, -1, 13073, 13073, 13073, -1, + 13074, 13074, 13074, -1, 13075, 13075, 13075, -1, + 13076, 13076, 13076, -1, 13077, 13077, 13077, -1, + 13078, 13078, 13078, -1, 13079, 13079, 13079, -1, + 13080, 13080, 13080, -1, 13081, 13081, 13081, -1, + 13082, 13082, 13082, -1, 13083, 13083, 13083, -1, + 13084, 13084, 13084, -1, 13085, 13085, 13085, -1, + 13086, 13086, 13086, -1, 13087, 13087, 13087, -1, + 13088, 13088, 13088, -1, 13089, 13089, 13089, -1, + 13090, 13090, 13090, -1, 13091, 13091, 13091, -1, + 13092, 13092, 13092, -1, 13093, 13093, 13093, -1, + 13094, 13094, 13094, -1, 13095, 13095, 13095, -1, + 13096, 13096, 13096, -1, 13097, 13097, 13097, -1, + 13098, 13098, 13098, -1, 13099, 13099, 13099, -1, + 13100, 13100, 13100, -1, 13101, 13101, 13101, -1, + 13102, 13102, 13102, -1, 13103, 13103, 13103, -1, + 13104, 13104, 13104, -1, 13105, 13105, 13105, -1, + 13106, 13106, 13106, -1, 13107, 13107, 13107, -1, + 13108, 13108, 13108, -1, 13109, 13109, 13109, -1, + 13110, 13110, 13110, -1, 13111, 13111, 13111, -1, + 13112, 13112, 13112, -1, 13113, 13113, 13113, -1, + 13114, 13114, 13114, -1, 13115, 13115, 13115, -1, + 13116, 13116, 13116, -1, 13117, 13117, 13117, -1, + 13118, 13118, 13118, -1, 13119, 13119, 13119, -1, + 13120, 13120, 13120, -1, 13121, 13121, 13121, -1, + 13122, 13122, 13122, -1, 13123, 13123, 13123, -1, + 13124, 13124, 13124, -1, 13125, 13125, 13125, -1, + 13126, 13126, 13126, -1, 13127, 13127, 13127, -1, + 13128, 13128, 13128, -1, 13129, 13129, 13129, -1, + 13130, 13130, 13130, -1, 13131, 13131, 13131, -1, + 13132, 13132, 13132, -1, 13133, 13133, 13133, -1, + 13134, 13134, 13134, -1, 13135, 13135, 13135, -1, + 13136, 13136, 13136, -1, 13137, 13137, 13137, -1, + 13138, 13138, 13138, -1, 13139, 13139, 13139, -1, + 13140, 13140, 13140, -1, 13141, 13141, 13141, -1, + 13142, 13142, 13142, -1, 13143, 13143, 13143, -1, + 13144, 13144, 13144, -1, 13145, 13145, 13145, -1, + 13146, 13146, 13146, -1, 13147, 13147, 13147, -1, + 13148, 13148, 13148, -1, 13149, 13149, 13149, -1, + 13150, 13150, 13150, -1, 13151, 13151, 13151, -1, + 13152, 13152, 13152, -1, 13153, 13153, 13153, -1, + 13154, 13154, 13154, -1, 13155, 13155, 13155, -1, + 13156, 13156, 13156, -1, 13157, 13157, 13157, -1, + 13158, 13158, 13158, -1, 13159, 13159, 13159, -1, + 13160, 13160, 13160, -1, 13161, 13161, 13161, -1, + 13162, 13162, 13162, -1, 13163, 13163, 13163, -1, + 13164, 13164, 13164, -1, 13165, 13165, 13165, -1, + 13166, 13166, 13166, -1, 13167, 13167, 13167, -1, + 13168, 13168, 13168, -1, 13169, 13169, 13169, -1, + 13170, 13170, 13170, -1, 13171, 13171, 13171, -1, + 13172, 13172, 13172, -1, 13173, 13173, 13173, -1, + 13174, 13174, 13174, -1, 13175, 13175, 13175, -1, + 13176, 13176, 13176, -1, 13177, 13177, 13177, -1, + 13178, 13178, 13178, -1, 13179, 13179, 13179, -1, + 13180, 13180, 13180, -1, 13181, 13181, 13181, -1, + 13182, 13182, 13182, -1, 13183, 13183, 13183, -1, + 13184, 13184, 13184, -1, 13185, 13185, 13185, -1, + 13186, 13186, 13186, -1, 13187, 13187, 13187, -1, + 13188, 13188, 13188, -1, 13189, 13189, 13189, -1, + 13190, 13190, 13190, -1, 13191, 13191, 13191, -1, + 13192, 13192, 13192, -1, 13193, 13193, 13193, -1, + 13194, 13194, 13194, -1, 13195, 13195, 13195, -1, + 13196, 13196, 13196, -1, 13197, 13197, 13197, -1, + 13198, 13198, 13198, -1, 13199, 13199, 13199, -1, + 13200, 13200, 13200, -1, 13201, 13201, 13201, -1, + 13202, 13202, 13202, -1, 13203, 13203, 13203, -1, + 13204, 13204, 13204, -1, 13205, 13205, 13205, -1, + 13206, 13206, 13206, -1, 13207, 13207, 13207, -1, + 13208, 13208, 13208, -1, 13209, 13209, 13209, -1, + 13210, 13210, 13210, -1, 13211, 13211, 13211, -1, + 13212, 13212, 13212, -1, 13213, 13213, 13213, -1, + 13214, 13214, 13214, -1, 13215, 13215, 13215, -1, + 13216, 13216, 13216, -1, 13217, 13217, 13217, -1, + 13218, 13218, 13218, -1, 13219, 13219, 13219, -1, + 13220, 13220, 13220, -1, 13221, 13221, 13221, -1, + 13222, 13222, 13222, -1, 13223, 13223, 13223, -1, + 13224, 13224, 13224, -1, 13225, 13225, 13225, -1, + 13226, 13226, 13226, -1, 13227, 13227, 13227, -1, + 13228, 13228, 13228, -1, 13229, 13229, 13229, -1, + 13230, 13230, 13230, -1, 13231, 13231, 13231, -1, + 13232, 13232, 13232, -1, 13233, 13233, 13233, -1, + 13234, 13234, 13234, -1, 13235, 13235, 13235, -1, + 13236, 13236, 13236, -1, 13237, 13237, 13237, -1, + 13238, 13238, 13238, -1, 13239, 13239, 13239, -1, + 13240, 13240, 13240, -1, 13241, 13241, 13241, -1, + 13242, 13242, 13242, -1, 13243, 13243, 13243, -1, + 13244, 13244, 13244, -1, 13245, 13245, 13245, -1, + 13246, 13246, 13246, -1, 13247, 13247, 13247, -1, + 13248, 13248, 13248, -1, 13249, 13249, 13249, -1, + 13250, 13250, 13250, -1, 13251, 13251, 13251, -1, + 13252, 13252, 13252, -1, 13253, 13253, 13253, -1, + 13254, 13254, 13254, -1, 13255, 13255, 13255, -1, + 13256, 13256, 13256, -1, 13257, 13257, 13257, -1, + 13258, 13258, 13258, -1, 13259, 13259, 13259, -1, + 13260, 13260, 13260, -1, 13261, 13261, 13261, -1, + 13262, 13262, 13262, -1, 13263, 13263, 13263, -1, + 13264, 13264, 13264, -1, 13265, 13265, 13265, -1, + 13266, 13266, 13266, -1, 13267, 13267, 13267, -1, + 13268, 13268, 13268, -1, 13269, 13269, 13269, -1, + 13270, 13270, 13270, -1, 13271, 13271, 13271, -1, + 13272, 13272, 13272, -1, 13273, 13273, 13273, -1, + 13274, 13274, 13274, -1, 13275, 13275, 13275, -1, + 13276, 13276, 13276, -1, 13277, 13277, 13277, -1, + 13278, 13278, 13278, -1, 13279, 13279, 13279, -1, + 13280, 13280, 13280, -1, 13281, 13281, 13281, -1, + 13282, 13282, 13282, -1, 13283, 13283, 13283, -1, + 13284, 13284, 13284, -1, 13285, 13285, 13285, -1, + 13286, 13286, 13286, -1, 13287, 13287, 13287, -1, + 13288, 13288, 13288, -1, 13289, 13289, 13289, -1, + 13290, 13290, 13290, -1, 13291, 13291, 13291, -1, + 13292, 13292, 13292, -1, 13293, 13293, 13293, -1, + 13294, 13294, 13294, -1, 13295, 13295, 13295, -1, + 13296, 13296, 13296, -1, 13297, 13297, 13297, -1, + 13298, 13298, 13298, -1, 13299, 13299, 13299, -1, + 13300, 13300, 13300, -1, 13301, 13301, 13301, -1, + 13302, 13302, 13302, -1, 13303, 13303, 13303, -1, + 13304, 13304, 13304, -1, 13305, 13305, 13305, -1, + 13306, 13306, 13306, -1, 13307, 13307, 13307, -1, + 13308, 13308, 13308, -1, 13309, 13309, 13309, -1, + 13310, 13310, 13310, -1, 13311, 13311, 13311, -1, + 13312, 13312, 13312, -1, 13313, 13313, 13313, -1, + 13314, 13314, 13314, -1, 13315, 13315, 13315, -1, + 13316, 13316, 13316, -1, 13317, 13317, 13317, -1, + 13318, 13318, 13318, -1, 13319, 13319, 13319, -1, + 13320, 13320, 13320, -1, 13321, 13321, 13321, -1, + 13322, 13322, 13322, -1, 13323, 13323, 13323, -1, + 13324, 13324, 13324, -1, 13325, 13325, 13325, -1, + 13326, 13326, 13326, -1, 13327, 13327, 13327, -1, + 13328, 13328, 13328, -1, 13329, 13329, 13329, -1, + 13330, 13330, 13330, -1, 13331, 13331, 13331, -1, + 13332, 13332, 13332, -1, 13333, 13333, 13333, -1, + 13334, 13334, 13334, -1, 13335, 13335, 13335, -1, + 13336, 13336, 13336, -1, 13337, 13337, 13337, -1, + 13338, 13338, 13338, -1, 13339, 13339, 13339, -1, + 13340, 13340, 13340, -1, 13341, 13341, 13341, -1, + 13342, 13342, 13342, -1, 13343, 13343, 13343, -1, + 13344, 13344, 13344, -1, 13345, 13345, 13345, -1, + 13346, 13346, 13346, -1, 13347, 13347, 13347, -1, + 13348, 13348, 13348, -1, 13349, 13349, 13349, -1, + 13350, 13350, 13350, -1, 13351, 13351, 13351, -1, + 13352, 13352, 13352, -1, 13353, 13353, 13353, -1, + 13354, 13354, 13354, -1, 13355, 13355, 13355, -1, + 13356, 13356, 13356, -1, 13357, 13357, 13357, -1, + 13358, 13358, 13358, -1, 13359, 13359, 13359, -1, + 13360, 13360, 13360, -1, 13361, 13361, 13361, -1, + 13362, 13362, 13362, -1, 13363, 13363, 13363, -1, + 13364, 13364, 13364, -1, 13365, 13365, 13365, -1, + 13366, 13366, 13366, -1, 13367, 13367, 13367, -1, + 13368, 13368, 13368, -1, 13369, 13369, 13369, -1, + 13370, 13370, 13370, -1, 13371, 13371, 13371, -1, + 13372, 13372, 13372, -1, 13373, 13373, 13373, -1, + 13374, 13374, 13374, -1, 13375, 13375, 13375, -1, + 13376, 13376, 13376, -1, 13377, 13377, 13377, -1, + 13378, 13378, 13378, -1, 13379, 13379, 13379, -1, + 13380, 13380, 13380, -1, 13381, 13381, 13381, -1, + 13382, 13382, 13382, -1, 13383, 13383, 13383, -1, + 13384, 13384, 13384, -1, 13385, 13385, 13385, -1, + 13386, 13386, 13386, -1, 13387, 13387, 13387, -1, + 13388, 13388, 13388, -1, 13389, 13389, 13389, -1, + 13390, 13390, 13390, -1, 13391, 13391, 13391, -1, + 13392, 13392, 13392, -1, 13393, 13393, 13393, -1, + 13394, 13394, 13394, -1, 13395, 13395, 13395, -1, + 13396, 13396, 13396, -1, 13397, 13397, 13397, -1, + 13398, 13398, 13398, -1, 13399, 13399, 13399, -1, + 13400, 13400, 13400, -1, 13401, 13401, 13401, -1, + 13402, 13402, 13402, -1, 13403, 13403, 13403, -1, + 13404, 13404, 13404, -1, 13405, 13405, 13405, -1, + 13406, 13406, 13406, -1, 13407, 13407, 13407, -1, + 13408, 13408, 13408, -1, 13409, 13409, 13409, -1, + 13410, 13410, 13410, -1, 13411, 13411, 13411, -1, + 13412, 13412, 13412, -1, 13413, 13413, 13413, -1, + 13414, 13414, 13414, -1, 13415, 13415, 13415, -1, + 13416, 13416, 13416, -1, 13417, 13417, 13417, -1, + 13418, 13418, 13418, -1, 13419, 13419, 13419, -1, + 13420, 13420, 13420, -1, 13421, 13421, 13421, -1, + 13422, 13422, 13422, -1, 13423, 13423, 13423, -1, + 13424, 13424, 13424, -1, 13425, 13425, 13425, -1, + 13426, 13426, 13426, -1, 13427, 13427, 13427, -1, + 13428, 13428, 13428, -1, 13429, 13429, 13429, -1, + 13430, 13430, 13430, -1, 13431, 13431, 13431, -1, + 13432, 13432, 13432, -1, 13433, 13433, 13433, -1, + 13434, 13434, 13434, -1, 13435, 13435, 13435, -1, + 13436, 13436, 13436, -1, 13437, 13437, 13437, -1, + 13438, 13438, 13438, -1, 13439, 13439, 13439, -1, + 13440, 13440, 13440, -1, 13441, 13441, 13441, -1, + 13442, 13442, 13442, -1, 13443, 13443, 13443, -1, + 13444, 13444, 13444, -1, 13445, 13445, 13445, -1, + 13446, 13446, 13446, -1, 13447, 13447, 13447, -1, + 13448, 13448, 13448, -1, 13449, 13449, 13449, -1, + 13450, 13450, 13450, -1, 13451, 13451, 13451, -1, + 13452, 13452, 13452, -1, 13453, 13453, 13453, -1, + 13454, 13454, 13454, -1, 13455, 13455, 13455, -1, + 13456, 13456, 13456, -1, 13457, 13457, 13457, -1, + 13458, 13458, 13458, -1, 13459, 13459, 13459, -1, + 13460, 13460, 13460, -1, 13461, 13461, 13461, -1, + 13462, 13462, 13462, -1, 13463, 13463, 13463, -1, + 13464, 13464, 13464, -1, 13465, 13465, 13465, -1, + 13466, 13466, 13466, -1, 13467, 13467, 13467, -1, + 13468, 13468, 13468, -1, 13469, 13469, 13469, -1, + 13470, 13470, 13470, -1, 13471, 13471, 13471, -1, + 13472, 13472, 13472, -1, 13473, 13473, 13473, -1, + 13474, 13474, 13474, -1, 13475, 13475, 13475, -1, + 13476, 13476, 13476, -1, 13477, 13477, 13477, -1, + 13478, 13478, 13478, -1, 13479, 13479, 13479, -1, + 13480, 13480, 13480, -1, 13481, 13481, 13481, -1, + 13482, 13482, 13482, -1, 13483, 13483, 13483, -1, + 13484, 13484, 13484, -1, 13485, 13485, 13485, -1, + 13486, 13486, 13486, -1, 13487, 13487, 13487, -1, + 13488, 13488, 13488, -1, 13489, 13489, 13489, -1, + 13490, 13490, 13490, -1, 13491, 13491, 13491, -1, + 13492, 13492, 13492, -1, 13493, 13493, 13493, -1, + 13494, 13494, 13494, -1, 13495, 13495, 13495, -1, + 13496, 13496, 13496, -1, 13497, 13497, 13497, -1, + 13498, 13498, 13498, -1, 13499, 13499, 13499, -1, + 13500, 13500, 13500, -1, 13501, 13501, 13501, -1, + 13502, 13502, 13502, -1, 13503, 13503, 13503, -1, + 13504, 13504, 13504, -1, 13505, 13505, 13505, -1, + 13506, 13506, 13506, -1, 13507, 13507, 13507, -1, + 13508, 13508, 13508, -1, 13509, 13509, 13509, -1, + 13510, 13510, 13510, -1, 13511, 13511, 13511, -1, + 13512, 13512, 13512, -1, 13513, 13513, 13513, -1, + 13514, 13514, 13514, -1, 13515, 13515, 13515, -1, + 13516, 13516, 13516, -1, 13517, 13517, 13517, -1, + 13518, 13518, 13518, -1, 13519, 13519, 13519, -1, + 13520, 13520, 13520, -1, 13521, 13521, 13521, -1, + 13522, 13522, 13522, -1, 13523, 13523, 13523, -1, + 13524, 13524, 13524, -1, 13525, 13525, 13525, -1, + 13526, 13526, 13526, -1, 13527, 13527, 13527, -1, + 13528, 13528, 13528, -1, 13529, 13529, 13529, -1, + 13530, 13530, 13530, -1, 13531, 13531, 13531, -1, + 13532, 13532, 13532, -1, 13533, 13533, 13533, -1, + 13534, 13534, 13534, -1, 13535, 13535, 13535, -1, + 13536, 13536, 13536, -1, 13537, 13537, 13537, -1, + 13538, 13538, 13538, -1, 13539, 13539, 13539, -1, + 13540, 13540, 13540, -1, 13541, 13541, 13541, -1, + 13542, 13542, 13542, -1, 13543, 13543, 13543, -1, + 13544, 13544, 13544, -1, 13545, 13545, 13545, -1, + 13546, 13546, 13546, -1, 13547, 13547, 13547, -1, + 13548, 13548, 13548, -1, 13549, 13549, 13549, -1, + 13550, 13550, 13550, -1, 13551, 13551, 13551, -1, + 13552, 13552, 13552, -1, 13553, 13553, 13553, -1, + 13554, 13554, 13554, -1, 13555, 13555, 13555, -1, + 13556, 13556, 13556, -1, 13557, 13557, 13557, -1, + 13558, 13558, 13558, -1, 13559, 13559, 13559, -1, + 13560, 13560, 13560, -1, 13561, 13561, 13561, -1, + 13562, 13562, 13562, -1, 13563, 13563, 13563, -1, + 13564, 13564, 13564, -1, 13565, 13565, 13565, -1, + 13566, 13566, 13566, -1, 13567, 13567, 13567, -1, + 13568, 13568, 13568, -1, 13569, 13569, 13569, -1, + 13570, 13570, 13570, -1, 13571, 13571, 13571, -1, + 13572, 13572, 13572, -1, 13573, 13573, 13573, -1, + 13574, 13574, 13574, -1, 13575, 13575, 13575, -1, + 13576, 13576, 13576, -1, 13577, 13577, 13577, -1, + 13578, 13578, 13578, -1, 13579, 13579, 13579, -1, + 13580, 13580, 13580, -1, 13581, 13581, 13581, -1, + 13582, 13582, 13582, -1, 13583, 13583, 13583, -1, + 13584, 13584, 13584, -1, 13585, 13585, 13585, -1, + 13586, 13586, 13586, -1, 13587, 13587, 13587, -1, + 13588, 13588, 13588, -1, 13589, 13589, 13589, -1, + 13590, 13590, 13590, -1, 13591, 13591, 13591, -1, + 13592, 13592, 13592, -1, 13593, 13593, 13593, -1, + 13594, 13594, 13594, -1, 13595, 13595, 13595, -1, + 13596, 13596, 13596, -1, 13597, 13597, 13597, -1, + 13598, 13598, 13598, -1, 13599, 13599, 13599, -1, + 13600, 13600, 13600, -1, 13601, 13601, 13601, -1, + 13602, 13602, 13602, -1, 13603, 13603, 13603, -1, + 13604, 13604, 13604, -1, 13605, 13605, 13605, -1, + 13606, 13606, 13606, -1, 13607, 13607, 13607, -1, + 13608, 13608, 13608, -1, 13609, 13609, 13609, -1, + 13610, 13610, 13610, -1, 13611, 13611, 13611, -1, + 13612, 13612, 13612, -1, 13613, 13613, 13613, -1, + 13614, 13614, 13614, -1, 13615, 13615, 13615, -1, + 13616, 13616, 13616, -1, 13617, 13617, 13617, -1, + 13618, 13618, 13618, -1, 13619, 13619, 13619, -1, + 13620, 13620, 13620, -1, 13621, 13621, 13621, -1, + 13622, 13622, 13622, -1, 13623, 13623, 13623, -1, + 13624, 13624, 13624, -1, 13625, 13625, 13625, -1, + 13626, 13626, 13626, -1, 13627, 13627, 13627, -1, + 13628, 13628, 13628, -1, 13629, 13629, 13629, -1, + 13630, 13630, 13630, -1, 13631, 13631, 13631, -1, + 13632, 13632, 13632, -1, 13633, 13633, 13633, -1, + 13634, 13634, 13634, -1, 13635, 13635, 13635, -1, + 13636, 13636, 13636, -1, 13637, 13637, 13637, -1, + 13638, 13638, 13638, -1, 13639, 13639, 13639, -1, + 13640, 13640, 13640, -1, 13641, 13641, 13641, -1, + 13642, 13642, 13642, -1, 13643, 13643, 13643, -1, + 13644, 13644, 13644, -1, 13645, 13645, 13645, -1, + 13646, 13646, 13646, -1, 13647, 13647, 13647, -1, + 13648, 13648, 13648, -1, 13649, 13649, 13649, -1, + 13650, 13650, 13650, -1, 13651, 13651, 13651, -1, + 13652, 13652, 13652, -1, 13653, 13653, 13653, -1, + 13654, 13654, 13654, -1, 13655, 13655, 13655, -1, + 13656, 13656, 13656, -1, 13657, 13657, 13657, -1, + 13658, 13658, 13658, -1, 13659, 13659, 13659, -1, + 13660, 13660, 13660, -1, 13661, 13661, 13661, -1, + 13662, 13662, 13662, -1, 13663, 13663, 13663, -1, + 13664, 13664, 13664, -1, 13665, 13665, 13665, -1, + 13666, 13666, 13666, -1, 13667, 13667, 13667, -1, + 13668, 13668, 13668, -1, 13669, 13669, 13669, -1, + 13670, 13670, 13670, -1, 13671, 13671, 13671, -1, + 13672, 13672, 13672, -1, 13673, 13673, 13673, -1, + 13674, 13674, 13674, -1, 13675, 13675, 13675, -1, + 13676, 13676, 13676, -1, 13677, 13677, 13677, -1, + 13678, 13678, 13678, -1, 13679, 13679, 13679, -1, + 13680, 13680, 13680, -1, 13681, 13681, 13681, -1, + 13682, 13682, 13682, -1, 13683, 13683, 13683, -1, + 13684, 13684, 13684, -1, 13685, 13685, 13685, -1, + 13686, 13686, 13686, -1, 13687, 13687, 13687, -1, + 13688, 13688, 13688, -1, 13689, 13689, 13689, -1, + 13690, 13690, 13690, -1, 13691, 13691, 13691, -1, + 13692, 13692, 13692, -1, 13693, 13693, 13693, -1, + 13694, 13694, 13694, -1, 13695, 13695, 13695, -1, + 13696, 13696, 13696, -1, 13697, 13697, 13697, -1, + 13698, 13698, 13698, -1, 13699, 13699, 13699, -1, + 13700, 13700, 13700, -1, 13701, 13701, 13701, -1, + 13702, 13702, 13702, -1, 13703, 13703, 13703, -1, + 13704, 13704, 13704, -1, 13705, 13705, 13705, -1, + 13706, 13706, 13706, -1, 13707, 13707, 13707, -1, + 13708, 13708, 13708, -1, 13709, 13709, 13709, -1, + 13710, 13710, 13710, -1, 13711, 13711, 13711, -1, + 13712, 13712, 13712, -1, 13713, 13713, 13713, -1, + 13714, 13714, 13714, -1, 13715, 13715, 13715, -1, + 13716, 13716, 13716, -1, 13717, 13717, 13717, -1, + 13718, 13718, 13718, -1, 13719, 13719, 13719, -1, + 13720, 13720, 13720, -1, 13721, 13721, 13721, -1, + 13722, 13722, 13722, -1, 13723, 13723, 13723, -1, + 13724, 13724, 13724, -1, 13725, 13725, 13725, -1, + 13726, 13726, 13726, -1, 13727, 13727, 13727, -1, + 13728, 13728, 13728, -1, 13729, 13729, 13729, -1, + 13730, 13730, 13730, -1, 13731, 13731, 13731, -1, + 13732, 13732, 13732, -1, 13733, 13733, 13733, -1, + 13734, 13734, 13734, -1, 13735, 13735, 13735, -1, + 13736, 13736, 13736, -1, 13737, 13737, 13737, -1, + 13738, 13738, 13738, -1, 13739, 13739, 13739, -1, + 13740, 13740, 13740, -1, 13741, 13741, 13741, -1, + 13742, 13742, 13742, -1, 13743, 13743, 13743, -1, + 13744, 13744, 13744, -1, 13745, 13745, 13745, -1, + 13746, 13746, 13746, -1, 13747, 13747, 13747, -1, + 13748, 13748, 13748, -1, 13749, 13749, 13749, -1, + 13750, 13750, 13750, -1, 13751, 13751, 13751, -1, + 13752, 13752, 13752, -1, 13753, 13753, 13753, -1, + 13754, 13754, 13754, -1, 13755, 13755, 13755, -1, + 13756, 13756, 13756, -1, 13757, 13757, 13757, -1, + 13758, 13758, 13758, -1, 13759, 13759, 13759, -1, + 13760, 13760, 13760, -1, 13761, 13761, 13761, -1, + 13762, 13762, 13762, -1, 13763, 13763, 13763, -1, + 13764, 13764, 13764, -1, 13765, 13765, 13765, -1, + 13766, 13766, 13766, -1, 13767, 13767, 13767, -1, + 13768, 13768, 13768, -1, 13769, 13769, 13769, -1, + 13770, 13770, 13770, -1, 13771, 13771, 13771, -1, + 13772, 13772, 13772, -1, 13773, 13773, 13773, -1, + 13774, 13774, 13774, -1, 13775, 13775, 13775, -1, + 13776, 13776, 13776, -1, 13777, 13777, 13777, -1, + 13778, 13778, 13778, -1, 13779, 13779, 13779, -1, + 13780, 13780, 13780, -1, 13781, 13781, 13781, -1, + 13782, 13782, 13782, -1, 13783, 13783, 13783, -1, + 13784, 13784, 13784, -1, 13785, 13785, 13785, -1, + 13786, 13786, 13786, -1, 13787, 13787, 13787, -1, + 13788, 13788, 13788, -1, 13789, 13789, 13789, -1, + 13790, 13790, 13790, -1, 13791, 13791, 13791, -1, + 13792, 13792, 13792, -1, 13793, 13793, 13793, -1, + 13794, 13794, 13794, -1, 13795, 13795, 13795, -1, + 13796, 13796, 13796, -1, 13797, 13797, 13797, -1, + 13798, 13798, 13798, -1, 13799, 13799, 13799, -1, + 13800, 13800, 13800, -1, 13801, 13801, 13801, -1, + 13802, 13802, 13802, -1, 13803, 13803, 13803, -1, + 13804, 13804, 13804, -1, 13805, 13805, 13805, -1, + 13806, 13806, 13806, -1, 13807, 13807, 13807, -1, + 13808, 13808, 13808, -1, 13809, 13809, 13809, -1, + 13810, 13810, 13810, -1, 13811, 13811, 13811, -1, + 13812, 13812, 13812, -1, 13813, 13813, 13813, -1, + 13814, 13814, 13814, -1, 13815, 13815, 13815, -1, + 13816, 13816, 13816, -1, 13817, 13817, 13817, -1, + 13818, 13818, 13818, -1, 13819, 13819, 13819, -1, + 13820, 13820, 13820, -1, 13821, 13821, 13821, -1, + 13822, 13822, 13822, -1, 13823, 13823, 13823, -1, + 13824, 13824, 13824, -1, 13825, 13825, 13825, -1, + 13826, 13826, 13826, -1, 13827, 13827, 13827, -1, + 13828, 13828, 13828, -1, 13829, 13829, 13829, -1, + 13830, 13830, 13830, -1, 13831, 13831, 13831, -1, + 13832, 13832, 13832, -1, 13833, 13833, 13833, -1, + 13834, 13834, 13834, -1, 13835, 13835, 13835, -1, + 13836, 13836, 13836, -1, 13837, 13837, 13837, -1, + 13838, 13838, 13838, -1, 13839, 13839, 13839, -1, + 13840, 13840, 13840, -1, 13841, 13841, 13841, -1, + 13842, 13842, 13842, -1, 13843, 13843, 13843, -1, + 13844, 13844, 13844, -1, 13845, 13845, 13845, -1, + 13846, 13846, 13846, -1, 13847, 13847, 13847, -1, + 13848, 13848, 13848, -1, 13849, 13849, 13849, -1, + 13850, 13850, 13850, -1, 13851, 13851, 13851, -1, + 13852, 13852, 13852, -1, 13853, 13853, 13853, -1, + 13854, 13854, 13854, -1, 13855, 13855, 13855, -1, + 13856, 13856, 13856, -1, 13857, 13857, 13857, -1, + 13858, 13858, 13858, -1, 13859, 13859, 13859, -1, + 13860, 13860, 13860, -1, 13861, 13861, 13861, -1, + 13862, 13862, 13862, -1, 13863, 13863, 13863, -1, + 13864, 13864, 13864, -1, 13865, 13865, 13865, -1, + 13866, 13866, 13866, -1, 13867, 13867, 13867, -1, + 13868, 13868, 13868, -1, 13869, 13869, 13869, -1, + 13870, 13870, 13870, -1, 13871, 13871, 13871, -1, + 13872, 13872, 13872, -1, 13873, 13873, 13873, -1, + 13874, 13874, 13874, -1, 13875, 13875, 13875, -1, + 13876, 13876, 13876, -1, 13877, 13877, 13877, -1, + 13878, 13878, 13878, -1, 13879, 13879, 13879, -1, + 13880, 13880, 13880, -1, 13881, 13881, 13881, -1, + 13882, 13882, 13882, -1, 13883, 13883, 13883, -1, + 13884, 13884, 13884, -1, 13885, 13885, 13885, -1, + 13886, 13886, 13886, -1, 13887, 13887, 13887, -1, + 13888, 13888, 13888, -1, 13889, 13889, 13889, -1, + 13890, 13890, 13890, -1, 13891, 13891, 13891, -1, + 13892, 13892, 13892, -1, 13893, 13893, 13893, -1, + 13894, 13894, 13894, -1, 13895, 13895, 13895, -1, + 13896, 13896, 13896, -1, 13897, 13897, 13897, -1, + 13898, 13898, 13898, -1, 13899, 13899, 13899, -1, + 13900, 13900, 13900, -1, 13901, 13901, 13901, -1, + 13902, 13902, 13902, -1, 13903, 13903, 13903, -1, + 13904, 13904, 13904, -1, 13905, 13905, 13905, -1, + 13906, 13906, 13906, -1, 13907, 13907, 13907, -1, + 13908, 13908, 13908, -1, 13909, 13909, 13909, -1, + 13910, 13910, 13910, -1, 13911, 13911, 13911, -1, + 13912, 13912, 13912, -1, 13913, 13913, 13913, -1, + 13914, 13914, 13914, -1, 13915, 13915, 13915, -1, + 13916, 13916, 13916, -1, 13917, 13917, 13917, -1, + 13918, 13918, 13918, -1, 13919, 13919, 13919, -1, + 13920, 13920, 13920, -1, 13921, 13921, 13921, -1, + 13922, 13922, 13922, -1, 13923, 13923, 13923, -1, + 13924, 13924, 13924, -1, 13925, 13925, 13925, -1, + 13926, 13926, 13926, -1, 13927, 13927, 13927, -1, + 13928, 13928, 13928, -1, 13929, 13929, 13929, -1, + 13930, 13930, 13930, -1, 13931, 13931, 13931, -1, + 13932, 13932, 13932, -1, 13933, 13933, 13933, -1, + 13934, 13934, 13934, -1, 13935, 13935, 13935, -1, + 13936, 13936, 13936, -1, 13937, 13937, 13937, -1, + 13938, 13938, 13938, -1, 13939, 13939, 13939, -1, + 13940, 13940, 13940, -1, 13941, 13941, 13941, -1, + 13942, 13942, 13942, -1, 13943, 13943, 13943, -1, + 13944, 13944, 13944, -1, 13945, 13945, 13945, -1, + 13946, 13946, 13946, -1, 13947, 13947, 13947, -1, + 13948, 13948, 13948, -1, 13949, 13949, 13949, -1, + 13950, 13950, 13950, -1, 13951, 13951, 13951, -1, + 13952, 13952, 13952, -1, 13953, 13953, 13953, -1, + 13954, 13954, 13954, -1, 13955, 13955, 13955, -1, + 13956, 13956, 13956, -1, 13957, 13957, 13957, -1, + 13958, 13958, 13958, -1, 13959, 13959, 13959, -1, + 13960, 13960, 13960, -1, 13961, 13961, 13961, -1, + 13962, 13962, 13962, -1, 13963, 13963, 13963, -1, + 13964, 13964, 13964, -1, 13965, 13965, 13965, -1, + 13966, 13966, 13966, -1, 13967, 13967, 13967, -1, + 13968, 13968, 13968, -1, 13969, 13969, 13969, -1, + 13970, 13970, 13970, -1, 13971, 13971, 13971, -1, + 13972, 13972, 13972, -1, 13973, 13973, 13973, -1, + 13974, 13974, 13974, -1, 13975, 13975, 13975, -1, + 13976, 13976, 13976, -1, 13977, 13977, 13977, -1, + 13978, 13978, 13978, -1, 13979, 13979, 13979, -1, + 13980, 13980, 13980, -1, 13981, 13981, 13981, -1, + 13982, 13982, 13982, -1, 13983, 13983, 13983, -1, + 13984, 13984, 13984, -1, 13985, 13985, 13985, -1, + 13986, 13986, 13986, -1, 13987, 13987, 13987, -1, + 13988, 13988, 13988, -1, 13989, 13989, 13989, -1, + 13990, 13990, 13990, -1, 13991, 13991, 13991, -1, + 13992, 13992, 13992, -1, 13993, 13993, 13993, -1, + 13994, 13994, 13994, -1, 13995, 13995, 13995, -1, + 13996, 13996, 13996, -1, 13997, 13997, 13997, -1, + 13998, 13998, 13998, -1, 13999, 13999, 13999, -1, + 14000, 14000, 14000, -1, 14001, 14001, 14001, -1, + 14002, 14002, 14002, -1, 14003, 14003, 14003, -1, + 14004, 14004, 14004, -1, 14005, 14005, 14005, -1, + 14006, 14006, 14006, -1, 14007, 14007, 14007, -1, + 14008, 14008, 14008, -1, 14009, 14009, 14009, -1, + 14010, 14010, 14010, -1, 14011, 14011, 14011, -1, + 14012, 14012, 14012, -1, 14013, 14013, 14013, -1, + 14014, 14014, 14014, -1, 14015, 14015, 14015, -1, + 14016, 14016, 14016, -1, 14017, 14017, 14017, -1, + 14018, 14018, 14018, -1, 14019, 14019, 14019, -1, + 14020, 14020, 14020, -1, 14021, 14021, 14021, -1, + 14022, 14022, 14022, -1, 14023, 14023, 14023, -1, + 14024, 14024, 14024, -1, 14025, 14025, 14025, -1, + 14026, 14026, 14026, -1, 14027, 14027, 14027, -1, + 14028, 14028, 14028, -1, 14029, 14029, 14029, -1, + 14030, 14030, 14030, -1, 14031, 14031, 14031, -1, + 14032, 14032, 14032, -1, 14033, 14033, 14033, -1, + 14034, 14034, 14034, -1, 14035, 14035, 14035, -1, + 14036, 14036, 14036, -1, 14037, 14037, 14037, -1, + 14038, 14038, 14038, -1, 14039, 14039, 14039, -1, + 14040, 14040, 14040, -1, 14041, 14041, 14041, -1, + 14042, 14042, 14042, -1, 14043, 14043, 14043, -1, + 14044, 14044, 14044, -1, 14045, 14045, 14045, -1, + 14046, 14046, 14046, -1, 14047, 14047, 14047, -1, + 14048, 14048, 14048, -1, 14049, 14049, 14049, -1, + 14050, 14050, 14050, -1, 14051, 14051, 14051, -1, + 14052, 14052, 14052, -1, 14053, 14053, 14053, -1, + 14054, 14054, 14054, -1, 14055, 14055, 14055, -1, + 14056, 14056, 14056, -1, 14057, 14057, 14057, -1, + 14058, 14058, 14058, -1, 14059, 14059, 14059, -1, + 14060, 14060, 14060, -1, 14061, 14061, 14061, -1, + 14062, 14062, 14062, -1, 14063, 14063, 14063, -1, + 14064, 14064, 14064, -1, 14065, 14065, 14065, -1, + 14066, 14066, 14066, -1, 14067, 14067, 14067, -1, + 14068, 14068, 14068, -1, 14069, 14069, 14069, -1, + 14070, 14070, 14070, -1, 14071, 14071, 14071, -1, + 14072, 14072, 14072, -1, 14073, 14073, 14073, -1, + 14074, 14074, 14074, -1, 14075, 14075, 14075, -1, + 14076, 14076, 14076, -1, 14077, 14077, 14077, -1, + 14078, 14078, 14078, -1, 14079, 14079, 14079, -1, + 14080, 14080, 14080, -1, 14081, 14081, 14081, -1, + 14082, 14082, 14082, -1, 14083, 14083, 14083, -1, + 14084, 14084, 14084, -1, 14085, 14085, 14085, -1, + 14086, 14086, 14086, -1, 14087, 14087, 14087, -1, + 14088, 14088, 14088, -1, 14089, 14089, 14089, -1, + 14090, 14090, 14090, -1, 14091, 14091, 14091, -1, + 14092, 14092, 14092, -1, 14093, 14093, 14093, -1, + 14094, 14094, 14094, -1, 14095, 14095, 14095, -1, + 14096, 14096, 14096, -1, 14097, 14097, 14097, -1, + 14098, 14098, 14098, -1, 14099, 14099, 14099, -1, + 14100, 14100, 14100, -1, 14101, 14101, 14101, -1, + 14102, 14102, 14102, -1, 14103, 14103, 14103, -1, + 14104, 14104, 14104, -1, 14105, 14105, 14105, -1, + 14106, 14106, 14106, -1, 14107, 14107, 14107, -1, + 14108, 14108, 14108, -1, 14109, 14109, 14109, -1, + 14110, 14110, 14110, -1, 14111, 14111, 14111, -1, + 14112, 14112, 14112, -1, 14113, 14113, 14113, -1, + 14114, 14114, 14114, -1, 14115, 14115, 14115, -1, + 14116, 14116, 14116, -1, 14117, 14117, 14117, -1, + 14118, 14118, 14118, -1, 14119, 14119, 14119, -1, + 14120, 14120, 14120, -1, 14121, 14121, 14121, -1, + 14122, 14122, 14122, -1, 14123, 14123, 14123, -1, + 14124, 14124, 14124, -1, 14125, 14125, 14125, -1, + 14126, 14126, 14126, -1, 14127, 14127, 14127, -1, + 14128, 14128, 14128, -1, 14129, 14129, 14129, -1, + 14130, 14130, 14130, -1, 14131, 14131, 14131, -1, + 14132, 14132, 14132, -1, 14133, 14133, 14133, -1, + 14134, 14134, 14134, -1, 14135, 14135, 14135, -1, + 14136, 14136, 14136, -1, 14137, 14137, 14137, -1, + 14138, 14138, 14138, -1, 14139, 14139, 14139, -1, + 14140, 14140, 14140, -1, 14141, 14141, 14141, -1, + 14142, 14142, 14142, -1, 14143, 14143, 14143, -1, + 14144, 14144, 14144, -1, 14145, 14145, 14145, -1, + 14146, 14146, 14146, -1, 14147, 14147, 14147, -1, + 14148, 14148, 14148, -1, 14149, 14149, 14149, -1, + 14150, 14150, 14150, -1, 14151, 14151, 14151, -1, + 14152, 14152, 14152, -1, 14153, 14153, 14153, -1, + 14154, 14154, 14154, -1, 14155, 14155, 14155, -1, + 14156, 14156, 14156, -1, 14157, 14157, 14157, -1, + 14158, 14158, 14158, -1, 14159, 14159, 14159, -1, + 14160, 14160, 14160, -1, 14161, 14161, 14161, -1, + 14162, 14162, 14162, -1, 14163, 14163, 14163, -1, + 14164, 14164, 14164, -1, 14165, 14165, 14165, -1, + 14166, 14166, 14166, -1, 14167, 14167, 14167, -1, + 14168, 14168, 14168, -1, 14169, 14169, 14169, -1, + 14170, 14170, 14170, -1, 14171, 14171, 14171, -1, + 14172, 14172, 14172, -1, 14173, 14173, 14173, -1, + 14174, 14174, 14174, -1, 14175, 14175, 14175, -1, + 14176, 14176, 14176, -1, 14177, 14177, 14177, -1, + 14178, 14178, 14178, -1, 14179, 14179, 14179, -1, + 14180, 14180, 14180, -1, 14181, 14181, 14181, -1, + 14182, 14182, 14182, -1, 14183, 14183, 14183, -1, + 14184, 14184, 14184, -1, 14185, 14185, 14185, -1, + 14186, 14186, 14186, -1, 14187, 14187, 14187, -1, + 14188, 14188, 14188, -1, 14189, 14189, 14189, -1, + 14190, 14190, 14190, -1, 14191, 14191, 14191, -1, + 14192, 14192, 14192, -1, 14193, 14193, 14193, -1, + 14194, 14194, 14194, -1, 14195, 14195, 14195, -1, + 14196, 14196, 14196, -1, 14197, 14197, 14197, -1, + 14198, 14198, 14198, -1, 14199, 14199, 14199, -1, + 14200, 14200, 14200, -1, 14201, 14201, 14201, -1, + 14202, 14202, 14202, -1, 14203, 14203, 14203, -1, + 14204, 14204, 14204, -1, 14205, 14205, 14205, -1, + 14206, 14206, 14206, -1, 14207, 14207, 14207, -1, + 14208, 14208, 14208, -1, 14209, 14209, 14209, -1, + 14210, 14210, 14210, -1, 14211, 14211, 14211, -1, + 14212, 14212, 14212, -1, 14213, 14213, 14213, -1, + 14214, 14214, 14214, -1, 14215, 14215, 14215, -1, + 14216, 14216, 14216, -1, 14217, 14217, 14217, -1, + 14218, 14218, 14218, -1, 14219, 14219, 14219, -1, + 14220, 14220, 14220, -1, 14221, 14221, 14221, -1, + 14222, 14222, 14222, -1, 14223, 14223, 14223, -1, + 14224, 14224, 14224, -1, 14225, 14225, 14225, -1, + 14226, 14226, 14226, -1, 14227, 14227, 14227, -1, + 14228, 14228, 14228, -1, 14229, 14229, 14229, -1, + 14230, 14230, 14230, -1, 14231, 14231, 14231, -1, + 14232, 14232, 14232, -1, 14233, 14233, 14233, -1, + 14234, 14234, 14234, -1, 14235, 14235, 14235, -1, + 14236, 14236, 14236, -1, 14237, 14237, 14237, -1, + 14238, 14238, 14238, -1, 14239, 14239, 14239, -1, + 14240, 14240, 14240, -1, 14241, 14241, 14241, -1, + 14242, 14242, 14242, -1, 14243, 14243, 14243, -1, + 14244, 14244, 14244, -1, 14245, 14245, 14245, -1, + 14246, 14246, 14246, -1, 14247, 14247, 14247, -1, + 14248, 14248, 14248, -1, 14249, 14249, 14249, -1, + 14250, 14250, 14250, -1, 14251, 14251, 14251, -1, + 14252, 14252, 14252, -1, 14253, 14253, 14253, -1, + 14254, 14254, 14254, -1, 14255, 14255, 14255, -1, + 14256, 14256, 14256, -1, 14257, 14257, 14257, -1, + 14258, 14258, 14258, -1, 14259, 14259, 14259, -1, + 14260, 14260, 14260, -1, 14261, 14261, 14261, -1, + 14262, 14262, 14262, -1, 14263, 14263, 14263, -1, + 14264, 14264, 14264, -1, 14265, 14265, 14265, -1, + 14266, 14266, 14266, -1, 14267, 14267, 14267, -1, + 14268, 14268, 14268, -1, 14269, 14269, 14269, -1, + 14270, 14270, 14270, -1, 14271, 14271, 14271, -1, + 14272, 14272, 14272, -1, 14273, 14273, 14273, -1, + 14274, 14274, 14274, -1, 14275, 14275, 14275, -1, + 14276, 14276, 14276, -1, 14277, 14277, 14277, -1, + 14278, 14278, 14278, -1, 14279, 14279, 14279, -1, + 14280, 14280, 14280, -1, 14281, 14281, 14281, -1, + 14282, 14282, 14282, -1, 14283, 14283, 14283, -1, + 14284, 14284, 14284, -1, 14285, 14285, 14285, -1, + 14286, 14286, 14286, -1, 14287, 14287, 14287, -1, + 14288, 14288, 14288, -1, 14289, 14289, 14289, -1, + 14290, 14290, 14290, -1, 14291, 14291, 14291, -1, + 14292, 14292, 14292, -1, 14293, 14293, 14293, -1, + 14294, 14294, 14294, -1, 14295, 14295, 14295, -1, + 14296, 14296, 14296, -1, 14297, 14297, 14297, -1, + 14298, 14298, 14298, -1, 14299, 14299, 14299, -1, + 14300, 14300, 14300, -1, 14301, 14301, 14301, -1, + 14302, 14302, 14302, -1, 14303, 14303, 14303, -1, + 14304, 14304, 14304, -1, 14305, 14305, 14305, -1, + 14306, 14306, 14306, -1, 14307, 14307, 14307, -1, + 14308, 14308, 14308, -1, 14309, 14309, 14309, -1, + 14310, 14310, 14310, -1, 14311, 14311, 14311, -1, + 14312, 14312, 14312, -1, 14313, 14313, 14313, -1, + 14314, 14314, 14314, -1, 14315, 14315, 14315, -1, + 14316, 14316, 14316, -1, 14317, 14317, 14317, -1, + 14318, 14318, 14318, -1, 14319, 14319, 14319, -1, + 14320, 14320, 14320, -1, 14321, 14321, 14321, -1, + 14322, 14322, 14322, -1, 14323, 14323, 14323, -1, + 14324, 14324, 14324, -1, 14325, 14325, 14325, -1, + 14326, 14326, 14326, -1, 14327, 14327, 14327, -1, + 14328, 14328, 14328, -1, 14329, 14329, 14329, -1, + 14330, 14330, 14330, -1, 14331, 14331, 14331, -1, + 14332, 14332, 14332, -1, 14333, 14333, 14333, -1, + 14334, 14334, 14334, -1, 14335, 14335, 14335, -1, + 14336, 14336, 14336, -1, 14337, 14337, 14337, -1, + 14338, 14338, 14338, -1, 14339, 14339, 14339, -1, + 14340, 14340, 14340, -1, 14341, 14341, 14341, -1, + 14342, 14342, 14342, -1, 14343, 14343, 14343, -1, + 14344, 14344, 14344, -1, 14345, 14345, 14345, -1, + 14346, 14346, 14346, -1, 14347, 14347, 14347, -1, + 14348, 14348, 14348, -1, 14349, 14349, 14349, -1, + 14350, 14350, 14350, -1, 14351, 14351, 14351, -1, + 14352, 14352, 14352, -1, 14353, 14353, 14353, -1, + 14354, 14354, 14354, -1, 14355, 14355, 14355, -1, + 14356, 14356, 14356, -1, 14357, 14357, 14357, -1, + 14358, 14358, 14358, -1, 14359, 14359, 14359, -1, + 14360, 14360, 14360, -1, 14361, 14361, 14361, -1, + 14362, 14362, 14362, -1, 14363, 14363, 14363, -1, + 14364, 14364, 14364, -1, 14365, 14365, 14365, -1, + 14366, 14366, 14366, -1, 14367, 14367, 14367, -1, + 14368, 14368, 14368, -1, 14369, 14369, 14369, -1, + 14370, 14370, 14370, -1, 14371, 14371, 14371, -1, + 14372, 14372, 14372, -1, 14373, 14373, 14373, -1, + 14374, 14374, 14374, -1, 14375, 14375, 14375, -1, + 14376, 14376, 14376, -1, 14377, 14377, 14377, -1, + 14378, 14378, 14378, -1, 14379, 14379, 14379, -1, + 14380, 14380, 14380, -1, 14381, 14381, 14381, -1, + 14382, 14382, 14382, -1, 14383, 14383, 14383, -1, + 14384, 14384, 14384, -1, 14385, 14385, 14385, -1, + 14386, 14386, 14386, -1, 14387, 14387, 14387, -1, + 14388, 14388, 14388, -1, 14389, 14389, 14389, -1, + 14390, 14390, 14390, -1, 14391, 14391, 14391, -1, + 14392, 14392, 14392, -1, 14393, 14393, 14393, -1, + 14394, 14394, 14394, -1, 14395, 14395, 14395, -1, + 14396, 14396, 14396, -1, 14397, 14397, 14397, -1, + 14398, 14398, 14398, -1, 14399, 14399, 14399, -1, + 14400, 14400, 14400, -1, 14401, 14401, 14401, -1, + 14402, 14402, 14402, -1, 14403, 14403, 14403, -1, + 14404, 14404, 14404, -1, 14405, 14405, 14405, -1, + 14406, 14406, 14406, -1, 14407, 14407, 14407, -1, + 14408, 14408, 14408, -1, 14409, 14409, 14409, -1, + 14410, 14410, 14410, -1, 14411, 14411, 14411, -1, + 14412, 14412, 14412, -1, 14413, 14413, 14413, -1, + 14414, 14414, 14414, -1, 14415, 14415, 14415, -1, + 14416, 14416, 14416, -1, 14417, 14417, 14417, -1, + 14418, 14418, 14418, -1, 14419, 14419, 14419, -1, + 14420, 14420, 14420, -1, 14421, 14421, 14421, -1, + 14422, 14422, 14422, -1, 14423, 14423, 14423, -1, + 14424, 14424, 14424, -1, 14425, 14425, 14425, -1, + 14426, 14426, 14426, -1, 14427, 14427, 14427, -1, + 14428, 14428, 14428, -1, 14429, 14429, 14429, -1, + 14430, 14430, 14430, -1, 14431, 14431, 14431, -1, + 14432, 14432, 14432, -1, 14433, 14433, 14433, -1, + 14434, 14434, 14434, -1, 14435, 14435, 14435, -1, + 14436, 14436, 14436, -1, 14437, 14437, 14437, -1, + 14438, 14438, 14438, -1, 14439, 14439, 14439, -1, + 14440, 14440, 14440, -1, 14441, 14441, 14441, -1, + 14442, 14442, 14442, -1, 14443, 14443, 14443, -1, + 14444, 14444, 14444, -1, 14445, 14445, 14445, -1, + 14446, 14446, 14446, -1, 14447, 14447, 14447, -1, + 14448, 14448, 14448, -1, 14449, 14449, 14449, -1, + 14450, 14450, 14450, -1, 14451, 14451, 14451, -1, + 14452, 14452, 14452, -1, 14453, 14453, 14453, -1, + 14454, 14454, 14454, -1, 14455, 14455, 14455, -1, + 14456, 14456, 14456, -1, 14457, 14457, 14457, -1, + 14458, 14458, 14458, -1, 14459, 14459, 14459, -1, + 14460, 14460, 14460, -1, 14461, 14461, 14461, -1, + 14462, 14462, 14462, -1, 14463, 14463, 14463, -1, + 14464, 14464, 14464, -1, 14465, 14465, 14465, -1, + 14466, 14466, 14466, -1, 14467, 14467, 14467, -1, + 14468, 14468, 14468, -1, 14469, 14469, 14469, -1, + 14470, 14470, 14470, -1, 14471, 14471, 14471, -1, + 14472, 14472, 14472, -1, 14473, 14473, 14473, -1, + 14474, 14474, 14474, -1, 14475, 14475, 14475, -1, + 14476, 14476, 14476, -1, 14477, 14477, 14477, -1, + 14478, 14478, 14478, -1, 14479, 14479, 14479, -1, + 14480, 14480, 14480, -1, 14481, 14481, 14481, -1, + 14482, 14482, 14482, -1, 14483, 14483, 14483, -1, + 14484, 14484, 14484, -1, 14485, 14485, 14485, -1, + 14486, 14486, 14486, -1, 14487, 14487, 14487, -1, + 14488, 14488, 14488, -1, 14489, 14489, 14489, -1, + 14490, 14490, 14490, -1, 14491, 14491, 14491, -1, + 14492, 14492, 14492, -1, 14493, 14493, 14493, -1, + 14494, 14494, 14494, -1, 14495, 14495, 14495, -1, + 14496, 14496, 14496, -1, 14497, 14497, 14497, -1, + 14498, 14498, 14498, -1, 14499, 14499, 14499, -1, + 14500, 14500, 14500, -1, 14501, 14501, 14501, -1, + 14502, 14502, 14502, -1, 14503, 14503, 14503, -1, + 14504, 14504, 14504, -1, 14505, 14505, 14505, -1, + 14506, 14506, 14506, -1, 14507, 14507, 14507, -1, + 14508, 14508, 14508, -1, 14509, 14509, 14509, -1, + 14510, 14510, 14510, -1, 14511, 14511, 14511, -1, + 14512, 14512, 14512, -1, 14513, 14513, 14513, -1, + 14514, 14514, 14514, -1, 14515, 14515, 14515, -1, + 14516, 14516, 14516, -1, 14517, 14517, 14517, -1, + 14518, 14518, 14518, -1, 14519, 14519, 14519, -1, + 14520, 14520, 14520, -1, 14521, 14521, 14521, -1, + 14522, 14522, 14522, -1, 14523, 14523, 14523, -1, + 14524, 14524, 14524, -1, 14525, 14525, 14525, -1, + 14526, 14526, 14526, -1, 14527, 14527, 14527, -1, + 14528, 14528, 14528, -1, 14529, 14529, 14529, -1, + 14530, 14530, 14530, -1, 14531, 14531, 14531, -1, + 14532, 14532, 14532, -1, 14533, 14533, 14533, -1, + 14534, 14534, 14534, -1, 14535, 14535, 14535, -1, + 14536, 14536, 14536, -1, 14537, 14537, 14537, -1, + 14538, 14538, 14538, -1, 14539, 14539, 14539, -1, + 14540, 14540, 14540, -1, 14541, 14541, 14541, -1, + 14542, 14542, 14542, -1, 14543, 14543, 14543, -1, + 14544, 14544, 14544, -1, 14545, 14545, 14545, -1, + 14546, 14546, 14546, -1, 14547, 14547, 14547, -1, + 14548, 14548, 14548, -1, 14549, 14549, 14549, -1, + 14550, 14550, 14550, -1, 14551, 14551, 14551, -1, + 14552, 14552, 14552, -1, 14553, 14553, 14553, -1, + 14554, 14554, 14554, -1, 14555, 14555, 14555, -1, + 14556, 14556, 14556, -1, 14557, 14557, 14557, -1, + 14558, 14558, 14558, -1, 14559, 14559, 14559, -1, + 14560, 14560, 14560, -1, 14561, 14561, 14561, -1, + 14562, 14562, 14562, -1, 14563, 14563, 14563, -1, + 14564, 14564, 14564, -1, 14565, 14565, 14565, -1, + 14566, 14566, 14566, -1, 14567, 14567, 14567, -1, + 14568, 14568, 14568, -1, 14569, 14569, 14569, -1, + 14570, 14570, 14570, -1, 14571, 14571, 14571, -1, + 14572, 14572, 14572, -1, 14573, 14573, 14573, -1, + 14574, 14574, 14574, -1, 14575, 14575, 14575, -1, + 14576, 14576, 14576, -1, 14577, 14577, 14577, -1, + 14578, 14578, 14578, -1, 14579, 14579, 14579, -1, + 14580, 14580, 14580, -1, 14581, 14581, 14581, -1, + 14582, 14582, 14582, -1, 14583, 14583, 14583, -1, + 14584, 14584, 14584, -1, 14585, 14585, 14585, -1, + 14586, 14586, 14586, -1, 14587, 14587, 14587, -1, + 14588, 14588, 14588, -1, 14589, 14589, 14589, -1, + 14590, 14590, 14590, -1, 14591, 14591, 14591, -1, + 14592, 14592, 14592, -1, 14593, 14593, 14593, -1, + 14594, 14594, 14594, -1, 14595, 14595, 14595, -1, + 14596, 14596, 14596, -1, 14597, 14597, 14597, -1, + 14598, 14598, 14598, -1, 14599, 14599, 14599, -1, + 14600, 14600, 14600, -1, 14601, 14601, 14601, -1, + 14602, 14602, 14602, -1, 14603, 14603, 14603, -1, + 14604, 14604, 14604, -1, 14605, 14605, 14605, -1, + 14606, 14606, 14606, -1, 14607, 14607, 14607, -1, + 14608, 14608, 14608, -1, 14609, 14609, 14609, -1, + 14610, 14610, 14610, -1, 14611, 14611, 14611, -1, + 14612, 14612, 14612, -1, 14613, 14613, 14613, -1, + 14614, 14614, 14614, -1, 14615, 14615, 14615, -1, + 14616, 14616, 14616, -1, 14617, 14617, 14617, -1, + 14618, 14618, 14618, -1, 14619, 14619, 14619, -1, + 14620, 14620, 14620, -1, 14621, 14621, 14621, -1, + 14622, 14622, 14622, -1, 14623, 14623, 14623, -1, + 14624, 14624, 14624, -1, 14625, 14625, 14625, -1, + 14626, 14626, 14626, -1, 14627, 14627, 14627, -1, + 14628, 14628, 14628, -1, 14629, 14629, 14629, -1, + 14630, 14630, 14630, -1, 14631, 14631, 14631, -1, + 14632, 14632, 14632, -1, 14633, 14633, 14633, -1, + 14634, 14634, 14634, -1, 14635, 14635, 14635, -1, + 14636, 14636, 14636, -1, 14637, 14637, 14637, -1, + 14638, 14638, 14638, -1, 14639, 14639, 14639, -1, + 14640, 14640, 14640, -1, 14641, 14641, 14641, -1, + 14642, 14642, 14642, -1, 14643, 14643, 14643, -1, + 14644, 14644, 14644, -1, 14645, 14645, 14645, -1, + 14646, 14646, 14646, -1, 14647, 14647, 14647, -1, + 14648, 14648, 14648, -1, 14649, 14649, 14649, -1, + 14650, 14650, 14650, -1, 14651, 14651, 14651, -1, + 14652, 14652, 14652, -1, 14653, 14653, 14653, -1, + 14654, 14654, 14654, -1, 14655, 14655, 14655, -1, + 14656, 14656, 14656, -1, 14657, 14657, 14657, -1, + 14658, 14658, 14658, -1, 14659, 14659, 14659, -1, + 14660, 14660, 14660, -1, 14661, 14661, 14661, -1, + 14662, 14662, 14662, -1, 14663, 14663, 14663, -1, + 14664, 14664, 14664, -1, 14665, 14665, 14665, -1, + 14666, 14666, 14666, -1, 14667, 14667, 14667, -1, + 14668, 14668, 14668, -1, 14669, 14669, 14669, -1, + 14670, 14670, 14670, -1, 14671, 14671, 14671, -1, + 14672, 14672, 14672, -1, 14673, 14673, 14673, -1, + 14674, 14674, 14674, -1, 14675, 14675, 14675, -1, + 14676, 14676, 14676, -1, 14677, 14677, 14677, -1, + 14678, 14678, 14678, -1, 14679, 14679, 14679, -1, + 14680, 14680, 14680, -1, 14681, 14681, 14681, -1, + 14682, 14682, 14682, -1, 14683, 14683, 14683, -1, + 14684, 14684, 14684, -1, 14685, 14685, 14685, -1, + 14686, 14686, 14686, -1, 14687, 14687, 14687, -1, + 14688, 14688, 14688, -1, 14689, 14689, 14689, -1, + 14690, 14690, 14690, -1, 14691, 14691, 14691, -1, + 14692, 14692, 14692, -1, 14693, 14693, 14693, -1, + 14694, 14694, 14694, -1, 14695, 14695, 14695, -1, + 14696, 14696, 14696, -1, 14697, 14697, 14697, -1, + 14698, 14698, 14698, -1, 14699, 14699, 14699, -1, + 14700, 14700, 14700, -1, 14701, 14701, 14701, -1, + 14702, 14702, 14702, -1, 14703, 14703, 14703, -1, + 14704, 14704, 14704, -1, 14705, 14705, 14705, -1, + 14706, 14706, 14706, -1, 14707, 14707, 14707, -1, + 14708, 14708, 14708, -1, 14709, 14709, 14709, -1, + 14710, 14710, 14710, -1, 14711, 14711, 14711, -1, + 14712, 14712, 14712, -1, 14713, 14713, 14713, -1, + 14714, 14714, 14714, -1, 14715, 14715, 14715, -1, + 14716, 14716, 14716, -1, 14717, 14717, 14717, -1, + 14718, 14718, 14718, -1, 14719, 14719, 14719, -1, + 14720, 14720, 14720, -1, 14721, 14721, 14721, -1, + 14722, 14722, 14722, -1, 14723, 14723, 14723, -1, + 14724, 14724, 14724, -1, 14725, 14725, 14725, -1, + 14726, 14726, 14726, -1, 14727, 14727, 14727, -1, + 14728, 14728, 14728, -1, 14729, 14729, 14729, -1, + 14730, 14730, 14730, -1, 14731, 14731, 14731, -1, + 14732, 14732, 14732, -1, 14733, 14733, 14733, -1, + 14734, 14734, 14734, -1, 14735, 14735, 14735, -1, + 14736, 14736, 14736, -1, 14737, 14737, 14737, -1, + 14738, 14738, 14738, -1, 14739, 14739, 14739, -1, + 14740, 14740, 14740, -1, 14741, 14741, 14741, -1, + 14742, 14742, 14742, -1, 14743, 14743, 14743, -1, + 14744, 14744, 14744, -1, 14745, 14745, 14745, -1, + 14746, 14746, 14746, -1, 14747, 14747, 14747, -1, + 14748, 14748, 14748, -1, 14749, 14749, 14749, -1, + 14750, 14750, 14750, -1, 14751, 14751, 14751, -1, + 14752, 14752, 14752, -1, 14753, 14753, 14753, -1, + 14754, 14754, 14754, -1, 14755, 14755, 14755, -1, + 14756, 14756, 14756, -1, 14757, 14757, 14757, -1, + 14758, 14758, 14758, -1, 14759, 14759, 14759, -1, + 14760, 14760, 14760, -1, 14761, 14761, 14761, -1, + 14762, 14762, 14762, -1, 14763, 14763, 14763, -1, + 14764, 14764, 14764, -1, 14765, 14765, 14765, -1, + 14766, 14766, 14766, -1, 14767, 14767, 14767, -1, + 14768, 14768, 14768, -1, 14769, 14769, 14769, -1, + 14770, 14770, 14770, -1, 14771, 14771, 14771, -1, + 14772, 14772, 14772, -1, 14773, 14773, 14773, -1, + 14774, 14774, 14774, -1, 14775, 14775, 14775, -1, + 14776, 14776, 14776, -1, 14777, 14777, 14777, -1, + 14778, 14778, 14778, -1, 14779, 14779, 14779, -1, + 14780, 14780, 14780, -1, 14781, 14781, 14781, -1, + 14782, 14782, 14782, -1, 14783, 14783, 14783, -1, + 14784, 14784, 14784, -1, 14785, 14785, 14785, -1, + 14786, 14786, 14786, -1, 14787, 14787, 14787, -1, + 14788, 14788, 14788, -1, 14789, 14789, 14789, -1, + 14790, 14790, 14790, -1, 14791, 14791, 14791, -1, + 14792, 14792, 14792, -1, 14793, 14793, 14793, -1, + 14794, 14794, 14794, -1, 14795, 14795, 14795, -1, + 14796, 14796, 14796, -1, 14797, 14797, 14797, -1, + 14798, 14798, 14798, -1, 14799, 14799, 14799, -1, + 14800, 14800, 14800, -1, 14801, 14801, 14801, -1, + 14802, 14802, 14802, -1, 14803, 14803, 14803, -1, + 14804, 14804, 14804, -1, 14805, 14805, 14805, -1, + 14806, 14806, 14806, -1, 14807, 14807, 14807, -1, + 14808, 14808, 14808, -1, 14809, 14809, 14809, -1, + 14810, 14810, 14810, -1, 14811, 14811, 14811, -1, + 14812, 14812, 14812, -1, 14813, 14813, 14813, -1, + 14814, 14814, 14814, -1, 14815, 14815, 14815, -1, + 14816, 14816, 14816, -1, 14817, 14817, 14817, -1, + 14818, 14818, 14818, -1, 14819, 14819, 14819, -1, + 14820, 14820, 14820, -1, 14821, 14821, 14821, -1, + 14822, 14822, 14822, -1, 14823, 14823, 14823, -1, + 14824, 14824, 14824, -1, 14825, 14825, 14825, -1, + 14826, 14826, 14826, -1, 14827, 14827, 14827, -1, + 14828, 14828, 14828, -1, 14829, 14829, 14829, -1, + 14830, 14830, 14830, -1, 14831, 14831, 14831, -1, + 14832, 14832, 14832, -1, 14833, 14833, 14833, -1, + 14834, 14834, 14834, -1, 14835, 14835, 14835, -1, + 14836, 14836, 14836, -1, 14837, 14837, 14837, -1, + 14838, 14838, 14838, -1, 14839, 14839, 14839, -1, + 14840, 14840, 14840, -1, 14841, 14841, 14841, -1, + 14842, 14842, 14842, -1, 14843, 14843, 14843, -1, + 14844, 14844, 14844, -1, 14845, 14845, 14845, -1, + 14846, 14846, 14846, -1, 14847, 14847, 14847, -1, + 14848, 14848, 14848, -1, 14849, 14849, 14849, -1, + 14850, 14850, 14850, -1, 14851, 14851, 14851, -1, + 14852, 14852, 14852, -1, 14853, 14853, 14853, -1, + 14854, 14854, 14854, -1, 14855, 14855, 14855, -1, + 14856, 14856, 14856, -1, 14857, 14857, 14857, -1, + 14858, 14858, 14858, -1, 14859, 14859, 14859, -1, + 14860, 14860, 14860, -1, 14861, 14861, 14861, -1, + 14862, 14862, 14862, -1, 14863, 14863, 14863, -1, + 14864, 14864, 14864, -1, 14865, 14865, 14865, -1, + 14866, 14866, 14866, -1, 14867, 14867, 14867, -1, + 14868, 14868, 14868, -1, 14869, 14869, 14869, -1, + 14870, 14870, 14870, -1, 14871, 14871, 14871, -1, + 14872, 14872, 14872, -1, 14873, 14873, 14873, -1, + 14874, 14874, 14874, -1, 14875, 14875, 14875, -1, + 14876, 14876, 14876, -1, 14877, 14877, 14877, -1, + 14878, 14878, 14878, -1, 14879, 14879, 14879, -1, + 14880, 14880, 14880, -1, 14881, 14881, 14881, -1, + 14882, 14882, 14882, -1, 14883, 14883, 14883, -1, + 14884, 14884, 14884, -1, 14885, 14885, 14885, -1, + 14886, 14886, 14886, -1, 14887, 14887, 14887, -1, + 14888, 14888, 14888, -1, 14889, 14889, 14889, -1, + 14890, 14890, 14890, -1, 14891, 14891, 14891, -1, + 14892, 14892, 14892, -1, 14893, 14893, 14893, -1, + 14894, 14894, 14894, -1, 14895, 14895, 14895, -1, + 14896, 14896, 14896, -1, 14897, 14897, 14897, -1, + 14898, 14898, 14898, -1, 14899, 14899, 14899, -1, + 14900, 14900, 14900, -1, 14901, 14901, 14901, -1, + 14902, 14902, 14902, -1, 14903, 14903, 14903, -1, + 14904, 14904, 14904, -1, 14905, 14905, 14905, -1, + 14906, 14906, 14906, -1, 14907, 14907, 14907, -1, + 14908, 14908, 14908, -1, 14909, 14909, 14909, -1, + 14910, 14910, 14910, -1, 14911, 14911, 14911, -1, + 14912, 14912, 14912, -1, 14913, 14913, 14913, -1, + 14914, 14914, 14914, -1, 14915, 14915, 14915, -1, + 14916, 14916, 14916, -1, 14917, 14917, 14917, -1, + 14918, 14918, 14918, -1, 14919, 14919, 14919, -1, + 14920, 14920, 14920, -1, 14921, 14921, 14921, -1, + 14922, 14922, 14922, -1, 14923, 14923, 14923, -1, + 14924, 14924, 14924, -1, 14925, 14925, 14925, -1, + 14926, 14926, 14926, -1, 14927, 14927, 14927, -1, + 14928, 14928, 14928, -1, 14929, 14929, 14929, -1, + 14930, 14930, 14930, -1, 14931, 14931, 14931, -1, + 14932, 14932, 14932, -1, 14933, 14933, 14933, -1, + 14934, 14934, 14934, -1, 14935, 14935, 14935, -1, + 14936, 14936, 14936, -1, 14937, 14937, 14937, -1, + 14938, 14938, 14938, -1, 14939, 14939, 14939, -1, + 14940, 14940, 14940, -1, 14941, 14941, 14941, -1, + 14942, 14942, 14942, -1, 14943, 14943, 14943, -1, + 14944, 14944, 14944, -1, 14945, 14945, 14945, -1, + 14946, 14946, 14946, -1, 14947, 14947, 14947, -1, + 14948, 14948, 14948, -1, 14949, 14949, 14949, -1, + 14950, 14950, 14950, -1, 14951, 14951, 14951, -1, + 14952, 14952, 14952, -1, 14953, 14953, 14953, -1, + 14954, 14954, 14954, -1, 14955, 14955, 14955, -1, + 14956, 14956, 14956, -1, 14957, 14957, 14957, -1, + 14958, 14958, 14958, -1, 14959, 14959, 14959, -1, + 14960, 14960, 14960, -1, 14961, 14961, 14961, -1, + 14962, 14962, 14962, -1, 14963, 14963, 14963, -1, + 14964, 14964, 14964, -1, 14965, 14965, 14965, -1, + 14966, 14966, 14966, -1, 14967, 14967, 14967, -1, + 14968, 14968, 14968, -1, 14969, 14969, 14969, -1, + 14970, 14970, 14970, -1, 14971, 14971, 14971, -1, + 14972, 14972, 14972, -1, 14973, 14973, 14973, -1, + 14974, 14974, 14974, -1, 14975, 14975, 14975, -1, + 14976, 14976, 14976, -1, 14977, 14977, 14977, -1, + 14978, 14978, 14978, -1, 14979, 14979, 14979, -1, + 14980, 14980, 14980, -1, 14981, 14981, 14981, -1, + 14982, 14982, 14982, -1, 14983, 14983, 14983, -1, + 14984, 14984, 14984, -1, 14985, 14985, 14985, -1, + 14986, 14986, 14986, -1, 14987, 14987, 14987, -1, + 14988, 14988, 14988, -1, 14989, 14989, 14989, -1, + 14990, 14990, 14990, -1, 14991, 14991, 14991, -1, + 14992, 14992, 14992, -1, 14993, 14993, 14993, -1, + 14994, 14994, 14994, -1, 14995, 14995, 14995, -1, + 14996, 14996, 14996, -1, 14997, 14997, 14997, -1, + 14998, 14998, 14998, -1, 14999, 14999, 14999, -1, + 15000, 15000, 15000, -1, 15001, 15001, 15001, -1, + 15002, 15002, 15002, -1, 15003, 15003, 15003, -1, + 15004, 15004, 15004, -1, 15005, 15005, 15005, -1, + 15006, 15006, 15006, -1, 15007, 15007, 15007, -1, + 15008, 15008, 15008, -1, 15009, 15009, 15009, -1, + 15010, 15010, 15010, -1, 15011, 15011, 15011, -1, + 15012, 15012, 15012, -1, 15013, 15013, 15013, -1, + 15014, 15014, 15014, -1, 15015, 15015, 15015, -1, + 15016, 15016, 15016, -1, 15017, 15017, 15017, -1, + 15018, 15018, 15018, -1, 15019, 15019, 15019, -1, + 15020, 15020, 15020, -1, 15021, 15021, 15021, -1, + 15022, 15022, 15022, -1, 15023, 15023, 15023, -1, + 15024, 15024, 15024, -1, 15025, 15025, 15025, -1, + 15026, 15026, 15026, -1, 15027, 15027, 15027, -1, + 15028, 15028, 15028, -1, 15029, 15029, 15029, -1, + 15030, 15030, 15030, -1, 15031, 15031, 15031, -1, + 15032, 15032, 15032, -1, 15033, 15033, 15033, -1, + 15034, 15034, 15034, -1, 15035, 15035, 15035, -1, + 15036, 15036, 15036, -1, 15037, 15037, 15037, -1, + 15038, 15038, 15038, -1, 15039, 15039, 15039, -1, + 15040, 15040, 15040, -1, 15041, 15041, 15041, -1, + 15042, 15042, 15042, -1, 15043, 15043, 15043, -1, + 15044, 15044, 15044, -1, 15045, 15045, 15045, -1, + 15046, 15046, 15046, -1, 15047, 15047, 15047, -1, + 15048, 15048, 15048, -1, 15049, 15049, 15049, -1, + 15050, 15050, 15050, -1, 15051, 15051, 15051, -1, + 15052, 15052, 15052, -1, 15053, 15053, 15053, -1, + 15054, 15054, 15054, -1, 15055, 15055, 15055, -1, + 15056, 15056, 15056, -1, 15057, 15057, 15057, -1, + 15058, 15058, 15058, -1, 15059, 15059, 15059, -1, + 15060, 15060, 15060, -1, 15061, 15061, 15061, -1, + 15062, 15062, 15062, -1, 15063, 15063, 15063, -1, + 15064, 15064, 15064, -1, 15065, 15065, 15065, -1, + 15066, 15066, 15066, -1, 15067, 15067, 15067, -1, + 15068, 15068, 15068, -1, 15069, 15069, 15069, -1, + 15070, 15070, 15070, -1, 15071, 15071, 15071, -1, + 15072, 15072, 15072, -1, 15073, 15073, 15073, -1, + 15074, 15074, 15074, -1, 15075, 15075, 15075, -1, + 15076, 15076, 15076, -1, 15077, 15077, 15077, -1, + 15078, 15078, 15078, -1, 15079, 15079, 15079, -1, + 15080, 15080, 15080, -1, 15081, 15081, 15081, -1, + 15082, 15082, 15082, -1, 15083, 15083, 15083, -1, + 15084, 15084, 15084, -1, 15085, 15085, 15085, -1, + 15086, 15086, 15086, -1, 15087, 15087, 15087, -1, + 15088, 15088, 15088, -1, 15089, 15089, 15089, -1, + 15090, 15090, 15090, -1, 15091, 15091, 15091, -1, + 15092, 15092, 15092, -1, 15093, 15093, 15093, -1, + 15094, 15094, 15094, -1, 15095, 15095, 15095, -1, + 15096, 15096, 15096, -1, 15097, 15097, 15097, -1, + 15098, 15098, 15098, -1, 15099, 15099, 15099, -1, + 15100, 15100, 15100, -1, 15101, 15101, 15101, -1, + 15102, 15102, 15102, -1, 15103, 15103, 15103, -1, + 15104, 15104, 15104, -1, 15105, 15105, 15105, -1, + 15106, 15106, 15106, -1, 15107, 15107, 15107, -1, + 15108, 15108, 15108, -1, 15109, 15109, 15109, -1, + 15110, 15110, 15110, -1, 15111, 15111, 15111, -1, + 15112, 15112, 15112, -1, 15113, 15113, 15113, -1, + 15114, 15114, 15114, -1, 15115, 15115, 15115, -1, + 15116, 15116, 15116, -1, 15117, 15117, 15117, -1, + 15118, 15118, 15118, -1, 15119, 15119, 15119, -1, + 15120, 15120, 15120, -1, 15121, 15121, 15121, -1, + 15122, 15122, 15122, -1, 15123, 15123, 15123, -1, + 15124, 15124, 15124, -1, 15125, 15125, 15125, -1, + 15126, 15126, 15126, -1, 15127, 15127, 15127, -1, + 15128, 15128, 15128, -1, 15129, 15129, 15129, -1, + 15130, 15130, 15130, -1, 15131, 15131, 15131, -1, + 15132, 15132, 15132, -1, 15133, 15133, 15133, -1, + 15134, 15134, 15134, -1, 15135, 15135, 15135, -1, + 15136, 15136, 15136, -1, 15137, 15137, 15137, -1, + 15138, 15138, 15138, -1, 15139, 15139, 15139, -1, + 15140, 15140, 15140, -1, 15141, 15141, 15141, -1, + 15142, 15142, 15142, -1, 15143, 15143, 15143, -1, + 15144, 15144, 15144, -1, 15145, 15145, 15145, -1, + 15146, 15146, 15146, -1, 15147, 15147, 15147, -1, + 15148, 15148, 15148, -1, 15149, 15149, 15149, -1, + 15150, 15150, 15150, -1, 15151, 15151, 15151, -1, + 15152, 15152, 15152, -1, 15153, 15153, 15153, -1, + 15154, 15154, 15154, -1, 15155, 15155, 15155, -1, + 15156, 15156, 15156, -1, 15157, 15157, 15157, -1, + 15158, 15158, 15158, -1, 15159, 15159, 15159, -1, + 15160, 15160, 15160, -1, 15161, 15161, 15161, -1, + 15162, 15162, 15162, -1, 15163, 15163, 15163, -1, + 15164, 15164, 15164, -1, 15165, 15165, 15165, -1, + 15166, 15166, 15166, -1, 15167, 15167, 15167, -1, + 15168, 15168, 15168, -1, 15169, 15169, 15169, -1, + 15170, 15170, 15170, -1, 15171, 15171, 15171, -1, + 15172, 15172, 15172, -1, 15173, 15173, 15173, -1, + 15174, 15174, 15174, -1, 15175, 15175, 15175, -1, + 15176, 15176, 15176, -1, 15177, 15177, 15177, -1, + 15178, 15178, 15178, -1, 15179, 15179, 15179, -1, + 15180, 15180, 15180, -1, 15181, 15181, 15181, -1, + 15182, 15182, 15182, -1, 15183, 15183, 15183, -1, + 15184, 15184, 15184, -1, 15185, 15185, 15185, -1, + 15186, 15186, 15186, -1, 15187, 15187, 15187, -1, + 15188, 15188, 15188, -1, 15189, 15189, 15189, -1, + 15190, 15190, 15190, -1, 15191, 15191, 15191, -1, + 15192, 15192, 15192, -1, 15193, 15193, 15193, -1, + 15194, 15194, 15194, -1, 15195, 15195, 15195, -1, + 15196, 15196, 15196, -1, 15197, 15197, 15197, -1, + 15198, 15198, 15198, -1, 15199, 15199, 15199, -1, + 15200, 15200, 15200, -1, 15201, 15201, 15201, -1, + 15202, 15202, 15202, -1, 15203, 15203, 15203, -1, + 15204, 15204, 15204, -1, 15205, 15205, 15205, -1, + 15206, 15206, 15206, -1, 15207, 15207, 15207, -1, + 15208, 15208, 15208, -1, 15209, 15209, 15209, -1, + 15210, 15210, 15210, -1, 15211, 15211, 15211, -1, + 15212, 15212, 15212, -1, 15213, 15213, 15213, -1, + 15214, 15214, 15214, -1, 15215, 15215, 15215, -1, + 15216, 15216, 15216, -1, 15217, 15217, 15217, -1, + 15218, 15218, 15218, -1, 15219, 15219, 15219, -1, + 15220, 15220, 15220, -1, 15221, 15221, 15221, -1, + 15222, 15222, 15222, -1, 15223, 15223, 15223, -1, + 15224, 15224, 15224, -1, 15225, 15225, 15225, -1, + 15226, 15226, 15226, -1, 15227, 15227, 15227, -1, + 15228, 15228, 15228, -1, 15229, 15229, 15229, -1, + 15230, 15230, 15230, -1, 15231, 15231, 15231, -1, + 15232, 15232, 15232, -1, 15233, 15233, 15233, -1, + 15234, 15234, 15234, -1, 15235, 15235, 15235, -1, + 15236, 15236, 15236, -1, 15237, 15237, 15237, -1, + 15238, 15238, 15238, -1, 15239, 15239, 15239, -1, + 15240, 15240, 15240, -1, 15241, 15241, 15241, -1, + 15242, 15242, 15242, -1, 15243, 15243, 15243, -1, + 15244, 15244, 15244, -1, 15245, 15245, 15245, -1, + 15246, 15246, 15246, -1, 15247, 15247, 15247, -1, + 15248, 15248, 15248, -1, 15249, 15249, 15249, -1, + 15250, 15250, 15250, -1, 15251, 15251, 15251, -1, + 15252, 15252, 15252, -1, 15253, 15253, 15253, -1, + 15254, 15254, 15254, -1, 15255, 15255, 15255, -1, + 15256, 15256, 15256, -1, 15257, 15257, 15257, -1, + 15258, 15258, 15258, -1, 15259, 15259, 15259, -1, + 15260, 15260, 15260, -1, 15261, 15261, 15261, -1, + 15262, 15262, 15262, -1, 15263, 15263, 15263, -1, + 15264, 15264, 15264, -1, 15265, 15265, 15265, -1, + 15266, 15266, 15266, -1, 15267, 15267, 15267, -1, + 15268, 15268, 15268, -1, 15269, 15269, 15269, -1, + 15270, 15270, 15270, -1, 15271, 15271, 15271, -1, + 15272, 15272, 15272, -1, 15273, 15273, 15273, -1, + 15274, 15274, 15274, -1, 15275, 15275, 15275, -1, + 15276, 15276, 15276, -1, 15277, 15277, 15277, -1, + 15278, 15278, 15278, -1, 15279, 15279, 15279, -1, + 15280, 15280, 15280, -1, 15281, 15281, 15281, -1, + 15282, 15282, 15282, -1, 15283, 15283, 15283, -1, + 15284, 15284, 15284, -1, 15285, 15285, 15285, -1, + 15286, 15286, 15286, -1, 15287, 15287, 15287, -1, + 15288, 15288, 15288, -1, 15289, 15289, 15289, -1, + 15290, 15290, 15290, -1, 15291, 15291, 15291, -1, + 15292, 15292, 15292, -1, 15293, 15293, 15293, -1, + 15294, 15294, 15294, -1, 15295, 15295, 15295, -1, + 15296, 15296, 15296, -1, 15297, 15297, 15297, -1, + 15298, 15298, 15298, -1, 15299, 15299, 15299, -1, + 15300, 15300, 15300, -1, 15301, 15301, 15301, -1, + 15302, 15302, 15302, -1, 15303, 15303, 15303, -1, + 15304, 15304, 15304, -1, 15305, 15305, 15305, -1, + 15306, 15306, 15306, -1, 15307, 15307, 15307, -1, + 15308, 15308, 15308, -1, 15309, 15309, 15309, -1, + 15310, 15310, 15310, -1, 15311, 15311, 15311, -1, + 15312, 15312, 15312, -1, 15313, 15313, 15313, -1, + 15314, 15314, 15314, -1, 15315, 15315, 15315, -1, + 15316, 15316, 15316, -1, 15317, 15317, 15317, -1, + 15318, 15318, 15318, -1, 15319, 15319, 15319, -1, + 15320, 15320, 15320, -1, 15321, 15321, 15321, -1, + 15322, 15322, 15322, -1, 15323, 15323, 15323, -1, + 15324, 15324, 15324, -1, 15325, 15325, 15325, -1, + 15326, 15326, 15326, -1, 15327, 15327, 15327, -1, + 15328, 15328, 15328, -1, 15329, 15329, 15329, -1, + 15330, 15330, 15330, -1, 15331, 15331, 15331, -1, + 15332, 15332, 15332, -1, 15333, 15333, 15333, -1, + 15334, 15334, 15334, -1, 15335, 15335, 15335, -1, + 15336, 15336, 15336, -1, 15337, 15337, 15337, -1, + 15338, 15338, 15338, -1, 15339, 15339, 15339, -1, + 15340, 15340, 15340, -1, 15341, 15341, 15341, -1, + 15342, 15342, 15342, -1, 15343, 15343, 15343, -1, + 15344, 15344, 15344, -1, 15345, 15345, 15345, -1, + 15346, 15346, 15346, -1, 15347, 15347, 15347, -1, + 15348, 15348, 15348, -1, 15349, 15349, 15349, -1, + 15350, 15350, 15350, -1, 15351, 15351, 15351, -1, + 15352, 15352, 15352, -1, 15353, 15353, 15353, -1, + 15354, 15354, 15354, -1, 15355, 15355, 15355, -1, + 15356, 15356, 15356, -1, 15357, 15357, 15357, -1, + 15358, 15358, 15358, -1, 15359, 15359, 15359, -1, + 15360, 15360, 15360, -1, 15361, 15361, 15361, -1, + 15362, 15362, 15362, -1, 15363, 15363, 15363, -1, + 15364, 15364, 15364, -1, 15365, 15365, 15365, -1, + 15366, 15366, 15366, -1, 15367, 15367, 15367, -1, + 15368, 15368, 15368, -1, 15369, 15369, 15369, -1, + 15370, 15370, 15370, -1, 15371, 15371, 15371, -1, + 15372, 15372, 15372, -1, 15373, 15373, 15373, -1, + 15374, 15374, 15374, -1, 15375, 15375, 15375, -1, + 15376, 15376, 15376, -1, 15377, 15377, 15377, -1, + 15378, 15378, 15378, -1, 15379, 15379, 15379, -1, + 15380, 15380, 15380, -1, 15381, 15381, 15381, -1, + 15382, 15382, 15382, -1, 15383, 15383, 15383, -1, + 15384, 15384, 15384, -1, 15385, 15385, 15385, -1, + 15386, 15386, 15386, -1, 15387, 15387, 15387, -1, + 15388, 15388, 15388, -1, 15389, 15389, 15389, -1, + 15390, 15390, 15390, -1, 15391, 15391, 15391, -1, + 15392, 15392, 15392, -1, 15393, 15393, 15393, -1, + 15394, 15394, 15394, -1, 15395, 15395, 15395, -1, + 15396, 15396, 15396, -1, 15397, 15397, 15397, -1, + 15398, 15398, 15398, -1, 15399, 15399, 15399, -1, + 15400, 15400, 15400, -1, 15401, 15401, 15401, -1, + 15402, 15402, 15402, -1, 15403, 15403, 15403, -1, + 15404, 15404, 15404, -1, 15405, 15405, 15405, -1, + 15406, 15406, 15406, -1, 15407, 15407, 15407, -1, + 15408, 15408, 15408, -1, 15409, 15409, 15409, -1, + 15410, 15410, 15410, -1, 15411, 15411, 15411, -1, + 15412, 15412, 15412, -1, 15413, 15413, 15413, -1, + 15414, 15414, 15414, -1, 15415, 15415, 15415, -1, + 15416, 15416, 15416, -1, 15417, 15417, 15417, -1, + 15418, 15418, 15418, -1, 15419, 15419, 15419, -1, + 15420, 15420, 15420, -1, 15421, 15421, 15421, -1, + 15422, 15422, 15422, -1, 15423, 15423, 15423, -1, + 15424, 15424, 15424, -1, 15425, 15425, 15425, -1, + 15426, 15426, 15426, -1, 15427, 15427, 15427, -1, + 15428, 15428, 15428, -1, 15429, 15429, 15429, -1, + 15430, 15430, 15430, -1, 15431, 15431, 15431, -1, + 15432, 15432, 15432, -1, 15433, 15433, 15433, -1, + 15434, 15434, 15434, -1, 15435, 15435, 15435, -1, + 15436, 15436, 15436, -1, 15437, 15437, 15437, -1, + 15438, 15438, 15438, -1, 15439, 15439, 15439, -1, + 15440, 15440, 15440, -1, 15441, 15441, 15441, -1, + 15442, 15442, 15442, -1, 15443, 15443, 15443, -1, + 15444, 15444, 15444, -1, 15445, 15445, 15445, -1, + 15446, 15446, 15446, -1, 15447, 15447, 15447, -1, + 15448, 15448, 15448, -1, 15449, 15449, 15449, -1, + 15450, 15450, 15450, -1, 15451, 15451, 15451, -1, + 15452, 15452, 15452, -1, 15453, 15453, 15453, -1, + 15454, 15454, 15454, -1, 15455, 15455, 15455, -1, + 15456, 15456, 15456, -1, 15457, 15457, 15457, -1, + 15458, 15458, 15458, -1, 15459, 15459, 15459, -1, + 15460, 15460, 15460, -1, 15461, 15461, 15461, -1, + 15462, 15462, 15462, -1, 15463, 15463, 15463, -1, + 15464, 15464, 15464, -1, 15465, 15465, 15465, -1, + 15466, 15466, 15466, -1, 15467, 15467, 15467, -1, + 15468, 15468, 15468, -1, 15469, 15469, 15469, -1, + 15470, 15470, 15470, -1, 15471, 15471, 15471, -1, + 15472, 15472, 15472, -1, 15473, 15473, 15473, -1, + 15474, 15474, 15474, -1, 15475, 15475, 15475, -1, + 15476, 15476, 15476, -1, 15477, 15477, 15477, -1, + 15478, 15478, 15478, -1, 15479, 15479, 15479, -1, + 15480, 15480, 15480, -1, 15481, 15481, 15481, -1, + 15482, 15482, 15482, -1, 15483, 15483, 15483, -1, + 15484, 15484, 15484, -1, 15485, 15485, 15485, -1, + 15486, 15486, 15486, -1, 15487, 15487, 15487, -1, + 15488, 15488, 15488, -1, 15489, 15489, 15489, -1, + 15490, 15490, 15490, -1, 15491, 15491, 15491, -1, + 15492, 15492, 15492, -1, 15493, 15493, 15493, -1, + 15494, 15494, 15494, -1, 15495, 15495, 15495, -1, + 15496, 15496, 15496, -1, 15497, 15497, 15497, -1, + 15498, 15498, 15498, -1, 15499, 15499, 15499, -1, + 15500, 15500, 15500, -1, 15501, 15501, 15501, -1, + 15502, 15502, 15502, -1, 15503, 15503, 15503, -1, + 15504, 15504, 15504, -1, 15505, 15505, 15505, -1, + 15506, 15506, 15506, -1, 15507, 15507, 15507, -1, + 15508, 15508, 15508, -1, 15509, 15509, 15509, -1, + 15510, 15510, 15510, -1, 15511, 15511, 15511, -1, + 15512, 15512, 15512, -1, 15513, 15513, 15513, -1, + 15514, 15514, 15514, -1, 15515, 15515, 15515, -1, + 15516, 15516, 15516, -1, 15517, 15517, 15517, -1, + 15518, 15518, 15518, -1, 15519, 15519, 15519, -1, + 15520, 15520, 15520, -1, 15521, 15521, 15521, -1, + 15522, 15522, 15522, -1, 15523, 15523, 15523, -1, + 15524, 15524, 15524, -1, 15525, 15525, 15525, -1, + 15526, 15526, 15526, -1, 15527, 15527, 15527, -1, + 15528, 15528, 15528, -1, 15529, 15529, 15529, -1, + 15530, 15530, 15530, -1, 15531, 15531, 15531, -1, + 15532, 15532, 15532, -1, 15533, 15533, 15533, -1, + 15534, 15534, 15534, -1, 15535, 15535, 15535, -1, + 15536, 15536, 15536, -1, 15537, 15537, 15537, -1, + 15538, 15538, 15538, -1, 15539, 15539, 15539, -1, + 15540, 15540, 15540, -1, 15541, 15541, 15541, -1, + 15542, 15542, 15542, -1, 15543, 15543, 15543, -1, + 15544, 15544, 15544, -1, 15545, 15545, 15545, -1, + 15546, 15546, 15546, -1, 15547, 15547, 15547, -1, + 15548, 15548, 15548, -1, 15549, 15549, 15549, -1, + 15550, 15550, 15550, -1, 15551, 15551, 15551, -1, + 15552, 15552, 15552, -1, 15553, 15553, 15553, -1, + 15554, 15554, 15554, -1, 15555, 15555, 15555, -1, + 15556, 15556, 15556, -1, 15557, 15557, 15557, -1, + 15558, 15558, 15558, -1, 15559, 15559, 15559, -1, + 15560, 15560, 15560, -1, 15561, 15561, 15561, -1, + 15562, 15562, 15562, -1, 15563, 15563, 15563, -1, + 15564, 15564, 15564, -1, 15565, 15565, 15565, -1, + 15566, 15566, 15566, -1, 15567, 15567, 15567, -1, + 15568, 15568, 15568, -1, 15569, 15569, 15569, -1, + 15570, 15570, 15570, -1, 15571, 15571, 15571, -1, + 15572, 15572, 15572, -1, 15573, 15573, 15573, -1, + 15574, 15574, 15574, -1, 15575, 15575, 15575, -1, + 15576, 15576, 15576, -1, 15577, 15577, 15577, -1, + 15578, 15578, 15578, -1, 15579, 15579, 15579, -1, + 15580, 15580, 15580, -1, 15581, 15581, 15581, -1, + 15582, 15582, 15582, -1, 15583, 15583, 15583, -1, + 15584, 15584, 15584, -1, 15585, 15585, 15585, -1, + 15586, 15586, 15586, -1, 15587, 15587, 15587, -1, + 15588, 15588, 15588, -1, 15589, 15589, 15589, -1, + 15590, 15590, 15590, -1, 15591, 15591, 15591, -1, + 15592, 15592, 15592, -1, 15593, 15593, 15593, -1, + 15594, 15594, 15594, -1, 15595, 15595, 15595, -1, + 15596, 15596, 15596, -1, 15597, 15597, 15597, -1, + 15598, 15598, 15598, -1, 15599, 15599, 15599, -1, + 15600, 15600, 15600, -1, 15601, 15601, 15601, -1, + 15602, 15602, 15602, -1, 15603, 15603, 15603, -1, + 15604, 15604, 15604, -1, 15605, 15605, 15605, -1, + 15606, 15606, 15606, -1, 15607, 15607, 15607, -1, + 15608, 15608, 15608, -1, 15609, 15609, 15609, -1, + 15610, 15610, 15610, -1, 15611, 15611, 15611, -1, + 15612, 15612, 15612, -1, 15613, 15613, 15613, -1, + 15614, 15614, 15614, -1, 15615, 15615, 15615, -1, + 15616, 15616, 15616, -1, 15617, 15617, 15617, -1, + 15618, 15618, 15618, -1, 15619, 15619, 15619, -1, + 15620, 15620, 15620, -1, 15621, 15621, 15621, -1, + 15622, 15622, 15622, -1, 15623, 15623, 15623, -1, + 15624, 15624, 15624, -1, 15625, 15625, 15625, -1, + 15626, 15626, 15626, -1, 15627, 15627, 15627, -1, + 15628, 15628, 15628, -1, 15629, 15629, 15629, -1, + 15630, 15630, 15630, -1, 15631, 15631, 15631, -1, + 15632, 15632, 15632, -1, 15633, 15633, 15633, -1, + 15634, 15634, 15634, -1, 15635, 15635, 15635, -1, + 15636, 15636, 15636, -1, 15637, 15637, 15637, -1, + 15638, 15638, 15638, -1, 15639, 15639, 15639, -1, + 15640, 15640, 15640, -1, 15641, 15641, 15641, -1, + 15642, 15642, 15642, -1, 15643, 15643, 15643, -1, + 15644, 15644, 15644, -1, 15645, 15645, 15645, -1, + 15646, 15646, 15646, -1, 15647, 15647, 15647, -1, + 15648, 15648, 15648, -1, 15649, 15649, 15649, -1, + 15650, 15650, 15650, -1, 15651, 15651, 15651, -1, + 15652, 15652, 15652, -1, 15653, 15653, 15653, -1, + 15654, 15654, 15654, -1, 15655, 15655, 15655, -1, + 15656, 15656, 15656, -1, 15657, 15657, 15657, -1, + 15658, 15658, 15658, -1, 15659, 15659, 15659, -1, + 15660, 15660, 15660, -1, 15661, 15661, 15661, -1, + 15662, 15662, 15662, -1, 15663, 15663, 15663, -1, + 15664, 15664, 15664, -1, 15665, 15665, 15665, -1, + 15666, 15666, 15666, -1, 15667, 15667, 15667, -1, + 15668, 15668, 15668, -1, 15669, 15669, 15669, -1, + 15670, 15670, 15670, -1, 15671, 15671, 15671, -1, + 15672, 15672, 15672, -1, 15673, 15673, 15673, -1, + 15674, 15674, 15674, -1, 15675, 15675, 15675, -1, + 15676, 15676, 15676, -1, 15677, 15677, 15677, -1, + 15678, 15678, 15678, -1, 15679, 15679, 15679, -1, + 15680, 15680, 15680, -1, 15681, 15681, 15681, -1, + 15682, 15682, 15682, -1, 15683, 15683, 15683, -1, + 15684, 15684, 15684, -1, 15685, 15685, 15685, -1, + 15686, 15686, 15686, -1, 15687, 15687, 15687, -1, + 15688, 15688, 15688, -1, 15689, 15689, 15689, -1, + 15690, 15690, 15690, -1, 15691, 15691, 15691, -1, + 15692, 15692, 15692, -1, 15693, 15693, 15693, -1, + 15694, 15694, 15694, -1, 15695, 15695, 15695, -1, + 15696, 15696, 15696, -1, 15697, 15697, 15697, -1, + 15698, 15698, 15698, -1, 15699, 15699, 15699, -1, + 15700, 15700, 15700, -1, 15701, 15701, 15701, -1, + 15702, 15702, 15702, -1, 15703, 15703, 15703, -1, + 15704, 15704, 15704, -1, 15705, 15705, 15705, -1, + 15706, 15706, 15706, -1, 15707, 15707, 15707, -1, + 15708, 15708, 15708, -1, 15709, 15709, 15709, -1, + 15710, 15710, 15710, -1, 15711, 15711, 15711, -1, + 15712, 15712, 15712, -1, 15713, 15713, 15713, -1, + 15714, 15714, 15714, -1, 15715, 15715, 15715, -1, + 15716, 15716, 15716, -1, 15717, 15717, 15717, -1, + 15718, 15718, 15718, -1, 15719, 15719, 15719, -1, + 15720, 15720, 15720, -1, 15721, 15721, 15721, -1, + 15722, 15722, 15722, -1, 15723, 15723, 15723, -1, + 15724, 15724, 15724, -1, 15725, 15725, 15725, -1, + 15726, 15726, 15726, -1, 15727, 15727, 15727, -1, + 15728, 15728, 15728, -1, 15729, 15729, 15729, -1, + 15730, 15730, 15730, -1, 15731, 15731, 15731, -1, + 15732, 15732, 15732, -1, 15733, 15733, 15733, -1, + 15734, 15734, 15734, -1, 15735, 15735, 15735, -1, + 15736, 15736, 15736, -1, 15737, 15737, 15737, -1, + 15738, 15738, 15738, -1, 15739, 15739, 15739, -1, + 15740, 15740, 15740, -1, 15741, 15741, 15741, -1, + 15742, 15742, 15742, -1, 15743, 15743, 15743, -1, + 15744, 15744, 15744, -1, 15745, 15745, 15745, -1, + 15746, 15746, 15746, -1, 15747, 15747, 15747, -1, + 15748, 15748, 15748, -1, 15749, 15749, 15749, -1, + 15750, 15750, 15750, -1, 15751, 15751, 15751, -1, + 15752, 15752, 15752, -1, 15753, 15753, 15753, -1, + 15754, 15754, 15754, -1, 15755, 15755, 15755, -1, + 15756, 15756, 15756, -1, 15757, 15757, 15757, -1, + 15758, 15758, 15758, -1, 15759, 15759, 15759, -1, + 15760, 15760, 15760, -1, 15761, 15761, 15761, -1, + 15762, 15762, 15762, -1, 15763, 15763, 15763, -1, + 15764, 15764, 15764, -1, 15765, 15765, 15765, -1, + 15766, 15766, 15766, -1, 15767, 15767, 15767, -1, + 15768, 15768, 15768, -1, 15769, 15769, 15769, -1, + 15770, 15770, 15770, -1, 15771, 15771, 15771, -1, + 15772, 15772, 15772, -1, 15773, 15773, 15773, -1, + 15774, 15774, 15774, -1, 15775, 15775, 15775, -1, + 15776, 15776, 15776, -1, 15777, 15777, 15777, -1, + 15778, 15778, 15778, -1, 15779, 15779, 15779, -1, + 15780, 15780, 15780, -1, 15781, 15781, 15781, -1, + 15782, 15782, 15782, -1, 15783, 15783, 15783, -1, + 15784, 15784, 15784, -1, 15785, 15785, 15785, -1, + 15786, 15786, 15786, -1, 15787, 15787, 15787, -1, + 15788, 15788, 15788, -1, 15789, 15789, 15789, -1, + 15790, 15790, 15790, -1, 15791, 15791, 15791, -1, + 15792, 15792, 15792, -1, 15793, 15793, 15793, -1, + 15794, 15794, 15794, -1, 15795, 15795, 15795, -1, + 15796, 15796, 15796, -1, 15797, 15797, 15797, -1, + 15798, 15798, 15798, -1, 15799, 15799, 15799, -1, + 15800, 15800, 15800, -1, 15801, 15801, 15801, -1, + 15802, 15802, 15802, -1, 15803, 15803, 15803, -1, + 15804, 15804, 15804, -1, 15805, 15805, 15805, -1, + 15806, 15806, 15806, -1, 15807, 15807, 15807, -1, + 15808, 15808, 15808, -1, 15809, 15809, 15809, -1, + 15810, 15810, 15810, -1, 15811, 15811, 15811, -1, + 15812, 15812, 15812, -1, 15813, 15813, 15813, -1, + 15814, 15814, 15814, -1, 15815, 15815, 15815, -1, + 15816, 15816, 15816, -1, 15817, 15817, 15817, -1, + 15818, 15818, 15818, -1, 15819, 15819, 15819, -1, + 15820, 15820, 15820, -1, 15821, 15821, 15821, -1, + 15822, 15822, 15822, -1, 15823, 15823, 15823, -1, + 15824, 15824, 15824, -1, 15825, 15825, 15825, -1, + 15826, 15826, 15826, -1, 15827, 15827, 15827, -1, + 15828, 15828, 15828, -1, 15829, 15829, 15829, -1, + 15830, 15830, 15830, -1, 15831, 15831, 15831, -1, + 15832, 15832, 15832, -1, 15833, 15833, 15833, -1, + 15834, 15834, 15834, -1, 15835, 15835, 15835, -1, + 15836, 15836, 15836, -1, 15837, 15837, 15837, -1, + 15838, 15838, 15838, -1, 15839, 15839, 15839, -1, + 15840, 15840, 15840, -1, 15841, 15841, 15841, -1, + 15842, 15842, 15842, -1, 15843, 15843, 15843, -1, + 15844, 15844, 15844, -1, 15845, 15845, 15845, -1, + 15846, 15846, 15846, -1, 15847, 15847, 15847, -1, + 15848, 15848, 15848, -1, 15849, 15849, 15849, -1, + 15850, 15850, 15850, -1, 15851, 15851, 15851, -1, + 15852, 15852, 15852, -1, 15853, 15853, 15853, -1, + 15854, 15854, 15854, -1, 15855, 15855, 15855, -1, + 15856, 15856, 15856, -1, 15857, 15857, 15857, -1, + 15858, 15858, 15858, -1, 15859, 15859, 15859, -1, + 15860, 15860, 15860, -1, 15861, 15861, 15861, -1, + 15862, 15862, 15862, -1, 15863, 15863, 15863, -1, + 15864, 15864, 15864, -1, 15865, 15865, 15865, -1, + 15866, 15866, 15866, -1, 15867, 15867, 15867, -1, + 15868, 15868, 15868, -1, 15869, 15869, 15869, -1, + 15870, 15870, 15870, -1, 15871, 15871, 15871, -1, + 15872, 15872, 15872, -1, 15873, 15873, 15873, -1, + 15874, 15874, 15874, -1, 15875, 15875, 15875, -1, + 15876, 15876, 15876, -1, 15877, 15877, 15877, -1, + 15878, 15878, 15878, -1, 15879, 15879, 15879, -1, + 15880, 15880, 15880, -1, 15881, 15881, 15881, -1, + 15882, 15882, 15882, -1, 15883, 15883, 15883, -1, + 15884, 15884, 15884, -1, 15885, 15885, 15885, -1, + 15886, 15886, 15886, -1, 15887, 15887, 15887, -1, + 15888, 15888, 15888, -1, 15889, 15889, 15889, -1, + 15890, 15890, 15890, -1, 15891, 15891, 15891, -1, + 15892, 15892, 15892, -1, 15893, 15893, 15893, -1, + 15894, 15894, 15894, -1, 15895, 15895, 15895, -1, + 15896, 15896, 15896, -1, 15897, 15897, 15897, -1, + 15898, 15898, 15898, -1, 15899, 15899, 15899, -1, + 15900, 15900, 15900, -1, 15901, 15901, 15901, -1, + 15902, 15902, 15902, -1, 15903, 15903, 15903, -1, + 15904, 15904, 15904, -1, 15905, 15905, 15905, -1, + 15906, 15906, 15906, -1, 15907, 15907, 15907, -1, + 15908, 15908, 15908, -1, 15909, 15909, 15909, -1, + 15910, 15910, 15910, -1, 15911, 15911, 15911, -1, + 15912, 15912, 15912, -1, 15913, 15913, 15913, -1, + 15914, 15914, 15914, -1, 15915, 15915, 15915, -1, + 15916, 15916, 15916, -1, 15917, 15917, 15917, -1, + 15918, 15918, 15918, -1, 15919, 15919, 15919, -1, + 15920, 15920, 15920, -1, 15921, 15921, 15921, -1, + 15922, 15922, 15922, -1, 15923, 15923, 15923, -1, + 15924, 15924, 15924, -1, 15925, 15925, 15925, -1, + 15926, 15926, 15926, -1, 15927, 15927, 15927, -1, + 15928, 15928, 15928, -1, 15929, 15929, 15929, -1, + 15930, 15930, 15930, -1, 15931, 15931, 15931, -1, + 15932, 15932, 15932, -1, 15933, 15933, 15933, -1, + 15934, 15934, 15934, -1, 15935, 15935, 15935, -1, + 15936, 15936, 15936, -1, 15937, 15937, 15937, -1, + 15938, 15938, 15938, -1, 15939, 15939, 15939, -1, + 15940, 15940, 15940, -1, 15941, 15941, 15941, -1, + 15942, 15942, 15942, -1, 15943, 15943, 15943, -1, + 15944, 15944, 15944, -1, 15945, 15945, 15945, -1, + 15946, 15946, 15946, -1, 15947, 15947, 15947, -1, + 15948, 15948, 15948, -1, 15949, 15949, 15949, -1, + 15950, 15950, 15950, -1, 15951, 15951, 15951, -1, + 15952, 15952, 15952, -1, 15953, 15953, 15953, -1, + 15954, 15954, 15954, -1, 15955, 15955, 15955, -1, + 15956, 15956, 15956, -1, 15957, 15957, 15957, -1, + 15958, 15958, 15958, -1, 15959, 15959, 15959, -1, + 15960, 15960, 15960, -1, 15961, 15961, 15961, -1, + 15962, 15962, 15962, -1, 15963, 15963, 15963, -1, + 15964, 15964, 15964, -1, 15965, 15965, 15965, -1, + 15966, 15966, 15966, -1, 15967, 15967, 15967, -1, + 15968, 15968, 15968, -1, 15969, 15969, 15969, -1, + 15970, 15970, 15970, -1, 15971, 15971, 15971, -1, + 15972, 15972, 15972, -1, 15973, 15973, 15973, -1, + 15974, 15974, 15974, -1, 15975, 15975, 15975, -1, + 15976, 15976, 15976, -1, 15977, 15977, 15977, -1, + 15978, 15978, 15978, -1, 15979, 15979, 15979, -1, + 15980, 15980, 15980, -1, 15981, 15981, 15981, -1, + 15982, 15982, 15982, -1, 15983, 15983, 15983, -1, + 15984, 15984, 15984, -1, 15985, 15985, 15985, -1, + 15986, 15986, 15986, -1, 15987, 15987, 15987, -1, + 15988, 15988, 15988, -1, 15989, 15989, 15989, -1, + 15990, 15990, 15990, -1, 15991, 15991, 15991, -1, + 15992, 15992, 15992, -1, 15993, 15993, 15993, -1, + 15994, 15994, 15994, -1, 15995, 15995, 15995, -1, + 15996, 15996, 15996, -1, 15997, 15997, 15997, -1, + 15998, 15998, 15998, -1, 15999, 15999, 15999, -1, + 16000, 16000, 16000, -1, 16001, 16001, 16001, -1, + 16002, 16002, 16002, -1, 16003, 16003, 16003, -1, + 16004, 16004, 16004, -1, 16005, 16005, 16005, -1, + 16006, 16006, 16006, -1, 16007, 16007, 16007, -1, + 16008, 16008, 16008, -1, 16009, 16009, 16009, -1, + 16010, 16010, 16010, -1, 16011, 16011, 16011, -1, + 16012, 16012, 16012, -1, 16013, 16013, 16013, -1, + 16014, 16014, 16014, -1, 16015, 16015, 16015, -1, + 16016, 16016, 16016, -1, 16017, 16017, 16017, -1, + 16018, 16018, 16018, -1, 16019, 16019, 16019, -1, + 16020, 16020, 16020, -1, 16021, 16021, 16021, -1, + 16022, 16022, 16022, -1, 16023, 16023, 16023, -1, + 16024, 16024, 16024, -1, 16025, 16025, 16025, -1, + 16026, 16026, 16026, -1, 16027, 16027, 16027, -1, + 16028, 16028, 16028, -1, 16029, 16029, 16029, -1, + 16030, 16030, 16030, -1, 16031, 16031, 16031, -1, + 16032, 16032, 16032, -1, 16033, 16033, 16033, -1, + 16034, 16034, 16034, -1, 16035, 16035, 16035, -1, + 16036, 16036, 16036, -1, 16037, 16037, 16037, -1, + 16038, 16038, 16038, -1, 16039, 16039, 16039, -1, + 16040, 16040, 16040, -1, 16041, 16041, 16041, -1, + 16042, 16042, 16042, -1, 16043, 16043, 16043, -1, + 16044, 16044, 16044, -1, 16045, 16045, 16045, -1, + 16046, 16046, 16046, -1, 16047, 16047, 16047, -1, + 16048, 16048, 16048, -1, 16049, 16049, 16049, -1, + 16050, 16050, 16050, -1, 16051, 16051, 16051, -1, + 16052, 16052, 16052, -1, 16053, 16053, 16053, -1, + 16054, 16054, 16054, -1, 16055, 16055, 16055, -1, + 16056, 16056, 16056, -1, 16057, 16057, 16057, -1, + 16058, 16058, 16058, -1, 16059, 16059, 16059, -1, + 16060, 16060, 16060, -1, 16061, 16061, 16061, -1, + 16062, 16062, 16062, -1, 16063, 16063, 16063, -1, + 16064, 16064, 16064, -1, 16065, 16065, 16065, -1, + 16066, 16066, 16066, -1, 16067, 16067, 16067, -1, + 16068, 16068, 16068, -1, 16069, 16069, 16069, -1, + 16070, 16070, 16070, -1, 16071, 16071, 16071, -1, + 16072, 16072, 16072, -1, 16073, 16073, 16073, -1, + 16074, 16074, 16074, -1, 16075, 16075, 16075, -1, + 16076, 16076, 16076, -1, 16077, 16077, 16077, -1, + 16078, 16078, 16078, -1, 16079, 16079, 16079, -1, + 16080, 16080, 16080, -1, 16081, 16081, 16081, -1, + 16082, 16082, 16082, -1, 16083, 16083, 16083, -1, + 16084, 16084, 16084, -1, 16085, 16085, 16085, -1, + 16086, 16086, 16086, -1, 16087, 16087, 16087, -1, + 16088, 16088, 16088, -1, 16089, 16089, 16089, -1, + 16090, 16090, 16090, -1, 16091, 16091, 16091, -1, + 16092, 16092, 16092, -1, 16093, 16093, 16093, -1, + 16094, 16094, 16094, -1, 16095, 16095, 16095, -1, + 16096, 16096, 16096, -1, 16097, 16097, 16097, -1, + 16098, 16098, 16098, -1, 16099, 16099, 16099, -1, + 16100, 16100, 16100, -1, 16101, 16101, 16101, -1, + 16102, 16102, 16102, -1, 16103, 16103, 16103, -1, + 16104, 16104, 16104, -1, 16105, 16105, 16105, -1, + 16106, 16106, 16106, -1, 16107, 16107, 16107, -1, + 16108, 16108, 16108, -1, 16109, 16109, 16109, -1, + 16110, 16110, 16110, -1, 16111, 16111, 16111, -1, + 16112, 16112, 16112, -1, 16113, 16113, 16113, -1, + 16114, 16114, 16114, -1, 16115, 16115, 16115, -1, + 16116, 16116, 16116, -1, 16117, 16117, 16117, -1, + 16118, 16118, 16118, -1, 16119, 16119, 16119, -1, + 16120, 16120, 16120, -1, 16121, 16121, 16121, -1, + 16122, 16122, 16122, -1, 16123, 16123, 16123, -1, + 16124, 16124, 16124, -1, 16125, 16125, 16125, -1, + 16126, 16126, 16126, -1, 16127, 16127, 16127, -1, + 16128, 16128, 16128, -1, 16129, 16129, 16129, -1, + 16130, 16130, 16130, -1, 16131, 16131, 16131, -1, + 16132, 16132, 16132, -1, 16133, 16133, 16133, -1, + 16134, 16134, 16134, -1, 16135, 16135, 16135, -1, + 16136, 16136, 16136, -1, 16137, 16137, 16137, -1, + 16138, 16138, 16138, -1, 16139, 16139, 16139, -1, + 16140, 16140, 16140, -1, 16141, 16141, 16141, -1, + 16142, 16142, 16142, -1, 16143, 16143, 16143, -1, + 16144, 16144, 16144, -1, 16145, 16145, 16145, -1, + 16146, 16146, 16146, -1, 16147, 16147, 16147, -1, + 16148, 16148, 16148, -1, 16149, 16149, 16149, -1, + 16150, 16150, 16150, -1, 16151, 16151, 16151, -1, + 16152, 16152, 16152, -1, 16153, 16153, 16153, -1, + 16154, 16154, 16154, -1, 16155, 16155, 16155, -1, + 16156, 16156, 16156, -1, 16157, 16157, 16157, -1, + 16158, 16158, 16158, -1, 16159, 16159, 16159, -1, + 16160, 16160, 16160, -1, 16161, 16161, 16161, -1, + 16162, 16162, 16162, -1, 16163, 16163, 16163, -1, + 16164, 16164, 16164, -1, 16165, 16165, 16165, -1, + 16166, 16166, 16166, -1, 16167, 16167, 16167, -1, + 16168, 16168, 16168, -1, 16169, 16169, 16169, -1, + 16170, 16170, 16170, -1, 16171, 16171, 16171, -1, + 16172, 16172, 16172, -1, 16173, 16173, 16173, -1, + 16174, 16174, 16174, -1, 16175, 16175, 16175, -1, + 16176, 16176, 16176, -1, 16177, 16177, 16177, -1, + 16178, 16178, 16178, -1, 16179, 16179, 16179, -1, + 16180, 16180, 16180, -1, 16181, 16181, 16181, -1, + 16182, 16182, 16182, -1, 16183, 16183, 16183, -1, + 16184, 16184, 16184, -1, 16185, 16185, 16185, -1, + 16186, 16186, 16186, -1, 16187, 16187, 16187, -1, + 16188, 16188, 16188, -1, 16189, 16189, 16189, -1, + 16190, 16190, 16190, -1, 16191, 16191, 16191, -1, + 16192, 16192, 16192, -1, 16193, 16193, 16193, -1, + 16194, 16194, 16194, -1, 16195, 16195, 16195, -1, + 16196, 16196, 16196, -1, 16197, 16197, 16197, -1, + 16198, 16198, 16198, -1, 16199, 16199, 16199, -1, + 16200, 16200, 16200, -1, 16201, 16201, 16201, -1, + 16202, 16202, 16202, -1, 16203, 16203, 16203, -1, + 16204, 16204, 16204, -1, 16205, 16205, 16205, -1, + 16206, 16206, 16206, -1, 16207, 16207, 16207, -1, + 16208, 16208, 16208, -1, 16209, 16209, 16209, -1, + 16210, 16210, 16210, -1, 16211, 16211, 16211, -1, + 16212, 16212, 16212, -1, 16213, 16213, 16213, -1, + 16214, 16214, 16214, -1, 16215, 16215, 16215, -1, + 16216, 16216, 16216, -1, 16217, 16217, 16217, -1, + 16218, 16218, 16218, -1, 16219, 16219, 16219, -1, + 16220, 16220, 16220, -1, 16221, 16221, 16221, -1, + 16222, 16222, 16222, -1, 16223, 16223, 16223, -1, + 16224, 16224, 16224, -1, 16225, 16225, 16225, -1, + 16226, 16226, 16226, -1, 16227, 16227, 16227, -1, + 16228, 16228, 16228, -1, 16229, 16229, 16229, -1, + 16230, 16230, 16230, -1, 16231, 16231, 16231, -1, + 16232, 16232, 16232, -1, 16233, 16233, 16233, -1, + 16234, 16234, 16234, -1, 16235, 16235, 16235, -1, + 16236, 16236, 16236, -1, 16237, 16237, 16237, -1, + 16238, 16238, 16238, -1, 16239, 16239, 16239, -1, + 16240, 16240, 16240, -1, 16241, 16241, 16241, -1, + 16242, 16242, 16242, -1, 16243, 16243, 16243, -1, + 16244, 16244, 16244, -1, 16245, 16245, 16245, -1, + 16246, 16246, 16246, -1, 16247, 16247, 16247, -1, + 16248, 16248, 16248, -1, 16249, 16249, 16249, -1, + 16250, 16250, 16250, -1, 16251, 16251, 16251, -1, + 16252, 16252, 16252, -1, 16253, 16253, 16253, -1, + 16254, 16254, 16254, -1, 16255, 16255, 16255, -1, + 16256, 16256, 16256, -1, 16257, 16257, 16257, -1, + 16258, 16258, 16258, -1, 16259, 16259, 16259, -1, + 16260, 16260, 16260, -1, 16261, 16261, 16261, -1, + 16262, 16262, 16262, -1, 16263, 16263, 16263, -1, + 16264, 16264, 16264, -1, 16265, 16265, 16265, -1, + 16266, 16266, 16266, -1, 16267, 16267, 16267, -1, + 16268, 16268, 16268, -1, 16269, 16269, 16269, -1, + 16270, 16270, 16270, -1, 16271, 16271, 16271, -1, + 16272, 16272, 16272, -1, 16273, 16273, 16273, -1, + 16274, 16274, 16274, -1, 16275, 16275, 16275, -1, + 16276, 16276, 16276, -1, 16277, 16277, 16277, -1, + 16278, 16278, 16278, -1, 16279, 16279, 16279, -1, + 16280, 16280, 16280, -1, 16281, 16281, 16281, -1, + 16282, 16282, 16282, -1, 16283, 16283, 16283, -1, + 16284, 16284, 16284, -1, 16285, 16285, 16285, -1, + 16286, 16286, 16286, -1, 16287, 16287, 16287, -1, + 16288, 16288, 16288, -1, 16289, 16289, 16289, -1, + 16290, 16290, 16290, -1, 16291, 16291, 16291, -1, + 16292, 16292, 16292, -1, 16293, 16293, 16293, -1, + 16294, 16294, 16294, -1, 16295, 16295, 16295, -1, + 16296, 16296, 16296, -1, 16297, 16297, 16297, -1, + 16298, 16298, 16298, -1, 16299, 16299, 16299, -1, + 16300, 16300, 16300, -1, 16301, 16301, 16301, -1, + 16302, 16302, 16302, -1, 16303, 16303, 16303, -1, + 16304, 16304, 16304, -1, 16305, 16305, 16305, -1, + 16306, 16306, 16306, -1, 16307, 16307, 16307, -1, + 16308, 16308, 16308, -1, 16309, 16309, 16309, -1, + 16310, 16310, 16310, -1, 16311, 16311, 16311, -1, + 16312, 16312, 16312, -1, 16313, 16313, 16313, -1, + 16314, 16314, 16314, -1, 16315, 16315, 16315, -1, + 16316, 16316, 16316, -1, 16317, 16317, 16317, -1, + 16318, 16318, 16318, -1, 16319, 16319, 16319, -1, + 16320, 16320, 16320, -1, 16321, 16321, 16321, -1, + 16322, 16322, 16322, -1, 16323, 16323, 16323, -1, + 16324, 16324, 16324, -1, 16325, 16325, 16325, -1, + 16326, 16326, 16326, -1, 16327, 16327, 16327, -1, + 16328, 16328, 16328, -1, 16329, 16329, 16329, -1, + 16330, 16330, 16330, -1, 16331, 16331, 16331, -1, + 16332, 16332, 16332, -1, 16333, 16333, 16333, -1, + 16334, 16334, 16334, -1, 16335, 16335, 16335, -1, + 16336, 16336, 16336, -1, 16337, 16337, 16337, -1, + 16338, 16338, 16338, -1, 16339, 16339, 16339, -1, + 16340, 16340, 16340, -1, 16341, 16341, 16341, -1, + 16342, 16342, 16342, -1, 16343, 16343, 16343, -1, + 16344, 16344, 16344, -1, 16345, 16345, 16345, -1, + 16346, 16346, 16346, -1, 16347, 16347, 16347, -1, + 16348, 16348, 16348, -1, 16349, 16349, 16349, -1, + 16350, 16350, 16350, -1, 16351, 16351, 16351, -1, + 16352, 16352, 16352, -1, 16353, 16353, 16353, -1, + 16354, 16354, 16354, -1, 16355, 16355, 16355, -1, + 16356, 16356, 16356, -1, 16357, 16357, 16357, -1, + 16358, 16358, 16358, -1, 16359, 16359, 16359, -1, + 16360, 16360, 16360, -1, 16361, 16361, 16361, -1, + 16362, 16362, 16362, -1, 16363, 16363, 16363, -1, + 16364, 16364, 16364, -1, 16365, 16365, 16365, -1, + 16366, 16366, 16366, -1, 16367, 16367, 16367, -1, + 16368, 16368, 16368, -1, 16369, 16369, 16369, -1, + 16370, 16370, 16370, -1, 16371, 16371, 16371, -1, + 16372, 16372, 16372, -1, 16373, 16373, 16373, -1, + 16374, 16374, 16374, -1, 16375, 16375, 16375, -1, + 16376, 16376, 16376, -1, 16377, 16377, 16377, -1, + 16378, 16378, 16378, -1, 16379, 16379, 16379, -1, + 16380, 16380, 16380, -1, 16381, 16381, 16381, -1, + 16382, 16382, 16382, -1, 16383, 16383, 16383, -1, + 16384, 16384, 16384, -1, 16385, 16385, 16385, -1, + 16386, 16386, 16386, -1, 16387, 16387, 16387, -1, + 16388, 16388, 16388, -1, 16389, 16389, 16389, -1, + 16390, 16390, 16390, -1, 16391, 16391, 16391, -1, + 16392, 16392, 16392, -1, 16393, 16393, 16393, -1, + 16394, 16394, 16394, -1, 16395, 16395, 16395, -1, + 16396, 16396, 16396, -1, 16397, 16397, 16397, -1, + 16398, 16398, 16398, -1, 16399, 16399, 16399, -1, + 16400, 16400, 16400, -1, 16401, 16401, 16401, -1, + 16402, 16402, 16402, -1, 16403, 16403, 16403, -1, + 16404, 16404, 16404, -1, 16405, 16405, 16405, -1, + 16406, 16406, 16406, -1, 16407, 16407, 16407, -1, + 16408, 16408, 16408, -1, 16409, 16409, 16409, -1, + 16410, 16410, 16410, -1, 16411, 16411, 16411, -1, + 16412, 16412, 16412, -1, 16413, 16413, 16413, -1, + 16414, 16414, 16414, -1, 16415, 16415, 16415, -1, + 16416, 16416, 16416, -1, 16417, 16417, 16417, -1, + 16418, 16418, 16418, -1, 16419, 16419, 16419, -1, + 16420, 16420, 16420, -1, 16421, 16421, 16421, -1, + 16422, 16422, 16422, -1, 16423, 16423, 16423, -1, + 16424, 16424, 16424, -1, 16425, 16425, 16425, -1, + 16426, 16426, 16426, -1, 16427, 16427, 16427, -1, + 16428, 16428, 16428, -1, 16429, 16429, 16429, -1, + 16430, 16430, 16430, -1, 16431, 16431, 16431, -1, + 16432, 16432, 16432, -1, 16433, 16433, 16433, -1, + 16434, 16434, 16434, -1, 16435, 16435, 16435, -1, + 16436, 16436, 16436, -1, 16437, 16437, 16437, -1, + 16438, 16438, 16438, -1, 16439, 16439, 16439, -1, + 16440, 16440, 16440, -1, 16441, 16441, 16441, -1, + 16442, 16442, 16442, -1, 16443, 16443, 16443, -1, + 16444, 16444, 16444, -1, 16445, 16445, 16445, -1, + 16446, 16446, 16446, -1, 16447, 16447, 16447, -1, + 16448, 16448, 16448, -1, 16449, 16449, 16449, -1, + 16450, 16450, 16450, -1, 16451, 16451, 16451, -1, + 16452, 16452, 16452, -1, 16453, 16453, 16453, -1, + 16454, 16454, 16454, -1, 16455, 16455, 16455, -1, + 16456, 16456, 16456, -1, 16457, 16457, 16457, -1, + 16458, 16458, 16458, -1, 16459, 16459, 16459, -1, + 16460, 16460, 16460, -1, 16461, 16461, 16461, -1, + 16462, 16462, 16462, -1, 16463, 16463, 16463, -1, + 16464, 16464, 16464, -1, 16465, 16465, 16465, -1, + 16466, 16466, 16466, -1, 16467, 16467, 16467, -1, + 16468, 16468, 16468, -1, 16469, 16469, 16469, -1, + 16470, 16470, 16470, -1, 16471, 16471, 16471, -1, + 16472, 16472, 16472, -1, 16473, 16473, 16473, -1, + 16474, 16474, 16474, -1, 16475, 16475, 16475, -1, + 16476, 16476, 16476, -1, 16477, 16477, 16477, -1, + 16478, 16478, 16478, -1, 16479, 16479, 16479, -1, + 16480, 16480, 16480, -1, 16481, 16481, 16481, -1, + 16482, 16482, 16482, -1, 16483, 16483, 16483, -1, + 16484, 16484, 16484, -1, 16485, 16485, 16485, -1, + 16486, 16486, 16486, -1, 16487, 16487, 16487, -1, + 16488, 16488, 16488, -1, 16489, 16489, 16489, -1, + 16490, 16490, 16490, -1, 16491, 16491, 16491, -1, + 16492, 16492, 16492, -1, 16493, 16493, 16493, -1, + 16494, 16494, 16494, -1, 16495, 16495, 16495, -1, + 16496, 16496, 16496, -1, 16497, 16497, 16497, -1, + 16498, 16498, 16498, -1, 16499, 16499, 16499, -1, + 16500, 16500, 16500, -1, 16501, 16501, 16501, -1, + 16502, 16502, 16502, -1, 16503, 16503, 16503, -1, + 16504, 16504, 16504, -1, 16505, 16505, 16505, -1, + 16506, 16506, 16506, -1, 16507, 16507, 16507, -1, + 16508, 16508, 16508, -1, 16509, 16509, 16509, -1, + 16510, 16510, 16510, -1, 16511, 16511, 16511, -1, + 16512, 16512, 16512, -1, 16513, 16513, 16513, -1, + 16514, 16514, 16514, -1, 16515, 16515, 16515, -1, + 16516, 16516, 16516, -1, 16517, 16517, 16517, -1, + 16518, 16518, 16518, -1, 16519, 16519, 16519, -1, + 16520, 16520, 16520, -1, 16521, 16521, 16521, -1, + 16522, 16522, 16522, -1, 16523, 16523, 16523, -1, + 16524, 16524, 16524, -1, 16525, 16525, 16525, -1, + 16526, 16526, 16526, -1, 16527, 16527, 16527, -1, + 16528, 16528, 16528, -1, 16529, 16529, 16529, -1, + 16530, 16530, 16530, -1, 16531, 16531, 16531, -1, + 16532, 16532, 16532, -1, 16533, 16533, 16533, -1, + 16534, 16534, 16534, -1, 16535, 16535, 16535, -1, + 16536, 16536, 16536, -1, 16537, 16537, 16537, -1, + 16538, 16538, 16538, -1, 16539, 16539, 16539, -1, + 16540, 16540, 16540, -1, 16541, 16541, 16541, -1, + 16542, 16542, 16542, -1, 16543, 16543, 16543, -1, + 16544, 16544, 16544, -1, 16545, 16545, 16545, -1, + 16546, 16546, 16546, -1, 16547, 16547, 16547, -1, + 16548, 16548, 16548, -1, 16549, 16549, 16549, -1, + 16550, 16550, 16550, -1, 16551, 16551, 16551, -1, + 16552, 16552, 16552, -1, 16553, 16553, 16553, -1, + 16554, 16554, 16554, -1, 16555, 16555, 16555, -1, + 16556, 16556, 16556, -1, 16557, 16557, 16557, -1, + 16558, 16558, 16558, -1, 16559, 16559, 16559, -1, + 16560, 16560, 16560, -1, 16561, 16561, 16561, -1, + 16562, 16562, 16562, -1, 16563, 16563, 16563, -1, + 16564, 16564, 16564, -1, 16565, 16565, 16565, -1, + 16566, 16566, 16566, -1, 16567, 16567, 16567, -1, + 16568, 16568, 16568, -1, 16569, 16569, 16569, -1, + 16570, 16570, 16570, -1, 16571, 16571, 16571, -1, + 16572, 16572, 16572, -1, 16573, 16573, 16573, -1, + 16574, 16574, 16574, -1, 16575, 16575, 16575, -1, + 16576, 16576, 16576, -1, 16577, 16577, 16577, -1, + 16578, 16578, 16578, -1, 16579, 16579, 16579, -1, + 16580, 16580, 16580, -1, 16581, 16581, 16581, -1, + 16582, 16582, 16582, -1, 16583, 16583, 16583, -1, + 16584, 16584, 16584, -1, 16585, 16585, 16585, -1, + 16586, 16586, 16586, -1, 16587, 16587, 16587, -1, + 16588, 16588, 16588, -1, 16589, 16589, 16589, -1, + 16590, 16590, 16590, -1, 16591, 16591, 16591, -1, + 16592, 16592, 16592, -1, 16593, 16593, 16593, -1, + 16594, 16594, 16594, -1, 16595, 16595, 16595, -1, + 16596, 16596, 16596, -1, 16597, 16597, 16597, -1, + 16598, 16598, 16598, -1, 16599, 16599, 16599, -1, + 16600, 16600, 16600, -1, 16601, 16601, 16601, -1, + 16602, 16602, 16602, -1, 16603, 16603, 16603, -1, + 16604, 16604, 16604, -1, 16605, 16605, 16605, -1, + 16606, 16606, 16606, -1, 16607, 16607, 16607, -1, + 16608, 16608, 16608, -1, 16609, 16609, 16609, -1, + 16610, 16610, 16610, -1, 16611, 16611, 16611, -1, + 16612, 16612, 16612, -1, 16613, 16613, 16613, -1, + 16614, 16614, 16614, -1, 16615, 16615, 16615, -1, + 16616, 16616, 16616, -1, 16617, 16617, 16617, -1, + 16618, 16618, 16618, -1, 16619, 16619, 16619, -1, + 16620, 16620, 16620, -1, 16621, 16621, 16621, -1, + 16622, 16622, 16622, -1, 16623, 16623, 16623, -1, + 16624, 16624, 16624, -1, 16625, 16625, 16625, -1, + 16626, 16626, 16626, -1, 16627, 16627, 16627, -1, + 16628, 16628, 16628, -1, 16629, 16629, 16629, -1, + 16630, 16630, 16630, -1, 16631, 16631, 16631, -1, + 16632, 16632, 16632, -1, 16633, 16633, 16633, -1, + 16634, 16634, 16634, -1, 16635, 16635, 16635, -1, + 16636, 16636, 16636, -1, 16637, 16637, 16637, -1, + 16638, 16638, 16638, -1, 16639, 16639, 16639, -1, + 16640, 16640, 16640, -1, 16641, 16641, 16641, -1, + 16642, 16642, 16642, -1, 16643, 16643, 16643, -1, + 16644, 16644, 16644, -1, 16645, 16645, 16645, -1, + 16646, 16646, 16646, -1, 16647, 16647, 16647, -1, + 16648, 16648, 16648, -1, 16649, 16649, 16649, -1, + 16650, 16650, 16650, -1, 16651, 16651, 16651, -1, + 16652, 16652, 16652, -1, 16653, 16653, 16653, -1, + 16654, 16654, 16654, -1, 16655, 16655, 16655, -1, + 16656, 16656, 16656, -1, 16657, 16657, 16657, -1, + 16658, 16658, 16658, -1, 16659, 16659, 16659, -1, + 16660, 16660, 16660, -1, 16661, 16661, 16661, -1, + 16662, 16662, 16662, -1, 16663, 16663, 16663, -1, + 16664, 16664, 16664, -1, 16665, 16665, 16665, -1, + 16666, 16666, 16666, -1, 16667, 16667, 16667, -1, + 16668, 16668, 16668, -1, 16669, 16669, 16669, -1, + 16670, 16670, 16670, -1, 16671, 16671, 16671, -1, + 16672, 16672, 16672, -1, 16673, 16673, 16673, -1, + 16674, 16674, 16674, -1, 16675, 16675, 16675, -1, + 16676, 16676, 16676, -1, 16677, 16677, 16677, -1, + 16678, 16678, 16678, -1, 16679, 16679, 16679, -1, + 16680, 16680, 16680, -1, 16681, 16681, 16681, -1, + 16682, 16682, 16682, -1, 16683, 16683, 16683, -1, + 16684, 16684, 16684, -1, 16685, 16685, 16685, -1, + 16686, 16686, 16686, -1, 16687, 16687, 16687, -1, + 16688, 16688, 16688, -1, 16689, 16689, 16689, -1, + 16690, 16690, 16690, -1, 16691, 16691, 16691, -1, + 16692, 16692, 16692, -1, 16693, 16693, 16693, -1, + 16694, 16694, 16694, -1, 16695, 16695, 16695, -1, + 16696, 16696, 16696, -1, 16697, 16697, 16697, -1, + 16698, 16698, 16698, -1, 16699, 16699, 16699, -1, + 16700, 16700, 16700, -1, 16701, 16701, 16701, -1, + 16702, 16702, 16702, -1, 16703, 16703, 16703, -1, + 16704, 16704, 16704, -1, 16705, 16705, 16705, -1, + 16706, 16706, 16706, -1, 16707, 16707, 16707, -1, + 16708, 16708, 16708, -1, 16709, 16709, 16709, -1, + 16710, 16710, 16710, -1, 16711, 16711, 16711, -1, + 16712, 16712, 16712, -1, 16713, 16713, 16713, -1, + 16714, 16714, 16714, -1, 16715, 16715, 16715, -1, + 16716, 16716, 16716, -1, 16717, 16717, 16717, -1, + 16718, 16718, 16718, -1, 16719, 16719, 16719, -1, + 16720, 16720, 16720, -1, 16721, 16721, 16721, -1, + 16722, 16722, 16722, -1, 16723, 16723, 16723, -1, + 16724, 16724, 16724, -1, 16725, 16725, 16725, -1, + 16726, 16726, 16726, -1, 16727, 16727, 16727, -1, + 16728, 16728, 16728, -1, 16729, 16729, 16729, -1, + 16730, 16730, 16730, -1, 16731, 16731, 16731, -1, + 16732, 16732, 16732, -1, 16733, 16733, 16733, -1, + 16734, 16734, 16734, -1, 16735, 16735, 16735, -1, + 16736, 16736, 16736, -1, 16737, 16737, 16737, -1, + 16738, 16738, 16738, -1, 16739, 16739, 16739, -1, + 16740, 16740, 16740, -1, 16741, 16741, 16741, -1, + 16742, 16742, 16742, -1, 16743, 16743, 16743, -1, + 16744, 16744, 16744, -1, 16745, 16745, 16745, -1, + 16746, 16746, 16746, -1, 16747, 16747, 16747, -1, + 16748, 16748, 16748, -1, 16749, 16749, 16749, -1, + 16750, 16750, 16750, -1, 16751, 16751, 16751, -1, + 16752, 16752, 16752, -1, 16753, 16753, 16753, -1, + 16754, 16754, 16754, -1, 16755, 16755, 16755, -1, + 16756, 16756, 16756, -1, 16757, 16757, 16757, -1, + 16758, 16758, 16758, -1, 16759, 16759, 16759, -1, + 16760, 16760, 16760, -1, 16761, 16761, 16761, -1, + 16762, 16762, 16762, -1, 16763, 16763, 16763, -1, + 16764, 16764, 16764, -1, 16765, 16765, 16765, -1, + 16766, 16766, 16766, -1, 16767, 16767, 16767, -1, + 16768, 16768, 16768, -1, 16769, 16769, 16769, -1, + 16770, 16770, 16770, -1, 16771, 16771, 16771, -1, + 16772, 16772, 16772, -1, 16773, 16773, 16773, -1, + 16774, 16774, 16774, -1, 16775, 16775, 16775, -1, + 16776, 16776, 16776, -1, 16777, 16777, 16777, -1, + 16778, 16778, 16778, -1, 16779, 16779, 16779, -1, + 16780, 16780, 16780, -1, 16781, 16781, 16781, -1, + 16782, 16782, 16782, -1, 16783, 16783, 16783, -1, + 16784, 16784, 16784, -1, 16785, 16785, 16785, -1, + 16786, 16786, 16786, -1, 16787, 16787, 16787, -1, + 16788, 16788, 16788, -1, 16789, 16789, 16789, -1, + 16790, 16790, 16790, -1, 16791, 16791, 16791, -1, + 16792, 16792, 16792, -1, 16793, 16793, 16793, -1, + 16794, 16794, 16794, -1, 16795, 16795, 16795, -1, + 16796, 16796, 16796, -1, 16797, 16797, 16797, -1, + 16798, 16798, 16798, -1, 16799, 16799, 16799, -1, + 16800, 16800, 16800, -1, 16801, 16801, 16801, -1, + 16802, 16802, 16802, -1, 16803, 16803, 16803, -1, + 16804, 16804, 16804, -1, 16805, 16805, 16805, -1, + 16806, 16806, 16806, -1, 16807, 16807, 16807, -1, + 16808, 16808, 16808, -1, 16809, 16809, 16809, -1, + 16810, 16810, 16810, -1, 16811, 16811, 16811, -1, + 16812, 16812, 16812, -1, 16813, 16813, 16813, -1, + 16814, 16814, 16814, -1, 16815, 16815, 16815, -1, + 16816, 16816, 16816, -1, 16817, 16817, 16817, -1, + 16818, 16818, 16818, -1, 16819, 16819, 16819, -1, + 16820, 16820, 16820, -1, 16821, 16821, 16821, -1, + 16822, 16822, 16822, -1, 16823, 16823, 16823, -1, + 16824, 16824, 16824, -1, 16825, 16825, 16825, -1, + 16826, 16826, 16826, -1, 16827, 16827, 16827, -1, + 16828, 16828, 16828, -1, 16829, 16829, 16829, -1, + 16830, 16830, 16830, -1, 16831, 16831, 16831, -1, + 16832, 16832, 16832, -1, 16833, 16833, 16833, -1, + 16834, 16834, 16834, -1, 16835, 16835, 16835, -1, + 16836, 16836, 16836, -1, 16837, 16837, 16837, -1, + 16838, 16838, 16838, -1, 16839, 16839, 16839, -1, + 16840, 16840, 16840, -1, 16841, 16841, 16841, -1, + 16842, 16842, 16842, -1, 16843, 16843, 16843, -1, + 16844, 16844, 16844, -1, 16845, 16845, 16845, -1, + 16846, 16846, 16846, -1, 16847, 16847, 16847, -1, + 16848, 16848, 16848, -1, 16849, 16849, 16849, -1, + 16850, 16850, 16850, -1, 16851, 16851, 16851, -1, + 16852, 16852, 16852, -1, 16853, 16853, 16853, -1, + 16854, 16854, 16854, -1, 16855, 16855, 16855, -1, + 16856, 16856, 16856, -1, 16857, 16857, 16857, -1, + 16858, 16858, 16858, -1, 16859, 16859, 16859, -1, + 16860, 16860, 16860, -1, 16861, 16861, 16861, -1, + 16862, 16862, 16862, -1, 16863, 16863, 16863, -1, + 16864, 16864, 16864, -1, 16865, 16865, 16865, -1, + 16866, 16866, 16866, -1, 16867, 16867, 16867, -1, + 16868, 16868, 16868, -1, 16869, 16869, 16869, -1, + 16870, 16870, 16870, -1, 16871, 16871, 16871, -1, + 16872, 16872, 16872, -1, 16873, 16873, 16873, -1, + 16874, 16874, 16874, -1, 16875, 16875, 16875, -1, + 16876, 16876, 16876, -1, 16877, 16877, 16877, -1, + 16878, 16878, 16878, -1, 16879, 16879, 16879, -1, + 16880, 16880, 16880, -1, 16881, 16881, 16881, -1, + 16882, 16882, 16882, -1, 16883, 16883, 16883, -1, + 16884, 16884, 16884, -1, 16885, 16885, 16885, -1, + 16886, 16886, 16886, -1, 16887, 16887, 16887, -1, + 16888, 16888, 16888, -1, 16889, 16889, 16889, -1, + 16890, 16890, 16890, -1, 16891, 16891, 16891, -1, + 16892, 16892, 16892, -1, 16893, 16893, 16893, -1, + 16894, 16894, 16894, -1, 16895, 16895, 16895, -1, + 16896, 16896, 16896, -1, 16897, 16897, 16897, -1, + 16898, 16898, 16898, -1, 16899, 16899, 16899, -1, + 16900, 16900, 16900, -1, 16901, 16901, 16901, -1, + 16902, 16902, 16902, -1, 16903, 16903, 16903, -1, + 16904, 16904, 16904, -1, 16905, 16905, 16905, -1, + 16906, 16906, 16906, -1, 16907, 16907, 16907, -1, + 16908, 16908, 16908, -1, 16909, 16909, 16909, -1, + 16910, 16910, 16910, -1, 16911, 16911, 16911, -1, + 16912, 16912, 16912, -1, 16913, 16913, 16913, -1, + 16914, 16914, 16914, -1, 16915, 16915, 16915, -1, + 16916, 16916, 16916, -1, 16917, 16917, 16917, -1, + 16918, 16918, 16918, -1, 16919, 16919, 16919, -1, + 16920, 16920, 16920, -1, 16921, 16921, 16921, -1, + 16922, 16922, 16922, -1, 16923, 16923, 16923, -1, + 16924, 16924, 16924, -1, 16925, 16925, 16925, -1, + 16926, 16926, 16926, -1, 16927, 16927, 16927, -1, + 16928, 16928, 16928, -1, 16929, 16929, 16929, -1, + 16930, 16930, 16930, -1, 16931, 16931, 16931, -1, + 16932, 16932, 16932, -1, 16933, 16933, 16933, -1, + 16934, 16934, 16934, -1, 16935, 16935, 16935, -1, + 16936, 16936, 16936, -1, 16937, 16937, 16937, -1, + 16938, 16938, 16938, -1, 16939, 16939, 16939, -1, + 16940, 16940, 16940, -1, 16941, 16941, 16941, -1, + 16942, 16942, 16942, -1, 16943, 16943, 16943, -1, + 16944, 16944, 16944, -1, 16945, 16945, 16945, -1, + 16946, 16946, 16946, -1, 16947, 16947, 16947, -1, + 16948, 16948, 16948, -1, 16949, 16949, 16949, -1, + 16950, 16950, 16950, -1, 16951, 16951, 16951, -1, + 16952, 16952, 16952, -1, 16953, 16953, 16953, -1, + 16954, 16954, 16954, -1, 16955, 16955, 16955, -1, + 16956, 16956, 16956, -1, 16957, 16957, 16957, -1, + 16958, 16958, 16958, -1, 16959, 16959, 16959, -1, + 16960, 16960, 16960, -1, 16961, 16961, 16961, -1, + 16962, 16962, 16962, -1, 16963, 16963, 16963, -1, + 16964, 16964, 16964, -1, 16965, 16965, 16965, -1, + 16966, 16966, 16966, -1, 16967, 16967, 16967, -1, + 16968, 16968, 16968, -1, 16969, 16969, 16969, -1, + 16970, 16970, 16970, -1, 16971, 16971, 16971, -1, + 16972, 16972, 16972, -1, 16973, 16973, 16973, -1, + 16974, 16974, 16974, -1, 16975, 16975, 16975, -1, + 16976, 16976, 16976, -1, 16977, 16977, 16977, -1, + 16978, 16978, 16978, -1, 16979, 16979, 16979, -1, + 16980, 16980, 16980, -1, 16981, 16981, 16981, -1, + 16982, 16982, 16982, -1, 16983, 16983, 16983, -1, + 16984, 16984, 16984, -1, 16985, 16985, 16985, -1, + 16986, 16986, 16986, -1, 16987, 16987, 16987, -1, + 16988, 16988, 16988, -1, 16989, 16989, 16989, -1, + 16990, 16990, 16990, -1, 16991, 16991, 16991, -1, + 16992, 16992, 16992, -1, 16993, 16993, 16993, -1, + 16994, 16994, 16994, -1, 16995, 16995, 16995, -1, + 16996, 16996, 16996, -1, 16997, 16997, 16997, -1, + 16998, 16998, 16998, -1, 16999, 16999, 16999, -1, + 17000, 17000, 17000, -1, 17001, 17001, 17001, -1, + 17002, 17002, 17002, -1, 17003, 17003, 17003, -1, + 17004, 17004, 17004, -1, 17005, 17005, 17005, -1, + 17006, 17006, 17006, -1, 17007, 17007, 17007, -1, + 17008, 17008, 17008, -1, 17009, 17009, 17009, -1, + 17010, 17010, 17010, -1, 17011, 17011, 17011, -1, + 17012, 17012, 17012, -1, 17013, 17013, 17013, -1, + 17014, 17014, 17014, -1, 17015, 17015, 17015, -1, + 17016, 17016, 17016, -1, 17017, 17017, 17017, -1, + 17018, 17018, 17018, -1, 17019, 17019, 17019, -1, + 17020, 17020, 17020, -1, 17021, 17021, 17021, -1, + 17022, 17022, 17022, -1, 17023, 17023, 17023, -1, + 17024, 17024, 17024, -1, 17025, 17025, 17025, -1, + 17026, 17026, 17026, -1, 17027, 17027, 17027, -1, + 17028, 17028, 17028, -1, 17029, 17029, 17029, -1, + 17030, 17030, 17030, -1, 17031, 17031, 17031, -1, + 17032, 17032, 17032, -1, 17033, 17033, 17033, -1, + 17034, 17034, 17034, -1, 17035, 17035, 17035, -1, + 17036, 17036, 17036, -1, 17037, 17037, 17037, -1, + 17038, 17038, 17038, -1, 17038, 17038, 17038, -1, + 17039, 17039, 17039, -1, 17039, 17039, 17039, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17040, 17040, 17040, -1, 17041, 17041, 17041, -1, + 17041, 17041, 17041, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17043, 17043, 17043, -1, + 17043, 17043, 17043, -1, 17044, 17044, 17044, -1, + 17044, 17044, 17044, -1, 17045, 17045, 17045, -1, + 17045, 17045, 17045, -1, 17046, 17046, 17046, -1, + 17046, 17046, 17046, -1, 17047, 17047, 17047, -1, + 17047, 17047, 17047, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17049, 17049, 17049, -1, + 17049, 17049, 17049, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17051, 17051, 17051, -1, + 17051, 17051, 17051, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17053, 17053, 17053, -1, + 17053, 17053, 17053, -1, 17054, 17054, 17054, -1, + 17054, 17054, 17054, -1, 17055, 17055, 17055, -1, + 17055, 17055, 17055, -1, 17056, 17056, 17056, -1, + 17056, 17056, 17056, -1, 17057, 17057, 17057, -1, + 17057, 17057, 17057, -1, 17058, 17058, 17058, -1, + 17058, 17058, 17058, -1, 17059, 17059, 17059, -1, + 17059, 17059, 17059, -1, 17060, 17060, 17060, -1, + 17060, 17060, 17060, -1, 17061, 17061, 17061, -1, + 17061, 17061, 17061, -1, 17062, 17062, 17062, -1, + 17062, 17062, 17062, -1, 17063, 17063, 17063, -1, + 17063, 17063, 17063, -1, 17064, 17064, 17064, -1, + 17064, 17064, 17064, -1, 17065, 17065, 17065, -1, + 17065, 17065, 17065, -1, 17066, 17066, 17066, -1, + 17066, 17066, 17066, -1, 17067, 17067, 17067, -1, + 17067, 17067, 17067, -1, 17068, 17068, 17068, -1, + 17068, 17068, 17068, -1, 17069, 17069, 17069, -1, + 17069, 17069, 17069, -1, 17070, 17070, 17070, -1, + 17070, 17070, 17070, -1, 17071, 17071, 17071, -1, + 17071, 17071, 17071, -1, 17072, 17072, 17072, -1, + 17072, 17072, 17072, -1, 17073, 17073, 17073, -1, + 17073, 17073, 17073, -1, 17074, 17074, 17074, -1, + 17074, 17074, 17074, -1, 17075, 17075, 17075, -1, + 17075, 17075, 17075, -1, 17076, 17076, 17076, -1, + 17076, 17076, 17076, -1, 17077, 17077, 17077, -1, + 17077, 17077, 17077, -1, 17078, 17078, 17078, -1, + 17078, 17078, 17078, -1, 17079, 17079, 17079, -1, + 17079, 17079, 17079, -1, 17080, 17080, 17080, -1, + 17080, 17080, 17080, -1, 17081, 17081, 17081, -1, + 17081, 17081, 17081, -1, 17082, 17082, 17082, -1, + 17082, 17082, 17082, -1, 17083, 17083, 17083, -1, + 17083, 17083, 17083, -1, 17084, 17084, 17084, -1, + 17084, 17084, 17084, -1, 17085, 17085, 17085, -1, + 17085, 17085, 17085, -1, 17086, 17086, 17086, -1, + 17086, 17086, 17086, -1, 17087, 17087, 17087, -1, + 17087, 17087, 17087, -1, 17088, 17088, 17088, -1, + 17088, 17088, 17088, -1, 17089, 17089, 17089, -1, + 17089, 17089, 17089, -1, 17090, 17090, 17090, -1, + 17090, 17090, 17090, -1, 17091, 17091, 17091, -1, + 17091, 17091, 17091, -1, 17092, 17092, 17092, -1, + 17092, 17092, 17092, -1, 17093, 17093, 17093, -1, + 17093, 17093, 17093, -1, 17094, 17094, 17094, -1, + 17094, 17094, 17094, -1, 17095, 17095, 17095, -1, + 17095, 17095, 17095, -1, 17096, 17096, 17096, -1, + 17096, 17096, 17096, -1, 17097, 17097, 17097, -1, + 17097, 17097, 17097, -1, 17098, 17098, 17098, -1, + 17098, 17098, 17098, -1, 17099, 17099, 17099, -1, + 17099, 17099, 17099, -1, 17100, 17100, 17100, -1, + 17100, 17100, 17100, -1, 17101, 17101, 17101, -1, + 17101, 17101, 17101, -1, 17102, 17102, 17102, -1, + 17102, 17102, 17102, -1, 17103, 17103, 17103, -1, + 17103, 17103, 17103, -1, 17104, 17104, 17104, -1, + 17104, 17104, 17104, -1, 17105, 17105, 17105, -1, + 17105, 17105, 17105, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17052, 17052, 17052, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } ] + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link2.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link2.wrl new file mode 100644 index 0000000..1d01de7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link2.wrl @@ -0,0 +1,44120 @@ +#VRML V2.0 utf8 + + +Group { + children [ + Group { + children + Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.059316002 0.208491 0.0112001, + -0.058772299 0.191489 0.0142281, + -0.058072701 0.20848601 0.0172511, + -0.028020401 0.20854101 -0.050889201, + -0.0307144 0.191539 -0.049389899, + -0.033327099 0.208538 -0.047727, + 0.036173999 0.208536 -0.045703001, + 0.040904202 0.208533 -0.0417298, + 0.038590301 0.191535 -0.043790799, + 0.054897901 0.208479 0.0263779, + 0.056071501 0.19148099 0.023506301, + 0.0570965 0.20848399 0.020605, + -0.0109552 0.208451 0.061157402, + -0.0079039196 0.191451 0.061629601, + -0.0048316298 0.208451 0.061971098, + -0.028376499 0.20845599 0.055031601, + -0.0256174 0.19145501 0.0564088, + -0.0227904 0.208454 0.057669099, + -0.033661801 0.208459 0.0518337, + -0.031060301 0.191457 0.0534872, + -0.038590301 0.208462 0.0481093, + -0.036173999 0.19146 0.050021499, + -0.0431097 0.208465 0.043897901, + -0.040904202 0.19146299 0.046048298, + -0.047172099 0.208469 0.039244201, + -0.045200799 0.191467 0.041609898, + -0.0471096 0.191469 0.039181501, + -0.049018301 0.191471 0.0367532, + -0.033617198 0.191459 0.0517544, + -0.0283389 0.191456 0.054947998, + -0.022760199 0.19145399 0.057581998, + -0.019903 0.19145299 0.058755301, + -0.0169627 0.208452 0.0597183, + -0.016940201 0.19145299 0.059628502, + -0.0139775 0.191452 0.060501698, + 0.0449345 0.20846701 0.041926399, + 0.040608101 0.208463 0.046335898, + 0.042828102 0.19146501 0.044173401, + 0.0358513 0.20846 0.0502772, + 0.038280498 0.191462 0.048354302, + 0.0307144 0.20845699 0.053708401, + 0.033327099 0.191459 0.052045502, + 0.025251999 0.208455 0.056593299, + 0.028020401 0.191456 0.0552077, + 0.0195219 0.208453 0.058901299, + 0.0224167 0.19145399 0.057807598, + 0.0135848 0.208452 0.060607899, + 0.016575299 0.191452 0.0598175, + 0.0075038001 0.208451 0.061694901, + 0.0105583 0.191451 0.061216202, + 0.0013432 0.208451 0.062151, + 0.0044293702 0.191451 0.061988801, + -0.0017465299 0.191451 0.062127098, + -0.0109407 0.191451 0.0610657, + -0.0048252302 0.191451 0.061878301, + 0.00134142 0.191451 0.062057901, + 0.0135668 0.191452 0.060516901, + 0.019495999 0.19145299 0.0588126, + 0.0252185 0.19145501 0.056507699, + 0.030673699 0.191457 0.053626601, + 0.0405543 0.19146299 0.046263799, + 0.0469217 0.191469 0.039547, + 0.048784502 0.208471 0.037095498, + 0.048719902 0.191471 0.0370357, + 0.050517999 0.19147301 0.034524299, + 0.0521175 0.20847499 0.0318943, + 0.0520484 0.191475 0.031841401, + 0.053578701 0.191477 0.0291584, + 0.0523162 0.20852201 -0.0272112, + 0.050734501 0.191524 -0.029878899, + 0.049018301 0.208526 -0.032434698, + 0.0550595 0.208517 -0.0216762, + 0.053759102 0.19152001 -0.0244925, + 0.0572192 0.20851301 -0.0158886, + 0.0562139 0.191515 -0.0188237, + 0.058772299 0.208508 -0.0099095702, + 0.058072701 0.19151001 -0.0129326, + 0.0597024 0.20850299 -0.00380253, + 0.059316002 0.191506 -0.0068815602, + 0.059999701 0.208498 0.00236775, + 0.0599305 0.19150101 -0.00073475501, + 0.0596609 0.20849299 0.0085359104, + 0.059909701 0.191496 0.0054426598, + 0.058689699 0.208488 0.0146365, + 0.059253901 0.19149099 0.0115852, + 0.057969999 0.191486 0.0176278, + 0.054825101 0.191479 0.0263323, + 0.057020701 0.191484 0.020567, + 0.0586119 0.191488 0.0146065, + 0.059920099 0.191498 0.0023539499, + 0.0596232 0.191503 -0.0038081601, + 0.058694299 0.191508 -0.0099071097, + 0.057143301 0.191513 -0.015878201, + 0.048953298 0.191526 -0.032402299, + 0.047172099 0.19152801 -0.034925699, + 0.045200799 0.20852999 -0.0372914, + 0.0451409 0.19153 -0.037252601, + 0.0431097 0.191532 -0.039579399, + -0.0105583 0.208545 -0.0568977, + -0.0135848 0.19154499 -0.056289401, + -0.016575299 0.208544 -0.055498999, + -0.0044293702 0.208546 -0.057670299, + -0.0075038001 0.19154599 -0.0573764, + 0.0017465299 0.208546 -0.0578086, + -0.0013432 0.19154599 -0.057832502, + 0.0079039196 0.208546 -0.057311099, + 0.0048316298 0.19154599 -0.0576526, + 0.0139775 0.208545 -0.0561832, + 0.0109552 0.19154499 -0.0568389, + 0.019903 0.208543 -0.054436799, + 0.0169627 0.191544 -0.055399802, + 0.0256174 0.208542 -0.052090298, + 0.0227904 0.191543 -0.053350601, + 0.031060301 0.20853899 -0.049168698, + 0.028376499 0.19154 -0.0507131, + 0.033661801 0.19153801 -0.047515199, + 0.040849999 0.191533 -0.041685101, + 0.036125999 0.19153599 -0.045653, + 0.0310192 0.191539 -0.049114201, + 0.0255835 0.191541 -0.052031901, + 0.019876599 0.191543 -0.054375201, + 0.013959 0.19154499 -0.0561193, + 0.0078934403 0.19154599 -0.057245798, + 0.00174422 0.19154599 -0.057742599, + -0.0044235 0.19154599 -0.057604399, + -0.0165534 0.191544 -0.055436101, + -0.0195219 0.191544 -0.054582801, + -0.0224167 0.208543 -0.0534891, + -0.022387 0.191543 -0.053428799, + -0.025251999 0.191542 -0.052274801, + -0.059909701 0.208501 -0.00112414, + -0.059253901 0.208506 -0.0072666798, + -0.0596609 0.191503 -0.0042174002, + -0.057969999 0.20851099 -0.0133093, + -0.058689699 0.191508 -0.010318, + -0.056071501 0.208515 -0.019187801, + -0.0570965 0.191513 -0.0162865, + -0.053578701 0.20852 -0.0248399, + -0.054897901 0.19151799 -0.0220594, + -0.050517999 0.208524 -0.030205799, + -0.0521175 0.191522 -0.0275758, + -0.0469217 0.208528 -0.035228498, + -0.048784502 0.191526 -0.032777, + -0.042828102 0.20853201 -0.039854899, + -0.0449345 0.19153 -0.037607901, + -0.038280498 0.208535 -0.0440358, + -0.040608101 0.191534 -0.0420174, + -0.0358513 0.19153699 -0.045958702, + -0.0279832 0.191541 -0.050832398, + -0.033282898 0.19153801 -0.047674298, + -0.0382297 0.191535 -0.043988001, + -0.042771298 0.191532 -0.039812699, + -0.046859499 0.19152801 -0.035192501, + -0.053507701 0.19152001 -0.024817601, + -0.0559972 0.191515 -0.019173, + -0.057893101 0.19151101 -0.0133022, + -0.0599305 0.208496 0.0050532599, + -0.059999701 0.19149899 0.00195076, + -0.059850998 0.191496 0.0050359098, + -0.0597024 0.191494 0.00812105, + -0.053759102 0.20847701 0.028811, + -0.0523162 0.191475 0.031529699, + -0.050734501 0.208473 0.034197401, + -0.0562139 0.208482 0.0231422, + -0.0550595 0.191479 0.025994699, + -0.0572192 0.191484 0.0202071, + -0.059237301 0.19149099 0.0111746, + -0.057995699 0.191486 0.017217601, + -0.056139302 0.19148199 0.0231009, + -0.0536878 0.191477 0.028762201, + -0.0506672 0.19147301 0.034141399, + 0.044874899 0.191467 0.0418602, + 0.059581801 0.191493 0.00851392, + -0.050450999 0.191524 -0.030176399, + -0.059830301 0.19150101 -0.00113332, + -0.020008201 0.208462 0.047988199, + -0.0147519 0.20846 0.049940299, + -0.020008201 0.191462 0.047974698, + -0.0147519 0.19146 0.049926799, + -0.0250128 0.19146401 0.0454464, + -0.0250128 0.208464 0.0454599, + -0.0297029 0.191466 0.042373601, + -0.0297029 0.20846599 0.042387102, + -0.0340195 0.191469 0.038795002, + -0.0340195 0.208469 0.038808499, + -0.037908301 0.19147199 0.034755599, + -0.041320302 0.191476 0.0303062, + -0.037908301 0.208472 0.034769099, + -0.041320302 0.20847601 0.0303197, + -0.044212699 0.19148 0.025502799, + -0.044212699 0.20848 0.0255163, + -0.043052498 0.19146501 0.043829098, + -0.0385391 0.191462 0.048034899, + -0.0093101496 0.208459 0.0512916, + -0.0093101496 0.191459 0.051278099, + 0.036642499 0.208471 0.036185499, + 0.040221099 0.20847499 0.031868901, + 0.036642499 0.191471 0.036171999, + 0.040221099 0.191475 0.031855401, + 0.0326031 0.191468 0.0400608, + 0.0326031 0.20846801 0.0400743, + 0.028153701 0.19146501 0.0434728, + 0.028153701 0.208465 0.043486301, + 0.0233503 0.19146299 0.046365201, + 0.0233503 0.208463 0.046378698, + -0.0037513 0.191459 0.052011602, + -0.0037513 0.208459 0.052025098, + 0.00185474 0.208459 0.052131601, + 0.00185474 0.191459 0.0521181, + 0.0074374499 0.208459 0.051609699, + 0.0074374499 0.191459 0.051596198, + 0.0129266 0.20846 0.050466102, + 0.0129266 0.19146 0.050452601, + 0.0182532 0.208461 0.0487151, + 0.0182532 0.191461 0.048701599, + 0.035803799 0.19146 0.0501999, + 0.043293901 0.208478 0.0271788, + 0.043293901 0.191478 0.027165299, + 0.045822199 0.208482 0.0221742, + 0.045822199 0.19148199 0.0221607, + 0.041320302 0.191521 -0.0260012, + 0.044212699 0.191517 -0.0211978, + 0.041320302 0.20852099 -0.0259877, + 0.044212699 0.208517 -0.021184299, + 0.037908301 0.208524 -0.030437101, + 0.037908301 0.191524 -0.030450599, + 0.0465491 0.191513 -0.016100699, + 0.0465491 0.20851301 -0.0160872, + 0.048300099 0.19150899 -0.0107741, + 0.048300099 0.208509 -0.0107606, + 0.049443699 0.191504 -0.0052849599, + 0.049443699 0.20850401 -0.0052714199, + 0.0477743 0.191487 0.016904401, + 0.0477743 0.208487 0.016917899, + 0.049125601 0.208491 0.0114762, + 0.049125601 0.19149099 0.0114627, + 0.049859099 0.20849501 0.00591732, + 0.049859099 0.191495 0.0059037898, + 0.049965601 0.2085 0.000311287, + 0.049965601 0.19149999 0.00029775, + 0.0340195 0.208528 -0.0344765, + 0.0340195 0.19152801 -0.03449, + -0.0129266 0.19153699 -0.0461476, + -0.0074374499 0.19153801 -0.047291201, + -0.0129266 0.208537 -0.046134099, + -0.0074374499 0.208538 -0.0472777, + -0.0182532 0.208535 -0.044383101, + -0.0182532 0.191535 -0.044396602, + -0.00185474 0.19153801 -0.047813099, + -0.00185474 0.208538 -0.047799598, + 0.0037513 0.19153801 -0.0477066, + 0.0037513 0.208538 -0.0476931, + 0.0093101496 0.19153699 -0.046973102, + 0.0093101496 0.208537 -0.046959601, + 0.0297029 0.19153 -0.0380686, + 0.0297029 0.20852999 -0.0380551, + 0.0250128 0.208533 -0.041127902, + 0.0250128 0.191533 -0.041141398, + 0.020008201 0.208535 -0.0436562, + 0.020008201 0.191535 -0.043669701, + 0.0147519 0.208536 -0.045608301, + 0.0147519 0.19153599 -0.045621801, + -0.0233503 0.208534 -0.0420467, + -0.0233503 0.191534 -0.0420602, + -0.049859099 0.208501 -0.00158527, + -0.049965601 0.208497 0.0040207598, + -0.049859099 0.19150101 -0.00159881, + -0.049965601 0.191497 0.00400723, + -0.049125601 0.191506 -0.0071576601, + -0.049125601 0.208506 -0.0071441201, + -0.0477743 0.19151001 -0.0125994, + -0.0477743 0.20851 -0.0125859, + -0.045822199 0.191514 -0.0178557, + -0.045822199 0.208514 -0.0178422, + -0.028153701 0.191531 -0.039167799, + -0.028153701 0.20853101 -0.039154299, + -0.0326031 0.208529 -0.035742301, + -0.0326031 0.19152901 -0.035755798, + -0.036642499 0.208525 -0.031853501, + -0.036642499 0.191525 -0.031867001, + -0.040221099 0.20852201 -0.027536901, + -0.040221099 0.191522 -0.027550399, + -0.043293901 0.208518 -0.022846799, + -0.043293901 0.19151799 -0.0228603, + -0.049443699 0.208492 0.0096034696, + -0.049443699 0.19149201 0.0095899301, + -0.048300099 0.191488 0.0150791, + -0.048300099 0.208488 0.0150926, + -0.0465491 0.20848399 0.020419201, + -0.0465491 0.191484 0.0204057, + 0.0074938498 0.191451 0.061602499, + 0.054986499 0.191517 -0.0216581, + 0.052246802 0.191522 -0.027185701, + -0.0105443 0.19154499 -0.056832898, + -0.059175301 0.191506 -0.0072677098 ] + + } + normal + Normal { + vector [ -0.97952574 0.004520549 0.20126796, + -0.51189011 0.0053594015 -0.85903418, + 0.64316899 0.0052897702 -0.765706, + 0.93450958 0.0043944181 0.35591081, + -0.13172005 0.0038898115 0.99127936, + -0.42695105 0.0039598006 0.90426612, + -0.51766694 0.0039966195 0.85557288, + -0.60289294 0.0040452196 0.79781187, + -0.68173021 0.0040957513 0.73159224, + -0.75333673 0.0041559688 0.65762174, + -0.78619182 -0.0051710187 0.61796087, + -0.78618872 -0.0051710182 0.61796474, + -0.56103611 -0.0053352416 0.82777417, + -0.56099981 -0.0053352583 0.82779872, + -0.47294718 -0.0053807218 0.88107431, + -0.47293377 -0.0053807171 0.88108158, + -0.3798331 -0.0054162815 0.92503923, + -0.37986091 -0.0054162587 0.92502779, + -0.33171692 0.0039322791 0.94337076, + -0.28269696 -0.0054429094 0.95919389, + -0.28270486 -0.0054429071 0.9591915, + -0.23295707 0.0039046309 0.97247922, + 0.7137928 0.0041238889 0.7003448, + 0.63800579 0.0040677493 0.77002084, + 0.55543393 0.0040218495 0.8315509, + 0.46700287 0.0039769192 0.88424677, + 0.37361312 0.0039421315 0.92757636, + 0.27625698 0.0039107394 0.9610759, + 0.17596301 0.0038951705 0.98438913, + 0.073832206 0.0038862205 0.99726313, + -0.029121911 0.0038855013 0.99956834, + -0.18259694 -0.005461318 0.98317266, + -0.18256705 -0.0054613315 0.98317826, + -0.080517709 -0.0054735104 0.99673814, + -0.080550566 -0.0054734973 0.99673551, + 0.0224046 -0.0054796198 0.99973398, + 0.022371294 -0.0054796184 0.99973476, + 0.22640406 -0.0054556816 0.97401822, + 0.2264331 -0.0054556727 0.97401148, + 0.32533985 -0.0054313871 0.9455815, + 0.32536796 -0.0054313797 0.9455719, + 0.42085779 -0.0053987871 0.90711057, + 0.42087278 -0.0053987773 0.9071036, + 0.51189774 -0.0053609475 0.85902959, + 0.51188278 -0.0053609577 0.85903859, + 0.67680424 -0.0052656117 0.73614424, + 0.67678708 -0.0052656205 0.73616004, + 0.78202099 0.0041815299 0.62323803, + 0.81304801 -0.0051388 0.582174, + 0.81307441 -0.0051387725 0.58213729, + 0.84195113 0.0042502303 0.53953707, + 0.868608 -0.0050734901 0.49547401, + 0.86863017 -0.0050734612 0.49543512, + 0.89297521 0.0043189409 0.45008513, + 0.84556383 0.0051031988 -0.5338499, + 0.89597899 0.0050309999 -0.44406801, + 0.9368844 0.0049586524 -0.34960419, + 0.96786863 0.004877008 -0.2514089, + 0.98858953 0.0047996677 -0.15055792, + 0.99883038 0.004717262 -0.04812222, + 0.99848402 0.00463385 0.054847401, + 0.98755312 0.0045563206 0.15722002, + 0.96615964 0.0044768788 0.2579059, + 0.91495675 -0.0050014388 0.40352091, + 0.91495132 -0.0050014518 0.40353316, + 0.9515999 -0.0049306997 0.30729997, + 0.95158702 -0.00493073 0.30734, + 0.97815663 -0.0048437282 0.20781292, + 0.97815001 -0.00484375 0.207844, + 0.99998337 -0.0046848617 0.0033641811, + 0.99998337 -0.0046848617 0.0033629611, + 0.99502754 -0.0046027577 -0.099493459, + 0.99503088 -0.0046027894 -0.099460684, + 0.97952336 -0.0045234016 -0.20128007, + 0.97952914 -0.0045234202 -0.20125203, + 0.95364535 -0.0044412115 -0.30090013, + 0.95364279 -0.0044411989 -0.30090794, + 0.816962 -0.0042215101 -0.57667601, + 0.81696284 -0.0042215092 -0.57667488, + 0.78619009 0.0051714503 -0.61796308, + 0.7533437 -0.0041539888 -0.65761375, + 0.75332981 -0.0041539692 -0.65762985, + 0.71848291 0.0052336496 -0.69552493, + -0.22641894 0.0054583987 -0.97401476, + -0.12506604 0.005467982 -0.99213338, + -0.022387907 0.0054766019 -0.99973434, + 0.080534093 0.0054705096 -0.99673688, + 0.1825819 0.0054640765 -0.9831754, + 0.2827009 0.0054421984 -0.95919263, + 0.37984681 0.0054135872 -0.92503357, + 0.47294083 0.0053820983 -0.88107771, + 0.56101775 0.0053391778 -0.82778656, + 0.68173122 -0.0040957415 -0.73159122, + 0.68173021 -0.0040957415 -0.73159224, + 0.60288495 -0.0040470297 -0.79781789, + 0.60290086 -0.004047039 -0.79780585, + 0.51768619 -0.0039926316 -0.85556132, + 0.51764816 -0.0039926115 -0.85558432, + 0.42697006 -0.0039560003 -0.90425712, + 0.42693207 -0.0039559905 -0.90427512, + 0.33172199 -0.0039313999 -0.94336897, + 0.33171186 -0.003931398 -0.94337255, + 0.23294593 -0.003906779 -0.97248179, + 0.23296909 -0.0039067916 -0.97247636, + 0.13173701 -0.0038867304 -0.9912771, + 0.13170394 -0.0038867281 -0.99128151, + 0.029137997 -0.0038825795 -0.99956787, + 0.029105792 -0.003882579 -0.99956876, + -0.073848195 -0.0038891295 -0.99726188, + -0.073816217 -0.0038891309 -0.99726427, + -0.27625209 -0.0039098114 -0.96107733, + -0.2762621 -0.0039098118 -0.96107447, + -0.32535389 0.0054340381 -0.94557667, + -0.37360692 -0.0039410591 -0.92757875, + -0.37361813 -0.0039410614 -0.92757434, + -0.42086509 0.0054003112 -0.90710723, + -0.99433821 0.0047639911 -0.10615502, + -0.97815323 0.0048408308 -0.20782904, + -0.95159352 0.0049269078 -0.30731985, + -0.91495413 0.0050002607 -0.40352705, + -0.86861885 0.0050774785 -0.49545488, + -0.81306088 0.0051428196 -0.58215594, + -0.74890685 0.0052075288 -0.66265482, + -0.67679596 0.0052634696 -0.73615193, + -0.5975197 0.0053171678 -0.80183667, + -0.46698913 -0.003974231 -0.88425422, + -0.46701601 -0.0039742398 -0.88423997, + -0.55542612 -0.0040200409 -0.8315562, + -0.5554418 -0.0040200488 -0.83154571, + -0.63801616 -0.0040700608 -0.7700122, + -0.63799596 -0.0040700496 -0.77002889, + -0.71378481 -0.0041218391 -0.70035285, + -0.71380079 -0.0041218586 -0.70033675, + -0.78201485 -0.004179629 -0.62324589, + -0.78202814 -0.0041796407 -0.62322909, + -0.89297473 -0.0043188389 -0.45008588, + -0.89297575 -0.0043188389 -0.45008388, + -0.93450767 -0.0043933485 -0.35591587, + -0.93451178 -0.0043933592 -0.35590491, + -0.96616077 -0.004477629 -0.25790194, + -0.96615863 -0.0044776187 -0.25790992, + -0.99998337 0.0046849716 -0.0033635711, + -0.99882954 -0.0047200378 0.048137378, + -0.99883109 -0.0047200206 0.048106909, + -0.99502933 0.004599662 0.099476241, + -0.87192881 0.0042928089 0.48961389, + -0.91764462 0.0043626786 0.39737785, + -0.9536441 0.0044420003 0.30090404, + -0.98858738 -0.0048028217 0.15057206, + -0.98859179 -0.0048027989 0.15054297, + -0.96786475 -0.004879849 0.25142395, + -0.9678725 -0.0048798178 0.25139388, + -0.93687922 -0.0049613914 0.34961808, + -0.93689001 -0.00496135 0.34958899, + -0.89597243 -0.0050336225 0.44408122, + -0.89598531 -0.005033602 0.44405514, + -0.84555185 -0.0051072985 0.53386891, + -0.84557581 -0.0051072687 0.53383088, + -0.81696284 0.0042214389 0.57667488, + 0.74890685 -0.0052075186 0.66265482, + 0.99433821 -0.0047639911 0.10615502, + -0.84195113 -0.0042502605 -0.53953707, + -0.99848402 -0.00463385 -0.054847401, + 0.34814897 0.00074646686 -0.93743891, + 0.45092005 0.00071073405 -0.89256412, + 0.54802299 0.00066606101 -0.83646297, + 0.63822806 0.00061301608 -0.7698471, + 0.7935378 0.00048455488 -0.60852087, + 0.72040915 0.00055226113 -0.69354916, + 0.85667658 0.0004107648 -0.51585376, + -0.71848291 -0.0052336496 0.69552493, + -0.64316899 -0.0052897702 0.765706, + 0.24100088 0.00077281165 -0.97052455, + -0.76984751 0.00050820969 -0.63822764, + -0.69354916 0.00057364913 -0.72040915, + -0.60852075 0.00063187978 -0.79353768, + -0.51585412 0.00068215717 -0.85667616, + 0.13081801 0.00078944012 -0.99140614, + 0.018993707 0.0007961393 -0.99981934, + -0.093079343 0.00079282635 -0.99565846, + -0.20395903 0.00077954412 -0.97897911, + -0.31228685 0.00075645867 -0.94998753, + -0.41668814 0.00072386023 -0.90904927, + 0.5975197 -0.0053171678 0.80183667, + -0.83646315 0.00043638112 -0.5480231, + -0.8925643 0.00035906013 -0.45092013, + -0.85667658 -0.0004107648 0.51585376, + -0.7935378 -0.00048455488 0.60852087, + -0.90904957 -0.00033180186 0.41668779, + -0.94998777 -0.00024866895 0.31228694, + -0.97897947 -0.00016240907 0.20395911, + -0.93743914 0.00027722502 -0.34814903, + -0.97052437 0.00019190708 -0.2410031, + -0.9914065 0.00010416695 -0.13081694, + -0.99981964 1.5124295e-005 -0.018993692, + -0.99565876 -7.4117284e-005 0.093079075, + -0.72040915 -0.00055226113 0.69354916, + 0.20395903 -0.00077954412 0.97897911, + 0.31228685 -0.00075645867 0.94998753, + 0.093079343 -0.00079282635 0.99565846, + -0.018993707 -0.0007961393 0.99981934, + -0.13081801 -0.00078944012 0.99140614, + -0.63822806 -0.00061301608 0.7698471, + -0.54802299 -0.00066606101 0.83646297, + -0.45092005 -0.00071073405 0.89256412, + -0.34814897 -0.00074646686 0.93743891, + -0.24100088 -0.00077281165 0.97052455, + 0.41668814 -0.00072386023 0.90904927, + 0.99981964 -1.5124295e-005 0.018993692, + 0.99140638 -0.00010416804 0.13081804, + 0.97052491 -0.00019190497 0.24100097, + 0.93743914 -0.00027722502 0.34814903, + 0.51585412 -0.00068215717 0.85667616, + 0.60852075 -0.00063187978 0.79353768, + 0.69354916 -0.00057364913 0.72040915, + 0.76984751 -0.00050820969 0.63822764, + 0.83646315 -0.00043638112 0.5480231, + 0.8925643 -0.00035906013 0.45092013, + 0.99565876 7.4117284e-005 -0.093079075, + 0.97897941 0.00016240889 -0.20395888, + 0.94998777 0.00024866895 -0.31228694, + 0.90904957 0.00033180186 -0.41668779, + 0.12506703 -0.0054678712 0.99213326, + 0.91764462 -0.0043627787 -0.39737785, + 0.87192881 -0.0042928993 -0.48961389, + -0.17596301 -0.0038950504 -0.98438913, + -0.98755324 -0.0045563709 -0.15721904, + 0 -0.99999964 -0.00079628272, + 0 0.99999964 0.00079628272 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 9, 10, 11, -1, + 12, 13, 14, -1, 15, 16, 17, -1, + 15, 18, 19, -1, 18, 20, 21, -1, + 20, 22, 23, -1, 24, 25, 22, -1, + 26, 24, 27, -1, 26, 25, 24, -1, + 28, 18, 21, -1, 28, 19, 18, -1, + 29, 15, 19, -1, 29, 16, 15, -1, + 30, 17, 16, -1, 30, 31, 17, -1, + 17, 31, 32, -1, 33, 32, 31, -1, + 33, 34, 32, -1, 32, 34, 12, -1, + 35, 36, 37, -1, 38, 39, 36, -1, + 40, 41, 38, -1, 40, 42, 43, -1, + 44, 45, 42, -1, 44, 46, 47, -1, + 48, 49, 46, -1, 50, 51, 48, -1, + 50, 14, 52, -1, 53, 12, 34, -1, + 53, 13, 12, -1, 54, 14, 13, -1, + 54, 52, 14, -1, 55, 50, 52, -1, + 55, 51, 50, -1, 56, 46, 49, -1, + 56, 47, 46, -1, 57, 44, 47, -1, + 57, 45, 44, -1, 58, 42, 45, -1, + 58, 43, 42, -1, 59, 40, 43, -1, + 59, 41, 40, -1, 60, 36, 39, -1, + 60, 37, 36, -1, 35, 61, 62, -1, + 63, 62, 61, -1, 63, 64, 62, -1, + 62, 64, 65, -1, 66, 65, 64, -1, + 66, 67, 65, -1, 9, 65, 67, -1, + 68, 69, 70, -1, 71, 72, 68, -1, + 73, 74, 71, -1, 73, 75, 76, -1, + 77, 78, 75, -1, 77, 79, 80, -1, + 79, 81, 82, -1, 81, 83, 84, -1, + 11, 85, 83, -1, 86, 9, 67, -1, + 86, 10, 9, -1, 87, 11, 10, -1, + 87, 85, 11, -1, 88, 83, 85, -1, + 88, 84, 83, -1, 89, 79, 82, -1, + 89, 80, 79, -1, 90, 77, 80, -1, + 90, 78, 77, -1, 91, 75, 78, -1, + 91, 76, 75, -1, 92, 73, 76, -1, + 92, 74, 73, -1, 93, 70, 69, -1, + 93, 94, 70, -1, 95, 70, 94, -1, + 96, 95, 94, -1, 96, 97, 95, -1, + 7, 95, 97, -1, 98, 99, 100, -1, + 101, 102, 98, -1, 103, 104, 101, -1, + 105, 106, 103, -1, 107, 108, 105, -1, + 109, 110, 107, -1, 111, 112, 109, -1, + 111, 113, 114, -1, 113, 6, 115, -1, + 116, 7, 97, -1, 116, 8, 7, -1, + 117, 6, 8, -1, 117, 115, 6, -1, + 118, 113, 115, -1, 118, 114, 113, -1, + 119, 111, 114, -1, 119, 112, 111, -1, + 120, 109, 112, -1, 120, 110, 109, -1, + 121, 107, 110, -1, 121, 108, 107, -1, + 122, 105, 108, -1, 122, 106, 105, -1, + 123, 103, 106, -1, 123, 104, 103, -1, + 124, 101, 104, -1, 124, 102, 101, -1, + 125, 100, 99, -1, 125, 126, 100, -1, + 127, 100, 126, -1, 128, 127, 126, -1, + 128, 129, 127, -1, 127, 129, 3, -1, + 130, 131, 132, -1, 133, 134, 131, -1, + 135, 136, 133, -1, 137, 138, 135, -1, + 139, 140, 137, -1, 139, 141, 142, -1, + 141, 143, 144, -1, 145, 146, 143, -1, + 5, 147, 145, -1, 148, 3, 129, -1, + 148, 4, 3, -1, 149, 5, 4, -1, + 149, 147, 5, -1, 150, 145, 147, -1, + 150, 146, 145, -1, 151, 143, 146, -1, + 151, 144, 143, -1, 152, 141, 144, -1, + 152, 142, 141, -1, 153, 137, 140, -1, + 153, 138, 137, -1, 154, 135, 138, -1, + 154, 136, 135, -1, 155, 133, 136, -1, + 155, 134, 133, -1, 156, 130, 157, -1, + 158, 156, 157, -1, 158, 159, 156, -1, + 156, 159, 0, -1, 160, 161, 162, -1, + 160, 163, 164, -1, 163, 2, 165, -1, + 166, 0, 159, -1, 166, 1, 0, -1, + 167, 2, 1, -1, 167, 165, 2, -1, + 168, 163, 165, -1, 168, 164, 163, -1, + 169, 160, 164, -1, 169, 161, 160, -1, + 170, 162, 161, -1, 170, 27, 162, -1, + 162, 27, 24, -1, 37, 171, 35, -1, + 35, 171, 61, -1, 84, 172, 81, -1, + 81, 172, 82, -1, 142, 173, 139, -1, + 139, 173, 140, -1, 132, 174, 130, -1, + 130, 174, 157, -1, 175, 176, 177, -1, + 177, 176, 178, -1, 177, 179, 175, -1, + 175, 179, 180, -1, 179, 181, 180, -1, + 180, 181, 182, -1, 181, 183, 182, -1, + 182, 183, 184, -1, 185, 186, 187, -1, + 187, 186, 188, -1, 187, 184, 185, -1, + 185, 184, 183, -1, 186, 189, 188, -1, + 188, 189, 190, -1, 25, 191, 22, -1, + 22, 191, 23, -1, 23, 192, 20, -1, + 20, 192, 21, -1, 176, 193, 178, -1, + 178, 193, 194, -1, 195, 196, 197, -1, + 197, 196, 198, -1, 197, 199, 195, -1, + 195, 199, 200, -1, 199, 201, 200, -1, + 200, 201, 202, -1, 201, 203, 202, -1, + 202, 203, 204, -1, 205, 194, 206, -1, + 206, 194, 193, -1, 206, 207, 205, -1, + 205, 207, 208, -1, 207, 209, 208, -1, + 208, 209, 210, -1, 209, 211, 210, -1, + 210, 211, 212, -1, 211, 213, 212, -1, + 212, 213, 214, -1, 213, 204, 214, -1, + 214, 204, 203, -1, 41, 215, 38, -1, + 38, 215, 39, -1, 196, 216, 198, -1, + 198, 216, 217, -1, 216, 218, 217, -1, + 217, 218, 219, -1, 220, 221, 222, -1, + 222, 221, 223, -1, 222, 224, 220, -1, + 220, 224, 225, -1, 221, 226, 223, -1, + 223, 226, 227, -1, 226, 228, 227, -1, + 227, 228, 229, -1, 228, 230, 229, -1, + 229, 230, 231, -1, 232, 219, 233, -1, + 233, 219, 218, -1, 233, 234, 232, -1, + 232, 234, 235, -1, 234, 236, 235, -1, + 235, 236, 237, -1, 236, 238, 237, -1, + 237, 238, 239, -1, 238, 231, 239, -1, + 239, 231, 230, -1, 224, 240, 225, -1, + 225, 240, 241, -1, 242, 243, 244, -1, + 244, 243, 245, -1, 244, 246, 242, -1, + 242, 246, 247, -1, 243, 248, 245, -1, + 245, 248, 249, -1, 248, 250, 249, -1, + 249, 250, 251, -1, 250, 252, 251, -1, + 251, 252, 253, -1, 254, 241, 255, -1, + 255, 241, 240, -1, 255, 256, 254, -1, + 254, 256, 257, -1, 256, 258, 257, -1, + 257, 258, 259, -1, 258, 260, 259, -1, + 259, 260, 261, -1, 260, 253, 261, -1, + 261, 253, 252, -1, 246, 262, 247, -1, + 247, 262, 263, -1, 264, 265, 266, -1, + 266, 265, 267, -1, 266, 268, 264, -1, + 264, 268, 269, -1, 268, 270, 269, -1, + 269, 270, 271, -1, 270, 272, 271, -1, + 271, 272, 273, -1, 274, 263, 275, -1, + 275, 263, 262, -1, 275, 276, 274, -1, + 274, 276, 277, -1, 276, 278, 277, -1, + 277, 278, 279, -1, 278, 280, 279, -1, + 279, 280, 281, -1, 280, 282, 281, -1, + 281, 282, 283, -1, 282, 273, 283, -1, + 283, 273, 272, -1, 265, 284, 267, -1, + 267, 284, 285, -1, 286, 285, 287, -1, + 287, 285, 284, -1, 287, 288, 286, -1, + 286, 288, 289, -1, 288, 190, 289, -1, + 289, 190, 189, -1, 51, 290, 48, -1, + 48, 290, 49, -1, 74, 291, 71, -1, + 71, 291, 72, -1, 72, 292, 68, -1, + 68, 292, 69, -1, 102, 293, 98, -1, + 98, 293, 99, -1, 134, 294, 131, -1, + 131, 294, 132, -1, 183, 181, 192, -1, + 192, 181, 21, -1, 21, 181, 28, -1, + 28, 181, 179, -1, 28, 179, 19, -1, + 19, 179, 29, -1, 179, 177, 29, -1, + 29, 177, 16, -1, 16, 177, 30, -1, + 30, 177, 31, -1, 177, 178, 31, -1, + 31, 178, 33, -1, 33, 178, 34, -1, + 34, 178, 194, -1, 34, 194, 53, -1, + 53, 194, 13, -1, 194, 205, 13, -1, + 13, 205, 54, -1, 54, 205, 52, -1, + 52, 205, 208, -1, 52, 208, 55, -1, + 55, 208, 51, -1, 208, 210, 51, -1, + 51, 210, 290, -1, 290, 210, 49, -1, + 49, 210, 56, -1, 210, 212, 56, -1, + 56, 212, 47, -1, 47, 212, 57, -1, + 57, 212, 214, -1, 57, 214, 45, -1, + 45, 214, 58, -1, 214, 203, 58, -1, + 58, 203, 43, -1, 43, 203, 59, -1, + 59, 203, 201, -1, 59, 201, 41, -1, + 41, 201, 215, -1, 201, 199, 215, -1, + 215, 199, 39, -1, 39, 199, 60, -1, + 60, 199, 197, -1, 60, 197, 37, -1, + 37, 197, 171, -1, 171, 197, 61, -1, + 61, 197, 198, -1, 61, 198, 63, -1, + 63, 198, 64, -1, 198, 217, 64, -1, + 64, 217, 66, -1, 66, 217, 67, -1, + 67, 217, 219, -1, 67, 219, 86, -1, + 86, 219, 10, -1, 219, 232, 10, -1, + 10, 232, 87, -1, 87, 232, 85, -1, + 85, 232, 235, -1, 85, 235, 88, -1, + 88, 235, 84, -1, 84, 235, 172, -1, + 172, 235, 237, -1, 172, 237, 82, -1, + 82, 237, 89, -1, 237, 239, 89, -1, + 89, 239, 80, -1, 80, 239, 90, -1, + 90, 239, 230, -1, 90, 230, 78, -1, + 78, 230, 91, -1, 230, 228, 91, -1, + 91, 228, 76, -1, 76, 228, 92, -1, + 92, 228, 226, -1, 92, 226, 74, -1, + 74, 226, 291, -1, 226, 221, 291, -1, + 291, 221, 72, -1, 72, 221, 292, -1, + 292, 221, 220, -1, 292, 220, 69, -1, + 69, 220, 93, -1, 93, 220, 94, -1, + 94, 220, 225, -1, 94, 225, 96, -1, + 96, 225, 97, -1, 225, 241, 97, -1, + 97, 241, 116, -1, 116, 241, 8, -1, + 8, 241, 254, -1, 8, 254, 117, -1, + 117, 254, 115, -1, 254, 257, 115, -1, + 115, 257, 118, -1, 118, 257, 114, -1, + 114, 257, 119, -1, 257, 259, 119, -1, + 119, 259, 112, -1, 112, 259, 120, -1, + 120, 259, 261, -1, 120, 261, 110, -1, + 110, 261, 121, -1, 261, 252, 121, -1, + 121, 252, 108, -1, 108, 252, 122, -1, + 122, 252, 250, -1, 122, 250, 106, -1, + 106, 250, 123, -1, 250, 248, 123, -1, + 123, 248, 104, -1, 104, 248, 124, -1, + 124, 248, 243, -1, 124, 243, 102, -1, + 102, 243, 293, -1, 243, 242, 293, -1, + 293, 242, 99, -1, 99, 242, 125, -1, + 125, 242, 126, -1, 242, 247, 126, -1, + 126, 247, 128, -1, 128, 247, 129, -1, + 129, 247, 263, -1, 129, 263, 148, -1, + 148, 263, 4, -1, 263, 274, 4, -1, + 4, 274, 149, -1, 149, 274, 147, -1, + 147, 274, 277, -1, 147, 277, 150, -1, + 150, 277, 146, -1, 146, 277, 151, -1, + 151, 277, 279, -1, 151, 279, 144, -1, + 144, 279, 152, -1, 279, 281, 152, -1, + 152, 281, 142, -1, 142, 281, 173, -1, + 173, 281, 283, -1, 173, 283, 140, -1, + 140, 283, 153, -1, 283, 272, 153, -1, + 153, 272, 138, -1, 138, 272, 154, -1, + 154, 272, 270, -1, 154, 270, 136, -1, + 136, 270, 155, -1, 270, 268, 155, -1, + 155, 268, 134, -1, 134, 268, 294, -1, + 294, 268, 266, -1, 294, 266, 132, -1, + 132, 266, 174, -1, 174, 266, 157, -1, + 157, 266, 267, -1, 157, 267, 158, -1, + 158, 267, 159, -1, 267, 285, 159, -1, + 159, 285, 166, -1, 166, 285, 1, -1, + 1, 285, 286, -1, 1, 286, 167, -1, + 167, 286, 165, -1, 286, 289, 165, -1, + 165, 289, 168, -1, 168, 289, 164, -1, + 164, 289, 169, -1, 289, 189, 169, -1, + 169, 189, 161, -1, 161, 189, 170, -1, + 170, 189, 186, -1, 170, 186, 27, -1, + 27, 186, 26, -1, 186, 185, 26, -1, + 26, 185, 25, -1, 25, 185, 191, -1, + 191, 185, 183, -1, 191, 183, 23, -1, + 23, 183, 192, -1, 15, 17, 175, -1, + 175, 17, 176, -1, 17, 32, 176, -1, + 176, 32, 193, -1, 32, 12, 193, -1, + 193, 12, 14, -1, 193, 14, 206, -1, + 206, 14, 50, -1, 206, 50, 207, -1, + 207, 50, 48, -1, 207, 48, 209, -1, + 209, 48, 46, -1, 209, 46, 211, -1, + 211, 46, 44, -1, 211, 44, 213, -1, + 213, 44, 42, -1, 213, 42, 204, -1, + 204, 42, 40, -1, 204, 40, 202, -1, + 202, 40, 38, -1, 202, 38, 200, -1, + 200, 38, 36, -1, 200, 36, 195, -1, + 195, 36, 35, -1, 195, 35, 196, -1, + 196, 35, 62, -1, 196, 62, 216, -1, + 216, 62, 65, -1, 216, 65, 218, -1, + 218, 65, 9, -1, 218, 9, 11, -1, + 218, 11, 233, -1, 233, 11, 83, -1, + 233, 83, 234, -1, 234, 83, 81, -1, + 234, 81, 236, -1, 236, 81, 79, -1, + 236, 79, 238, -1, 238, 79, 77, -1, + 238, 77, 231, -1, 231, 77, 75, -1, + 231, 75, 229, -1, 229, 75, 73, -1, + 229, 73, 227, -1, 227, 73, 71, -1, + 227, 71, 223, -1, 223, 71, 68, -1, + 223, 68, 222, -1, 222, 68, 70, -1, + 222, 70, 224, -1, 224, 70, 95, -1, + 224, 95, 240, -1, 240, 95, 7, -1, + 240, 7, 6, -1, 240, 6, 255, -1, + 255, 6, 113, -1, 255, 113, 256, -1, + 256, 113, 111, -1, 256, 111, 258, -1, + 258, 111, 109, -1, 258, 109, 260, -1, + 260, 109, 107, -1, 260, 107, 253, -1, + 253, 107, 105, -1, 253, 105, 251, -1, + 251, 105, 103, -1, 251, 103, 249, -1, + 249, 103, 101, -1, 249, 101, 245, -1, + 245, 101, 98, -1, 245, 98, 244, -1, + 244, 98, 100, -1, 244, 100, 246, -1, + 246, 100, 127, -1, 246, 127, 262, -1, + 262, 127, 3, -1, 262, 3, 5, -1, + 262, 5, 275, -1, 275, 5, 145, -1, + 275, 145, 276, -1, 276, 145, 143, -1, + 276, 143, 278, -1, 278, 143, 141, -1, + 278, 141, 280, -1, 280, 141, 139, -1, + 280, 139, 282, -1, 282, 139, 137, -1, + 282, 137, 273, -1, 273, 137, 135, -1, + 273, 135, 271, -1, 271, 135, 133, -1, + 271, 133, 269, -1, 269, 133, 131, -1, + 269, 131, 264, -1, 264, 131, 130, -1, + 264, 130, 265, -1, 265, 130, 156, -1, + 265, 156, 284, -1, 284, 156, 0, -1, + 284, 0, 2, -1, 284, 2, 287, -1, + 287, 2, 163, -1, 287, 163, 288, -1, + 288, 163, 160, -1, 288, 160, 190, -1, + 190, 160, 162, -1, 190, 162, 188, -1, + 188, 162, 24, -1, 188, 24, 187, -1, + 187, 24, 22, -1, 187, 22, 184, -1, + 184, 22, 20, -1, 184, 20, 182, -1, + 182, 20, 18, -1, 182, 18, 180, -1, + 180, 18, 15, -1, 180, 15, 175, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 159, 159, 159, -1, 160, 160, 160, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 161, 161, 161, -1, 162, 162, 162, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 163, 163, 163, -1, 164, 164, 164, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 165, 165, 165, -1, 166, 166, 166, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 167, 167, 167, -1, 168, 168, 168, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 169, 169, 169, -1, 170, 170, 170, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 171, 171, 171, -1, 172, 172, 172, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 173, 173, 173, -1, 174, 174, 174, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 177, 177, 177, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 179, 179, 179, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 181, 181, 181, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 187, 187, 187, -1, 188, 188, 188, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 190, 190, 190, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 191, 191, 191, -1, 192, 192, 192, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 194, 194, 194, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 195, 195, 195, -1, 196, 196, 196, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 197, 197, 197, -1, 198, 198, 198, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 200, 200, 200, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 201, 201, 201, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 203, 203, 203, -1, 204, 204, 204, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 205, 205, 205, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 207, 207, 207, -1, 208, 208, 208, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 209, 209, 209, -1, 210, 210, 210, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 211, 211, 211, -1, 212, 212, 212, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 213, 213, 213, -1, 214, 214, 214, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 215, 215, 215, -1, 216, 216, 216, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 217, 217, 217, -1, 218, 218, 218, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 219, 219, 219, -1, 220, 220, 220, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 221, 221, 221, -1, 222, 222, 222, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 224, 224, 224, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 225, 225, 225, -1, 226, 226, 226, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + + } + + }, + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.0078125 0.1875 0.65625 + ambientIntensity 0.46584472 + specularColor 0 0.1 0.5 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.059011199 0.17149 0.0128905, + 0.058998398 0.164345 0.0132011, + 0.059330199 0.171491 0.0110768, + 0.059445001 0.16446 0.010426, + 0.050208401 0.171472 0.034961998, + 0.0497806 0.19147199 0.035647102, + 0.049818899 0.171472 0.035574201, + 0.0583959 0.19150899 -0.0116288, + 0.057670102 0.17151099 -0.0143697, + 0.056669399 0.191514 -0.01756, + 0.0081428103 0.119973 -0.035020299, + 0.0109179 0.11973 -0.034569301, + 0.0081428103 0.11849 -0.033389699, + 0.0109179 0.121281 -0.036160398, + 0.0137106 0.120975 -0.035569102, + 0.0137106 0.122596 -0.0371175, + 0.0165099 0.122232 -0.036382802, + 0.0165099 0.123923 -0.0378858, + 0.019305199 0.123507 -0.0370056, + 0.019305199 0.12526999 -0.038460702, + 0.0220857 0.124804 -0.037432302, + 0.0220857 0.12663899 -0.038837299, + 0.0248404 0.126131 -0.037659299, + 0.0248404 0.128038 -0.039011501, + 0.027557701 0.12749401 -0.0376851, + 0.027557701 0.129473 -0.038982298, + 0.0302257 0.12890001 -0.037509698, + 0.0302257 0.130952 -0.038749401, + 0.0328326 0.130357 -0.037132598, + 0.0328326 0.13248201 -0.038312498, + 0.035366699 0.13187 -0.0365544, + 0.035366699 0.134067 -0.0376723, + 0.0378174 0.133449 -0.035778899, + 0.0378174 0.135717 -0.0368325, + 0.040174201 0.13509899 -0.0348108, + 0.040174201 0.13744 -0.035799202, + 0.0424264 0.13682701 -0.033656102, + 0.0424264 0.139239 -0.0345782, + 0.044564299 0.13864 -0.032321099, + 0.044564299 0.141119 -0.033176102, + 0.0465803 0.140542 -0.030814899, + 0.0465803 0.143089 -0.0316021, + 0.048467699 0.142538 -0.0291472, + 0.048467699 0.145151 -0.029865401, + 0.050219599 0.144633 -0.027327601, + 0.050219599 0.147311 -0.027976001, + 0.051830001 0.14683101 -0.0253658, + 0.051830001 0.149572 -0.025943501, + 0.0532961 0.14913499 -0.023272701, + 0.0532961 0.15193599 -0.0237792, + 0.0546159 0.148689 -0.020552499, + 0.0546159 0.154406 -0.0214958, + 0.055787299 0.15406699 -0.018739101, + 0.055787299 0.15990201 -0.0194056, + 0.056809202 0.15967201 -0.016624101, + 0.0576833 0.15944199 -0.0138277, + 0.056809202 0.153724 -0.0159567, + 0.055787299 0.148237 -0.017795, + 0.0546159 0.142998 -0.019324001, + 0.055787299 0.142435 -0.0165655, + 0.056809202 0.147782 -0.0150116, + 0.0576833 0.15338001 -0.0131595, + 0.058412101 0.15921 -0.0110273, + 0.058986001 0.171507 -0.00877917, + 0.059372 0.171505 -0.0065220501, + 0.058998398 0.16525801 -0.0086359698, + 0.0588759 0.171508 -0.0094234003, + 0.058412101 0.16537499 -0.011429, + 0.058383498 0.171509 -0.0116419, + 0.0582381 0.17151 -0.0122969, + 0.0576833 0.165492 -0.0142287, + 0.056809202 0.165609 -0.0170244, + 0.057460099 0.17151199 -0.0151357, + 0.0557741 0.171516 -0.019943999, + 0.056543902 0.171514 -0.017932899, + 0.055787299 0.16572601 -0.019805299, + 0.056661699 0.171514 -0.017573399, + 0.0546159 0.16013101 -0.022161501, + 0.0532961 0.154741 -0.024215, + 0.051830001 0.152319 -0.0264496, + 0.050219599 0.14999899 -0.0285533, + 0.048467699 0.14777701 -0.0305133, + 0.0465803 0.14565299 -0.032319698, + 0.044564299 0.143619 -0.033962701, + 0.0424264 0.141671 -0.0354327, + 0.040174201 0.139806 -0.036720801, + 0.0378174 0.138016 -0.037820201, + 0.035366699 0.136297 -0.038725201, + 0.0328326 0.13464101 -0.039429698, + 0.0302257 0.13304301 -0.039928701, + 0.027557701 0.131494 -0.0402213, + 0.0248404 0.129989 -0.040307999, + 0.0220857 0.128521 -0.040188801, + 0.019305199 0.127083 -0.039864901, + 0.0165099 0.12566701 -0.039340299, + 0.0137106 0.124272 -0.038619898, + 0.0109179 0.122889 -0.037708402, + 0.0081428103 0.121514 -0.036610998, + 0.0053973799 0.120143 -0.035335299, + 0.0053973799 0.117249 -0.032038201, + 0.00268824 0.117358 -0.032223102, + 0.00268824 0.11471 -0.028792201, + 0 0.114749 -0.0288518, + 0 0.112351 -0.0253148, + -0.00268824 0.11471 -0.0287917, + -0.00268824 0.117358 -0.032222901, + -0.0053973799 0.117249 -0.032037798, + -0.0053973799 0.118667 -0.033704799, + -0.051830001 0.160577 -0.0275851, + -0.050219599 0.15809099 -0.029892299, + -0.051830001 0.155066 -0.026914701, + -0.0137073 0.171545 -0.0562611, + -0.0122706 0.171545 -0.056583501, + -0.0137106 0.169404 -0.056247499, + -0.058412101 0.15921199 -0.0110678, + -0.058412101 0.165379 -0.0114622, + -0.0576833 0.15944301 -0.0138677, + -0.0576833 0.153375 -0.0131927, + -0.056809202 0.15371899 -0.0159893, + -0.056809202 0.14777 -0.015035, + -0.055787299 0.14822599 -0.0178179, + -0.055787299 0.142418 -0.0165854, + -0.0546159 0.14298201 -0.019343499, + -0.0546159 0.137339 -0.017835701, + -0.0546159 0.14867701 -0.020575, + -0.055787299 0.154062 -0.018771101, + -0.056809202 0.159674 -0.016663499, + -0.0576833 0.16549601 -0.0142615, + -0.0581921 0.17151 -0.0124812, + -0.0583972 0.171509 -0.0115706, + -0.0583813 0.171509 -0.0116414, + -0.0583959 0.19150899 -0.0116288, + -0.058839001 0.171508 -0.0096097104, + -0.058998398 0.165263 -0.0086695198, + -0.059445001 0.16514701 -0.00589443, + -0.059344199 0.171505 -0.00670995, + -0.058998398 0.15898199 -0.0082745701, + -0.058412101 0.15302899 -0.0103918, + -0.0576833 0.147312 -0.0122372, + -0.056809202 0.14184999 -0.0138015, + -0.055787299 0.136663 -0.0150766, + -0.0546159 0.131771 -0.016054999, + -0.0532961 0.12985601 -0.017787, + -0.0532961 0.12719101 -0.0167291, + -0.051830001 0.128066 -0.0194041, + -0.051830001 0.125488 -0.018281, + -0.050219599 0.126398 -0.0208955, + -0.050219599 0.123907 -0.019708799, + -0.048467699 0.124845 -0.022251399, + -0.048467699 0.122444 -0.0210036, + -0.0465803 0.123403 -0.0234634, + -0.0465803 0.121093 -0.0221569, + -0.044564299 0.122066 -0.024523599, + -0.044564299 0.119847 -0.0231607, + -0.0424264 0.120826 -0.025423801, + -0.0424264 0.118702 -0.024007101, + -0.040174201 0.119677 -0.0261568, + -0.040174201 0.117647 -0.024688801, + -0.0378174 0.11861 -0.026717801, + -0.0378174 0.116675 -0.025201101, + -0.035366699 0.11762 -0.0271025, + -0.035366699 0.115778 -0.0255397, + -0.0328326 0.116694 -0.027306801, + -0.0328326 0.114946 -0.025702599, + -0.0302257 0.115824 -0.027329, + -0.0302257 0.114165 -0.0256947, + -0.027557701 0.114998 -0.027176101, + -0.027557701 0.113424 -0.025514999, + -0.0248404 0.114205 -0.0268474, + -0.0248404 0.112718 -0.0251594, + -0.0220857 0.113441 -0.026339199, + -0.0220857 0.112039 -0.0246247, + -0.019305199 0.112696 -0.0256499, + -0.019305199 0.11138 -0.0239101, + -0.0165099 0.111966 -0.0247823, + -0.0165099 0.110733 -0.0230189, + -0.0137106 0.108962 -0.020126, + -0.0137106 0.111243 -0.023740999, + -0.0109179 0.109406 -0.0206958, + -0.0137106 0.112454 -0.0255096, + -0.0165099 0.113258 -0.026526799, + -0.019305199 0.114071 -0.0273684, + -0.0220857 0.114899 -0.028030001, + -0.0248404 0.115748 -0.0285096, + -0.027557701 0.116622 -0.0288096, + -0.0302257 0.117535 -0.028930999, + -0.0328326 0.118495 -0.0288675, + -0.035366699 0.119513 -0.0286172, + -0.0378174 0.120596 -0.028184, + -0.040174201 0.121755 -0.027572, + -0.0424264 0.122995 -0.026785299, + -0.044564299 0.124326 -0.025828799, + -0.0465803 0.125752 -0.0247101, + -0.048467699 0.12728199 -0.0234371, + -0.050219599 0.128922 -0.022017799, + -0.051830001 0.130676 -0.0204613, + -0.0532961 0.132549 -0.018778, + -0.0532961 0.135267 -0.0197016, + -0.051830001 0.133314 -0.021451499, + -0.050219599 0.131477 -0.0230741, + -0.048467699 0.12975401 -0.024558499, + -0.0465803 0.12813801 -0.0258948, + -0.044564299 0.126625 -0.027074501, + -0.0424264 0.12520701 -0.0280893, + -0.040174201 0.123878 -0.0289321, + -0.0378174 0.122631 -0.029597601, + -0.035366699 0.121458 -0.030081799, + -0.0328326 0.12035 -0.030380299, + -0.0302257 0.119301 -0.0304897, + -0.027557701 0.118301 -0.030409699, + -0.0248404 0.117342 -0.0301426, + -0.0220857 0.116413 -0.0296934, + -0.019305199 0.115504 -0.029061601, + -0.0165099 0.114611 -0.028248699, + -0.0137106 0.113727 -0.0272581, + -0.0109179 0.114104 -0.027846299, + -0.0137106 0.11506 -0.0289829, + -0.0165099 0.116022 -0.029944099, + -0.019305199 0.116993 -0.0307259, + -0.0220857 0.11798 -0.031325702, + -0.0248404 0.11899 -0.0317409, + -0.027557701 0.120034 -0.031966601, + -0.0302257 0.121121 -0.032000899, + -0.0328326 0.122257 -0.031843301, + -0.035366699 0.123451 -0.031493898, + -0.0378174 0.124711 -0.030956401, + -0.040174201 0.12604401 -0.030234899, + -0.0424264 0.12745801 -0.029333901, + -0.044564299 0.128961 -0.028258201, + -0.0465803 0.130558 -0.027015399, + -0.048467699 0.132256 -0.0256141, + -0.050219599 0.13406099 -0.0240638, + -0.051830001 0.135977 -0.0223745, + -0.0532961 0.138006 -0.0205575, + -0.0532961 0.143539 -0.0220642, + -0.051830001 0.14136501 -0.024017001, + -0.0532961 0.149124 -0.0232946, + -0.051830001 0.146817 -0.025384899, + -0.0546159 0.154402 -0.021527199, + -0.055787299 0.159905 -0.0194443, + -0.056809202 0.16561399 -0.0170567, + -0.0574052 0.17151199 -0.0153175, + -0.057668298 0.17151099 -0.0143692, + -0.056669399 0.191514 -0.01756, + -0.051438902 0.191523 -0.028735099, + -0.0528998 0.17152099 -0.026176101, + -0.054342099 0.19151901 -0.023282399, + -0.051818501 0.17152201 -0.028082499, + -0.0514476 0.171523 -0.028736399, + -0.051830001 0.16607 -0.0279765, + -0.048459999 0.171527 -0.033224698, + -0.048175599 0.171527 -0.033628099, + -0.048467699 0.16891199 -0.033208098, + -0.0479904 0.19152699 -0.0338604, + -0.049871601 0.171525 -0.031222399, + -0.050219599 0.166179 -0.0305831, + 0.0484627 0.171527 -0.033226699, + 0.0479904 0.19152699 -0.0338604, + 0.049977001 0.171525 -0.0310644, + 0.048288502 0.171527 -0.033475399, + 0.048467699 0.168909 -0.033190999, + 0.050219599 0.16617499 -0.030554499, + -0.048467699 0.163647 -0.032956399, + -0.048467699 0.16628499 -0.033116899, + -0.0465803 0.1638 -0.035406802, + -0.0465803 0.161204 -0.0351771, + -0.044564299 0.16139901 -0.037533801, + -0.044564299 0.158847 -0.0372352, + -0.0424264 0.159079 -0.0394876, + -0.0424264 0.156571 -0.039119899, + -0.040174201 0.156835 -0.041258398, + -0.040174201 0.15437201 -0.0408215, + -0.0378174 0.154661 -0.0428386, + -0.0378174 0.152243 -0.042332102, + -0.035366699 0.15255199 -0.044220801, + -0.035366699 0.150181 -0.0436447, + -0.0328326 0.15050299 -0.045398101, + -0.0328326 0.148178 -0.044752602, + -0.0302257 0.148508 -0.046364699, + -0.0302257 0.146228 -0.0456503, + -0.027557701 0.146559 -0.047118101, + -0.027557701 0.144327 -0.046335399, + -0.0248404 0.144651 -0.047656901, + -0.0248404 0.14246701 -0.0468066, + -0.0220857 0.14277899 -0.047979701, + -0.0220857 0.140644 -0.0470622, + -0.019305199 0.140936 -0.048085701, + -0.019305199 0.13885 -0.047102001, + -0.0165099 0.139118 -0.047977399, + -0.0165099 0.13708 -0.046928, + -0.0137106 0.13732 -0.047658101, + -0.0137106 0.135331 -0.046544001, + -0.0109179 0.135537 -0.047131199, + -0.0109179 0.133597 -0.045954499, + -0.0081428103 0.133763 -0.046401899, + -0.0081428103 0.131873 -0.0451652, + -0.0053973799 0.13199501 -0.045477699, + -0.0053973799 0.130154 -0.044183299, + -0.00268824 0.13022999 -0.044366501, + -0.00268824 0.128438 -0.043016698, + 0 0.128465 -0.043076299, + 0 0.12672199 -0.041673601, + 0.00268824 0.12843899 -0.043015499, + 0.00268824 0.13023099 -0.044365101, + 0.0053973799 0.130156 -0.044180501, + 0.0053973799 0.131997 -0.045474701, + 0.0081428103 0.13187601 -0.0451607, + 0.0081428103 0.133766 -0.046397202, + 0.0109179 0.13360199 -0.045948301, + 0.0109179 0.13554101 -0.0471249, + 0.0137106 0.135336 -0.046535999, + 0.0137106 0.137325 -0.047650401, + 0.0165099 0.137086 -0.046918701, + 0.0165099 0.13912401 -0.0479686, + 0.019305199 0.13885701 -0.0470916, + 0.019305199 0.140944 -0.048076201, + 0.0220857 0.140652 -0.0470514, + 0.0220857 0.14278699 -0.047969799, + 0.0248404 0.14247601 -0.046795499, + 0.0248404 0.14466 -0.047646899, + 0.027557701 0.144337 -0.046324302, + 0.027557701 0.146568 -0.047107801, + 0.0302257 0.146238 -0.045639101, + 0.0302257 0.148517 -0.046353899, + 0.0328326 0.14818799 -0.0447408, + 0.0328326 0.15051199 -0.045386098, + 0.035366699 0.15019 -0.043631598, + 0.035366699 0.15256 -0.044206299, + 0.0378174 0.15225101 -0.042316601, + 0.0378174 0.154667 -0.0428202, + 0.040174201 0.154378 -0.040801998, + 0.040174201 0.156838 -0.041235302, + 0.0424264 0.156574 -0.039095499, + 0.0424264 0.15908 -0.03946, + 0.044564299 0.158848 -0.037206098, + 0.044564299 0.16139799 -0.0375029, + 0.0465803 0.161203 -0.035144798, + 0.0465803 0.16379701 -0.035375401, + 0.048467699 0.163644 -0.032923698, + 0.048467699 0.166281 -0.033089299, + 0.0465803 0.166384 -0.0355407, + 0.044564299 0.16394401 -0.037733201, + 0.0424264 0.161584 -0.039756499, + 0.040174201 0.1593 -0.041599501, + 0.0378174 0.157086 -0.043253198, + 0.035366699 0.154938 -0.0447095, + 0.0328326 0.15284701 -0.0459604, + 0.0302257 0.15080801 -0.046998698, + 0.027557701 0.148816 -0.0478223, + 0.0248404 0.146865 -0.048430201, + 0.0220857 0.14494701 -0.048820902, + 0.019305199 0.143059 -0.048994299, + 0.0165099 0.141194 -0.048953, + 0.0137106 0.139348 -0.048700102, + 0.0109179 0.13751601 -0.048239, + 0.0081428103 0.13569599 -0.047573701, + 0.0053973799 0.133881 -0.046711199, + 0.00268824 0.13206799 -0.045659401, + 0 0.130255 -0.044425901, + -0.00268824 0.13206699 -0.045660902, + -0.0053973799 0.13387901 -0.046714298, + -0.0081428103 0.135693 -0.047578398, + -0.0109179 0.137512 -0.048245098, + -0.0137106 0.13934299 -0.0487074, + -0.0165099 0.141188 -0.048961099, + -0.019305199 0.143051 -0.049002901, + -0.0220857 0.14493901 -0.048829801, + -0.0248404 0.14685699 -0.048439398, + -0.027557701 0.148808 -0.047832198, + -0.0302257 0.1508 -0.0470098, + -0.0328326 0.152841 -0.045973901, + -0.035366699 0.15493301 -0.0447267, + -0.0378174 0.157083 -0.043274902, + -0.040174201 0.159299 -0.041625701, + -0.0424264 0.161586 -0.039785899, + -0.044564299 0.163947 -0.037763201, + -0.0465803 0.16638801 -0.035567202, + -0.050219599 0.16079199 -0.0301922, + -0.051438499 0.171523 -0.028750701, + -0.050209399 0.171524 -0.0306895, + -0.055419099 0.171517 -0.020857399, + -0.058983799 0.171507 -0.0087787397, + -0.059503399 0.191504 -0.0055514099, + -0.059431799 0.171505 -0.0060046101, + -0.0594863 0.17150401 -0.00556522, + -0.059706699 0.17150301 -0.0037888801, + -0.059757002 0.165032 -0.0031489199, + -0.059445001 0.158751 -0.0054989201, + -0.058998398 0.152685 -0.0075976802, + -0.058412101 0.146853 -0.0094353501, + -0.0576833 0.141278 -0.0110026, + -0.056809202 0.13598099 -0.0122914, + -0.055787299 0.130981 -0.0132945, + -0.0546159 0.12629899 -0.0140046, + -0.0532961 0.124555 -0.015605, + -0.051830001 0.122942 -0.017093301, + -0.050219599 0.121452 -0.01846, + -0.048467699 0.120081 -0.0196958, + -0.0465803 0.118824 -0.020792499, + -0.044564299 0.117674 -0.021742299, + -0.0424264 0.116625 -0.0225372, + -0.040174201 0.115666 -0.023170101, + -0.0378174 0.114792 -0.023636101, + -0.035366699 0.113991 -0.0239332, + -0.0328326 0.113251 -0.0240674, + -0.0302257 0.112557 -0.024034999, + -0.027557701 0.111903 -0.0238303, + -0.0248404 0.111286 -0.023449499, + -0.0220857 0.110694 -0.022890599, + -0.019305199 0.110124 -0.022152901, + -0.0165099 0.108411 -0.019417699, + -0.0137106 0.107778 -0.018302999, + -0.0109179 0.107024 -0.0170619, + -0.0081428103 0.107387 -0.0174853, + -0.0081428103 0.104836 -0.0139376, + -0.0053973799 0.105107 -0.0142246, + -0.0053973799 0.102382 -0.0107762, + -0.00268824 0.102552 -0.0109386, + -0.00268824 0.099652201 -0.0076088398, + 0 0.099710897 -0.0076597701, + 0 0.096640401 -0.00446577, + 0.00268824 0.099652998 -0.0076094, + 0.00268824 0.102553 -0.0109395, + 0.0053973799 0.102384 -0.0107779, + 0.0053973799 0.105108 -0.0142262, + 0.0081428103 0.104836 -0.01394, + 0.0081428103 0.107387 -0.017486701, + 0.0109179 0.107024 -0.0170638, + 0.0109179 0.109406 -0.0206967, + 0.0137106 0.107778 -0.0183047, + 0.0137106 0.111243 -0.023743, + 0.0137106 0.113728 -0.0272604, + 0.0165099 0.111966 -0.0247852, + 0.0109179 0.111652 -0.024323501, + 0.0081428103 0.109743 -0.0211305, + 0.0053973799 0.107641 -0.0177822, + 0.00268824 0.105267 -0.0143941, + 0 0.102607 -0.010992, + -0.00268824 0.105267 -0.0143933, + -0.0053973799 0.107641 -0.0177812, + -0.0081428103 0.109744 -0.021129901, + -0.0109179 0.111652 -0.024321901, + -0.0081428103 0.111964 -0.024764501, + -0.0053973799 0.109979 -0.021433201, + -0.00268824 0.10779 -0.017955, + 0 0.10532 -0.0144485, + 0.00268824 0.10779 -0.017955501, + 0.0053973799 0.109979 -0.0214337, + 0.0081428103 0.111964 -0.0247656, + 0.0109179 0.114104 -0.0278481, + 0.0137106 0.115061 -0.028984601, + 0.0165099 0.114612 -0.0282507, + 0.0165099 0.116022 -0.029945301, + 0.019305199 0.115504 -0.029062999, + 0.019305199 0.116993 -0.0307265, + 0.0220857 0.116413 -0.029694101, + 0.0220857 0.11798 -0.031326801, + 0.0248404 0.117342 -0.030143799, + 0.0248404 0.118992 -0.031739801, + 0.027557701 0.118303 -0.0304085, + 0.027557701 0.120038 -0.031961601, + 0.0302257 0.119306 -0.0304842, + 0.0302257 0.121128 -0.0319921, + 0.0328326 0.120358 -0.030370699, + 0.0328326 0.122266 -0.031830698, + 0.035366699 0.121468 -0.0300682, + 0.035366699 0.123463 -0.031477701, + 0.0378174 0.122644 -0.0295802, + 0.0378174 0.124724 -0.030936901, + 0.040174201 0.123892 -0.0289113, + 0.040174201 0.126059 -0.0302126, + 0.0424264 0.125222 -0.028065801, + 0.0424264 0.127474 -0.0293095, + 0.044564299 0.126642 -0.0270488, + 0.044564299 0.128978 -0.028232399, + 0.0465803 0.12815601 -0.025867799, + 0.0465803 0.130576 -0.026989199, + 0.048467699 0.12977301 -0.024531201, + 0.048467699 0.132274 -0.0255883, + 0.050219599 0.131496 -0.023047401, + 0.050219599 0.13407999 -0.024039101, + 0.051830001 0.133333 -0.021426, + 0.051830001 0.135996 -0.022351401, + 0.0532961 0.135287 -0.0196779, + 0.0532961 0.138024 -0.020536, + 0.0546159 0.13735799 -0.017813699, + 0.0546159 0.14017101 -0.018603699, + 0.055787299 0.136682 -0.015054, + 0.0546159 0.134564 -0.016954999, + 0.0532961 0.132569 -0.018751699, + 0.051830001 0.130696 -0.020433599, + 0.050219599 0.128942 -0.0219894, + 0.048467699 0.12730099 -0.023408899, + 0.0465803 0.12577 -0.0246833, + 0.044564299 0.124342 -0.025804101, + 0.0424264 0.12301 -0.0267634, + 0.040174201 0.121768 -0.0275534, + 0.0378174 0.120607 -0.0281695, + 0.035366699 0.119522 -0.028606899, + 0.0328326 0.118501 -0.0288614, + 0.0302257 0.117537 -0.028929699, + 0.027557701 0.116623 -0.028811, + 0.0248404 0.115748 -0.028510399, + 0.0220857 0.114899 -0.028031601, + 0.019305199 0.114072 -0.027370701, + 0.0165099 0.113259 -0.026529601, + 0.019305199 0.112696 -0.0256531, + 0.0220857 0.113441 -0.0263419, + 0.0248404 0.114205 -0.026849199, + 0.027557701 0.114998 -0.027177, + 0.0302257 0.115824 -0.027330499, + 0.0328326 0.116696 -0.027305299, + 0.035366699 0.117625 -0.0270961, + 0.0378174 0.118619 -0.0267068, + 0.040174201 0.119689 -0.026141301, + 0.0424264 0.12084 -0.025404301, + 0.044564299 0.122082 -0.0245005, + 0.0465803 0.12342 -0.0234375, + 0.048467699 0.124863 -0.022223501, + 0.050219599 0.126417 -0.0208664, + 0.051830001 0.128086 -0.0193749, + 0.0532961 0.129876 -0.0177586, + 0.0546159 0.131791 -0.016028199, + 0.059445001 0.15875 -0.0054576802, + 0.059757002 0.15852299 -0.0027113899, + 0.059445001 0.152348 -0.0047869799, + 0.058998398 0.15268999 -0.0075637801, + 0.058998398 0.14640699 -0.0066158799, + 0.058412101 0.146865 -0.0094113704, + 0.058412101 0.140723 -0.0081787398, + 0.0576833 0.141295 -0.010982, + 0.0576833 0.135315 -0.0094681997, + 0.056809202 0.13600001 -0.0122685, + 0.056809202 0.13020501 -0.0104802, + 0.055787299 0.13100199 -0.0132671, + 0.048467699 0.106853 -0.0107047, + 0.0465803 0.108189 -0.0131796, + 0.048467699 0.108938 -0.0123237, + 0.050219599 0.107614 -0.0097675398, + 0.050219599 0.109807 -0.0113419, + 0.051830001 0.108504 -0.00871519, + 0.051830001 0.110804 -0.0102425, + 0.0532961 0.10953 -0.0075567202, + 0.0532961 0.111935 -0.0090343803, + 0.0546159 0.110696 -0.00630122, + 0.0546159 0.113205 -0.0077267401, + 0.055787299 0.112009 -0.0049578799, + 0.055787299 0.114618 -0.00632883, + 0.056809202 0.113471 -0.0035357601, + 0.056809202 0.116178 -0.0048498102, + 0.0576833 0.117887 -0.00329822, + -0.0597477 0.17149401 0.0075332499, + -0.059803601 0.17149501 0.0067658201, + -0.059757002 0.16458 0.0076464801, + -0.0165099 0.0989765 -0.00729982, + -0.0165099 0.097448699 -0.0056958701, + -0.019305199 0.098145299 -0.0065421001, + -0.019305199 0.099655896 -0.0081654796, + -0.0220857 0.0987112 -0.0072608502, + -0.0220857 0.100205 -0.0089015402, + -0.0248404 0.099153697 -0.0078442497, + -0.0248404 0.100634 -0.0095000304, + -0.027557701 0.099485703 -0.0082875304, + -0.027557701 0.100957 -0.0099565098, + -0.0302257 0.099722102 -0.0085876202, + -0.0302257 0.101188 -0.0102685, + -0.0328326 0.099877603 -0.0087425802, + -0.0328326 0.101343 -0.0104355, + -0.035366699 0.099967897 -0.0087532401, + -0.035366699 0.10144 -0.0104617, + -0.0378174 0.100013 -0.0086275199, + -0.0378174 0.10149 -0.0103328, + -0.040174201 0.100024 -0.0083530396, + -0.040174201 0.101572 -0.0100227, + -0.0424264 0.100079 -0.0079050101, + -0.0424264 0.101738 -0.0095611103, + -0.044564299 0.100229 -0.0073143002, + -0.044564299 0.101996 -0.0089629199, + -0.0465803 0.10048 -0.0065989601, + -0.0465803 0.102352 -0.0082423501, + -0.048467699 0.102812 -0.00741529, + -0.0165099 0.101906 -0.010613, + -0.0165099 0.100464 -0.0089393603, + -0.019305199 0.101122 -0.00982391, + -0.019305199 0.102542 -0.0115153, + -0.0220857 0.101653 -0.0105763, + -0.0220857 0.103056 -0.0122827, + -0.0248404 0.102069 -0.0111889, + -0.0248404 0.103456 -0.0129084, + -0.027557701 0.102382 -0.0116579, + -0.027557701 0.10376 -0.0133899, + -0.0302257 0.102609 -0.011982, + -0.0302257 0.103984 -0.0137292, + -0.0328326 0.102766 -0.0121642, + -0.0328326 0.104136 -0.0139067, + -0.035366699 0.102863 -0.0121863, + -0.035366699 0.104298 -0.0138895, + -0.0378174 0.10298 -0.0120198, + -0.0378174 0.104523 -0.0137051, + -0.040174201 0.103171 -0.0116939, + -0.040174201 0.10482 -0.0133665, + -0.0424264 0.103445 -0.0112221, + -0.0424264 0.105196 -0.0128837, + -0.044564299 0.103806 -0.0106156, + -0.044564299 0.105657 -0.0122684, + -0.0465803 0.104262 -0.0098892404, + -0.0465803 0.106208 -0.0115357, + -0.048467699 0.106853 -0.0107022, + -0.055787299 0.111991 -0.0049835299, + -0.055787299 0.109424 -0.00355193, + -0.056809202 0.113451 -0.00356511, + -0.0546159 0.110681 -0.0063222498, + -0.0546159 0.108218 -0.0048373202, + -0.0532961 0.109517 -0.0075722798, + -0.0532961 0.107161 -0.0060365601, + -0.051830001 0.108496 -0.0087245498, + -0.051830001 0.106248 -0.0071402998, + -0.050219599 0.10761 -0.0097696995, + -0.050219599 0.105472 -0.0081429603, + -0.0137106 0.101138 -0.0095847603, + -0.0137106 0.102561 -0.011271, + -0.0165099 0.103303 -0.0123184, + -0.019305199 0.103916 -0.0132371, + -0.0220857 0.10441 -0.0140186, + -0.0248404 0.104797 -0.0146573, + -0.027557701 0.105092 -0.015154, + -0.0302257 0.105307 -0.0154881, + -0.0328326 0.105521 -0.015625, + -0.035366699 0.105787 -0.015588, + -0.0378174 0.106116 -0.0153888, + -0.040174201 0.106515 -0.0150367, + -0.0424264 0.106991 -0.014542, + -0.044564299 0.107546 -0.0139171, + -0.0465803 0.108188 -0.0131773, + -0.048467699 0.108934 -0.0123258, + -0.050219599 0.109799 -0.011351, + -0.051830001 0.110792 -0.0102576, + -0.0532961 0.11192 -0.0090549001, + -0.0546159 0.113187 -0.0077518602, + -0.055787299 0.114598 -0.0063576498, + -0.056809202 0.118899 -0.00613624, + -0.0576833 0.117865 -0.0033314601, + -0.0576833 0.123566 -0.0056519499, + -0.058412101 0.122647 -0.00284501, + -0.058412101 0.128581 -0.00490154, + -0.058998398 0.127781 -0.00210282, + -0.058998398 0.133922 -0.00388997, + -0.059445001 0.133241 -0.0011102, + -0.059445001 0.139566 -0.0026247001, + -0.059757002 0.13900401 0.00012431999, + -0.059757002 0.14549001 -0.00111454, + -0.0599402 0.145046 0.00159714, + -0.0599402 0.15166999 0.00063649297, + -0.059999999 0.151338 0.0033262901, + -0.059999999 0.158079 0.00264592, + -0.0599402 0.157857 0.00533491, + -0.0599402 0.164693 0.0049371198, + -0.059930101 0.171496 0.0050316099, + -0.059821099 0.191495 0.0067830202, + -0.0081428103 0.0784325 0.0092367698, + -0.0109179 0.079817399 0.0083335396, + -0.0081428103 0.082199603 0.0069623301, + -0.0053973799 0.078788698 0.0091049401, + -0.0053973799 0.074928701 0.0112088, + -0.00268824 0.075134903 0.011148, + -0.00268824 0.071191698 0.0130617, + 0 0.0712571 0.0130472, + 0 0.0672471 0.0147569, + 0.00268824 0.071191698 0.0130617, + 0.00268824 0.075135797 0.0111478, + 0.0053973799 0.074930497 0.0112084, + 0.0053973799 0.078791402 0.0091049997, + 0.0081428103 0.078436501 0.0092368601, + -0.054602899 0.171479 0.026971299, + -0.055455498 0.17148 0.0250427, + -0.0546159 0.163765 0.027092099, + -0.055579402 0.19148 0.024756201, + -0.054265399 0.171478 0.027734799, + -0.0532961 0.163652 0.0298099, + -0.0546159 0.15602501 0.0274949, + -0.055787299 0.156253 0.0247391, + -0.055787299 0.148615 0.025426099, + -0.056809202 0.148958 0.0226437, + -0.056809202 0.141441 0.023612101, + -0.0576833 0.141899 0.020814, + -0.0576833 0.13452201 0.0220611, + -0.058412101 0.135095 0.019257899, + -0.058412101 0.127877 0.020781299, + -0.058998398 0.128563 0.017983699, + -0.058998398 0.121524 0.0197811, + -0.059445001 0.122319 0.0169998, + -0.059445001 0.115479 0.0190688, + -0.059757002 0.116379 0.0163156, + -0.059757002 0.109757 0.018651601, + -0.0599402 0.110759 0.015933, + -0.0599402 0.104373 0.0185252, + -0.059999999 0.105482 0.015825, + -0.059999999 0.0993523 0.018659901, + -0.0599402 0.100578 0.015956299, + -0.0599402 0.094724298 0.0190196, + -0.059757002 0.096079104 0.0162901, + -0.059757002 0.090520903 0.0195641, + -0.059445001 0.092017002 0.0167915, + -0.059445001 0.086696804 0.0200666, + -0.058998398 0.0883395 0.017265201, + -0.058998398 0.083177596 0.020382199, + -0.058412101 0.084973902 0.0175812, + -0.058412101 0.080025896 0.020539301, + -0.0576833 0.081980802 0.0177665, + -0.0576833 0.077266403 0.0205941, + -0.056809202 0.0793809 0.0178778, + -0.056809202 0.077064 0.0192494, + -0.055787299 0.079247698 0.016579499, + -0.055787299 0.076975502 0.017914699, + -0.0532961 0.074870899 0.016571799, + -0.0532961 0.072621197 0.0177224, + -0.0546159 0.074726097 0.017850701, + -0.051830001 0.075086802 0.0153615, + -0.051830001 0.072881296 0.016494101, + -0.050219599 0.075358503 0.0142353, + -0.050219599 0.073205002 0.0153554, + -0.048467699 0.075677 0.0132089, + -0.048467699 0.0735991 0.0143173, + -0.0465803 0.076046303 0.0122918, + -0.0465803 0.0739979 0.013359, + -0.044564299 0.076403402 0.0114656, + -0.044564299 0.074374102 0.0124885, + -0.0424264 0.076721899 0.0107382, + -0.0424264 0.074720502 0.0117252, + -0.040174201 0.076993302 0.0101264, + -0.040174201 0.075020202 0.0110856, + -0.0378174 0.077202298 0.0096433498, + -0.0378174 0.075257301 0.0105845, + -0.035366699 0.077332899 0.0093012797, + -0.035366699 0.075413503 0.0102331, + -0.0328326 0.077366203 0.0091089103, + -0.0328326 0.075467199 0.0100386, + -0.0302257 0.077281602 0.0090708099, + -0.0302257 0.075396903 0.0100032, + -0.027557701 0.077061497 0.0091848401, + -0.027557701 0.075183503 0.0101224, + -0.0248404 0.076688997 0.0094442302, + -0.0248404 0.074810199 0.0103866, + -0.0220857 0.076148301 0.0098378602, + -0.0220857 0.074261203 0.0107819, + -0.019305199 0.075426303 0.0103503, + -0.019305199 0.073525101 0.0112913, + -0.0165099 0.074516401 0.0109623, + -0.0165099 0.072596803 0.0118959, + -0.0137106 0.073416203 0.0116545, + -0.0137106 0.071475402 0.0125717, + -0.0109179 0.072126403 0.012403, + -0.0109179 0.070161298 0.0132896, + -0.0109179 0.074075401 0.0114602, + -0.0137106 0.075343102 0.010688, + -0.0109179 0.077922799 0.0094254296, + -0.0081428103 0.0745776 0.0113122, + -0.0165099 0.076422997 0.0099809999, + -0.019305199 0.0773158 0.0093591698, + -0.0220857 0.078025401 0.0088422699, + -0.0248404 0.078560099 0.0084481398, + -0.027557701 0.078933403 0.0081897397, + -0.0302257 0.079161197 0.0080755604, + -0.0328326 0.079259597 0.0081101004, + -0.035366699 0.079245299 0.0082930801, + -0.0378174 0.079136699 0.00861861, + -0.040174201 0.078950502 0.0090766, + -0.0424264 0.078702301 0.0096562197, + -0.044564299 0.078399703 0.0103439, + -0.0465803 0.078067601 0.011133, + -0.048467699 0.0777665 0.0120395, + -0.050219599 0.077495903 0.0130546, + -0.051830001 0.077265099 0.0141645, + -0.0532961 0.077090397 0.0153549, + -0.0546159 0.076988801 0.0166106, + -0.055787299 0.0746684 0.0191823, + -0.056809202 0.074712098 0.0205492, + -0.0576833 0.074868597 0.0219333, + -0.058412101 0.075148799 0.0233145, + -0.058998398 0.078075603 0.023305601, + -0.059445001 0.081392698 0.023165699, + -0.059757002 0.085071698 0.022838, + -0.0599402 0.089044698 0.0223001, + -0.059999999 0.0933799 0.0217281, + -0.0599402 0.098126397 0.021363599, + -0.059757002 0.103255 0.0212464, + -0.059445001 0.108741 0.021406701, + -0.058998398 0.114569 0.021851599, + -0.058412101 0.120724 0.0225801, + -0.0576833 0.12719101 0.023585699, + -0.056809202 0.13395099 0.0248603, + -0.055787299 0.140985 0.0263955, + -0.0546159 0.148276 0.028182801, + -0.0532961 0.155801 0.030213499, + -0.052944701 0.17147601 0.0303654, + -0.052960001 0.17147601 0.0303348, + -0.051830001 0.16354001 0.0324785, + -0.050210599 0.171472 0.0349635, + -0.0497806 0.19147199 0.035647102, + -0.051496498 0.17147399 0.032928001, + -0.049775898 0.171472 0.035627801, + -0.048461299 0.17147 0.037498701, + -0.048467699 0.163325 0.037620898, + 0.0465803 0.163219 0.040098701, + 0.046066999 0.171468 0.040566999, + 0.044564299 0.16312 0.042454999, + 0.0576833 0.067480102 0.0254851, + 0.056809202 0.0699123 0.022918001, + 0.0576833 0.0699718 0.024373701, + 0.058412101 0.0676139 0.0269868, + 0.058412101 0.070156701 0.0258395, + 0.058998398 0.067883298 0.028485401, + 0.058998398 0.070475399 0.027295601, + 0.059445001 0.068295904 0.0299601, + 0.059445001 0.070935801 0.0287205, + 0.059757002 0.068859003 0.031388301, + 0.059757002 0.074220099 0.028765, + 0.0599402 0.072328202 0.031448402, + 0.0599402 0.077886 0.0286266, + 0.059999999 0.076156899 0.031323001, + 0.059999999 0.081877202 0.0282821, + 0.0599402 0.080285899 0.030995799, + 0.0599402 0.086115897 0.027726799, + 0.059757002 0.084639601 0.030462701, + 0.059757002 0.090690702 0.0271769, + 0.059445001 0.089317799 0.029943001, + 0.059445001 0.095656298 0.026872599, + 0.058998398 0.094390802 0.0296636, + 0.058998398 0.100998 0.026822099, + 0.058412101 0.099845201 0.029627001, + 0.058412101 0.106703 0.027027899, + 0.0576833 0.105666 0.029836699, + 0.0576833 0.112756 0.0274921, + 0.056809202 0.111839 0.030294999, + 0.056809202 0.119143 0.028215401, + 0.055787299 0.118346 0.0310017, + 0.055787299 0.125843 0.029193999, + 0.0546159 0.125167 0.031953301, + 0.0546159 0.132835 0.030422701, + 0.0532961 0.13227899 0.033143301, + 0.0532961 0.1401 0.031895101, + 0.051830001 0.139663 0.0345653, + 0.051830001 0.147615 0.033601899, + 0.050219599 0.147294 0.036209799, + 0.050219599 0.15536299 0.035525698, + 0.048467699 0.155154 0.038059998, + 0.051830001 0.155579 0.032918599, + 0.0532961 0.147944 0.0309327, + 0.0546159 0.140545 0.029175401, + 0.055787299 0.13339899 0.027664499, + 0.056809202 0.126525 0.026409, + 0.0576833 0.119944 0.0254142, + 0.058412101 0.113674 0.0246852, + 0.058998398 0.107737 0.0242256, + 0.059445001 0.102143 0.0240348, + 0.059757002 0.096908301 0.0241115, + 0.0599402 0.092045501 0.0244474, + 0.059999999 0.0875808 0.025011901, + 0.0599402 0.0834684 0.0255685, + 0.059757002 0.079628602 0.0259094, + 0.059445001 0.076137401 0.026045701, + 0.058998398 0.073035002 0.0260239, + 0.058412101 0.072668798 0.0246142, + 0.0576833 0.072435603 0.0231873, + 0.056809202 0.072326399 0.021764399, + 0.055787299 0.072331503 0.020364501, + -0.0532961 0.070346102 0.0188058, + -0.0532961 0.068059497 0.0198234, + -0.0546159 0.070110202 0.020127, + -0.051830001 0.070661999 0.0175636, + -0.051830001 0.068465397 0.0185664, + -0.050219599 0.0710686 0.0164118, + -0.050219599 0.068909802 0.0173638, + -0.048467699 0.071496397 0.0153278, + -0.048467699 0.0693627 0.016224699, + -0.0465803 0.071917303 0.0143202, + -0.0465803 0.069820598 0.0151719, + -0.044564299 0.072325997 0.0134095, + -0.044564299 0.070268497 0.0142261, + -0.0424264 0.072706297 0.0126149, + -0.0424264 0.070689298 0.0134086, + -0.040174201 0.073040299 0.0119552, + -0.040174201 0.071062803 0.0127375, + -0.0378174 0.073309802 0.011444, + -0.0378174 0.071367197 0.0122254, + -0.035366699 0.073493503 0.0110913, + -0.035366699 0.0715793 0.0118798, + -0.0328326 0.073568299 0.010902, + -0.0328326 0.071674198 0.0117031, + -0.0302257 0.073511101 0.0108756, + -0.0302257 0.071627997 0.0116915, + -0.027557701 0.073302701 0.0110048, + -0.027557701 0.071421303 0.0118344, + -0.0248404 0.072925799 0.0112769, + -0.0248404 0.071038097 0.0121172, + -0.0220857 0.072366297 0.0116761, + -0.0220857 0.070465602 0.0125239, + -0.019305199 0.071614303 0.0121854, + -0.019305199 0.069695398 0.0130324, + -0.0165099 0.070666 0.0127813, + -0.0165099 0.068722501 0.0136078, + -0.0137106 0.069519997 0.0134315, + -0.0137106 0.067548499 0.0142396, + -0.0109179 0.068180099 0.0141247, + -0.0109179 0.0661847 0.0149083, + -0.0109179 0.062159099 0.0163178, + -0.0137106 0.063566998 0.015700201, + -0.0081428103 0.062617801 0.0162901, + -0.0081428103 0.062109899 0.0164562, + -0.0053973799 0.062428899 0.016440099, + -0.0053973799 0.061942901 0.0165496, + -0.00268824 0.062129501 0.0165418, + -0.00268824 0.061590001 0.0165218, + 0 0.061651099 0.0165195, + 0 0.061101001 0.016341699, + 0.00268824 0.061590899 0.0165208, + 0.00268824 0.062129699 0.0165409, + 0.0053973799 0.0619433 0.016547799, + 0.0053973799 0.062428899 0.016439199, + 0.0081428103 0.062109798 0.0164549, + 0.0081428103 0.062618397 0.0162894, + 0.0109179 0.06216 0.016316799, + 0.055787299 0.065173499 0.023530699, + 0.056809202 0.065012001 0.025006101, + 0.055787299 0.0627397 0.0244468, + 0.0546159 0.065426297 0.022113699, + 0.0546159 0.063086197 0.023008101, + 0.0532961 0.065799601 0.0207626, + 0.0532961 0.063527897 0.0215875, + 0.051830001 0.066251002 0.0194446, + 0.051830001 0.064011201 0.0202004, + 0.050219599 0.066728503 0.018175101, + 0.050219599 0.064533196 0.018876299, + 0.048467699 0.067226902 0.016982, + 0.048467699 0.065081 0.0176415, + 0.0465803 0.0677329 0.015889401, + 0.0465803 0.0656396 0.016521299, + 0.044564299 0.068230301 0.01492, + 0.044564299 0.0661899 0.015537, + 0.0424264 0.068699099 0.0140929, + 0.0424264 0.0667082 0.0147084, + 0.040174201 0.069115497 0.0134245, + 0.040174201 0.067167997 0.0140493, + 0.0378174 0.069455601 0.0129247, + 0.0378174 0.067542799 0.0135672, + 0.035366699 0.069694199 0.0125978, + 0.035366699 0.067805901 0.0132634, + 0.0328326 0.069805399 0.0124431, + 0.0328326 0.067930698 0.0131345, + 0.0302257 0.069765002 0.0124541, + 0.0302257 0.0678932 0.0131694, + 0.027557701 0.069554202 0.0126171, + 0.027557701 0.0676746 0.0133471, + 0.0248404 0.069156997 0.0129102, + 0.0248404 0.067262203 0.0136527, + 0.0220857 0.068562701 0.0133173, + 0.0220857 0.066647999 0.0140665, + 0.019305199 0.067766003 0.0138192, + 0.019305199 0.065821297 0.0145538, + 0.0165099 0.066763103 0.0143825, + 0.0165099 0.064789802 0.015106, + 0.0137106 0.065562896 0.014996, + 0.0137106 0.063566998 0.0156995, + 0.0109179 0.064178899 0.0156374, + 0.0081428103 0.066658303 0.0148404, + 0.0053973799 0.062938802 0.0162702, + 0.00268824 0.062616199 0.016430199, + 0 0.062190499 0.016538899, + -0.00268824 0.062616199 0.0164306, + -0.0053973799 0.0629384 0.0162706, + -0.0081428103 0.0666584 0.0148408, + -0.0081428103 0.0706499 0.0131816, + -0.0053973799 0.066989303 0.0147936, + -0.00268824 0.063126497 0.0162593, + 0 0.062677301 0.016427301, + 0.00268824 0.063126698 0.016259, + 0.0053973799 0.066989303 0.0147933, + 0.0081428103 0.0706499 0.0131816, + 0.0109179 0.068180002 0.0141247, + 0.0109179 0.070161201 0.0132896, + 0.0109179 0.074078903 0.0114594, + 0.0137106 0.071476601 0.0125663, + 0.0137106 0.069519803 0.0134314, + 0.0165099 0.070667498 0.0127748, + 0.0165099 0.072602101 0.0118947, + 0.019305199 0.071620502 0.012184, + 0.019305199 0.073533803 0.0112935, + 0.0220857 0.0723764 0.0116785, + 0.0220857 0.074272104 0.0107822, + 0.0248404 0.072938003 0.0112771, + 0.0248404 0.074822798 0.0103845, + 0.027557701 0.073316701 0.0110025, + 0.027557701 0.075197697 0.0101182, + 0.0302257 0.073526703 0.0108711, + 0.0302257 0.075412199 0.0099963397, + 0.0328326 0.073585004 0.0108946, + 0.0328326 0.075483099 0.0100286, + 0.035366699 0.073510602 0.0110805, + 0.035366699 0.075429298 0.0102196, + 0.0378174 0.073326699 0.0114296, + 0.0378174 0.075272299 0.0105677, + 0.040174201 0.073056199 0.0119374, + 0.040174201 0.075033203 0.0110664, + 0.0424264 0.072719902 0.0125946, + 0.0424264 0.074730597 0.0117055, + 0.044564299 0.072336704 0.0133889, + 0.044564299 0.074380703 0.0124717, + 0.0465803 0.071924202 0.0143026, + 0.0465803 0.0739998 0.0133469, + 0.048467699 0.071498498 0.0153152, + 0.048467699 0.073597699 0.0143092, + 0.050219599 0.071067102 0.016403399, + 0.050219599 0.073220901 0.015345, + 0.051830001 0.070678398 0.0175528, + 0.051830001 0.072906099 0.0164789, + 0.0532961 0.070371702 0.0187902, + 0.0532961 0.072637103 0.017704699, + 0.0546159 0.070126399 0.0201088, + 0.0546159 0.0724397 0.0190055, + 0.055787299 0.069967799 0.0214906, + 0.055787299 0.067581102 0.022546099, + 0.0546159 0.067790397 0.0211442, + 0.0532961 0.068076402 0.0198124, + 0.051830001 0.068463802 0.018557699, + 0.050219599 0.068911903 0.0173507, + 0.048467699 0.069369897 0.0162064, + 0.0465803 0.069831803 0.0151503, + 0.044564299 0.070282899 0.0142047, + 0.0424264 0.070706204 0.0133898, + 0.040174201 0.071080796 0.0127222, + 0.0378174 0.071385503 0.0122139, + 0.035366699 0.0715973 0.0118718, + 0.0328326 0.071691103 0.0116981, + 0.0302257 0.071643397 0.011689, + 0.027557701 0.071434803 0.0118347, + 0.0248404 0.0710494 0.0121199, + 0.0220857 0.070472904 0.0125223, + 0.019305199 0.069697097 0.0130249, + 0.0165099 0.068722397 0.0136077, + 0.0137106 0.067548402 0.0142396, + 0.0109179 0.066184603 0.0149076, + 0.0576833 0.064964503 0.026520601, + 0.058412101 0.065044403 0.028055999, + 0.058998398 0.065261699 0.0295939, + 0.059445001 0.065624297 0.0311145, + 0.059757002 0.066139698 0.032596201, + 0.0599402 0.066809699 0.034020901, + 0.059999999 0.070450999 0.034111101, + 0.0599402 0.074427798 0.034019299, + 0.059757002 0.078682303 0.0337306, + 0.059445001 0.083143599 0.0332353, + 0.058998398 0.087930098 0.032738902, + 0.058412101 0.0931172 0.032472201, + 0.0576833 0.098689802 0.032438699, + 0.056809202 0.104632 0.0326415, + 0.055787299 0.110927 0.033082802, + 0.0546159 0.117556 0.033762299, + 0.0532961 0.124499 0.034674998, + 0.051830001 0.131733 0.035814598, + 0.050219599 0.13923401 0.037174299, + 0.048467699 0.146981 0.0387449, + 0.0465803 0.15495101 0.040510599, + 0.00267513 0.162294 0.0622104, + 0.0053918599 0.162302 0.062027998, + 0.0030883299 0.171451 0.062051501, + 0.050219599 0.043872301 0.0200058, + 0.048467699 0.0458913 0.019167099, + 0.050219599 0.0446858 0.020122601, + 0.051830001 0.041756999 0.020985899, + 0.051830001 0.0434127 0.021307301, + 0.0532961 0.040389199 0.0223122, + 0.0532961 0.042113502 0.0227086, + 0.0546159 0.039017599 0.023856699, + 0.0546159 0.040834401 0.0243281, + 0.055787299 0.0376896 0.025618199, + 0.055787299 0.0396179 0.026148399, + 0.056809202 0.036447801 0.027576501, + 0.056809202 0.0385032 0.028141299, + 0.0576833 0.035330798 0.029700899, + 0.0576833 0.037523098 0.030274, + 0.058412101 0.034370501 0.031955399, + 0.058412101 0.036704998 0.032507401, + 0.058998398 0.0335932 0.034298498, + 0.058998398 0.036067098 0.0347999, + 0.059445001 0.033016101 0.036685798, + 0.059445001 0.035621099 0.037106901, + 0.059757002 0.032650001 0.0390701, + 0.059757002 0.035370599 0.039385099, + 0.0599402 0.032490801 0.041410401, + 0.0599402 0.035307799 0.041595601, + 0.059999999 0.032505602 0.043684401, + 0.059999999 0.0354001 0.043723099, + 0.0599402 0.032656301 0.045882501, + 0.0599402 0.0355964 0.045758601, + 0.059757002 0.032891098 0.047997501, + 0.059757002 0.0359344 0.047723599, + 0.059445001 0.033256602 0.050048899, + 0.059445001 0.036455002 0.049719501, + 0.058998398 0.033818401 0.0521238, + 0.058998398 0.0370849 0.051747698, + 0.058412101 0.034504201 0.054218899, + 0.058412101 0.037845898 0.053784799, + 0.0576833 0.035333801 0.056310501, + 0.0576833 0.0387499 0.0558112, + 0.056809202 0.036317602 0.0583786, + 0.056809202 0.039804801 0.057807799, + 0.055787299 0.037462801 0.0604035, + 0.055787299 0.041016899 0.059754498, + 0.0546159 0.038774598 0.062364601, + 0.0546159 0.042390998 0.061630201, + 0.0532961 0.040256899 0.064239398, + 0.0532961 0.043930698 0.063412704, + 0.051830001 0.0419126 0.066005401, + 0.051830001 0.045635302 0.065085299, + 0.050219599 0.043739501 0.067645103, + 0.050219599 0.047522701 0.066632703, + 0.048467699 0.045752998 0.069142997, + 0.048467699 0.049592599 0.068029597, + 0.0465803 0.047949798 0.070474401, + 0.0465803 0.051832099 0.069254898, + 0.044564299 0.0503162 0.071618803, + 0.044564299 0.0542273 0.070288301, + 0.0424264 0.052837498 0.072556399, + 0.0424264 0.056763701 0.071110502, + 0.040174201 0.055498201 0.073268697, + 0.040174201 0.0594263 0.071703702, + 0.0378174 0.0582815 0.073740803, + 0.0378174 0.062197801 0.072053999, + 0.035366699 0.0611693 0.073959999, + 0.035366699 0.069150597 0.070569597, + 0.0328326 0.068274297 0.072334498, + 0.0328326 0.076464802 0.0691863, + 0.0302257 0.0757301 0.070805401, + 0.0302257 0.084108002 0.067908503, + 0.027557701 0.083502501 0.069380403, + 0.027557701 0.092047401 0.066742502, + 0.0248404 0.091558397 0.068066098, + 0.0248404 0.10025 0.0656946, + 0.0220857 0.099865198 0.066868499, + 0.0220857 0.108683 0.064769603, + 0.019305199 0.108391 0.065792903, + 0.019305199 0.117315 0.063970402, + 0.0165099 0.117099 0.064845502, + 0.0165099 0.126111 0.063302301, + 0.0137106 0.12596101 0.064031698, + 0.0137106 0.135038 0.062770702, + 0.0109179 0.134942 0.063356899, + 0.0109179 0.14406499 0.062379599, + 0.0081421202 0.14401101 0.062825702, + 0.0081421202 0.153164 0.062130701, + 0.0053918599 0.153138 0.062442001, + 0.0026750399 0.171451 0.062072799, + -5.2000001e-008 0.171451 0.062134199, + 0.051042698 0.0339665 0.018012101, + 0.050219599 0.035296101 0.017932, + 0.051830001 0.034147698 0.018691899, + -0.0220857 0.0573759 0.016653299, + -0.0220857 0.0568421 0.016439799, + -0.023467001 0.0568006 0.016671, + -0.020698 0.057376999 0.016427601, + -0.0220857 0.056375802 0.0160689, + -0.019305199 0.057404 0.0160526, + -0.019305199 0.057055399 0.0155805, + -0.0165099 0.057931799 0.0155716, + -0.0165099 0.057736099 0.0150566, + -0.0137106 0.058464799 0.0150528, + -0.0147097 0.058157299 0.0145463, + -0.0118392 0.058808699 0.0145468, + -0.0109151 0.058971301 0.014547, + -0.0107568 0.059020299 0.0095469998, + -0.0211595 0.171454 0.058265001, + -0.0220857 0.162469 0.0580501, + -0.020292999 0.171453 0.058600601, + 0.034109399 0.052265901 0.0169114, + 0.0328326 0.053147402 0.016858401, + 0.035366699 0.053187601 0.0167551, + 0.037815802 0.046566602 0.0145371, + 0.0360066 0.047970701 0.0145382, + 0.0378174 0.046616402 0.0151005, + 0.035366699 0.048505299 0.0150921, + 0.045588002 0.040814001 0.017375501, + 0.044564299 0.0420013 0.017328801, + 0.045588002 0.041213602 0.0174892, + 0.0465803 0.039996099 0.0175496, + 0.047540501 0.0391674 0.017699201, + 0.0465803 0.040414199 0.017624199, + 0.048467699 0.039513599 0.0181461, + 0.044564299 0.042833801 0.0174786, + 0.0465803 0.042071499 0.0178858, + 0.048467699 0.041120499 0.018472699, + 0.050219599 0.038432799 0.0188551, + 0.050219599 0.039989199 0.019253001, + 0.051830001 0.037180599 0.019764001, + 0.051830001 0.038681101 0.0202507, + 0.0532961 0.035762001 0.0208962, + 0.0532961 0.037221398 0.0214052, + 0.0546159 0.034204502 0.0221841, + 0.0546159 0.035706598 0.022769, + 0.055787299 0.032611702 0.023681199, + 0.055787299 0.0341882 0.024373099, + 0.056809202 0.0310372 0.025420399, + 0.056809202 0.032710999 0.0261952, + 0.0576833 0.0295262 0.027376, + 0.0576833 0.031323999 0.028229499, + 0.058412101 0.028128101 0.029540399, + 0.058412101 0.030068999 0.030450299, + 0.058998398 0.0268848 0.031884801, + 0.058998398 0.0289841 0.032821, + 0.059445001 0.025834501 0.034369301, + 0.059445001 0.028100001 0.0352998, + 0.059757002 0.025008 0.036948901, + 0.059757002 0.027442001 0.037838999, + 0.0599402 0.024423299 0.039576501, + 0.0599402 0.0270191 0.040392701, + 0.059999999 0.0240636 0.042219799, + 0.059999999 0.026808999 0.042929702, + 0.0599402 0.023899799 0.044852, + 0.0599402 0.0267756 0.0454299, + 0.059757002 0.0238958 0.0474553, + 0.059757002 0.026879599 0.047878198, + 0.059445001 0.0240178 0.050011501, + 0.059445001 0.0270888 0.050264101, + 0.058998398 0.0242563 0.0524933, + 0.058998398 0.0273785 0.052559901, + 0.058412101 0.024589701 0.054868001, + 0.058412101 0.027825801 0.0547648, + 0.0576833 0.025095301 0.057135802, + 0.0576833 0.028505201 0.056968901, + 0.056809202 0.0258493 0.059390899, + 0.056809202 0.029334299 0.0591694, + 0.055787299 0.026764899 0.061629798, + 0.055787299 0.0303303 0.061341099, + 0.0546159 0.0278582 0.063826501, + 0.0546159 0.031501502 0.063462503, + 0.0532961 0.0291372 0.065958299, + 0.0532961 0.0328537 0.065512098, + 0.051830001 0.030606501 0.068002902, + 0.051830001 0.034390699 0.067466997, + 0.050219599 0.032268502 0.069937102, + 0.050219599 0.036114 0.069304504, + 0.048467699 0.0341237 0.071737804, + 0.048467699 0.038023699 0.071001403, + 0.0465803 0.036169901 0.073382899, + 0.0465803 0.040114701 0.072540298, + 0.044564299 0.038401 0.074854597, + 0.044564299 0.0423958 0.073904999, + 0.0424264 0.040822901 0.076136, + 0.0424264 0.044860199 0.075072199, + 0.040174201 0.043427099 0.077205002, + 0.040174201 0.047492299 0.076022401, + 0.0378174 0.0461956 0.078044698, + 0.0378174 0.050274301 0.076739602, + 0.035366699 0.0491096 0.078640297, + 0.035366699 0.053187601 0.077209301, + 0.0328326 0.052150499 0.078977898, + 0.0328326 0.056214899 0.077418201, + 0.0302257 0.0553004 0.079045303, + 0.0302257 0.059337098 0.077355802, + 0.027557701 0.058538198 0.078836396, + 0.027557701 0.066735499 0.075433701, + 0.0248404 0.066075303 0.076762997, + 0.0248404 0.074458897 0.073606297, + 0.0220857 0.0739244 0.074783899, + 0.0220857 0.082473397 0.071881302, + 0.019305199 0.082051203 0.072907001, + 0.019305199 0.090745702 0.070265502, + 0.0165099 0.090421699 0.071141802, + 0.0165099 0.099242203 0.068768203, + 0.0137106 0.0990026 0.069498301, + 0.0137106 0.10793 0.067398198, + 0.0109179 0.107762 0.067984901, + 0.0109179 0.116776 0.0661617, + 0.0081421202 0.116666 0.066608503, + 0.0081421202 0.12574799 0.065064803, + 0.0053918599 0.12568399 0.0653769, + 0.0053918599 0.13481601 0.064115196, + 0.00267513 0.13478599 0.0642979, + 0.00267513 0.14395 0.063319601, + 0 0.143942 0.063378699, + 0 0.153118 0.062683001, + -0.00267513 0.143949 0.063318104, + -0.00267513 0.13478599 0.064296797, + -0.0053918599 0.13481501 0.064112999, + -0.0053918599 0.12568299 0.065375, + -0.0081421202 0.125746 0.065062001, + -0.0081421202 0.116663 0.066605203, + -0.0109179 0.116772 0.066157296, + -0.0109179 0.107757 0.067979597, + -0.0137106 0.107924 0.067391403, + -0.0137106 0.098997302 0.0694905, + -0.0165099 0.0992359 0.068758801, + -0.0165099 0.090415403 0.071132302, + -0.019305199 0.090738401 0.0702544, + -0.019305199 0.0820444 0.072896898, + -0.0220857 0.082465596 0.071869902, + -0.0220857 0.073918 0.074775398, + -0.0248404 0.0744517 0.073596701, + -0.0248404 0.066071197 0.076758601, + -0.027557701 0.066730998 0.075428702, + -0.027557701 0.058537699 0.078837797, + -0.0302257 0.059336599 0.0773573, + -0.0302257 0.0553004 0.079046302, + -0.0328326 0.056214999 0.077419199, + -0.0328326 0.052150398 0.0789802, + -0.035366699 0.0531874 0.077211797, + -0.035366699 0.049109001 0.078644603, + -0.0378174 0.050273601 0.076744199, + -0.0378174 0.046194401 0.078051001, + -0.040174201 0.0474911 0.0760291, + -0.040174201 0.043426 0.077212296, + -0.0424264 0.0448591 0.075079903, + -0.0424264 0.040823199 0.076142102, + -0.044564299 0.042396002 0.073911399, + -0.044564299 0.038403001 0.074857697, + -0.0465803 0.040116802 0.072543599, + -0.0465803 0.036171101 0.073386401, + -0.048467699 0.038024899 0.071005099, + -0.048467699 0.034124698 0.071743801, + -0.050219599 0.036114998 0.069310598, + -0.050219599 0.032269299 0.069946103, + -0.051830001 0.0343915 0.067476302, + -0.051830001 0.030606501 0.0680153, + -0.0532961 0.032853801 0.065524802, + -0.0532961 0.029135101 0.065973997, + -0.0546159 0.0314993 0.063478597, + -0.0546159 0.027851 0.063844502, + -0.055787299 0.030322799 0.061359499, + -0.055787299 0.0267483 0.061648302, + -0.056809202 0.0293175 0.059188299, + -0.056809202 0.025822099 0.059407599, + -0.0576833 0.0284776 0.0569859, + -0.0576833 0.025077101 0.057147801, + -0.058412101 0.0278074 0.0547769, + -0.058412101 0.0245915 0.054877698, + -0.058998398 0.0273802 0.052569699, + -0.058998398 0.024253899 0.0525086, + -0.059445001 0.027086301 0.050279599, + -0.059445001 0.024009099 0.050033901, + -0.059757002 0.0268708 0.0479008, + -0.059757002 0.023881501 0.047483001, + -0.0599402 0.026761301 0.045457698, + -0.0599402 0.0238805 0.0448808, + -0.059999999 0.026789701 0.042958401, + -0.059999999 0.0240399 0.042246401, + -0.0599402 0.026995501 0.040419299, + -0.0599402 0.024396401 0.039599299, + -0.059757002 0.027415199 0.037861701, + -0.059757002 0.024979001 0.036967099, + -0.059445001 0.0280712 0.035317902, + -0.059445001 0.0258043 0.034382802, + -0.058998398 0.0289542 0.032834299, + -0.058998398 0.026854301 0.031893801, + -0.058412101 0.0300388 0.030459199, + -0.058412101 0.028098401 0.0295454, + -0.0576833 0.031294599 0.028234299, + -0.0576833 0.029497899 0.0273754, + -0.056809202 0.032683201 0.0261945, + -0.056809202 0.031011401 0.0254142, + -0.055787299 0.034162801 0.024367001, + -0.055787299 0.0325936 0.023685399, + -0.0465803 0.0395982 0.017439, + -0.0465803 0.039996602 0.017557001, + -0.045588002 0.040810999 0.017391, + -0.047540501 0.0387551 0.017618701, + -0.0465803 0.040410701 0.0176281, + -0.048467699 0.037894402 0.0177797, + -0.048467699 0.039513901 0.018148599, + -0.0465803 0.0420717 0.0178883, + -0.044564299 0.042830501 0.0174824, + -0.048467699 0.041120999 0.018475501, + -0.050219599 0.038433298 0.018858001, + -0.050219599 0.039989602 0.019252799, + -0.051830001 0.037181001 0.019763799, + -0.051830001 0.0386815 0.0202509, + -0.0532961 0.0357625 0.020896399, + -0.0532961 0.037216701 0.021426, + -0.0546159 0.0341998 0.022205301, + -0.0546159 0.035689 0.0227731, + -0.055787299 0.035851698 0.025019901, + -0.056809202 0.034486402 0.026925201, + -0.0576833 0.033230901 0.0290212, + -0.058412101 0.032124002 0.031275999, + -0.058998398 0.0311967 0.033650901, + -0.059445001 0.030474501 0.036100801, + -0.059757002 0.0299742 0.038578101, + -0.0599402 0.0296988 0.041036099, + -0.059999999 0.0296189 0.043447901, + -0.0599402 0.0296946 0.045795899, + -0.059757002 0.0298885 0.048074201, + -0.059445001 0.030151401 0.050276302, + -0.058998398 0.0305312 0.052411601, + -0.058412101 0.031137099 0.054560699, + -0.0576833 0.031900201 0.056715101, + -0.056809202 0.0328178 0.058851101, + -0.055787299 0.0338961 0.0609487, + -0.0546159 0.035142701 0.0629884, + -0.0532961 0.0365634 0.064948604, + -0.051830001 0.0381625 0.066807598, + -0.050219599 0.039941799 0.068542503, + -0.048467699 0.041898999 0.070137098, + -0.0465803 0.044041801 0.071577199, + -0.044564299 0.0463688 0.072833501, + -0.0424264 0.048866201 0.073885001, + -0.040174201 0.051517598 0.074714199, + -0.0378174 0.054304499 0.075306699, + -0.035366699 0.057209801 0.075649098, + -0.0328326 0.060214099 0.075731099, + -0.0302257 0.0674638 0.0739512, + -0.027557701 0.0750532 0.072268903, + -0.0248404 0.082948498 0.070692502, + -0.0220857 0.091116004 0.069228202, + -0.019305199 0.099522099 0.067881599, + -0.0165099 0.108133 0.066660203, + -0.0137106 0.116916 0.065569498, + -0.0109179 0.125838 0.064614303, + -0.0081421202 0.134866 0.0638, + -0.0053918599 0.14397199 0.063134097, + -0.00267513 0.15312301 0.062622301, + 0 0.162292 0.0622693, + 0.00267513 0.15312301 0.062624097, + 0.0053918599 0.14397199 0.063137203, + 0.0081421202 0.134868 0.063803397, + 0.0109179 0.12584101 0.0646182, + 0.0137106 0.116921 0.065575004, + 0.0165099 0.108139 0.066668302, + 0.019305199 0.099529497 0.067892499, + 0.0220857 0.0911244 0.069240898, + 0.0248404 0.082957298 0.070705302, + 0.027557701 0.075061202 0.072279498, + 0.0302257 0.0674688 0.073956698, + 0.0328326 0.060214698 0.0757294, + 0.035366699 0.0572097 0.075648002, + 0.0378174 0.054304801 0.075304002, + 0.040174201 0.051518299 0.074709304, + 0.0424264 0.048867401 0.073877998, + 0.044564299 0.04637 0.072825402, + 0.0465803 0.044041499 0.071570501, + 0.048467699 0.041896801 0.070133701, + 0.050219599 0.039940599 0.068538703, + 0.051830001 0.038161501 0.066801198, + 0.0532961 0.036562499 0.064939097, + 0.0546159 0.0351425 0.062975302, + 0.055787299 0.033898398 0.060932402, + 0.056809202 0.032825399 0.0588325, + 0.0576833 0.031917501 0.056695901, + 0.058412101 0.031165 0.054543499, + 0.058998398 0.030549901 0.0523993, + 0.059445001 0.0301496 0.0502664, + 0.059757002 0.029890999 0.0480587, + 0.0599402 0.0297036 0.045773201, + 0.059999999 0.0296332 0.043420099, + 0.0599402 0.0297183 0.0410074, + 0.059757002 0.029997701 0.038551599, + 0.059445001 0.030501099 0.0360782, + 0.058998398 0.031225299 0.033632901, + 0.058412101 0.0321537 0.0312628, + 0.0576833 0.033260699 0.029012401, + 0.056809202 0.034515299 0.0269203, + 0.055787299 0.035879102 0.0250204, + 0.0546159 0.0373099 0.0233356, + 0.0532961 0.0387595 0.0218693, + 0.0424264 0.045146201 0.0173396, + 0.041313998 0.045816801 0.017261, + 0.040174201 0.047341101 0.0172075, + 0.0424264 0.0468821 0.0173964, + 0.044564299 0.044531301 0.017635601, + 0.044564299 0.046219401 0.0177474, + 0.0465803 0.043719798 0.018103, + 0.0465803 0.045359898 0.018276, + 0.048467699 0.042719498 0.0187563, + 0.048467699 0.044305898 0.0190069, + 0.050219599 0.041533299 0.019619999, + 0.050219599 0.043077901 0.0198934, + 0.051830001 0.0401836 0.0206406, + 0.051830001 0.0409595 0.0208103, + 0.0532961 0.037978601 0.021633601, + 0.043510102 0.043571301 0.017372301, + 0.0424264 0.043840699 0.0170525, + 0.043510102 0.043161999 0.017283101, + 0.044564299 0.041557599 0.017121499, + 0.0424264 0.043377299 0.0167346, + 0.041313998 0.044939399 0.0170194, + 0.0424264 0.044295002 0.0172386, + 0.044564299 0.042405698 0.017430101, + 0.0465803 0.039168499 0.017193601, + 0.044564299 0.0411047 0.016785299, + 0.0424264 0.042965699 0.0162795, + 0.040174201 0.045114201 0.016245499, + 0.040174201 0.044791002 0.0157024, + 0.0378174 0.046811301 0.0156822, + 0.0390082 0.0479412 0.0171558, + 0.040174201 0.046894599 0.0172076, + 0.0390082 0.047514599 0.017111899, + 0.0378174 0.048525099 0.017072201, + 0.0378174 0.048051599 0.016925599, + 0.036603201 0.049024999 0.016896199, + 0.036603201 0.048537198 0.0166195, + 0.035366699 0.0494726 0.016598601, + 0.035366699 0.0490366 0.0161837, + 0.0378174 0.047140099 0.0162136, + 0.035366699 0.048702501 0.0156633, + 0.0328326 0.0504581 0.0156457, + 0.027557701 0.053337801 0.0150707, + 0.0248404 0.0546588 0.0150649, + 0.027557701 0.0535408 0.0156148, + 0.0302257 0.052071799 0.015629601, + 0.0302257 0.051870398 0.0150771, + 0.032827701 0.050200298 0.01454, + 0.0308851 0.0514233 0.014541, + 0.0328326 0.050258599 0.0150843, + 0.040174201 0.045534302 0.016686499, + 0.040174201 0.046007998 0.0169871, + 0.041313998 0.0453986 0.017195201, + 0.0424264 0.044708598 0.0173159, + 0.040174201 0.046472099 0.0171529, + 0.0390082 0.0470456 0.016955899, + 0.0378174 0.047568399 0.016641101, + 0.0390082 0.048392199 0.0171443, + 0.0378174 0.048955899 0.017105499, + 0.036603201 0.049502902 0.0170338, + 0.035366699 0.0499648 0.0168679, + 0.034109399 0.0503738 0.016578499, + 0.0328326 0.0507969 0.016155999, + 0.0302257 0.052414998 0.016130401, + 0.031537499 0.052070301 0.016540799, + 0.027557701 0.0538879 0.0161072, + 0.0288986 0.053622399 0.016506201, + 0.0248404 0.054863099 0.0156016, + 0.0220857 0.055831399 0.0150599, + 0.0228185 0.05548 0.0145442, + 0.0220806 0.055762399 0.0145444, + 0.0197125 0.056661699 0.0095451204, + 0.0200695 0.056532301 0.014545, + 0.0165099 0.057729501 0.0150518, + 0.019305199 0.056854401 0.0150555, + 0.017272299 0.057448499 0.0145457, + 0.019305199 0.057060599 0.0155796, + 0.0220857 0.0560368 0.0155899, + 0.0220857 0.056390401 0.016067799, + 0.0248404 0.055213701 0.016086301, + 0.023467001 0.0562842 0.016447101, + 0.00814154 0.059422798 0.0145473, + 0.0077019902 0.059475999 0.0145474, + 0.0081428103 0.059493799 0.0150448, + 0.0086586103 0.059360299 0.0145473, + 0.0109179 0.059046399 0.0150465, + 0.0109179 0.059253599 0.0155578, + 0.0137106 0.058666401 0.0155636, + 0.0137106 0.059026401 0.016026299, + 0.0165099 0.058294501 0.016037799, + 0.0165099 0.058768 0.016392101, + 0.019305199 0.0578865 0.016411601, + 0.019305199 0.058419298 0.0166141, + 0.0220857 0.057383802 0.0166451, + 0.0220857 0.057900999 0.0167046, + 0.023467001 0.056809001 0.0166623, + 0.00268824 0.059990302 0.0150433, + 0.00154448 0.059950799 0.0145477, + 0 0.0600507 0.0150434, + 0.0026881699 0.0599255 0.0145477, + 0.0028003999 0.059923001 0.0145477, + 0.0053973799 0.0598066 0.0150437, + 0.0053973799 0.060013201 0.0155503, + 0.0081428103 0.059700798 0.0155534, + 0.0081428103 0.0600628 0.016009999, + 0.0109179 0.059614699 0.0160171, + 0.0109179 0.0600935 0.016363099, + 0.0137106 0.059502698 0.016376, + 0.0137106 0.060043499 0.0165659, + 0.0165099 0.059305001 0.016587799, + 0.0165099 0.059831701 0.016629299, + 0.019305199 0.058941599 0.016664, + 0.019305199 0.0594147 0.016587701, + 0.0220857 0.058369901 0.0166394, + 0.0220857 0.058863498 0.0165148, + 0.0248404 0.057660799 0.016587, + 0.0248404 0.059604701 0.0161024, + 0.027557701 0.0582272 0.0162425, + 0.027557701 0.060136698 0.015767699, + 0.0302257 0.058581699 0.015988899, + 0.0302257 0.060456902 0.0155296, + 0.0328326 0.058721799 0.015845301, + 0.0328326 0.060556401 0.0154134, + 0.035366699 0.058639601 0.015837301, + 0.035366699 0.060436498 0.0154134, + 0.0378174 0.058341101 0.0159541, + 0.0378174 0.060130499 0.0155706, + 0.040174201 0.057865702 0.016238101, + 0.040174201 0.0596609 0.0159063, + 0.0424264 0.057238299 0.016711701, + 0.0424264 0.059053 0.0164269, + 0.044564299 0.056487199 0.0173785, + 0.044564299 0.058339201 0.0171472, + 0.0465803 0.055648901 0.018250801, + 0.0465803 0.057553299 0.0180678, + 0.048467699 0.054759402 0.019326599, + 0.048467699 0.0567309 0.0191804, + 0.050219599 0.053855099 0.0205942, + 0.050219599 0.055904899 0.0204702, + 0.051830001 0.052969299 0.022035901, + 0.051830001 0.0551061 0.0219163, + 0.0532961 0.052133501 0.023627199, + 0.0532961 0.054360699 0.0234925, + 0.0546159 0.0513734 0.025338899, + 0.0546159 0.0536904 0.025167599, + 0.055787299 0.0507094 0.027137101, + 0.055787299 0.053109899 0.0269095, + 0.056809202 0.050154399 0.028987899, + 0.056809202 0.052628499 0.0286847, + 0.0576833 0.0497148 0.030856499, + 0.0576833 0.0522517 0.0304613, + 0.058412101 0.049394399 0.0327099, + 0.058412101 0.051972099 0.032205999, + 0.058998398 0.049183201 0.034513999, + 0.058998398 0.051847499 0.033905201, + 0.059445001 0.0491409 0.036255501, + 0.059445001 0.0519276 0.035610002, + 0.059757002 0.049319301 0.037988499, + 0.059757002 0.052161001 0.037311502, + 0.0599402 0.049657699 0.0397087, + 0.0599402 0.0525616 0.038989902, + 0.059999999 0.050149299 0.041415099, + 0.059999999 0.053114899 0.040647801, + 0.0599402 0.050776001 0.0431167, + 0.0599402 0.053801201 0.042295299, + 0.059757002 0.051519301 0.044824202, + 0.059757002 0.054602001 0.043942999, + 0.059445001 0.052367099 0.046544101, + 0.059445001 0.055505201 0.045597199, + 0.058998398 0.053325702 0.048261799, + 0.058998398 0.056517601 0.047242701, + 0.058412101 0.054405101 0.049956501, + 0.058412101 0.057644799 0.048867598, + 0.0576833 0.0556091 0.051616602, + 0.0576833 0.0589213 0.050464399, + 0.056809202 0.0569693 0.053233299, + 0.056809202 0.060359199 0.0520075, + 0.055787299 0.058495399 0.054781102, + 0.055787299 0.061951 0.053475101, + 0.0546159 0.060179099 0.056238201, + 0.0546159 0.063689202 0.054846801, + 0.0532961 0.062012602 0.057583202, + 0.0532961 0.065564901 0.0561007, + 0.051830001 0.063985601 0.0587941, + 0.051830001 0.067568801 0.0572154, + 0.050219599 0.066088401 0.059849501, + 0.050219599 0.0696894 0.058169801, + 0.048467699 0.068308502 0.060729101, + 0.048467699 0.075703003 0.057371099, + 0.0465803 0.074477501 0.059840001, + 0.0465803 0.0821224 0.056715399, + 0.044564299 0.081047498 0.059085399, + 0.044564299 0.0889211 0.056204598, + 0.0424264 0.0879912 0.0584663, + 0.0424264 0.0960728 0.0558392, + 0.040174201 0.095281199 0.057983901, + 0.040174201 0.10355 0.055619501, + 0.0378174 0.102888 0.0576404, + 0.0378174 0.111325 0.055546101, + 0.035366699 0.110783 0.057436999, + 0.035366699 0.119365 0.055617802, + 0.0328326 0.118934 0.057372101, + 0.0328326 0.12763999 0.055831801, + 0.0302257 0.12730899 0.057443801, + 0.0302257 0.13611799 0.0561857, + 0.027557701 0.135878 0.0576526, + 0.027557701 0.14477 0.056678802, + 0.0248404 0.14460699 0.057998601, + 0.0248404 0.15356199 0.0573061, + 0.0220857 0.153466 0.058476899, + 0.019305199 0.153382 0.059498101, + 0.0220857 0.144462 0.059169799, + 0.0248404 0.13566101 0.0589731, + 0.027557701 0.127009 0.058911402, + 0.0302257 0.118539 0.058984801, + 0.0328326 0.110281 0.059192199, + 0.035366699 0.102269 0.0595324, + 0.0378174 0.094534598 0.060006302, + 0.040174201 0.0871085 0.060613099, + 0.0424264 0.0800201 0.0613501, + 0.044564299 0.073298797 0.062214401, + 0.0465803 0.066973098 0.063203998, + 0.048467699 0.064649299 0.062410101, + 0.050219599 0.0624425 0.061425701, + 0.051830001 0.060366198 0.0602699, + 0.0532961 0.058431402 0.058963701, + 0.0546159 0.056648798 0.057528999, + 0.055787299 0.0550276 0.055987399, + 0.056809202 0.053576399 0.0543615, + 0.0576833 0.052287601 0.052676801, + 0.058412101 0.0511324 0.0509433, + 0.058998398 0.050108101 0.0491734, + 0.059445001 0.049206901 0.047387201, + 0.059757002 0.048418801 0.045605, + 0.0599402 0.047736999 0.043840401, + 0.059999999 0.047173601 0.042087302, + 0.0599402 0.046745501 0.040335599, + 0.059757002 0.046463199 0.038580801, + 0.059445001 0.046412099 0.036807399, + 0.058998398 0.0465439 0.034953199, + 0.058412101 0.046796899 0.033031501, + 0.0576833 0.0471831 0.031077599, + 0.056809202 0.047700599 0.029125201, + 0.055787299 0.048345 0.0272108, + 0.0546159 0.049106002 0.025369801, + 0.0532961 0.0499648 0.023638301, + 0.051830001 0.0508967 0.022048499, + 0.050219599 0.051870398 0.020628201, + 0.048467699 0.052851301 0.019398499, + 0.0465803 0.053802401 0.0183741, + 0.044564299 0.0546862 0.0175601, + 0.0424264 0.055464 0.016945999, + 0.040174201 0.056102902 0.0165317, + 0.0378174 0.056574602 0.016294001, + 0.035366699 0.056834299 0.0161887, + 0.0328326 0.056873702 0.016231799, + 0.0302257 0.056697 0.016398201, + 0.027557701 0.0563059 0.0166685, + 0.0248404 0.057172101 0.016698601, + 0.0057364102 0.059713598 0.0145476, + 0.0077038999 0.059495799 0.0095473798, + 0.0109157 0.0589744 0.014547, + 0.01156 0.058864299 0.0145469, + 0.0137106 0.058459301 0.0150489, + 0.0165099 0.0579363 0.0155709, + 0.019305199 0.0574167 0.0160516, + 0.0220857 0.0568561 0.016434399, + 0.0248404 0.0561965 0.016680701, + 0.0144335 0.0582265 0.0145464, + 0.0137785 0.058371902 0.0145465, + 0.016506299 0.0576584 0.0145459, + 0.0193008 0.056784101 0.0145452, + 0.019710001 0.056650098 0.0145451, + 0.0262044 0.0550276 0.016474999, + 0.027557701 0.055364098 0.0168039, + 0.0262044 0.055546399 0.0167001, + 0.0248404 0.056708202 0.016751301, + 0.027557701 0.0558227 0.016765499, + 0.0288986 0.054636199 0.0168324, + 0.027557701 0.054858901 0.0167208, + 0.0248404 0.055674601 0.016460599, + 0.0302257 0.054800801 0.0167589, + 0.0328326 0.0550161 0.0165691, + 0.035366699 0.055015601 0.0164961, + 0.0378174 0.054800801 0.0165585, + 0.040174201 0.054368898 0.016781701, + 0.0424264 0.0537294 0.017144199, + 0.044564299 0.0529337 0.0176918, + 0.0465803 0.052015699 0.018447701, + 0.048467699 0.0510104 0.0194095, + 0.050219599 0.0499583 0.0205853, + 0.051830001 0.048898298 0.021967201, + 0.0532961 0.0478689 0.023537001, + 0.0546159 0.046904702 0.025270401, + 0.055787299 0.046036702 0.0271364, + 0.056809202 0.045288201 0.029100301, + 0.0576833 0.0446756 0.031123901, + 0.058412101 0.044207402 0.033170301, + 0.058998398 0.043885998 0.035201401, + 0.059445001 0.043711402 0.037182201, + 0.059757002 0.043670598 0.039076298, + 0.0599402 0.043820899 0.040875301, + 0.059999999 0.044191401 0.042664699, + 0.0599402 0.044689599 0.044465799, + 0.059757002 0.0453059 0.046284601, + 0.059445001 0.04603 0.0481265, + 0.058998398 0.046869401 0.049977802, + 0.058412101 0.047834702 0.051819298, + 0.0576833 0.0489337 0.053631298, + 0.056809202 0.0501731 0.055393301, + 0.055787299 0.051554501 0.057091899, + 0.0546159 0.053103901 0.0587161, + 0.0532961 0.054827198 0.060239598, + 0.051830001 0.056715202 0.061639901, + 0.050219599 0.058757499 0.062895097, + 0.048467699 0.060942501 0.063983798, + 0.0465803 0.063257597 0.064886399, + 0.044564299 0.065688796 0.065584198, + 0.0424264 0.072172299 0.064483397, + 0.040174201 0.079044901 0.063499898, + 0.0378174 0.086276002 0.062637404, + 0.035366699 0.0938356 0.061899502, + 0.0328326 0.101693 0.061288401, + 0.0302257 0.109819 0.0608056, + 0.027557701 0.118178 0.060452901, + 0.0248404 0.126739 0.0602323, + 0.0220857 0.135469 0.060145099, + 0.019305199 0.144336 0.060191501, + 0.0165099 0.153309 0.0603715, + 0.0137106 0.153249 0.061099499, + 0.0165099 0.144228 0.061065398, + 0.019305199 0.13530099 0.0611674, + 0.0220857 0.126499 0.061404798, + 0.0248404 0.117854 0.0617745, + 0.027557701 0.109398 0.062274098, + 0.0302257 0.101165 0.0629026, + 0.0328326 0.093186803 0.063656799, + 0.035366699 0.085496597 0.0645326, + 0.0378174 0.078125097 0.065527, + 0.040174201 0.071103103 0.066637099, + 0.0424264 0.064461499 0.0678588, + 0.044564299 0.061919399 0.067267701, + 0.0465803 0.059491798 0.066457897, + 0.048467699 0.057193801 0.0654471, + 0.050219599 0.0550384 0.064254701, + 0.051830001 0.053038798 0.062901102, + 0.0532961 0.051206298 0.0614076, + 0.0546159 0.049551301 0.059797, + 0.055787299 0.048069902 0.058095202, + 0.056809202 0.0467383 0.056315299, + 0.0576833 0.0455558 0.054471701, + 0.058412101 0.0445171 0.052584998, + 0.058998398 0.043615501 0.050675102, + 0.059445001 0.042842198 0.048761498, + 0.059757002 0.042186201 0.046863001, + 0.0599402 0.041637398 0.044993799, + 0.059999999 0.041198801 0.043152198, + 0.0599402 0.0409653 0.041315202, + 0.059757002 0.040909201 0.039387502, + 0.059445001 0.0409934 0.037357502, + 0.058998398 0.0412388 0.035257999, + 0.058412101 0.041646302 0.033125602, + 0.0576833 0.042215101 0.0309998, + 0.056809202 0.042938702 0.028919499, + 0.055787299 0.0438025 0.026924901, + 0.0546159 0.044785101 0.025053101, + 0.0532961 0.045856498 0.023337601, + 0.051830001 0.0469823 0.0218061, + 0.050219599 0.048123199 0.0204801, + 0.048467699 0.0492386 0.0193708, + 0.0465803 0.050286099 0.018471999, + 0.044564299 0.051228799 0.0177896, + 0.0424264 0.0520298 0.0172989, + 0.040174201 0.0526287 0.016953699, + 0.0378174 0.053013802 0.016780799, + 0.0302257 0.054323599 0.0168397, + 0.0302257 0.053871199 0.0168624, + 0.0288986 0.054134302 0.0167425, + 0.027557701 0.054343399 0.016490201, + 0.0302257 0.053373002 0.016765401, + 0.031537499 0.053069498 0.016893901, + 0.0328326 0.052677002 0.0169212, + 0.0328326 0.0522312 0.0169267, + 0.031537499 0.052574899 0.016789399, + 0.0302257 0.0528646 0.0165231, + 0.0328326 0.051740602 0.0168145, + 0.034109399 0.0513569 0.016961001, + 0.036603201 0.0503968 0.017023699, + 0.035366699 0.051348701 0.016966499, + 0.0378174 0.051217601 0.0169555, + 0.035366699 0.0508858 0.0170098, + 0.034109399 0.0517992 0.0169647, + 0.040174201 0.0508755 0.017085001, + 0.0424264 0.050325502 0.017372699, + 0.044564299 0.049565699 0.0178438, + 0.0465803 0.0486123 0.018464901, + 0.048467699 0.047532901 0.0192836, + 0.050219599 0.0463669 0.020325299, + 0.051830001 0.0451531 0.021581501, + 0.0532961 0.043936599 0.0230556, + 0.0546159 0.042758498 0.0247334, + 0.055787299 0.0416587 0.026590001, + 0.056809202 0.040671099 0.028595001, + 0.0576833 0.039824199 0.0307121, + 0.058412101 0.039137401 0.032902099, + 0.058998398 0.0386241 0.035122599, + 0.059445001 0.038288999 0.037332602, + 0.059757002 0.038131699 0.0394907, + 0.0599402 0.038144 0.041563701, + 0.059999999 0.0382808 0.043536901, + 0.0599402 0.0385768 0.045428999, + 0.059757002 0.039063498 0.0473409, + 0.059445001 0.0396493 0.0492923, + 0.058998398 0.040352002 0.051265098, + 0.058412101 0.041185498 0.053240102, + 0.0576833 0.0421593 0.055198301, + 0.056809202 0.0432803 0.0571201, + 0.055787299 0.044554502 0.058985099, + 0.0546159 0.045986101 0.060772099, + 0.0532961 0.047575399 0.062465299, + 0.051830001 0.049343102 0.064050399, + 0.050219599 0.051291399 0.065501697, + 0.048467699 0.053408399 0.066796601, + 0.0465803 0.055681601 0.067915, + 0.044564299 0.0580968 0.068837002, + 0.0424264 0.060640302 0.069543503, + 0.040174201 0.063296497 0.0700178, + 0.0378174 0.070094697 0.068668097, + 0.035366699 0.0772641 0.067424797, + 0.0328326 0.084773101 0.0662916, + 0.0302257 0.092590503 0.0652721, + 0.027557701 0.100684 0.064372003, + 0.0248404 0.109019 0.063596196, + 0.0220857 0.117566 0.062947303, + 0.019305199 0.126289 0.062427599, + 0.0165099 0.135158 0.0620417, + 0.0137106 0.14413799 0.061793901, + 0.0109179 0.153201 0.061685, + 0.0109156 0.171451 0.0611219, + 0.0092316195 0.171451 0.061411198, + 0.0109179 0.162333 0.061270799, + 0.0081421202 0.162315 0.061716601, + 0.0137106 0.162358 0.060685299, + 0.016506201 0.171452 0.059806101, + 0.0152764 0.171452 0.0601441, + 0.0165099 0.162388 0.059957199, + 0.019305199 0.162425 0.059083901, + 0.0220857 0.162468 0.058062699, + 0.021159001 0.171454 0.0582636, + 0.0248404 0.162517 0.0568919, + 0.0228623 0.171454 0.057610098, + 0.027557701 0.153671 0.0559869, + 0.0302257 0.14495 0.055212598, + 0.0328326 0.136383 0.0545743, + 0.035366699 0.12799799 0.054077901, + 0.0378174 0.119828 0.0537275, + 0.040174201 0.111902 0.0535261, + 0.0424264 0.104252 0.0534762, + 0.044564299 0.096906699 0.0535798, + 0.0465803 0.089894101 0.053837899, + 0.048467699 0.083240204 0.054251, + 0.050219599 0.076970503 0.054818001, + 0.051830001 0.071110003 0.055537, + 0.0532961 0.069083802 0.054519501, + 0.0546159 0.067173302 0.053357702, + 0.055787299 0.065389201 0.052072801, + 0.056809202 0.063739501 0.0506863, + 0.0576833 0.0622329 0.049219102, + 0.058412101 0.060876299 0.047691599, + 0.058998398 0.0596756 0.0461253, + 0.059445001 0.058616702 0.044546101, + 0.059757002 0.057661399 0.042961098, + 0.0599402 0.056807399 0.0413762, + 0.059999999 0.0560655 0.039785799, + 0.0599402 0.055454001 0.038178898, + 0.059757002 0.054992601 0.036545798, + 0.059445001 0.0546978 0.0348824, + 0.058998398 0.054563999 0.0332058, + 0.058412101 0.054571301 0.031539999, + 0.0576833 0.0547674 0.0298925, + 0.056809202 0.055104699 0.028216099, + 0.055787299 0.0555267 0.026524501, + 0.0546159 0.056038 0.0248503, + 0.0532961 0.056630801 0.0232247, + 0.051830001 0.057293899 0.021679601, + 0.050219599 0.058010601 0.020244701, + 0.048467699 0.058758602 0.018948199, + 0.0465803 0.059512001 0.0178131, + 0.044564299 0.06024 0.016857401, + 0.0424264 0.060910001 0.0160925, + 0.040174201 0.061488502 0.0155238, + 0.0378174 0.0619452 0.0151469, + 0.035366699 0.0622508 0.0149457, + 0.0328326 0.062381499 0.0149116, + 0.0302257 0.0623184 0.0150238, + 0.027557701 0.062036399 0.0152423, + 0.0248404 0.061536402 0.0155686, + 0.0220857 0.0608273 0.015977999, + 0.019305199 0.0599126 0.0164518, + 0.0165099 0.060308401 0.016543601, + 0.0137106 0.060573898 0.0166004, + 0.0109179 0.0606374 0.016548401, + 0.0081428103 0.060543399 0.016353199, + 0.0053973799 0.060375601 0.016005101, + 0.00268824 0.0601964 0.0155485, + -0.023037801 0.171454 0.057537399, + -0.0248404 0.16251899 0.056877799, + -0.0248404 0.15356299 0.0572889, + -0.0030847499 0.059909102 0.0145477, + -0.0046291598 0.059791502 0.0145476, + -0.00268824 0.059991401 0.0150441, + -0.0053973799 0.059808701 0.0150453, + -0.0053973799 0.0600118 0.0155506, + -0.000142344 0.059988201 0.0145478, + -0.00268824 0.060195699 0.0155486, + -0.0053973799 0.060371999 0.016005401, + -0.0081428103 0.060057402 0.0160104, + -0.0081428103 0.060538299 0.0163552, + -0.0109179 0.0600866 0.016365699, + -0.0109179 0.060633499 0.0165524, + -0.0137106 0.0600386 0.0165709, + -0.0137106 0.060573 0.0166051, + -0.0165099 0.059830699 0.0166349, + -0.0165099 0.060308602 0.016546199, + -0.019305199 0.059414901 0.0165908, + -0.019305199 0.059911098 0.0164534, + -0.0220857 0.0588619 0.0165167, + -0.0220857 0.060827401 0.015979201, + -0.0248404 0.059604801 0.0161037, + -0.0248404 0.0615367 0.01557, + -0.027557701 0.060137 0.015769299, + -0.027557701 0.0620366 0.0152422, + -0.0302257 0.0604572 0.0155295, + -0.0302257 0.062318601 0.0150239, + -0.0328326 0.060556602 0.0154135, + -0.0328326 0.0623786 0.0149244, + -0.035366699 0.060433399 0.0154272, + -0.035366699 0.0622393 0.0149483, + -0.0378174 0.060118299 0.0155734, + -0.0378174 0.061928 0.0151428, + -0.040174201 0.059642602 0.015902, + -0.040174201 0.061468799 0.0155233, + -0.0424264 0.059032101 0.0164265, + -0.0424264 0.060888398 0.0160961, + -0.044564299 0.058316499 0.017150899, + -0.044564299 0.060217001 0.016864199, + -0.0465803 0.0575293 0.018075, + -0.0465803 0.0594883 0.0178237, + -0.048467699 0.056706298 0.0191913, + -0.048467699 0.058735099 0.018963, + -0.050219599 0.055880599 0.0204855, + -0.050219599 0.0579881 0.0202638, + -0.051830001 0.055082802 0.0219361, + -0.051830001 0.057273299 0.021702601, + -0.0532961 0.054339699 0.0235161, + -0.0532961 0.056613602 0.0232503, + -0.0546159 0.053672802 0.025193701, + -0.0546159 0.056024998 0.0248756, + -0.055787299 0.0530966 0.0269354, + -0.055787299 0.055518501 0.0265455, + -0.056809202 0.052620102 0.0287062, + -0.056809202 0.0551023 0.028230799, + -0.0576833 0.052249201 0.0304763, + -0.0576833 0.054769199 0.029902101, + -0.058412101 0.051973801 0.0322157, + -0.058412101 0.054552801 0.031552002, + -0.058998398 0.051828802 0.033917401, + -0.058998398 0.054535799 0.0332231, + -0.059445001 0.051899102 0.035627399, + -0.059445001 0.054680198 0.0349022, + -0.059757002 0.052143302 0.037331399, + -0.059757002 0.0549847 0.036565401, + -0.0599402 0.052553698 0.039009601, + -0.0599402 0.055451602 0.0381965, + -0.059999999 0.0531126 0.040665399, + -0.059999999 0.056065701 0.0398001, + -0.0599402 0.053801399 0.042309701, + -0.0599402 0.056808401 0.041386899, + -0.059757002 0.054602899 0.043953702, + -0.059757002 0.057662699 0.0429684, + -0.059445001 0.055506401 0.045604501, + -0.059445001 0.058618199 0.044550601, + -0.058998398 0.056519099 0.047247201, + -0.058998398 0.059678301 0.046129402, + -0.058412101 0.0576474 0.0488717, + -0.058412101 0.0608766 0.0477001, + -0.0576833 0.058921698 0.0504728, + -0.0576833 0.062231299 0.0492296, + -0.056809202 0.0603576 0.052017801, + -0.056809202 0.063737698 0.050695799, + -0.055787299 0.061949302 0.053484399, + -0.055787299 0.065388002 0.052079599, + -0.0546159 0.063688204 0.054853499, + -0.0546159 0.067172997 0.053361699, + -0.0532961 0.065564603 0.0561046, + -0.0532961 0.069083899 0.054521199, + -0.051830001 0.067568898 0.057216998, + -0.051830001 0.071109198 0.055539601, + -0.050219599 0.069688603 0.0581723, + -0.050219599 0.0769623 0.0548089, + -0.048467699 0.075695097 0.057362299, + -0.048467699 0.083226196 0.054232299, + -0.0465803 0.082108997 0.056697499, + -0.0465803 0.089877501 0.053813901, + -0.044564299 0.0889052 0.056181598, + -0.044564299 0.096889697 0.053554099, + -0.0424264 0.096056603 0.055814799, + -0.0424264 0.104235 0.053452302, + -0.040174201 0.103535 0.055596799, + -0.040174201 0.111887 0.0535064, + -0.0378174 0.11131 0.055527501, + -0.0378174 0.119815 0.053712301, + -0.035366699 0.119353 0.0556035, + -0.035366699 0.127988 0.054065201, + -0.0328326 0.12763 0.055819899, + -0.0328326 0.13637599 0.054560799, + -0.0302257 0.136112 0.056173299, + -0.0302257 0.14494801 0.055195201, + -0.027557701 0.144767 0.056662999, + -0.027557701 0.15367199 0.0559678, + -0.025727101 0.171455 0.056340899, + -0.027557701 0.16257399 0.055557299, + -0.0302257 0.15379401 0.054500401, + -0.0328326 0.145146 0.053583201, + -0.035366699 0.136663 0.052806702, + -0.0378174 0.128373 0.0521749, + -0.040174201 0.120309 0.051692199, + -0.0424264 0.112499 0.051363301, + -0.044564299 0.104974 0.0511932, + -0.0465803 0.097761497 0.051188599, + -0.048467699 0.0908885 0.051351801, + -0.050219599 0.084381603 0.051683299, + -0.051830001 0.078265801 0.052182201, + -0.0532961 0.072563 0.052845199, + -0.0546159 0.070626996 0.051775701, + -0.055787299 0.068803601 0.0505809, + -0.056809202 0.067103803 0.049279802, + -0.0576833 0.065535702 0.047892202, + -0.058412101 0.064107798 0.046437301, + -0.058998398 0.062826797 0.0449339, + -0.059445001 0.061696298 0.0434044, + -0.059757002 0.060695 0.041882701, + -0.0599402 0.059790399 0.040367201, + -0.059999999 0.0589967 0.03884, + -0.0599402 0.058329999 0.037290599, + -0.059757002 0.057808802 0.035708301, + -0.059445001 0.057448398 0.0340885, + -0.058998398 0.057244498 0.032446701, + -0.058412101 0.0571892 0.0308035, + -0.0576833 0.057283301 0.029180899, + -0.056809202 0.0575605 0.027591901, + -0.055787299 0.057940401 0.025997199, + -0.0546159 0.058389999 0.0244049, + -0.0532961 0.0589136 0.0228438, + -0.051830001 0.0595011 0.021342, + -0.050219599 0.060139801 0.019930501, + -0.048467699 0.060812298 0.0186381, + -0.0465803 0.061495699 0.017490599, + -0.044564299 0.0621638 0.0165084, + -0.0424264 0.062785603 0.0157071, + -0.040174201 0.063329898 0.0150947, + -0.0378174 0.063766502 0.0146716, + -0.035366699 0.064067602 0.0144321, + -0.0328326 0.064208202 0.014368, + -0.0302257 0.064166799 0.0144621, + -0.027557701 0.063922599 0.0146692, + -0.0248404 0.063458502 0.0149835, + -0.0220857 0.062779203 0.0153932, + -0.019305199 0.061894 0.0158707, + -0.0165099 0.0608087 0.0163993, + -0.0137106 0.061053898 0.016509, + -0.0109179 0.061170101 0.016581099, + -0.0081428103 0.0610868 0.0165381, + -0.0053973799 0.0608541 0.016347799, + -0.00268824 0.060557 0.0160024, + 0 0.060256001 0.015548, + 0.00268824 0.0605588 0.016002299, + 0.0053973799 0.060857501 0.016346499, + 0.0081428103 0.061089799 0.0165351, + 0.0109179 0.061170802 0.0165774, + 0.0137106 0.061053801 0.0165068, + 0.0165099 0.06081 0.0163978, + 0.019305199 0.061893899 0.015869601, + 0.0220857 0.062778898 0.0153919, + 0.0248404 0.063458301 0.0149836, + 0.027557701 0.063922398 0.0146691, + 0.0302257 0.064169399 0.0144504, + 0.0328326 0.064218797 0.0143656, + 0.035366699 0.064083703 0.0144359, + 0.0378174 0.063785002 0.014672, + 0.040174201 0.063350402 0.0150913, + 0.0424264 0.0628075 0.015700599, + 0.044564299 0.062186401 0.0164984, + 0.0465803 0.0615183 0.0174764, + 0.048467699 0.060834002 0.018619601, + 0.050219599 0.060159702 0.019908199, + 0.051830001 0.059517801 0.0213171, + 0.0532961 0.058926299 0.0228191, + 0.0546159 0.058398001 0.024384299, + 0.055787299 0.0579427 0.0259827, + 0.056809202 0.057558801 0.0275824, + 0.0576833 0.0573016 0.029169001, + 0.058412101 0.057217099 0.030786401, + 0.058998398 0.057262 0.032427099, + 0.059445001 0.0574563 0.034069002, + 0.059757002 0.057811201 0.035690799, + 0.0599402 0.058329798 0.037276302, + 0.059999999 0.058995701 0.038829301, + 0.0599402 0.059789199 0.040359799, + 0.059757002 0.060693499 0.0418781, + 0.059445001 0.061693601 0.043400198, + 0.058998398 0.062826499 0.044925399, + 0.058412101 0.064109497 0.046426602, + 0.0576833 0.065537497 0.047882602, + 0.056809202 0.067104898 0.049272802, + 0.055787299 0.068803899 0.050576899, + 0.0546159 0.0706269 0.051773898, + 0.0532961 0.072563902 0.052842598, + 0.051830001 0.078274302 0.0521915, + 0.050219599 0.084396198 0.0517026, + 0.048467699 0.0909058 0.051376801, + 0.0465803 0.097779103 0.051215399, + 0.044564299 0.104991 0.051218402, + 0.0424264 0.112515 0.051384099, + 0.040174201 0.120324 0.051708501, + 0.0378174 0.12838399 0.0521884, + 0.035366699 0.13666999 0.0528212, + 0.0328326 0.14514901 0.053601999, + 0.0302257 0.15379301 0.0545214, + 0.027557701 0.162572 0.055572901, + 0.0255554 0.171455 0.056422099, + 0.0275521 0.17145599 0.055421501, + 0.026817599 0.17145599 0.055789601, + 0.026825599 0.191456 0.055821698, + 0.0322018 0.191458 0.052779, + 0.030220101 0.17145699 0.053956602, + 0.032192402 0.17145801 0.052748099, + 0.032827299 0.17145801 0.052347701, + 0.0302257 0.162633 0.054107498, + 0.0328326 0.1627 0.0524978, + 0.030750699 0.17145699 0.053657301, + 0.0328326 0.153926 0.052911401, + 0.035366699 0.154071 0.0511599, + 0.035366699 0.145366 0.051849902, + 0.0378174 0.14559799 0.0499621, + 0.0378174 0.136979 0.050932601, + 0.040174201 0.13731 0.048915099, + 0.040174201 0.12879799 0.050170202, + 0.0424264 0.129236 0.0480299, + 0.0424264 0.120849 0.049567301, + 0.044564299 0.121401 0.047311701, + 0.044564299 0.113161 0.0491274, + 0.0465803 0.113837 0.046766099, + 0.0465803 0.105765 0.048855599, + 0.048467699 0.106569 0.046398699, + 0.048467699 0.098686501 0.0487567, + 0.050219599 0.099624597 0.046214201, + 0.050219599 0.091951899 0.048831802, + 0.051830001 0.093028098 0.046213798, + 0.051830001 0.085585102 0.049081098, + 0.0532961 0.086801998 0.046397898, + 0.0532961 0.0796085 0.049503598, + 0.0546159 0.080967501 0.046766002, + 0.0546159 0.0740446 0.050098401, + 0.055787299 0.075545698 0.047316398, + 0.055787299 0.072191097 0.048990499, + 0.056809202 0.073770098 0.046181001, + 0.056809202 0.070449799 0.047770102, + 0.0576833 0.072104402 0.044948298, + 0.0576833 0.0688297 0.046457998, + 0.058412101 0.070557103 0.043639101, + 0.058412101 0.067338102 0.045074701, + 0.058998398 0.069134399 0.0422737, + 0.058998398 0.0659815 0.0436408, + 0.059445001 0.064764403 0.042176701, + 0.037815198 0.171461 0.0487139, + 0.0372269 0.171461 0.049171299, + 0.0378174 0.162852 0.0488596, + 0.035366699 0.162774 0.0507464, + 0.0378174 0.154227 0.049272802, + 0.040174201 0.154393 0.047257099, + 0.040174201 0.14584699 0.047945399, + 0.0424264 0.146111 0.045807, + 0.0424264 0.137661 0.046775602, + 0.044564299 0.13803101 0.044521701, + 0.044564299 0.129697 0.045775, + 0.0465803 0.130178 0.043415599, + 0.0465803 0.12198 0.0449512, + 0.048467699 0.122582 0.042496599, + 0.048467699 0.11454 0.044310302, + 0.050219599 0.115266 0.041770998, + 0.050219599 0.1074 0.043857999, + 0.051830001 0.108256 0.041244298, + 0.051830001 0.100589 0.0435987, + 0.0532961 0.101577 0.0409218, + 0.0532961 0.0941296 0.043534402, + 0.0546159 0.095251203 0.040805399, + 0.0546159 0.088041298 0.043665301, + 0.055787299 0.089297697 0.0408949, + 0.055787299 0.082345098 0.043990601, + 0.056809202 0.0837356 0.041189302, + 0.056809202 0.077060901 0.044508401, + 0.0576833 0.078584097 0.041685399, + 0.0576833 0.0753574 0.043356501, + 0.058412101 0.0769471 0.040527999, + 0.058412101 0.0737615 0.042122401, + 0.058998398 0.075414501 0.0393034, + 0.058998398 0.0722804 0.040826801, + 0.059445001 0.070919402 0.039490201, + 0.059445001 0.077057198 0.036502, + 0.059757002 0.072685301 0.0367365, + 0.059757002 0.066681698 0.039457299, + 0.0599402 0.068573602 0.036773801, + 0.0576833 0.059876502 0.028361101, + 0.056809202 0.060027901 0.026801599, + 0.0576833 0.0624291 0.0274793, + 0.058412101 0.059842601 0.029956199, + 0.058412101 0.062452499 0.029046001, + 0.058998398 0.0599465 0.031565402, + 0.058998398 0.062614501 0.0306208, + 0.059445001 0.060199998 0.033169299, + 0.059445001 0.062924199 0.032184299, + 0.059757002 0.060611699 0.034747198, + 0.059757002 0.063389398 0.033715598, + 0.0599402 0.061184 0.036282301, + 0.0599402 0.064011902 0.0351975, + 0.059999999 0.0619005 0.037778601, + 0.059999999 0.064776197 0.036633201, + 0.0599402 0.0627428 0.039245602, + 0.059757002 0.063689999 0.040704299, + 0.0332404 0.171459 0.052087199, + 0.035362698 0.17146 0.050598498, + 0.028186901 0.17145599 0.055103399, + 0.055787299 0.060335301 0.0252847, + 0.0546159 0.0607544 0.0237701, + 0.0532961 0.061230302 0.0222732, + 0.051830001 0.061762199 0.0208249, + 0.050219599 0.062338699 0.0194533, + 0.048467699 0.0629455 0.018186299, + 0.0465803 0.063564301 0.017048201, + 0.044564299 0.064172097 0.016061001, + 0.0424264 0.0647422 0.015242, + 0.040174201 0.0652446 0.0146027, + 0.0378174 0.065651603 0.0141473, + 0.035366699 0.065935098 0.0138746, + 0.0328326 0.066068597 0.013776, + 0.0302257 0.066027798 0.0138325, + 0.027557701 0.065797001 0.0140305, + 0.0248404 0.065366298 0.0143499, + 0.0220857 0.0647204 0.014754, + 0.019305199 0.063862696 0.0152378, + 0.0165099 0.062806301 0.015776901, + 0.0137106 0.061558198 0.016352899, + 0.0109179 0.061653201 0.0164773, + 0.0081428103 0.061625499 0.016559901, + 0.0053973799 0.0614057 0.016526001, + 0.00268824 0.0610415 0.0163427, + 0 0.060617998 0.0160014, + -0.00268824 0.061039802 0.016343299, + -0.0053973799 0.0614038 0.016527999, + -0.0081428103 0.061625 0.0165627, + -0.0109179 0.061653301 0.016479, + -0.0137106 0.0615572 0.016354101, + -0.0165099 0.062806301 0.0157777, + -0.019305199 0.063862897 0.0152389, + -0.0220857 0.064720601 0.0147539, + -0.0248404 0.065366499 0.01435, + -0.027557701 0.065794602 0.0140413, + -0.0302257 0.066018 0.0138347, + -0.0328326 0.066053703 0.0137724, + -0.035366699 0.065917701 0.0138742, + -0.0378174 0.065632299 0.0141505, + -0.040174201 0.065223902 0.0146087, + -0.0424264 0.064720601 0.0152515, + -0.044564299 0.064150497 0.0160746, + -0.0465803 0.063543402 0.017065899, + -0.048467699 0.062926397 0.0182078, + -0.050219599 0.062322602 0.019477401, + -0.051830001 0.061749902 0.0208489, + -0.0532961 0.061222501 0.0222934, + -0.0546159 0.060752101 0.0237843, + -0.055787299 0.060337 0.025294, + -0.056809202 0.0600099 0.0268133, + -0.0576833 0.059848901 0.028378099, + -0.058412101 0.0598251 0.0299755, + -0.058998398 0.059938598 0.031584799, + -0.059445001 0.060197599 0.033186801, + -0.059757002 0.0606119 0.0347616, + -0.0599402 0.061184999 0.036293, + -0.059999999 0.0619017 0.037785999, + -0.0599402 0.062744297 0.039250098, + -0.059757002 0.063692696 0.0407084, + -0.059445001 0.064764798 0.042185299, + -0.058998398 0.065979898 0.043651599, + -0.058412101 0.067336299 0.045084398, + -0.0576833 0.068828598 0.046464998, + -0.056809202 0.070449501 0.047774199, + -0.055787299 0.072191298 0.048992202, + -0.0546159 0.074043699 0.050101101, + -0.0532961 0.079599798 0.049493998, + -0.051830001 0.085570201 0.049061101, + -0.050219599 0.091934197 0.0488059, + -0.048467699 0.098668002 0.048728801, + -0.0465803 0.105747 0.048829399, + -0.044564299 0.113145 0.049105499, + -0.0424264 0.120834 0.049550202, + -0.040174201 0.128786 0.0501558, + -0.0378174 0.136971 0.0509171, + -0.035366699 0.145363 0.051829498, + -0.0328326 0.153927 0.052888699, + -0.0302257 0.162635 0.054090299, + -0.028354499 0.17145599 0.055013899, + -0.041876599 0.19146401 0.045121599, + -0.040171102 0.171463 0.046697199, + -0.037236601 0.191461 0.0491997, + -0.058998398 0.078533098 0.037707999, + -0.058998398 0.081630401 0.036040802, + -0.059445001 0.0770569 0.036506299, + -0.058412101 0.080108598 0.0388612, + -0.058412101 0.086523898 0.035542101, + -0.0576833 0.085124098 0.0383626, + -0.0576833 0.091823801 0.0352653, + -0.056809202 0.090549298 0.038076799, + -0.056809202 0.097515799 0.035216801, + -0.055787299 0.096368499 0.0380098, + -0.055787299 0.103582 0.035399299, + -0.0546159 0.102563 0.038164001, + -0.0546159 0.110003 0.035813998, + -0.0532961 0.109111 0.038539201, + -0.0532961 0.116758 0.0364591, + -0.051830001 0.115994 0.039133299, + -0.051830001 0.123826 0.037326399, + -0.050219599 0.123186 0.0399382, + -0.050219599 0.131184 0.0384068, + -0.048467699 0.130666 0.040944599, + -0.048467699 0.138809 0.039690599, + -0.0465803 0.13840701 0.042144001, + -0.0465803 0.14667501 0.0411698, + -0.044564299 0.146384 0.043528501, + -0.044564299 0.15475801 0.042836301, + -0.0424264 0.154571 0.045090001, + -0.0424264 0.163029 0.0446826, + -0.040347401 0.171463 0.046544701, + -0.0418665 0.171464 0.045095, + -0.040174201 0.16294 0.0468213, + -0.0378174 0.162855 0.048838101, + -0.035366699 0.16277599 0.050726298, + -0.037225999 0.171461 0.0491702, + -0.0378174 0.154228 0.049246602, + -0.058998398 0.072279297 0.040833998, + -0.058998398 0.075414203 0.039307602, + -0.059445001 0.070917502 0.039500099, + -0.058412101 0.073761202 0.0421266, + -0.058412101 0.076947302 0.040529799, + -0.0576833 0.075357601 0.0433584, + -0.0576833 0.078583099 0.0416882, + -0.056809202 0.077059999 0.044511199, + -0.056809202 0.083726302 0.041179098, + -0.055787299 0.082336001 0.043980598, + -0.055787299 0.089281499 0.040873501, + -0.0546159 0.088025503 0.043644302, + -0.0546159 0.095231801 0.040777098, + -0.0532961 0.094110601 0.043506801, + -0.0532961 0.101557 0.0408911, + -0.051830001 0.10057 0.043568801, + -0.051830001 0.108236 0.041215099, + -0.050219599 0.107381 0.043829601, + -0.050219599 0.115247 0.0417464, + -0.048467699 0.114521 0.044286601, + -0.048467699 0.122565 0.042477101, + -0.0465803 0.121964 0.044932399, + -0.0465803 0.130165 0.043398902, + -0.044564299 0.129684 0.0457591, + -0.044564299 0.13802201 0.044503398, + -0.0424264 0.13765299 0.046758201, + -0.0424264 0.146108 0.0457827, + -0.040174201 0.145844 0.047922298, + -0.040174201 0.154394 0.047229301, + -0.038121 0.171461 0.048470002, + -0.059757002 0.072683401 0.036746498, + -0.059757002 0.069680303 0.038144901, + -0.0599402 0.0685739 0.036782499, + -0.0599402 0.066811197 0.034025501, + -0.0599402 0.072328597 0.0314571, + -0.059757002 0.068860501 0.031392898, + -0.059757002 0.066140898 0.032603599, + -0.059445001 0.068297103 0.029967399, + -0.059445001 0.065625302 0.031125201, + -0.058998398 0.067884304 0.0284959, + -0.058998398 0.065261804 0.029608, + -0.058412101 0.067614101 0.0270008, + -0.058412101 0.065042101 0.028073199, + -0.0576833 0.0674778 0.025502, + -0.0576833 0.064956799 0.026539501, + -0.056809202 0.067465201 0.0240175, + -0.056809202 0.064995103 0.025025001, + -0.055787299 0.065146796 0.0235471, + -0.055787299 0.067564502 0.022564599, + -0.0546159 0.065408997 0.022125, + -0.055787299 0.0699604 0.0215089, + -0.056809202 0.069909997 0.022934699, + -0.0576833 0.069972001 0.024387499, + -0.058412101 0.070157699 0.025849899, + -0.058998398 0.070476599 0.0273028, + -0.059445001 0.070937201 0.028725, + -0.059757002 0.074220397 0.028773701, + -0.0599402 0.077884197 0.028636601, + -0.059999999 0.076155096 0.031332999, + -0.059999999 0.081876896 0.0282865, + -0.0599402 0.080285601 0.0310001, + -0.0599402 0.086114898 0.0277298, + -0.059757002 0.084638603 0.0304657, + -0.059757002 0.090680897 0.027166201, + -0.059445001 0.089308001 0.0299323, + -0.059445001 0.095639102 0.026849801, + -0.058998398 0.094373703 0.0296409, + -0.058998398 0.100977 0.026791601, + -0.058412101 0.099824503 0.029596901, + -0.058412101 0.106681 0.0269942, + -0.0576833 0.105644 0.0298035, + -0.0576833 0.112734 0.027459599, + -0.056809202 0.111818 0.0302628, + -0.056809202 0.119122 0.028187601, + -0.055787299 0.118325 0.030974301, + -0.055787299 0.12582301 0.0291715, + -0.0546159 0.125148 0.0319313, + -0.0546159 0.132819 0.030403201, + -0.0532961 0.132263 0.033124201, + -0.0532961 0.14008901 0.0318732, + -0.051830001 0.139652 0.034543999, + -0.051830001 0.14761101 0.033572, + -0.050219599 0.14729001 0.036180899, + -0.050219599 0.15536501 0.0354908, + -0.048467699 0.155155 0.038026299, + -0.0465803 0.163222 0.0400723, + -0.044564299 0.163123 0.0424297, + -0.0460645 0.171468 0.040564898, + -0.0465803 0.154953 0.0404783, + -0.048467699 0.14697701 0.038717002, + -0.050219599 0.13922399 0.037153699, + -0.051830001 0.13171799 0.035796098, + -0.0532961 0.12448 0.034653399, + -0.0546159 0.117536 0.033735398, + -0.055787299 0.110906 0.033051301, + -0.056809202 0.10461 0.0326088, + -0.0576833 0.098669298 0.032408901, + -0.058412101 0.093100302 0.032449599, + -0.058998398 0.087920398 0.032728299, + -0.059445001 0.083142601 0.033238299, + -0.059757002 0.078681998 0.033734899, + -0.0599402 0.074425898 0.034029301, + -0.059999999 0.0704512 0.0341198, + -0.059999999 0.067617603 0.035408501, + -0.042476799 0.17146499 0.044512499, + -0.044503901 0.17146599 0.042378299, + -0.0424252 0.17146499 0.044561699, + -0.0378129 0.171461 0.048710998, + -0.0358027 0.17146 0.050283801, + -0.032825802 0.17145801 0.052345399, + -0.0322018 0.191458 0.052779, + -0.033398401 0.171459 0.051981699, + -0.035360798 0.17146 0.050595898, + -0.0378174 0.048956402 0.017111501, + -0.0378174 0.048522599 0.0170851, + -0.0390082 0.0479417 0.0171619, + -0.0378174 0.049408101 0.0170862, + -0.035366699 0.050886199 0.017015399, + -0.040174201 0.047338098 0.017210901, + -0.040174201 0.049113501 0.017171601, + -0.0424264 0.046882302 0.0173987, + -0.0424264 0.048608501 0.017410001, + -0.044564299 0.0462198 0.017750001, + -0.044564299 0.047899298 0.0178139, + -0.0465803 0.045360301 0.018275799, + -0.0465803 0.046987601 0.018414101, + -0.048467699 0.044306301 0.0190071, + -0.048467699 0.045887198 0.019185999, + -0.050219599 0.043073598 0.019912999, + -0.050219599 0.044669501 0.020126401, + -0.051830001 0.041740201 0.020989699, + -0.051830001 0.043389302 0.021301599, + -0.0532961 0.042087302 0.022708099, + -0.0030374301 0.171451 0.0620596, + -0.00308863 0.171451 0.0620557, + -0.00267513 0.162295 0.062208701, + -0.0053918599 0.162303 0.062024899, + -0.0053918599 0.153138 0.062438201, + -0.0081421202 0.153165 0.062125102, + -0.0081421202 0.14401001 0.062821001, + -0.0109179 0.14406399 0.062373299, + -0.0109179 0.13494 0.063352503, + -0.0137106 0.13503499 0.062765002, + -0.0137106 0.125957 0.064026803, + -0.0165099 0.12610599 0.0632964, + -0.0165099 0.117094 0.064838797, + -0.019305199 0.117308 0.063962601, + -0.019305199 0.108383 0.065783501, + -0.0220857 0.108675 0.064758703, + -0.0220857 0.099856801 0.066855997, + -0.0248404 0.100241 0.065680496, + -0.0248404 0.091548897 0.0680518, + -0.027557701 0.092036903 0.066726699, + -0.027557701 0.083492696 0.069366202, + -0.0302257 0.084097303 0.067892902, + -0.0302257 0.075721398 0.0707938, + -0.0328326 0.076455303 0.069173701, + -0.0328326 0.068268903 0.0723285, + -0.035366699 0.0691448 0.070563197, + -0.035366699 0.061168801 0.073961802, + -0.0378174 0.062197201 0.072055899, + -0.0378174 0.0582816 0.073742002, + -0.040174201 0.059426401 0.071704999, + -0.040174201 0.055498 0.073271602, + -0.0424264 0.056763399 0.071113601, + -0.0424264 0.052836701 0.072561599, + -0.044564299 0.054226499 0.070293702, + -0.044564299 0.050314799 0.071626298, + -0.0465803 0.051830601 0.069262601, + -0.0465803 0.047948498 0.070482902, + -0.048467699 0.049591199 0.068038397, + -0.048467699 0.0457533 0.069150001, + -0.050219599 0.047522899 0.066639997, + -0.050219599 0.0437418 0.067648701, + -0.051830001 0.0456376 0.065088898, + -0.051830001 0.041913699 0.066009402, + -0.0532961 0.043931998 0.063416801, + -0.0532961 0.040258002 0.064245999, + -0.0546159 0.042392101 0.061636999, + -0.0546159 0.038775299 0.062374301, + -0.055787299 0.041017801 0.059764501, + -0.055787299 0.037462901 0.0604169, + -0.056809202 0.039804898 0.0578214, + -0.056809202 0.0363153 0.058395199, + -0.0576833 0.038747601 0.055828199, + -0.0576833 0.035326201 0.056329299, + -0.058412101 0.037838198 0.053803898, + -0.058412101 0.034486901 0.054238301, + -0.058998398 0.037067398 0.051767301, + -0.058998398 0.033790201 0.052141201, + -0.059445001 0.0364266 0.049736999, + -0.059445001 0.033237699 0.0500613, + -0.059757002 0.035915501 0.047736, + -0.059757002 0.032892901 0.048007399, + -0.0599402 0.0355982 0.045768499, + -0.0599402 0.032653801 0.045898098, + -0.059999999 0.0353976 0.0437387, + -0.059999999 0.032496799 0.043707099, + -0.0599402 0.035298899 0.041618198, + -0.0599402 0.0324765 0.0414382, + -0.059757002 0.035356399 0.0394127, + -0.059757002 0.032630801 0.039098699, + -0.059445001 0.035601798 0.0371354, + -0.059445001 0.032992698 0.036712199, + -0.058998398 0.0360438 0.0348261, + -0.058998398 0.033566799 0.034320898, + -0.058412101 0.036678798 0.0325296, + -0.058412101 0.034342099 0.031973202, + -0.0576833 0.0374952 0.0302916, + -0.0576833 0.035301398 0.029713901, + -0.056809202 0.038474299 0.028154099, + -0.056809202 0.036418401 0.027585199, + -0.055787299 0.0395891 0.0261568, + -0.055787299 0.037661199 0.025622901, + -0.0546159 0.040806599 0.0243327, + -0.0546159 0.038990799 0.0238561, + -0.0532961 0.0387422 0.021873301, + -0.051830001 0.0401791 0.0206607, + -0.050219599 0.041533701 0.019620201, + -0.048467699 0.042719901 0.0187562, + -0.0465803 0.043720301 0.018105701, + -0.044564299 0.044531502 0.017638, + -0.0424264 0.045143001 0.017343201, + -0.041313998 0.0458172 0.0172676, + -0.033437699 0.049807198 0.0145397, + -0.032825399 0.0501968 0.01454, + -0.033494599 0.049773 0.0095396396, + -0.024833901 0.054589801 0.0145435, + -0.0226037 0.055571798 0.0095442496, + -0.025769901 0.054172501 0.0145431, + -0.0230815 0.055371098 0.0145441, + -0.0248404 0.054668799 0.0150721, + -0.027557701 0.053348899 0.0150787, + -0.027557701 0.053533401 0.015616, + -0.0302257 0.0520637 0.015630901, + -0.0302257 0.052395001 0.0161319, + -0.027557701 0.053869698 0.0161086, + -0.0248404 0.054856502 0.0156027, + -0.0220857 0.055840299 0.0150663, + -0.0225999 0.0555581 0.0145442, + -0.0220796 0.0557601 0.0145444, + -0.0203376 0.056436501 0.0145449, + -0.019300001 0.056781799 0.0145452, + -0.0167691 0.0576014 0.0095458701, + -0.0175448 0.057365902 0.0145457, + -0.019305199 0.056862101 0.0150611, + -0.0220857 0.056030899 0.0155908, + -0.0248404 0.055197299 0.016087599, + -0.0220857 0.057899602 0.016712099, + -0.019305199 0.058940299 0.016670501, + -0.020698 0.057913002 0.016636699, + -0.0220857 0.058370199 0.0166429, + -0.0248404 0.057172399 0.016702499, + -0.0248404 0.057659 0.0165892, + -0.027557701 0.056303799 0.016670801, + -0.027557701 0.058227301 0.016244, + -0.0302257 0.0566971 0.016399801, + -0.0302257 0.058582101 0.0159906, + -0.0328326 0.0568741 0.016233699, + -0.0328326 0.058722101 0.0158452, + -0.035366699 0.056834601 0.016188599, + -0.035366699 0.058639899 0.015837399, + -0.0378174 0.0565749 0.016294099, + -0.0378174 0.0583378 0.0159689, + -0.040174201 0.056099299 0.0165473, + -0.040174201 0.0578527 0.0162411, + -0.0424264 0.055450201 0.016949199, + -0.0424264 0.057219099 0.016706999, + -0.044564299 0.054666001 0.017555101, + -0.044564299 0.056465399 0.017378001, + -0.0465803 0.053779501 0.018373599, + -0.0465803 0.0556252 0.0182548, + -0.048467699 0.052826598 0.0194027, + -0.048467699 0.054734401 0.019334, + -0.050219599 0.0518445 0.020635899, + -0.050219599 0.053829599 0.020605501, + -0.051830001 0.050870299 0.022060201, + -0.051830001 0.052944198 0.022051699, + -0.0532961 0.049938899 0.023654601, + -0.0532961 0.052109599 0.0236475, + -0.0546159 0.049081501 0.025390601, + -0.0546159 0.051351901 0.025363101, + -0.055787299 0.048323002 0.027235599, + -0.055787299 0.0506914 0.0271639, + -0.056809202 0.0476822 0.0291525, + -0.056809202 0.050140802 0.029014301, + -0.0576833 0.047169302 0.0311043, + -0.0576833 0.049706299 0.0308783, + -0.058412101 0.046788301 0.033053599, + -0.058412101 0.049391899 0.032725099, + -0.058998398 0.0465414 0.034968499, + -0.058998398 0.049185 0.0345238, + -0.059445001 0.046413898 0.036817301, + -0.059445001 0.049121998 0.036267798, + -0.059757002 0.046444301 0.038593199, + -0.059757002 0.049290702 0.038006101, + -0.0599402 0.046716802 0.040353298, + -0.0599402 0.049639899 0.0397285, + -0.059999999 0.047155801 0.042107198, + -0.059999999 0.050141301 0.041434798, + -0.0599402 0.047729 0.0438601, + -0.0599402 0.050773598 0.043134298, + -0.059757002 0.048416398 0.045622502, + -0.059757002 0.051519498 0.0448386, + -0.059445001 0.049207099 0.047401499, + -0.059445001 0.052368 0.0465548, + -0.058998398 0.0501091 0.049183901, + -0.058998398 0.053326901 0.0482691, + -0.058412101 0.051133499 0.050950501, + -0.058412101 0.054406501 0.049961001, + -0.0576833 0.052289002 0.052681301, + -0.0576833 0.0556117 0.051620599, + -0.056809202 0.053578999 0.054365501, + -0.056809202 0.056969602 0.053241499, + -0.055787299 0.055027898 0.055995502, + -0.055787299 0.0584938 0.054791201, + -0.0546159 0.056647301 0.057538901, + -0.0546159 0.060177501 0.056247301, + -0.0532961 0.0584298 0.058972601, + -0.0532961 0.0620116 0.057589699, + -0.051830001 0.0603652 0.060276199, + -0.051830001 0.0639854 0.058797799, + -0.050219599 0.062442299 0.061429299, + -0.050219599 0.066088498 0.059851099, + -0.048467699 0.064649403 0.062411699, + -0.048467699 0.068307698 0.0607315, + -0.0465803 0.0669723 0.063206397, + -0.0465803 0.074469797 0.059831601, + -0.044564299 0.073291399 0.062206302, + -0.044564299 0.081034496 0.059068099, + -0.0424264 0.080007799 0.061333701, + -0.0424264 0.087976098 0.058444399, + -0.040174201 0.087094203 0.060592301, + -0.040174201 0.095265903 0.057960801, + -0.0378174 0.094520301 0.059984501, + -0.0378174 0.102874 0.057619002, + -0.035366699 0.102256 0.059512399, + -0.035366699 0.11077 0.057419699, + -0.0328326 0.110269 0.059176099, + -0.0328326 0.118922 0.057358898, + -0.0302257 0.118528 0.058972601, + -0.0302257 0.12730099 0.057433002, + -0.027557701 0.127001 0.058901399, + -0.027557701 0.13587201 0.057641301, + -0.0248404 0.135656 0.0589629, + -0.0248404 0.144605 0.0579843, + -0.0220857 0.14445999 0.0591571, + -0.0220857 0.153466 0.058461599, + -0.019305199 0.153382 0.059484601, + -0.019305199 0.16242599 0.059072901, + -0.0165099 0.162389 0.0599478, + -0.0174994 0.171453 0.0595279, + -0.0109179 0.162334 0.061264601, + -0.0117927 0.171452 0.060966201, + -0.0137106 0.162359 0.060677499, + -0.0137106 0.153249 0.06109, + -0.0081421202 0.16231599 0.061712001, + -0.0092321504 0.171451 0.061414398, + -0.0109179 0.153201 0.0616774, + -0.0137106 0.144137 0.061786, + -0.0165099 0.144226 0.061055899, + -0.0165099 0.13515399 0.062034901, + -0.019305199 0.135297 0.061159499, + -0.019305199 0.126283 0.0624207, + -0.0220857 0.12649199 0.061396901, + -0.0220857 0.117558 0.0629384, + -0.0248404 0.117845 0.0617644, + -0.0248404 0.10901 0.063584, + -0.027557701 0.109388 0.062260602, + -0.027557701 0.100673 0.064356402, + -0.0302257 0.101153 0.0628855, + -0.0302257 0.092578903 0.065254703, + -0.0328326 0.093174301 0.063637897, + -0.0328326 0.0847615 0.066274703, + -0.035366699 0.085484102 0.064514302, + -0.035366699 0.077253804 0.067411102, + -0.0378174 0.078114301 0.065512396, + -0.0378174 0.070088401 0.068661302, + -0.040174201 0.071096502 0.066629902, + -0.040174201 0.063295901 0.070019901, + -0.0424264 0.064460799 0.067860901, + -0.0424264 0.060640398 0.069544896, + -0.044564299 0.061919499 0.067269199, + -0.044564299 0.058096599 0.068840198, + -0.0465803 0.059491601 0.066461198, + -0.0465803 0.0556807 0.0679207, + -0.048467699 0.057193 0.065453, + -0.048467699 0.053406902 0.0668047, + -0.050219599 0.055036802 0.064263098, + -0.050219599 0.051289901 0.065510802, + -0.051830001 0.053037401 0.062910601, + -0.051830001 0.0493434 0.064057902, + -0.0532961 0.0512066 0.0614154, + -0.0532961 0.047577798 0.062469002, + -0.0546159 0.0495538 0.0598008, + -0.0546159 0.045987502 0.060776301, + -0.055787299 0.048071299 0.058099501, + -0.055787299 0.044555701 0.058991998, + -0.056809202 0.0467395 0.056322299, + -0.056809202 0.043281302 0.0571303, + -0.0576833 0.045556799 0.054482002, + -0.0576833 0.0421593 0.055212099, + -0.058412101 0.044517301 0.052599002, + -0.058412101 0.0411832 0.053257301, + -0.058998398 0.043613002 0.050692402, + -0.058998398 0.040344201 0.051284499, + -0.059445001 0.042834401 0.048781, + -0.059445001 0.039631501 0.049311999, + -0.059757002 0.042168502 0.046882801, + -0.059757002 0.039034899 0.047358502, + -0.0599402 0.041608799 0.045011301, + -0.0599402 0.038557801 0.0454414, + -0.059999999 0.041179799 0.0431646, + -0.059999999 0.038282599 0.0435468, + -0.0599402 0.040967099 0.0413251, + -0.0599402 0.0381415 0.041579299, + -0.059757002 0.040906601 0.0394031, + -0.059757002 0.038122799 0.039513201, + -0.059445001 0.0409845 0.037379902, + -0.059445001 0.038274899 0.037360098, + -0.058998398 0.0412248 0.035285302, + -0.058998398 0.038605101 0.0351508, + -0.058412101 0.0416274 0.033153702, + -0.058412101 0.039114401 0.032928102, + -0.0576833 0.042192299 0.0310253, + -0.0576833 0.0397982 0.030734001, + -0.056809202 0.042913198 0.0289411, + -0.056809202 0.040643599 0.028612301, + -0.055787299 0.043775398 0.026942, + -0.055787299 0.041630398 0.0266026, + -0.0546159 0.0447574 0.0250654, + -0.0546159 0.042730398 0.0247417, + -0.0532961 0.045829002 0.0233458, + -0.0532961 0.043909501 0.0230601, + -0.051830001 0.046955999 0.0218105, + -0.051830001 0.045127701 0.021580899, + -0.050219599 0.048098601 0.020479601, + -0.050219599 0.046344101 0.020319801, + -0.048467699 0.049216598 0.019365501, + -0.048467699 0.047517199 0.0192871, + -0.0465803 0.050271001 0.018475501, + -0.0465803 0.048608299 0.018483, + -0.044564299 0.051224899 0.017806901, + -0.044564299 0.049566001 0.017844001, + -0.0424264 0.052030101 0.017299, + -0.0424264 0.0503259 0.017372601, + -0.040174201 0.052629098 0.0169535, + -0.040174201 0.050875999 0.017087299, + -0.0378174 0.053014301 0.016783001, + -0.0378174 0.051217798 0.0169574, + -0.035366699 0.053187702 0.016757, + -0.035366699 0.051346101 0.0169695, + -0.0328326 0.053144898 0.0168611, + -0.0328326 0.0526774 0.0169263, + -0.0302257 0.054324001 0.016844399, + -0.031537499 0.053067401 0.0169046, + -0.027557701 0.055822998 0.0167698, + -0.0288986 0.054634299 0.016842199, + -0.0302257 0.054798499 0.0167615, + -0.0328326 0.055016201 0.016570801, + -0.035366699 0.055016 0.0164981, + -0.0378174 0.0548012 0.016558399, + -0.040174201 0.054369301 0.016781799, + -0.0424264 0.053725701 0.017160701, + -0.044564299 0.052919298 0.017695, + -0.0465803 0.051994499 0.018442599, + -0.048467699 0.050986599 0.019409001, + -0.050219599 0.0499328 0.020589599, + -0.051830001 0.048871499 0.0219751, + -0.0532961 0.047841799 0.0235491, + -0.0546159 0.0468782 0.025287, + -0.055787299 0.046011701 0.0271575, + -0.056809202 0.045265801 0.0291255, + -0.0576833 0.0446571 0.0311516, + -0.058412101 0.044193499 0.033197299, + -0.058998398 0.0438773 0.0352237, + -0.059445001 0.043708902 0.037197702, + -0.059757002 0.043672401 0.0390862, + -0.0599402 0.0438019 0.040887699, + -0.059999999 0.044162702 0.042682301, + -0.0599402 0.0446718 0.0444858, + -0.059757002 0.045297898 0.0463042, + -0.059445001 0.046027601 0.048143901, + -0.058998398 0.046869598 0.049991898, + -0.058412101 0.0478356 0.0518298, + -0.0576833 0.048934899 0.053638399, + -0.056809202 0.050174501 0.0553976, + -0.055787299 0.051557101 0.0570958, + -0.0546159 0.053104199 0.058724001, + -0.0532961 0.054825801 0.060249299, + -0.051830001 0.0567136 0.0616486, + -0.050219599 0.058756601 0.062901199, + -0.048467699 0.0609423 0.0639873, + -0.0465803 0.063257702 0.064887904, + -0.044564299 0.065688103 0.065586403, + -0.0424264 0.072165303 0.0644757, + -0.040174201 0.079033203 0.063484304, + -0.0378174 0.086262599 0.062617898, + -0.035366699 0.0938223 0.061879199, + -0.0328326 0.101681 0.061269902, + -0.0302257 0.109808 0.060790699, + -0.027557701 0.118169 0.060441799, + -0.0248404 0.12673201 0.060223401, + -0.0220857 0.135464 0.060136002, + -0.019305199 0.144334 0.0601804, + -0.0165099 0.15331 0.06036, + -0.015277 0.171452 0.060146399, + -0.0262044 0.056053199 0.0167857, + -0.0248404 0.055658899 0.016466601, + -0.023467001 0.0562694 0.0164528, + -0.0248404 0.0561876 0.0166898, + -0.0262044 0.055537 0.016709801, + -0.027557701 0.055362299 0.016813301, + -0.027557701 0.054848999 0.016731, + -0.0262044 0.055011101 0.016481301, + -0.027557701 0.054326098 0.0164969, + -0.0288986 0.054124001 0.0167532, + -0.0302257 0.053869199 0.0168727, + -0.0302257 0.053362101 0.016776601, + -0.0288986 0.0536041 0.0165132, + -0.0302257 0.0528455 0.0165304, + -0.031537499 0.0525636 0.0168011, + -0.0328326 0.052229099 0.0169379, + -0.034109399 0.051354699 0.0169727, + -0.0328326 0.0517288 0.0168266, + -0.031537499 0.052050401 0.016548401, + -0.0328326 0.0507752 0.016157599, + -0.035366699 0.049013302 0.0161855, + -0.0378174 0.047115099 0.016215499, + -0.036603201 0.048514102 0.016628301, + -0.035366699 0.048693102 0.015664799, + -0.040174201 0.045087699 0.0162476, + -0.0390082 0.046542499 0.0166729, + -0.0378174 0.046801101 0.015683901, + -0.035366699 0.0485195 0.0151023, + -0.0328326 0.050271802 0.0150938, + -0.033493701 0.049767699 0.0145396, + -0.030218599 0.051805999 0.0145413, + -0.0281986 0.052953102 0.00954217, + -0.030954201 0.051387198 0.0145409, + -0.0283962 0.052843399 0.0145421, + -0.0302257 0.051882599 0.0150859, + -0.0328326 0.050449301 0.0156471, + -0.034109399 0.050352301 0.016586799, + -0.028196299 0.052944601 0.0145422, + -0.0275509 0.053271201 0.0145424, + 0.059692498 0.0060553099 0.0145048, + 0.059744101 0.0053848098 0.0145043, + 0.059682 0.00616168 0.0095049096, + 0.058998398 0.0109309 0.0152639, + 0.0587232 0.0122597 0.0145098, + 0.058412101 0.0137252 0.0152509, + 0.058998398 0.0110715 0.0160405, + 0.059445001 0.0082903402 0.016068401, + 0.059445001 0.0085070599 0.016823599, + 0.059757002 0.0060091098 0.017571401, + 0.0546159 -0.0127807 0.051533502, + 0.055787299 -0.0107478 0.0488385, + 0.0546159 -0.0116027 0.052773599, + 0.0532961 -0.0146871 0.0542899, + 0.0532961 -0.0134315 0.055543501, + 0.051830001 -0.0164496 0.057089999, + 0.051830001 -0.0151149 0.0583486, + 0.050219599 -0.0180513 0.059914801, + 0.050219599 -0.016636699 0.061169401, + 0.048467699 -0.019477099 0.062744103, + 0.048467699 -0.0179836 0.063986003, + 0.0465803 -0.0207147 0.065558203, + 0.0465803 -0.0191443 0.066778697, + 0.044564299 -0.021754 0.068336397, + 0.044564299 -0.0201093 0.0695263, + 0.0424264 -0.022585901 0.071057402, + 0.0424264 -0.020870199 0.0722076, + 0.040174201 -0.0232033 0.073699698, + 0.040174201 -0.0214216 0.0748026, + 0.0378174 -0.0236036 0.076244801, + 0.0378174 -0.021761701 0.077293098, + 0.035366699 -0.023786901 0.078674801, + 0.035366699 -0.021891 0.079661101, + 0.0328326 -0.0237536 0.080971397, + 0.0328326 -0.021810699 0.0818891, + 0.0302257 -0.023506399 0.083117902, + 0.0302257 -0.021522401 0.083962299, + 0.027557701 -0.0230508 0.085101999, + 0.027557701 -0.021032 0.085869104, + 0.0248404 -0.022393599 0.0869129, + 0.0248404 -0.020346699 0.0875993, + 0.0220857 -0.0215423 0.088540703, + 0.0220857 -0.019477 0.089143001, + 0.019305199 -0.020508699 0.0899764, + 0.019305199 -0.0184473 0.0904897, + 0.0165099 -0.01932 0.091212302, + 0.0165099 -0.0172497 0.091641001, + 0.0137106 -0.0179695 0.092251197, + 0.0137106 -0.015781401 0.092630297, + 0.0109179 -0.0163536 0.093127102, + 0.0109179 -0.0118731 0.093787, + 0.0081421202 -0.0122981 0.094174303, + 0.0081421202 -0.0077637001 0.094694003, + 0.0053918599 -0.0080525 0.094970502, + 0.0053918599 -0.00347784 0.0953357, + 0.00267513 -0.00364236 0.095501401, + 0.00267513 0.00096041098 0.0957065, + 0 0.00090833602 0.095761903, + 0 0.0055275899 0.095803797, + -0.00267513 0.00096032 0.095707297, + -0.00267513 -0.0036427299 0.095502198, + -0.0053918599 -0.0034785401 0.095337503, + -0.0053918599 -0.0080541195 0.094972298, + -0.0081421202 -0.0077661402 0.094696604, + -0.0081421202 -0.012302 0.094176702, + -0.0109179 -0.0118783 0.0937903, + -0.0109179 -0.0163571 0.0931293, + -0.0137106 -0.0157857 0.092633098, + -0.0137106 -0.017970299 0.092253402, + -0.0165099 -0.017250599 0.091643699, + -0.0165099 -0.019319501 0.091215096, + -0.019305199 -0.018446701 0.090492897, + -0.019305199 -0.0205085 0.089980297, + -0.0220857 -0.019476701 0.089147501, + -0.0220857 -0.0215433 0.0885465, + -0.0248404 -0.0203477 0.087605797, + -0.0248404 -0.022396 0.086920798, + -0.027557701 -0.021034701 0.085877903, + -0.027557701 -0.0230549 0.0851124, + -0.0302257 -0.021526899 0.083973698, + -0.0302257 -0.0235123 0.083130799, + -0.0328326 -0.021817001 0.081903197, + -0.0328326 -0.0237615 0.080986597, + -0.035366699 -0.021899501 0.0796775, + -0.035366699 -0.023796899 0.078691699, + -0.0378174 -0.0217724 0.077311203, + -0.0378174 -0.0236158 0.076263003, + -0.040174201 -0.021434501 0.0748218, + -0.040174201 -0.0232177 0.073718399, + -0.0424264 -0.020885499 0.072227404, + -0.0424264 -0.0226027 0.071076199, + -0.044564299 -0.0201269 0.069545999, + -0.044564299 -0.021772901 0.068354897, + -0.0465803 -0.019164 0.066798002, + -0.0465803 -0.020735599 0.065575898, + -0.048467699 -0.0180053 0.064004503, + -0.048467699 -0.019499799 0.0627608, + -0.050219599 -0.0166602 0.0611866, + -0.050219599 -0.018075701 0.059930101, + -0.051830001 -0.0151401 0.058364399, + -0.051830001 -0.016475501 0.057103701, + -0.0532961 -0.0134581 0.055557702, + -0.0532961 -0.0147142 0.054301899, + -0.0546159 -0.0116304 0.052786, + -0.0546159 -0.0128088 0.051543798, + -0.055787299 -0.0096740602 0.050067399, + -0.055787299 -0.0107765 0.0488469, + -0.055787299 -0.0144795 0.0436811, + -0.0546159 -0.0168043 0.046231199, + -0.055787299 -0.0127711 0.046309799, + -0.0599402 0.0029843601 0.0169133, + -0.0599402 0.0028075001 0.016125901, + -0.059999999 0.00028193899 0.016956, + -0.059999999 0.00052374101 0.0177081, + -0.0599402 -0.0021895 0.0177691, + -0.0599402 -0.00165337 0.019070501, + -0.059757002 -0.00441236 0.019179501, + -0.059757002 -0.0039599799 0.020299099, + -0.055787299 -0.015899001 0.041003101, + -0.0546159 -0.0183565 0.043446399, + -0.056809202 -0.012748 0.039955799, + -0.056809202 -0.0139128 0.0373918, + -0.0576833 -0.0107721 0.0364662, + -0.0576833 -0.0117106 0.034061901, + -0.058412101 -0.00860254 0.0332595, + -0.058412101 -0.0093888799 0.0308808, + -0.058998398 -0.00633338 0.030205199, + -0.058998398 -0.0079687396 0.025460601, + -0.059445001 -0.0050254902 0.0250418, + -0.059445001 -0.0067788102 0.020468701, + -0.059757002 -0.00492378 0.0178304, + -0.0599402 -0.0024204601 0.016998701, + -0.059999999 0.000113206 0.016153, + -0.059935998 0.0026765901 0.0145021, + -0.0599324 0.0028361699 0.0145023, + -0.0599204 0.0030811401 0.0095024602, + -0.059748501 0.0053852098 0.0145043, + -0.059914999 0.0030767999 0.0145025, + -0.059757002 0.0055227298 0.0160986, + -0.059757002 0.0057078502 0.016870299, + -0.059445001 0.0082743801 0.016070999, + -0.0599402 0.00323702 0.017647199, + -0.059999999 0.00108433 0.018962501, + -0.0599402 -0.00117841 0.0201317, + -0.059757002 -0.0021136701 0.024627499, + -0.059445001 -0.00329723 0.0295338, + -0.058998398 -0.0055018901 0.032458801, + -0.058412101 -0.0076269298 0.035539199, + -0.0576833 -0.0095801102 0.038903002, + -0.056809202 -0.0113116 0.0425064, + -0.056809202 -0.0095967203 0.045007799, + -0.0576833 -0.0081266603 0.041325402, + -0.058412101 -0.0064076101 0.037848599, + -0.058998398 -0.0044891699 0.0346145, + -0.059445001 -0.0024208699 0.031663299, + -0.059757002 -0.00029346501 0.028869599, + -0.0599402 0.00075967598 0.024218701, + -0.059999999 0.00158166 0.0199656, + -0.0599402 0.0038220601 0.018854201, + -0.059757002 0.0059714098 0.0175859, + -0.059445001 0.0084678596 0.0168266, + -0.058998398 0.0110557 0.016043101, + -0.0592747 0.0092200805 0.0145073, + -0.053284999 0.027540499 0.0145219, + -0.053653099 0.026806001 0.0145213, + -0.0532961 0.027602 0.0152026, + -0.056809202 0.020744899 0.018185399, + -0.056809202 0.0200097 0.017270399, + -0.0576833 0.0178982 0.018298, + -0.0576833 0.018533099 0.018945299, + -0.058412101 0.0156589 0.0191183, + -0.058412101 0.018152401 0.021744, + -0.058998398 0.0151904 0.022165401, + -0.058998398 0.017557001 0.0249223, + -0.059445001 0.0145207 0.0255937, + -0.059445001 0.015660699 0.0269938, + -0.059757002 0.0126125 0.027781099, + -0.059757002 0.0138422 0.029211801, + -0.0599402 0.0107982 0.030108901, + -0.0599402 0.0121777 0.031672399, + -0.059999999 0.0091309603 0.032684799, + -0.059999999 0.0106851 0.034350399, + -0.0599402 0.00762195 0.035486199, + -0.0599402 0.0093747796 0.0372256, + -0.059757002 0.0062816702 0.0384943, + -0.059757002 0.0082509797 0.040274799, + -0.059445001 0.0051206201 0.041685, + -0.059445001 0.0073201 0.0434696, + -0.058998398 0.00417051 0.045017999, + -0.058998398 0.0066039301 0.046767399, + -0.058412101 0.0034587299 0.048444901, + -0.058412101 0.0061237598 0.050116699, + -0.0576833 0.0030046201 0.051911999, + -0.0576833 0.0058884001 0.053466301, + -0.056809202 0.0028152501 0.055365901, + -0.056809202 0.0058981301 0.056763001, + -0.019305199 0.012751 0.092659697, + -0.0220857 0.0113294 0.091802798, + -0.019305199 0.00821527 0.092827499, + -0.0165099 0.0120395 0.093487598, + -0.0165099 0.016597001 0.0931696, + -0.0137106 0.016024601 0.093869403, + -0.0137106 0.020592 0.093398102, + -0.0109179 0.0201486 0.093967699, + -0.0109179 0.024713499 0.093341298, + -0.0081421202 0.0243886 0.093779698, + -0.0081421202 0.0289384 0.092996597, + -0.0053918599 0.028720301 0.093305498, + -0.0053918599 0.033242401 0.092363998, + -0.00267513 0.033119701 0.092546403, + -0.00267513 0.037601698 0.091448098, + 0 0.037563201 0.091507703, + 0 0.0419931 0.090255298, + 0.00267513 0.037601799 0.091447599, + 0.00267513 0.033119701 0.092545897, + 0.0053918599 0.033242598 0.092363, + 0.0053918599 0.028720301 0.093304798, + 0.0081421202 0.028938301 0.092995502, + 0.0081421202 0.0243882 0.093779303, + 0.0109179 0.024713 0.093340598, + 0.0109179 0.0201483 0.093966901, + 0.0137106 0.0205917 0.093397103, + 0.0137106 0.016024301 0.093867697, + 0.0165099 0.016596699 0.093167603, + 0.0165099 0.0120392 0.0934847, + 0.019305199 0.0127507 0.092656299, + 0.019305199 0.0082152104 0.092822902, + 0.0220857 0.0090759303 0.091868602, + 0.0220857 0.0045742001 0.091889597, + 0.0248404 0.0055935201 0.090813302, + 0.0378174 -6.8612797e-005 0.083024301, + 0.035366699 -0.00186236 0.0846598, + 0.0378174 -0.0042372602 0.082606599, + 0.040174201 -0.00227051 0.080898799, + 0.040174201 -0.0042942399 0.080659702, + 0.0424264 -0.0021830699 0.078870401, + 0.0424264 -0.0040851999 0.078601301, + 0.044564299 -0.0018362 0.076739803, + 0.044564299 -0.00371387 0.076412097, + 0.0465803 -0.0013345 0.074490502, + 0.0465803 -0.0032001201 0.074102797, + 0.048467699 -0.000698674 0.072133899, + 0.048467699 -0.00253442 0.071692102, + 0.050219599 8.0006299e-005 0.069688499, + 0.050219599 -0.0017186099 0.069197297, + 0.051830001 0.00099882297 0.067171499, + 0.051830001 -0.00075841398 0.066635601, + 0.0532961 0.0020506999 0.064600296, + 0.0532961 0.00033854501 0.064024203, + 0.0546159 0.0032271901 0.0619925, + 0.0546159 0.00156349 0.061381001, + 0.055787299 0.0029072801 0.058724299, + -0.0302257 -0.0072271102 0.087338403, + -0.0302257 -0.0093684001 0.087059997, + -0.027557701 -0.00646473 0.088852398, + -0.0328326 -0.0077980701 0.085696302, + -0.0328326 -0.00988096 0.0853986, + -0.035366699 -0.0081510702 0.083932497, + -0.035366699 -0.0101168 0.083600603, + -0.0378174 -0.0082320496 0.082041003, + -0.0378174 -0.0101811 0.081643097, + -0.040174201 -0.0081456397 0.079999797, + -0.040174201 -0.0100884 0.079533599, + -0.0424264 -0.0079063596 0.077816598, + -0.0424264 -0.0098218601 0.077287503, + -0.044564299 -0.0074984799 0.075507298, + -0.044564299 -0.00937826 0.074919701, + -0.0465803 -0.0069218501 0.073088899, + -0.0465803 -0.0087608797 0.072446801, + -0.048467699 -0.0061808601 0.070578098, + -0.048467699 -0.00797466 0.069885999, + -0.050219599 -0.00528104 0.067991801, + -0.050219599 -0.0070253899 0.067254297, + -0.051830001 -0.0042288899 0.065347202, + -0.051830001 -0.0059191901 0.064571097, + -0.0532961 -0.0030321099 0.062663503, + -0.0532961 -0.0046641901 0.061855599, + -0.0546159 -0.00169957 0.059960101, + -0.0546159 -0.00326998 0.0591271, + -0.055787299 -0.000241544 0.057255201, + -0.055787299 -0.00174767 0.056403901, + -0.056809202 -0.000109933 0.053704601, + -0.0576833 0.016549399 0.0152548, + -0.0576833 0.0166605 0.0159868, + -0.056809202 0.019346001 0.0152416, + 0.019305199 -0.0053264801 0.0923599, + 0.0165099 -0.0061345799 0.093133703, + 0.019305199 -0.0097911898 0.091889098, + 0.0220857 -0.0066049499 0.091248304, + 0.055787299 -0.00459179 0.0544912, + 0.056809202 -0.00281437 0.051787999, + 0.055787299 -0.0031829299 0.0554666, + 0.0546159 -0.0062527298 0.057233501, + 0.0546159 -0.0047743199 0.058201399, + 0.0532961 -0.0077831601 0.059997302, + 0.0532961 -0.00623621 0.060949899, + 0.051830001 -0.0091698803 0.062763497, + 0.051830001 -0.0075562699 0.063692696, + 0.050219599 -0.010401 0.065511897, + 0.050219599 -0.0087238997 0.066410802, + 0.048467699 -0.0114666 0.068223402, + 0.048467699 -0.00973015 0.069085099, + 0.0465803 -0.0123595 0.070878796, + 0.0465803 -0.0105684 0.071696199, + 0.044564299 -0.0130739 0.0734585, + 0.044564299 -0.0112333 0.074224897, + 0.0424264 -0.0136048 0.075943097, + 0.0424264 -0.0117194 0.076653302, + 0.040174201 -0.0139481 0.078314804, + 0.040174201 -0.0120233 0.0789643, + 0.0378174 -0.0141033 0.080558501, + 0.0378174 -0.0121445 0.081142798, + 0.035366699 -0.014071 0.082659297, + 0.035366699 -0.0120871 0.083174303, + 0.0328326 -0.0138559 0.084602803, + 0.0328326 -0.0118672 0.085042797, + 0.0302257 -0.0134754 0.086373903, + 0.0302257 -0.0114693 0.086741298, + 0.027557701 -0.0129171 0.087968402, + 0.027557701 -0.0107892 0.088295698, + 0.0248404 -0.0120768 0.089413799, + 0.0248404 -0.0077060899 0.089988098, + 0.0220857 -0.00881969 0.091003403, + 0.0220857 -0.0132199 0.090406202, + 0.0248404 -0.0142204 0.089073204, + 0.027557701 -0.0149392 0.087585703, + 0.0302257 -0.0154817 0.085915998, + 0.0328326 -0.0158592 0.084066898, + 0.035366699 -0.0160504 0.0820508, + 0.0378174 -0.0160497 0.079881698, + 0.040174201 -0.0158558 0.077574201, + 0.0424264 -0.0154682 0.075142801, + 0.044564299 -0.0148882 0.072603799, + 0.0465803 -0.0141191 0.069976397, + 0.048467699 -0.0131663 0.067280501, + 0.050219599 -0.0120364 0.064535499, + 0.051830001 -0.0107375 0.061760802, + 0.0532961 -0.0092808502 0.058976602, + 0.0546159 -0.0076791602 0.0562029, + 0.055787299 -0.00594613 0.0534584, + 0.0576833 0.016675999 0.015984301, + 0.056809202 0.0194775 0.015956201, + 0.0576833 0.0169177 0.0166908, + 0.058412101 0.0141038 0.0167352, + 0.058412101 0.0143993 0.017383199, + 0.058998398 0.0115807 0.017446401, + 0.058998398 0.0122071 0.018502999, + 0.059445001 0.0093809301 0.018614599, + 0.059445001 0.0099466704 0.019457299, + 0.059757002 0.0071278298 0.019626901, + 0.059757002 0.0093346899 0.022995001, + 0.0599402 0.0064613498 0.0234039, + 0.0599402 0.0085524498 0.026913101, + 0.059999999 0.00561126 0.027563499, + 0.059999999 0.00662508 0.0293053, + 0.0599402 0.00364039 0.0300761, + 0.0599402 0.00477676 0.031884801, + 0.059757002 0.00173278 0.032782, + 0.059757002 0.0030410099 0.034724101, + 0.059445001 -7.0618597e-005 0.035758201, + 0.059445001 0.00143604 0.0377912, + 0.058998398 -0.0017261 0.0389635, + 0.058998398 8.9189198e-006 0.041074701, + 0.058412101 -0.00317978 0.042382699, + 0.058412101 -0.00119748 0.044536099, + 0.0576833 -0.0043896101 0.045974098, + 0.0576833 -0.0021468401 0.048125099, + 0.056809202 -0.0053197402 0.049684901, + 0.055787299 -0.0072418302 0.0523718, + 0.0546159 -0.0090489602 0.055113301, + 0.0532961 -0.0107246 0.057891499, + 0.051830001 -0.0122541 0.060688101, + 0.050219599 -0.0136243 0.063483797, + 0.048467699 -0.014823 0.0662582, + 0.0465803 -0.015840599 0.068990797, + 0.044564299 -0.016669899 0.071662098, + 0.0424264 -0.017304599 0.0742523, + 0.040174201 -0.017741101 0.076741703, + 0.0378174 -0.017978599 0.079112299, + 0.035366699 -0.018017299 0.081348799, + 0.0328326 -0.0178579 0.083436199, + 0.0302257 -0.017503001 0.0853609, + 0.027557701 -0.016961901 0.087111503, + 0.0248404 -0.0162571 0.088676602, + 0.0220857 -0.0153772 0.090053797, + 0.019305199 -0.014217 0.091271996, + 0.0165099 -0.0106224 0.092646897, + 0.0137106 -0.0068085399 0.093779199, + 0.0137106 -0.0022704201 0.094121002, + 0.0109179 -0.0027966499 0.094650298, + 0.0109179 0.00178007 0.094840303, + 0.0081421202 0.00139144 0.095250897, + 0.0081421202 0.0059951101 0.095284797, + 0.0053918599 0.0057322499 0.095576398, + 0.0053918599 0.0103511 0.095450498, + 0.00267513 0.0102021 0.095624298, + 0.00267513 0.0148243 0.095335498, + 0 0.0147773 0.095393099, + 0 0.0193907 0.0949407, + -0.00267513 0.0148243 0.095335796, + -0.00267513 0.0102021 0.0956247, + -0.0053918599 0.0103512 0.0954514, + -0.0053918599 0.0057322402 0.095577702, + -0.0081421202 0.0059951101 0.095286697, + -0.0081421202 0.0013911 0.095253304, + -0.0109179 0.00177964 0.094843604, + -0.0109179 -0.00279809 0.094653897, + -0.0137106 -0.0022722499 0.094125502, + -0.0137106 -0.0068126 0.093783699, + -0.0165099 -0.0061395098 0.093139201, + -0.0165099 -0.0106303 0.092651702, + -0.055787299 -0.0072696302 0.052386601, + -0.055787299 -0.0059732101 0.053475399, + -0.056809202 -0.0053485902 0.049697701, + -0.0546159 -0.00907546 0.055129901, + -0.0546159 -0.0077047399 0.056221701, + -0.0532961 -0.0107496 0.057909802, + -0.0532961 -0.00930476 0.058996901, + -0.051830001 -0.0122773 0.0607077, + -0.051830001 -0.0107595 0.0617822, + -0.050219599 -0.0136455 0.063504599, + -0.050219599 -0.0120562 0.064557798, + -0.048467699 -0.0148421 0.066279702, + -0.048467699 -0.0131838 0.067303099, + -0.0465803 -0.015857499 0.069012597, + -0.0465803 -0.0141341 0.069998696, + -0.044564299 -0.016684201 0.071683504, + -0.044564299 -0.0149007 0.072625197, + -0.0424264 -0.0173166 0.0742727, + -0.0424264 -0.0154784 0.0751625, + -0.040174201 -0.0177506 0.0767603, + -0.040174201 -0.015863599 0.077591397, + -0.0378174 -0.017985901 0.079128496, + -0.0378174 -0.016055301 0.079896003, + -0.035366699 -0.0180225 0.081362098, + -0.035366699 -0.0160539 0.082062103, + -0.0328326 -0.0178612 0.083446696, + -0.0328326 -0.015860699 0.084075503, + -0.0302257 -0.017504301 0.0853687, + -0.0302257 -0.0154813 0.085922197, + -0.027557701 -0.016961601 0.087117098, + -0.027557701 -0.0149385 0.087590203, + -0.0248404 -0.016256399 0.088680796, + -0.0248404 -0.0142218 0.089077197, + -0.0220857 -0.0153786 0.090057403, + -0.0220857 -0.0132269 0.090410799, + -0.019305199 -0.0142231 0.091275997, + -0.019305199 -0.0098004397 0.091894798, + -0.019305199 -0.0053322199 0.092366301, + -0.0220857 -0.0066138399 0.0912553, + -0.055787299 -0.0046179299 0.054510299, + -0.055787299 -0.0032079399 0.0554878, + -0.056809202 -0.0028419399 0.051805299, + -0.0546159 -0.0062772199 0.0572543, + -0.0546159 -0.00479746 0.058224101, + -0.0532961 -0.00780576 0.0600194, + -0.0532961 -0.0062572602 0.060973499, + -0.051830001 -0.0091903498 0.062786497, + -0.051830001 -0.0075749699 0.063716903, + -0.050219599 -0.0104191 0.065535299, + -0.050219599 -0.0087400898 0.066434897, + -0.048467699 -0.0114822 0.0682467, + -0.048467699 -0.0097438097 0.0691083, + -0.0465803 -0.0123727 0.0709012, + -0.0465803 -0.0105795 0.071717702, + -0.044564299 -0.0130845 0.073479198, + -0.044564299 -0.0112419 0.074244, + -0.0424264 -0.013613 0.075961299, + -0.0424264 -0.0117258 0.076669298, + -0.040174201 -0.0139541 0.078330003, + -0.040174201 -0.0120273 0.078977101, + -0.0378174 -0.014107 0.080570497, + -0.0378174 -0.0121461 0.0811527, + -0.035366699 -0.0140725 0.082668498, + -0.035366699 -0.0120866 0.083181597, + -0.0328326 -0.0138555 0.084609598, + -0.0328326 -0.0118663 0.085048199, + -0.0302257 -0.0134744 0.086378902, + -0.0302257 -0.0114711 0.086746097, + -0.027557701 -0.0129188 0.087972797, + -0.027557701 -0.0107979 0.088301398, + -0.0248404 -0.0120847 0.089418903, + -0.0248404 -0.00771796 0.089995399, + -0.0220857 -0.0088302502 0.0910099, + -0.0576833 -0.00217615 0.048138101, + -0.0576833 -0.0044193701 0.045982901, + -0.058412101 -0.00122764 0.044544999, + -0.058412101 -0.0032094701 0.042387702, + -0.058998398 -2.1084101e-005 0.0410797, + -0.058998398 -0.00175509 0.038962901, + -0.059445001 0.00140683 0.0377905, + -0.059445001 -9.76214e-005 0.0357516, + -0.059757002 0.00301386 0.034717601, + -0.059757002 0.00171342 0.0327865, + -0.0599402 0.00475732 0.031889301, + -0.0599402 0.00363521 0.030099399, + -0.059999999 0.0066198702 0.0293287, + -0.059999999 0.0056117801 0.0275637, + -0.0599402 0.0085529396 0.0269133, + -0.0599402 0.0064620101 0.0234074, + -0.059757002 0.0093353298 0.0229984, + -0.059757002 0.0071233502 0.019632, + -0.059445001 0.0099422103 0.0194623, + -0.059445001 0.0093770102 0.0186348, + -0.058998398 0.0122032 0.018523101, + -0.058998398 0.0115435 0.0174607, + -0.058412101 0.0143625 0.017397299, + -0.058412101 0.0140653 0.016738201, + -0.0576833 0.0168796 0.0166936, + -0.056809202 0.0194622 0.0159587, + -0.055787299 0.022127699 0.0152284, + -0.056127101 0.0211474 0.0145168, + -0.0546159 0.0248836 0.0152154, + -0.0554736 0.0228507 0.0145182, + -0.055787299 0.022249 0.0159306, + -0.056809202 0.019689901 0.0166493, + -0.0576833 0.017188 0.0173338, + -0.058412101 0.0150472 0.018410699, + -0.058998398 0.0127914 0.019290799, + -0.059445001 0.0122471 0.0225842, + -0.059757002 0.011517 0.026257901, + -0.0599402 0.00960455 0.0285579, + -0.059999999 0.0077777798 0.0309991, + -0.0599402 0.00608422 0.0336973, + -0.059757002 0.0045350399 0.036630701, + -0.059445001 0.00314718 0.039780099, + -0.058998398 0.0019565499 0.043110501, + -0.058412101 0.00100093 0.046576198, + -0.0576833 0.00030609299 0.0501264, + -0.0248404 -0.0055165798 0.090229802, + -0.0220857 -0.0043883501 0.091462597, + -0.019305199 -0.00308623 0.092543297, + -0.0165099 -0.00161838 0.093468301, + -0.0137106 0.00228963 0.094305597, + -0.0109179 0.0063713002 0.094870098, + -0.0081421202 0.0106052 0.095155999, + -0.0053918599 0.0149682 0.095160097, + -0.00267513 0.0194361 0.0948826, + 0 0.023984799 0.094324499, + 0.00267513 0.019436 0.094882399, + 0.0053918599 0.0149681 0.095159501, + 0.0081421202 0.0106051 0.095154501, + 0.0109179 0.0063712699 0.094867498, + 0.0137106 0.0022901699 0.094301596, + 0.0165099 -0.00161617 0.093462899, + 0.019305199 -0.00083160802 0.092673898, + 0.0220857 -0.0021513 0.091623098, + 0.0165099 0.00292443 0.0936317, + 0.0137106 0.0068650199 0.094319902, + 0.0109179 0.0109687 0.094731197, + 0.0081421202 0.0152132 0.094859697, + 0.0053918599 0.019574501 0.0947043, + 0.00267513 0.024028201 0.094265699, + 0 0.028550699 0.093545802, + -0.00267513 0.024028299 0.094265901, + -0.0053918599 0.019574599 0.094704702, + -0.0081421202 0.0152134 0.094860703, + -0.0109179 0.0109689 0.094733097, + -0.0137106 0.00686508 0.094323203, + -0.0165099 0.0029237601 0.093636602, + -0.019305199 0.00142298 0.092777297, + -0.035366699 -0.0039910199 0.084458202, + -0.035366699 -0.00187928 0.084670201, + -0.0378174 -0.00424923 0.082614399, + -0.0328326 -0.0035431201 0.086187698, + -0.0328326 -0.0013983099 0.086381197, + -0.0302257 -0.00290695 0.0877911, + -0.0302257 -0.00073288498 0.087962396, + -0.027557701 -0.0020872201 0.089259297, + -0.027557701 0.000112554 0.089405201, + -0.0248404 -0.00108919 0.090584204, + -0.0248404 0.00113365 0.0907024, + -0.0220857 8.2635102e-005 0.091758803, + -0.0220857 0.002326 0.091847301, + -0.019305199 0.00368426 0.092834197, + -0.0165099 0.0074789999 0.093643203, + -0.0137106 0.0114461 0.094177902, + -0.0109179 0.0155641 0.094431996, + -0.0081421202 0.019810701 0.094401598, + -0.0053918599 0.0241616 0.0940862, + -0.00267513 0.028592501 0.093486801, + 0 0.033079699 0.092605896, + 0.00267513 0.028592501 0.093486398, + 0.0053918599 0.0241614 0.094085798, + 0.0081421202 0.0198105 0.094401002, + 0.0109179 0.0155639 0.0944307, + 0.0137106 0.0114458 0.094175398, + 0.0165099 0.0074789701 0.093639202, + 0.019305199 0.0036850199 0.092828497, + 0.0220857 8.5569904e-005 0.091751501, + 0.0248404 -0.00108408 0.090575904, + 0.0248404 -0.0032989299 0.090418302, + 0.027557701 -0.00207904 0.089250103, + 0.027557701 -0.0042692199 0.089065701, + 0.0302257 -0.0028947601 0.087781399, + 0.0302257 -0.0050580399 0.0875737, + 0.0328326 -0.0035274201 0.086177997, + 0.0328326 -0.0077876798 0.085689403, + 0.035366699 -0.0060785199 0.084205396, + 0.035366699 -0.0081489496 0.083926901, + 0.0378174 -0.00628511 0.082347199, + 0.0378174 -0.00823317 0.0820347, + 0.040174201 -0.0062200101 0.080368303, + 0.040174201 -0.0081461603 0.079991497, + 0.0424264 -0.0059877601 0.078248501, + 0.0424264 -0.0079045501 0.077805497, + 0.044564299 -0.0056056599 0.075996101, + 0.044564299 -0.0074941101 0.075493097, + 0.0465803 -0.0050627501 0.073629797, + 0.0465803 -0.0069149402 0.073071301, + 0.048467699 -0.0043602898 0.071166702, + 0.048467699 -0.00617145 0.070557401, + 0.050219599 -0.0035032299 0.068624198, + 0.050219599 -0.0052690599 0.067968503, + 0.051830001 -0.0024977301 0.0660192, + 0.051830001 -0.0042143101 0.065322302, + 0.0532961 -0.00135182 0.063369602, + 0.0532961 -0.00301491 0.062637903, + 0.0546159 -7.4055999e-005 0.060694501, + 0.0546159 -0.00167987 0.059934601, + 0.055787299 0.001326 0.058012299, + 0.055787299 -0.000219522 0.057230499, + 0.056809202 0.00283767 0.0553407, + 0.0328326 -0.00138506 0.086370699, + 0.0302257 -0.00072390499 0.087952502, + 0.027557701 0.000118178 0.089396, + 0.0248404 0.00113695 0.090694197, + 0.0248404 0.0033631399 0.090773404, + 0.027557701 0.00232143 0.089503199, + 0.0302257 0.00145372 0.088085398, + 0.0328326 0.00076456601 0.086526997, + 0.035366699 0.00025724599 0.084836103, + 0.035366699 0.00238379 0.084976502, + 0.0328326 0.00292073 0.086645901, + 0.0302257 0.00363718 0.088179998, + 0.027557701 0.0045296601 0.089571401, + -0.0220857 0.0068236399 0.091904998, + -0.0378174 0.00201123 0.083194897, + -0.0378174 0.0041169501 0.083318703, + -0.040174201 0.00182812 0.081289098, + -0.035366699 0.00237328 0.084988303, + -0.035366699 0.0045093298 0.085091703, + -0.0328326 0.0029140001 0.086656801, + -0.0328326 0.0050781202 0.086737603, + -0.0302257 0.0036331799 0.0881899, + -0.0302257 0.0058231 0.088245802, + -0.027557701 0.0045274901 0.089580096, + -0.027557701 0.0067407801 0.0896089, + -0.0248404 0.0055925399 0.090820603, + -0.0248404 0.0078266701 0.090820499, + -0.0220857 0.0090759797 0.091873899, + -0.0248404 0.0100627 0.090780601, + -0.027557701 0.0089567099 0.089598604, + -0.0302257 0.00801636 0.088262796, + -0.0328326 0.00724624 0.086779997, + -0.035366699 0.0066500199 0.085157402, + -0.0378174 0.00622808 0.083405502, + -0.040174201 0.00597951 0.081535198, + -0.0424264 0.00385872 0.079437204, + -0.0424264 -0.00019842001 0.079096697, + -0.044564299 0.0019980201 0.077189296, + -0.044564299 3.8332299e-005 0.076992303, + -0.0465803 0.00236549 0.075020202, + -0.0465803 0.00051856402 0.074799597, + -0.048467699 0.00296582 0.0727745, + -0.048467699 0.0011403901 0.0725023, + -0.050219599 0.0036989099 0.070436597, + -0.050219599 0.0018858199 0.070111103, + -0.051830001 0.00454664 0.0680172, + -0.051830001 0.0027643801 0.067643903, + -0.0532961 0.0055167298 0.065535001, + -0.0532961 0.00377209 0.065118201, + -0.0546159 0.0066044 0.063007198, + -0.0546159 0.0049010902 0.062550902, + -0.055787299 0.0078012398 0.0604502, + -0.055787299 0.0061422898 0.059958499, + -0.055787299 0.0045032199 0.0593917, + -0.0546159 0.00321417 0.062017798, + -0.0532961 0.0020403401 0.064623103, + -0.051830001 0.00099114701 0.067190997, + -0.050219599 7.5080599e-005 0.069704503, + -0.048467699 -0.00070072903 0.072146498, + -0.0465803 -0.00133389 0.074500099, + -0.044564299 -0.0018348499 0.076747201, + -0.0424264 -0.0021856099 0.078877099, + -0.040174201 -0.00228324 0.080907099, + -0.0378174 -8.6688699e-005 0.083035499, + -0.035366699 0.000242985 0.084847398, + -0.0328326 0.00075479102 0.086538002, + -0.0302257 0.00144755 0.088095501, + -0.027557701 0.0023177599 0.089512199, + -0.0248404 0.00336118 0.090781197, + -0.0220857 0.0045733401 0.091896102, + -0.040174201 -0.0042966502 0.080666102, + -0.0424264 -0.00408393 0.078608401, + -0.044564299 -0.00371329 0.076421201, + -0.0465803 -0.0032021201 0.074114896, + -0.048467699 -0.00253916 0.071707599, + -0.050219599 -0.00172608 0.069216304, + -0.051830001 -0.000768503 0.0666577, + -0.0532961 0.00032583001 0.064048901, + -0.0546159 0.0015481201 0.0614071, + -0.055787299 0.00288929 0.058750998, + -0.055787299 0.00130587 0.058038399, + -0.0546159 -9.1685797e-005 0.0607206, + -0.0532961 -0.00136683 0.063395202, + -0.051830001 -0.0025100801 0.066043198, + -0.050219599 -0.0035129699 0.068645701, + -0.048467699 -0.0043674698 0.071185, + -0.0465803 -0.0050673098 0.073644601, + -0.044564299 -0.00560755 0.076007701, + -0.0424264 -0.00598722 0.078257203, + -0.040174201 -0.0062188199 0.080375001, + -0.0378174 -0.0062873801 0.082353197, + -0.035366699 -0.0060897302 0.084212698, + -0.0328326 -0.0056771799 0.085958898, + -0.0302257 -0.0050724898 0.087582603, + -0.027557701 -0.0042803399 0.0890745, + -0.0248404 -0.0033063199 0.090426497, + -0.0220857 -0.0021558199 0.091630504, + -0.019305199 -0.00083417603 0.092680298, + -0.055787299 0.0224855 0.0166051, + -0.0546159 0.0250101 0.015902899, + -0.054285601 0.0255438 0.0145203, + -0.053669199 0.026818 0.0095213596, + -0.051820099 0.0302085 0.0145241, + -0.0529669 0.028175401 0.0145224, + -0.051830001 0.0302712 0.0151899, + -0.0532961 0.0277337 0.0158756, + -0.0546159 0.025255 0.0165613, + -0.055787299 0.0228163 0.0172073, + -0.055787299 0.0231998 0.0176968, + -0.0546159 0.025597 0.017144799, + -0.0532961 0.0279871 0.016518099, + -0.051830001 0.0304079 0.0158487, + -0.050219599 0.032879099 0.0151775, + -0.0506116 0.032180801 0.0145256, + 0.051830001 0.0302503 0.0151749, + 0.051374301 0.0309832 0.0145247, + 0.050219599 0.032858901 0.0151629, + 0.0576833 0.019832101 0.0201484, + 0.058412101 0.0181517 0.0217406, + 0.0576833 0.0185374 0.0189404, + 0.056809202 0.021407399 0.0187677, + 0.056809202 0.020748699 0.018166, + 0.055787299 0.0235803 0.0180544, + 0.055787299 0.022851501 0.0171938, + 0.0546159 0.0256315 0.0171315, + 0.0546159 0.025291 0.0165585, + 0.0532961 0.0280223 0.0165154, + 0.0532961 0.027748 0.015873199, + 0.051830001 0.030421801 0.0158464, + 0.0423088 0.042532001 0.0145339, + 0.040746599 0.044011202 0.014535, + 0.0424264 0.042459399 0.0151193, + -0.0465803 0.0122129 0.0755665, + -0.0465803 0.0162064 0.075550698, + -0.048467699 0.0144772 0.073398501, + -0.048467699 0.0105645 0.0733217, + -0.050219599 0.0129718 0.071126401, + -0.050219599 0.0091577796 0.070971802, + -0.051830001 0.0117001 0.068763897, + -0.051830001 0.0098620104 0.068667002, + -0.0532961 0.0124966 0.066434197, + -0.0532961 0.0107639 0.066321097, + -0.055787299 0.0145492 0.061675701, + -0.055787299 0.012855 0.061479099, + -0.0546159 0.011768 0.063921303, + -0.0546159 0.0134774 0.0640755, + -0.0532961 0.0143022 0.066504396, + -0.051830001 0.0154481 0.068868101, + -0.050219599 0.016818499 0.071156502, + -0.048467699 0.0184054 0.073340103, + -0.0465803 0.020208299 0.0753958, + -0.044564299 0.0181577 0.07756, + -0.044564299 0.022227 0.077301502, + -0.0424264 0.0203299 0.079403698, + -0.0424264 0.0244595 0.079034999, + -0.040174201 0.022719201 0.081060298, + -0.040174201 0.026900901 0.080574498, + 0.048467699 0.0355739 0.0157947, + 0.0465803 0.038029902 0.015770201, + 0.048467699 0.035870899 0.016391501, + 0.050219599 0.033323899 0.0164316, + 0.052581199 0.031257 0.018175, + 0.0532961 0.029880401 0.0182578, + 0.052581199 0.0305184 0.0177809, + 0.051830001 0.03187 0.017727699, + 0.051830001 0.031472102 0.017426301, + 0.0532961 0.028767399 0.017508101, + 0.051830001 0.031066 0.0170098, + 0.050219599 0.033696599 0.016951, + 0.048467699 0.036253899 0.0168938, + 0.0465803 0.0383339 0.016352501, + 0.044564299 0.040391698 0.0157465, + 0.044564299 0.040205602 0.0151295, + 0.044344399 0.040405899 0.0145322, + 0.046273202 0.038182501 0.0145304, + 0.045055199 0.039586499 0.0145315, + 0.0465803 0.037847199 0.0151401, + 0.0484582 0.0353484 0.0145282, + 0.0480907 0.035867199 0.0145286, + 0.048467699 0.035394698 0.0151514, + 0.050219599 0.033034299 0.0158202, + 0.051830001 0.0307038 0.0164731, + 0.0532961 0.028373601 0.0170701, + 0.0546159 0.0263856 0.017943799, + 0.0576833 0.0224033 0.022452099, + 0.058412101 0.020611901 0.0242463, + 0.0576833 0.021120699 0.0213181, + 0.056809202 0.024085499 0.020896301, + 0.056809202 0.022749599 0.0198515, + 0.055787299 0.025651701 0.019556301, + 0.055787299 0.0242621 0.0185958, + 0.0546159 0.0270904 0.018425699, + 0.0532961 0.0291529 0.017834701, + 0.0546159 0.0285269 0.0192638, + 0.055787299 0.027034501 0.020476701, + 0.056809202 0.025415 0.021904301, + 0.0576833 0.0236747 0.0235691, + 0.058412101 0.0218475 0.0253745, + 0.058998398 0.018746899 0.0261751, + 0.058998398 0.020064199 0.0273793, + 0.059445001 0.016946301 0.028298199, + 0.059445001 0.018386699 0.029624499, + 0.059757002 0.0152753 0.030658601, + 0.059757002 0.016864499 0.032070801, + 0.0599402 0.0137776 0.0332154, + 0.0599402 0.0155438 0.034702498, + 0.059999999 0.0124746 0.035961401, + 0.059999999 0.0144361 0.037493099, + 0.0599402 0.0113709 0.038874, + 0.0599402 0.0135413 0.040412702, + 0.059757002 0.0104664 0.041924302, + 0.059757002 0.0128502 0.043433201, + 0.059445001 0.0097580804 0.045082401, + 0.059445001 0.0123543 0.0465234, + 0.058998398 0.0092619602 0.048303202, + 0.058998398 0.0120597 0.049639899, + 0.058412101 0.0089890799 0.051538099, + 0.058412101 0.0119712 0.052734502, + 0.0576833 0.0089416504 0.054736599, + 0.0576833 0.0120829 0.055763699, + 0.056809202 0.0091113402 0.057853799, + 0.056809202 0.0123823 0.058685299, + 0.055787299 0.0094839903 0.0608459, + 0.055787299 0.0128574 0.0614646, + 0.0546159 0.0100456 0.063677497, + -0.035366699 0.025977099 0.084047697, + -0.035366699 0.0281146 0.083735503, + -0.0378174 0.025317499 0.082510203, + -0.0328326 0.026789401 0.085437797, + -0.0328326 0.031097701 0.084721602, + -0.0302257 0.0299266 0.086302899, + -0.0302257 0.034256201 0.085455596, + -0.027557701 0.033232301 0.086907603, + -0.027557701 0.037572999 0.085921101, + -0.0248404 0.036688399 0.087237298, + -0.0248404 0.041025899 0.086109601, + -0.0220857 0.0402725 0.087284297, + -0.0220857 0.044592399 0.086014502, + -0.019305199 0.043962002 0.0870433, + -0.019305199 0.0482499 0.085631602, + -0.0165099 0.047732498 0.086513899, + -0.0165099 0.051976599 0.084960401, + -0.0137106 0.0515627 0.085696898, + -0.0137106 0.055750001 0.084004201, + -0.0109179 0.055430502 0.084596202, + -0.0109179 0.063880801 0.081175402, + -0.0081421202 0.063657701 0.081625603, + -0.0081421202 0.072251998 0.078456797, + -0.0053918599 0.072110102 0.078771196, + -0.0053918599 0.080830202 0.075861499, + -0.00267513 0.0807551 0.076046199, + -0.00267513 0.089582801 0.073401101, + 0 0.089561202 0.073461801, + 0 0.098479003 0.0710866, + 0.00267513 0.089583799 0.073402703, + 0.00267513 0.080756098 0.076047502, + 0.0053918599 0.080832101 0.0758643, + 0.0053918599 0.072111703 0.078773201, + 0.0081421202 0.0722543 0.07846, + 0.0081421202 0.063658997 0.081626996, + 0.0109179 0.063882597 0.081177302, + 0.0109179 0.0554308 0.084595598, + 0.0137106 0.055750199 0.084003501, + 0.0137106 0.0515626 0.085696399, + 0.0165099 0.051976599 0.084959902, + 0.0165099 0.047732599 0.0865127, + 0.019305199 0.0482499 0.085630201, + 0.019305199 0.0439623 0.087040998, + 0.0220857 0.044592801 0.086011797, + 0.0220857 0.040273201 0.087280601, + 0.0248404 0.0410267 0.086105399, + 0.0248404 0.036688998 0.087232798, + 0.027557701 0.037573799 0.085916102, + 0.027557701 0.033232201 0.086903602, + 0.0302257 0.034256101 0.085451201, + 0.0302257 0.0299253 0.086300798, + 0.0328326 0.0310962 0.084719397, + 0.0328326 0.0267886 0.085435301, + 0.035366699 0.028113799 0.083732799, + 0.035366699 0.0238344 0.0843179, + 0.0378174 0.0253167 0.082505502, + 0.0378174 0.021077299 0.0829634, + 0.040174201 0.0227185 0.081053101, + 0.040174201 0.0185291 0.081389599, + 0.0424264 0.0203298 0.079393499, + 0.0424264 0.016199799 0.079615697, + 0.044564299 0.0181596 0.077546902, + 0.044564299 0.0140977 0.077661902, + 0.0465803 0.016212599 0.075535402, + 0.0465803 0.0122267 0.075551003, + 0.048467699 0.0144916 0.0733824, + 0.048467699 0.0105876 0.073307499, + 0.050219599 0.0129957 0.071111701, + 0.050219599 0.0091736903 0.070961297, + 0.051830001 0.0117167 0.068753302, + 0.051830001 0.0080980901 0.068517298, + 0.0532961 0.0107623 0.066312201, + 0.0532961 0.0090238899 0.066125497, + 0.0546159 0.0117673 0.063910097, + 0.0546159 0.0134757 0.064066499, + 0.0532961 0.0143192 0.066493303, + 0.051830001 0.0154729 0.068852797, + 0.050219599 0.016833499 0.071139798, + 0.048467699 0.0184118 0.073324203, + 0.0465803 0.0202101 0.075382099, + 0.044564299 0.0222269 0.077290803, + 0.0424264 0.0244588 0.079027399, + 0.040174201 0.0269001 0.080569498, + 0.0378174 0.0295415 0.081898503, + 0.035366699 0.032370199 0.082998902, + 0.0328326 0.035380598 0.083855897, + 0.0302257 0.038556602 0.084453501, + 0.027557701 0.041875701 0.084781498, + 0.0248404 0.045315798 0.084831998, + 0.0220857 0.048854802 0.084598601, + 0.019305199 0.052472901 0.084076598, + 0.0165099 0.0561474 0.083267301, + 0.0137106 0.064175896 0.080586903, + 0.0109179 0.072458401 0.078011297, + 0.0081421202 0.080961399 0.075551599, + 0.0053918599 0.089652099 0.073219597, + 0.00267513 0.098499201 0.071027502, + 0 0.107472 0.068986103, + -0.00267513 0.098498203 0.071025997, + -0.0053918599 0.089649998 0.073216498, + -0.0081421202 0.080958501 0.075547397, + -0.0109179 0.072455302 0.078007102, + -0.0137106 0.064173803 0.080584504, + -0.0165099 0.056147099 0.083268099, + -0.019305199 0.052473001 0.084077299, + -0.0220857 0.048854701 0.084600098, + -0.0248404 0.045315299 0.084835097, + -0.027557701 0.0418749 0.084786102, + -0.0302257 0.038555801 0.084458999, + -0.0328326 0.035380799 0.083860703, + -0.035366699 0.0323718 0.083001398, + -0.0378174 0.0295424 0.081901401, + -0.0378174 0.0231991 0.082758799, + -0.035366699 0.023835201 0.084322199, + -0.0328326 0.0246264 0.085740097, + -0.0302257 0.025571199 0.087002598, + -0.027557701 0.028860399 0.0877425, + -0.0248404 0.032310799 0.088214599, + -0.0220857 0.035903201 0.088405602, + -0.019305199 0.0396153 0.088308997, + -0.0165099 0.043422598 0.0879234, + -0.0137106 0.047301002 0.087249599, + -0.0109179 0.0512297 0.0862891, + -0.0081421202 0.055187199 0.085047103, + -0.0053918599 0.063501902 0.081940301, + -0.00267513 0.072026901 0.078956001, + 0 0.080730803 0.076106898, + 0.00267513 0.072027698 0.078956999, + 0.0053918599 0.063502803 0.081941202, + 0.0081421202 0.0551874 0.085046701, + 0.0109179 0.0512297 0.086288802, + 0.0137106 0.047301099 0.087248601, + 0.0165099 0.0434229 0.087921403, + 0.019305199 0.039615899 0.088305801, + 0.0220857 0.0359038 0.088401601, + 0.0248404 0.032310601 0.088211, + 0.027557701 0.028859099 0.087740503, + 0.0302257 0.0255704 0.087000303, + 0.0328326 0.022458401 0.086000197, + 0.035366699 0.0195409 0.0847518, + 0.0378174 0.016830901 0.083271801, + 0.040174201 0.0143396 0.081579402, + 0.0424264 0.0120764 0.079694197, + 0.044564299 0.0100487 0.077636696, + 0.0465803 0.0082588801 0.075430997, + 0.048467699 0.0067017102 0.073108003, + 0.050219599 0.0054949098 0.070671901, + 0.051830001 0.00633022 0.068300799, + 0.0532961 0.0072720801 0.065860398, + 0.0546159 0.0083252396 0.063369699, + 0.0546159 0.0066124802 0.062986597, + 0.0532961 0.0055219298 0.065517999, + 0.051830001 0.00454885 0.068003699, + 0.050219599 0.0036982801 0.070426203, + 0.048467699 0.00296437 0.072766401, + 0.0302257 0.0124091 0.088173397, + 0.027557701 0.0111742 0.0895423, + 0.0302257 0.0102124 0.088233098, + 0.0328326 0.0115914 0.086741298, + 0.0328326 0.0094187902 0.086774498, + 0.035366699 0.0109432 0.085165098, + 0.035366699 0.00879726 0.085174203, + 0.0378174 0.0083485702 0.083442599, + 0.0378174 0.0125855 0.083431304, + 0.040174201 0.0101578 0.081623398, + 0.040174201 0.00599143 0.081521899, + 0.0424264 0.0079672299 0.079629898, + 0.0424264 0.00387902 0.079424702, + 0.044564299 0.0060192998 0.077473097, + 0.044564299 0.0020121201 0.077179998, + 0.0465803 0.0043111001 0.075183697, + 0.0465803 0.00236828 0.075012699, + 0.048467699 0.0047883401 0.072961502, + 0.035366699 0.0152412 0.085034102, + -0.0302257 0.023384901 0.087295704, + -0.0302257 0.0211943 0.087550297, + -0.027557701 0.024462201 0.088427097, + -0.0328326 0.022459099 0.086004198, + -0.0328326 0.0202884 0.086230204, + -0.035366699 0.021689599 0.084559098, + -0.035366699 0.0195415 0.084758103, + -0.0378174 0.021077899 0.082970098, + -0.0378174 0.018954899 0.083144203, + -0.040174201 0.018529201 0.081399202, + -0.040174201 0.0164333 0.081513599, + -0.0424264 0.016198101 0.079628102, + -0.0378174 0.0168311 0.083280899, + -0.035366699 0.017391801 0.084919304, + -0.0328326 0.018115301 0.086417697, + -0.0302257 0.0190005 0.0877662, + -0.027557701 0.0200429 0.088957898, + -0.0248404 0.023463801 0.089709498, + -0.0248404 0.0279007 0.089038298, + -0.0220857 0.0270488 0.0901886, + -0.0220857 0.031492598 0.089374699, + -0.019305199 0.030779 0.090386599, + -0.019305199 0.035218298 0.0894247, + -0.0165099 0.0346324 0.090296403, + -0.0165099 0.039053101 0.089185499, + -0.0137106 0.038584299 0.089916401, + -0.0137106 0.0429729 0.088657103, + -0.0109179 0.0426111 0.089247398, + -0.0109179 0.046954099 0.087841198, + -0.0081421202 0.0466897 0.088291898, + -0.0081421202 0.050976101 0.086740397, + -0.0053918599 0.0507989 0.087055698, + -0.0053918599 0.055017099 0.085362203, + -0.00267513 0.054917399 0.085547097, + -0.00267513 0.063410498 0.082125001, + 0 0.063380897 0.082185499, + 0 0.072000101 0.079016499, + 0.00267513 0.063410901 0.0821255, + 0.00267513 0.054917499 0.085547, + 0.0053918599 0.055017199 0.085361898, + 0.0053918599 0.0507989 0.087055497, + 0.0081421202 0.050976101 0.086740099, + 0.0081421202 0.0466897 0.088291399, + 0.0109179 0.046954099 0.087840401, + 0.0109179 0.042611301 0.089245997, + 0.0137106 0.042973101 0.088655502, + 0.0137106 0.038584702 0.089914098, + 0.0165099 0.0390536 0.089182697, + 0.0165099 0.034632798 0.0902934, + 0.019305199 0.035218801 0.089421198, + 0.019305199 0.0307789 0.090383798, + 0.0220857 0.031492501 0.089371502, + 0.0220857 0.0270478 0.090186998, + 0.0248404 0.0278995 0.089036599, + 0.0248404 0.023463201 0.089707598, + 0.027557701 0.0244615 0.088425003, + 0.027557701 0.0200423 0.088954501, + 0.0302257 0.0211937 0.087546602, + 0.0302257 0.0168039 0.087937802, + 0.0328326 0.0181148 0.086411797, + 0.0328326 0.0159404 0.086560003, + 0.035366699 0.0173914 0.084911898, + -0.044564299 0.0140918 0.077676602, + -0.044564299 0.0100355 0.077651501, + -0.0465803 0.0082365898 0.075444698, + -0.048467699 0.0066863499 0.073118001, + -0.050219599 0.0072878301 0.070848599, + -0.051830001 0.00809965 0.068526, + -0.0532961 0.00902458 0.066136502, + -0.0546159 0.0100433 0.063691698, + -0.055787299 0.0111617 0.061209701, + -0.056809202 0.012374 0.058706801, + -0.0424264 0.043350499 0.0167449, + -0.044564299 0.041076601 0.0167962, + -0.043510102 0.042697601 0.0171027, + -0.0424264 0.0429377 0.016281599, + -0.048467699 0.036666699 0.017286601, + -0.050219599 0.034097001 0.017364999, + -0.049361002 0.0358219 0.017588699, + -0.048467699 0.036223199 0.0169055, + -0.040174201 0.044615 0.0151212, + -0.040382501 0.044364698 0.0145353, + -0.0424264 0.042476501 0.0151316, + -0.0424264 0.0426373 0.015725801, + -0.044564299 0.040379699 0.015748501, + -0.044564299 0.040672999 0.0163175, + -0.0465803 0.0383032 0.0163549, + -0.0465803 0.038697399 0.016849799, + -0.0465803 0.039151799 0.017210901, + -0.047540501 0.038361602 0.0174881, + -0.040174201 0.044780198 0.0157042, + -0.0378174 0.046631601 0.0151115, + -0.038430501 0.046055399 0.0145367, + -0.035840798 0.048107401 0.0145383, + -0.0353604 0.048447199 0.0145386, + -0.038435601 0.0460652 0.0095366798, + -0.0381575 0.046291798 0.0145369, + -0.037812401 0.046562299 0.0145371, + -0.040170401 0.0445484 0.0145355, + -0.0429691 0.041869 0.0095333401, + -0.044563901 0.040162198 0.014532, + -0.046453901 0.0379625 0.0145302, + -0.044564299 0.040223502 0.0151424, + -0.046577401 0.037803601 0.0145301, + -0.0470348 0.0372153 0.0145296, + -0.0465803 0.037865799 0.0151537, + -0.0465803 0.038017299 0.015772199, + -0.0532961 0.0298764 0.018262399, + -0.0532961 0.0291494 0.017852901, + -0.0546159 0.027086301 0.018430401, + -0.0546159 0.0285271 0.0192666, + -0.055787299 0.0256519 0.019559201, + -0.055787299 0.0270351 0.020479901, + -0.056809202 0.025415501 0.021903999, + -0.056809202 0.0240862 0.020899599, + -0.0576833 0.023675101 0.023569301, + -0.055787299 0.024258001 0.0186006, + -0.0546159 0.0263821 0.0179624, + -0.0532961 0.0287483 0.017527901, + -0.051830001 0.031453598 0.017445499, + -0.051830001 0.0310333 0.017022399, + -0.050219599 0.033664901 0.016963201, + -0.050219599 0.0332908 0.0164342, + -0.048467699 0.035838999 0.0163939, + -0.048467699 0.035560898 0.0157969, + -0.048467699 0.0354142 0.0151654, + -0.048260398 0.0356385 0.0145284, + -0.047047202 0.037229002 0.0095296502, + -0.0445357 0.040194999 0.014532, + -0.0429601 0.041856501 0.0145333, + -0.0425102 0.042330801 0.0145337, + -0.0424245 0.042412799 0.0145338, + -0.051830001 0.031866599 0.017745299, + -0.051830001 0.0322343 0.017942701, + -0.050219599 0.034521502 0.0176402, + -0.050219599 0.0348997 0.017810199, + -0.051830001 0.032615699 0.018097499, + -0.0532961 0.0313632 0.018978, + -0.0546159 0.0299567 0.0200643, + -0.055787299 0.0284111 0.021359099, + -0.056809202 0.026733501 0.022893, + -0.0576833 0.024950501 0.024594501, + -0.058412101 0.0218425 0.0253972, + -0.058412101 0.023182999 0.0264589, + -0.058998398 0.0200451 0.0273837, + -0.058998398 0.021505 0.0285729, + -0.059445001 0.0183597 0.029618001, + -0.059445001 0.019963499 0.0309103, + -0.059757002 0.0168352 0.032070201, + -0.059757002 0.018606501 0.033438802, + -0.0599402 0.0155133 0.034707598, + -0.0599402 0.017470401 0.036121301, + -0.059999999 0.0144051 0.037502199, + -0.059999999 0.016562 0.0389263, + -0.0599402 0.0135109 0.040426299, + -0.0599402 0.0158724 0.041824099, + -0.059757002 0.0128213 0.043451399, + -0.059757002 0.0153867 0.044785202, + -0.059445001 0.0123276 0.0465459, + -0.059445001 0.0150874 0.047780201, + -0.058998398 0.0120364 0.049666099, + -0.058998398 0.0149746 0.0507656, + -0.058412101 0.0119524 0.052762602, + -0.058412101 0.0150447 0.053697798, + -0.0576833 0.0120691 0.055790398, + -0.0576833 0.0152876 0.056534901, + -0.056809202 0.015692901 0.059245698, + -0.055787299 0.016228201 0.061799001, + -0.0546159 0.016952399 0.064203098, + -0.0532961 0.0179825 0.066556796, + -0.051830001 0.019227199 0.0688501, + -0.050219599 0.020679399 0.071054101, + -0.048467699 0.022340599 0.0731453, + -0.0465803 0.0242121 0.075101703, + -0.044564299 0.0262929 0.076901302, + -0.0424264 0.028580001 0.0785219, + -0.040174201 0.0310675 0.079942502, + -0.0378174 0.033744399 0.081148103, + -0.035366699 0.0366042 0.082125597, + -0.0328326 0.0396352 0.0828529, + -0.0302257 0.042817801 0.083315797, + -0.027557701 0.046129599 0.083506301, + -0.0248404 0.049548201 0.083417803, + -0.0220857 0.0530532 0.083044797, + -0.019305199 0.056623399 0.082385503, + -0.0165099 0.064538002 0.079849802, + -0.0137106 0.072722197 0.077416897, + -0.0109179 0.081142299 0.075098, + -0.0081421202 0.089765102 0.072902597, + -0.0053918599 0.098557703 0.070841499, + -0.00267513 0.107489 0.0689255, + 0 0.116529 0.067162901, + 0.00267513 0.10749 0.068926796, + 0.0053918599 0.098559797 0.070844598, + 0.0081421202 0.089768201 0.072907299, + 0.0109179 0.081146203 0.0751037, + 0.0137106 0.072726198 0.077422202, + 0.0165099 0.064540699 0.079852797, + 0.019305199 0.056623802 0.082384497, + 0.0220857 0.0530532 0.083044097, + 0.0248404 0.049548302 0.083416, + 0.027557701 0.046130098 0.083502904, + 0.0302257 0.042818699 0.083310798, + 0.0328326 0.039636102 0.082846902, + 0.035366699 0.036603998 0.082120501, + 0.0378174 0.033742599 0.081145503, + 0.040174201 0.0310665 0.079939403, + 0.0424264 0.0285792 0.078516699, + 0.044564299 0.026292199 0.0768933, + 0.0465803 0.0242119 0.075090498, + 0.048467699 0.022342499 0.073131002, + 0.050219599 0.020686001 0.071037598, + 0.051830001 0.0192426 0.0688328, + 0.0532961 0.018007999 0.066541202, + 0.0546159 0.016969699 0.064191699, + 0.055787299 0.0162265 0.061789699, + 0.056809202 0.0156953 0.059230901, + 0.0576833 0.0152961 0.056513201, + 0.058412101 0.0150587 0.053670701, + 0.058998398 0.0149936 0.0507374, + 0.059445001 0.0151108 0.0477538, + 0.059757002 0.0154136 0.044762399, + 0.0599402 0.0159015 0.0418058, + 0.059999999 0.016592501 0.038912699, + 0.0599402 0.0175013 0.0361121, + 0.059757002 0.018636899 0.033433799, + 0.059445001 0.0199927 0.0309109, + 0.058998398 0.021531699 0.0285795, + 0.058412101 0.0232019 0.026454501, + 0.0576833 0.0249555 0.024572, + 0.056809202 0.0267331 0.022892799, + 0.055787299 0.0284106 0.0213593, + 0.0546159 0.029956101 0.0200611, + 0.0532961 0.031362999 0.018975301, + 0.051830001 0.032619599 0.0180931, + 0.051042698 0.0332059 0.017674999, + 0.050219599 0.034115002 0.017346401, + 0.048467699 0.0366841 0.017268701, + 0.049361002 0.0358251 0.0175719, + 0.0465803 0.038726699 0.0168385, + 0.044564299 0.040702298 0.016315199, + 0.0424264 0.042648699 0.015723901, + 0.040174201 0.044598799 0.0151096, + 0.045067899 0.039601501 0.0095315399, + 0.046573199 0.037800301 0.0145301, + 0.048901699 0.0347577 0.0095276805, + 0.040756401 0.044025499 0.0095350603, + 0.042423598 0.042412098 0.0145338, + 0.0308876 0.051431298 0.0095409602, + 0.033201002 0.0499654 0.0145398, + 0.036012899 0.047982801 0.00953821, + 0.0254349 0.054334499 0.0095432699, + 0.028145101 0.052977599 0.0145422, + 0.037937399 0.0464723 0.014537, + 0.0401715 0.044555798 0.0145355, + 0.0445593 0.040158201 0.014532, + 0.049792401 0.033465501 0.0145267, + 0.048886999 0.034743302 0.0145277, + 0.058998398 0.0175565 0.024922, + 0.059445001 0.015665799 0.026970699, + 0.059757002 0.0138616 0.0292073, + 0.0599402 0.0122049 0.0316789, + 0.059999999 0.0107146 0.034350999, + 0.0599402 0.0094052702 0.0372205, + 0.059757002 0.0082818102 0.040265601, + 0.059445001 0.0073502902 0.043456301, + 0.058998398 0.0066325502 0.046749402, + 0.058412101 0.0061499602 0.0500945, + 0.0576833 0.00591115 0.053440701, + 0.056809202 0.0059164301 0.056735702, + 0.055787299 0.0061555901 0.059932701, + 0.0546159 0.0049116998 0.062527597, + 0.0532961 0.0037799799 0.065098099, + 0.051830001 0.00276945 0.0676274, + 0.050219599 0.00188797 0.070097998, + 0.048467699 0.00113976 0.072492301, + 0.0465803 0.00051716599 0.074791901, + 0.044564299 4.1022999e-005 0.0769853, + 0.0424264 -0.000184955 0.079087898, + 0.040174201 0.00184733 0.081277303, + 0.0378174 0.00412816 0.083306096, + 0.027557701 0.0089570703 0.089591198, + 0.0248404 0.0100626 0.0907747, + 0.027557701 0.00674188 0.089600801, + 0.0302257 0.0080175595 0.0882539, + 0.0302257 0.00582546 0.088236302, + 0.0328326 0.0072488398 0.0867697, + 0.0328326 0.0050824601 0.0867268, + 0.035366699 0.0066547301 0.085145801, + 0.035366699 0.0045165699 0.085079797, + 0.0378174 0.0062358198 0.083392799, + 0.0248404 0.0145361 0.090577699, + 0.0220857 0.0135825 0.091687799, + 0.0220857 0.0180858 0.0913468, + 0.019305199 0.017283199 0.092328198, + 0.019305199 0.0218042 0.091839202, + 0.0165099 0.021143001 0.092688702, + 0.0165099 0.0256691 0.092049003, + 0.0137106 0.025139101 0.092764802, + 0.0137106 0.0296595 0.091972001, + 0.0109179 0.0292501 0.092552803, + 0.0109179 0.033751201 0.091605701, + 0.0081421202 0.033451799 0.092051499, + 0.0081421202 0.037920401 0.0909504, + 0.0053918599 0.037719499 0.091263697, + 0.0053918599 0.042143099 0.0900103, + 0.00267513 0.0420301 0.090194903, + 0.00267513 0.046396598 0.088791497, + 0 0.046361201 0.088851899, + 0 0.050660901 0.087301098, + -0.00267513 0.046396598 0.088791698, + -0.00267513 0.0420301 0.090195201, + -0.0053918599 0.042142998 0.090011001, + -0.0053918599 0.037719399 0.091264598, + -0.0081421202 0.037920099 0.090951703, + -0.0081421202 0.033451501 0.092052899, + -0.0109179 0.033750899 0.091607697, + -0.0109179 0.029250201 0.092554398, + -0.0137106 0.029659601 0.091973998, + -0.0137106 0.025139799 0.092765696, + -0.0165099 0.025669901 0.092050202, + -0.0165099 0.021143399 0.092689998, + -0.019305199 0.0218047 0.091840699, + -0.019305199 0.0172836 0.092330597, + -0.0220857 0.018086201 0.091349497, + -0.0220857 0.0135829 0.091691799, + -0.0248404 0.016772401 0.090423398, + -0.040174201 0.0122441 0.081632301, + -0.040174201 0.014338 0.081591196, + -0.0424264 0.0120707 0.079708204, + -0.0378174 0.012584 0.083442397, + -0.0378174 0.0147071 0.083380297, + -0.035366699 0.013091 0.085127898, + -0.035366699 0.0152413 0.085042603, + -0.0328326 0.0137657 0.0866777, + -0.0328326 0.0159408 0.086566903, + -0.0302257 0.014607 0.088081397, + -0.0302257 0.016804401 0.087943196, + -0.027557701 0.0156109 0.089332096, + -0.027557701 0.0178279 0.0891646, + -0.0248404 0.019006301 0.090225004, + -0.0220857 0.022577699 0.090847798, + -0.019305199 0.026305599 0.091191903, + -0.0165099 0.0301685 0.091252297, + -0.0137106 0.034143802 0.091023199, + -0.0109179 0.0382073 0.090504102, + -0.0081421202 0.0423356 0.089696802, + -0.0053918599 0.046505 0.088606901, + -0.00267513 0.050694801 0.087240703, + 0 0.054884799 0.085607402, + 0.00267513 0.050694801 0.087240599, + 0.0053918599 0.046505101 0.088606499, + 0.0081421202 0.042335801 0.089695796, + 0.0109179 0.038207602 0.090502299, + 0.0137106 0.0341441 0.091020703, + 0.0165099 0.030168399 0.091249801, + 0.019305199 0.026304699 0.091190599, + 0.0220857 0.0225772 0.090846099, + 0.0248404 0.0190058 0.090221897, + 0.027557701 0.0156104 0.089327097, + 0.0302257 0.0146066 0.088075101, + 0.0328326 0.0137656 0.086669803, + 0.035366699 0.0130915 0.085118398, + -0.0424264 0.0100109 0.0796941, + -0.040174201 0.0101525 0.0816366, + -0.0378174 0.0104624 0.083467402, + -0.035366699 0.0109418 0.085175499, + -0.0328326 0.0115909 0.086750098, + -0.0302257 0.0124092 0.088180698, + -0.027557701 0.0133927 0.089460202, + -0.0248404 0.0145365 0.090582199, + -0.0248404 0.0122997 0.0907012, + -0.027557701 0.0111743 0.089548901, + -0.0302257 0.010212 0.088241197, + -0.0328326 0.0094175003 0.086784102, + -0.035366699 0.0087944698 0.085185297, + -0.0378174 0.0083435504 0.083455101, + -0.040174201 0.0080640204 0.081604198, + -0.0424264 0.0079546496 0.079644002, + -0.044564299 0.0059980201 0.077486202, + -0.0465803 0.0042963298 0.075193398, + -0.048467699 0.0047854399 0.072969303, + -0.050219599 0.00549642 0.070680201, + -0.051830001 0.0063308901 0.068311498, + -0.0532961 0.00726985 0.065874301, + -0.0546159 0.0083198901 0.063387103, + -0.055787299 0.0094757099 0.060867, + -0.056809202 0.0090977997 0.0578801, + -0.0576833 0.0089230398 0.0547642, + -0.058412101 0.0089660203 0.051564001, + -0.058998398 0.0092355097 0.048325699, + -0.059445001 0.0097292596 0.0451006, + -0.059757002 0.0104361 0.041937798, + -0.0599402 0.0113399 0.038883101, + -0.059999999 0.0124441 0.035966601, + -0.0599402 0.0137482 0.0332148, + -0.059757002 0.0152482 0.0306521, + -0.059445001 0.016927101 0.028302699, + -0.058998398 0.018741701 0.026198, + -0.058412101 0.0206124 0.0242466, + -0.0576833 0.021121399 0.021321399, + -0.056809202 0.021403201 0.018772401, + -0.055787299 0.0235766 0.0180734, + -0.0546159 0.025993001 0.017611699, + -0.0532961 0.028340001 0.017083099, + -0.051830001 0.0306697 0.016475599, + -0.050219599 0.033020802 0.015822399, + -0.0499507 0.0332288 0.0145265, + 0.0576833 0.0030304899 0.051890001, + 0.058412101 0.0034870701 0.048427101, + 0.058998398 0.0042004902 0.0450048, + 0.059445001 0.0051513002 0.041675899, + 0.059757002 0.0063120602 0.0384892, + 0.0599402 0.00765137 0.035486799, + 0.059999999 0.0091581997 0.0326914, + 0.0599402 0.0108176 0.030104401, + 0.059757002 0.0126176 0.0277579, + 0.059445001 0.0145202 0.0255934, + 0.058998398 0.0151898 0.022162, + 0.058412101 0.015663199 0.0191133, + 0.0576833 0.017902 0.018278399, + 0.056809202 0.0200455 0.0172567, + 0.055787299 0.0225222 0.0166022, + 0.0546159 0.025024701 0.0159005, + 0.0532961 0.0275806 0.0151871, + 0.0528326 0.028426399 0.0145226, + 0.052201699 0.0295325 0.0145235, + 0.0522171 0.0295453 0.0095235296, + 0.051817201 0.0302068 0.0145241, + 0.050207902 0.032813501 0.0145261, + 0.053282399 0.027539199 0.0145219, + 0.054979 0.024019601 0.00951913, + 0.054163702 0.0258011 0.0145205, + 0.054601099 0.0248222 0.0145198, + 0.054964401 0.024009099 0.0145191, + 0.0546159 0.0248616 0.0151996, + 0.055364501 0.023113601 0.0145184, + 0.055787299 0.022264 0.0159282, + 0.056809202 0.0197274 0.0166464, + 0.0576833 0.017224399 0.0173198, + 0.058412101 0.0150512 0.018390801, + 0.058998398 0.0127958 0.0192858, + 0.059445001 0.0122465 0.022580801, + 0.059757002 0.0115165 0.026257699, + 0.0599402 0.0096097598 0.028534601, + 0.059999999 0.0077972198 0.0309946, + 0.0599402 0.0061114701 0.033703901, + 0.059757002 0.0045643998 0.036631301, + 0.059445001 0.00317744 0.039774999, + 0.058998398 0.00198701 0.043101501, + 0.058412101 0.00103064 0.046562999, + 0.0576833 0.00033409201 0.050108802, + 0.056809202 -8.44639e-005 0.053683002, + 0.055787299 -0.00172404 0.056380801, + 0.0546159 -0.0032484101 0.0591029, + 0.0532961 -0.0046449401 0.0618308, + 0.051830001 -0.0059024398 0.064546198, + 0.050219599 -0.0070112399 0.067230202, + 0.048467699 -0.0079631004 0.069863603, + 0.0465803 -0.0087518198 0.072426997, + 0.044564299 -0.0093716597 0.0749029, + 0.0424264 -0.0098176897 0.077273898, + 0.040174201 -0.0100867 0.079523198, + 0.0378174 -0.0101815 0.081635296, + 0.035366699 -0.0101179 0.083594702, + 0.0328326 -0.0098789698 0.085393399, + 0.0302257 -0.0093588103 0.087053701, + 0.027557701 -0.0064515499 0.088844202, + 0.0248404 -0.00550659 0.090221897, + 0.0220857 -0.0043818201 0.091455199, + 0.055787299 0.022105301 0.0152123, + 0.055771399 0.022067901 0.0145176, + 0.056432001 0.020370601 0.0145162, + 0.056809202 0.019323099 0.0152251, + 0.0576833 0.0165262 0.0152381, + 0.057145901 0.0182312 0.0145145, + 0.058412101 0.0138705 0.0160124, + 0.058998398 0.0112965 0.016779499, + 0.059445001 0.00878001 0.0175092, + 0.059757002 0.0065849698 0.0187249, + 0.0599402 0.0043462701 0.0197943, + 0.059999999 0.00361019 0.023809601, + 0.0599402 0.0026701 0.028213801, + 0.059757002 0.00063247501 0.030852901, + 0.059445001 -0.00135199 0.033691101, + 0.058998398 -0.0032158301 0.036803301, + 0.058412101 -0.0049084001 0.0401434, + 0.0576833 -0.0063760998 0.043693699, + 0.056809202 -0.0075771199 0.047410101, + 0.055787299 -0.0084758298 0.051236399, + 0.0546159 -0.0103579 0.053968601, + 0.0532961 -0.0121097 0.056745801, + 0.051830001 -0.0137148 0.059549399, + 0.050219599 -0.0151594 0.062360302, + 0.048467699 -0.0164304 0.065158702, + 0.0465803 -0.0175178 0.067924201, + 0.044564299 -0.0184124 0.070635699, + 0.0424264 -0.019107601 0.073273197, + 0.040174201 -0.019598501 0.075817198, + 0.0378174 -0.0198844 0.078249499, + 0.035366699 -0.0199659 0.080552302, + 0.0328326 -0.019843601 0.082710497, + 0.0302257 -0.0195194 0.084709696, + 0.027557701 -0.0189995 0.086538903, + 0.0248404 -0.018294301 0.088187702, + 0.0220857 -0.017426901 0.089644998, + 0.019305199 -0.016386401 0.090909302, + 0.0165099 -0.01507 0.092012599, + 0.0137106 -0.0113155 0.093278699, + 0.0109179 -0.0073506301 0.094298303, + 0.0081421202 -0.0031976099 0.095053703, + 0.0053918599 0.00111985 0.095537901, + 0.00267513 0.0055779698 0.095747702, + 0 0.0101534 0.095681101, + -0.00267513 0.0055780001 0.095748402, + -0.0053918599 0.0011196299 0.095539503, + -0.0081421202 -0.00319868 0.0950564, + -0.0109179 -0.0073538702 0.094301999, + -0.0137106 -0.0113221 0.0932827, + -0.0165099 -0.0150753 0.092015997, + -0.019305199 -0.0163876 0.090912402, + -0.0220857 -0.0174262 0.089648701, + -0.0248404 -0.018293999 0.088192798, + -0.027557701 -0.019000599 0.086545996, + -0.0302257 -0.019522401 0.084719397, + -0.0328326 -0.019848499 0.082722902, + -0.035366699 -0.0199729 0.080567501, + -0.0378174 -0.0198934 0.078267001, + -0.040174201 -0.0196098 0.075836502, + -0.0424264 -0.0191213 0.073293597, + -0.044564299 -0.018428501 0.070656396, + -0.0465803 -0.0175361 0.067944802, + -0.048467699 -0.016450999 0.065178797, + -0.050219599 -0.0151819 0.062379401, + -0.051830001 -0.0137391 0.059567198, + -0.0532961 -0.0121355 0.056761999, + -0.0546159 -0.0103851 0.053982999, + -0.055787299 -0.0085041597 0.051249001, + -0.056809202 -0.0076064202 0.047418799, + -0.0576833 -0.00640547 0.043698601, + -0.058412101 -0.00493709 0.040142801, + -0.058998398 -0.00324262 0.036796801, + -0.059445001 -0.00137125 0.0336955, + -0.059757002 0.0006273 0.0308761, + -0.0599402 0.0026705801 0.028214, + -0.059999999 0.0036108301 0.023813, + -0.0599402 0.0043417802 0.0197994, + -0.059757002 0.0065810601 0.018745201, + -0.059445001 0.0087425197 0.0175236, + -0.058998398 0.0112577 0.0167826, + -0.058412101 0.0138548 0.0160149, + -0.058412101 0.0137486 0.015268, + -0.058866698 0.0115948 0.0145092, + -0.058398601 0.013696 0.0145109, + -0.058021698 0.0152727 0.00951216, + -0.058226701 0.0144679 0.0145115, + -0.058007602 0.0152648 0.0145122, + -0.057669599 0.0164946 0.0145131, + 0.056809202 -0.0095678195 0.0450029, + 0.0576833 -0.0080983099 0.041326098, + 0.058412101 -0.0063810698 0.037854999, + 0.058998398 -0.0044700601 0.0346101, + 0.059445001 -0.0024157299 0.031640101, + 0.059757002 -0.00029395401 0.028869299, + 0.0599402 0.00075900799 0.024215201, + 0.059999999 0.00158619 0.0199605, + 0.0599402 0.00382597 0.0188339, + 0.058157299 0.014744 0.0145117, + 0.0573637 0.017578499 0.014514, + 0.0576673 0.0164939 0.0145131, + 0.057158101 0.018239301 0.0095145302, + 0.056793101 0.0192883 0.0145154, + 0.058731299 0.0122655 0.0095097702, + 0.058396202 0.0136953 0.0145109, + 0.058811001 0.0118741 0.0145095, + 0.058982499 0.0109035 0.0145087, + 0.059323099 0.0089755096 0.0145072, + 0.0594301 0.0081293797 0.0145065, + 0.0546159 -0.017591201 0.044845399, + 0.0546159 -0.0158881 0.0475954, + 0.0532961 -0.019878 0.0474393, + 0.055787299 -0.0144521 0.0436817, + 0.0546159 -0.013889 0.0502536, + 0.0532961 -0.018027199 0.0502735, + 0.055787299 -0.0127427 0.046305198, + 0.056809202 -0.0112837 0.042507, + 0.056809202 -0.0127221 0.039962001, + 0.0576833 -0.0095539102 0.038909301, + 0.0576833 -0.0107534 0.036461901, + 0.058412101 -0.00760801 0.035535, + 0.058412101 -0.0085974801 0.033236701, + 0.058998398 -0.0054968102 0.032435801, + 0.058998398 -0.0063338899 0.030205, + 0.059445001 -0.0032977201 0.0295336, + 0.059445001 -0.0050261701 0.025038401, + 0.059757002 -0.00211434 0.024623999, + 0.059757002 -0.00395549 0.020293999, + 0.0599402 -0.00117393 0.0201266, + 0.0599402 -0.00164945 0.019050101, + 0.059999999 0.00108828 0.018942, + 0.059999999 0.00056159502 0.0176936, + 0.0599402 0.0032748401 0.017632701, + 0.0599402 0.0028235901 0.0161233, + 0.059757002 0.00553875 0.016096, + 0.059757002 0.0054073599 0.0152896, + 0.059679601 0.0061574001 0.0145049, + 0.059445001 0.0081543103 0.0152768, + 0.059757002 -0.0044084499 0.019159099, + 0.059445001 -0.0067743598 0.020463601, + 0.059757002 -0.00488608 0.017815899, + 0.0599402 -0.0021516799 0.017754501, + 0.0599402 -0.0025649699 0.016177399, + 0.059999999 0.00012932099 0.016150299, + 0.059999999 7.0921701e-006 0.0153147, + 0.0599402 0.00269674 0.0153022, + 0.059999 0.00033305801 0.0145003, + 0.059931099 0.0026764099 0.0145021, + 0.059999999 -7.5646799e-006 0.0094999997, + 0.059918199 0.0031204999 0.0145025, + 0.058998398 -0.0079693701 0.0254572, + 0.058412101 -0.0093893697 0.0308806, + 0.0576833 -0.0117056 0.034039501, + 0.056809202 -0.0138944 0.037387598, + 0.055787299 -0.0158737 0.041009199, + -0.050219599 -0.0291108 0.041871101, + -0.050219599 -0.028633701 0.043459799, + -0.051830001 -0.026182 0.041007999, + -0.048467699 -0.031957898 0.042710301, + -0.048467699 -0.032341801 0.041074298, + -0.0465803 -0.0350799 0.041830398, + -0.0465803 -0.035367299 0.040169001, + -0.044564299 -0.037983801 0.040844399, + -0.044564299 -0.038342599 0.037283398, + -0.0424264 -0.0408068 0.0378282, + -0.0424264 -0.0413871 0.030215001, + -0.040174201 -0.043654501 0.030537499, + -0.040174201 -0.0441733 0.0227184, + -0.0378174 -0.046243101 0.022842901, + -0.040174201 -0.044449002 0.018715199, + -0.0424264 -0.042291999 0.0186671, + -0.0424264 -0.042406101 0.016579401, + -0.044564299 -0.0401491 0.016556799, + -0.042958502 -0.041878 0.0144667, + -0.0465803 -0.0377874 0.016533099, + -0.048467699 -0.035331499 0.016508499, + -0.047033701 -0.037237499 0.0144704, + -0.0465803 -0.037641399 0.0185632, + -0.050219599 -0.032791801 0.0164831, + -0.0498452 -0.033409901 0.0144734, + -0.048467699 -0.035168398 0.0185079, + -0.0465803 -0.037246302 0.0223017, + -0.044564299 -0.039666001 0.022447299, + -0.044564299 -0.038998298 0.0298752, + -0.0424264 -0.0419783 0.0225864, + -0.044564299 -0.0400194 0.0186163, + -0.046333499 -0.038132399 0.0144696, + -0.0465803 -0.035764098 0.036713101, + -0.048467699 -0.032646399 0.039466701, + -0.050219599 -0.029510399 0.0402922, + -0.059445001 -0.0079036197 0.017085301, + -0.059445001 -0.0080478098 0.016234901, + -0.058998398 -0.0104954 0.017955299, + -0.059757002 -0.0052962699 0.0162073, + -0.059702002 -0.0059841401 0.0144952, + -0.059431199 -0.0081526199 0.0144935, + -0.059337199 -0.0089049097 0.0144929, + -0.059285302 -0.0092409896 0.0094926404, + -0.056793701 -0.019311599 0.0144846, + -0.056809202 -0.019234899 0.016347099, + -0.057391401 -0.017511001 0.0144861, + -0.056464098 -0.020304499 0.0144838, + -0.056143001 -0.0211727 0.00948314, + -0.0576679 -0.0165172 0.0144869, + -0.058021698 -0.0152879 0.0094878301, + -0.055400901 -0.023049301 0.0144817, + -0.055771999 -0.022091201 0.0144824, + -0.054601699 -0.0248456 0.0144802, + -0.0546159 -0.0247823 0.0164028, + -0.054204401 -0.025738601 0.0144795, + -0.053669199 -0.026833201 0.0094786398, + -0.0528774 -0.028365999 0.0144774, + -0.0532832 -0.0275626 0.0144781, + -0.051817998 -0.030230399 0.0144759, + -0.051830001 -0.030179201 0.0164569, + -0.051423199 -0.030925101 0.0144754, + -0.050626501 -0.0322094 0.0094743501, + -0.048459399 -0.035372298 0.0144718, + -0.047047202 -0.037244201 0.0094703501, + -0.048147298 -0.0358142 0.0144715, + -0.0424252 -0.0424367 0.0144662, + -0.0429691 -0.041884098 0.00946665, + -0.042376 -0.042488299 0.0144662, + -0.0402418 -0.044515401 0.0144646, + -0.040174201 -0.0445484 0.016600801, + -0.038010798 -0.046435501 0.014463, + -0.038435601 -0.046080299 0.0094633102, + -0.037814599 -0.046588201 0.0144629, + -0.0378174 -0.046568699 0.0166211, + -0.0356883 -0.048243701 0.0144616, + -0.033491299 -0.049787398 0.0144604, + -0.035362199 -0.048472799 0.0144614, + -0.033494599 -0.049788099 0.0094603598, + -0.035366699 -0.0484601 0.01664, + -0.0328326 -0.0501546 0.0188425, + -0.0332799 -0.049936 0.0144602, + -0.0328269 -0.050222099 0.01446, + -0.0307914 -0.051507998 0.014459, + -0.0302257 -0.0516329 0.023166999, + -0.028228801 -0.052956201 0.0144578, + -0.030219801 -0.051831 0.0144587, + -0.0281986 -0.0529682 0.0094578201, + -0.035366699 -0.0483873 0.018803099, + -0.0328326 -0.049979601 0.023067599, + -0.0328326 -0.049652699 0.031390801, + -0.035366699 -0.047794599 0.0311264, + -0.035366699 -0.047416601 0.039289899, + -0.0378174 -0.045351502 0.038833201, + -0.035366699 -0.047322601 0.041331202, + -0.0328326 -0.0493333 0.039713699, + -0.0302257 -0.0513607 0.031633701, + -0.027557701 -0.053137999 0.023257401, + -0.028198199 -0.052971501 0.0144578, + -0.0275518 -0.053296 0.0144576, + -0.0255982 -0.054276899 0.0144568, + -0.0226037 -0.055586901 0.0094557405, + -0.0167691 -0.057616498 0.00945412, + -0.0193005 -0.0568063 0.0144548, + 0.040171701 -0.044572901 0.0144645, + 0.040174201 -0.044537701 0.0165991, + 0.038084399 -0.0463751 0.0144631, + 0.040312301 -0.044451501 0.0144646, + 0.040756401 -0.044040602 0.0094649298, + 0.045056298 -0.039610699 0.0144685, + 0.044562198 -0.040183902 0.014468, + 0.045067899 -0.0396166 0.0094684605, + 0.046393901 -0.038058899 0.0144697, + 0.0465803 -0.037774902 0.0165311, + 0.0546159 -0.0201139 0.039220698, + 0.055787299 -0.017018599 0.038308401, + 0.0546159 -0.018996 0.042046599, + 0.059746899 -0.0054081799 0.0144957, + 0.059682 -0.0061768098 0.0094950804, + 0.059927799 -0.00295392 0.0144977, + 0.0597114 -0.0058894102 0.0144953, + 0.059757002 -0.0053930799 0.01534, + 0.059934001 -0.0026996301 0.0144979, + 0.059999999 -1.15461e-005 0.0145, + 0.0599402 -0.0026825599 0.0153273, + 0.059757002 -0.00528024 0.016204599, + 0.059445001 -0.0080318796 0.016232301, + 0.059445001 -0.0076571498 0.0178781, + 0.058998398 -0.0104582 0.017941101, + 0.058998398 -0.0096236104 0.0206351, + 0.058412101 -0.012491 0.0208077, + 0.058412101 -0.0109313 0.025878601, + 0.0576833 -0.0139003 0.026301, + 0.0576833 -0.0124521 0.031557899, + 0.056809202 -0.0155105 0.032234199, + 0.056809202 -0.0148091 0.034841102, + 0.055787299 -0.0178963 0.035638601, + 0.048467699 -0.035318501 0.0165064, + 0.048887499 -0.0347667 0.0144723, + 0.050219599 -0.0327783 0.0164809, + 0.048204001 -0.035737801 0.0144715, + 0.0465803 -0.037611999 0.018552, + 0.044564299 -0.039991301 0.018605599, + 0.044564299 -0.0396626 0.022443499, + 0.0424264 -0.0419752 0.022582799, + 0.044564299 -0.038998801 0.0298726, + 0.0465803 -0.0372428 0.0222978, + 0.048467699 -0.035137899 0.0184961, + 0.052201401 -0.0295555 0.0144765, + 0.051819 -0.030231001 0.0144759, + 0.0522171 -0.029560501 0.0094764596, + 0.051830001 -0.030232901 0.015457, + 0.051472198 -0.0308435 0.0144754, + 0.050209999 -0.032838002 0.0144739, + 0.052922402 -0.0282821 0.0144775, + 0.053284001 -0.027563101 0.0144781, + 0.054245099 -0.0256526 0.0144796, + 0.0532961 -0.027563799 0.0154444, + 0.0546159 -0.0215664 0.0335733, + 0.055787299 -0.018552501 0.032906801, + 0.0546159 -0.020954801 0.036428601, + 0.055787299 -0.019814 0.027142501, + 0.056809202 -0.016865101 0.026722999, + 0.056809202 -0.018235199 0.0211535, + 0.0576833 -0.0153652 0.020980701, + 0.0576833 -0.0161027 0.0180679, + 0.058412101 -0.013277 0.0180043, + 0.058412101 -0.0136123 0.016288299, + 0.058998398 -0.0108133 0.016260199, + 0.058998398 -0.0109163 0.0153658, + 0.059445001 -0.0081399204 0.0153528, + 0.059432399 -0.0081528099 0.0144935, + 0.0596756 -0.00618 0.0144951, + 0.059351299 -0.0088107605 0.014493, + 0.058984298 -0.0109269 0.0144913, + 0.058848299 -0.0117109 0.0144907, + 0.058731299 -0.0122807 0.0094902199, + 0.055772699 -0.0220915 0.0144824, + 0.056496199 -0.0202149 0.0144839, + 0.055787299 -0.022089399 0.0154184, + 0.051830001 -0.028447401 0.028371099, + 0.051830001 -0.0274585 0.034876201, + 0.050219599 -0.0312123 0.028764499, + 0.051830001 -0.0294479 0.021828501, + 0.0532961 -0.0267085 0.0216635, + 0.0532961 -0.0272546 0.0183187, + 0.0546159 -0.0245116 0.018257, + 0.0546159 -0.0247676 0.016400401, + 0.055787299 -0.022006501 0.016372601, + 0.056809202 -0.019307701 0.0154053, + 0.056794401 -0.019311899 0.0144846, + 0.0571438 -0.018253701 0.0144855, + 0.057158101 -0.0182545 0.0094854701, + 0.054979 -0.0240348 0.0094808601, + 0.055437401 -0.0229614 0.0144817, + 0.0546159 -0.0248453 0.0154314, + 0.0532961 -0.027491201 0.016427699, + 0.051830001 -0.029947899 0.018379301, + 0.050219599 -0.032124501 0.021989601, + 0.048467699 -0.0339 0.029146999, + 0.050219599 -0.030310599 0.035507001, + 0.051830001 -0.027212501 0.036491401, + 0.0532961 -0.0245394 0.034230798, + 0.058412101 -0.0137104 0.015379, + 0.0576833 -0.016511099 0.0153922, + 0.058203701 -0.0145829 0.0144884, + 0.0576833 -0.016418001 0.0163165, + 0.056809202 -0.0192197 0.016344599, + 0.056809202 -0.0189243 0.018131301, + 0.055787299 -0.0217309 0.0181944, + 0.055787299 -0.0210901 0.0213253, + 0.0546159 -0.0239185 0.021495599, + 0.0546159 -0.022735801 0.027558301, + 0.0532961 -0.0256177 0.027968399, + 0.057419099 -0.017419901 0.0144861, + 0.057668701 -0.016517401 0.0144869, + 0.058397699 -0.0137188 0.0144891, + 0.058720101 -0.0122821 0.0144902, + 0.0532961 -0.0239718 0.037207901, + 0.051830001 -0.0269341 0.037973199, + 0.050219599 -0.030086299 0.037182398, + 0.048467699 -0.033083301 0.036120102, + 0.0465803 -0.036499199 0.029516799, + 0.048467699 -0.034726501 0.0221464, + 0.050219599 -0.032579601 0.0184386, + 0.051830001 -0.0301654 0.0164546, + 0.0546025 -0.0248459 0.0144802, + 0.054963201 -0.024031701 0.0144809, + 0.0465803 -0.0357645 0.036713, + 0.048467699 -0.032880001 0.0378539, + 0.050219599 -0.0298285 0.038720999, + 0.051830001 -0.026587 0.039471101, + 0.0532961 -0.023167299 0.040120602, + 0.048901699 -0.034772899 0.0094723096, + 0.0498982 -0.033330798 0.0144735, + 0.048460599 -0.0353733 0.0144718, + 0.0465759 -0.037825499 0.0144699, + 0.042443302 -0.042420998 0.0144662, + 0.036012899 -0.047997899 0.0094617801, + 0.037813399 -0.0465867 0.0144629, + 0.035366699 -0.0484506 0.016638501, + 0.036008701 -0.047996499 0.0144618, + 0.0378174 -0.046558499 0.016619399, + 0.035366699 -0.0483649 0.018794499, + 0.0328326 -0.050133899 0.0188345, + 0.0328326 -0.049977101 0.0230648, + 0.0302257 -0.0517601 0.0188713, + 0.0328326 -0.050206799 0.016656199, + 0.033358999 -0.049883101 0.0144603, + 0.035361301 -0.048471499 0.0144614, + 0.035764702 -0.048187099 0.0144616, + 0.0378174 -0.046459101 0.0187515, + 0.035366699 -0.0481782 0.022956399, + 0.035366699 -0.047795001 0.031124299, + 0.0378174 -0.045793202 0.030839499, + 0.0378174 -0.0453519 0.0388331, + 0.040174201 -0.0431461 0.0383454, + 0.040174201 -0.043019101 0.040291701, + 0.0424264 -0.0406623 0.039724998, + 0.0424264 -0.040480699 0.041473199, + 0.044564299 -0.037980001 0.040827099, + 0.044564299 -0.037703902 0.0425434, + 0.0465803 -0.035070401 0.041815501, + 0.0465803 -0.034696098 0.043518301, + 0.048467699 -0.031942099 0.042706698, + 0.048467699 -0.0314744 0.044360101, + 0.0465803 -0.034241501 0.045227099, + 0.0465803 -0.033705398 0.046933599, + 0.044564299 -0.0373444 0.044298802, + 0.0424264 -0.0402207 0.043239001, + 0.040174201 -0.042854398 0.042086601, + 0.0378174 -0.045241602 0.040826101, + 0.035366699 -0.047416899 0.039289799, + 0.0328326 -0.049653001 0.031388901, + 0.0302257 -0.051630698 0.023164401, + 0.027557701 -0.053240702 0.0189049, + 0.0302257 -0.051821101 0.016672401, + 0.0308873 -0.051449999 0.014459, + 0.0302191 -0.051830001 0.0144587, + 0.0308876 -0.051446401 0.0094590401, + 0.030873001 -0.0514591 0.014459, + 0.0283127 -0.0529113 0.0144579, + 0.0328261 -0.050220899 0.01446, + 0.0254349 -0.054349601 0.0094567202, + 0.0275514 -0.053295098 0.0144576, + 0.025684301 -0.0542362 0.0144568, + 0.027557701 -0.0532909 0.0166873, + 0.0248404 -0.054573599 0.018935001, + 0.027557701 -0.053135999 0.0232551, + 0.0302257 -0.051360998 0.031631902, + 0.0328326 -0.049333598 0.039713599, + 0.035366699 -0.047322199 0.041326299, + 0.0378174 -0.045092899 0.042665102, + 0.040174201 -0.0426098 0.043899301, + 0.0424264 -0.039875299 0.045044702, + 0.044564299 -0.036902498 0.046060901, + -0.019305199 -0.056641702 0.032384701, + -0.0220857 -0.055695701 0.023411199, + -0.020158799 -0.056523599 0.014455, + -0.040174201 -0.041371599 0.049469899, + -0.0424264 -0.038949199 0.0486646, + -0.040174201 -0.041875701 0.047611099, + -0.0378174 -0.044151202 0.048324499, + -0.0378174 -0.044555601 0.046423201, + -0.035366699 -0.046675801 0.047048099, + -0.0248404 -0.054315399 0.032054, + -0.0220857 -0.055557899 0.032230701, + -0.0248404 -0.054143298 0.0407773, + -0.027557701 -0.052699301 0.040458001, + -0.027557701 -0.052645199 0.042610101, + -0.0302257 -0.051029101 0.042221799, + -0.0302257 -0.050924499 0.044183601, + -0.0328326 -0.049136501 0.043722302, + -0.0328326 -0.048936401 0.045656599, + -0.035366699 -0.046978999 0.045116302, + -0.0378174 -0.0448705 0.044534098, + -0.040174201 -0.042290699 0.045755599, + -0.0424264 -0.0394627 0.0468546, + -0.044564299 -0.036397099 0.047816198, + -0.0424264 -0.0383467 0.0504729, + 0.0137813 -0.058403399 0.0094534997, + 0.0197125 -0.056676898 0.0094548697, + 0.0165058 -0.057679798 0.0144541, + 0.0193002 -0.056805499 0.0144548, + 0.019709 -0.0566702 0.0144549, + 0.019305199 -0.056812901 0.0167228, + 0.017454101 -0.0574167 0.0144543, + 0.0165099 -0.057672098 0.0190056, + 0.019305199 -0.056789 0.018985501, + 0.019305199 -0.056743301 0.023472499, + 0.0220857 -0.055693999 0.0234093, + 0.0220857 -0.0555581 0.032229401, + 0.0248404 -0.054315601 0.032052498, + 0.0248404 -0.0541435 0.040777199, + 0.027557701 -0.052699499 0.040457901, + 0.027557701 -0.052645002 0.042606302, + 0.0302257 -0.051028799 0.042217702, + 0.0302257 -0.050921801 0.044171799, + 0.0328326 -0.049133699 0.043709598, + 0.0328326 -0.048929699 0.045646202, + 0.035366699 -0.046971802 0.045104999, + 0.035366699 -0.046664398 0.047045499, + 0.0378174 -0.0445433 0.046420299, + 0.0378174 -0.044135898 0.048327301, + 0.040174201 -0.0418594 0.047614101, + 0.040174201 -0.041353401 0.049474299, + 0.0424264 -0.038929999 0.0486692, + 0.0424264 -0.038326401 0.050476, + 0.044564299 -0.036376901 0.047821, + 0.0424264 -0.039445501 0.0468577, + 0.040174201 -0.042277601 0.0457527, + 0.0378174 -0.044862699 0.044521999, + 0.035366699 -0.047188502 0.043206699, + 0.0328326 -0.049253501 0.041790701, + 0.0302257 -0.051095501 0.040103201, + 0.027557701 -0.052916002 0.0318533, + 0.0248404 -0.054491099 0.023336699, + 0.0220857 -0.0557568 0.018962, + 0.024834299 -0.054613601 0.0144565, + 0.0254324 -0.054347999 0.0144567, + 0.0248404 -0.054613899 0.016700599, + 0.022994 -0.055430599 0.0144559, + 0.0220799 -0.055783801 0.0144556, + 0.0202484 -0.056491598 0.014455, + 0.0220857 -0.055788402 0.016712399, + 0.0146178 -0.0582036 0.0144537, + 0.0109153 -0.058995299 0.014453, + 0.0077038999 -0.059510902 0.0094526103, + 0.0053910702 -0.059758 0.0144524, + 0.0059254402 -0.059718199 0.0144525, + 0.0053918599 -0.059770498 0.023655299, + 0.00154487 -0.059987601 0.0094522396, + 0.0029901101 -0.0599369 0.0144523, + -0.0081421202 -0.059426799 0.041945599, + -0.0053918599 -0.059768301 0.042021099, + -0.0081421202 -0.059423499 0.044238102, + -0.0109179 -0.058931202 0.044119898, + -0.0109179 -0.0588824 0.046235099, + -0.0137106 -0.0582317 0.046067499, + -0.0137106 -0.0580885 0.048182599, + -0.0165099 -0.057274301 0.047958001, + -0.0165099 -0.057027198 0.050099101, + -0.019305199 -0.056045499 0.049809799, + -0.019305199 -0.055695001 0.051944301, + -0.0220857 -0.054542001 0.051582702, + -0.0220857 -0.054087199 0.053697601, + -0.0248404 -0.052760102 0.053256299, + -0.0248404 -0.052200399 0.055343401, + -0.027557701 -0.050700601 0.054816101, + -0.027557701 -0.050035302 0.056866799, + -0.0302257 -0.048365399 0.056247398, + -0.027557701 -0.049267702 0.058905698, + -0.0248404 -0.0515384 0.0574244, + -0.0220857 -0.053531501 0.055811599, + -0.019305199 -0.055244699 0.054082699, + -0.0165099 -0.056681201 0.052253701, + -0.0137106 -0.057845701 0.050340399, + -0.0109179 -0.058743201 0.048363101, + -0.0081421202 -0.059378099 0.046362601, + -0.0053918599 -0.0597676 0.044320501, + -0.00267513 -0.059968699 0.042065501, + 0.00267513 -0.055976201 0.0640359, + 0 -0.0560451 0.0640641, + 0.00267513 -0.0568415 0.0618646, + 0 -0.055072401 0.066209398, + -0.00267513 -0.055977602 0.064036101, + 0 -0.056910399 0.061891299, + 0 -0.057667401 0.0596992, + -0.00267513 -0.056842901 0.0618647, + -0.0053918599 -0.055769101 0.063950501, + -0.00267513 -0.055004898 0.066180103, + 0 -0.053993199 0.068318702, + 0.00267513 -0.055003501 0.066179797, + 0.0053918599 -0.0557664 0.063950099, + -0.00267513 -0.058789499 0.0552628, + 0 -0.058856599 0.055285498, + -0.00267513 -0.058248099 0.057471398, + -0.0053918599 -0.0580405 0.0573982, + -0.0053918599 -0.0573918 0.059596501, + -0.0081421202 -0.057036899 0.0594646, + -0.0081421202 -0.0562791 0.0616442, + -0.0109179 -0.0557702 0.0614453, + -0.0081421202 -0.055413499 0.0638045, + -0.0053918599 -0.056634501 0.061783198, + -0.00267513 -0.057599802 0.059673801, + 0 -0.058315501 0.057495501, + 0.00267513 -0.058246799 0.057471599, + 0.00267513 -0.057598501 0.059673999, + 0.0053918599 -0.0573892 0.059596501, + 0.0053918599 -0.0566318 0.0617829, + 0.0081421202 -0.056274999 0.061643898, + -0.0053918599 -0.054796498 0.066090301, + -0.00267513 -0.053925801 0.0682882, + 0 -0.052808899 0.0703841, + 0.00267513 -0.0539244 0.068287797, + 0.0053918599 -0.054793701 0.066089697, + 0.0081421202 -0.055409402 0.063803799, + 0.0109179 -0.055764701 0.061444901, + 0.0081421202 -0.057032902 0.059464701, + 0.0053918599 -0.058037899 0.057398599, + 0.00267513 -0.0587883 0.055263098, + 0 -0.0592933 0.053073999, + -0.00267513 -0.059226301 0.053052802, + -0.0053918599 -0.0585826 0.0551937, + -0.0081421202 -0.0576864 0.057273399, + -0.0109179 -0.056528602 0.059275899, + -0.0137106 -0.055101998 0.061184201, + -0.0109179 -0.054904401 0.063595504, + -0.0081421202 -0.054441001 0.065937303, + -0.0053918599 -0.053717598 0.068194203, + -0.00267513 -0.052741501 0.070352197, + 0 -0.051522899 0.072397903, + 0.00267513 -0.052740101 0.070351698, + 0.0053918599 -0.053714801 0.068193398, + 0.0081421202 -0.054436799 0.065936297, + 0.0109179 -0.054898798 0.063594498, + 0.0137106 -0.055095099 0.061183698, + 0.0109179 -0.056523301 0.0592761, + 0.0081421202 -0.057682499 0.057273999, + 0.0053918599 -0.058580101 0.0551943, + 0.00267513 -0.059225202 0.053052999, + 0 -0.059627499 0.050865602, + -0.00267513 -0.059560802 0.050845999, + -0.0053918599 -0.059020098 0.052987799, + -0.0081421202 -0.058229499 0.055075999, + -0.0109179 -0.057179399 0.057094902, + -0.0137106 -0.055861399 0.059028201, + -0.0165099 -0.054271001 0.060859699, + -0.0137106 -0.054235701 0.063321002, + -0.0109179 -0.053931899 0.065718099, + -0.0081421202 -0.0533625 0.068034202, + -0.0053918599 -0.052533802 0.070254304, + -0.00267513 -0.051455598 0.072364897, + 0 -0.050138898 0.074352898, + 0.00267513 -0.051454201 0.0723643, + 0.0053918599 -0.052531101 0.070253298, + 0.0081421202 -0.053358302 0.068032898, + 0.0109179 -0.0539263 0.065716803, + 0.0137106 -0.054228701 0.063319802, + 0.0165099 -0.054262701 0.060858998, + 0.0137106 -0.0558546 0.059028398, + 0.0109179 -0.057174101 0.057095699, + 0.0081421202 -0.058225799 0.055077001, + 0.0053918599 -0.0590179 0.052988201, + 0.00267513 -0.0595599 0.050845802, + 0 -0.059861299 0.048670501, + -0.00267513 -0.059794798 0.0486525, + -0.0053918599 -0.059355501 0.0507854, + -0.0081421202 -0.058668301 0.052877299, + -0.0109179 -0.057723898 0.054907698, + -0.0137106 -0.0565136 0.0568606, + -0.0165099 -0.055031601 0.058720302, + -0.019305199 -0.0532743 0.060470399, + -0.0165099 -0.053404301 0.062979802, + -0.0137106 -0.0532635 0.065430298, + -0.0109179 -0.052854002 0.067805, + -0.0081421202 -0.052179299 0.070087299, + -0.0053918599 -0.051248498 0.072262898, + -0.00267513 -0.050071999 0.074318603, + 0 -0.048661198 0.076241799, + 0.00267513 -0.050070599 0.074317798, + 0.0053918599 -0.051245701 0.072261699, + 0.0081421202 -0.052175101 0.070085801, + 0.0109179 -0.052848302 0.067803301, + 0.0137106 -0.053256501 0.065428697, + 0.0165099 -0.053395901 0.062978402, + 0.019305199 -0.053264599 0.060469601, + 0.0165099 -0.055023499 0.058720499, + 0.0137106 -0.056506999 0.056861602, + 0.0109179 -0.057718899 0.054908901, + 0.0081421202 -0.058665 0.052877899, + 0.0053918599 -0.059353702 0.050785001, + 0.00267513 -0.059794199 0.048651699, + 0 -0.059994102 0.046520099, + -0.00267513 -0.059927698 0.0465036, + -0.0053918599 -0.059590399 0.048596501, + -0.0081421202 -0.059005301 0.050682101, + -0.0109179 -0.058164701 0.052719198, + -0.0137106 -0.057060201 0.0546868, + -0.0165099 -0.055685598 0.056569301, + -0.019305199 -0.054036301 0.058350999, + -0.0220857 -0.052108899 0.060015298, + -0.019305199 -0.0524069 0.062570497, + -0.0165099 -0.052432202 0.065072604, + -0.0137106 -0.052186299 0.067504101, + -0.0109179 -0.051671699 0.069848202, + -0.0081421202 -0.050894901 0.072089098, + -0.0053918599 -0.049865499 0.074212797, + -0.00267513 -0.048594501 0.0762062, + 0 -0.047093902 0.078057401, + 0.00267513 -0.048593201 0.076205403, + 0.0053918599 -0.049862798 0.074211299, + 0.0081421202 -0.0508908 0.072087303, + 0.0109179 -0.0516661 0.069846198, + 0.0137106 -0.052179199 0.067501999, + 0.0165099 -0.052423701 0.065070599, + 0.019305199 -0.052397098 0.062568903, + 0.0220857 -0.052097902 0.0600143, + 0.019305199 -0.054026801 0.0583512, + 0.0165099 -0.055677701 0.0565705, + 0.0137106 -0.057054002 0.0546882, + 0.0109179 -0.058160301 0.052719999, + 0.0081421202 -0.059002601 0.050681502, + 0.0053918599 -0.0595893 0.048594698, + 0.00267513 -0.059927501 0.046502501, + 0 -0.0600354 0.044384599, + -0.00267513 -0.059969399 0.044369001, + -0.0053918599 -0.059724499 0.046451598, + -0.0081421202 -0.059241898 0.048500501, + -0.0109179 -0.0585039 0.050534301, + -0.0137106 -0.057503499 0.052511599, + -0.0165099 -0.056234699 0.054412, + -0.019305199 -0.054692499 0.056219999, + -0.0220857 -0.052872501 0.057919301, + -0.0248404 -0.050772998 0.059493601, + -0.0220857 -0.051240999 0.062092099, + -0.019305199 -0.051435299 0.064643502, + -0.0165099 -0.051355898 0.067129903, + -0.0137106 -0.051005401 0.069534197, + -0.0109179 -0.050388701 0.071840197, + -0.0081421202 -0.049513299 0.074032299, + -0.0053918599 -0.048388898 0.076096602, + -0.00267513 -0.047027402 0.078020804, + 0 -0.045442998 0.079794303, + 0.00267513 -0.047026198 0.078019798, + 0.0053918599 -0.048386302 0.076095, + 0.0081421202 -0.049509201 0.074030101, + 0.0109179 -0.050383199 0.071837701, + 0.0137106 -0.0509983 0.069531702, + 0.0165099 -0.051347401 0.067127302, + 0.019305199 -0.051425301 0.0646412, + 0.0220857 -0.051229801 0.062090199, + 0.0248404 -0.0507605 0.059492499, + 0.0220857 -0.052861702 0.057919499, + 0.019305199 -0.054683302 0.056221399, + 0.0165099 -0.0562272 0.054413799, + 0.0137106 -0.0574979 0.052512702, + 0.0109179 -0.058500402 0.0505335, + 0.0081421202 -0.0592403 0.0484979, + 0.0053918599 -0.0597241 0.046449501, + 0.00267513 -0.059969399 0.044368599, + 0 -0.0600341 0.042079899, + -0.0248404 -0.049904201 0.061543599, + -0.0220857 -0.050269499 0.064141802, + -0.019305199 -0.050359901 0.066681102, + -0.0165099 -0.050176602 0.069143899, + -0.0137106 -0.049724098 0.071513399, + -0.0109179 -0.049008802 0.073773801, + -0.0081421202 -0.048038099 0.0759096, + -0.0053918599 -0.046822801 0.077907398, + -0.00267513 -0.045376901 0.079756401, + 0 -0.043714799 0.081446998, + 0.00267513 -0.045375701 0.079755403, + 0.0053918599 -0.046820302 0.077905498, + 0.0081421202 -0.048034199 0.075907104, + 0.0109179 -0.0490034 0.073770903, + 0.0137106 -0.049717199 0.0715103, + 0.0165099 -0.050168101 0.069140799, + 0.019305199 -0.050349999 0.066678099, + 0.0220857 -0.050258201 0.064139098, + 0.0248404 -0.049891599 0.061541501, + 0.027557701 -0.0492539 0.058904499, + 0.0248404 -0.0515262 0.057424702, + 0.0220857 -0.053520899 0.055813201, + 0.019305199 -0.055236001 0.0540848, + 0.0165099 -0.056674499 0.0522549, + 0.0137106 -0.0578412 0.050339401, + 0.0109179 -0.058741 0.048359599, + 0.0081421202 -0.059377398 0.046359401, + 0.0053918599 -0.0597675 0.044319801, + 0.00267513 -0.059968699 0.042065501, + 0 -0.060026001 0.032865699, + -0.00267513 -0.0599626 0.0328568, + -0.0053918599 -0.059768301 0.032829199, + -0.0046292599 -0.059815101 0.0144524, + -0.0081406701 -0.059444599 0.0144527, + -0.0058307201 -0.059727501 0.0144524, + -0.0081421202 -0.059437301 0.032782201, + -0.0109179 -0.058938202 0.041837599, + -0.0137106 -0.058285002 0.043964799, + -0.0165099 -0.0574225 0.045859098, + -0.019305199 -0.056297999 0.0476887, + -0.0220857 -0.0548978 0.049471501, + -0.0248404 -0.053220101 0.051167998, + -0.027557701 -0.051265001 0.0527592, + -0.0302257 -0.049034499 0.054230299, + -0.0328326 -0.0465311 0.055567101, + -0.0302257 -0.0475954 0.0582527, + -0.027557701 -0.048397999 0.060925599, + -0.0248404 -0.0489331 0.0635667, + -0.0220857 -0.049195498 0.066156298, + -0.019305199 -0.049182501 0.0686756, + -0.0165099 -0.048897501 0.071107097, + -0.0137106 -0.0483464 0.073434398, + -0.0109179 -0.047535699 0.075641803, + -0.0081421202 -0.046473801 0.077714004, + -0.0053918599 -0.045173399 0.079639502, + -0.00267513 -0.0436491 0.081408001, + 0 -0.0419157 0.0830101, + 0.00267513 -0.0436479 0.081406899, + 0.0053918599 -0.045171 0.079637498, + 0.0081421202 -0.046470001 0.077711202, + 0.0109179 -0.047530401 0.075638399, + 0.0137106 -0.048339602 0.073430799, + 0.0165099 -0.048889101 0.071103297, + 0.019305199 -0.049172599 0.068672001, + 0.0220857 -0.049184099 0.066152997, + 0.0248404 -0.0489203 0.063563697, + 0.027557701 -0.048384 0.060923301, + 0.0302257 -0.047580302 0.0582514, + 0.0302257 -0.048350599 0.0562477, + 0.0328326 -0.046514999 0.055567399, + 0.0302257 -0.04902 0.0542325, + 0.027557701 -0.050687399 0.054818202, + 0.027557701 -0.051252499 0.052762199, + 0.0248404 -0.0527489 0.053259101, + 0.0248404 -0.053210001 0.051169898, + 0.0220857 -0.054533001 0.0515843, + 0.0220857 -0.054890599 0.049469799, + 0.019305199 -0.0560393 0.049808301, + 0.019305199 -0.056294002 0.047682501, + 0.0165099 -0.057271 0.047952801, + 0.0165099 -0.057421099 0.045852698, + 0.0137106 -0.058230501 0.046062201, + 0.0137106 -0.058284901 0.0439629, + 0.0109179 -0.058931101 0.044118401, + 0.0109179 -0.058938298 0.041837599, + 0.0081421202 -0.0594269 0.041945599, + 0.0081421202 -0.059437402 0.032781702, + 0.0053918599 -0.059768401 0.032828901, + 0.00267513 -0.0599587 0.0236667, + 0.0026749601 -0.059944902 0.0144523, + 4.7590001e-005 -0.060011499 0.0144522, + 0.00154442 -0.059973601 0.0144522, + 0 -0.060020201 0.0236705, + 0.00267513 -0.0599626 0.032856699, + 0.0053918599 -0.059768401 0.042021099, + 0.0081421202 -0.059423398 0.044236999, + 0.0109179 -0.058881499 0.0462308, + 0.0137106 -0.058085699 0.0481783, + 0.0165099 -0.0570218 0.050097901, + 0.019305199 -0.0556872 0.051945802, + 0.0220857 -0.054077201 0.053700201, + 0.0248404 -0.0521884 0.055345301, + 0.027557701 -0.050021801 0.0568671, + -0.0026750199 -0.059946802 0.0144523, + 2.7e-008 -0.0600104 0.0144522, + -0.0046305298 -0.059828501 0.0094523598, + -0.00289505 -0.059941601 0.0144523, + -0.0053912001 -0.059759598 0.0144524, + -0.0107568 -0.059035402 0.0094529903, + -0.035366699 -0.0452132 0.052886799, + -0.0378174 -0.043067999 0.052132599, + -0.035366699 -0.045794599 0.050940201, + -0.0328326 -0.0477795 0.051600199, + -0.0328326 -0.048258699 0.049612299, + -0.0302257 -0.050076202 0.0501821, + -0.0302257 -0.050452799 0.048161302, + -0.027557701 -0.052099701 0.0486467, + -0.027557701 -0.052373402 0.046605501, + -0.0248404 -0.0538477 0.0470125, + -0.0248404 -0.054017201 0.044981301, + -0.0220857 -0.0553177 0.045316599, + -0.0220857 -0.055391502 0.043269798, + -0.019305199 -0.056518 0.0435404, + -0.019305199 -0.056543 0.041308001, + -0.0165099 -0.057499401 0.0415194, + -0.0137106 -0.058341801 0.032626498, + -0.0165099 -0.0575688 0.032516599, + -0.0145255 -0.058226701 0.0144536, + -0.0167659 -0.057608899 0.0144541, + -0.017363001 -0.057444301 0.0144543, + -0.0220857 -0.055424899 0.041060802, + -0.0248404 -0.0541001 0.042959601, + -0.027557701 -0.052552 0.0446034, + -0.0302257 -0.0507356 0.0461534, + -0.0328326 -0.048643801 0.047628202, + -0.035366699 -0.046281401 0.048992399, + -0.0378174 -0.043655999 0.0502293, + -0.040174201 -0.040776599 0.051327001, + -0.0378174 -0.0423855 0.054029498, + 0.0081421202 -0.0594499 0.0236359, + 0.0088465102 -0.059355699 0.0144527, + 0.0109179 -0.0590013 0.019036001, + 0.0117463 -0.058850501 0.0144531, + 0.0137106 -0.058408801 0.0190224, + 0.0137106 -0.058389299 0.0235718, + 0.0165099 -0.057640899 0.0235267, + 0.0165099 -0.0575689 0.032515701, + 0.019305199 -0.056641899 0.032383598, + 0.019305199 -0.056543101 0.0413079, + 0.0220857 -0.0554251 0.041060701, + 0.0220857 -0.0553913 0.043266799, + 0.0248404 -0.054099798 0.042956199, + 0.0248404 -0.0540151 0.0449716, + 0.027557701 -0.052549701 0.044592701, + 0.027557701 -0.052367698 0.046596698, + 0.0302257 -0.050729401 0.046143699, + 0.0302257 -0.050443001 0.048159, + 0.0328326 -0.048633099 0.047625698, + 0.0328326 -0.0482453 0.049614701, + 0.035366699 -0.046266999 0.048994999, + 0.035366699 -0.045778502 0.050944101, + 0.0378174 -0.043638799 0.050233401, + 0.0378174 -0.043049902 0.0521354, + 0.040174201 -0.040757399 0.051330101, + 0.0378174 -0.0423669 0.054029901, + 0.035366699 -0.045196202 0.052889299, + 0.0328326 -0.047764599 0.051603802, + 0.0302257 -0.050063901 0.050184399, + 0.027557701 -0.0520906 0.048644599, + 0.0248404 -0.0538426 0.047004499, + 0.0220857 -0.0553158 0.045308001, + 0.019305199 -0.056517798 0.043537699, + 0.0165099 -0.057499502 0.041519299, + 0.0137106 -0.058341999 0.032625701, + 0.0109179 -0.058991302 0.0236081, + 0.0109179 -0.058963802 0.0327143, + 0.0137106 -0.0582969 0.041695699, + 0.0165099 -0.057481401 0.043769501, + 0.019305199 -0.056450501 0.045601599, + 0.0220857 -0.055151898 0.0473666, + 0.0248404 -0.053574 0.049081799, + 0.027557701 -0.051719502 0.050703, + 0.0302257 -0.049590301 0.0522101, + 0.0328326 -0.047188599 0.053589199, + 0.035366699 -0.044518199 0.054827299, + 0.035366699 -0.0437424 0.056753699, + 0.0328326 -0.045742001 0.057534099, + 0.0328326 -0.044870201 0.059482198, + 0.0302257 -0.0467095 0.060236499, + 0.0302257 -0.045738999 0.0621952, + 0.027557701 -0.0474132 0.0629154, + 0.027557701 -0.046342202 0.064872898, + 0.0248404 -0.047847699 0.065550998, + 0.0248404 -0.046675 0.067495801, + 0.0220857 -0.0480089 0.068124004, + 0.0220857 -0.046735801 0.070044801, + 0.019305199 -0.0478963 0.070615299, + 0.019305199 -0.046525098 0.072501101, + 0.0165099 -0.047514498 0.073008001, + 0.0165099 -0.0460479 0.074847497, + 0.0137106 -0.046869598 0.0752858, + 0.0137106 -0.045311201 0.0770685, + 0.0109179 -0.045968801 0.077433199, + 0.0109179 -0.044324301 0.079149798, + 0.0081421202 -0.0448227 0.079436697, + 0.0081421202 -0.043098502 0.0810785, + 0.0053918599 -0.0434446 0.081285298, + 0.0053918599 -0.041647501 0.0828439, + 0.00267513 -0.041849501 0.082968898, + 0.00267513 -0.0399867 0.084436603, + 0 -0.0400525 0.0844789, + 0 -0.0381325 0.085850403, + -0.00267513 -0.039987601 0.084437899, + -0.00267513 -0.0418505 0.082970098, + -0.0053918599 -0.041649699 0.082846299, + -0.0053918599 -0.043446802 0.081287503, + -0.0081421202 -0.043102 0.081081897, + -0.0081421202 -0.044826299 0.079439797, + -0.0109179 -0.0443292 0.079153903, + -0.0109179 -0.045974001 0.077436998, + -0.0137106 -0.045317698 0.077073202, + -0.0137106 -0.0468762 0.075290002, + -0.0165099 -0.046055902 0.074852601, + -0.0165099 -0.047522798 0.073012397, + -0.019305199 -0.046534698 0.072506197, + -0.019305199 -0.047906101 0.070619702, + -0.0220857 -0.046746999 0.0700498, + -0.0220857 -0.0480203 0.068128102, + -0.0248404 -0.0466878 0.067500502, + -0.0248404 -0.047860499 0.065554798, + -0.027557701 -0.046356399 0.0648771, + -0.027557701 -0.0474273 0.0629187, + -0.0302257 -0.0457545 0.062198799, + -0.0302257 -0.046724901 0.060239099, + -0.0328326 -0.044886898 0.059485, + -0.0328326 -0.045758501 0.057535499, + -0.035366699 -0.043760099 0.0567552, + -0.035366699 -0.0445356 0.0548269, + -0.0328326 -0.047204301 0.0535868, + -0.0302257 -0.049604099 0.052206799, + -0.027557701 -0.0517307 0.050701, + -0.0248404 -0.053582001 0.049083602, + -0.0220857 -0.055156399 0.047373701, + -0.019305199 -0.056452099 0.045609102, + -0.0165099 -0.057481602 0.0437718, + -0.0137106 -0.0582968 0.0416958, + -0.0109179 -0.058963601 0.0327149, + -0.0116529 -0.058869001 0.0144531, + -0.0107542 -0.0590242 0.014453, + -0.0109155 -0.058996301 0.014453, + -0.00875236 -0.059369698 0.0144527, + 0.0077017802 -0.0594978 0.0144526, + 0.0081404904 -0.059443399 0.0144527, + 0.0137072 -0.0584087 0.0144535, + 0.013778 -0.0583928 0.0144535, + 0.040174201 -0.0400692 0.053178199, + 0.0378174 -0.041588102 0.055912901, + 0.035366699 -0.0428693 0.058661699, + 0.0328326 -0.043900199 0.061404198, + 0.0302257 -0.0446698 0.064119503, + 0.027557701 -0.0451723 0.0667881, + 0.0248404 -0.0454056 0.0693909, + 0.0220857 -0.045368701 0.071908399, + 0.019305199 -0.045062799 0.074322, + 0.0165099 -0.044493701 0.076615199, + 0.0137106 -0.043670502 0.078773201, + 0.0109179 -0.0426034 0.080782801, + 0.0081421202 -0.041303899 0.082631104, + 0.0053918599 -0.039786302 0.0843082, + 0.00267513 -0.0380673 0.085807003, + 0 -0.036163799 0.087121896, + -0.00267513 -0.038068201 0.085808203, + -0.0053918599 -0.039788298 0.084310703, + -0.0081421202 -0.041307099 0.082634702, + -0.0109179 -0.042608 0.080787398, + -0.0137106 -0.0436766 0.078778498, + -0.0165099 -0.044501401 0.076620899, + -0.019305199 -0.045072202 0.074327901, + -0.0220857 -0.045379698 0.0719143, + -0.0248404 -0.045418199 0.069396503, + -0.027557701 -0.045186501 0.0667933, + -0.0302257 -0.044685401 0.064124197, + -0.0328326 -0.043917 0.061407998, + -0.035366699 -0.0428872 0.058664698, + -0.0378174 -0.041607 0.055914499, + -0.040174201 -0.040089 0.0531778, + -0.0248404 -0.054492999 0.023338901, + -0.027557701 -0.0529157 0.031854901, + -0.0302257 -0.051095299 0.040103301, + -0.0328326 -0.0492539 0.041795202, + -0.035366699 -0.047191501 0.043220501, + -0.0378174 -0.0450962 0.042679802, + -0.040174201 -0.042617999 0.043912102, + -0.0424264 -0.039889 0.045047902, + -0.044564299 -0.0369206 0.046057601, + -0.0465803 -0.033726599 0.046928499, + -0.044564299 -0.0357867 0.049573001, + -0.0424264 -0.037653401 0.052274499, + -0.040174201 -0.039307199 0.055016499, + -0.0378174 -0.040732998 0.057780799, + -0.035366699 -0.041917901 0.060547799, + -0.0328326 -0.042849801 0.063297197, + -0.0302257 -0.0435187 0.0660078, + -0.027557701 -0.043920901 0.068660296, + -0.0248404 -0.044055399 0.071235701, + -0.0220857 -0.043921899 0.073714502, + -0.019305199 -0.0435226 0.076078303, + -0.0165099 -0.042865101 0.0783116, + -0.0137106 -0.041959502 0.080400497, + -0.0109179 -0.040816601 0.082331799, + -0.0081421202 -0.039448299 0.084093601, + -0.0053918599 -0.0378704 0.085677996, + -0.00267513 -0.036100101 0.087078802, + 0 -0.034154098 0.0882909, + 0.00267513 -0.036099199 0.087077498, + 0.0053918599 -0.037868701 0.085675403, + 0.0081421202 -0.0394454 0.084089801, + 0.0109179 -0.040812299 0.082327001, + 0.0137106 -0.041953702 0.080394797, + 0.0165099 -0.042857699 0.078305297, + 0.019305199 -0.043513499 0.076071598, + 0.0220857 -0.0439112 0.073707901, + 0.0248404 -0.044043001 0.0712291, + 0.027557701 -0.043906901 0.068654202, + 0.0302257 -0.043503199 0.066002198, + 0.0328326 -0.0428329 0.063292101, + 0.035366699 -0.0418997 0.060543701, + 0.0378174 -0.040713701 0.057777599, + 0.040174201 -0.039287001 0.0550148, + 0.0424264 -0.037632599 0.052274998, + 0.044564299 -0.035765398 0.049576201, + -0.0137074 -0.058409601 0.0144535, + -0.016505999 -0.057680599 0.0144541, + -0.0220802 -0.055784602 0.0144556, + -0.0226011 -0.0555843 0.0144557, + -0.0229061 -0.055466998 0.0144558, + -0.0248347 -0.054614399 0.0144565, + -0.040174201 -0.0428578 0.0421023, + -0.0424264 -0.040229499 0.043252502, + -0.044564299 -0.037358802 0.044302098, + -0.0465803 -0.0342604 0.045223601, + -0.048467699 -0.0314942 0.044356499, + -0.0465803 -0.034711201 0.043521799, + -0.044564299 -0.037713099 0.042557601, + -0.0424264 -0.040484399 0.041489702, + -0.040174201 -0.043145798 0.038345501, + -0.0378174 -0.045792799 0.0308416, + -0.035366699 -0.048180901 0.0229594, + -0.0378174 -0.046483099 0.0187607, + -0.0384284 -0.046076 0.0144633, + -0.040173098 -0.044574499 0.0144645, + -0.044560701 -0.040182602 0.014468, + -0.044408198 -0.040358901 0.0144679, + -0.0599204 -0.0030962699 0.0094975401, + -0.059745401 -0.0054080202 0.0144957, + -0.059919201 -0.00310016 0.0144975, + -0.059923101 -0.0030489999 0.0144976, + -0.0599402 -0.0025810599 0.016179901, + -0.059757002 -0.0051438198 0.0170417, + -0.059445001 -0.00769467 0.0178925, + -0.058998398 -0.0096280398 0.020640099, + -0.058412101 -0.0124954 0.0208127, + -0.058412101 -0.0109307 0.025882, + -0.0576833 -0.0138997 0.0263044, + -0.0576833 -0.0124516 0.0315581, + -0.056809202 -0.01551 0.032234401, + -0.056809202 -0.0148141 0.0348632, + -0.055787299 -0.0179011 0.0356603, + -0.055787299 -0.0170366 0.038312498, + -0.0546159 -0.020131599 0.039224699, + -0.0532961 -0.022679299 0.041593399, + -0.0546159 -0.0190208 0.042040601, + -0.0546159 -0.0209595 0.036449801, + -0.0532961 -0.0236167 0.038664401, + -0.0546159 -0.021565899 0.033573501, + -0.0532961 -0.024538999 0.034231, + -0.0546159 -0.022735201 0.0275614, + -0.055787299 -0.0198134 0.027145701, + -0.055787299 -0.0210943 0.0213301, + -0.056809202 -0.018239601 0.0211583, + -0.056809202 -0.0189602 0.018145099, + -0.0576833 -0.016139099 0.0180819, + -0.0576833 -0.0164335 0.016318999, + -0.058412101 -0.013628 0.016290899, + -0.0580099 -0.0152885 0.0144878, + -0.058998398 -0.0108291 0.0162628, + -0.058829699 -0.0118043 0.0144906, + -0.058412101 -0.013314 0.018018501, + -0.0576833 -0.0153695 0.0209856, + -0.056809202 -0.016864499 0.026726199, + -0.055787299 -0.018552 0.032907002, + -0.0592779 -0.0092436904 0.0144926, + -0.0589833 -0.0109267 0.0144913, + -0.0581805 -0.0146752 0.0144883, + -0.058396801 -0.0137186 0.0144891, + -0.055787299 -0.0217661 0.018208001, + -0.0546159 -0.0239226 0.021500301, + -0.0532961 -0.0256171 0.027971501, + -0.051830001 -0.028446799 0.0283741, + -0.0532961 -0.0267125 0.021668101, + -0.0546159 -0.0245462 0.0182702, + -0.055787299 -0.0220215 0.0163751, + -0.056128498 -0.021171 0.0144831, + -0.0532961 -0.027288301 0.0183316, + -0.051830001 -0.029451801 0.0218329, + -0.050219599 -0.0312117 0.028767399, + -0.051830001 -0.027458001 0.034876399, + -0.0532961 -0.023976499 0.0372287, + -0.051830001 -0.0269386 0.037993401, + -0.050219599 -0.030310201 0.035507198, + -0.048467699 -0.033899501 0.029149801, + -0.050219599 -0.032128301 0.0219939, + -0.051830001 -0.0299807 0.018391799, + -0.0532961 -0.0275055 0.0164301, + -0.050219599 -0.032611299 0.0184507, + -0.048467699 -0.034730099 0.0221505, + -0.0465803 -0.036498699 0.0295195, + -0.048467699 -0.033082802 0.036120299, + -0.050219599 -0.029833 0.038740501, + -0.051830001 -0.026597699 0.039487701, + -0.050611299 -0.0322036 0.0144744, + -0.0502089 -0.032837301 0.0144739, + -0.046574499 -0.0378244 0.0144699, + -0.048467699 -0.030949401 0.046005402, + -0.0465803 -0.033107799 0.048631299, + -0.044564299 -0.035087701 0.051323101, + -0.0424264 -0.0368683 0.0540644, + -0.040174201 -0.038431801 0.056836698, + -0.0378174 -0.039764199 0.059621099, + -0.035366699 -0.040852901 0.062397402, + -0.0328326 -0.041686598 0.065144897, + -0.0302257 -0.042257499 0.0678427, + -0.027557701 -0.042563301 0.070471197, + -0.0248404 -0.042603299 0.073011301, + -0.0220857 -0.042378101 0.075443797, + -0.019305199 -0.041891702 0.077751502, + -0.0165099 -0.041153099 0.079919398, + -0.0137106 -0.0401727 0.081933998, + -0.0109179 -0.0389615 0.083782598, + -0.0081421202 -0.037533201 0.085455403, + -0.0053918599 -0.035903901 0.0869454, + -0.00267513 -0.034090899 0.088246897, + 0 -0.032111 0.0893557, + 0.00267513 -0.034090199 0.088245697, + 0.0053918599 -0.0359024 0.086942799, + 0.0081421202 -0.037530601 0.085451499, + 0.0109179 -0.0389576 0.083777599, + 0.0137106 -0.040167298 0.081928, + 0.0165099 -0.0411461 0.0799127, + 0.019305199 -0.0418831 0.077744097, + 0.0220857 -0.0423677 0.075436197, + 0.0248404 -0.042591199 0.073003702, + 0.027557701 -0.042549599 0.070463903, + 0.0302257 -0.042242199 0.067835897, + 0.0328326 -0.0416697 0.065138698, + 0.035366699 -0.040834598 0.062392, + 0.0378174 -0.039744802 0.059616599, + 0.040174201 -0.038411401 0.056833301, + 0.0424264 -0.0368471 0.054062501, + 0.044564299 -0.0350658 0.0513235, + 0.0465803 -0.033085499 0.048634801, + 0.048467699 -0.030927399 0.046010699, + 0.050219599 -0.0286132 0.043463498, + 0.044564299 -0.040137202 0.016554801, + 0.0424264 -0.042394701 0.016577501, + 0.044472098 -0.0402884 0.0144679, + 0.0424264 -0.042265199 0.0186568, + 0.040174201 -0.044423599 0.0187055, + 0.040174201 -0.044170301 0.022715, + 0.0378174 -0.0462403 0.022839701, + 0.040174201 -0.0436549 0.0305351, + 0.0424264 -0.041387599 0.0302126, + 0.0424264 -0.040807098 0.037828099, + 0.044564299 -0.038343001 0.037283201, + 0.044564299 -0.038179599 0.039128099, + 0.0465803 -0.035581499 0.038503502, + 0.0465803 -0.035363302 0.040151, + 0.048467699 -0.032642201 0.0394479, + 0.048467699 -0.032331899 0.041058801, + 0.050219599 -0.029500101 0.040276099, + 0.050219599 -0.0290945 0.041867401, + 0.051830001 -0.0261652 0.041004099, + 0.040748298 -0.044036102 0.0144649, + 0.051830001 -0.025669999 0.042541299, + 0.050219599 -0.028054999 0.045056399, + 0.048467699 -0.030299 0.047655702, + 0.0465803 -0.032379899 0.0503278, + 0.044564299 -0.034276601 0.053059202, + 0.0424264 -0.035969902 0.055831999, + 0.040174201 -0.0374429 0.058626302, + 0.0378174 -0.038681898 0.0614223, + 0.035366699 -0.039675198 0.064199403, + 0.0328326 -0.0404137 0.066936903, + 0.0302257 -0.040890701 0.069613896, + 0.027557701 -0.041104201 0.072210602, + 0.0248404 -0.041054301 0.074707903, + 0.0220857 -0.040743802 0.0770882, + 0.019305199 -0.0401778 0.079334401, + 0.0165099 -0.039365299 0.081432, + 0.0137106 -0.038317502 0.083367899, + 0.0109179 -0.037046801 0.085131504, + 0.0081421202 -0.035567202 0.086713798, + 0.0053918599 -0.033895198 0.088108003, + 0.00267513 -0.032047801 0.089309402, + 0 -0.0300407 0.090316102, + -0.00267513 -0.0320483 0.089310601, + -0.0053918599 -0.033896498 0.088110603, + -0.0081421202 -0.0355695 0.086717702, + -0.0109179 -0.037050299 0.085136697, + -0.0137106 -0.0383224 0.083374299, + -0.0165099 -0.0393718 0.081439398, + -0.019305199 -0.040185899 0.079342403, + -0.0220857 -0.0407537 0.077096596, + -0.0248404 -0.041065902 0.074716397, + -0.027557701 -0.041117501 0.072218999, + -0.0302257 -0.0409058 0.069621801, + -0.0328326 -0.040430401 0.066944398, + -0.035366699 -0.0396934 0.064206101, + -0.0378174 -0.0387014 0.0614281, + -0.040174201 -0.037463602 0.0586311, + -0.0424264 -0.035991501 0.055835601, + -0.044564299 -0.034298901 0.053061198, + -0.0465803 -0.032402799 0.050327402, + -0.048467699 -0.0303222 0.0476522, + -0.050219599 -0.0280778 0.0450509, + -0.051830001 -0.025691099 0.042537399, + -0.0532961 -0.023184501 0.040124401, + -0.051830001 -0.0251236 0.044069, + -0.050219599 -0.0274415 0.046639699, + -0.048467699 -0.0296109 0.049291998, + -0.0465803 -0.031610101 0.0520114, + -0.044564299 -0.033420499 0.0547809, + -0.0424264 -0.035023902 0.057581302, + -0.040174201 -0.036403298 0.0603926, + -0.0378174 -0.037546001 0.0631947, + -0.035366699 -0.038442601 0.065967098, + -0.0328326 -0.039085001 0.068688899, + -0.0302257 -0.039466999 0.071338698, + -0.027557701 -0.039587598 0.0738969, + -0.0248404 -0.039448999 0.076345801, + -0.0220857 -0.039055198 0.0786677, + -0.019305199 -0.038411401 0.0808459, + -0.0165099 -0.037527598 0.082866304, + -0.0137106 -0.0364164 0.084718198, + -0.0109179 -0.0350908 0.086391598, + -0.0081421202 -0.0335651 0.087877899, + -0.0053918599 -0.031855699 0.089171499, + -0.00267513 -0.029978599 0.090270199, + 0 -0.0279493 0.091173202, + 0.00267513 -0.029978201 0.090269201, + 0.0053918599 -0.0318547 0.089169197, + 0.0081421202 -0.0335632 0.0878741, + 0.0109179 -0.035087701 0.086386301, + 0.0137106 -0.036412001 0.084711596, + 0.0165099 -0.037521701 0.0828586, + 0.019305199 -0.038403701 0.080837302, + 0.0220857 -0.039045699 0.078658499, + 0.0248404 -0.039437901 0.076336302, + 0.027557701 -0.039574601 0.073887497, + 0.0302257 -0.039452299 0.071329497, + 0.0328326 -0.039068598 0.068680197, + 0.035366699 -0.0384246 0.0659592, + 0.0378174 -0.0375266 0.063187599, + 0.040174201 -0.036382601 0.060386501, + 0.0424264 -0.035002101 0.057576202, + 0.044564299 -0.033397801 0.054777101, + 0.0465803 -0.0315868 0.052009501, + 0.048467699 -0.029587099 0.049292602, + 0.050219599 -0.0274175 0.046643302, + 0.051830001 -0.0251 0.044074599, + 0.0532961 -0.0226577 0.041597299, + 0.0532961 -0.022075901 0.043069798, + 0.051830001 -0.0244534 0.0456018, + 0.050219599 -0.026698999 0.048222002, + 0.048467699 -0.028790001 0.050917801, + 0.0465803 -0.030706501 0.053673301, + 0.044564299 -0.032430701 0.056469999, + 0.0424264 -0.033944301 0.0592882, + 0.040174201 -0.035231698 0.062106799, + 0.0378174 -0.036281899 0.0649058, + 0.035366699 -0.037086502 0.067664601, + 0.0328326 -0.037637901 0.0703618, + 0.0302257 -0.037930999 0.072976097, + 0.027557701 -0.037966698 0.075489402, + 0.0248404 -0.037748098 0.077883899, + 0.0220857 -0.037279699 0.0801422, + 0.019305199 -0.036567401 0.082248099, + 0.0165099 -0.0356226 0.084189802, + 0.0137106 -0.034458499 0.0859567, + 0.0109179 -0.033087999 0.087539598, + 0.0081421202 -0.031525798 0.088930503, + 0.0053918599 -0.029787101 0.090126298, + 0.00267513 -0.027887501 0.091125399, + 0 -0.0258427 0.091927499, + -0.00267513 -0.027887801 0.0911263, + -0.0053918599 -0.0297879 0.090128303, + -0.0081421202 -0.0315274 0.088933997, + -0.0109179 -0.033090599 0.087544702, + -0.0137106 -0.034462299 0.085963301, + -0.0165099 -0.035628099 0.084197603, + -0.019305199 -0.036574401 0.082257196, + -0.0220857 -0.037288301 0.080151998, + -0.0248404 -0.0377586 0.077894203, + -0.027557701 -0.037978999 0.0754999, + -0.0302257 -0.0379452 0.072986498, + -0.0328326 -0.0376538 0.070371702, + -0.035366699 -0.0371041 0.067673899, + -0.0378174 -0.036301099 0.064914301, + -0.040174201 -0.035252299 0.062114298, + -0.0424264 -0.033966199 0.059294701, + -0.044564299 -0.0324536 0.056475401, + -0.0465803 -0.0307303 0.053677201, + -0.048467699 -0.0288142 0.050919902, + -0.050219599 -0.0267237 0.048221301, + -0.051830001 -0.0244783 0.045598, + -0.0532961 -0.0221001 0.043063998, + -0.0532961 -0.021445399 0.044532001, + -0.051830001 -0.0237536 0.047120001, + -0.050219599 -0.025923001 0.049791101, + -0.048467699 -0.0279327 0.0525296, + -0.0465803 -0.029764 0.055318099, + -0.044564299 -0.031398699 0.058137801, + -0.0424264 -0.0328198 0.060968701, + -0.040174201 -0.034013402 0.063789703, + -0.0378174 -0.03497 0.0665804, + -0.035366699 -0.0356814 0.069319703, + -0.0328326 -0.036141101 0.0719864, + -0.0302257 -0.036346 0.074560098, + -0.027557701 -0.036297999 0.077022597, + -0.0248404 -0.036001001 0.079356603, + -0.0220857 -0.035459898 0.081544802, + -0.019305199 -0.034682602 0.0835732, + -0.0165099 -0.0336807 0.0854306, + -0.0137106 -0.032467902 0.0871071, + -0.0109179 -0.031057499 0.088593997, + -0.0081421202 -0.029462799 0.089886397, + -0.0053918599 -0.027698999 0.090981998, + -0.00267513 -0.0257817 0.091879897, + 0 -0.02373 0.092579603, + 0.00267513 -0.0257816 0.091879196, + 0.0053918599 -0.027698399 0.090980299, + 0.0081421202 -0.0294616 0.089883298, + 0.0109179 -0.0310554 0.088589303, + 0.0137106 -0.032464601 0.0871007, + 0.0165099 -0.033675998 0.085422702, + 0.019305199 -0.034676298 0.083563998, + 0.0220857 -0.0354519 0.081534497, + 0.0248404 -0.035991199 0.079345502, + 0.027557701 -0.036286298 0.077011198, + 0.0302257 -0.036332499 0.074548602, + 0.0328326 -0.036125701 0.071975201, + 0.035366699 -0.035664201 0.069309004, + 0.0378174 -0.034951098 0.066570401, + 0.040174201 -0.033992998 0.063780703, + 0.0424264 -0.032798 0.060960699, + 0.044564299 -0.031375699 0.058130998, + 0.0465803 -0.029740101 0.055312499, + 0.048467699 -0.027907999 0.052525401, + 0.050219599 -0.0258979 0.0497889, + 0.051830001 -0.023728199 0.047120601, + 0.0532961 -0.0214199 0.044535998, + 0.0532961 -0.015873499 0.052990202, + 0.051830001 -0.0177157 0.055778801, + 0.050219599 -0.0193986 0.0586011, + 0.048467699 -0.020905901 0.061437398, + 0.0465803 -0.022223899 0.064267099, + 0.044564299 -0.023341199 0.067070097, + 0.0424264 -0.0242482 0.069825202, + 0.040174201 -0.024936801 0.072510898, + 0.0378174 -0.025403401 0.075106896, + 0.035366699 -0.025646601 0.0775951, + 0.0328326 -0.025666701 0.079957299, + 0.0302257 -0.025465799 0.082175903, + 0.027557701 -0.025050201 0.084236696, + 0.0248404 -0.024426701 0.0861279, + 0.0220857 -0.023602299 0.087839298, + 0.019305199 -0.0225855 0.089361899, + 0.0165099 -0.021391099 0.090689301, + 0.0137106 -0.020047899 0.091815002, + 0.0109179 -0.0185485 0.0927421, + 0.0081421202 -0.0167896 0.093505703, + 0.0053918599 -0.0125952 0.094445102, + 0.00267513 -0.0082221497 0.095133103, + 0 -0.00369621 0.095555797, + -0.00267513 -0.0082229497 0.095133901, + -0.0053918599 -0.0125978 0.094446696, + -0.0081421202 -0.016792201 0.093507297, + -0.0109179 -0.0185491 0.092743903, + -0.0137106 -0.020047501 0.091817297, + -0.0165099 -0.0213909 0.090692699, + -0.019305199 -0.022586299 0.089366898, + -0.0220857 -0.023604499 0.087846398, + -0.0248404 -0.024430299 0.086137302, + -0.027557701 -0.0250556 0.084248498, + -0.0302257 -0.025473099 0.082189903, + -0.0328326 -0.0256759 0.079973102, + -0.035366699 -0.025658 0.077612102, + -0.0378174 -0.025417 0.075124599, + -0.040174201 -0.024952799 0.072528698, + -0.0424264 -0.0242662 0.0698428, + -0.044564299 -0.0233612 0.067087002, + -0.0465803 -0.0222457 0.064283103, + -0.048467699 -0.0209294 0.061452001, + -0.050219599 -0.0194236 0.058614299, + -0.051830001 -0.017742099 0.055790499, + -0.0532961 -0.015900901 0.053000201, + -0.0546159 -0.0139172 0.0502619, + -0.0546159 -0.0149533 0.048945401, + -0.0532961 -0.0170152 0.051657699, + -0.051830001 -0.0189369 0.05443, + -0.050219599 -0.020700499 0.0572448, + -0.048467699 -0.022289401 0.060082901, + -0.0465803 -0.023689101 0.062923998, + -0.044564299 -0.0248864 0.065747, + -0.0424264 -0.0258704 0.0685312, + -0.040174201 -0.0266327 0.071254998, + -0.0378174 -0.0271689 0.073898301, + -0.035366699 -0.027475899 0.076440804, + -0.0328326 -0.027553501 0.078864299, + -0.0302257 -0.0274032 0.0811508, + -0.027557701 -0.027031099 0.083285399, + -0.0248404 -0.0264448 0.085254498, + -0.0220857 -0.0256512 0.087047003, + -0.019305199 -0.024658499 0.088653803, + -0.0165099 -0.023478299 0.090068698, + -0.0137106 -0.022126799 0.0912866, + -0.0109179 -0.0206329 0.092301503, + -0.0081421202 -0.018990099 0.093117401, + -0.0053918599 -0.017096199 0.093771301, + -0.00267513 -0.0127711 0.094604999, + 0 -0.0082777999 0.095186397, + 0.00267513 -0.0127698 0.094604298, + 0.0053918599 -0.0170945 0.093770199, + 0.0081421202 -0.0189896 0.093116097, + 0.0109179 -0.0206332 0.0922997, + 0.0137106 -0.022127001 0.091283798, + 0.0165099 -0.023477601 0.090064399, + 0.019305199 -0.024656599 0.088647597, + 0.0220857 -0.025647899 0.087038599, + 0.0248404 -0.02644 0.085243799, + 0.027557701 -0.027024601 0.083272599, + 0.0302257 -0.027394701 0.081136301, + 0.0328326 -0.0275429 0.078848504, + 0.035366699 -0.0274632 0.076424301, + 0.0378174 -0.027153799 0.073881499, + 0.040174201 -0.0266157 0.071238399, + 0.0424264 -0.025851401 0.068515003, + 0.044564299 -0.0248654 0.065731697, + 0.0465803 -0.023666499 0.062909797, + 0.048467699 -0.0222652 0.060070001, + 0.050219599 -0.020675 0.057233602, + 0.051830001 -0.018910199 0.0544204, + 0.0532961 -0.0169877 0.0516495, + 0.051830001 -0.0200302 0.053020202, + 0.050219599 -0.0218776 0.055817802, + 0.048467699 -0.023551701 0.0586478, + 0.0465803 -0.0250376 0.061490599, + 0.044564299 -0.026321299 0.064325698, + 0.0424264 -0.027389999 0.0671314, + 0.040174201 -0.0282341 0.069886602, + 0.0378174 -0.0288484 0.072571203, + 0.035366699 -0.029229499 0.075164698, + 0.0328326 -0.029375101 0.077647299, + 0.0302257 -0.0292861 0.080000699, + 0.027557701 -0.0289679 0.082209803, + 0.0248404 -0.0284278 0.084260002, + 0.0220857 -0.0276735 0.086137898, + 0.019305199 -0.0267132 0.087833203, + 0.0165099 -0.025558401 0.0893391, + 0.0137106 -0.0242217 0.090650201, + 0.0109179 -0.022718901 0.091761902, + 0.0081421202 -0.021079199 0.092668898, + 0.0053918599 -0.019297799 0.093377501, + 0.00267513 -0.017273501 0.093925603, + 0 -0.0128274 0.0946564, + -0.00267513 -0.0172744 0.093926199, + -0.0053918599 -0.019298101 0.093378402, + -0.0081421202 -0.0210789 0.092670299, + -0.0109179 -0.0227187 0.091764197, + -0.0137106 -0.024222299 0.090653799, + -0.0165099 -0.0255602 0.089344397, + -0.019305199 -0.026716201 0.087840497, + -0.0220857 -0.027677899 0.086147301, + -0.0248404 -0.028433699 0.084271498, + -0.027557701 -0.028975699 0.082222998, + -0.0302257 -0.0292958 0.080015302, + -0.0328326 -0.0293869 0.077662602, + -0.035366699 -0.029243501 0.075180396, + -0.0378174 -0.0288644 0.072586797, + -0.040174201 -0.028252101 0.069901899, + -0.0424264 -0.027409799 0.067146003, + -0.044564299 -0.0263429 0.064339198, + -0.0465803 -0.0250609 0.061503001, + -0.048467699 -0.023576301 0.0586586, + -0.050219599 -0.021903399 0.0558272, + -0.051830001 -0.020057 0.053027999, + -0.0532961 -0.018054601 0.0502798, + -0.0546159 -0.0159159 0.047599901, + -0.0532961 -0.019018 0.048872501, + -0.051830001 -0.0210997 0.051589999, + -0.050219599 -0.023029 0.054367099, + -0.048467699 -0.024786901 0.0571853, + -0.0465803 -0.026357399 0.0600258, + -0.044564299 -0.027726 0.062868498, + -0.0424264 -0.028879 0.065691799, + -0.040174201 -0.0298051 0.068473898, + -0.0378174 -0.030498 0.0711945, + -0.035366699 -0.030953599 0.0738336, + -0.0328326 -0.0311691 0.0763705, + -0.0302257 -0.0311436 0.078785598, + -0.027557701 -0.0308821 0.081063002, + -0.0248404 -0.030391101 0.083187997, + -0.0220857 -0.0296786 0.085146599, + -0.019305199 -0.0287534 0.086926103, + -0.0165099 -0.027627099 0.088519096, + -0.0137106 -0.0263119 0.089920104, + -0.0109179 -0.0248206 0.0911244, + -0.0081421202 -0.0231697 0.092128001, + -0.0053918599 -0.0213906 0.092928, + -0.00267513 -0.0194789 0.0935314, + 0 -0.0173322 0.093976498, + 0.00267513 -0.019478699 0.093530901, + 0.0053918599 -0.021390701 0.092927098, + 0.0081421202 -0.0231697 0.092126399, + 0.0109179 -0.024820101 0.091121599, + 0.0137106 -0.0263106 0.0899157, + 0.0165099 -0.0276246 0.088512801, + 0.019305199 -0.028749701 0.086917803, + 0.0220857 -0.029673399 0.085136399, + 0.0248404 -0.030384099 0.083176099, + 0.027557701 -0.030873099 0.081049703, + 0.0302257 -0.0311327 0.078771502, + 0.0328326 -0.0311561 0.076355897, + 0.035366699 -0.0309387 0.0738189, + 0.0378174 -0.0304811 0.071180202, + 0.040174201 -0.0297863 0.068460099, + 0.0424264 -0.028858401 0.065678902, + 0.044564299 -0.027703799 0.062856801, + 0.0465803 -0.026333701 0.060015298, + 0.048467699 -0.024762001 0.057176199, + 0.050219599 -0.023003099 0.054359399, + 0.051830001 -0.021073001 0.0515838, + 0.0532961 -0.0189909 0.048868001, + 0.051830001 -0.0220374 0.050117601, + 0.050219599 -0.0240491 0.052864201, + 0.048467699 -0.0258931 0.055661298, + 0.0465803 -0.027551601 0.058490001, + 0.044564299 -0.0290091 0.061330501, + 0.0424264 -0.0302517 0.064162299, + 0.040174201 -0.0312667 0.066963501, + 0.0378174 -0.032046098 0.069713101, + 0.035366699 -0.032584701 0.0723911, + 0.0328326 -0.032878902 0.0749771, + 0.0302257 -0.0329272 0.077450998, + 0.027557701 -0.0327328 0.0797951, + 0.0248404 -0.032301798 0.081994198, + 0.0220857 -0.0316412 0.084034003, + 0.019305199 -0.030759901 0.085901, + 0.0165099 -0.029670199 0.087585099, + 0.0137106 -0.0283846 0.0890797, + 0.0109179 -0.0269155 0.090379603, + 0.0081421202 -0.0252761 0.091480598, + 0.0053918599 -0.0234848 0.092381001, + 0.00267513 -0.021573599 0.0930788, + 0 -0.019537801 0.093581297, + -0.00267513 -0.021573501 0.093079098, + -0.0053918599 -0.0234848 0.092382103, + -0.0081421202 -0.0252764 0.091482803, + -0.0109179 -0.0269165 0.090383098, + -0.0137106 -0.0283866 0.089084901, + -0.0165099 -0.0296735 0.087592199, + -0.019305199 -0.0307645 0.085909903, + -0.0220857 -0.031647399 0.084044598, + -0.0248404 -0.0323098 0.082006097, + -0.027557701 -0.032742798 0.0798079, + -0.0302257 -0.032939099 0.077464402, + -0.0328326 -0.032892801 0.074990697, + -0.035366699 -0.0326006 0.072404601, + -0.0378174 -0.032063801 0.069726102, + -0.040174201 -0.031286199 0.066975698, + -0.0424264 -0.0302728 0.064173497, + -0.044564299 -0.0290318 0.0613406, + -0.0465803 -0.027575601 0.058498699, + -0.048467699 -0.0259181 0.0556687, + -0.050219599 -0.024074901 0.052870099, + -0.051830001 -0.022063799 0.0501219, + -0.0532961 -0.019904699 0.047441602, + -0.0546159 -0.017618001 0.044844899, + -0.0532961 -0.020713899 0.045992799, + -0.051830001 -0.022948699 0.048629899, + -0.050219599 -0.0250398 0.0513428, + -0.048467699 -0.026967101 0.054114599, + -0.0465803 -0.028712001 0.056927498, + -0.044564299 -0.030257201 0.059761699, + -0.0424264 -0.031587601 0.062597103, + -0.040174201 -0.032690302 0.065412298, + -0.0378174 -0.033556301 0.068186402, + -0.035366699 -0.034178399 0.070898302, + -0.0328326 -0.034552202 0.073527701, + -0.0302257 -0.0346753 0.076054297, + -0.027557701 -0.034550499 0.078460202, + -0.0248404 -0.034182299 0.080728099, + -0.0220857 -0.033577099 0.082843199, + -0.019305199 -0.032743301 0.084791698, + -0.0165099 -0.031693399 0.086562797, + -0.0137106 -0.030440601 0.088147499, + -0.0109179 -0.028997401 0.089539804, + -0.0081421202 -0.027377101 0.090735599, + -0.0053918599 -0.025594899 0.091733001, + -0.00267513 -0.0236696 0.092531197, + 0 -0.021633301 0.093128398, + 0.00267513 -0.023669699 0.092530698, + 0.0053918599 -0.0255946 0.0917316, + 0.0081421202 -0.0273763 0.090732999, + 0.0109179 -0.028995899 0.089535698, + 0.0137106 -0.0304379 0.088141702, + 0.0165099 -0.031689402 0.086555101, + 0.019305199 -0.0327379 0.084782399, + 0.0220857 -0.033569999 0.082832597, + 0.0248404 -0.034173299 0.080716498, + 0.027557701 -0.034539599 0.078447901, + 0.0302257 -0.034662601 0.076041803, + 0.0328326 -0.034537401 0.073515199, + 0.035366699 -0.034161899 0.070886202, + 0.0378174 -0.033537898 0.068174899, + 0.040174201 -0.0326703 0.065401599, + 0.0424264 -0.031565901 0.0625875, + 0.044564299 -0.030234201 0.059753299, + 0.0465803 -0.0286879 0.056920301, + 0.048467699 -0.026942199 0.054108899, + 0.050219599 -0.0250143 0.051338501, + 0.051830001 -0.0229227 0.048627701, + 0.0532961 -0.020687699 0.045993399, + -0.059999902 -0.000106517 0.0144999, + -0.059932198 -0.00269957 0.0144979, + -0.0599977 -1.16071e-005 0.0145, + -0.059720598 0.0057720202 0.0145046, + -0.059285302 0.0092258602 0.0095073497, + -0.059433699 0.0081299003 0.0145065, + -0.059365101 0.0086939204 0.0145069, + -0.058985401 0.010904 0.0145087, + -0.057446498 0.017306101 0.0145138, + -0.056143001 0.021157499 0.0095168501, + -0.056795198 0.019289 0.0145154, + -0.056527998 0.0201026 0.014516, + -0.055773601 0.0220688 0.0145176, + -0.054603402 0.024823301 0.0145198, + -0.050626501 0.032194201 0.0095256399, + -0.051520798 0.030739101 0.0145245, + -0.050211199 0.032815699 0.0145261, + -0.048462 0.035351101 0.0145282, + -0.040174201 0.045508999 0.016696099, + -0.041313998 0.044924501 0.0170347, + -0.040174201 0.0459936 0.017002, + -0.041313998 0.045395799 0.017209301, + -0.0424264 0.0442921 0.017253, + -0.0424264 0.044709101 0.0173227, + -0.043510102 0.0435718 0.0173792, + -0.040174201 0.046469402 0.0171666, + -0.0390082 0.047031701 0.0169704, + -0.0378174 0.047544599 0.0166503, + -0.0378174 0.048037998 0.016939601, + -0.0390082 0.047511999 0.0171252, + -0.040174201 0.046895001 0.0172139, + -0.036603201 0.0490118 0.0169097, + -0.035366699 0.049450301 0.016607201, + -0.035366699 0.049952101 0.016881, + -0.036603201 0.049500499 0.017046301, + -0.035366699 0.050444901 0.0170088, + -0.034109399 0.050858099 0.016853301, + -0.0328326 0.051219299 0.0165672, + -0.0059725801 0.171451 0.0618385, + -0.0088933604 0.171451 0.061473701, + -0.0081404103 0.171451 0.061567798, + -0.00923343 0.191451 0.061437801, + -0.0109152 0.171451 0.061119799, + -0.0152803 0.191452 0.060174201, + -0.0146637 0.171452 0.060316999, + -0.0137071 0.171452 0.0605333, + -0.0165057 0.171452 0.059804399, + -0.021165101 0.19145399 0.0582955, + -0.026825599 0.191456 0.055821698, + -0.0248341 0.171455 0.056738202, + -0.030218899 0.17145699 0.053954501, + -0.030913601 0.17145699 0.053559698, + -0.0275511 0.17145599 0.055419698, + -0.022079799 0.171454 0.057908501, + -0.019300099 0.171453 0.0589302, + -0.0165099 0.0592991 0.0165939, + -0.0137106 0.059494101 0.016379301, + -0.0109179 0.059607498 0.016017601, + -0.0081428103 0.0596986 0.0155537, + -0.0060197199 0.0596857 0.0145475, + -0.0081428103 0.059496999 0.0150472, + -0.0109179 0.059250601 0.0155583, + -0.0137106 0.059017301 0.016027, + -0.0165099 0.058757599 0.0163961, + -0.019305199 0.058412399 0.016621299, + -0.019305199 0.0578744 0.0164163, + -0.0165099 0.058283601 0.0160386, + -0.0137106 0.058662701 0.0155642, + -0.0109179 0.059050798 0.0150496, + -0.0089402199 0.059318598 0.0145472, + -0.0107539 0.058999602 0.014547, + -0.0248404 0.056706499 0.0167598, + -0.0167653 0.0575835 0.0145459, + -0.016505601 0.057656001 0.0145459, + -0.013707 0.058384899 0.0145465, + -0.0046305298 0.059813399 0.0095476303, + -0.002688 0.0599197 0.0145477, + 0.00154487 0.059972499 0.0095477598, + -0.0081410101 0.059418999 0.0145473, + -0.0053964402 0.0597331 0.0145476, + -7.3000002e-008 0.059985101 0.0145478, + 0.0053968299 0.059737802 0.0145476, + 0.0137813 0.0583883 0.0095464997, + 0.0137077 0.0583876 0.0145465, + 0.0248351 0.0545923 0.0145435, + 0.025434 0.054328699 0.0145433, + 0.0255125 0.054294098 0.0145432, + 0.0275524 0.053273998 0.0145424, + 0.030220401 0.051809099 0.0145413, + 0.030710001 0.051533502 0.014541, + 0.035363302 0.0484511 0.0145386, + 0.035611998 0.048276901 0.0145384, + 0.047540501 0.038364701 0.0174719, + 0.049361002 0.036607102 0.0178532, + 0.048467699 0.037898 0.0177755, + 0.050219599 0.036868598 0.0184152, + 0.048467699 0.037490301 0.0176738, + 0.047540501 0.038754601 0.017611099, + 0.0465803 0.039601199 0.017423199, + 0.051830001 0.0356679 0.0192485, + 0.0532961 0.034306102 0.020286901, + 0.0546159 0.032788999 0.0215536, + 0.055787299 0.0311461 0.022973699, + 0.056809202 0.029487699 0.024601899, + 0.0576833 0.027869301 0.0264732, + 0.058412101 0.0263367 0.028558699, + 0.058998398 0.0249396 0.030848401, + 0.059445001 0.0237207 0.033310302, + 0.059757002 0.0227185 0.0359012, + 0.0599402 0.0219568 0.038576201, + 0.059999999 0.021427801 0.041300699, + 0.0599402 0.021107901 0.0440467, + 0.059757002 0.020967901 0.0467894, + 0.059445001 0.0209774 0.049507901, + 0.058998398 0.021125199 0.052167799, + 0.058412101 0.021405799 0.0547367, + 0.0576833 0.021794399 0.0571816, + 0.056809202 0.0223688 0.059503399, + 0.055787299 0.0232074 0.061799899, + 0.0546159 0.024219301 0.064067401, + 0.0532961 0.025419701 0.066278197, + 0.051830001 0.026815699 0.068408899, + 0.050219599 0.0284106 0.070436597, + 0.048467699 0.0302056 0.072338201, + 0.0465803 0.032198999 0.074091099, + 0.044564299 0.034387201 0.075673103, + 0.0424264 0.036763199 0.077066302, + 0.040174201 0.039329998 0.078253701, + 0.0378174 0.042075701 0.079216197, + 0.035366699 0.044981498 0.079938002, + 0.0328326 0.048028599 0.080404602, + 0.0302257 0.051197302 0.0806036, + 0.027557701 0.054467801 0.080526799, + 0.0248404 0.057819001 0.080169402, + 0.0220857 0.0654893 0.077943102, + 0.019305199 0.073458001 0.075811103, + 0.0165099 0.081689999 0.073784202, + 0.0137106 0.090151399 0.071872398, + 0.0109179 0.098809697 0.070085302, + 0.0081421202 0.107633 0.068431802, + 0.0053918599 0.116589 0.066920601, + 0.00267513 0.12564699 0.065559797, + 0 0.134776 0.064357199, + -0.00267513 0.125646 0.065558903, + -0.0053918599 0.116587 0.0669185, + -0.0081421202 0.10763 0.068427801, + -0.0109179 0.098805502 0.0700792, + -0.0137106 0.090146199 0.071864501, + -0.0165099 0.081684098 0.073775701, + -0.019305199 0.073452398 0.075803697, + -0.0220857 0.065485701 0.077939101, + -0.0248404 0.057818599 0.080170602, + -0.027557701 0.054467902 0.0805277, + -0.0302257 0.0511971 0.080605797, + -0.0328326 0.048028 0.0804087, + -0.035366699 0.044980399 0.079943798, + -0.0378174 0.042074598 0.079223, + -0.040174201 0.039330199 0.078259498, + -0.0424264 0.036765099 0.077069297, + -0.044564299 0.0343883 0.075676501, + -0.0465803 0.032199901 0.074096799, + -0.048467699 0.030206401 0.072346903, + -0.050219599 0.0284108 0.0704486, + -0.051830001 0.0268136 0.068424098, + -0.0532961 0.025412699 0.066295803, + -0.0546159 0.024203099 0.064085603, + -0.055787299 0.023180701 0.061816402, + -0.056809202 0.022350799 0.059515201, + -0.0576833 0.0217961 0.057191201, + -0.058412101 0.0214034 0.054751899, + -0.058998398 0.0211164 0.052190099, + -0.059445001 0.020963199 0.049535502, + -0.059757002 0.020948701 0.0468181, + -0.0599402 0.021084299 0.044073299, + -0.059999999 0.021400901 0.041323502, + -0.0599402 0.0219278 0.038594499, + -0.059757002 0.0226881 0.0359147, + -0.059445001 0.02369 0.033319399, + -0.058998398 0.024909601 0.030853299, + -0.058412101 0.026308 0.0285581, + -0.0576833 0.027843 0.0264669, + -0.056809202 0.0294693 0.0246062, + -0.055787299 0.031141199 0.022995399, + -0.0546159 0.032789402 0.0215538, + -0.0532961 0.034306601 0.0202867, + -0.051830001 0.035668399 0.019251499, + -0.050219599 0.036868799 0.0184178, + -0.050219599 0.035292398 0.0179363, + -0.049361002 0.0362054 0.017745299, + -0.051830001 0.0341479 0.0186946, + -0.0532961 0.032838698 0.019654199, + -0.0546159 0.031378899 0.020819301, + -0.055787299 0.029775601 0.022220301, + -0.056809202 0.0280542 0.0237928, + -0.0576833 0.0263285 0.025531899, + -0.058412101 0.0246702 0.0275212, + -0.058998398 0.0231256 0.029737899, + -0.059445001 0.0217411 0.032152999, + -0.059757002 0.0205596 0.034729701, + -0.0599402 0.019613201 0.0374263, + -0.059999999 0.0189001 0.040209301, + -0.0599402 0.0184054 0.043047599, + -0.059757002 0.018105701 0.0459144, + -0.059445001 0.0179777 0.048781302, + -0.058998398 0.0180133 0.051610101, + -0.058412101 0.018205401 0.054359902, + -0.0576833 0.018546101 0.057000499, + -0.056809202 0.019004701 0.059501201, + -0.055787299 0.019639 0.061870102, + -0.0546159 0.0205639 0.0642028, + -0.0532961 0.021692401 0.0664896, + -0.051830001 0.0230186 0.068702497, + -0.050219599 0.024545399 0.070818096, + -0.048467699 0.026276199 0.072814099, + -0.0465803 0.028211299 0.074668601, + -0.044564299 0.030348901 0.076359503, + -0.0424264 0.032684602 0.077864997, + -0.040174201 0.035210501 0.079168499, + -0.0378174 0.0379223 0.080256298, + -0.035366699 0.040809501 0.0811055, + -0.0328326 0.0438536 0.081700802, + -0.0302257 0.047034301 0.082030103, + -0.027557701 0.050329302 0.082085602, + -0.0248404 0.053718399 0.081861198, + -0.0220857 0.0571802 0.081353597, + -0.019305199 0.0649748 0.078969002, + -0.0165099 0.073054202 0.076683402, + -0.0137106 0.081383802 0.074508503, + -0.0109179 0.089929797 0.072453603, + -0.0081421202 0.098659597 0.070527799, + -0.0053918599 0.107541 0.068741299, + -0.00267513 0.116543 0.067102402, + 0 0.125634 0.0656192, + 0.00267513 0.116544 0.067103498, + 0.0053918599 0.107543 0.068743996, + 0.0081421202 0.098662697 0.070532396, + 0.0109179 0.089933902 0.072459899, + 0.0137106 0.0813886 0.074515603, + 0.0165099 0.073059 0.076689698, + 0.019305199 0.064978004 0.078972399, + 0.0220857 0.057180598 0.081352502, + 0.0248404 0.053718299 0.081860401, + 0.027557701 0.050329398 0.082083598, + 0.0302257 0.0470348 0.0820264, + 0.0328326 0.043854602 0.081695303, + 0.035366699 0.040810499 0.0810991, + 0.0378174 0.037922099 0.0802508, + 0.040174201 0.035208602 0.079165697, + 0.0424264 0.032683499 0.077861801, + 0.044564299 0.030347999 0.076353997, + 0.0465803 0.0282107 0.074660301, + 0.048467699 0.0262761 0.072802499, + 0.050219599 0.024547501 0.070803396, + 0.051830001 0.0230255 0.068685502, + 0.0532961 0.0217082 0.066471897, + 0.0546159 0.02059 0.0641867, + 0.055787299 0.0196566 0.061858501, + 0.056809202 0.019003 0.059491701, + 0.0576833 0.0185485 0.056985501, + 0.058412101 0.018214099 0.0543379, + 0.058998398 0.018027401 0.051582798, + 0.059445001 0.017996799 0.0487528, + 0.059757002 0.018129401 0.045887999, + 0.0599402 0.018432301 0.043024801, + 0.059999999 0.0189292 0.040190998, + 0.0599402 0.0196437 0.0374128, + 0.059757002 0.0205904 0.034720499, + 0.059445001 0.021771399 0.032147899, + 0.058998398 0.0231546 0.029738501, + 0.058412101 0.024696801 0.027527601, + 0.0576833 0.026347199 0.0255275, + 0.056809202 0.028059101 0.0237708, + 0.055787299 0.0297751 0.022220099, + 0.0546159 0.0313785 0.0208195, + 0.0532961 0.032838199 0.0196511, + 0.049361002 0.0362048 0.0177375, + 0.048467699 0.037105601 0.017521501, + 0.050219599 0.034899201 0.0178023, + 0.050219599 0.034524798 0.0176231, + -0.048467699 0.037102301 0.017537899, + -0.048467699 0.0374908 0.0176815, + -0.044564299 0.041541699 0.017138001, + -0.044564299 0.041998401 0.017343899, + -0.045588002 0.041214202 0.0174964, + -0.044564299 0.042406298 0.017437199, + -0.043510102 0.043159202 0.017297899, + -0.0424264 0.0438256 0.0170682, + -9.4966999e-005 0.171451 0.0621364, + 0.0465803 0.046987198 0.018414, + 0.044564299 0.0478989 0.0178141, + 0.0424264 0.048608098 0.0174076, + 0.040174201 0.0491134 0.0171695, + 0.0378174 0.049410999 0.017083, + 0.036603201 0.049937699 0.017056899, + 0.035366699 0.050447199 0.016996801, + 0.034109399 0.050870299 0.0168407, + 0.0328326 0.051240001 0.0165592, + 0.0057835602 0.171451 0.061857101, + 0.0081407595 0.171451 0.061570302, + 0.00923343 0.191451 0.061437801, + 0.00870548 0.171451 0.0615016, + 0.0165099 0.167217 -0.055416301, + 0.019305199 0.16718 -0.054541301, + 0.0165099 0.16503499 -0.0552544, + 0.0137106 0.16508099 -0.0559843, + 0.0137106 0.16290601 -0.055756599, + 0.0109179 0.162955 -0.056343999, + 0.0109179 0.160787 -0.056049202, + 0.0081428103 0.160833 -0.056496799, + 0.0081428103 0.158672 -0.056134, + 0.0053973799 0.15871 -0.056446999, + 0.0053973799 0.15655699 -0.056014899, + 0.00268824 0.156583 -0.056198701, + 0.00268824 0.15443701 -0.055696301, + 0 0.15444601 -0.0557568, + 0 0.15231 -0.0551835, + -0.00268824 0.15443601 -0.0556974, + -0.00268824 0.156583 -0.056200098, + -0.0053973799 0.156556 -0.056017499, + -0.0053973799 0.15871 -0.056450099, + -0.0081428103 0.15867101 -0.056138702, + -0.0081428103 0.160832 -0.0565021, + -0.0109179 0.160787 -0.056056298, + -0.0109179 0.162955 -0.056351501, + -0.0137106 0.16290601 -0.055766098, + -0.0137106 0.16508199 -0.055993602, + -0.0165099 0.16503599 -0.055265501, + -0.0165099 0.167218 -0.0554257, + -0.019305199 0.167181 -0.054552302, + -0.019305199 0.16937 -0.054645501, + -0.0165099 0.169388 -0.0555191, + -0.018242201 0.171544 -0.055007201, + -0.019300301 0.171544 -0.054657798, + -0.0202034 0.171543 -0.0543596, + -0.0220857 0.169348 -0.053624202, + 0.044033099 0.191531 -0.038603898, + 0.042423699 0.17153201 -0.040286999, + 0.039609101 0.191534 -0.0429154, + 0.040174201 0.16910701 -0.042390101, + 0.0404175 0.171534 -0.0422078, + 0.0424264 0.16906101 -0.040251799, + 0.035366699 0.16919 -0.046294399, + 0.035878699 0.171537 -0.045954101, + 0.0378174 0.169149 -0.0444065, + 0.035366699 0.166831 -0.046194799, + 0.0328326 0.166904 -0.0479475, + 0.0328326 0.16457 -0.047784101, + 0.0302257 0.16467001 -0.049395598, + 0.0302257 0.16236199 -0.049166899, + 0.027557701 0.16248301 -0.050634298, + 0.027557701 0.160199 -0.050339099, + 0.0248404 0.160335 -0.051660299, + 0.0248404 0.158077 -0.051297199, + 0.0220857 0.158222 -0.052470099, + 0.0220857 0.15598699 -0.052037999, + 0.019305199 0.15613399 -0.053061299, + 0.019305199 0.153926 -0.052558899, + 0.0165099 0.15406901 -0.053434402, + 0.0165099 0.151885 -0.052861199, + 0.0137106 0.15201899 -0.0535914, + 0.0137106 0.14986099 -0.0529477, + 0.0109179 0.14998101 -0.053535201, + 0.0109179 0.147848 -0.052821901, + 0.0081428103 0.147947 -0.053269699, + 0.0081428103 0.145842 -0.052487802, + 0.0053973799 0.145918 -0.052800901, + 0.0053973799 0.143839 -0.051951099, + 0.00268824 0.143889 -0.052135199, + 0.00268824 0.141838 -0.051218301, + 0 0.141855 -0.0512789, + 0 0.139833 -0.050295498, + -0.00268824 0.141837 -0.051219601, + -0.00268824 0.143888 -0.052136399, + -0.0053973799 0.143838 -0.051953498, + -0.0053973799 0.145916 -0.052803099, + -0.0081428103 0.14584 -0.052491099, + -0.0081428103 0.147945 -0.053272702, + -0.0109179 0.147844 -0.052825999, + -0.0109179 0.149977 -0.053539101, + -0.0137106 0.149856 -0.052952599, + -0.0137106 0.152016 -0.0535965, + -0.0165099 0.15188099 -0.052867301, + -0.0165099 0.154066 -0.0534412, + -0.019305199 0.15392201 -0.0525668, + -0.019305199 0.156131 -0.053070702, + -0.0220857 0.155984 -0.052048702, + -0.0220857 0.15821999 -0.052482799, + -0.0248404 0.158075 -0.0513115, + -0.0248404 0.160335 -0.051676501, + -0.027557701 0.160199 -0.050356999, + -0.027557701 0.16248301 -0.050653402, + -0.0302257 0.16236199 -0.049187899, + -0.0302257 0.164672 -0.049415998, + -0.0328326 0.164572 -0.0478063, + -0.0328326 0.166906 -0.047966201, + -0.035366699 0.166833 -0.046214901, + -0.035366699 0.169192 -0.046306901, + -0.0378174 0.16915201 -0.0444199, + -0.035726301 0.171537 -0.046067402, + -0.037813999 0.171535 -0.044439301, + -0.034765299 0.19153699 -0.046749201, + -0.033319298 0.171538 -0.0477616, + -0.0328326 0.169229 -0.048058402, + -0.034755301 0.171537 -0.046750899, + -0.0353618 0.171537 -0.046324, + -0.0302257 0.16697399 -0.049575999, + -0.027557701 0.164764 -0.050881401, + -0.0248404 0.16259199 -0.051972602, + -0.0220857 0.160455 -0.052847501, + -0.019305199 0.158346 -0.053504501, + -0.0165099 0.156257 -0.0539448, + -0.0137106 0.154185 -0.054170199, + -0.0109179 0.152124 -0.054182801, + -0.0081428103 0.150069 -0.0539857, + -0.0053973799 0.14801601 -0.053584799, + -0.00268824 0.145962 -0.052986, + 0 0.143904 -0.052195702, + 0.00268824 0.145963 -0.052985001, + 0.0053973799 0.148018 -0.053582799, + 0.0081428103 0.150071 -0.053982802, + 0.0109179 0.152126 -0.0541788, + 0.0137106 0.15418801 -0.0541646, + 0.0165099 0.15626 -0.053936802, + 0.019305199 0.15834799 -0.053493399, + 0.0220857 0.160456 -0.052833099, + 0.0248404 0.16259199 -0.051955398, + 0.027557701 0.16476201 -0.0508628, + 0.0302257 0.166972 -0.0495588, + 0.0328326 0.169227 -0.048046801, + 0.034754898 0.171537 -0.0467504, + 0.033477101 0.171538 -0.047655798, + 0.032825101 0.171538 -0.048071299, + 0.034765299 0.19153699 -0.046749201, + 0.029552899 0.19154 -0.050064601, + 0.0302184 0.17154001 -0.049680602, + 0.030994801 0.17153899 -0.049237698, + 0.035360001 0.171537 -0.046321601, + 0.037811901 0.171535 -0.0444366, + 0.038194101 0.171535 -0.044136599, + 0.0395981 0.171534 -0.0429186, + 0.0378174 0.166751 -0.044306599, + 0.035366699 0.164461 -0.046031099, + 0.0328326 0.162229 -0.047555201, + 0.0302257 0.16004901 -0.048871599, + 0.027557701 0.157915 -0.049975902, + 0.0248404 0.15582 -0.050864998, + 0.0220857 0.153758 -0.051535599, + 0.019305199 0.151724 -0.051985499, + 0.0165099 0.149712 -0.052217301, + 0.0137106 0.147717 -0.052234299, + 0.0109179 0.145733 -0.052039899, + 0.0081428103 0.143757 -0.051637799, + 0.0053973799 0.14178599 -0.051034, + 0.00268824 0.139815 -0.050234899, + 0 0.137843 -0.049246501, + -0.00268824 0.139814 -0.0502363, + -0.0053973799 0.141784 -0.051036701, + -0.0081428103 0.14375401 -0.051641401, + -0.0109179 0.14572901 -0.052044298, + -0.0137106 0.14771201 -0.052239399, + -0.0165099 0.149707 -0.052223202, + -0.019305199 0.151719 -0.0519927, + -0.0220857 0.153754 -0.051544599, + -0.0248404 0.155817 -0.050877001, + -0.027557701 0.157912 -0.049991801, + -0.0302257 0.16004799 -0.048891298, + -0.0328326 0.16223 -0.047577899, + -0.035366699 0.164463 -0.0460549, + -0.0378174 0.16675401 -0.044328101, + -0.040174201 0.169109 -0.042404301, + -0.039599199 0.171534 -0.042919699, + -0.040172402 0.171534 -0.042425599, + -0.0402769 0.171534 -0.042335499, + -0.0424264 0.169063 -0.040266801, + -0.040174201 0.16666999 -0.0423126, + -0.0378174 0.164345 -0.044167999, + -0.035366699 0.162085 -0.045826498, + -0.0328326 0.15988199 -0.047281001, + -0.0302257 0.157731 -0.048525602, + -0.027557701 0.155627 -0.049557, + -0.0248404 0.153561 -0.050372601, + -0.0220857 0.151531 -0.0509702, + -0.019305199 0.149528 -0.051348399, + -0.0165099 0.147548 -0.051509898, + -0.0137106 0.145585 -0.051457599, + -0.0109179 0.143635 -0.0511945, + -0.0081428103 0.14169399 -0.0507246, + -0.0053973799 0.13975801 -0.050053399, + -0.00268824 0.137823 -0.049187299, + 0 0.135888 -0.0481328, + 0.00268824 0.137824 -0.049185801, + 0.0053973799 0.13976 -0.050050501, + 0.0081428103 0.141697 -0.050720599, + 0.0109179 0.143639 -0.051189698, + 0.0137106 0.14559001 -0.051452, + 0.0165099 0.147553 -0.051503699, + 0.019305199 0.149534 -0.0513415, + 0.0220857 0.151537 -0.050961901, + 0.0248404 0.153567 -0.050362401, + 0.027557701 0.15563001 -0.049543601, + 0.0302257 0.15773401 -0.048508201, + 0.0328326 0.15988301 -0.047259599, + 0.035366699 0.162084 -0.0458019, + 0.0378174 0.164343 -0.0441425, + 0.040174201 0.166667 -0.042289801, + 0.042543601 0.17153201 -0.040172201, + 0.044022799 0.17153101 -0.03861, + 0.044564299 0.169012 -0.037999101, + 0.0424264 0.166577 -0.040151201, + 0.040174201 0.16421799 -0.0421254, + 0.0378174 0.161928 -0.0439132, + 0.035366699 0.159702 -0.045506101, + 0.0328326 0.157535 -0.0468961, + 0.0302257 0.15542001 -0.048075799, + 0.027557701 0.15335099 -0.049040899, + 0.0248404 0.15132099 -0.049788699, + 0.0220857 0.149325 -0.050317802, + 0.019305199 0.147356 -0.050627802, + 0.0165099 0.145411 -0.050721299, + 0.0137106 0.143483 -0.050601698, + 0.0109179 0.141569 -0.050272301, + 0.0081428103 0.13966499 -0.049736898, + 0.0053973799 0.13776501 -0.049001299, + 0.00268824 0.135867 -0.048071999, + -0.00268824 0.135866 -0.048073601, + -0.0053973799 0.13776299 -0.049004398, + -0.0081428103 0.139662 -0.049741302, + -0.0109179 0.141565 -0.050277699, + -0.0137106 0.14347801 -0.050607901, + -0.0165099 0.14540499 -0.050728001, + -0.019305199 0.14735 -0.050634999, + -0.0220857 0.14931799 -0.050325699, + -0.0248404 0.151315 -0.0497979, + -0.027557701 0.153345 -0.049052201, + -0.0302257 0.155415 -0.048090398, + -0.0328326 0.15753201 -0.046914998, + -0.035366699 0.159701 -0.045529202, + -0.0378174 0.161929 -0.0439394, + -0.040174201 0.16422001 -0.042152401, + -0.0424264 0.166581 -0.0401753, + -0.044564299 0.16901501 -0.038014799, + -0.044024602 0.17153101 -0.038611699, + -0.044440001 0.17152999 -0.038175698, + -0.044033099 0.191531 -0.038603898, + -0.044561401 0.17152999 -0.038035098, + -0.0463636 0.171529 -0.0359478, + -0.0465803 0.168965 -0.035658501, + -0.044564299 0.166486 -0.037923399, + -0.0424264 0.164087 -0.040015001, + -0.040174201 0.161762 -0.041923601, + -0.0378174 0.15950701 -0.043641798, + -0.035366699 0.157316 -0.0451627, + -0.0328326 0.155184 -0.0464794, + -0.0302257 0.15310401 -0.047585301, + -0.027557701 0.151072 -0.048477098, + -0.0248404 0.149078 -0.049153201, + -0.0220857 0.147121 -0.049612101, + -0.019305199 0.145191 -0.0498529, + -0.0165099 0.14328501 -0.049878102, + -0.0137106 0.141397 -0.049690802, + -0.0109179 0.139523 -0.0492943, + -0.0081428103 0.13766 -0.0486922, + -0.0053973799 0.135802 -0.0478907, + -0.00268824 0.133947 -0.0468974, + 0 0.13396899 -0.046956498, + 0 0.132091 -0.0457201, + 0.00268824 0.133948 -0.046895798, + 0.0053973799 0.135804 -0.047887601, + 0.0081428103 0.13766301 -0.0486876, + 0.0109179 0.13952699 -0.0492885, + 0.0137106 0.141403 -0.0496841, + 0.0165099 0.143291 -0.0498708, + 0.019305199 0.145198 -0.049845099, + 0.0220857 0.147128 -0.049603902, + 0.0248404 0.149086 -0.049144302, + 0.027557701 0.151079 -0.048466899, + 0.0302257 0.153111 -0.0475729, + 0.0328326 0.15518899 -0.0464634, + 0.035366699 0.15731899 -0.045142401, + 0.0378174 0.159508 -0.0436172, + 0.040174201 0.161761 -0.041895799, + 0.0424264 0.164084 -0.039986499, + 0.044564299 0.166483 -0.037898101, + 0.0465803 0.168962 -0.035642099, + 0.046578299 0.171528 -0.035679199, + 0.047982302 0.171527 -0.03387, + 0.0464839 0.171529 -0.0358008, + 0.044567399 0.17152999 -0.038034901, + 0.040169802 0.171534 -0.042422701, + 0.027550699 0.17154101 -0.051145799, + 0.0240272 0.191542 -0.052826501, + 0.028437899 0.17154001 -0.050696, + 0.027557701 0.169294 -0.0511242, + 0.0258127 0.17154101 -0.052027099, + 0.0248338 0.171542 -0.0524645, + 0.0240207 0.171542 -0.052827802, + 0.0248404 0.169322 -0.052444499, + 0.0231252 0.171542 -0.053227901, + 0.0248404 0.167089 -0.0523463, + 0.0220857 0.167138 -0.053518601, + 0.0220857 0.16491801 -0.0533562, + 0.019305199 0.16497999 -0.054379102, + 0.019305199 0.162773 -0.0541512, + 0.0165099 0.162846 -0.055026501, + 0.0165099 0.160652 -0.054731701, + 0.0137106 0.160726 -0.055461802, + 0.0137106 0.158545 -0.055098999, + 0.0109179 0.15861601 -0.055686299, + 0.0109179 0.15644801 -0.055254199, + 0.0081428103 0.15651201 -0.0557019, + 0.0081428103 0.154357 -0.0551995, + 0.0053973799 0.15440699 -0.055512499, + 0.0053973799 0.152266 -0.0549394, + 0.00268824 0.152299 -0.055123098, + 0.00268824 0.150171 -0.0544797, + 0 0.15018301 -0.054540101, + 0 0.148072 -0.0538271, + -0.00268824 0.15017 -0.054480601, + -0.00268824 0.152298 -0.0551241, + -0.0053973799 0.152265 -0.054941401, + -0.0053973799 0.154406 -0.055514701, + -0.0081428103 0.154355 -0.055202901, + -0.0081428103 0.15651099 -0.055705801, + -0.0109179 0.15644699 -0.0552595, + -0.0109179 0.15861601 -0.055692598, + -0.0137106 0.158544 -0.0551068, + -0.0137106 0.160726 -0.055470701, + -0.0165099 0.160651 -0.0547425, + -0.0165099 0.162846 -0.055037901, + -0.019305199 0.162774 -0.0541646, + -0.019305199 0.16498201 -0.0543922, + -0.0220857 0.164919 -0.053371102, + -0.0220857 0.16713899 -0.053531099, + -0.0248404 0.16709 -0.052360501, + -0.0248404 0.169323 -0.052453201, + -0.027557701 0.169295 -0.051133901, + -0.0256411 0.171542 -0.0521085, + -0.027551601 0.17154101 -0.051147401, + -0.0240272 0.191542 -0.052826501, + -0.024020201 0.171542 -0.052826598, + -0.0229499 0.171542 -0.053300802, + -0.024834501 0.171542 -0.052465901, + 0.0220857 0.169347 -0.053616401, + 0.022079499 0.171543 -0.0536348, + 0.020382199 0.171543 -0.054295398, + 0.019305199 0.169369 -0.054638799, + 0.0165099 0.169387 -0.0555133, + 0.018242801 0.171544 -0.055009302, + 0.0137106 0.167248 -0.056145899, + 0.0109179 0.165117 -0.056571499, + 0.0081428103 0.162991 -0.0567916, + 0.0053973799 0.160864 -0.056809999, + 0.00268824 0.158733 -0.056630999, + 0 0.156591 -0.056259301, + -0.00268824 0.158732 -0.056632601, + -0.0053973799 0.160864 -0.056813501, + -0.0081428103 0.162991 -0.056797199, + -0.0109179 0.16511799 -0.056578901, + -0.0137106 0.16724899 -0.0561537, + -0.0109179 0.167273 -0.0567392, + -0.0081428103 0.16514499 -0.057024602, + -0.0053973799 0.163018 -0.057108499, + -0.00268824 0.16088299 -0.056995802, + 0 0.15874 -0.056691598, + 0.00268824 0.16088299 -0.056994099, + 0.0053973799 0.163018 -0.057104699, + 0.0081428103 0.16514499 -0.0570191, + 0.0109179 0.167272 -0.056733001, + 0.0137106 0.169403 -0.056242701, + 0.0147556 0.171545 -0.056020699, + 0.0165055 0.171544 -0.055530701, + 0.0182469 0.191544 -0.055005599, + 0.0175901 0.171544 -0.055227101, + 0.0192999 0.171544 -0.054656502, + 0.0116065 0.171451 0.061003201, + 0.0152803 0.191452 0.060174201, + 0.0137075 0.171452 0.060535099, + 0.0144795 0.171452 0.0603632, + 0.051830001 0.16606601 -0.027946999, + 0.051830001 0.160576 -0.0275492, + 0.050219599 0.163486 -0.030388501, + 0.0532961 0.16595399 -0.025278401, + 0.0529892 0.17152099 -0.0260085, + 0.051820699 0.17152201 -0.028083799, + 0.051545098 0.171523 -0.028573399, + 0.051438902 0.191523 -0.028735099, + 0.053285599 0.17151999 -0.025415801, + 0.054305699 0.171519 -0.0233759, + 0.054342099 0.19151901 -0.023282399, + 0.017317699 0.171453 0.059583001, + 0.021165101 0.19145399 0.0582955, + 0.019300601 0.171453 0.058931701, + 0.0201142 0.171453 0.058664501, + 0.022080399 0.171454 0.0579101, + 0.024834899 0.171455 0.0567399, + 0.037236601 0.191461 0.0491997, + 0.035650201 0.17146 0.050396901, + 0.040173799 0.171463 0.046700399, + 0.037974101 0.171461 0.048590399, + 0.040174201 0.162937 0.046844199, + 0.0424264 0.15457 0.045119401, + 0.044564299 0.14638799 0.043554101, + 0.0465803 0.13841701 0.042163201, + 0.048467699 0.13067999 0.040961999, + 0.050219599 0.123204 0.039958399, + 0.051830001 0.116013 0.039158799, + 0.0532961 0.109131 0.038569301, + 0.0546159 0.102584 0.038195401, + 0.055787299 0.096388303 0.038038701, + 0.056809202 0.090565696 0.0380987, + 0.0576833 0.085133597 0.038373001, + 0.058412101 0.080109604 0.038858201, + 0.058998398 0.078533001 0.037706099, + 0.058998398 0.0816314 0.0360379, + 0.058412101 0.086533502 0.035552599, + 0.0576833 0.091840498 0.035287499, + 0.056809202 0.097536102 0.035246201, + 0.055787299 0.103603 0.0354314, + 0.0546159 0.110023 0.035844799, + 0.0532961 0.116778 0.036485199, + 0.051830001 0.123844 0.037347302, + 0.050219599 0.131199 0.0384247, + 0.048467699 0.13881899 0.039710499, + 0.0465803 0.146679 0.041196499, + 0.044564299 0.15475599 0.042867299, + 0.0424264 0.16302501 0.044706799, + 0.041868102 0.171464 0.045096599, + 0.042342398 0.171464 0.044646699, + 0.042424399 0.17146499 0.044560999, + 0.044376299 0.17146599 0.042518999, + -0.0165099 0.064790003 0.0151069, + -0.019305199 0.065821499 0.0145537, + -0.0220857 0.0666482 0.0140665, + -0.0248404 0.067259997 0.0136624, + -0.027557701 0.067665704 0.0133491, + -0.0302257 0.067879498 0.0131661, + -0.0328326 0.067914598 0.0131341, + -0.035366699 0.067787901 0.0132665, + -0.0378174 0.067523301 0.013573, + -0.040174201 0.067147598 0.0140584, + -0.0424264 0.066687599 0.0147213, + -0.044564299 0.066169903 0.015554, + -0.0465803 0.065621197 0.0165419, + -0.048467699 0.065065399 0.017664799, + -0.050219599 0.064521298 0.0188995, + -0.051830001 0.064003602 0.02022, + -0.0532961 0.063525602 0.021601399, + -0.0546159 0.063087799 0.0230172, + -0.055787299 0.062721997 0.0244583, + -0.056809202 0.062504798 0.0259562, + -0.0576833 0.062412001 0.0274985, + -0.058412101 0.062444702 0.029065199, + -0.058998398 0.062612101 0.030638101, + -0.059445001 0.0629244 0.0321986, + -0.059757002 0.063390397 0.033726301, + -0.0599402 0.064013101 0.035204802, + -0.059999999 0.064777702 0.036637802, + -0.0599402 0.065662801 0.0380482, + -0.059757002 0.066682003 0.039465901, + -0.059445001 0.067840099 0.0408834, + -0.058998398 0.069132499 0.042283501, + -0.058412101 0.070556097 0.043646201, + -0.0576833 0.072104096 0.044952501, + -0.056809202 0.073770098 0.046182901, + -0.055787299 0.075544797 0.0473192, + -0.0546159 0.080958501 0.0467561, + -0.0532961 0.086786598 0.046377402, + -0.051830001 0.0930098 0.046187099, + -0.050219599 0.099605598 0.046185199, + -0.048467699 0.10655 0.0463714, + -0.0465803 0.11382 0.046743099, + -0.044564299 0.121386 0.0472937, + -0.0424264 0.129223 0.0480147, + -0.040174201 0.137302 0.0488986, + -0.0378174 0.145595 0.049940299, + -0.035366699 0.154072 0.051135398, + -0.0328326 0.16270199 0.052479099, + -0.0321921 0.17145801 0.052747801, + -0.0532961 0.065801203 0.0207715, + -0.051830001 0.066248901 0.0194581, + -0.050219599 0.066721 0.0181941, + -0.048467699 0.067215301 0.017004499, + -0.0465803 0.067717798 0.015911801, + -0.044564299 0.068212703 0.0149398, + -0.0424264 0.0686801 0.0141091, + -0.040174201 0.069095999 0.0134368, + -0.0378174 0.069436401 0.0129332, + -0.035366699 0.069675997 0.0126033, + -0.0328326 0.069788702 0.0124459, + -0.0302257 0.0697501 0.0124537, + -0.027557701 0.0695417 0.0126141, + -0.0248404 0.069149002 0.012912, + -0.0220857 0.068560801 0.0133259, + -0.019305199 0.067766197 0.0138193, + -0.0165099 0.066763297 0.0143824, + -0.0137106 0.065563098 0.0149968, + -0.055787299 0.072329298 0.020380899, + -0.056809202 0.072326504 0.021778001, + -0.0576833 0.072436497 0.023197601, + -0.058412101 0.072669901 0.0246213, + -0.058998398 0.073036402 0.0260284, + -0.059445001 0.076137699 0.0260543, + -0.059757002 0.079626702 0.0259194, + -0.0599402 0.083468102 0.025572799, + -0.059999999 0.087579802 0.0250149, + -0.0599402 0.092035703 0.024436601, + -0.059757002 0.096891001 0.0240885, + -0.059445001 0.102122 0.0240041, + -0.058998398 0.107714 0.024191599, + -0.058412101 0.113652 0.0246522, + -0.0576833 0.119922 0.025385801, + -0.056809202 0.126505 0.026386, + -0.055787299 0.13338199 0.027644601, + -0.0546159 0.140534 0.029153001, + -0.0532961 0.14793999 0.030902, + -0.051830001 0.15558 0.032882702, + -0.050219599 0.163431 0.035085998, + -0.0499245 0.171472 0.035416499, + -0.0053973799 0.070991397 0.013106, + -0.00268824 0.067183599 0.0147659, + 0 0.063188002 0.016255399, + 0.00268824 0.067183599 0.0147658, + 0.0053973799 0.070991397 0.013106, + 0.0081428103 0.0745802 0.0113116, + 0.054601401 0.171479 0.0269705, + 0.055579402 0.19148 0.024756201, + 0.054184102 0.171478 0.0279065, + 0.055569701 0.17148 0.024736499, + 0.055771701 0.171481 0.024216199, + 0.056448001 0.171482 0.0224742, + 0.056793399 0.171483 0.0214366, + 0.055787299 0.163877 0.024368601, + 0.0109179 0.0779282 0.0094255498, + 0.0109179 0.076013103 0.0104685, + 0.0137106 0.077260897 0.0096732201, + 0.0137106 0.079154298 0.0086070402, + 0.0165099 0.078322798 0.0089482795, + 0.0165099 0.080197297 0.0078654001, + 0.019305199 0.079201303 0.0083141997, + 0.019305199 0.081060797 0.00721935, + 0.0220857 0.079901598 0.0077892202, + 0.0220857 0.081751198 0.0066857398, + 0.0248404 0.080432497 0.0073889899, + 0.0248404 0.0822777 0.00627833, + 0.027557701 0.080807701 0.0071242698, + 0.027557701 0.082653902 0.0060058702, + 0.0302257 0.081042603 0.0070016501, + 0.0302257 0.082894497 0.0058729402, + 0.0328326 0.081152201 0.0070239198, + 0.0328326 0.083013602 0.0058814501, + 0.035366699 0.081151702 0.0071906201, + 0.035366699 0.083024897 0.00602934, + 0.0378174 0.081057802 0.0074954, + 0.0378174 0.082943901 0.0063090501, + 0.040174201 0.080886103 0.0079281796, + 0.040174201 0.082782298 0.00670871, + 0.0424264 0.080647498 0.0084753502, + 0.0424264 0.082577102 0.0072201299, + 0.044564299 0.080380701 0.0091274902, + 0.044564299 0.0823562 0.0078607798, + 0.0465803 0.080117598 0.0099023096, + 0.0465803 0.0821165 0.0086278301, + 0.048467699 0.079852201 0.010796, + 0.048467699 0.081885099 0.0095098801, + 0.050219599 0.079611197 0.0117959, + 0.050219599 0.081682198 0.0104951, + 0.051830001 0.079414003 0.0128891, + 0.051830001 0.081524603 0.0115705, + 0.0532961 0.079277299 0.014061, + 0.0532961 0.081428997 0.0127205, + 0.0546159 0.079216897 0.0152949, + 0.0546159 0.081410103 0.0139277, + 0.055787299 0.079246603 0.016572701, + 0.055787299 0.081482701 0.0151716, + 0.056809202 0.079379499 0.0178735, + 0.056809202 0.083932601 0.0149894, + 0.0576833 0.081980497 0.0177582, + 0.0576833 0.086776301 0.0147637, + 0.058412101 0.084975697 0.0175715, + 0.058412101 0.089992799 0.014442, + 0.058998398 0.088339798 0.017261, + 0.058998398 0.0935302 0.013986, + 0.059445001 0.092018001 0.016788499, + 0.059445001 0.097461797 0.0135347, + 0.059757002 0.096088797 0.0163009, + 0.059757002 0.10183 0.0132546, + 0.0599402 0.100595 0.0159794, + 0.0599402 0.106614 0.0131558, + 0.059999999 0.105504 0.015856, + 0.059999999 0.111776 0.0132699, + 0.0599402 0.110782 0.015967499, + 0.0599402 0.117291 0.0136327, + 0.059757002 0.116402 0.016349301, + 0.059757002 0.123129 0.0142776, + 0.059445001 0.122341 0.017029, + 0.059445001 0.129265 0.0152276, + 0.058998398 0.128584 0.0180075, + 0.058998398 0.135684 0.0164824, + 0.058412101 0.135113 0.0192788, + 0.058412101 0.14237 0.018035799, + 0.0576833 0.141911 0.0208377, + 0.0576833 0.149307 0.019879701, + 0.056809202 0.148963 0.022676401, + 0.056809202 0.156482 0.0219969, + 0.055787299 0.156251 0.0247778, + 0.0546159 0.163761 0.0271232, + 0.055382699 0.17148 0.025218099, + 0.0532961 0.16364799 0.029840199, + 0.0546159 0.15602399 0.027532799, + 0.055787299 0.14861999 0.025458099, + 0.056809202 0.141453 0.0236354, + 0.0576833 0.13453899 0.022081699, + 0.058412101 0.12789799 0.0208048, + 0.058998398 0.121546 0.019810099, + 0.059445001 0.115502 0.0191023, + 0.059757002 0.109779 0.018686101, + 0.0599402 0.104394 0.018556099, + 0.059999999 0.099369697 0.018683, + 0.0599402 0.094734102 0.0190304, + 0.059757002 0.090521902 0.019561101, + 0.059445001 0.086697102 0.020062299, + 0.058998398 0.083179399 0.0203724, + 0.058412101 0.080025598 0.020530799, + 0.0576833 0.077265002 0.0205897, + 0.056809202 0.077062801 0.0192424, + 0.055787299 0.076974504 0.017904701, + 0.0546159 0.0769886 0.0165975, + 0.0532961 0.077092499 0.0153393, + 0.051830001 0.077272102 0.0141475, + 0.050219599 0.077510796 0.0130379, + 0.048467699 0.077789702 0.0120252, + 0.0465803 0.078082398 0.0111234, + 0.044564299 0.078398399 0.0103365, + 0.0424264 0.078704 0.0096451901, + 0.040174201 0.0789565 0.0090614296, + 0.0378174 0.0791457 0.0086010899, + 0.035366699 0.079256698 0.0082761096, + 0.0328326 0.079272598 0.0080955401, + 0.0302257 0.079174697 0.0080640595, + 0.027557701 0.078946702 0.0081813503, + 0.0248404 0.078572698 0.0084425304, + 0.0220857 0.0780368 0.0088389004, + 0.019305199 0.077325597 0.0093575399, + 0.0165099 0.076431103 0.0099811703, + 0.0137106 0.075349301 0.0106895, + -0.0137106 0.079147398 0.0086081997, + -0.0137106 0.081020601 0.0074932901, + -0.0165099 0.080188699 0.0078679202, + -0.0165099 0.082043797 0.0067356699, + -0.019305199 0.081050999 0.00722371, + -0.019305199 0.082892098 0.0060782102, + -0.0220857 0.081740499 0.0066924598, + -0.0220857 0.083572499 0.0055359299, + -0.0248404 0.082266599 0.0062877801, + -0.0248404 0.084094703 0.0051205498, + -0.027557701 0.082643099 0.0060180901, + -0.027557701 0.084471799 0.0048384001, + -0.0302257 0.082884803 0.0058874399, + -0.0302257 0.084717996 0.0046920902, + -0.0328326 0.083005801 0.00589666, + -0.0328326 0.084845997 0.0046809702, + -0.035366699 0.083019704 0.00604269, + -0.035366699 0.084868804 0.0048024501, + -0.0378174 0.0829423 0.0063188798, + -0.0378174 0.084796697 0.0050490401, + -0.040174201 0.082783498 0.0067153899, + -0.040174201 0.084649198 0.00541797, + -0.0424264 0.082563698 0.0072289198, + -0.0424264 0.084475197 0.0059222602, + -0.044564299 0.082334898 0.0078738704, + -0.044564299 0.084280699 0.0065577002, + -0.0465803 0.082102701 0.0086433096, + -0.0465803 0.084077999 0.00731452, + -0.048467699 0.081878699 0.0095258001, + -0.048467699 0.083885103 0.0081822202, + -0.050219599 0.081680201 0.0105099, + -0.050219599 0.083720498 0.0091492003, + -0.051830001 0.081524797 0.011583, + -0.051830001 0.083601698 0.0102022, + -0.0532961 0.081429899 0.0127301, + -0.0532961 0.083545402 0.0113252, + -0.0546159 0.081411198 0.0139344, + -0.0546159 0.083567902 0.0124989, + -0.056809202 0.16399799 0.021555999, + -0.055787299 0.163881 0.024336901, + -0.056512099 0.171482 0.022295401, + -0.056809202 0.15648299 0.0219575, + -0.0576833 0.15671401 0.0191612, + -0.0576833 0.14930201 0.0198466, + -0.058412101 0.149647 0.017045399, + -0.058412101 0.14235801 0.0180119, + -0.058998398 0.14281601 0.0152163, + -0.058998398 0.135666 0.0164613, + -0.059445001 0.136234 0.0136825, + -0.059445001 0.129244 0.0152037, + -0.059757002 0.12991799 0.0124535, + -0.059757002 0.123106 0.0142482, + -0.0599402 0.123882 0.011533, + -0.0599402 0.117268 0.0135989, + -0.059999999 0.118149 0.0109032, + -0.059999999 0.111754 0.0132354, + -0.0599402 0.112749 0.0105378, + -0.0599402 0.106593 0.0131249, + -0.059757002 0.10771 0.0104038, + -0.059757002 0.101813 0.0132316, + -0.059445001 0.103066 0.0104705, + -0.059445001 0.097452 0.013524, + -0.058998398 0.0988397 0.0107281, + -0.058998398 0.093529202 0.013989, + -0.058412101 0.095050998 0.0111686, + -0.058412101 0.089992501 0.0144462, + -0.0576833 0.091649599 0.0116203, + -0.0576833 0.086774498 0.0147733, + -0.056809202 0.088572502 0.0119696, + -0.056809202 0.083932899 0.0149976, + -0.055787299 0.085874602 0.0122436, + -0.055787299 0.081484102 0.0151759, + -0.0546159 0.079217799 0.0153047, + -0.0532961 0.079277501 0.0140737, + -0.051830001 0.079411797 0.0129043, + -0.050219599 0.079604603 0.0118124, + -0.048467699 0.079837903 0.0108121, + -0.0465803 0.080095299 0.0099160001, + -0.044564299 0.0803665 0.0091367196, + -0.0424264 0.080648802 0.0084824003, + -0.040174201 0.080884397 0.0079386299, + -0.0378174 0.081052102 0.0075096702, + -0.035366699 0.081143297 0.0072070002, + -0.0328326 0.081141599 0.0070396699, + -0.0302257 0.081030697 0.0070150602, + -0.027557701 0.0807954 0.00713475, + -0.0248404 0.080420397 0.0073965602, + -0.0220857 0.0798904 0.0077942, + -0.019305199 0.079191297 0.0083171399, + -0.0165099 0.078314401 0.00894967, + -0.0137106 0.077254198 0.0096730804, + -0.0555728 0.17148 0.024737701, + -0.055773102 0.171481 0.024216801, + -0.0567948 0.171483 0.021437099, + -0.057432801 0.17148501 0.0194996, + -0.057608999 0.191485 0.018921601, + -0.052960701 0.191476 0.0303511, + -0.0532845 0.17147601 0.029688399, + -0.0518195 0.17147399 0.032356299, + -0.048232201 0.17147 0.037824798, + -0.0460728 0.191468 0.0405881, + -0.046576701 0.171468 0.039951101, + -0.046423901 0.171468 0.040147301, + -0.044562999 0.17146599 0.042309601, + -0.059027899 0.19148999 0.0129093, + -0.058398101 0.171487 0.015844001, + -0.059432998 0.171492 0.0102779, + -0.050219599 0.095307 9.4803099e-006, + -0.050219599 0.093379602 0.0015982901, + -0.051830001 0.095596701 0.00101599, + -0.048467699 0.095149301 -0.00091194198, + -0.048467699 0.0933358 0.00067895203, + -0.0465803 0.0951178 -0.00172762, + -0.0465803 0.093384102 -0.000111852, + -0.044564299 0.095166802 -0.00240208, + -0.044564299 0.093454301 -0.00078936701, + -0.0424264 0.095223203 -0.00295206, + -0.0424264 0.093533598 -0.0013581, + -0.040174201 0.095273897 -0.0033838099, + -0.040174201 0.093602203 -0.00180373, + -0.0378174 0.095300302 -0.0036860199, + -0.0378174 0.093642101 -0.00211812, + -0.035366699 0.095284402 -0.0038519001, + -0.035366699 0.093635902 -0.00229579, + -0.0328326 0.095208101 -0.0038767401, + -0.0328326 0.093564898 -0.0023326799, + -0.0302257 0.0950533 -0.00375802, + -0.0302257 0.093412198 -0.00222666, + -0.027557701 0.094805703 -0.0034972299, + -0.027557701 0.093167901 -0.0019789201, + -0.0248404 0.094455503 -0.0030970101, + -0.0248404 0.092820697 -0.00159294, + -0.0220857 0.0939904 -0.0025613001, + -0.0220857 0.092340097 -0.00107893, + -0.019305199 0.093383104 -0.00190014, + -0.019305199 0.091715701 -0.000441699, + -0.0165099 0.092626996 -0.0011214, + -0.0165099 0.090941697 0.000312939, + -0.0137106 0.091716804 -0.00023263101, + -0.0137106 0.090010598 0.00117657, + -0.0109179 0.0906455 0.0007567, + -0.0109179 0.088915698 0.00213903, + 0.0109179 0.098735802 -0.0068125399, + 0.0109179 0.101683 -0.0101075, + 0.0137106 0.099676199 -0.0079357401, + 0.0081428103 0.099170901 -0.0071905199, + -0.0081428103 0.096073702 -0.0040188599, + -0.0109179 0.097196802 -0.0052159899, + -0.0081428103 0.099168301 -0.0071888398, + -0.0053973799 0.096392304 -0.00426991, + -0.0053973799 0.093147397 -0.00124002, + -0.00268824 0.093342401 -0.00137757, + -0.00268824 0.089952901 0.00149713, + 0 0.090019204 0.00145588, + 0 0.0864904 0.0041585602, + 0.00268824 0.089953899 0.00149593, + 0.00268824 0.093342997 -0.00137882, + 0.0053973799 0.093148701 -0.0012425201, + 0.0053973799 0.096392497 -0.0042713098, + 0.0081428103 0.096074 -0.0040209801, + 0.0109179 0.0956183 -0.0036625899, + 0.0137106 0.095020004 -0.0031920699, + 0.0109179 0.093999803 -0.0021484201, + 0.056809202 0.110802 -0.0021631501, + 0.0576833 0.112318 -0.00072782702, + 0.056809202 0.108173 -0.00073379697, + 0.055787299 0.109441 -0.0035304499, + 0.055787299 0.106915 -0.00204839, + 0.0546159 0.108231 -0.0048213699, + 0.0546159 0.105812 -0.00328908, + 0.0532961 0.10717 -0.00602694, + 0.0532961 0.104859 -0.0044469498, + 0.051830001 0.106252 -0.0071380702, + 0.051830001 0.104051 -0.0055128098, + 0.050219599 0.105472 -0.0081454804, + 0.050219599 0.101312 -0.0048607001, + 0.048467699 0.102812 -0.0074187699, + 0.048467699 0.100841 -0.0057803299, + 0.0465803 0.102353 -0.0082480302, + 0.0465803 0.100481 -0.0066067101, + 0.044564299 0.101997 -0.0089703295, + 0.044564299 0.10023 -0.0073224101, + 0.0424264 0.10174 -0.0095688403, + 0.0424264 0.100079 -0.0079111597, + 0.040174201 0.101572 -0.0100285, + 0.040174201 0.098486602 -0.0066714101, + 0.0378174 0.100012 -0.0086304098, + 0.0378174 0.098484799 -0.0069454899, + 0.035366699 0.099967197 -0.0087575801, + 0.035366699 0.098450899 -0.00708886, + 0.0328326 0.099877097 -0.0087484596, + 0.0328326 0.098365597 -0.0070918398, + 0.0302257 0.099721998 -0.0085948603, + 0.0302257 0.098211303 -0.0069495402, + 0.027557701 0.099486798 -0.0082956199, + 0.027557701 0.097972803 -0.0066622002, + 0.0248404 0.099156998 -0.00785241, + 0.0248404 0.097635798 -0.0062321401, + 0.0220857 0.098717801 -0.0072681801, + 0.0220857 0.097184397 -0.0056628599, + 0.019305199 0.098154597 -0.00654777, + 0.019305199 0.096601799 -0.0049592401, + 0.0165099 0.0974539 -0.0056992802, + 0.0165099 0.095883101 -0.0041314098, + 0.0137106 0.096611001 -0.0047335601, + 0.0081428103 0.092817202 -0.0010098401, + 0.0053973799 0.089753099 0.0016198, + 0.00268824 0.086423799 0.0041940799, + 0 0.082834601 0.0066765901, + -0.00268824 0.086422503 0.0041948901, + -0.0053973799 0.089750998 0.0016222, + -0.0081428103 0.092815302 -0.0010060699, + -0.0109179 0.093998201 -0.0021442999, + -0.055787299 0.106902 -0.00206467, + -0.055787299 0.104424 -0.00052358001, + -0.056809202 0.108157 -0.000755671, + -0.0546159 0.105803 -0.0032989299, + -0.0546159 0.103434 -0.00170849, + -0.0532961 0.104854 -0.0044492502, + -0.0532961 0.102596 -0.00281575, + -0.051830001 0.10405 -0.0055102101, + -0.051830001 0.0997684 -0.00222547, + -0.050219599 0.101312 -0.0048570898, + -0.050219599 0.097273499 -0.00159885, + -0.048467699 0.098903596 -0.0041407598, + -0.048467699 0.097005799 -0.00251852, + -0.0465803 0.0986486 -0.0049632699, + -0.0465803 0.096860699 -0.0033394999, + -0.044564299 0.098506398 -0.0056739999, + -0.044564299 0.096831501 -0.0040419302, + -0.0424264 0.098469302 -0.0062536299, + -0.0424264 0.096870497 -0.0045907898, + -0.040174201 0.098487496 -0.0066683502, + -0.040174201 0.096902199 -0.0050049298, + -0.0378174 0.098485596 -0.0069408501, + -0.0378174 0.096914999 -0.0052940999, + -0.035366699 0.098451503 -0.0070825201, + -0.035366699 0.096890099 -0.0054482301, + -0.0328326 0.098365702 -0.0070839701, + -0.0328326 0.096808799 -0.0054612602, + -0.0302257 0.098210096 -0.0069406698, + -0.0302257 0.096653402 -0.0053300401, + -0.027557701 0.097969197 -0.0066531398, + -0.027557701 0.096408501 -0.0050556799, + -0.0248404 0.0976284 -0.0062238802, + -0.0248404 0.096060202 -0.00464105, + -0.0220857 0.097173803 -0.0056563602, + -0.0220857 0.095598496 -0.0040894598, + -0.019305199 0.096595697 -0.0049552401, + -0.019305199 0.095010698 -0.0034060499, + -0.0165099 0.0958836 -0.0041286699, + -0.0165099 0.0942754 -0.0026026401, + -0.0137106 0.0950194 -0.0031884999, + -0.0137106 0.093387097 -0.00168828, + -0.0109179 0.092340298 -0.00067153899, + -0.0532961 0.098189101 0.00046783799, + -0.0546159 0.101116 -7.1531998e-005, + -0.055787299 0.101995 0.00107001, + -0.056809202 0.103034 0.00227773, + -0.0576833 0.106881 0.00205553, + -0.0576833 0.112297 -0.00075762998, + -0.058412101 0.111141 0.00205398, + -0.058412101 0.116828 -0.000522535, + -0.058998398 0.115794 0.0022797401, + -0.058998398 0.121731 -4.4720698e-005, + -0.059445001 0.120821 0.00273791, + -0.059445001 0.126985 0.000678243, + -0.059757002 0.12619799 0.0034296601, + -0.059757002 0.132567 0.0016399299, + -0.0599402 0.13190199 0.00435373, + -0.0599402 0.13845 0.00283703, + -0.059999999 0.13789999 0.0055288202, + -0.059999999 0.14460599 0.00428792, + -0.0599402 0.144164 0.00697872, + -0.0599402 0.151007 0.0060161198, + -0.059757002 0.150673 0.0087269004, + -0.059757002 0.15763301 0.0080448501, + -0.059445001 0.157405 0.0107911, + -0.059445001 0.164465 0.0103922, + -0.058998398 0.164349 0.0131675, + -0.059358198 0.171491 0.010889, + -0.0590127 0.17149 0.0128908, + -0.058984801 0.17149 0.0130521, + -0.059716001 0.17149401 0.0079672802, + -0.0137106 0.096611403 -0.0047312798, + -0.0109179 0.095617801 -0.0036597501, + -0.0137106 0.098159999 -0.0063134902, + -0.0109179 0.098732203 -0.00681028, + -0.0109179 0.10168 -0.0101039, + -0.0109179 0.104448 -0.013527, + -0.0081428103 0.102093 -0.0104995, + -0.0053973799 0.099473201 -0.0074534402, + -0.00268824 0.096579298 -0.0044173799, + 0 0.093406402 -0.00142291, + 0.00268824 0.096579403 -0.0044180802, + 0.0053973799 0.099474899 -0.0074545499, + 0.0081428103 0.102095 -0.0105022, + 0.0109179 0.104448 -0.0135302, + 0.0137106 0.102563 -0.0112755, + 0.0137106 0.103938 -0.0129922, + 0.0165099 0.103304 -0.0123232, + 0.0165099 0.104652 -0.0140573, + 0.019305199 0.103916 -0.0132417, + 0.019305199 0.105241 -0.0149904, + 0.0220857 0.104409 -0.0140226, + 0.0220857 0.105716 -0.015784901, + 0.0248404 0.104796 -0.0146603, + 0.0248404 0.10609 -0.0164384, + 0.027557701 0.105092 -0.0151561, + 0.027557701 0.10767 -0.018676599, + 0.0302257 0.106646 -0.017224601, + 0.0302257 0.108043 -0.018947899, + 0.0328326 0.106963 -0.017341699, + 0.0328326 0.108458 -0.0190449, + 0.035366699 0.107332 -0.017287901, + 0.035366699 0.108924 -0.018972, + 0.0378174 0.10776 -0.017071599, + 0.0378174 0.109449 -0.0187381, + 0.040174201 0.108256 -0.016703, + 0.040174201 0.11004 -0.0183543, + 0.0424264 0.108826 -0.0161941, + 0.0424264 0.1107 -0.017834101, + 0.044564299 0.109472 -0.0155596, + 0.044564299 0.111449 -0.0171728, + 0.0465803 0.110218 -0.0147956, + 0.0465803 0.1123 -0.016364601, + 0.048467699 0.111075 -0.0138953, + 0.048467699 0.113261 -0.0154178, + 0.050219599 0.11205 -0.0128668, + 0.050219599 0.11434 -0.0143403, + 0.051830001 0.113151 -0.011718, + 0.051830001 0.115543 -0.0131398, + 0.0532961 0.114385 -0.010458, + 0.0532961 0.116876 -0.0118257, + 0.0546159 0.115755 -0.0090960702, + 0.0546159 0.118343 -0.0104073, + 0.055787299 0.117266 -0.0076414798, + 0.055787299 0.119949 -0.0088939704, + 0.056809202 0.118921 -0.0061035198, + 0.056809202 0.124505 -0.0084226998, + 0.0576833 0.123589 -0.0056194002, + 0.059999999 0.158077 0.0026875399, + 0.0599402 0.157855 0.0053764898, + 0.059999999 0.151343 0.0033607599, + 0.0599402 0.151675 0.00067093602, + 0.0599402 0.145059 0.00162175, + 0.059757002 0.145503 -0.00109, + 0.059757002 0.13902199 0.000145725, + 0.059445001 0.13958301 -0.00260341, + 0.059445001 0.133261 -0.00108621, + 0.058998398 0.13394199 -0.0038661601, + 0.058998398 0.127803 -0.00207384, + 0.058412101 0.128603 -0.0048728599, + 0.058412101 0.12267 -0.0028120501, + 0.044564299 0.107546 -0.0139185, + 0.0424264 0.106991 -0.014545, + 0.040174201 0.106516 -0.0150416, + 0.0378174 0.106117 -0.0153951, + 0.035366699 0.105788 -0.0155945, + 0.0328326 0.105521 -0.015629699, + 0.0302257 0.103983 -0.0137315, + 0.027557701 0.10376 -0.0133932, + 0.0248404 0.103456 -0.0129129, + 0.0220857 0.103055 -0.012288, + 0.019305199 0.102543 -0.0115209, + 0.0165099 0.101908 -0.0106184, + 0.0137106 0.101142 -0.00958932, + 0.0165099 0.100469 -0.0089448504, + 0.019305199 0.101125 -0.0098302597, + 0.0220857 0.101654 -0.0105828, + 0.0248404 0.102069 -0.0111948, + 0.027557701 0.102381 -0.0116628, + 0.0302257 0.102608 -0.0119857, + 0.0328326 0.102765 -0.0121668, + 0.035366699 0.104298 -0.0138946, + 0.0378174 0.104524 -0.013712, + 0.040174201 0.104821 -0.0133732, + 0.0424264 0.105197 -0.0128889, + 0.044564299 0.105658 -0.0122716, + 0.0465803 0.106208 -0.0115372, + 0.0465803 0.104263 -0.0098925903, + 0.044564299 0.103807 -0.010621, + 0.0424264 0.103446 -0.0112291, + 0.040174201 0.103172 -0.0117011, + 0.0378174 0.10298 -0.0120253, + 0.035366699 0.101439 -0.0104644, + 0.0328326 0.101343 -0.0104396, + 0.0302257 0.101188 -0.010274, + 0.027557701 0.100957 -0.0099631101, + 0.0248404 0.100635 -0.0095073199, + 0.0220857 0.100208 -0.0089087998, + 0.019305199 0.099661604 -0.0081718899, + 0.0165099 0.098984398 -0.0073046698, + 0.0137106 0.098164402 -0.0063163298, + 0.058412101 0.11685 -0.00048888102, + 0.058998398 0.121754 -1.14264e-005, + 0.059445001 0.12700699 0.000707442, + 0.059757002 0.132588 0.0016640601, + 0.0599402 0.138468 0.00285849, + 0.059999999 0.144618 0.00431256, + 0.0599402 0.151012 0.0060505602, + 0.059757002 0.15763099 0.0080863005, + 0.059757002 0.164575 0.0076804501, + 0.0596973 0.17149401 0.00815628, + 0.059920698 0.171496 0.0052213101, + 0.059803098 0.17149501 0.00676572, + 0.0599402 0.16468801 0.0049712001, + 0.059999999 0.164801 0.0022828199, + 0.0599402 0.158299 -1.45023e-006, + 0.059757002 0.152009 -0.00203985, + 0.059445001 0.145952 -0.00383811, + 0.058998398 0.14015099 -0.0053822198, + 0.058412101 0.134627 -0.0066638198, + 0.0576833 0.12940399 -0.0076785898, + 0.055787299 0.12541699 -0.0112111, + 0.0599402 0.164913 -0.00040559101, + 0.059962399 0.1715 0.00059207901, + 0.059937101 0.1715 -0.00055160502, + 0.059934601 0.171501 -0.000663838, + 0.059757002 0.16502699 -0.0031149399, + 0.059445001 0.165142 -0.00586063, + 0.059725199 0.17150301 -0.00359985, + 0.058998398 0.15898 -0.0082336403, + 0.058412101 0.153034 -0.0103582, + 0.0576833 0.147324 -0.0122136, + 0.056809202 0.141867 -0.0137811, + 0.0546159 0.129042 -0.0150343, + 0.0532961 0.127211 -0.016698999, + 0.051830001 0.125508 -0.018251, + 0.050219599 0.123926 -0.0196799, + 0.048467699 0.122462 -0.0209767, + 0.0465803 0.121109 -0.0221329, + 0.044564299 0.119862 -0.023140199, + 0.0424264 0.118714 -0.023990801, + 0.040174201 0.117657 -0.0246771, + 0.0378174 0.116681 -0.0251943, + 0.035366699 0.115781 -0.025538201, + 0.0328326 0.114947 -0.025704199, + 0.0302257 0.114165 -0.0256957, + 0.027557701 0.113424 -0.025517, + 0.0248404 0.112718 -0.025162499, + 0.0220857 0.11204 -0.024628401, + 0.019305199 0.11138 -0.0239136, + 0.0165099 0.110733 -0.023021201, + 0.0137106 0.108962 -0.020127101, + 0.0165099 0.10841 -0.019418901, + 0.019305199 0.110123 -0.0221557, + 0.0220857 0.110695 -0.0228946, + 0.0248404 0.111286 -0.023453699, + 0.027557701 0.111904 -0.023833601, + 0.0302257 0.112557 -0.024037199, + 0.0328326 0.113251 -0.024068501, + 0.035366699 0.113992 -0.023934999, + 0.0378174 0.114795 -0.0236344, + 0.040174201 0.115673 -0.0231629, + 0.0424264 0.116635 -0.0225248, + 0.044564299 0.117687 -0.0217251, + 0.0465803 0.11884 -0.020771099, + 0.048467699 0.120098 -0.019670799, + 0.050219599 0.12147 -0.018432099, + 0.051830001 0.122961 -0.0170635, + 0.0532961 0.124576 -0.0155742, + 0.0546159 0.12632 -0.0139738, + 0.055787299 0.128196 -0.0122723, + 0.0546159 0.123628 -0.0128481, + 0.0532961 0.121973 -0.0143858, + 0.051830001 0.120451 -0.0158145, + 0.050219599 0.119053 -0.017124901, + 0.048467699 0.117776 -0.0183076, + 0.0465803 0.116613 -0.019354399, + 0.044564299 0.115558 -0.020257499, + 0.0424264 0.114605 -0.0210086, + 0.040174201 0.113742 -0.0216009, + 0.0378174 0.112964 -0.0220291, + 0.035366699 0.112256 -0.022298399, + 0.0328326 0.111604 -0.0224116, + 0.0302257 0.111 -0.022357401, + 0.027557701 0.110437 -0.022130201, + 0.0248404 0.10991 -0.021726299, + 0.0220857 0.10941 -0.021143701, + 0.019305199 0.10775 -0.0185696, + 0.0165099 0.107205 -0.017604999, + 0.0137106 0.106546 -0.0165087, + 0.0137106 0.105266 -0.0147374, + 0.0165099 0.105953 -0.0158183, + 0.019305199 0.106518 -0.0167659, + 0.0220857 0.106976 -0.0175767, + 0.0248404 0.108592 -0.019983601, + 0.027557701 0.109025 -0.0204101, + 0.0302257 0.109494 -0.020659899, + 0.0328326 0.110006 -0.020736, + 0.035366699 0.110566 -0.020643299, + 0.0378174 0.111184 -0.020391401, + 0.040174201 0.111865 -0.019993, + 0.0424264 0.112626 -0.019444499, + 0.044564299 0.113478 -0.018739199, + 0.0465803 0.114432 -0.017885, + 0.048467699 0.115495 -0.0168893, + 0.050219599 0.116676 -0.015760301, + 0.051830001 0.117977 -0.014506, + 0.0532961 0.119406 -0.0131356, + 0.0546159 0.120968 -0.0116586, + 0.055787299 0.122667 -0.0100845, + -0.0137106 0.105266 -0.0147341, + -0.0248404 0.107333 -0.0182239, + -0.0248404 0.108592 -0.01998, + -0.0220857 0.106977 -0.017574999, + -0.027557701 0.10767 -0.0186726, + -0.027557701 0.109024 -0.020405, + -0.0302257 0.108042 -0.018942401, + -0.0302257 0.109493 -0.0206549, + -0.0328326 0.108457 -0.0190394, + -0.0328326 0.110005 -0.020732, + -0.035366699 0.108924 -0.018967699, + -0.035366699 0.110566 -0.020640699, + -0.0378174 0.109449 -0.018735399, + -0.0378174 0.111184 -0.020390199, + -0.040174201 0.11004 -0.018353, + -0.040174201 0.111864 -0.019990999, + -0.0424264 0.110699 -0.017832, + -0.0424264 0.112622 -0.0194463, + -0.044564299 0.111445 -0.0171747, + -0.044564299 0.113471 -0.0187473, + -0.0465803 0.112292 -0.016372999, + -0.0465803 0.114421 -0.0178985, + -0.048467699 0.11325 -0.015432, + -0.048467699 0.115481 -0.016907901, + -0.050219599 0.114325 -0.0143596, + -0.050219599 0.116659 -0.015783301, + -0.051830001 0.115527 -0.0131637, + -0.051830001 0.117959 -0.0145328, + -0.0532961 0.116857 -0.0118533, + -0.0532961 0.119387 -0.0131652, + -0.0546159 0.118323 -0.0104377, + -0.0546159 0.120948 -0.0116901, + -0.0546159 0.123607 -0.0128797, + -0.055787299 0.125395 -0.0112427, + -0.0532961 0.121954 -0.0144165, + -0.051830001 0.120431 -0.0158433, + -0.050219599 0.119035 -0.017150801, + -0.048467699 0.11776 -0.0183299, + -0.0465803 0.116599 -0.0193724, + -0.044564299 0.115548 -0.0202705, + -0.0424264 0.114598 -0.0210164, + -0.040174201 0.113739 -0.021602601, + -0.0378174 0.112963 -0.0220272, + -0.035366699 0.112256 -0.0222972, + -0.0328326 0.111604 -0.022409201, + -0.0302257 0.110999 -0.0223538, + -0.027557701 0.110437 -0.0221256, + -0.0248404 0.109909 -0.021721801, + -0.0220857 0.10941 -0.021140501, + -0.019305199 0.10775 -0.0185681, + -0.019305199 0.106519 -0.016763501, + -0.0165099 0.107206 -0.0176029, + -0.0165099 0.105954 -0.0158154, + -0.0137106 0.106546 -0.016506299, + -0.056809202 0.13018399 -0.0105081, + -0.0576833 0.135295 -0.0094914902, + -0.058412101 0.140705 -0.0081996601, + -0.058998398 0.146395 -0.0066401102, + -0.059445001 0.152343 -0.0048211301, + -0.059757002 0.158525 -0.0027528401, + -0.0599402 0.16491801 -0.00043966901, + -0.0599254 0.171501 -0.00085355103, + -0.059999999 0.164805 0.00224871, + -0.059962101 0.1715 0.00059214502, + -0.0599402 0.158301 -4.3027601e-005, + -0.059757002 0.152004 -0.0020741799, + -0.059445001 0.14594001 -0.00386252, + -0.058998398 0.14013299 -0.0054033501, + -0.058412101 0.134607 -0.0066874102, + -0.0576833 0.129383 -0.0077069202, + -0.056809202 0.124483 -0.0084547503, + -0.055787299 0.119928 -0.0089261103, + -0.0546159 0.115735 -0.00912428, + -0.0532961 0.114367 -0.0104825, + -0.051830001 0.113136 -0.011738, + -0.050219599 0.112038 -0.0128814, + -0.048467699 0.111067 -0.0139041, + -0.0465803 0.110214 -0.0147976, + -0.044564299 0.109471 -0.0155573, + -0.0424264 0.108826 -0.016192799, + -0.040174201 0.108256 -0.0167001, + -0.0378174 0.10776 -0.017067, + -0.035366699 0.107331 -0.017282, + -0.0328326 0.106962 -0.0173357, + -0.0302257 0.106646 -0.017220199, + -0.027557701 0.106374 -0.0169279, + -0.0248404 0.106091 -0.0164365, + -0.0220857 0.105717 -0.015782099, + -0.019305199 0.105242 -0.014987, + -0.0165099 0.104652 -0.0140534, + -0.0137106 0.103937 -0.0129882, + -0.059935 0.171496 0.00482467, + -0.059980098 0.19149999 0.00060761301, + -0.0599989 0.171498 0.0021365299, + -0.059999999 0.171498 0.00208897, + -0.0599331 0.1715 -0.00055149401, + -0.059746101 0.17150301 -0.0032599999, + -0.0030887299 0.191451 0.062072899, + -0.00267493 0.171451 0.062068999, + -0.0122731 0.19154499 -0.0565788, + -0.0145714 0.171545 -0.056067102, + -0.0182469 0.191544 -0.055005599, + -0.0053966301 0.171546 -0.057610299, + -0.00294237 0.171546 -0.0577912, + -0.0053973799 0.169433 -0.057590999, + -0.00616926 0.19154599 -0.057529502, + -0.0058778701 0.171546 -0.057574801, + -0.0109154 0.171545 -0.056847699, + -0.0087992204 0.171546 -0.0572147, + -0.0116994 0.171545 -0.0567117, + -0.0109179 0.169416 -0.056833301, + -0.0081412597 0.171546 -0.057295799, + -0.0061684698 0.171546 -0.057539001, + -0.0081428103 0.16942599 -0.057279401, + -0.0081428103 0.167292 -0.057185099, + -0.0053973799 0.16730499 -0.057496399, + -0.0053973799 0.16516501 -0.057335801, + -0.00268824 0.165177 -0.057518099, + -0.00268824 0.16303299 -0.057290699, + 0 0.163038 -0.0573496, + 0 0.160889 -0.057054799, + 0.00268824 0.16303299 -0.0572889, + 0.00268824 0.165176 -0.057516299, + 0.0053973799 0.16516501 -0.057332199, + 0.0053973799 0.16730399 -0.057493299, + 0.0081428103 0.167291 -0.057180401, + 0.0081428103 0.16942599 -0.057276499, + 0.0109179 0.169416 -0.0568294, + 0.0089870598 0.171546 -0.057186499, + 0.010915 0.171545 -0.0568459, + 0.0118856 0.171545 -0.056674398, + 0.0122731 0.19154499 -0.0565788, + 0.00616926 0.19154599 -0.057529502, + 0.00814093 0.171546 -0.057293501, + 0.0061689499 0.171546 -0.057542998, + 0.0060668602 0.171546 -0.057555899, + 0.0053973799 0.169432 -0.057589099, + 0.00268824 0.167312 -0.057677299, + 0 0.16518 -0.057576999, + -0.00268824 0.167312 -0.0576788, + 0 0.19154599 -0.0578475, + 0.0026879699 0.171546 -0.0577945, + 0.0031320599 0.171546 -0.057781599, + 0.00268824 0.16943599 -0.0577727, + 0.000344617 0.171546 -0.057862401, + 0 0.16943701 -0.057833001, + 0 0.16731501 -0.057737801, + -0.00268824 0.16943599 -0.057773702, + -0.0026880901 0.171546 -0.057797499, + 0 0.171546 -0.057863399, + 0.0053963801 0.171546 -0.057607401, + 0.0030887299 0.191451 0.062072899, + 0.0028477299 0.171451 0.062068898, + 0.0053912699 0.171451 0.061885402, + 0.0137069 0.171545 -0.056259599, + 0.0122713 0.171545 -0.056586601, + -0.016505901 0.171544 -0.055532102, + -0.017408401 0.171544 -0.0552825, + -0.022080099 0.171543 -0.0536361, + -0.029552899 0.19154 -0.050064601, + -0.0282706 0.17154001 -0.050785799, + -0.0302257 0.169264 -0.049668301, + -0.027557701 0.167035 -0.051041398, + -0.0248404 0.164846 -0.0522005, + -0.0220857 0.162689 -0.053143501, + -0.019305199 0.160561 -0.053869002, + -0.0165099 0.158453 -0.054378301, + -0.0137106 0.156363 -0.0546735, + -0.0109179 0.154282 -0.0547565, + -0.0081428103 0.152207 -0.0546294, + -0.0053973799 0.150133 -0.054297801, + -0.00268824 0.148058 -0.0537677, + 0 0.14597701 -0.053045399, + 0.00268824 0.148059 -0.053766701, + 0.0053973799 0.150134 -0.054295901, + 0.0081428103 0.152209 -0.054626402, + 0.0109179 0.154284 -0.054752, + 0.0137106 0.15636501 -0.054666899, + 0.0165099 0.158455 -0.054368801, + 0.019305199 0.160561 -0.053856399, + 0.0220857 0.162689 -0.053128101, + 0.0248404 0.16484401 -0.052183699, + 0.027557701 0.167033 -0.0510257, + 0.0302257 0.16926301 -0.049657598, + 0.0295441 0.17154001 -0.0500651, + -0.030832 0.17153899 -0.049335599, + -0.0302194 0.17154001 -0.049682401, + -0.029544 0.17154001 -0.050064798, + -0.032826498 0.171538 -0.0480734, + -0.039609101 0.191534 -0.0429154, + -0.038047399 0.171535 -0.044257302, + -0.042409498 0.17153201 -0.040306699, + -0.0465752 0.171528 -0.0356768, + -0.047984999 0.171527 -0.033872101, + 0.050211899 0.171524 -0.0306911, + 0.051434901 0.171523 -0.028748499, + 0.048467699 0.161 -0.032692801, + 0.0465803 0.15860599 -0.034847699, + 0.044564299 0.156297 -0.0368414, + 0.0424264 0.154071 -0.038661901, + 0.040174201 0.151921 -0.040298101, + 0.0378174 0.14984199 -0.041741699, + 0.035366699 0.147829 -0.042986199, + 0.0328326 0.14587601 -0.044025701, + 0.0302257 0.143978 -0.0448552, + 0.027557701 0.14212599 -0.045472499, + 0.0248404 0.14031699 -0.0458767, + 0.0220857 0.13854399 -0.0460665, + 0.019305199 0.136801 -0.046041399, + 0.0165099 0.135083 -0.045804001, + 0.0137106 0.133385 -0.045359202, + 0.0109179 0.13170201 -0.0447115, + 0.0081428103 0.13002799 -0.043866299, + 0.0053973799 0.12836 -0.042830799, + 0.00268824 0.12669501 -0.041612901, + 0 0.125029 -0.0402201, + -0.00268824 0.12669399 -0.041613899, + -0.0053973799 0.12835801 -0.042833298, + -0.0081428103 0.130025 -0.043870602, + -0.0109179 0.131698 -0.044717599, + -0.0137106 0.133379 -0.045367099, + -0.0165099 0.135077 -0.045813698, + -0.019305199 0.136793 -0.046052299, + -0.0220857 0.13853499 -0.046078298, + -0.0248404 0.14030799 -0.045888901, + -0.027557701 0.142116 -0.0454848, + -0.0302257 0.143967 -0.0448674, + -0.0328326 0.14586601 -0.044038001, + -0.035366699 0.147819 -0.042998798, + -0.0378174 0.149832 -0.041755602, + -0.040174201 0.151912 -0.0403146, + -0.0424264 0.154064 -0.038682502, + -0.044564299 0.156293 -0.036867, + -0.0465803 0.15860499 -0.034878101, + -0.048467699 0.161002 -0.0327265, + -0.048467699 0.158352 -0.032427002, + -0.0465803 0.156003 -0.034509499, + -0.044564299 0.15374 -0.0364291, + -0.0424264 0.15156101 -0.038175199, + -0.040174201 0.149461 -0.039737701, + -0.0378174 0.147433 -0.041109301, + -0.035366699 0.14547201 -0.042283799, + -0.0328326 0.143571 -0.0432547, + -0.0302257 0.141725 -0.044016499, + -0.027557701 0.139929 -0.0445669, + -0.0248404 0.138175 -0.044904701, + -0.0220857 0.136457 -0.0450284, + -0.019305199 0.134771 -0.044937599, + -0.0165099 0.13311 -0.044636499, + -0.0137106 0.131467 -0.0441298, + -0.0109179 0.129841 -0.043422598, + -0.0081428103 0.128223 -0.0425203, + -0.0053973799 0.12661 -0.041430298, + -0.00268824 0.125 -0.040160399, + 0 0.123389 -0.038718499, + 0.00268824 0.125001 -0.040159602, + 0.0053973799 0.12661199 -0.041428201, + 0.0081428103 0.128225 -0.0425166, + 0.0109179 0.12984499 -0.043416999, + 0.0137106 0.131473 -0.0441222, + 0.0165099 0.13311601 -0.044627, + 0.019305199 0.13477799 -0.044926502, + 0.0220857 0.136466 -0.045015901, + 0.0248404 0.138184 -0.044891398, + 0.027557701 0.139939 -0.044553399, + 0.0302257 0.141736 -0.044002902, + 0.0328326 0.143582 -0.0432414, + 0.035366699 0.145483 -0.042270701, + 0.0378174 0.14744399 -0.041095801, + 0.040174201 0.149471 -0.039722901, + 0.0424264 0.15157001 -0.038157798, + 0.044564299 0.15374701 -0.036407501, + 0.0465803 0.15600701 -0.034482699, + 0.048467699 0.158353 -0.0323954, + 0.050219599 0.16079099 -0.0301574, + 0.050219599 0.15809201 -0.029859601, + 0.048467699 0.155705 -0.032030001, + 0.0465803 0.153409 -0.034048501, + 0.044564299 0.15120199 -0.035902999, + 0.0424264 0.149078 -0.0375822, + 0.040174201 0.14703199 -0.0390766, + 0.0378174 0.145059 -0.0403799, + 0.035366699 0.143153 -0.041485898, + 0.0328326 0.14130899 -0.042388901, + 0.0302257 0.13951901 -0.0430834, + 0.027557701 0.137779 -0.043567698, + 0.0248404 0.13608199 -0.043840401, + 0.0220857 0.134422 -0.043900602, + 0.019305199 0.13279299 -0.043749101, + 0.0165099 0.131189 -0.043389801, + 0.0137106 0.129603 -0.042827498, + 0.0109179 0.128032 -0.042067099, + 0.0081428103 0.12647 -0.041113801, + 0.0053973799 0.124914 -0.039974801, + 0.00268824 0.123359 -0.038658001, + 0 0.121804 -0.037170999, + -0.00268824 0.123359 -0.0386585, + -0.0053973799 0.124912 -0.039976399, + -0.0081428103 0.126468 -0.041116901, + -0.0109179 0.128029 -0.042072099, + -0.0137106 0.12959801 -0.042834502, + -0.0165099 0.131182 -0.043398902, + -0.019305199 0.13278501 -0.043760199, + -0.0220857 0.134414 -0.043913402, + -0.0248404 0.13607199 -0.043854401, + -0.027557701 0.137769 -0.043582302, + -0.0302257 0.13950799 -0.0430982, + -0.0328326 0.141297 -0.042403501, + -0.035366699 0.143141 -0.0415002, + -0.0378174 0.145046 -0.040394001, + -0.040174201 0.14702 -0.039090998, + -0.0424264 0.149067 -0.037597802, + -0.044564299 0.15119299 -0.035921201, + -0.0465803 0.153402 -0.034071099, + -0.048467699 0.155701 -0.0320579, + -0.0532961 0.165959 -0.0253087, + -0.053283598 0.17151999 -0.0254148, + -0.0542247 0.171519 -0.0235477, + -0.054336499 0.171519 -0.023295799, + -0.054602101 0.171518 -0.0226977, + -0.0546159 0.16584501 -0.0225916, + -0.0532961 0.160357 -0.0249169, + -0.050219599 0.152686 -0.0290832, + -0.051830001 0.149561 -0.0259648, + -0.0532961 0.154737 -0.024245599, + -0.0546159 0.16013201 -0.0221994, + -0.055787299 0.16573 -0.0198371, + -0.055772301 0.171516 -0.019943301, + -0.056480099 0.171514 -0.018111801, + -0.0566587 0.171514 -0.017572399, + -0.056793999 0.171514 -0.017163601, + -0.050219599 0.14729799 -0.0279945, + -0.050219599 0.144618 -0.0273456, + -0.048467699 0.145137 -0.0298828, + -0.048467699 0.14252201 -0.0291653, + -0.0465803 0.14307299 -0.0316194, + -0.0465803 0.140526 -0.030833701, + -0.044564299 0.141103 -0.033194099, + -0.044564299 0.138624 -0.032340899, + -0.0424264 0.13922299 -0.034597099, + -0.0424264 0.136812 -0.0336769, + -0.040174201 0.13742501 -0.035818901, + -0.040174201 0.135084 -0.034832198, + -0.0378174 0.135703 -0.036852699, + -0.0378174 0.133434 -0.035800301, + -0.035366699 0.13405401 -0.0376922, + -0.035366699 0.13185599 -0.0365749, + -0.0328326 0.132469 -0.038331501, + -0.0328326 0.130345 -0.037151501, + -0.0302257 0.130941 -0.038766801, + -0.0302257 0.12888899 -0.037526499, + -0.027557701 0.129463 -0.038997602, + -0.027557701 0.12748399 -0.037699401, + -0.0248404 0.128029 -0.039024301, + -0.0248404 0.126123 -0.037670702, + -0.0220857 0.126632 -0.038847402, + -0.0220857 0.124798 -0.037440799, + -0.019305199 0.125264 -0.0384681, + -0.019305199 0.123502 -0.037011199, + -0.0165099 0.12392 -0.037890598, + -0.0165099 0.122229 -0.036385801, + -0.0137106 0.122594 -0.037119899, + -0.0137106 0.120974 -0.035569701, + -0.0109179 0.121281 -0.036160901, + -0.0109179 0.11973 -0.034568802, + -0.0081428103 0.119973 -0.035019901, + -0.0081428103 0.11849 -0.033389501, + -0.0081428103 0.117064 -0.031722799, + -0.0109179 0.118236 -0.0329381, + -0.0137106 0.11941 -0.0339767, + -0.0165099 0.120593 -0.034834601, + -0.019305199 0.121791 -0.035505299, + -0.0220857 0.123013 -0.035983, + -0.0248404 0.124263 -0.036263298, + -0.027557701 0.125549 -0.036344901, + -0.0302257 0.12687901 -0.036227498, + -0.0328326 0.128259 -0.035910498, + -0.035366699 0.129695 -0.035394199, + -0.0378174 0.131198 -0.0346823, + -0.040174201 0.132772 -0.033779301, + -0.0424264 0.134426 -0.032689702, + -0.044564299 0.13616601 -0.031420201, + -0.0465803 0.137996 -0.02998, + -0.048467699 0.139924 -0.0283792, + -0.050219599 0.14195099 -0.0266276, + -0.051830001 0.144085 -0.024735499, + -0.050219599 0.139302 -0.025841, + -0.048467699 0.137344 -0.0275249, + -0.0465803 0.13549 -0.0290587, + -0.044564299 0.133734 -0.030432399, + -0.0424264 0.13207 -0.031636, + -0.040174201 0.130493 -0.0326607, + -0.0378174 0.128997 -0.033500999, + -0.035366699 0.127572 -0.0341524, + -0.0328326 0.126214 -0.034610599, + -0.0302257 0.124912 -0.034871999, + -0.027557701 0.123661 -0.034936398, + -0.0248404 0.122453 -0.034804299, + -0.0220857 0.12128 -0.034476001, + -0.019305199 0.120136 -0.033952899, + -0.0165099 0.119014 -0.033240501, + -0.0137106 0.117903 -0.032345701, + -0.0109179 0.1168 -0.0312718, + -0.0081428103 0.115698 -0.030023299, + -0.0053973799 0.114593 -0.028607801, + -0.00268824 0.11231 -0.025255401, + 0 0.110163 -0.0216696, + 0.00268824 0.11231 -0.025255799, + 0.0053973799 0.114593 -0.0286087, + 0.0081428103 0.117064 -0.031723399, + 0.0109179 0.118236 -0.032938499, + 0.0137106 0.11941 -0.0339773, + 0.0165099 0.120595 -0.034833901, + 0.019305199 0.121795 -0.035501901, + 0.0220857 0.123018 -0.0359766, + 0.0248404 0.12427 -0.036253698, + 0.027557701 0.125558 -0.036332201, + 0.0302257 0.12688901 -0.0362119, + 0.0328326 0.128271 -0.0358923, + 0.035366699 0.12970901 -0.0353739, + 0.0378174 0.131212 -0.034660399, + 0.040174201 0.132788 -0.033756599, + 0.0424264 0.134442 -0.0326671, + 0.044564299 0.136182 -0.0313983, + 0.0465803 0.13801301 -0.029959301, + 0.048467699 0.13994101 -0.028359599, + 0.050219599 0.141968 -0.026608899, + 0.051830001 0.1441 -0.024716999, + 0.0532961 0.146339 -0.0226945, + 0.0109179 0.1168 -0.031272601, + 0.0137106 0.116452 -0.030680999, + 0.0109179 0.115423 -0.0295747, + 0.0137106 0.117903 -0.0323462, + 0.0165099 0.117489 -0.0316098, + 0.0165099 0.119014 -0.033241302, + 0.019305199 0.118537 -0.032358602, + 0.019305199 0.120138 -0.033952098, + 0.0220857 0.119604 -0.0329214, + 0.0220857 0.121284 -0.034472, + 0.0248404 0.120699 -0.033291601, + 0.0248404 0.122459 -0.034797002, + 0.027557701 0.121828 -0.033468202, + 0.027557701 0.123669 -0.0349258, + 0.0302257 0.123001 -0.033450801, + 0.0302257 0.124922 -0.0348581, + 0.0328326 0.124224 -0.033239, + 0.0328326 0.12622599 -0.034593601, + 0.035366699 0.12550201 -0.032833301, + 0.035366699 0.12758499 -0.0341327, + 0.0378174 0.126848 -0.032237299, + 0.0378174 0.12901101 -0.033479199, + 0.040174201 0.12826499 -0.031455498, + 0.040174201 0.130509 -0.032637499, + 0.0424264 0.12976301 -0.0304923, + 0.0424264 0.13208701 -0.031612098, + 0.044564299 0.131348 -0.029353, + 0.044564299 0.133751 -0.030408701, + 0.0465803 0.133027 -0.0280456, + 0.0465803 0.135507 -0.0290359, + 0.048467699 0.13480601 -0.0265793, + 0.048467699 0.137362 -0.0275033, + 0.050219599 0.13668799 -0.0249639, + 0.050219599 0.139319 -0.0258207, + 0.051830001 0.13868 -0.023209, + 0.051830001 0.14138199 -0.0239977, + 0.0532961 0.140782 -0.0213254, + 0.0532961 0.143555 -0.0220451, + 0.0081428103 0.114392 -0.0282958, + 0.0053973799 0.112182 -0.025074599, + 0.00268824 0.110118 -0.021611501, + 0 0.107839 -0.018011799, + -0.00268824 0.110118 -0.021611299, + -0.0053973799 0.112182 -0.0250738, + -0.0081428103 0.114392 -0.0282945, + -0.0109179 0.115423 -0.0295734, + -0.0137106 0.116452 -0.030680001, + -0.0165099 0.117489 -0.031609301, + -0.019305199 0.118537 -0.0323577, + -0.0220857 0.119602 -0.032922398, + -0.0248404 0.120695 -0.033296, + -0.027557701 0.121822 -0.0334762, + -0.0302257 0.122992 -0.033462401, + -0.0328326 0.124213 -0.033254098, + -0.035366699 0.12548999 -0.032851599, + -0.0378174 0.12683401 -0.032258298, + -0.040174201 0.12825 -0.031478599, + -0.0424264 0.129747 -0.0305169, + -0.044564299 0.131331 -0.029378099, + -0.0465803 0.133009 -0.0280704, + -0.048467699 0.13478699 -0.026603101, + -0.050219599 0.13666999 -0.0249862, + -0.051830001 0.138662 -0.023229901, + 0.059434399 0.171505 -0.0060049798, + 0.0594876 0.17150401 -0.00556543, + 0.059503399 0.191504 -0.0055514099, + 0.0583992 0.171509 -0.0115711, + 0.056795701 0.171514 -0.017164201, + 0.0554916 0.171517 -0.020681901, + 0.0546159 0.165841 -0.0225606, + 0.0532961 0.160355 -0.024879901, + 0.051830001 0.15782399 -0.027251, + 0 0.117393 -0.032283299, + -0.00268824 0.118771 -0.033889901, + 0 0.120275 -0.035580602, + 0.00268824 0.120243 -0.0355203, + 0.00268824 0.121773 -0.037110601, + 0.0053973799 0.121677 -0.0369258, + 0.0053973799 0.123268 -0.038473301, + 0.0081428103 0.123112 -0.038158599, + 0.0081428103 0.124765 -0.039660301, + 0.0109179 0.124551 -0.039210301, + 0.0109179 0.126266 -0.040664099, + 0.0137106 0.126 -0.040073998, + 0.0137106 0.12777799 -0.0414773, + 0.0165099 0.127461 -0.040743999, + 0.0165099 0.12930299 -0.0420947, + 0.019305199 0.128942 -0.0412159, + 0.019305199 0.13084701 -0.0425114, + 0.0220857 0.130447 -0.041484699, + 0.0220857 0.132415 -0.042722799, + 0.0248404 0.131982 -0.041546501, + 0.0248404 0.134014 -0.042724699, + 0.027557701 0.133554 -0.041400101, + 0.027557701 0.13564999 -0.042516202, + 0.0302257 0.135169 -0.041045301, + 0.0302257 0.13733 -0.0420973, + 0.0328326 0.13683499 -0.040482201, + 0.0328326 0.13905799 -0.041468799, + 0.035366699 0.138557 -0.039712399, + 0.035366699 0.140843 -0.040633, + 0.0378174 0.140342 -0.038741302, + 0.0378174 0.142691 -0.039594799, + 0.040174201 0.142196 -0.037574802, + 0.040174201 0.14460599 -0.038360398, + 0.0424264 0.144125 -0.0362188, + 0.0424264 0.146594 -0.036935601, + 0.044564299 0.146135 -0.034679901, + 0.044564299 0.148663 -0.035326902, + 0.0465803 0.148229 -0.032967199, + 0.0465803 0.15081599 -0.033543602, + 0.048467699 0.150414 -0.031090099, + 0.048467699 0.15305699 -0.031595401, + 0.050219599 0.152693 -0.0290589, + 0.050219599 0.15539201 -0.0294939, + 0.051830001 0.15507001 -0.026884999, + -0.0053973799 0.120143 -0.035335101, + -0.0081428103 0.121514 -0.036611401, + -0.0109179 0.122887 -0.037710302, + -0.0137106 0.124269 -0.038623899, + -0.0165099 0.125663 -0.039346602, + -0.019305199 0.127076 -0.039873801, + -0.0220857 0.12851299 -0.0402002, + -0.0248404 0.12998 -0.040321801, + -0.027557701 0.131484 -0.0402372, + -0.0302257 0.133031 -0.039946198, + -0.0328326 0.134628 -0.039448202, + -0.035366699 0.13628399 -0.038744099, + -0.0378174 0.13800199 -0.037838802, + -0.040174201 0.139791 -0.036738701, + -0.0424264 0.14165699 -0.0354499, + -0.044564299 0.143604 -0.033979401, + -0.0465803 0.145639 -0.032336399, + -0.048467699 0.147765 -0.0305312, + -0.050219599 0.149988 -0.0285739, + -0.048467699 0.15040401 -0.03111, + -0.0465803 0.14821699 -0.032984398, + -0.044564299 0.146121 -0.034696002, + -0.0424264 0.14411099 -0.036234599, + -0.040174201 0.14218201 -0.037590999, + -0.0378174 0.140328 -0.0387582, + -0.035366699 0.13854399 -0.0397298, + -0.0328326 0.136822 -0.040499698, + -0.0302257 0.135158 -0.0410624, + -0.027557701 0.133543 -0.041416101, + -0.0248404 0.131972 -0.041560799, + -0.0220857 0.130439 -0.041497, + -0.019305199 0.12893599 -0.041225899, + -0.0165099 0.12745599 -0.040751599, + -0.0137106 0.12599599 -0.040079199, + -0.0109179 0.124549 -0.039213501, + -0.0081428103 0.12311 -0.03816, + -0.0053973799 0.121676 -0.036926001, + -0.00268824 0.120243 -0.0355202, + -0.00268824 0.121773 -0.037110701, + -0.0053973799 0.123267 -0.038474198, + -0.0081428103 0.124763 -0.0396627, + -0.0109179 0.12626299 -0.040668301, + -0.0137106 0.127773 -0.0414836, + -0.0165099 0.129297 -0.042103201, + -0.019305199 0.13083901 -0.042522099, + -0.0220857 0.13240699 -0.042735599, + -0.0248404 0.134004 -0.042739101, + -0.027557701 0.135639 -0.0425318, + -0.0302257 0.137318 -0.042113401, + -0.0328326 0.139046 -0.0414849, + -0.035366699 0.14083 -0.040648699, + -0.0378174 0.14267799 -0.039610099, + -0.040174201 0.144593 -0.038375299, + -0.0424264 0.14658201 -0.036950801, + -0.044564299 0.148651 -0.035343401, + -0.0465803 0.15080599 -0.033562701, + -0.048467699 0.15305001 -0.031618901, + -0.050219599 0.155388 -0.029522801, + 0.054340299 0.171519 -0.023297399, + 0.054603901 0.171518 -0.022698499, + 0.041876599 0.19146401 0.045121599, + 0.0402066 0.171463 0.046672199, + 0.059821099 0.191495 0.0067830202, + 0.059931301 0.171496 0.0048245601, + 0.059980098 0.19149999 0.00060761301, + 0.0460728 0.191468 0.0405881, + 0.04456 0.17146599 0.0423069, + 0.046303399 0.171468 0.040293999, + 0.0465739 0.171468 0.039948899, + 0.048119001 0.17147 0.037977301, + 0.048467699 0.163321 0.037648398, + 0.050219599 0.163427 0.035114501, + 0.0497793 0.171472 0.0356302, + 0.0518176 0.17147399 0.0323552, + 0.052960701 0.191476 0.0303511, + 0.051398799 0.17147399 0.0330908, + 0.052855 0.17147601 0.0305328, + 0.051830001 0.163536 0.032508001, + 0.0532961 0.155799 0.0302504, + 0.0546159 0.14827999 0.028214199, + 0.055787299 0.14099699 0.026418401, + 0.056809202 0.133967 0.024880599, + 0.0576833 0.127211 0.023608999, + 0.058412101 0.120746 0.0226089, + 0.058998398 0.114591 0.021885, + 0.059445001 0.108763 0.021441, + 0.059757002 0.103276 0.021277299, + 0.0599402 0.098143801 0.0213868, + 0.059999999 0.093389802 0.021739, + 0.0599402 0.089045703 0.022297001, + 0.059757002 0.085072003 0.022833699, + 0.059445001 0.081394501 0.023155799, + 0.058998398 0.078075297 0.023297001, + 0.058412101 0.075147502 0.02331, + 0.0576833 0.074867502 0.021926301, + 0.056809202 0.074711099 0.020539001, + 0.055787299 0.0746684 0.0191689, + 0.0546159 0.074728303 0.017834701, + 0.0532961 0.074877903 0.016554199, + 0.051830001 0.075102203 0.0153443, + 0.050219599 0.075382501 0.0142205, + 0.048467699 0.075692303 0.0131988, + 0.0465803 0.076044902 0.0122841, + 0.044564299 0.076405302 0.011454, + 0.0424264 0.076728202 0.0107221, + 0.040174201 0.077002898 0.0101078, + 0.0378174 0.077214599 0.0096252104, + 0.035366699 0.077346899 0.0092855999, + 0.0328326 0.077380903 0.0090964204, + 0.0302257 0.077296197 0.0090616001, + 0.027557701 0.077075496 0.0091786198, + 0.0248404 0.076701798 0.0094404398, + 0.0220857 0.076159596 0.0098359901, + 0.019305199 0.075435802 0.0103505, + 0.0165099 0.074523903 0.0109641, + 0.0137106 0.073420703 0.0116535, + 0.052956201 0.17147601 0.030332901, + 0.053282801 0.17147601 0.0296875, + 0.0484588 0.17147 0.037496898, + 0.059027899 0.19148999 0.0129093, + 0.059430599 0.171492 0.0102776, + 0.057608999 0.191485 0.018921601, + 0.0583965 0.171487 0.0158436, + 0.057377499 0.17148399 0.0196814, + 0.056809202 0.163993 0.021588299, + 0.0576833 0.156712 0.0192012, + 0.058412101 0.149652 0.017078901, + 0.058998398 0.142828 0.0152405, + 0.059445001 0.136252 0.0137038, + 0.059757002 0.12993801 0.0124776, + 0.0599402 0.123905 0.0115626, + 0.059999999 0.118172 0.010937, + 0.0599402 0.112772 0.0105723, + 0.059757002 0.107732 0.0104346, + 0.059445001 0.103083 0.0104933, + 0.058998398 0.098849401 0.0107387, + 0.058412101 0.095051996 0.0111657, + 0.0576833 0.091649897 0.0116161, + 0.056809202 0.088574201 0.0119601, + 0.055787299 0.085874297 0.0122355, + 0.0546159 0.083566599 0.0124947, + 0.0532961 0.083544299 0.0113187, + 0.051830001 0.083600901 0.010193, + 0.050219599 0.083720401 0.0091371601, + 0.048467699 0.083887003 0.0081679896, + 0.0465803 0.084084198 0.0072992202, + 0.044564299 0.084293902 0.0065428899, + 0.0424264 0.0844955 0.0059097898, + 0.040174201 0.084661901 0.0054096598, + 0.0378174 0.084795497 0.0050427602, + 0.035366699 0.084870301 0.0047932598, + 0.0328326 0.0848509 0.0046685799, + 0.0302257 0.084725201 0.0046780999, + 0.027557701 0.084480703 0.0048251799, + 0.0248404 0.084104501 0.0051095402, + 0.0220857 0.083582401 0.0055275299, + 0.019305199 0.082901403 0.00607232, + 0.0165099 0.082052201 0.00673194, + 0.0137106 0.081027597 0.0074912002, + 0.0109179 0.079822898 0.0083326101, + 0.0081428103 0.082203798 0.0069610798, + 0.0081428103 0.085867196 0.0044907299, + 0.0081428103 0.089410603 0.00183129, + 0.0109179 0.087158002 0.0034701601, + 0.0053973799 0.086218096 0.0043036798, + -0.0081428103 0.0858633 0.0044932002, + -0.0109179 0.087153196 0.0034743201, + -0.0081428103 0.089407399 0.0018349, + -0.0053973799 0.086215504 0.0043053199, + -0.0053973799 0.082556203 0.0068017999, + -0.00268824 0.082765698 0.0067075202, + -0.00268824 0.078997999 0.0090275798, + 0 0.079066798 0.0090023195, + 0 0.075202599 0.0111281, + 0.00268824 0.078999303 0.0090276096, + 0.00268824 0.082767099 0.00670711, + 0.0053973799 0.0825589 0.0068009798, + 0.0109179 0.083543397 0.0059987898, + -0.0109179 0.083537802 0.0060012499, + -0.051830001 0.0895973 0.0057274401, + -0.051830001 0.087641403 0.0072656502, + -0.0532961 0.089695901 0.00682334, + -0.050219599 0.089613497 0.0047323299, + -0.050219599 0.0876882 0.0062602302, + -0.048467699 0.0896786 0.0038268601, + -0.048467699 0.087786801 0.0053310501, + -0.0465803 0.089781702 0.0030089901, + -0.0465803 0.087919302 0.0044953199, + -0.044564299 0.089904398 0.00229503, + -0.044564299 0.088068098 0.0037664101, + -0.0424264 0.090027802 0.0016976, + -0.0424264 0.088214204 0.00315572, + -0.040174201 0.090132698 0.00122661, + -0.040174201 0.088338003 0.00267251, + -0.0378174 0.090201303 0.000888284, + -0.0378174 0.088422798 0.0023227099, + -0.035366699 0.090216599 0.00068714301, + -0.035366699 0.088457197 0.00211138, + -0.0328326 0.090166301 0.00062730099, + -0.0328326 0.0884308 0.0020409599, + -0.0302257 0.090038903 0.00070983998, + -0.0302257 0.088300802 0.0021009201, + -0.027557701 0.089797199 0.00092290202, + -0.027557701 0.088053197 0.0022895399, + -0.0248404 0.089429103 0.00126356, + -0.0248404 0.0876799 0.00260811, + -0.0220857 0.088925503 0.00173169, + -0.0220857 0.087168701 0.00305562, + -0.019305199 0.088275 0.00232421, + -0.019305199 0.086507201 0.0036287201, + -0.0165099 0.087468803 0.0030340401, + -0.0165099 0.085686497 0.0043188399, + -0.0137106 0.086499304 0.00385083, + -0.0137106 0.084698699 0.0051144599, + -0.0109179 0.0853597 0.0047618998, + -0.0137106 0.088270701 0.0025380601, + -0.0165099 0.089221403 0.00169847, + -0.019305199 0.0900122 0.00096707698, + -0.0220857 0.090650298 0.000352826, + -0.0248404 0.091144301 -0.000137582, + -0.027557701 0.091502801 -0.00050201197, + -0.0302257 0.091737501 -0.00073692697, + -0.0328326 0.091881603 -0.00083105301, + -0.035366699 0.091945603 -0.00078212901, + -0.0378174 0.091942102 -0.000592614, + -0.040174201 0.091887899 -0.00026619699, + -0.0424264 0.091801502 0.000192274, + -0.044564299 0.091700204 0.000775958, + -0.0465803 0.091603398 0.00147363, + -0.048467699 0.091530301 0.0022696899, + -0.050219599 0.091493003 0.00316748, + -0.051830001 0.091559 0.0041805501, + -0.0532961 0.093880601 0.0036921301, + -0.0546159 0.092132799 0.0064176498, + -0.0546159 0.096580699 0.0032108801, + -0.055787299 0.094950102 0.0059916801, + -0.055787299 0.099614799 0.00271047, + -0.056809202 0.098099597 0.00551849, + -0.056809202 0.100543 0.00387449, + -0.0576833 0.101636 0.0050940001, + -0.058412101 0.164231 0.0159606, + -0.0576833 0.164114 0.018760299, + -0.058215201 0.171487 0.0166621, + -0.058412101 0.15694501 0.016360801, + -0.058998398 0.157176 0.0135671, + -0.058998398 0.149992 0.0142508, + -0.059445001 0.150334 0.011474, + -0.059445001 0.14327 0.0124386, + -0.059757002 0.14372 0.0096904701, + -0.059757002 0.136795 0.0109334, + -0.0599402 0.13734899 0.0082206298, + -0.0599402 0.130582 0.0097395396, + -0.059999999 0.13124201 0.0070466301, + -0.059999999 0.124652 0.0088388901, + -0.0599402 0.125422 0.0061447299, + -0.0599402 0.119032 0.0082074897, + -0.059757002 0.119921 0.0054908702, + -0.059757002 0.113752 0.0078192502, + -0.059445001 0.114768 0.0050643301, + -0.059445001 0.108843 0.00764619, + -0.058998398 0.109989 0.0048589301, + -0.058998398 0.104331 0.0076795099, + -0.058412101 0.105605 0.0048708599, + -0.058412101 0.100237 0.0079143997, + -0.0576833 0.096576497 0.0083414698, + -0.056809202 0.093304202 0.0087984903, + -0.055787299 0.090360902 0.00918072, + -0.0546159 0.087798201 0.0095149102, + -0.0532961 0.085623302 0.0098583503, + -0.051830001 0.085640803 0.0087634204, + -0.050219599 0.085723899 0.0077321799, + -0.048467699 0.085855097 0.0067833099, + -0.0465803 0.086017497 0.00593118, + -0.044564299 0.086193003 0.0051879999, + -0.0424264 0.086362198 0.00456452, + -0.040174201 0.086506903 0.0040697302, + -0.0378174 0.086616002 0.0037101901, + -0.035366699 0.086681299 0.00348902, + -0.0328326 0.086656898 0.0033948501, + -0.0302257 0.086524799 0.00342919, + -0.027557701 0.086276799 0.0035954099, + -0.0248404 0.0859005 0.0038939801, + -0.0220857 0.085383199 0.0043238099, + -0.019305199 0.084711798 0.0048799999, + -0.0165099 0.083877198 0.00555271, + -0.0137106 0.082871802 0.0063286601, + -0.0109179 0.081689604 0.00719195, + -0.057597399 0.17148501 0.018902499, + -0.057669099 0.17148501 0.018642601, + -0.058857501 0.171489 0.0137895, + 0.0109179 0.090649001 0.00075146201, + 0.050219599 0.099276997 -0.0032285801, + 0.051830001 0.099768601 -0.0022292, + 0.050219599 0.097275101 -0.00160721, + 0.048467699 0.098904997 -0.0041488302, + 0.048467699 0.097007103 -0.0025273401, + 0.0465803 0.098649897 -0.0049717501, + 0.0465803 0.096860401 -0.0033462499, + 0.044564299 0.0985061 -0.0056804498, + 0.044564299 0.0951657 -0.00240548, + 0.0424264 0.096869402 -0.0045940299, + 0.0424264 0.095222302 -0.00295727, + 0.040174201 0.096901402 -0.00500987, + 0.040174201 0.095273197 -0.00339101, + 0.0378174 0.0969145 -0.0053008799, + 0.0378174 0.095300198 -0.0036950901, + 0.035366699 0.096890002 -0.0054567098, + 0.035366699 0.095285803 -0.0038622899, + 0.0328326 0.096810102 -0.0054708999, + 0.0328326 0.095212497 -0.00388753, + 0.0302257 0.096657403 -0.0053399699, + 0.0302257 0.095062301 -0.0037680599, + 0.027557701 0.096416697 -0.00506484, + 0.027557701 0.094818898 -0.0035053301, + 0.0248404 0.0960721 -0.0046483502, + 0.0248404 0.094463401 -0.00310214, + 0.0220857 0.0956055 -0.0040940298, + 0.0220857 0.0939897 -0.0025649699, + 0.019305199 0.095010102 -0.00340926, + 0.019305199 0.093383901 -0.00190515, + 0.0165099 0.0942761 -0.00260693, + 0.0165099 0.0926295 -0.00112764, + 0.0137106 0.093389101 -0.00169346, + 0.0137106 0.09172 -0.000238981, + 0.0109179 0.092342898 -0.00067659601, + 0.0532961 0.102597 -0.0028184201, + 0.0546159 0.103439 -0.00170614, + 0.055787299 0.104433 -0.00051351398, + 0.056809202 0.105585 0.00075051503, + 0.0576833 0.106898 0.0020777399, + 0.058412101 0.111162 0.00208417, + 0.058998398 0.115817 0.0023137301, + 0.059445001 0.120844 0.00277145, + 0.059757002 0.126221 0.00345901, + 0.0599402 0.131923 0.0043779402, + 0.059999999 0.137918 0.00555031, + 0.0599402 0.144177 0.0070033302, + 0.059757002 0.15067799 0.0087612299, + 0.059445001 0.15740301 0.0108323, + 0.0532961 0.0938823 0.0036832599, + 0.051830001 0.095598303 0.00100737, + 0.0532961 0.098189399 0.00046400499, + 0.0546159 0.0965809 0.0032069499, + 0.0546159 0.101117 -7.4272197e-005, + 0.055787299 0.099615797 0.00270767, + 0.055787299 0.102 0.00107241, + 0.056809202 0.100548 0.0038769499, + 0.056809202 0.103043 0.0022879899, + 0.0576833 0.101646 0.0051044198, + 0.0576833 0.10425 0.00356431, + 0.058412101 0.105622 0.0048933499, + 0.058412101 0.100246 0.0079249498, + 0.058998398 0.104348 0.00770223, + 0.058998398 0.11001 0.0048894198, + 0.059445001 0.108865 0.0076768999, + 0.059445001 0.11479 0.0050985799, + 0.059757002 0.113775 0.0078536803, + 0.059757002 0.119944 0.0055245901, + 0.0599402 0.119054 0.0082412995, + 0.0599402 0.12544499 0.0061741802, + 0.059999999 0.124675 0.0088683702, + 0.059999999 0.131263 0.0070708501, + 0.0599402 0.130603 0.00976374, + 0.0599402 0.137367 0.0082421098, + 0.059757002 0.136813 0.0109548, + 0.059757002 0.14373299 0.0097150104, + 0.059445001 0.14328299 0.012463, + 0.059445001 0.15033901 0.0115082, + 0.058998398 0.149997 0.0142847, + 0.058998398 0.15717401 0.0136081, + 0.058412101 0.15694401 0.0164013, + 0.058412101 0.16422699 0.0159938, + 0.058168899 0.171487 0.016846299, + 0.0576833 0.16411 0.0187931, + 0.0588204 0.171489 0.0139758, + 0.050219599 0.095308401 3.4244499e-007, + 0.048467699 0.095149003 -0.00091896299, + 0.0465803 0.093382902 -0.00011541, + 0.044564299 0.0934534 -0.00079483999, + 0.0424264 0.093532898 -0.0013657, + 0.040174201 0.093602099 -0.00181336, + 0.0378174 0.093643703 -0.0021292199, + 0.035366699 0.093640603 -0.0023074099, + 0.0328326 0.093574703 -0.0023435799, + 0.0302257 0.093426697 -0.00223554, + 0.027557701 0.093176603 -0.00198463, + 0.0248404 0.092819899 -0.00159707, + 0.0220857 0.092340998 -0.00108467, + 0.019305199 0.091718599 -0.00044898599, + 0.0165099 0.090945601 0.00030529199, + 0.0137106 0.090015098 0.0011699999, + 0.0109179 0.088920102 0.0021342, + 0.0137106 0.088276103 0.0025319699, + 0.0165099 0.0892267 0.00169055, + 0.019305199 0.090016797 0.000958135, + 0.0220857 0.090653598 0.00034448999, + 0.0248404 0.091145404 -0.000144039, + 0.027557701 0.091502003 -0.00050659297, + 0.0302257 0.091747001 -0.00074318203, + 0.0328326 0.091897301 -0.00084070099, + 0.035366699 0.091956198 -0.00079388003, + 0.0378174 0.091947101 -0.00060503703, + 0.040174201 0.091889501 -0.00027799001, + 0.0424264 0.091801398 0.000182106, + 0.044564299 0.091699503 0.00076797698, + 0.0465803 0.0916024 0.00146791, + 0.048467699 0.091529101 0.00226598, + 0.050219599 0.093379296 0.00159101, + 0.051830001 0.093561001 0.00260059, + 0.051830001 0.091558702 0.0041730399, + 0.050219599 0.089612201 0.0047284998, + 0.048467699 0.089677602 0.0038209099, + 0.0465803 0.089780897 0.0030006501, + 0.044564299 0.089904301 0.0022843501, + 0.0424264 0.0900295 0.00168514, + 0.040174201 0.0901381 0.0012134199, + 0.0378174 0.090212502 0.00087571802, + 0.035366699 0.090233497 0.00067674997, + 0.0328326 0.090176702 0.00062050502, + 0.0302257 0.090038002 0.00070481497, + 0.027557701 0.089798398 0.00091573998, + 0.0248404 0.089432701 0.00125418, + 0.0220857 0.088930897 0.00172145, + 0.019305199 0.088281199 0.0023149501, + 0.0165099 0.0874753 0.0030267199, + 0.0137106 0.086505502 0.00384561, + 0.0109179 0.085364901 0.0047585801, + 0.0137106 0.084705502 0.0051102801, + 0.0165099 0.085693903 0.0043125702, + 0.019305199 0.086514801 0.00362015, + 0.0220857 0.087175801 0.0030450299, + 0.0248404 0.087686002 0.0025966, + 0.027557701 0.088057302 0.00227913, + 0.0302257 0.088302098 0.0020930599, + 0.0328326 0.088429801 0.0020355, + 0.035366699 0.088468499 0.00210406, + 0.0378174 0.088440903 0.0023115899, + 0.040174201 0.088349998 0.0026591599, + 0.0424264 0.088219799 0.0031417799, + 0.044564299 0.088069797 0.0037533301, + 0.0465803 0.087919198 0.0044841501, + 0.048467699 0.087785996 0.0053223702, + 0.050219599 0.087687202 0.0062540602, + 0.051830001 0.087640204 0.0072617, + 0.0532961 0.089695603 0.0068156202, + 0.0546159 0.092134498 0.0064085699, + 0.055787299 0.0949504 0.0059876698, + 0.056809202 0.098100603 0.0055156401, + 0.0576833 0.099087402 0.0066964198, + 0.0576833 0.096577398 0.0083385799, + 0.056809202 0.0933045 0.0087943999, + 0.055787299 0.090362601 0.00917143, + 0.0546159 0.087797999 0.0095070004, + 0.0532961 0.085621998 0.0098542804, + 0.051830001 0.0856397 0.0087570501, + 0.050219599 0.085723102 0.0077231899, + 0.048467699 0.085855 0.0067716902, + 0.0465803 0.0860193 0.0059174998, + 0.044564299 0.086198904 0.00517336, + 0.0424264 0.086374797 0.0045504202, + 0.040174201 0.086526103 0.0040579201, + 0.0378174 0.086627901 0.00370237, + 0.035366699 0.086680301 0.0034831399, + 0.0328326 0.086658299 0.0033863301, + 0.0302257 0.0865293 0.0034177799, + 0.027557701 0.086283401 0.0035826501, + 0.0248404 0.085908502 0.0038820701, + 0.0220857 0.085391901 0.0043140198, + 0.019305199 0.084720403 0.0048726499, + 0.0165099 0.0838852 0.0055476902, + 0.0137106 0.082878701 0.0063255699, + 0.0109179 0.081695303 0.0071902801, + 0.0575951 0.17148501 0.018901899, + 0.057667602 0.17148501 0.0186422, + 0.058982901 0.17149 0.0130517, + 0.059744701 0.17149401 0.0075329999, + 0.059999801 0.171498 0.0022789, + 0.059996702 0.171498 0.00213663, + 0.059749398 0.17150301 -0.00326027, + -0.053653602 -0.0268292 0.0144786, + -0.0268177 0.17145599 0.0557901, + -0.0053910101 0.171451 0.061882298, + -0.011126 0.0487388 0.0095388098, + -0.016514 0.047186598 0.0095375804, + -0.0216942 0.045040801 0.0095358696, + -0.0266016 0.0423286 0.0095337098, + -0.0311745 0.039083999 0.0095311198, + -0.0353553 0.0353477 0.0095281499, + -0.039091598 0.0311669 0.0095248204, + -0.042336199 0.026594 0.0095211798, + -0.045048401 0.021686601 0.0095172701, + -0.047194201 0.016506299 0.00951315, + -0.0487464 0.0111184 0.0095088603, + -0.049685601 0.0055906698 0.0095044496, + -0.050000001 -7.5646799e-006 0.0094999997, + -0.049685601 -0.0056058001 0.0094955396, + -0.0487464 -0.0111336 0.00949114, + -0.047194201 -0.0165215 0.0094868504, + -0.045048401 -0.0217018 0.0094827199, + -0.042336199 -0.026609199 0.0094788102, + -0.039091598 -0.031182099 0.0094751697, + -0.0353553 -0.035362899 0.0094718402, + -0.0311745 -0.039099101 0.0094688702, + -0.0266016 -0.042343799 0.0094662802, + -0.0216942 -0.045056 0.0094641196, + -0.016514 -0.047201701 0.0094624199, + -0.011126 -0.048753899 0.0094611803, + -0.00559822 -0.0496931 0.0094604297, + 0 -0.0500075 0.0094601801, + 0.00559822 -0.0496931 0.0094604297, + 0.011126 -0.048753899 0.0094611803, + 0.016514 -0.047201701 0.0094624199, + 0.0216942 -0.045056 0.0094641196, + 0.0266016 -0.042343799 0.0094662802, + 0.0311745 -0.039099101 0.0094688702, + 0.0353553 -0.035362899 0.0094718402, + 0.039091598 -0.031182099 0.0094751697, + 0.042336199 -0.026609199 0.0094788102, + 0.045048401 -0.0217018 0.0094827199, + 0.047194201 -0.0165215 0.0094868504, + 0.0487464 -0.0111336 0.00949114, + 0.049685601 -0.0056058001 0.0094955396, + 0.050000001 -7.5646799e-006 0.0094999997, + 0.049685601 0.0055906698 0.0095044496, + 0.0487464 0.0111184 0.0095088603, + 0.047194201 0.016506299 0.00951315, + 0.045048401 0.021686601 0.0095172701, + 0.042336199 0.026594 0.0095211798, + 0.039091598 0.0311669 0.0095248204, + 0.0353553 0.0353477 0.0095281499, + 0.0311745 0.039083999 0.0095311198, + 0.0266016 0.0423286 0.0095337098, + 0.0216942 0.045040801 0.0095358696, + 0.016514 0.047186598 0.0095375804, + 0.011126 0.0487388 0.0095388098, + 0.00559822 0.049678002 0.0095395604, + 0 0.049992401 0.00953981, + -0.00559822 0.049678002 0.0095395604 ] + + } + normal + Normal { + vector [ 0.98486513 0.0057662507 0.17322701, + 0.98728687 0.0014080199 0.15894198, + 0.84375131 -0.00033863712 0.53673416, + 0.9601441 0.0034589805 -0.27948403, + 0.044446189 -0.7390008 -0.6722368, + 0.050594583 -0.71511078 -0.69717777, + 0.069329202 -0.71430498 -0.696392, + 0.077281103 -0.68883401 -0.720788, + 0.099514112 -0.68747008 -0.71936208, + 0.10923901 -0.66033208 -0.74298608, + 0.13510205 -0.65821725 -0.74060625, + 0.14639993 -0.62965173 -0.76295865, + 0.175826 -0.62659401 -0.75925303, + 0.18838297 -0.59700596 -0.77980489, + 0.221793 -0.59275001 -0.77424502, + 0.23538603 -0.56214404 -0.79283512, + 0.27175301 -0.556629 -0.78505701, + 0.28600401 -0.52530801 -0.80140698, + 0.32517102 -0.51841605 -0.79089111, + 0.33983296 -0.48634395 -0.8049739, + 0.38153493 -0.47800195 -0.7911669, + 0.39609194 -0.44574395 -0.80275989, + 0.43959895 -0.43602693 -0.7852599, + 0.45356289 -0.4041709 -0.79430884, + 0.49790195 -0.39329094 -0.77292687, + 0.51095915 -0.36207408 -0.77963018, + 0.55515224 -0.35034117 -0.75436538, + 0.5669027 -0.32043085 -0.75891066, + 0.61049592 -0.30807498 -0.72964692, + 0.62069124 -0.28002807 -0.73234326, + 0.66319698 -0.26730901 -0.69908202, + 0.67174125 -0.24148008 -0.70032221, + 0.71194679 -0.22891192 -0.66387576, + 0.71897024 -0.20518407 -0.66406423, + 0.756437 -0.193088 -0.62491602, + 0.7620157 -0.17165194 -0.62439376, + 0.79673785 -0.16019195 -0.58270687, + 0.80108321 -0.14082003 -0.58175212, + 0.8329379 -0.13018899 -0.53783393, + 0.83616179 -0.11313997 -0.5366869, + 0.8646419 -0.10363199 -0.49158394, + 0.86696601 -0.088679701 -0.49041399, + 0.89152074 -0.080603577 -0.44575089, + 0.8954733 -0.072463021 -0.43917716, + 0.91544658 -0.065515473 -0.39707083, + 0.91740012 -0.045156803 -0.39539605, + 0.93684989 -0.039683595 -0.34747297, + 0.95311815 -0.033736903 -0.30071202, + 0.93640321 -0.039124813 -0.3487381, + 0.93489587 -0.056742191 -0.35035697, + 0.91461378 -0.064640686 -0.3991279, + 0.91173977 -0.086672977 -0.40151992, + 0.91065568 -0.085650668 -0.40419084, + 0.93204033 -0.075117432 -0.35448313, + 0.93425721 -0.056015115 -0.35217309, + 0.951666 -0.048245002 -0.30332199, + 0.95278174 -0.033270493 -0.30182794, + 0.96681666 -0.027990991 -0.25393292, + 0.98568809 -0.0019067603 -0.16856901, + 0.98570651 -0.0019042491 -0.16846092, + 0.97859126 -0.0067361714 -0.20570305, + 0.97846878 -0.013418797 -0.20595795, + 0.96729851 -0.016490592 -0.25310388, + 0.9762311 -0.0029699905 -0.21671203, + 0.96763152 -0.0082392162 -0.25223288, + 0.96744198 -0.0167369 -0.25253901, + 0.95380026 -0.019868005 -0.29978406, + 0.95427877 -0.0096322279 -0.29876295, + 0.95400375 -0.020173695 -0.29911494, + 0.93777287 -0.023366999 -0.34646198, + 0.9338994 -0.0064338134 -0.35747817, + 0.95026821 -0.0052135312 -0.31138906, + 0.93842614 -0.010962901 -0.34530604, + 0.93804389 -0.023731995 -0.34570298, + 0.9191736 -0.026973886 -0.39292783, + 0.91797626 -0.04581831 -0.39398009, + 0.89595073 -0.051307488 -0.44117987, + 0.89415377 -0.068728387 -0.44245389, + 0.86942458 -0.075835966 -0.48821077, + 0.86750114 -0.090118505 -0.48920405, + 0.8396101 -0.098407611 -0.53420109, + 0.83685815 -0.11496303 -0.5352121, + 0.80568618 -0.12439703 -0.57913309, + 0.80196089 -0.14307098 -0.57999092, + 0.76791114 -0.15341301 -0.62191409, + 0.76303685 -0.17424396 -0.62242585, + 0.72634542 -0.18529111 -0.66188341, + 0.72019017 -0.20825605 -0.66178221, + 0.68075705 -0.21988402 -0.69872808, + 0.67317206 -0.24506202 -0.69769907, + 0.63130409 -0.25701004 -0.73171103, + 0.62231004 -0.28403902 -0.72941905, + 0.57909131 -0.29582915 -0.75969636, + 0.5686571 -0.32471609 -0.75577021, + 0.52461076 -0.33607185 -0.78220165, + 0.51283693 -0.36656198 -0.77629286, + 0.46852487 -0.37722191 -0.79886681, + 0.455639 -0.40896201 -0.79066002, + 0.41168022 -0.41868421 -0.80945837, + 0.39829794 -0.45058995 -0.79895389, + 0.35578704 -0.45909405 -0.81403214, + 0.34214011 -0.49111718 -0.80108929, + 0.301893 -0.498274 -0.81276298, + 0.2884171 -0.52995616 -0.7974723, + 0.2506569 -0.53580683 -0.80627668, + 0.23786491 -0.5665428 -0.78895468, + 0.20279998 -0.57116294 -0.79538989, + 0.19088708 -0.60106325 -0.7760703, + 0.15961394 -0.60447276 -0.78047168, + 0.14889009 -0.63331634 -0.75943547, + 0.120738 -0.63576901 -0.76237798, + 0.11145101 -0.66328204 -0.74002403, + 0.087082408 -0.66490406 -0.74183506, + 0.079314001 -0.69128197 -0.71821898, + 0.058550425 -0.69227737 -0.71925235, + 0.052503712 -0.71718121 -0.69490618, + 0.035300408 -0.7177242 -0.69543219, + 0.031334601 -0.73936898 -0.672571, + 0.014950496 -0.75139982 -0.6596778, + 0.014729604 -0.7514022 -0.65968019, + 0.0097830202 -0.791628 -0.61092502, + 0.002061299 -0.79166365 -0.61095369, + 0.00043170512 -0.82772416 -0.56113511, + -0.00053589407 -0.8277241 -0.56113505, + -0.0021736394 -0.79168868 -0.61092079, + -0.0098244101 -0.79165298 -0.610892, + -0.013568505 -0.76155329 -0.64796025, + -0.84927589 -0.063760094 -0.52408493, + -0.218952 -0.0058585699 -0.97571802, + -0.96729976 -0.016186496 -0.25311893, + -0.96679562 -0.028253391 -0.25398391, + -0.9527421 -0.033585504 -0.30191803, + -0.95161235 -0.048673119 -0.30342212, + -0.93417579 -0.056515183 -0.3523089, + -0.93199414 -0.075242706 -0.35457802, + -0.90675473 -0.10884498 -0.40736791, + -0.91060024 -0.085790925 -0.40428609, + -0.911708 -0.086831801 -0.40155801, + -0.91453272 -0.065211579 -0.39922085, + -0.9348231 -0.057248209 -0.35046902, + -0.93635076 -0.039487988 -0.34883791, + -0.95307863 -0.03405039 -0.30080187, + -0.95379514 -0.019504203 -0.29982403, + -0.96744126 -0.016429704 -0.25256205, + -0.96764112 -0.0072000711 -0.25222802, + -0.97569788 -0.0015037598 -0.21911497, + -0.97554713 -0.0015241102 -0.21978503, + -0.97554791 -0.00057334395 -0.21978597, + -0.97569889 -0.00057387695 -0.21911497, + -0.97554612 -0.00057585904 -0.21979403, + -0.97554535 -0.0015161206 -0.21979308, + -0.97859746 -0.0059899529 -0.2056971, + -0.97846991 -0.013171298 -0.20596898, + -0.9872545 -0.0047520725 -0.15907907, + -0.98718137 -0.010015504 -0.15928806, + -0.97837549 -0.012979593 -0.2064289, + -0.97804552 -0.022649689 -0.2071569, + -0.96655446 -0.027874513 -0.25494212, + -0.96575898 -0.040388599 -0.25627801, + -0.95113033 -0.048071019 -0.30502513, + -0.94951385 -0.063998491 -0.30712798, + -0.93114674 -0.074385785 -0.3569769, + -0.92817986 -0.094371088 -0.35996696, + -0.9053607 -0.10768797 -0.41076186, + -0.90024269 -0.13261996 -0.41469884, + -0.86885202 -0.18266501 -0.460141, + -0.8278138 -0.20699196 -0.52141988, + -0.82033998 -0.22834501 -0.52430999, + -0.78396171 -0.24788392 -0.5691728, + -0.77406412 -0.27227902 -0.57156706, + -0.73374999 -0.29219601 -0.61337799, + -0.72112477 -0.31948087 -0.61474478, + -0.67791176 -0.33900389 -0.65231276, + -0.66243201 -0.36880001 -0.65205097, + -0.61711806 -0.38738406 -0.68490803, + -0.59876192 -0.41930893 -0.68239594, + -0.55213183 -0.43649685 -0.71036679, + -0.53099102 -0.470184 -0.704965, + -0.48456699 -0.485374 -0.727741, + -0.46127388 -0.51988888 -0.71898681, + -0.4164362 -0.53272521 -0.73673934, + -0.39143506 -0.56762904 -0.72427607, + -0.34943098 -0.57796496 -0.73746496, + -0.3237029 -0.61227286 -0.72134483, + -0.28547505 -0.62018514 -0.73066717, + -0.26027298 -0.65279591 -0.71141791, + -0.2259061 -0.65861928 -0.71776533, + -0.20352195 -0.68723685 -0.69734085, + -0.17385499 -0.69123894 -0.70140094, + -0.15352498 -0.71743196 -0.67950094, + -0.12743801 -0.72011906 -0.68204707, + -0.107861 -0.74591899 -0.65724498, + -0.085920967 -0.74752176 -0.65865678, + -0.067871191 -0.77225989 -0.63167095, + -0.050246771 -0.77306652 -0.63233167, + -0.03378889 -0.79699069 -0.60304576, + -0.021165792 -0.79726768 -0.60325474, + -0.0069938824 -0.81963032 -0.57285017, + 0.025421306 -0.84545517 -0.53344113, + 0.016303806 -0.84561628 -0.53354216, + 0.0014338304 -0.81964916 -0.57286412, + -0.002833141 -0.82500929 -0.56511217, + -0.014413504 -0.8034482 -0.59520012, + -0.025276197 -0.80327487 -0.59507191, + -0.038985308 -0.78037119 -0.62410015, + -0.054205112 -0.77981716 -0.62365609, + -0.070053168 -0.75538862 -0.65152168, + -0.089282289 -0.75422388 -0.65051895, + -0.10672799 -0.72887397 -0.67627794, + -0.13031803 -0.7268092 -0.6743632, + -0.14862406 -0.70122623 -0.69727522, + -0.17636596 -0.69798684 -0.69405282, + -0.19676192 -0.67006278 -0.71575177, + -0.2281101 -0.66540432 -0.71077633, + -0.25123385 -0.63382864 -0.7315346, + -0.2874859 -0.62718779 -0.72386974, + -0.31167594 -0.59360886 -0.74194783, + -0.35124287 -0.58492279 -0.73109078, + -0.3752639 -0.55050987 -0.74573183, + -0.41810185 -0.5395118 -0.73083377, + -0.44097415 -0.50517619 -0.74184823, + -0.48612106 -0.49187705 -0.72231805, + -0.50727493 -0.45814595 -0.72991395, + -0.55362308 -0.44272006 -0.70533705, + -0.57268685 -0.40997291 -0.70989585, + -0.61849308 -0.39297706 -0.68046707, + -0.63490701 -0.362176 -0.68243802, + -0.67920399 -0.344062 -0.64830798, + -0.69296598 -0.31542599 -0.64830899, + -0.73494518 -0.29668206 -0.60978311, + -0.74610198 -0.27055201 -0.60838598, + -0.78501886 -0.25171396 -0.56602591, + -0.79374516 -0.22835106 -0.56375915, + -0.8286981 -0.21012303 -0.51875603, + -0.8351891 -0.18993503 -0.51612407, + -0.86609513 -0.17263801 -0.46912205, + -0.8724857 -0.14883894 -0.46541983, + -0.87904233 -0.15340605 -0.45138815, + -0.8416732 -0.17375605 -0.51126814, + -0.83605117 -0.19283704 -0.51364613, + -0.80231488 -0.20979597 -0.55881697, + -0.79476011 -0.23181103 -0.56091005, + -0.7570979 -0.24952397 -0.60377192, + -0.74724919 -0.27455306 -0.6051771, + -0.70656675 -0.29236087 -0.64442879, + -0.69426036 -0.32008114 -0.64463228, + -0.65112275 -0.33753589 -0.67978579, + -0.63634276 -0.36749589 -0.67824376, + -0.59126997 -0.38420194 -0.70907593, + -0.574224 -0.41576901 -0.70526803, + -0.52822393 -0.43121094 -0.73146194, + -0.50891691 -0.46434993 -0.72483295, + -0.46364579 -0.47794577 -0.74605662, + -0.44273689 -0.51168787 -0.73631483, + -0.39913291 -0.5232389 -0.75293684, + -0.37713382 -0.55707574 -0.73988962, + -0.33624592 -0.56646788 -0.75236481, + -0.31367296 -0.60007393 -0.73588091, + -0.27569595 -0.60747689 -0.74495882, + -0.25338703 -0.64008605 -0.72531706, + -0.22001192 -0.64546776 -0.73141378, + -0.199085 -0.67601597 -0.70948398, + -0.16983296 -0.67980385 -0.71345884, + -0.15131409 -0.7072804 -0.69054943, + -0.12646504 -0.70977426 -0.69298422, + -0.10996602 -0.73520005 -0.66887105, + -0.088431098 -0.73678797 -0.67031598, + -0.073489033 -0.76119131 -0.64435023, + -0.056034598 -0.76205599 -0.645082, + -0.042650595 -0.78572887 -0.61709893, + -0.029706892 -0.78609782 -0.61738789, + -0.018362192 -0.80844671 -0.58828276, + -0.014634197 -0.80849582 -0.5883199, + -0.021882806 -0.79095715 -0.61148012, + -0.033321407 -0.79070717 -0.61128712, + -0.0443132 -0.76779199 -0.63916498, + -0.059541684 -0.76718384 -0.63865781, + -0.072322488 -0.74324483 -0.66509885, + -0.091580547 -0.74206436 -0.66404331, + -0.10592498 -0.7172538 -0.68871385, + -0.12932397 -0.71525484 -0.6867938, + -0.14554693 -0.68872565 -0.71026266, + -0.17253406 -0.68569922 -0.70714122, + -0.19137797 -0.65590197 -0.73018295, + -0.22246006 -0.65150815 -0.72529221, + -0.24274294 -0.6198619 -0.74622184, + -0.27798194 -0.6137889 -0.73891079, + -0.29905888 -0.5807898 -0.75713068, + -0.3383221 -0.57275414 -0.7466532, + -0.35913908 -0.53953409 -0.76152617, + -0.40107891 -0.52956688 -0.74745882, + -0.421426 -0.49597201 -0.75921798, + -0.465446 -0.484056 -0.74097902, + -0.48456824 -0.45088521 -0.74959737, + -0.52993017 -0.43711615 -0.72670722, + -0.54731882 -0.40496784 -0.73242277, + -0.59284788 -0.38967291 -0.70475984, + -0.60830873 -0.35877088 -0.70798576, + -0.65257704 -0.34250802 -0.67589307, + -0.66577423 -0.31355911 -0.67707121, + -0.70789796 -0.29681796 -0.64092094, + -0.7187978 -0.27017093 -0.64057583, + -0.75826585 -0.25335497 -0.60070294, + -0.76687253 -0.22955887 -0.59934062, + -0.80331272 -0.21301892 -0.55615783, + -0.80988789 -0.19211297 -0.55423295, + -0.84250188 -0.17642799 -0.50898296, + -0.84736788 -0.15834698 -0.50684696, + -0.87616056 -0.14373893 -0.46008879, + -0.88097429 -0.12214004 -0.45712814, + -0.85858691 -0.13471799 -0.49465093, + -0.88268977 -0.12349497 -0.45343989, + -0.88748258 -0.097399652 -0.45043078, + -0.8658728 -0.10762598 -0.48854989, + -0.88882267 -0.098587364 -0.44752085, + -0.89235878 -0.074047484 -0.44521087, + -0.91534811 -0.066063508 -0.39720705, + -0.91732711 -0.045569602 -0.39551806, + -0.93679774 -0.040045287 -0.34757191, + -0.93776524 -0.022944206 -0.3465111, + -0.95399767 -0.019808793 -0.29915887, + -0.95428914 -0.0083306106 -0.29876903, + -0.96358752 0.0054751672 -0.26733688, + -0.96359766 -0.0023844391 -0.26734591, + -0.96359938 -0.0023843108 -0.26734009, + -0.96360177 0.0015751896 -0.26733693, + -0.96014446 0.0033655616 -0.27948412, + -0.88267559 0.0043434883 -0.46996278, + -0.86981845 0.00041111177 -0.4933717, + -0.86982512 0.00041164106 -0.49336007, + -0.86979687 -0.0077623092 -0.49334893, + -0.86979002 -0.0077625602 -0.493361, + -0.81730288 -0.0012550598 -0.57620692, + -0.81730402 0.00087633799 -0.57620603, + -0.81731111 0.00087685313 -0.57619607, + -0.81731039 -0.0012549706 -0.57619631, + -0.82496685 -0.013870996 -0.56501091, + 0.81910884 0.0011682998 -0.57363689, + 0.81906319 0.0011651902 -0.5737021, + 0.81904513 -0.0062643308 -0.57369506, + 0.81909043 -0.0062633627 -0.57363027, + 0.82482386 -0.016467499 -0.56514996, + -0.79056281 -0.037186991 -0.61125088, + -0.7894398 -0.054081988 -0.6114409, + -0.75626785 -0.057644486 -0.65171784, + -0.75455511 -0.07624881 -0.65179205, + -0.71875077 -0.080783769 -0.69055879, + -0.71633595 -0.10120498 -0.69037694, + -0.67804629 -0.10661105 -0.72724634, + -0.67484277 -0.12888396 -0.72661978, + -0.63465071 -0.13496894 -0.76092166, + -0.63058919 -0.15908705 -0.75963718, + -0.58879304 -0.16568102 -0.79112113, + -0.58382487 -0.19165996 -0.7889328, + -0.54043204 -0.19862503 -0.8176071, + -0.53465283 -0.22600593 -0.81428969, + -0.489907 -0.233147 -0.84002, + -0.48338905 -0.26178604 -0.8353461, + -0.43855122 -0.26875412 -0.85758042, + -0.43140894 -0.29858997 -0.85131091, + -0.38681108 -0.30521005 -0.87018615, + -0.37928885 -0.33575687 -0.86221069, + -0.33517608 -0.34188208 -0.87793726, + -0.32748398 -0.37294897 -0.8681379, + -0.28438604 -0.37841704 -0.88086611, + -0.27678898 -0.40974793 -0.86919188, + -0.23549403 -0.41441506 -0.8790921, + -0.22824411 -0.4457612 -0.86556441, + -0.18920895 -0.44957587 -0.87297285, + -0.18259795 -0.48050189 -0.85777384, + -0.14592107 -0.48348719 -0.86310327, + -0.14023705 -0.51347917 -0.84656531, + -0.10614298 -0.51567388 -0.8501848, + -0.10154404 -0.54471117 -0.83245331, + -0.070691392 -0.54617196 -0.83468491, + -0.067352109 -0.57386005 -0.8161791, + -0.039132915 -0.57472515 -0.81741029, + -0.0370907 -0.601215 -0.798226, + -0.011650799 -0.60158896 -0.7987209, + -0.010959798 -0.62689483 -0.77902681, + 0.011538097 -0.62689078 -0.77902168, + 0.012230098 -0.60152692 -0.79875886, + 0.037730284 -0.60114378 -0.79824972, + 0.039772484 -0.57465082 -0.81743169, + 0.068008319 -0.5737741 -0.81618518, + 0.071347818 -0.54608011 -0.8346892, + 0.10238998 -0.54459786 -0.83242381, + 0.10694101 -0.51579207 -0.85001314, + 0.14085598 -0.51359391 -0.84639287, + 0.14655803 -0.48350513 -0.86298519, + 0.18322301 -0.48050806 -0.85763711, + 0.18980895 -0.44969189 -0.87278283, + 0.22879508 -0.44586915 -0.8653633, + 0.23605503 -0.41446906 -0.87891614, + 0.27713397 -0.40981594 -0.86904991, + 0.28468686 -0.37869483 -0.88064957, + 0.32786104 -0.37320602 -0.86788511, + 0.33552998 -0.34222096 -0.87766987, + 0.37959492 -0.33609092 -0.86194581, + 0.38710892 -0.30556893 -0.86992782, + 0.43163291 -0.29894495 -0.85107285, + 0.43880701 -0.26896 -0.85738498, + 0.48365277 -0.26197988 -0.8351326, + 0.49021405 -0.23312803 -0.83984613, + 0.53490019 -0.22599107 -0.81413132, + 0.54076213 -0.19819905 -0.81749219, + 0.58411211 -0.19124804 -0.78882021, + 0.58914894 -0.16484898 -0.79102987, + 0.63093793 -0.15828098 -0.75951588, + 0.63501418 -0.13399804 -0.76079017, + 0.6752072 -0.12795003 -0.72644615, + 0.67838693 -0.10573999 -0.72705597, + 0.71667194 -0.10037199 -0.69014996, + 0.71903181 -0.080332175 -0.69031882, + 0.75478983 -0.075822987 -0.65156984, + 0.75643802 -0.0578954 -0.65149802, + 0.78957999 -0.054317798 -0.61123902, + 0.79064769 -0.038371686 -0.61106777, + 0.82141781 -0.035742994 -0.56920588, + 0.8220129 -0.022022597 -0.56904292, + 0.79165828 -0.023627309 -0.61050725, + 0.79096317 -0.039023809 -0.61061811, + 0.7581073 -0.041591916 -0.65080225, + 0.75691414 -0.058862407 -0.65085804, + 0.72150785 -0.062365286 -0.68959183, + 0.71969867 -0.081666663 -0.68946666, + 0.68174094 -0.086054996 -0.72651494, + 0.67921394 -0.10737199 -0.72604394, + 0.63937968 -0.11248495 -0.76061863, + 0.63602597 -0.13597098 -0.7595939, + 0.59455526 -0.14167805 -0.79147428, + 0.59034395 -0.16714099 -0.78965688, + 0.54721093 -0.17332098 -0.8188529, + 0.54211617 -0.20075108 -0.81597131, + 0.49752519 -0.20723608 -0.84233129, + 0.49171188 -0.23588593 -0.83819884, + 0.44681299 -0.242351 -0.86117601, + 0.44044501 -0.27188399 -0.85562098, + 0.39556095 -0.27814096 -0.8753109, + 0.38877416 -0.30843711 -0.86817127, + 0.34428787 -0.31430587 -0.8846907, + 0.33730498 -0.34514698 -0.87584186, + 0.29344106 -0.3504931 -0.88940823, + 0.28650615 -0.38154519 -0.87882739, + 0.24449691 -0.38615385 -0.88944173, + 0.237873 -0.41715801 -0.87715203, + 0.19767907 -0.42101014 -0.88525331, + 0.19151992 -0.4520708 -0.87117857, + 0.15366597 -0.45512688 -0.87706679, + 0.14827304 -0.48573411 -0.86143917, + 0.11264802 -0.48803705 -0.8655231, + 0.10830402 -0.51744008 -0.84883809, + 0.075594507 -0.51901305 -0.85141712, + 0.072396912 -0.54725909 -0.83382618, + 0.042531397 -0.54820192 -0.83526391, + 0.040557984 -0.57546979 -0.81681669, + 0.013329102 -0.57589203 -0.81741714, + 0.012666699 -0.60195196 -0.79843187, + -0.012028898 -0.60195696 -0.79843789, + -0.012690303 -0.57592613 -0.8174032, + -0.03988982 -0.57551432 -0.81681842, + -0.041863188 -0.54824889 -0.83526683, + -0.071710661 -0.54731679 -0.83384758, + -0.074912339 -0.51903921 -0.85146141, + -0.10763402 -0.51747805 -0.84890014, + -0.11199001 -0.48800406 -0.86562711, + -0.14763197 -0.48571187 -0.86156183, + -0.15303901 -0.45503506 -0.87722415, + -0.19094296 -0.45198688 -0.8713488, + -0.19712608 -0.42081514 -0.88546932, + -0.23722997 -0.41698393 -0.87740886, + -0.24388503 -0.38589707 -0.8897211, + -0.2862049 -0.38126585 -0.87904668, + -0.29313993 -0.3501749 -0.88963276, + -0.33697093 -0.34484392 -0.87608975, + -0.34397188 -0.31393689 -0.88494468, + -0.38847592 -0.30807894 -0.86843181, + -0.39523315 -0.2779291 -0.87552631, + -0.44018689 -0.27167293 -0.85582083, + -0.44650587 -0.24239895 -0.86132181, + -0.49142307 -0.23593603 -0.83835411, + -0.49719518 -0.20754008 -0.84245127, + -0.54172719 -0.20106107 -0.81615329, + -0.54676503 -0.17406 -0.81899399, + -0.58992893 -0.16785799 -0.78981489, + -0.59412575 -0.14260796 -0.79162973, + -0.63562793 -0.13686799 -0.75976586, + -0.63899696 -0.11337698 -0.76080787, + -0.67886722 -0.10822704 -0.72624123, + -0.68145204 -0.086499505 -0.72673309, + -0.7194072 -0.082094125 -0.68972015, + -0.72128719 -0.062095314 -0.68984717, + -0.75674164 -0.058605969 -0.65108168, + -0.75799215 -0.040356304 -0.65101403, + -0.79088914 -0.037862603 -0.61078703, + -0.79161817 -0.021201706 -0.6106481, + -0.82199073 -0.019761093 -0.56915784, + -0.82136589 -0.034637798 -0.56934893, + -0.82426268 -0.040977087 -0.56472284, + -0.84939867 -0.038194086 -0.52636784, + -0.85040081 -0.013625497 -0.5259589, + -0.84352469 -0.015667494 -0.53686184, + -0.84363383 0.00040260391 -0.53691888, + -0.84458399 0.000401417 -0.53542298, + -0.8445462 -0.0090504121 -0.53540611, + -0.84456915 -0.009049641 -0.53537005, + -0.84460688 0.00039644694 -0.53538692, + -0.82967269 0.0044084587 -0.55823284, + -0.926314 0.0042038802 -0.37672901, + -0.98379302 0.00337071 -0.179276, + -0.98514599 0.0044956398 -0.17166001, + -0.98515499 -0.00069902599 -0.171666, + -0.98516226 -0.00069826818 -0.17162405, + -0.98516077 0.0020997296 -0.17162095, + -0.99237537 -0.00075980031 -0.12325004, + -0.99237567 -7.566507e-005 -0.12324996, + -0.99239498 -7.2922303e-005 -0.123094, + -0.99239463 -0.00076340168 -0.12309495, + -0.99239022 -0.00076337415 -0.12313103, + -0.99239051 -7.100356e-005 -0.12312994, + -0.99358255 -0.0034571884 -0.11305594, + -0.9935475 -0.0070007034 -0.11320105, + -0.98712498 -0.0098730801 -0.159646, + -0.98693025 -0.017224304 -0.16022505, + -0.97788525 -0.022354206 -0.20794405, + -0.97736478 -0.032375291 -0.20906895, + -0.96541226 -0.039899509 -0.25765705, + -0.96427548 -0.053100627 -0.25952512, + -0.94886488 -0.063279793 -0.30927497, + -0.94666225 -0.080287822 -0.31206506, + -0.9270829 -0.093400992 -0.36303398, + -0.92312258 -0.11505995 -0.36688682, + -0.89849079 -0.13136397 -0.41887692, + -0.89169568 -0.15882695 -0.42385486, + -0.86139327 -0.17823306 -0.47564119, + -0.8529017 -0.20479693 -0.48022583, + -0.8194111 -0.22485603 -0.52726203, + -0.81081879 -0.24743994 -0.5304209, + -0.77301562 -0.26819187 -0.57490867, + -0.76178366 -0.29372886 -0.5774157, + -0.71995115 -0.3146731 -0.61858809, + -0.70573705 -0.34306702 -0.61987108, + -0.66115892 -0.36329296 -0.65641993, + -0.64373207 -0.39434305 -0.65582204, + -0.59743011 -0.41324008 -0.68724817, + -0.57681084 -0.44647884 -0.68406576, + -0.529603 -0.46362299 -0.710334, + -0.50625885 -0.49813783 -0.70396078, + -0.45980695 -0.51294595 -0.72488892, + -0.43417194 -0.54822195 -0.71480596, + -0.389862 -0.56041998 -0.73071003, + -0.36274478 -0.59559864 -0.71671361, + -0.32201213 -0.60508823 -0.72813225, + -0.29487905 -0.63876218 -0.7106542, + -0.25841993 -0.64577985 -0.71846181, + -0.23416294 -0.67512685 -0.69955081, + -0.201395 -0.680206 -0.70481199, + -0.17956005 -0.70646816 -0.68458819, + -0.15087 -0.70991999 -0.68793303, + -0.12945703 -0.73592716 -0.6645692, + -0.10461298 -0.73809981 -0.6665318, + -0.083856799 -0.76387 -0.63989902, + -0.064298682 -0.76498383 -0.64083183, + -0.045321979 -0.78950864 -0.61206371, + -0.029716689 -0.78997171 -0.61242276, + -0.012629001 -0.81339413 -0.58157605, + -0.0027692397 -0.81345588 -0.58161992, + 0.015432105 -0.84035927 -0.54181015, + 0.028167091 -0.84012568 -0.54165983, + 0.027050281 -0.83824939 -0.54461557, + 0.022000089 -0.83835357 -0.54468274, + 0.017818591 -0.83621657 -0.54810977, + 0.02585119 -0.8360697 -0.54801381, + 0.01722909 -0.81179255 -0.58369166, + 0.019185493 -0.8117637 -0.58367074, + 0.012683903 -0.78445417 -0.62005711, + 0.012077798 -0.78445989 -0.62006193, + 0.0079767527 -0.7541253 -0.65668225, + 0.0040366193 -0.75414288 -0.65669793, + 0.0026217701 -0.72090006 -0.69303405, + -0.0025530208 -0.72090024 -0.69303423, + -0.0039509395 -0.75415289 -0.65668696, + -0.0078932187 -0.75413591 -0.65667093, + -0.011985103 -0.78456318 -0.61993313, + -0.013173693 -0.7845515 -0.61992365, + -0.019631898 -0.81167889 -0.58377391, + -0.0173073 -0.81171298 -0.58380002, + -0.017844802 -0.83614713 -0.54821503, + -0.025924604 -0.83599913 -0.54811805, + -0.003917099 -0.81675184 -0.57697588, + 0.00017422595 -0.81675768 -0.57698083, + -0.015172392 -0.84998655 -0.52658576, + -0.02100189 -0.84989661 -0.52653074, + -0.017201407 -0.83964241 -0.54286724, + -0.019321889 -0.8396095 -0.54284668, + -0.012980998 -0.81443983 -0.58010286, + -0.011892695 -0.81445068 -0.58011085, + -0.0078961411 -0.78624213 -0.61786807, + -0.0037494705 -0.78626114 -0.61788309, + -0.00237409 -0.754798 -0.65595299, + 0.0024354397 -0.75479788 -0.65595293, + 0.0038306015 -0.78615928 -0.61801225, + 0.007989781 -0.78613913 -0.61799806, + 0.012012898 -0.8143869 -0.58019793, + 0.012881695 -0.81437868 -0.58019084, + 0.019229989 -0.83956051 -0.54292572, + 0.017426603 -0.83958811 -0.54294407, + 0.021234006 -0.8498472 -0.52660114, + 0.01507479 -0.84994251 -0.52665973, + 0.0034209595 -0.82500786 -0.56511092, + 0.0071318392 -0.82088286 -0.57105196, + 0.0010312705 -0.82090342 -0.57106632, + 0.0126224 -0.85334003 -0.52120203, + 0.015535897 -0.8533048 -0.52118087, + 0.012598698 -0.84214187 -0.53910893, + 0.011778698 -0.84214985 -0.53911495, + 0.0078451894 -0.81600189 -0.57799596, + 0.00391735 -0.81602103 -0.57800901, + 0.002539519 -0.7866587 -0.61738276, + -0.0027228799 -0.78665888 -0.61738193, + -0.0040878914 -0.8159973 -0.5780412, + -0.0079487618 -0.81597817 -0.57802814, + -0.011873202 -0.84211516 -0.53916711, + -0.012916093 -0.84210449 -0.53915972, + -0.015847804 -0.85323417 -0.52128714, + -0.012672497 -0.8532728 -0.52131087, + -0.00111839 -0.82091802 -0.57104498, + 0.0095078181 -0.82088184 -0.57101887, + 0.022097994 -0.79085082 -0.61160988, + 0.033307798 -0.79060501 -0.61141998, + 0.044210013 -0.76787019 -0.6390782, + 0.059454106 -0.7672621 -0.63857204, + 0.07224118 -0.74331278 -0.66503179, + 0.091782503 -0.74211401 -0.66395998, + 0.106106 -0.71732497 -0.68861198, + 0.12924302 -0.71534604 -0.68671405, + 0.14612001 -0.68772304 -0.71111608, + 0.1732209 -0.68467557 -0.7079646, + 0.19227298 -0.65447897 -0.73122394, + 0.22377187 -0.65001059 -0.72623158, + 0.24392492 -0.61846775 -0.74699277, + 0.27930307 -0.61235112 -0.73960519, + 0.30013502 -0.57964504 -0.75758213, + 0.339479 -0.57157302 -0.747033, + 0.36030498 -0.53825295 -0.76188189, + 0.40228283 -0.52825975 -0.74773663, + 0.42226201 -0.49519601 -0.75926, + 0.46632013 -0.48325512 -0.74095219, + 0.48538595 -0.45011693 -0.74952996, + 0.53055894 -0.43639493 -0.72668195, + 0.5478189 -0.4044469 -0.73233682, + 0.59346491 -0.38910395 -0.70455492, + 0.60869974 -0.3586129 -0.70772976, + 0.65291685 -0.34235391 -0.67564285, + 0.66598785 -0.31366092 -0.67681384, + 0.70807517 -0.29691505 -0.64068019, + 0.71885121 -0.2705681 -0.64034826, + 0.75828212 -0.25374004 -0.60052007, + 0.76687789 -0.22998098 -0.59917194, + 0.80327117 -0.21343304 -0.55605912, + 0.8098368 -0.19258195 -0.55414486, + 0.8424648 -0.17685595 -0.50889587, + 0.84731472 -0.15884894 -0.50677884, + 0.87611145 -0.14419791 -0.46003872, + 0.87963378 -0.12861498 -0.45793289, + 0.90381521 -0.11571003 -0.41198209, + 0.90145212 -0.12715201 -0.41378307, + 0.87542909 -0.14197502 -0.46202505, + 0.87138009 -0.15825102 -0.46438506, + 0.84163839 -0.17419589 -0.51117563, + 0.83601171 -0.19327992 -0.51354384, + 0.80229086 -0.21026596 -0.55867493, + 0.7947579 -0.23220797 -0.56074893, + 0.75712401 -0.249938 -0.60356802, + 0.74740374 -0.2746419 -0.60494578, + 0.70674396 -0.29245898 -0.64418995, + 0.69456756 -0.31990683 -0.64438766, + 0.65145797 -0.33736396 -0.67954993, + 0.63689393 -0.36692598 -0.67803496, + 0.59188193 -0.38361895 -0.70888096, + 0.57488179 -0.41515684 -0.70509279, + 0.52888787 -0.4306089 -0.73133683, + 0.50985998 -0.46333599 -0.724819, + 0.46447405 -0.47697905 -0.74616003, + 0.44383284 -0.51035684 -0.73657876, + 0.40032595 -0.52189696 -0.75323486, + 0.3783499 -0.55579388 -0.74023283, + 0.33738503 -0.56522304 -0.75279111, + 0.31507799 -0.59853202 -0.73653603, + 0.27699593 -0.60597688 -0.7456978, + 0.25501487 -0.63822168 -0.72638863, + 0.22121499 -0.64369297 -0.73261398, + 0.19972596 -0.67513984 -0.71013784, + 0.17058693 -0.67892271 -0.71411765, + 0.15145491 -0.7073496 -0.69044757, + 0.126384 -0.70986599 -0.69290501, + 0.11006907 -0.7350114 -0.66906142, + 0.08849518 -0.73660284 -0.67051083, + 0.073408313 -0.76124918 -0.64429116, + 0.055935416 -0.76211315 -0.64502317, + 0.042666927 -0.78558946 -0.61727536, + 0.029666511 -0.7859593 -0.61756623, + 0.021028493 -0.80310172 -0.59547079, + 0.02506149 -0.80302668 -0.59541577, + 0.038842902 -0.77999502 -0.62457901, + 0.054097988 -0.77944082 -0.62413585, + 0.069826506 -0.75519115 -0.65177506, + 0.089390725 -0.75400817 -0.65075415, + 0.10682302 -0.72866321 -0.67649019, + 0.13045397 -0.72659379 -0.67456883, + 0.14868002 -0.70111203 -0.69737804, + 0.17617606 -0.69790322 -0.69418526, + 0.19731396 -0.66894495 -0.71664494, + 0.22905193 -0.66421878 -0.71158177, + 0.25277898 -0.63171792 -0.73282695, + 0.28895196 -0.62507093 -0.72511595, + 0.31295186 -0.5916487 -0.74297565, + 0.352873 -0.58286601 -0.73194802, + 0.376423 -0.54902101 -0.74624503, + 0.4195469 -0.53793091 -0.73117083, + 0.44210315 -0.50396615 -0.74199921, + 0.48724011 -0.49065211 -0.72239721, + 0.50821489 -0.4571209 -0.7299028, + 0.55457783 -0.44167584 -0.70524174, + 0.57334793 -0.40936494 -0.70971292, + 0.61911595 -0.39236993 -0.68025094, + 0.63546503 -0.36163601 -0.68220502, + 0.67960203 -0.34358099 -0.64814597, + 0.69324815 -0.31515908 -0.64813715, + 0.73516667 -0.29643786 -0.6096347, + 0.74622464 -0.27052888 -0.60824573, + 0.78511268 -0.2516959 -0.56590384, + 0.79371816 -0.22866206 -0.56367111, + 0.82867569 -0.21040893 -0.5186758, + 0.83513659 -0.19033392 -0.51606178, + 0.86603385 -0.17301299 -0.46909693, + 0.8706882 -0.15591803 -0.46646711, + 0.90384239 -0.13563806 -0.40579718, + 0.99342662 -0.011926095 -0.11384796, + 0.98684454 -0.016843893 -0.16079192, + 0.98654288 -0.024392197 -0.16167298, + 0.97716022 -0.031702209 -0.21012604, + 0.97640353 -0.042492382 -0.2117319, + 0.96383613 -0.052437406 -0.26128602, + 0.96226209 -0.066777706 -0.26380402, + 0.94583189 -0.079668991 -0.31472996, + 0.92169952 -0.11439206 -0.3706542, + 0.94286734 -0.098250635 -0.31835213, + 0.51554388 -0.52546591 -0.67683083, + 0.5673821 -0.50497913 -0.65044117, + 0.59722108 -0.46771505 -0.65159005, + 0.64905792 -0.44360894 -0.61800891, + 0.67353785 -0.40885893 -0.6157769, + 0.72262794 -0.38235494 -0.57585895, + 0.7417388 -0.35108492 -0.57145691, + 0.78638327 -0.32336712 -0.5263412, + 0.80074465 -0.29589486 -0.52082074, + 0.84041631 -0.26770708 -0.47120419, + 0.85056484 -0.24460694 -0.46551788, + 0.88464975 -0.21687695 -0.41274592, + 0.89156491 -0.19777396 -0.40742794, + 0.92587799 -0.16499101 -0.339894, + -0.99735421 0.0025313806 0.072650716, + 0.028333601 -0.72377801 -0.68945098, + 0.033015583 -0.73168057 -0.68084759, + 0.027093695 -0.73181093 -0.68096894, + 0.032167189 -0.73902577 -0.67290878, + 0.0238121 -0.73919898 -0.67306602, + 0.028798496 -0.74528396 -0.66612494, + 0.0175984 -0.74547702 -0.66629899, + 0.021812895 -0.74997282 -0.66110879, + 0.0079250867 -0.75012761 -0.6612457, + 0.011551304 -0.75356132 -0.65727621, + -0.0058836308 -0.75359911 -0.65730804, + -0.0030629712 -0.7560063 -0.65455723, + -0.024182612 -0.75578839 -0.65436929, + -0.022240512 -0.75730437 -0.65268332, + -0.0473447 -0.75664198 -0.65211302, + -0.049778592 -0.75486887 -0.65398395, + -0.079467937 -0.75341535 -0.65272528, + -0.11414094 -0.72845858 -0.67551458, + -0.151605 -0.72477502 -0.67209899, + -0.19327909 -0.69330734 -0.69423938, + -0.23789904 -0.68634504 -0.68726605, + -0.27594104 -0.65564007 -0.70284605, + -0.325746 -0.64491898 -0.69135302, + -0.35920888 -0.61582476 -0.70123374, + -0.44015816 -0.59250724 -0.67468226, + 0.028339203 -0.75719911 -0.65256906, + 0.033407088 -0.76536173 -0.64273274, + 0.027587393 -0.7654978 -0.64284682, + 0.032520313 -0.7721833 -0.63456726, + 0.024671091 -0.77235669 -0.63470978, + 0.029462384 -0.77792454 -0.62766665, + 0.018611902 -0.77812713 -0.62783104, + 0.022891607 -0.78247333 -0.62226325, + 0.0092405789 -0.78264487 -0.62239993, + 0.012616798 -0.78568989 -0.61849195, + -0.0041398988 -0.78574568 -0.61853576, + -0.0037883299 -0.78603297 -0.618173, + -0.0246893 -0.78579903 -0.617989, + -0.053186107 -0.76358014 -0.64351904, + -0.07998962 -0.76221216 -0.64236617, + -0.11765206 -0.73235738 -0.67067927, + -0.15163094 -0.72895175 -0.66756076, + -0.187135 -0.699691 -0.689502, + -0.22742595 -0.69360983 -0.6835078, + -0.26121193 -0.66438484 -0.70025784, + -0.30666104 -0.65511805 -0.69049203, + -0.33719009 -0.62714916 -0.7021302, + -0.38661924 -0.61436135 -0.68781239, + -0.41347006 -0.58806103 -0.69514507, + -0.48703894 -0.56407595 -0.66679192, + -0.88572812 -0.22609103 -0.40542406, + -0.83913809 -0.26491603 -0.47504407, + -0.8270492 -0.29022107 -0.48141611, + -0.78483999 -0.31994301 -0.53071898, + -0.76784384 -0.3498069 -0.53670388, + -0.72040892 -0.37869895 -0.58103192, + -0.69779098 -0.41260001 -0.58553302, + -0.64653593 -0.43943095 -0.62361193, + -0.6186161 -0.47571412 -0.62530816, + -0.56532007 -0.49943507 -0.65648907, + -0.53652894 -0.53252792 -0.65463793, + -0.46969312 -0.55710614 -0.68485117, + -0.4408448 -0.5860827 -0.67982572, + -0.3875539 -0.60192591 -0.69820285, + -0.35752892 -0.62966681 -0.68970484, + -0.30780989 -0.64149678 -0.70266277, + -0.27397403 -0.67064005 -0.68933308, + -0.22862098 -0.67885393 -0.69777495, + -0.19124791 -0.70912063 -0.67865473, + -0.152594 -0.71399498 -0.68331999, + -0.11235899 -0.74491495 -0.65762997, + -0.08045119 -0.74723095 -0.65967697, + -0.049125407 -0.77052909 -0.63550907, + -0.023973804 -0.7712391 -0.63609403, + -0.022983795 -0.7719968 -0.63521081, + -0.0021463702 -0.77219909 -0.63537705, + -0.0049372599 -0.76987302 -0.63817799, + 0.012239807 -0.7698245 -0.63813835, + 0.0086614387 -0.76651585 -0.64216691, + 0.022420395 -0.76635182 -0.64202982, + 0.0181091 -0.76186299 -0.64748502, + 0.029087592 -0.76166582 -0.64731681, + 0.024459895 -0.75615281 -0.65393782, + 0.032367788 -0.7559827 -0.65379077, + 0.027323095 -0.74897581 -0.6620338, + 0.03326311 -0.74884123 -0.66191423, + 0.0280861 -0.74029797 -0.67169201, + 0.023255905 -0.74038917 -0.67177618, + 0.031725194 -0.7571218 -0.65250283, + 0.027030487 -0.76388866 -0.64478171, + 0.031971198 -0.77334887 -0.63317394, + 0.028508108 -0.77343017 -0.63324016, + 0.033538107 -0.78133017 -0.62321609, + 0.027702393 -0.78146982 -0.62332785, + 0.032633085 -0.78798366 -0.61483067, + 0.0250898 -0.78815597 -0.61496401, + 0.029668396 -0.79333889 -0.60805696, + 0.01916619 -0.79354262 -0.60821271, + 0.023427898 -0.79775691 -0.60252392, + 0.0095738405 -0.79793912 -0.60266209, + 0.010820399 -0.79903889 -0.60118192, + -0.0057043466 -0.7990725 -0.60120761, + -0.030981196 -0.77811688 -0.62735492, + -0.053952727 -0.77735734 -0.62674129, + -0.088199079 -0.74895483 -0.65672481, + -0.11776201 -0.74665308 -0.65470707, + -0.15154798 -0.71794593 -0.67940193, + -0.18682989 -0.71354657 -0.6752376, + -0.21966296 -0.68465596 -0.69497794, + -0.26072484 -0.67752355 -0.6877386, + -0.29141003 -0.64925903 -0.70252603, + -0.33670709 -0.63908619 -0.69151819, + -0.364227 -0.61233401 -0.701702, + -0.41312879 -0.59876573 -0.68615168, + -0.43680006 -0.57425106 -0.69241709, + -0.48718125 -0.55748826 -0.67220628, + -0.51382005 -0.52766204 -0.67643309, + -0.56543934 -0.50729829 -0.6503284, + -0.59496802 -0.47061399 -0.651564, + -0.64690399 -0.44650301 -0.61818302, + -0.67186368 -0.41126478 -0.61600369, + -0.72095639 -0.38478217 -0.57633728, + -0.74059123 -0.35281712 -0.57187819, + -0.78547382 -0.32495692 -0.52671987, + -0.79997987 -0.29730996 -0.52118993, + -0.83977997 -0.26901799 -0.47159201, + -0.85013688 -0.24551797 -0.46581995, + -0.88431102 -0.21769901 -0.413039, + -0.89372313 -0.19146803 -0.40570804, + -0.92289823 -0.16433504 -0.34821409, + -0.92978698 -0.138776 -0.34093601, + -0.95148343 -0.11600494 -0.28499481, + -0.95517486 -0.096947484 -0.27971798, + -0.97102666 -0.078257971 -0.22579393, + -0.97283167 -0.06468688 -0.22229293, + -0.98415375 -0.049544189 -0.17025496, + -0.98494679 -0.04025089 -0.16810596, + -0.99255478 -0.028361492 -0.11845097, + -0.99284822 -0.022398006 -0.11726403, + -0.99748886 -0.013287598 -0.069566794, + -0.99756402 -0.0100122 -0.069035403, + -0.99973851 -0.0032820383 -0.022630088, + -0.99974412 -0.0022716802 -0.022505801, + -0.99974614 0.0022630002 0.022419801, + -0.99974954 0.0012999194 0.022340288, + -0.9977029 0.0039349995 0.067626789, + -0.99771464 0.0018782692 0.067541681, + -0.9973501 0.00047047104 0.072750509, + -0.99734986 -0.00093512988 0.072749391, + -0.99735725 -0.00093505025 0.072648115, + 0.020683898 -0.51675093 -0.85588586, + 0.025946187 -0.51668775 -0.8557806, + 0.019927293 -0.47847381 -0.87787569, + 0.016746296 -0.47850189 -0.87792677, + 0.013068405 -0.43656814 -0.89957631, + 0.0057883905 -0.43659806 -0.89963812, + 0.0045986078 -0.39217183 -0.91988057, + -0.0045986078 -0.39217183 -0.91988057, + -0.005787197 -0.43655381 -0.89965957, + -0.012986093 -0.43652472 -0.89959848, + -0.016637506 -0.47833619 -0.87801927, + -0.019663999 -0.47830993 -0.87797087, + -0.914581 0.0078766001 0.40432599, + -0.91461128 0.00012562705 0.40433416, + -0.91462421 0.00012185803 0.4043051, + -0.91459328 0.0078761829 0.40429816, + -0.8994627 0.0044657788 0.43697485, + -0.89893889 0.022768198 0.43748194, + -0.91950715 0.020429403 0.39254206, + -0.91867512 0.035385102 0.39342606, + -0.93697786 0.031297997 0.34798396, + -0.93593311 0.045000505 0.34929103, + -0.95193774 0.03913739 0.30378094, + -0.95079935 0.05164222 0.30547312, + -0.96467286 0.043914795 0.25976497, + -0.96354246 0.055259626 0.26178712, + -0.975429 0.045502599 0.215564, + -0.97440064 0.055626381 0.21782793, + -0.98439187 0.043544795 0.17051798, + -0.98355341 0.052288368 0.1728829, + -0.9914791 0.037711903 0.12468801, + -0.9909001 0.044778805 0.12693301, + -0.99664348 0.027234713 0.077201441, + -0.99636263 0.032050189 0.078957468, + -0.99958891 0.010783799 0.026566597, + -0.99954665 0.012637495 0.027327091, + -0.99952489 -0.012936798 -0.027974296, + -0.99946475 -0.015167097 -0.028984392, + -0.99480498 -0.0471984 -0.090196103, + -0.99399567 -0.05553478 -0.094279364, + -0.98216265 -0.095434159 -0.16201495, + -0.98098052 -0.10175795 -0.16529493, + -0.95966613 -0.14738701 -0.23941202, + -0.96086103 -0.14320099 -0.237149, + -0.92878288 -0.19158097 -0.31726798, + -0.92991263 -0.18872093 -0.31566888, + -0.88381577 -0.24006194 -0.40154693, + -0.88318723 -0.24124905 -0.4022181, + -0.81773698 -0.296065 -0.49361101, + -0.82171214 -0.29031602 -0.49041405, + -0.75731611 -0.33267102 -0.56196308, + -0.76015913 -0.32916704 -0.56018507, + -0.63071007 -0.35335803 -0.69090009, + -0.55543888 -0.37864792 -0.74034685, + -0.55329114 -0.38053709 -0.74098617, + -0.47854912 -0.4011271 -0.7810812, + -0.47144419 -0.40694314 -0.78239232, + -0.39958808 -0.4230001 -0.8132652, + -0.38481995 -0.43442294 -0.81436491, + -0.31903088 -0.44607285 -0.83620471, + -0.33257911 -0.43575716 -0.83636528, + -0.27103707 -0.44476411 -0.85365319, + -0.28874406 -0.4309361 -0.85493916, + -0.23042104 -0.43799606 -0.86894512, + -0.24121606 -0.42923909 -0.87038416, + -0.1869709 -0.4344998 -0.8810516, + -0.19347893 -0.42896885 -0.88235569, + -0.14402898 -0.43267092 -0.88997275, + -0.14599305 -0.43090516 -0.89050931, + -0.10190204 -0.43330416 -0.89546829, + -0.10067502 -0.43448409 -0.89503527, + -0.062440716 -0.4358511 -0.89785022, + -0.059498809 -0.43892205 -0.8965531, + -0.02737879 -0.43953586 -0.89780772, + -0.024131894 -0.44327089 -0.89606279, + 0.0017297094 -0.44339886 -0.89632273, + 0.004249231 -0.44664112 -0.89470321, + 0.02417269 -0.44651484 -0.89444971, + 0.025310896 -0.44817993 -0.89358491, + 0.039696295 -0.44796994 -0.8931669, + 0.039170399 -0.44707999 -0.89363599, + 0.048572291 -0.44689494 -0.89326686, + 0.046697214 -0.44314814 -0.89523131, + 0.051764581 -0.44303685 -0.89500773, + 0.04919121 -0.43683809 -0.89819425, + 0.050393011 -0.4368121 -0.89814025, + 0.047039192 -0.42681894 -0.90311289, + 0.040774297 -0.41088495 -0.91077489, + 0.044955887 -0.42685986 -0.90319967, + 0.032188904 -0.46726707 -0.88353014, + 0.037435509 -0.46718213 -0.88336825, + 0.030787989 -0.43528184 -0.8997677, + 0.040133417 -0.43513715 -0.89946932, + 0.043597478 -0.44791079 -0.89301461, + 0.044760976 -0.44788778 -0.8929686, + 0.047963988 -0.45712188 -0.88810974, + 0.045674611 -0.45717111 -0.88820523, + 0.048582278 -0.4639608 -0.88452256, + 0.042541083 -0.4640888 -0.88476658, + 0.044603497 -0.46809295 -0.88255286, + 0.034243587 -0.46828482 -0.88291371, + 0.035058405 -0.46962807 -0.88216811, + 0.019840002 -0.46982405 -0.88253713, + 0.019478204 -0.46930712 -0.88282025, + -0.00098483427 -0.46939611 -0.88298726, + -0.0021323897 -0.46795094 -0.88375187, + -0.028084099 -0.46776801 -0.88340503, + -0.029311804 -0.46638307 -0.8840971, + -0.060908906 -0.46571705 -0.88283509, + -0.061141469 -0.46547878 -0.88294458, + -0.098147556 -0.46409979 -0.8803286, + -0.096171066 -0.46596381 -0.87956172, + -0.13824797 -0.46363789 -0.87517273, + -0.13272803 -0.46849111 -0.87344116, + -0.17946102 -0.46499905 -0.86693114, + -0.17048892 -0.47242075 -0.8647266, + -0.22153901 -0.467527 -0.85576802, + -0.20653796 -0.47929987 -0.85300285, + -0.26110303 -0.47286907 -0.8415581, + -0.24945997 -0.48164493 -0.84011185, + -0.30841404 -0.47312406 -0.82524812, + -0.32297608 -0.46217611 -0.82588118, + -0.38918909 -0.44984612 -0.80384719, + -0.39696091 -0.44379389 -0.80341083, + -0.46868017 -0.42712814 -0.77324027, + -0.47174588 -0.4246169 -0.77275884, + -0.54652274 -0.40328783 -0.73394263, + -0.54770803 -0.40224907 -0.73362905, + -0.62322086 -0.3759869 -0.68573284, + -0.62343311 -0.3757821 -0.6856522, + -0.69655019 -0.3448461 -0.62920517, + -0.69719636 -0.34520817 -0.6282903, + -0.76634568 -0.30935687 -0.56303883, + -0.76424652 -0.31195483 -0.56445664, + -0.82726872 -0.27174991 -0.49170983, + -0.824323 -0.276041 -0.49426001, + -0.87886029 -0.23262408 -0.41652215, + -0.87498212 -0.23945002 -0.42079705, + -0.92614537 -0.18653706 -0.32780913, + -0.92530626 -0.18853004 -0.32903609, + -0.95983034 -0.13949105 -0.24345009, + -0.95857209 -0.14370002 -0.24594703, + -0.9808929 -0.098144881 -0.16797799, + -0.98005438 -0.10234704 -0.17034806, + -0.99338621 -0.059133817 -0.098422721, + -0.99374962 -0.055833183 -0.09666606, + -0.99936175 -0.017866597 -0.030933093, + -0.9994455 -0.015216207 -0.029619414, + -0.99947512 0.014804602 0.028818004, + -0.99953222 0.012651203 0.027843008, + -0.99589199 0.0374582 0.082438603, + -0.99626225 0.032017007 0.080227725, + -0.98993313 0.052460507 0.13145502, + -0.99068397 0.044641599 0.128656, + -0.98213273 0.061690785 0.17779095, + -0.98322612 0.052037306 0.17481002, + -0.97263485 0.066288196 0.22268197, + -0.97397465 0.055274483 0.21981393, + -0.96156722 0.066958614 0.26628006, + -0.96304554 0.054837074 0.26369688, + -0.94875246 0.06434153 0.30940115, + -0.95027012 0.051190309 0.30719104, + -0.93395478 0.058745585 0.35252991, + -0.93541223 0.04455971 0.35074008, + -0.91694415 0.050288707 0.39583406, + -0.91822863 0.03501479 0.39449984, + -0.89764029 0.038964614 0.43900314, + -0.89863098 0.022519199 0.43812701, + -0.89438128 0.0084213726 0.44722614, + -0.87633973 0.0051659388 0.48166588, + -0.87573373 0.024782294 0.48215789, + -0.84542942 -7.8989338e-005 0.53408724, + -0.81821001 -0.000744919 0.57491899, + -0.81817073 0.0092618959 0.57490081, + 0.75959182 0.010342197 0.65031785, + 0.84009409 -0.22097003 -0.49539307, + 0.89044142 -0.18538909 -0.4156262, + 0.88862628 -0.18863107 -0.41804516, + 0.92942464 -0.15177093 -0.33635589, + 0.92764688 -0.15578899 -0.33941296, + 0.95905924 -0.11813903 -0.25738806, + 0.95765388 -0.12237798 -0.26061997, + 0.97989035 -0.084810726 -0.18061607, + 0.97859323 -0.090456821 -0.18485904, + 0.99333447 -0.050663922 -0.10353705, + 0.99296379 -0.05360819 -0.10558898, + 0.99932063 -0.016684795 -0.032862891, + 0.99927467 -0.017874494 -0.033624791, + 0.99934334 0.017007606 0.031994112, + 0.99929237 0.018395908 0.032807011, + 0.99399602 0.053514302 0.095436797, + 0.99424225 0.051134109 0.094169021, + 0.98491251 0.082579464 0.15207893, + 0.98665887 0.070973694 0.14651598, + 0.97501224 0.096847825 0.19992904, + 0.97738075 0.083555281 0.19428195, + 0.96386564 0.10524596 0.24471691, + 0.96668911 0.090717204 0.23933803, + 0.95170766 0.10881096 0.28707591, + 0.954817 0.093313403 0.28216499, + 0.93837023 0.10852202 0.3281531, + 0.94161385 0.092202894 0.32382396, + 0.92358935 0.10498804 0.36872813, + 0.92681086 0.08803349 0.36506397, + 0.90706223 0.098692425 0.4092651, + 0.91015089 0.081090994 0.40626293, + 0.88877058 0.089718357 0.44948578, + 0.89162421 0.071362115 0.44711712, + 0.8684358 0.078143276 0.48960489, + 0.87092215 0.059103008 0.48785406, + 0.84554529 0.064212523 0.53002816, + 0.8197481 0.048383508 0.57067704, + 0.8475219 0.044838496 0.52886295, + 0.84822714 0.045275204 0.52769405, + 0.8735503 0.041608114 0.48495218, + 0.87180072 0.059646379 0.48621583, + 0.89480668 0.054361083 0.44313186, + 0.89264774 0.071983583 0.44496989, + 0.91363961 0.064920269 0.40130782, + 0.91122621 0.081718326 0.4037191, + 0.9304229 0.072707593 0.35920298, + 0.92788899 0.088620402 0.36217201, + 0.94519675 0.077602684 0.3171449, + 0.94264477 0.09270148 0.32066691, + 0.95821774 0.079438277 0.27478793, + 0.95576513 0.093684807 0.27881202, + 0.96969265 0.07782197 0.23160291, + 0.96749562 0.090921268 0.23597792, + 0.979819 0.071865797 0.18652099, + 0.97801661 0.083577871 0.19104493, + 0.98836964 0.060950179 0.13932195, + 0.98709035 0.070825525 0.14365405, + 0.99512774 0.043598689 0.088430978, + 0.99445802 0.050882298 0.0920012, + 0.99935699 0.0173527 0.031375799, + 0.99932486 0.018273799 0.031872198, + 0.99926865 -0.019019593 -0.033172689, + 0.9993155 -0.01777309 -0.032442983, + 0.99305046 -0.056544725 -0.10321605, + 0.99342126 -0.053468112 -0.10126902, + 0.9793005 -0.094506547 -0.17899509, + 0.98012626 -0.090716824 -0.17641704, + 0.9550131 -0.13561802 -0.26373804, + 0.95741034 -0.12847404 -0.25857309, + 0.92482036 -0.16926506 -0.34067112, + 0.92694288 -0.16448599 -0.33722597, + 0.88491768 -0.20418093 -0.41860586, + 0.88712156 -0.20024791 -0.4158318, + 0.83555388 -0.23837297 -0.49500296, + 0.83740115 -0.23566206 -0.49317613, + 0.77688986 -0.27146897 -0.56810796, + -0.6440478 -0.31102395 -0.6989038, + -0.56598032 -0.33518815 -0.75320333, + -0.55370486 -0.34583491 -0.75750184, + -0.47907007 -0.36455104 -0.79849511, + -0.49649394 -0.35024998 -0.79424089, + -0.42356908 -0.36551109 -0.8288492, + -0.44663695 -0.34670696 -0.8248089, + -0.37598583 -0.35907283 -0.85422558, + -0.39152494 -0.34631398 -0.85251087, + -0.32377389 -0.35608688 -0.87656868, + -0.33382314 -0.34771419 -0.87616044, + -0.26950094 -0.35522592 -0.89508873, + -0.27295303 -0.35227704 -0.89520812, + -0.21325393 -0.35775888 -0.90913773, + -0.2112111 -0.35956919 -0.90890044, + -0.15762594 -0.36326888 -0.91825366, + -0.15159506 -0.36889011 -0.91702735, + -0.10494903 -0.37114212 -0.92262638, + -0.096986786 -0.37906393 -0.9202739, + -0.057738625 -0.38022417 -0.9230904, + -0.049574982 -0.38904786 -0.91988266, + -0.0178646 -0.389465 -0.92086798, + -0.011105096 -0.39754686 -0.91751462, + 0.013355498 -0.39753494 -0.91748989, + 0.017722704 -0.40341109 -0.91484725, + 0.035649691 -0.4032169 -0.91440976, + 0.037699081 -0.40636981 -0.91293061, + 0.049751077 -0.40615582 -0.91244859, + 0.050136693 -0.40684593 -0.91211987, + 0.05701628 -0.40669584 -0.91178268, + 0.055363815 -0.4031851 -0.91344225, + 0.057924673 -0.40312582 -0.91330957, + 0.05314029 -0.3908039 -0.91893876, + 0.05344598 -0.39079785 -0.91892362, + 0.049699891 -0.37880296 -0.92414188, + 0.047653306 -0.37884107 -0.92423409, + 0.044333015 -0.36518613 -0.92987835, + 0.042083599 -0.330167 -0.94298398, + 0.045146387 -0.33012292 -0.94285774, + 0.041841101 -0.31053701 -0.94963998, + 0.030545885 -0.31066486 -0.95002854, + 0.019837897 -0.21978398 -0.97534686, + 0.012313797 -0.21981095 -0.97546476, + -0.0054383087 0.036910791 -0.99930376, + -0.0017128403 0.036911402 -0.99931711, + -0.0078240409 0.30762002 -0.95147711, + 0.0073674563 0.30762085 -0.95148051, + 0.0013343701 0.037142105 -0.99930912, + 0.0051200897 0.037141494 -0.9992969, + -0.012513602 -0.21826603 -0.9758091, + -0.019806901 -0.21824002 -0.97569412, + -0.030530289 -0.30925888 -0.95048761, + -0.041673914 -0.30913612 -0.95010436, + 0.79161167 -0.2152409 -0.5718587, + 0.72612756 -0.24220085 -0.64348865, + 0.72135144 -0.24726714 -0.64692438, + 0.64997196 -0.27132696 -0.70987195, + 0.66795123 -0.25401008 -0.69951421, + 0.59480411 -0.27437407 -0.75559717, + 0.62041104 -0.25076002 -0.74310803, + 0.54621303 -0.26782402 -0.79367614, + 0.5649159 -0.25104293 -0.7860328, + 0.49006495 -0.26520196 -0.83036387, + 0.50292194 -0.25390896 -0.8261959, + 0.42876005 -0.26539102 -0.86355811, + 0.43470892 -0.26022893 -0.86215383, + 0.36256713 -0.26929909 -0.8922013, + 0.3619771 -0.26981106 -0.89228624, + 0.29336405 -0.27670205 -0.91508126, + 0.28618315 -0.28301814 -0.91542339, + 0.22313592 -0.28792492 -0.93129462, + 0.211419 -0.298558 -0.93067998, + 0.15593301 -0.30172703 -0.94055611, + 0.14183103 -0.31518209 -0.93837327, + 0.095025256 -0.31695986 -0.94366652, + 0.080962598 -0.331341 -0.94003099, + 0.042949602 -0.33212504 -0.94225711, + 0.030668288 -0.34585488 -0.93778664, + 0.0014156399 -0.34601796 -0.93822688, + -0.0073694088 -0.35696697 -0.93408787, + -0.028859107 -0.35682809 -0.93372422, + -0.032409009 -0.3618491 -0.93167323, + -0.047575109 -0.36163002 -0.9311071, + -0.049267583 -0.36438888 -0.92994267, + -0.058793508 -0.36420003 -0.92946315, + -0.058558185 -0.3637509 -0.92965376, + -0.063551612 -0.3636401 -0.92936921, + -0.058788631 -0.35278618 -0.93385541, + -0.061598178 -0.35272688 -0.93369663, + -0.058326475 -0.34366685 -0.93727857, + -0.058085579 -0.34367189 -0.93729162, + -0.054671891 -0.33193997 -0.94171488, + -0.051787693 -0.33199096 -0.9418599, + -0.04874092 -0.31857011 -0.94664538, + -0.043277685 -0.31865087 -0.94688362, + -0.031284809 -0.33744809 -0.94082421, + -0.032808211 -0.33743113 -0.94077837, + -0.030076085 -0.31449184 -0.94878352, + -0.018579202 -0.31458002 -0.94904912, + -0.012083603 -0.22188406 -0.97499824, + -0.0043115313 -0.22189808 -0.97506034, + 0.0015392096 0.035993494 -0.99935079, + -0.0018764904 0.035993509 -0.99935025, + 0.0040214118 -0.2227671 -0.97486347, + 0.011963895 -0.2227529 -0.97480154, + 0.018478002 -0.31564003 -0.94869912, + 0.030122312 -0.31555113 -0.94843036, + 0.032732304 -0.33744204 -0.94077712, + 0.034700811 -0.33742011 -0.94071436, + 0.039711315 -0.36525711 -0.93005937, + 0.027789991 -0.38369486 -0.92304164, + 0.030401511 -0.38366616 -0.92297137, + 0.025152296 -0.34243196 -0.93920588, + 0.019843701 -0.34247303 -0.93931812, + 0.018122802 -0.31820402 -0.94784909, + 0.0060872589 -0.31825098 -0.9479869, + 0.0039009715 -0.22348608 -0.97469938, + -0.004045479 -0.22348595 -0.97469878, + -0.0062214001 -0.317974 -0.94807899, + -0.018115297 -0.3179279 -0.94794178, + -0.019854192 -0.34248188 -0.93931466, + -0.02519981 -0.34244111 -0.93920135, + -0.030437611 -0.38357913 -0.92300636, + -0.027714191 -0.38360885 -0.92307967, + -0.035260983 -0.4229908 -0.9054476, + -0.03924071 -0.42292809 -0.90531325, + -0.032516506 -0.38821006 -0.92099714, + -0.04238528 -0.38806581 -0.92065656, + -0.046376489 -0.40389091 -0.91363078, + -0.048694506 -0.40384606 -0.91353011, + -0.051825389 -0.41351593 -0.90902078, + -0.051131908 -0.41353106 -0.90905315, + -0.054276109 -0.42136806 -0.90526414, + -0.0500376 -0.42146099 -0.90546501, + -0.052645892 -0.42683893 -0.90279388, + -0.044562284 -0.42700684 -0.90314972, + -0.044898402 -0.42759207 -0.90285611, + -0.0316751 -0.427809 -0.90331399, + -0.029975707 -0.42526108 -0.90457422, + -0.011092898 -0.4254249 -0.90492576, + -0.0075934702 -0.42082301 -0.90711099, + 0.017614806 -0.42077014 -0.90699631, + 0.022538593 -0.41499686 -0.90954369, + 0.054479774 -0.41448578 -0.9084236, + 0.059961077 -0.40866485 -0.91071272, + 0.098743588 -0.40739995 -0.90789586, + 0.10339702 -0.40284708 -0.90940821, + 0.14883 -0.400507 -0.90412599, + 0.15095201 -0.39856306 -0.9046331, + 0.202553 -0.39482599 -0.89614999, + 0.20102403 -0.39615405 -0.89590812, + 0.25823393 -0.39069292 -0.88355774, + 0.25162202 -0.39621106 -0.88300812, + 0.31315708 -0.38879108 -0.86647218, + 0.30071995 -0.39886791 -0.86629784, + 0.36578912 -0.38924316 -0.84539229, + 0.34511498 -0.40562293 -0.84638387, + 0.41315794 -0.39356494 -0.8212229, + 0.39949295 -0.40430194 -0.8227669, + 0.47114375 -0.38900781 -0.79164165, + 0.48147112 -0.38061208 -0.7895062, + 0.55629307 -0.36086404 -0.74854207, + 0.55935317 -0.35818613 -0.74754721, + 0.63440937 -0.33401722 -0.69710642, + 0.63645476 -0.33205488 -0.69617873, + 0.70935762 -0.30343986 -0.63618869, + 0.70979506 -0.30296904 -0.63592505, + 0.77781737 -0.27031612 -0.5673883, + 0.78219068 -0.2519879 -0.56980681, + 0.71545702 -0.28257099 -0.638964, + 0.71467203 -0.283416 -0.63946801, + 0.64234406 -0.31054604 -0.70068204, + 0.640311 -0.31249201 -0.70167702, + 0.56563789 -0.33549291 -0.75332481, + 0.55669004 -0.34327403 -0.75647813, + 0.48207012 -0.36203909 -0.79783219, + 0.4979609 -0.34894991 -0.79389483, + 0.42500815 -0.36423713 -0.8286733, + 0.44828689 -0.3452169 -0.82453883, + 0.37761095 -0.35760397 -0.8541249, + 0.39249691 -0.34535792 -0.8524518, + 0.32464108 -0.3551521 -0.87662727, + 0.33314398 -0.34806398 -0.87627989, + 0.26884007 -0.35556111 -0.8951543, + 0.2712341 -0.35351813 -0.89524132, + 0.21166797 -0.35896498 -0.90903288, + 0.20931897 -0.36104298 -0.90875387, + 0.15592305 -0.36470711 -0.91797435, + 0.14980599 -0.370399 -0.916713, + 0.10339203 -0.37262011 -0.92220634, + 0.095545739 -0.38041914 -0.91986537, + 0.056488708 -0.38155606 -0.92261809, + 0.048590288 -0.3900899 -0.91949373, + 0.017058408 -0.39049417 -0.92044741, + 0.010502304 -0.39833415 -0.91718036, + -0.013828502 -0.39831805 -0.91714311, + -0.018328499 -0.40437195 -0.91441089, + -0.03604481 -0.40417716 -0.91397029, + -0.038016085 -0.40721086 -0.9125427, + -0.04994091 -0.40699708 -0.91206324, + -0.0486915 -0.40475699 -0.91312701, + -0.055950414 -0.40460309 -0.91277921, + -0.053786188 -0.39999491 -0.91493773, + -0.056979999 -0.39992499 -0.91477501, + -0.054317791 -0.39306295 -0.91790587, + -0.054142326 -0.39306718 -0.91791439, + -0.049703889 -0.37885892 -0.92411876, + -0.047666993 -0.37889594 -0.92421091, + -0.044264596 -0.36490497 -0.9299919, + -0.039760988 -0.36497292 -0.93016875, + -0.035571981 -0.34170285 -0.93913454, + -0.0463285 -0.341553 -0.93871999, + -0.04962039 -0.3555719 -0.93333077, + -0.052108817 -0.35552713 -0.93321234, + -0.055607483 -0.36714089 -0.92850167, + -0.055380017 -0.36714607 -0.92851323, + -0.060076907 -0.37969005 -0.92316109, + -0.057839692 -0.37974095 -0.92328286, + -0.059575014 -0.38355809 -0.92159325, + -0.053472508 -0.38369107 -0.92191213, + -0.054076787 -0.3848089 -0.92141074, + -0.043164611 -0.3850131 -0.92190123, + -0.042380895 -0.38377193 -0.92245489, + -0.026055794 -0.38398692 -0.92297077, + -0.021086305 -0.37714007 -0.92591625, + 0.0019502488 -0.37722278 -0.92612046, + 0.0099817198 -0.36742401 -0.93000001, + 0.040620487 -0.36713892 -0.92927879, + 0.050787989 -0.35596591 -0.93311775, + 0.089575581 -0.3549929 -0.93056774, + 0.10062602 -0.34384808 -0.93361825, + 0.14750803 -0.3418211 -0.92811626, + 0.15757409 -0.3323262 -0.92990851, + 0.21227802 -0.32886103 -0.92021114, + 0.21928793 -0.32256788 -0.92079467, + 0.28086093 -0.31730691 -0.90577775, + 0.28273609 -0.31567913 -0.90576327, + 0.34936181 -0.30836985 -0.8847906, + 0.34544411 -0.31171012 -0.8851583, + 0.41563609 -0.30210805 -0.8578912, + 0.404955 -0.31116301 -0.859761, + 0.47758025 -0.29899716 -0.82614642, + 0.46042413 -0.31359309 -0.83046317, + 0.53466499 -0.29853201 -0.79057699, + 0.50957227 -0.32008916 -0.79867333, + 0.58427078 -0.30190888 -0.75331169, + 0.56681991 -0.31728792 -0.76029181, + 0.64131224 -0.29550412 -0.70809323, + 0.64825416 -0.28891206 -0.70448315, + 0.71993357 -0.26334584 -0.64214063, + 0.72087038 -0.26234213 -0.64150029, + 0.78720909 -0.23342903 -0.57080007, + 0.77567989 -0.24740997 -0.58061093, + 0.84963715 -0.20673504 -0.48515713, + 0.84522372 -0.20341893 -0.49418381, + 0.89351189 -0.17092298 -0.41523695, + 0.8919667 -0.17367893 -0.41740984, + 0.93165487 -0.13958198 -0.33546397, + 0.93014097 -0.143005 -0.33821201, + 0.96051598 -0.108353 -0.25625899, + 0.95931262 -0.11199496 -0.25918391, + 0.98069054 -0.077572361 -0.17952292, + 0.97993386 -0.080909796 -0.18216299, + 0.99329513 -0.046927206 -0.10565302, + 0.99281675 -0.05055169 -0.10844098, + 0.99931961 -0.015583495 -0.033429191, + 0.99927378 -0.016729096 -0.034235794, + 0.99935442 0.015772391 0.032277983, + 0.99930489 0.017096698 0.033126097, + 0.99420738 0.04929322 0.095508836, + 0.99371564 0.05383338 0.098138161, + 0.98378533 0.086256728 0.15724605, + 0.98434752 0.082923062 0.15551093, + 0.97100914 0.11247302 0.21092904, + 0.97420663 0.096987359 0.20375192, + 0.95917761 0.12154896 0.25535092, + 0.96285725 0.10516502 0.24868906, + 0.94659364 0.12558095 0.29696789, + 0.95055211 0.10852601 0.29098603, + 0.93302077 0.12573896 0.33713791, + 0.93710637 0.10806504 0.33189413, + 0.91818202 0.122652 0.37669399, + 0.92225623 0.10440102 0.37221509, + 0.90181142 0.11670205 0.4160732, + 0.90572 0.098026298 0.412386, + 0.88384622 0.10817903 0.45509711, + 0.88747925 0.089030325 0.45216611, + 0.86396486 0.097280487 0.49406594, + 0.86724383 0.077480689 0.49181789, + 0.84171629 0.084022433 0.53334218, + 0.84452158 0.063630067 0.53172779, + 0.8167643 0.068555124 0.5728842, + 0.81895614 0.047930308 0.57185107, + 0.78916371 0.051298283 0.61203676, + 0.7906763 0.030462811 0.61147624, + 0.758775 0.032409102 0.65054601, + 0.066942275 0.014282895 0.99765462, + 0.53761584 0.11978096 -0.83463871, + 0.61940324 0.11152504 -0.77711129, + 0.65757006 0.14357102 -0.73958707, + 0.72927797 0.13038799 -0.67167896, + 0.748905 0.148497 -0.64582503, + 0.8084082 0.13190302 -0.5736531, + 0.81971884 0.14386196 -0.55440485, + 0.86705512 0.12513602 -0.48224106, + 0.8710832 0.13019603 -0.47356412, + 0.90819949 0.11094993 -0.40356377, + 0.90816802 0.110902 -0.40364799, + 0.93699223 0.092554219 -0.33686709, + 0.93534374 0.089456975 -0.34224191, + 0.95765209 0.072813809 -0.27856904, + 0.95553935 0.067855723 -0.28695008, + 0.97273409 0.053371307 -0.22569902, + 0.97082037 0.04764092 -0.23502809, + 0.98384565 0.035564188 -0.17545094, + 0.98239589 0.029809697 -0.18441698, + 0.9917385 0.020468991 -0.12663195, + 0.99086076 0.015512196 -0.13399397, + 0.99695724 0.0089643719 -0.077434018, + 0.99658149 0.0054212129 -0.082438238, + 0.99965262 0.0017294394 -0.026298791, + 0.99960464 0.00037592885 -0.028113291, + 0.9996295 -0.00036397917 0.027219612, + 0.9995715 0.0012330695 0.029247288, + 0.99629748 0.0036214716 0.085897535, + 0.99577838 0.0082270857 0.09141995, + 0.98889321 0.013321503 0.14803003, + 0.98849189 0.015495198 0.15047799, + 0.97855467 0.021099493 0.20490393, + 0.97786045 0.02393561 0.2078851, + 0.96507186 0.029966697 0.26026598, + 0.96375823 0.034370106 0.26455405, + 0.94844788 0.040831797 0.31429198, + 0.94641948 0.046703123 0.31954515, + 0.92868012 0.053636309 0.36698303, + 0.92580324 0.061064214 0.37304109, + 0.90570211 0.068480611 0.41834706, + 0.90182412 0.077628709 0.42507306, + 0.87949568 0.085498169 0.46816382, + 0.87446117 0.096540019 0.47539213, + 0.85029799 0.10474 0.51577401, + 0.84402168 0.11773296 0.5232268, + 0.81819683 0.12621297 0.56091386, + 0.81105018 0.14036302 0.56788713, + 0.7834571 0.14911401 0.60329103, + 0.77622581 0.16299395 0.60902089, + 0.74682707 0.17193002 0.64240909, + 0.73837966 0.1878069 0.64770669, + 0.70769984 0.19675395 0.67856383, + 0.69807595 0.21458197 0.68311393, + 0.66621226 0.22349508 0.71148527, + 0.65547681 0.24321894 0.71497881, + 0.62231201 0.252092 0.74106503, + 0.61053199 0.27369499 0.74319702, + 0.57622433 0.28243816 0.76693833, + 0.56357908 0.30573303 0.76740211, + 0.52888995 0.31410697 0.7884239, + 0.51555216 0.33896613 0.78696132, + 0.48077375 0.34687182 0.80531764, + 0.48310706 0.34232903 0.80586511, + 0.4513602 0.34889117 0.82130939, + 0.46554288 0.31752792 0.82610279, + 0.43172416 0.32362112 0.84195232, + 0.44354612 0.29289305 0.8470422, + 0.40826014 0.29832211 0.86274427, + 0.41805193 0.26796198 0.86800289, + 0.38121685 0.27269992 0.88335073, + 0.38923693 0.24247497 0.88865089, + 0.35060504 0.24652503 0.90349412, + 0.35704288 0.21629493 0.9087007, + 0.31650901 0.219653 0.92280799, + 0.3215099 0.18945995 0.92775875, + 0.279645 0.192101 0.94068903, + 0.28340292 0.16186693 0.94524163, + 0.24052612 0.16383207 0.95671648, + 0.24319997 0.13346699 0.96074986, + 0.19906305 0.13484403 0.97066522, + 0.20082805 0.10432902 0.97405523, + 0.15577106 0.10520004 0.98217535, + 0.15678802 0.074781805 0.98479712, + 0.11146297 0.075246282 0.99091578, + 0.11194398 0.044850595 0.99270189, + 0.066800572 0.045033477 0.99674952, + 0.0229441 0.0150131 0.99962401, + 0.57850504 0.31276402 -0.75333309, + -0.16433795 0.3663899 -0.91583377, + -0.14961793 0.36725783 -0.9180066, + -0.23961508 0.60433424 -0.75984532, + -0.22124103 0.58593506 -0.77957213, + -0.28818199 0.77029401 -0.56885701, + -0.2462749 0.77964473 -0.57576281, + -0.28225592 0.89679372 -0.34072387, + -0.25101289 0.96379155 -0.089990452, + -0.236889 0.90819597 -0.345056, + -0.17328905 0.98486227 0.0041620508, + -0.36111709 0.014918503 0.93240124, + -0.0386522 -0.115656 -0.99253702, + 0.61151969 0.78800863 -0.071316063, + 0.60954297 0.79057086 -0.058780193, + 0.33987215 0.25741211 -0.90455842, + 0.3668029 0.25462794 -0.89477378, + 0.35589099 0.219442 -0.90839797, + 0.29181987 0.16809994 -0.94158566, + 0.26558602 0.16943802 -0.94908112, + 0.25421995 0.15437198 -0.95474678, + 0.25024894 0.15096897 -0.95633876, + 0.32827297 0.14728898 -0.93302888, + 0.37548009 0.18464205 -0.90825224, + 0.46101278 0.17678592 -0.8696056, + 0.5090968 0.21320993 -0.8338837, + 0.59454405 0.19917703 -0.77900314, + 0.64314634 0.23625414 -0.7283864, + 0.71852207 0.21458302 -0.66157407, + 0.73107004 0.22472003 -0.64423406, + 0.79489291 0.19983597 -0.57289696, + 0.8096239 0.21298197 -0.54694396, + 0.85986698 0.185247 -0.475723, + 0.87123102 0.197281 -0.449485, + 0.90876573 0.16771495 -0.38212091, + 0.91212839 0.17217109 -0.37199318, + 0.9400481 0.14324802 -0.30949903, + 0.94108689 0.14501798 -0.30549198, + 0.96163833 0.11763904 -0.24781609, + 0.96131653 0.11691495 -0.24940188, + 0.9763965 0.091676652 -0.19556391, + 0.97563279 0.089363381 -0.20038696, + 0.98656386 0.066541493 -0.14921099, + 0.98587447 0.063634031 -0.15492707, + 0.99339086 0.043609597 -0.10617398, + 0.99293453 0.040752281 -0.11144595, + 0.99765176 0.023521895 -0.064325586, + 0.99745512 0.021387102 -0.068013906, + 0.99974149 0.0068200934 -0.021688912, + 0.9997161 0.0059653712 -0.023070702, + 0.99973345 -0.005779543 0.022352012, + 0.99970424 -0.0047917608 0.023846006, + 0.99743533 -0.014100605 0.070170723, + 0.99712187 -0.010638599 0.075064689, + 0.99238563 -0.017283695 0.12195095, + 0.99137914 -0.010738701 0.13058402, + 0.98383921 -0.014675104 0.17845204, + 0.98149562 -0.0040829987 0.19144093, + 0.97066653 -0.0051266579 0.24037488, + 0.96679324 0.0081476523 0.25543007, + 0.95262778 0.0096963979 0.30398393, + 0.95071876 0.015155897 0.30968395, + 0.93421614 0.017436402 0.35628104, + 0.93205577 0.022984494 0.3615849, + 0.91336626 0.025828106 0.40631908, + 0.91014576 0.033444591 0.41293591, + 0.88929009 0.036920305 0.45585105, + 0.88506424 0.04627401 0.46316311, + 0.86240214 0.050325606 0.50371605, + 0.85713184 0.061405286 0.51142389, + 0.8327468 0.066001683 0.54970586, + 0.82632858 0.078965865 0.55762476, + 0.80012786 0.084103391 0.59390396, + 0.79253018 0.098994523 0.60174412, + 0.7645399 0.10463499 0.63602692, + 0.75574511 0.12150501 0.64349508, + 0.72663426 0.12747204 0.67509526, + 0.71706796 0.14560099 0.68162596, + 0.68686742 0.15182209 0.71074843, + 0.67716205 0.17017701 0.71588504, + 0.64548594 0.17663799 0.74306595, + 0.63485318 0.19685905 0.7471332, + 0.60183328 0.20348111 0.77226436, + 0.59042102 0.22544301 0.77497, + 0.55674207 0.23203203 0.79762113, + 0.54472685 0.25557992 0.79871869, + 0.51060998 0.262041 0.81890899, + 0.49813306 0.28711504 0.8181861, + 0.46346313 0.29341105 0.83612919, + 0.45075011 0.31981009 0.83339417, + 0.41569999 0.32584801 0.84912699, + 0.40299806 0.35335502 0.84423512, + 0.36844811 0.35893312 0.8575623, + 0.3695991 0.35624608 0.8581872, + 0.33763492 0.36087891 0.86934984, + 0.34885088 0.33024588 0.87706369, + 0.3148151 0.3344661 0.88827026, + 0.3239359 0.30416295 0.89585179, + 0.28776491 0.30789989 0.90685672, + 0.29505888 0.27774891 0.91421872, + 0.25730905 0.28090307 0.92460024, + 0.26301703 0.25071403 0.93164611, + 0.22379403 0.25327304 0.94115311, + 0.22811393 0.22294395 0.94776577, + 0.18733501 0.22492804 0.95619714, + 0.19042791 0.1946139 0.96221751, + 0.14823593 0.19605091 0.96932453, + 0.15030299 0.16565998 0.97466189, + 0.10732107 0.1665951 0.98016757, + 0.108552 0.136057 0.98473603, + 0.064988628 0.13657705 0.98849547, + 0.065578617 0.10592602 0.99220926, + 0.021639999 0.10612898 0.9941169, + 0.021793295 0.075577088 0.99690175, + -0.022381894 0.075576082 0.99688876, + -0.0222381 0.106182 0.99409801, + -0.066016488 0.10597698 0.99217474, + -0.065436713 0.13660403 0.98846221, + -0.108954 0.13608301 0.98468798, + -0.10773604 0.16652806 0.98013335, + -0.15074302 0.16558805 0.97460622, + -0.14868902 0.19592303 0.96928114, + -0.19100609 0.19447809 0.96213049, + -0.1879169 0.2248279 0.95610654, + -0.22871096 0.22283797 0.94764686, + -0.22439189 0.25321788 0.9410255, + -0.26360205 0.25065306 0.93149722, + -0.25787404 0.28098103 0.92441911, + -0.29554114 0.27782613 0.91403943, + -0.28820303 0.30817804 0.90662313, + -0.32423887 0.30444688 0.89564568, + -0.31503299 0.335031 0.88797998, + -0.34884408 0.3308301 0.87684625, + -0.33756301 0.361617 0.86907101, + -0.36924192 0.35701892 0.85801983, + -0.36844298 0.35888198 0.85758591, + -0.40301186 0.35330188 0.84425068, + -0.41557294 0.32610896 0.84908891, + -0.45060411 0.3200731 0.83337218, + -0.46328813 0.29374406 0.83610916, + -0.49787617 0.28746009 0.81822127, + -0.51038003 0.26234499 0.818955, + -0.54448199 0.255885 0.79878801, + -0.55658603 0.232173 0.79768902, + -0.59026569 0.2255829 0.77504766, + -0.60186911 0.20325404 0.77229619, + -0.63492399 0.196631 0.74713302, + -0.64571792 0.17608799 0.74299496, + -0.67741597 0.16963698 0.71577293, + -0.68682724 0.15183106 0.71078521, + -0.71703094 0.14560999 0.68166292, + -0.72638208 0.12789801 0.67528605, + -0.75551403 0.121914 0.64368898, + -0.7642619 0.10515098 0.63627595, + -0.79223287 0.099495187 0.60205293, + -0.79983371 0.084619768 0.59422678, + -0.82604915 0.07945662 0.55796909, + -0.83249956 0.066445373 0.55002677, + -0.8568933 0.061824322 0.51177317, + -0.86226702 0.0505399 0.50392598, + -0.88494331 0.046473015 0.46337417, + -0.88929874 0.036835793 0.45584089, + -0.9101541 0.033367705 0.41292405, + -0.91348714 0.025478704 0.40606907, + -0.93216556 0.022670988 0.36132181, + -0.93439221 0.016941004 0.3558431, + -0.95086914 0.014722502 0.30924302, + -0.95268273 0.0095267985 0.30381694, + -0.96683437 0.0080047827 0.25527909, + -0.97054774 -0.0047066091 0.24086294, + -0.98141402 -0.0037491799 0.191866, + -0.98375487 -0.014285098 0.17894799, + -0.9913311 -0.010455201 0.13097101, + -0.99235487 -0.017082598 0.12222899, + -0.99710989 -0.010515699 0.075241789, + -0.99743187 -0.014063098 0.07022699, + -0.99970376 -0.0047790492 0.023865195, + -0.99973363 -0.0057857782 0.022342592, + -0.99971622 0.0059716315 -0.023060305, + -0.99974197 0.0068347501 -0.0216648, + -0.99745965 0.021431193 -0.067932576, + -0.99765736 0.023582209 -0.064216524, + -0.99295276 0.040853489 -0.11124697, + -0.99340802 0.043714002 -0.10597, + -0.98591465 0.063778877 -0.15461095, + -0.98660189 0.066686392 -0.14889498, + -0.97570187 0.08955849 -0.19996297, + -0.97646827 0.091887824 -0.19510604, + -0.96144211 0.11717401 -0.24879603, + -0.96182352 0.11803594 -0.24690688, + -0.94137979 0.14549997 -0.30435795, + -0.94040489 0.14382999 -0.30814198, + -0.9126581 0.17287502 -0.37036404, + -0.90810353 0.1668431 -0.38407224, + -0.36598396 0.26411498 -0.89235586, + -0.39393187 0.26085591 -0.8813467, + -0.2716451 0.16294307 -0.94850338, + -0.35336918 0.21013111 -0.91157842, + -0.3506391 0.20799008 -0.9131223, + -0.24906611 0.14990108 -0.95681548, + -0.32697189 0.14627095 -0.93364567, + -0.37563214 0.18477006 -0.90816331, + -0.46120995 0.17689998 -0.86947787, + -0.50743413 0.21190305 -0.83522916, + -0.59298509 0.19801505 -0.78048617, + -0.64331532 0.23638612 -0.72819436, + -0.71865773 0.21469992 -0.66138875, + -0.73842496 0.23076896 -0.63361996, + -0.80080891 0.20495997 -0.56275797, + -0.80691451 0.21043389 -0.55191165, + -0.85781789 0.18310298 -0.48023093, + -0.87030846 0.19623189 -0.45172572, + -0.86687732 0.17974406 -0.46499017, + -0.90966356 0.14975493 -0.38740882, + -0.91243929 0.15367106 -0.37926215, + -0.94016439 0.12795104 -0.31578413, + -0.94027764 0.12815395 -0.31536388, + -0.96104175 0.10405798 -0.25606793, + -0.96013403 0.10195 -0.260286, + -0.97563189 0.08002159 -0.20430097, + -0.97454876 0.076702788 -0.21064496, + -0.98594779 0.057158284 -0.15697095, + -0.98504364 0.053370681 -0.16383094, + -0.99299449 0.03660002 -0.11235005, + -0.99242538 0.033115711 -0.11830205, + -0.99748063 0.019122493 -0.068312876, + -0.99723321 0.016534904 -0.072474517, + -0.9997189 0.0052740597 -0.023116898, + -0.99968725 0.0042636008 -0.024645006, + -0.99970651 -0.0041299784 0.02387259, + -0.99966913 -0.0029458404 0.025555205, + -0.99713385 -0.0086640595 0.07516069, + -0.99674052 -0.0046279877 0.080540963, + -0.9913919 -0.0075108591 0.13071199, + -0.99011421 0.00014911203 0.14026403, + -0.98151624 0.00020345204 0.19137904, + -0.97913122 0.010184003 0.20297405, + -0.96701354 0.012764393 0.25440487, + -0.96579909 0.016796801 0.25874704, + -0.95125002 0.0199793 0.30777299, + -0.94960326 0.024721107 0.31247807, + -0.93276435 0.028430309 0.35936412, + -0.93014234 0.035201412 0.36550811, + -0.91101468 0.039531887 0.41047484, + -0.90744269 0.047984783 0.41742685, + -0.88611311 0.052929007 0.46043706, + -0.88157743 0.062943228 0.46782422, + -0.85840368 0.068401679 0.50839382, + -0.85278499 0.080152698 0.51607502, + -0.82793701 0.0860705 0.55417699, + -0.82117188 0.099641584 0.56191492, + -0.79451412 0.10602602 0.59791803, + -0.7865417 0.12151895 0.60546279, + -0.75820398 0.128304 0.63926899, + -0.74957275 0.14471996 0.64590776, + -0.72007775 0.15170994 0.67710578, + -0.71142006 0.16801201 0.68238807, + -0.68065178 0.17514594 0.71136278, + -0.67047125 0.19426507 0.71605122, + -0.63830221 0.20155704 0.74293017, + -0.62713081 0.22258694 0.74643284, + -0.59371388 0.22994894 0.77112085, + -0.5818612 0.25246409 0.77311027, + -0.54788774 0.25968587 0.79522467, + -0.53544211 0.28370607 0.79549515, + -0.50112283 0.29069391 0.81509072, + -0.48829705 0.31602702 0.81344509, + -0.45357579 0.32274184 0.83072656, + -0.44064012 0.34910208 0.82702118, + -0.40564683 0.35545883 0.84208059, + -0.40673086 0.35310289 0.84254873, + -0.37502107 0.35830903 0.8549701, + -0.3873851 0.32724109 0.86188519, + -0.3538008 0.33199778 0.87441546, + -0.36399317 0.30124414 0.88134044, + -0.32845092 0.30548695 0.89375478, + -0.3366999 0.27501693 0.90055478, + -0.29897997 0.27870998 0.91265088, + -0.30553597 0.24831897 0.91923088, + -0.26630107 0.25137207 0.93053526, + -0.2713711 0.22096308 0.93676734, + -0.23070607 0.22338507 0.94703424, + -0.2344631 0.19304708 0.95276433, + -0.19241403 0.19487204 0.96177012, + -0.19504796 0.16457295 0.96688777, + -0.151677 0.16585401 0.97441602, + -0.15339206 0.13544205 0.97883934, + -0.10950094 0.13623995 0.98460555, + -0.11048596 0.10564797 0.98824662, + -0.066321202 0.106065 0.992145, + -0.066769622 0.07545343 0.99491137, + -0.022475293 0.075602971 0.99688464, + -0.022574907 0.045035515 0.99873036, + 0.021903006 0.045036212 0.99874526, + 0.021804808 0.075580433 0.99690133, + 0.066216692 0.07543239 0.99494988, + 0.065782167 0.10598395 0.99218953, + 0.11002396 0.10556896 0.98830664, + 0.10902904 0.13619405 0.98466438, + 0.15300307 0.13539805 0.97890633, + 0.15127203 0.16593504 0.97446525, + 0.19461897 0.16465698 0.96695989, + 0.19196901 0.19504499 0.961824, + 0.23402703 0.19322203 0.9528361, + 0.23027395 0.22353594 0.94710374, + 0.27077103 0.22112803 0.93690211, + 0.26571 0.251432 0.93068802, + 0.30496505 0.24838306 0.91940325, + 0.29843488 0.27861691 0.91285771, + 0.3362439 0.27492294 0.90075374, + 0.32804909 0.30518007 0.89400727, + 0.36375004 0.30092704 0.88154912, + 0.3536599 0.33137992 0.8747068, + 0.38745207 0.32660303 0.86209714, + 0.37517017 0.35749018 0.85524744, + 0.40716591 0.35224491 0.8426978, + 0.40565407 0.35553002 0.8420471, + 0.44062701 0.34917599 0.82699698, + 0.45372412 0.32248309 0.83074617, + 0.48847705 0.31576404 0.81343913, + 0.50135219 0.2903221 0.81508231, + 0.53568184 0.28333592 0.79546571, + 0.54810184 0.25934991 0.7951867, + 0.58209991 0.25212598 0.77304089, + 0.59385306 0.22979003 0.77106112, + 0.62728792 0.22242597 0.74634892, + 0.63824403 0.20180003 0.74291408, + 0.67039698 0.19450399 0.71605599, + 0.68041396 0.17570299 0.71145296, + 0.71114093 0.16856399 0.68254292, + 0.72010702 0.15169001 0.67707902, + 0.74959594 0.14470199 0.64588493, + 0.7584309 0.12788899 0.63908297, + 0.78679198 0.121113 0.60521901, + 0.7948063 0.10551903 0.59761924, + 0.82143998 0.0991605 0.56160802, + 0.82820868 0.08556097 0.55384982, + 0.8530609 0.079666495 0.51569396, + 0.85863811 0.067982905 0.50805408, + 0.8817693 0.062558122 0.46751419, + 0.88622409 0.052712306 0.46024805, + 0.907547 0.0477846 0.41722301, + 0.91099727 0.039617416 0.41050515, + 0.93012524 0.035278209 0.36554408, + 0.93264741 0.028771713 0.35964018, + 0.94950461 0.025020791 0.31275389, + 0.95110601 0.0204194 0.308189, + 0.9656899 0.017168999 0.25912997, + 0.96698225 0.012886803 0.25451806, + 0.97910833 0.010282304 0.20307907, + 0.98159701 -0.000145873 0.190964, + 0.99015933 -0.00010690104 0.13994505, + 0.9914391 -0.007811971 0.13033602, + 0.99675989 -0.0048124394 0.080291189, + 0.99714565 -0.0087905973 0.074987873, + 0.99967051 -0.0029886186 0.025494287, + 0.99970686 -0.0041425894 0.023854697, + 0.99968755 0.0042765983 -0.024626389, + 0.99971867 0.0052669081 -0.023128593, + 0.99723065 0.016513094 -0.07251408, + 0.99747574 0.019072097 -0.068398587, + 0.99240887 0.033031695 -0.11846299, + 0.99297535 0.036489613 -0.11255503, + 0.98500162 0.053211082 -0.16413493, + 0.98590475 0.056982987 -0.15730496, + 0.97446722 0.076472215 -0.21110605, + 0.97555715 0.079801507 -0.20474403, + 0.96000123 0.10168202 -0.26088005, + 0.96090537 0.10377404 -0.25669408, + 0.94006824 0.12780303 -0.3161301, + 0.93983978 0.12739398 -0.31697291, + 0.91195971 0.15300094 -0.38068384, + 0.90907079 0.14894497 -0.3891089, + 0.87182128 0.17510706 -0.45745516, + 0.86488813 0.16724502 -0.47328407, + 0.8163588 0.19242695 -0.54454589, + 0.089667074 0.032117993 -0.99545377, + 0.09015099 0.032617997 -0.99539387, + 0.14621601 0.032399401 -0.98872203, + 0.18124704 0.065014318 -0.98128623, + 0.249797 0.064013503 -0.96618003, + 0.29216194 0.10032897 -0.95109177, + 0.37125397 0.097408585 -0.92340785, + 0.42507207 0.14121501 -0.89407611, + 0.50979418 0.13421604 -0.84976232, + 0.52723086 0.14811897 -0.83671284, + 0.61017627 0.13810304 -0.78013629, + 0.64196795 0.16382599 -0.74902493, + 0.70103616 0.15237203 -0.69665718, + 0.74740106 0.19191302 -0.63605106, + 0.79728532 0.17435905 -0.5778712, + 0.79725879 0.17431895 -0.5779199, + 0.7346378 0.19592595 -0.64955384, + 0.71142679 0.17651996 -0.68022984, + 0.63591093 0.19385198 -0.74701995, + 0.62014878 0.18136793 -0.76323068, + 0.53675699 0.195067 -0.82087803, + 0.48280883 0.15292095 -0.86227071, + 0.39763591 0.16022296 -0.90344578, + 0.35041797 0.12236299 -0.92856586, + 0.27183488 0.12572794 -0.95409554, + 0.22963311 0.089608647 -0.96914345, + 0.16217692 0.090849958 -0.98257053, + 0.16344796 0.09204448 -0.98224878, + 0.39800009 0.34702209 -0.84921819, + 0.53343481 0.47842282 -0.69753778, + 0.50376606 0.48860306 -0.71238106, + 0.37291098 0.35169896 -0.85862988, + 0.39831999 0.347673 -0.84880197, + 0.25419608 0.20603707 -0.94495136, + 0.27770594 0.20465496 -0.93861377, + 0.17622794 0.11091396 -0.97808063, + 0.18536301 0.11072502 -0.97641212, + 0.32110688 0.23015492 -0.91865063, + 0.29576203 0.23215203 -0.92662311, + 0.45092911 0.37771708 -0.80869818, + 0.46981606 0.37357202 -0.79982311, + 0.46854281 0.37118587 -0.80167872, + 0.59227675 0.48026583 -0.64695674, + 0.5465399 0.49915987 -0.67240882, + 0.62675881 0.5779689 -0.52261388, + 0.58306295 0.60260493 -0.54488993, + 0.63753301 0.662094 -0.393933, + 0.59540069 0.69045866 -0.41080979, + 0.63200104 0.73479909 -0.24626203, + 0.59061098 0.76512998 -0.25642699, + 0.13475594 0.10127696 -0.98568952, + 0.11904501 0.10148201 -0.98768914, + 0.27226695 0.28472993 -0.91912979, + 0.25188297 0.28636798 -0.92441785, + 0.38458177 0.45557174 -0.80283952, + 0.36174679 0.46010473 -0.81082851, + 0.470889 0.60820597 -0.63902199, + 0.47024989 0.59738886 -0.64960885, + 0.5495742 0.70302624 -0.45135614, + 0.50604099 0.72580099 -0.465978, + 0.41507486 0.85242271 -0.31794387, + 0.45982495 0.8320179 -0.31033397, + 0.45965478 0.83440161 -0.30412385, + 0.50411206 0.8114211 -0.29574803, + 0.53033477 0.84245461 -0.094948754, + 0.52499402 0.84883499 -0.062132198, + 0.5039981 0.81385916 -0.28917006, + 0.5479852 0.78821331 -0.2800571, + 0.54791987 0.79070783 -0.27306595, + 0.59063673 0.76273566 -0.26340589, + 0.55103493 0.70966393 -0.43901893, + 0.59388125 0.68421125 -0.42327315, + 0.53404301 0.612082 -0.58322698, + 0.57791007 0.59082907 -0.56297505, + 0.46383411 0.46748713 -0.7525382, + 0.46577278 0.47424975 -0.74708962, + 0.33999789 0.33613887 -0.87830073, + 0.36421087 0.33288288 -0.8697927, + 0.2155001 0.17944609 -0.95987445, + 0.23705903 0.17852601 -0.95495111, + 0.107965 0.053649899 -0.992706, + 0.10251202 0.053680912 -0.99328226, + 0.19959795 0.15239497 -0.96795475, + 0.18008794 0.15298094 -0.97168165, + 0.33178598 0.31733698 -0.8883779, + 0.30875596 0.31995597 -0.89571089, + 0.44690895 0.47943494 -0.7552579, + 0.4092561 0.45657212 -0.78996921, + 0.52896982 0.59950578 -0.60065275, + 0.49929905 0.61207205 -0.61324406, + 0.38732791 0.4676939 -0.79450583, + 0.41074592 0.46252289 -0.78572279, + 0.27933601 0.30320299 -0.91106498, + 0.30103213 0.30112511 -0.90482229, + 0.14805499 0.12704599 -0.98078489, + 0.16557404 0.12668903 -0.97802621, + 0.046444595 -0.00032256698 -0.99892086, + 0.044149697 -0.00032260397 -0.99902487, + 0.031275406 -0.025349906 -0.99918926, + 0.020605301 -0.025356904 -0.99946612, + 0.10704906 0.076499134 -0.99130648, + 0.093105875 0.076606981 -0.99270475, + 0.24542002 0.26814103 -0.93159515, + 0.22624694 0.26942796 -0.93606675, + 0.35924289 0.44794786 -0.81871068, + 0.33710486 0.45189479 -0.82592458, + 0.4513078 0.61522168 -0.6463927, + 0.42343292 0.5988639 -0.67975479, + 0.50475585 0.71911383 -0.47759488, + 0.46070519 0.73934925 -0.49103317, + 0.37814915 0.59812021 -0.70658022, + 0.45962995 0.73262495 -0.50199693, + 0.41589892 0.75019681 -0.51403588, + 0.33515596 0.59558094 -0.73003691, + 0.41507486 0.74358875 -0.52420282, + 0.37182197 0.7587229 -0.53487194, + 0.4152981 0.8501792 -0.32360908, + 0.3701759 0.86819482 -0.33046591, + 0.3908129 0.91780174 -0.070036985, + 0.35742411 0.93394136 -0.0013078605, + 0.35447398 0.9263339 -0.12748998, + 0.35457113 0.92629737 -0.12748605, + 0.35752192 0.93390375 -0.0013610696, + 0.29791602 0.95128411 -0.07940121, + 0.28013405 0.89333326 -0.35139808, + 0.32529899 0.87998003 -0.34614399, + 0.28575391 0.77033371 -0.57002681, + 0.32813087 0.7593447 -0.56189483, + 0.25600684 0.58726865 -0.76783854, + 0.11894899 0.98289585 -0.14059499, + 0.11879405 0.98291433 -0.14059705, + 0.15843804 0.98235822 -0.099346824, + 0.14800496 0.91658074 -0.3714489, + 0.19201402 0.90954214 -0.36859703, + 0.16495205 0.7784853 -0.60560024, + 0.2044569 0.77262366 -0.60104072, + 0.15792105 0.59163314 -0.79058915, + 0.19093002 0.58812904 -0.78590709, + 0.11774303 0.3528761 -0.92823225, + 0.14132001 0.35178199 -0.92535299, + 0.059850808 0.11409701 -0.99166512, + 0.053558808 0.11413801 -0.99202013, + 0.022262799 0.99120986 -0.13041198, + 0.021926206 0.99131823 -0.12964404, + 0.0220678 0.99131501 -0.12964401, + 0.06718903 0.99057847 -0.11933106, + 0.062726386 0.92412877 -0.37689692, + 0.105211 0.92081302 -0.375545, + 0.089524254 0.78050464 -0.6187067, + 0.12707798 0.77729785 -0.61616492, + 0.096180581 0.58295888 -0.8067888, + 0.12662698 0.58095992 -0.80402189, + 0.074257895 0.33042097 -0.9409079, + 0.094376162 0.32985687 -0.93930167, + 0.02852531 0.07855773 -0.99650139, + 0.037369292 0.078534774 -0.99621075, + -0.038434297 -0.15916298 -0.9865039, + -0.041472796 -0.15914398 -0.98638386, + -0.073758803 -0.2441 -0.966941, + -0.081164904 -0.24395902 -0.9663831, + -0.079913802 -0.241142 -0.96719402, + -0.072417863 -0.24128088 -0.96774954, + -0.072098598 -0.240668 -0.96792603, + -0.060080417 -0.24086106 -0.96869826, + -0.058018021 -0.23745909 -0.96966338, + -0.040680818 -0.23766312 -0.97049546, + -0.034622092 -0.22898194 -0.97281474, + -0.010490997 -0.22910695 -0.97334474, + -0.010860196 -0.22956991 -0.97323161, + 0.018406203 -0.22954406 -0.97312427, + 0.036512498 -0.20940597 -0.97714686, + 0.07535021 -0.20895003 -0.9750191, + 0.10330603 -0.18076305 -0.97808623, + 0.154287 -0.17955901 -0.971573, + 0.18336706 -0.15238807 -0.97116137, + 0.24587491 -0.15025695 -0.95758462, + 0.28109413 -0.11894606 -0.95228046, + 0.353443 -0.115944 -0.92824298, + 0.38512081 -0.088264354 -0.91863561, + 0.46295795 -0.084774889 -0.88231689, + 0.48568276 -0.064658269 -0.87174058, + 0.56421804 -0.061070208 -0.82336414, + 0.57699096 -0.049305592 -0.81526089, + 0.65221369 -0.045761079 -0.75665265, + 0.65586215 -0.04218531 -0.75370115, + 0.72474962 -0.03850428 -0.68793565, + 0.72164518 -0.041799311 -0.69100016, + 0.78324085 -0.037539694 -0.62058395, + 0.77548516 -0.04656731 -0.62964618, + 0.83017039 -0.041120019 -0.55599123, + 0.82018518 -0.053998113 -0.56954414, + 0.8684687 -0.046791285 -0.49353081, + 0.85753256 -0.062582768 -0.51060873, + 0.89965874 -0.053113688 -0.43335092, + 0.88904613 -0.070468009 -0.45236206, + 0.92558497 -0.058265202 -0.37402901, + 0.91551614 -0.07718581 -0.39480707, + 0.94708955 -0.06158457 -0.31500584, + 0.94089735 -0.075445428 -0.33018211, + 0.96675187 -0.056962293 -0.24929097, + 0.9663915 -0.058020473 -0.25044188, + 0.98409635 -0.040091414 -0.17305206, + 0.98374754 -0.041608382 -0.17466991, + 0.99457598 -0.024102701 -0.101182, + 0.99441034 -0.025369609 -0.10249203, + 0.99943274 -0.0080919284 -0.032690991, + 0.99941242 -0.008585575 -0.033181582, + 0.99945134 0.0082974229 0.03206791, + 0.99942964 0.0088498574 0.032590687, + 0.99509376 0.025926894 0.095479079, + 0.99488527 0.027763808 0.097121522, + 0.98659998 0.044845 0.156874, + 0.98599535 0.04817652 0.15966307, + 0.97403365 0.065401778 0.21675092, + 0.97279924 0.070453614 0.22067606, + 0.9573549 0.087870091 0.27522796, + 0.95551223 0.093972825 0.27958107, + 0.93713367 0.11118396 0.33078489, + 0.93537414 0.11619201 0.33402804, + 0.91435379 0.13303196 0.3824389, + 0.9117319 0.13968998 0.38630494, + 0.88810831 0.15630206 0.43224216, + 0.88432574 0.16504596 0.43672392, + 0.8581816 0.18147591 0.48019877, + 0.85314286 0.19223997 0.48496494, + 0.82489699 0.20830899 0.52550203, + 0.81839073 0.22131793 0.53033483, + 0.78814131 0.2370441 0.56801718, + 0.78009486 0.25225297 0.57255596, + 0.747769 0.267694 0.60760301, + 0.73803002 0.285245 0.61151201, + 0.70379674 0.30030888 0.64380479, + 0.70859176 0.29175988 0.64247477, + 0.67807525 0.30390513 0.66922021, + 0.69447774 0.2722199 0.66603076, + 0.66334873 0.2831139 0.69268674, + 0.67737406 0.25276303 0.69085103, + 0.6449948 0.26257294 0.71766084, + 0.65705228 0.2330461 0.71691835, + 0.62324005 0.24176003 0.74372303, + 0.63358182 0.21270895 0.74386084, + 0.59860605 0.22023302 0.77017415, + 0.60740322 0.19139607 0.77099228, + 0.57105494 0.19778597 0.79672891, + 0.57838005 0.16918302 0.79803109, + 0.54026204 0.17451902 0.82320112, + 0.54623419 0.14595006 0.82481933, + 0.50612503 0.15027602 0.84926713, + 0.51085597 0.121542 0.85103101, + 0.46937183 0.12484196 0.87413073, + 0.47292799 0.095923796 0.87586403, + 0.42999378 0.098289557 0.89746559, + 0.43245307 0.069511205 0.89897311, + 0.38807586 0.071050778 0.91888463, + 0.34190008 0.072102718 0.93696624, + 0.38715693 0.070742793 0.91929591, + 0.38487408 0.099959426 0.91754025, + 0.42865992 0.097846977 0.89815176, + 0.4253059 0.12717597 0.89606977, + 0.46746087 0.12421897 0.87524277, + 0.46295005 0.15339701 0.8730101, + 0.50368607 0.14950301 0.85085213, + 0.49792701 0.178499 0.84864998, + 0.53725517 0.17360106 0.8253603, + 0.53011692 0.20261496 0.82336086, + 0.56748921 0.19675007 0.7995283, + 0.55883908 0.22597703 0.79789311, + 0.59449375 0.21911693 0.77366972, + 0.58424187 0.24854393 0.7725848, + 0.61862791 0.24061294 0.7479338, + 0.60659599 0.27046901 0.74758798, + 0.63988119 0.26144207 0.7226342, + 0.62580782 0.29205194 0.72323585, + 0.65771806 0.28205004 0.69846606, + 0.64118993 0.31390098 0.70024395, + 0.6718868 0.30296794 0.67585385, + 0.66740704 0.31087303 0.67670208, + 0.70183074 0.29736787 0.64730674, + 0.71256465 0.27841687 0.6439997, + 0.74586403 0.26432604 0.61140704, + 0.75500584 0.24758095 0.60718191, + 0.78636086 0.23325297 0.57203996, + 0.79397231 0.21867907 0.56726319, + 0.82331151 0.20415989 0.52960068, + 0.82942313 0.19182703 0.52465206, + 0.85683787 0.17704898 0.48423395, + 0.8616302 0.16675505 0.47936013, + 0.88703376 0.15169796 0.4360719, + 0.89056587 0.14352098 0.43161795, + 0.91354769 0.12833695 0.38595384, + 0.91607171 0.12194396 0.38202384, + 0.93657124 0.10657603 0.3338801, + 0.93918663 0.099134065 0.32878688, + 0.95700061 0.08374127 0.27773592, + 0.95892847 0.077321336 0.27290612, + 0.97383976 0.061943684 0.21862996, + 0.97496438 0.057317823 0.21484707, + 0.98651087 0.042195495 0.15816398, + 0.98706222 0.039151911 0.15548404, + 0.99506563 0.02422769 0.096215665, + 0.99525797 0.022533201 0.094624601, + 0.9994489 0.007689679 0.032291595, + 0.99946898 0.0071791802 0.0317844, + 0.99943167 -0.0074272272 -0.032882489, + 0.99945015 -0.0069786711 -0.032414604, + 0.99458265 -0.021878192 -0.10161997, + 0.99471927 -0.020841705 -0.10049503, + 0.98417813 -0.035980504 -0.17349002, + 0.98444813 -0.034820404 -0.17219001, + 0.96713197 -0.050399501 -0.24923, + 0.97080314 -0.039375104 -0.23662403, + 0.94792014 -0.052281909 -0.31418803, + 0.95447546 -0.036644917 -0.29603016, + 0.92690802 -0.0461041 -0.372446, + 0.93447465 -0.03097209 -0.35467988, + 0.90172511 -0.037607905 -0.43067107, + 0.91015702 -0.023134399 -0.41361701, + 0.87160611 -0.027375404 -0.48944205, + 0.88000703 -0.0148014 -0.47473001, + 0.83485919 -0.017154204 -0.55019611, + 0.84229028 -0.0073436326 -0.53897417, + 0.79010397 -0.0083510904 -0.61291599, + 0.79456514 -0.0031001805 -0.60717106, + 0.73454219 -0.0034646608 -0.67855418, + 0.73390096 -0.0041453796 -0.67924392, + 0.66560417 -0.0045545609 -0.74629116, + 0.65699881 -0.012920598 -0.75378084, + 0.58140379 -0.013944095 -0.8134957, + 0.56251508 -0.031122504 -0.82620114, + 0.48315713 -0.032957409 -0.87491316, + 0.452865 -0.059418101 -0.889597, + 0.3746101 -0.061790716 -0.92512125, + 0.33688885 -0.094445258 -0.93679559, + 0.26522794 -0.096716374 -0.95932275, + 0.23073809 -0.12737805 -0.96464235, + 0.16951798 -0.12901498 -0.97704589, + 0.13364205 -0.16281205 -0.97756433, + 0.085419975 -0.16368395 -0.98280776, + 0.061112378 -0.18859492 -0.98015165, + 0.023766397 -0.18889397 -0.9817099, + 0.021924006 -0.19100004 -0.98134524, + -0.0092819082 -0.19103795 -0.98153877, + -0.019836506 -0.20467904 -0.97862822, + -0.042870704 -0.20453003 -0.97792113, + -0.047918908 -0.21197703 -0.97609913, + -0.064561203 -0.211778 -0.97518301, + -0.06705863 -0.21602011 -0.97408348, + -0.078421026 -0.21584107 -0.97327435, + -0.08149717 -0.22191292 -0.97165465, + -0.075625487 -0.22201595 -0.97210574, + -0.038583007 -0.13769303 -0.98972327, + -0.037093502 -0.137701 -0.989779, + 0.050064009 0.095005013 -0.9942171, + 0.03947458 0.095049955 -0.99468952, + 0.11653806 0.34008616 -0.9331454, + 0.094852298 0.34087601 -0.93531102, + 0.15795298 0.58434892 -0.79598188, + 0.12630795 0.58703876 -0.79964471, + 0.16535099 0.7753579 -0.60949093, + 0.12663205 0.77985132 -0.61302227, + 0.14819904 0.91601527 -0.37276408, + 0.10509104 0.92111439 -0.37483913, + 0.11222301 0.98451209 -0.13469201, + 0.11935297 0.98743874 -0.10353497, + 0.12000702 0.99276513 0.0039736005, + 0.12015503 0.99274725 0.0039735911, + 0.119999 0.99276602 0.0039875, + 0.16852292 0.98568255 -0.0054698973, + 0.16681498 0.97579986 -0.14137699, + 0.16673002 0.9758141 -0.14137901, + 0.20493603 0.97446209 -0.091787905, + 0.19172397 0.91052788 -0.36630696, + 0.23607901 0.90151501 -0.362681, + 0.20412596 0.77666885 -0.59591788, + 0.244497 0.76929402 -0.59026098, + 0.19131291 0.5969677 -0.77912062, + 0.22589993 0.59247988 -0.77326381, + 0.14355201 0.36704701 -0.91905898, + 0.16367006 0.36588711 -0.91615433, + 0.17862798 0.37330797 -0.91034788, + 0.16340208 0.37431017 -0.9127934, + 0.25465408 0.59811324 -0.75987631, + 0.22680187 0.60238564 -0.76530552, + 0.28572491 0.76498473 -0.57719982, + 0.24431796 0.77407187 -0.58405596, + 0.28046501 0.89173198 -0.35518101, + 0.23575106 0.90283322 -0.35960209, + 0.21457796 0.96673876 -0.13918497, + 0.25144696 0.9641369 -0.084937893, + 0.26183689 0.95545954 -0.13615593, + 0.26178887 0.95547253 -0.13615695, + 0.26420513 0.96419746 -0.022783911, + 0.31126085 0.9503215 0.0023617588, + 0.30848911 0.94196433 -0.13243005, + 0.30843315 0.94198245 -0.13243206, + 0.31120497 0.95033985 0.0023566799, + 0.31138888 0.95027965 0.0023566291, + 0.30862284 0.94194353 -0.13226594, + 0.34443 0.93582797 -0.074793696, + 0.32498688 0.88183969 -0.34167588, + 0.37044981 0.86611259 -0.33558285, + 0.32841396 0.76528591 -0.55360794, + 0.37126404 0.75231713 -0.54422605, + 0.29458901 0.59191501 -0.75023597, + 0.096440434 0.15648706 -0.98296034, + -0.022008901 -0.08350721 -0.9962641, + -0.024141004 -0.083503105 -0.99621511, + 0.10845298 0.16134596 -0.98092073, + 0.097053356 0.16153793 -0.98208255, + 0.21133192 0.38904786 -0.89664972, + 0.19468592 0.39042184 -0.89981568, + 0.29370204 0.60267204 -0.74197406, + 0.27629703 0.60593504 -0.74599105, + 0.17856905 0.38220009 -0.90666223, + 0.194515 0.381024 -0.90387201, + 0.079057232 0.13627705 -0.98751134, + 0.073973969 0.13633096 -0.98789763, + 0.073659606 0.13144502 -0.98858315, + -0.03196789 -0.11266496 -0.99311864, + -0.031527691 -0.11266597 -0.99313265, + -0.073336266 -0.19609591 -0.97783852, + -0.077471986 -0.19603495 -0.97753179, + -0.071977064 -0.18643291 -0.97982752, + -0.056005485 -0.18662396 -0.98083377, + -0.050610408 -0.17844102 -0.98264813, + -0.028370401 -0.178598 -0.983513, + -0.019368198 -0.16664998 -0.9858259, + 0.010511303 -0.16667207 -0.98595637, + 0.026851695 -0.14747797 -0.98870075, + 0.066461377 -0.14720494 -0.98687065, + 0.071086764 -0.14234893 -0.98726052, + 0.11795203 -0.14171404 -0.98285526, + 0.14887998 -0.11226597 -0.98246175, + 0.20759195 -0.11105797 -0.97189075, + 0.25087607 -0.072543517 -0.96529722, + 0.32173812 -0.070955426 -0.94416636, + 0.3596471 -0.038392909 -0.93229824, + 0.43801394 -0.036988895 -0.89820689, + 0.47494093 -0.0052749496 -0.8800019, + 0.55519402 -0.0049854601 -0.83170599, + 0.58125889 0.018262396 -0.81351382, + 0.6575228 0.016909396 -0.75324482, + 0.67134321 0.030124007 -0.74053419, + 0.73944384 0.027362993 -0.67266184, + 0.74408478 0.032242388 -0.66730678, + 0.80293584 0.028766593 -0.59537089, + 0.80143011 0.026993403 -0.59747905, + 0.8516283 0.02365621 -0.5236122, + 0.84676111 0.017145703 -0.53169703, + 0.88928598 0.0147407 -0.45711401, + 0.88284898 0.0048516402 -0.469632, + 0.91846037 0.0040857312 -0.39549214, + 0.91192585 -0.0075764488 -0.41028494, + 0.94157398 -0.0062185102 -0.33674899, + 0.93554688 -0.018909998 -0.35269597, + 0.96002823 -0.014985603 -0.27950206, + 0.95509362 -0.027547991 -0.29502088, + 0.97491264 -0.020694492 -0.22162393, + 0.97114211 -0.032789104 -0.23623703, + 0.98637223 -0.022619305 -0.16296704, + 0.98456424 -0.030576207 -0.17233205, + 0.99484688 -0.017712198 -0.099829383, + 0.99472713 -0.018610202 -0.10085402, + 0.99946475 -0.0059364587 -0.032171294, + 0.99944925 -0.0063080415 -0.032578409, + 0.99948525 0.0060987715 0.031497706, + 0.9994669 0.0065632393 0.031982195, + 0.99541026 0.019238103 0.093746021, + 0.99523222 0.020803906 0.09529002, + 0.98749036 0.033632711 0.15405107, + 0.98697925 0.036455806 0.15666205, + 0.97581124 0.04954851 0.21292605, + 0.97478187 0.053794291 0.21657898, + 0.96035975 0.067197986 0.27054295, + 0.95859414 0.073110506 0.27523103, + 0.94136226 0.086619921 0.32608908, + 0.93864489 0.094398282 0.33171496, + 0.91874987 0.10807198 0.37976193, + 0.91527909 0.11687002 0.38549405, + 0.89288068 0.13064395 0.43092486, + 0.8894971 0.13847001 0.43545505, + 0.86478621 0.15216704 0.47852913, + 0.86027414 0.16189002 0.48344606, + 0.83361381 0.17538996 0.52376187, + 0.82779181 0.18721895 0.52887589, + 0.79930001 0.200532 0.566486, + 0.79211468 0.21443492 0.57146484, + 0.76162201 0.227662 0.60671401, + 0.75296885 0.24373494 0.61125386, + 0.72056675 0.2568199 0.64407074, + 0.71042997 0.27502596 0.64780396, + 0.67686898 0.28766301 0.67756802, + 0.66526568 0.30796286 0.68013269, + 0.63071072 0.32009384 0.70692563, + 0.63481694 0.31284797 0.70649391, + 0.60361093 0.32281598 0.72900194, + 0.62003988 0.29091293 0.72864282, + 0.58744693 0.30006897 0.75157487, + 0.60138077 0.26929292 0.75221169, + 0.56771791 0.27746993 0.77505285, + 0.57956606 0.24737804 0.77647114, + 0.54469019 0.25457609 0.79906428, + 0.55471814 0.22486606 0.80107617, + 0.51814592 0.23114997 0.82346487, + 0.52654493 0.20159297 0.8258999, + 0.488051 0.20696899 0.84792101, + 0.49491605 0.17759801 0.8505981, + 0.45502114 0.18200006 0.8716833, + 0.46050811 0.15264003 0.87443316, + 0.41926116 0.15611506 0.8943423, + 0.42349085 0.12659895 0.89701068, + 0.38055894 0.12923399 0.9156819, + 0.38365316 0.09956494 0.91809434, + 0.33907908 0.10142802 0.93527424, + 0.34114715 0.071857035 0.93725944, + 0.29572016 0.073023938 0.95247948, + 0.24955308 0.073779933 0.96554637, + 0.29501513 0.072799422 0.95271534, + 0.29318103 0.10266201 0.9505291, + 0.33792716 0.10106404 0.9357304, + 0.33512211 0.13103405 0.93301839, + 0.37886882 0.12870795 0.91645658, + 0.37496409 0.15852804 0.91338426, + 0.41699579 0.15542692 0.89552057, + 0.41186684 0.18508895 0.89224869, + 0.45218286 0.18116494 0.87333268, + 0.44568378 0.21082589 0.87001055, + 0.48463717 0.20600407 0.85011131, + 0.47661093 0.23580196 0.84689987, + 0.51409906 0.23006603 0.82630014, + 0.50441927 0.25998613 0.8233884, + 0.54005307 0.25341502 0.80257314, + 0.52853721 0.28365314 0.80011839, + 0.56248307 0.27626902 0.7792871, + 0.54886287 0.30711794 0.77744985, + 0.58161205 0.29887202 0.75657314, + 0.56549329 0.33073214 0.75553536, + 0.59712714 0.32166708 0.73482621, + 0.59345001 0.32822299 0.73490602, + 0.62840182 0.3172189 0.71026981, + 0.64069223 0.29569113 0.70857626, + 0.67453873 0.28430784 0.68129772, + 0.68553704 0.26472303 0.67820406, + 0.71829182 0.25297993 0.64811879, + 0.72792292 0.23542698 0.64397395, + 0.75948828 0.22336207 0.61097223, + 0.76770115 0.20793103 0.60613507, + 0.79737788 0.19581898 0.57082695, + 0.80422914 0.18245402 0.56562006, + 0.8319571 0.17033401 0.52804708, + 0.83747786 0.15906498 0.52280897, + 0.86342686 0.14684099 0.48262995, + 0.86775088 0.13751498 0.47759596, + 0.89181721 0.12517403 0.43473408, + 0.89619428 0.11502705 0.42849115, + 0.91797978 0.10283197 0.3830649, + 0.92154163 0.09374547 0.37679285, + 0.94084877 0.081805676 0.32880291, + 0.94334489 0.074618593 0.32331496, + 0.96004498 0.062932201 0.27267799, + 0.96167588 0.057453293 0.26810196, + 0.97563988 0.045968197 0.21450797, + 0.976596 0.042022001 0.21093699, + 0.98741353 0.030900786 0.15511192, + 0.98788714 0.028288504 0.15257402, + 0.99538678 0.017490696 0.094335474, + 0.99554998 0.016062301 0.0928564, + 0.99948347 0.005478153 0.031669315, + 0.99949878 0.0050898585 0.031243892, + 0.99946409 -0.0052636503 -0.032310702, + 0.99947864 -0.0049161883 -0.031910889, + 0.99486578 -0.015409696 -0.10002298, + 0.99548751 -0.010627096 -0.094295852, + 0.9864729 -0.018357798 -0.16289298, + 0.98828566 -0.0098188166 -0.15229894, + 0.97514486 -0.014255098 -0.22110897, + 0.97799766 -0.0044667288 -0.20856793, + 0.96050179 -0.0059582088 -0.27820995, + 0.96443522 0.0046168608 -0.26427907, + 0.9424479 0.0058401395 -0.33430198, + 0.94714421 0.016154803 -0.3204011, + 0.92000097 0.019735601 -0.39141899, + 0.925111 0.0291271 -0.37857801, + 0.89191121 0.034689806 -0.45087811, + 0.89644212 0.041760605 -0.44118905, + 0.85598987 0.048717994 -0.51469195, + 0.8586399 0.052271493 -0.50990695, + 0.80994886 0.059809793 -0.58344293, + 0.80843037 0.058039024 -0.58572328, + 0.75024486 0.065194793 -0.65793794, + 0.74154323 0.056222517 -0.66854525, + 0.67315668 0.06197077 -0.73689866, + 0.65315878 0.043321684 -0.75598073, + 0.5758701 0.046772812 -0.81620216, + 0.5431928 0.018339993 -0.83940768, + 0.46212313 0.019371204 -0.88660425, + 0.4241311 -0.012733603 -0.90551126, + 0.34580782 -0.013193393 -0.93821251, + 0.29711503 -0.054708809 -0.95327312, + 0.22819503 -0.055784408 -0.9720161, + 0.19100505 -0.089007922 -0.97754526, + 0.13333896 -0.089867674 -0.98698765, + 0.12538403 -0.097595923 -0.98729622, + 0.075975738 -0.098087944 -0.99227345, + 0.052561089 -0.12325797 -0.99098176, + 0.014462095 -0.12341595 -0.99224967, + 0.00046010618 -0.14025505 -0.99011534, + -0.028540807 -0.14019702 -0.98971224, + -0.037857186 -0.15288495 -0.98751867, + -0.059217777 -0.15272693 -0.98649263, + -0.068004221 -0.16641305 -0.98370838, + -0.066149428 -0.16643308 -0.98383147, + -0.010644501 -0.068328008 -0.9976061, + -0.00636777 -0.050198 -0.99871898, + 0.12293703 0.17496604 -0.97686923, + 0.11053897 0.17522195 -0.97830379, + 0.22918893 0.3974739 -0.88853079, + 0.21176092 0.39908084 -0.89212769, + 0.31674111 0.61039925 -0.72600824, + 0.33469486 0.60641873 -0.72127366, + 0.22988807 0.4078961 -0.88361323, + 0.24809404 0.40601707 -0.87954509, + 0.12555806 0.18958409 -0.97380346, + 0.13897096 0.18924193 -0.97204661, + -0.0067259278 -0.050197981 -0.99871665, + 0.011667294 -0.030990785 -0.99945152, + -0.052436888 -0.13200797 -0.98986077, + -0.05005978 -0.13202396 -0.98998165, + -0.011621702 -0.012435202 -0.99985522, + 0.017296901 -0.012434202 -0.99977314, + 0.15665302 0.20418903 -0.9663161, + 0.14218293 0.2046409 -0.96845549, + 0.268038 0.41449001 -0.86968601, + 0.24906611 0.4166742 -0.87427044, + 0.35947099 0.613841 -0.70283699, + 0.37809119 0.6089803 -0.69727337, + 0.26931894 0.42561492 -0.8638978, + 0.28920597 0.42305893 -0.85870886, + 0.160423 0.220033 -0.96221101, + 0.17604904 0.21943806 -0.95961124, + -0.0082616173 -0.070710778 -0.99746263, + -0.025644995 -0.093161575 -0.99532074, + -0.031917695 -0.093144692 -0.99514091, + 0.041890603 0.0082534812 -0.99908811, + 0.032505486 0.0082563665 -0.99943751, + -0.0088109756 -0.11332795 -0.99351853, + -0.039123282 -0.11324495 -0.99279654, + -0.039780505 -0.11413901 -0.99266809, + -0.010570899 -0.11422299 -0.9933989, + 0.0035974013 -0.096789934 -0.99529839, + 0.040618218 -0.096710742 -0.99448347, + 0.060840592 -0.074546196 -0.9953599, + 0.10848399 -0.074243695 -0.99132186, + 0.14024505 -0.042799514 -0.98919135, + 0.20062298 -0.042347796 -0.97875285, + 0.21223895 -0.031815294 -0.97669977, + 0.28077799 -0.0312474 -0.95926398, + 0.32233202 0.0040330403 -0.94661814, + 0.39979714 0.0039051315 -0.91659528, + 0.45001614 0.045623314 -0.89185429, + 0.53174978 0.043267079 -0.84579557, + 0.56605792 0.07237839 -0.82118189, + 0.64461499 0.067123003 -0.76155502, + 0.67044294 0.090444691 -0.73642796, + 0.73967576 0.082033873 -0.66794479, + 0.75322247 0.095595062 -0.65078241, + 0.81124818 0.084976323 -0.57849413, + 0.81576389 0.090132795 -0.57131892, + 0.86347359 0.078602366 -0.49823177, + 0.86300433 0.077978827 -0.49914217, + 0.90187597 0.066679798 -0.42681801, + 0.89893061 0.062062468 -0.43367279, + 0.93023312 0.051987007 -0.36326802, + 0.92648113 0.044960402 -0.37364602, + 0.95159036 0.036720514 -0.30516812, + 0.94786775 0.028274992 -0.31740692, + 0.96788448 0.022306411 -0.25040412, + 0.96479303 0.0136098 -0.262658, + 0.98043513 0.0101858 -0.19657902, + 0.97815764 0.0019100093 -0.20785592, + 0.98972303 0.00131397 -0.142992, + 0.98834378 -0.0056518684 -0.15213397, + 0.99611413 -0.0032696605 -0.088011511, + 0.99550301 -0.0083100302 -0.094364598, + 0.99954313 -0.0026513801 -0.030107804, + 0.999479 -0.0042184698 -0.0319997, + 0.99951261 0.0040801484 0.030950289, + 0.99949723 0.0044645811 0.031392708, + 0.99566615 0.013094402 0.092073508, + 0.99552852 0.014290494 0.093374453, + 0.98825276 0.023120595 0.15106897, + 0.98781633 0.025519209 0.15351807, + 0.97732663 0.034720387 0.20887093, + 0.97643566 0.038393587 0.21236593, + 0.9628911 0.048015207 0.26558504, + 0.96137726 0.053106513 0.27006206, + 0.94516999 0.0630133 0.32044199, + 0.94285476 0.069701985 0.32583192, + 0.92410511 0.079938509 0.37368402, + 0.92080587 0.088405095 0.37986994, + 0.89962101 0.098979399 0.42530599, + 0.8951599 0.10938998 0.43211395, + 0.87169832 0.12026104 0.47505718, + 0.86638832 0.13175105 0.48167717, + 0.8411122 0.14269704 0.5216971, + 0.83580983 0.15354897 0.52710986, + 0.80878729 0.16448006 0.56463218, + 0.80226433 0.17728008 0.57003832, + 0.7733379 0.18827596 0.60539293, + 0.76548511 0.20316803 0.61053705, + 0.7346788 0.21420695 0.64370984, + 0.72551703 0.23111403 0.64823705, + 0.69349498 0.241947 0.67862099, + 0.68302 0.26089001 0.682217, + 0.64989394 0.27147198 0.70988792, + 0.63817096 0.29238296 0.71221495, + 0.60384113 0.30271706 0.73738617, + 0.59101522 0.32543212 0.73810226, + 0.55574638 0.33539322 0.76069546, + 0.5589819 0.32950991 0.76089585, + 0.52741611 0.33762708 0.77964115, + 0.5430398 0.30588487 0.78201169, + 0.51019305 0.31329903 0.80096614, + 0.52334422 0.28244415 0.80395037, + 0.48878106 0.28916702 0.82308912, + 0.49983588 0.25883594 0.82653981, + 0.46341106 0.26482004 0.84564811, + 0.47263011 0.23474006 0.84942216, + 0.43479407 0.23987202 0.86799514, + 0.44236493 0.20989697 0.8719269, + 0.40303615 0.21419108 0.88976628, + 0.40911201 0.184287 0.89368099, + 0.36809099 0.187782 0.91062999, + 0.37281209 0.15788405 0.91437626, + 0.3300311 0.16061704 0.93020523, + 0.33356404 0.13055901 0.9336431, + 0.28969291 0.13255195 0.94789666, + 0.29217598 0.10235199 0.95087188, + 0.24736209 0.10369604 0.96335834, + 0.24895009 0.073592126 0.96571636, + 0.20337392 0.074396372 0.97627062, + 0.16929007 0.016128106 0.98543435, + 0.15845996 0.014096996 0.98726475, + 0.15811898 0.044741996 0.98640591, + 0.20424007 0.044356816 0.97791535, + 0.20460998 0.044471998 0.97783285, + 0.25058991 0.043983486 0.96709365, + 0.26497397 0.016178098 0.96411985, + 0.25154603 0.014275902 0.96774012, + 0.25102091 0.044121087 0.96697563, + 0.29693297 0.043524697 0.95390588, + 0.29741785 0.043683376 0.95374751, + 0.34326288 0.042973787 0.93825567, + 0.34451091 0.014536897 0.93866974, + 0.3438381 0.043167312 0.93803626, + 0.38956186 0.042338487 0.92002666, + 0.3909241 0.012563803 0.92033726, + 0.39015001 0.042542499 0.91976798, + 0.43500879 0.041603383 0.89946461, + 0.43340299 0.069839202 0.89849001, + 0.47695011 0.068113312 0.87628722, + 0.47435406 0.096410312 0.8750391, + 0.51657605 0.093771718 0.85109115, + 0.51285315 0.12221003 0.84973317, + 0.55368274 0.11854494 0.82424659, + 0.54880184 0.14678393 0.82296473, + 0.58755577 0.14208396 0.79661173, + 0.58145779 0.17014293 0.79558671, + 0.61838108 0.16435002 0.7685011, + 0.61097795 0.19245097 0.76789886, + 0.6464172 0.18548304 0.7400952, + 0.63759369 0.2138069 0.74010867, + 0.67185456 0.20556588 0.71158558, + 0.66155773 0.23416291 0.71239674, + 0.69423878 0.22474892 0.68375474, + 0.68232608 0.25383404 0.68556505, + 0.71367085 0.24322094 0.65689981, + 0.69989079 0.27318895 0.65993983, + 0.73053837 0.26118812 0.63094729, + 0.71450824 0.29255912 0.63552123, + 0.74480516 0.27903306 0.60614014, + 0.73979378 0.28816491 0.60800177, + 0.7731517 0.2716279 0.57310981, + 0.78177214 0.25558102 0.56878006, + 0.81300002 0.238653 0.53110802, + 0.81990916 0.22499906 0.52642614, + 0.84907186 0.20762096 0.48576793, + 0.85445416 0.19621405 0.48104912, + 0.88141078 0.17839596 0.4373669, + 0.88539529 0.16922006 0.43294314, + 0.90971029 0.15116505 0.38675115, + 0.91254878 0.14395396 0.38279492, + 0.9341231 0.12564501 0.33410704, + 0.93594825 0.12042503 0.33090609, + 0.95476365 0.10169296 0.27943692, + 0.95588112 0.097985514 0.27693003, + 0.97184336 0.07859683 0.22213307, + 0.97300678 0.073858887 0.21863796, + 0.98542464 0.054443881 0.16116494, + 0.98609114 0.050789807 0.15825501, + 0.99468642 0.03146008 0.098025844, + 0.9949159 0.029442597 0.096308984, + 0.99940854 0.010053695 0.032886386, + 0.99943227 0.009448912 0.032341309, + 0.99939185 -0.0097787492 -0.033470295, + 0.99941391 -0.0092421686 -0.032962497, + 0.99422324 -0.028976908 -0.10334703, + 0.99440575 -0.027574293 -0.10196498, + 0.98324138 -0.04759182 -0.17598706, + 0.98366767 -0.045723684 -0.17408994, + 0.96549022 -0.066158712 -0.25189605, + 0.96608633 -0.064386524 -0.25006309, + 0.93972725 -0.085258521 -0.33112508, + 0.939982 -0.084699102 -0.33054501, + 0.90466022 -0.10577602 -0.41279709, + 0.913836 -0.089552999 -0.39608601, + 0.87248939 -0.10775805 -0.47660324, + 0.88660657 -0.086004756 -0.45445779, + 0.84024286 -0.10082199 -0.53275394, + 0.8539983 -0.081843428 -0.51379818, + 0.80202281 -0.093959078 -0.58985686, + 0.81515998 -0.077565096 -0.57401901, + 0.75754535 -0.087413847 -0.64690328, + 0.76846886 -0.074964091 -0.63548094, + 0.70484281 -0.083103277 -0.7044788, + 0.71207124 -0.075507931 -0.69803524, + 0.64229572 -0.082428262 -0.76201165, + 0.64320117 -0.081541523 -0.76134318, + 0.56813598 -0.087637 -0.81825501, + 0.56108278 -0.094169654 -0.82238561, + 0.48332518 -0.099594437 -0.86975729, + 0.46714801 -0.114032 -0.87679499, + 0.3899999 -0.11875697 -0.91312474, + 0.36554208 -0.14028104 -0.92016321, + 0.29299811 -0.14409605 -0.94519234, + 0.26279807 -0.17100905 -0.94957525, + 0.19894807 -0.17369606 -0.96449435, + 0.16851996 -0.20194496 -0.96478975, + 0.11601303 -0.20349105 -0.97217923, + 0.093007773 -0.22636592 -0.96959162, + 0.0515467 -0.22705001 -0.97251803, + 0.030906508 -0.24953605 -0.96787226, + 0.00014970894 -0.24965592 -0.96833462, + -0.012541702 -0.26510802 -0.96413714, + -0.035069693 -0.26496595 -0.96361977, + -0.032986388 -0.26207492 -0.96448362, + -0.051241409 -0.26187304 -0.96374112, + -0.053926218 -0.2661671 -0.96241736, + -0.066547118 -0.26596406 -0.96168321, + -0.066429116 -0.26574406 -0.96175224, + -0.074494891 -0.26559296 -0.96120286, + -0.073277026 -0.26293308 -0.96202737, + -0.077402197 -0.26284999 -0.96172702, + -0.077277638 -0.26252612 -0.96182549, + -0.068809874 -0.26268992 -0.96242362, + -0.041019786 -0.17680594 -0.98339063, + -0.036730394 -0.17683595 -0.98355478, + 0.027516587 0.064927869 -0.99751055, + 0.020072507 0.064939424 -0.99768734, + 0.074321315 0.3216151 -0.94394922, + 0.055557307 0.32200903 -0.94510514, + 0.096642599 0.578381 -0.810022, + 0.067522116 0.57977611 -0.81197315, + 0.089870676 0.77895385 -0.62060785, + 0.05321769 0.78101081 -0.62224591, + 0.062735707 0.92410815 -0.37694606, + 0.020778099 0.92573202 -0.37760901, + -0.39137509 0.011027703 0.92016524, + -0.39057082 0.042211581 0.9196046, + -0.075506471 0.99169463 -0.10411796, + -0.066712528 0.98830348 -0.13713406, + -0.062621459 0.92602646 -0.37222779, + -0.021926088 0.99266654 -0.11887994, + -0.020533405 0.92670625 -0.3752251, + -0.063064322 0.92505634 -0.37455812, + -0.053587165 0.7828365 -0.61991566, + -0.090604052 0.78073847 -0.61825436, + -0.068103686 0.58129787 -0.81083584, + -0.097431377 0.57987887 -0.80885583, + -0.056064215 0.32259208 -0.94487625, + -0.074895486 0.32219291 -0.94370675, + -0.0202318 0.063904099 -0.997751, + -0.0275659 0.063892797 -0.997576, + 0.037898686 -0.18236794 -0.98249966, + 0.042627417 -0.18233305 -0.98231238, + 0.06978149 -0.26621696 -0.96138388, + 0.078534238 -0.26604411 -0.96075648, + 0.077348486 -0.26295793 -0.96170175, + 0.073290832 -0.26303908 -0.96199733, + 0.074427828 -0.26552308 -0.96122736, + 0.066320188 -0.26567495 -0.96177876, + 0.066909373 -0.26677087 -0.96143454, + 0.05442021 -0.26697305 -0.96216625, + 0.05117958 -0.2617909 -0.96376663, + 0.032926615 -0.26199111 -0.96450847, + 0.030892096 -0.25916496 -0.96533889, + 0.0073847137 -0.25928211 -0.96577346, + 0.0049817082 -0.25635591 -0.96656966, + -0.024671804 -0.25628203 -0.96628714, + -0.047768906 -0.23119903 -0.97173309, + -0.08857429 -0.23055397 -0.96901989, + -0.11766603 -0.20166405 -0.97236127, + -0.17046502 -0.20010203 -0.96483213, + -0.20105907 -0.17167006 -0.96441936, + -0.26510394 -0.16897796 -0.94929779, + -0.29468685 -0.14258392 -0.94489652, + -0.36736304 -0.13877602 -0.91966611, + -0.39198795 -0.11707199 -0.9124909, + -0.46906587 -0.11238897 -0.87598276, + -0.48542288 -0.097758979 -0.86879683, + -0.5631181 -0.092402622 -0.82119417, + -0.5700497 -0.085964955 -0.81710058, + -0.64497018 -0.07995902 -0.76001316, + -0.64381725 -0.081091732 -0.76087028, + -0.71335316 -0.074269414 -0.69685817, + -0.70578092 -0.082245491 -0.70363992, + -0.7692402 -0.074180417 -0.6346392, + -0.75758213 -0.087482311 -0.64685106, + -0.81519169 -0.077624969 -0.57396585, + -0.80115771 -0.095112562 -0.59084678, + -0.85333472 -0.082860567 -0.51473683, + -0.83919317 -0.10230003 -0.53412509, + -0.88583356 -0.087282859 -0.4557198, + -0.87179118 -0.10883402 -0.47763512, + -0.9133417 -0.090463974 -0.39701784, + -0.90431225 -0.10637902 -0.41340408, + -0.93976277 -0.08518558 -0.33104292, + -0.9399389 -0.084798694 -0.33064198, + -0.96620363 -0.064039581 -0.24969891, + -0.96570766 -0.065518774 -0.2512289, + -0.98376775 -0.045283888 -0.17363895, + -0.98328888 -0.047388893 -0.17577599, + -0.99442124 -0.027457608 -0.10184602, + -0.99422026 -0.029002508 -0.10336802, + -0.99941355 -0.0092505654 -0.032969985, + -0.99939024 -0.0098188324 -0.033507809, + -0.99943078 0.0094865784 0.032373991, + -0.99940652 0.010105396 0.032931685, + -0.99489897 0.029592801 0.096438102, + -0.99466962 0.031604789 0.098150462, + -0.98604989 0.051017791 0.15843898, + -0.98538864 0.05463608 0.16131994, + -0.97294587 0.074111491 0.21882397, + -0.97184402 0.078594297 0.222131, + -0.95588064 0.097984262 0.27693191, + -0.95488602 0.101287 0.27916601, + -0.93610674 0.11995797 0.3306269, + -0.93418175 0.12547196 0.33400792, + -0.91261023 0.14376903 0.38271809, + -0.90964621 0.15130003 0.38684908, + -0.88532072 0.16936494 0.43303886, + -0.88123488 0.17876698 0.43756995, + -0.85427082 0.19659795 0.48121789, + -0.84887099 0.20803 0.485944, + -0.81968373 0.22543192 0.52659184, + -0.81280082 0.23901995 0.53124785, + -0.78156066 0.25596088 0.56889969, + -0.77319402 0.27153 0.57309902, + -0.73983604 0.28806403 0.60799807, + -0.74403501 0.280424 0.606444, + -0.71384603 0.29392299 0.63563597, + -0.73005879 0.26227191 0.63105273, + -0.69953996 0.27424997 0.65987194, + -0.71355903 0.24380203 0.65680605, + -0.68227774 0.25441492 0.68539774, + -0.69434798 0.224952 0.683577, + -0.66174918 0.23435706 0.71215516, + -0.67214316 0.20547205 0.71134019, + -0.6379478 0.21370195 0.73983383, + -0.64682317 0.18514904 0.73982418, + -0.61129689 0.19213195 0.76772481, + -0.61870706 0.16397402 0.76831913, + -0.58177507 0.16976202 0.79543614, + -0.58782178 0.14187495 0.7964527, + -0.54904002 0.146576 0.82284302, + -0.5538668 0.11864395 0.82410872, + -0.51313311 0.12230703 0.84955019, + -0.51681 0.094189398 0.85090297, + -0.47468677 0.096835956 0.87481159, + -0.47731104 0.068389706 0.87606913, + -0.43389285 0.070119776 0.89823169, + -0.43553421 0.04127622 0.89922541, + -0.43689907 0.010687001 0.89944714, + -0.43604395 0.041458998 0.89896989, + -0.48011705 0.040412202 0.8762731, + -0.47837925 0.06877093 0.87545639, + -0.52108216 0.06684082 0.85088527, + -0.51835316 0.09473294 0.84990329, + -0.55968088 0.091801777 0.8236078, + -0.5558902 0.11934204 0.82264429, + -0.59523392 0.11536498 0.79522789, + -0.59032905 0.14271301 0.79444611, + -0.62782592 0.13761999 0.76609087, + -0.62173486 0.16494295 0.76566285, + -0.65766191 0.15864399 0.73641896, + -0.65027994 0.18619098 0.73652494, + -0.68482298 0.178596 0.70648497, + -0.67604375 0.20655192 0.70731974, + -0.70890582 0.19770496 0.67702681, + -0.69870317 0.22602606 0.67876816, + -0.73010033 0.2158931 0.64833927, + -0.71834004 0.24480604 0.65119708, + -0.74883008 0.23321803 0.62037307, + -0.73526818 0.26313606 0.62461209, + -0.76527917 0.24990606 0.59320712, + -0.74970198 0.28106901 0.59912199, + -0.77907127 0.2662721 0.56758016, + -0.7747491 0.27440703 0.56961805, + -0.80704516 0.25627407 0.53197914, + -0.81424385 0.24225497 0.52755994, + -0.8444339 0.22353297 0.48678994, + -0.850142 0.211568 0.48218, + -0.87799633 0.19232808 0.43832916, + -0.88228989 0.18251298 0.43388194, + -0.90738612 0.16296801 0.38741705, + -0.91046757 0.15516092 0.38337183, + -0.93267179 0.13533197 0.33437791, + -0.93476921 0.12931703 0.33088309, + -0.95403886 0.10908799 0.27912298, + -0.95526576 0.10498198 0.27648893, + -0.97152537 0.084105328 0.22150607, + -0.97206259 0.08190845 0.21996713, + -0.9849081 0.060397107 0.16219802, + -0.98549253 0.057210475 0.15978593, + -0.99445087 0.035462495 0.099045083, + -0.99470311 0.033259302 0.097260617, + -0.99938333 0.011362104 0.033226412, + -0.9994095 0.010696605 0.032655116, + -0.99936712 -0.011073301 -0.033805404, + -0.99939197 -0.0104675 -0.033259399, + -0.99400622 -0.032820009 -0.10428102, + -0.99421901 -0.0311807 -0.102744, + -0.98268491 -0.053806793 -0.17729999, + -0.98321986 -0.051446993 -0.17501998, + -0.96456325 -0.074411117 -0.25314206, + -0.96541947 -0.071835838 -0.25060913, + -0.93858099 -0.095080398 -0.33170101, + -0.93914676 -0.093819976 -0.3304559, + -0.90337688 -0.11712599 -0.41254294, + -0.90240169 -0.11881596 -0.41419086, + -0.8565681 -0.14229302 -0.49602807, + -0.86881942 -0.12453706 -0.47921124, + -0.81700385 -0.14503796 -0.55809391, + -0.83517468 -0.12143195 -0.53641182, + -0.77867609 -0.13853002 -0.61194205, + -0.79570287 -0.11823399 -0.59403497, + -0.73457897 -0.13245198 -0.66546994, + -0.75034797 -0.11504 -0.65095598, + -0.68452543 -0.12686308 -0.71786541, + -0.69632083 -0.11469097 -0.70850784, + -0.62557107 -0.12466802 -0.77014214, + -0.63175815 -0.11865003 -0.76603121, + -0.55675888 -0.12714598 -0.82088584, + -0.55529988 -0.12849997 -0.82166284, + -0.47838089 -0.13568397 -0.86760682, + -0.46840587 -0.14463197 -0.87159485, + -0.39220494 -0.15058398 -0.90746886, + -0.37396881 -0.16671793 -0.91233361, + -0.30167601 -0.17138501 -0.93787998, + -0.27751592 -0.19296493 -0.94114262, + -0.21282603 -0.19625303 -0.95717812, + -0.18670101 -0.22042903 -0.95736814, + -0.13222705 -0.22240408 -0.96594638, + -0.10736602 -0.24684402 -0.96308911, + -0.064016178 -0.24776991 -0.96670163, + -0.041846085 -0.27144891 -0.96154267, + -0.009270031 -0.27167603 -0.96234411, + 0.0069751493 -0.29092696 -0.95671988, + 0.029892389 -0.29080391 -0.95631564, + 0.029821711 -0.29071009 -0.95634633, + 0.047599781 -0.2905089 -0.95568764, + 0.047503181 -0.29035991 -0.95573765, + 0.060915709 -0.29014802 -0.95504111, + 0.061571922 -0.29132909 -0.95463938, + 0.07008402 -0.29116508 -0.95410234, + 0.068074189 -0.28691298 -0.95553488, + 0.0727304 -0.28681901 -0.95521998, + 0.070524581 -0.28125292 -0.95703864, + 0.071784034 -0.28122813 -0.95695245, + 0.071758896 -0.28115097 -0.95697689, + 0.062168822 -0.28133309 -0.95759434, + 0.039116398 -0.19585297 -0.97985286, + 0.033453614 -0.19589309 -0.9800545, + -0.020016897 0.053449694 -0.99836987, + -0.013855302 0.053455308 -0.99847412, + -0.05645512 0.31585813 -0.94712538, + -0.038935196 0.31612298 -0.94791889, + -0.068652309 0.57763803 -0.8134011, + -0.040394396 0.57853192 -0.81465888, + -0.054026082 0.7812317 -0.62189877, + -0.017697601 0.782251 -0.62271202, + -0.020863691 0.92606056 -0.37679783, + 0.020608008 0.92606539 -0.37680015, + 0.017450092 0.78133267 -0.62387073, + 0.053401906 0.78033614 -0.62307608, + 0.039886482 0.57758069 -0.81535858, + 0.067982122 0.57670319 -0.81412029, + 0.038450785 0.3157059 -0.94807762, + 0.055933699 0.31544501 -0.947294, + 0.013619 0.054333001 -0.99843001, + 0.019843001 0.054327399 -0.998326, + -0.0328172 -0.191376 -0.980968, + -0.038049694 -0.19134095 -0.98078579, + -0.061585624 -0.27863207 -0.95842135, + -0.070892118 -0.27845907 -0.95782822, + -0.071793437 -0.28121513 -0.95695549, + -0.070554219 -0.28124008 -0.95704037, + -0.072793193 -0.28688997 -0.95519388, + -0.068142101 -0.28698301 -0.95550901, + -0.069792777 -0.2904759 -0.95433366, + -0.061189078 -0.29064092 -0.95487362, + -0.060966294 -0.29023996 -0.95500988, + -0.047563087 -0.29045194 -0.95570678, + -0.050844118 -0.29552713 -0.95398039, + -0.033938192 -0.29573894 -0.95466578, + -0.025764214 -0.28474715 -0.95825648, + -0.0017967302 -0.28484103 -0.9585731, + 0.012443498 -0.26791596 -0.96336186, + 0.045653701 -0.26765701 -0.96243203, + 0.0626809 -0.24945 -0.96635699, + 0.105788 -0.248538 -0.96282798, + 0.13047804 -0.22428508 -0.96574938, + 0.18464698 -0.22232997 -0.95732689, + 0.21129499 -0.19769301 -0.95722097, + 0.27584904 -0.19441102 -0.94133514, + 0.29983193 -0.17301595 -0.93817174, + 0.37196511 -0.16834706 -0.9128533, + 0.39002109 -0.15240303 -0.90810627, + 0.4662528 -0.14641793 -0.87245059, + 0.47622889 -0.13749097 -0.86850584, + 0.55327117 -0.13024904 -0.82275528, + 0.55496591 -0.12868199 -0.8218599, + 0.63010907 -0.12011702 -0.76716012, + 0.62438625 -0.12567005 -0.7709403, + 0.69528615 -0.11563403 -0.7093702, + 0.68440193 -0.12685299 -0.71798491, + 0.75026017 -0.11502903 -0.65105915, + 0.73560375 -0.13123396 -0.66457874, + 0.7965579 -0.11712099 -0.59310895, + 0.78000027 -0.13692604 -0.61061525, + 0.8362202 -0.11999303 -0.53510511, + 0.81794089 -0.14382999 -0.55703294, + 0.86951786 -0.12347998 -0.47821695, + 0.85721356 -0.14136793 -0.49517676, + 0.9028421 -0.11803702 -0.41345307, + 0.90306109 -0.11765701 -0.41308305, + 0.9389509 -0.094246387 -0.33089098, + 0.93816376 -0.095993578 -0.33261693, + 0.96518654 -0.07252726 -0.25130588, + 0.96444511 -0.07474871 -0.25349203, + 0.98316699 -0.051676799 -0.175249, + 0.98269165 -0.05377198 -0.17727295, + 0.99422109 -0.031160804 -0.10273001, + 0.99402225 -0.032694306 -0.10416802, + 0.99939352 -0.010427495 -0.033223387, + 0.99936938 -0.011018803 -0.033756312, + 0.9994114 0.010644794 0.032610781, + 0.99938536 0.011311204 0.03318271, + 0.99471974 0.033112593 0.097139478, + 0.99446523 0.035340607 0.098944023, + 0.98552835 0.057017718 0.15963405, + 0.98490763 0.060404778 0.16219795, + 0.97206163 0.081918873 0.21996692, + 0.97144586 0.084434889 0.22172897, + 0.95514613 0.10538702 0.27674803, + 0.95398802 0.109256 0.27923101, + 0.93471438 0.12949905 0.33096713, + 0.93272913 0.13519101 0.33427504, + 0.9105286 0.15501292 0.38328683, + 0.90752286 0.16263399 0.38723695, + 0.88246286 0.18214199 0.43368593, + 0.87818927 0.19192305 0.43812013, + 0.85033786 0.21115197 0.48201695, + 0.84460109 0.22318803 0.48665807, + 0.81443882 0.24188495 0.52742887, + 0.80701917 0.25634107 0.53198612, + 0.77469987 0.27448797 0.56964594, + 0.7797963 0.2648811 0.56723517, + 0.75037783 0.27967995 0.59892589, + 0.76577085 0.24880397 0.59303594, + 0.73566663 0.26204687 0.62460071, + 0.74898517 0.23262106 0.62041014, + 0.71840775 0.24421892 0.65134275, + 0.73000783 0.21568996 0.64851081, + 0.69857693 0.22581898 0.67896694, + 0.70867294 0.19780996 0.67723995, + 0.6757955 0.20665585 0.7075265, + 0.68450719 0.17893904 0.7067042, + 0.64994222 0.18654206 0.73673421, + 0.65734082 0.15898596 0.73663181, + 0.62135762 0.16530189 0.76589155, + 0.62749803 0.13784501 0.7663191, + 0.59008592 0.14292899 0.79458791, + 0.59505713 0.11526203 0.79537517, + 0.55568284 0.11923596 0.82279968, + 0.55951512 0.091363624 0.82376915, + 0.51804221 0.094288737 0.8501423, + 0.52075905 0.066534504 0.85110712, + 0.47791982 0.068459481 0.87573171, + 0.47961706 0.040772904 0.87653011, + 0.43562779 0.04182528 0.8991546, + 0.43645984 0.012369895 0.89963871, + 0.44798201 0.0155087 0.89390802, + 0.44794807 0.015505502 0.89392513, + 0.44800684 -0.0016108694 0.89402872, + 0.44804084 -0.0016108494 0.89401168, + 0.49254289 0.0024418193 0.8702848, + 0.53342986 -0.0015543896 0.84584284, + 0.52513307 0.012167602 0.85093313, + 0.52422816 0.040098116 0.85063332, + 0.56663913 0.038797908 0.82305217, + 0.56483102 0.065198198 0.82262701, + 0.60529101 0.062890902 0.79351598, + 0.60248077 0.089311272 0.79312068, + 0.64091003 0.085896596 0.76279497, + 0.63702101 0.112439 0.76260197, + 0.67376095 0.10778698 0.73104596, + 0.6688332 0.13403803 0.73122919, + 0.70396394 0.12805699 0.69859594, + 0.69799918 0.15409203 0.69932318, + 0.73115098 0.14680099 0.66623402, + 0.72410822 0.17284606 0.66767621, + 0.755584 0.164166 0.63414699, + 0.74743378 0.19039492 0.63646877, + 0.77764672 0.18018194 0.60232878, + 0.76838511 0.20664203 0.60570908, + 0.79771984 0.19470896 0.5707289, + 0.78727603 0.221655 0.57538301, + 0.81557041 0.2080161 0.53997624, + 0.8038168 0.23579194 0.54615086, + 0.8314051 0.22025102 0.51015204, + 0.81806511 0.24944703 0.51821405, + 0.84560782 0.23152494 0.48098189, + 0.84074116 0.24177006 0.48446012, + 0.87066299 0.219641 0.44011801, + 0.87561876 0.20852296 0.4356719, + 0.90243328 0.18599907 0.38861114, + 0.90590233 0.17730007 0.38458514, + 0.92950535 0.15440805 0.33493012, + 0.93179739 0.14784905 0.33150312, + 0.95214963 0.12449095 0.27912891, + 0.95352262 0.11986995 0.27645192, + 0.97141087 0.094442382 0.21781097, + 0.61373925 0.013511505 0.78939331, + 0.60973489 0.013124498 0.7924968, + 0.60884804 0.037962303 0.79237813, + 0.64806318 0.036445308 0.76071417, + 0.64625776 0.061267879 0.7606557, + 0.68376428 0.058585126 0.72734737, + 0.6810112 0.083400622 0.72750819, + 0.71669996 0.079426691 0.69284391, + 0.71297801 0.104272 0.69339001, + 0.74646503 0.098953798 0.65802598, + 0.74185783 0.12345997 0.6590938, + 0.7732842 0.11674003 0.62322015, + 0.76782912 0.14093801 0.62496006, + 0.79770517 0.13266502 0.58827412, + 0.79141968 0.15676793 0.59082878, + 0.81995332 0.14680606 0.55328518, + 0.81283885 0.17099398 0.55682492, + 0.83991009 0.15932101 0.51881409, + 0.83202499 0.183621 0.523467, + 0.85792798 0.17006101 0.484808, + 0.84928441 0.19465908 0.49073824, + 0.8744911 0.17884402 0.45086607, + 0.8650474 0.2040661 0.45831221, + 0.88988876 0.18555295 0.4167349, + 0.87956327 0.21184207 0.42601815, + 0.90411127 0.19025305 0.38260508, + 0.90013623 0.20033005 0.38681108, + 0.92548001 0.17420299 0.33636299, + 0.92818522 0.16655605 0.33276308, + 0.94985801 0.139953 0.279612, + 0.95147365 0.13452895 0.2767669, + 0.97048151 0.10543295 0.2169089, + 0.97056347 0.10542705 0.2165451, + 0.98362625 0.078888722 0.16203704, + 0.98497021 0.071298413 0.15732205, + 0.99398845 0.045194123 0.099722244, + 0.85234618 -0.17075604 -0.49431613, + 0.89905912 -0.14295402 -0.41383207, + 0.89795411 -0.14490801 -0.41554806, + 0.93560624 -0.11624703 -0.33335808, + 0.93444735 -0.11885504 -0.33568111, + 0.96303189 -0.089912094 -0.25393996, + 0.96210152 -0.092725955 -0.25644189, + 0.98203689 -0.064161696 -0.17744498, + 0.98145515 -0.066739008 -0.17969902, + 0.99380612 -0.038689803 -0.10417502, + 0.99356091 -0.040581096 -0.10578199, + 0.99934673 -0.012943897 -0.033740893, + 0.99931663 -0.013678195 -0.034340788, + 0.99936289 0.013206098 0.033155795, + 0.99931234 0.014472306 0.034140211, + 0.99445415 0.041047204 0.096830316, + 0.99431598 0.040963199 0.098273903, + 0.98485726 0.066701613 0.16002205, + 0.98403978 0.071185082 0.16308996, + 0.97169662 0.094500564 0.21650693, + 0.970034 0.101521 0.220743, + 0.95255899 0.12717099 0.276512, + 0.95107126 0.13217904 0.27927107, + 0.93009025 0.15714605 0.3320201, + 0.92762113 0.16417702 0.33550704, + 0.90319312 0.18866403 0.38554907, + 0.89941776 0.19804196 0.3896499, + 0.8715778 0.22213094 0.43704692, + 0.87607175 0.21186395 0.43314192, + 0.84971285 0.23166494 0.47362387, + 0.86165512 0.20373903 0.46480206, + 0.83530712 0.22071603 0.50353408, + 0.84599668 0.19407293 0.49661383, + 0.81927019 0.20871304 0.53407413, + 0.82887781 0.18285495 0.5287019, + 0.80124885 0.19556996 0.56546688, + 0.80987573 0.17011894 0.56139183, + 0.78094929 0.18113706 0.59775221, + 0.78864014 0.15583502 0.59477907, + 0.758587 0.165141 0.63029701, + 0.7652989 0.14001198 0.62826294, + 0.73387384 0.14775798 0.66302085, + 0.73962402 0.122592 0.66176099, + 0.70634019 0.12894003 0.6960302, + 0.7111392 0.10352702 0.69538718, + 0.67573178 0.10854796 0.72911179, + 0.67956531 0.082799934 0.72892737, + 0.64241999 0.0864949 0.76145601, + 0.64522278 0.060832176 0.76156873, + 0.60635072 0.063316673 0.79267263, + 0.60816622 0.037673716 0.79291528, + 0.56734288 0.03908189 0.82255381, + 0.56826484 0.012105695 0.82275671, + 0.57419699 0.0142007 0.81859398, + 0.5742591 0.0015064303 0.81867218, + 0.53340483 -0.0015555294 0.84585869, + 0.53334087 0.014810396 0.84577084, + 0.53336596 0.014810198 0.84575486, + 0.53336412 0.014810003 0.84575617, + 0.53342807 -0.0015543902 0.84584409, + 0.49129981 0.0026063491 0.8709867, + 0.49123982 0.015202294 0.87089169, + 0.49121606 0.015202502 0.8709051, + 0.49127612 0.0021599405 0.87100118, + 0.44800207 -0.0016126502 0.89403111, + 0.44794285 0.015508994 0.89392769, + 0.48114994 0.012239198 0.87655288, + 0.48027393 0.041017197 0.87615889, + 0.52356482 0.039841983 0.85105371, + 0.52180117 0.066919625 0.8504383, + 0.5637728 0.064790875 0.8233847, + 0.56098908 0.091901705 0.8227061, + 0.60095799 0.088733003 0.79434001, + 0.59706986 0.11597997 0.79376084, + 0.63499922 0.11168904 0.76439631, + 0.63000607 0.13871002 0.7641021, + 0.66640997 0.13317199 0.73359597, + 0.66031671 0.15996492 0.73375267, + 0.695144 0.153124 0.70237303, + 0.68787074 0.17997295 0.70316678, + 0.72091097 0.17183799 0.67138594, + 0.71241862 0.1988579 0.67298973, + 0.74387419 0.18938404 0.64092517, + 0.73411703 0.21670103 0.64351606, + 0.76455301 0.20570301 0.610856, + 0.75344086 0.23353197 0.61464596, + 0.7831738 0.22084694 0.58126187, + 0.77054048 0.24953783 0.58651358, + 0.7994439 0.23518898 0.55278891, + 0.78494614 0.26536304 0.55985904, + 0.813416 0.249138 0.52562797, + 0.80836099 0.25913 0.52858698, + 0.83961201 0.23910099 0.48773199, + 0.84580386 0.22627696 0.48312995, + 0.87464112 0.20561104 0.43900707, + 0.87920988 0.19524497 0.43459094, + 0.90510929 0.17424005 0.38783714, + 0.90833628 0.16609406 0.38384616, + 0.93120211 0.14475401 0.33452803, + 0.9333269 0.13865998 0.33117098, + 0.95311612 0.11686902 0.27912602, + 0.95438677 0.11260197 0.27652594, + 0.97103447 0.090111941 0.2212961, + 0.97167414 0.087473206 0.21954003, + 0.98474109 0.064414404 0.16166602, + 0.98501652 0.06290257 0.16057892, + 0.99426854 0.038994581 0.099546053, + 0.99450153 0.036963783 0.097981453, + 0.99935937 0.012632305 0.033485111, + 0.99938852 0.011893095 0.032881085, + 0.99934453 -0.012313395 -0.034042787, + 0.99937135 -0.011659403 -0.03348171, + 0.99380338 -0.036554415 -0.10497004, + 0.99402255 -0.034861285 -0.10345895, + 0.982099 -0.0601486 -0.17850401, + 0.98262334 -0.057829421 -0.17637207, + 0.96331537 -0.083614632 -0.25501409, + 0.96415037 -0.08109843 -0.2526601, + 0.93637186 -0.10727599 -0.33421496, + 0.93738365 -0.10501196 -0.33209088, + 0.90065825 -0.13101003 -0.4143081, + 0.90146989 -0.12958498 -0.41298893, + 0.85525817 -0.15514003 -0.49443412, + 0.85406858 -0.15683992 -0.49595177, + 0.79811317 -0.18167004 -0.57446611, + 0.81324279 -0.16299595 -0.55863088, + 0.75204098 -0.184617 -0.63273299, + 0.77400202 -0.15971 -0.61271, + 0.70942295 -0.17776999 -0.68199492, + 0.72792792 -0.15810099 -0.66717696, + 0.65959316 -0.17331305 -0.73136818, + 0.67477506 -0.15809701 -0.72089106, + 0.6026631 -0.17094405 -0.77947116, + 0.61255676 -0.16151494 -0.7737487, + 0.53737009 -0.17232901 -0.82555211, + 0.54092097 -0.169076 -0.82390398, + 0.46468389 -0.17800196 -0.86740083, + 0.46038917 -0.18183206 -0.86889529, + 0.38531485 -0.18901493 -0.9032197, + 0.37335488 -0.19956693 -0.90596873, + 0.30198705 -0.20507905 -0.93099225, + 0.28390405 -0.22118805 -0.93299222, + 0.21927197 -0.22506598 -0.94934988, + 0.19774409 -0.24488212 -0.94917345, + 0.14248599 -0.24726596 -0.9584139, + 0.12050101 -0.26865602 -0.95566911, + 0.075587295 -0.26985398 -0.95992988, + 0.056724984 -0.28968793 -0.95543873, + 0.021932889 -0.29008484 -0.9567495, + 0.010242799 -0.30367097 -0.95272189, + -0.0158781 -0.30364799 -0.95265198, + -0.024870196 -0.31542096 -0.94862586, + -0.043097712 -0.31522408 -0.94803822, + -0.04768962 -0.32209811 -0.94550437, + -0.060023271 -0.32188386 -0.94487453, + -0.055915475 -0.31473985 -0.94752949, + -0.065190323 -0.31456313 -0.94699538, + -0.063688621 -0.31148812 -0.94811338, + -0.068834469 -0.31138185 -0.94778854, + -0.066181704 -0.30490303 -0.95008111, + -0.068012007 -0.30486503 -0.94996411, + -0.06514252 -0.29636613 -0.95285034, + -0.063936986 -0.29638895 -0.95292479, + -0.062535487 -0.29124695 -0.95460176, + -0.052452218 -0.29141608 -0.95515734, + -0.033248495 -0.20310196 -0.97859287, + -0.02709979 -0.20313993 -0.97877467, + 0.013865796 0.046096791 -0.99884075, + 0.0086328564 0.046099376 -0.99889952, + 0.038952097 0.31101996 -0.94960487, + 0.022451801 0.31117904 -0.95008612, + 0.040240087 0.5758028 -0.8165977, + 0.012979198 0.57622093 -0.81719089, + 0.017429095 0.7813977 -0.62378979, + -0.0179752 0.78139001 -0.62378401, + -0.013405995 0.5767048 -0.81684268, + -0.04084279 0.57627487 -0.81623483, + -0.022913288 0.31150386 -0.94996852, + -0.039448582 0.31134287 -0.94947851, + -0.0089477105 0.045526404 -0.99892312, + -0.014099296 0.045523789 -0.99886376, + 0.027384896 -0.20669597 -0.97802186, + 0.033844102 -0.20665602 -0.97782815, + 0.05278511 -0.29372907 -0.95443022, + 0.063092783 -0.29355195 -0.95385873, + 0.063901603 -0.296518 -0.952887, + 0.065073393 -0.29649496 -0.95281488, + 0.067895211 -0.30485305 -0.94997627, + 0.066096611 -0.30489007 -0.95009124, + 0.06901142 -0.31200913 -0.94756937, + 0.063993603 -0.312114 -0.947887, + 0.065146774 -0.31447488 -0.94702762, + 0.055864885 -0.31465191 -0.94756174, + 0.057491716 -0.31748408 -0.94651926, + 0.044449277 -0.31769484 -0.94715053, + 0.046423104 -0.32064804 -0.94606012, + 0.029067803 -0.32085803 -0.94668114, + 0.018517697 -0.30708197 -0.95150286, + -0.0070331618 -0.30712807 -0.95164222, + -0.022947907 -0.28865409 -0.95715839, + -0.057978291 -0.28824496 -0.95579988, + -0.077028841 -0.26820111 -0.96027845, + -0.12216905 -0.2669861 -0.95592535, + -0.14376095 -0.24596392 -0.95855862, + -0.19922404 -0.24356306 -0.94920325, + -0.22099698 -0.22350398 -0.94931889, + -0.28574494 -0.21961494 -0.93280178, + -0.30411413 -0.20322508 -0.93070638, + -0.37560314 -0.19771008 -0.90544629, + -0.3874909 -0.18719895 -0.90266675, + -0.46261713 -0.18002805 -0.86808717, + -0.4666748 -0.17640191 -0.86665857, + -0.54281098 -0.167512 -0.82297999, + -0.53877813 -0.17121305 -0.82486618, + -0.61384588 -0.16043796 -0.77295083, + -0.60289794 -0.17088298 -0.7793029, + -0.67496395 -0.15803899 -0.72072697, + -0.65848732 -0.17453709 -0.73207337, + -0.72692716 -0.15925905 -0.66799217, + -0.70781666 -0.17950691 -0.68320769, + -0.77267665 -0.16131292 -0.6139617, + -0.75085086 -0.18597798 -0.63374692, + -0.81229413 -0.16423301 -0.55964804, + -0.79707539 -0.18295386 -0.57549858, + -0.85327411 -0.15798402 -0.49695507, + -0.85567969 -0.15455094 -0.49388883, + -0.90176022 -0.12908603 -0.41251108, + -0.90136689 -0.12977798 -0.41315293, + -0.93783367 -0.10401396 -0.33113289, + -0.93661338 -0.10675403 -0.33370513, + -0.96428162 -0.080707267 -0.2522839, + -0.9633109 -0.08363539 -0.25502396, + -0.98261952 -0.057846773 -0.17638791, + -0.98205203 -0.060353801 -0.178693, + -0.99400687 -0.034980796 -0.10356998, + -0.99377936 -0.036733717 -0.10513504, + -0.99936914 -0.011715 -0.033529304, + -0.99934226 -0.012368402 -0.034090109, + -0.99938655 0.011945094 0.032923486, + -0.99935752 0.012677995 0.033522286, + -0.99448735 0.037092116 0.09807694, + -0.99426901 0.038993798 0.099541999, + -0.98501778 0.062901482 0.16057196, + -0.98478955 0.064154074 0.16147393, + -0.97175187 0.087140292 0.21932797, + -0.97106624 0.089971423 0.22121406, + -0.95443475 0.11242897 0.27643093, + -0.95307398 0.117 0.27921501, + -0.93327099 0.13880999 0.33126599, + -0.93108773 0.14506596 0.3347109, + -0.90820313 0.16643402 0.38401407, + -0.90495825 0.17461705 0.3880201, + -0.87902302 0.19566099 0.434782, + -0.8744812 0.20595305 0.43916512, + -0.84564084 0.22662795 0.48325089, + -0.83965302 0.239026 0.48769799, + -0.80838484 0.25906393 0.52858287, + -0.81270987 0.25053096 0.52605796, + -0.78429699 0.266747 0.56011099, + -0.79896909 0.23629902 0.55300206, + -0.77013689 0.25064397 0.58657193, + -0.78301716 0.22144306 0.58124614, + -0.75332868 0.23413292 0.61455476, + -0.7646023 0.20591708 0.61072224, + -0.73422784 0.21690795 0.64331985, + -0.7440908 0.18927796 0.64070481, + -0.71264601 0.198753 0.67277998, + -0.72120166 0.17148992 0.67116272, + -0.68814844 0.1796201 0.70298541, + -0.6954174 0.15275209 0.70218343, + -0.66054517 0.15959305 0.73362815, + -0.666601 0.132937 0.73346502, + -0.6302588 0.13845997 0.76393884, + -0.63517725 0.11180504 0.76423132, + -0.59728771 0.11609795 0.79357964, + -0.60112226 0.089210629 0.79416227, + -0.56128788 0.092387974 0.82244784, + -0.56409502 0.065107197 0.82313901, + -0.52217883 0.067245975 0.85018069, + -0.52398878 0.03946038 0.85081059, + -0.48069194 0.040626295 0.87594789, + -0.48159581 0.010402396 0.87633169, + -0.66015816 0.0028809106 0.75112116, + -0.969212 0.116706 0.216813, + -0.94885767 0.14963694 0.27798891, + -0.95111877 0.14190897 0.27428994, + -0.93119889 0.16749698 0.32374898, + -0.93803376 0.14541897 0.3145569, + -0.91755545 0.1668459 0.36090779, + -0.92429578 0.14495496 0.35307992, + -0.90302289 0.16315298 0.39740494, + -0.9095121 0.14145702 0.39086807, + -0.88722891 0.15699299 0.43379495, + -0.89339077 0.13532098 0.42841691, + -0.87012881 0.14843597 0.46993887, + -0.87588298 0.12665699 0.46560401, + -0.8514061 0.13767801 0.50611508, + -0.85660613 0.11598402 0.50276607, + -0.83050019 0.12521003 0.54276311, + -0.835109 0.103447 0.54026997, + -0.80712819 0.11102303 0.5798431, + -0.81110036 0.089018948 0.57809329, + -0.78143227 0.094967037 0.61672121, + -0.78472829 0.072535619 0.61558121, + -0.7532019 0.076976396 0.65326995, + -0.75576431 0.053943418 0.65261823, + -0.72194976 0.05699968 0.68959373, + -0.72371697 0.0331975 0.68929797, + -0.69035405 0.0094404612 0.72341007, + -0.68833697 0.010227299 0.72531897, + -0.68743503 0.034936603 0.72540504, + -0.61006624 0.011345903 0.79226929, + -0.6091423 0.037511617 0.79217339, + -0.97042978 0.10566998 0.21702495, + -0.95138198 0.134839 0.27693099, + -0.94978052 0.14020894 0.27974689, + -0.92808914 0.16684401 0.33288702, + -0.92550063 0.17415693 0.33632988, + -0.90015769 0.20028393 0.38678485, + -0.90363055 0.19149691 0.38311982, + -0.87904799 0.213146 0.426431, + -0.88952112 0.18657401 0.41706407, + -0.86467516 0.20512904 0.45854011, + -0.87431985 0.17942598 0.45096695, + -0.84912968 0.19526093 0.49076682, + -0.85792011 0.17026602 0.48475006, + -0.83206517 0.18381804 0.52333415, + -0.84003448 0.1592401 0.5186373, + -0.81297886 0.17091098 0.55664593, + -0.8201521 0.14648402 0.55307609, + -0.7916128 0.15643695 0.59065789, + -0.79790282 0.13228397 0.58809191, + -0.76804119 0.14053904 0.62478912, + -0.77344584 0.11650797 0.62306291, + -0.74201816 0.12322003 0.6589582, + -0.74655563 0.099076755 0.65790468, + -0.71312219 0.10439602 0.69322318, + -0.71678704 0.079927906 0.69269603, + -0.68115371 0.08392226 0.72731465, + -0.68393195 0.058941994 0.72716093, + -0.64652604 0.061636206 0.76039809, + -0.64838904 0.036009803 0.7604571, + -0.64995372 0.0095697856 0.75991362, + -0.64900202 0.036282301 0.75992101, + -0.68684906 0.034661405 0.72597307, + -0.68502194 0.059424091 0.72609496, + -0.72093821 0.056526516 0.69069016, + -0.71825618 0.080569126 0.69109815, + -0.7518453 0.076349631 0.65490425, + -0.74834365 0.099837758 0.65575469, + -0.77979183 0.094228178 0.61890686, + -0.775509 0.117352 0.62033403, + -0.80525231 0.11021303 0.58259916, + -0.80021518 0.13317204 0.5847401, + -0.82843328 0.12437304 0.54610419, + -0.82265383 0.14735897 0.54911387, + -0.84919786 0.13686998 0.51002896, + -0.8426978 0.16004795 0.51404786, + -0.86781245 0.14771192 0.47442874, + -0.86070442 0.17094007 0.47954923, + -0.88485879 0.15641996 0.43881389, + -0.87717277 0.17989495 0.44520289, + -0.90065044 0.16279908 0.40289617, + -0.892416 0.186759 0.41074899, + -0.91522413 0.16678101 0.36680904, + -0.90653533 0.19131407 0.37628815, + -0.92893976 0.16779296 0.3300249, + -0.92603213 0.17618401 0.33380204, + -0.94848466 0.14788695 0.2801899, + -0.95017314 0.14225101 0.27737302, + -0.96870786 0.11326499 0.22085297, + -0.97050714 0.10566401 0.21668203, + -0.98359138 0.079075031 0.16215806, + -0.98448926 0.074062817 0.15904604, + -0.99425751 0.045175079 0.097011253, + -0.99283147 -0.050442021 -0.10835705, + -0.99327475 -0.047084689 -0.10577498, + -0.97987276 -0.081180677 -0.18237096, + -0.98061675 -0.077906884 -0.17978096, + -0.95915735 -0.11247404 -0.25955108, + -0.96036625 -0.10882502 -0.25662005, + -0.929865 -0.14363401 -0.33870399, + -0.93147641 -0.13999806 -0.33578616, + -0.8917079 -0.17417298 -0.41775694, + -0.8935774 -0.17084007 -0.4151302, + -0.84437084 -0.20389296 -0.49544489, + -0.84617633 -0.20125008 -0.49344116, + -0.72097296 -0.26087296 -0.64198393, + -0.78894114 -0.23132303 -0.56926405, + -0.78797382 -0.23252194 -0.57011485, + -0.7837379 -0.25043896 -0.56836194, + -0.7822488 -0.25228894 -0.56959391, + -0.84167027 -0.21868607 -0.49372819, + -0.83973086 -0.22152697 -0.49575993, + -0.89018869 -0.18586694 -0.41595384, + -0.88819778 -0.18941495 -0.41860092, + -0.92914563 -0.15241595 -0.33683488, + -0.92736602 -0.156426 -0.33988699, + -0.95890266 -0.11862396 -0.25774792, + -0.95752186 -0.12277898 -0.26091596, + -0.97982925 -0.085087322 -0.18081704, + -0.97864074 -0.090259977 -0.18470396, + -0.99334747 -0.050559822 -0.10346305, + -0.99296486 -0.053601392 -0.10558198, + -0.99932063 -0.016683195 -0.032861888, + -0.999273 -0.0179173 -0.033652298, + -0.99934191 0.017047498 0.032018695, + -0.99929178 0.018411096 0.032817092, + -0.99399185 0.053553794 0.095457882, + -0.99420065 0.051540282 0.094385266, + -0.98481297 0.083209097 0.15238, + -0.98659098 0.071447298 0.146743, + -0.97489899 0.097465403 0.20018101, + -0.97732538 0.083891928 0.19441508, + -0.96379524 0.10564302 0.24482305, + -0.96667123 0.090865023 0.23935406, + -0.95168579 0.10898398 0.28708294, + -0.95484012 0.093265206 0.28210303, + -0.93841076 0.10845798 0.32805791, + -0.94168186 0.091974795 0.32369098, + -0.92365664 0.10474296 0.36862889, + -0.92687923 0.08775752 0.36495709, + -0.90716201 0.098376803 0.40911999, + -0.91022074 0.080902979 0.4061439, + -0.88883024 0.089521125 0.44940713, + -0.89163512 0.071470305 0.44707805, + -0.86846715 0.07825692 0.48953113, + -0.87091231 0.059566922 0.48781517, + -0.84557289 0.064708695 0.52992392, + -0.84757131 0.045188516 0.52875417, + -0.8198359 0.048757691 0.57051891, + -0.82128221 0.028273307 0.56982112, + -0.79138017 0.030295307 0.61057311, + -0.75978798 0.0086847804 0.65011299, + -0.75894701 0.031932499 0.65036899, + -0.7908808 0.030011093 0.61123389, + -0.78931302 0.051681999 0.611812, + -0.81902611 0.048295408 0.57172006, + -0.81681091 0.069077596 0.57275492, + -0.84453416 0.064120017 0.53164911, + -0.84177786 0.084149495 0.53322494, + -0.86728483 0.077600583 0.49172688, + -0.86406714 0.097057112 0.49393106, + -0.88754177 0.088833675 0.45208189, + -0.88393915 0.10784802 0.45499507, + -0.90582502 0.097711101 0.41223001, + -0.90191579 0.11642997 0.41592291, + -0.92233598 0.104159 0.37208501, + -0.91822886 0.12257399 0.37660494, + -0.93713987 0.10799898 0.33182096, + -0.93299401 0.12593199 0.33713999, + -0.95052564 0.10869896 0.29100791, + -0.94649565 0.12603895 0.29708588, + -0.96277714 0.10556702 0.24882904, + -0.95900822 0.12229903 0.25562906, + -0.97408485 0.097615384 0.20403397, + -0.97083235 0.11330204 0.21129908, + -0.98424011 0.083566807 0.15584601, + -0.98377454 0.086319052 0.15727893, + -0.99371123 0.053874012 0.09816172, + -0.99419546 0.049406521 0.095574446, + -0.99930334 0.017138405 0.033153512, + -0.99935454 0.015770592 0.032277286, + -0.99927378 -0.016726997 -0.034234993, + -0.99932086 -0.015551598 -0.033407297, + -0.99929589 -0.015531898 -0.034153495, + -0.99934125 0.015023404 0.033035409, + -0.99931109 0.015799701 0.033582002, + -0.9943549 0.045170795 0.096010081, + -0.99386662 0.04961748 0.09882886, + -0.9844349 0.078855492 0.15706599, + -0.98304766 0.086741872 0.16153394, + -0.969069 0.116755 0.217425, + -0.96977699 0.113692 0.215886, + -0.95274925 0.14154103 0.26876605, + -0.95773488 0.12240799 0.26030797, + -0.93982875 0.14538397 0.30916893, + -0.94506055 0.12588593 0.30168384, + -0.92619026 0.14520203 0.3479771, + -0.93144286 0.12555498 0.34154096, + -0.91147679 0.14193197 0.38608992, + -0.91663378 0.12203197 0.38064492, + -0.89535725 0.13595903 0.42408809, + -0.90030342 0.11576705 0.4195852, + -0.8778109 0.12740198 0.46175393, + -0.8823809 0.10712998 0.45817795, + -0.85845 0.116775 0.49942699, + -0.8625716 0.096319556 0.49668175, + -0.83681411 0.10423002 0.53747404, + -0.84042656 0.083455563 0.53546077, + -0.81262368 0.089748673 0.57583684, + -0.81566489 0.068475395 0.57445794, + -0.78602201 0.073171198 0.61385298, + -0.7884239 0.051209893 0.61299694, + -0.75672871 0.054423083 0.65145975, + -0.75840819 0.031645708 0.65101117, + -0.72427893 0.033477496 0.68869394, + -0.72514981 0.0095504383 0.68852484, + -0.72502899 0.0094883395 0.68865299, + -0.72506499 0.000788017 0.68867999, + -0.69010603 -0.0013277602 0.72370708, + -0.69006485 0.010468697 0.72367179, + -0.69042873 0.010463797 0.72332478, + -0.69047093 -0.0013080199 0.72335893, + -0.69038808 -0.0013080802 0.72343808, + -0.65420592 0.0037970794 0.75630689, + -0.65416622 0.011241804 0.75626731, + -0.65405095 0.011243199 0.75636691, + -0.65409625 0.0013293305 0.7564103, + -0.61611992 -0.0014897498 0.78765088, + -0.61607099 0.0119491 0.78759998, + -0.61616468 0.011948095 0.78752667, + -0.61621308 -0.0014852702 0.78757811, + -0.61620975 -0.0014852694 0.78758073, + -0.61617988 0.0091915885 0.78755182, + -0.53616184 -0.0015689294 0.84411371, + -0.57684106 0.0019515502 0.81685412, + -0.576792 0.0126551 0.81679302, + -0.57684302 0.0126545 0.81675702, + -0.57689101 0.00291832 0.81681597, + -0.57941306 0.0025570602 0.8150301, + -0.093484826 0.060359821 -0.99378937, + 0.0047935699 -0.0557895 -0.99843103, + 0.0052858777 -0.055789374 -0.99842852, + -0.026445905 -0.030060407 -0.99919826, + -0.033428285 -0.022110488 -0.99919653, + -0.078658961 -0.022054289 -0.99665755, + -0.10670099 0.0064931992 -0.99426991, + -0.16407305 0.0064419913 -0.98642725, + -0.19745795 0.037292294 -0.97960174, + -0.26681507 0.036662206 -0.96305025, + -0.31759313 0.080295533 -0.94482136, + -0.39761201 0.077698 -0.914258, + -0.4268159 0.10171898 -0.89859974, + -0.51004285 0.09674786 -0.85469073, + -0.52946693 0.11241899 -0.84084886, + -0.6113041 0.10487402 -0.7844162, + -0.65409893 0.14053698 -0.74323893, + -0.7422632 0.12450203 -0.65844119, + -0.075917818 0.013232603 0.99702626, + -0.067487404 0.013623402 0.99762714, + -0.067331769 0.044951178 0.99671751, + -0.11256999 0.044766996 0.99263489, + -0.11207402 0.075321309 0.99084109, + -0.15734008 0.074854836 0.98470348, + -0.15631701 0.10538101 0.98206913, + -0.201288 0.104509 0.97394103, + -0.19953798 0.13489999 0.9705599, + -0.24356188 0.13352194 0.9606505, + -0.2409111 0.16373406 0.95663637, + -0.28386194 0.16176295 0.94512177, + -0.28013694 0.19188996 0.94058573, + -0.321989 0.189247 0.92763603, + -0.31698608 0.21944706 0.92269325, + -0.35757798 0.21608198 0.9085409, + -0.35111782 0.24644189 0.90331757, + -0.38973692 0.24238694 0.88845575, + -0.38167006 0.27281603 0.88311911, + -0.41845408 0.26807505 0.86777419, + -0.40857914 0.29870611 0.86246032, + -0.44369915 0.29329112 0.84682429, + -0.43174601 0.32434899 0.84166098, + -0.46534094 0.31828597 0.82592487, + -0.45104313 0.34986508 0.82106918, + -0.482577 0.343339 0.80575299, + -0.48079899 0.34679899 0.80533397, + -0.51557118 0.33889511 0.78697932, + -0.52871495 0.31440398 0.78842288, + -0.5633812 0.30603212 0.76742828, + -0.57598615 0.28282607 0.76697415, + -0.61027908 0.27408203 0.74326205, + -0.62207103 0.25247499 0.74113703, + -0.65523994 0.24359497 0.71506792, + -0.66609025 0.22367108 0.71154422, + -0.69793463 0.2147619 0.68320173, + -0.70778275 0.19651793 0.67854577, + -0.73846304 0.18757802 0.64767808, + -0.74709803 0.171335 0.64225298, + -0.77652216 0.16241005 0.6087991, + -0.78343111 0.14914101 0.60331804, + -0.81102228 0.14039105 0.56792021, + -0.81797159 0.12664095 0.56114578, + -0.84380198 0.118142 0.523489, + -0.85005844 0.10520694 0.5160737, + -0.87423116 0.096981622 0.47572511, + -0.8792479 0.085995294 0.46853793, + -0.90161443 0.078084335 0.4254342, + -0.90553975 0.068840884 0.41863891, + -0.92565227 0.061395217 0.37336108, + -0.9286049 0.053781692 0.36715198, + -0.94636422 0.04682941 0.31969008, + -0.94847363 0.040724885 0.31422788, + -0.96378177 0.034277491 0.26447994, + -0.96515673 0.029661292 0.25998595, + -0.97792011 0.023688404 0.20763204, + -0.97862411 0.020805102 0.20460203, + -0.9885329 0.015276498 0.15023099, + -0.98889941 0.013287691 0.14799091, + -0.99578089 0.0082060993 0.091394693, + -0.99627924 0.003791421 0.086101323, + -0.99956924 0.0012911303 0.029320907, + -0.99962711 -0.00029753803 0.027303904, + -0.99960214 0.00030734504 -0.028203905, + -0.99965113 0.0016816902 -0.026361704, + -0.99656552 0.0052718776 -0.082640462, + -0.9969539 0.0089251092 -0.077481389, + -0.99084938 0.015445406 -0.13408604, + -0.99174863 0.020523893 -0.12654395, + -0.98242003 0.0298873 -0.184276, + -0.98388833 0.035726711 -0.17517807, + -0.97090352 0.047853976 -0.23464088, + -0.9728291 0.053636208 -0.22522603, + -0.95569813 0.06819021 -0.28634104, + -0.95781636 0.073177531 -0.27790809, + -0.9355976 0.089904055 -0.34142986, + -0.93724036 0.092999928 -0.33605313, + -0.90854573 0.11143097 -0.40265092, + -0.9085834 0.11148805 -0.40255019, + -0.87161982 0.13083297 -0.47239989, + -0.86788458 0.12612595 -0.48048776, + -0.82080591 0.14502598 -0.55248994, + -0.81607491 0.13994898 -0.56074595, + -0.73371708 0.16452901 -0.65923405, + -0.71110576 0.14500396 -0.68796974, + -0.636383 0.159087 -0.75479001, + -0.62081409 0.14645602 -0.77015615, + -0.53872794 0.15738899 -0.82764786, + -0.50996989 0.13435598 -0.84963483, + -0.42529491 0.14136297 -0.89394677, + -0.36938897 0.095874988 -0.92431587, + -0.29034603 0.098727517 -0.95181513, + -0.24996094 0.064116389 -0.96613073, + -0.18140501 0.06511981 -0.98125011, + -0.14540392 0.031603884 -0.98886752, + -0.08946418 0.031815294 -0.99548179, + -0.082753927 0.024883609 -0.99625933, + -0.53683203 0.84368914 0.00033511102, + -0.40719393 0.9133389 -0.0022486697, + -0.40720585 0.91333371 -0.0022552893, + -0.40315181 0.90435058 -0.14006694, + -0.40313992 0.90435576 -0.14006697, + -0.43582115 0.89685231 -0.075603828, + -0.41806009 0.85919917 -0.29496205, + -0.46332201 0.83817399 -0.287745, + -0.41983092 0.75707781 -0.50057489, + -0.41897005 0.74988407 -0.51199406, + -0.37530276 0.76549453 -0.52265269, + -0.41841906 0.85626012 -0.30289304, + -0.37270096 0.87482989 -0.30946198, + -0.39024591 0.91723377 -0.079939179, + -0.35804501 0.922243 -0.14584801, + -0.36195388 0.93219167 0.002826069, + -0.36192292 0.93220377 0.0028260793, + -0.35801297 0.92224985 -0.14588298, + -0.35804904 0.92223614 -0.14588201, + -0.36196011 0.93218935 0.0028304309, + -0.315685 0.948632 -0.0209824, + -0.32852098 0.94442689 -0.011485299, + -0.31575292 0.94883174 -0.0042991191, + -0.31218812 0.93823534 -0.14917506, + -0.31219113 0.93823433 -0.14917506, + -0.34387082 0.93530661 -0.083392665, + -0.32701102 0.88821214 -0.32271203, + -0.37312704 0.87200814 -0.31682503, + -0.33141398 0.77188289 -0.54255092, + -0.37472108 0.75850916 -0.53314912, + -0.054964386 0.10719298 -0.99271774, + 0.03965579 -0.14543498 -0.98857278, + 0.041826412 -0.14542203 -0.98848522, + 0.07729277 -0.22612193 -0.97102761, + 0.083561607 -0.22600703 -0.9705351, + 0.078484811 -0.21599004 -0.97323614, + 0.067109779 -0.21616992 -0.97404665, + 0.064476512 -0.21169704 -0.97520626, + 0.047789209 -0.21189603 -0.97612309, + 0.043485899 -0.20555 -0.97768003, + 0.020628892 -0.20569992 -0.97839767, + 0.0092007117 -0.19093205 -0.98156023, + -0.022016594 -0.19089395 -0.98136377, + -0.030374596 -0.18132599 -0.98295391, + -0.068887427 -0.18097909 -0.98107147, + -0.078128368 -0.17150994 -0.98207963, + -0.125204 -0.170682 -0.97733903, + -0.16451694 -0.13380395 -0.97725666, + -0.22513489 -0.13216893 -0.96532154, + -0.26766598 -0.094413288 -0.95887488, + -0.33951291 -0.092168279 -0.93607473, + -0.37718105 -0.059503108 -0.92422611, + -0.45549184 -0.05719658 -0.88840067, + -0.48489511 -0.031463306 -0.87400615, + -0.56417716 -0.02970341 -0.82511932, + -0.5831129 -0.012447897 -0.81229579, + -0.65853918 -0.011530903 -0.75245816, + -0.66721869 -0.0030699386 -0.74485564, + -0.73527795 -0.0027934099 -0.67775995, + -0.73582983 -0.0022055595 -0.67716283, + -0.79559702 -0.0019731901 -0.60582298, + -0.79099488 -0.0074075689 -0.61177796, + -0.84298611 -0.0065129912 -0.53789604, + -0.83533591 -0.016638298 -0.54948795, + -0.88034588 -0.014355998 -0.47411495, + -0.87156957 -0.027503688 -0.48949975, + -0.91011697 -0.023244601 -0.413699, + -0.90124559 -0.038444482 -0.4315998, + -0.93415844 -0.031661715 -0.35545117, + -0.92639321 -0.047127713 -0.37359709, + -0.95415175 -0.037461493 -0.29696995, + -0.94761622 -0.05298451 -0.31498608, + -0.97063637 -0.039903115 -0.2372191, + -0.96706074 -0.050612688 -0.24946295, + -0.98441553 -0.034966886 -0.1723469, + -0.9842391 -0.035724502 -0.17319702, + -0.99473876 -0.020695195 -0.10033198, + -0.99461037 -0.021671508 -0.10139304, + -0.99945277 -0.0069136983 -0.032346793, + -0.99943286 -0.0073980489 -0.032852095, + -0.99947011 0.0071513909 0.031756803, + -0.99944854 0.0077003362 0.032302186, + -0.9952541 0.022564901 0.094658017, + -0.99505365 0.024328291 0.09631376, + -0.98703289 0.039311398 0.15562999, + -0.98646885 0.042419195 0.15836598, + -0.9748891 0.057617906 0.21510804, + -0.97376579 0.062227786 0.21887894, + -0.95882475 0.077663988 0.27317294, + -0.95690835 0.08403483 0.2779651, + -0.93906534 0.09947294 0.32903111, + -0.93656522 0.10658202 0.33389509, + -0.9160707 0.12194595 0.38202584, + -0.9137429 0.12784699 0.38565394, + -0.89078468 0.14299296 0.43134186, + -0.8871156 0.15149592 0.43597579, + -0.8617152 0.16654305 0.47928113, + -0.85675502 0.17719799 0.484326, + -0.82932758 0.19198591 0.52474475, + -0.82309484 0.20455295 0.52978587, + -0.79374069 0.21908693 0.56742984, + -0.786111 0.23367999 0.572209, + -0.7547608 0.24801394 0.60730988, + -0.74565178 0.26468492 0.61151075, + -0.71236515 0.27877605 0.6440652, + -0.70187396 0.29729396 0.64729393, + -0.6674493 0.31079715 0.67669529, + -0.67114395 0.30428597 0.67599994, + -0.64056998 0.315193 0.70023102, + -0.65726995 0.28307799 0.69847196, + -0.62552679 0.29304889 0.72307575, + -0.63982576 0.26197892 0.72248876, + -0.60663575 0.27099892 0.74736375, + -0.61881173 0.24078688 0.74772567, + -0.58449799 0.248712 0.77233702, + -0.59484005 0.21900202 0.77343613, + -0.55925214 0.22585505 0.79763818, + -0.56794286 0.19644596 0.79928082, + -0.53051698 0.202319 0.82317603, + -0.53764606 0.17328501 0.82517213, + -0.49828181 0.17818494 0.8485077, + -0.50400871 0.14928891 0.85069847, + -0.46321201 0.15318701 0.872908, + -0.46767518 0.12431104 0.87511528, + -0.4256281 0.12726504 0.89590424, + -0.42894599 0.098206401 0.89797598, + -0.38529581 0.10032295 0.91732359, + -0.38759387 0.070976578 0.91909367, + -0.34245089 0.072339676 0.93674666, + -0.34383681 0.042710681 0.93805754, + -0.29856396 0.011615499 0.95431888, + -0.29792204 0.043418411 0.95360225, + -0.20560497 0.012293098 0.97855788, + -0.20515007 0.044279713 0.97772837, + -0.15902202 0.013176702 0.98718715, + -0.15867496 0.044581987 0.98632377, + -0.20488304 0.044196211 0.97778821, + -0.204006 0.074548997 0.97612703, + -0.24948403 0.073742405 0.96556711, + -0.24789897 0.10394099 0.96319389, + -0.29249901 0.102598 0.950746, + -0.29002914 0.13261206 0.9477855, + -0.33389613 0.13061604 0.93351638, + -0.3303951 0.16047604 0.93010026, + -0.37322199 0.157739 0.91423398, + -0.36852804 0.18754002 0.91050309, + -0.40956491 0.18404296 0.89352375, + -0.40350693 0.21391697 0.88961887, + -0.44287685 0.20961593 0.87173468, + -0.43526614 0.23979309 0.86778033, + -0.473077 0.234658 0.84919602, + -0.46379489 0.26496595 0.84539181, + -0.50017184 0.2589789 0.82629168, + -0.48901206 0.28960702 0.82279712, + -0.52339596 0.28290397 0.80375487, + -0.51006597 0.31415701 0.80071098, + -0.54272223 0.30677015 0.78188539, + -0.52696306 0.33873904 0.77946514, + -0.55834311 0.33065709 0.76086718, + -0.5557822 0.33530912 0.76070631, + -0.59104103 0.32535201 0.73811698, + -0.60364687 0.30303195 0.73741585, + -0.63797385 0.29269594 0.71226281, + -0.64964467 0.27189389 0.70995462, + -0.68274218 0.26131606 0.68233216, + -0.69324607 0.24233703 0.67873603, + -0.72526783 0.23149794 0.64837885, + -0.73455679 0.21436696 0.64379585, + -0.76534653 0.20333289 0.61065567, + -0.77341753 0.18802688 0.60536861, + -0.80235767 0.17703594 0.56998283, + -0.80905718 0.16387604 0.56442112, + -0.83608699 0.15296499 0.52683997, + -0.84108984 0.14271997 0.52172691, + -0.8663711 0.13177001 0.48170307, + -0.87150502 0.12067 0.475308, + -0.89498788 0.10976999 0.43237394, + -0.89942014 0.099440716 0.42562306, + -0.92063373 0.08882568 0.38018891, + -0.92393339 0.080373228 0.37401512, + -0.94270903 0.070091501 0.32617, + -0.94505388 0.06332849 0.32072198, + -0.96129423 0.053373512 0.27030507, + -0.96285689 0.048124794 0.26568896, + -0.97641188 0.038482998 0.21245897, + -0.97735137 0.034609612 0.20877407, + -0.98783052 0.025436686 0.15343992, + -0.98829126 0.022900505 0.15085103, + -0.99554455 0.014152193 0.093223758, + -0.99568164 0.012958095 0.09192507, + -0.99949914 0.0044176304 0.031338703, + -0.99951249 0.004083382 0.030954115, + -0.99947888 -0.0042218496 -0.032003697, + -0.99954063 -0.002714969 -0.030184589, + -0.99547738 -0.0085103726 -0.094616637, + -0.99608862 -0.0034914389 -0.088290773, + -0.98826355 -0.0060360571 -0.15263893, + -0.98967326 0.0010504503 -0.14333802, + -0.97805148 0.0015269407 -0.20835811, + -0.98041534 0.010097004 -0.19668208, + -0.96475625 0.013491303 -0.26279905, + -0.96794248 0.022457911 -0.25016612, + -0.94797897 0.028463 -0.317058, + -0.95176065 0.037062585 -0.30459487, + -0.92673457 0.045381878 -0.37296581, + -0.93052942 0.052508827 -0.36243317, + -0.89935875 0.062687986 -0.4326939, + -0.90233374 0.067367986 -0.4257409, + -0.86365002 0.078786001 -0.497897, + -0.86409456 0.079378366 -0.49703076, + -0.81659281 0.091030478 -0.56999087, + -0.81211787 0.085906193 -0.57713497, + -0.75431383 0.096656881 -0.64935982, + -0.74131966 0.08361046 -0.66592371, + -0.67238569 0.092212453 -0.73443466, + -0.64694029 0.069165632 -0.75939733, + -0.56859714 0.074614719 -0.81922519, + -0.52673596 0.039149296 -0.84912688, + -0.44488794 0.041247398 -0.89463586, + -0.3899301 -0.0041406211 -0.92083526, + -0.31298003 -0.0042706407 -0.94975013, + -0.29285896 -0.021366198 -0.95591688, + -0.22329086 -0.021781787 -0.9745084, + -0.20079203 -0.042234104 -0.97872311, + -0.14040299 -0.042684995 -0.98917389, + -0.10708396 -0.075665168 -0.99136662, + -0.059588708 -0.07596761 -0.99532813, + -0.040826481 -0.096528657 -0.99449253, + -0.0037487515 -0.096608534 -0.99531537, + 0.010907101 -0.11464102 -0.99334711, + 0.03886972 -0.11456205 -0.99265546, + 0.055658113 -0.13798504 -0.98886925, + -0.003497211 -0.044207811 -0.99901623, + 0.056052018 -0.13798204 -0.98884737, + 0.017098203 -0.08003822 -0.99664521, + 0.068900995 -0.17155099 -0.98276287, + 0.071262822 -0.17152306 -0.98259938, + 0.059386823 -0.15303107 -0.98643535, + 0.038004182 -0.15319093 -0.9874655, + 0.028407691 -0.14012195 -0.98972666, + -0.00061040308 -0.14017801 -0.99012613, + -0.013496798 -0.12468297 -0.99210477, + -0.05133171 -0.12453003 -0.99088722, + -0.076092929 -0.097916834 -0.99228138, + -0.12555605 -0.097424537 -0.98729134, + -0.14294893 -0.080492161 -0.98645151, + -0.20188807 -0.079652831 -0.97616434, + -0.21910293 -0.064268284 -0.97358274, + -0.28715286 -0.063094571 -0.95580453, + -0.34037092 -0.017960696 -0.94011974, + -0.41848293 -0.017348198 -0.90805888, + -0.46483099 0.0217588 -0.88513201, + -0.54583299 0.020591401 -0.837641, + -0.57819587 0.048825789 -0.81443584, + -0.65525174 0.045205984 -0.75405669, + -0.67451376 0.063216679 -0.73555076, + -0.74271607 0.057337806 -0.66714704, + -0.751396 0.066312902 -0.65651101, + -0.80933917 0.059025913 -0.58436811, + -0.81086868 0.060815077 -0.5820598, + -0.85934412 0.053142808 -0.50862908, + -0.85663891 0.049504194 -0.51353592, + -0.89690787 0.042432595 -0.44017693, + -0.89232957 0.035265781 -0.45000479, + -0.92539078 0.029611792 -0.3778559, + -0.92018676 0.020027794 -0.39096692, + -0.94726962 0.016393295 -0.32001787, + -0.94239813 0.0056886002 -0.33444503, + -0.96440214 0.0044972203 -0.26440203, + -0.96030813 -0.006485261 -0.27886602, + -0.97789139 -0.0048617818 -0.20905708, + -0.97497112 -0.014838802 -0.22183603, + -0.98820567 -0.010220196 -0.15279093, + -0.98639452 -0.018713791 -0.16332692, + -0.99546188 -0.010832499 -0.094541982, + -0.99486148 -0.015440907 -0.10006104, + -0.99947822 -0.0049260715 -0.031922206, + -0.99946612 -0.0052156406 -0.032255404, + -0.99950063 0.0050438982 0.031193189, + -0.99948555 0.0054235971 0.031609185, + -0.9955669 0.015905999 0.09270139, + -0.99539298 0.017431799 0.094281599, + -0.98790354 0.028193187 0.15248492, + -0.98740125 0.030963408 0.15517803, + -0.97657424 0.042105909 0.21102105, + -0.97558451 0.046185877 0.2147129, + -0.96159488 0.057720494 0.26833498, + -0.959939 0.063272998 0.27297199, + -0.94320136 0.075017527 0.32364112, + -0.94070464 0.082191467 0.32911888, + -0.92137134 0.094174534 0.37710214, + -0.91782838 0.10319804 0.38332915, + -0.89602631 0.11542205 0.42873615, + -0.8918131 0.12518202 0.43474007, + -0.86773384 0.13752997 0.47762287, + -0.86367518 0.14629003 0.48235312, + -0.8377499 0.15848199 0.52254993, + -0.8320598 0.17010896 0.52795786, + -0.80432415 0.18222405 0.56555915, + -0.79726917 0.19598705 0.57092112, + -0.76756972 0.20811093 0.60623974, + -0.75923532 0.22375907 0.61114126, + -0.72768599 0.235825 0.64409602, + -0.71803385 0.25340194 0.64823979, + -0.68526804 0.26515502 0.67830706, + -0.67431474 0.2846449 0.68137878, + -0.64050919 0.29601806 0.70860517, + -0.62844104 0.31715202 0.71026504, + -0.59348488 0.32815591 0.73490781, + -0.59644604 0.32288304 0.73484606, + -0.56501669 0.33190486 0.75537765, + -0.58128011 0.29981005 0.75645715, + -0.54869819 0.30803213 0.77720428, + -0.56251568 0.27675587 0.77909064, + -0.52867699 0.284132 0.79985601, + -0.54031801 0.25356001 0.80234897, + -0.5047558 0.2601299 0.82313669, + -0.51451087 0.22995093 0.82607579, + -0.47697723 0.23569912 0.84672242, + -0.48504919 0.20572308 0.84994429, + -0.44616693 0.21053697 0.86983287, + -0.45265612 0.18086705 0.87314916, + -0.41218692 0.18480496 0.89215976, + -0.41729394 0.15525198 0.89541191, + -0.37527007 0.15835202 0.91328913, + -0.37914193 0.12878399 0.9163329, + -0.33551198 0.13110799 0.93286788, + -0.33829084 0.10135496 0.93556756, + -0.29365888 0.10295596 0.95034963, + -0.29550293 0.072972588 0.95255077, + -0.25016704 0.07395491 0.96537411, + -0.25122702 0.043791004 0.96693712, + -0.25207907 0.013086903 0.96761823, + -0.25154307 0.043891616 0.96685034, + -0.29754701 0.043295801 0.95372498, + -0.29632512 0.073233932 0.95227534, + -0.34160909 0.072065018 0.93707526, + -0.33952999 0.101746 0.935076, + -0.38393208 0.099882126 0.91794324, + -0.38085991 0.12931897 0.91554475, + -0.42378601 0.126679 0.89686, + -0.41959986 0.15595295 0.89421171, + -0.46090713 0.15247203 0.8742522, + -0.45546505 0.18169501 0.8715151, + -0.49532217 0.17729805 0.85042429, + -0.48846531 0.20669012 0.84775048, + -0.52699494 0.20130996 0.82568187, + -0.51855999 0.23103701 0.82323599, + -0.55513698 0.22474501 0.80081999, + -0.54502231 0.25473714 0.79878646, + -0.5798139 0.24754494 0.77623284, + -0.5678342 0.27797309 0.77478731, + -0.60136294 0.26981196 0.75203991, + -0.5872187 0.30102286 0.75137162, + -0.61964804 0.29189304 0.72858405, + -0.60305899 0.32404801 0.728912, + -0.63407105 0.31412703 0.70659608, + -0.63073421 0.32000908 0.70694315, + -0.66530198 0.30787501 0.68013698, + -0.67665821 0.28801209 0.67763025, + -0.7102198 0.27537093 0.64788783, + -0.72031707 0.25725102 0.64417803, + -0.75271583 0.24415994 0.6113959, + -0.76138288 0.22807796 0.60685796, + -0.79187882 0.21484196 0.57163888, + -0.79919267 0.20070091 0.56657767, + -0.82769561 0.18737891 0.52896976, + -0.83371013 0.17515801 0.52368605, + -0.86036086 0.16167098 0.48336494, + -0.86502671 0.15160795 0.47827181, + -0.88972121 0.13794403 0.43516409, + -0.89287591 0.13063999 0.43093595, + -0.91527522 0.11686703 0.3855041, + -0.91860074 0.10844298 0.38001692, + -0.93852174 0.094731681 0.33196792, + -0.94122022 0.08702112 0.32639208, + -0.95848978 0.073453486 0.27550295, + -0.9602555 0.067552269 0.27082488, + -0.97470576 0.054088891 0.21684796, + -0.97575688 0.049761694 0.21312498, + -0.98694915 0.036614105 0.15681502, + -0.98747921 0.033689607 0.15411003, + -0.99522775 0.020839494 0.095328279, + -0.99541736 0.019172808 0.093684629, + -0.99946791 0.0065399893 0.031956594, + -0.99948752 0.0060402774 0.031435184, + -0.99945176 -0.0062474688 -0.032513492, + -0.99946666 -0.0058883778 -0.03212009, + -0.99474764 -0.018456992 -0.10067996, + -0.99483967 -0.017766295 -0.099891663, + -0.98454189 -0.030669795 -0.17244299, + -0.98629349 -0.022980388 -0.16339193, + -0.97097576 -0.033311293 -0.23684694, + -0.974738 -0.021296199 -0.222334, + -0.95477176 -0.028350793 -0.29598495, + -0.9598341 -0.015517702 -0.28013903, + -0.93523264 -0.019580992 -0.35349187, + -0.94153267 -0.0063422276 -0.33686188, + -0.91187024 -0.0077268719 -0.41040608, + -0.91866964 0.0044177086 -0.39500186, + -0.88315231 0.0052459617 -0.46905717, + -0.88974768 0.015403095 -0.45619285, + -0.84739912 0.017917302 -0.53065407, + -0.85234398 0.0245525 -0.52240503, + -0.80237466 0.028018987 -0.59616268, + -0.8039428 0.029871793 -0.59395587, + -0.74535275 0.033486389 -0.66582876, + -0.74069619 0.028574808 -0.67123216, + -0.67279005 0.031466704 -0.73916405, + -0.65896869 0.018220691 -0.75194967, + -0.5828619 0.019683894 -0.81233281, + -0.55764711 -0.0028582907 -0.83007318, + -0.47751081 -0.0030254489 -0.87862068, + -0.4407542 -0.034662616 -0.89695841, + -0.36230478 -0.035992179 -0.93136448, + -0.31594697 -0.07575319 -0.94574785, + -0.24550205 -0.077399418 -0.96630126, + -0.19816096 -0.11932797 -0.97287875, + -0.140614 -0.120534 -0.98269999, + -0.12727603 -0.13323402 -0.98287827, + -0.079113007 -0.13390602 -0.98783112, + -0.066565596 -0.14710198 -0.98687887, + -0.026944287 -0.14737593 -0.9887135, + -0.0095637357 -0.16778892 -0.98577654, + 0.020166703 -0.16776301 -0.98562109, + 0.02823391 -0.17846906 -0.98354036, + 0.050487392 -0.17831199 -0.98267788, + 0.056144185 -0.18689196 -0.98077476, + 0.072034724 -0.18670106 -0.97977233, + 0.08012598 -0.20083496 -0.97634274, + 0.075609915 -0.20090604 -0.97668827, + 0.030645508 -0.11119303 -0.99332625, + -0.278422 0.609541 -0.74225402, + -0.17921294 0.38264886 -0.90634573, + -0.19519188 0.38146377 -0.90354049, + -0.083606996 0.14499998 -0.98589289, + -0.094000913 0.14486502 -0.98497611, + 0.027751587 -0.094050959 -0.99518055, + 0.029597497 -0.094045885 -0.99512786, + -0.10664193 0.15741591 -0.9817574, + -0.095483474 0.15759495 -0.98287678, + -0.21201 0.38945901 -0.89631099, + -0.19530907 0.39084414 -0.89949727, + -0.29586396 0.60622293 -0.73821294, + -0.29678804 0.59561908 -0.74642807, + -0.31913498 0.61408591 -0.72183895, + -0.21237205 0.3993071 -0.89188123, + -0.22975494 0.39769691 -0.88828474, + -0.10858096 0.17079994 -0.97930467, + -0.12080096 0.17055795 -0.97791463, + 0.012920304 -0.062179223 -0.99798137, + 0.013766002 -0.062178608 -0.9979701, + -0.13638704 0.18445304 -0.97333223, + -0.12326898 0.18477298 -0.97501987, + -0.24858503 0.40598106 -0.87942314, + -0.23037305 0.40786508 -0.88350123, + -0.33719814 0.61002028 -0.71705836, + -0.33770484 0.59948373 -0.72565466, + -0.36207309 0.61757714 -0.69821316, + -0.24948394 0.4166269 -0.87417382, + -0.268462 0.41443801 -0.86957997, + -0.13939595 0.19930792 -0.96997166, + -0.15363398 0.19888397 -0.96790588, + -0.0090681454 -0.025738187 -0.99962753, + -0.0096224146 -0.025738113 -0.99962246, + -0.17269102 0.21388602 -0.96147311, + -0.15723999 0.21444698 -0.96399587, + -0.28949809 0.42284414 -0.85871631, + -0.26964498 0.42539793 -0.86390287, + -0.38076583 0.61262268 -0.69261163, + -0.3808929 0.60189688 -0.70188379, + -0.46394107 0.73894608 -0.48858705, + -0.47329083 0.60086477 -0.64417177, + -0.55444902 0.70893502 -0.43588701, + -0.52119732 0.59620535 -0.61064935, + -0.59878987 0.68962383 -0.40727091, + -0.55588275 0.71576065 -0.42270678, + -0.59482801 0.76807803 -0.237141, + -0.56755 0.82042801 -0.069173001, + -0.5518322 0.79684031 -0.24602209, + -0.49476293 0.86902785 -0.00051527895, + -0.49471 0.86905801 -0.00048675499, + -0.49062493 0.86198187 -0.12757099, + -0.49067813 0.86195219 -0.12756702, + -0.5245102 0.84851128 -0.070125923, + -0.50770187 0.82036179 -0.26314494, + -0.55200922 0.79399037 -0.25468612, + -0.51069379 0.73239964 -0.45031378, + -0.42635885 0.60253274 -0.67466474, + -0.50938791 0.72529781 -0.46310589, + -0.46504694 0.74615794 -0.47642395, + -0.50792819 0.81745732 -0.27161109, + -0.46303278 0.84112656 -0.27947587, + -0.48053017 0.87398428 -0.072403923, + -0.44758487 0.88421679 -0.13352297, + -0.45167178 0.89218259 0.0017214292, + -0.45152014 0.8922593 0.0017214906, + -0.44742012 0.88426524 -0.13375503, + -0.44743812 0.88425624 -0.13375403, + -0.45153812 0.89225024 0.0017243205, + -0.42386207 0.90560311 -0.014971701, + 0.99705201 0.076727398 -0.00046187101, + 0.97867239 0.20537308 0.0047339117, + 0.97804767 0.20504892 -0.037117586, + 0.98699147 0.15820208 -0.028637514, + 0.98640776 0.15794095 -0.045325588, + 0.99291635 0.11420604 -0.03277481, + 0.94333977 -0.24057794 0.22854394, + 0.92773724 -0.27059707 0.25706205, + 0.9266119 -0.26567298 0.26609796, + 0.91043222 -0.29226705 0.29273406, + 0.90891302 -0.28607401 0.303379, + 0.8906281 -0.31197003 0.33084202, + 0.88862276 -0.30430993 0.34313992, + 0.86803013 -0.32943904 0.37147504, + 0.86548632 -0.32027712 0.38517016, + 0.84276986 -0.34415197 0.41388193, + 0.83960772 -0.33331987 0.42890185, + 0.81460541 -0.35591474 0.45797667, + 0.81071728 -0.34315312 0.47432417, + 0.78311354 -0.3645128 0.50384873, + 0.77839732 -0.34956512 0.52144217, + 0.74803704 -0.36954704 0.55124909, + 0.74252582 -0.3525269 0.5695439, + 0.70978808 -0.37073603 0.59896207, + 0.70347321 -0.35153311 0.61769724, + 0.66844529 -0.36787519 0.64641231, + 0.66128397 -0.34620997 0.66546392, + 0.62370896 -0.36075798 0.69342697, + 0.61574012 -0.33651409 0.71247619, + 0.57566899 -0.34921199 0.739362, + 0.56706303 -0.32255104 0.75789213, + 0.52533299 -0.33321199 0.78293997, + 0.51625592 -0.30420998 0.80058485, + 0.47315612 -0.31292909 0.82352817, + 0.46380806 -0.28167504 0.83996511, + 0.41939691 -0.28862694 0.86069781, + 0.41004601 -0.255362 0.87558699, + 0.36465281 -0.26070389 0.8939026, + 0.3556259 -0.22585094 0.90692979, + 0.31019884 -0.22972789 0.92249757, + 0.30169511 -0.19329508 0.93360436, + 0.25669792 -0.19594893 0.94641966, + 0.2504389 -0.16524594 0.95392567, + 0.20576903 -0.16703302 0.96424013, + 0.20163497 -0.14271298 0.96900791, + 0.15834606 -0.14386705 0.97684634, + 0.15420707 -0.11248804 0.98161435, + 0.11116701 -0.11314402 0.98734009, + 0.10796102 -0.07910122 0.99100322, + 0.065502286 -0.079395376 0.99468875, + 0.063524619 -0.044418715 0.99699134, + 0.021533607 -0.044498216 0.99877733, + 0.0208642 -0.00908521 0.99974102, + -0.020567505 -0.0090852622 0.99974722, + -0.021235999 -0.044495896 0.99878389, + -0.063151106 -0.044417102 0.99701512, + -0.065124683 -0.079381675 0.99471474, + -0.10761794 -0.079088561 0.99104154, + -0.11081995 -0.11317495 0.9873755, + -0.15385106 -0.11252104 0.98166639, + -0.15801105 -0.14416103 0.97685724, + -0.20144592 -0.14300196 0.96900463, + -0.20561296 -0.16755596 0.96418273, + -0.25037807 -0.16576104 0.95385224, + -0.25654787 -0.19603992 0.94644153, + -0.30159998 -0.19338296 0.93361688, + -0.31001282 -0.22940487 0.92264044, + -0.35537499 -0.22554199 0.90710503, + -0.36432803 -0.26007202 0.8942191, + -0.40967801 -0.25475499 0.87593597, + -0.41903007 -0.28797704 0.86109412, + -0.46336389 -0.28106093 0.84041584, + -0.47270724 -0.31225315 0.82404244, + -0.51577896 -0.30357298 0.80113387, + -0.52488518 -0.33261913 0.78349233, + -0.56658512 -0.3220011 0.75848317, + -0.57524115 -0.34876409 0.73990619, + -0.61531913 -0.33609807 0.71303618, + -0.62335473 -0.36050689 0.69387579, + -0.66093475 -0.34598488 0.66592777, + -0.66814196 -0.36775696 0.64679295, + -0.70320505 -0.35142303 0.61806506, + -0.70957279 -0.3707689 0.59919685, + -0.74231595 -0.35257298 0.56978893, + -0.74785304 -0.36966303 0.55142105, + -0.77825916 -0.34966108 0.52158409, + -0.78299153 -0.36465478 0.50393569, + -0.81061834 -0.34328315 0.47439924, + -0.81452513 -0.35610604 0.45797107, + -0.83953899 -0.33349901 0.42889699, + -0.84271187 -0.34436998 0.41381893, + -0.8654539 -0.32046098 0.38508993, + -0.86799932 -0.32963711 0.37137112, + -0.88859868 -0.30449089 0.34304187, + -0.89061022 -0.31218305 0.3306891, + -0.90890324 -0.28626207 0.30323106, + -0.91042525 -0.29247707 0.29254606, + -0.92661399 -0.26585099 0.26591301, + -0.92773664 -0.27077192 0.2568799, + -0.94207889 -0.24331696 0.23083398, + -0.9428941 -0.24718203 0.22327504, + -0.94361466 -0.27757692 0.18039495, + -0.99974477 0.022043994 -0.0049518184, + -0.99973273 0.022010094 -0.0070763682, + -0.99973601 -0.021876 0.0070332401, + -0.99972123 -0.021831706 0.0089937216, + -0.99751252 -0.065175273 0.026849488, + -0.99752462 -0.065196075 0.02634369, + -0.94288588 -0.29432696 0.15600598, + -0.95459467 -0.26321891 0.13951595, + -0.95529687 -0.26917398 0.12228298, + -0.96552688 -0.23699497 0.10766298, + -0.96592677 -0.24109994 0.09410838, + -0.97483736 -0.20765908 0.081055328, + -0.97507513 -0.21066204 0.069642209, + -0.98272437 -0.17572206 0.058091924, + -0.982678 -0.17520601 0.060389299, + -0.98849809 -0.14297901 0.049281806, + -0.98833388 -0.14220898 0.054522794, + -0.99335426 -0.10746902 0.04120351, + -0.99327701 -0.107331 0.043368701, + -0.99324054 -0.10853795 0.04114398, + -0.99748546 -0.066269733 0.025121212, + -0.99759489 -0.066393994 0.019904498, + -0.99973577 -0.022018194 0.0066009285, + -0.99974614 -0.022049502 0.0046330406, + -0.999744 0.0221423 -0.0046525602, + -0.99974525 0.022145206 -0.0043711509, + -0.99973565 0.022563493 -0.0044048284, + -0.99974465 0.022561193 -0.0012942696, + -0.99734211 0.071945108 -0.011522501, + -0.99740833 0.071939826 0.0011392303, + -0.99739563 0.072116077 0.0011393595, + -0.99738985 0.072119392 -0.0035184396, + -0.99772513 0.067274511 -0.0043273303, + -0.99762821 0.067159615 -0.015086204, + -0.99330223 0.11235803 -0.026954006, + -0.99763387 0.066854492 -0.016038198, + -0.99750614 0.066736311 -0.022974903, + -0.99973261 0.021864492 -0.0075271572, + -0.99971449 0.021814188 -0.0097491657, + -0.99972373 -0.021458395 0.0095901582, + -0.99972361 -0.021457892 0.009603966, + -0.99754041 -0.06397716 0.028634483, + -0.997572 -0.064058103 0.027324099, + -0.99402326 -0.10041502 0.042832211, + -0.99412823 -0.10099202 0.038856208, + -0.98961574 -0.13415197 0.051614389, + -0.98965621 -0.13459103 0.04965781, + -0.98348701 -0.169791 0.062645003, + -0.9832775 -0.16742708 0.071648434, + -0.9758569 -0.20079698 0.085928991, + -0.97551525 -0.19756004 0.096644223, + -0.96682239 -0.22946508 0.11225104, + -0.96621555 -0.2245709 0.12647294, + -0.95616353 -0.25515187 0.14369692, + -0.95515567 -0.24827892 0.16135395, + -0.95525336 -0.23253308 0.18281005, + -0.95659512 -0.24036004 0.16478102, + -0.96656066 -0.21150692 0.14500095, + -0.96739364 -0.21718493 0.13030796, + -0.97595102 -0.18692601 0.112153, + -0.97643948 -0.19082609 0.10075404, + -0.9836911 -0.15905702 0.08398021, + -0.98395276 -0.16149595 0.075868085, + -0.98995399 -0.12797201 0.0601191, + -0.99011064 -0.12973295 0.053388983, + -0.9947421 -0.094705515 0.038974304, + -0.99471366 -0.094366863 0.040491585, + -0.99786901 -0.059962198 0.025729001, + -0.99782223 -0.059598815 0.028262008, + -0.99972838 -0.021059008 0.0099862441, + -0.99972445 -0.021032309 0.010427805, + -0.99971426 0.021416705 -0.010618303, + -0.99971652 0.02142599 -0.010384696, + -0.99729866 0.066099279 -0.032036889, + -0.99750215 0.066284008 -0.024412403, + -0.99290389 0.11159199 -0.041099295, + -0.99331415 0.11183502 -0.028635703, + -0.9873035 0.15841192 -0.011719895, + -0.98660791 0.15801199 -0.040459696, + -0.89264458 0.44739878 -0.054955374, + -0.934228 0.27803001 -0.22342201, + -0.92393398 0.273112 -0.26787299, + -0.94810277 0.22700194 -0.22264594, + -0.94940948 0.2277181 -0.2162551, + -0.97228163 0.16954294 -0.16100794, + -0.9740265 0.17181192 -0.14748892, + -0.98698634 0.12201405 -0.10474104, + -0.9873265 0.12306794 -0.10020296, + -0.99410576 0.084071875 -0.068452485, + -0.99395579 0.083254576 -0.071557686, + -0.99800134 0.047924519 -0.041191414, + -0.9979775 0.047668021 -0.042056918, + -0.99979526 0.015174604 -0.013388303, + -0.99979013 0.014979202 -0.013976102, + -0.99980336 -0.014501706 0.013530605, + -0.99979651 -0.014209193 0.014318894, + -0.99823487 -0.041832697 0.042155597, + -0.99815965 -0.040668786 0.044982184, + -0.99511653 -0.066197671 0.073218763, + -0.99486703 -0.063758299 0.078578599, + -0.99032313 -0.087442808 0.10776801, + -0.98975343 -0.083345547 0.11593793, + -0.98360598 -0.105261 0.146422, + -0.98249787 -0.098988086 0.15779498, + -0.97470403 -0.11877 0.18933, + -0.97279435 -0.10991704 0.20393507, + -0.96315211 -0.12760802 0.23675802, + -0.96004546 -0.11551605 0.25489011, + -0.31067395 0.035138194 0.94986677, + -0.27548599 0.035537001 0.960648, + -0.26762098 0.067058891 0.9611879, + -0.22888903 0.06774991 0.9710921, + -0.221981 0.100073 0.96990198, + -0.18340296 0.10089198 0.97784674, + -0.17759395 0.13377796 0.97496867, + -0.13920796 0.13461596 0.98107064, + -0.13457404 0.16809806 0.97654134, + -0.096791066 0.16884494 0.98087865, + -0.093396991 0.20293997 0.97472686, + -0.056437384 0.20350595 0.97744578, + -0.054383889 0.23765995 0.96982479, + -0.018240491 0.23797289 0.97110051, + -0.017551105 0.2720241 0.96213037, + 0.017719194 0.2720229 0.96212763, + 0.018411696 0.23796694 0.97109878, + 0.054545667 0.23765285 0.9698174, + 0.056599684 0.20355695 0.97742575, + 0.093540967 0.20298992 0.97470266, + 0.096928619 0.16896005 0.98084521, + 0.13463502 0.16821301 0.97651315, + 0.139286 0.134599 0.981062, + 0.17766401 0.13376202 0.97495812, + 0.18349595 0.10074098 0.97784477, + 0.22211097 0.099921688 0.96988785, + 0.229027 0.067556702 0.97107297, + 0.2678279 0.066865876 0.96114361, + 0.27570492 0.035281688 0.96059465, + 0.31476802 0.034838505 0.94852912, + 0.32340303 0.0044183806 0.94625109, + 0.36251909 0.0043516811 0.93196625, + 0.59330302 -0.080260701 0.80096799, + 0.62668699 -0.077697396 0.775388, + 0.63292783 -0.090842277 0.76886284, + 0.66854376 -0.087259173 0.73853576, + 0.67624056 -0.10319894 0.72941661, + 0.71044058 -0.098586738 0.69681758, + 0.72037023 -0.11924504 0.68326223, + 0.75230283 -0.11326697 0.6490078, + 0.76109588 -0.13197199 0.63507193, + 0.79057485 -0.12459097 0.59955686, + 0.7980392 -0.14098904 0.5858801, + 0.82522702 -0.132144 0.54912502, + 0.83143401 -0.14636099 0.53600001, + 0.85631102 -0.13604499 0.49822, + 0.86134428 -0.14819206 0.48592716, + 0.88356942 -0.13660505 0.4479332, + 0.88758332 -0.14691806 0.43659014, + 0.90724921 -0.13414402 0.39862809, + 0.91036612 -0.14276302 0.38839707, + 0.92971265 -0.12705895 0.34567389, + -0.46545106 -0.11411601 0.87768614, + -0.51221603 -0.11073501 0.85168815, + -0.51642907 -0.12118302 0.8477121, + -0.55621499 -0.117604 0.82267499, + -0.56463194 -0.13743898 0.81381887, + -0.60283887 -0.13286297 0.78672284, + -0.61372614 -0.15790504 0.7735672, + -0.65024495 -0.15194598 0.74437493, + -0.66043472 -0.17522691 0.73015165, + -0.69529378 -0.16772294 0.69888175, + -0.70454782 -0.18895295 0.68403882, + -0.73748004 -0.17982301 0.65098906, + -0.74563503 -0.19880803 0.63600606, + -0.77600282 -0.18817796 0.60200387, + -0.78305614 -0.20500903 0.58719206, + -0.8108288 -0.19292195 0.55257386, + -0.81680429 -0.20767607 0.53823918, + -0.84222412 -0.19407403 0.50298506, + -0.84719086 -0.20689197 0.48934993, + -0.87030029 -0.19179508 0.45364314, + -0.8742519 -0.20255996 0.44119495, + -0.89479429 -0.18629105 0.40575716, + -0.89789569 -0.19529192 0.39451784, + -0.91602677 -0.17794995 0.3594839, + -0.91840714 -0.18538302 0.34951603, + -0.93440223 -0.16691405 0.31469408, + -0.93618226 -0.17296705 0.30601507, + -0.95136374 -0.15158997 0.26819295, + -0.95354927 0.29782507 -0.04521041, + 0.29228505 -0.10027903 0.95105922, + 0.32982191 -0.098990574 0.93883878, + 0.95353585 -0.17149799 0.24770497, + 0.93906534 -0.19566707 0.28261408, + 0.93764025 -0.19039704 0.29082605, + 0.9223429 -0.21162997 0.32325897, + 0.92040002 -0.20501401 0.33291599, + 0.903063 -0.225218 0.365724, + 0.90047622 -0.21702604 0.37688509, + 0.88082427 -0.23625706 0.41028208, + 0.87754422 -0.22650807 0.4226231, + 0.85540581 -0.24467695 0.4565239, + 0.85133046 -0.23320086 0.46995074, + 0.8269223 -0.24995309 0.5037092, + 0.82192087 -0.23648497 0.51818997, + 0.79515213 -0.25176704 0.55167603, + 0.78912169 -0.23610091 0.56704783, + 0.75971287 -0.24994797 0.60030192, + 0.7526533 -0.23210108 0.61615121, + 0.7205658 -0.24442793 0.64887583, + 0.71248984 -0.22435895 0.66484684, + 0.6782822 -0.23494905 0.69622719, + 0.66916007 -0.21244404 0.71210408, + 0.63301319 -0.22131306 0.7418322, + 0.62300086 -0.19653496 0.75712883, + 0.58483493 -0.20380397 0.78513187, + 0.57410896 -0.17687598 0.79944587, + 0.53413808 -0.18262501 0.82543612, + 0.52286208 -0.15355702 0.83847213, + 0.48203993 -0.15783198 0.86181587, + 0.47317082 -0.13393095 0.8707307, + 0.43179405 -0.13712402 0.89148813, + 0.42513114 -0.11791504 0.89741832, + 0.38573885 -0.12019096 0.91474569, + 0.37995985 -0.10165096 0.91940063, + 0.33455789 -0.10355996 0.93666762, + 0.34091991 -0.12643097 0.93155175, + 0.38155818 -0.12431306 0.91594744, + 0.38794315 -0.14463404 0.91026431, + 0.43038315 -0.14164604 0.89146328, + 0.43905213 -0.16707106 0.88279128, + 0.48078594 -0.16304998 0.86154491, + 0.49185377 -0.19372891 0.84885156, + 0.53296691 -0.18826897 0.82492489, + 0.54368681 -0.21688193 0.81078172, + 0.58373702 -0.20981599 0.784365, + 0.59394908 -0.23639002 0.76898915, + 0.63200581 -0.22771095 0.74075383, + 0.6414367 -0.25193989 0.72462761, + 0.67738718 -0.24157906 0.69482815, + 0.6858812 -0.26336405 0.6783852, + 0.71978116 -0.25123605 0.6471442, + 0.72734696 -0.27080998 0.63057792, + 0.75902712 -0.25691602 0.59822404, + 0.76557797 -0.27418199 0.58199197, + 0.79456419 -0.25877106 0.54927713, + 0.8000893 -0.2737481 0.53377819, + 0.82642317 -0.25694105 0.50100511, + 0.83100897 -0.26983699 0.48642799, + 0.85498816 -0.25159207 0.45353812, + 0.85875016 -0.26266506 0.43994913, + 0.88048214 -0.24302404 0.40705106, + 0.88350213 -0.25241503 0.39460206, + 0.90278876 -0.23175494 0.3623009, + 0.90510869 -0.23944591 0.35134587, + 0.92212898 -0.217878 0.31969899, + 0.92388135 -0.22411707 0.3101851, + 0.93890637 -0.20156607 0.2789731, + 0.94019651 -0.20655189 0.27086288, + 0.95334899 -0.18304799 0.24004, + 0.95001179 0.29539993 -0.10107598, + 0.96487635 0.24855709 -0.085047632, + 0.96230602 0.24745201 -0.112848, + 0.97533566 0.20082892 -0.091585971, + 0.97268599 0.19967601 -0.11837, + 0.98426837 0.15198205 -0.090096027, + 0.98324138 0.15136506 -0.10161204, + 0.99189025 0.10552502 -0.070839211, + 0.99199349 0.10563405 -0.06921313, + 0.99757802 0.0581806 -0.038120698, + 0.99766755 0.058638468 -0.034941584, + 0.99978149 0.01796061 -0.010702404, + 0.99978286 0.018009298 -0.010482299, + 0.99979699 -0.0174137 0.0101355, + 0.99979287 -0.017234698 0.010828199, + 0.9982065 -0.050689977 0.031847283, + 0.99817222 -0.050123211 0.033763207, + 0.99515635 -0.081532732 0.054920819, + 0.99502337 -0.08005473 0.059328523, + 0.99062526 -0.10975303 0.08133772, + 0.99032611 -0.10720202 0.088101506, + 0.9845261 -0.13538502 0.11126202, + 0.98394036 -0.13132605 0.12089205, + 0.9767769 -0.15763699 0.14511198, + 0.97572976 -0.15157297 0.15804096, + 0.96708155 -0.17613791 0.18365391, + 0.96537286 -0.16772498 0.19980897, + 0.95506763 -0.19055893 0.22700892, + 0.95509279 -0.19039096 0.22704394, + 0.94114864 -0.21717593 0.25898591, + 0.93997574 -0.21242796 0.26705796, + 0.92518187 -0.23625997 0.29701796, + 0.92359543 -0.23033911 0.30645615, + 0.90684402 -0.25322899 0.33691099, + 0.90475124 -0.24595906 0.34774908, + 0.88578576 -0.26799095 0.37889892, + 0.88306791 -0.25912797 0.39120793, + 0.8616938 -0.28021294 0.42304191, + 0.85823268 -0.26953891 0.43678984, + 0.83462697 -0.28926 0.46875, + 0.83040029 -0.2768231 0.48353317, + 0.80446386 -0.29512498 0.51549894, + 0.7993868 -0.28073993 0.5311929, + 0.77079886 -0.29768497 0.56325191, + 0.76477683 -0.28111193 0.57973486, + 0.73347884 -0.29656494 0.6116029, + 0.72644657 -0.27759683 0.62866163, + 0.69285196 -0.29127198 0.65963393, + 0.68487394 -0.26997596 0.67680192, + 0.64918399 -0.281822 0.706496, + 0.64034104 -0.25821403 0.72338706, + 0.60237575 -0.26834092 0.75175571, + 0.59275377 -0.24235891 0.7680527, + 0.55264521 -0.2507951 0.79478627, + 0.54240692 -0.22248697 0.81011987, + 0.50108278 -0.2291829 0.83450061, + 0.49052799 -0.198916 0.84841901, + 0.44832411 -0.20403905 0.87027216, + 0.43765685 -0.17187095 0.8825627, + 0.39477307 -0.17562501 0.90183711, + 0.38645694 -0.14869699 0.9102419, + 0.34297892 -0.15144297 0.92705476, + 0.33698902 -0.13002402 0.93248713, + 0.29569986 -0.13192494 0.94612753, + 0.28872284 -0.10326394 0.95182753, + 0.2472759 -0.10450796 0.96329266, + 0.24071789 -0.07289996 0.96785355, + 0.19907196 -0.073605284 0.97721678, + 0.19345105 -0.04070501 0.98026526, + 0.151821 -0.041007798 0.98755699, + 0.147321 -0.0072752 0.98906201, + 0.10612104 -0.007313923 0.99432635, + 0.10283105 0.027108112 0.99432945, + 0.062325709 0.027199704 0.99768513, + 0.060311507 0.062227607 0.99623811, + 0.020378293 0.062327977 0.99784762, + 0.019699091 0.097581655 0.99503255, + -0.019588394 0.097581878 0.99503475, + -0.020266891 0.06235107 0.99784851, + -0.060126685 0.062251084 0.99624777, + -0.062138472 0.027284887 0.99769455, + -0.10260702 0.027193505 0.99435025, + -0.10589502 -0.0072065117 0.99435127, + -0.14702399 -0.0071685091 0.98910689, + -0.151527 -0.040915299 0.98760599, + -0.19312793 -0.040613987 0.98033261, + -0.19875591 -0.073572859 0.97728354, + -0.24036606 -0.072869718 0.96794325, + -0.24694106 -0.10459402 0.96336925, + -0.95510989 -0.19052097 0.22686297, + -0.941158 -0.21734799 0.25880799, + -0.9399839 -0.21258897 0.26690096, + -0.92518735 -0.23644608 0.29685313, + -0.92359489 -0.23049697 0.30633897, + -0.90683377 -0.25341594 0.33679792, + -0.90473598 -0.246124 0.34767199, + -0.88575727 -0.26818106 0.37883109, + -0.88302547 -0.25926986 0.39120975, + -0.86164069 -0.28036892 0.42304686, + -0.85815799 -0.26962599 0.436883, + -0.83454001 -0.289352 0.46884799, + -0.83027387 -0.27680597 0.48375994, + -0.80431366 -0.29510686 0.51574373, + -0.79920012 -0.28063503 0.53152907, + -0.77059513 -0.29756504 0.56359404, + -0.76450688 -0.28083697 0.58022392, + -0.73317021 -0.29627311 0.61211425, + -0.72606897 -0.277156 0.62929201, + -0.69247282 -0.29078895 0.66024482, + -0.68442607 -0.26935202 0.67750305, + -0.64872503 -0.28115204 0.70718408, + -0.63984674 -0.2574999 0.72407877, + -0.60191202 -0.26757199 0.75240099, + -0.59227508 -0.24160303 0.76866013, + -0.55217409 -0.24999607 0.79536515, + -0.54195672 -0.22179587 0.81061053, + -0.50069219 -0.22845207 0.83493531, + -0.49022219 -0.19846907 0.84870028, + -0.44810012 -0.20356604 0.87049818, + -0.43761387 -0.17195895 0.88256675, + -0.39468899 -0.175717 0.90185601, + -0.38658708 -0.14947502 0.91005921, + -0.34297588 -0.15224394 0.92692465, + -0.33689696 -0.13047099 0.93245786, + -0.29547101 -0.132384 0.94613498, + -0.28841606 -0.10335002 0.95191121, + -0.29199201 -0.100357 0.951141, + -0.32951301 -0.099070102 0.93893898, + -0.95355237 -0.17161407 0.24756108, + -0.93907475 -0.19581796 0.28247795, + -0.93764597 -0.190529 0.290721, + -0.9223401 -0.21178903 0.32316303, + -0.92038238 -0.20512107 0.33289912, + -0.90304011 -0.22533603 0.36570802, + -0.90043873 -0.21709692 0.37693384, + -0.88076824 -0.23634405 0.41035208, + -0.87745988 -0.22651596 0.42279395, + -0.85530901 -0.244683 0.45670199, + -0.8511827 -0.2330749 0.47028083, + -0.82675928 -0.24981108 0.50404716, + -0.82169211 -0.23618802 0.51868808, + -0.7949053 -0.25143909 0.55218118, + -0.78880221 -0.23562007 0.5676921, + -0.75936365 -0.24942788 0.60095972, + -0.75223017 -0.23143706 0.61691713, + -0.72013992 -0.24370597 0.64961994, + -0.7120114 -0.22355914 0.66562843, + -0.6777848 -0.23409495 0.69699883, + -0.6686697 -0.21166089 0.71279764, + -0.63253874 -0.22047593 0.74248576, + -0.62253201 -0.19576401 0.75771397, + -0.58441186 -0.20298496 0.78565884, + -0.57378513 -0.17634705 0.79979515, + -0.5338279 -0.18207195 0.82575881, + -0.52281284 -0.15368894 0.83847868, + -0.48198095 -0.15796798 0.86182386, + -0.47341201 -0.13486101 0.87045598, + -0.43192494 -0.13808699 0.89127588, + -0.42512894 -0.11846498 0.89734685, + -0.38563415 -0.12075704 0.91471529, + -0.37973014 -0.10178903 0.91948038, + -0.33431408 -0.10370002 0.93673927, + -0.34076592 -0.12693398 0.93153977, + -0.3815349 -0.12480097 0.91589075, + -0.38803184 -0.14551096 0.91008669, + -0.430554 -0.142498 0.89124501, + -0.43898311 -0.16723704 0.88279426, + -0.48072389 -0.16321196 0.86154884, + -0.49155983 -0.19322893 0.8491357, + -0.53264219 -0.18779208 0.82524329, + -0.54326022 -0.21609211 0.81127834, + -0.58330172 -0.20906289 0.78488964, + -0.59349072 -0.23552687 0.76960766, + -0.63152784 -0.22689794 0.74141079, + -0.64096522 -0.25108808 0.72534025, + -0.67688298 -0.24078999 0.695593, + -0.68543971 -0.26268387 0.67909467, + -0.71934599 -0.250606 0.64787197, + -0.72697699 -0.270302 0.63122201, + -0.75867486 -0.25644898 0.59887093, + -0.76530886 -0.27390096 0.58247793, + -0.79431129 -0.25851709 0.54976219, + -0.79990345 -0.27365115 0.53410631, + -0.8262549 -0.25685596 0.50132596, + -0.830881 -0.26985401 0.486637, + -0.85489011 -0.25159904 0.45371905, + -0.85867786 -0.26274398 0.44004294, + -0.88042486 -0.24309397 0.40713295, + -0.88346326 -0.25254607 0.3946051, + -0.90276289 -0.23186697 0.36229396, + -0.90509731 -0.23960608 0.35126612, + -0.92212391 -0.21801797 0.31961796, + -0.92388326 -0.22428806 0.31005606, + -0.93891323 -0.20171104 0.27884507, + -0.94020754 -0.20672089 0.27069589, + -0.95335978 -0.18319196 0.23988694, + -0.9550795 -0.19072191 0.2268219, + -0.96538788 -0.16785498 0.19962697, + -0.96709275 -0.17626895 0.18346895, + -0.97574013 -0.15168001 0.15787502, + -0.97678661 -0.15775494 0.14491795, + -0.98395014 -0.13141201 0.12071902, + -0.98453873 -0.13550597 0.11100297, + -0.99033552 -0.10728995 0.087888658, + -0.9906354 -0.10986293 0.081064954, + -0.99502963 -0.080127172 0.059123777, + -0.99515635 -0.081540532 0.05490962, + -0.99817222 -0.050127011 0.033755708, + -0.99820745 -0.050708622 0.031789716, + -0.99979299 -0.017240399 0.0108082, + -0.99979788 -0.017456798 0.0099704992, + -0.99978399 0.0180481 -0.0103082, + -0.99978137 0.017959006 -0.010710604, + -0.9976669 0.058634091 -0.034968898, + -0.9975751 0.058165807 -0.038218603, + -0.9919821 0.10561901 -0.069398411, + -0.99181437 0.10544304 -0.072014421, + -0.98307914 0.15126802 -0.10331202, + -0.98391575 0.15175997 -0.094226979, + -0.97206742 0.19939388 -0.12380192, + -0.97543025 0.20084004 -0.090549521, + -0.96245003 0.24747001 -0.111573, + -0.9654789 0.24879996 -0.077129893, + -0.95085979 0.29573694 -0.091680877, + -0.95364922 0.29704407 -0.048145313, + -0.93837351 0.34459817 -0.026596813, + -0.93728912 0.34406304 -0.055766106, + -0.92029661 0.39113382 -0.008282816, + -0.91833621 0.39002109 -0.067396715, + -0.93741035 0.34314111 -0.059295822, + -0.93327588 0.34108996 -0.11248899, + -0.95080686 0.29419798 -0.097024985, + -0.94601035 0.29201713 -0.14067905, + -0.96215165 0.24550991 -0.11827496, + -0.95605999 0.242907 -0.164151, + -0.97187102 0.195135 -0.131868, + -0.969666 0.194015 -0.148681, + -0.98264599 0.147231 -0.112827, + -0.98304188 0.14752798 -0.10892299, + -0.99281442 0.096268043 -0.071076557, + -0.99314147 0.097162947 -0.065034829, + -0.997908 0.053726301 -0.035960998, + -0.99794078 0.05403899 -0.034555592, + -0.99979174 0.017191997 -0.010993497, + -0.99978638 0.016989606 -0.011776905, + -0.99980003 -0.016436201 0.0113933, + -0.99979621 -0.016273905 0.011943803, + -0.99823451 -0.047883376 0.035142686, + -0.99818712 -0.047110707 0.037459403, + -0.99519241 -0.076658756 0.060954064, + -0.99503136 -0.074938528 0.065551125, + -0.99063522 -0.10276702 0.089893319, + -0.99026066 -0.099743761 0.097133964, + -0.98441637 -0.12598504 0.12268805, + -0.98367822 -0.12120803 0.13298804, + -0.97639412 -0.14549902 0.15963902, + -0.97511065 -0.13861196 0.17304894, + -0.96624702 -0.161054 0.201068, + -0.96414089 -0.15148899 0.21790697, + -0.95348811 -0.17206001 0.24749903, + -0.95139652 -0.16367193 0.26087588, + -0.93774486 -0.18458799 0.29421398, + -0.93614966 -0.17892994 0.30266789, + -0.92052424 -0.19882004 0.33631209, + -0.9183439 -0.19171497 0.34625098, + -0.9006294 -0.2105121 0.38019916, + -0.89779431 -0.20192307 0.39139816, + -0.87770873 -0.21970195 0.42586192, + -0.87410229 -0.20944907 0.43826514, + -0.85149872 -0.22609892 0.47310582, + -0.84698361 -0.21393989 0.48667076, + -0.8220818 -0.22913094 0.52122986, + -0.81653059 -0.2148359 0.53583878, + -0.7892769 -0.22850597 0.56993592, + -0.78270316 -0.21217005 0.58511513, + -0.7527979 -0.22439297 0.61882395, + -0.74518299 -0.205953 0.63426, + -0.71268624 -0.21664608 0.66719025, + -0.70398957 -0.19591889 0.68265259, + -0.66946107 -0.20492204 0.71402305, + -0.65976775 -0.18194894 0.72910976, + -0.62343276 -0.18930992 0.75861269, + -0.61296314 -0.16437005 0.77282518, + -0.57476985 -0.17023696 0.80041182, + -0.56374872 -0.14354692 0.81337661, + -0.52389312 -0.14803703 0.83882117, + -0.5153141 -0.12652403 0.84761018, + -0.47468495 -0.12994199 0.87051088, + -0.46772778 -0.11148395 0.87681359, + -0.42939106 -0.11391102 0.89590609, + -0.4232212 -0.095950142 0.90093142, + -0.38120115 -0.09790574 0.91929334, + -0.37744695 -0.085917793 0.92203689, + -0.33461803 -0.08743231 0.93828911, + -0.33090311 -0.074133433 0.94074833, + -0.28589907 -0.075280018 0.95529824, + -0.28024092 -0.069690481 0.95739663, + -0.24354294 -0.070413582 0.96733075, + -0.23685694 -0.038313191 0.97078878, + -0.1958281 -0.038671918 0.9798755, + -0.19016109 -0.005677063 0.98173648, + -0.149177 -0.0057178698 0.98879403, + -0.14464502 0.028047305 0.98908609, + -0.10417602 0.028191207 0.99415922, + -0.10086302 0.06262961 0.99292713, + -0.061088778 0.062832981 0.99615264, + -0.059071392 0.097633183 0.99346787, + -0.019938298 0.097784482 0.99500787, + -0.019254802 0.13290201 0.99094212, + 0.019336091 0.13290194 0.99094051, + 0.020019 0.097767003 0.99500799, + 0.059187185 0.097615078 0.99346274, + 0.06120627 0.062768571 0.99614954, + 0.10108198 0.062564492 0.9929089, + 0.10439695 0.028103987 0.99413854, + 0.14490199 0.027960297 0.98905087, + 0.14943895 -0.0058479384 0.98875362, + 0.19045496 -0.0058060987 0.98167878, + 0.19611895 -0.038784992 0.97981274, + 0.23718108 -0.038424514 0.97070533, + 0.24385805 -0.070470713 0.96724725, + 0.28481299 -0.0696548 0.95604903, + 0.32521302 -0.065895505 0.94334209, + 0.28836593 -0.066723384 0.95519274, + 0.28075004 -0.035638005 0.95911914, + 0.240301 -0.036043402 0.970029, + 0.2335691 -0.0038989619 0.97233248, + 0.19308791 -0.0039344081 0.98117352, + 0.18737805 0.029117508 0.98185623, + 0.14694192 0.029320784 0.9887104, + 0.14236805 0.063179724 0.98779535, + 0.10255498 0.063493393 0.99269891, + 0.099225014 0.097862415 0.99024111, + 0.06011077 0.098169953 0.99335253, + 0.058083486 0.13287997 0.98942876, + 0.019642994 0.13307898 0.99091077, + 0.018956991 0.16810092 0.98558754, + -0.0188777 0.168101 0.98558903, + -0.0195645 0.133081 0.99091202, + -0.058011476 0.13288195 0.98943263, + -0.060036194 0.098212786 0.99335289, + -0.099075764 0.097906061 0.99025166, + -0.102401 0.063599497 0.99270803, + -0.14221103 0.063285612 0.98781127, + -0.14678 0.0294712 0.98873001, + -0.18711402 0.029267604 0.98190212, + -0.19282497 -0.0037836796 0.98122591, + -0.23324403 -0.0037496805 0.9724111, + -0.23998395 -0.035928693 0.97011179, + -0.27615306 -0.035571106 0.96045524, + -0.59384227 -0.080360733 0.80055827, + -0.55165905 -0.083306007 0.82989913, + -0.54815888 -0.075154886 0.83299083, + -0.5085628 -0.077369973 0.85754168, + -0.50470412 -0.067820713 0.86062419, + -0.46444818 -0.06957332 0.88286328, + -0.46037781 -0.058768179 0.88577569, + -0.41954795 -0.060092792 0.90574187, + -0.41546515 -0.04832942 0.9083243, + -0.37395203 -0.049277209 0.9261381, + -0.36996117 -0.03661662 0.92832541, + -0.3278299 -0.037234992 0.94400275, + -0.32404688 -0.02379759 0.94574165, + -0.28189003 -0.024134804 0.9591431, + -0.27625999 -0.0013979001 0.96108198, + -0.23635094 -0.0014132897 0.97166675, + -0.22955306 0.030845808 0.97280723, + -0.18974698 0.031116296 0.98133987, + -0.18398301 0.064254411 0.98082709, + -0.14433296 0.06468568 0.98741263, + -0.13974501 0.098400414 0.98528612, + -0.10062002 0.098871216 0.99000013, + -0.097285025 0.13300502 0.98632926, + -0.058891315 0.13340603 0.98931026, + -0.05685392 0.16798706 0.98414838, + -0.019101098 0.16822898 0.98556286, + -0.018410601 0.20316701 0.978971, + 0.018555705 0.20316705 0.97896826, + 0.019246496 0.16826595 0.98555374, + 0.056932174 0.16802393 0.98413754, + 0.058970898 0.13340899 0.98930502, + 0.097360052 0.13300695 0.98632151, + 0.10070302 0.098785713 0.99000013, + 0.13986298 0.098314583 0.98527789, + 0.144457 0.064557299 0.98740298, + 0.18421191 0.064125068 0.98079252, + 0.18998195 0.030944992 0.98129976, + 0.22981709 0.030675411 0.97275037, + 0.23661812 -0.0016053508 0.97160149, + 0.27656287 -0.0015878192 0.96099454, + 0.2842491 -0.032797411 0.95818937, + 0.32429004 -0.032359704 0.94540411, + 0.33042011 -0.054081619 0.94228333, + 0.37278509 -0.053169712 0.92639321, + 0.37673706 -0.065732107 0.92398512, + 0.41842616 -0.064449824 0.90596128, + 0.422434 -0.076021597 0.90319997, + 0.46336505 -0.074325204 0.88304514, + 0.46719587 -0.084509879 0.88010573, + 0.50754011 -0.082356825 0.85768318, + 0.51373303 -0.097753897 0.85236299, + 0.55006516 -0.095152937 0.8296833, + 0.55678874 -0.11071495 0.8232426, + 0.59495425 -0.10712904 0.7965883, + 0.60353494 -0.12631299 0.78726786, + 0.64023805 -0.12169302 0.75847614, + 0.65111208 -0.14568701 0.74486804, + 0.68626517 -0.13961503 0.71382618, + 0.69619977 -0.16161893 0.69941777, + 0.72956073 -0.15397994 0.66635674, + 0.73828596 -0.17357199 0.65177196, + 0.76914233 -0.16445908 0.61755431, + 0.77669716 -0.18183404 0.60305715, + 0.80499989 -0.17126898 0.56801593, + 0.8113609 -0.18639499 0.55403095, + 0.8373161 -0.17433402 0.51817906, + 0.84260553 -0.18746389 0.50484967, + 0.86624169 -0.17392094 0.46837682, + 0.8705256 -0.18513492 0.45597178, + 0.8915571 -0.17038201 0.41963807, + 0.89490587 -0.17971699 0.40846694, + 0.91349059 -0.16385193 0.37240782, + 0.91605574 -0.17154296 0.3625119, + 0.93245423 -0.15453503 0.32657009, + 0.93437743 -0.16081007 0.31792915, + 0.94870138 -0.14270605 0.28213608, + 0.94840354 -0.13018595 0.28910586, + 0.93234235 -0.14846206 0.32969213, + 0.93024099 -0.141872 0.33841401, + 0.91338485 -0.15739399 0.37543994, + 0.91056275 -0.14926697 0.3854799, + 0.8914659 -0.16360898 0.42251694, + 0.88777924 -0.15374303 0.43383309, + 0.86617583 -0.16692695 0.47103587, + 0.86152542 -0.15524207 0.48339823, + 0.83728999 -0.16718 0.52057302, + 0.83158302 -0.153574 0.533746, + 0.80503112 -0.16403502 0.57010305, + 0.79813784 -0.14828297 0.58394188, + 0.76924717 -0.15726104 0.61929613, + 0.7611261 -0.13929902 0.63346905, + 0.72975618 -0.14683902 0.66775316, + 0.7203328 -0.12647296 0.68200082, + 0.68654698 -0.13257299 0.71489698, + 0.67608422 -0.11025104 0.72852921, + 0.64064878 -0.11489195 0.75918972, + 0.63244504 -0.097314619 0.76846814, + 0.59568173 -0.10090996 0.79685664, + 0.58916801 -0.086594 0.80335701, + 0.55435389 -0.089194976 0.82748783, + 0.54825026 -0.074924834 0.83295143, + 0.50868869 -0.077131756 0.85748845, + 0.50491285 -0.067795582 0.86050379, + 0.46466383 -0.069548279 0.8827517, + 0.46062511 -0.058826916 0.88564324, + 0.41982687 -0.060153078 0.90560871, + 0.4157488 -0.048401378 0.90819061, + 0.3742449 -0.04935139 0.92601573, + 0.36908808 -0.033032406 0.92880726, + 0.41304392 -0.032368291 0.91013575, + 0.41714215 -0.044149116 0.90776831, + 0.45783606 -0.043187004 0.88798714, + 0.46193221 -0.054039627 0.88526744, + 0.50208092 -0.052693292 0.8632139, + 0.50607204 -0.062549509 0.86022013, + 0.54556787 -0.060778085 0.83585984, + 0.54921716 -0.069263823 0.83280432, + 0.58736992 -0.067078993 0.80653387, + 0.58906168 -0.053234674 0.80633265, + 0.5465309 -0.055168185 0.83561981, + 0.54267699 -0.046216901 0.838669, + 0.50322199 -0.0475494 0.86284798, + 0.49915496 -0.037523597 0.86569989, + 0.45912987 -0.038469993 0.88753575, + 0.45498616 -0.027515309 0.8900733, + 0.41444206 -0.028120104 0.90964115, + 0.41032115 -0.016302105 0.91179532, + 0.36919689 -0.016613295 0.92920262, + 0.36453983 -0.028630387 0.93074757, + 0.32811296 -0.029043796 0.94419187, + 0.31958708 0.0011700202 0.94755626, + 0.28003502 0.0011853701 0.95998913, + 0.27225912 0.032575916 0.96167248, + 0.232851 0.032924201 0.971955, + 0.22597803 0.065332204 0.97193915, + 0.18675494 0.065887079 0.98019463, + 0.18095393 0.099004462 0.97849566, + 0.14190696 0.09964776 0.98485166, + 0.13728903 0.13331103 0.98151922, + 0.098847613 0.13392702 0.98604912, + 0.095483884 0.16807498 0.98113889, + 0.057842813 0.16856304 0.98399222, + 0.055789206 0.20308203 0.97757113, + 0.018899003 0.20336205 0.97892123, + 0.018207997 0.23785195 0.97113079, + -0.018028097 0.23785298 0.97113389, + -0.018717999 0.20334198 0.97892886, + -0.055681016 0.20306304 0.97758126, + -0.057735778 0.16850995 0.98400766, + -0.095444903 0.16802099 0.981152, + -0.098803803 0.133945 0.98605102, + -0.13721304 0.13333003 0.98152721, + -0.14181991 0.099753737 0.98485339, + -0.18079695 0.099111676 0.97851378, + -0.18658891 0.066059873 0.98021454, + -0.22581108 0.065504119 0.97196639, + -0.23267291 0.03315749 0.97198963, + -0.27200788 0.032807685 0.96173555, + -0.27978793 0.0014178896 0.96006078, + -0.31553108 0.0014014303 0.94891423, + -0.62598181 -0.045761287 0.77849382, + -0.58529514 -0.047579311 0.80942321, + -0.58156008 -0.039333403 0.81255209, + -0.54342192 -0.040588498 0.83847791, + -0.539451 -0.031383902 0.84143198, + -0.50002509 -0.032278206 0.8654092, + -0.49590212 -0.022136705 0.86809617, + -0.45598912 -0.022687607 0.88969624, + -0.4517808 -0.011592695 0.8920536, + -0.41140205 -0.011843801 0.91137713, + -0.40724295 4.9349994e-005 0.91331989, + -0.36630788 5.0278581e-005 0.93049365, + -0.36223203 0.012870802 0.93199915, + -0.32076308 0.013078903 0.94706923, + -0.31598186 0.029880784 0.94829452, + -0.35959819 0.029387714 0.93264443, + -0.36368009 0.016587304 0.93137622, + -0.40442306 0.016285403 0.9144271, + -0.4086411 0.004257021 0.91268522, + -0.44885293 0.0041679796 0.89359587, + -0.45307401 -0.0069303699 0.89144599, + -0.49289599 -0.00676412 0.87006199, + -0.49706006 -0.016977603 0.86755013, + -0.53639901 -0.016512901 0.84380299, + -0.54042011 -0.025814205 0.84099919, + -0.5785172 -0.02502491 0.81528628, + -0.58231288 -0.033389192 0.81227881, + -0.61920822 -0.032249913 0.78456432, + -0.62573922 -0.046162415 0.7786653, + -0.65815067 -0.044555977 0.75156665, + -0.66681403 -0.062329501 0.74261302, + -0.69808704 -0.059886307 0.71350408, + -0.70369881 -0.071050286 0.70693684, + -0.73649603 -0.067644708 0.67305106, + -0.74243033 -0.079441935 0.6651963, + -0.77318132 -0.07520403 0.62971026, + -0.78146601 -0.092006803 0.617127, + -0.81007701 -0.086458802 0.57991397, + -0.81734431 -0.10179204 0.56708616, + -0.84370089 -0.094841883 0.52836895, + -0.84967428 -0.10810604 0.5161072, + -0.87332588 -0.099870488 0.47678894, + -0.87811071 -0.11117496 0.46536183, + -0.89913768 -0.10169696 0.42568684, + -0.90288597 -0.111229 0.415241, + -0.92150891 -0.10048498 0.37513193, + -0.92436701 -0.108417 0.36577499, + -0.94457489 -0.10729399 0.31026798, + -0.92735535 -0.12229104 0.35363412, + -0.92472988 -0.11470199 0.36292997, + -0.9067449 -0.12707399 0.40207693, + -0.90329099 -0.117927 0.412503, + -0.88294929 -0.12904304 0.45138514, + -0.87854278 -0.11820897 0.46280587, + -0.85561484 -0.12809397 0.50151289, + -0.85011399 -0.115385 0.51380199, + -0.82450014 -0.12398802 0.55211109, + -0.81777209 -0.10922401 0.56508309, + -0.78988081 -0.11638197 0.60211587, + -0.78188086 -0.099527389 0.61543196, + -0.75176114 -0.10527501 0.65097809, + -0.74277395 -0.08690089 0.66387892, + -0.71031499 -0.091358103 0.69792998, + -0.70372319 -0.078032717 0.70617616, + -0.66923475 -0.081610471 0.73855579, + -0.66317123 -0.069239825 0.74525821, + -0.63081604 -0.071780406 0.77260512, + -0.62490726 -0.059172623 0.77845329, + -0.58804888 -0.061304286 0.80649883, + -0.58454007 -0.053545609 0.80959612, + -0.54637796 -0.055272993 0.83571291, + -0.5424549 -0.046160787 0.83881581, + -0.50296575 -0.047491577 0.86300057, + -0.49887693 -0.037412696 0.86586487, + -0.45884699 -0.0383556 0.88768703, + -0.45469314 -0.027378809 0.89022732, + -0.41414291 -0.027980192 0.90978175, + -0.40999693 -0.016092198 0.91194487, + -0.36889511 -0.016398806 0.92932636, + -0.36486301 -0.0036770499 0.931054, + -0.32074898 -0.0037406494 0.94715691, + -0.32549709 -0.020524906 0.94532025, + -0.36743209 -0.020188505 0.92983127, + -0.37142292 -0.032814793 0.92788374, + -0.41275501 -0.032191999 0.91027302, + -0.41687486 -0.044035085 0.9078967, + -0.45754793 -0.043076895 0.88814086, + -0.4616788 -0.054022275 0.88540059, + -0.50181013 -0.052678213 0.86337221, + -0.5058499 -0.062659487 0.8603428, + -0.54540712 -0.060883515 0.83595717, + -0.54912484 -0.069534376 0.83284271, + -0.58729011 -0.067340918 0.80657017, + -0.59342992 -0.08099629 0.80079991, + -0.6269238 -0.078399375 0.7751258, + -0.63335592 -0.091971695 0.76837587, + -0.66901082 -0.088333875 0.73798484, + -0.6762076 -0.10325294 0.72943956, + -0.71041673 -0.098637462 0.69683474, + -0.72004503 -0.11865301 0.68370807, + -0.75196183 -0.11271497 0.64949882, + -0.76062 -0.131092 0.63582402, + -0.79012269 -0.12377296 0.60032177, + -0.79756314 -0.14006701 0.58674908, + -0.82478356 -0.13129294 0.54999477, + -0.83100867 -0.14550495 0.53689182, + -0.85592312 -0.13526201 0.49909905, + -0.8610152 -0.14751004 0.4867171, + -0.88326222 -0.13599503 0.44872412, + -0.887344 -0.146448 0.43723401, + -0.90704477 -0.13372096 0.39923492, + -0.91022927 -0.14250603 0.38881209, + -0.92762876 -0.12853298 0.3506909, + -0.92998677 -0.13562897 0.34165692, + -0.94518214 -0.12048302 0.30350402, + -0.94827962 -0.13103296 0.28912991, + -0.94839811 -0.13013701 0.28914604, + -0.93230325 -0.14844103 0.32981208, + -0.93017459 -0.14177093 0.33863884, + -0.91330129 -0.15728205 0.37569016, + -0.91042721 -0.14901903 0.38589609, + -0.89130324 -0.16333504 0.42296609, + -0.88754326 -0.15329804 0.4344731, + -0.86591786 -0.16642898 0.47168595, + -0.861202 -0.154615 0.484175, + -0.836927 -0.166494 0.52137601, + -0.83116382 -0.15280198 0.53461987, + -0.80457884 -0.16319495 0.57098186, + -0.79766589 -0.14744999 0.58479697, + -0.7687729 -0.15635498 0.62011397, + -0.76065314 -0.13844901 0.63422304, + -0.72928119 -0.14592503 0.66847217, + -0.72001094 -0.12593098 0.68244094, + -0.68621379 -0.13199995 0.71532273, + -0.67605603 -0.110346 0.72854102, + -0.6406092 -0.11499103 0.7592082, + -0.63288504 -0.098426513 0.76796412, + -0.5960539 -0.10207498 0.79642981, + -0.592246 -0.093645103 0.80029702, + -0.55403012 -0.096752726 0.82685518, + -0.55069214 -0.088980623 0.82995218, + -0.51105583 -0.091628373 0.85464972, + -0.50740892 -0.082594194 0.8577379, + -0.46702418 -0.084754527 0.88017333, + -0.46313018 -0.074396133 0.88316232, + -0.42216405 -0.07609421 0.90332013, + -0.41812721 -0.064434826 0.90610039, + -0.37645805 -0.065714806 0.9241001, + -0.37248918 -0.053095225 0.92651641, + -0.33012116 -0.054005027 0.94239247, + -0.32635313 -0.040582716 0.94437635, + -0.28180802 -0.041193303 0.9585861, + -0.28597715 -0.058182627 0.95646846, + -0.32865304 -0.057345506 0.94270813, + -0.332398 -0.070720702 0.94048399, + -0.3750079 -0.069512084 0.92441177, + -0.37893113 -0.082016729 0.92178333, + -0.4207609 -0.080398977 0.90360177, + -0.42463216 -0.091600128 0.9007203, + -0.46572605 -0.089532405 0.88038814, + -0.46944818 -0.099442936 0.87734228, + -0.5099048 -0.096882865 0.85475773, + -0.51336211 -0.10544603 0.85166919, + -0.55308491 -0.10236898 0.82681185, + -0.55714285 -0.11182597 0.82285285, + -0.59534776 -0.10819697 0.79614973, + -0.60348797 -0.12641199 0.78728789, + -0.64020377 -0.12178796 0.75848973, + -0.65077585 -0.14509697 0.74527681, + -0.68593419 -0.13905703 0.71425319, + -0.69572723 -0.16070506 0.70009822, + -0.72908705 -0.15312402 0.66707206, + -0.73780692 -0.17265698 0.65255696, + -0.76866966 -0.16360992 0.61836773, + -0.77623314 -0.18095301 0.60391909, + -0.8045519 -0.17045799 0.56889397, + -0.81098115 -0.18569905 0.55482012, + -0.8369568 -0.17369996 0.51897186, + -0.8423149 -0.18696299 0.50551993, + -0.86598682 -0.17346196 0.46901789, + -0.87034428 -0.18484306 0.45643616, + -0.89139587 -0.17012098 0.42008594, + -0.89480239 -0.17960209 0.40874422, + -0.91340631 -0.16374806 0.37266013, + -0.91600776 -0.17153895 0.3626349, + -0.93241435 -0.15453306 0.32668513, + -0.93436521 -0.16089705 0.3179211, + -0.94869548 -0.14277907 0.28211915, + -0.95126837 -0.15227906 0.26814109, + -0.96239865 -0.13414395 0.23620792, + -0.96494347 -0.14483307 0.21887811, + -0.9741379 -0.12468999 0.18843497, + -0.97571826 -0.13256402 0.17435804, + -0.98320651 -0.11045295 0.14527592, + -0.98410845 -0.11590605 0.13452306, + -0.99006897 -0.091763496 0.106503, + -0.99053621 -0.09532132 0.098752119, + -0.99497998 -0.069501698 0.072003201, + -0.99518025 -0.071549714 0.067059211, + -0.99818313 -0.043962605 0.041203402, + -0.99824363 -0.044925187 0.038617086, + -0.99979746 -0.015263308 0.013120106, + -0.99980265 -0.015490995 0.012435395, + -0.99978936 0.016006906 -0.012849605, + -0.99979275 0.016134497 -0.012416997, + -0.99795121 0.050703913 -0.039021209, + -0.99800438 0.051262919 -0.036869016, + -0.99396223 0.089077219 -0.064065516, + -0.99383622 0.088454023 -0.066824615, + -0.98557538 0.13503404 -0.10201504, + -0.98475212 0.13356501 -0.11146201, + -0.96932 0.188721 -0.15749, + -0.96854788 0.18824796 -0.16271998, + -0.9505499 0.23495997 -0.20309797, + -0.95555812 0.23735704 -0.17484401, + -0.93524939 0.28501016 -0.20994711, + -0.94548953 0.28955084 -0.14902993, + -0.92596233 0.33575311 -0.17281106, + -0.93315434 0.33923313 -0.11892805, + -0.91260713 0.38581505 -0.13525902, + -0.91847563 0.38894284 -0.07159508, + -0.896842 0.43504199 -0.080080703, + -0.89898258 0.43627679 -0.038638882, + -0.89402974 0.44800687 0.00071987783, + -0.89402431 0.44800115 0.0039525814, + -0.89400727 0.44803512 0.003952601, + -0.86944985 0.49047393 -0.059094392, + -0.8709358 0.49127287 -0.011038597, + -0.89405525 0.44793913 0.0039701308, + -0.89269257 0.4473038 -0.054947574, + -0.87637687 0.48127395 -0.018409397, + -0.87281984 0.47896287 -0.09370248, + -0.89699131 0.43382415 -0.084871531, + -0.88899279 0.42919692 -0.15962996, + -0.91238922 0.3836481 -0.14268903, + -0.90207469 0.37825486 -0.20780893, + -0.92513663 0.33272788 -0.18279594, + -0.90890622 0.3250531 -0.26120907, + -0.9093613 0.32747212 -0.25656208, + -0.88506842 0.36640117 -0.28706115, + -0.90084302 0.37456399 -0.21950801, + -0.87444514 0.41854706 -0.24528404, + -0.8886413 0.42662415 -0.16825105, + -0.86239856 0.47092977 -0.18572491, + -0.8729738 0.47759789 -0.099081181, + -0.84985983 0.52455086 -0.05083989, + -0.84607899 0.52194399 -0.108281, + 0.85091555 0.5252853 -0.0042660525, + 0.95368034 0.20522907 -0.21994308, + 0.92218363 0.26385292 -0.28276992, + 0.92076814 0.26310503 -0.28803104, + 0.88976711 0.30782303 -0.33698604, + 0.90930277 0.31755692 -0.26893494, + 0.87920678 0.36357692 -0.30790794, + 0.90021777 0.37434492 -0.22242694, + 0.87367189 0.41825494 -0.24851596, + 0.88651514 0.42551506 -0.18173602, + 0.85987616 0.46947613 -0.20051205, + 0.87084347 0.47627971 -0.12161092, + 0.8436479 0.52020693 -0.13282698, + 0.68674493 0.72531694 -0.047924694, + -0.75289112 0.0026067202 0.65814006, + -0.76072532 -0.012724205 0.64894927, + -0.78797489 -0.012070098 0.61558896, + -0.79436511 -0.024607604 0.60694206, + -0.8202219 -0.023173798 0.57157594, + -0.82362717 -0.029874507 0.56634414, + -0.85028231 -0.027725009 0.5255962, + -0.85333699 -0.033953201 0.520253, + -0.90878624 -0.048111312 0.41447908, + -0.90463614 -0.038304202 0.42446005, + -0.88280314 -0.042219102 0.46784207, + -0.87771767 -0.031206088 0.47816083, + -0.87581903 -0.0187585 0.48227501, + -0.8493309 -0.020516098 0.52746195, + -0.84648579 -0.014793696 0.53220588, + -0.82220685 -0.015815599 0.56896895, + -0.8165161 -0.0045117904 0.57730508, + -0.79037011 -0.0047877105 0.61261106, + -0.78322172 0.0092378864 0.62167376, + -0.75568414 0.0097310506 0.65486407, + -0.74750406 0.025695303 0.66376007, + -0.71860701 0.026900601 0.69489598, + -0.70952106 0.044669304 0.70326704, + -0.67907017 0.046532411 0.73259717, + -0.66916478 0.066085078 0.74016976, + -0.63728875 0.068531677 0.76757169, + -0.62663698 0.089922301 0.77410603, + 0.760382 0.58147001 -0.28933001, + 0.79527581 0.54276788 -0.27007294, + 0.71016395 0.33142698 -0.62114692, + 0.67283052 0.34826177 -0.65269655, + 0.75260121 0.39763209 -0.52486211, + 0.74790317 0.38912109 -0.53779709, + 0.80558109 0.42414105 -0.41369507, + 0.76687533 0.45944017 -0.44812614, + 0.80324268 0.48395783 -0.34725487, + 0.76679027 0.52153218 -0.37421513, + 0.76305431 0.51397115 -0.39189515, + 0.72421896 0.54835296 -0.41810995, + 0.75917262 0.5769847 -0.30123985, + 0.72214895 0.61319494 -0.32014498, + 0.72512084 0.68766582 -0.036269993, + 0.71084976 0.67337275 -0.20312993, + 0.74741381 0.63604879 -0.19187096, + 0.7552101 0.65517807 -0.019986402, + 0.7593497 0.64888376 -0.048350282, + 0.74741793 0.63806891 -0.18502599, + 0.78168488 0.59899795 -0.17369598, + 0.81474161 0.57718068 -0.055302974, + 0.7924009 0.60976195 -0.017062599, + 0.78167391 0.60081792 -0.16734299, + 0.81380886 0.55982393 -0.15592399, + 0.7962808 0.54669988 -0.25895193, + 0.8288359 0.50563794 -0.23950197, + 0.80629665 0.49034077 -0.33083487, + 0.83954519 0.45036712 -0.30386406, + 0.8123877 0.43365484 -0.38983285, + 0.8423146 0.40083483 -0.36032981, + 0.96094686 0.18330298 -0.20731898, + 0.93372273 0.23713094 -0.26819894, + 0.92689711 0.23121403 -0.29563802, + 0.8923496 0.27805188 -0.35552683, + 0.87996298 0.27010399 -0.39078, + 0.83073628 0.31651512 -0.45792514, + 0.82904369 0.31559187 -0.46161482, + 0.781259 0.35228899 -0.515293, + 0.81729412 0.37245703 -0.43966606, + 0.79082215 0.39561406 -0.46700105, + 0.71590519 0.35101208 -0.60354811, + 0.76091373 0.32620487 -0.56089282, + 0.76159865 0.32659885 -0.55973274, + 0.82369632 0.28576809 -0.48975617, + 0.84310985 0.29796094 -0.44764388, + 0.88893902 0.253791 -0.381284, + 0.90049458 0.26274088 -0.34652081, + 0.9324609 0.21827497 -0.28787598, + 0.93958336 0.22592607 -0.2571781, + 0.96093225 0.18267305 -0.20794204, + 0.96193451 0.18426691 -0.20181091, + 0.97692847 0.14400408 -0.15771407, + 0.97694474 0.14403997 -0.15757996, + 0.98735762 0.10694296 -0.11699595, + 0.98741186 0.10713998 -0.11635698, + 0.99413574 0.073250286 -0.079551481, + 0.99401861 0.072546281 -0.08163397, + 0.99801886 0.041793197 -0.047028393, + 0.99796009 0.041119203 -0.048836708, + 0.99979323 0.013098403 -0.015556804, + 0.99978465 0.012770696 -0.016355194, + 0.999798 -0.0123689 0.0158408, + 0.99978745 -0.011926506 0.016822308, + 0.99815488 -0.035118096 0.049533892, + 0.99804014 -0.033468805 0.052875008, + 0.99479926 -0.05447631 0.086063124, + 0.99442565 -0.051169682 0.092191868, + 0.98949587 -0.070154995 0.12639698, + 0.98865134 -0.064764924 0.13555105, + 0.98186445 -0.081732035 0.17106207, + 0.98023576 -0.073665783 0.18360595, + 0.97148597 -0.088285998 0.220047, + 0.96870899 -0.077135503 0.235909, + 0.95772767 -0.089404173 0.27343091, + 0.95326048 -0.07444194 0.29283616, + 0.93970847 -0.084254339 0.33143514, + 0.93293822 -0.064948715 0.35413009, + 0.9165076 -0.072160862 0.39345482, + -0.55066311 0.12063703 0.82596415, + -0.50757498 0.124522 0.85256201, + -0.49969989 0.14203697 0.85447383, + -0.46462005 0.14520301 0.87352413, + -0.45362005 0.17115201 0.87460613, + -0.41820106 0.17444701 0.89144611, + -0.40705785 0.20241593 0.8906917, + -0.37154713 0.20574208 0.9053303, + -0.36081699 0.23468199 0.90262699, + -0.32519698 0.23795597 0.91521788, + -0.3150861 0.26763806 0.91054422, + -0.27945513 0.27076712 0.92118943, + -0.27011997 0.30108798 0.91453886, + -0.23513703 0.30394503 0.9232161, + -0.2267119 0.33479184 0.91461259, + -0.19256397 0.33730897 0.92148888, + -0.18524301 0.36828604 0.91107112, + -0.15186007 0.37042516 0.91636443, + -0.15176997 0.37088892 0.91619176, + -0.11933304 0.37255311 0.92030638, + -0.12343193 0.3432928 0.93108249, + -0.08904323 0.34456411 0.93453038, + -0.091708705 0.31519303 0.9445861, + -0.055664591 0.31603596 0.94711286, + -0.057108417 0.28656808 0.95635635, + -0.019451797 0.28698093 0.95773876, + -0.01988131 0.25732112 0.96612149, + 0.019206604 0.25732407 0.96613425, + 0.018771602 0.28695503 0.9577601, + 0.056487627 0.28654715 0.9563995, + 0.055042092 0.31595898 0.94717491, + 0.091262527 0.31511813 0.94465435, + 0.088603891 0.34437996 0.93463987, + 0.12323203 0.34310508 0.93117821, + 0.11914498 0.37226596 0.92044687, + 0.15186003 0.37058908 0.91629821, + 0.15188891 0.3704378 0.91635448, + 0.18522398 0.36830097 0.91106886, + 0.192579 0.33717999 0.92153299, + 0.22682308 0.33465713 0.91463429, + 0.23525392 0.30377987 0.92324066, + 0.2702781 0.30092013 0.91454732, + 0.27962098 0.27057397 0.92119586, + 0.31528896 0.26744097 0.91053188, + 0.32536212 0.2378711 0.91518128, + 0.36097196 0.23459797 0.90258688, + 0.37161803 0.20589203 0.90526712, + 0.40710309 0.20256504 0.89063722, + 0.41814509 0.17486104 0.89139122, + 0.45347494 0.17156799 0.87459987, + 0.46467081 0.14516295 0.87350368, + 0.49976718 0.14199604 0.85444129, + 0.51119381 0.11642296 0.85154372, + 0.54545981 0.11353397 0.83041167, + 0.55679685 0.08920607 0.82584471, + 0.59017825 0.086695731 0.80260432, + 0.60112393 0.063976794 0.79659086, + 0.63381398 0.061921801 0.77100301, + 0.64410621 0.041097917 0.76383132, + 0.67587698 0.039597798 0.73594999, + 0.68543184 0.020618694 0.72784483, + 0.71567762 0.01977749 0.69815063, + 0.72436816 0.0027025908 0.68940818, + 0.75299603 0.00257954 0.65802002, + 0.76067889 -0.012451898 0.64900893, + 0.78790951 -0.011812492 0.61567765, + 0.79407513 -0.023891104 0.60735005, + 0.81990433 -0.022502808 0.5720582, + 0.82699811 -0.036584903 0.56101304, + 0.85080791 -0.034194995 0.52436292, + 0.86055315 -0.054385006 0.50644904, + 0.88399923 -0.049914312 0.46481612, + 0.88903069 -0.061290178 0.45372686, + 0.90990227 -0.055530619 0.41108915, + 0.90774977 -0.038236994 0.41776592, + 0.88306689 -0.042770095 0.46729395, + 0.87460703 -0.024659 0.48420501, + 0.85233891 -0.026599696 0.52231294, + 0.84619129 -0.014124105 0.53269219, + 0.821913 -0.0150977 0.56941301, + 0.81643569 -0.0042363685 0.57742083, + 0.7903012 -0.0044952207 0.61270213, + 0.78330773 0.0092234667 0.62156576, + 0.75577885 0.0097159278 0.65475482, + 0.74772108 0.025448404 0.66352504, + 0.718835 0.026643001 0.69467002, + 0.7098372 0.044256411 0.7029742, + 0.67936999 0.046105701 0.732346, + 0.6695022 0.065606616 0.73990721, + 0.63760984 0.068039782 0.76734883, + 0.62693381 0.089497775 0.77391481, + 0.59422505 0.092395708 0.7989741, + 0.58299106 0.11553501 0.80422211, + 0.54968983 0.11878996 0.82687968, + 0.53821284 0.14320995 0.8305527, + 0.50406826 0.14675307 0.85110444, + 0.49272323 0.17192408 0.85303342, + 0.45761299 0.175671 0.87162501, + 0.44623712 0.20224105 0.87176317, + 0.41095784 0.20602393 0.88806969, + 0.39976916 0.23377208 0.88630432, + 0.36449888 0.2374929 0.9004097, + 0.35370392 0.26621693 0.89667279, + 0.31840709 0.26980305 0.90874821, + 0.30816799 0.29941401 0.90298599, + 0.27292091 0.30278289 0.91314667, + 0.26343614 0.3330822 0.90534955, + 0.22900894 0.3361029 0.91355878, + 0.22048107 0.36677513 0.90380532, + 0.18697599 0.36939698 0.91026688, + 0.18703493 0.36914587 0.9103567, + 0.15455092 0.37126184 0.91557556, + 0.159853 0.34187499 0.92605001, + 0.12517095 0.34360385 0.93073559, + 0.12892397 0.31417391 0.94057077, + 0.092551805 0.31545904 0.94441509, + 0.094977103 0.28591701 0.95353597, + 0.057217386 0.28674495 0.95629674, + 0.058527894 0.25699496 0.96463889, + 0.019436793 0.25738791 0.96611261, + 0.019828198 0.22740696 0.97359788, + -0.020457292 0.22740392 0.97358567, + -0.020073008 0.25737408 0.96610337, + -0.059161969 0.25697488 0.96460551, + -0.057856884 0.28676993 0.95625079, + -0.095556997 0.28593701 0.95347202, + -0.093130179 0.31556791 0.94432175, + -0.12936305 0.31428212 0.94047433, + -0.12559605 0.34385011 0.93058735, + -0.16001098 0.34212896 0.92592889, + -0.15469107 0.37161818 0.91540742, + -0.18693194 0.36951587 0.91022772, + -0.18696696 0.36936492 0.91028178, + -0.22041394 0.36674792 0.90383273, + -0.22889797 0.33623797 0.91353691, + -0.26337597 0.33321297 0.90531886, + -0.27283496 0.30300096 0.91309988, + -0.30797997 0.29964098 0.9029749, + -0.31822589 0.27001491 0.90874869, + -0.3535111 0.26643106 0.89668524, + -0.36435404 0.23758502 0.90044409, + -0.39959517 0.23386811 0.88635743, + -0.41088992 0.20585695 0.88813978, + -0.44620314 0.20207408 0.87181932, + -0.45770407 0.17520401 0.87167114, + -0.49285707 0.17146201 0.8530491, + -0.50398213 0.14677203 0.85115218, + -0.53815407 0.14322601 0.8305881, + -0.54947281 0.11915296 0.82697171, + -0.58274668 0.11589295 0.80434763, + -0.59395427 0.092828631 0.79912531, + -0.59458393 0.093719393 0.79855287, + -0.55307174 0.097111158 0.82745457, + -0.54880512 0.10626102 0.82916915, + -0.51113707 0.10925402 0.85252714, + -0.50663388 0.11936897 0.85385782, + -0.46814781 0.12234396 0.87513971, + -0.46033511 0.14082003 0.87650526, + -0.42490116 0.14359404 0.89377832, + -0.41419095 0.17073698 0.8940329, + -0.37841991 0.17363395 0.90920275, + -0.3678109 0.20259096 0.90756375, + -0.33187288 0.20551592 0.92066467, + -0.32184485 0.23535489 0.91707361, + -0.28576398 0.23821597 0.92821985, + -0.27652907 0.26866007 0.92268825, + -0.24101891 0.2713199 0.93182367, + -0.23269591 0.30229789 0.92437464, + -0.19787908 0.30468413 0.93167138, + -0.19059588 0.33605579 0.92235547, + -0.15648392 0.33811286 0.92800456, + -0.15039608 0.36953917 0.9169634, + -0.11708495 0.37121981 0.92113358, + -0.11697499 0.37195498 0.92085087, + -0.084563427 0.37318411 0.92389536, + -0.087459996 0.34415099 0.93483198, + -0.053162709 0.34498602 0.93710113, + -0.054746326 0.31579015 0.94724846, + -0.018648803 0.31620908 0.94850624, + -0.0191247 0.286892 0.95777202, + 0.018553207 0.2868951 0.95778233, + 0.018071402 0.31617704 0.94852811, + 0.054307792 0.31576198 0.94728291, + 0.052724589 0.34486392 0.93717074, + 0.087252967 0.34402788 0.93489665, + 0.084362909 0.37298003 0.92399609, + 0.11707298 0.37174097 0.9209249, + 0.117146 0.371259 0.92110997, + 0.15046692 0.36957681 0.91693658, + 0.15657896 0.33802691 0.92801976, + 0.19067796 0.33596992 0.92236978, + 0.19797596 0.30453396 0.93169987, + 0.23283209 0.30214512 0.92439038, + 0.24115796 0.27115098 0.9318369, + 0.27672502 0.26848602 0.92268014, + 0.28592986 0.23813888 0.92818856, + 0.32201704 0.23527703 0.91703314, + 0.33197385 0.20565389 0.92059755, + 0.36786789 0.20272993 0.90750968, + 0.37840107 0.17399201 0.90914214, + 0.41407284 0.17109694 0.89401871, + 0.42493808 0.14356703 0.89376521, + 0.46039599 0.14079 0.87647802, + 0.47162282 0.11408097 0.87438971, + 0.50689721 0.11151905 0.85476243, + 0.51820791 0.085991375 0.8509208, + 0.5525862 0.083799727 0.82923228, + 0.56366891 0.059834287 0.82383084, + 0.59709686 0.058107983 0.80006182, + 0.60770077 0.035954189 0.79335171, + 0.64031708 0.034774605 0.76732314, + 0.65030372 0.014463494 0.75953662, + 0.68196404 0.013924802 0.73125309, + 0.69120383 -0.0045024692 0.72264582, + 0.72125506 -0.0043156105 0.69265604, + 0.72956675 -0.020683793 0.68359679, + 0.75794232 -0.019728508 0.65202326, + 0.76474947 -0.03303542 0.64348036, + 0.79172599 -0.0313203 0.61007297, + 0.79975766 -0.047084976 0.59847373, + 0.82513952 -0.044308774 0.56318867, + 0.8361659 -0.066673793 0.54440892, + 0.86141729 -0.061741021 0.5041312, + 0.86724901 -0.074493997 0.49226999, + 0.88979572 -0.068282276 0.45122185, + 0.89426523 -0.07881292 0.44054312, + 0.91675913 -0.070342809 0.39319807, + 0.918235 -0.086460002 0.38648301, + 0.89895159 -0.095631652 0.4274818, + 0.89489567 -0.085682668 0.43797284, + 0.87316197 -0.093584202 0.47836199, + 0.86793882 -0.081685379 0.48990789, + 0.84353614 -0.088329904 0.52975905, + 0.83691829 -0.074169733 0.54227918, + 0.80980301 -0.079505399 0.58129001, + 0.44745293 0.024276895 0.89397788, + 0.48705983 0.023708491 0.8730467, + 0.49130988 0.013334298 0.87088281, + 0.53049111 0.012977703 0.84759116, + 0.53457218 0.0035786012 0.8451153, + 0.57749087 0.003456959 0.8163898, + 0.57657814 0.0021639005 0.81703919, + 0.61001396 0.0020986097 0.7923879, + 0.62006706 -0.019111602 0.78431612, + 0.65256172 -0.018458391 0.75751066, + 0.66189104 -0.037568703 0.74865806, + 0.69323802 -0.036120702 0.71980298, + 0.70118296 -0.052009791 0.71108192, + 0.73084408 -0.049789608 0.68072605, + 0.73576093 -0.059393093 0.67463195, + 0.76691329 -0.05628062 0.63927823, + 0.7726298 -0.067540586 0.63125384, + 0.8019529 -0.063554294 0.59399694, + 0.80012399 -0.045768801 0.598086, + 0.76644289 -0.049009994 0.64043993, + 0.76203901 -0.0404751 0.64626497, + 0.73389 -0.042458899 0.67794001, + 0.72648436 -0.027879514 0.68661731, + 0.69663501 -0.029106401 0.71683502, + 0.68776619 -0.011371302 0.72584319, + 0.65628475 -0.011818895 0.7544207, + 0.6465708 0.0080210278 0.76281184, + 0.61400193 0.0082991393 0.78926086, + 0.60370308 0.029934105 0.79664713, + 0.5702647 0.030844685 0.82088161, + -0.42374384 0.10455296 0.8997277, + -0.47043517 0.10185704 0.87653631, + -0.47491288 0.091120176 0.87530273, + -0.51364005 0.088839509 0.85339409, + -0.51802915 0.078899927 0.85171628, + -0.55583411 0.076679617 0.82774919, + -0.55998188 0.067716584 0.82573283, + -0.6013869 0.065301582 0.79628479, + -0.64392215 0.04171171 0.76395315, + -0.60405588 0.043448187 0.79575682, + -0.6002571 0.051378909 0.79815519, + -0.56334811 0.053075612 0.8245132, + -0.55923778 0.061986569 0.82668656, + -0.52139103 0.063804507 0.85092914, + -0.51707906 0.073604509 0.85276711, + -0.47822583 0.075522073 0.87498373, + -0.47377688 0.08623258 0.87641275, + -0.43476909 0.088181019 0.89621425, + -0.42710185 0.10782396 0.89775169, + -0.39095306 0.10975701 0.9138431, + -0.38068095 0.13830599 0.91430485, + -0.34419709 0.14042903 0.92833626, + -0.33454984 0.16976592 0.92696059, + -0.297622 0.171983 0.93906498, + -0.28851604 0.20277403 0.9357571, + -0.25199103 0.20494503 0.94577914, + -0.24378698 0.23635997 0.94058585, + -0.2077529 0.23839588 0.94868654, + -0.20059896 0.27019095 0.94167775, + -0.16511901 0.27201101 0.94802201, + -0.15910895 0.30410993 0.93925577, + -0.12416406 0.30565014 0.94401348, + -0.11939704 0.33791012 0.93357438, + -0.085535578 0.3390969 0.93685478, + -0.082087405 0.37129802 0.92487812, + -0.049396317 0.37210011 0.92687738, + -0.04932173 0.37326822 0.92641151, + -0.016825097 0.37367091 0.92740875, + -0.017391797 0.3450239 0.93843275, + 0.017166192 0.34502482 0.93843651, + 0.016598597 0.37360391 0.92743975, + 0.049390391 0.3731989 0.92643577, + 0.049459994 0.37210998 0.92686987, + 0.082119323 0.37130809 0.92487127, + 0.085573137 0.33905816 0.93686539, + 0.11950398 0.33786798 0.93357587, + 0.12428206 0.30554014 0.9440335, + 0.15919393 0.30400088 0.93927664, + 0.16520801 0.27188003 0.94804412, + 0.200782 0.27005401 0.94167799, + 0.20791893 0.23834191 0.94866365, + 0.24395105 0.23630506 0.94055724, + 0.25211412 0.2050551 0.94572246, + 0.2886059 0.20288293 0.93570566, + 0.29765987 0.17227393 0.93899965, + 0.33449098 0.17005998 0.92692786, + 0.34424296 0.14040498 0.92832285, + 0.38075086 0.13827996 0.9142797, + 0.39110816 0.10948504 0.9138093, + 0.42728895 0.10755499 0.89769489, + 0.43805811 0.079794519 0.89539826, + 0.47406194 0.078156389 0.87701589, + 0.48179212 0.059574313 0.87425816, + 0.52073079 0.058040377 0.85174572, + 0.52500474 0.048284478 0.84972858, + 0.56293917 0.046888817 0.8251673, + 0.56476468 0.061293371 0.8229726, + 0.52168113 0.063364714 0.85078418, + 0.51391101 0.080934398 0.85401702, + 0.47839218 0.082849927 0.87422931, + 0.46728095 0.10950699 0.87730086, + 0.43156508 0.11173403 0.89513522, + 0.42069307 0.13952802 0.89640909, + 0.3848801 0.14195202 0.91198522, + 0.37448487 0.17059994 0.91140372, + 0.33827502 0.17314202 0.92498213, + 0.32841489 0.20282492 0.92249966, + 0.29192698 0.20538197 0.93412888, + 0.28280991 0.23584192 0.92972964, + 0.24675891 0.23827592 0.93932664, + 0.23853494 0.26934594 0.93303478, + 0.20308304 0.27157307 0.94074726, + 0.195867 0.30316699 0.93259102, + 0.16098799 0.30512297 0.93860686, + 0.15492006 0.33700612 0.92866933, + 0.12078101 0.33862802 0.93313611, + 0.11597607 0.37057221 0.92153454, + 0.082984604 0.37180302 0.92459512, + 0.082899109 0.37260202 0.92428112, + 0.050222188 0.37341791 0.92630279, + 0.051939983 0.34465688 0.93729067, + 0.017334098 0.34506997 0.9384169, + 0.017859003 0.31612003 0.94855112, + -0.018307991 0.31611684 0.94854355, + -0.017786905 0.34513012 0.93838638, + -0.05213882 0.34471512 0.93725836, + -0.050419599 0.373557 0.92623597, + -0.082863525 0.37274608 0.92422622, + -0.082964711 0.37180004 0.9245981, + -0.115977 0.37056801 0.92153603, + -0.12076598 0.33872497 0.93310291, + -0.15484805 0.33710811 0.92864436, + -0.16091307 0.30523813 0.93858236, + -0.19572495 0.30328694 0.93258178, + -0.202931 0.27172899 0.94073498, + -0.238379 0.26950401 0.933029, + -0.24662402 0.23835103 0.93934309, + -0.28264499 0.23592 0.92975998, + -0.29182005 0.20526004 0.93418926, + -0.32833588 0.20270292 0.92255467, + -0.33826891 0.17279695 0.92504877, + -0.3745231 0.17025705 0.91145223, + -0.38479006 0.14195901 0.91202211, + -0.4206312 0.13953306 0.89643741, + -0.42828107 0.12009201 0.89563012, + -0.46701181 0.11751395 0.87640768, + -0.47155806 0.10665801 0.87536114, + -0.51018798 0.104024 0.85374898, + -0.51458907 0.094097413 0.85225815, + -0.55233395 0.091483891 0.82858789, + -0.55657405 0.082355611 0.82670611, + -0.59344512 0.07978572 0.80091017, + -0.60079879 0.064441174 0.79679871, + -0.63346571 0.062375169 0.77125263, + -0.64379495 0.041498996 0.76407188, + -0.67555004 0.039986804 0.73622906, + -0.68517292 0.020889599 0.72808093, + -0.71544182 0.020037495 0.69838482, + -0.72425497 0.0027310299 0.68952692, + -0.72112584 -0.004291439 0.69279081, + -0.72958362 -0.020949591 0.68357068, + -0.7579813 -0.019981207 0.65197027, + -0.76503789 -0.033792995 0.64309794, + -0.792027 -0.032035202 0.60964501, + -0.79601401 -0.039789699 0.60396898, + -0.82446414 -0.037202004 0.56469005, + -0.82821798 -0.044694901 0.55862099, + -0.85436618 -0.041446213 0.5180161, + -0.86026329 -0.053804919 0.50700319, + -0.88374275 -0.049385689 0.46535987, + -0.88867325 -0.060501516 0.45453212, + -0.90958923 -0.054823715 0.41187608, + -0.91330731 -0.063975424 0.40221515, + -0.93358737 -0.05629072 0.35390112, + -0.51968622 0.47256222 -0.71176636, + -0.62948626 0.58019519 -0.51683718, + -0.60448164 0.39093375 -0.69409859, + -0.70349121 0.46315917 -0.53905821, + -0.68728274 0.72350675 -0.064656675, + -0.6761542 0.71116519 -0.19250904, + -0.71478766 0.67504668 -0.18273091, + -0.68625307 0.64651108 -0.33328703, + -0.72523296 0.61197096 -0.31548196, + -0.68142217 0.57248312 -0.45599011, + -0.72208136 0.54113024 -0.4310182, + -0.65921992 0.49003893 -0.57034296, + -0.53176087 0.3808229 -0.75644183, + -0.64787024 0.47388417 -0.59640425, + -0.60255486 0.49648288 -0.62484586, + -0.67682624 0.56280315 -0.47450918, + -0.63440579 0.59098089 -0.49826789, + -0.68486172 0.64101672 -0.34649983, + -0.64390028 0.67307031 -0.36382517, + -0.67626923 0.70873123 -0.20089808, + -0.63608181 0.74237281 -0.21043396, + -0.64881098 0.757936 -0.0676568, + -0.57747191 0.81640989 0.00098652288, + -0.60013688 0.79975283 -0.015201896, + -0.61690301 0.78703803 -0.00135914, + -0.61682898 0.78709602 -0.00137409, + -0.61371505 0.7832011 -0.099749416, + -0.61378896 0.78314388 -0.099743389, + -0.65342993 0.75464988 -0.059438091, + -0.6546098 0.7559638 0.0021463595, + -0.65470308 0.7558831 0.0021463102, + -0.65202701 0.75286603 -0.089741498, + -0.65200871 0.75288165 -0.089743055, + -0.65468484 0.75589883 0.0021575796, + -0.67919731 0.73380435 -0.014905808, + -0.75681782 0.65031481 -0.065706886, + -0.78777838 0.6125443 -0.064766832, + -0.78787684 0.61241889 -0.064754687, + -0.75906867 0.64882773 -0.053266473, + -0.7509529 0.64139396 -0.15710999, + -0.75414473 0.32229087 -0.57218385, + -0.76052731 0.32594913 -0.56156516, + -0.8228761 0.28524503 -0.49143705, + -0.84312588 0.29795596 -0.44761693, + -0.93858898 0.208013 -0.27528399, + -0.90021676 0.26251593 -0.3474119, + -0.88894522 0.25379205 -0.3812691, + -0.88971776 0.25867793 -0.37614891, + -0.82996809 0.31607804 -0.45961705, + -0.82455099 0.31313601 -0.47123399, + -0.7758081 0.34921104 -0.52552205, + -0.81064302 0.368617 -0.45495, + -0.76962173 0.40195686 -0.49609783, + -0.80325681 0.42250791 -0.41983992, + -0.76426619 0.45745611 -0.4545671, + -0.80471027 0.48472017 -0.34276512, + -0.76844311 0.52248305 -0.36946803, + -0.79889584 0.54524589 -0.25391394, + -0.76433772 0.58454078 -0.27221292, + -0.78501713 0.60168606 -0.14738402, + -0.78487998 0.60357702 -0.14020801, + -0.79116482 0.60880786 -0.058405586, + -0.78887272 0.61320078 -0.040798184, + -0.78954268 0.61368477 0.0036370286, + -0.78945714 0.61379504 0.0036371204, + -0.78955489 0.61366892 0.0036608896, + -0.75846809 0.65168607 -0.0056040906, + -0.75104117 0.66010219 -0.014226303, + -0.7581352 0.65181118 -0.019320704, + -0.75661886 0.65054393 -0.065729789, + -0.72401202 0.686634 -0.065881997, + -0.72561175 0.68809777 0.0030240589, + -0.72552216 0.68819219 0.0030241406, + -0.69133085 0.72253084 -0.0032850392, + -0.69097394 0.72287196 -0.0033611394, + -0.68879503 0.72065204 -0.078879304, + -0.68915278 0.72031379 -0.078844368, + -0.72392607 0.68673307 -0.06579221, + -0.72398508 0.68668103 -0.065686308, + -0.71467024 0.67732024 -0.17459606, + -0.75107831 0.63931423 -0.16479906, + -0.72649342 0.61694938 -0.30262318, + -0.76324785 0.5800789 -0.28453693, + -0.72620898 0.54967701 -0.41288701, + -0.76488113 0.51505405 -0.38688007, + -0.71355116 0.47706011 -0.51308709, + -0.75581765 0.44585878 -0.47953075, + -0.70880795 0.41443995 -0.57081592, + -0.75412232 0.38584614 -0.53143418, + -0.69755936 0.35164818 -0.62430328, + -0.6898098 0.3424049 -0.63790381, + -0.64192379 0.36263689 -0.67559475, + -0.68938524 0.39410916 -0.60780424, + -0.65821415 0.40958008 -0.6316632, + -0.55978787 0.33968291 -0.75581282, + -0.60179621 0.3273901 -0.72846222, + -0.57276005 0.30830303 -0.75953615, + -0.6279943 0.29269314 -0.72107834, + -0.67370725 0.32048011 -0.66589123, + -0.74857402 0.287545 -0.59745699, + -0.77791315 0.30615506 -0.54874414, + -0.83625698 0.26716101 -0.478852, + -0.8540681 0.28006804 -0.43832606, + -0.89686477 0.23814894 -0.37271792, + -0.90935874 0.24967894 -0.33275691, + -0.93852675 0.20718296 -0.27612093, + -0.94155526 0.21104905 -0.26254907, + -0.96214509 0.17075102 -0.21241704, + -0.96175301 0.17005999 -0.214734, + -0.97678179 0.13300797 -0.16794695, + -0.9772079 0.13407798 -0.16458398, + -0.98748934 0.099593334 -0.12225404, + -0.987405 0.099268198 -0.123196, + -0.99412662 0.067902781 -0.084270068, + -0.99397987 0.06698779 -0.086698391, + -0.99800402 0.038611401 -0.049972501, + -0.99792546 0.037697919 -0.052188225, + -0.99978954 0.012012694 -0.016630093, + -0.99977863 0.011593997 -0.017559394, + -0.99979222 -0.011232203 0.017011404, + -0.99977922 -0.010704303 0.018084504, + -0.99808311 -0.031523302 0.053257108, + -0.99794221 -0.029576808 0.056890715, + -0.99453962 -0.048138481 0.092593871, + -0.99408698 -0.0443337 0.099123903, + -0.98886186 -0.060766593 0.13586599, + -0.98782325 -0.05452821 0.14571203, + -0.98055553 -0.068779074 0.18379392, + -0.97857052 -0.05960397 0.19709691, + -0.96912289 -0.071375594 0.23602197, + -0.9656741 -0.058538206 0.25307503, + -0.95372713 -0.067759007 0.29293904, + -0.94826478 -0.050886691 0.31337592, + -0.93345386 -0.057493191 0.35405996, + -0.92801875 -0.04295389 0.37004891, + -0.92603725 -0.027650708 0.37641808, + -0.90366811 -0.031372402 0.42708305, + -0.89691126 -0.016222803 0.44191313, + -0.87598926 -0.017694604 0.48200613, + -0.87090373 -0.0070016976 0.49140382, + -0.8481397 -0.0075476272 0.52971882, + -0.84316611 0.0025589503 0.53764707, + -0.81856471 0.0027339191 0.57440782, + -0.81215483 0.015472597 0.58323687, + -0.78567016 0.016406303 0.61842811, + -0.77819085 0.031045396 0.62725997, + -0.75034183 0.032677893 0.66024184, + -0.74188185 0.049123488 0.66872883, + -0.71273422 0.051387619 0.69954926, + -0.70335215 0.069640316 0.7074222, + -0.672732 0.0724857 0.73632699, + -0.66249603 0.092565209 0.74332404, + -0.6304962 0.095917523 0.77024317, + -0.61954808 0.11773501 0.77607912, + -0.58683306 0.12144802 0.80054814, + -0.57563818 0.14430104 0.80487132, + -0.54234594 0.14826198 0.82696986, + -0.53124809 0.17168105 0.8296392, + -0.49695525 0.1758481 0.84977239, + -0.48526487 0.20154895 0.85082084, + -0.45011994 0.20583597 0.86892086, + -0.43841881 0.2328479 0.86808461, + -0.4032729 0.23707294 0.88383675, + -0.39185295 0.26501396 0.88103288, + -0.35683504 0.26908702 0.89457309, + -0.34583411 0.29791611 0.88974428, + -0.31086901 0.30177701 0.901272, + -0.30047402 0.33133602 0.89438909, + -0.265811 0.33489099 0.90398699, + -0.25625807 0.3648591 0.89510322, + -0.22236504 0.36801302 0.90284014, + -0.22241703 0.36782703 0.90290314, + -0.19042103 0.37037402 0.90915513, + -0.19695804 0.34065402 0.91932714, + -0.16276301 0.34282604 0.9251911, + -0.16764405 0.3130511 0.93482333, + -0.13132498 0.3147949 0.94003075, + -0.13475105 0.28500408 0.94900733, + -0.096826285 0.28627697 0.95324188, + -0.099019952 0.25635788 0.96149653, + -0.059850093 0.25716296 0.96451288, + -0.061015677 0.22706793 0.97196567, + -0.020600306 0.22744405 0.97357327, + -0.020940505 0.19731104 0.98011726, + 0.020388808 0.19731407 0.98012835, + 0.020040294 0.22746594 0.97357976, + 0.060351521 0.22709708 0.97200036, + 0.059178777 0.25717291 0.96455163, + 0.098372944 0.25637513 0.96155846, + 0.096177198 0.286239 0.95331901, + 0.13415197 0.28497195 0.94910175, + 0.13073395 0.31464687 0.94016266, + 0.16721299 0.31290299 0.93494999, + 0.16235505 0.34250909 0.92538023, + 0.19678308 0.34032813 0.91948533, + 0.19026895 0.36994192 0.90936273, + 0.22259192 0.36737087 0.90304571, + 0.22240993 0.3680259 0.90282375, + 0.25623992 0.36487788 0.89510071, + 0.26584592 0.33474287 0.90403169, + 0.30061507 0.3311781 0.89440024, + 0.311037 0.30153501 0.90129501, + 0.34600678 0.29767582 0.88975745, + 0.3570019 0.26885295 0.89457679, + 0.39204895 0.26477697 0.88101691, + 0.40341792 0.23695295 0.88380277, + 0.43859199 0.23272499 0.86803001, + 0.45016414 0.20601207 0.86885631, + 0.48525387 0.20172696 0.85078484, + 0.49682093 0.17630598 0.84975588, + 0.53105927 0.17213809 0.82966542, + 0.54239088 0.14823197 0.82694584, + 0.57570308 0.14426701 0.80483115, + 0.58706105 0.12107102 0.80043811, + 0.61977476 0.11736695 0.77595371, + 0.63076276 0.095450766 0.77008271, + 0.66280693 0.092106692 0.74310392, + 0.67305392 0.07198479 0.73608196, + 0.70369291 0.069153495 0.70713097, + 0.71303564 0.050955974 0.69927365, + 0.74219018 0.048707511 0.66841716, + 0.75055188 0.032436796 0.66001493, + 0.778391 0.0308154 0.62702298, + 0.78574717 0.016408104 0.61833012, + 0.81222713 0.015474302 0.58313608, + 0.81848073 0.0030482388 0.57452583, + 0.84306115 0.0028534406 0.53781015, + 0.84785599 -0.0068752901 0.530182, + 0.87063003 -0.0063788202 0.49189699, + 0.87583029 -0.017293606 0.48230919, + 0.89675814 -0.015856702 0.44223705, + 0.90748143 -0.040358718 0.4181492, + 0.92543942 -0.036400918 0.37714317, + 0.93371475 -0.058178984 0.35325891, + 0.9484809 -0.051486693 0.31262296, + 0.95386821 -0.068195112 0.29237807, + 0.96579051 -0.058904272 0.25254488, + 0.96916527 -0.071501017 0.23581006, + 0.97859967 -0.059708979 0.19691992, + 0.98055488 -0.068753392 0.18380699, + 0.98782223 -0.054508612 0.14572603, + 0.98885286 -0.060693491 0.13596399, + 0.99408197 -0.0442813 0.099197902, + 0.99453312 -0.048067007 0.092700809, + 0.99793947 -0.029535314 0.056960925, + 0.99808055 -0.031478986 0.053332575, + 0.99977887 -0.010690399 0.018111998, + 0.99979186 -0.011217899 0.017039698, + 0.99977821 0.011580002 -0.017589804, + 0.99978924 0.011998303 -0.016661903, + 0.99792165 0.037655987 -0.052292481, + 0.99799854 0.03854768 -0.050129879, + 0.99396235 0.066883922 -0.08698003, + 0.99410611 0.06777551 -0.084614106, + 0.9873575 0.099095345 -0.12371506, + 0.98751777 0.099712275 -0.12192697, + 0.97726274 0.13422997 -0.16413395, + 0.97688389 0.13327199 -0.16714199, + 0.96192878 0.17038596 -0.21368596, + 0.96144485 0.16954099 -0.21651697, + 0.94043714 0.20959704 -0.26767004, + 0.93850011 0.20714903 -0.27623704, + 0.90932322 0.24963206 -0.33288908, + 0.89719588 0.23842697 -0.37174198, + 0.8545292 0.28041306 -0.43720508, + 0.83622581 0.26713893 -0.47891888, + 0.77785528 0.30613911 -0.54883516, + 0.74970096 0.28826997 -0.59569192, + 0.68609983 0.31690192 -0.65485883, + 0.67997724 0.33568913 -0.65187722, + 0.66599 0.32685599 -0.67053902, + 0.62640929 0.34154916 -0.70068234, + 0.73312426 0.41068715 -0.54209316, + 0.68394017 0.39827409 -0.61123115, + 0.75829285 0.44773394 -0.47384194, + 0.71621704 0.47930205 -0.50725007, + 0.61417389 0.39822292 -0.68132883, + 0.70601296 0.46530795 -0.53388596, + 0.66184896 0.49253395 -0.56512493, + 0.71995598 0.53976297 -0.43625599, + 0.67917204 0.57084006 -0.46137506, + 0.72080576 0.60831279 -0.33225688, + 0.68163574 0.64214873 -0.35073888, + 0.71083558 0.67121559 -0.21019588, + 0.67214799 0.706581 -0.22126999, + 0.68780226 0.72381526 -0.05495102, + 0.78404909 0.62057304 -0.012496202, + 0.71608198 0.69788402 -0.013583, + 0.55817193 0.82958889 -0.015042698, + 0.46991017 0.88258332 -0.015201606, + 0.64052868 0.76779562 -0.014594894, + 0.65108794 0.75898987 -0.0043369895, + 0.64991003 0.7576611 -0.059722606, + 0.68643326 0.72492021 -0.057445422, + 0.68758905 0.72609204 0.0034215504, + 0.68755203 0.72612709 0.0034215804, + 0.72218198 0.691477 -0.017685501, + 0.72101396 0.69039196 -0.059143193, + 0.72102523 0.69038022 -0.059142321, + 0.72229362 0.69155365 -0.0067422269, + 0.75534081 0.65532082 0.0038674991, + 0.75404531 0.65424526 -0.058128621, + 0.75411099 0.65416998 -0.058123, + 0.75540715 0.65524417 0.003882691, + 0.755364 0.655294 0.0038827299, + 0.78653109 0.61738306 -0.014393002, + 0.78534168 0.61648375 -0.056446582, + 0.78531218 0.61652112 -0.056449115, + 0.78654981 0.61745489 -0.0094350977, + 0.816006 0.57802898 0.0040889601, + 0.81593418 0.57813513 0.0033558507, + 0.8159318 0.57813388 0.0040612691, + 0.81589782 0.57818186 0.0040613092, + 0.81463313 0.57733303 -0.055312607, + 0.82216412 0.56782109 -0.040315602, + 0.81377912 0.56153208 -0.14981802, + 0.84369588 0.51867795 -0.13838498, + 0.82964784 0.50910789 -0.22911493, + 0.85926211 0.46647507 -0.20992804, + 0.84197116 0.45577711 -0.28870705, + 0.87184888 0.41375095 -0.26208696, + 0.84098113 0.39651906 -0.36813504, + 0.87633687 0.35301298 -0.32774296, + 0.84239233 0.33512512 -0.42197916, + 0.88172674 0.29339194 -0.3694309, + 0.88347876 0.29431695 -0.36447591, + 0.92082256 0.24500687 -0.30340984, + 0.92821109 0.25006104 -0.27548802, + 0.95359886 0.20235898 -0.22293498, + 0.95734078 0.20619196 -0.20244396, + 0.97645098 0.153944 -0.151145, + 0.97690648 0.15491408 -0.14715807, + 0.98735636 0.11492804 -0.10917404, + 0.98724985 0.11456899 -0.11050598, + 0.99406654 0.078290164 -0.075513765, + 0.99403602 0.078116298 -0.076093398, + 0.99802601 0.044986099 -0.043821201, + 0.99797666 0.044431984 -0.045479584, + 0.99979502 0.0141492 -0.0144828, + 0.99978834 0.013890404 -0.015180806, + 0.99980152 -0.013449494 0.014698992, + 0.99979311 -0.013093702 0.015566102, + 0.99820501 -0.038551699 0.045831099, + 0.99811113 -0.037150804 0.048928507, + 0.99498779 -0.060470086 0.07964088, + 0.99468315 -0.057636708 0.08534281, + 0.98997837 -0.079036728 0.11703005, + 0.98927861 -0.074296869 0.12572895, + 0.98285574 -0.093799978 0.15873295, + 0.98151988 -0.086730592 0.17057699, + 0.97331166 -0.10401096 0.20456293, + 0.97099334 -0.094012737 0.21984908, + 0.96075875 -0.10906298 0.25504494, + 0.95706922 -0.095742121 0.27359107, + 0.94451755 -0.10849195 0.31002584, + 0.93887186 -0.091084391 0.33199897, + 0.92369503 -0.101366 0.36947599, + 0.92394423 -0.099660121 0.36931708, + 0.90316123 -0.11184603 0.4144761, + 0.8994621 -0.10240401 0.42483106, + 0.87847924 -0.11196103 0.46447712, + 0.87371027 -0.10065003 0.47592017, + 0.85009319 -0.10896502 0.51523614, + 0.8441087 -0.095631361 0.52757484, + 0.81778812 -0.10265002 0.56629103, + 0.81039882 -0.087021075 0.57937986, + 0.78181118 -0.092611425 0.61659914, + 0.77318788 -0.075105496 0.62971395, + 0.74244285 -0.079337277 0.66519481, + 0.73601234 -0.066568628 0.67368728, + 0.70322984 -0.069911286 0.70751685, + 0.69781822 -0.059165023 0.71382725, + 0.66660124 -0.061572023 0.74286723, + 0.65820122 -0.044357516 0.75153428, + 0.62579805 -0.045956604 0.77863014, + 0.40069494 0.0039847894 0.9162029, + 0.44917393 0.0038857795 0.8934359, + 0.45337901 -0.0071744001 0.891289, + 0.49319676 -0.0070021367 0.86988956, + 0.49734676 -0.017185992 0.86738157, + 0.5366801 -0.016715204 0.84362018, + 0.54067385 -0.025955794 0.84083182, + 0.57876211 -0.025161706 0.81510818, + 0.5825001 -0.033399407 0.81214416, + 0.61936677 -0.032259889 0.78443873, + 0.62046307 -0.018472102 0.7840181, + 0.57951468 -0.019195791 0.81473559, + 0.57571417 -0.010837804 0.81757927, + 0.53764397 -0.011175999 0.84309787, + 0.53361708 -0.0018806902 0.84572411, + 0.49433783 -0.0019330293 0.8692677, + 0.49016589 0.008279738 0.87158984, + 0.45045415 0.0084808525 0.89275932, + 0.44617411 0.019706605 0.89472926, + 0.40612501 0.0201221 0.91359597, + 0.39897406 0.040349305 0.9160741, + 0.36122099 0.041032199 0.93157703, + 0.3517051 0.070686318 0.93343824, + 0.31349885 0.071703963 0.94687754, + 0.30465403 0.10242301 0.94694012, + 0.26667494 0.10364098 0.95819777, + 0.25868604 0.13517901 0.95645612, + 0.22111003 0.13647902 0.96565211, + 0.21410011 0.16874208 0.96212649, + 0.17668906 0.17003006 0.96946937, + 0.17077599 0.202888 0.96419501, + 0.13373204 0.20406404 0.96978027, + 0.12903903 0.23724206 0.96284223, + 0.092714176 0.23821194 0.96677774, + 0.089314058 0.27151689 0.9582805, + 0.053956691 0.27220997 0.96072388, + 0.051890619 0.30557713 0.95075238, + 0.0174639 0.305942 0.95188999, + 0.016766192 0.33924785 0.94054753, + -0.016696507 0.33924916 0.94054848, + -0.017392999 0.30596197 0.95188487, + -0.051759887 0.30559793 0.95075274, + -0.053822074 0.27225187 0.96071953, + -0.089190096 0.27155998 0.95827991, + -0.092588954 0.23823288 0.96678454, + -0.12882903 0.23726706 0.96286422, + -0.13353199 0.20400196 0.96982086, + -0.17065302 0.20282502 0.96423012, + -0.17659001 0.16982602 0.96952313, + -0.21404296 0.16853896 0.96217477, + -0.22100502 0.13649301 0.9656741, + -0.25861511 0.13519207 0.95647347, + -0.26656196 0.10382998 0.95820874, + -0.30450696 0.10261199 0.94696689, + -0.31332985 0.071979366 0.94691253, + -0.34815091 0.071054287 0.93474174, + -0.65013069 0.014884492 0.75967664, + -0.61046404 0.015515602 0.79189211, + -0.60678214 0.023244405 0.79452819, + -0.56988317 0.02402981 0.8213743, + -0.56590211 0.032713208 0.82382315, + -0.52794302 0.033697501 0.848611, + -0.52373409 0.043327812 0.85077918, + -0.48471111 0.044487011 0.87354219, + -0.48036084 0.055032481 0.87534273, + -0.44107494 0.056312494 0.89570189, + -0.43666878 0.067750171 0.89706761, + -0.39709714 0.069117419 0.91517031, + -0.39274201 0.081368104 0.91604197, + -0.35282996 0.082787089 0.93201786, + -0.34588003 0.10416202 0.93247914, + -0.30824196 0.10560799 0.94542789, + -0.29937887 0.13613395 0.94437265, + -0.26197997 0.13769399 0.9551999, + -0.25400192 0.16891494 0.95233965, + -0.21684605 0.17048804 0.96120322, + -0.20975304 0.20281103 0.95648915, + -0.17290808 0.2043011 0.96351647, + -0.16695204 0.23701505 0.95705324, + -0.13054402 0.23833203 0.9623701, + -0.12583497 0.27120095 0.95426178, + -0.090362675 0.27225494 0.95797276, + -0.086946145 0.30526015 0.94829148, + -0.052462213 0.30599907 0.95058525, + -0.050388418 0.33898813 0.93944037, + -0.016916597 0.33936998 0.94050086, + -0.016220098 0.37210998 0.92804688, + 0.016254505 0.37211013 0.92804635, + 0.016951801 0.33935103 0.94050711, + 0.05044828 0.33896688 0.93944466, + 0.052526508 0.30593902 0.9506011, + 0.087043494 0.30519998 0.94830185, + 0.090461694 0.27219698 0.95797986, + 0.12601103 0.27113906 0.95425624, + 0.13071901 0.23828501 0.962358, + 0.16712499 0.23696697 0.95703489, + 0.17305902 0.20438203 0.96347213, + 0.20986603 0.20289204 0.95644712, + 0.21693005 0.17070805 0.96114522, + 0.2539809 0.16913794 0.95230561, + 0.26202404 0.13766304 0.95519227, + 0.29944906 0.13610102 0.94435525, + 0.30836207 0.10539802 0.94541222, + 0.3460688 0.10395194 0.93243247, + 0.35569689 0.07417047 0.93165362, + 0.39303017 0.072974034 0.91662544, + 0.40316081 0.044355679 0.91405356, + 0.44005194 0.043523997 0.89691687, + 0.43683305 0.040218603 0.89864314, + 0.483895 0.039126899 0.87425101, + 0.48818889 0.028674792 0.87226683, + 0.5273028 0.02791699 0.84921873, + 0.53144497 0.018405598 0.84689289, + 0.56944996 0.017860997 0.82183188, + 0.57124901 0.032198001 0.82014501, + 0.52825582 0.033308487 0.84843171, + 0.52405417 0.042931017 0.85060227, + 0.485028 0.044080898 0.87338698, + 0.48066407 0.054667506 0.87519914, + 0.44132215 0.055941917 0.8956033, + 0.43375894 0.075479195 0.8978619, + 0.39720881 0.076878063 0.91450256, + 0.38693491 0.10568298 0.91603076, + 0.35005996 0.10735799 0.93055487, + 0.34034801 0.137154 0.93024302, + 0.30313703 0.13899902 0.9427551, + 0.29417604 0.16959402 0.94058412, + 0.25718793 0.17147696 0.95102578, + 0.24907994 0.20288396 0.94699377, + 0.21251504 0.20470105 0.95547622, + 0.20541693 0.23666291 0.94962865, + 0.16924295 0.23833095 0.95632374, + 0.16327792 0.27065587 0.9487285, + 0.12757203 0.27209607 0.95377624, + 0.12283602 0.30466604 0.9445051, + 0.088065393 0.30579796 0.94801486, + 0.084624805 0.33850902 0.93715012, + 0.051010974 0.33928484 0.93929952, + 0.04892832 0.37181312 0.92701733, + 0.016436206 0.37220913 0.92800337, + 0.016407596 0.37355292 0.92746377, + -0.016384495 0.3735539 0.92746377, + -0.016412908 0.37221518 0.9280014, + -0.048894119 0.37182012 0.92701638, + -0.050974682 0.33931789 0.93928963, + -0.084578097 0.338543 0.93714201, + -0.088014208 0.30588603 0.94799113, + -0.12268697 0.30475795 0.94449478, + -0.12742496 0.27217391 0.95377362, + -0.16311005 0.27073705 0.94873422, + -0.16907698 0.23838396 0.9563399, + -0.20525308 0.23671809 0.94965035, + -0.21238296 0.20460695 0.95552576, + -0.24898006 0.20279005 0.94704026, + -0.25713289 0.17119993 0.95109051, + -0.29415989 0.16931894 0.94063866, + -0.30303699 0.139008 0.94278598, + -0.34028196 0.13716199 0.9302659, + -0.34991813 0.10760804 0.93057936, + -0.38675505 0.10593201 0.91607809, + -0.39411995 0.085408494 0.91508186, + -0.43349993 0.083744593 0.89725387, + -0.43794715 0.072243325 0.89609331, + -0.47709399 0.070624299 0.87601, + -0.48149887 0.059982587 0.87439179, + -0.52043277 0.058439676 0.85190058, + -0.52469301 0.048724402 0.84989601, + -0.56260413 0.04731831 0.82537121, + -0.5666492 0.038520515 0.82305831, + -0.60354108 0.037275705 0.79646009, + -0.60729486 0.029415892 0.79393184, + -0.64340395 0.028344097 0.76500189, + -0.65005177 0.014747694 0.75974673, + -0.68169898 0.0141993 0.73149502, + -0.69106793 -0.0044771796 0.72277594, + -0.69082499 -0.0049649398 0.723005, + -0.65292972 -0.0052011278 0.75740063, + -0.64960998 0.00157709 0.76026601, + -0.61359006 0.0016380002 0.78962314, + -0.60994792 0.009302659 0.79238689, + -0.57305884 0.0096204765 0.81945771, + -0.56913596 0.018202098 0.82204187, + -0.53112495 0.018756699 0.84708589, + -0.5269829 0.028263893 0.84940583, + -0.48789206 0.029029803 0.87242115, + -0.48357576 0.039526183 0.87440956, + -0.44414622 0.040458817 0.89504039, + -0.43979606 0.051791109 0.89660311, + -0.40005085 0.052851982 0.91496772, + -0.39572418 0.065068029 0.9160614, + -0.35299113 0.066290826 0.93327534, + -0.3583599 0.049603891 0.93226475, + -0.39866015 0.048728019 0.91580331, + -0.40294784 0.036579084 0.91449171, + -0.44284487 0.035834692 0.89588177, + -0.44714305 0.024601104 0.89412409, + -0.48675382 0.02402569 0.8732087, + -0.49100411 0.013656002 0.87105018, + -0.53016394 0.013291298 0.8477909, + -0.5342651 0.0038530009 0.84530818, + -0.57230699 0.00373777 0.82003099, + -0.57617188 -0.0047384589 0.8173148, + -0.61307412 -0.0045801611 0.79001218, + -0.61668587 -0.012197398 0.7871148, + -0.65265781 -0.011739397 0.7575618, + -0.65591204 -0.018396601 0.7546131, + -0.69080216 -0.017621703 0.72282916, + -0.69662791 -0.029351296 0.71683192, + -0.72649908 -0.028113104 0.68659204, + -0.73415595 -0.043205295 0.67760491, + -0.76235712 -0.041180305 0.64584506, + -0.76690781 -0.050020888 0.63980484, + -0.79668885 -0.047108293 0.60255092, + -0.80119967 -0.05601358 0.59576976, + -0.82913768 -0.05232998 0.55658984, + -0.83584589 -0.066093296 0.54497093, + -0.86113709 -0.061206307 0.50467503, + -0.86685681 -0.073678888 0.49308288, + -0.889449 -0.067542501 0.452016, + -0.89390713 -0.07800971 0.44141206, + -0.91398925 -0.070611112 0.3995471, + -0.91737759 -0.079292163 0.39003983, + -0.93500537 -0.070649423 0.34752512, + -0.93953621 -0.083787926 0.33204108, + -0.95311463 -0.074039973 0.29341188, + -0.95767313 -0.08926741 0.27366704, + -0.96866411 -0.077023104 0.23613003, + -0.9714815 -0.088324659 0.2200509, + -0.98023474 -0.073694088 0.18359995, + -0.98187453 -0.081819162 0.17096193, + -0.9886601 -0.064827509 0.13545701, + -0.98950636 -0.070238225 0.12626904, + -0.99443209 -0.051226109 0.092090607, + -0.99480575 -0.054540288 0.085946977, + -0.99804264 -0.033507288 0.05280238, + -0.99815714 -0.035156902 0.049460907, + -0.99978763 -0.011938196 0.016795294, + -0.99979836 -0.012381305 0.015812205, + -0.99978501 0.0127826 -0.0163248, + -0.99979365 0.013117195 -0.015509894, + -0.99796522 0.041174412 -0.048685111, + -0.99802476 0.041860688 -0.046843488, + -0.99403763 0.072655581 -0.081303872, + -0.99412674 0.073191285 -0.079718977, + -0.98739153 0.10705695 -0.11660495, + -0.98732263 0.10680896 -0.11741295, + -0.97687811 0.14386602 -0.15815102, + -0.97727466 0.14480396 -0.15480994, + -0.96253037 0.18524206 -0.19804208, + -0.96098536 0.18275505 -0.20762408, + -0.93349642 0.23692612 -0.26916611, + -0.92771924 0.23190206 -0.29250407, + -0.88155049 0.29328883 -0.3699328, + -0.87890911 0.29190403 -0.37724105, + -0.83878613 0.33319503 -0.43060306, + -0.85845882 0.3433719 -0.3809779, + -0.82226312 0.38101405 -0.42274305, + -0.84513414 0.39383307 -0.36144704, + -0.81003213 0.43202007 -0.39649305, + -0.840716 0.450901 -0.299808, + -0.80763435 0.49104425 -0.32650015, + -0.83195531 0.50760621 -0.22402307, + -0.79978883 0.54917687 -0.24236894, + -0.81676519 0.56200612 -0.13055202, + -0.82226187 0.56806391 -0.034479298, + -0.8166157 0.5637368 -0.12385295, + -0.84623402 0.52039999 -0.114332, + -0.83264929 0.5110302 -0.21340908, + -0.86188489 0.46793994 -0.19541398, + -0.8430047 0.45620286 -0.2849949, + -0.87271112 0.41407806 -0.25867903, + -0.85024899 0.40143001 -0.34048599, + -0.88134998 0.36031201 -0.30561, + -0.86664116 0.35270408 -0.3528921, + -0.89761513 0.31159502 -0.31176203, + -0.88751978 0.30668095 -0.34388292, + -0.91912144 0.26222312 -0.29403216, + -0.92111474 0.26326695 -0.28677195, + -0.95400202 0.202747 -0.22084799, + -0.95730901 0.20615 -0.202637, + -0.97643399 0.15391099 -0.151288, + -0.97720367 0.15556493 -0.14447296, + -0.98751014 0.11544801 -0.10721701, + -0.98722947 0.11449105 -0.11076906, + -0.99405777 0.078232579 -0.075689286, + -0.99402988 0.078074291 -0.07621669, + -0.99802411 0.044961203 -0.043891404, + -0.99798214 0.044490203 -0.045301404, + -0.9997955 0.014169306 -0.014427607, + -0.99978876 0.013906796 -0.015135496, + -0.99980187 -0.013467198 0.014657198, + -0.99979347 -0.013105807 0.015537907, + -0.99820721 -0.038590107 0.045751311, + -0.99811333 -0.037184715 0.048858218, + -0.99499297 -0.060529299 0.079531603, + -0.99468935 -0.057697721 0.085229933, + -0.98998815 -0.079127707 0.11688601, + -0.98928821 -0.074377514 0.12560603, + -0.98286879 -0.093908481 0.15858796, + -0.98152912 -0.086809605 0.17048402, + -0.97332335 -0.10410903 0.20445807, + -0.97098851 -0.094034955 0.2198609, + -0.96075213 -0.10908902 0.25505903, + -0.95701301 -0.095600098 0.273837, + -0.94444448 -0.10833094 0.31030482, + -0.94066077 -0.096437275 0.3253569, + -0.93967611 -0.082611911 0.33194003, + -0.92104489 -0.094057284 0.37792793, + -0.9179436 -0.085789062 0.38732383, + -0.89861774 -0.094876178 0.42835093, + -0.894548 -0.084929898 0.438829, + -0.87276816 -0.092751123 0.47924212, + -0.86755484 -0.080916576 0.49071488, + -0.84311986 -0.08748699 0.53056091, + -0.83660072 -0.073575467 0.54284984, + -0.80947018 -0.078860424 0.58184111, + -0.80195487 -0.063604996 0.59398896, + -0.77261412 -0.067596905 0.63126707, + -0.76739115 -0.057297308 0.63861406, + -0.73623282 -0.060474087 0.67402083, + -0.73113525 -0.05049742 0.68036121, + -0.70143163 -0.052755274 0.71078163, + -0.69323099 -0.0363364 0.71979898, + -0.66183996 -0.037794895 0.74869192, + -0.655635 -0.0250012 0.754664, + -0.61972827 -0.02598591 0.78438628, + -0.61616713 -0.018457703 0.78739917, + -0.57926929 -0.019102609 0.81491244, + -0.57541996 -0.010642399 0.8177889, + -0.53736585 -0.010974097 0.84327781, + -0.53330785 -0.0016098995 0.84591973, + -0.49404806 -0.0016546502 0.8694331, + -0.48985794 0.0085961791 0.87175989, + -0.45014384 0.0088047571 0.89291269, + -0.44586307 0.020028802 0.89487714, + -0.40581393 0.020450698 0.91372687, + -0.40157685 0.032493889 0.91524869, + -0.36104509 0.033087209 0.93196124, + -0.35692701 0.045959398 0.93300098, + -0.31589115 0.046680823 0.9476465, + -0.30951685 0.068858273 0.94839752, + -0.27105007 0.069703415 0.96003824, + -0.26312602 0.10122801 0.95943612, + -0.22499304 0.10223501 0.9689821, + -0.21806096 0.13441198 0.96663475, + -0.1801111 0.13547406 0.97427249, + -0.17426609 0.16828308 0.97021246, + -0.13645901 0.16929902 0.97607213, + -0.13176505 0.2028911 0.97029549, + -0.094741598 0.20375501 0.97442698, + -0.091345802 0.237488 0.96708602, + -0.055177882 0.23812191 0.96966666, + -0.053122081 0.27184892 0.96087265, + -0.017845903 0.27219003 0.96207809, + -0.017153399 0.30582896 0.95193189, + 0.017259305 0.30582812 0.95193034, + 0.017953498 0.27215496 0.9620859, + 0.053266909 0.27181202 0.96087509, + 0.055322673 0.23810488 0.96966255, + 0.091477208 0.23747003 0.96707809, + 0.09486942 0.20379505 0.97440624, + 0.13192697 0.20292796 0.97026575, + 0.13660394 0.16946793 0.97602254, + 0.1743129 0.16845292 0.97017455, + 0.18018894 0.13546295 0.97425961, + 0.21816808 0.13440004 0.96661234, + 0.22512689 0.10208695 0.96896654, + 0.26329604 0.10108002 0.95940512, + 0.27123293 0.069492288 0.96000177, + 0.30976495 0.068647482 0.94833177, + 0.31852901 0.037979499 0.94715202, + 0.35717604 0.037423603 0.93328714, + 0.36654696 0.0080232192 0.93036491, + 0.40469083 0.0078857066 0.91441959, + 0.41171315 -0.012092405 0.91123331, + 0.45208794 -0.011835798 0.89189488, + 0.45626912 -0.022861606 0.88954824, + 0.49619982 -0.022305792 0.86792171, + 0.50029886 -0.032389492 0.86524683, + 0.53971481 -0.031491589 0.8412587, + 0.54364485 -0.040603586 0.83833271, + 0.58175194 -0.039348196 0.81241387, + 0.58843291 -0.054177988 0.80672884, + 0.62185186 -0.052475289 0.78137481, + 0.63061285 -0.071034387 0.77283984, + 0.66292673 -0.068525374 0.74554175, + 0.66878217 -0.080447622 0.73909318, + 0.70324308 -0.076929808 0.70677507, + 0.7103442 -0.091268323 0.69791216, + 0.74278092 -0.086818092 0.66388196, + 0.7521081 -0.10590401 0.65047508, + 0.78222084 -0.10011297 0.61490488, + 0.79033762 -0.11725394 0.60134673, + 0.81820911 -0.11002801 0.56429404, + 0.82494819 -0.12486603 0.55124313, + 0.85052484 -0.11618997 0.51293987, + 0.85600841 -0.12890491 0.50063264, + 0.87890321 -0.11894103 0.46193311, + 0.88326257 -0.12970094 0.4505828, + 0.90355986 -0.11852098 0.41174293, + 0.90695375 -0.12753697 0.40145892, + 0.92490786 -0.11511198 0.36234596, + 0.9294734 -0.12861706 0.34574118, + 0.94362038 -0.11541705 0.31025711, + 0.94829702 -0.13099299 0.28909099, + 0.96005464 -0.11548596 0.25486892, + 0.96314275 -0.12750196 0.23685294, + 0.97278315 -0.10983402 0.20403303, + 0.97468799 -0.118651 0.189487, + 0.98248535 -0.098893136 0.15793306, + 0.98359346 -0.10515305 0.14658408, + 0.98974389 -0.083267294 0.11607599, + 0.9903149 -0.087364189 0.10790698, + 0.99486214 -0.06370461 0.078684308, + 0.99511176 -0.066137984 0.073337883, + 0.9981575 -0.040635683 0.045059279, + 0.99823213 -0.041783903 0.042270802, + 0.99979621 -0.014193804 0.014359304, + 0.99980289 -0.014482498 0.013581198, + 0.99978966 0.014961095 -0.014029996, + 0.99979538 0.015179305 -0.013373905, + 0.99797875 0.047681689 -0.042010687, + 0.99800253 0.047938578 -0.041143883, + 0.99395978 0.083278574 -0.071475089, + 0.99404824 0.083755225 -0.069664918, + 0.98719335 0.12264805 -0.10201403, + 0.98699349 0.12203606 -0.10464706, + 0.974042 0.17184 -0.14735401, + 0.97232938 0.16960905 -0.16065006, + 0.94950902 0.227782 -0.21574999, + 0.94897974 0.22748993 -0.21837096, + 0.92522442 0.27372012 -0.26274911, + 0.93581635 0.27883109 -0.21564108, + 0.91105378 0.32613492 -0.25222394, + 0.92470801 0.332609 -0.185166, + 0.90152574 0.3780849 -0.21048295, + 0.91072589 0.38285193 -0.15492798, + 0.88695931 0.42812216 -0.17324705, + 0.89527243 0.43283021 -0.10557105, + 0.87078142 0.47766724 -0.11650705, + 0.87652314 0.48135805 0.0013204201, + 0.86751831 0.49485818 -0.050273418, + 0.8686288 0.49544787 0.003941929, + 0.86868984 0.49534088 0.0039418391, + 0.86758602 0.494755 -0.050120302, + 0.86749816 0.49490812 -0.05012881, + 0.86860198 0.49549499 0.0039144498, + 0.84324515 0.53738606 -0.012403202, + 0.84325629 0.5373922 -0.011338804, + 0.84371501 0.536663 -0.0117421, + 0.89442891 0.44706994 -0.011198899, + 0.89188474 0.45218089 -0.008605388, + 0.89094311 0.45173305 -0.046450604, + 0.89092076 0.45177689 -0.046452887, + 0.891783 0.452191 -0.015698399, + 0.91299742 0.40795022 0.0035181316, + 0.91214222 0.40756708 -0.04342391, + 0.91301179 0.40791792 0.003520919, + 0.91300374 0.40793592 0.003520929, + 0.91213298 0.407585 -0.0434504, + 0.91212672 0.40759885 -0.043450985, + 0.89959931 0.43668616 0.0051360517, + 0.89520079 0.4340609 -0.10102798, + 0.91711915 0.38823605 -0.090362206, + 0.91102231 0.38507614 -0.14749506, + 0.93190688 0.33870196 -0.12973298, + 0.92559111 0.33568004 -0.17492901, + 0.94521576 0.28949594 -0.15086196, + 0.93678176 0.28573895 -0.20197296, + 0.95661312 0.23792502 -0.16817601, + 0.95125353 0.23532487 -0.19934592, + 0.96899563 0.18852693 -0.15970294, + 0.96937448 0.18876009 -0.15710807, + 0.9847759 0.13360599 -0.11120199, + 0.98558289 0.13504799 -0.10192399, + 0.99383914 0.088464804 -0.066766806, + 0.99391186 0.08882039 -0.065192789, + 0.997989 0.051100101 -0.037506599, + 0.99795121 0.050708212 -0.039015409, + 0.99979275 0.016135296 -0.012414797, + 0.99978936 0.016009506 -0.012841205, + 0.99980277 -0.015493697 0.012427397, + 0.99979711 -0.015247202 0.013168902, + 0.99824065 -0.044872586 0.038756184, + 0.99818045 -0.043920424 0.041314717, + 0.99517387 -0.071474396 0.067233689, + 0.99497521 -0.069451213 0.072117716, + 0.99052888 -0.095243484 0.098900385, + 0.99006122 -0.091692023 0.10663702, + 0.98409754 -0.11580895 0.13468593, + 0.98319411 -0.11036001 0.14543101, + 0.97570378 -0.13244297 0.17453095, + 0.97412276 -0.12457997 0.18858595, + 0.96492922 -0.14469303 0.21903306, + 0.9623909 -0.13404298 0.23629697, + 0.95126265 -0.15215795 0.2682299, + 0.95135099 -0.15151601 0.26828, + 0.93618476 -0.17285796 0.30606893, + 0.93441665 -0.16684794 0.31468588, + 0.91843402 -0.18530101 0.349489, + 0.9160763 -0.17793706 0.35936412, + 0.89795488 -0.19527997 0.39438894, + 0.89489812 -0.18640001 0.40547806, + 0.874376 -0.20268001 0.44089401, + 0.87048072 -0.19204992 0.45318884, + 0.84740043 -0.2071701 0.48886925, + 0.84251332 -0.19452707 0.50232518, + 0.81710929 -0.20818007 0.53758121, + 0.81120682 -0.19356395 0.55179387, + 0.78344887 -0.20571098 0.58642197, + 0.77646512 -0.18899903 0.60115004, + 0.74610603 -0.199696 0.63517499, + 0.73795897 -0.18067898 0.65020895, + 0.70505697 -0.18986297 0.68326193, + 0.69577283 -0.16851196 0.69821483, + 0.66088593 -0.17607199 0.72953993, + 0.65058309 -0.15249002 0.74396807, + 0.61405373 -0.15847993 0.77318966, + 0.60288125 -0.13276304 0.78670728, + 0.56468409 -0.13733603 0.81380016, + 0.55584592 -0.11652499 0.82307786, + 0.51615375 -0.12005894 0.84803957, + 0.50934988 -0.10330198 0.8543368, + 0.47203976 -0.10582495 0.8752026, + 0.46588218 -0.089366831 0.88032228, + 0.42485484 -0.091428474 0.90063268, + 0.42102605 -0.080357105 0.90348214, + 0.37917277 -0.081976347 0.92168748, + 0.37527683 -0.069565572 0.92429858, + 0.33029491 -0.070838884 0.94121575, + 0.33491808 -0.087344125 0.93819022, + 0.3777101 -0.085831024 0.92193723, + 0.38144115 -0.097731836 0.91921234, + 0.42344886 -0.095778562 0.90084273, + 0.42946994 -0.11328299 0.89594787, + 0.467684 -0.110876 0.87691402, + 0.47448283 -0.12888795 0.87077773, + 0.5150069 -0.12550896 0.84794784, + 0.52394575 -0.14790493 0.83881158, + 0.56380111 -0.14341803 0.81336319, + 0.57509291 -0.17078498 0.80006289, + 0.61329597 -0.164891 0.77244997, + 0.62388992 -0.19016898 0.75802189, + 0.66022003 -0.182761 0.72849703, + 0.66993719 -0.20584305 0.7133112, + 0.70450103 -0.19677202 0.68187904, + 0.71316397 -0.21747699 0.66640902, + 0.74565876 -0.20671992 0.63345075, + 0.75322211 -0.22508503 0.61805606, + 0.7830959 -0.21281198 0.58435595, + 0.78959614 -0.22900803 0.56929207, + 0.81683588 -0.21528997 0.53519094, + 0.8223111 -0.22942403 0.52073908, + 0.84719342 -0.21420211 0.48619023, + 0.85164589 -0.22621398 0.47278595, + 0.87422812 -0.20955403 0.43796405, + 0.87779123 -0.21969606 0.42569509, + 0.89785522 -0.20192404 0.39125809, + 0.90066475 -0.21043895 0.38015592, + 0.91837287 -0.19164898 0.34621096, + 0.92053926 -0.19871004 0.33633608, + 0.93615437 -0.17884105 0.30270612, + 0.93773675 -0.18444896 0.29432693, + 0.95138878 -0.16355096 0.26097995, + 0.95347601 -0.171914 0.247647, + 0.96412575 -0.15137197 0.21805495, + 0.96623135 -0.16091606 0.20125407, + 0.97509724 -0.13849802 0.17321604, + 0.97638321 -0.14538303 0.15981105, + 0.98366737 -0.12112404 0.13314505, + 0.98440599 -0.125891 0.122867, + 0.99025363 -0.099672563 0.097278364, + 0.99062574 -0.10266398 0.090115078, + 0.99502522 -0.074871518 0.065720215, + 0.99518585 -0.076576091 0.061165292, + 0.99818414 -0.047065608 0.037593704, + 0.99823463 -0.047885481 0.035135288, + 0.99979633 -0.016274605 0.011941205, + 0.99979991 -0.016433598 0.011402399, + 0.99978626 0.016987404 -0.011786803, + 0.99979055 0.017144293 -0.011179394, + 0.99792713 0.053906608 -0.035151403, + 0.99790865 0.053732682 -0.035932288, + 0.99314433 0.097169638 -0.06497962, + 0.99282449 0.096292652 -0.070902362, + 0.98306888 0.14755198 -0.10864598, + 0.98284733 0.14738306 -0.11085804, + 0.97002465 0.19420293 -0.14607294, + 0.97251624 0.19549005 -0.12647504, + 0.95707023 0.24336506 -0.15744905, + 0.96198535 0.24547809 -0.11968604, + 0.94577122 0.29197806 -0.14235803, + 0.94991475 0.29383495 -0.10640997, + 0.93208843 0.34058514 -0.12334106, + 0.93639064 0.34263888 -0.075967468, + 0.91704261 0.38933486 -0.086320467, + 0.92029464 0.39115086 0.0076606474, + 0.93114525 0.36236009 -0.04078931, + 0.9319129 0.36262998 -0.0061436989, + 0.9318859 0.36269996 -0.0061121793, + 0.93111789 0.36242998 -0.040792298, + 0.938622 0.3448 0.0100889, + 0.93631786 0.34357396 -0.072565295, + 0.95291579 0.29668993 -0.062663183, + 0.95446438 0.29826412 -0.0060326322, + 0.95284837 0.29751113 -0.059726223, + 0.96677262 0.25063691 -0.050316181, + 0.96491933 0.24985109 -0.080655128, + 0.97698075 0.20301196 -0.065534882, + 0.97550374 0.20237796 -0.086230278, + 0.98557913 0.15567301 -0.066330306, + 0.98430073 0.15506697 -0.084299177, + 0.99235779 0.10840998 -0.058935385, + 0.99200433 0.10812904 -0.065081023, + 0.99725962 0.06338618 -0.038151287, + 0.99729252 0.063446969 -0.037177481, + 0.99974835 0.019354507 -0.011341004, + 0.9997561 0.019490102 -0.010389501, + 0.99978763 -0.018184094 0.0096933162, + 0.99978876 -0.018227596 0.0094969785, + 0.99817288 -0.053584792 0.027918896, + 0.99813765 -0.052987583 0.030222889, + 0.99506855 -0.086159855 0.049143579, + 0.99497622 -0.085088626 0.052747313, + 0.99054086 -0.11662699 0.072298191, + 0.99029714 -0.11440202 0.078891009, + 0.9844861 -0.14444701 0.099611014, + 0.98401898 -0.14095201 0.108808, + 0.97689497 -0.169177 0.130596, + 0.97606987 -0.16396798 0.14283599, + 0.96754289 -0.19054697 0.16598998, + 0.96615952 -0.1830949 0.18169191, + 0.95607424 -0.20806605 0.20647204, + 0.95470423 -0.20148204 0.21896306, + 0.94190377 -0.22743393 0.24716593, + 0.94086677 -0.22302394 0.25500995, + 0.92626524 -0.24810305 0.28368607, + 0.92482513 -0.24245404 0.29311204, + 0.90830302 -0.26662299 0.32233199, + 0.9064061 -0.25969803 0.33314404, + 0.88771057 -0.28305686 0.36310983, + 0.88526213 -0.27467003 0.37532306, + 0.8641901 -0.29715404 0.40604806, + 0.86107582 -0.28706795 0.41969091, + 0.83782214 -0.30822104 0.45061505, + 0.83391798 -0.296168 0.46568799, + 0.80833483 -0.31593591 0.49676889, + 0.80365616 -0.30205205 0.51273912, + 0.77542502 -0.32049999 0.54405499, + 0.7698878 -0.30456793 0.56081289, + 0.73892003 -0.32156503 0.59210908, + 0.732458 -0.30336401 0.60948801, + 0.69918609 -0.31857103 0.64004004, + 0.69173825 -0.29783812 0.65786827, + 0.65625602 -0.31119701 0.68737501, + 0.6479668 -0.28816593 0.70505279, + 0.61013687 -0.29975295 0.7334038, + 0.60107476 -0.2743319 0.75063372, + 0.56094193 -0.28416997 0.77755487, + 0.55126286 -0.25641394 0.79395282, + 0.509776 -0.26439801 0.81867099, + 0.49965519 -0.23435009 0.83392131, + 0.45709616 -0.24062508 0.85624927, + 0.44687912 -0.20877005 0.86989319, + 0.40344799 -0.213532 0.88973802, + 0.39332515 -0.17984407 0.90163827, + 0.34925798 -0.18329199 0.91892487, + 0.34148011 -0.15499906 0.92702037, + 0.29753205 -0.15744305 0.94164026, + 0.29206195 -0.13501997 0.94682074, + 0.25019211 -0.13668506 0.95849949, + 0.24405488 -0.10703395 0.96383655, + 0.20190893 -0.10809696 0.97342062, + 0.19637392 -0.075569369 0.97761261, + 0.15415807 -0.076148838 0.98510748, + 0.14968607 -0.042460918 0.98782146, + 0.10785998 -0.042694196 0.99324888, + 0.10459097 -0.0082946178 0.99448079, + 0.063389808 -0.0083235912 0.99795413, + 0.061392423 0.026631609 0.99775833, + 0.020758292 0.026676191 0.99942863, + 0.02007989 0.062154371 0.99786454, + -0.019929091 0.062154569 0.99786752, + -0.020606102 0.026739104 0.99943012, + -0.061168529 0.026694713 0.99777049, + -0.063165493 -0.0082589993 0.99796885, + -0.104298 -0.00823039 0.99451202, + -0.107565 -0.042622998 0.99328399, + -0.14935802 -0.042390805 0.98787409, + -0.15382907 -0.07610184 0.9851625, + -0.19607505 -0.075523518 0.97767621, + -0.20161897 -0.10814998 0.97347486, + -0.24375889 -0.10708695 0.96390551, + -0.24995209 -0.13706805 0.95850736, + -0.29193297 -0.13539499 0.94680691, + -0.29748106 -0.15817204 0.94153422, + -0.34151888 -0.15571094 0.92688662, + -0.34913683 -0.18343891 0.91894156, + -0.39322594 -0.17998698 0.90165287, + -0.40319508 -0.21315004 0.88994426, + -0.44662395 -0.20839997 0.8701129, + -0.45674995 -0.23993698 0.85662687, + -0.49924219 -0.23369908 0.8343513, + -0.50932205 -0.26357704 0.8192181, + -0.55078876 -0.25563589 0.79453266, + -0.56049103 -0.28340501 0.77815902, + -0.60060108 -0.27361304 0.75127512, + -0.60968709 -0.29905105 0.73406416, + -0.64750695 -0.28751197 0.70574194, + -0.65587419 -0.31071305 0.68795818, + -0.69135302 -0.297396 0.65847301, + -0.69886684 -0.31827092 0.6405378, + -0.73214507 -0.30309603 0.60999703, + -0.73867506 -0.32145903 0.59247208, + -0.76967973 -0.30446589 0.56115383, + -0.7752583 -0.32049912 0.54429317, + -0.80350101 -0.30205899 0.51297802, + -0.80822599 -0.31606799 0.49686199, + -0.83382529 -0.29629213 0.46577519, + -0.83773702 -0.308366 0.450674, + -0.8610239 -0.28718397 0.41971794, + -0.86415201 -0.29732201 0.40600601, + -0.88523322 -0.27482206 0.37528008, + -0.88769001 -0.283243 0.363015, + -0.9063943 -0.25986108 0.33304912, + -0.90829957 -0.26682687 0.32217285, + -0.92482775 -0.24262995 0.29295793, + -0.92626661 -0.24828288 0.28352386, + -0.94087422 -0.22317407 0.25485107, + -0.94191152 -0.2275929 0.24698988, + -0.95471627 -0.20161004 0.21879306, + -0.95608562 -0.20820493 0.20627892, + -0.96617103 -0.18321 0.18151499, + -0.96755278 -0.19067496 0.16578496, + -0.97608012 -0.16406801 0.14265102, + -0.97690874 -0.16932096 0.13030598, + -0.98403102 -0.14106099 0.108558, + -0.98449862 -0.14458196 0.09929046, + -0.99030721 -0.11449603 0.078628421, + -0.99054164 -0.11664695 0.072254978, + -0.99497676 -0.085102081 0.05271519, + -0.99507135 -0.086203627 0.049010418, + -0.99813902 -0.053010501 0.030138699, + -0.99817902 -0.0537007 0.027475299, + -0.99978954 -0.018261291 0.009343205, + -0.99978763 -0.018182294 0.009700086, + -0.99975598 0.019489201 -0.0103973, + -0.99974811 0.019350503 -0.011371301, + -0.99728912 0.063440308 -0.037280805, + -0.99723923 0.063349113 -0.038742006, + -0.99194264 0.10807896 -0.066097081, + -0.9921965 0.10827595 -0.061825369, + -0.98396277 0.15490097 -0.088448077, + -0.98562688 0.15567899 -0.065602392, + -0.97558552 0.2023849 -0.085283764, + -0.97735661 0.20316693 -0.059136678, + -0.96549046 0.25006112 -0.072786041, + -0.96727121 0.25087106 -0.038082808, + -0.97766322 0.20993204 -0.010158502, + -0.97555125 0.21735604 -0.032498308, + -0.97605926 0.21744704 -0.0050076316, + -0.97607523 0.21737504 -0.0050313915, + -0.97556746 0.2172841 -0.032493714, + -0.96410334 0.2650601 0.015746906, + -0.96421552 0.26510087 0.0031375587, + -0.96424079 0.26500893 0.0031374793, + -0.96356523 0.26485506 -0.037335306, + -0.96770513 0.25175604 -0.012869602, + -0.96719378 0.25151494 -0.035726294, + -0.97840363 0.20464893 -0.02906929, + -0.97734737 0.20416008 -0.055774018, + -0.98662263 0.15725794 -0.042960986, + -0.98569322 0.15681104 -0.061799314, + -0.99288213 0.11080702 -0.043669004, + -0.99218953 0.11040594 -0.058055375, + -0.99731022 0.064874917 -0.034113608, + -0.99726087 0.064811289 -0.035639696, + -0.99971378 0.020965094 -0.011528697, + -0.99971837 0.020992707 -0.011071804, + -0.99975687 -0.019504698 0.010286999, + -0.99976325 -0.019632505 0.0093899518, + -0.99808609 -0.055788107 0.026682703, + -0.99809963 -0.056006182 0.02570029, + -0.99496925 -0.091051623 0.041782111, + -0.99487376 -0.089847974 0.046405189, + -0.99035364 -0.12311196 0.063585579, + -0.9901799 -0.12139098 0.069339991, + -0.984303 -0.153248 0.087536901, + -0.9839431 -0.15026401 0.096316218, + -0.97679049 -0.18033209 0.11558905, + -0.9761411 -0.17577401 0.12748401, + -0.96764022 -0.20426604 0.14814803, + -0.96655726 -0.19776905 0.16326204, + -0.95658267 -0.22476892 0.18554895, + -0.95549387 -0.21892197 0.19774897, + -0.95606762 -0.20831692 0.20624892, + -0.94248247 -0.23753011 0.23517312, + -0.94156611 -0.23342302 0.24283104, + -0.92711389 -0.25972298 0.27019197, + -0.92583686 -0.25443298 0.27944598, + -0.90950227 -0.27986506 0.30737805, + -0.90778202 -0.27323201 0.318239, + -0.88929731 -0.29791212 0.34698513, + -0.88707542 -0.28988314 0.35925618, + -0.86626011 -0.31372604 0.38880506, + -0.86343968 -0.30410188 0.40248486, + -0.84045488 -0.32666498 0.43234894, + -0.8369261 -0.31520602 0.44743705, + -0.81164187 -0.33642197 0.47755393, + -0.80731171 -0.32293487 0.49392381, + -0.77938616 -0.34286508 0.52440512, + -0.7742359 -0.32734796 0.54166591, + -0.74355495 -0.34585398 0.57228595, + -0.73754936 -0.32818216 0.59018427, + -0.70454305 -0.34488404 0.62022108, + -0.69763696 -0.32483798 0.63857895, + -0.66236681 -0.33967692 0.66774982, + -0.65454602 -0.317063 0.686324, + -0.6168291 -0.33009508 0.71453416, + -0.60826176 -0.30513689 0.73274076, + -0.5681631 -0.3163541 0.75967818, + -0.55899566 -0.28910384 0.77713752, + -0.5173918 -0.29837087 0.80204773, + -0.50777888 -0.26883593 0.81846684, + -0.46500888 -0.27626893 0.84109581, + -0.45520386 -0.24467792 0.85610873, + -0.4112958 -0.25047988 0.8764106, + -0.40167114 -0.21741207 0.8896023, + -0.35692781 -0.2217689 0.90742558, + -0.34766307 -0.18715404 0.91875124, + -0.30302989 -0.19021992 0.93380362, + -0.29606205 -0.16114604 0.94147724, + -0.25170487 -0.16327693 0.95393151, + -0.24679892 -0.13957396 0.95896262, + -0.20414211 -0.14099507 0.9687345, + -0.19891797 -0.11013599 0.97380787, + -0.15603794 -0.11100596 0.98149365, + -0.15163207 -0.077610336 0.98538548, + -0.109218 -0.078048497 0.99094898, + -0.10596997 -0.043653283 0.99341065, + -0.064138092 -0.043809995 0.99697888, + -0.062154409 -0.0088778809 0.99802715, + -0.020895302 -0.0088931508 0.99974209, + -0.020221999 0.026514696 0.99944389, + 0.02048159 0.026514586 0.99943852, + 0.021155009 -0.0089147845 0.99973649, + 0.062449064 -0.0088993646 0.99800843, + 0.064435475 -0.043858286 0.99695766, + 0.10630202 -0.043700602 0.9933731, + 0.10955097 -0.078066982 0.99091077, + 0.15200607 -0.077627137 0.98532647, + 0.15641208 -0.11095905 0.98143947, + 0.19920105 -0.11009003 0.97375524, + 0.2043909 -0.14066093 0.96873051, + 0.24697202 -0.13924402 0.95896614, + 0.25182688 -0.16265492 0.95400554, + 0.29605302 -0.16053702 0.94158411, + 0.30314213 -0.19009708 0.93379235, + 0.34777281 -0.18703191 0.91873461, + 0.35716009 -0.22212406 0.90724725, + 0.401939 -0.21775299 0.88939798, + 0.41164485 -0.2511369 0.8760587, + 0.45556805 -0.24531002 0.85573411, + 0.46540007 -0.27703604 0.84062713, + 0.50826281 -0.26955491 0.81792969, + 0.51785088 -0.29906493 0.80149281, + 0.5594762 -0.2897571 0.77654833, + 0.56861889 -0.31698492 0.75907379, + 0.60873967 -0.30571985 0.73210067, + 0.61724311 -0.33053908 0.7139712, + 0.65494221 -0.31747511 0.68575525, + 0.6627028 -0.33995491 0.66727483, + 0.69796693 -0.32508597 0.63809192, + 0.704813 -0.34498501 0.61985803, + 0.73779982 -0.32826892 0.58982289, + 0.74375975 -0.34582388 0.57203782, + 0.77440912 -0.32732204 0.54143405, + 0.77952516 -0.3427451 0.52427709, + 0.80742121 -0.3228291 0.49381411, + 0.81173921 -0.3362821 0.47748712, + 0.83701319 -0.31507108 0.44736913, + 0.84052229 -0.32646611 0.43236816, + 0.86347997 -0.30393299 0.40252599, + 0.86629111 -0.31351802 0.38890406, + 0.88710022 -0.28969207 0.3593491, + 0.88932079 -0.29770693 0.34710091, + 0.90778512 -0.27306703 0.31837204, + 0.90950722 -0.27969605 0.30751705, + 0.92583615 -0.25428703 0.27958104, + 0.927109 -0.25954801 0.27037701, + 0.94156098 -0.23326799 0.243, + 0.94324613 -0.24107203 0.22841004, + 0.95484042 -0.21568286 0.20435388, + 0.95657748 -0.2246201 0.18575609, + 0.96654689 -0.19765697 0.16345899, + 0.96762633 -0.20410408 0.14846206, + 0.97612727 -0.17564805 0.12776303, + 0.97677636 -0.18017606 0.11595105, + 0.98393053 -0.15014693 0.096625656, + 0.98430198 -0.153209 0.087616302, + 0.99017811 -0.12136701 0.069406904, + 0.99034786 -0.12304098 0.063812494, + 0.99487001 -0.089802898 0.0465746, + 0.99495709 -0.090878606 0.042443603, + 0.9980939 -0.055914994 0.026114296, + 0.99808621 -0.055792715 0.026665505, + 0.99976325 -0.019633505 0.0093836216, + 0.99975711 -0.019508902 0.010258501, + 0.99971867 0.020994792 -0.011039896, + 0.99971545 0.020975409 -0.011363205, + 0.99727774 0.064834088 -0.035123192, + 0.9973619 0.064946294 -0.032421496, + 0.99234426 0.11049903 -0.055161614, + 0.99286264 0.11080496 -0.044113185, + 0.98565251 0.15681693 -0.062431071, + 0.98641151 0.15716892 -0.047856178, + 0.97699124 0.20403105 -0.062125314, + 0.97809035 0.20449208 -0.039016213, + 0.96671778 0.25131193 -0.047949091, + 0.96767288 0.25184298 0.013575498, + 0.96297574 0.26955894 -0.003974149, + 0.96295202 0.26964399 -0.0039420901, + 0.96242189 0.26951897 -0.033219896, + 0.96244586 0.26943398 -0.033216696, + 0.94778323 0.3162331 0.041275911, + 0.94857836 0.31653011 0.0028260709, + 0.94856298 0.316576 0.0028261, + 0.94790775 0.31638992 -0.036989693, + 0.94793791 0.31629997 -0.036985897, + 0.94859254 0.31648687 0.0028470387, + 0.93561465 0.35272589 -0.014479394, + 0.96691376 0.25464895 -0.015222397, + 0.97501922 0.22211306 0.0018295805, + 0.97457975 0.22203794 -0.029888693, + 0.97458464 0.22201693 -0.029887989, + 0.97502398 0.222092 0.00183605, + 0.97505498 0.221956 0.0018359401, + 0.9744581 0.22179303 0.035203505, + 0.98438615 0.17393002 -0.027062204, + 0.98438185 0.17395398 -0.027062995, + 0.98474377 0.17399795 -0.0020736395, + 0.98474813 0.17397402 -0.0020804603, + 0.99209887 0.12545699 0.00060948596, + 0.98796326 0.15389203 -0.015682304, + 0.92887723 -0.3148891 0.19501804, + 0.94179225 -0.28582007 0.17701505, + 0.92923909 -0.29529303 0.22207403, + 0.94204634 -0.26812309 0.20164007, + 0.94363737 -0.27730808 0.18069007, + 0.95514375 -0.24811894 0.16167095, + 0.95615399 -0.254958 0.144104, + 0.96620053 -0.2244249 0.12684594, + 0.96682048 -0.22938611 0.11242905, + 0.97551203 -0.19749901 0.096801199, + 0.97584742 -0.20064788 0.086383551, + 0.98326766 -0.16731894 0.072035074, + 0.98346937 -0.16953306 0.063613325, + 0.98964077 -0.13441497 0.050436489, + 0.98961645 -0.13415806 0.051585425, + 0.99412888 -0.10099398 0.038833298, + 0.99402714 -0.10043202 0.042703804, + 0.99757397 -0.064063497 0.0272399, + 0.99754936 -0.063999921 0.02827131, + 0.99972475 -0.021462295 0.0094806878, + 0.99972826 -0.021478806 0.0090614818, + 0.99971938 0.021827007 -0.0092083933, + 0.99973911 0.021887202 -0.0065431311, + 0.99754411 0.067106307 -0.020061202, + 0.99355751 0.11289494 0.0099079954, + 0.99345338 0.11275204 -0.018372007, + 0.997679 0.067206703 -0.0109509, + 0.99322289 -0.10950799 0.038940795, + 0.99752098 -0.066302903 0.0235771, + 0.99763787 -0.066449195 0.017413298, + 0.99973834 -0.022130707 0.0057994518, + 0.99974924 -0.022156706 0.0032410107, + 0.99974799 0.022212399 -0.00324915, + 0.99972266 0.022262793 0.0076834871, + 0.99957687 0.029031597 -0.0018089098, + 0.99957889 0.028965397 -0.0017733597, + 0.99950689 0.028971497 -0.012107398, + 0.99950498 0.0290378 -0.0121091, + 0.99768686 0.06746839 0.0083065089, + 0.99767309 0.067380905 -0.010410001, + 0.99974865 0.022154992 -0.0034228389, + 0.99973601 0.022126799 -0.0061978898, + 0.99974149 -0.021896111 0.0061332528, + 0.99972552 -0.021843189 0.008467366, + 0.99754912 -0.065239407 0.025289604, + 0.99753213 -0.065209106 0.026026905, + 0.99329615 -0.10736202 0.042851202, + 0.99335903 -0.107476 0.041070301, + 0.98833936 -0.14223604 0.05435342, + 0.98849851 -0.14298493 0.049254376, + 0.98267853 -0.1752139 0.06035617, + 0.98270649 -0.17552109 0.05899493, + 0.97506148 -0.21037011 0.070708536, + 0.97482622 -0.20751205 0.081564523, + 0.96591961 -0.2409009 0.094688766, + 0.96552509 -0.23690502 0.10787702, + 0.95530152 -0.26905188 0.12251594, + 0.95458603 -0.26303801 0.139916, + 0.94295764 -0.29391888 0.15634094, + -0.88451731 -0.44679216 0.13418604, + -0.86117911 -0.48682007 0.14620802, + -0.86083084 -0.49543387 0.11625697, + -0.83271116 -0.53906512 0.12649503, + -0.83167112 -0.54714304 0.094645016, + -0.80057317 -0.59046614 0.10213903, + -0.79817384 -0.59939289 0.060387883, + -0.76082528 -0.64568824 0.065052122, + -0.7598092 -0.6482662 0.049407013, + -0.712264 -0.69988197 0.053340901, + -0.71202195 -0.70061696 0.046483897, + -0.660541 -0.749143 0.049703501, + -0.66053385 -0.74902183 0.05158719, + -0.69138503 -0.72077906 0.049642008, + -0.69158608 -0.72121704 0.039429802, + -0.72601604 -0.68759006 0.010986101, + -0.72568065 -0.6870057 0.037559383, + -0.79290164 -0.60923368 0.011886694, + -0.7923528 -0.6084919 0.043756589, + -0.82305986 -0.56755793 0.021222997, + -0.82248217 -0.56691015 0.046217613, + -0.79449087 -0.60526794 0.049344692, + -0.79399151 -0.60456163 0.063895665, + -0.76853585 -0.63626295 0.067246296, + -0.76871914 -0.63701808 0.057261508, + -0.73471779 -0.67564875 0.060734078, + -0.73469383 -0.67552984 0.062324684, + -0.76208764 -0.64473569 0.059483469, + -0.76247281 -0.64535379 0.04640729, + -0.76055038 -0.6490413 0.017568408, + -0.760149 -0.64846498 0.040824801, + -0.72815806 -0.68405503 0.043065403, + -0.72787267 -0.68352669 0.054706175, + -0.69853097 -0.71329898 0.057089001, + -0.69854796 -0.71342397 0.055291593, + -0.74778593 -0.66195494 0.051302593, + -0.74799681 -0.66111779 0.058515284, + -0.79238665 -0.60764372 0.053782273, + -0.7932831 -0.60487807 0.069459207, + -0.82764328 -0.55759019 0.06402912, + -0.82957917 -0.54862612 0.10396102, + -0.85808885 -0.50452286 0.095604375, + -0.85880011 -0.49665606 0.12567902, + -0.88437539 -0.45251322 0.11450806, + -0.98660213 -0.16084902 0.027272904, + -0.99347347 -0.11245905 0.019068209, + -0.99355966 -0.11252796 0.013293396, + -0.99229246 -0.12391806 -0.00040594421, + -0.992284 -0.123985 -0.00040185999, + -0.99228233 -0.12398405 -0.0019659507, + -0.99229074 -0.12391597 -0.0019807196, + -0.94906479 -0.3150399 0.0050788084, + -0.9490605 -0.31505314 0.0050793625, + -0.94905686 -0.31504297 -0.0062483293, + -0.9490611 -0.31503004 -0.006253541, + -0.96340376 -0.26804495 0.0022653195, + -0.95252663 -0.30407888 -0.015133695, + -0.93249136 -0.36118111 0.0028368009, + -0.91352522 -0.4064281 -0.016966803, + -0.91362971 -0.40649286 0.0066514076, + -0.91363287 -0.40648594 0.0066511389, + -0.91362214 -0.40646905 -0.008814781, + -0.91625661 -0.40042081 -0.011709195, + -0.89259225 -0.45085412 0.0031309007, + -0.86936301 -0.49398199 -0.0137742, + -0.86941344 -0.49402824 0.0075076139, + -0.86938339 -0.49408123 0.0075091738, + -0.86935514 -0.49405107 -0.011626901, + -0.87022328 -0.49250019 -0.012447305, + -0.81673568 -0.57682383 -0.014732894, + -0.81496501 -0.57935798 -0.0132845, + -0.72370404 -0.69010603 0.0024564003, + -0.68866992 -0.72505093 -0.0059228889, + -0.68863696 -0.72502893 0.010591199, + -0.61418927 -0.78914928 -0.0038768414, + -0.61417806 -0.78914213 0.0063258708, + -0.61432207 -0.78903013 0.0063246707, + -0.61433327 -0.78903735 -0.003847532, + -0.5749197 -0.81820959 0.00049695378, + -0.57491511 -0.81820518 0.0036071609, + -0.56529164 -0.8247385 0.01586549, + -0.57496887 -0.81797981 0.017886296, + -0.57506704 -0.81810611 0.00049703603, + -0.53408706 -0.8454271 -0.0020583803, + -0.53398895 -0.84548891 -0.0020767497, + -0.53394514 -0.84542918 0.012329803, + -0.534042 -0.84536803 0.0123288, + -0.5199458 -0.85392773 0.021535693, + -0.49200812 -0.87059015 -0.00087851525, + -0.49190694 -0.87042987 0.019474398, + -0.49186876 -0.87045157 0.019474991, + -0.49196911 -0.8706122 -0.00085804425, + -0.51472813 -0.85719317 -0.016575504, + -0.60013908 -0.79973012 -0.016277602, + -0.57485801 -0.81825298 0.00053123001, + -0.57485408 -0.81824809 0.0036075304, + -0.61097503 -0.791565 0.01159, + -0.61087185 -0.79128182 0.026623594, + -0.5721119 -0.8197118 0.027580192, + -0.57206589 -0.8195048 0.033949394, + -0.53619307 -0.84337211 0.034938104, + -0.53617716 -0.84345531 0.033124711, + -0.59316313 -0.80446219 0.031593308, + -0.59343004 -0.8040241 0.037229605, + -0.64780706 -0.76098913 0.035236802, + -0.64779001 -0.76101297 0.0350332, + -0.60672998 -0.79406703 0.036554798, + -0.60620987 -0.79471982 0.030495392, + -0.54983687 -0.83465785 0.032027893, + -0.54958296 -0.83500791 0.026840895, + -0.49188411 -0.87021118 0.027972508, + -0.49176505 -0.87050915 0.019519001, + -0.4471758 -0.89430958 0.015626693, + -0.44723594 -0.89441586 -0.00055082195, + -0.44865173 -0.89370644 -0.00055024266, + -0.44859079 -0.89359856 0.015743092, + -0.44865274 -0.89356744 0.01574249, + -0.44871289 -0.89367574 -0.00054025691, + -0.42386121 -0.90557539 -0.016583208, + -0.32851985 -0.94440353 -0.013286693, + 0.65347308 -0.75685912 0.011715601, + 0.65348923 -0.7568453 0.011715304, + 0.65353495 -0.75688487 -0.0041511897, + 0.6535188 -0.75689882 -0.0041544889, + 0.75742972 -0.65291178 0.0025300591, + 0.7574451 -0.65289408 0.0025300703, + 0.75726479 -0.65275484 0.021475095, + 0.93953824 -0.31843108 0.12597503, + 0.99729335 -0.073508032 -0.0016444806, + 0.99728888 -0.073567092 -0.0016353398, + 0.99723464 -0.073555872 -0.010614696, + 0.99723899 -0.0734969 -0.0106158, + 0.9996745 -0.024539988 -0.0069709267, + 0.99967891 -0.024362896 -0.0069746091, + 0.99770051 -0.067399867 0.0071324366, + 0.99768788 -0.067391194 0.0087955091, + 0.99354249 -0.11250705 0.014683708, + 0.99333662 -0.11237296 0.025586192, + 0.98702335 -0.15657006 0.03564921, + 0.98653841 -0.15620591 0.048389971, + 0.97862524 -0.19644204 0.060854416, + 0.97864562 -0.19647193 0.060428377, + 0.97103864 -0.22836493 0.070237778, + 0.97127253 -0.2294229 0.063203871, + 0.96310562 -0.25945792 0.071478479, + 0.96312553 -0.25981489 0.069895171, + 0.95228177 -0.29474095 0.07929118, + 0.9520995 -0.29049385 0.095497854, + 0.93993211 -0.32428804 0.10660701, + 0.82316881 -0.56757289 0.015940497, + 0.7928651 -0.60897207 0.022758102, + 0.79224432 -0.60823125 0.049027417, + 0.76250386 -0.64489192 0.051982492, + 0.76240748 -0.64473635 0.055225935, + 0.73480296 -0.67580593 0.057887092, + 0.73476994 -0.67562497 0.060367193, + 0.76873887 -0.63702494 0.056918193, + 0.76864219 -0.63659418 0.062746413, + 0.79429215 -0.60460609 0.059593514, + 0.7944563 -0.60483724 0.054873418, + 0.82235116 -0.56665313 0.05140911, + 0.87022746 -0.49263969 0.0032166583, + 0.84847319 -0.52887112 0.019715006, + 0.84494358 -0.53472376 0.011863294, + 0.84495711 -0.53471404 -0.011337001, + 0.87018818 -0.49270913 0.0032042607, + 0.87014771 -0.49267483 -0.010702396, + 0.87018669 -0.49260584 -0.010702697, + 0.87014914 -0.49267107 -0.010762201, + 0.87019056 -0.49270475 0.0032166084, + 0.89327526 -0.44936311 -0.011497503, + 0.93493789 -0.34694096 0.074317396, + 0.93493986 -0.34660298 0.075853296, + 0.94560766 -0.31778789 0.069547474, + 0.94538224 -0.31652609 0.077869512, + 0.95541036 -0.28673208 0.070539825, + 0.9553051 -0.28657904 0.072558209, + 0.96674126 -0.24793306 0.062773615, + 0.96743286 -0.24843197 0.048531294, + 0.97805774 -0.20446895 0.039943088, + 0.97853339 -0.20473307 0.02359801, + 0.98715687 -0.15870298 0.018292397, + 0.99240822 -0.12232903 -0.012715803, + 0.99240965 -0.12231696 -0.012715995, + 0.98719037 -0.15871707 0.016252706, + 0.98519379 -0.17088695 -0.013816096, + 0.98520052 -0.17084792 -0.013816593, + 0.98528689 -0.17087099 -0.0035920094, + 0.98528022 -0.17091005 -0.003581201, + 0.93297291 -0.35968497 -0.013723898, + 0.86628383 -0.49387789 0.075079381, + 0.8662824 -0.49381423 0.07551384, + 0.88120401 -0.46730399 0.0714598, + 0.88101089 -0.46691296 0.07623639, + 0.89949685 -0.43121696 0.070408195, + 0.90004009 -0.43172505 0.059510309, + 0.91944087 -0.38954493 0.053695992, + 0.92016912 -0.39005405 0.033864602, + 0.93829012 -0.34455302 0.029914305, + 0.93849689 -0.34467396 0.020577699, + 0.94947588 -0.31353596 -0.013810799, + 0.94948936 -0.31349513 -0.013811205, + 0.94957262 -0.31353489 0.002761069, + 0.94955909 -0.31357604 0.0027514102, + 0.93291837 -0.35966113 -0.017527405, + 0.93565822 -0.35272208 -0.011439803, + 0.9330551 -0.35963702 -0.0083401408, + 0.93300098 -0.35961199 -0.0137246, + 0.92015886 -0.39101794 0.020311799, + 0.91991466 -0.39086285 0.031354688, + 0.89949888 -0.43552393 0.034937296, + 0.89879102 -0.434986 0.054423898, + 0.87730789 -0.47621495 0.059582394, + 0.87686533 -0.47576219 0.068974525, + 0.85647798 -0.51084298 0.074060403, + 0.85666031 -0.51126719 0.068840124, + 0.8402307 -0.5373798 0.072356075, + 0.84022886 -0.53744692 0.071876891, + 0.87499416 -0.47986111 0.064175613, + 0.87527698 -0.47810799 0.072822101, + 0.89746475 -0.43605691 0.066417187, + 0.8974613 -0.43608314 0.066293523, + 0.96759665 -0.25169292 0.020185793, + 0.967489 -0.25164101 0.0253345, + 0.9542765 -0.29742184 0.029943686, + 0.95360762 -0.29702088 0.04910228, + 0.93856591 -0.34047896 0.056286592, + 0.93787414 -0.33992904 0.069573708, + 0.922773 -0.377518 0.077266999, + 0.92294723 -0.3778041 0.073705211, + 0.91055822 -0.4057321 0.079153821, + 0.91069669 -0.40708485 0.070095778, + 0.88969499 -0.44993401 0.077473901, + 0.88969111 -0.44988006 0.077832006, + 0.90323001 -0.42287499 0.073159799, + 0.90303957 -0.42252979 0.077383362, + 0.91983289 -0.38589194 0.070673496, + 0.92046237 -0.38643315 0.058468822, + 0.93777001 -0.34334901 0.051950201, + 0.93848687 -0.34381098 0.032194395, + 0.95413023 -0.29808807 0.027913107, + 0.95445812 -0.29829603 0.0054090503, + 0.94889712 -0.31333503 0.037621904, + 0.94957399 -0.31353101 0.0027610699, + 0.96380377 -0.26654893 -0.0058219787, + 0.96373177 -0.26652294 -0.013663197, + 0.96373361 -0.26651591 -0.013663296, + 0.9638055 -0.26654312 -0.0058244229, + 0.96691978 -0.25462595 -0.015220596, + 0.97570914 -0.21906003 0.0020901302, + 0.97562265 -0.21902692 -0.013697595, + 0.97564536 -0.21892607 -0.013698905, + 0.97573179 -0.21895894 0.0021207395, + 0.97572386 -0.21899398 0.0021207097, + 0.97523713 -0.21890803 0.031493604, + 0.978652 -0.205318 0.0092105102, + 0.97846574 -0.20521896 0.022135094, + 0.96759135 -0.25106508 0.027080009, + 0.96700412 -0.25073004 0.045140304, + 0.95420951 -0.29440615 0.053003527, + 0.95349425 -0.29386905 0.067006618, + 0.94023538 -0.33200413 0.075702131, + 0.9403801 -0.33222604 0.07287731, + 0.9291051 -0.36122704 0.079239011, + 0.92929542 -0.36255017 0.070479237, + 0.91746336 -0.39051014 0.075914532, + 0.91750813 -0.38889506 0.083304606, + 0.92052025 -0.38378409 0.073160313, + 0.90123326 -0.4256691 0.08114472, + 0.90142858 -0.4254868 0.079921365, + 0.87786824 -0.47067112 0.088408619, + 0.87705344 -0.47614571 0.063737065, + 0.85022599 -0.52176398 0.069843799, + 0.84986442 -0.52342325 0.061308231, + 0.8118701 -0.57987404 0.067920208, + 0.811876 -0.57980299 0.068453804, + 0.8295511 -0.55457908 0.065475807, + 0.82939088 -0.55413693 0.071013391, + 0.85174215 -0.51971108 0.066601709, + 0.85208315 -0.52009708 0.058765307, + 0.87581015 -0.47960407 0.054190107, + 0.87646788 -0.48015293 0.035457596, + 0.89918178 -0.43638691 0.032225594, + 0.8994481 -0.43657407 0.019908102, + 0.91421741 -0.40502816 -0.012602706, + 0.91422856 -0.40500283 -0.012602895, + 0.9142133 -0.40503615 -0.012636905, + 0.91427726 -0.4050771 0.0031337508, + 0.91429186 -0.40504393 0.0031337696, + 0.91428077 -0.4050689 0.0031288592, + 0.89324403 -0.44934499 -0.0142902, + 0.89442527 -0.44704914 -0.012268905, + 0.89332944 -0.4492642 -0.011150805, + 0.8933261 -0.44926205 -0.011498, + 0.87636322 -0.48128211 0.018847505, + 0.87608159 -0.48106277 0.032554187, + 0.85092598 -0.52408701 0.035465799, + 0.85033798 -0.52354598 0.0531509, + 0.82433802 -0.56320298 0.057176899, + 0.82409167 -0.56289279 0.063439779, + 0.80009389 -0.59610093 0.067182496, + 0.8002249 -0.59654397 0.061443493, + 0.78121632 -0.62097526 0.063960023, + 0.7812053 -0.62104625 0.063403822, + 0.82232744 -0.56607229 0.057791427, + 0.82276118 -0.56451911 0.066197813, + 0.8521502 -0.51973611 0.060946416, + 0.85323811 -0.51435304 0.086173207, + 0.8796351 -0.46911106 0.078593507, + 0.8803221 -0.46213207 0.10708401, + 0.90175575 -0.4210889 0.097573876, + 0.90523589 -0.40956995 0.11313899, + 0.92079157 -0.37597382 0.10385895, + 0.92374474 -0.3667379 0.11044897, + 0.9375211 -0.33314803 0.10033301, + 0.937594 -0.33811301 0.081222698, + 0.95017678 -0.30308893 0.072809182, + 0.95016664 -0.30273187 0.074409373, + 0.95956564 -0.2733489 0.067187279, + 0.95932525 -0.27217507 0.074938312, + 0.96812576 -0.24147893 0.066486686, + 0.96806449 -0.24139112 0.067687526, + 0.97772664 -0.20208792 0.05666668, + 0.97834152 -0.20252791 0.04278088, + 0.98685449 -0.15812208 0.033400916, + 0.98719674 -0.15831695 0.019448197, + 0.99352276 -0.11278497 0.013854897, + 0.99357253 -0.11281095 0.0093449457, + 0.99232852 -0.12227094 0.018274391, + 0.99249536 -0.12227704 0.0011925604, + 0.99248636 -0.12235004 0.0011925105, + 0.99248791 -0.12233698 0.0011975499, + 0.98796654 -0.15386693 -0.015718192, + 0.84370971 -0.53663981 -0.013100895, + 0.84497881 -0.53461087 -0.014217597, + 0.84499484 -0.53464288 0.011860698, + 0.81741917 -0.57538712 0.027489807, + 0.81773371 -0.57558882 0.0030265888, + 0.81778157 -0.57552069 0.0030266386, + 0.81771618 -0.57548213 0.012669703, + 0.81762558 -0.5756107 0.012673395, + 0.81769085 -0.57564986 0.0030031693, + 0.78853279 -0.61493188 -0.0086488277, + 0.78848213 -0.61491108 0.013429902, + 0.78851497 -0.614869 0.0134288, + 0.78847682 -0.61481386 -0.017558597, + 0.78404152 -0.62054664 -0.014168192, + 0.71607322 -0.69785225 -0.015533705, + 0.64052492 -0.76776689 -0.016176699, + 0.61542386 -0.78819585 0.00084865384, + 0.61110574 -0.79140371 0.015163395, + 0.61095387 -0.79104179 0.031438693, + 0.5724529 -0.81929082 0.032561392, + 0.57246989 -0.81936282 0.030376792, + 0.5293352 -0.8478303 0.031432111, + 0.52935201 -0.84792799 0.028364301, + 0.56952703 -0.82151312 0.027480803, + 0.56961787 -0.82176483 0.015430696, + 0.57620615 -0.81730115 -0.0023208605, + 0.57619613 -0.81730819 -0.0023228906, + 0.57618201 -0.81729603 0.0064413399, + 0.57619202 -0.81728899 0.00644125, + 0.61549199 -0.787956 0.0171763, + 0.61558902 -0.78806698 0.00074033602, + 0.61561096 -0.78804988 0.00074034987, + 0.61558187 -0.78801984 0.0091559282, + 0.61539596 -0.78816485 0.0091581689, + 0.65091777 -0.75897872 0.016038995, + 0.65068978 -0.75851971 0.035364188, + 0.61385399 -0.78856301 0.036764901, + 0.61386901 -0.78861499 0.035373401, + 0.57950395 -0.81415087 0.036518797, + 0.5795151 -0.81406617 0.038192008, + 0.63472009 -0.77189314 0.036213502, + 0.63500321 -0.7713353 0.042576917, + 0.68718618 -0.7253772 0.040040113, + 0.68776375 -0.72439277 0.04728708, + 0.72758335 -0.68456233 0.044687022, + 0.72958523 -0.68022925 0.070665821, + 0.76681787 -0.63842893 0.066323295, + 0.76897019 -0.63116819 0.10154602, + 0.80293489 -0.58849895 0.094681785, + 0.80426139 -0.58041531 0.12760006, + 0.83498818 -0.5374341 0.11815003, + 0.83559531 -0.52860719 0.14951606, + 0.83810383 -0.52042788 0.16351396, + 0.83786571 -0.52753383 0.14031796, + 0.80751586 -0.57002592 0.15161999, + 0.8066079 -0.57906795 0.11859199, + 0.7730338 -0.62146586 0.12727498, + 0.77136582 -0.6296038 0.092702478, + 0.73450398 -0.67136598 0.098851599, + 0.7320022 -0.67845321 0.062242515, + 0.69245702 -0.71844202 0.065911204, + 0.69031405 -0.72240406 0.039985705, + 0.64836079 -0.76016968 0.042075984, + 0.64778924 -0.76100427 0.035238013, + 0.59340996 -0.80403888 0.037230697, + 0.59313011 -0.80449718 0.031320609, + 0.53624594 -0.84342289 0.032836094, + 0.53615987 -0.84373283 0.025446594, + 0.48530406 -0.8739481 0.026357904, + 0.48530975 -0.87400657 0.024227088, + 0.52643687 -0.84988785 0.023558494, + 0.52648592 -0.85005391 0.014863398, + 0.49337205 -0.86981809 -0.00076561613, + 0.49335995 -0.86982489 -0.00076777587, + 0.49335799 -0.86982399 0.0020409999, + 0.49337006 -0.86981714 0.0020409303, + 0.53681493 -0.84348488 0.019052098, + 0.53691882 -0.84363371 -0.00057203177, + 0.53542292 -0.84458387 -0.00057280192, + 0.53541815 -0.84457833 0.0038571814, + 0.53538024 -0.84460241 0.0038574419, + 0.53538501 -0.84460801 -0.00055231299, + 0.55817014 -0.82956219 -0.016514704, + 0.46990982 -0.8825587 -0.016577994, + 0.45016605 -0.89294213 -0.0022305301, + 0.45010021 -0.89297539 -0.0021953608, + 0.45010006 -0.89297813 0.00042034805, + 0.45016715 -0.89294428 0.00042009415, + 0.48253807 -0.87575811 0.014308902, + 0.48251581 -0.87566268 0.019834792, + 0.44049093 -0.89752686 0.020330098, + 0.4404912 -0.89749742 0.021587912, + 0.49183875 -0.87043458 0.02093699, + 0.49193224 -0.87019241 0.027712412, + 0.54957205 -0.83502311 0.026592404, + 0.54983813 -0.83465719 0.032020807, + 0.60620886 -0.79472083 0.030488692, + 0.60675913 -0.79402816 0.036914408, + 0.650967 -0.75828701 0.035252798, + 0.6532017 -0.75471961 0.061039869, + 0.69495499 -0.71671301 0.057966001, + 0.69776499 -0.70989001 0.095813297, + 0.7370078 -0.66981083 0.09040378, + 0.73900878 -0.66169477 0.12659396, + 0.77549183 -0.62011087 0.11863797, + 0.77670503 -0.61094701 0.153209, + 0.8099277 -0.56891382 0.14266795, + 0.81039488 -0.55894494 0.17561498, + -0.35266092 -0.93569076 0.010627598, + -0.74935794 -0.63907892 0.17332299, + -0.71098596 -0.67868894 0.18406598, + -0.70968801 -0.68910098 0.14657, + -0.66866094 -0.72729796 0.15469399, + -0.41203278 -0.91099161 0.01797829, + -0.47077799 -0.88208002 0.0174077, + -0.47116882 -0.88176471 0.022159992, + -0.52026397 -0.85373586 0.021455599, + -0.52239275 -0.85149461 0.045416079, + -0.57032216 -0.82025528 0.043749914, + -0.57369912 -0.81471616 0.084302925, + -0.6200161 -0.78042215 0.080754325, + -0.62284297 -0.77288187 0.12132698, + -0.66658002 -0.73641503 0.115603, + -0.66388518 -0.73765719 0.12295703, + -0.70514524 -0.69941324 0.11658204, + -0.7069788 -0.69017982 0.15437897, + -0.74560606 -0.65031707 0.14546202, + -0.74664384 -0.63996279 0.18157795, + -0.7824977 -0.59900874 0.16995794, + -0.78279752 -0.59037262 0.19669288, + -0.749874 -0.627662 0.209116, + 0.279466 -0.96006298 -0.0133356, + 0.31420401 -0.94934797 -0.0037928501, + 0.31429797 -0.94931686 -0.0037929595, + 0.30034807 -0.95378923 0.0087814517, + 0.30130306 -0.95347524 0.010070203, + 0.30130205 -0.95347923 0.0097162714, + 0.35326281 -0.93547559 0.0095327953, + 0.35333911 -0.93538433 0.014410205, + 0.4118498 -0.9111436 0.014036694, + 0.41203406 -0.91099113 0.017975302, + 0.47077683 -0.88208067 0.017404795, + 0.47118416 -0.8817513 0.022365008, + 0.52030689 -0.85370481 0.021653594, + 0.52251983 -0.85135072 0.046636984, + 0.57046515 -0.8200922 0.044924609, + 0.57384795 -0.81445289 0.085820094, + 0.62024468 -0.78008962 0.082199059, + 0.62302071 -0.77256763 0.12241094, + 0.66680402 -0.73605102 0.116625, + 0.66883975 -0.72700179 0.15531194, + 0.70985699 -0.68880302 0.14715099, + 0.7111302 -0.67840821 0.18454304, + 0.74948901 -0.63880402 0.173769, + 0.74998784 -0.6273728 0.20957495, + 0.78289717 -0.59009713 0.19712305, + 0.78261113 -0.59873503 0.17040001, + 0.74676019 -0.63969117 0.18205604, + 0.74574506 -0.65002704 0.14604501, + 0.70712209 -0.68989307 0.15500301, + 0.70533264 -0.69905162 0.11761194, + 0.66406727 -0.73731035 0.12404906, + 0.66149974 -0.74510676 0.085052967, + 0.61755276 -0.78145468 0.089202069, + 0.61428708 -0.78755009 0.049156606, + 0.56786799 -0.82152098 0.051276799, + 0.56560093 -0.82426888 0.026006795, + 0.51769298 -0.85514098 0.026980899, + 0.5172292 -0.85557628 0.021521507, + 0.45909512 -0.88810623 0.022339806, + 0.45887813 -0.88831925 0.017883005, + 0.40050992 -0.91610676 0.018442396, + 0.40042293 -0.9162389 0.012950098, + 0.34809488 -0.93736565 0.013248695, + 0.34808403 -0.93741113 0.0099005606, + 0.40585691 -0.91393578 -0.0012206997, + 0.40576115 -0.91397828 -0.0012204505, + 0.36041892 -0.93278176 -0.0040341089, + 0.36047411 -0.93276036 -0.0040638014, + 0.36047488 -0.93276465 -0.0028261691, + 0.36041996 -0.93278587 -0.0028260797, + 0.39221907 -0.91979313 0.012033902, + 0.39221781 -0.91978157 0.012924094, + 0.34575212 -0.93823338 0.013183405, + 0.34575409 -0.93826222 0.010868003, + 0.314325 -0.94930798 -0.0037688101, + 0.31432596 -0.94931388 0.0014956797, + 0.31420499 -0.94935399 0.00149565, + 0.31429896 -0.94932288 0.0015041898, + 0.26728609 -0.96337038 -0.021811908, + 0.26734406 -0.96360022 0.0013840804, + 0.26733798 -0.96360189 0.0013840899, + 0.26733398 -0.96358389 -0.006216439, + 0.17926492 -0.98370552 -0.013693693, + 0.074272208 -0.99723715 -0.0013531301, + 0.074264795 -0.99712688 -0.014922398, + 0.077161416 -0.99692625 -0.013572503, + 0.074302405 -0.9971711 -0.011362001, + 0.074306563 -0.99723452 -0.0013531293, + -0.12324799 -0.9923749 0.0014159299, + -0.174687 -0.98462301 0.0014048601, + -0.1755219 -0.98421341 0.022713287, + -0.22815397 -0.9733659 0.022462899, + -0.23018298 -0.9709239 0.065745592, + -0.28347915 -0.95678747 0.064788327, + -0.28570291 -0.95199966 0.10986596, + -0.33935091 -0.93445778 0.10784098, + -0.34149608 -0.92746222 0.15229703, + -0.39522991 -0.90644276 0.14884497, + -0.39714983 -0.89724159 0.19294991, + -0.45053595 -0.87280488 0.18769397, + -0.45205799 -0.86154401 0.23105299, + -0.5039019 -0.83427984 0.22374094, + -0.50487924 -0.8210634 0.26636812, + -0.55488575 -0.79132563 0.25672087, + -0.5552119 -0.77837783 0.29303193, + -0.50815111 -0.80604118 0.30344707, + -0.50773412 -0.82097816 0.26115307, + -0.45572415 -0.8482393 0.2698251, + -0.45470014 -0.86137831 0.22644007, + -0.40107006 -0.88594609 0.23290002, + -0.39958614 -0.89702427 0.18888707, + -0.34540692 -0.91831475 0.19336995, + -0.34362796 -0.9272269 0.14889598, + -0.28941706 -0.94509524 0.15176603, + -0.28751794 -0.95176977 0.10708698, + -0.23356511 -0.96624446 0.10871606, + -0.23168907 -0.97071522 0.063500017, + -0.17829606 -0.98187834 0.064230226, + -0.17669806 -0.98404038 0.021032207, + -0.124732 -0.99196398 0.021201501, + -0.12414304 -0.99226433 0.00028811712, + -0.073583402 -0.997289 0.00028957601, + 0.027817607 -0.92860126 0.37003508, + 0.027798695 -0.91040289 0.41278794, + -0.027290912 -0.91041541 0.4127942, + -0.027303591 -0.92869663 0.36983389, + 0.02762411 -0.92868835 0.36983112, + 0.027605604 -0.94487214 0.32627404, + -0.027099499 -0.94488502 0.32627901, + -0.0271248 -0.92862499 0.37002701, + -0.082668997 -0.92578697 0.36889601, + -0.08262001 -0.90754712 0.41174304, + -0.027491214 -0.91031641 0.41299921, + -0.027438616 -0.88991153 0.45530728, + 0.027954491 -0.88989872 0.45530084, + 0.028012987 -0.91029656 0.4130078, + 0.083080694 -0.90750587 0.41174093, + 0.083135396 -0.92574489 0.36889696, + -0.026383709 -0.97090334 0.23801409, + -0.080360621 -0.96810025 0.23732705, + -0.080642402 -0.95598298 0.282123, + -0.13606697 -0.95018679 0.28041193, + -0.13635406 -0.93572342 0.32531413, + -0.19298796 -0.92678887 0.32220796, + -0.19311491 -0.91078657 0.36493081, + -0.13744093 -0.91945058 0.36840281, + -0.13733996 -0.93598878 0.3241339, + -0.08141274 -0.9418065 0.32614815, + -0.081237227 -0.95613837 0.28142509, + -0.026704704 -0.95896709 0.28225702, + -0.026606906 -0.97096026 0.23775706, + 0.027060613 -0.97094846 0.23775412, + 0.027149197 -0.95895189 0.28226596, + 0.081700765 -0.9560985 0.28142586, + 0.081871219 -0.94174325 0.3262161, + 0.13780798 -0.93589985 0.32419196, + 0.13790095 -0.91982561 0.36729288, + 0.082533091 -0.9255299 0.36957097, + 0.082475096 -0.94192988 0.32552397, + 0.027387587 -0.94479555 0.32651386, + 0.027333695 -0.95900786 0.28205797, + -0.026878295 -0.9590199 0.28206098, + -0.026940703 -0.94482911 0.32645404, + -0.082003005 -0.94198912 0.32547203, + -0.082065694 -0.92557186 0.36956996, + -0.13842602 -0.91976315 0.36725202, + -0.13833997 -0.90161777 0.40981391, + -0.083218068 -0.90721369 0.41235685, + -0.083053477 -0.88707274 0.45409688, + -0.0276289 -0.88980901 0.45549601, + -0.027534992 -0.86716068 0.49726683, + 0.028062107 -0.86714816 0.49725911, + 0.028161591 -0.88978672 0.45550686, + 0.083557889 -0.88702691 0.45409393, + 0.083727993 -0.90714389 0.41240695, + 0.13883296 -0.90152472 0.40985185, + 0.13892606 -0.9192344 0.36838517, + 0.19356903 -0.91068012 0.36495602, + 0.19344808 -0.92667139 0.32227013, + 0.13680995 -0.93563157 0.32538685, + 0.136531 -0.95011199 0.28044, + 0.081076667 -0.95593566 0.28215891, + 0.080804177 -0.96805274 0.23736994, + 0.026791597 -0.97087985 0.23806398, + 0.026669813 -0.98071247 0.19362809, + -0.026252709 -0.98072338 0.19363007, + -0.026107991 -0.98069364 0.19379993, + -0.079413973 -0.97792965 0.19325392, + -0.079794891 -0.96798086 0.23800397, + -0.13462698 -0.96223688 0.23659196, + -0.13509105 -0.94997233 0.28160807, + -0.19127293 -0.94105965 0.27896491, + -0.19165708 -0.92648333 0.32387713, + -0.24865206 -0.91433525 0.31963009, + -0.24879187 -0.89844257 0.36180583, + -0.19449295 -0.90989578 0.36641791, + -0.19436008 -0.89252329 0.40697214, + -0.13932903 -0.90099925 0.4108381, + -0.13905002 -0.88117713 0.45187607, + -0.083667397 -0.886702 0.45470801, + -0.083379865 -0.86435258 0.49592575, + -0.027742404 -0.86703914 0.49746707, + -0.02760721 -0.84249127 0.53800219, + 0.028148808 -0.84247917 0.53799313, + 0.028289191 -0.86701471 0.49747881, + 0.083895281 -0.86430383 0.49592388, + 0.084188037 -0.88664544 0.4547222, + 0.13955399 -0.88109702 0.451877, + 0.13983704 -0.90089631 0.41089115, + 0.19486503 -0.89239413 0.40701407, + 0.195004 -0.909751 0.36650601, + 0.24922697 -0.89828891 0.36188796, + 0.24909499 -0.91417402 0.31974599, + 0.19206508 -0.92635334 0.32400712, + 0.19168991 -0.94095254 0.27903989, + 0.13551103 -0.94988823 0.28169006, + 0.13505603 -0.96216524 0.23663905, + 0.08023078 -0.96793175 0.23805694, + 0.079859503 -0.97788799 0.19328099, + 0.026495796 -0.98067689 0.19383197, + 0.026344404 -0.98839611 0.14959702, + -0.025950106 -0.98840624 0.14959903, + -0.025749905 -0.98837525 0.14983803, + -0.078364737 -0.98566246 0.14942707, + -0.078835167 -0.97783667 0.19395992, + -0.13305892 -0.97216743 0.19283588, + -0.13368604 -0.96207821 0.23776805, + -0.18927602 -0.95324409 0.23558503, + -0.18990704 -0.94081521 0.28071705, + -0.24644712 -0.92869741 0.27710113, + -0.24691197 -0.91400087 0.32192698, + -0.30350903 -0.8987121 0.31654203, + -0.30364195 -0.88297975 0.3579779, + -0.25054595 -0.89717579 0.36373392, + -0.25036004 -0.8801831 0.40323406, + -0.19576102 -0.89154613 0.40844005, + -0.19536997 -0.87213486 0.44856593, + -0.140045 -0.88050801 0.45287201, + -0.139566 -0.85854101 0.49338499, + -0.083977096 -0.8639639 0.49650195, + -0.083566919 -0.83973718 0.53652412, + -0.027817808 -0.84235919 0.53819811, + -0.027638707 -0.81588018 0.57756013, + 0.028195197 -0.81586689 0.57755196, + 0.028379304 -0.84233409 0.53820807, + 0.08406195 -0.83969051 0.53651971, + 0.084476367 -0.8639257 0.49648383, + 0.14008102 -0.8584761 0.49335206, + 0.14056401 -0.8804161 0.45289007, + 0.19583891 -0.87202561 0.4485738, + 0.19623609 -0.89143741 0.4084492, + 0.2508001 -0.88005728 0.40323514, + 0.25099307 -0.89701223 0.36382908, + 0.304066 -0.88279903 0.358064, + 0.30393907 -0.89853722 0.3166261, + 0.24737412 -0.91384339 0.32201916, + 0.24691808 -0.92856133 0.27713808, + 0.19034591 -0.94071251 0.28076389, + 0.18972391 -0.95313251 0.23567589, + 0.13407296 -0.96199965 0.23786791, + 0.13345604 -0.97209322 0.19293605, + 0.079216599 -0.97778499 0.194065, + 0.07875213 -0.98562336 0.14948206, + 0.026093706 -0.98835725 0.14989702, + 0.025910605 -0.99404424 0.10585202, + -0.025568396 -0.99405289 0.10585398, + -0.025430191 -0.99403864 0.10602096, + -0.077292658 -0.9913854 0.10573894, + -0.077843674 -0.98560566 0.15007295, + -0.13135396 -0.98003966 0.14922594, + -0.13213305 -0.97205937 0.19401407, + -0.18711101 -0.96333802 0.192274, + -0.18797404 -0.9530791 0.23728903, + -0.24400197 -0.94104689 0.23429397, + -0.24478206 -0.92846423 0.27934906, + -0.30094305 -0.91320425 0.27475706, + -0.30146199 -0.89839202 0.31939399, + -0.35735407 -0.88001025 0.31285807, + -0.35746381 -0.86447859 0.35340682, + -0.30569914 -0.88132644 0.36029419, + -0.30545017 -0.86476755 0.39859423, + -0.25209004 -0.87884015 0.40508106, + -0.25158405 -0.85990417 0.44415113, + -0.19672804 -0.87111914 0.44994405, + -0.19606297 -0.84960389 0.48962495, + -0.14056903 -0.85781717 0.49435812, + -0.13989204 -0.83403128 0.53368717, + -0.084158979 -0.83932585 0.53707486, + -0.083625272 -0.81321073 0.57592982, + -0.027827309 -0.81575328 0.57773018, + -0.027606303 -0.7873171 0.61593008, + 0.02817939 -0.7873047 0.61591977, + 0.028405193 -0.8157258 0.57774091, + 0.084167868 -0.8131597 0.57592285, + 0.084705897 -0.83924198 0.53711998, + 0.14043306 -0.83392245 0.53371525, + 0.14111708 -0.85772842 0.49435624, + 0.19657205 -0.84949416 0.48961112, + 0.19724192 -0.87097555 0.4499968, + 0.25202999 -0.85974997 0.444197, + 0.25254303 -0.87870413 0.40509406, + 0.30586585 -0.86461759 0.39860082, + 0.30612203 -0.88114411 0.36038104, + 0.35785082 -0.8642866 0.35348481, + 0.35775003 -0.87979913 0.31299904, + 0.30184087 -0.89820969 0.31954888, + 0.30132988 -0.91303569 0.2748929, + 0.245171 -0.92831802 0.27949399, + 0.24440201 -0.94090903 0.234431, + 0.18838093 -0.95296264 0.23743391, + 0.18752892 -0.96323162 0.19239992, + 0.13250402 -0.97198212 0.19414803, + 0.13173206 -0.97997147 0.14934108, + 0.078179389 -0.98556089 0.15019199, + 0.077627227 -0.99134839 0.10584204, + 0.02568499 -0.99402064 0.10612796, + 0.025465604 -0.99777514 0.061613806, + -0.02522371 -0.99778134 0.061614223, + -0.025115391 -0.99777561 0.061749477, + -0.076126017 -0.99519426 0.061589815, + -0.0767617 -0.991355 0.106409, + -0.12950803 -0.98591524 0.10582502, + -0.13042803 -0.97998023 0.15042403, + -0.18474196 -0.97140974 0.14910898, + -0.18581694 -0.96324265 0.19399893, + -0.24127306 -0.95135427 0.19160505, + -0.24234594 -0.94090474 0.23657294, + -0.29805699 -0.925735 0.232759, + -0.29895607 -0.91300124 0.27758607, + -0.35447687 -0.89462972 0.27199993, + -0.35502192 -0.87972474 0.31629691, + -0.41019499 -0.85821301 0.30856201, + -0.41025707 -0.84291309 0.34811902, + -0.35983011 -0.86236727 0.35615313, + -0.3595092 -0.84630847 0.39308423, + -0.30750304 -0.86300111 0.40083805, + -0.30687904 -0.84459114 0.43873805, + -0.25331998 -0.8584649 0.44594494, + -0.25247398 -0.83749586 0.48462093, + -0.19745199 -0.84849602 0.49098599, + -0.19651604 -0.82524115 0.52948904, + -0.14090198 -0.83325589 0.53463197, + -0.14002201 -0.80764014 0.57281005, + -0.084209323 -0.81277817 0.57645512, + -0.083545335 -0.78471535 0.61420029, + -0.0278216 -0.78716397 0.61611599, + -0.027553987 -0.75668162 0.65320271, + 0.028115984 -0.75666952 0.65319258, + 0.028387308 -0.78715616 0.61610013, + 0.084098294 -0.78468388 0.61416495, + 0.084763937 -0.81271839 0.57645828, + 0.14051703 -0.80756116 0.5728001, + 0.1414009 -0.83317852 0.5346207, + 0.197006 -0.82514101 0.52946299, + 0.19794704 -0.84839618 0.49095911, + 0.252931 -0.83737999 0.48458299, + 0.25377986 -0.85829747 0.44600573, + 0.30734393 -0.8443988 0.43878287, + 0.30797294 -0.8628028 0.40090391, + 0.35990009 -0.84611219 0.39314908, + 0.3602289 -0.86216283 0.35624492, + 0.4106051 -0.84270716 0.34820709, + 0.41055015 -0.85799032 0.30870911, + 0.35540792 -0.87951279 0.31645292, + 0.35487282 -0.8944276 0.27214789, + 0.29932693 -0.91283077 0.27774695, + 0.29843903 -0.92556912 0.23292904, + 0.242716 -0.94076401 0.236753, + 0.24165297 -0.95121789 0.19180296, + 0.18617405 -0.96313226 0.19420505, + 0.18510605 -0.97131437 0.14927906, + 0.13075902 -0.97990912 0.15060002, + 0.12984002 -0.9858461 0.10606202, + 0.076986574 -0.99131167 0.10664997, + 0.076335035 -0.99516749 0.06176313, + 0.025217306 -0.99776226 0.061924115, + 0.024979604 -0.99950111 0.019329201, + -0.024895806 -0.99950325 0.019329203, + -0.024740506 -0.99950325 0.019525304, + -0.074959926 -0.99699634 0.019476308, + -0.075643606 -0.99519211 0.062215608, + -0.12758501 -0.98989511 0.061884508, + -0.12865095 -0.98590565 0.10695297, + -0.18222706 -0.97752136 0.10604404, + -0.18350092 -0.97138554 0.15078993, + -0.23828012 -0.95970249 0.14897607, + -0.23963097 -0.95130289 0.19390696, + -0.29481611 -0.93630135 0.19084908, + -0.29607007 -0.92564225 0.23564605, + -0.35121709 -0.90735322 0.23099107, + -0.35219812 -0.89447832 0.2754361, + -0.40708995 -0.87293887 0.26880398, + -0.40762606 -0.85798115 0.31258503, + -0.46169713 -0.83344716 0.30364707, + -0.46169189 -0.81843984 0.3420479, + -0.41282779 -0.8403706 0.35121283, + -0.41242424 -0.82487446 0.38663724, + -0.361797 -0.84412903 0.39566299, + -0.36105809 -0.82629019 0.43229809, + -0.30891815 -0.84272242 0.4408952, + -0.30790088 -0.82240772 0.47837481, + -0.25414908 -0.83601928 0.48629218, + -0.25296906 -0.8133682 0.5238691, + -0.19787605 -0.82408917 0.53077513, + -0.19666597 -0.79907387 0.56815791, + -0.14099398 -0.80684888 0.57368594, + -0.13990402 -0.77928913 0.61084807, + -0.084154576 -0.7842378 0.6147269, + -0.083358809 -0.7542001 0.65133208, + -0.027737891 -0.75654268 0.65335578, + -0.027427288 -0.72454864 0.68867767, + 0.028009608 -0.72453725 0.68866622, + 0.028321199 -0.75651401 0.653364, + 0.08390858 -0.75414884 0.65132082, + 0.084708571 -0.78420568 0.61469173, + 0.14044395 -0.77923369 0.61079478, + 0.14153592 -0.80673063 0.57371873, + 0.19718893 -0.79893368 0.56817383, + 0.19840209 -0.82395744 0.53078324, + 0.25346187 -0.81321758 0.52386475, + 0.254648 -0.83586401 0.48629799, + 0.30834812 -0.82224232 0.47837117, + 0.30936897 -0.84254086 0.44092593, + 0.3614811 -0.82609415 0.43231907, + 0.36222404 -0.84389609 0.39576906, + 0.4128001 -0.8246392 0.38673809, + 0.41320914 -0.8401283 0.35134411, + 0.4620502 -0.81818742 0.34216815, + 0.46206501 -0.83318502 0.30380699, + 0.40796095 -0.8577559 0.31276596, + 0.407435 -0.872715 0.26900801, + 0.35254812 -0.89427328 0.27565408, + 0.35157898 -0.90716588 0.23117597, + 0.29643485 -0.9254756 0.23584189, + 0.29519504 -0.93614113 0.19104902, + 0.24000292 -0.95116663 0.19411492, + 0.23866406 -0.95956624 0.14923903, + 0.18378896 -0.97128874 0.15106197, + 0.18251905 -0.97742522 0.10642702, + 0.12886605 -0.98583537 0.10734203, + 0.12778807 -0.98984945 0.062196732, + 0.075743482 -0.99516475 0.062530681, + 0.075041518 -0.99698824 0.019577205, + 0.024744105 -0.99950111 0.019626603, + 0.024627989 -0.99969655 -0.00053625577, + -0.024627989 -0.99969655 -0.00053625577, + -0.024442406 -0.99970126 -0.00031924609, + -0.074085295 -0.99725187 -0.00031846296, + -0.074433506 -0.99702209 0.020166002, + -0.12556703 -0.99188226 0.020062106, + -0.12671196 -0.98993278 0.063065387, + -0.1794849 -0.98177052 0.062545367, + -0.18096894 -0.97756565 0.10777596, + -0.23508406 -0.96612126 0.10651402, + -0.23668788 -0.95974153 0.15124492, + -0.29130995 -0.94496673 0.14891697, + -0.29289585 -0.9363206 0.19368991, + -0.34759399 -0.91820502 0.189942, + -0.34898382 -0.90733361 0.23442689, + -0.40352494 -0.88587791 0.22888397, + -0.40454915 -0.87285727 0.27287409, + -0.45844483 -0.84823871 0.26517791, + -0.45893878 -0.83328056 0.30825084, + -0.51108682 -0.80613971 0.29820988, + -0.51099485 -0.79144579 0.3354069, + -0.46447989 -0.81538481 0.34555191, + -0.46398783 -0.80048168 0.37939987, + -0.41501293 -0.82214588 0.38966694, + -0.41415995 -0.80497891 0.42482993, + -0.36338198 -0.82393688 0.43483493, + -0.36220703 -0.8043431 0.47099707, + -0.30991086 -0.82045257 0.48042977, + -0.30850199 -0.79849899 0.51693898, + -0.25468987 -0.81176162 0.52552474, + -0.25317097 -0.7874499 0.56198496, + -0.19803791 -0.79784662 0.56940472, + -0.19653909 -0.77094138 0.60582328, + -0.14090209 -0.77843249 0.61171037, + -0.13959302 -0.74897408 0.64772809, + -0.083952308 -0.75370914 0.65182406, + -0.083031923 -0.72214717 0.68673819, + -0.027649293 -0.72437185 0.68885481, + -0.027299199 -0.69088399 0.72245002, + 0.027881008 -0.69087321 0.72243816, + 0.028233493 -0.7243588 0.6888448, + 0.083600104 -0.72211105 0.68670708, + 0.084523097 -0.75364101 0.651829, + 0.14014502 -0.74888307 0.64771408, + 0.1414571 -0.77836245 0.61167133, + 0.19703293 -0.77085572 0.60577178, + 0.19853397 -0.7977289 0.56939691, + 0.2536509 -0.78731269 0.56196082, + 0.25517493 -0.81161684 0.52551287, + 0.30896094 -0.79833782 0.51691389, + 0.31037202 -0.82027113 0.48044205, + 0.362611 -0.80415702 0.47100401, + 0.3637909 -0.82375181 0.4348439, + 0.414518 -0.80479199 0.424835, + 0.41537377 -0.82192254 0.38975376, + 0.46432489 -0.80024981 0.3794769, + 0.46482295 -0.81514388 0.34565896, + 0.51128119 -0.79121631 0.33551213, + 0.51138198 -0.80587101 0.29843, + 0.45926511 -0.8330152 0.30848205, + 0.458783 -0.84799898 0.26536, + 0.40490282 -0.87263256 0.27306789, + 0.40389299 -0.88565201 0.229109, + 0.34930983 -0.90714556 0.23466888, + 0.34793296 -0.9180249 0.19019197, + 0.29323396 -0.93616086 0.19394997, + 0.29165906 -0.94481021 0.14922702, + 0.23703088 -0.95960653 0.15156393, + 0.23543508 -0.96598834 0.10694404, + 0.18121994 -0.97747064 0.10821496, + 0.17972492 -0.98170155 0.062936269, + 0.12685305 -0.98988938 0.063461326, + 0.12568699 -0.99186391 0.020215798, + 0.074474491 -0.99701589 0.020320797, + 0.074121617 -0.99724925 -0.00031838109, + 0.024442406 -0.99970126 -0.0003191641, + 0.024439296 -0.9997009 -0.0008825449, + -0.024439296 -0.9997009 -0.0008825449, + -0.023693699 -0.99971902 -0.00066560699, + -0.073567897 -0.99729002 -0.00066398998, + -0.071341984 -0.99745178 -0.00041668891, + -0.071346179 -0.99745166 -1.9550594e-006, + -0.12320995 -0.99238062 -1.9451493e-006, + -0.12156098 -0.99258387 0.00038594296, + -0.11947796 -0.99283665 0.00065260177, + -0.11948603 -0.99283522 0.0011383602, + -0.17339495 -0.98485178 0.0011292098, + -0.17346489 -0.98483539 0.0030132781, + -0.2255961 -0.97421646 0.0029807915, + -0.22667298 -0.97365791 0.024692096, + -0.27928096 -0.95990086 0.024343297, + -0.28169805 -0.95711923 0.067594215, + -0.33470404 -0.93998212 0.066383906, + -0.337228 -0.93482202 0.111288, + -0.39055207 -0.9141261 0.10882401, + -0.39288199 -0.90679997 0.152832, + -0.44594207 -0.88261414 0.14875501, + -0.44794807 -0.87313312 0.19230503, + -0.49956781 -0.8459987 0.18632793, + -0.50107825 -0.83454943 0.2290151, + -0.55102336 -0.80473948 0.22083414, + -0.55191201 -0.79149503 0.26254299, + -0.60001498 -0.75930601 0.25186601, + -0.60022414 -0.74667817 0.28671005, + -0.55826485 -0.77452683 0.29740295, + -0.55804497 -0.7621659 0.32815996, + -0.51389885 -0.7879197 0.33924988, + -0.51331496 -0.77368486 0.37137496, + -0.46670017 -0.79731828 0.38272014, + -0.46573901 -0.78088403 0.416302, + -0.41665399 -0.80218798 0.427661, + -0.41533214 -0.7833513 0.46245018, + -0.36448404 -0.80190015 0.47340006, + -0.36287418 -0.78075933 0.50866222, + -0.31048504 -0.79646111 0.51889205, + -0.30868298 -0.77294087 0.55432594, + -0.25485596 -0.78579187 0.56354195, + -0.25298092 -0.75968868 0.59906077, + -0.19784707 -0.76970929 0.60696322, + -0.19605204 -0.74094015 0.64231718, + -0.1405571 -0.74810243 0.64852637, + -0.13904601 -0.71712708 0.68293107, + -0.083633393 -0.72162491 0.68721396, + -0.082589954 -0.68862444 0.72039944, + -0.027490992 -0.69072384 0.72259581, + -0.0270971 -0.65563798 0.75458902, + 0.027703209 -0.65562725 0.75457633, + 0.028099297 -0.69069093 0.72260392, + 0.083151996 -0.68857092 0.72038597, + 0.08419843 -0.72159123 0.68718022, + 0.13959803 -0.71707219 0.68287617, + 0.14111108 -0.74801034 0.6485123, + 0.19660898 -0.74082392 0.64228094, + 0.19840592 -0.76956171 0.60696775, + 0.25347304 -0.75952911 0.59905505, + 0.25535196 -0.78563589 0.56353492, + 0.30917898 -0.77276188 0.55429894, + 0.31098297 -0.7962569 0.51890695, + 0.36328691 -0.78055781 0.50867689, + 0.36490181 -0.80169666 0.47342277, + 0.4157322 -0.78313237 0.4624612, + 0.41705886 -0.80194569 0.42772084, + 0.46610111 -0.78063917 0.41635609, + 0.46706781 -0.79704672 0.38283685, + 0.51362294 -0.77342486 0.37149096, + 0.51421386 -0.78765082 0.33939692, + 0.55830526 -0.76191235 0.32830614, + 0.55853313 -0.77423918 0.29764807, + 0.60046077 -0.74639773 0.2869449, + 0.60026389 -0.75902385 0.25212294, + 0.5521692 -0.7912243 0.2628181, + 0.55129701 -0.80446798 0.22114, + 0.50137293 -0.83428389 0.22933698, + 0.49987799 -0.84574699 0.186639, + 0.44822189 -0.8729198 0.19263496, + 0.44623905 -0.88238311 0.14923401, + 0.39318994 -0.90658289 0.15332699, + 0.39087915 -0.91390532 0.10950103, + 0.33750492 -0.93463874 0.11198597, + 0.33498502 -0.93982512 0.067184605, + 0.28182793 -0.95702279 0.068413988, + 0.27938795 -0.95985574 0.024885094, + 0.226702 -0.97363698 0.025242301, + 0.225601 -0.97421497 0.0030679901, + 0.17347005 -0.98483425 0.0031014306, + 0.17339592 -0.98485154 0.0011286894, + 0.11948603 -0.99283522 0.0011378402, + 0.11947095 -0.99283767 0.00022670091, + 0.069113784 -0.99760878 0.00022779194, + 0.069112889 -0.9976089 9.0520789e-006, + 0.025374696 -0.99967688 -0.0014909498, + 0.025374604 -0.99967414 0.0028057103, + 0.025311405 -0.99967927 -0.0008064232, + 0.025311191 -0.99967563 0.002804629, + 0.025379296 -0.9996739 0.0028046297, + 0.025379494 -0.99967676 -0.0014909497, + 0.022983102 -0.99973512 -0.0011967901, + 0.022984194 -0.99973577 -0.00042632292, + 0.071305737 -0.99745446 -0.00042535021, + 0.071310014 -0.99745423 -2.3954508e-006, + 0.12320995 -0.99238062 -2.3831092e-006, + 0.12324994 -0.99237454 0.0015061992, + 0.17469005 -0.98462236 0.0014944306, + 0.175539 -0.98420101 0.023117401, + 0.22828098 -0.97332686 0.022861999, + 0.23033297 -0.97084087 0.066443592, + 0.283694 -0.95667702 0.065474302, + 0.28592193 -0.95185179 0.11057497, + 0.339636 -0.93427402 0.108533, + 0.34176201 -0.92729002 0.152748, + 0.39558005 -0.90621912 0.14927602, + 0.39748186 -0.89703071 0.19324593, + 0.45083693 -0.87258786 0.18797997, + 0.45234695 -0.86129189 0.23142697, + 0.50417691 -0.83401787 0.22409797, + 0.50513709 -0.82081914 0.26663202, + 0.5551579 -0.7910558 0.25696394, + 0.55547214 -0.77810615 0.29326007, + 0.5084362 -0.80577129 0.30368611, + 0.50803101 -0.82073402 0.261343, + 0.45605299 -0.84799898 0.27002501, + 0.45504496 -0.86112386 0.22671497, + 0.40139705 -0.88572115 0.23319203, + 0.39992881 -0.89681256 0.1891669, + 0.34571612 -0.91813636 0.19366507, + 0.34395397 -0.92704791 0.14925799, + 0.28972098 -0.94494188 0.15213999, + 0.28783506 -0.95161027 0.10765202, + 0.2338119 -0.96611953 0.10929295, + 0.23192991 -0.97062063 0.064062677, + 0.17840809 -0.98182046 0.064801931, + 0.17678699 -0.98401791 0.021330899, + 0.12474497 -0.99195576 0.021502994, + 0.12414697 -0.99226373 0.00037571791, + 0.07354717 -0.99729162 0.00037761385, + 0.073530287 -0.99729276 -0.00066399283, + 0.023693699 -0.99971902 -0.00066560903, + 0.023693804 -0.99971914 -0.00063306605, + -0.023693804 -0.99971914 -0.00063306605, + -0.024459185 -0.99970043 -0.00085607247, + -0.023769496 -0.99971688 -0.0010563399, + -0.023092294 -0.99973273 -0.0010563597, + -0.023090901 -0.99966502 -0.0116897, + -0.023767991 -0.99964666 -0.011898795, + -0.025752805 -0.99957621 -0.013574403, + -0.023621803 -0.9996171 -0.014408902, + -0.023623988 -0.99972051 -0.00085608556, + -0.072750114 -0.99735022 -0.00026636507, + -0.072749674 -0.99734664 0.0026948291, + -0.072647505 -0.99735409 0.0026948203, + -0.072647862 -0.99735755 -0.00047112376, + -0.072841838 -0.99734348 -0.00047112323, + -0.072841302 -0.99734002 0.00266515, + -0.12155694 -0.99254251 -0.0091251554, + -0.12837601 -0.99162698 -0.0139824, + -0.67975283 -0.7027688 0.20988595, + -0.63640606 -0.73909605 0.22073603, + -0.63523418 -0.75081116 0.18099804, + -0.5890761 -0.78557318 0.18937804, + -0.58719027 -0.79574937 0.14829208, + -0.53914791 -0.82795686 0.15429498, + -0.53664595 -0.83631891 0.11216898, + -0.48705077 -0.86562258 0.11609995, + -0.48403081 -0.87202072 0.072759978, + -0.43315309 -0.89819926 0.074944414, + -0.42991686 -0.90228271 0.032519288, + -0.37807807 -0.9251731 0.033344403, + -0.37634891 -0.92641973 0.010384697, + -0.32441184 -0.94585651 0.010602595, + -0.26638287 -0.96384954 0.0058418773, + -0.2664381 -0.96382338 0.0074330429, + -0.32419804 -0.94596112 0.0072952812, + -0.26574692 -0.96402466 0.0059076077, + -0.3151471 -0.94900626 0.0083443318, + -0.31523189 -0.94895667 0.010495496, + -0.3738519 -0.92743164 0.010257396, + -0.37412411 -0.92727238 0.014038204, + -0.42568007 -0.90477014 0.013697502, + -0.42757991 -0.90321875 0.037032492, + -0.47817788 -0.87752575 0.035979092, + -0.48154107 -0.87295711 0.077873506, + -0.53092384 -0.84406769 0.075296268, + -0.53396016 -0.8372463 0.11792004, + -0.58196688 -0.80526483 0.11341597, + -0.58438778 -0.79660672 0.15462394, + -0.63063592 -0.76185989 0.14787799, + -0.63236725 -0.75155032 0.18784007, + -0.67583382 -0.71505785 0.17871995, + -0.67681295 -0.70335895 0.21727997, + -0.71742505 -0.66560006 0.20561603, + -0.71767282 -0.65525681 0.23576294, + -0.68016201 -0.68977201 0.248182, + 0.16346601 -0.98654598 0.0024175099, + 0.2075661 -0.97820646 0.0053427424, + 0.20756197 -0.97821289 0.0041884095, + 0.25835201 -0.96604198 0.0041362899, + 0.25840095 -0.96600676 0.007731508, + 0.31508592 -0.94903278 0.0075956583, + 0.31520215 -0.9489665 0.010505305, + 0.37382391 -0.92744279 0.010266997, + 0.37410888 -0.92727566 0.014224395, + 0.42572385 -0.90474671 0.013878895, + 0.42768085 -0.90313268 0.037953787, + 0.47831887 -0.87741178 0.036872793, + 0.48170999 -0.87273902 0.079259597, + 0.53116679 -0.8437947 0.076630972, + 0.53416198 -0.83697301 0.118942, + 0.58222705 -0.80493909 0.11438902, + 0.58460814 -0.7963202 0.15526603, + 0.63084584 -0.76156682 0.14849097, + 0.63255125 -0.75127733 0.18831207, + 0.67601502 -0.71477598 0.179162, + 0.67697418 -0.70308119 0.21767604, + 0.71757543 -0.66532344 0.20598611, + 0.71780998 -0.65497297 0.23613399, + 0.68031007 -0.68948406 0.24857603, + 0.67991877 -0.70249379 0.21026893, + 0.63661098 -0.73879999 0.221136, + 0.63545597 -0.75052989 0.18138498, + 0.58930212 -0.78530419 0.18979004, + 0.58744168 -0.79545367 0.14888193, + 0.53936213 -0.82770115 0.15491703, + 0.53689694 -0.8360309 0.11310998, + 0.48728111 -0.86536115 0.11707803, + 0.48429212 -0.8717742 0.073965319, + 0.43331385 -0.89801669 0.076191768, + 0.43005306 -0.90218711 0.033359103, + 0.37814215 -0.92511535 0.034206912, + 0.37636116 -0.92641336 0.010521304, + 0.32442096 -0.94585186 0.010741999, + 0.32419804 -0.94596112 0.007294571, + 0.26647106 -0.96381426 0.0074322317, + 0.26638794 -0.96385276 0.0050341086, + 0.21079308 -0.97751737 0.0051054819, + 0.21075797 -0.9775359 0.0021292197, + 0.16303305 -0.98661834 0.0021489908, + 0.16304095 -0.98661476 0.0029849892, + 0.21740808 -0.97607636 0.0029531112, + 0.2174629 -0.97605652 0.0048513175, + 0.27424711 -0.96164745 0.0047797025, + 0.27441388 -0.96158051 0.0077386862, + 0.32644996 -0.94518387 0.0076067289, + 0.32802108 -0.94416922 0.030769007, + 0.38040307 -0.92433012 0.030122403, + 0.38345695 -0.92064691 0.07328099, + 0.43581805 -0.89719713 0.071414508, + 0.43872914 -0.89119732 0.11525705, + 0.48993987 -0.86455584 0.11181297, + 0.49242413 -0.85654217 0.15444703, + 0.54214305 -0.82695013 0.14911202, + 0.54410285 -0.81698769 0.19100593, + 0.59217823 -0.7846483 0.18344507, + 0.59348971 -0.77296865 0.22425289, + 0.63959783 -0.73826784 0.21418495, + 0.64017969 -0.72512162 0.25370988, + 0.68336117 -0.68911719 0.24111205, + 0.68328118 -0.67730016 0.27274805, + 0.64632004 -0.70782906 0.28504103, + 0.64589494 -0.69682497 0.31185699, + 0.60619289 -0.72593385 0.32488492, + 0.60542202 -0.71316999 0.35334501, + 0.56349987 -0.74024081 0.3667579, + 0.56234008 -0.72542506 0.39690307, + 0.51816583 -0.75031668 0.41052285, + 0.51659393 -0.73323596 0.44214895, + 0.46995994 -0.75589287 0.45581093, + 0.46801588 -0.73661882 0.48821488, + 0.41884905 -0.75690413 0.50165904, + 0.41658586 -0.73527277 0.53463084, + 0.36570489 -0.75277072 0.5473538, + 0.36318997 -0.72851592 0.58082491, + 0.31089097 -0.74316096 0.59250194, + 0.30824593 -0.71623385 0.6260938, + 0.2545529 -0.72809374 0.63646078, + 0.25196904 -0.69882405 0.66944504, + 0.19719197 -0.70794392 0.67818195, + 0.194846 -0.67637002 0.71032298, + 0.13986903 -0.68280816 0.71708417, + 0.13794601 -0.64890504 0.74826008, + 0.083196193 -0.65289694 0.75286388, + 0.081892699 -0.616813 0.78283799, + 0.027632516 -0.61865538 0.78517646, + 0.027155086 -0.58102071 0.81343555, + -0.026563291 -0.58102983 0.81344873, + -0.027041914 -0.6186713 0.78518438, + -0.081279978 -0.6168499 0.7828728, + -0.082582265 -0.65297973 0.75285965, + -0.13732602 -0.64901006 0.74828309, + -0.13924605 -0.68291223 0.71710622, + -0.19429795 -0.67648882 0.71035981, + -0.19663788 -0.70802361 0.67825961, + -0.25146192 -0.69891876 0.66953677, + -0.25405005 -0.72826117 0.6364702, + -0.30774787 -0.71642178 0.62612379, + -0.31039113 -0.74335927 0.59251523, + -0.36275402 -0.72871709 0.58084506, + -0.36526498 -0.75296891 0.54737496, + -0.41619095 -0.73547596 0.53465897, + -0.41845301 -0.75712901 0.50164998, + -0.46764818 -0.73685223 0.48821518, + -0.46959105 -0.75615412 0.45575806, + -0.51627797 -0.73348993 0.44209695, + -0.51784474 -0.75058264 0.41044179, + -0.56205809 -0.72568518 0.3968271, + -0.56321192 -0.74050695 0.36666298, + -0.60518622 -0.71341723 0.35325012, + -0.60595196 -0.72621691 0.32470196, + -0.64570206 -0.69708407 0.31167704, + -0.64611977 -0.70812178 0.2847679, + -0.68310905 -0.67757905 0.27248603, + -0.68317801 -0.68940502 0.240808, + -0.63996518 -0.72542316 0.25338906, + -0.63936776 -0.73856574 0.21384493, + -0.593288 -0.77323103 0.223882, + -0.59195703 -0.78491509 0.18301702, + -0.54386383 -0.81725168 0.19055693, + -0.54188013 -0.82721919 0.14857402, + -0.49214783 -0.85680169 0.15388794, + -0.48963195 -0.8648389 0.11096898, + -0.43848988 -0.89142776 0.11438097, + -0.43555814 -0.89740729 0.070350625, + -0.38327882 -0.9208076 0.072184965, + -0.38025308 -0.92441422 0.029428007, + -0.32797292 -0.94420874 0.030058093, + -0.32644102 -0.94518811 0.0074721407, + -0.27440596 -0.96158385 0.0076017589, + -0.27424595 -0.96164775 0.0047692088, + -0.21746407 -0.97605634 0.004840672, + -0.21743095 -0.97606874 0.003697919, + -0.17044201 -0.98536509 0.0022998003, + -0.17011705 -0.98542124 0.0023105806, + -0.17011707 -0.98542237 0.0017452306, + -0.170443 -0.98536599 0.00174508, + -0.17007704 -0.98542923 0.0017485705, + -0.17007606 -0.98542833 0.0022997509, + -0.12152497 -0.99243176 -0.017633196, + -0.12154203 -0.99258626 0.00038595108, + -0.16828799 -0.98573589 0.0019675097, + -0.16830599 -0.98573101 0.0027376299, + -0.22397693 -0.97459066 0.0027066891, + -0.22408794 -0.97455579 0.0050650085, + -0.2761949 -0.96108866 0.004995028, + -0.27750805 -0.96033925 0.027163006, + -0.32996792 -0.94361478 0.026689995, + -0.33271608 -0.94044721 0.069706917, + -0.38551185 -0.92017865 0.068204574, + -0.38827705 -0.91461813 0.11275902, + -0.44095385 -0.89078569 0.10982096, + -0.44341195 -0.88310289 0.15334599, + -0.49482876 -0.85617858 0.14866993, + -0.49685413 -0.8464402 0.19150704, + -0.54668278 -0.8166976 0.18477792, + -0.54813087 -0.80510283 0.22663194, + -0.59623295 -0.77277786 0.21753298, + -0.5969919 -0.75955284 0.25822493, + -0.64299816 -0.72510916 0.24651606, + -0.64307415 -0.71286815 0.27977607, + -0.60327595 -0.74240392 0.29136696, + -0.60295773 -0.73068666 0.32021686, + -0.56098288 -0.75821382 0.33227992, + -0.56030595 -0.74466091 0.36268097, + -0.51615077 -0.77002466 0.37503383, + -0.51508582 -0.7543577 0.40697786, + -0.46842501 -0.77756101 0.419496, + -0.46697095 -0.75958186 0.45273995, + -0.41780379 -0.78042465 0.4651638, + -0.41601506 -0.76017213 0.49906906, + -0.36510208 -0.77823716 0.51092809, + -0.36305317 -0.75560236 0.54521322, + -0.31065115 -0.77081233 0.55618721, + -0.30843589 -0.74557978 0.59074378, + -0.25465986 -0.75795251 0.60054666, + -0.25241694 -0.73003185 0.63508981, + -0.19738795 -0.73961884 0.64342982, + -0.195316 -0.70939201 0.67721099, + -0.140029 -0.716196 0.683707, + -0.13831694 -0.68383169 0.71640962, + -0.083195239 -0.68807435 0.72085536, + -0.082022674 -0.65351081 0.75245982, + -0.027282303 -0.65547603 0.75472313, + -0.026843296 -0.61885196 0.7850489, + 0.027427793 -0.6188429 0.78503585, + 0.027867116 -0.65548444 0.75469446, + 0.082561232 -0.65350026 0.75241029, + 0.083733089 -0.68804193 0.72082394, + 0.1388929 -0.68377459 0.71635258, + 0.14060496 -0.71611774 0.68367076, + 0.19589397 -0.70928895 0.67715192, + 0.19796596 -0.73948091 0.64341092, + 0.25290096 -0.72988695 0.63506395, + 0.2551471 -0.75779629 0.60053724, + 0.30892095 -0.7454018 0.59071487, + 0.31113896 -0.77063888 0.55615497, + 0.363478 -0.75542498 0.54517603, + 0.36552802 -0.77801812 0.51095706, + 0.41641986 -0.75994068 0.49908382, + 0.41821501 -0.78018999 0.465188, + 0.46731704 -0.75935411 0.45276505, + 0.46877611 -0.77732617 0.41953909, + 0.51537985 -0.7541337 0.40702084, + 0.51644826 -0.76977336 0.37514019, + 0.56059605 -0.74439704 0.36277404, + 0.56127715 -0.75790828 0.33248013, + 0.6032089 -0.73039484 0.32040992, + 0.60353631 -0.74208337 0.29164416, + 0.64327878 -0.71257675 0.28004792, + 0.64321607 -0.72481108 0.24682403, + 0.5972051 -0.7592712 0.25856006, + 0.59646189 -0.77251381 0.21784295, + 0.54839593 -0.80483091 0.22695597, + 0.54696697 -0.81642491 0.18514198, + 0.49712175 -0.84619558 0.19189291, + 0.49511987 -0.85591584 0.14921297, + 0.44365507 -0.88288212 0.15391402, + 0.44122478 -0.89054859 0.11065195, + 0.38849387 -0.91441971 0.11361796, + 0.3857429 -0.92000675 0.069209687, + 0.33285889 -0.94031966 0.070737779, + 0.33007985 -0.94355851 0.027284987, + 0.27757913 -0.96030146 0.027769113, + 0.276234 -0.96107697 0.0050836201, + 0.22409303 -0.97455412 0.0051549105, + 0.22397693 -0.97459066 0.0027170491, + 0.16827196 -0.98573679 0.0027481292, + 0.16823906 -0.98574537 0.0013489504, + 0.11576595 -0.99327564 0.0013592496, + 0.11576403 -0.99327624 0.0010750302, + 0.12313005 -0.99239033 -0.00072888623, + 0.12312902 -0.99238712 0.0026554402, + 0.12305996 -0.99239564 0.0026554291, + 0.12306099 -0.99239886 -0.00072551292, + 0.12326998 -0.99237287 -0.00072553195, + 0.12326897 -0.99236977 0.0026368194, + 0.17161892 -0.98512554 -0.008636686, + 0.17162393 -0.98516154 -0.0013762893, + 0.17165892 -0.98515552 -0.0013762993, + 0.17163308 -0.9849925 -0.01822081, + 0.21979395 -0.97554374 0.0022267096, + 0.21979503 -0.97554612 -0.00017146801, + 0.219115 -0.97569901 -0.00017096401, + 0.21911395 -0.97569674 0.0022164795, + 0.21978404 -0.97554612 0.0022166003, + 0.21978508 -0.97554839 -0.00016055605, + 0.25451213 -0.96704346 0.0071170931, + 0.25451094 -0.96704674 0.0066950386, + 0.30582589 -0.95206463 0.0065913177, + 0.30588886 -0.95200551 0.010833494, + 0.36366981 -0.93146759 0.010599895, + 0.36381903 -0.93136412 0.014023002, + 0.42294484 -0.90605271 0.013641795, + 0.42329586 -0.9058097 0.018150594, + 0.47368211 -0.88051921 0.017643904, + 0.47578606 -0.87855011 0.042158704, + 0.52511275 -0.85005456 0.04079118, + 0.52853703 -0.84489709 0.082447909, + 0.57654715 -0.81320119 0.079354919, + 0.57947302 -0.80599898 0.120734, + 0.62576729 -0.77140337 0.11555205, + 0.62800384 -0.76253283 0.15541796, + 0.67161906 -0.72597104 0.14796601, + 0.67312592 -0.71559495 0.18661599, + 0.71393704 -0.67754906 0.17669502, + 0.71467179 -0.66595578 0.21388592, + 0.75279909 -0.62672007 0.20128503, + 0.7528618 -0.61679989 0.22968894, + 0.72075784 -0.64960682 0.24190694, + 0.72051823 -0.64079225 0.26502609, + 0.68623394 -0.67215997 0.27799997, + 0.68571615 -0.66186619 0.30286404, + 0.64884031 -0.69192433 0.31661814, + 0.64798969 -0.67996371 0.34315985, + 0.60831589 -0.7085728 0.35759792, + 0.6070779 -0.69461381 0.38596392, + 0.56517416 -0.72112525 0.40069515, + 0.56351221 -0.70499122 0.43062913, + 0.51931787 -0.72928983 0.44547188, + 0.51725686 -0.71104485 0.47629887, + 0.47057506 -0.73308605 0.49106407, + 0.46813789 -0.71249682 0.52268088, + 0.41898507 -0.73212004 0.53707707, + 0.41622579 -0.70895362 0.56933367, + 0.36536303 -0.72579807 0.58286107, + 0.36237597 -0.69994897 0.61543095, + 0.31015703 -0.71395808 0.62774706, + 0.30711505 -0.68569517 0.65992618, + 0.25361398 -0.69695896 0.67076695, + 0.25069112 -0.66635329 0.70223033, + 0.1961479 -0.6749627 0.71130264, + 0.19352102 -0.64192104 0.74194807, + 0.13887103 -0.64795017 0.74891615, + 0.136738 -0.61255097 0.77851403, + 0.082458541 -0.61625332 0.78321934, + 0.081043325 -0.57916611 0.81117117, + 0.027324004 -0.58086103 0.81354409, + 0.026810788 -0.54236877 0.83971256, + -0.0262527 -0.542377 0.83972502, + -0.026764309 -0.58083916 0.81357831, + -0.080454223 -0.57916415 0.8112312, + -0.081867598 -0.61626899 0.78326899, + -0.13618499 -0.61258394 0.7785849, + -0.13831805 -0.64798623 0.74898726, + -0.192968 -0.64197898 0.74204201, + -0.19560114 -0.67508149 0.71134055, + -0.25014508 -0.66649425 0.70229125, + -0.25306809 -0.69709826 0.67082822, + -0.30663899 -0.68584102 0.65999597, + -0.30968207 -0.71412116 0.62779617, + -0.36192408 -0.70012718 0.61549413, + -0.36491197 -0.72602195 0.58286494, + -0.4158062 -0.70918733 0.56934929, + -0.41856301 -0.73236299 0.53707498, + -0.46777579 -0.71273464 0.52268076, + -0.47020823 -0.73332137 0.49106425, + -0.51693183 -0.71127778 0.47630382, + -0.51899177 -0.72956365 0.44540378, + -0.56321585 -0.70526481 0.4305689, + -0.56487405 -0.72141808 0.40059105, + -0.6068421 -0.69488019 0.38585508, + -0.60807371 -0.70883566 0.35748881, + -0.64779615 -0.68020415 0.34304908, + -0.64864224 -0.69219923 0.31642312, + -0.68554497 -0.66212893 0.30267698, + -0.68605715 -0.6724562 0.27772006, + -0.72036701 -0.64107299 0.26475799, + -0.72059864 -0.6499427 0.24147888, + -0.7527408 -0.61710089 0.22927694, + -0.75266373 -0.62700975 0.20088792, + -0.71454406 -0.66623104 0.21345504, + -0.71378881 -0.67783082 0.17621295, + -0.67297679 -0.71586883 0.18610196, + -0.67144293 -0.72626692 0.14731199, + -0.62783778 -0.76281071 0.15472394, + -0.62555784 -0.77172881 0.11450797, + -0.57928014 -0.80630118 0.11963703, + -0.57631469 -0.81349456 0.078024261, + -0.5283218 -0.84516573 0.08106187, + -0.5249117 -0.85022748 0.039760977, + -0.47571906 -0.87863714 0.041089606, + -0.47368383 -0.88052273 0.017416194, + -0.42327791 -0.90582275 0.017916497, + -0.42294484 -0.90605271 0.013643796, + -0.36381698 -0.93136489 0.014024998, + -0.36383992 -0.93134779 0.014549197, + -0.41185793 -0.91113687 0.014233498, + -0.40045515 -0.91612631 0.018664908, + -0.45891419 -0.88829631 0.018098006, + -0.45911899 -0.88809401 0.0223336, + -0.51722687 -0.85557783 0.021515895, + -0.51767105 -0.85516214 0.026729004, + -0.56555206 -0.82431012 0.025764704, + -0.56773907 -0.82168615 0.050043207, + -0.61412287 -0.78775084 0.04797639, + -0.61738092 -0.78176886 0.087625891, + -0.6612618 -0.7454868 0.083559178, + -0.6586712 -0.74691719 0.090922825, + -0.70015901 -0.70875502 0.086277202, + -0.70252317 -0.70070815 0.12437603, + -0.74143177 -0.66070074 0.11727495, + -0.742984 -0.651425 0.153689, + -0.77913052 -0.61011165 0.14394191, + -0.77989483 -0.59989589 0.17857495, + -0.81279516 -0.55833709 0.16620405, + -0.81290799 -0.55013102 0.191145, + -0.78549784 -0.58458287 0.20311595, + -0.78537101 -0.57773 0.222307, + -0.75553131 -0.61141026 0.23526609, + -0.75519884 -0.60323989 0.25646895, + -0.72318602 -0.63559502 0.270224, + -0.72259277 -0.62602478 0.29317689, + -0.68837082 -0.65689284 0.30763194, + -0.68745768 -0.64570969 0.33235684, + -0.65062499 -0.67520601 0.34753999, + -0.64933205 -0.66215503 0.37405702, + -0.60964489 -0.6901648 0.3898789, + -0.60791975 -0.67499578 0.41810784, + -0.5659579 -0.7008698 0.4341349, + -0.56380802 -0.683635 0.46342599, + -0.51957911 -0.70723915 0.47942713, + -0.51701808 -0.68777007 0.50957304, + -0.47028676 -0.70909363 0.52537274, + -0.46733311 -0.68707019 0.5563581, + -0.41815785 -0.70594978 0.5716458, + -0.41488579 -0.68125373 0.60312772, + -0.36404082 -0.69735867 0.61738569, + -0.36060882 -0.67021471 0.64867067, + -0.30851412 -0.68351024 0.66153824, + -0.30507481 -0.65394461 0.69230461, + -0.25178403 -0.66455704 0.70354009, + -0.24850309 -0.63247222 0.73363823, + -0.19426997 -0.64051497 0.74296695, + -0.191349 -0.60598499 0.77211899, + -0.13713795 -0.61156076 0.77922171, + -0.13482004 -0.57517618 0.80684328, + -0.081034631 -0.57856721 0.81159931, + -0.079514295 -0.54063994 0.83748788, + -0.026464906 -0.54216814 0.83985317, + -0.025914406 -0.50264013 0.86410719, + 0.026483495 -0.5026319 0.86409479, + 0.02703391 -0.54214919 0.83984733, + 0.080102205 -0.54060405 0.83745509, + 0.081621878 -0.5785709 0.8115378, + 0.135381 -0.57516402 0.80675799, + 0.13769598 -0.61152196 0.77915388, + 0.19190304 -0.60592812 0.77202618, + 0.19482502 -0.64045405 0.74287409, + 0.24903095 -0.63239384 0.73352683, + 0.25231004 -0.66443908 0.70346308, + 0.30557215 -0.65381128 0.69221133, + 0.30900902 -0.68333906 0.66148406, + 0.3610948 -0.67002457 0.64859664, + 0.3645249 -0.69713581 0.61735189, + 0.41528192 -0.6810388 0.60309786, + 0.41855806 -0.70573908 0.57161307, + 0.46770719 -0.68685126 0.55631417, + 0.47066101 -0.70883399 0.525388, + 0.51734596 -0.68751395 0.50958592, + 0.51991278 -0.70698863 0.47943476, + 0.56407189 -0.68340582 0.46344289, + 0.56622493 -0.70063794 0.43416095, + 0.60816312 -0.67476416 0.4181281, + 0.60988694 -0.68988097 0.39000294, + 0.64955598 -0.66187203 0.37416899, + 0.65085405 -0.67489707 0.34771103, + 0.68765444 -0.64541537 0.3325212, + 0.68857193 -0.65656495 0.30788198, + 0.72275221 -0.62572622 0.29342112, + 0.72335303 -0.63527298 0.27053401, + 0.75529981 -0.6029799 0.25678295, + 0.75563967 -0.61112177 0.23566692, + 0.78546399 -0.57745802 0.22268499, + 0.78560013 -0.58428907 0.20356503, + 0.8129878 -0.54986489 0.19157095, + 0.81288815 -0.55806905 0.16664901, + 0.7799899 -0.59962791 0.17905898, + 0.77924937 -0.60981631 0.14454907, + 0.74308634 -0.65115231 0.15434808, + 0.74157596 -0.66034997 0.11833499, + 0.70265818 -0.70037121 0.12550603, + 0.70035201 -0.70837402 0.087825097, + 0.65884972 -0.74655867 0.092559054, + 0.65577883 -0.75305182 0.053544387, + 0.61167723 -0.78911531 0.056108717, + 0.60940194 -0.79227185 0.030570196, + 0.56294495 -0.82587987 0.031866997, + 0.5624308 -0.82643872 0.025897091, + 0.50503212 -0.86267716 0.027032806, + 0.50478721 -0.86296129 0.022086008, + 0.44670278 -0.89438957 0.022890288, + 0.44660985 -0.89457172 0.016765594, + 0.39474601 -0.91862899 0.017216399, + 0.39474508 -0.91864121 0.016578203, + 0.4377622 -0.89894444 0.016222807, + 0.43777013 -0.89898825 0.013324203, + 0.40565884 -0.9140237 -0.0012832995, + 0.40565914 -0.91402429 0.00049874815, + 0.40585718 -0.91393644 0.00049882825, + 0.40576106 -0.91397911 0.00048504505, + 0.37668917 -0.92619544 -0.016351307, + -0.22966994 -0.97317177 -0.013726196, + -0.21821196 -0.97587889 -0.0066264891, + -0.21821408 -0.97589433 0.0036041413, + -0.2181821 -0.97590148 0.0036041816, + -0.21813895 -0.97568774 -0.021187395, + -0.26581612 -0.96402246 0.0016319508, + -0.265811 -0.96400702 0.0059104702, + -0.26593894 -0.96397173 0.0059102187, + -0.26594496 -0.96398687 0.0016391698, + -0.26575202 -0.9640401 0.0016391203, + -0.3127681 -0.94981927 -0.0044349912, + -0.31275609 -0.94979423 0.0086386018, + -0.3128261 -0.94977123 0.0086383717, + -0.3127481 -0.94950837 -0.024953809, + -0.35897791 -0.93334574 0.00068354281, + -0.35896087 -0.93330866 0.0090518976, + -0.35889292 -0.93333477 0.0090522077, + -0.35890996 -0.9333719 0.00067533297, + -0.35895488 -0.93335462 0.00067534577, + -0.35893819 -0.93331742 0.0090550343, + -0.4003709 -0.91625679 0.013286198, + -0.40429983 -0.91454458 0.012242994, + -0.40433314 -0.9146083 -0.0025186508, + -0.40430409 -0.91462123 -0.0025034908, + -0.40427116 -0.91455728 0.012243205, + -0.44657579 -0.89459658 0.016338093, + -0.44667912 -0.89439523 0.023131305, + -0.504798 -0.86294901 0.022318101, + -0.50503093 -0.86267787 0.027027896, + -0.56245178 -0.8264246 0.025891988, + -0.56293792 -0.82589787 0.031521898, + -0.60936725 -0.79231131 0.03024001, + -0.61156189 -0.78929883 0.054767586, + -0.65559793 -0.75329888 0.052269693, + -0.65638417 -0.75277019 0.049968813, + -0.6939888 -0.71840483 0.04768759, + -0.69762623 -0.71025121 0.094132036, + -0.73681635 -0.6702323 0.088828146, + -0.73887998 -0.66203803 0.12554701, + -0.7753588 -0.62046289 0.11766297, + -0.77660912 -0.61122906 0.15256901, + -0.8098371 -0.56919104 0.14207602, + -0.81032485 -0.55920589 0.17510696, + -0.83803213 -0.52069008 0.16304602, + -0.83778089 -0.52780795 0.13979198, + -0.8074342 -0.57029414 0.15104502, + -0.80649418 -0.5794121 0.11768103, + -0.77292418 -0.6218031 0.12629002, + -0.77119291 -0.63004893 0.091103889, + -0.73436517 -0.67176819 0.09713652, + -0.73109674 -0.68027776 0.052151881, + -0.68835485 -0.72325182 0.055446487, + -0.68717098 -0.72539097 0.040050998, + -0.63500404 -0.77133411 0.042587705, + -0.63473392 -0.77186787 0.036509395, + -0.57947314 -0.81408119 0.038506109, + -0.57948315 -0.81398129 0.040419016, + -0.61351687 -0.78870982 0.039164089, + -0.61359912 -0.78898519 0.031600706, + -0.65067983 -0.75874382 0.030389393, + -0.65084481 -0.75913185 0.010948597, + -0.65237194 -0.75780886 0.011682899, + -0.65241891 -0.75785691 0.0015944497, + -0.65230119 -0.75795817 0.0015943703, + -0.65227276 -0.75793171 0.0089245569, + -0.65213674 -0.75804871 0.0089260573, + -0.65216517 -0.75807518 0.0016771203, + -0.67920083 -0.73378479 -0.015687795, + -0.75619382 -0.65409684 -0.018115597, + -0.75105029 -0.66008723 -0.014440405, + -0.99457622 -0.10278302 -0.015929503, + -0.99717462 -0.075118467 0.00016995794, + -0.99717301 -0.075116903 -0.00185374, + -0.99717474 -0.075094186 -0.0018552395, + -0.99717635 -0.075096034 0.00018044306, + -0.99711013 -0.075969808 0.00017974702, + -0.99704921 -0.075973816 0.010996102, + -0.99770278 -0.067233682 0.0082912985, + -0.99766463 -0.067191079 0.012275595, + -0.99349838 -0.11199304 0.020460807, + -0.99330467 -0.11183796 0.028950788, + -0.98685485 -0.15645199 0.040500097, + -0.98644203 -0.15616301 0.050450899, + -0.97849888 -0.19626397 0.063405991, + -0.97863549 -0.19645809 0.060637329, + -0.97103 -0.228329 0.0704742, + -0.97127163 -0.22941791 0.063236676, + -0.96310502 -0.25944999 0.0715148, + -0.96313787 -0.26005098 0.068840295, + -0.95227921 -0.29506505 0.078109413, + -0.95210755 -0.29071084 0.094754554, + -0.92607933 -0.35100311 0.13847004, + -0.93953598 -0.31855801 0.12567, + -0.93992877 -0.3245649 0.10578997, + -0.92358714 -0.36738604 0.10961001, + -0.93752366 -0.33339888 0.099470764, + -0.93748862 -0.34052989 0.071794376, + -0.91750854 -0.38916123 0.08204715, + -0.91746789 -0.39049393 0.075941391, + -0.92929423 -0.36254808 0.070506819, + -0.9290961 -0.36118203 0.079549104, + -0.94036174 -0.33221391 0.073168889, + -0.94003421 -0.3317261 0.079332225, + -0.95328176 -0.29379794 0.070261784, + -0.95435274 -0.29460195 0.049198888, + -0.9677971 -0.25125304 0.015513401, + -0.96712863 -0.2508139 0.041886285, + -0.97860926 -0.20479704 0.019548405, + -0.97815514 -0.20452502 0.037175305, + -0.96755534 -0.24858609 0.045184016, + -0.96656334 -0.24787009 0.065694526, + -0.95512265 -0.28632492 0.075886473, + -0.95539588 -0.28671396 0.070807993, + -0.94537312 -0.31648204 0.078159511, + -0.94560689 -0.31778398 0.069577396, + -0.93494034 -0.34659511 0.075885527, + -0.93492812 -0.34531802 0.081639208, + -0.95018226 -0.30333307 0.071713313, + -0.95016623 -0.30272505 0.074442916, + -0.95956337 -0.27334908 0.067218922, + -0.959315 -0.27213901 0.075200297, + -0.96811122 -0.24147105 0.066726014, + -0.96790433 -0.24118209 0.070657022, + -0.97758991 -0.20202696 0.059185792, + -0.97843933 -0.20263508 0.039945114, + -0.98692077 -0.15816195 0.031178292, + -0.98727673 -0.15839095 0.014030396, + -0.98474002 -0.17238601 0.023879699, + -0.9850229 -0.17241798 0.0013647799, + -0.98502254 -0.17241991 0.0013647693, + -0.9850229 -0.17241998 0.0011105998, + -0.98502612 -0.17240201 0.0011095802, + -0.98502576 -0.17240195 0.0013709996, + -0.97873867 -0.20451193 -0.015670795, + -0.97536951 -0.22054189 -0.003955388, + -0.97536415 -0.22056603 -0.0039475504, + -0.97536689 -0.22057097 0.0028163197, + -0.97537214 -0.22054803 0.0028150803, + -0.96292323 -0.26788107 0.031914707, + -0.96341777 -0.26799494 0.0022376396, + -0.96337461 -0.26814991 0.0022375192, + -0.96336848 -0.26814911 0.004158562, + -0.9633975 -0.26804513 0.004153532, + -0.95442474 -0.29756895 0.022938995, + -0.95375526 -0.29713506 0.045407612, + -0.93872601 -0.340709 0.0520663, + -0.93763638 -0.33983913 0.073126033, + -0.92256325 -0.37721208 0.08116772, + -0.9229269 -0.37779295 0.074015595, + -0.91055214 -0.40568206 0.079479709, + -0.91069657 -0.40708178 0.070114873, + -0.88969368 -0.44993284 0.077495471, + -0.88968575 -0.44983187 0.078170374, + -0.90320927 -0.42286316 0.073483728, + -0.90283114 -0.42220107 0.081500508, + -0.91956991 -0.38580394 0.074474394, + -0.92062575 -0.38670892 0.053892989, + -0.93794036 -0.34347713 0.047868118, + -0.938676 -0.34399101 0.0236148, + -0.93248612 -0.36115903 0.0058131902, + -0.93249923 -0.36116108 0.0028210906, + -0.93246287 -0.36125496 0.0028210199, + -0.93245 -0.36125299 0.0057644299, + -0.93247879 -0.3611789 0.0057614585, + -0.92038041 -0.39028516 0.02403021, + -0.9196189 -0.38970894 0.049274594, + -0.90019768 -0.43204185 0.05462718, + -0.89921814 -0.43112707 0.074406609, + -0.88081121 -0.46657011 0.080523625, + -0.88118201 -0.46729401 0.071795203, + -0.86628002 -0.493765 0.075862303, + -0.86628282 -0.49387589 0.075103983, + -0.89745623 -0.43609008 0.066316515, + -0.89775461 -0.4329398 0.08123906, + -0.92048573 -0.3840729 0.072069488, + -0.92079866 -0.37834084 0.094805263, + -0.90178579 -0.41922191 0.10504898, + -0.9011426 -0.42762581 0.071261659, + -0.87545413 -0.47672707 0.079444304, + -0.87500125 -0.47984713 0.064185418, + -0.84023684 -0.53743291 0.071888283, + -0.84023958 -0.53731775 0.072711863, + -0.85663986 -0.51125497 0.069185093, + -0.85629684 -0.51048988 0.078458577, + -0.87656826 -0.47569212 0.073110312, + -0.87744099 -0.47658601 0.054435201, + -0.89896888 -0.43518293 0.049706094, + -0.89971697 -0.43580201 0.0242058, + -0.89257157 -0.45084679 0.0072994367, + -0.87668413 -0.48047906 0.023765303, + -0.87597531 -0.47983617 0.049239218, + -0.85219502 -0.520491 0.0534111, + -0.85144287 -0.51964194 0.07083299, + -0.82922 -0.553801 0.075489402, + -0.82951981 -0.55458587 0.065813683, + -0.8118788 -0.57975787 0.068800986, + -0.81186932 -0.57987219 0.067945525, + -0.84985715 -0.52343214 0.061332215, + -0.8504653 -0.52039319 0.076809332, + -0.87925285 -0.47124994 0.069555789, + -0.88029331 -0.46254617 0.10552104, + -0.90343279 -0.41799092 0.095356077, + -0.903602 -0.41320401 0.112986, + -0.88250071 -0.45365685 0.12404796, + -0.88209414 -0.46121407 0.095872417, + -0.85612887 -0.50594693 0.10517099, + -0.85465097 -0.51484501 0.067129299, + -0.82309502 -0.56313699 0.073425896, + -0.82233709 -0.56605709 0.057802808, + -0.78120416 -0.62104613 0.063417912, + -0.78122109 -0.62093306 0.064310506, + -0.80020398 -0.59653699 0.061783802, + -0.79995912 -0.59575707 0.071686104, + -0.8237769 -0.56285393 0.067726992, + -0.82440013 -0.56364006 0.051715106, + -0.8505069 -0.52376395 0.048056394, + -0.85115832 -0.52441919 0.022671407, + -0.84414017 -0.53606814 0.0076339017, + -0.84416187 -0.53607893 0.0031790696, + -0.84417659 -0.53605574 0.0031790885, + -0.84415483 -0.5360449 0.0076434482, + -0.84408742 -0.53615123 0.0076462235, + -0.84410918 -0.53616214 0.0031601707, + -0.81681103 -0.57680303 -0.0108668, + -0.81682402 -0.576828 0.0082495902, + -0.8167879 -0.57687896 0.0082507692, + -0.78737968 -0.61606973 0.022164693, + -0.78757715 -0.61620909 0.0029418408, + -0.78757489 -0.61621195 0.0029418296, + -0.78754532 -0.61619323 0.0088540632, + -0.78752202 -0.61622298 0.00885465, + -0.78755212 -0.61624104 0.0029362305, + -0.75640398 -0.65405297 -0.0082287705, + -0.75639111 -0.65405506 0.0091976812, + -0.75627601 -0.65418798 0.0092000104, + -0.7233482 -0.69031417 0.015289403, + -0.72343618 -0.69038719 0.0023783306, + -0.72335708 -0.69047004 0.0023782603, + -0.72332257 -0.69044358 0.0095944041, + -0.72367078 -0.69007874 0.0095888963, + -0.68922096 -0.72445595 0.011747899, + -0.68898082 -0.72397983 0.034039892, + -0.65334606 -0.7562241 0.035556003, + -0.65321225 -0.75587028 0.044430215, + -0.62093025 -0.78251529 0.045996316, + -0.62092811 -0.78262818 0.044062011, + -0.67428583 -0.73730284 0.04151009, + -0.67454815 -0.73666918 0.047993813, + -0.72455692 -0.68775696 0.044807196, + -0.72567081 -0.6853888 0.060365386, + -0.7659995 -0.64036238 0.056399733, + -0.76884699 -0.63159502 0.099810101, + -0.80280381 -0.5889349 0.093068779, + -0.80418903 -0.58073199 0.12661099, + -0.83489412 -0.53777808 0.11724602, + -0.8355307 -0.52886581 0.14896093, + -0.86328387 -0.48581594 0.13683498, + -0.86335212 -0.47912607 0.15830801, + -0.84038609 -0.51462507 0.17003602, + -0.8402921 -0.50954103 0.18514101, + -0.81537789 -0.54412395 0.19770697, + -0.81515199 -0.537925 0.214858, + -0.78792971 -0.57183784 0.22840393, + -0.78751385 -0.56437796 0.24758697, + -0.75783652 -0.59748065 0.26210785, + -0.75717467 -0.58866471 0.28312585, + -0.72530496 -0.62039995 0.29838997, + -0.72434026 -0.61006325 0.32117611, + -0.69019824 -0.64030623 0.33709711, + -0.68886304 -0.62818706 0.36173004, + -0.65207475 -0.65701276 0.37832886, + -0.65031129 -0.64288032 0.40472218, + -0.61062801 -0.67017198 0.421904, + -0.60842425 -0.65402925 0.44951716, + -0.56646514 -0.67914319 0.46677813, + -0.56381583 -0.66082579 0.49539983, + -0.51959091 -0.68364096 0.51250392, + -0.51649511 -0.66283119 0.54211414, + -0.46978718 -0.68333626 0.5588842, + -0.46629587 -0.65990382 0.58914787, + -0.41717505 -0.67795408 0.60526305, + -0.41342109 -0.65204316 0.63554919, + -0.36271408 -0.66734016 0.65045816, + -0.3588419 -0.63901085 0.6803658, + -0.30691105 -0.65156621 0.69373417, + -0.303058 -0.62063301 0.723167, + -0.25004804 -0.63057208 0.73474807, + -0.24640404 -0.59705007 0.7634241, + -0.19261193 -0.60450876 0.77296168, + -0.18944097 -0.56901896 0.80020589, + -0.13574199 -0.57414901 0.80742002, + -0.13324994 -0.53692275 0.83304161, + -0.080103293 -0.54001194 0.83783686, + -0.078470223 -0.50106412 0.8618452, + -0.026107004 -0.50244308 0.86421615, + -0.025517903 -0.46198407 0.8865211, + 0.026037503 -0.46197805 0.88650912, + 0.026627909 -0.5024842 0.86417627, + 0.079012305 -0.50109106 0.86178011, + 0.080643229 -0.5400272 0.83777529, + 0.13380997 -0.53691989 0.83295381, + 0.13630104 -0.57413715 0.8073343, + 0.189973 -0.56899202 0.80009902, + 0.19314392 -0.60447574 0.77285469, + 0.24693485 -0.59699762 0.7632935, + 0.25057694 -0.63049179 0.73463684, + 0.30356088 -0.62053776 0.72303778, + 0.30740982 -0.65142858 0.69364256, + 0.35930988 -0.63885975 0.68026078, + 0.36317989 -0.66717374 0.65036875, + 0.41383922 -0.65187228 0.63545227, + 0.41758585 -0.67771477 0.60524774, + 0.46667606 -0.65965807 0.58912206, + 0.47017118 -0.68309826 0.5588522, + 0.51681697 -0.66260397 0.54208499, + 0.51991314 -0.68338919 0.5125131, + 0.56409812 -0.66058016 0.49540612, + 0.56674689 -0.6788758 0.46682489, + 0.60869592 -0.65375394 0.44954994, + 0.61090213 -0.6698792 0.4219721, + 0.65052927 -0.64261323 0.40479615, + 0.65229696 -0.65672594 0.37844393, + 0.68903399 -0.62792999 0.36185101, + 0.69037402 -0.64004499 0.33723301, + 0.72447801 -0.609828 0.32131201, + 0.72544515 -0.62013113 0.29860806, + 0.75728518 -0.58842009 0.28333905, + 0.75794989 -0.59718192 0.26246098, + 0.78761691 -0.56408894 0.24791797, + 0.78803891 -0.57151395 0.22883697, + 0.81522429 -0.5376482 0.21527608, + 0.81545901 -0.54383999 0.198153, + 0.84034312 -0.50930107 0.18556902, + 0.84044421 -0.51438713 0.17046805, + 0.86339498 -0.47891501 0.158712, + 0.86333811 -0.48557606 0.13734402, + 0.72605592 -0.68740696 0.017738698, + 0.72563124 -0.68675226 0.042785514, + 0.69172579 -0.72076279 0.044904385, + 0.69171381 -0.72073483 0.045533691, + 0.66058475 -0.74925774 0.047335681, + 0.66058081 -0.74912983 0.049370188, + 0.71199483 -0.70066482 0.046176188, + 0.71224898 -0.69989699 0.053344, + 0.75979799 -0.64827901 0.049409799, + 0.76033473 -0.64699775 0.057314079, + 0.79510897 -0.604101 0.053514201, + 0.7967093 -0.59913123 0.079348333, + 0.82825851 -0.55549562 0.073569156, + 0.82965982 -0.54818988 0.10560498, + 0.85818321 -0.50407511 0.097107425, + 0.85884881 -0.49636489 0.12649398, + 0.88442159 -0.4522348 0.11524795, + 0.88455027 -0.44658014 0.13467404, + 0.86121559 -0.48659477 0.14674193, + 0.8608911 -0.49512705 0.11711401, + 0.83277619 -0.53874409 0.12743104, + 0.83178788 -0.54669595 0.096190087, + 0.80067468 -0.59003574 0.10381597, + 0.79889733 -0.59736127 0.070162125, + 0.76449811 -0.64022505 0.075196505, + 0.76267833 -0.64490223 0.049225118, + 0.725124 -0.68662101 0.0524095, + 0.72455657 -0.68775761 0.044802476, + 0.67455095 -0.73666692 0.047988694, + 0.67427629 -0.73732835 0.041210819, + 0.62094873 -0.78262973 0.043742783, + 0.62094414 -0.78273416 0.041900512, + 0.65355873 -0.75579363 0.040458381, + 0.65355206 -0.75577313 0.040948205, + 0.68899584 -0.7237038 0.039210688, + 0.68932593 -0.72429192 0.015198698, + 0.68970907 -0.72392309 0.015388402, + 0.68979478 -0.72400278 0.0017719694, + 0.68983579 -0.72396374 0.0017719994, + 0.68975902 -0.72389299 0.0145446, + 0.72443795 -0.68918991 0.014389498, + 0.72450691 -0.68923897 -0.006271759, + 0.75735891 -0.65299392 0.0025135498, + 0.75728434 -0.65293831 0.013861206, + 0.75735515 -0.65285617 0.013859204, + 0.760647 -0.64897799 0.0156143, + 0.7600823 -0.64818925 0.046105314, + 0.72823465 -0.68360072 0.048624076, + 0.72818822 -0.68351525 0.050485719, + 0.69858718 -0.7135812 0.052706413, + 0.69857001 -0.71342897 0.0549464, + 0.74777776 -0.66198874 0.050984681, + 0.74799865 -0.66111672 0.058504876, + 0.7923857 -0.60764575 0.053772982, + 0.79288 -0.60621703 0.0619854, + 0.82483584 -0.56243986 0.057509184, + 0.82618898 -0.55723 0.083105899, + 0.85515797 -0.51269698 0.076464102, + 0.85619015 -0.50550908 0.10676701, + 0.88215911 -0.46078607 0.097321711, + 0.8825289 -0.45340094 0.12478098, + 0.90531278 -0.40951991 0.11270397, + 0.90528786 -0.40433794 0.13024898, + 0.8864401 -0.44055006 0.14191401, + 0.88633972 -0.43697685 0.15314394, + 0.865457 -0.47278899 0.165695, + 0.86527389 -0.46828493 0.17891398, + 0.8425563 -0.50313717 0.19222908, + 0.84224814 -0.49760005 0.20739403, + 0.81755781 -0.53152788 0.22153394, + 0.81707519 -0.52482611 0.23863307, + 0.7900542 -0.55805814 0.25374305, + 0.78934312 -0.55007207 0.27268702, + 0.75982529 -0.58248317 0.28875408, + 0.758825 -0.57304198 0.30952799, + 0.72708392 -0.60405993 0.32628298, + 0.72572505 -0.59290308 0.34898302, + 0.69166791 -0.62240297 0.36634696, + 0.68988699 -0.60933501 0.390854, + 0.65316975 -0.63735974 0.40882984, + 0.65094292 -0.62235093 0.43468693, + 0.61133122 -0.64878923 0.45315215, + 0.60863811 -0.63167518 0.48015213, + 0.56670296 -0.65593594 0.49859393, + 0.56352615 -0.63643825 0.5266732, + 0.51931983 -0.65838075 0.54483181, + 0.51567197 -0.63626093 0.57380694, + 0.46906093 -0.65585095 0.59147394, + 0.465069 -0.63133103 0.62058997, + 0.41608679 -0.64848268 0.63744968, + 0.41186208 -0.62149215 0.66642118, + 0.36136097 -0.63593692 0.68191093, + 0.35701904 -0.60625505 0.71062803, + 0.30543181 -0.61801362 0.72441059, + 0.30115703 -0.58573508 0.75247514, + 0.24851088 -0.59498268 0.76435465, + 0.24455789 -0.56058276 0.79116267, + 0.19122805 -0.56746912 0.80088121, + 0.18781798 -0.53115892 0.82619286, + 0.13473403 -0.53585213 0.83349216, + 0.13205591 -0.49763966 0.85727239, + 0.079599634 -0.50044322 0.86210239, + 0.077855542 -0.46053326 0.88422155, + 0.026227705 -0.46177712 0.88660824, + 0.025608104 -0.42070705 0.90683514, + -0.025123809 -0.42071214 0.90684628, + -0.02574419 -0.46174383 0.88663971, + -0.077300481 -0.46051487 0.88427979, + -0.079047441 -0.50042731 0.86216253, + -0.13151397 -0.49763787 0.85735685, + -0.13419099 -0.53583497 0.83359087, + -0.18727398 -0.53115791 0.82631689, + -0.19068795 -0.5675059 0.80098385, + -0.24399203 -0.56064105 0.79129612, + -0.24794994 -0.59507388 0.76446581, + -0.30060598 -0.58584493 0.75260991, + -0.30488813 -0.61816627 0.72450924, + -0.35655296 -0.60640997 0.71072996, + -0.36089492 -0.63608783 0.68201685, + -0.41142586 -0.62165374 0.66653979, + -0.4156549 -0.64867979 0.6375308, + -0.46470326 -0.63152236 0.62066936, + -0.46869919 -0.65607226 0.59151524, + -0.51533705 -0.63648707 0.57385707, + -0.51898605 -0.65863305 0.54484504, + -0.56323385 -0.63668483 0.52668786, + -0.56641012 -0.65620619 0.49857113, + -0.60835892 -0.63195193 0.48014194, + -0.6110521 -0.64908618 0.45310313, + -0.65072596 -0.62261891 0.43462795, + -0.65295082 -0.63763583 0.40874892, + -0.68971223 -0.60958725 0.39076915, + -0.69149196 -0.62267894 0.36620998, + -0.72556382 -0.59317386 0.34885791, + -0.72692084 -0.60436088 0.32608891, + -0.75870001 -0.57331097 0.30933601, + -0.75969583 -0.58278185 0.28849193, + -0.78924584 -0.55033785 0.27243194, + -0.78995311 -0.55835706 0.25340003, + -0.81700253 -0.52508968 0.23830186, + -0.8174811 -0.53183407 0.22108203, + -0.8421948 -0.49786988 0.20696296, + -0.84249586 -0.50341797 0.19175798, + -0.86523443 -0.46852821 0.17846809, + -0.86541086 -0.47301894 0.16527899, + -0.88631469 -0.43716484 0.15275194, + -0.88641024 -0.44075412 0.14146703, + -0.90527213 -0.40450707 0.12983301, + -0.90531921 -0.40726009 0.12056703, + -0.92372537 -0.36729813 0.10873704, + -0.9235909 -0.36254197 0.12467199, + -0.9068709 -0.39850393 0.13703899, + -0.90672088 -0.39546093 0.14651899, + -0.88808721 -0.43104109 0.15970205, + -0.88785714 -0.42714405 0.17104901, + -0.86717314 -0.46231607 0.18513401, + -0.86682415 -0.45743611 0.19841404, + -0.84427029 -0.49165916 0.21325807, + -0.8437528 -0.48562589 0.22857994, + -0.81921172 -0.51888484 0.2442349, + -0.81848013 -0.51166105 0.26133004, + -0.79156387 -0.54421294 0.27795497, + -0.79055762 -0.53561777 0.29687086, + -0.76111019 -0.56731009 0.31443709, + -0.75975585 -0.5570789 0.33531192, + -0.72804374 -0.58734179 0.35352787, + -0.72627592 -0.57529193 0.37624794, + -0.69223779 -0.60396987 0.3950029, + -0.69002604 -0.59008408 0.41912407, + -0.65327507 -0.61726207 0.43842807, + -0.65058523 -0.60135925 0.46379519, + -0.61089689 -0.62691784 0.48350689, + -0.60768926 -0.60869926 0.51009721, + -0.56572914 -0.63201219 0.5296331, + -0.56199008 -0.61120504 0.55731106, + -0.51777989 -0.63216782 0.57642686, + -0.51362401 -0.60903603 0.60437202, + -0.46702304 -0.62765509 0.62284708, + -0.46252611 -0.60204214 0.65085715, + -0.41359916 -0.61823922 0.66836822, + -0.40886378 -0.58994472 0.69627267, + -0.35853708 -0.60346812 0.7122342, + -0.35370803 -0.57240605 0.73975807, + -0.30241495 -0.58331186 0.75385183, + -0.29776901 -0.55010903 0.78020102, + -0.245524 -0.55861002 0.79225802, + -0.24126694 -0.52336186 0.81724083, + -0.18849392 -0.52962583 0.82702273, + -0.18482801 -0.49232906 0.85055912, + -0.13242503 -0.49654812 0.85784817, + -0.12955897 -0.45733789 0.87980479, + -0.07790681 -0.45982406 0.8845861, + -0.076065816 -0.4193891 0.90461421, + -0.025344295 -0.42047095 0.9069519, + -0.024693409 -0.37908015 0.92503434, + 0.025095595 -0.3790769 0.92502475, + 0.025747191 -0.42055485 0.90690172, + 0.076510333 -0.41946116 0.90454328, + 0.078353323 -0.45996511 0.88447326, + 0.13004501 -0.45746505 0.8796671, + 0.13290602 -0.49662206 0.8577311, + 0.18539105 -0.49238119 0.85040629, + 0.18904905 -0.52961314 0.82690418, + 0.24181803 -0.52333206 0.81709713, + 0.24607302 -0.55857408 0.79211313, + 0.29828504 -0.55005908 0.78003913, + 0.30292803 -0.58325207 0.75369209, + 0.35420904 -0.57233006 0.73957705, + 0.35902196 -0.60328394 0.71214592, + 0.40933475 -0.58974564 0.69616461, + 0.41406822 -0.61802232 0.66827828, + 0.46292412 -0.60183012 0.65077019, + 0.46741611 -0.62741315 0.62279612, + 0.51396918 -0.60879827 0.60431826, + 0.51812625 -0.6319173 0.57639033, + 0.56230694 -0.61095291 0.55726796, + 0.56604284 -0.63171977 0.52964681, + 0.60795903 -0.60841805 0.51011103, + 0.61117238 -0.62664133 0.48351729, + 0.65078819 -0.60111815 0.46382311, + 0.6534813 -0.61700827 0.4384782, + 0.69019705 -0.58984709 0.41917607, + 0.69241077 -0.60371274 0.39509284, + 0.72642106 -0.57505107 0.37633607, + 0.72819197 -0.58709103 0.35363901, + 0.7598753 -0.55684918 0.33542311, + 0.76122862 -0.56704569 0.31462684, + 0.79065597 -0.53537202 0.297052, + 0.79166311 -0.54392904 0.27822804, + 0.81854701 -0.51141697 0.26159799, + 0.81928283 -0.51861089 0.24457794, + 0.84379989 -0.48538795 0.22891097, + 0.84432191 -0.49137595 0.21370597, + 0.86685812 -0.45718807 0.19883703, + 0.86721283 -0.46205488 0.18559995, + 0.88788772 -0.42690685 0.17148194, + 0.88812369 -0.43080387 0.16013893, + 0.90673625 -0.39527309 0.14693102, + 0.90689009 -0.39832306 0.13743801, + 0.92360586 -0.36237898 0.12503499, + 0.92609948 -0.35082379 0.13878891, + 0.92613065 -0.35081187 0.13861096, + 0.90821987 -0.38921395 0.15378298, + 0.90795922 -0.38589808 0.16337904, + 0.88954097 -0.42070401 0.178115, + 0.88916427 -0.41647714 0.18956207, + 0.86867881 -0.45086989 0.20521596, + 0.86814499 -0.445602 0.218548, + 0.84576583 -0.47903988 0.23494893, + 0.84503043 -0.47264323 0.2500641, + 0.82063472 -0.50511384 0.26724291, + 0.81964183 -0.49742189 0.28418094, + 0.79285681 -0.5291419 0.30230293, + 0.79153019 -0.51989913 0.32122409, + 0.76217568 -0.55072981 0.34027189, + 0.76044381 -0.53973991 0.3611179, + 0.72879517 -0.56910211 0.38076308, + 0.72662818 -0.55637515 0.40306109, + 0.69261807 -0.58413106 0.42316806, + 0.68996465 -0.56946069 0.4468368, + 0.65323997 -0.59566492 0.46739793, + 0.65004641 -0.57876337 0.49241531, + 0.61041564 -0.60327762 0.5132727, + 0.60665596 -0.58390594 0.53946495, + 0.56473708 -0.60616606 0.56003106, + 0.56049401 -0.58449298 0.586698, + 0.51633304 -0.60441607 0.60669708, + 0.51165986 -0.58028787 0.63361681, + 0.46520311 -0.59785914 0.65280217, + 0.46017995 -0.57109892 0.67976493, + 0.41144714 -0.58628523 0.69784021, + 0.40618891 -0.55671185 0.72462583, + 0.35618702 -0.56927705 0.74098206, + 0.35096309 -0.53746915 0.7667802, + 0.30001813 -0.54753816 0.7811473, + 0.295019 -0.51354098 0.80575401, + 0.24328606 -0.5213151 0.81795019, + 0.23871803 -0.48515907 0.84121013, + 0.18658391 -0.49082875 0.85104257, + 0.18265991 -0.4525758 0.87281758, + 0.13094205 -0.45635715 0.88010931, + 0.12792103 -0.41663808 0.90002722, + 0.077037789 -0.41884094 0.90478587, + 0.075106084 -0.3779299 0.92278278, + 0.025270494 -0.3788799 0.92510074, + 0.024589991 -0.33703589 0.94117063, + -0.024235494 -0.3370389 0.94117874, + -0.024915794 -0.3788299 0.92513078, + -0.07471057 -0.37788886 0.92283165, + -0.076639101 -0.418713 0.90487897, + -0.12743205 -0.41652414 0.90014929, + -0.13045396 -0.45623186 0.8802467, + -0.18213904 -0.45246813 0.8729822, + -0.18606506 -0.49072117 0.85121828, + -0.23821403 -0.48506507 0.84140712, + -0.242792 -0.52126801 0.81812698, + -0.29449287 -0.51351684 0.80596173, + -0.29950407 -0.5475871 0.7813102, + -0.3504349 -0.53753889 0.76697284, + -0.35566711 -0.5693872 0.74114722, + -0.40577608 -0.55681312 0.72477919, + -0.41103795 -0.58638793 0.69799495, + -0.45978311 -0.57121611 0.67993516, + -0.46482006 -0.59804904 0.65290105, + -0.51130801 -0.58048201 0.63372302, + -0.51598895 -0.60465795 0.60674894, + -0.56016499 -0.584741 0.58676499, + -0.56441104 -0.60644203 0.56006104, + -0.60640097 -0.58415693 0.53947991, + -0.61015993 -0.60353696 0.51327193, + -0.64983916 -0.57900214 0.49240813, + -0.65303296 -0.59592396 0.46735695, + -0.68978107 -0.56971204 0.44680005, + -0.69243497 -0.58440393 0.42309093, + -0.72647494 -0.55663097 0.40298393, + -0.72864091 -0.56937593 0.38064894, + -0.7603147 -0.53999585 0.36100689, + -0.76204413 -0.55100006 0.34012902, + -0.79143131 -0.52013916 0.32107911, + -0.79275566 -0.52940577 0.30210584, + -0.81956911 -0.49765307 0.28398603, + -0.82056189 -0.50538892 0.26694596, + -0.8449809 -0.47288394 0.24977598, + -0.84571409 -0.47930905 0.23458603, + -0.86810881 -0.44583988 0.21820596, + -0.86864185 -0.45115095 0.20475397, + -0.88913798 -0.416729 0.18913101, + -0.88950968 -0.42096385 0.17765693, + -0.90794957 -0.38610381 0.16294593, + -0.90820527 -0.38941014 0.15337206, + -0.92611867 -0.35098988 0.13823995, + -0.92566991 -0.34552497 0.15410298, + -0.90932989 -0.37999594 0.16947599, + -0.90896028 -0.37639314 0.17921905, + -0.89068514 -0.41046605 0.19544204, + -0.89016467 -0.40587986 0.20704693, + -0.86980373 -0.43951586 0.22420393, + -0.86909181 -0.4338659 0.23757094, + -0.8468166 -0.46652478 0.25545287, + -0.84585685 -0.45963287 0.27067295, + -0.8215369 -0.49129593 0.28931898, + -0.82026082 -0.48296487 0.30645895, + -0.79351783 -0.51383287 0.32604492, + -0.79185462 -0.50386977 0.34508184, + -0.76250213 -0.53380007 0.36557904, + -0.76041198 -0.52218503 0.38613001, + -0.72873974 -0.5506078 0.40714785, + -0.72616464 -0.53714275 0.42914179, + -0.69209784 -0.56392688 0.45054087, + -0.68897092 -0.54832494 0.47398195, + -0.65218872 -0.57349271 0.49573776, + -0.6484707 -0.55553573 0.52044779, + -0.60875696 -0.57897395 0.54240596, + -0.60448927 -0.5587132 0.56783116, + -0.56252515 -0.57987118 0.58933425, + -0.55775803 -0.55723208 0.61514103, + -0.51359779 -0.57604772 0.63591373, + -0.50837111 -0.55077612 0.6619702, + -0.46196511 -0.5672521 0.68177217, + -0.45636806 -0.53917706 0.70782506, + -0.40785575 -0.55326867 0.72632456, + -0.40213916 -0.52283716 0.75161529, + -0.35238603 -0.53441608 0.76826012, + -0.34674698 -0.50175494 0.79246986, + -0.29620495 -0.51093787 0.8069728, + -0.2908251 -0.47599018 0.82997233, + -0.23967089 -0.48299375 0.8421846, + -0.23476508 -0.44580615 0.86379528, + -0.18334392 -0.45084879 0.87356758, + -0.17920202 -0.41207206 0.89335513, + -0.12832302 -0.41538906 0.90054715, + -0.12515797 -0.37531692 0.91840774, + -0.07526309 -0.37721893 0.92306089, + -0.073244981 -0.3359859 0.93901473, + -0.024450706 -0.33679008 0.94126225, + -0.023742694 -0.29484293 0.95525074, + 0.024004195 -0.29484093 0.95524478, + 0.024711797 -0.33689496 0.9412179, + 0.073562361 -0.33608484 0.93895453, + 0.075581573 -0.37735385 0.92297965, + 0.12558404 -0.37544009 0.91829926, + 0.12875201 -0.41557705 0.90039915, + 0.17966996 -0.4122459 0.89318079, + 0.18380904 -0.45103213 0.87337518, + 0.23527886 -0.44596872 0.86357147, + 0.24017406 -0.48308811 0.84198719, + 0.29134101 -0.47606599 0.82974797, + 0.29671502 -0.51098406 0.80675614, + 0.34723699 -0.50178701 0.79223502, + 0.35286787 -0.53441781 0.76803768, + 0.40258694 -0.52282792 0.75138187, + 0.40828091 -0.55314386 0.72618079, + 0.45681587 -0.53902787 0.70764983, + 0.46240282 -0.56705582 0.68163878, + 0.50874007 -0.55058807 0.66184306, + 0.51396006 -0.57582808 0.63582003, + 0.55807364 -0.55701667 0.61504966, + 0.56284004 -0.57964504 0.58925605, + 0.60476214 -0.5584951 0.5677551, + 0.60901904 -0.57869905 0.54240507, + 0.64869392 -0.55527395 0.52044892, + 0.65241176 -0.5732078 0.49577382, + 0.68916994 -0.54804796 0.47401294, + 0.69229692 -0.56362891 0.45060793, + 0.72632062 -0.53687179 0.4292168, + 0.72889817 -0.55032915 0.40724108, + 0.76052487 -0.52194291 0.38623494, + 0.76262128 -0.53356117 0.36567912, + 0.79195184 -0.50364989 0.34517992, + 0.79361516 -0.51358712 0.32619509, + 0.82033086 -0.48274994 0.30660996, + 0.82160771 -0.49105781 0.2895219, + 0.84591669 -0.45941082 0.27086291, + 0.8468731 -0.46624407 0.25577804, + 0.86912769 -0.43362284 0.23788291, + 0.86984199 -0.439248 0.22458, + 0.89018142 -0.40565917 0.2074071, + 0.89070439 -0.41021922 0.19587208, + 0.9089669 -0.37618494 0.17962198, + 0.90933889 -0.37977093 0.16993198, + 0.92567301 -0.34533 0.154521, + 0.9278329 -0.33336198 0.16731998, + 0.94095451 -0.30256087 0.15185992, + 0.94173086 -0.30968896 0.13128498, + 0.95357662 -0.27726492 0.11753996, + 0.95399511 -0.28216904 0.10136101, + 0.96448678 -0.24857894 0.089295477, + 0.96471924 -0.25212005 0.075843714, + 0.97391498 -0.21729399 0.065367401, + 0.97388846 -0.2169531 0.066878729, + 0.98087525 -0.18600105 0.057337016, + 0.98066938 -0.18508406 0.063494921, + 0.98707521 -0.15158603 0.05200281, + 0.98708552 -0.15160093 0.051762573, + 0.99310189 -0.11096498 0.037887797, + 0.9934209 -0.11124098 0.027211396, + 0.99760813 -0.06714461 0.016424801, + 0.99769467 -0.06722188 0.0092979958, + 0.99974853 -0.022213088 0.0030724786, + 0.99975288 -0.022225197 0.00050844793, + 0.99999577 0.0029003292 -6.6350884e-005, + 0.99999577 0.0029002794 2.3094397e-006, + 0.99969876 -0.024546094 -1.9545594e-005, + 0.99970311 -0.024369104 7.5871205e-005, + 0.99854845 -0.051458728 -0.015911408, + 0.99854785 0.051483892 -0.015865197, + 0.9970569 0.07666409 -0.00047176893, + 0.99688375 0.076665185 -0.018577896, + 0.99687886 0.076728493 -0.018579498, + 0.99187237 0.12532805 0.021957507, + 0.99210924 0.12537503 0.00058345712, + 0.99209064 0.12552196 0.00058357377, + 0.99182034 0.12550704 -0.023245808, + 0.99182862 0.12544195 -0.023243792, + 0.98721611 0.15884602 0.013128602, + 0.98696375 0.15861796 -0.027256895, + 0.99346888 0.11245499 -0.019324299, + 0.99303663 0.11223996 -0.035782687, + 0.99757111 0.066364504 -0.021157302, + 0.99734849 0.066143431 -0.030349515, + 0.99972153 0.021448091 -0.0098413052, + 0.99971563 0.021422993 -0.010472996, + 0.99972576 -0.021040494 0.010285997, + 0.99972862 -0.021060392 0.009956466, + 0.99782389 -0.059610393 0.028181197, + 0.99786925 -0.059964515 0.025713105, + 0.99471426 -0.094371222 0.040466912, + 0.99473089 -0.094565682 0.039594695, + 0.99009466 -0.12950796 0.054224983, + 0.98994738 -0.12789305 0.060395923, + 0.98394549 -0.16138007 0.076209739, + 0.98368949 -0.15900907 0.084089935, + 0.97643775 -0.19076596 0.10088398, + 0.97593665 -0.18679094 0.11250196, + 0.96738124 -0.21700504 0.13070004, + 0.96654677 -0.21136196 0.14530496, + 0.95658511 -0.24017303 0.16511202, + 0.95524752 -0.23240089 0.18300791, + 0.94375122 -0.25978005 0.20456804, + 0.94242185 -0.25282398 0.21890897, + 0.92816877 -0.28134993 0.24360794, + 0.92717034 -0.2767041 0.25256708, + 0.91109711 -0.30443904 0.27788302, + 0.90975767 -0.29863387 0.2883729, + 0.89161032 -0.32572711 0.31453612, + 0.88984221 -0.31854609 0.32666409, + 0.86943388 -0.34492296 0.35371298, + 0.86713499 -0.33613399 0.36754701, + 0.84461689 -0.36130497 0.39507094, + 0.84176081 -0.35094291 0.4102169, + 0.81699413 -0.37486202 0.43817705, + 0.81348819 -0.36270109 0.45462611, + 0.78613514 -0.38544807 0.48313707, + 0.78188699 -0.37124801 0.50082701, + 0.75177318 -0.39268708 0.5297491, + 0.74669993 -0.37620193 0.54855394, + 0.71419966 -0.39587283 0.57723773, + 0.70835125 -0.37721515 0.59661323, + 0.67352283 -0.3950139 0.62476486, + 0.66692007 -0.37411204 0.64440507, + 0.62948281 -0.39012092 0.67197984, + 0.62210923 -0.36669412 0.69174826, + 0.58209181 -0.38083485 0.71842474, + 0.574018 -0.35477501 0.73799598, + 0.53220618 -0.36680713 0.7630263, + 0.52364677 -0.33836785 0.78185767, + 0.48030293 -0.34836298 0.80495489, + 0.47145417 -0.31766111 0.82269228, + 0.42667708 -0.32577109 0.84369415, + 0.41773707 -0.29283002 0.86008513, + 0.37180787 -0.29919189 0.87877369, + 0.36307693 -0.26434794 0.89347374, + 0.3168999 -0.2690849 0.90948772, + 0.30871797 -0.23289996 0.92219889, + 0.26281703 -0.23625302 0.9354741, + 0.25534385 -0.19860888 0.94623148, + 0.20981905 -0.20084605 0.95688921, + 0.20452 -0.169138 0.96413898, + 0.15940194 -0.17058094 0.97236466, + 0.15608306 -0.14544904 0.97697634, + 0.11256602 -0.14631902 0.98281211, + 0.109549 -0.114203 0.98739898, + 0.066471174 -0.11464096 0.99118066, + 0.064519122 -0.080003031 0.99470437, + 0.021861801 -0.080150798 0.99654299, + 0.021193493 -0.044698086 0.99877566, + -0.020891301 -0.044698402 0.9987821, + -0.021555208 -0.080142431 0.99655038, + -0.064130306 -0.079996005 0.99473011, + -0.066074982 -0.11466197 0.99120474, + -0.10921305 -0.11422605 0.98743349, + -0.11223495 -0.14653693 0.98281753, + -0.15585798 -0.14566599 0.97697985, + -0.15919299 -0.17097899 0.97232902, + -0.2044431 -0.16953008 0.96408647, + -0.209686 -0.200919 0.95690298, + -0.25520492 -0.19868192 0.94625366, + -0.26261294 -0.23597795 0.93560076, + -0.30850601 -0.23263399 0.922337, + -0.31663308 -0.26854506 0.90974021, + -0.36270109 -0.26383406 0.89377826, + -0.37141913 -0.29859111 0.87914228, + -0.41734207 -0.29225004 0.86047411, + -0.4262782 -0.32512915 0.84414339, + -0.47097811 -0.3170611 0.82319617, + -0.47985017 -0.34779513 0.80547029, + -0.52317989 -0.33783391 0.78240085, + -0.53178406 -0.36637703 0.7635271, + -0.57357216 -0.35438213 0.73853123, + -0.58170289 -0.38058692 0.71887082, + -0.62174892 -0.36646396 0.69219393, + -0.62916577 -0.39000386 0.67234474, + -0.66660976 -0.37401587 0.64478177, + -0.67326015 -0.3950451 0.62502819, + -0.70813608 -0.37723807 0.59685403, + -0.71400696 -0.39595494 0.57741994, + -0.74651825 -0.37628916 0.54874116, + -0.75161791 -0.39285594 0.52984393, + -0.78176016 -0.3714031 0.5009101, + -0.78602684 -0.3856689 0.48313689, + -0.81340283 -0.36290291 0.45461789, + -0.81691486 -0.37509093 0.43812895, + -0.84169984 -0.3511509 0.41016391, + -0.84456527 -0.36155111 0.39495614, + -0.86709768 -0.33635488 0.36743289, + -0.8693971 -0.34515902 0.35357302, + -0.88982153 -0.31875017 0.32652122, + -0.89158797 -0.325937 0.31438199, + -0.90975112 -0.29880702 0.28821403, + -0.91109198 -0.30462599 0.277695, + -0.92716736 -0.27687109 0.25239509, + -0.92816538 -0.28152409 0.24342009, + -0.94242924 -0.25295907 0.21872105, + -0.94375777 -0.25992894 0.20434795, + -0.94379377 -0.25974894 0.20441096, + -0.92840725 -0.29199106 0.22978505, + -0.92752659 -0.28759184 0.23871589, + -0.91151386 -0.31645596 0.26267496, + -0.91033369 -0.31097189 0.27310991, + -0.89226979 -0.33924291 0.29794094, + -0.89071232 -0.33247212 0.30999011, + -0.87043017 -0.36006409 0.3357161, + -0.86840719 -0.35179609 0.3494401, + -0.84603888 -0.37823793 0.37570494, + -0.84345913 -0.36826503 0.39109805, + -0.81886184 -0.39349091 0.4178879, + -0.81569469 -0.38182384 0.43457186, + -0.78852165 -0.40593183 0.46200979, + -0.78469145 -0.39237124 0.4799003, + -0.754758 -0.415232 0.50786102, + -0.75016868 -0.39948285 0.5269348, + -0.71787322 -0.42058316 0.5547682, + -0.71246099 -0.40240899 0.574862, + -0.67776394 -0.42165893 0.60236192, + -0.67162526 -0.40127715 0.62281322, + -0.63431495 -0.41870794 0.64986795, + -0.62746108 -0.39593405 0.67046905, + -0.58746308 -0.41149607 0.69682008, + -0.57994211 -0.38617408 0.71731216, + -0.53807104 -0.39956206 0.74217904, + -0.52998424 -0.37160018 0.76225334, + -0.48647895 -0.38285494 0.78534091, + -0.47806188 -0.35254091 0.80446982, + -0.43300408 -0.36179909 0.82559615, + -0.4245168 -0.32940584 0.84337258, + -0.37807307 -0.33681202 0.86233312, + -0.36972591 -0.30235693 0.87856877, + -0.32295799 -0.307978 0.89490098, + -0.31503788 -0.2718119 0.90932369, + -0.268347 -0.27589199 0.92297, + -0.26118797 -0.23870097 0.93530887, + -0.2147159 -0.24151789 0.94634354, + -0.20845801 -0.20309 0.95671302, + -0.16244498 -0.20489398 0.9652099, + -0.158235 -0.17244799 0.97222602, + -0.11310998 -0.17352799 0.9783119, + -0.11067495 -0.14756493 0.98284054, + -0.066928968 -0.14814393 0.98669851, + -0.065093905 -0.11527002 0.99119914, + -0.021877 -0.115488 0.99306798, + -0.021224495 -0.080336981 0.99654174, + 0.021546599 -0.080336392 0.99653488, + 0.022208298 -0.11547699 0.9930619, + 0.065477721 -0.11525705 0.99117535, + 0.0673199 -0.148003 0.98669302, + 0.11088697 -0.14742497 0.98283774, + 0.11331595 -0.17323191 0.97834051, + 0.15837505 -0.17215405 0.97225535, + 0.16261199 -0.20480397 0.9652009, + 0.20860003 -0.20300002 0.9567011, + 0.21490495 -0.24174494 0.94624275, + 0.26142192 -0.23891991 0.93518764, + 0.26862001 -0.27634501 0.922755, + 0.31535488 -0.27224991 0.90908271, + 0.32329616 -0.30854815 0.89458239, + 0.37014213 -0.30290011 0.87820631, + 0.3784861 -0.33738407 0.86192816, + 0.42495701 -0.32995 0.84293801, + 0.43343115 -0.36234313 0.82513332, + 0.47853923 -0.35304618 0.80396438, + 0.48691183 -0.38324186 0.78488368, + 0.53043276 -0.37195581 0.76176763, + 0.53847474 -0.39979881 0.74175864, + 0.58034396 -0.38638595 0.71687293, + 0.58781993 -0.41159093 0.69646293, + 0.62778896 -0.39601895 0.67011195, + 0.63459992 -0.41866693 0.64961594, + 0.67189574 -0.40122685 0.62255377, + 0.67801106 -0.42154706 0.60216206, + 0.71266079 -0.40230986 0.57468385, + 0.71804607 -0.42039907 0.55468404, + 0.75033027 -0.39929914 0.5268442, + 0.75490868 -0.41501185 0.50781679, + 0.78479713 -0.39218205 0.47988206, + 0.78861982 -0.40570891 0.46203789, + 0.81577301 -0.38161999 0.43460399, + 0.8189342 -0.39325908 0.4179641, + 0.84350884 -0.3680599 0.39118391, + 0.84608918 -0.37803108 0.3758001, + 0.86843884 -0.35161692 0.3495419, + 0.8704561 -0.35985103 0.33587703, + 0.89073688 -0.33227098 0.31013498, + 0.89229411 -0.33902702 0.29811403, + 0.91034102 -0.310794 0.27328801, + 0.91152412 -0.31627703 0.26285502, + 0.92753088 -0.28743696 0.23888597, + 0.92903399 -0.295223 0.223023, + 0.91172576 -0.32778192 0.24761894, + 0.91068888 -0.32258996 0.25803396, + 0.892703 -0.351915 0.28149101, + 0.89133477 -0.34552091 0.29349193, + 0.87114269 -0.37424189 0.31788889, + 0.86937171 -0.36647588 0.33149388, + 0.84713787 -0.39407495 0.35645798, + 0.84488201 -0.38473499 0.37169001, + 0.82045281 -0.41117391 0.39723191, + 0.81760859 -0.39998582 0.41415879, + 0.79062814 -0.42535806 0.44042906, + 0.78718197 -0.41238099 0.45857, + 0.75747788 -0.43654695 0.48544195, + 0.75336319 -0.4215731 0.5046981, + 0.72126716 -0.44404411 0.53160012, + 0.71640599 -0.42678401 0.55192202, + 0.6819225 -0.44742367 0.57861358, + 0.67628884 -0.4277029 0.5997529, + 0.63912582 -0.44655287 0.62618583, + 0.63281482 -0.4245179 0.64755684, + 0.59289199 -0.441502 0.67346501, + 0.58598125 -0.41711414 0.69472426, + 0.54408085 -0.43189192 0.71933681, + 0.53661895 -0.40491495 0.74032694, + 0.49296519 -0.41749814 0.76333529, + 0.48508319 -0.38787714 0.78373832, + 0.43966699 -0.398386 0.80497301, + 0.4316439 -0.3665089 0.82422984, + 0.38470784 -0.37503985 0.8434127, + 0.37677699 -0.34105 0.86123401, + 0.32932699 -0.347644 0.87788802, + 0.32172087 -0.31166488 0.89406973, + 0.27417699 -0.31655198 0.9080869, + 0.26718199 -0.27898499 0.922378, + 0.21972799 -0.28243399 0.93378299, + 0.21365005 -0.24390607 0.94597226, + 0.16656592 -0.24618287 0.95480353, + 0.16154996 -0.20650496 0.96501678, + 0.11559401 -0.20785204 0.97130615, + 0.11250102 -0.17437701 0.97823113, + 0.067707382 -0.17508896 0.98222178, + 0.066221721 -0.14868806 0.98666435, + 0.022478005 -0.14897703 0.98858523, + 0.021848906 -0.11568903 0.99304521, + -0.021535499 -0.11568999 0.99305189, + -0.022150092 -0.14900994 0.98858762, + -0.066000901 -0.14872199 0.98667401, + -0.067488506 -0.17528401 0.98220211, + -0.11236697 -0.17457196 0.97821176, + -0.11544401 -0.20788403 0.97131711, + -0.16141894 -0.20653793 0.96503162, + -0.16640602 -0.24596304 0.95488811, + -0.21345297 -0.24369197 0.94607186, + -0.21950497 -0.28202197 0.9339599, + -0.2668789 -0.27858791 0.92258567, + -0.27386209 -0.31605712 0.90835428, + -0.32133415 -0.31119215 0.89437342, + -0.328942 -0.34714201 0.87823099, + -0.37631792 -0.34057692 0.8616218, + -0.38426509 -0.3745971 0.84381115, + -0.43115905 -0.36609802 0.82466614, + -0.43921316 -0.39804715 0.80538827, + -0.48462006 -0.38756505 0.78417909, + -0.49253711 -0.41727909 0.76373118, + -0.53620023 -0.40471718 0.74073833, + -0.54369819 -0.43179315 0.71968526, + -0.58561689 -0.41703191 0.69508082, + -0.59257299 -0.441558 0.67370898, + -0.63252091 -0.42457893 0.64780396, + -0.63884884 -0.44665888 0.62639284, + -0.67604083 -0.42780891 0.59995687, + -0.68170184 -0.44761989 0.57872188, + -0.71623224 -0.42696014 0.55201119, + -0.72110003 -0.44424707 0.53165704, + -0.75321519 -0.42176908 0.50475514, + -0.75734586 -0.43680394 0.48541695, + -0.78707689 -0.41261595 0.45853895, + -0.79052532 -0.42561015 0.44037014, + -0.81753385 -0.40021092 0.4140889, + -0.82037681 -0.41140291 0.39715192, + -0.84482914 -0.38493606 0.37160203, + -0.84709281 -0.3943229 0.35629091, + -0.86934072 -0.36669689 0.3313309, + -0.87110716 -0.37446108 0.3177281, + -0.89131021 -0.34571609 0.29333705, + -0.89267778 -0.35211891 0.28131595, + -0.91067672 -0.32276189 0.25786191, + -0.91171432 -0.32796913 0.24741308, + -0.9276951 -0.29804304 0.22483803, + -0.9284479 -0.30210397 0.21614297, + -0.94265276 -0.27145293 0.19421396, + -0.94365454 -0.27758387 0.18017592, + -0.92829663 -0.31189689 0.20244892, + -0.92765987 -0.30814597 0.21093397, + -0.91167569 -0.33907789 0.23210691, + -0.91079414 -0.33424702 0.24234903, + -0.89281458 -0.36465782 0.26439887, + -0.89162469 -0.35858488 0.27644593, + -0.87146968 -0.38842186 0.29944789, + -0.86992383 -0.38105091 0.31310192, + -0.84775215 -0.40979809 0.33672208, + -0.84578329 -0.40097615 0.35195011, + -0.8214395 -0.42861074 0.37620476, + -0.81894988 -0.41805294 0.39313194, + -0.7920748 -0.44468588 0.41817692, + -0.78898531 -0.43221015 0.43668815, + -0.759408 -0.45767701 0.462419, + -0.75570214 -0.44328406 0.48209307, + -0.72372681 -0.46708989 0.50798291, + -0.7193532 -0.45058912 0.52867812, + -0.68496972 -0.47259676 0.55449873, + -0.67987704 -0.45372805 0.57610607, + -0.64278984 -0.47397089 0.60180789, + -0.63695592 -0.45250294 0.62412196, + -0.59707308 -0.47086707 0.64945203, + -0.59064186 -0.44704887 0.67178082, + -0.54869324 -0.46316519 0.69599837, + -0.54174787 -0.43690392 0.71806979, + -0.49793112 -0.45077011 0.7408582, + -0.49058989 -0.42199191 0.76239383, + -0.44491506 -0.43370306 0.7835511, + -0.43731493 -0.40229294 0.80431086, + -0.39001292 -0.41191092 0.82354081, + -0.38246191 -0.3783229 0.84296781, + -0.33449385 -0.38586882 0.85977858, + -0.32724988 -0.35038087 0.87757671, + -0.27903593 -0.35606992 0.89182574, + -0.27232313 -0.31879416 0.9078604, + -0.22409403 -0.32288903 0.91952413, + -0.21818204 -0.28421807 0.93360424, + -0.17015894 -0.28698692 0.94270062, + -0.16533205 -0.24764407 0.95464021, + -0.118302 -0.249336 0.961164, + -0.11467005 -0.20901811 0.97116548, + -0.068916678 -0.20990592 0.97528964, + -0.067036599 -0.175871 0.98212802, + -0.022333793 -0.17622393 0.98409665, + -0.021833612 -0.14919707 0.98856646, + 0.022106089 -0.14919592 0.9885605, + 0.022612611 -0.17612308 0.98410845, + 0.067182921 -0.17576906 0.98213637, + 0.069066688 -0.20986596 0.97528774, + 0.11482698 -0.20897597 0.97115588, + 0.118468 -0.24945 0.96111399, + 0.16556399 -0.24775197 0.9545719, + 0.17040505 -0.28726605 0.94257122, + 0.21849105 -0.28448606 0.93345022, + 0.224416 -0.323275 0.91930997, + 0.27270898 -0.31916296 0.90761489, + 0.27943194 -0.35651791 0.89152277, + 0.32767397 -0.35080996 0.87724686, + 0.33490813 -0.38628516 0.85943031, + 0.38293201 -0.37871099 0.84258002, + 0.39045805 -0.41222006 0.82317513, + 0.437796 -0.40257099 0.80391002, + 0.44536901 -0.433902 0.78318298, + 0.49103576 -0.42217079 0.76200765, + 0.49834889 -0.45086288 0.74052083, + 0.54214001 -0.436984 0.71772498, + 0.54904491 -0.46311587 0.69575381, + 0.59096205 -0.44699505 0.67153507, + 0.59737915 -0.47077513 0.64923716, + 0.63723171 -0.45240879 0.6239087, + 0.64303803 -0.47378007 0.60169303, + 0.68009877 -0.45354185 0.5759908, + 0.68517917 -0.47236413 0.55443811, + 0.71952808 -0.45037207 0.52862507, + 0.72389281 -0.46683589 0.50797987, + 0.75583118 -0.44305411 0.48210213, + 0.7595349 -0.45742694 0.46245795, + 0.78908634 -0.43198121 0.4367322, + 0.7921713 -0.44443014 0.41826615, + 0.81903243 -0.4178122 0.39321619, + 0.82151914 -0.42834207 0.37633705, + 0.84582698 -0.400754 0.35209799, + 0.84780014 -0.40957806 0.33686903, + 0.8699584 -0.38085419 0.31324515, + 0.87150586 -0.38821495 0.29961097, + 0.89165014 -0.35840103 0.27660203, + 0.89283973 -0.36445689 0.26459092, + 0.91080612 -0.33407804 0.24253704, + 0.91168529 -0.33888012 0.23235808, + 0.92766356 -0.30797485 0.2111679, + 0.9287799 -0.31487596 0.19550197, + 0.91141671 -0.34958288 0.21705192, + 0.91068143 -0.34514219 0.22701611, + 0.89269972 -0.37650785 0.24764691, + 0.89169788 -0.37088597 0.25945798, + 0.87156773 -0.40173185 0.2810359, + 0.87023157 -0.39474881 0.29473785, + 0.84810811 -0.42454106 0.31698203, + 0.84639573 -0.41617584 0.33228287, + 0.82213467 -0.44488585 0.35520589, + 0.81998229 -0.43498716 0.37204212, + 0.79321998 -0.46276 0.39579701, + 0.79052389 -0.45100093 0.41433093, + 0.76108509 -0.47767505 0.43883505, + 0.75778085 -0.46389288 0.45888087, + 0.7259562 -0.48894012 0.48365811, + 0.72204 -0.47315601 0.50475901, + 0.68780226 -0.49644017 0.52959919, + 0.68324304 -0.47847506 0.55158007, + 0.64630693 -0.50002396 0.57642293, + 0.64105892 -0.47955993 0.59922093, + 0.60126686 -0.49927789 0.62385887, + 0.59536594 -0.47621194 0.64711791, + 0.55342317 -0.49366418 0.67083424, + 0.54701489 -0.46819088 0.69395381, + 0.50312698 -0.48334101 0.71641099, + 0.49634799 -0.45549399 0.73902899, + 0.45046422 -0.46843821 0.76003134, + 0.44343105 -0.43805805 0.78196812, + 0.39572209 -0.44884112 0.80121517, + 0.38861606 -0.41588807 0.82220113, + 0.340096 -0.42445901 0.83914798, + 0.33321679 -0.38941577 0.85867447, + 0.28433505 -0.3959721 0.87313217, + 0.27793291 -0.35910287 0.89095372, + 0.22880693 -0.36391488 0.9028917, + 0.22311589 -0.32536885 0.91888756, + 0.17406301 -0.32868704 0.92826015, + 0.16933593 -0.28887984 0.94227052, + 0.12120596 -0.29095292 0.94902867, + 0.11768098 -0.25057897 0.96091688, + 0.070828326 -0.25169909 0.96521038, + 0.068610094 -0.21048297 0.97518688, + 0.023057012 -0.2109241 0.97723049, + 0.022421489 -0.1763529 0.98407155, + -0.022225998 -0.17635399 0.9840759, + -0.022861501 -0.21099803 0.9772191, + -0.068434089 -0.21055897 0.97518289, + -0.070644811 -0.25160202 0.96524912, + -0.11750097 -0.25048393 0.96096379, + -0.12101303 -0.29067606 0.94913822, + -0.16908398 -0.28861198 0.94239789, + -0.17380498 -0.32835796 0.92842489, + -0.22274986 -0.32505479 0.91908747, + -0.22843695 -0.3635439 0.90313476, + -0.2774789 -0.35875389 0.89123571, + -0.28388703 -0.39563406 0.87343115, + -0.33274913 -0.38909715 0.85900033, + -0.33964416 -0.42418122 0.8394714, + -0.38814199 -0.41563299 0.82255399, + -0.39526606 -0.44863605 0.8015551, + -0.44296816 -0.43787614 0.7823323, + -0.45003411 -0.46837312 0.76032621, + -0.49590695 -0.45545194 0.73935091, + -0.50271612 -0.48340213 0.71665817, + -0.54665595 -0.46824995 0.69419694, + -0.55308414 -0.49379012 0.67102116, + -0.59504175 -0.47634682 0.64731675, + -0.60096192 -0.49948493 0.62398696, + -0.64080781 -0.47975188 0.59933591, + -0.64605993 -0.50022894 0.57652193, + -0.68304503 -0.478661 0.55166399, + -0.68761694 -0.49667794 0.52961695, + -0.72187716 -0.47338411 0.50477815, + -0.72579992 -0.48920095 0.48362893, + -0.75765264 -0.46413478 0.45884779, + -0.76096088 -0.47794795 0.43875295, + -0.7904247 -0.45125285 0.41424584, + -0.79311889 -0.46301794 0.39569795, + -0.81990802 -0.43521601 0.37193799, + -0.82206011 -0.44513205 0.35507002, + -0.84634489 -0.41638994 0.33214396, + -0.84805667 -0.42476386 0.31682089, + -0.87019283 -0.39494991 0.29458293, + -0.87152946 -0.40194976 0.28084281, + -0.89167076 -0.37107992 0.25927395, + -0.89267325 -0.3767271 0.24740906, + -0.91067213 -0.34532002 0.22678304, + -0.91140878 -0.34979191 0.21674795, + -0.9274351 -0.31790003 0.19698703, + -0.92796934 -0.32138813 0.18863407, + -0.94225574 -0.28882095 0.16951896, + -0.94298422 -0.29432207 0.15542004, + -0.92746526 -0.33064109 0.17459905, + -0.92702544 -0.32738614 0.18287209, + -0.91092741 -0.36018419 0.20119309, + -0.91031772 -0.35600388 0.21114692, + -0.89226377 -0.38834691 0.23032995, + -0.89143622 -0.38310409 0.24201806, + -0.8712607 -0.41495484 0.26213992, + -0.87014973 -0.40844786 0.2756989, + -0.84800917 -0.43927613 0.29650807, + -0.84654361 -0.4313198 0.31197286, + -0.82228798 -0.461099 0.33351201, + -0.82042813 -0.45166805 0.35056204, + -0.79369479 -0.48055488 0.37298191, + -0.7913748 -0.46948588 0.39154691, + -0.7619791 -0.49734005 0.41477805, + -0.75910699 -0.48432499 0.434955, + -0.72735125 -0.51058817 0.45854118, + -0.723858 -0.49540499 0.480212, + -0.68968177 -0.51993585 0.50398982, + -0.68559402 -0.50268501 0.52656299, + -0.64869708 -0.52551603 0.55047709, + -0.64398599 -0.505952 0.57384199, + -0.60418105 -0.52698904 0.59770209, + -0.598849 -0.50489599 0.62165898, + -0.55689907 -0.52363205 0.64472705, + -0.55097824 -0.49880123 0.66904432, + -0.50695312 -0.51521009 0.69105518, + -0.50064081 -0.48799282 0.71499777, + -0.45455801 -0.50212097 0.73569798, + -0.44801107 -0.47253406 0.75894511, + -0.39996591 -0.48442787 0.77804685, + -0.393332 -0.45234001 0.80042398, + -0.34439003 -0.46189907 0.81734014, + -0.33786902 -0.42735207 0.83857912, + -0.28837806 -0.4347631 0.85312319, + -0.28228009 -0.39831915 0.87273127, + -0.23244694 -0.4038319 0.88480973, + -0.22701903 -0.36576304 0.90259612, + -0.17717502 -0.36962703 0.91213214, + -0.17263201 -0.33008003 0.92803311, + -0.12358303 -0.33254209 0.93495625, + -0.12014206 -0.29188314 0.94887847, + -0.072252363 -0.29324386 0.95330352, + -0.070114583 -0.25230294 0.96510476, + -0.023454696 -0.25285497 0.96721989, + -0.022707701 -0.211191 0.97718102, + 0.022844601 -0.21119003 0.9771781, + 0.023589389 -0.25290087 0.96720451, + 0.070339352 -0.25234485 0.9650774, + 0.072481811 -0.29340002 0.95323813, + 0.120426 -0.292034 0.94879597, + 0.12386803 -0.33275908 0.93484122, + 0.17297406 -0.33028811 0.92789537, + 0.17751996 -0.36990392 0.91195273, + 0.22746105 -0.3660211 0.90238023, + 0.23288989 -0.40411583 0.88456357, + 0.28277186 -0.39858282 0.8724516, + 0.28886497 -0.43503493 0.85281986, + 0.33833385 -0.42760879 0.83826059, + 0.3448351 -0.46208513 0.81704718, + 0.393812 -0.452499 0.800098, + 0.40042105 -0.48448506 0.77777714, + 0.44845399 -0.47257501 0.75865799, + 0.45498306 -0.50210208 0.73544806, + 0.50104004 -0.48796207 0.71473908, + 0.50733209 -0.51511204 0.69085008, + 0.5513078 -0.49870482 0.66884476, + 0.55720574 -0.52344775 0.64461172, + 0.59915304 -0.50470006 0.62152505, + 0.60447693 -0.52675992 0.59760493, + 0.64424092 -0.50573295 0.57374895, + 0.64893603 -0.52522403 0.55047405, + 0.6857962 -0.50241011 0.52656209, + 0.68988705 -0.51966709 0.50398606, + 0.72401094 -0.49516794 0.48022595, + 0.72750205 -0.51033205 0.45858705, + 0.75922179 -0.48409489 0.43501091, + 0.76209712 -0.49710405 0.41484407, + 0.79146802 -0.469271 0.39161599, + 0.79378819 -0.48032212 0.37308308, + 0.82049614 -0.45146307 0.35066703, + 0.82235771 -0.46087983 0.33364287, + 0.84659082 -0.43113092 0.31210595, + 0.84805518 -0.43906012 0.29669607, + 0.87018716 -0.40824908 0.27587506, + 0.87129784 -0.41473091 0.26237094, + 0.89146227 -0.3829051 0.24223706, + 0.89228886 -0.38811594 0.23062196, + 0.91032571 -0.35581589 0.21142893, + 0.91093278 -0.3599489 0.20158896, + 0.92702538 -0.32718113 0.18323906, + 0.92780685 -0.33336398 0.16745998, + 0.91024643 -0.37000719 0.18586609, + 0.90975571 -0.36612788 0.19569093, + 0.89162278 -0.3993189 0.21343195, + 0.89095509 -0.39447206 0.22492403, + 0.87071282 -0.42722291 0.24359794, + 0.86981088 -0.42121395 0.25691998, + 0.84764588 -0.45295295 0.27627897, + 0.84644049 -0.44555727 0.29157719, + 0.82219088 -0.47628993 0.31168896, + 0.82061714 -0.46737507 0.32885903, + 0.79392487 -0.49725693 0.34988397, + 0.79193372 -0.48675382 0.36866188, + 0.76260185 -0.51565993 0.39055493, + 0.76013827 -0.50342315 0.41079816, + 0.72847217 -0.53078413 0.4331241, + 0.72545278 -0.51649684 0.45491686, + 0.69138902 -0.54216999 0.47752801, + 0.68776196 -0.52563596 0.50068992, + 0.65095896 -0.54965794 0.52357292, + 0.64675444 -0.53093559 0.54755455, + 0.60705191 -0.55318588 0.57050288, + 0.60228109 -0.53211313 0.59507412, + 0.56034589 -0.55209291 0.61741889, + 0.55502409 -0.52840704 0.64244407, + 0.51098508 -0.54603803 0.66388005, + 0.50519109 -0.51965004 0.68901807, + 0.45895213 -0.53497612 0.70934016, + 0.45289999 -0.50621903 0.73391002, + 0.40461177 -0.5192377 0.75278252, + 0.39846492 -0.48808989 0.77652681, + 0.34910589 -0.49867982 0.79337472, + 0.34305099 -0.46515799 0.81605399, + 0.29300007 -0.47347611 0.8306452, + 0.2872479 -0.43764985 0.85202771, + 0.23666909 -0.44392514 0.86424428, + 0.23149493 -0.40623292 0.88395977, + 0.18078801 -0.41069606 0.89366913, + 0.17644 -0.371447 0.91153502, + 0.12642294 -0.37433884 0.91863358, + 0.12310696 -0.33378589 0.93457562, + 0.074096411 -0.3354201 0.93915021, + 0.072002865 -0.29401284 0.95308554, + 0.02412881 -0.29469311 0.95528734, + 0.023408297 -0.25312296 0.96715087, + -0.023235895 -0.25312394 0.96715474, + -0.023958391 -0.29458588 0.95532465, + -0.071730815 -0.29391205 0.95313722, + -0.073822588 -0.3352659 0.93922675, + -0.12276898 -0.33364096 0.93467188, + -0.126081 -0.374107 0.91877502, + -0.17605498 -0.37122497 0.91169989, + -0.18039991 -0.41041079 0.89387858, + -0.23104 -0.405967 0.88420099, + -0.23621795 -0.44366989 0.86449879, + -0.28673398 -0.43741995 0.85231888, + -0.29250905 -0.47336212 0.8308832, + -0.34255308 -0.46506312 0.8163172, + -0.34862292 -0.49863887 0.79361284, + -0.39799094 -0.48806593 0.7767849, + -0.40415406 -0.51926708 0.75300813, + -0.45245999 -0.50626302 0.73415101, + -0.45852911 -0.53508312 0.70953315, + -0.504803 -0.51976198 0.68921798, + -0.51061583 -0.54623181 0.66400474, + -0.5547142 -0.52859116 0.64256024, + -0.56004006 -0.55229205 0.61751807, + -0.60199207 -0.53231704 0.59518409, + -0.60677093 -0.55343193 0.57056296, + -0.64653915 -0.53115511 0.5475961, + -0.65074706 -0.54990005 0.52358204, + -0.68756121 -0.5258792 0.50071019, + -0.69119298 -0.54244798 0.477496, + -0.72529882 -0.51674891 0.45487589, + -0.72831964 -0.53105575 0.4330478, + -0.76001185 -0.50367594 0.41072193, + -0.76247728 -0.51594716 0.39041916, + -0.79182488 -0.48702693 0.36853498, + -0.79381269 -0.49753883 0.34973788, + -0.82053632 -0.46762219 0.32870913, + -0.82210946 -0.47655728 0.31149518, + -0.84638721 -0.44578612 0.29138207, + -0.84758842 -0.45318121 0.27608112, + -0.86977899 -0.42140099 0.25672099, + -0.87068313 -0.42745805 0.24329104, + -0.89092731 -0.39469415 0.22464408, + -0.89159822 -0.39959809 0.21301204, + -0.90974456 -0.36636582 0.19529691, + -0.91023421 -0.37027109 0.18540004, + -0.92643911 -0.33660603 0.16854401, + -0.92678314 -0.33959404 0.16046502, + -0.94128186 -0.30525896 0.14424099, + -0.94172525 -0.30982405 0.13100603, + -0.95357615 -0.27737504 0.11728501, + -0.95399725 -0.28241205 0.10066102, + -0.96449763 -0.24876191 0.088666968, + -0.96472663 -0.25243092 0.074707672, + -0.97393113 -0.21751803 0.064375311, + -0.9738875 -0.2169459 0.066914469, + -0.98087466 -0.18599394 0.057367578, + -0.98066235 -0.18505105 0.063698925, + -0.98706722 -0.15157802 0.052176412, + -0.98699486 -0.15146498 0.053846393, + -0.99304521 -0.11093203 0.03943691, + -0.99331939 -0.11115193 0.031011581, + -0.99759138 -0.066813521 0.018641107, + -0.99767298 -0.066906102 0.0131248, + -0.99974537 -0.022145908 0.0043443013, + -0.99975026 -0.022160506 0.0028855507, + -0.99965525 -0.026096705 -0.0029155207, + -0.99965674 -0.026036495 -0.0029197694, + -0.99966091 -0.026038697 -0.00029376097, + -0.99965936 -0.026098909 -0.00028897912, + -0.99928826 0.023198506 -0.029746408, + -0.99972624 0.023187406 -0.0031420006, + -0.99973178 0.022948094 -0.0031239393, + -0.99973589 0.022946699 -0.0012630599, + -0.99988055 1.2309195e-005 -0.015458393, + -0.99457926 0.10280802 -0.015579304, + -0.99740821 0.071942411 0.0011380102, + -0.99734187 0.071947694 -0.011522699, + -0.993626 0.112613 -0.00507815, + -0.99251014 0.12078101 -0.018321402, + -0.99267387 0.12078799 -0.0029871895, + -0.99267989 0.12073798 -0.0029982096, + -0.99251634 0.12073105 -0.018317007, + -0.98554665 0.16933294 -0.0049238582, + -0.9855569 0.16932899 0.0022853597, + -0.98555964 0.16931294 0.0022853492, + -0.98524851 0.16928193 -0.025081089, + -0.98524237 0.16931707 -0.025084609, + -0.98555374 0.16934796 0.0022731796, + -0.97874433 0.20453808 -0.014962906, + -0.95253462 0.30410388 -0.014089495, + -0.96421945 0.26508713 0.0031167914, + -0.96354336 0.26493409 -0.037340716, + -0.95446521 0.29832205 -0.0003386201, + -0.94918579 0.31180093 -0.042736288, + -0.95003653 0.31205285 -0.0073118769, + -0.95004791 0.31201798 -0.0073262393, + -0.94919711 0.31176704 -0.042733904, + -0.93356788 0.35820797 0.011753698, + -0.93362379 0.35823593 0.0036911492, + -0.93364024 0.3581931 0.003691121, + -0.93257499 0.35782599 -0.047586601, + -0.93256611 0.35784903 -0.047588408, + -0.93363112 0.35821703 0.0036861706, + -0.91483301 0.40358299 -0.0141886, + -0.91370797 0.403117 -0.0513262, + -0.9137277 0.40307286 -0.051322781, + -0.9149003 0.40355715 -0.0099496637, + -0.91625232 0.40043816 -0.011447104, + -0.8702181 0.49251705 -0.012146102, + -0.87091315 0.49127007 -0.012807302, + -0.86944711 0.49047905 -0.059094906, + -0.84570313 0.53335303 -0.017913101, + -0.8458401 0.53342205 0.0039481707, + -0.84583884 0.5334239 0.0039481693, + -0.84415752 0.5324167 -0.06269446, + -0.84417391 0.53239095 -0.062692292, + -0.84585518 0.53339809 0.0039526909, + -0.81864202 0.57424599 -0.0081757, + -0.81696761 0.57311571 -0.064047873, + -0.8169598 0.57312685 -0.064048886, + -0.8185544 0.57420731 -0.015965207, + -0.8149581 0.57937407 -0.013006002, + -0.51472777 0.85721856 -0.015220293, + -0.53675812 0.84373617 0.0003213631, + -0.53281814 0.83763719 -0.12028603, + -0.5328908 0.83759171 -0.12028096, + -0.57549798 0.81591201 -0.055584401, + -0.57641006 0.81716013 0.00096707011, + -0.57750815 0.81638432 0.00096644834, + -0.57393581 0.81142372 -0.11040496, + -0.57389987 0.81144881 -0.11040697, + -0.60911709 0.79037815 -0.065412618, + -0.594684 0.77084899 -0.228348, + -0.63620579 0.73974484 -0.21913394, + -0.60028404 0.69609904 -0.39383405, + -0.64241201 0.667005 -0.37737399, + -0.58581513 0.6051591 -0.53907609, + -0.46289501 0.46593899 -0.75407499, + -0.58074689 0.59334987 -0.55737686, + -0.55067587 0.60838985 -0.57150489, + -0.44004387 0.47934687 -0.75933385, + -0.46475205 0.47265506 -0.74873406, + -0.33258688 0.32759789 -0.8843447, + -0.35646087 0.32455489 -0.87612772, + -0.19837607 0.16164106 -0.96670538, + -0.21904607 0.16091307 -0.96235436, + -0.10095295 0.046828676 -0.99378854, + -0.095933452 0.046851978 -0.99428451, + -0.18256405 0.13483703 -0.97390425, + -0.16399007 0.13528505 -0.97714138, + -0.32464591 0.30914894 -0.89388579, + -0.30190396 0.31159997 -0.9009769, + -0.4369958 0.46737379 -0.76850265, + -0.41297886 0.47323382 -0.77813768, + -0.52198517 0.60680825 -0.59942925, + -0.5022012 0.61520022 -0.60771924, + -0.38676792 0.46638587 -0.79554683, + -0.41014194 0.46124995 -0.7867859, + -0.27318707 0.29524806 -0.91553122, + -0.29452199 0.293309 -0.90951997, + -0.13292103 0.10957303 -0.98505121, + -0.14961602 0.10931101 -0.98268312, + -0.040527888 -0.006868578 -0.99915475, + -0.038453691 -0.006869148 -0.99923676, + -0.11988306 0.084336534 -0.98919946, + -0.105062 0.084478997 -0.99087101, + -0.26644799 0.27732399 -0.92309099, + -0.246445 0.278851 -0.92817402, + -0.38415 0.45435899 -0.80373299, + -0.36132199 0.45887199 -0.81171602, + -0.47382799 0.611485 -0.63369799, + -0.45420778 0.61862171 -0.64109468, + -0.33694184 0.45097879 -0.82649159, + -0.35899112 0.44705814 -0.81930733, + -0.221442 0.26249999 -0.939179, + -0.24033706 0.26129407 -0.93486023, + -0.080478691 0.060428493 -0.99492288, + -0.07252714 0.042501319 -0.9964605, + -0.041837201 0.0150575 -0.99901098, + -0.21588589 0.24509688 -0.94515651, + -0.19818403 0.24603602 -0.9487831, + -0.33487508 0.43924311 -0.8336212, + -0.31349012 0.44265914 -0.8401053, + -0.42658892 0.61317688 -0.6648578, + -0.40714508 0.61922312 -0.67141318, + -0.29097304 0.43408906 -0.85258514, + -0.31171203 0.43111506 -0.84674412, + -0.17691799 0.23007697 -0.95695591, + -0.19333901 0.22935399 -0.95394802, + -0.039563183 0.015058893 -0.99910355, + -0.032661911 -0.0034930513 -0.99946034, + 0.035245705 -0.099311113 -0.99443209, + 0.0311622 -0.099325001 -0.99456698, + 0.0086439028 -0.071022324 -0.99743736, + -0.02724221 -0.07099852 -0.99710435, + -0.048082393 -0.047718294 -0.9977029, + -0.094592348 -0.047559522 -0.99437946, + -0.12042298 -0.021632697 -0.99248689, + -0.1787409 -0.02144039 -0.98366255, + -0.22123908 0.017566806 -0.97506136, + -0.29243505 0.017225804 -0.95613027, + -0.31924301 0.040245101 -0.94681799, + -0.39764115 0.038965516 -0.91671336, + -0.4186739 0.056220386 -0.90639478, + -0.50090891 0.053580791 -0.86383986, + -0.55223012 0.095661722 -0.8281852, + -0.63229203 0.088896111 -0.76961315, + -0.66609395 0.11834698 -0.73641896, + -0.7362982 0.10736502 -0.66808516, + -0.7540881 0.12455702 -0.64485407, + -0.81227732 0.11061703 -0.5726862, + -0.81989831 0.11906604 -0.55999118, + -0.8669318 0.10365798 -0.48752889, + -0.86852288 0.10573398 -0.48423994, + -0.90613639 0.090233043 -0.41324919, + -0.90472078 0.088023581 -0.41681191, + -0.93444097 0.073583297 -0.34843299, + -0.93175489 0.068499289 -0.35656798, + -0.95518976 0.055841785 -0.29067895, + -0.952353 0.049240299 -0.30099699, + -0.97071087 0.038787197 -0.23709898, + -0.96820486 0.031464096 -0.24817197, + -0.98236591 0.023516396 -0.18548399, + -0.98051554 0.016457593 -0.19575091, + -0.99084479 0.011310497 -0.13453098, + -0.98970187 0.0051969797 -0.14304999, + -0.99656999 0.0030044799 -0.082699999, + -0.99609214 -0.0012096001 -0.088311709, + -0.99960309 -0.00038586505 -0.028171604, + -0.99954075 -0.0020110996 -0.030235093, + -0.99957013 0.0019459903 0.029256204, + -0.99951202 0.0034308999 0.031048801, + -0.99579126 0.010066103 0.091095723, + -0.99566233 0.011178404 0.09236633, + -0.98859298 0.0180953 0.14952099, + -0.98822337 0.020117607 0.15169007, + -0.97806388 0.027386297 0.20649697, + -0.97719836 0.030949811 0.21006107, + -0.96405274 0.038730994 0.26287293, + -0.96257091 0.043711197 0.26748198, + -0.94681185 0.051897291 0.31757498, + -0.9445855 0.058332827 0.32304114, + -0.92633063 0.066941574 0.37071589, + -0.92322677 0.074925289 0.3768799, + -0.90257168 0.083950073 0.42227584, + -0.89842379 0.093674481 0.42902192, + -0.87551951 0.10307206 0.47206128, + -0.87016988 0.11470999 0.47921395, + -0.84545785 0.12432198 0.51936996, + -0.83940589 0.13675098 0.52601993, + -0.81304353 0.14648791 0.56347263, + -0.80707711 0.15825002 0.56884408, + -0.77883768 0.16810794 0.60427779, + -0.77114815 0.18280701 0.60984606, + -0.74104118 0.19280104 0.64318419, + -0.73204118 0.20958005 0.64822221, + -0.70070994 0.21948197 0.67884696, + -0.69057405 0.23804103 0.68296707, + -0.6581322 0.24779706 0.71095616, + -0.64690977 0.26811892 0.71387678, + -0.61318201 0.277744 0.73950398, + -0.60095197 0.29979196 0.74093294, + -0.56620514 0.30916205 0.76408815, + -0.55323595 0.33260596 0.76374286, + -0.51819313 0.3414861 0.78413218, + -0.52035302 0.33744299 0.78445202, + -0.48909113 0.34466809 0.80124515, + -0.50418508 0.31288102 0.80492413, + -0.47112983 0.31957188 0.82213771, + -0.48383623 0.28838614 0.82627839, + -0.44871399 0.29448801 0.84376103, + -0.4592838 0.26382887 0.84820557, + -0.42274806 0.26916203 0.86535311, + -0.4314599 0.23877995 0.8699578, + -0.39335209 0.24334706 0.88659823, + -0.40042016 0.21305807 0.8912183, + -0.36047113 0.21688108 0.9072063, + -0.366025 0.18682 0.91166002, + -0.32429001 0.18990301 0.9267, + -0.32851684 0.15992293 0.93086058, + -0.28559703 0.16226901 0.94451213, + -0.2886799 0.13220796 0.94825363, + -0.24478903 0.13388501 0.96028811, + -0.24690303 0.10363901 0.96348214, + -0.20207496 0.10474398 0.97375274, + -0.20339188 0.074361354 0.97626942, + -0.15781493 0.074997269 0.98461664, + -0.15849407 0.044526722 0.98635548, + -0.11271197 0.04480939 0.99261677, + -0.112966 0.0130633 0.99351299, + -0.12401196 -0.00032385089 0.99228066, + -0.12390795 -0.00031812288 0.99229366, + -0.12389199 0.015676599 0.99217188, + -0.123995 0.0156764 0.99215901, + -0.172399 0.0115081 0.98496002, + -0.17241204 -0.0011598702 0.98502421, + -0.17239501 0.015687 0.98490298, + -0.17239694 0.015686994 0.98490262, + -0.20454793 0.0030969689 0.97885162, + -0.2205459 0.00016827592 0.97537655, + -0.22055893 0.00016722294 0.97537363, + -0.22053006 0.015546003 0.97525626, + -0.22051705 0.015546104 0.97525924, + -0.26797804 0.010100401 0.96337211, + -0.26799297 -0.0013799199 0.96341985, + -0.26814911 -0.0013798807 0.96337646, + -0.26811391 0.015363694 0.96326464, + -0.26803491 0.015363994 0.96328664, + -0.26806894 -0.0013851597 0.96339875, + -0.30412185 0.0029631886 0.95262855, + -0.400455 0.00211811 0.91631401, + -0.49254301 0.00232098 0.87028497, + -0.49408889 0.0021162296 0.86940885, + -0.49403894 0.013759998 0.86933088, + -0.49398601 0.0137604 0.86936098, + -0.49403501 0.0026531599 0.86943799, + -0.45085412 -0.0015832403 0.89259624, + -0.45080388 0.014154197 0.89251077, + -0.40649006 0.0013953202 0.91365415, + -0.40644309 0.014556804 0.91356021, + -0.40645006 0.014556802 0.91355711, + -0.40649399 0.0034338201 0.913647, + -0.36121303 -0.0015201102 0.93248212, + -0.36116901 0.0149253 0.93238097, + -0.36117697 0.014925298 0.93237787, + -0.36122099 -0.00151969 0.93247902, + -0.36116108 -0.0015197103 0.93250221, + -0.31505296 0.00074365886 0.94907385, + -0.31502414 0.00074661232 0.94908345, + -0.31498513 0.015170005 0.94897538, + -0.31501302 0.015169902 0.94896615, + -0.34504613 0.011337103 0.93851733, + -0.34432292 0.042873889 0.93787175, + -0.39010081 0.042048283 0.91981161, + -0.38857785 0.071306176 0.91865265, + -0.43285584 0.069762081 0.89875972, + -0.4303889 0.09868478 0.89723277, + -0.47316182 0.096315861 0.87569469, + -0.46963701 0.124949 0.87397301, + -0.5111469 0.12164297 0.85084182, + -0.50648206 0.15007302 0.8490901, + -0.54651827 0.14575608 0.82466543, + -0.54057986 0.17418195 0.82306385, + -0.57880604 0.16883402 0.79779613, + -0.57149321 0.19747707 0.79649132, + -0.60779303 0.19109704 0.77075911, + -0.59895301 0.220119 0.76993698, + -0.63390505 0.21259503 0.74361807, + -0.62346512 0.24194206 0.7434752, + -0.65720993 0.23323298 0.71671295, + -0.64500326 0.26312208 0.71745223, + -0.67725474 0.2533319 0.69075978, + -0.66299397 0.28415298 0.69260097, + -0.69402409 0.27326903 0.66607404, + -0.67744124 0.30523011 0.66925925, + -0.70782185 0.29311895 0.64270484, + -0.70383221 0.30022311 0.64380622, + -0.73808038 0.28515515 0.61149329, + -0.74756616 0.26806507 0.60768914, + -0.77987719 0.25262606 0.5726881, + -0.78789902 0.237478 0.56817198, + -0.81815702 0.22174001 0.53051901, + -0.82468468 0.20870292 0.52567881, + -0.85295248 0.19261289 0.48515171, + -0.85809988 0.18162599 0.48028794, + -0.88424909 0.16518901 0.43682507, + -0.88818479 0.15609197 0.43216091, + -0.91179526 0.13950104 0.38622409, + -0.91454071 0.13251996 0.38216984, + -0.93553627 0.11572503 0.33373609, + -0.93712842 0.11118805 0.33079815, + -0.95551097 0.093973897 0.279585, + -0.95726401 0.0881733 0.27544701, + -0.97273767 0.070701979 0.22086793, + -0.97396123 0.065703712 0.21698505, + -0.98595363 0.048403382 0.15985194, + -0.9865585 0.045078821 0.15706807, + -0.9948681 0.027912203 0.097254112, + -0.99508214 0.026030604 0.095571816, + -0.99942821 0.0088861017 0.032625508, + -0.99945086 0.0083064493 0.032076795, + -0.99941212 -0.0085950308 -0.033191305, + -0.99943411 -0.0080584306 -0.032658003, + -0.99442422 -0.025263306 -0.10238302, + -0.99460548 -0.023873812 -0.10094605, + -0.98384124 -0.041207112 -0.17423704, + -0.98415411 -0.039842304 -0.17278102, + -0.96651649 -0.057658527 -0.25004312, + -0.96665555 -0.057249673 -0.24959888, + -0.94072789 -0.075823791 -0.33057797, + -0.94678211 -0.062308606 -0.31578702, + -0.91502625 -0.078089118 -0.39576408, + -0.92506689 -0.059301592 -0.37514594, + -0.88828111 -0.07171391 -0.45366707, + -0.89917576 -0.053968888 -0.4342469, + -0.85687357 -0.06358137 -0.51159078, + -0.86845499 -0.046885401 -0.49354601, + -0.82018101 -0.0541046 -0.56954002, + -0.830706 -0.040516101 -0.55523503, + -0.77617389 -0.045887597 -0.62884694, + -0.78421611 -0.036503606 -0.61941308, + -0.72282416 -0.040653709 -0.68983519, + -0.72615594 -0.037106995 -0.68652797, + -0.65752208 -0.040664103 -0.7523371, + -0.65394884 -0.044175588 -0.75524783, + -0.57891303 -0.047612008 -0.8139981, + -0.56602091 -0.059515085 -0.82223982, + -0.48753706 -0.063031711 -0.8708241, + -0.46475813 -0.08323092 -0.88151723, + -0.38694909 -0.086677223 -0.91801822, + -0.35600802 -0.11375701 -0.92753309, + -0.28345698 -0.11673999 -0.95185286, + -0.24825189 -0.14808592 -0.95730954, + -0.18544494 -0.15021995 -0.97110462, + -0.149198 -0.184047 -0.97152799, + -0.098937355 -0.1852169 -0.97770452, + -0.067963876 -0.21633093 -0.97395164, + -0.030322095 -0.21673296 -0.97575986, + -0.024801509 -0.22287108 -0.97453237, + 0.0055686701 -0.222937 -0.97481698, + 0.010410897 -0.22901694 -0.97336674, + 0.034560498 -0.22889297 -0.97283787, + 0.041299418 -0.23854712 -0.97025245, + 0.058507722 -0.23834209 -0.96941733, + 0.059991661 -0.24078985 -0.96872139, + 0.071991019 -0.24059808 -0.96795136, + 0.072450466 -0.24147987 -0.9676975, + 0.079914533 -0.24134108 -0.96714437, + 0.082767479 -0.24776293 -0.96527874, + 0.075064361 -0.24791388 -0.96586955, + 0.043739095 -0.16550899 -0.9852379, + 0.040177222 -0.16553311 -0.9853856, + -0.037177004 0.076892309 -0.99634612, + -0.028511601 0.076914199 -0.99663001, + -0.095018625 0.33045608 -0.93902624, + -0.074822515 0.33102709 -0.94065022, + -0.12759902 0.58295709 -0.80242109, + -0.096913047 0.58499432 -0.80522639, + -0.12801903 0.77992117 -0.61264509, + -0.090054691 0.78319585 -0.61521894, + -0.10568403 0.92265135 -0.37087113, + -0.11226998 0.98823786 -0.10383399, + -0.10515195 0.92397457 -0.36771482, + -0.14892094 0.91876465 -0.36564189, + -0.12743895 0.78323567 -0.60852373, + -0.16660005 0.77863818 -0.6049521, + -0.12725598 0.58939385 -0.79775983, + -0.15912202 0.58665407 -0.79405111, + -0.095482953 0.34156185 -0.9349966, + -0.11723895 0.34076288 -0.93281066, + -0.039173316 0.092752129 -0.99491835, + -0.044249617 0.09273243 -0.99470735, + -0.13673897 0.3528049 -0.92565179, + -0.11842994 0.35364383 -0.92785257, + -0.19235897 0.59095097 -0.78343791, + -0.15907802 0.59452903 -0.78818113, + -0.20604303 0.77679515 -0.59509307, + -0.1660669 0.7828055 -0.59969765, + -0.19301993 0.91327071 -0.35871989, + -0.14832003 0.92047924 -0.36155108, + -0.15806101 0.98250514 -0.098491319, + -0.17111394 0.97299165 -0.15494294, + -0.17322604 0.98487324 0.0041743508, + -0.17292 0.984927 0.0041743899, + -0.17081393 0.97305864 -0.15485294, + -0.17117895 0.97299576 -0.15484497, + -0.20454796 0.97430074 -0.094329774, + -0.19243604 0.91519326 -0.3541041, + -0.23747408 0.9059453 -0.35052711, + -0.20564397 0.78161991 -0.58888096, + -0.24649291 0.77404672 -0.58317482, + -0.19274396 0.60016191 -0.77630883, + -0.21937697 0.59673196 -0.77187085, + -0.13610397 0.36012891 -0.92292076, + -0.150104 0.359393 -0.92103499, + -0.054979809 0.11143102 -0.99225014, + -0.059133913 0.11140503 -0.99201423, + -0.072696209 0.12834102 -0.98906213, + 0.0356104 -0.12183 -0.99191201, + 0.039454289 -0.12181197 -0.99176878, + -0.08255662 0.13308503 -0.98766023, + -0.072985612 0.13318503 -0.98840022, + -0.17931791 0.37381881 -0.91000259, + -0.16402805 0.37483108 -0.91246724, + -0.25658897 0.60162795 -0.7564429, + -0.25797206 0.59088814 -0.76439619, + -0.33111691 0.76522082 -0.55208588, + -0.28820392 0.77655768 -0.56026483, + -0.32750398 0.88553387 -0.32950097, + -0.28171092 0.89926368 -0.33460987, + -0.29743084 0.95081955 -0.086469352, + -0.2657381 0.95205635 -0.15156506, + -0.26887503 0.96316814 0.0036490306, + -0.26887903 0.96316713 0.0036490306, + -0.26574287 0.95205551 -0.15156193, + -0.26572111 0.95206147 -0.15156308, + -0.26885706 0.96317321 0.003647801, + -0.22131993 0.97504866 -0.017250195, + -0.218702 0.96362197 -0.15363, + -0.21862103 0.96364009 -0.15363201, + -0.2212681 0.97519046 -0.006634023, + -0.22967106 0.97319627 -0.011846303, + -0.025753001 0.999605 -0.0112503, + -0.12837699 0.99165386 -0.011915698, + -0.12462997 0.99210578 -0.013911896, + -0.123152 0.98045403 -0.153439, + -0.12325097 0.98044175 -0.15343797, + -0.12473702 0.99214613 -0.0093213813, + -0.075832091 0.9971109 0.0043933797, + -0.07496687 0.98585767 -0.14988194, + -0.075026132 0.98585337 -0.14988106, + -0.075892039 0.99710649 0.0043841419, + -0.075924993 0.99710387 0.0043841396, + -0.026708404 0.99958414 -0.010878801, + -0.026432896 0.98937887 -0.14293599, + -0.026619803 0.9893741 -0.14293501, + -0.026896788 0.99956352 -0.012218994, + 0.021793593 0.99975365 0.0042105485, + 0.021603107 0.99112236 -0.13118604, + 0.022008488 0.99111354 -0.13118494, + 0.022202602 0.99974412 0.0043369606, + 0.022115 0.99974602 0.0043369601, + 0.022257799 0.99974298 0.0043042898, + 0.071145095 0.9974339 -0.0079945587, + 0.070468321 0.98804837 -0.13709405, + 0.070406474 0.98805267 -0.13709396, + 0.071076088 0.99735075 -0.015479797, + 0.077160828 0.99693835 -0.012652405, + 0.17926393 0.98372066 -0.012574395, + 0.16840802 0.98553413 -0.019008001, + 0.21668404 0.97623622 0.0033226807, + 0.2145509 0.96674055 -0.13921393, + 0.21437804 0.96677822 -0.13921903, + 0.216509 0.97627503 0.00332011, + 0.21671008 0.97623038 0.0033200812, + 0.2643241 0.96442837 -0.0032727011, + 0.27947891 0.96007466 -0.012169096, + 0.376674 0.92622298 -0.0150927, + 0.40288907 0.9152481 0.0011364401, + 0.39994609 0.90866023 -0.11991603, + 0.39990294 0.90867889 -0.11991799, + 0.40284482 0.91526759 0.0011302395, + 0.40335208 0.91504425 0.0011300802, + 0.40043992 0.90853477 -0.11921597, + 0.43640193 0.89739388 -0.065097094, + 0.44442812 0.88881421 -0.11177203, + 0.44726595 0.89440089 0.00028179298, + 0.447272 0.89439797 0.00027851199, + 0.44443411 0.88881123 -0.11177203, + 0.48112911 0.8745082 -0.061239313, + 0.48793307 0.8666721 -0.10392702, + 0.49062487 0.87137079 -0.00037517291, + 0.49053282 0.87142271 -0.00039151186, + 0.48784113 0.86672318 -0.10393202, + 0.531955 0.84526002 -0.050590001, + 0.53265494 0.84633088 0.0016176398, + 0.53277588 0.84625483 0.0016175796, + 0.53258187 0.84637684 0.0017226496, + 0.53014112 0.84257519 -0.094959922, + 0.56815118 0.82090729 -0.057579324, + 0.57160914 0.81627917 -0.083375119, + 0.5736357 0.81910759 -0.0021938491, + 0.57370031 0.81906241 -0.002181231, + 0.57167405 0.81623411 -0.083371006, + 0.61213475 0.78889573 -0.054170482, + 0.61305422 0.79003632 0.0026814109, + 0.61310714 0.78999519 0.0026813806, + 0.61282307 0.79021513 0.0028462003, + 0.61123604 0.78822714 -0.071334705, + 0.64944476 0.7583757 -0.055567183, + 0.63200098 0.73717302 -0.239062, + 0.67213529 0.70431834 -0.2284071, + 0.63908195 0.66803795 -0.38118193, + 0.68015683 0.63670784 -0.3633039, + 0.63182795 0.58883792 -0.50404692, + 0.67436194 0.56095195 -0.48017594, + 0.60482001 0.498851 -0.620758, + 0.65011424 0.47597119 -0.59228623, + 0.54151601 0.388843 -0.74536002, + 0.46733981 0.2728079 -0.84093368, + 0.39831781 0.2220939 -0.88995355, + 0.36798391 0.22514094 -0.90216374, + 0.46287078 0.29807186 -0.83480757, + 0.43325585 0.30306289 -0.84878868, + 0.5440529 0.3933309 -0.74114585, + 0.52411598 0.39923599 -0.75227201, + 0.38578606 0.28107402 -0.87873012, + 0.41410086 0.2773079 -0.8669607, + 0.31559289 0.19809993 -0.92798567, + 0.34395102 0.19603103 -0.91829711, + 0.36034617 0.20855311 -0.90920639, + 0.43802121 0.20098409 -0.87620944, + 0.48636889 0.23657894 -0.84111583, + 0.57348216 0.22181307 -0.78861731, + 0.61749905 0.25372404 -0.74452609, + 0.69627708 0.23153202 -0.67940503, + 0.73560375 0.26150492 -0.62490177, + 0.79908013 0.23209403 -0.55462009, + 0.80804282 0.23971593 -0.53814787, + 0.859038 0.208298 -0.46761701, + 0.86726761 0.21642789 -0.44833678, + 0.90599376 0.18401796 -0.38119891, + 0.91208369 0.19151393 -0.36252689, + 0.94010288 0.15923099 -0.30141696, + 0.94142222 0.16135505 -0.29612306, + 0.96191353 0.13079195 -0.24003288, + 0.96206337 0.13111505 -0.23925509, + 0.97688514 0.10273202 -0.18746102, + 0.97645164 0.10144896 -0.19039492, + 0.9870311 0.075487711 -0.14167301, + 0.98651409 0.073312305 -0.14634001, + 0.9936955 0.050216824 -0.10023805, + 0.993339 0.0479494 -0.104778, + 0.99778736 0.027666708 -0.060456522, + 0.99762726 0.025873605 -0.063800514, + 0.99975902 0.00824943 -0.020341899, + 0.99973851 0.0075292764 -0.021592289, + 0.99975455 -0.0072952965 0.02092129, + 0.99973035 -0.0064357421 0.022311108, + 0.99766135 -0.018943608 0.065673023, + 0.99740762 -0.015958894 0.07016588, + 0.99313378 -0.025944794 0.11407097, + 0.99231386 -0.020222198 0.12208299, + 0.9855665 -0.027664613 0.16701308, + 0.98370898 -0.018587301 0.17880499, + 0.97410601 -0.023376999 0.22487999, + 0.97047347 -0.0099413246 0.24100313, + 0.95774388 -0.011854198 0.28737798, + 0.95231098 0.0042306599 0.30509999, + 0.93626302 0.0048708199 0.351266, + 0.93364298 0.0115751 0.35801801, + 0.91530687 0.013014798 0.40254694, + 0.91254085 0.019528799 0.40851894, + 0.89213526 0.021571705 0.45125312, + 0.88816601 0.0303555 0.45851901, + 0.86595589 0.033037398 0.49902794, + 0.86093712 0.043607004 0.50683904, + 0.83699989 0.046906594 0.54518896, + 0.83091128 0.059250921 0.55324119, + 0.80512571 0.063158877 0.58973175, + 0.79789752 0.077404857 0.59780264, + 0.77030611 0.081884004 0.63239509, + 0.76191473 0.098100759 0.64020479, + 0.73312807 0.10301001 0.67224407, + 0.72362274 0.12117296 0.67947578, + 0.69369906 0.12645102 0.70907807, + 0.68351793 0.14584999 0.71521395, + 0.65229559 0.15145092 0.7426796, + 0.64196599 0.171259 0.74736202, + 0.60933292 0.17710699 0.77288187, + 0.59822696 0.19870697 0.77629888, + 0.56486291 0.20462295 0.79941183, + 0.55315703 0.22786203 0.80130911, + 0.51926619 0.23375309 0.82202327, + 0.5071519 0.25846195 0.82218879, + 0.47257489 0.26429093 0.84072781, + 0.46021807 0.29039103 0.83897114, + 0.4251588 0.29605386 0.8553316, + 0.4127759 0.32337692 0.85149485, + 0.37800193 0.32869196 0.86549187, + 0.36586502 0.35693002 0.85950214, + 0.33161604 0.36181802 0.87127411, + 0.33245286 0.35969383 0.87183458, + 0.30031997 0.36378196 0.88174289, + 0.31041104 0.33341002 0.8902151, + 0.2759859 0.33711287 0.90010369, + 0.28407985 0.30697885 0.90832961, + 0.24793696 0.31017298 0.91777986, + 0.25429603 0.28012204 0.92567015, + 0.21656908 0.28276908 0.93441933, + 0.221426 0.25264001 0.94188303, + 0.18204398 0.25474298 0.94971889, + 0.18559301 0.22445004 0.95664912, + 0.14456193 0.22601889 0.96333653, + 0.14698093 0.19569992 0.96958655, + 0.10507096 0.19675392 0.97480667, + 0.10654701 0.16637601 0.9802891, + 0.063944273 0.16698593 0.9838835, + 0.064674132 0.13648707 0.98852849, + 0.021437999 0.13674098 0.99037486, + 0.021636002 0.10612801 0.99411714, + -0.022044005 0.10612702 0.99410826, + -0.021844406 0.13674603 0.99036527, + -0.065036021 0.13649005 0.98850435, + -0.064305708 0.16694401 0.98386711, + -0.10703304 0.16632806 0.98024434, + -0.10556795 0.19667192 0.97476953, + -0.14757197 0.19561096 0.96951479, + -0.14517103 0.22593705 0.96326423, + -0.18621804 0.22436206 0.95654821, + -0.18267198 0.25469598 0.94961089, + -0.22203608 0.25258809 0.94175333, + -0.21716696 0.28284094 0.93425876, + -0.25482196 0.28018996 0.92550486, + -0.24842909 0.31042013 0.91756338, + -0.28441504 0.30723202 0.90813911, + -0.27625793 0.33760491 0.89983577, + -0.31040993 0.33392391 0.89002275, + -0.30026689 0.36443889 0.88148969, + -0.33214113 0.36037913 0.87167031, + -0.33159 0.36177701 0.871301, + -0.36586988 0.35688487 0.85951871, + -0.3778919 0.32891592 0.86545479, + -0.41261178 0.32360786 0.85148656, + -0.42496321 0.29636714 0.85532039, + -0.46001711 0.29070306 0.83897316, + -0.47239777 0.26456687 0.84074056, + -0.50690126 0.25874811 0.82225341, + -0.51909882 0.23387691 0.82209373, + -0.55298692 0.22798698 0.80139089, + -0.56486213 0.20441304 0.79946619, + -0.59827596 0.19849297 0.77631587, + -0.60953766 0.1765779 0.77284151, + -0.64222115 0.17073305 0.74726319, + -0.6522612 0.15147403 0.74270517, + -0.68348283 0.14587297 0.7152428, + -0.69346625 0.12686305 0.70923221, + -0.72335815 0.12157803 0.67968518, + -0.73282605 0.10350701 0.67249703, + -0.76161909 0.098579712 0.64048308, + -0.77000153 0.082401849 0.63269866, + -0.79759318 0.077901617 0.59814411, + -0.80486369 0.063592076 0.59004277, + -0.83065081 0.059663083 0.55358785, + -0.8368333 0.047142819 0.54542416, + -0.86079514 0.043827005 0.50706106, + -0.86594588 0.032982796 0.49904895, + -0.88816828 0.030304112 0.45851818, + -0.89225847 0.021246588 0.45102474, + -0.91265726 0.019232605 0.4082731, + -0.91552413 0.012466802 0.40207005, + -0.93382663 0.011086596 0.35755387, + -0.93634111 0.0046424805 0.35106102, + -0.95237774 0.004031959 0.30489394, + -0.95758402 -0.0113652 0.28793001, + -0.97035325 -0.0095326221 0.24150306, + -0.97397935 -0.022889307 0.22547807, + -0.98362386 -0.018202698 0.17931199, + -0.98551226 -0.027389508 0.16737804, + -0.99228287 -0.020023998 0.12236699, + -0.99312478 -0.025883794 0.11416297, + -0.9974041 -0.015922002 0.070225708, + -0.99766248 -0.01896031 0.065652333, + -0.99973053 -0.0064410469 0.022302888, + -0.99975491 -0.0073089991 0.020899598, + -0.99973887 0.0075432393 -0.021569299, + -0.9997595 0.0082678236 -0.02031111, + -0.9976325 0.025927788 -0.063695468, + -0.99779236 0.02772351 -0.060346924, + -0.99335521 0.048044711 -0.10458102, + -0.99371064 0.050313182 -0.10003896, + -0.98654926 0.073446013 -0.14603503, + -0.98706609 0.075627707 -0.14135401, + -0.97651821 0.10163102 -0.18995604, + -0.97698224 0.10301203 -0.18680005, + -0.96223211 0.13145901 -0.23838603, + -0.96211565 0.13120596 -0.23899491, + -0.9417429 0.16185799 -0.29482597, + -0.9397561 0.15866202 -0.30279502, + -0.91157198 0.190824 -0.36417401, + -0.9048779 0.18264599 -0.38449493, + -0.86571616 0.21476905 -0.45211712, + -0.8628794 0.21195111 -0.45882019, + -0.81312102 0.24411 -0.52843601, + -0.79918182 0.23217194 -0.55444086, + -0.735717 0.26160401 -0.62472701, + -0.6950568 0.23063494 -0.68095779, + -0.6161111 0.25267506 -0.74603117, + -0.57362592 0.22188698 -0.7884919, + -0.48653707 0.23666203 -0.84099513, + -0.43647984 0.19981793 -0.87724471, + -0.46957517 0.2654821 -0.84203231, + -0.46087894 0.25922096 -0.8487609, + -0.5496338 0.24401592 -0.79897368, + -0.59615189 0.27613395 -0.75389183, + -0.67773718 0.25289607 -0.6904462, + -0.71271718 0.27760106 -0.64418316, + -0.78049135 0.24741112 -0.5741263, + -0.81024486 0.27070096 -0.51983094, + -0.86101556 0.23490013 -0.45108128, + -0.8700369 0.24334697 -0.42873994, + -0.90819073 0.20660692 -0.36400989, + -0.90906745 0.20761389 -0.36123779, + -0.93811035 0.17257705 -0.30027711, + -0.94130945 0.17731509 -0.28722116, + -0.96189123 0.14363603 -0.23266706, + -0.96256053 0.14499892 -0.2290249, + -0.97721225 0.11354503 -0.17934304, + -0.97702086 0.11299598 -0.18072699, + -0.98735666 0.084034771 -0.13440596, + -0.98699778 0.082542278 -0.13792098, + -0.99392545 0.056517128 -0.094435245, + -0.99364799 0.054737799 -0.098323099, + -0.99789113 0.031573005 -0.056713209, + -0.99776411 0.030113304 -0.059666809, + -0.99977291 0.0096006487 -0.019022899, + -0.9997561 0.0089873513 -0.020172201, + -0.99977112 -0.0087084109 0.019546103, + -0.99975145 -0.0079730442 0.02082311, + -0.99784255 -0.023475688 0.061310969, + -0.99763125 -0.020837905 0.065557413, + -0.99372077 -0.033893391 0.10663098, + -0.99304253 -0.028840788 0.11416995, + -0.98691809 -0.039486505 0.15631202, + -0.98536062 -0.031325888 0.16757993, + -0.97669065 -0.039441787 0.21099693, + -0.97374237 -0.027693709 0.22596207, + -0.96232802 -0.033075299 0.26987201, + -0.95726067 -0.016941193 0.28872991, + -0.94269389 -0.019543799 0.33308598, + -0.93586975 -0.0014703596 0.3523429, + -0.91804022 -0.0016545603 0.39648408, + -0.91473532 0.0061233821 0.40400714, + -0.8947081 0.0067689507 0.44660005, + -0.89116168 0.014603795 0.45345086, + -0.8693732 0.015906503 0.49390012, + -0.86451286 0.026151497 0.50192994, + -0.84100211 0.028150704 0.54029906, + -0.83503872 0.040263884 0.54871583, + -0.8096531 0.042950902 0.58533508, + -0.80267733 0.056741428 0.59370828, + -0.77546889 0.060068391 0.62852192, + -0.76741987 0.075694293 0.63666093, + -0.73893762 0.079546466 0.66906172, + -0.72985208 0.097014718 0.67668605, + -0.70019174 0.10132197 0.70672876, + -0.69011992 0.12065098 0.71356696, + -0.65914679 0.12537296 0.74148977, + -0.64863497 0.14567798 0.74702793, + -0.61634928 0.15072708 0.77291334, + -0.6058107 0.17140992 0.77692467, + -0.5727151 0.17661305 0.80050319, + -0.56112719 0.19988108 0.80323333, + -0.52740175 0.20516789 0.82447159, + -0.51542211 0.22992706 0.8255142, + -0.48098695 0.23523697 0.84457988, + -0.46888211 0.26118305 0.84376121, + -0.43378484 0.26643392 0.86072272, + -0.42170593 0.29352698 0.85790789, + -0.3868351 0.29851705 0.87249416, + -0.37498504 0.32659602 0.86759514, + -0.34047711 0.33125412 0.8799693, + -0.32913086 0.35996181 0.87298357, + -0.29495084 0.36424282 0.8833636, + -0.29529512 0.36327913 0.8836453, + -0.26311204 0.36683902 0.89230114, + -0.27207309 0.33658811 0.90149027, + -0.23795392 0.3397359 0.90992171, + -0.24503595 0.30956495 0.91876376, + -0.20911796 0.31223896 0.9267019, + -0.2145371 0.28215516 0.93507344, + -0.17675099 0.28433296 0.94229186, + -0.18073891 0.25417787 0.9501195, + -0.141102 0.25584799 0.95636398, + -0.14385405 0.22557607 0.96354634, + -0.10309702 0.22673206 0.96848524, + -0.10479898 0.19645695 0.97489578, + -0.063044794 0.19715098 0.9783439, + -0.063914463 0.16683289 0.9839114, + -0.021460505 0.16713604 0.98570025, + -0.021702899 0.13670598 0.99037391, + 0.021318402 0.13670701 0.99038213, + 0.021066099 0.16715799 0.98570502, + 0.063492067 0.16685793 0.98393452, + 0.06261199 0.19721997 0.97835785, + 0.10426998 0.19652997 0.97493786, + 0.10256005 0.2268081 0.96852446, + 0.14324999 0.22565897 0.96361691, + 0.14049304 0.25588706 0.95644325, + 0.18011095 0.2542229 0.95022666, + 0.17612991 0.28427485 0.94242555, + 0.213999 0.282098 0.93521398, + 0.208602 0.31202599 0.92689002, + 0.24467103 0.30934802 0.91893411, + 0.23763897 0.33930197 0.91016591, + 0.27198595 0.33613992 0.90168375, + 0.26307005 0.36625308 0.89255422, + 0.29554102 0.36266804 0.8838141, + 0.29496685 0.36427581 0.88334459, + 0.3291449 0.35999489 0.87296468, + 0.34058309 0.3310501 0.88000524, + 0.37511817 0.32638916 0.8676154, + 0.3869971 0.29823405 0.8725192, + 0.42192891 0.29323593 0.85789782, + 0.43399405 0.26616302 0.86070114, + 0.46907276 0.26091689 0.8437376, + 0.48111382 0.23509991 0.84454572, + 0.51557499 0.22978599 0.82545799, + 0.52739906 0.20535003 0.82442814, + 0.56110114 0.20006305 0.80320621, + 0.57252812 0.17712805 0.80052316, + 0.60558623 0.17191906 0.77698731, + 0.61639601 0.150712 0.772879, + 0.64867705 0.14566402 0.74699408, + 0.65938675 0.12496796 0.74134475, + 0.69036424 0.12025604 0.71339726, + 0.70047426 0.10083604 0.70651823, + 0.73016715 0.096539423 0.67641419, + 0.73926115 0.079032123 0.66876519, + 0.76773709 0.07519991 0.63633704, + 0.77574283 0.059636984 0.62822485, + 0.80295116 0.056328915 0.59337711, + 0.80983919 0.042696211 0.58509612, + 0.83521241 0.040023517 0.54846925, + 0.84102881 0.028201593 0.54025489, + 0.86453331 0.026199209 0.50189215, + 0.86925972 0.016242795 0.49408883, + 0.89104861 0.014913793 0.45366278, + 0.89446712 0.0073750308 0.44707307, + 0.91450971 0.0066728778 0.40450886, + 0.91793603 -0.00137661 0.39672601, + 0.93577713 -0.0012234601 0.35259002, + 0.94289249 -0.02008621 0.33249116, + 0.95742285 -0.017408399 0.28816396, + 0.96249801 -0.033631299 0.269196, + 0.97387123 -0.028153408 0.22534905, + 0.97677326 -0.039767113 0.21055305, + 0.98541623 -0.031579908 0.16720505, + 0.98693585 -0.039564896 0.15617998, + 0.99305212 -0.028897803 0.11407202, + 0.99371922 -0.033870306 0.10665302, + 0.99763036 -0.020824907 0.065574922, + 0.99783999 -0.023438901 0.061367098, + 0.99975109 -0.0079611512 0.020843701, + 0.99977064 -0.0086928476 0.019573092, + 0.99975562 0.0089719472 -0.020201592, + 0.99977255 0.0095841056 -0.01905439, + 0.99775922 0.030064408 -0.059771813, + 0.99788666 0.03152319 -0.05681958, + 0.99363363 0.054655083 -0.098514162, + 0.99391139 0.05643072 -0.094634734, + 0.98696488 0.082424596 -0.13822599, + 0.98730963 0.08385177 -0.13486496, + 0.97693187 0.11275698 -0.18135598, + 0.97710454 0.11324995 -0.18011391, + 0.96237755 0.14463192 -0.23002389, + 0.96206051 0.14398593 -0.23174889, + 0.94157225 0.17774804 -0.28609005, + 0.93866122 0.17340705 -0.29806906, + 0.90988678 0.20861596 -0.35858792, + 0.90586388 0.20403098 -0.37118998, + 0.86676383 0.24022993 -0.43704692, + 0.86096144 0.23484112 -0.45121521, + 0.81015712 0.27064103 -0.51999909, + 0.7813502 0.24807206 -0.57267112, + 0.71377963 0.27839187 -0.64266372, + 0.6776368 0.25285193 -0.69056082, + 0.59603423 0.27608109 -0.7540043, + 0.55112779 0.24506691 -0.79762173, + 0.47257313 0.25883305 -0.84242517, + 0.45432988 0.24605694 -0.85617781, + 0.42247185 0.25034991 -0.87111568, + 0.5119918 0.31614789 -0.79869568, + 0.48161319 0.32255012 -0.81486827, + 0.59703374 0.41253984 -0.68801278, + 0.61775804 0.40439007 -0.67442107, + 0.5299179 0.3390519 -0.77732283, + 0.56064296 0.33105898 -0.75899887, + 0.47791088 0.27288294 -0.83494681, + 0.51087314 0.26705807 -0.81712216, + 0.58380008 0.35047203 -0.73235708, + 0.57757199 0.35238999 -0.73636401, + 0.66771501 0.41661 -0.61692202, + 0.68837404 0.40594307 -0.60112506, + 0.57719982 0.33082789 -0.74658775, + 0.6185239 0.31833491 -0.71839482, + 0.58429796 0.29608998 -0.75559688, + 0.65763676 0.2748549 -0.70140475, + 0.69507074 0.29942489 -0.65362173, + 0.76608318 0.26768905 -0.5843451, + 0.7929762 0.28665406 -0.53760409, + 0.8478108 0.24950694 -0.46793488, + 0.86720985 0.26567498 -0.42114595, + 0.90634614 0.22544204 -0.35736904, + 0.90981656 0.22911389 -0.34603581, + 0.9387601 0.19022603 -0.28730404, + 0.94040251 0.19248492 -0.28034389, + 0.96134377 0.15585697 -0.22699495, + 0.96253997 0.158117 -0.220263, + 0.97722936 0.12373804 -0.17237106, + 0.97715223 0.12352903 -0.17295705, + 0.98744524 0.09180782 -0.12854303, + 0.98723137 0.09094923 -0.13077705, + 0.99404162 0.062234979 -0.089488067, + 0.99384052 0.060960371 -0.092546254, + 0.99795663 0.035147388 -0.05335848, + 0.99785513 0.033970803 -0.055957008, + 0.99978238 0.010827004 -0.017834306, + 0.99976873 0.010319897 -0.018865095, + 0.99978298 -0.0099984501 0.018277301, + 0.99976689 -0.009370449 0.019454198, + 0.99797654 -0.027591787 0.057283875, + 0.99780589 -0.025348896 0.061162692, + 0.99418086 -0.041244198 0.099515587, + 0.9936285 -0.036866881 0.10650495, + 0.98800778 -0.050507188 0.14590997, + 0.98676676 -0.043526091 0.15619497, + 0.97889334 -0.054861117 0.19687107, + 0.97650713 -0.044577803 0.21082403, + 0.96620852 -0.053323675 0.25218588, + 0.96212101 -0.039177101 0.269793, + 0.94903755 -0.045290276 0.31189185, + 0.94240248 -0.026294613 0.33344615, + 0.92613697 -0.029651901 0.37602001, + 0.91724223 -0.0079801418 0.3982501, + 0.8976993 -0.0088271424 0.44052014, + 0.89340687 0.00062214694 0.44924793, + 0.8719818 0.00067794981 0.48953789, + 0.8678782 0.0092968717 0.49669012, + 0.8447656 0.010014796 0.53504276, + 0.8392821 0.021166801 0.54328406, + 0.81430799 0.022597101 0.57999301, + 0.80770588 0.035697397 0.58850396, + 0.78086799 0.037823301 0.62355, + 0.77321315 0.052768108 0.63194704, + 0.74505305 0.055502407 0.66469204, + 0.73634076 0.072376579 0.67272878, + 0.70692116 0.075658612 0.7032342, + 0.6971938 0.094485678 0.71062881, + 0.66637409 0.098273017 0.73911303, + 0.65576607 0.11894701 0.74553508, + 0.62364197 0.12316099 0.77194691, + 0.61253273 0.14513496 0.77700669, + 0.57976598 0.14960299 0.80093098, + 0.56861597 0.172188 0.80438, + 0.53510702 0.17682999 0.82607001, + 0.5235278 0.20102993 0.82795268, + 0.4891881 0.20578805 0.84755319, + 0.47740093 0.23139597 0.8476699, + 0.44231114 0.23618309 0.86520427, + 0.4305228 0.26303589 0.86340159, + 0.39546475 0.26767084 0.87861246, + 0.38385692 0.29565293 0.87478185, + 0.3490479 0.30004194 0.88777274, + 0.33782884 0.32896286 0.88184756, + 0.30321994 0.3330569 0.89282179, + 0.29263085 0.36262983 0.88479757, + 0.25842005 0.3663491 0.89387226, + 0.25877512 0.36523217 0.89422643, + 0.22640306 0.36829409 0.90172124, + 0.23412301 0.33843499 0.91139901, + 0.1998219 0.34108886 0.91854757, + 0.20577504 0.31130406 0.92776424, + 0.16954999 0.31350598 0.93432689, + 0.17396298 0.28370398 0.9429999, + 0.13586102 0.28542605 0.94872224, + 0.13894802 0.25547007 0.95678025, + 0.099537298 0.25669199 0.96135402, + 0.10150002 0.22651707 0.96870422, + 0.060971878 0.22726792 0.97192162, + 0.062001314 0.19704905 0.97843122, + 0.020649102 0.19738702 0.98010814, + 0.020943791 0.16712293 0.98571354, + -0.021411095 0.16712196 0.98570377, + -0.021125594 0.19736296 0.98010278, + -0.062575169 0.1970199 0.97840053, + -0.061554492 0.22721697 0.97189689, + -0.10210601 0.22645903 0.9686541, + -0.10014798 0.25666493 0.96129775, + -0.13957796 0.25543591 0.95669764, + -0.136489 0.28546599 0.94862002, + -0.17449994 0.28374091 0.94288963, + -0.17007194 0.31367689 0.93417466, + -0.206139 0.31147799 0.927625, + -0.20015092 0.34145287 0.91834062, + -0.23420601 0.33881101 0.91123801, + -0.22645102 0.36880302 0.90150112, + -0.25857806 0.3657611 0.89406723, + -0.25840494 0.3663069 0.89389378, + -0.29260594 0.36259091 0.88482177, + -0.30311602 0.33324203 0.89278811, + -0.33769992 0.32915092 0.88182676, + -0.34889618 0.30029914 0.88774544, + -0.38366586 0.29591289 0.87477767, + -0.39528394 0.26791698 0.8786189, + -0.430291 0.263289 0.86343998, + -0.442139 0.236305 0.86525899, + -0.47725406 0.23151504 0.84772015, + -0.48918331 0.20559612 0.84760249, + -0.52352804 0.20084202 0.8279981, + -0.53525215 0.17632806 0.8260833, + -0.56881982 0.17168795 0.80434269, + -0.57970417 0.14963706 0.8009693, + -0.61249495 0.14516498 0.77703089, + -0.62342972 0.12354694 0.77205664, + -0.655509 0.119329 0.7457, + -0.66607797 0.098752603 0.73931599, + -0.69689894 0.094951086 0.71085596, + -0.70660394 0.076187089 0.70349592, + -0.73601204 0.072888106 0.67303306, + -0.74476582 0.055955186 0.66497582, + -0.77293485 0.053201493 0.63225096, + -0.78068697 0.0380807 0.623761, + -0.80750853 0.035943877 0.58875966, + -0.81424642 0.022580311 0.58008027, + -0.83925015 0.021149902 0.54333407, + -0.84487957 0.0096959854 0.53486878, + -0.86798614 0.009000591 0.49650705, + -0.872244 4.3462202e-005 0.48907101, + -0.8936609 3.9877697e-005 0.44874293, + -0.8978349 -0.0091662994 0.44023693, + -0.91736186 -0.0082861995 0.39796793, + -0.92589635 -0.029062711 0.37665814, + -0.94220078 -0.025775595 0.3340559, + -0.94882512 -0.044669405 0.31262702, + -0.96194786 -0.038648196 0.27048597, + -0.96609437 -0.05293832 0.25270408, + -0.97642362 -0.044259585 0.21127692, + -0.97886527 -0.054754514 0.19704005, + -0.98674822 -0.04344321 0.15633504, + -0.98800933 -0.050531518 0.14589106, + -0.99362963 -0.036883485 0.10648796, + -0.99418634 -0.041298915 0.099437937, + -0.99780834 -0.025380408 0.061109822, + -0.99797952 -0.027634688 0.057211474, + -0.99976724 -0.0093843322 0.019428203, + -0.99978334 -0.010013604 0.018248908, + -0.99976921 0.010335003 -0.018834604, + -0.99978274 0.010842497 -0.017802795, + -0.99785936 0.034016512 -0.055853419, + -0.99796075 0.035195094 -0.053250488, + -0.99385375 0.061039183 -0.092352778, + -0.9940604 0.062355261 -0.08919435, + -0.98727489 0.091114394 -0.13033198, + -0.98749685 0.092010491 -0.12799999, + -0.97725034 0.12379204 -0.17221306, + -0.97715455 0.12353294 -0.17294091, + -0.96241337 0.15786105 -0.22099908, + -0.96108967 0.15537494 -0.22839692, + -0.94000876 0.19188696 -0.28206894, + -0.94007897 0.191984 -0.28176901, + -0.91178375 0.23123793 -0.33938092, + -0.90638477 0.22547194 -0.35725191, + -0.86725414 0.26572204 -0.42102507, + -0.84725899 0.249075 -0.469163, + -0.79225379 0.28612393 -0.53894991, + -0.76616538 0.26773512 -0.5842163, + -0.69516093 0.29948598 -0.65349793, + -0.65627557 0.27397385 -0.7030226, + -0.57169414 0.29791906 -0.76446718, + -0.51670116 0.26178008 -0.81516331, + -0.47302288 0.26938894 -0.8388558, + -0.54194689 0.3177349 -0.77803481, + -0.51104391 0.32497191 -0.7957558, + -0.60790604 0.39683107 -0.68773204, + -0.58716398 0.40455699 -0.70112199, + -0.46211305 0.30729803 -0.83187711, + -0.49238312 0.30160105 -0.81645316, + -0.37920105 0.21884303 -0.89906311, + -0.36195502 0.22047003 -0.90574914, + -0.44277373 0.28246284 -0.85097945, + -0.41351905 0.28682902 -0.8641361, + -0.53398192 0.38477495 -0.75286889, + -0.51404822 0.39035717 -0.76379037, + -0.45931894 0.36273196 -0.81083387, + -0.59022599 0.47805199 -0.65046102, + -0.56022364 0.49054971 -0.66746557, + -0.43365216 0.37041813 -0.82142329, + -0.46046883 0.36490789 -0.80920368, + -0.32010013 0.23964009 -0.9165743, + -0.3465009 0.23727894 -0.90754378, + -0.25874108 0.16354406 -0.95200133, + -0.247021 0.14815 -0.957618, + -0.17815396 0.10435198 -0.97845376, + -0.30120704 0.21244504 -0.92959213, + -0.27669501 0.214094 -0.93680501, + -0.42465115 0.35254312 -0.83389729, + -0.39862183 0.35712183 -0.84472758, + -0.52191383 0.47983482 -0.70524079, + -0.50212687 0.48647088 -0.71499282, + -0.36482811 0.34289113 -0.86563629, + -0.3899641 0.33911908 -0.85611117, + -0.23597895 0.18795596 -0.95340776, + -0.25866994 0.18683596 -0.94772476, + -0.16943595 0.10451498 -0.97998375, + -0.15623999 0.085184589 -0.98403889, + -0.16123904 0.089879222 -0.98281425, + -0.22856504 0.088660009 -0.96948314, + -0.27198109 0.12581505 -0.95404238, + -0.35056689 0.12244596 -0.92849863, + -0.3958891 0.15877405 -0.90446824, + -0.48102313 0.15158303 -0.86350417, + -0.53693497 0.195242 -0.82072002, + -0.62034291 0.18151996 -0.76303685, + -0.64553124 0.20157607 -0.73665226, + -0.71976721 0.18322706 -0.66959924, + -0.73040277 0.19215192 -0.65543073, + -0.793778 0.171106 -0.58364302, + -0.80747414 0.18384002 -0.56052506, + -0.87174088 0.15269598 -0.46556595, + -0.8729822 0.15421103 -0.46273211, + -0.90974361 0.13126294 -0.39387381, + -0.91109169 0.13325696 -0.39006984, + -0.9391281 0.11106802 -0.32511902, + -0.93837023 0.10966403 -0.32777309, + -0.95972067 0.089143567 -0.2664389, + -0.95826524 0.085718624 -0.27272707, + -0.9744491 0.067346506 -0.21427403, + -0.97296888 0.062829591 -0.22222497, + -0.98505354 0.046862576 -0.16575092, + -0.98390698 0.042158 -0.173637, + -0.99245465 0.028929189 -0.11915096, + -0.9917345 0.02467539 -0.12591194, + -0.99724966 0.014253295 -0.072731279, + -0.99694264 0.011194796 -0.077330768, + -0.99968934 0.0035710712 -0.02466801, + -0.99964952 0.0023747389 -0.026367787, + -0.99967134 -0.0022996708 0.02553441, + -0.9996255 -0.00094511651 0.027350187, + -0.99676001 -0.0027778 0.080385201, + -0.99626625 0.0019192805 0.086312421, + -0.99015838 0.0031112612 0.13991705, + -0.9888615 0.010345195 0.14847893, + -0.97922277 0.014094897 0.20229696, + -0.97849399 0.017056299 0.205569, + -0.96603566 0.021366993 0.25752392, + -0.96490014 0.025161404 0.26140904, + -0.95001203 0.029913099 0.31077701, + -0.94804615 0.035598304 0.31613502, + -0.93076891 0.040910497 0.36331198, + -0.92795599 0.048174899 0.36956301, + -0.90833426 0.054063611 0.41473609, + -0.90461421 0.062849917 0.42157209, + -0.88278174 0.069271885 0.46464789, + -0.8780036 0.07978446 0.47195777, + -0.85434669 0.086627074 0.51243281, + -0.84845471 0.098888062 0.51994783, + -0.82310915 0.10610303 0.55788314, + -0.8159759 0.12031499 0.56542695, + -0.7888822 0.12790303 0.60108709, + -0.78106499 0.142986 0.60785902, + -0.75227827 0.15086105 0.64134121, + -0.74446064 0.16565092 0.64679068, + -0.71435994 0.17361699 0.67789894, + -0.70489681 0.19131896 0.68302083, + -0.67361879 0.19934796 0.71168685, + -0.66304374 0.21900593 0.71582776, + -0.63038981 0.22710994 0.7423138, + -0.61895877 0.24835891 0.74512279, + -0.58513272 0.25642687 0.76932764, + -0.57292515 0.27927908 0.7705583, + -0.5386101 0.28709906 0.7921322, + -0.525801 0.311409 0.79155397, + -0.49126893 0.31887797 0.81053787, + -0.47813606 0.34433803 0.80797112, + -0.44331712 0.35142508 0.8246032, + -0.44473186 0.34853289 0.82506871, + -0.41282079 0.35442683 0.83902359, + -0.42619908 0.32308909 0.84496617, + -0.39267108 0.32846409 0.85902315, + -0.40378207 0.29754704 0.86511612, + -0.36851782 0.30234987 0.87907857, + -0.3776159 0.27178395 0.88517779, + -0.3404651 0.27597907 0.89884323, + -0.34780481 0.24556188 0.90483761, + -0.30859303 0.24913102 0.91798913, + -0.31437913 0.21873207 0.92375433, + -0.27374098 0.22161298 0.93592387, + -0.27813193 0.19132395 0.94129574, + -0.236233 0.193545 0.95222598, + -0.23942906 0.16330704 0.95708126, + -0.19628502 0.16492702 0.96657711, + -0.19847596 0.13458897 0.97082078, + -0.15420803 0.13567904 0.97867823, + -0.15558393 0.10516496 0.98220867, + -0.11101596 0.10580296 0.98817062, + -0.11175 0.075225502 0.99088502, + -0.067030109 0.075529404 0.99488813, + -0.067324705 0.044949003 0.99671811, + -0.022589395 0.045039687 0.99872977, + -0.022633597 0.014272398 0.9996419, + 0.02318099 0.014747192 0.99962252, + 0.022034686 0.014747592 0.99964839, + 0.021991502 0.045061905 0.9987421, + 0.066594407 0.044972703 0.99676609, + 0.066302225 0.075457431 0.99494237, + 0.11115403 0.075155228 0.99095738, + 0.11041203 0.10568302 0.98825121, + 0.15524293 0.10504396 0.98227566, + 0.15386492 0.13564794 0.97873652, + 0.19809701 0.134562 0.97090203, + 0.19588795 0.16501996 0.96664178, + 0.23903488 0.16340193 0.95716351, + 0.23582987 0.19372891 0.95228851, + 0.27757895 0.19151695 0.94141978, + 0.27317205 0.22178607 0.93604922, + 0.31380311 0.21890907 0.92390835, + 0.30803001 0.249198 0.91816002, + 0.34725004 0.24563403 0.90503114, + 0.33994514 0.27587011 0.89907342, + 0.377184 0.27167299 0.885396, + 0.3681519 0.30200395 0.87935078, + 0.40357885 0.29718989 0.86533368, + 0.39258307 0.32779202 0.8593201, + 0.42632878 0.32239285 0.84516656, + 0.41305178 0.35352683 0.83928961, + 0.44522411 0.34759209 0.8252002, + 0.44331193 0.35150498 0.82457191, + 0.47811812 0.34441909 0.80794716, + 0.49143276 0.31860086 0.81054765, + 0.5259949 0.31112793 0.79153579, + 0.53884393 0.28672698 0.79210788, + 0.57317972 0.27890688 0.77050364, + 0.58536375 0.25608492 0.76926571, + 0.61923075 0.2480109 0.74501276, + 0.6305508 0.22695693 0.7422238, + 0.66318703 0.218859 0.71574003, + 0.67355168 0.1995929 0.71168166, + 0.70481294 0.19155997 0.68303996, + 0.71410185 0.17419796 0.67802185, + 0.74417216 0.16622205 0.64697617, + 0.75230211 0.15084901 0.64131606, + 0.78109819 0.14297003 0.60782009, + 0.78912264 0.12747794 0.60086173, + 0.81620914 0.11990701 0.56517708, + 0.8233723 0.10561503 0.55758721, + 0.84869689 0.098427087 0.51963997, + 0.85461003 0.086102903 0.51208198, + 0.87825429 0.079291932 0.47157419, + 0.8829717 0.06889578 0.46434283, + 0.90478212 0.062503807 0.42126307, + 0.90843332 0.053870019 0.41454414, + 0.92803389 0.048002191 0.36938998, + 0.93074387 0.041000698 0.36336598, + 0.94802511 0.035677403 0.31618902, + 0.94990736 0.030241711 0.31106511, + 0.96482015 0.025440203 0.26167703, + 0.96593112 0.021736601 0.25788504, + 0.97842133 0.017354006 0.20589007, + 0.97920662 0.014168495 0.20236993, + 0.98885125 0.010399903 0.14854303, + 0.99020326 0.0028485407 0.13960503, + 0.99628466 0.0017568694 0.086103372, + 0.99677914 -0.0029679304 0.08014141, + 0.99962777 -0.0010096797 0.027263794, + 0.99967265 -0.002343969 0.02547509, + 0.99965113 0.0024201702 -0.026303304, + 0.99968976 0.003583109 -0.024650794, + 0.99694622 0.011232803 -0.077278912, + 0.99724686 0.014227498 -0.072775491, + 0.99172574 0.024630895 -0.12598997, + 0.99243712 0.028826904 -0.11932202, + 0.98386753 0.04201138 -0.17389591, + 0.98500848 0.046680722 -0.16607007, + 0.97288114 0.062592208 -0.22267602, + 0.97436088 0.067093894 -0.21475397, + 0.95811427 0.085402921 -0.27335605, + 0.95957613 0.088831507 -0.26706302, + 0.93814474 0.10928198 -0.32854491, + 0.93889964 0.11067496 -0.32591188, + 0.9107433 0.13279104 -0.39104116, + 0.90921539 0.13054006 -0.39533117, + 0.87223858 0.15335193 -0.4644168, + 0.86603284 0.14591797 -0.47822088, + 0.81810498 0.16783001 -0.55003399, + 0.80568999 0.155339 -0.57160598, + 0.74524194 0.17486499 -0.64345694, + 0.71679795 0.14989498 -0.68097895, + 0.65922576 0.16164695 -0.73436475, + 0.59901714 0.11220903 -0.79283518, + 0.53636408 0.11826901 -0.83565915, + 0.497796 0.087223299 -0.86289698, + 0.41444391 0.091525778 -0.90546077, + 0.39737481 0.07753966 -0.91437459, + 0.31740192 0.080128275 -0.94489974, + 0.26867509 0.038243715 -0.96247137, + 0.19910704 0.038908504 -0.97920513, + 0.16392194 0.0063864575 -0.98645264, + 0.10655797 0.0064371675 -0.99428564, + 0.079251871 -0.021361992 -0.99662566, + 0.034819704 -0.021416502 -0.9991641, + 0.034100909 -0.020252706 -0.99921322, + 0.0092753191 -0.049240094 -0.99874389, + 0.00017436598 -0.049242094 -0.99878687, + 0.082503974 0.05274969 -0.99519378, + 0.070165902 0.052799799 -0.99613702, + 0.22049201 0.251766 -0.94233602, + 0.20250203 0.25277102 -0.94609714, + 0.33491296 0.44000894 -0.83320189, + 0.3135339 0.44343087 -0.8396818, + 0.42374706 0.60966909 -0.66988206, + 0.40431583 0.61561871 -0.67641872, + 0.2908181 0.43468115 -0.85233629, + 0.31163406 0.43169308 -0.84647816, + 0.18048806 0.23603308 -0.95483637, + 0.197303 0.235258 -0.95169598, + 0.049897183 0.029700588 -0.99831265, + 0.060718071 0.029682785 -0.99771351, + -0.017247794 -0.071983576 -0.99725664, + -0.009724929 -0.071990989 -0.9973579, + -0.0084520895 -0.070430391 -0.99748087, + 0.0276924 -0.070405997 -0.99713397, + 0.047888812 -0.047842912 -0.99770623, + 0.094424635 -0.047683917 -0.99438936, + 0.12181803 -0.020184705 -0.99234724, + 0.18036391 -0.020002691 -0.98339653, + 0.22103 0.017333601 -0.97511297, + 0.29221305 0.016997404 -0.95620221, + 0.30715597 0.029788297 -0.95119286, + 0.38488305 0.028890103 -0.92251313, + 0.42766213 0.063942619 -0.90167427, + 0.50986212 0.060852613 -0.85810119, + 0.55664897 0.099464782 -0.82477188, + 0.63638377 0.092355669 -0.76582372, + 0.66391182 0.11637697 -0.73869979, + 0.73442209 0.10562102 -0.67042404, + 0.75258613 0.12311202 -0.64688307, + 0.8110823 0.10936004 -0.57461816, + 0.81910384 0.11822297 -0.56133085, + 0.86633933 0.10293303 -0.48873419, + 0.86795789 0.10503799 -0.48540294, + 0.90572226 0.089647919 -0.4142831, + 0.9043079 0.087446794 -0.41782793, + 0.93416423 0.073099613 -0.3492761, + 0.93148446 0.068043463 -0.35736078, + 0.95501709 0.055468306 -0.29131702, + 0.95219666 0.048923083 -0.30154288, + 0.97062021 0.038534407 -0.23751105, + 0.96815377 0.031340592 -0.24838693, + 0.98233867 0.023423392 -0.18563995, + 0.98053735 0.016552206 -0.19563407, + 0.99085534 0.011375303 -0.13444805, + 0.98975176 0.0054575684 -0.14269397, + 0.99658579 0.0031554692 -0.082502879, + 0.99611777 -0.00099141675 -0.088025376, + 0.99960554 -0.00031629886 -0.028083187, + 0.99954337 -0.0019492607 -0.030156512, + 0.99957234 0.0018864108 0.029184312, + 0.9995119 0.0034331495 0.031051496, + 0.99579042 0.010072694 0.091103546, + 0.99564612 0.011316301 0.092524208, + 0.98855376 0.018315697 0.14975297, + 0.98818702 0.020317901 0.15189999, + 0.97800052 0.027655886 0.2067609, + 0.9771769 0.031041896 0.21014696, + 0.96402478 0.038842991 0.26295894, + 0.96260864 0.043602884 0.26736391, + 0.94686276 0.051770188 0.31744391, + 0.94470364 0.058019176 0.32275188, + 0.92647624 0.066587612 0.37041607, + 0.92340225 0.074507013 0.37653309, + 0.90277791 0.083489291 0.42192593, + 0.89862901 0.093234003 0.42868799, + 0.87574178 0.10259898 0.47175187, + 0.87036699 0.114312 0.47895101, + 0.84567171 0.12389895 0.51912284, + 0.83942997 0.13672601 0.52598798, + 0.8130697 0.14646193 0.56344181, + 0.80679172 0.15883094 0.56908685, + 0.77855402 0.168708 0.60447598, + 0.77105433 0.18303207 0.60989726, + 0.74096197 0.19302897 0.64320695, + 0.73216748 0.20942485 0.64812952, + 0.70085907 0.21931803 0.67874604, + 0.69084096 0.23767397 0.68282497, + 0.658373 0.24743301 0.71086001, + 0.64717895 0.26771897 0.71378297, + 0.61342388 0.27734593 0.73945284, + 0.6011529 0.29948294 0.74089479, + 0.56639111 0.30885306 0.76407516, + 0.55320394 0.33269596 0.76372689, + 0.51818895 0.34157097 0.78409791, + 0.52097189 0.3363589 0.7845068, + 0.48946106 0.34363002 0.80146509, + 0.50444007 0.31204703 0.8050881, + 0.47113594 0.31877398 0.8224439, + 0.48368418 0.28796509 0.8265143, + 0.44847113 0.29406905 0.84403616, + 0.45894617 0.26369408 0.84843028, + 0.42228806 0.26903504 0.8656171, + 0.43095291 0.23884994 0.87018985, + 0.39278507 0.24341802 0.88683009, + 0.39983085 0.21330093 0.89142472, + 0.35999483 0.21710989 0.90734059, + 0.36555892 0.18705496 0.91179878, + 0.32387084 0.19013192 0.9267996, + 0.32812089 0.16005394 0.93097764, + 0.28522184 0.16239692 0.9446035, + 0.28833395 0.13214397 0.94836777, + 0.24439394 0.13381997 0.96039778, + 0.24652503 0.10344201 0.9636001, + 0.20154998 0.10454599 0.97388285, + 0.20286199 0.0742402 0.97638899, + 0.15710005 0.074875213 0.98474026, + 0.15778306 0.044639416 0.98646438, + 0.11217595 0.044920277 0.9926725, + 0.11242799 0.013736598 0.9935649, + 0.12076201 0.015904002 0.99255413, + 0.12077906 -1.8469209e-005 0.99267948, + 0.12076095 -1.7465794e-005 0.99268162, + 0.12074404 0.015904006 0.99255633, + 0.16932207 0.012742107 0.98547846, + 0.16933706 -0.0013225104 0.98555738, + 0.16931404 -0.0013225103 0.98556125, + 0.2971321 -0.070632525 -0.95222038, + 0.25055712 -0.071613841 -0.96544945, + 0.24947201 -0.100853 -0.96311599, + 0.20304993 -0.10197696 -0.97384363, + 0.20182499 -0.13194001 -0.97049397, + 0.15567292 -0.13306995 -0.97880453, + 0.15444693 -0.16359593 -0.97436255, + 0.10948998 -0.16458699 -0.98026687, + 0.10841902 -0.19562005 -0.97466826, + 0.06451232 -0.19637008 -0.97840536, + 0.063754879 -0.22753893 -0.97167963, + 0.021137998 -0.22795197 -0.97344285, + 0.020857194 -0.25911695 -0.96562076, + -0.02036551 -0.25912011 -0.96563047, + -0.0206545 -0.227983 -0.97344601, + -0.063241802 -0.22757401 -0.97170502, + -0.064005211 -0.19650704 -0.97841114, + -0.10778298 -0.19576398 -0.97470987, + -0.10885798 -0.16486299 -0.98029089, + -0.15387607 -0.16387306 -0.97440636, + -0.15509394 -0.13325995 -0.97887063, + -0.20114991 -0.13213494 -0.97060752, + -0.20238596 -0.10185397 -0.97399473, + -0.24889709 -0.10073303 -0.96327734, + -0.24999888 -0.070876062 -0.96564853, + -0.29666007 -0.069905318 -0.95242125, + -0.29749301 -0.040654801 -0.95385802, + -0.29779002 -0.041080803 -0.95374709, + -0.298188 -0.0129743 -0.95441902, + -0.3135561 -0.0046520317 -0.94955838, + -0.31353989 -0.0046520983 -0.94956362, + -0.3446171 -0.018941803 -0.93855226, + -0.34425783 -0.039979883 -0.93802351, + 0.69793826 0.0041052615 -0.71614623, + 0.68829715 -0.014542404 -0.72528321, + 0.60997188 -0.018212195 -0.7922138, + 0.60957301 -0.033446901 -0.79202402, + 0.56782812 -0.034730308 -0.82241416, + 0.56678104 -0.057547808 -0.82185614, + 0.52322811 -0.059526313 -0.85011119, + 0.52161193 -0.084109291 -0.84902686, + 0.47708312 -0.086640522 -0.87457716, + 0.47490701 -0.112784 -0.87277901, + 0.42963707 -0.11572801 -0.89555514, + 0.42691615 -0.14355305 -0.89282429, + 0.38095516 -0.14677507 -0.91286927, + 0.37779906 -0.17580801 -0.90904313, + 0.33144292 -0.17914796 -0.92631078, + 0.3279449 -0.20953695 -0.92116576, + 0.28212893 -0.21279295 -0.93547976, + 0.27849704 -0.24389303 -0.92895412, + 0.23353803 -0.24691802 -0.94047409, + 0.22998406 -0.27822807 -0.93257523, + 0.18605305 -0.28090009 -0.94153035, + 0.18280296 -0.31185994 -0.93237674, + 0.14027996 -0.3140679 -0.93897974, + 0.13749495 -0.34481588 -0.92854565, + 0.096797578 -0.34648791 -0.93304676, + 0.094637558 -0.37673381 -0.92147458, + 0.055969708 -0.37783906 -0.92417812, + 0.054570712 -0.40758508 -0.91153526, + 0.017983194 -0.40812784 -0.91274768, + 0.017491095 -0.43733487 -0.89912868, + -0.016894702 -0.43733907 -0.89913809, + -0.017391605 -0.40809613 -0.91277331, + -0.05416939 -0.40755892 -0.91157079, + -0.055557508 -0.37792906 -0.92416614, + -0.094268352 -0.37682882 -0.92147356, + -0.096437901 -0.34638301 -0.93312299, + -0.13690102 -0.34472802 -0.92866611, + -0.13970003 -0.31401709 -0.93908322, + -0.18238194 -0.31180787 -0.93247664, + -0.18564795 -0.28076094 -0.94165176, + -0.2295921 -0.27809513 -0.93271142, + -0.23311706 -0.24712107 -0.94052523, + -0.27805892 -0.24410091 -0.92903066, + -0.281663 -0.21333399 -0.93549699, + -0.32749814 -0.2100741 -0.92120242, + -0.3309769 -0.17989896 -0.92633176, + -0.37726405 -0.17655702 -0.90912014, + -0.3804369 -0.14742997 -0.91297978, + -0.42639592 -0.14419897 -0.89296877, + -0.4291378 -0.11622195 -0.89573056, + -0.47438481 -0.11327196 -0.87299973, + -0.476625 -0.086365603 -0.87485403, + -0.52120578 -0.08384306 -0.84930259, + -0.52287591 -0.058271684 -0.85041481, + -0.56653684 -0.056332182 -0.82210869, + -0.56762183 -0.032090988 -0.82266372, + -0.6094749 -0.030902792 -0.79220283, + -0.60990286 -0.012611497 -0.7923758, + -0.61494809 -0.0055426816 -0.78854817, + -0.61495811 0.0026677707 -0.7885552, + -0.57548106 -0.016224802 -0.81765413, + -0.57556319 -0.00021721507 -0.81775731, + -0.57558382 -0.00021722693 -0.81774271, + -0.5756501 -0.00021427606 -0.81769615, + -0.57564199 -0.0047720401 -0.81768799, + -0.57557619 -0.004772522 -0.8177343, + -0.56848019 -0.007555183 -0.82266229, + -0.56794369 -0.032623883 -0.8224206, + -0.52446991 -0.033748098 -0.85075986, + -0.52337688 -0.059092786 -0.85004979, + -0.47892907 -0.060878806 -0.87574011, + -0.47728094 -0.087426096 -0.8743909, + -0.43206105 -0.089723609 -0.8973701, + -0.42989916 -0.11743405 -0.89520729, + -0.38394892 -0.12009697 -0.91551077, + -0.38135895 -0.14886598 -0.91236186, + -0.33485496 -0.15173799 -0.92997187, + -0.3319439 -0.18136495 -0.92569977, + -0.2857849 -0.18424794 -0.94041467, + -0.28267205 -0.21481605 -0.93485326, + -0.23726809 -0.21755408 -0.94677037, + -0.23414902 -0.24858002 -0.93988413, + -0.18953907 -0.25105208 -0.94923538, + -0.186619 -0.28207499 -0.94106698, + -0.14312193 -0.28416285 -0.94803351, + -0.14056899 -0.31513798 -0.93857789, + -0.099112198 -0.31673101 -0.94332302, + -0.097128764 -0.34722689 -0.93273765, + -0.057220291 -0.34830597 -0.93563288, + -0.055921327 -0.37835118 -0.92397141, + -0.018143302 -0.37888205 -0.9252671, + -0.017687999 -0.40842393 -0.9126209, + 0.018247604 -0.4084211 -0.91261125, + 0.018696401 -0.37895307 -0.92522711, + 0.056466907 -0.37841505 -0.92391211, + 0.057759676 -0.34837589 -0.93557364, + 0.097459413 -0.34729704 -0.93267709, + 0.099449836 -0.31675813 -0.94327837, + 0.14111999 -0.31515098 -0.93849087, + 0.14364107 -0.28434515 -0.94790047, + 0.18705404 -0.28225306 -0.94092727, + 0.19000401 -0.25082299 -0.94920301, + 0.23455206 -0.24835105 -0.93984425, + 0.23769906 -0.21704005 -0.94678026, + 0.28315485 -0.2142999 -0.9348256, + 0.28627795 -0.18360296 -0.94039077, + 0.33248091 -0.18072195 -0.92563277, + 0.33538684 -0.15108493 -0.92988658, + 0.38188007 -0.14821903 -0.91224927, + 0.38445592 -0.11967097 -0.91535378, + 0.43044195 -0.11700998 -0.89500189, + 0.43255216 -0.089974128 -0.89710832, + 0.47771794 -0.087669395 -0.87412786, + 0.47931689 -0.062075686 -0.87544376, + 0.52367288 -0.060256284 -0.8497858, + 0.52472806 -0.036336504 -0.85049415, + 0.56806833 -0.035129014 -0.82223141, + 0.56861615 -0.011595304 -0.82252127, + 0.53741693 0.0036133695 -0.84330887, + 0.53669089 0.003714439 -0.8437708, + 0.49550119 -0.00018832408 -0.86860728, + 0.53741688 0.0038795192 -0.84330779, + 0.57797593 -0.023199799 -0.8157239, + 0.57813984 -0.00025051591 -0.8159377, + 0.57818896 -0.00025054297 -0.81590289, + 0.57816809 -0.0078155221 -0.81588018, + 0.57808912 -0.0078164022 -0.81593621, + 0.57810885 -0.0002540969 -0.81595969, + 0.61745566 0.0031033882 -0.78659952, + 0.61743212 -0.0084998515 -0.78657818, + 0.61741489 -0.0085000582 -0.78659183, + 0.65518701 -0.018009299 -0.755252, + 0.64995605 -0.011210401 -0.75988913, + 0.64945781 -0.031646091 -0.7597388, + 0.6093111 -0.033000208 -0.7922442, + 0.60828787 -0.054693986 -0.79182982, + 0.56633389 -0.056792885 -0.82221681, + 0.56472796 -0.080283396 -0.82136285, + 0.5209679 -0.083036378 -0.84952784, + 0.51875705 -0.10827901 -0.84803712, + 0.47413296 -0.11151299 -0.8733629, + 0.47132081 -0.13852195 -0.87101573, + 0.42601192 -0.14209697 -0.89348876, + 0.42267984 -0.17042494 -0.89011073, + 0.37677085 -0.17419194 -0.90978068, + 0.37297791 -0.20398396 -0.90513974, + 0.32679212 -0.20777908 -0.92197335, + 0.32270989 -0.23858692 -0.91593373, + 0.27733597 -0.24218497 -0.92974788, + 0.27322695 -0.27322695 -0.92233074, + 0.2287619 -0.27650288 -0.93338859, + 0.224806 -0.307567 -0.92458898, + 0.18171391 -0.31039086 -0.9330796, + 0.17811996 -0.34130991 -0.92291975, + 0.13655099 -0.34360701 -0.929133, + 0.13351306 -0.37415618 -0.9177044, + 0.093922362 -0.37586686 -0.92190164, + 0.091577306 -0.40601805 -0.9092651, + 0.054175094 -0.40713295 -0.91176087, + 0.052678619 -0.43661815 -0.8981033, + 0.017330097 -0.4371599 -0.89921677, + 0.016802292 -0.4662838 -0.88447559, + -0.016169794 -0.46628883 -0.88448471, + -0.016701296 -0.4371289 -0.89924377, + -0.052055594 -0.43659693 -0.89814991, + -0.053567883 -0.40687084 -0.91191369, + -0.090911344 -0.40576819 -0.90944344, + -0.093271427 -0.37562016 -0.92206836, + -0.13291803 -0.3739171 -0.91788822, + -0.135957 -0.34351799 -0.92925298, + -0.17769408 -0.34121916 -0.92303544, + -0.18129 -0.31033701 -0.93317997, + -0.22450189 -0.30751085 -0.9246816, + -0.22844894 -0.27648395 -0.93347079, + -0.27280596 -0.27322197 -0.92245686, + -0.2768949 -0.24239092 -0.92982566, + -0.32236198 -0.23878796 -0.91600388, + -0.32639298 -0.20838997 -0.92197686, + -0.37253398 -0.20459397 -0.90518486, + -0.37630299 -0.17504799 -0.90981001, + -0.42209685 -0.17127794 -0.89022368, + -0.4254739 -0.14271396 -0.89364678, + -0.47075981 -0.13913296 -0.87122172, + -0.47359988 -0.11198397 -0.87359184, + -0.51834226 -0.10873405 -0.84823239, + -0.52060509 -0.08284311 -0.84976912, + -0.56439131 -0.080098234 -0.82161242, + -0.56605989 -0.055527885 -0.82249182, + -0.60808271 -0.053474072 -0.79207063, + -0.60914075 -0.030333688 -0.79248172, + -0.64937925 -0.029086811 -0.75990832, + -0.64986718 -0.0074595618 -0.7600112, + -0.65289778 -0.0061906176 -0.75742072, + -0.65297997 -0.0061899391 -0.75734991, + -0.68827194 -0.0085901394 -0.72540194, + -0.68784225 -0.027257109 -0.72534823, + -0.64908195 -0.028566096 -0.7601819, + -0.648063 -0.050494201 -0.759911, + -0.60761279 -0.052658681 -0.79248571, + -0.60598701 -0.076048702 -0.79183102, + -0.56373 -0.078962997 -0.82217598, + -0.5614658 -0.10380896 -0.82096273, + -0.5175209 -0.10734298 -0.84891081, + -0.51462394 -0.13364199 -0.84693688, + -0.46983281 -0.13759096 -0.87196672, + -0.46633187 -0.16532995 -0.86902285, + -0.42102006 -0.16952302 -0.89106911, + -0.41701895 -0.19836697 -0.88698685, + -0.37130511 -0.20264708 -0.90612727, + -0.366889 -0.232694 -0.90069199, + -0.32112288 -0.23688892 -0.91693163, + -0.31651998 -0.26754197 -0.91007489, + -0.271597 -0.27144101 -0.92333901, + -0.267019 -0.30236501 -0.91502798, + -0.22331093 -0.30583388 -0.92552567, + -0.21897601 -0.336676 -0.91580498, + -0.17651106 -0.33963212 -0.92384738, + -0.17259499 -0.37026799 -0.91275001, + -0.13190003 -0.37262508 -0.91856027, + -0.12855798 -0.40329394 -0.90599489, + -0.090277031 -0.40500814 -0.90984529, + -0.087746255 -0.43498227 -0.89615351, + -0.051602092 -0.43608493 -0.89842486, + -0.049989589 -0.46558189 -0.88359177, + -0.015998397 -0.46610489 -0.88458478, + -0.015435806 -0.49492916 -0.86879629, + 0.016105592 -0.49492475 -0.86878657, + 0.016665494 -0.46613681 -0.8845557, + 0.050647888 -0.46560389 -0.88354278, + 0.052255791 -0.43614092 -0.89835978, + 0.088315926 -0.43503216 -0.89607328, + 0.090836793 -0.40513095 -0.9097349, + 0.12906994 -0.40340981 -0.90587056, + 0.13240702 -0.37275109 -0.91843623, + 0.1730819 -0.37038681 -0.91260958, + 0.17698795 -0.33979088 -0.92369765, + 0.21928906 -0.33683908 -0.91567022, + 0.22363903 -0.30592304 -0.92541713, + 0.26740396 -0.30244297 -0.91488987, + 0.2719911 -0.27140608 -0.92323333, + 0.31690192 -0.26750195 -0.90995377, + 0.32151103 -0.23674802 -0.91683209, + 0.36739087 -0.23253791 -0.90052772, + 0.37183392 -0.20217095 -0.90601677, + 0.41751984 -0.19789493 -0.88685668, + 0.421565 -0.16860799 -0.89098501, + 0.46682781 -0.16443294 -0.8689267, + 0.4703021 -0.13682503 -0.87183416, + 0.515113 -0.132889 -0.84675801, + 0.5179652 -0.10693604 -0.84869128, + 0.5618999 -0.10341198 -0.82071584, + 0.56410491 -0.079211891 -0.82189488, + 0.60631496 -0.076287992 -0.79155689, + 0.60787606 -0.053977709 -0.79219514, + 0.64823717 -0.051762011 -0.75967717, + 0.64921701 -0.031224901 -0.75996202, + 0.68790138 -0.029796315 -0.72519237, + 0.72607285 -0.012300097 -0.68750781, + 0.72517663 -0.011078794 -0.68847364, + 0.72475702 -0.0278864 -0.68844002, + 0.68767381 -0.029384492 -0.72542483, + 0.68675077 -0.04866958 -0.72526175, + 0.64781505 -0.051006809 -0.76008815, + 0.64631474 -0.07214658 -0.75965267, + 0.60571688 -0.075229883 -0.79211581, + 0.60356975 -0.098288462 -0.79122871, + 0.56111586 -0.10203898 -0.82142383, + 0.55827409 -0.12697802 -0.81988215, + 0.51417172 -0.13126792 -0.84758252, + 0.51063806 -0.15799302 -0.84515512, + 0.46574795 -0.16260898 -0.86984891, + 0.46155283 -0.19104692 -0.86629671, + 0.4162572 -0.19581409 -0.88791144, + 0.41153309 -0.22552006 -0.88305223, + 0.36597711 -0.23027809 -0.90168327, + 0.36090603 -0.26079902 -0.89539415, + 0.3155109 -0.26536295 -0.91106278, + 0.31035593 -0.29609594 -0.90333074, + 0.2659249 -0.30026188 -0.91603869, + 0.26083687 -0.33126786 -0.90676659, + 0.21790993 -0.33490089 -0.91670966, + 0.21315089 -0.36569083 -0.90600055, + 0.17183593 -0.36872482 -0.91351759, + 0.16754596 -0.39951491 -0.90128577, + 0.12788405 -0.40191615 -0.90670228, + 0.12429597 -0.43221191 -0.89316475, + 0.087380655 -0.4339228 -0.89670259, + 0.084648728 -0.46383119 -0.88187027, + 0.050032619 -0.46491918 -0.88393831, + 0.048316911 -0.49406013 -0.86808419, + 0.015774803 -0.49457613 -0.8689912, + -0.015075305 -0.49455017 -0.86901832, + -0.0476261 -0.49404499 -0.86813098, + -0.049345318 -0.46486518 -0.88400531, + -0.084006794 -0.46378693 -0.88195491, + -0.086748555 -0.4337998 -0.89682359, + -0.12371194 -0.43209678 -0.89330161, + -0.12731305 -0.40172514 -0.90686733, + -0.16700296 -0.3993319 -0.90146774, + -0.17129694 -0.36853689 -0.91369468, + -0.21272208 -0.36550513 -0.90617627, + -0.21750295 -0.33460391 -0.91691476, + -0.26047894 -0.3309769 -0.90697575, + -0.26553708 -0.30017912 -0.91617829, + -0.30998501 -0.29602 -0.90348297, + -0.31512815 -0.26540011 -0.91118443, + -0.36062199 -0.26083201 -0.89549899, + -0.36563203 -0.23068602 -0.90171909, + -0.41117299 -0.225927 -0.88311601, + -0.415865 -0.196467 -0.88795102, + -0.46109611 -0.19169804 -0.86639619, + -0.46526799 -0.163536 -0.869932, + -0.51015711 -0.15890105 -0.84527516, + -0.51371521 -0.13207905 -0.84773332, + -0.55780393 -0.12777099 -0.82007891, + -0.56069613 -0.10246602 -0.82165718, + -0.60318309 -0.098701321 -0.7914722, + -0.60539168 -0.074994966 -0.79238665, + -0.64605284 -0.071919985 -0.75989681, + -0.64761883 -0.049699288 -0.76034182, + -0.68660885 -0.04742039 -0.72547883, + -0.68756592 -0.026757196 -0.72562891, + -0.72473198 -0.0253904 -0.68856299, + -0.72512984 -0.0078122183 -0.68856782, + -0.72400296 -3.7848295e-005 -0.68979692, + -0.72397482 -0.0083469478 -0.68977582, + -0.75688368 -0.0044020084 -0.65353477, + -0.75689316 0.0014075304 -0.65353715, + -0.75690651 0.0014083391 -0.6535216, + -0.75689811 -0.0044018705 -0.65351808, + -0.75972402 -0.0091703804 -0.650181, + -0.75939661 -0.023494288 -0.6502037, + -0.72446603 -0.0248912 -0.68886101, + -0.72357309 -0.044248104 -0.68882805, + -0.68618184 -0.04663159 -0.72593385, + -0.68470603 -0.067584507 -0.72567904, + -0.64545518 -0.070828013 -0.76050717, + -0.64332592 -0.093350992 -0.75987989, + -0.60241914 -0.09732452 -0.79222417, + -0.59957922 -0.12154304 -0.79103231, + -0.55688703 -0.12614001 -0.82095414, + -0.55333221 -0.15189408 -0.8189944, + -0.50904495 -0.15695898 -0.84630787, + -0.50478989 -0.18427795 -0.84334379, + -0.45984712 -0.18956204 -0.86752915, + -0.45493314 -0.21838808 -0.86333227, + -0.40983114 -0.22369407 -0.88430732, + -0.4044849 -0.25332093 -0.87876076, + -0.35917699 -0.25850701 -0.89675301, + -0.35352108 -0.28892207 -0.88968927, + -0.30854699 -0.29379699 -0.90469998, + -0.30284184 -0.32450986 -0.89609158, + -0.25905502 -0.32887602 -0.9081471, + -0.25347203 -0.35985902 -0.89791614, + -0.21136689 -0.36360383 -0.90725756, + -0.20616205 -0.3944751 -0.89548123, + -0.16567099 -0.39756495 -0.90249389, + -0.16102405 -0.42825809 -0.88919425, + -0.12255404 -0.43065014 -0.89415932, + -0.11867999 -0.46091095 -0.87947488, + -0.082984999 -0.46259001 -0.88268, + -0.080055393 -0.49229193 -0.86674088, + -0.046975687 -0.49333188 -0.86857182, + -0.045155905 -0.52207708 -0.85170209, + -0.013876297 -0.54983687 -0.8351568, + 0.014576701 -0.54983205 -0.8351481, + 0.045818724 -0.52206123 -0.8516764, + 0.04763712 -0.49331519 -0.86854529, + 0.080702521 -0.49226511 -0.86669618, + 0.08362332 -0.46263111 -0.88259822, + 0.11927298 -0.46094295 -0.8793779, + 0.12313299 -0.43075994 -0.89402688, + 0.16170296 -0.42834991 -0.88902676, + 0.16630407 -0.39786714 -0.90224427, + 0.20657603 -0.39478305 -0.89525014, + 0.21179695 -0.36379191 -0.90708178, + 0.25388193 -0.36003992 -0.89772779, + 0.25943592 -0.32919788 -0.90792173, + 0.30317083 -0.32482681 -0.89586544, + 0.308916 -0.29387099 -0.90455002, + 0.35387397 -0.28898996 -0.8895269, + 0.35952297 -0.25857097 -0.8965959, + 0.40481207 -0.25338003 -0.87859315, + 0.41022316 -0.22333908 -0.8842153, + 0.45533493 -0.21803397 -0.8632099, + 0.46028799 -0.18888099 -0.86744398, + 0.50522888 -0.18360895 -0.84322685, + 0.50951415 -0.15602507 -0.84619832, + 0.55377203 -0.15098502 -0.81886512, + 0.55730879 -0.12525895 -0.82080269, + 0.59999096 -0.12068798 -0.79085088, + 0.60277611 -0.096854925 -0.79201019, + 0.64367115 -0.092896722 -0.7596432, + 0.64573175 -0.071079575 -0.76024872, + 0.68494296 -0.06782449 -0.72543293, + 0.68635792 -0.047943592 -0.72568196, + 0.72369874 -0.045494586 -0.68861479, + 0.72455025 -0.02749891 -0.68867326, + 0.7594198 -0.025958095 -0.65008283, + 0.78998917 -0.0082619116 -0.61306512, + 0.78987682 -0.0082640983 -0.6132099, + 0.75977421 -0.011676203 -0.65008217, + 0.75899512 0.0017538102 -0.65109408, + 0.7589519 -0.010189899 -0.65106696, + 0.72605205 -0.010668101 -0.68755704, + 0.72609806 -0.00016333001 -0.68759108, + 0.72613215 -0.00016335904 -0.68755519, + 0.69157016 0.0051348815 -0.72229117, + 0.69154209 -0.0095427707 -0.72227305, + 0.69153082 -0.0095429579 -0.72228384, + 0.69156516 0.0023984304 -0.72231019, + 0.6553272 -0.00023495605 -0.75534517, + 0.65529698 -0.00897869 -0.75531799, + 0.65522093 -0.0089797191 -0.75538391, + 0.65525109 -0.00023871603 -0.75541115, + 0.65529984 -0.00023874994 -0.75536883, + 0.61743605 0.0043479004 -0.78660911, + 0.62061214 0.0038722109 -0.78410816, + 0.44708911 0.003598891 -0.89448225, + 0.45218989 0.0029494793 -0.89191675, + 0.45217714 -0.0071689929 -0.89189929, + 0.45224294 -0.0071684592 -0.89186591, + 0.45225307 0.0047276006 -0.89187711, + 0.40795499 -7.1316201e-005 -0.91300201, + 0.40791085 -0.0070337178 -0.91299468, + 0.40792316 -7.2010029e-005 -0.91301632, + 0.40794116 -7.2016526e-005 -0.91300827, + 0.40792885 -0.0070257075 -0.9129867, + 0.40794316 -0.0070256223 -0.91298032, + 0.43673107 -0.022204703 -0.8993181, + 0.43635201 -0.039537702 -0.89890701, + 0.39066699 -0.040449802 -0.91964298, + 0.38969994 -0.067199491 -0.91848689, + 0.34310088 -0.068538979 -0.93679464, + 0.34174284 -0.096542753 -0.93482161, + 0.29506904 -0.098153815 -0.95042109, + 0.29338902 -0.12731901 -0.9474771, + 0.24705487 -0.12905094 -0.96036953, + 0.24520104 -0.15908901 -0.95633012, + 0.19918993 -0.16080894 -0.96667665, + 0.19730103 -0.19158103 -0.9614411, + 0.15188502 -0.19315504 -0.9693411, + 0.15011497 -0.22442494 -0.96285975, + 0.10625698 -0.22571197 -0.96838188, + 0.10480598 -0.25709596 -0.96068591, + 0.062244177 -0.25801891 -0.96413267, + 0.06127283 -0.28893015 -0.95538747, + 0.020201391 -0.28941485 -0.95699054, + 0.019846398 -0.31986296 -0.94725591, + -0.019409301 -0.319866 -0.94726402, + -0.019771991 -0.28945786 -0.95698655, + -0.060920384 -0.28897694 -0.95539576, + -0.061887369 -0.25810888 -0.96413153, + -0.10429402 -0.25719503 -0.96071512, + -0.10575201 -0.22583704 -0.96840811, + -0.14963202 -0.22455303 -0.96290511, + -0.15138808 -0.1935131 -0.96934748, + -0.19671592 -0.19194393 -0.96148866, + -0.19861192 -0.16122992 -0.96672553, + -0.24451102 -0.15951301 -0.9564361, + -0.24638803 -0.12927201 -0.96051115, + -0.29279903 -0.12753801 -0.94763011, + -0.29448894 -0.097999781 -0.95061678, + -0.34118608 -0.096394025 -0.93504024, + -0.34258816 -0.067545831 -0.9370544, + -0.38926092 -0.066225782 -0.91874379, + -0.3902559 -0.038197294 -0.91991377, + -0.43614006 -0.037333302 -0.89910412, + -0.43653786 -0.017803894 -0.89950973, + -0.44939479 -0.004153878 -0.8933236, + -0.44939715 0.0041947616 -0.89332229, + -0.40507686 -0.00013605396 -0.91428268, + -0.40500191 -0.00013602697 -0.91431576, + -0.40510994 -0.00013080398 -0.9142679, + -0.40510491 -0.0041686893 -0.91426075, + -0.40499681 -0.004169248 -0.91430861, + -0.40507218 -0.0041360818 -0.91427541, + -0.39099881 -0.018387591 -0.92020756, + -0.3906149 -0.038736794 -0.91973877, + -0.34393996 -0.039512698 -0.93815988, + -0.34301803 -0.068180904 -0.93685114, + -0.29625788 -0.069326177 -0.95258862, + -0.29500285 -0.098743357 -0.9503805, + -0.24844894 -0.10010198 -0.96345878, + -0.24696609 -0.13008904 -0.96025234, + -0.200699 -0.13151599 -0.97078502, + -0.19914 -0.161953 -0.96649599, + -0.15344898 -0.16330598 -0.9745689, + -0.15196399 -0.19427399 -0.96910501, + -0.10751302 -0.19541803 -0.97480911, + -0.10626196 -0.22648193 -0.96820164, + -0.063033216 -0.22731906 -0.97177821, + -0.062163707 -0.25844404 -0.96402413, + -0.020173308 -0.2588931 -0.96569538, + -0.019842798 -0.28954098 -0.9569599, + 0.020307101 -0.28953803 -0.95695114, + 0.020629691 -0.25884888 -0.96569753, + 0.062555626 -0.2583971 -0.96401137, + 0.063431531 -0.22714311 -0.97179347, + 0.10672201 -0.22630203 -0.96819311, + 0.10798195 -0.19506191 -0.97482854, + 0.15246001 -0.19391502 -0.9690991, + 0.15395702 -0.16294505 -0.97454923, + 0.19975697 -0.16158698 -0.96642989, + 0.20131201 -0.131236 -0.97069597, + 0.24758995 -0.12980796 -0.96012974, + 0.24905303 -0.10026202 -0.9632861, + 0.29558304 -0.098897912 -0.95018411, + 0.29682288 -0.07018698 -0.95234966, + 0.34343213 -0.069029026 -0.93663734, + 0.34433213 -0.041500013 -0.93793035, + 0.39082509 -0.040687412 -0.91956526, + 0.39119107 -0.022432001 -0.92003614, + 0.36262304 -0.0068059908 -0.93191111, + 0.36263219 0.0023502212 -0.93192941, + 0.3627021 0.0023423405 -0.93190223, + 0.36269209 -0.0068055815 -0.93188423, + 0.34486297 -0.022641398 -0.93837988, + 0.34451798 -0.041772597 -0.93784988, + 0.29794484 -0.042475682 -0.95363754, + 0.29845798 -0.016798098 -0.95427489, + 0.29807103 -0.042656403 -0.9535901, + 0.25155598 -0.043250695 -0.96687585, + 0.25084305 -0.072016813 -0.96534526, + 0.20432892 -0.072825879 -0.97618961, + 0.20342095 -0.10248598 -0.97371274, + 0.157084 -0.103375 -0.98215997, + 0.15612194 -0.13366696 -0.97865164, + 0.11079403 -0.13449302 -0.98470122, + 0.10992295 -0.16514492 -0.98012453, + 0.065407574 -0.16579594 -0.98398864, + 0.064759187 -0.19667496 -0.97832775, + 0.021502398 -0.19704397 -0.98015887, + 0.021257099 -0.22809497 -0.97340685, + -0.020750508 -0.22809708 -0.97341734, + -0.020991001 -0.19722202 -0.98013413, + -0.064288117 -0.19685705 -0.97832227, + -0.064922296 -0.16597898 -0.98398989, + -0.10922495 -0.16533493 -0.98017055, + -0.11010806 -0.13457806 -0.98476648, + -0.15546602 -0.13375501 -0.97874409, + -0.15643096 -0.10329398 -0.98227274, + -0.20278992 -0.10240895 -0.97385252, + -0.20371193 -0.072164275 -0.97636765, + -0.25034502 -0.071362808 -0.96552312, + -0.25107312 -0.041654717 -0.96707147, + -0.25137609 -0.042081013 -0.96697438, + -0.20464303 -0.042556904 -0.97791111, + -0.20403507 -0.072607726 -0.97626734, + -0.157438 -0.073243 -0.98480898, + -0.15671699 -0.10367598 -0.98218685, + -0.11106002 -0.10432301 -0.98832309, + -0.11035696 -0.13489896 -0.98469466, + -0.065562323 -0.13543704 -0.98861438, + -0.065032333 -0.16611607 -0.9839595, + -0.021135891 -0.16643092 -0.98582655, + -0.020919302 -0.19713503 -0.98015314, + 0.021575889 -0.19713192 -0.98013949, + 0.021784095 -0.16645895 -0.98580778, + 0.065682814 -0.16614005 -0.98391223, + 0.066218585 -0.13529697 -0.98858976, + 0.11099803 -0.13475603 -0.98464227, + 0.111699 -0.104361 -0.98824698, + 0.15733492 -0.10370995 -0.98208451, + 0.15805808 -0.073781639 -0.98466951, + 0.20455895 -0.073140785 -0.97611779, + 0.20515689 -0.043911677 -0.97774351, + 0.25167787 -0.043421779 -0.96683651, + 0.25195992 -0.022649392 -0.96747261, + 0.26955813 0.0018140208 -0.96298248, + 0.26964292 0.0018059993 -0.96295863, + 0.26963398 -0.007210149 -0.96293586, + 0.26954892 -0.0072105071 -0.96295965, + 0.31635699 -0.032628201 -0.94807899, + 0.31653285 0.00011183095 -0.94858152, + 0.31657904 0.00011181901 -0.94856614, + 0.31657016 -0.0069759833 -0.94854349, + 0.31648108 -0.0069764419 -0.94857323, + 0.31648996 0.00010659098 -0.94859588, + 0.3527509 0.004435529 -0.93570673, + 0.204548 0.0030034401 0.97885197, + 0.16932702 -0.0013214301 0.98555911, + 0.16930301 0.016128102 0.98543215, + 0.20505692 0.013229296 0.97866064, + 0.21743396 0.016188296 0.97594076, + 0.217465 0.00051527499 0.97606802, + 0.21734802 0.00052501407 0.97609413, + 0.21731603 0.016188702 0.97596711, + 0.26508304 0.011731802 0.96415424, + 0.26510391 -0.0014994094 0.96421862, + 0.265012 -0.00149943 0.96424401, + 0.85207599 -0.037818301 -0.52205002, + 0.87528759 -0.034941483 -0.48233876, + 0.87608111 -0.014914602 -0.48193306, + 0.87142289 0.00066195591 -0.49053195, + 0.87136787 -0.010818099 -0.49051094, + 0.8713156 -0.010820494 -0.49060377, + 0.87137002 0.00065793499 -0.49062601, + 0.89436901 0.00835294 -0.44725201, + 0.8943556 -0.0093587451 -0.4472588, + 0.89435869 -0.0093585765 -0.44725284, + 0.89437199 0.0083542597 -0.44724599, + 0.88268274 0.00059124688 -0.46996889, + 0.30412197 0.0028246997 0.95262891, + 0.26509106 -0.0014942203 0.96422225, + 0.26505303 0.016177703 0.9640981, + 0.29804698 0.012839599 0.95446485, + 0.312011 0.016163999 0.94994098, + 0.31205511 0.0011336204 0.95006335, + 0.31202084 0.0011371895 0.95007449, + 0.31197584 0.016164092 0.94995254, + 0.35821509 0.011260003 0.93357122, + 0.3582409 -0.0015949097 0.93362778, + 0.35819811 -0.0015949205 0.93364435, + 0.35814792 0.016058195 0.93352675, + 0.35817096 0.016058099 0.93351787, + 0.35822204 -0.0015936802 0.93363512, + 0.40361184 0.0028993292 0.91492569, + 0.40355906 0.015803803 0.91481709, + 0.40351483 0.015803993 0.91483659, + 0.40356916 0.0018393107 0.91494727, + 0.40045491 0.0022120595 0.91631377, + 0.57941282 0.0027181192 0.81502968, + 0.57413399 0.0034731899 0.81875402, + 0.5740748 0.014202096 0.81867969, + 0.61366802 0.011735 0.78947699, + 0.61371469 -0.0014157793 0.78952664, + 0.61380011 -0.0014157303 0.78946018, + 0.65163469 0.012813994 0.75842464, + 0.65169269 0.00092681253 0.75848264, + 0.6136741 -0.0014217703 0.78955817, + 0.61361313 0.013513103 0.78949118, + 0.64962715 0.011940603 0.76015919, + 0.64871997 0.036737397 0.76013988, + 0.68654895 0.035098895 0.72623593, + 0.68478197 0.059035692 0.72635293, + 0.72076362 0.056154273 0.69090265, + 0.71810097 0.080039591 0.69132096, + 0.75177413 0.075839706 0.65504503, + 0.74821794 0.099700786 0.65591896, + 0.7797097 0.094093464 0.61903077, + 0.7753529 0.11758499 0.62048495, + 0.805107 0.110435 0.58275801, + 0.80002385 0.13355298 0.58491492, + 0.82825917 0.12473303 0.54628611, + 0.82247883 0.14768697 0.54928786, + 0.84903711 0.13718101 0.51021308, + 0.84259403 0.160134 0.51419097, + 0.86771113 0.14779902 0.47458705, + 0.86068898 0.17073201 0.479651, + 0.88487643 0.15621008 0.4388532, + 0.87731898 0.179315 0.445149, + 0.90079927 0.16224906 0.40278515, + 0.89274311 0.18574701 0.41049707, + 0.91553432 0.16582505 0.36646813, + 0.90697187 0.19008997 0.37585595, + 0.92934185 0.16663499 0.32947898, + 0.92601711 0.17624801 0.33381003, + 0.94846624 0.14795204 0.28021806, + 0.95024925 0.14199702 0.27724206, + 0.96876067 0.11305296 0.22072993, + 0.96927863 0.11660396 0.21656993, + 0.948838 0.149693 0.27802601, + 0.95140654 0.14089693 0.27381289, + 0.93156087 0.16635899 0.32329398, + 0.93828613 0.14454702 0.31420603, + 0.91783875 0.16590096 0.36062291, + 0.92443067 0.14443696 0.35293889, + 0.90315157 0.16260593 0.39733681, + 0.90952742 0.14126907 0.39090016, + 0.88724613 0.15678501 0.43383506, + 0.89332914 0.13538902 0.42852405, + 0.87002897 0.148524 0.47009599, + 0.87573725 0.12695403 0.46579713, + 0.85125411 0.13798901 0.50628608, + 0.85645545 0.11633393 0.50294173, + 0.83035117 0.12557803 0.54290611, + 0.83499712 0.10366601 0.54040104, + 0.80700791 0.11125498 0.57996595, + 0.81104887 0.088899195 0.57818395, + 0.78136665 0.094840258 0.61682367, + 0.78471118 0.072039418 0.61566114, + 0.75311309 0.076459207 0.65343308, + 0.75565082 0.053574789 0.65277982, + 0.72174925 0.056616019 0.68983525, + 0.72345066 0.033645984 0.68955564, + 0.68720108 0.035404902 0.72560406, + 0.68806791 0.012006298 0.72554696, + 0.68814176 0.012014295 0.72547674, + 0.72247499 0.0121127 0.69129097, + 0.72281677 0.012106596 0.69093376, + 0.72493738 0.011044705 0.68872637, + 0.72408122 0.03395981 0.68887824, + 0.75819963 0.032103784 0.65123171, + 0.75658214 0.054038808 0.65166205, + 0.78831464 0.050846774 0.6131677, + 0.78593814 0.072643705 0.61402303, + 0.81565702 0.0679712 0.57452899, + 0.8125661 0.089627005 0.57593703, + 0.84039015 0.083339907 0.53553605, + 0.836716 0.104455 0.53758299, + 0.86245668 0.096537963 0.49683881, + 0.8582989 0.11712299 0.49960494, + 0.88225585 0.10744999 0.45834395, + 0.87768269 0.12770195 0.46191481, + 0.90019774 0.11604197 0.41973591, + 0.89529711 0.13602701 0.42419305, + 0.91657025 0.12210403 0.38077509, + 0.91147923 0.14174204 0.38615409, + 0.93147373 0.12536097 0.34152791, + 0.92631298 0.14468899 0.347864, + 0.94516754 0.12542194 0.30154186, + 0.94005603 0.14452399 0.30888101, + 0.95792037 0.12164505 0.25998309, + 0.95301539 0.14054805 0.26834309, + 0.96997225 0.11284603 0.21545205, + 0.969091 0.116667 0.217374, + 0.98305923 0.086678021 0.16149804, + 0.98446554 0.078676365 0.15696393, + 0.99388009 0.049499307 0.098753914, + 0.99435425 0.045176812 0.096013822, + 0.99931097 0.015801899 0.0335836, + 0.99936014 0.014527001 0.032685902, + 0.99926734 -0.015544405 -0.034975011, + 0.99931926 -0.014301703 -0.034008909, + 0.99328679 -0.044842288 -0.10663298, + 0.99356645 -0.042694017 -0.10489506, + 0.98074055 -0.073630661 -0.18090491, + 0.98139924 -0.070716918 -0.17847905, + 0.96077877 -0.10215198 -0.25781593, + 0.96182865 -0.098971061 -0.25512791, + 0.93238664 -0.13072996 -0.33699387, + 0.93369979 -0.12776497 -0.33448592, + 0.89506114 -0.15912502 -0.41658705, + 0.89637828 -0.15678406 -0.41463816, + 0.848221 -0.187326 -0.49540901, + 0.85665143 -0.17485109 -0.48536125, + 0.78533912 -0.20981804 -0.58242506, + 0.79325134 -0.20037208 -0.57498127, + 0.72815722 -0.22555207 -0.64723521, + 0.74530923 -0.20708407 -0.63374323, + 0.67674476 -0.22866993 -0.69980478, + 0.70128405 -0.20385604 -0.68311304, + 0.63052225 -0.22195508 -0.74375921, + 0.64974177 -0.20338693 -0.73244077, + 0.57648098 -0.21862499 -0.78732002, + 0.59099805 -0.20514803 -0.78015113, + 0.51583183 -0.21786693 -0.8285237, + 0.52395403 -0.21055603 -0.82531112, + 0.44861495 -0.22093298 -0.86598688, + 0.44989988 -0.21979894 -0.86560881, + 0.37619215 -0.22803408 -0.89804232, + 0.36994481 -0.23351389 -0.89922857, + 0.29975003 -0.23978902 -0.9233911, + 0.28725901 -0.250866 -0.92441797, + 0.22319807 -0.25529808 -0.94074738, + 0.20656104 -0.27052006 -0.94029325, + 0.15086991 -0.27331886 -0.95001841, + 0.13289905 -0.2906391 -0.94755834, + 0.086708598 -0.29213601 -0.952438, + 0.069665588 -0.30980393 -0.94824475, + 0.03303811 -0.31038913 -0.95003533, + 0.019610608 -0.32567513 -0.94527835, + -0.007969643 -0.32572711 -0.94543034, + -0.015160498 -0.33490497 -0.94212991, + -0.035295717 -0.33473414 -0.94165146, + -0.040126685 -0.34175888 -0.93893063, + -0.053678919 -0.34154212 -0.93833238, + -0.055506501 -0.344614 -0.93710202, + -0.063911423 -0.34444013 -0.93663037, + -0.059318677 -0.33536288 -0.94021964, + -0.065060973 -0.33524284 -0.93988252, + -0.062428776 -0.32902688 -0.94225466, + -0.064702809 -0.32897902 -0.94211811, + -0.061501514 -0.31980509 -0.94548523, + -0.060774829 -0.31981915 -0.94552749, + -0.057673685 -0.30879995 -0.94937676, + -0.054277588 -0.30885893 -0.94955778, + -0.05265459 -0.30147594 -0.95201874, + -0.041928999 -0.30162901 -0.95250303, + -0.026958097 -0.21184297 -0.97693187, + -0.020239994 -0.21187696 -0.97708678, + 0.0090792086 0.040562388 -0.99913573, + 0.0046735499 0.040563598 -0.99916601, + 0.022890102 0.30837303 -0.95099014, + 0.0071994672 0.30844587 -0.95121467, + 0.013065903 0.57586813 -0.81743819, + -0.013612702 0.57586408 -0.81743211, + -0.0076117474 0.30866387 -0.95114064, + -0.0233691 0.30858701 -0.95090902, + -0.0050238185 0.040082689 -0.99918377, + -0.0093894638 0.040081415 -0.99915236, + 0.020198593 -0.21450692 -0.97651362, + 0.0272553 -0.214471 -0.97635001, + 0.042083114 -0.30336612 -0.95194435, + 0.05297808 -0.30320787 -0.95145065, + 0.054236989 -0.30893394 -0.94953579, + 0.057660572 -0.30887386 -0.94935352, + 0.060721178 -0.31974888 -0.94555461, + 0.061409377 -0.31973588 -0.94551462, + 0.064813927 -0.32949114 -0.94193149, + 0.062644467 -0.32953584 -0.9420625, + 0.065042809 -0.33520004 -0.93989915, + 0.059263006 -0.33532104 -0.94023812, + 0.061963886 -0.34066191 -0.93814176, + 0.052915499 -0.34084001 -0.938631, + 0.05624 -0.34642601 -0.93638998, + 0.043543804 -0.34664503 -0.93698514, + 0.037443284 -0.33779487 -0.94047463, + 0.01784279 -0.33797884 -0.94098455, + 0.0072409129 -0.32446411 -0.94587034, + -0.020567808 -0.32440311 -0.94569534, + -0.034216892 -0.30885994 -0.95049179, + -0.07105349 -0.30825996 -0.94864488, + -0.087740369 -0.29095292 -0.95270562, + -0.13412397 -0.28943995 -0.94775277, + -0.15236701 -0.27184603 -0.95020211, + -0.2082631 -0.26902613 -0.94034648, + -0.22511303 -0.25359002 -0.9407531, + -0.28937805 -0.24913506 -0.92422521, + -0.30193099 -0.237982 -0.92314798, + -0.37217781 -0.2316989 -0.89877659, + -0.37822315 -0.22638507 -0.89760631, + -0.45198795 -0.21814597 -0.86493886, + -0.45022005 -0.21970902 -0.8654651, + -0.52547818 -0.20934707 -0.82464927, + -0.51616287 -0.21774395 -0.82834983, + -0.59130788 -0.20501995 -0.77994984, + -0.57532811 -0.21984605 -0.7878232, + -0.64866382 -0.20456496 -0.73306781, + -0.62875623 -0.22374508 -0.74471724, + -0.699687 -0.20557401 -0.68423498, + -0.6753462 -0.23010406 -0.7006852, + -0.74411923 -0.20843408 -0.63469821, + -0.72665179 -0.22717692 -0.64835775, + -0.79200786 -0.20188197 -0.57616591, + -0.79648584 -0.19645196 -0.57185388, + -0.85283428 -0.16965505 -0.49385318, + -0.85301298 -0.169397 -0.493633, + -0.89982778 -0.14159697 -0.41262591, + -0.89837301 -0.144181 -0.414895, + -0.93587512 -0.11565501 -0.33280903, + -0.93444711 -0.11887102 -0.33567604, + -0.9630335 -0.089922555 -0.25392988, + -0.96200562 -0.093029372 -0.2566919, + -0.98199087 -0.064373493 -0.17762299, + -0.98138279 -0.067061387 -0.17997396, + -0.99378234 -0.038876314 -0.10433304, + -0.99353665 -0.040765684 -0.10593896, + -0.99934453 -0.013001094 -0.033786286, + -0.99931467 -0.013724695 -0.03437759, + -0.9993611 0.013251602 0.033192404, + -0.9993369 0.013865299 0.033669498, + -0.99430764 0.040571384 0.09852086, + -0.99424547 0.041117217 0.098920844, + -0.98490465 0.066438481 0.15983994, + -0.98459399 0.068166301 0.16102199, + -0.97130686 0.092715792 0.21901298, + -0.97053611 0.095919415 0.22104102, + -0.95348078 0.12000297 0.27653894, + -0.95206678 0.12475897 0.27929193, + -0.93168473 0.14815997 0.33168092, + -0.92938036 0.15474506 0.33512112, + -0.90575159 0.17767091 0.38476881, + -0.90230298 0.186307 0.38876599, + -0.87546003 0.20886099 0.43582901, + -0.8706879 0.21956398 0.44010693, + -0.84077489 0.24168298 0.48444495, + -0.84495085 0.23290896 0.48146793, + -0.8174473 0.25083208 0.51852018, + -0.83096498 0.22133701 0.51039898, + -0.80339783 0.23689994 0.54628789, + -0.81539088 0.20861296 0.54001695, + -0.78715169 0.22225192 0.57532281, + -0.79774499 0.194934 0.57061702, + -0.76846355 0.20686215 0.60553443, + -0.77783215 0.18008605 0.60211813, + -0.74765497 0.190291 0.63624001, + -0.75586581 0.16382295 0.63389981, + -0.72438991 0.17249699 0.66746092, + -0.731426 0.14642 0.66601598, + -0.69823402 0.15370899 0.69917297, + -0.70415401 0.12784 0.69844401, + -0.66904801 0.133812 0.73107398, + -0.67390573 0.10789395 0.73089665, + -0.63719177 0.11255097 0.76244271, + -0.64103109 0.086376607 0.76263911, + -0.60268891 0.089804575 0.79290682, + -0.60552406 0.063219108 0.79331213, + -0.56520182 0.065532781 0.82234567, + -0.56705981 0.038405687 0.82278073, + -0.52459806 0.039696105 0.85042411, + -0.52553618 0.010184304 0.85071027, + -0.53602707 0.013300202 0.84409612, + -0.53607917 -0.0015736906 0.84416628, + -0.53605598 -0.0015737 0.844181, + -0.53600389 0.013298097 0.84411085, + -0.53611016 0.013297104 0.84404331, + -0.56862813 0.0099743325 0.8225342, + -0.56766903 0.038651805 0.82234913, + -0.60853785 0.037255794 0.79264981, + -0.60666901 0.063678898 0.7924, + -0.64545006 0.061183508 0.76134813, + -0.64262217 0.087006025 0.76122719, + -0.67964983 0.083298579 0.72879183, + -0.67586893 0.10865299 0.72896892, + -0.71123093 0.10362998 0.69527793, + -0.70649576 0.12871096 0.69591475, + -0.73981398 0.122363 0.66159099, + -0.73411304 0.14736702 0.66284305, + -0.76555789 0.13962698 0.62803292, + -0.75885582 0.16479495 0.63006383, + -0.78886169 0.15551195 0.59456974, + -0.781111 0.181034 0.59757203, + -0.80999583 0.17002895 0.56124586, + -0.80126309 0.19579104 0.56537008, + -0.82891029 0.18305106 0.52858317, + -0.8191461 0.20931503 0.53402907, + -0.84581786 0.19467697 0.49668193, + -0.83491486 0.22179598 0.50370991, + -0.86122513 0.20480803 0.46512905, + -0.84911287 0.23303597 0.47402695, + -0.87550122 0.21318504 0.4336471, + -0.87160611 0.22206703 0.43702307, + -0.8994379 0.19798598 0.38963193, + -0.90306586 0.18897897 0.38569295, + -0.92752165 0.16445693 0.33564487, + -0.92996991 0.15749198 0.33219296, + -0.95097762 0.13248396 0.2794449, + -0.95247775 0.12744197 0.27666694, + -0.96997923 0.10174502 0.22088106, + -0.97078633 0.098377839 0.21885107, + -0.98435867 0.072231881 0.16068794, + -0.98471802 0.070216902 0.159374, + -0.99419498 0.043379799 0.098461002, + -0.99428689 0.042559795 0.097888984, + -0.99933702 0.0145163 0.033388101, + -0.99934065 0.014423494 0.033319388, + -0.99929303 -0.0149351 -0.0345014, + -0.99931735 -0.014348205 -0.034045011, + -0.99326646 -0.044993524 -0.10675905, + -0.99354225 -0.042879712 -0.10504902, + -0.98066723 -0.073951215 -0.18117104, + -0.98132652 -0.07104066 -0.1787499, + -0.96063054 -0.10261095 -0.25818589, + -0.96173453 -0.099274255 -0.25536489, + -0.93220621 -0.13113903 -0.3373341, + -0.93371314 -0.12774101 -0.33445802, + -0.89510524 -0.15907905 -0.41651008, + -0.89684111 -0.15598801 -0.41393706, + -0.84888202 -0.186396 -0.494627, + -0.85028201 -0.184351 -0.49298599, + -0.79321414 -0.21328802 -0.57036805, + -0.79202902 -0.214748 -0.57146603, + -0.72663891 -0.24166997 -0.64311093, + -0.71957195 -0.24915397 -0.64818096, + -0.64792502 -0.273296 -0.71098697, + -0.66656709 -0.25540504 -0.70032609, + -0.59329104 -0.27580604 -0.7562651, + -0.618689 -0.25245601 -0.74396902, + -0.54441094 -0.26954597 -0.79433089, + -0.56381613 -0.25217706 -0.78645921, + -0.48891506 -0.26635402 -0.8306731, + -0.50334901 -0.25368401 -0.82600498, + -0.42925707 -0.26516303 -0.86338115, + -0.43641114 -0.25894809 -0.86167932, + -0.3642219 -0.26803195 -0.89190876, + -0.36407197 -0.26816198 -0.89193088, + -0.29538003 -0.27507502 -0.91492313, + -0.28839508 -0.28123009 -0.91528028, + -0.22515407 -0.2861681 -0.93135035, + -0.21332397 -0.29692098 -0.93076891, + -0.15769005 -0.30011407 -0.94077921, + -0.14327498 -0.31388098 -0.93858987, + -0.096218035 -0.31568113 -0.94397438, + -0.08194571 -0.33028302 -0.94031811, + -0.043822695 -0.33107898 -0.94258487, + -0.031793013 -0.34453118 -0.93823647, + -0.0022707507 -0.3447051 -0.93870836, + 0.0066797277 -0.35586187 -0.93451464, + 0.028347796 -0.35572696 -0.93415987, + 0.034614217 -0.36458018 -0.9305284, + 0.049300712 -0.36435509 -0.92995423, + 0.05196159 -0.36868292 -0.92810178, + 0.060702924 -0.36850113 -0.92764336, + 0.056514286 -0.3605099 -0.93104178, + 0.0621568 -0.36038899 -0.93072897, + 0.058785621 -0.35270211 -0.93388736, + 0.061567992 -0.35264397 -0.93372989, + 0.058476277 -0.34408289 -0.93711662, + 0.058173709 -0.34408903 -0.93713313, + 0.054617982 -0.33186987 -0.94174266, + 0.044054497 -0.33204296 -0.94223487, + 0.049654912 -0.3559151 -0.93319821, + 0.052232418 -0.35586813 -0.93307537, + 0.055608019 -0.36707613 -0.92852736, + 0.055342413 -0.36708108 -0.92854124, + 0.059054386 -0.37699991 -0.92432874, + 0.056282986 -0.37706092 -0.92447674, + 0.060946815 -0.38731408 -0.91993123, + 0.055544391 -0.38743594 -0.92022187, + 0.055426285 -0.38721791 -0.92032075, + 0.044964716 -0.38742214 -0.92080534, + 0.042054195 -0.38282093 -0.92286485, + 0.025566597 -0.38303494 -0.9233799, + 0.020464092 -0.37600484 -0.92639166, + -0.0027719906 -0.37608209 -0.92658222, + -0.010612103 -0.36651608 -0.93035126, + -0.04145309 -0.3662219 -0.92960376, + -0.051805373 -0.35484281 -0.93348956, + -0.090725072 -0.35385489 -0.93088967, + -0.102097 -0.34237701 -0.933999, + -0.149235 -0.34032199 -0.92839098, + -0.15937595 -0.33074591 -0.93016475, + -0.21427596 -0.32724592 -0.92032379, + -0.22116593 -0.32105088 -0.92087567, + -0.28289798 -0.31575596 -0.9056859, + -0.28440005 -0.3144491 -0.90567023, + -0.35107702 -0.30711502 -0.88454813, + -0.34604889 -0.31140688 -0.88502872, + -0.41622385 -0.30179688 -0.85771573, + -0.403896 -0.312242 -0.85986799, + -0.47648695 -0.30008298 -0.82638389, + -0.45869201 -0.31518999 -0.83081698, + -0.53293598 -0.300136 -0.79113698, + -0.50806206 -0.32144904 -0.79908913, + -0.58279186 -0.30327395 -0.75390881, + -0.56420213 -0.3195971 -0.76127118, + -0.63892096 -0.29777896 -0.70930094, + -0.63383019 -0.30253005 -0.71185321, + -0.72904623 -0.26771608 -0.62993622, + -0.71678883 -0.28116494 -0.63809085, + -0.71065634 -0.30246815 -0.63520128, + -0.778032 -0.270089 -0.56720197, + -0.7764191 -0.27209103 -0.56845409, + -0.83704382 -0.23622194 -0.4935149, + -0.83496171 -0.23927091 -0.49556881, + -0.8866899 -0.20103396 -0.41637295, + -0.88446432 -0.20499608 -0.41916513, + -0.92665726 -0.16514805 -0.33768708, + -0.92459124 -0.16979104 -0.34103107, + -0.95727724 -0.12888104 -0.25886306, + -0.95511174 -0.13533297 -0.26352695, + -0.98016751 -0.090529956 -0.17628391, + -0.97930437 -0.09449444 -0.17898005, + -0.99342221 -0.05346271 -0.10126302, + -0.99303389 -0.056680992 -0.10329998, + -0.99931413 -0.017813902 -0.032465603, + -0.99926811 -0.019034302 -0.033180203, + -0.99932438 0.018288407 0.03188001, + -0.99935222 0.017494004 0.031451907, + -0.99441999 0.051278401 0.092192002, + -0.99510175 0.043897588 0.088574477, + -0.9870289 0.07128989 0.14384599, + -0.98834062 0.061198279 0.13941896, + -0.97796589 0.083909892 0.19115897, + -0.97980201 0.071998797 0.18655901, + -0.96748322 0.091068722 0.23597206, + -0.96971178 0.077776887 0.23153794, + -0.95578736 0.09363693 0.27875209, + -0.95826113 0.079253308 0.27469003, + -0.94271547 0.092477143 0.32052416, + -0.94526714 0.077345811 0.31699803, + -0.92795312 0.088344507 0.36207503, + -0.93046576 0.072539583 0.35912591, + -0.91128814 0.081526406 0.40361807, + -0.91365623 0.065020017 0.40125409, + -0.89266622 0.072095118 0.44491512, + -0.89478791 0.054806791 0.44311494, + -0.87182009 0.060126007 0.48612207, + -0.87358987 0.041944098 0.48485193, + -0.84829789 0.045637798 0.52754897, + -0.84959799 0.0264339 0.52676803, + -0.82174879 0.028559893 0.56913388, + -0.82248503 0.0070627802 0.56874299, + -0.81808698 0.0063944999 0.575059, + -0.818106 -0.00074503699 0.57506698, + -0.84549081 -7.4331983e-005 0.53398991, + -0.84545285 0.0090871081 0.53397286, + -0.84539127 0.0090885432 0.53407019, + -0.8506887 0.0059843375 0.52563584, + -0.8500123 0.02671041 0.5260852, + -0.8753677 0.024514491 0.48283583, + -0.87421715 0.042367913 0.48368311, + -0.89709073 0.038555693 0.44016087, + -0.89556068 0.055329081 0.44148585, + -0.9162969 0.049802992 0.39739093, + -0.91450876 0.065589689 0.39921391, + -0.93326801 0.058231499 0.35442901, + -0.93133235 0.073101833 0.35675812, + -0.9480741 0.063843705 0.31157604, + -0.94609588 0.077851892 0.31439096, + -0.96094209 0.066521704 0.26863602, + -0.95902288 0.079668693 0.27189696, + -0.97210366 0.065952979 0.22508793, + -0.97036564 0.078062773 0.22868493, + -0.98172277 0.061482184 0.18011196, + -0.9803111 0.072131507 0.18381302, + -0.98966402 0.052385502 0.133495, + -0.98868024 0.061179616 0.13699803, + -0.99576497 0.037488099 0.083945699, + -0.99526685 0.043773796 0.086761996, + -0.99945635 0.014851905 0.029437112, + -0.99937737 0.017396506 0.030698411, + -0.99933565 -0.017968494 -0.031707488, + -0.99930239 -0.018903408 -0.032211311, + -0.99305999 -0.059526201 -0.101432, + -0.99342936 -0.05636622 -0.099604338, + -0.97975248 -0.098606348 -0.17424709, + -0.98063987 -0.094328485 -0.17160298, + -0.95710886 -0.13956499 -0.25389796, + -0.95827162 -0.13588895 -0.25149491, + -0.92072266 -0.18549794 -0.34330788, + -0.92389691 -0.17843099 -0.33849198, + -0.88033623 -0.22119506 -0.4196201, + -0.88297021 -0.21652104 -0.4165121, + -0.82990968 -0.2573269 -0.49500781, + -0.83229589 -0.25383797 -0.49279794, + -0.7704888 -0.29190093 -0.56669289, + -0.77223271 -0.28973791 -0.56542784, + -0.70325291 -0.32421398 -0.63270897, + -0.71823525 -0.30774513 -0.62404424, + -0.62113523 -0.34662312 -0.70288223, + -0.63728106 -0.33132604 -0.69577008, + -0.56238997 -0.35550696 -0.74654692, + -0.5564869 -0.36068591 -0.74848384, + -0.48175099 -0.380418 -0.78942901, + -0.46776319 -0.39175916 -0.79228932, + -0.39614895 -0.40697694 -0.82306486, + -0.41179314 -0.39472815 -0.82135028, + -0.34379011 -0.40675616 -0.84637928, + -0.36427203 -0.39056206 -0.84543914, + -0.29934594 -0.4001449 -0.86618483, + -0.31238088 -0.38960084 -0.86638868, + -0.25089207 -0.39700708 -0.88285822, + -0.25897303 -0.39026606 -0.88353014, + -0.20175508 -0.39574113 -0.8959263, + -0.20417392 -0.39363584 -0.89630568, + -0.15242197 -0.39740792 -0.90489477, + -0.15052906 -0.39914414 -0.90444732, + -0.10489695 -0.40151682 -0.90982461, + -0.10027696 -0.40604284 -0.90833569, + -0.061294571 -0.40733278 -0.91122061, + -0.055701982 -0.41327584 -0.90890068, + -0.0235266 -0.41380399 -0.91006202, + -0.01839569 -0.41982079 -0.90742058, + 0.006963673 -0.41988119 -0.90755242, + 0.010640697 -0.42471686 -0.90526372, + 0.029658407 -0.4245531 -0.90491724, + 0.031282384 -0.42698878 -0.90371561, + 0.044597976 -0.4267728 -0.90325856, + 0.044350412 -0.4263421 -0.90347421, + 0.052635282 -0.42616984 -0.90311068, + 0.051217008 -0.42325005 -0.90456414, + 0.055070028 -0.42316321 -0.90437841, + 0.05228921 -0.41624409 -0.90774822, + 0.052394606 -0.41624206 -0.9077431, + 0.047789913 -0.40203309 -0.91437721, + 0.045869511 -0.40207008 -0.91445923, + 0.042338904 -0.38806707 -0.92065811, + 0.032502588 -0.38820985 -0.92099762, + 0.036898293 -0.41094792 -0.91091174, + 0.024649309 -0.42962414 -0.90267128, + 0.02859821 -0.42957914 -0.90257633, + 0.022971092 -0.38845184 -0.92118263, + 0.018416096 -0.38848791 -0.92126977, + 0.015151593 -0.34539083 -0.93833655, + 0.0065583489 -0.34542397 -0.93842387, + 0.0059411325 -0.31902912 -0.94772637, + -0.0060230708 -0.31902802 -0.94772613, + -0.006636709 -0.34539798 -0.93843287, + -0.015219 -0.34536499 -0.93834502, + -0.018479707 -0.38842914 -0.92129338, + -0.022963092 -0.38839287 -0.92120767, + -0.028581696 -0.42945895 -0.90263391, + -0.029507296 -0.42944694 -0.90260988, + 0.91334075 0.0004197479 0.4071959, + 0.93220723 -0.0008091412 0.36192408, + 0.94879812 0.0051690205 0.31584102, + 0.9322111 -0.00080884009 0.36191404, + 0.93216985 0.0091675492 0.36190498, + 0.9321661 0.0091677411 0.36191502, + -0.027869096 -0.47808594 -0.87787086, + -0.036371998 -0.47795501 -0.87763101, + -0.039935786 -0.49027982 -0.8706497, + -0.039494511 -0.49028811 -0.87066519, + -0.042988822 -0.49976525 -0.86509341, + -0.039176501 -0.49984401 -0.86522901, + -0.0423862 -0.50692397 -0.86094803, + -0.034887295 -0.50707096 -0.86119789, + -0.037559692 -0.51199186 -0.85816884, + -0.026014503 -0.51218003 -0.85848415, + -0.028130796 -0.51550293 -0.85642588, + -0.012255803 -0.51566911 -0.85670018, + -0.014022204 -0.51808012 -0.85521716, + 0.0063110008 -0.51812106 -0.85528409, + 0.0043909289 -0.52043688 -0.85388881, + 0.029157603 -0.52022207 -0.85353315, + 0.026671804 -0.52290905 -0.85197109, + 0.055868115 -0.52227813 -0.85094321, + 0.051877007 -0.52619004 -0.84878314, + 0.08518973 -0.52498519 -0.84683728, + 0.078762822 -0.53076512 -0.84385115, + 0.11587998 -0.52883291 -0.84077787, + 0.10495204 -0.53792918 -0.83643132, + 0.14545991 -0.5351637 -0.83213055, + 0.13929103 -0.53997213 -0.83007717, + 0.18442504 -0.53593409 -0.82387018, + 0.19279808 -0.52964717 -0.82601631, + 0.24537791 -0.5232718 -0.81607372, + 0.24884088 -0.52069879 -0.8166706, + 0.30792406 -0.51148713 -0.80222416, + 0.3128531 -0.50779712 -0.80266118, + 0.37839419 -0.49488223 -0.78224635, + 0.38300592 -0.49132589 -0.78224385, + 0.45412794 -0.47387394 -0.75446087, + 0.45749301 -0.471145 -0.75413698, + 0.53214318 -0.44859514 -0.71804327, + 0.53382015 -0.44713315 -0.71771026, + 0.60974509 -0.41910705 -0.67272604, + 0.60942292 -0.41941494 -0.67282593, + 0.68457103 -0.38561201 -0.61860001, + 0.68207699 -0.38828501 -0.61968201, + 0.75395584 -0.34880492 -0.55667388, + 0.74952966 -0.35422781 -0.55922079, + 0.82873398 -0.29947099 -0.472776, + 0.83272785 -0.29324794 -0.46964887, + 0.89070421 -0.24076205 -0.38559008, + 0.89088011 -0.24040402 -0.38540706, + 0.93276215 -0.19079003 -0.30586603, + 0.93154711 -0.19404003 -0.30752003, + 0.9615261 -0.14659601 -0.23233002, + 0.96444327 -0.13559203 -0.22685707, + 0.98299277 -0.09421768 -0.15763296, + 0.98530966 -0.080040567 -0.15085894, + 0.9950161 -0.046734706 -0.088084109, + 0.99558061 -0.039888587 -0.085018769, + 0.99954122 -0.012865003 -0.027420407, + 0.9995845 -0.010988605 -0.026650613, + 0.99960053 0.010773594 0.026128987, + 0.999632 0.0091597401 0.025535, + 0.99672151 0.027319012 0.076158337, + 0.99693513 0.023026701 0.07476791, + 0.99164051 0.03797818 0.12331594, + 0.99208164 0.031625289 0.12154795, + 0.98464203 0.043961398 0.16896001, + 0.98528898 0.035888199 0.16708601, + 0.97575814 0.045958802 0.21397203, + 0.97655565 0.036342688 0.21217492, + 0.96506411 0.044235304 0.25825304, + 0.96592414 0.033249203 0.25668103, + 0.95235199 0.039181098 0.30247399, + 0.95315522 0.027226906 0.30125406, + 0.93732762 0.03136459 0.34703487, + 0.93797189 0.018580198 0.34621298, + 0.91972679 0.021037195 0.39199492, + 0.92015642 0.0052238423 0.39151618, + 0.932154 0.0091659296 0.36194599, + 0.93219566 -0.00080916472 0.36195388, + 0.91333491 0.00042138994 0.40720895, + 0.91328889 0.0097760586 0.40719494, + 0.91329426 0.0097758723 0.40718308, + 0.89938068 0.0059579578 0.43712586, + 0.89887321 0.023167806 0.43759611, + 0.91945136 0.020788407 0.39265415, + 0.91865724 0.035078607 0.39349508, + 0.93696803 0.031026 0.34803501, + 0.93593657 0.044610679 0.34933183, + 0.95195401 0.0387928 0.303774, + 0.95079511 0.051553808 0.30550104, + 0.96466899 0.043840099 0.259792, + 0.96351635 0.055391219 0.2618551, + 0.97541386 0.045608897 0.21560997, + 0.97437602 0.055811599 0.21789099, + 0.98437667 0.043690186 0.17056894, + 0.98353809 0.052419007 0.17293102, + 0.99147046 0.037807819 0.12472806, + 0.99089766 0.044792086 0.12694696, + 0.99664223 0.027244706 0.077214912, + 0.99636525 0.031991906 0.078948021, + 0.99958915 0.010764301 0.026563503, + 0.99954778 0.012585697 0.027311394, + 0.9995265 -0.012877894 -0.027945787, + 0.99946779 -0.015061696 -0.028934393, + 0.9948355 -0.046866421 -0.090033442, + 0.99404162 -0.055084083 -0.094058864, + 0.98230726 -0.094640821 -0.16160305, + 0.98099566 -0.10167896 -0.16525394, + 0.95969564 -0.14727694 -0.23936091, + 0.96094722 -0.14288902 -0.23698805, + 0.92894834 -0.19115607 -0.31704012, + 0.92990738 -0.18872507 -0.31568211, + 0.88379622 -0.24007706 -0.40158108, + 0.88294071 -0.2416909 -0.40249386, + 0.81736386 -0.29658797 -0.49391493, + 0.82225269 -0.28951392 -0.48998183, + 0.75798184 -0.3318139 -0.5615719, + 0.7609899 -0.32809797 -0.55968392, + 0.69022483 -0.36594293 -0.62423986, + 0.69151378 -0.36455387 -0.62362576, + 0.61698991 -0.39715895 -0.67940295, + 0.61654878 -0.39758384 -0.67955476, + 0.54075807 -0.42478305 -0.72604406, + 0.53835297 -0.42688593 -0.72659796, + 0.46363187 -0.44882387 -0.76393884, + 0.45968801 -0.45203301 -0.76442999, + 0.3882249 -0.46907687 -0.79325181, + 0.38333091 -0.47286487 -0.79338282, + 0.31742692 -0.4854959 -0.81457585, + 0.31336591 -0.48855388 -0.81431985, + 0.25385505 -0.49761412 -0.82942015, + 0.24398306 -0.50497913 -0.82793015, + 0.19180401 -0.51104802 -0.837879, + 0.19924302 -0.50538206 -0.83957809, + 0.15172593 -0.5097518 -0.84683669, + 0.16446196 -0.49952388 -0.85054582, + 0.12057606 -0.50272423 -0.85599643, + 0.12785095 -0.49648783 -0.85857671, + 0.088123828 -0.49864817 -0.86231327, + 0.092146799 -0.494939 -0.86402798, + 0.05688468 -0.49624881 -0.86631471, + 0.058707178 -0.49442282 -0.86723667, + 0.028227707 -0.49507913 -0.86838919, + 0.029045189 -0.49417582 -0.8688767, + 0.003579658 -0.4943817 -0.86923748, + 0.0039797993 -0.49388894 -0.8695159, + -0.016509695 -0.49382481 -0.86940467, + -0.015790001 -0.49281999 -0.86998802, + -0.031405617 -0.49263823 -0.86966741, + -0.029949296 -0.49029493 -0.87104189, + -0.040955011 -0.49010411 -0.87070119, + -0.038641278 -0.48572969 -0.87325448, + -0.045419917 -0.48559117 -0.87300527, + -0.042424705 -0.47879505 -0.87690109, + -0.04546351 -0.47873011 -0.87678427, + -0.041985698 -0.46900693 -0.88219589, + -0.041671187 -0.46901283 -0.88220769, + -0.03791932 -0.45561221 -0.88937044, + -0.034942891 -0.45566189 -0.88946676, + -0.022890098 -0.47367194 -0.88040388, + -0.027329994 -0.47361889 -0.88030577, + -0.021497006 -0.43391109 -0.90069926, + -0.017346699 -0.43394595 -0.90077186, + -0.013869897 -0.39122692 -0.92018974, + -0.0061794287 -0.3912569 -0.92026079, + -0.0050587882 -0.34633389 -0.93809766, + 0.0050238487 -0.34633392 -0.93809777, + 0.0061456524 -0.39127713 -0.92025238, + 0.013871504 -0.39124709 -0.92018121, + 0.017353896 -0.43403292 -0.90072978, + 0.021571092 -0.43399784 -0.90065569, + 0.027442399 -0.473874 -0.88016498, + 0.027189605 -0.47387713 -0.88017124, + 0.03278292 -0.49906629 -0.86594355, + 0.034569316 -0.49903625 -0.8658914, + 0.038168181 -0.51108277 -0.85868359, + 0.036968179 -0.51110572 -0.85872245, + 0.040555313 -0.5205422 -0.85287231, + 0.035978407 -0.5206331 -0.85302216, + 0.039352685 -0.52786881 -0.84841371, + 0.031207208 -0.52802014 -0.8486582, + 0.034263197 -0.53350294 -0.84510386, + 0.022263398 -0.53368396 -0.84539086, + 0.02507611 -0.53799617 -0.8425743, + 0.0090806875 -0.5381428 -0.84280473, + 0.012016503 -0.54206109 -0.84025317, + -0.0079619121 -0.54208314 -0.84028721, + -0.0044702208 -0.54620409 -0.83764017, + -0.028299799 -0.545991 -0.837313, + -0.023501391 -0.55105984 -0.8341347, + -0.05103479 -0.5504939 -0.83327782, + -0.044778068 -0.55647558 -0.82965642, + -0.075779714 -0.55543309 -0.82810116, + -0.066254809 -0.56375408 -0.82328111, + -0.100235 -0.56215101 -0.82093799, + -0.092391297 -0.56848103 -0.81749201, + -0.13035293 -0.56605166 -0.81399852, + -0.139862 -0.55877298 -0.817442, + -0.18538606 -0.55453718 -0.81124628, + -0.19160688 -0.54988968 -0.81296253, + -0.24402091 -0.54333383 -0.80326968, + -0.24742398 -0.54081392 -0.80392885, + -0.30625302 -0.53134906 -0.78985912, + -0.30919394 -0.52915388 -0.79018682, + -0.37434089 -0.51596284 -0.77048773, + -0.37704217 -0.51388925 -0.77055633, + -0.4478159 -0.49609587 -0.74387485, + -0.44981405 -0.49448305 -0.74374306, + -0.52430868 -0.47145474 -0.70910561, + -0.52501714 -0.47084111 -0.7089892, + -0.60117811 -0.44208613 -0.6656912, + -0.59987068 -0.44332778 -0.66604471, + -0.93858415 0.0031730004 0.34503603, + -0.93822026 0.018461304 0.3455461, + -0.95395589 0.016002199 0.29951996, + -0.95343125 0.027773608 0.30032906, + -0.96680337 0.023529408 0.25443608, + -0.96620065 0.033881988 0.25555491, + -0.97740489 0.027781596 0.20954198, + -0.97682089 0.036720797 0.21088497, + -0.98599327 0.028611308 0.16431305, + -0.98550612 0.036073305 0.16576001, + -0.99256325 0.025885306 0.11894603, + -0.99222726 0.031702608 0.12033303, + -0.99716514 0.019169401 0.072761305, + -0.99700123 0.023072705 0.073866017, + -0.99966526 0.0077144718 0.024697406, + -0.99964088 0.0091818888 0.025176497, + -0.99962866 -0.009336316 -0.025599891, + -0.99959552 -0.011018694 -0.026219187, + -0.9961279 -0.034060996 -0.081048995, + -0.99570566 -0.040032785 -0.083472371, + -0.98741663 -0.068385281 -0.14258996, + -0.9857325 -0.080427565 -0.14786093, + -0.97035176 -0.11548897 -0.21231996, + -0.96552235 -0.13621704 -0.22183707, + -0.93943709 -0.17933601 -0.29205602, + -0.93451875 -0.19353396 -0.29869595, + -0.89599699 -0.241466 -0.37267101, + -0.89628679 -0.24083994 -0.37237892, + -0.84439373 -0.29093692 -0.44983885, + -0.84216291 -0.29470897 -0.45156193, + -0.77299166 -0.34673584 -0.53127974, + -0.76446617 -0.3580471 -0.53609115, + -0.67401206 -0.41028607 -0.61430705, + -0.67574871 -0.4084388 -0.6136297, + -0.68172002 -0.387629 -0.62048501, + -0.60829097 -0.42053199 -0.67315298, + -0.60872006 -0.42012206 -0.67302108, + -0.53270596 -0.44814193 -0.71790892, + -0.53164214 -0.44906911 -0.71811819, + -0.45701975 -0.47159672 -0.75414151, + -0.45483094 -0.47337294 -0.75435185, + -0.38375807 -0.49083707 -0.7821821, + -0.38097095 -0.49299094 -0.78218991, + -0.31532496 -0.50599992 -0.80282891, + -0.31161398 -0.50879097 -0.8025139, + -0.25225896 -0.51813596 -0.81725186, + -0.24499606 -0.52354515 -0.81601316, + -0.19245204 -0.52990711 -0.82593018, + -0.18074402 -0.53867006 -0.82290113, + -0.136041 -0.54259801 -0.82890302, + -0.14478202 -0.53580505 -0.8318361, + -0.10437704 -0.53855217 -0.83610231, + -0.11528496 -0.52948284 -0.8404507, + -0.078273833 -0.53140116 -0.84349632, + -0.085027166 -0.52533174 -0.84663856, + -0.051785119 -0.5265342 -0.84857529, + -0.056543019 -0.52187115 -0.85114831, + -0.027262909 -0.52251315 -0.85219532, + -0.030156193 -0.51938391 -0.85400879, + -0.0052359803 -0.51961404 -0.85438514, + -0.0072201402 -0.51722002 -0.85582203, + 0.0132711 -0.51718801 -0.85576898, + 0.011542297 -0.51482791 -0.85721582, + 0.027593492 -0.51466584 -0.85694671, + 0.025569696 -0.51148796 -0.8589099, + 0.037251718 -0.51130027 -0.85859442, + 0.034666795 -0.50654393 -0.86151689, + 0.042269815 -0.50639617 -0.86126429, + 0.039138604 -0.49949706 -0.86543113, + 0.043053698 -0.49941593 -0.86529189, + 0.039530601 -0.48987499 -0.87089598, + 0.040050581 -0.48986375 -0.87087858, + 0.033951014 -0.46875525 -0.88267541, + 0.042090174 -0.46861073 -0.88240147, + 0.045533706 -0.47822705 -0.87705511, + 0.042370886 -0.47829282 -0.87717772, + 0.045402303 -0.48516506 -0.87324309, + 0.038527094 -0.48530489 -0.87349582, + 0.040746395 -0.48949793 -0.87105191, + 0.029622797 -0.48968893 -0.87139386, + 0.030967316 -0.49185124 -0.87012839, + 0.015179706 -0.49203119 -0.87044531, + 0.015796209 -0.49289131 -0.86994755, + -0.0048531089 -0.49294689 -0.87004584, + -0.0044919997 -0.49339294 -0.86979491, + -0.030128097 -0.49317393 -0.86940891, + -0.029224196 -0.49417195 -0.86887288, + -0.059882108 -0.49349606 -0.86768413, + -0.057539687 -0.49584487 -0.86650282, + -0.092863105 -0.49452206 -0.8641901, + -0.08791057 -0.49908781 -0.86208069, + -0.12755096 -0.49693483 -0.85836267, + -0.1199 -0.50348699 -0.85564297, + -0.163688 -0.500305 -0.850236, + -0.15097402 -0.51050204 -0.84651911, + -0.19833504 -0.50616205 -0.8393231, + -0.188354 -0.51374 -0.83701497, + -0.24014895 -0.50779486 -0.8273288, + -0.25363806 -0.49776313 -0.8293972, + -0.31318399 -0.488702 -0.81430101, + -0.32097799 -0.48281801 -0.814776, + -0.38701886 -0.47006583 -0.79325569, + -0.39065483 -0.46723878 -0.79314363, + -0.46211672 -0.45012474 -0.76409155, + -0.46424222 -0.4483912 -0.76382238, + -0.53896493 -0.42642993 -0.72641194, + -0.54020303 -0.42534706 -0.72612709, + -0.61603886 -0.3981449 -0.67968881, + -0.61595625 -0.39822415 -0.67971724, + -0.69057393 -0.36560997 -0.62404895, + -0.68921262 -0.36707282 -0.62469471, + -0.68310207 -0.38823506 -0.61858308, + -0.75329417 -0.3496201 -0.5570581, + -0.74998778 -0.35366988 -0.55895984, + -0.8290661 -0.29897103 -0.47251007, + -0.83274287 -0.29323697 -0.46962893, + -0.89071399 -0.240753 -0.385573, + -0.89063722 -0.24090905 -0.38565308, + -0.93261087 -0.19119696 -0.30607298, + -0.93149358 -0.19418292 -0.30759186, + -0.96149677 -0.14670397 -0.23238294, + -0.96415091 -0.13672298 -0.22741997, + -0.98285776 -0.09499298 -0.15800895, + -0.98522067 -0.080610469 -0.15113594, + -0.99498755 -0.047060076 -0.088232853, + -0.99556655 -0.04006378 -0.085100159, + -0.99953961 -0.012922895 -0.027449891, + -0.99958378 -0.011009097 -0.026663994, + -0.99960011 0.010792701 0.026140004, + -0.99963188 0.0091579892 0.025537696, + -0.99672222 0.027308706 0.076152317, + -0.99693787 0.022972697 0.074747592, + -0.99165022 0.037884608 0.12326703, + -0.99209136 0.031514511 0.12149704, + -0.98465526 0.043815311 0.16892104, + -0.98529625 0.035804007 0.16706105, + -0.97577065 0.045850486 0.21393792, + -0.97655445 0.036399517 0.21217111, + -0.96506274 0.04430389 0.25824594, + -0.96590686 0.033546895 0.25670698, + -0.95233899 0.039527301 0.30247, + -0.95315254 0.027471887 0.30123985, + -0.93734413 0.031641904 0.34696501, + -0.93801677 0.018252097 0.34610891, + -0.91977012 0.020667503 0.39191306, + -0.920214 0.00382879 0.391397, + -0.9333269 0.0074146092 0.35895097, + -0.93335462 -0.00064046774 0.35895488, + -0.9333719 -0.00064043293 0.35890996, + -0.93334466 0.0074174772 0.35890487, + -0.93331814 0.0074185207 0.35897404, + -0.93334585 -0.00064253493 0.35897797, + -0.94978851 0.0058019771 0.31283885, + -0.94978225 0.0067982813 0.31283808, + -0.94980526 0.0067972112 0.3127681, + -0.94982839 0.00067061925 0.31277111, + -0.94448322 0.0028722908 0.32854709, + -0.90569514 0.0036284404 0.42391405, + -0.89367586 -0.00040014295 0.44871294, + -0.89364189 0.0082968595 0.44870394, + -0.89367312 0.0082959505 0.44864205, + -0.89370656 -0.00039760378 0.44865179, + -0.89441586 -0.00039647295 0.44723594, + -0.87059069 -0.00034545688 0.49200782, + -0.87055486 0.0087289494 0.49199393, + -0.87057739 0.0087283636 0.49195424, + -0.87061316 -0.00035076108 0.49196813, + -0.85730779 0.0035637692 0.51479191, + -0.79983455 0.0034327079 0.60021067, + -0.81825286 -0.00075344788 0.57485795, + -0.81821412 0.0092610111 0.57483906, + -0.79218131 0.0076217428 0.61023825, + -0.78900599 0.0093684997 0.61431402, + -0.78904384 0.00031562592 0.61433691, + -0.78896284 0.00031026592 0.61444086, + -0.78892499 0.0093700001 0.61441803, + -0.75791538 0.0084370235 0.65229827, + -0.75794572 -0.0010689097 0.65231675, + -0.75795829 -0.0010689003 0.65230227, + -0.75792021 0.009504512 0.65227818, + -0.75803763 0.0095024956 0.65214169, + -0.75807619 -0.0010895003 0.65216517, + -0.73387492 0.0032353795 0.67927694, + -0.97325885 0.0030551895 0.22969097, + -0.99171662 0.0031930588 0.12840496, + -0.51241195 -0.54621094 -0.66263694, + -0.42024684 -0.57716781 -0.70019275, + -0.38011 -0.60997099 -0.69530702, + -0.3183859 -0.62515181 -0.71261179, + -0.27768582 -0.65497756 -0.70277661, + -0.22244203 -0.66470903 -0.71321905, + -0.21562003 -0.66943407 -0.71089107, + -0.16684394 -0.67595077 -0.71781176, + -0.16570799 -0.67673796 -0.71733296, + -0.12303806 -0.68101132 -0.72186238, + -0.121971 -0.68176901 -0.72132802, + -0.085205689 -0.68439996 -0.72411096, + -0.084973581 -0.6845718 -0.72397584, + -0.053550467 -0.68607157 -0.72556061, + -0.054391406 -0.68541008 -0.72612303, + -0.027780604 -0.68616104 -0.72691905, + -0.029772397 -0.68447095 -0.72843194, + -0.0074741808 -0.68475604 -0.72873408, + -0.010224301 -0.68220007 -0.73109406, + 0.0081513496 -0.68221301 -0.73110801, + 0.0058441428 -0.67983329 -0.73334336, + 0.020387584 -0.67970353 -0.73320347, + 0.018018289 -0.67695856 -0.73580056, + 0.028779807 -0.67678815 -0.73561519, + 0.022221398 -0.66808194 -0.74375594, + 0.030945504 -0.66792709 -0.74358308, + 0.024652494 -0.65815485 -0.75247884, + 0.031596504 -0.65802705 -0.75233114, + 0.02611999 -0.64790076 -0.76127672, + 0.031031212 -0.64780927 -0.76117033, + 0.0260546 -0.63658899 -0.77076298, + 0.024475206 -0.62409115 -0.78096819, + 0.0288487 -0.63654 -0.77070397, + -0.017130401 -0.74522406 -0.66659409, + -0.026043287 -0.74508166 -0.66646469, + 0.011753094 -0.71552265 -0.69849062, + 0.01916049 -0.71544063 -0.69841063, + 0.012362299 -0.68242192 -0.73085392, + 0.012013799 -0.68242496 -0.73085696, + 0.0078363102 -0.646797 -0.762622, + 0.0042345487 -0.64681077 -0.76263869, + 0.0027998702 -0.60804707 -0.79389614, + -0.0029278009 -0.60804623 -0.79389632, + -0.0043359087 -0.64686078 -0.76259571, + -0.0080277771 -0.64684677 -0.76257771, + -0.012174698 -0.68241584 -0.7308628, + -0.012527395 -0.68241274 -0.73085976, + -0.019253291 -0.71513164 -0.69872463, + -0.01695439 -0.71516156 -0.6987536, + -0.023338297 -0.68299097 -0.73005396, + 0.91519928 -0.19248807 -0.35406011, + 0.87547523 -0.23082305 -0.42457509, + 0.86607742 -0.25296611 -0.43118221, + 0.82739216 -0.28419405 -0.48441312, + 0.81346112 -0.31121403 -0.49135205, + 0.76870853 -0.3422378 -0.54033369, + 0.74939084 -0.3736679 -0.54661286, + 0.69958824 -0.40325016 -0.58988625, + 0.67379779 -0.43902186 -0.59435374, + 0.62039495 -0.46597993 -0.63085091, + 0.59300977 -0.49901581 -0.63191974, + 0.52404493 -0.52783191 -0.66840893, + 0.49889177 -0.55396378 -0.66650671, + 0.4425098 -0.57320273 -0.68965465, + 0.41392514 -0.60025626 -0.68436724, + 0.35978803 -0.61524004 -0.70145005, + 0.32588291 -0.64474285 -0.6914528, + 0.27577105 -0.65552717 -0.70301819, + 0.23762497 -0.68630493 -0.68740094, + 0.1933111 -0.69321537 -0.69432235, + 0.14658399 -0.72832394 -0.66937095, + 0.085651755 -0.73357141 -0.67419344, + 0.07844732 -0.73866516 -0.66949219, + 0.048304912 -0.74008417 -0.6707772, + 0.049515493 -0.73918492 -0.67167991, + 0.023888109 -0.73988223 -0.67231226, + 0.025647797 -0.73847592 -0.67379194, + 0.0042419625 -0.73871243 -0.67400742, + 0.0066839275 -0.73657978 -0.67631775, + -0.010935696 -0.73655176 -0.67629278, + -0.007668871 -0.73338705 -0.67976809, + -0.021846807 -0.73323321 -0.67962623, + -0.017898604 -0.72892821 -0.68435615, + -0.028921688 -0.72873974 -0.68417978, + -0.024252005 -0.72291416 -0.69051218, + -0.032478407 -0.72274518 -0.69035119, + -0.02703421 -0.71482825 -0.69877726, + -0.0328977 -0.71470302 -0.698654, + -0.0279634 -0.70618099 -0.707479, + -0.031435505 -0.70610803 -0.70740604, + -0.026434794 -0.6955958 -0.71794683, + -0.028077507 -0.69556415 -0.71791518, + -0.017114505 -0.71066421 -0.70332325, + -0.025859695 -0.71053082 -0.7031908, + -0.017870402 -0.68306804 -0.73013604, + -0.011951997 -0.67882282 -0.73420483, + -0.019734791 -0.67873973 -0.73411363, + -0.013018705 -0.64446121 -0.76452631, + -0.012810092 -0.64446265 -0.76452851, + -0.0086812489 -0.60723096 -0.79447788, + -0.0045532286 -0.60724878 -0.79449868, + -0.0031778605 -0.56723905 -0.82354712, + 0.00320541 -0.56723899 -0.82354701, + 0.0046057999 -0.60715902 -0.79456699, + 0.0085680373 -0.60714376 -0.79454571, + 0.012723405 -0.64436024 -0.76461631, + 0.012787005 -0.64436024 -0.7646153, + 0.019548701 -0.67876208 -0.73409808, + 0.011770393 -0.67884457 -0.7341876, + -0.8665607 -0.26362392 -0.42376286, + -0.81180698 -0.30844599 -0.49581301, + -0.79508519 -0.3381291 -0.50349611, + -0.74725682 -0.3704859 -0.55167687, + -0.724778 -0.403918 -0.558164, + -0.67199498 -0.43415299 -0.59994501, + -0.64964718 -0.46271712 -0.60320109, + -0.58066869 -0.49552575 -0.6459707, + -0.55660188 -0.52166587 -0.6465748, + -0.47851393 -0.55136693 -0.68338794, + -0.44600412 -0.58156013 -0.68034416, + -0.38649809 -0.59927315 -0.70106417, + -0.35006002 -0.62977308 -0.69342905, + -0.29468489 -0.64245778 -0.70739573, + -0.25129899 -0.67549598 -0.69322002, + -0.20204598 -0.68349892 -0.70143193, + -0.1626149 -0.71125156 -0.6838696, + -0.12089702 -0.71555907 -0.68801105, + -0.11587802 -0.71901804 -0.68526304, + -0.080119908 -0.72156805 -0.68769205, + -0.080479577 -0.72131079 -0.6879198, + -0.04989988 -0.72275674 -0.68929875, + -0.050749902 -0.72211301 -0.68991101, + -0.024867794 -0.72282183 -0.69058681, + -0.026698597 -0.72132891 -0.69207793, + -0.0050186301 -0.721578 -0.69231498, + -0.0078801075 -0.71902478 -0.69493973, + 0.0099893995 -0.71901095 -0.69492692, + 0.0062028589 -0.71525997 -0.69883096, + 0.020674298 -0.71512091 -0.69869494, + 0.016352491 -0.71029758 -0.70371157, + 0.027764 -0.71011901 -0.70353401, + 0.02375529 -0.70500565 -0.70880365, + 0.032127611 -0.70484126 -0.70863724, + 0.028002704 -0.69872606 -0.71484107, + 0.033385485 -0.69861066 -0.71472263, + 0.027404293 -0.68806982 -0.7251268, + 0.031104188 -0.68799478 -0.72504878, + 0.025743697 -0.67646694 -0.73602295, + 0.027853001 -0.67642897 -0.73598099, + 0.023249298 -0.66393495 -0.74742895, + 0.02355689 -0.66392976 -0.74742377, + 0.01813611 -0.64431828 -0.76454234, + 0.023679109 -0.64424425 -0.76445329, + 0.0281805 -0.65675199 -0.75357997, + 0.025714995 -0.6567958 -0.7536298, + 0.030836411 -0.66807222 -0.74345726, + 0.026410306 -0.66815621 -0.74355221, + 0.032293305 -0.67877805 -0.73363304, + 0.026214492 -0.67889875 -0.73376375, + 0.032544106 -0.68849015 -0.7245152, + 0.02465079 -0.68864578 -0.72467875, + 0.028060604 -0.69307607 -0.72031808, + 0.016770402 -0.69325209 -0.72050005, + 0.020054806 -0.69699121 -0.7167992, + 0.005382047 -0.69712162 -0.71693265, + 0.0090179555 -0.70080143 -0.71329939, + -0.0091297934 -0.70080024 -0.71329921, + -0.006163253 -0.70350337 -0.71066535, + -0.028132692 -0.70323783 -0.71039784, + -0.026255 -0.70480001 -0.70892, + -0.052491099 -0.70407099 -0.70818698, + -0.051686607 -0.70469207 -0.70762807, + -0.082692005 -0.70321804 -0.70614904, + -0.082825109 -0.70312107 -0.70623004, + -0.11910199 -0.70052391 -0.70361996, + -0.119564 -0.70020002 -0.70386398, + -0.16163802 -0.69598603 -0.69962609, + -0.16770498 -0.69182795 -0.70231694, + -0.21604304 -0.68519419 -0.69558215, + -0.25671303 -0.65622306 -0.70955604, + -0.31217289 -0.64504576 -0.69746977, + -0.35460287 -0.61183578 -0.70704573, + -0.41538706 -0.59523404 -0.68785906, + -0.44941521 -0.56555831 -0.69149834, + -0.51303798 -0.54342699 -0.66443902, + -0.54102504 -0.51601207 -0.66409606, + -0.6197347 -0.48153275 -0.61972171, + -0.638457 -0.45983601 -0.61719, + -0.70615333 -0.42303321 -0.56779432, + -0.72466892 -0.39747193 -0.56291294, + -0.77565199 -0.36405501 -0.51558501, + -0.79473621 -0.33291909 -0.50750309, + -0.83964187 -0.29791597 -0.45414495, + -0.85733718 -0.26228905 -0.44291911, + -0.89653569 -0.22571293 -0.38115284, + -0.90903658 -0.19210491 -0.36979482, + -0.93744314 -0.16049002 -0.30893904, + -0.94395751 -0.13620993 -0.30065086, + -0.96400511 -0.10972302 -0.24218804, + -0.96719766 -0.092612773 -0.23654091, + -0.98101687 -0.070700489 -0.18057498, + -0.98242837 -0.059144624 -0.17702106, + -0.99137527 -0.041529812 -0.12430003, + -0.99189645 -0.034373514 -0.12231106, + -0.99717623 -0.020317506 -0.072296314, + -0.99731237 -0.016532706 -0.071377821, + -0.99971366 -0.0053996979 -0.023312593, + -0.99972445 -0.0042712218 -0.023082212, + -0.9997285 0.0042398381 0.022912689, + -0.99973625 0.0031992407 0.022742305, + -0.99759686 0.0096516088 0.068609595, + -0.99764597 0.0066883801 0.068247698, + -0.99344265 0.011151196 0.11378596, + -0.99352849 0.0064093131 0.11340305, + -0.98719966 0.0089996569 0.15923494, + -0.98729199 0.00096049003 0.158914, + -0.98536736 -0.00090683333 0.17044206, + -0.98535633 0.0046317517 0.17044505, + -0.98541898 0.00461757 0.170083, + -0.98543 -0.00090654398 0.17007899, + -0.99258351 0.0041198083 0.12149494, + -0.99258524 0.003671441 0.12149503, + -0.99257553 0.003672698 0.12157394, + -0.99258047 0.001982701 0.12157406, + -0.99734312 -0.00092772511 0.072842009, + -0.99734014 0.0025345401 0.072844408, + -0.99360234 0.00065225025 0.11293404, + -0.99355412 0.0064895009 0.11317302, + -0.99769354 0.0038859481 0.067768671, + -0.99766213 0.0067632408 0.068004608, + -0.99974436 0.0022378308 0.022501407, + -0.99973887 0.0032312896 0.022623599, + -0.99973589 -0.0032492494 -0.022749398, + -0.9997279 -0.0043088896 -0.022922497, + -0.99745637 -0.013168205 -0.070052624, + -0.99735433 -0.016659906 -0.070759021, + -0.99243701 -0.028132901 -0.119488, + -0.99204552 -0.034602687 -0.12102994, + -0.98385763 -0.049192183 -0.17205894, + -0.98280036 -0.059477724 -0.17483106, + -0.97040313 -0.077778004 -0.22862303, + -0.96798891 -0.093041591 -0.23311096, + -0.95030552 -0.11540395 -0.28913885, + -0.94543844 -0.13670292 -0.29573381, + -0.92083412 -0.16362101 -0.35396704, + -0.91164011 -0.19265103 -0.36304003, + -0.87816656 -0.22422889 -0.42254579, + -0.86541414 -0.25450704 -0.43160707, + -0.82649183 -0.28594396 -0.48491988, + -0.81229872 -0.31333488 -0.49192682, + -0.76734489 -0.34449098 -0.54083997, + -0.74760097 -0.376432 -0.547167, + -0.69745576 -0.40617585 -0.59040374, + -0.67206305 -0.44119307 -0.59471005, + -0.61854994 -0.46815395 -0.63105291, + -0.592686 -0.499266 -0.63202602, + -0.52392399 -0.52798599 -0.66838199, + -0.4948197 -0.55808663 -0.66610259, + -0.41929314 -0.58304119 -0.69588524, + -0.38334894 -0.61518592 -0.68890494, + -0.32844415 -0.62911928 -0.70450938, + -0.29078683 -0.65983558 -0.69286358, + -0.24100298 -0.66930896 -0.70281094, + -0.19772005 -0.7018832 -0.68430018, + -0.15467301 -0.70740104 -0.68968105, + -0.11727306 -0.73383534 -0.6691283, + -0.081580803 -0.73646998 -0.67153299, + -0.077994309 -0.73899406 -0.66918206, + -0.04798729 -0.74039781 -0.67045385, + -0.049092099 -0.73957902 -0.67127699, + -0.023555705 -0.7402662 -0.67190117, + -0.025398891 -0.73879474 -0.67345178, + -0.0040421621 -0.73902738 -0.67366332, + -0.0067985584 -0.73662084 -0.6762718, + 0.010811097 -0.7365948 -0.67624784, + 0.0071323798 -0.73303002 -0.68015897, + 0.021376099 -0.73288101 -0.68002099, + 0.016941303 -0.72804117 -0.68532419, + 0.028193083 -0.72785658 -0.68514961, + 0.023381712 -0.72184736 -0.69165736, + 0.031876788 -0.72167778 -0.69149476, + 0.027400708 -0.71517217 -0.69841117, + 0.033185106 -0.71504718 -0.6982882, + 0.028690305 -0.70730108 -0.70633006, + 0.031831089 -0.70723277 -0.70626378, + 0.026325304 -0.69567204 -0.71787703, + 0.0279429 -0.69564199 -0.71784502, + 0.023194293 -0.68305373 -0.72999978, + 0.017749 -0.68313003 -0.73008102, + 0.023150308 -0.70177925 -0.71201825, + 0.023523103 -0.70177305 -0.71201205, + 0.028382296 -0.71435392 -0.69920892, + 0.02727101 -0.71437621 -0.69923025, + 0.031814698 -0.72370195 -0.68937892, + 0.021471899 -0.73935091 -0.67297792, + 0.031760495 -0.73914796 -0.67279392, + 0.024167595 -0.72005993 -0.69349092, + 0.0185326 -0.720146 -0.69357502, + 0.0260894 -0.74488997 -0.666677, + 0.0207402 -0.74498302 -0.66676098, + 0.028497096 -0.7638579 -0.64475495, + 0.017460596 -0.77749884 -0.62864184, + 0.026185496 -0.7773509 -0.62852192, + 0.017229199 -0.749282 -0.662027, + 0.019409293 -0.74925178 -0.66200078, + 0.01278319 -0.71854448 -0.69536352, + 0.011750208 -0.71855354 -0.69537246, + 0.0075756311 -0.68454409 -0.72893208, + 0.0039860685 -0.68455774 -0.72894776, + 0.0025502699 -0.647605 -0.76197201, + -0.0027589803 -0.64760405 -0.76197213, + -0.0041707694 -0.68454796 -0.72895592, + -0.0077376389 -0.68453395 -0.72893995, + -0.011878205 -0.71835124 -0.69557923, + -0.012651902 -0.71834403 -0.69557303, + -0.019340003 -0.74942118 -0.66181117, + -0.017223699 -0.74944997 -0.66183692, + -0.026203694 -0.77764779 -0.6281538, + -0.017695002 -0.77779412 -0.62827003, + -0.021903606 -0.7802372 -0.6251002, + -0.027467282 -0.78012955 -0.62501466, + -0.032223497 -0.78900987 -0.61353493, + -0.028914396 -0.78908986 -0.61359692, + -0.033762682 -0.7965095 -0.60368264, + -0.028144417 -0.7966485 -0.60378736, + -0.033013005 -0.8029111 -0.59518409, + -0.025132691 -0.8030957 -0.59531975, + -0.029687304 -0.8081181 -0.58827204, + -0.019206602 -0.80832511 -0.58842307, + -0.017537298 -0.80670285 -0.59069693, + 0.011806895 -0.80677068 -0.59074676, + 0.044564102 -0.77596003 -0.629206, + 0.066029087 -0.77503681 -0.62845683, + 0.094657563 -0.74809676 -0.65680379, + 0.12248903 -0.74581218 -0.65479815, + 0.15161106 -0.71821225 -0.67910624, + 0.18428694 -0.71416676 -0.67528075, + 0.21331711 -0.68610728 -0.69552338, + 0.25104111 -0.67978227 -0.68911135, + 0.27831796 -0.65257597 -0.70475793, + 0.31987396 -0.64372396 -0.69519794, + 0.34450999 -0.61817098 -0.70652503, + 0.38917923 -0.60656738 -0.69326442, + 0.41866109 -0.57425213 -0.70353216, + 0.46648481 -0.55932081 -0.68523878, + 0.49801606 -0.52184409 -0.69257408, + 0.54753798 -0.50355798 -0.66830498, + 0.57494217 -0.46759719 -0.67141223, + 0.62463105 -0.44629505 -0.64082503, + 0.64789683 -0.4121519 -0.64059383, + 0.69620597 -0.38840601 -0.60368699, + 0.71492308 -0.35724303 -0.60105103, + 0.7598471 -0.33215502 -0.55884308, + 0.77421415 -0.30461004 -0.55480206, + 0.81453985 -0.27919093 -0.50850487, + 0.82521909 -0.25526404 -0.50383908, + 0.86070281 -0.23008794 -0.45414788, + 0.8683008 -0.20982595 -0.44947389, + 0.89865869 -0.18554994 -0.39747185, + 0.90565068 -0.16264294 -0.39159185, + 0.93144339 -0.13957606 -0.33605316, + 0.99974614 0.0022413903 0.022418402, + 0.99974424 -0.0022498404 -0.022502905, + 0.99973875 -0.0032518094 -0.022626095, + 0.9975661 -0.0099192914 -0.069018506, + 0.99748951 -0.013263093 -0.069560967, + 0.99285173 -0.022354394 -0.11724197, + 0.99255335 -0.028425109 -0.11844804, + 0.98494112 -0.040344704 -0.16811702, + 0.98414034 -0.049711719 -0.17028406, + 0.97280937 -0.064905122 -0.22232707, + 0.97100598 -0.078442402 -0.22581901, + 0.95514423 -0.097174026 -0.27974406, + 0.95149535 -0.11600304 -0.2849561, + 0.92980886 -0.13876998 -0.34087896, + 0.92459542 -0.15835908 -0.34647617, + 0.89808601 -0.182831 -0.40001801, + 0.89212656 -0.20065191 -0.40478283, + 0.86001211 -0.22662804 -0.45718607, + 0.85122287 -0.24827597 -0.46236193, + 0.81377387 -0.27494597 -0.51203191, + 0.80145431 -0.30046013 -0.51710218, + 0.75905567 -0.32707188 -0.56290179, + 0.74242204 -0.35654804 -0.56717104, + 0.69545025 -0.38243514 -0.60835224, + 0.67412275 -0.41524485 -0.61084378, + 0.62395287 -0.43933088 -0.64627481, + 0.59764725 -0.47497219 -0.64592522, + 0.54699314 -0.49593011 -0.67442715, + 0.51579106 -0.53370506 -0.67016304, + 0.46606818 -0.55116916 -0.69209325, + 0.43685806 -0.58336508 -0.68471909, + 0.38882014 -0.59749222 -0.70130026, + 0.36468482 -0.62234068 -0.69260162, + 0.31943396 -0.63335395 -0.70485795, + 0.29172605 -0.66048217 -0.69185215, + 0.25041211 -0.6685183 -0.70026934, + 0.22027206 -0.69680119 -0.68260419, + 0.18332189 -0.70224059 -0.68793261, + 0.15217806 -0.73049927 -0.66574222, + 0.12101605 -0.73367524 -0.66863722, + 0.08918529 -0.76194388 -0.64147294, + 0.063975908 -0.76342613 -0.64271903, + 0.02791171 -0.79496932 -0.60600722, + -0.006899152 -0.79526019 -0.60622913, + -0.0096967248 -0.79774153 -0.60292166, + -0.023002006 -0.7975682 -0.60279012, + -0.018908396 -0.7935158 -0.60825586, + -0.029463993 -0.79331285 -0.60810089, + -0.02472309 -0.78793973 -0.61525577, + -0.032903593 -0.78775382 -0.61511087, + -0.028173093 -0.78150481 -0.62326288, + -0.033744205 -0.7813701 -0.62315506, + -0.028759403 -0.77353811 -0.63309705, + -0.032233398 -0.77345598 -0.63303, + -0.027461195 -0.76431686 -0.64425594, + -0.028625792 -0.76429182 -0.64423484, + -0.022012306 -0.74822116 -0.66308415, + -0.0270954 -0.748128 -0.663001, + -0.032005012 -0.75776929 -0.65173721, + -0.02868709 -0.7578457 -0.65180278, + -0.033539716 -0.76566434 -0.64236528, + -0.028013587 -0.76579463 -0.64247471, + -0.032888904 -0.77240109 -0.63428307, + -0.024719905 -0.77258319 -0.6344322, + -0.029105011 -0.77768332 -0.62798226, + -0.018749399 -0.77787602 -0.62813801, + -0.022783989 -0.78197461 -0.62289369, + -0.0090795411 -0.7821461 -0.62302905, + -0.012738605 -0.78544831 -0.61879623, + 0.0043649706 -0.7855041 -0.61884105, + 0.0082249083 -0.7823348 -0.62280387, + 0.0486986 -0.78143299 -0.62208599, + 0.088034526 -0.74901515 -0.6566782, + 0.11758901 -0.74671805 -0.65466404, + 0.15159799 -0.71781796 -0.67952591, + 0.18688904 -0.71341616 -0.67535919, + 0.22004603 -0.68422109 -0.69528508, + 0.26116708 -0.67706925 -0.68801826, + 0.29168686 -0.6489327 -0.70271266, + 0.33729202 -0.63867909 -0.69160908, + 0.36468089 -0.61202276 -0.70173776, + 0.41336879 -0.5985027 -0.68623668, + 0.43677992 -0.57424986 -0.69243079, + 0.48690987 -0.55757886 -0.67232782, + 0.486774 -0.56397098 -0.66707402, + 0.41371891 -0.58777988 -0.69523484, + 0.3872481 -0.61373115 -0.68802118, + 0.33779001 -0.62654299 -0.70238298, + 0.30716503 -0.65463305 -0.69072807, + 0.261659 -0.66392303 -0.70052898, + 0.22752306 -0.69347119 -0.68361616, + 0.18719399 -0.69955993 -0.68961895, + 0.15143201 -0.72903407 -0.66751605, + 0.11746199 -0.73243392 -0.67062896, + 0.074825302 -0.76603502 -0.63842899, + 0.0283066 -0.76788002 -0.63996798, + 0.023026902 -0.77194512 -0.63527209, + 0.0024069406 -0.77214718 -0.63543916, + 0.0052649006 -0.76976311 -0.63830805, + -0.011978205 -0.76971835 -0.63827127, + -0.0084180189 -0.76642388 -0.64227992, + -0.022496406 -0.76625717 -0.64214015, + -0.018237999 -0.76182085 -0.64753091, + -0.029241711 -0.76162231 -0.64736122, + -0.024894411 -0.75644338 -0.65358531, + -0.032794204 -0.75627112 -0.65343606, + -0.027956491 -0.74955475 -0.66135174, + -0.033650797 -0.74942297 -0.66123593, + -0.028586404 -0.74106807 -0.67082107, + -0.031911004 -0.74099308 -0.67075408, + -0.026789887 -0.73069364 -0.68217969, + -0.028291516 -0.73066342 -0.68215144, + -0.021566793 -0.71354073 -0.70028174, + -0.026736297 -0.71345192 -0.70019394, + -0.031577703 -0.72341007 -0.68969607, + -0.0279989 -0.72348702 -0.68976998, + -0.033414502 -0.73263597 -0.67979997, + -0.027746303 -0.73276305 -0.67991805, + -0.032701604 -0.73980504 -0.67202604, + -0.024585694 -0.73997682 -0.6721828, + -0.029210286 -0.74561661 -0.66573471, + -0.018082498 -0.74581295 -0.66590995, + -0.021935906 -0.74992317 -0.66116118, + -0.0080618905 -0.7500791 -0.66129905, + -0.0113596 -0.75320399 -0.65768898, + 0.0060660602 -0.75323898 -0.65771902, + 0.0033543715 -0.75555533 -0.65507632, + 0.024500186 -0.75533253 -0.65488356, + 0.022289602 -0.7570591 -0.65296608, + 0.047647923 -0.75638735 -0.65238631, + 0.053922199 -0.751791 -0.65719301, + 0.10733107 -0.74853742 -0.65434843, + 0.15237497 -0.7141118 -0.68324685, + 0.19128293 -0.70920777 -0.67855376, + 0.2287049 -0.67889172 -0.69771063, + 0.27376902 -0.67073208 -0.68932503, + 0.30832285 -0.64095569 -0.70293164, + 0.35810301 -0.62909698 -0.68992698, + 0.38819015 -0.60126221 -0.69842124, + 0.441284 -0.58546603 -0.68007201, + 0.46956882 -0.55704784 -0.68498379, + 0.53665787 -0.53238088 -0.65465182, + 0.56725109 -0.49713105 -0.65657204, + 0.62047201 -0.473398 -0.62522697, + 0.64868253 -0.43654069 -0.62341261, + 0.69993204 -0.40966806 -0.58503604, + 0.72207308 -0.37627605 -0.58054006, + 0.76921201 -0.347545 -0.53621399, + 0.78574866 -0.31835586 -0.53032875, + 0.82797217 -0.28861907 -0.48079211, + 0.8397963 -0.2637541 -0.47452718, + 0.8760249 -0.23429596 -0.42152795, + 0.88408726 -0.21372004 -0.41558808, + 0.91403711 -0.18550701 -0.36072603, + 0.92097664 -0.16327494 -0.35375589, + 0.94551426 -0.13644002 -0.29561305, + 0.95031786 -0.11540298 -0.28909898, + 0.96799511 -0.093043007 -0.23308504, + 0.97038138 -0.077963829 -0.22865207, + 0.98278725 -0.059620615 -0.17485605, + 0.98384362 -0.04936038 -0.17209095, + 0.99204051 -0.034716986 -0.12103894, + 0.99243522 -0.028196407 -0.11948803, + 0.99735326 -0.016699104 -0.070765413, + 0.99745715 -0.013143502 -0.070046104, + 0.99972802 -0.00430123 -0.0229226, + 0.99973613 -0.0032188105 -0.022745403, + 0.99973899 0.00320109 0.022620199, + 0.99974447 0.0022164311 0.022499111, + 0.99766266 0.0066990578 0.068002477, + 0.99360067 0.0008057307 0.11294696, + 0.99355191 0.0066149193 0.11318499, + 0.99769253 0.0039611883 0.067778073, + 0.99711353 6.6780769e-005 0.075925462, + 0.99771255 0.0022840588 0.067561172, + 0.99770224 0.0040113311 0.067632616, + 0.99974948 0.0013251706 0.022342911, + 0.99975049 0.0013418695 0.02229449, + 0.99974948 -0.0013448508 -0.022344012, + 0.99974602 -0.00227571 -0.022420799, + 0.99764234 -0.0069301021 -0.068277225, + 0.99759012 -0.010023701 -0.068655007, + 0.99316275 -0.016864996 -0.11551297, + 0.99294353 -0.022569388 -0.11642095, + 0.98578 -0.031981301 -0.16497, + 0.98517567 -0.040690783 -0.16665295, + 0.97467321 -0.053045113 -0.21725205, + 0.97330689 -0.065399989 -0.21999197, + 0.95884174 -0.08091148 -0.27216893, + 0.95608467 -0.097825766 -0.27628291, + 0.93661511 -0.11694101 -0.33026803, + 0.91471314 -0.13718902 -0.38010406, + 0.93789989 -0.11777198 -0.32630298, + 0.94181722 -0.097407624 -0.32170209, + 0.95957911 -0.08155971 -0.26936203, + 0.96166599 -0.066143602 -0.26612699, + 0.97506666 -0.05352588 -0.21535993, + 0.97609651 -0.04204848 -0.21323089, + 0.98596245 -0.032303415 -0.16381307, + 0.98640686 -0.024114596 -0.16254199, + 0.99322975 -0.017047796 -0.11490897, + 0.99337935 -0.011780005 -0.11427504, + 0.99765903 -0.0070122899 -0.068025, + 0.99769109 -0.0041420204 -0.067789711, + 0.99975049 -0.0013622193 -0.022294588, + 0.99975276 -9.3634077e-007 -0.022237895, + 0.99975538 -1.951479e-005 -0.022115286, + 0.99975234 -2.2665907e-005 -0.022257308, + 0.99771512 -0.0017996102 -0.067538708, + 0.99770111 -0.0041971304 -0.067637905, + 0.99351835 -0.0070401723 -0.11345404, + 0.99358237 -0.0035861013 -0.11305404, + 0.99354666 -0.0071367975 -0.11319897, + 0.98712403 -0.0100648 -0.15964, + 0.98693889 -0.017060699 -0.16018899, + 0.97789991 -0.022142097 -0.20789798, + 0.97738624 -0.032077607 -0.20901504, + 0.96544987 -0.039529696 -0.25757298, + 0.964293 -0.0530065 -0.25947899, + 0.94888824 -0.063168816 -0.30922607, + 0.94664949 -0.080452837 -0.31206116, + 0.92706299 -0.093594298 -0.36303499, + 0.92306697 -0.115419 -0.366914, + 0.89845431 -0.13175204 -0.41883314, + 0.89330298 -0.152831 -0.42267299, + 0.86530256 -0.17044292 -0.47138175, + 0.85990888 -0.18859898 -0.47432795, + 0.82779503 -0.207288 -0.52133203, + 0.82038289 -0.22845697 -0.52419394, + 0.78408486 -0.24796897 -0.56896591, + 0.77428353 -0.27214485 -0.57133365, + 0.73400062 -0.29205984 -0.61314273, + 0.72150606 -0.31909603 -0.61449707, + 0.67833221 -0.33861211 -0.65207922, + 0.66310304 -0.36798203 -0.65183103, + 0.61770022 -0.38660714 -0.68482226, + 0.59951192 -0.41829795 -0.68235797, + 0.55307978 -0.43542078 -0.71028966, + 0.53225386 -0.46870288 -0.70499885, + 0.48564377 -0.48396775 -0.72795963, + 0.46255195 -0.51827896 -0.71932793, + 0.41786721 -0.53109026 -0.73710936, + 0.39321205 -0.56564307 -0.72486705, + 0.35109198 -0.57603592 -0.73818493, + 0.32543501 -0.610385 -0.72216499, + 0.28702787 -0.61836272 -0.73160267, + 0.26133984 -0.65171057 -0.71202159, + 0.22689307 -0.65756625 -0.71841925, + 0.20365089 -0.6873247 -0.69721663, + 0.17374098 -0.69135994 -0.70130992, + 0.15369694 -0.71718776 -0.67971975, + 0.12756701 -0.71988207 -0.68227303, + 0.108022 -0.745655 -0.65751803, + 0.086012609 -0.74726504 -0.65893608, + 0.067748427 -0.77230638 -0.63162732, + 0.050383281 -0.77310169 -0.63227779, + 0.034003109 -0.7969352 -0.60310709, + 0.021088699 -0.79721886 -0.60332197, + 0.0068214815 -0.8197372 -0.57269913, + -0.0015536298 -0.81975585 -0.57271093, + -0.016396195 -0.84567469 -0.53344685, + -0.025488395 -0.84551382 -0.53334486, + -0.022000492 -0.83827168 -0.5448088, + -0.027323203 -0.83816111 -0.54473805, + -0.028469687 -0.84008658 -0.54170477, + -0.0158072 -0.84032202 -0.541857, + 0.0024456899 -0.81334686 -0.58177394, + 0.012900097 -0.81328183 -0.58172691, + 0.029927507 -0.78991616 -0.6124841, + 0.044967286 -0.78947067 -0.61213875, + 0.064064607 -0.76479214 -0.64108407, + 0.084266372 -0.7636407 -0.64011878, + 0.10486404 -0.73804224 -0.66655624, + 0.129443 -0.73588997 -0.66461301, + 0.15103807 -0.70965326 -0.68817127, + 0.17977194 -0.70619273 -0.68481678, + 0.20146105 -0.68009615 -0.70489919, + 0.23421006 -0.67502016 -0.69963819, + 0.2594291 -0.64446527 -0.71927822, + 0.29605806 -0.63739717 -0.71138918, + 0.32369491 -0.60298288 -0.72913182, + 0.36476383 -0.59338373 -0.71752566, + 0.39162377 -0.55838364 -0.73132658, + 0.435837 -0.54618597 -0.71535099, + 0.46108413 -0.51132613 -0.72522217, + 0.50774872 -0.4964307 -0.70409358, + 0.53086191 -0.46213794 -0.71036196, + 0.57802498 -0.44499299 -0.68400902, + 0.59821093 -0.41236094 -0.68709695, + 0.64448398 -0.39346501 -0.65561098, + 0.66183084 -0.36248592 -0.65618885, + 0.70625293 -0.34232497 -0.61969393, + 0.72031081 -0.31420192 -0.61840886, + 0.76208711 -0.29328504 -0.57724106, + 0.77321202 -0.267968 -0.57474899, + 0.8110339 -0.24719997 -0.53020394, + 0.81946713 -0.22501503 -0.52710706, + 0.8529399 -0.20494696 -0.48009393, + 0.85914129 -0.18577206 -0.47682819, + 0.88835102 -0.166687 -0.42784101, + 0.89269632 -0.15059206 -0.42475316, + 0.9177016 -0.13275194 -0.37443382, + 0.91954213 -0.14020102 -0.36713204, + 0.88771671 -0.16424593 -0.43009585, + 0.88270086 -0.18131098 -0.43354994, + 0.85215569 -0.20189592 -0.48277181, + 0.84507418 -0.22205506 -0.48635513, + 0.81011331 -0.24349609 -0.5333162, + 0.800403 -0.26706201 -0.53668702, + 0.76107419 -0.28898206 -0.58073711, + 0.74849176 -0.31546089 -0.58330482, + 0.70514798 -0.33730301 -0.62369299, + 0.68922019 -0.36680609 -0.62484312, + 0.64328706 -0.38759905 -0.66026407, + 0.62398428 -0.41953421 -0.65926832, + 0.57679719 -0.43856716 -0.68917626, + 0.55424988 -0.47238088 -0.68531984, + 0.50645804 -0.48935807 -0.70995003, + 0.48081076 -0.52466077 -0.70253265, + 0.43451715 -0.53892517 -0.72163326, + 0.40679577 -0.57446766 -0.71028459, + 0.36333698 -0.58587396 -0.72438794, + 0.33403316 -0.62133229 -0.70877934, + 0.29450899 -0.62995899 -0.71862102, + 0.26791406 -0.66083419 -0.70108515, + 0.23233491 -0.66713977 -0.70777476, + 0.20919989 -0.69345963 -0.68945563, + 0.17745495 -0.69789582 -0.69386685, + 0.15392105 -0.72458524 -0.67177725, + 0.12662205 -0.72742224 -0.67440623, + 0.10377794 -0.75356454 -0.64913064, + 0.080885909 -0.75517315 -0.65051603, + 0.058845524 -0.78095728 -0.62180626, + 0.041216914 -0.78164828 -0.62235624, + 0.021283405 -0.80591017 -0.59165514, + 0.0087455967 -0.80606169 -0.59176677, + -0.012947001 -0.83389515 -0.55177104, + -0.029441297 -0.83360291 -0.55157894, + -0.028669596 -0.83250988 -0.55326796, + -0.031993195 -0.83242589 -0.55321193, + -0.027345303 -0.8244471 -0.56527805, + -0.028585004 -0.82441813 -0.56525904, + -0.022097699 -0.81023097 -0.58569402, + -0.027356103 -0.81012613 -0.58561707, + -0.032057695 -0.81843787 -0.57369995, + -0.028829092 -0.81851882 -0.57375586, + -0.033593118 -0.82541347 -0.56352836, + -0.028481787 -0.8255446 -0.56361771, + -0.028603204 -0.82569313 -0.56339407, + -0.0079134321 -0.82600516 -0.5636071, + 0.017280893 -0.79736966 -0.60324371, + 0.032476094 -0.79706782 -0.6030159, + 0.055371985 -0.77188283 -0.63334882, + 0.07633131 -0.77081311 -0.63247204, + 0.100901 -0.74436402 -0.66010702, + 0.126289 -0.74219197 -0.65818101, + 0.151538 -0.71524203 -0.68225002, + 0.18232496 -0.71146983 -0.67865181, + 0.20734701 -0.68463898 -0.69876802, + 0.24239103 -0.67897707 -0.69299108, + 0.26646402 -0.65273309 -0.70918006, + 0.30473503 -0.64500809 -0.70078605, + 0.33277488 -0.61343777 -0.71620876, + 0.375101 -0.60301602 -0.70403898, + 0.40563285 -0.56672585 -0.71713579, + 0.45152599 -0.55322301 -0.70004898, + 0.47969916 -0.51727617 -0.70874125, + 0.52776295 -0.50074494 -0.68609095, + 0.55314207 -0.46547407 -0.69091809, + 0.60114789 -0.44650489 -0.66276282, + 0.62287503 -0.41320407 -0.66429603, + 0.67020392 -0.39200094 -0.63020796, + 0.6881426 -0.36123678 -0.62925965, + 0.733042 -0.33863801 -0.58989298, + 0.74745804 -0.31058803 -0.58723205, + 0.78854489 -0.28752398 -0.54362392, + 0.79947788 -0.26301298 -0.54005492, + 0.83613032 -0.24017309 -0.49315616, + 0.84428209 -0.21876803 -0.48921207, + 0.87627059 -0.19669092 -0.4398438, + 0.88203788 -0.17862798 -0.43600595, + 0.90940732 -0.15767406 -0.38486016, + 0.91114801 -0.16533899 -0.377455, + 0.87559915 -0.19381003 -0.44245207, + 0.86897588 -0.21293597 -0.44669795, + 0.835325 -0.236561 -0.49625701, + 0.82600689 -0.25915098 -0.50055295, + 0.78766412 -0.28326404 -0.54712605, + 0.77508032 -0.30935612 -0.55095315, + 0.73208827 -0.33351612 -0.59398127, + 0.71580625 -0.36282811 -0.59663826, + 0.66922867 -0.38608381 -0.63487971, + 0.64875096 -0.41858995 -0.63553494, + 0.60020792 -0.43995595 -0.66797394, + 0.57571608 -0.47471106 -0.66573304, + 0.52684319 -0.49347118 -0.69204223, + 0.49872181 -0.52964681 -0.68611276, + 0.45062721 -0.54550421 -0.70665437, + 0.41931686 -0.58247882 -0.69634175, + 0.37416679 -0.59500366 -0.71131557, + 0.34521109 -0.62698817 -0.69836617, + 0.30366501 -0.63651103 -0.70897198, + 0.2792159 -0.66235977 -0.69521075, + 0.24098806 -0.66946518 -0.70266718, + 0.214531 -0.696652 -0.684582, + 0.18051901 -0.70154005 -0.68938708, + 0.15325703 -0.72904718 -0.66708517, + 0.12396502 -0.73207206 -0.66985303, + 0.096917212 -0.7592001 -0.64360106, + 0.073394991 -0.7607339 -0.64490092, + 0.047513306 -0.78689814 -0.61525106, + 0.028954696 -0.78745788 -0.61568797, + 0.00010346001 -0.81704211 -0.57657808, + -0.024497297 -0.8167969 -0.57640493, + -0.025282595 -0.8176468 -0.57516485, + -0.033141594 -0.81745881 -0.57503289, + -0.028306397 -0.81141186 -0.58378893, + -0.033663105 -0.81127709 -0.58369207, + -0.028853612 -0.80411428 -0.59377426, + -0.031977788 -0.80403769 -0.59371775, + -0.027352592 -0.79562783 -0.60516787, + -0.028549897 -0.79560089 -0.60514796, + -0.017937694 -0.8079567 -0.58896875, + -0.026083604 -0.80781114 -0.58886409, + -0.0173622 -0.78180599 -0.62327999, + -0.019491099 -0.78177488 -0.62325597, + -0.012864698 -0.7524209 -0.65855694, + -0.0118278 -0.75243098 -0.65856498, + -0.007705729 -0.72025192 -0.69366992, + -0.0040222383 -0.72026765 -0.69368464, + -0.0026142406 -0.68525016 -0.72830319, + 0.0024500398 -0.68525094 -0.72830296, + 0.0038722286 -0.72036177 -0.69358778, + 0.0078182593 -0.72034496 -0.69357193, + 0.011943296 -0.75240469 -0.65859276, + 0.012619597 -0.75239885 -0.6585868, + 0.019219099 -0.78158391 -0.62350392, + 0.017119195 -0.78161371 -0.62352777, + 0.025949387 -0.80791765 -0.58872372, + 0.017825402 -0.80806112 -0.58882904, + 0.032389808 -0.81220216 -0.58247614, + -0.0046702307 -0.8126201 -0.58277506, + -0.029015293 -0.7874878 -0.6156469, + -0.04757189 -0.78692681 -0.61520988, + -0.073397487 -0.76082683 -0.64479083, + -0.096936181 -0.75929183 -0.64348984, + -0.12377796 -0.73238474 -0.66954577, + -0.15327401 -0.72933906 -0.66676205, + -0.18048094 -0.70189577 -0.68903476, + -0.21414299 -0.69705999 -0.68428802, + -0.24065594 -0.66983885 -0.70242482, + -0.27886397 -0.66274494 -0.69498491, + -0.30364305 -0.63655818 -0.70893919, + -0.34518704 -0.62703705 -0.69833404, + -0.37261179 -0.59679765 -0.71062857, + -0.41767001 -0.584328 -0.69578201, + -0.44856799 -0.54799497 -0.70603698, + -0.49641582 -0.53225881 -0.68576378, + -0.52498293 -0.49569595 -0.69186592, + -0.57399201 -0.47691301 -0.66564798, + -0.59878576 -0.44187185 -0.66798574, + -0.64727592 -0.42054695 -0.63574696, + -0.66813302 -0.38757199 -0.63512701, + -0.71488494 -0.36423597 -0.59688497, + -0.73145074 -0.33449388 -0.59421676, + -0.77446687 -0.31032097 -0.55127293, + -0.78720313 -0.28398204 -0.54741704, + -0.82566649 -0.25979015 -0.50078332, + -0.83514285 -0.23684993 -0.49642587, + -0.88480574 -0.19028896 -0.42533392, + -0.84415615 -0.21893203 -0.48935607, + -0.83594888 -0.24046397 -0.49332196, + -0.79926389 -0.26332396 -0.54021996, + -0.78809816 -0.28831807 -0.54385114, + -0.74692881 -0.31143495 -0.58745688, + -0.73240799 -0.339627 -0.59011197, + -0.68736792 -0.36229497 -0.62949795, + -0.66910774 -0.39350885 -0.63043278, + -0.62182999 -0.414682 -0.66435403, + -0.59972471 -0.4484458 -0.66274172, + -0.55154592 -0.46746495 -0.69084996, + -0.52589619 -0.50295317 -0.68590921, + -0.47801393 -0.51939392 -0.70833093, + -0.44946 -0.55566901 -0.69944102, + -0.40346181 -0.56916469 -0.71642864, + -0.37351802 -0.60460109 -0.70352107, + -0.33152393 -0.61491489 -0.71552181, + -0.30470803 -0.64506108 -0.70074904, + -0.266413 -0.65279102 -0.70914602, + -0.24206091 -0.67932874 -0.69276178, + -0.20709093 -0.68497175 -0.69851774, + -0.18225302 -0.71159106 -0.67854404, + -0.15152702 -0.71535504 -0.68213403, + -0.12610191 -0.74247849 -0.65789354, + -0.10046201 -0.74466705 -0.65983206, + -0.076270498 -0.77068698 -0.63263297, + -0.055629659 -0.77174145 -0.63349855, + -0.032540806 -0.79713619 -0.60292214, + -0.017308399 -0.79743999 -0.60315001, + 0.0078293122 -0.82600319 -0.56361109, + 0.02826399 -0.82569867 -0.56340283, + 0.028419893 -0.82588983 -0.56311488, + 0.033768393 -0.82575184 -0.5630219, + 0.028848989 -0.81863868 -0.57358384, + 0.031731099 -0.81856698 -0.57353401, + 0.027040403 -0.81027412 -0.58542705, + 0.022056101 -0.81037301 -0.58549899, + 0.028531304 -0.82452214 -0.56511009, + 0.027028605 -0.82455617 -0.56513411, + 0.031689484 -0.83255857 -0.55302978, + 0.028996792 -0.83262682 -0.5530749, + 0.029544186 -0.83340156 -0.55187774, + 0.0130069 -0.83369499 -0.55207199, + -0.0084723989 -0.80615491 -0.59164393, + -0.021312509 -0.80600035 -0.59153128, + -0.041466787 -0.7814728 -0.62255991, + -0.059090894 -0.78077888 -0.62200695, + -0.08057607 -0.75565571 -0.64999378, + -0.10339998 -0.75405788 -0.64861792, + -0.12663805 -0.72748435 -0.67433631, + -0.15390597 -0.7246508 -0.67170984, + -0.17724495 -0.69819474 -0.69361979, + -0.20894289 -0.69376862 -0.68922263, + -0.23228697 -0.66722196 -0.70771295, + -0.26786196 -0.66091692 -0.70102692, + -0.29334 -0.631383 -0.71784902, + -0.33278078 -0.62279463 -0.70808458, + -0.36136702 -0.58833504 -0.72337806, + -0.40463799 -0.57701099 -0.70945501, + -0.43285805 -0.54098606 -0.72108805, + -0.47911993 -0.52675593 -0.70211995, + -0.50500619 -0.49125919 -0.70967126, + -0.55264586 -0.47435489 -0.68525183, + -0.57559121 -0.44007516 -0.68922323, + -0.62293422 -0.42099014 -0.65933323, + -0.64255917 -0.38860407 -0.66038215, + -0.68844044 -0.36783922 -0.62509537, + -0.70461184 -0.33795691 -0.62394488, + -0.74792618 -0.3161391 -0.58366311, + -0.76073003 -0.289253 -0.58105302, + -0.80016989 -0.26728597 -0.53692293, + -0.80989432 -0.24371609 -0.53354818, + -0.84494913 -0.22222403 -0.48649505, + -0.85212898 -0.201791 -0.48286301, + -0.8826521 -0.18123701 -0.43368006, + -0.88953859 -0.15753293 -0.42884079, + -0.91648126 -0.13795303 -0.37554109, + -0.92175156 -0.11402795 -0.37063682, + -0.94289535 -0.097945534 -0.31836313, + -0.94583648 -0.079495735 -0.31476015, + -0.96226555 -0.066632472 -0.26382789, + -0.96381462 -0.05252808 -0.26134691, + -0.97639453 -0.042561781 -0.2117599, + -0.97713691 -0.031999696 -0.21018897, + -0.98653036 -0.024619808 -0.16171506, + -0.98683625 -0.017009404 -0.16082604, + -0.99342364 -0.012042295 -0.11386196, + -0.99351966 -0.0069063175 -0.11344996, + -0.99771386 -0.0020039098 -0.067549594, + -0.99770153 -0.0041174679 -0.067636967, + -0.99975288 0.00015861899 -0.022231398, + -0.99975061 -0.0013363195 -0.022294292, + -0.99769163 -0.0040631085 -0.067786381, + -0.9976579 -0.007079869 -0.068033695, + -0.99337554 -0.011894194 -0.11429594, + -0.99322379 -0.017207997 -0.11493597, + -0.98639375 -0.024342295 -0.16258796, + -0.9859575 -0.032357216 -0.16383207, + -0.97608745 -0.042119417 -0.2132591, + -0.97507423 -0.053413112 -0.21535404, + -0.96167666 -0.066005081 -0.26612291, + -0.95960778 -0.081308678 -0.26933593, + -0.94185722 -0.09710902 -0.32167509, + -0.93793809 -0.11750901 -0.32628804, + -0.91476214 -0.13688701 -0.38009506, + -0.90773714 -0.16368702 -0.38629007, + -0.87783188 -0.18687499 -0.44100896, + -0.86879867 -0.21322292 -0.44690585, + -0.87073511 -0.22254004 -0.43851605, + -0.82486486 -0.25583798 -0.50412792, + -0.81400418 -0.28011006 -0.50885713, + -0.77360302 -0.30557799 -0.55512202, + -0.75895512 -0.33356702 -0.55921406, + -0.71400565 -0.35866681 -0.60129368, + -0.694929 -0.39031199 -0.60392898, + -0.64643151 -0.41413769 -0.6407935, + -0.62284392 -0.44858894 -0.64096296, + -0.57322496 -0.46983394 -0.67131895, + -0.54522395 -0.50639397 -0.66805393, + -0.49573183 -0.52462882 -0.69210875, + -0.46475282 -0.56128085 -0.68481278, + -0.41702294 -0.57614893 -0.70295393, + -0.38921407 -0.60657406 -0.69323903, + -0.34448981 -0.61819172 -0.70651662, + -0.31944501 -0.64415801 -0.69499302, + -0.27796412 -0.65298527 -0.70451838, + -0.25059596 -0.68025595 -0.68880594, + -0.21292892 -0.68656379 -0.69519174, + -0.18423101 -0.71428204 -0.67517406, + -0.15158997 -0.71832383 -0.67899281, + -0.12247495 -0.74590874 -0.65469074, + -0.094677076 -0.74819082 -0.65669382, + -0.066120982 -0.77505583 -0.62842381, + -0.044632699 -0.77598202 -0.62917399, + -0.016560506 -0.80255729 -0.59634525, + -0.0011805494 -0.80266666 -0.59642673, + 0.017796896 -0.82120484 -0.57035589, + 0.028366007 -0.82100415 -0.57021713, + 0.025391715 -0.81781048 -0.57492733, + 0.033190012 -0.81762332 -0.5747962, + 0.028345 -0.81156802 -0.58357, + 0.0336615 -0.81143397 -0.58347398, + 0.028708013 -0.80406034 -0.59385431, + 0.031819519 -0.80398446 -0.59379834, + 0.02716771 -0.79552829 -0.60530722, + 0.02861689 -0.7954967 -0.60528177, + 0.021947999 -0.78010386 -0.62526494, + 0.027218914 -0.78000236 -0.6251843, + 0.032012884 -0.78894866 -0.61362469, + 0.028718892 -0.78902781 -0.61368591, + 0.033598017 -0.79649246 -0.60371435, + 0.02800009 -0.79662973 -0.60381877, + 0.033035781 -0.80310452 -0.59492165, + 0.025258388 -0.80328667 -0.59505671, + 0.0297985 -0.80829 -0.58802998, + 0.019638101 -0.80849302 -0.58817798, + 0.021643801 -0.81042898 -0.585437, + 0.0079309586 -0.8105939 -0.58555496, + -0.013754805 -0.79121131 -0.61138827, + -0.032879993 -0.79085881 -0.61111486, + -0.064073212 -0.7634002 -0.64274019, + -0.089336656 -0.76191366 -0.64148772, + -0.121004 -0.73379499 -0.66850799, + -0.152128 -0.73062199 -0.66561902, + -0.18325789 -0.70238656 -0.68780059, + -0.219891 -0.69699901 -0.68252498, + -0.24995098 -0.66881996 -0.70014596, + -0.29146084 -0.66075569 -0.69170266, + -0.31900108 -0.63381219 -0.70464218, + -0.36423498 -0.62281293 -0.69241393, + -0.38886005 -0.59747106 -0.70129603, + -0.43687093 -0.58335096 -0.68472296, + -0.464342 -0.55312997 -0.69168901, + -0.51405376 -0.53570676 -0.66990072, + -0.54468876 -0.49879575 -0.67417872, + -0.5953849 -0.47786087 -0.6458838, + -0.62218469 -0.44174379 -0.64633471, + -0.67244118 -0.41763908 -0.61106509, + -0.69417918 -0.38435009 -0.6085971, + -0.74128604 -0.35839304 -0.56749403, + -0.75818062 -0.32856986 -0.5632087, + -0.80068785 -0.30188093 -0.5174619, + -0.81325287 -0.27594197 -0.51232392, + -0.85079509 -0.24919103 -0.46265706, + -0.8627432 -0.21950406 -0.45551312, + -0.89638627 -0.19242905 -0.39932808, + -0.90559685 -0.16264598 -0.39171493, + -0.93140787 -0.13957499 -0.33615196, + -0.93664211 -0.11666802 -0.33028802, + -0.95610499 -0.0975952 -0.27629399, + -0.95886463 -0.080652967 -0.27216491, + -0.97332853 -0.065182872 -0.2199609, + -0.97468114 -0.052932009 -0.21724403, + -0.98518312 -0.040600102 -0.16663101, + -0.98577654 -0.032038786 -0.16497892, + -0.99294013 -0.022612803 -0.11644101, + -0.99315578 -0.017023396 -0.11554997, + -0.99758822 -0.010116703 -0.068669118, + -0.99764115 -0.0069973511 -0.06828811, + -0.99974591 -0.0022976499 -0.022422997, + -0.99974954 -0.0013193594 -0.022342289, + -0.99975061 0.0013164296 0.022292592, + -0.99975109 0.0011324601 0.022285001, + -0.9997189 0.0011555098 0.023681697, + -0.99971378 0.0033747694 0.023683395, + -0.99966365 0.0031729687 0.025741192, + -0.99972963 0.0027052991 0.023095893, + -0.99971378 0.0027565493 0.023766495, + -0.99971747 0.0005624133 0.023764912, + -0.99973321 0.00055117614 0.023094205, + -0.99967939 -0.00060410268 -0.025311986, + -0.99967927 -0.00088002323 -0.025312105, + -0.99967825 -0.00087999325 -0.025349606, + -0.99967849 0.00064755528 -0.025348412, + -0.99967486 0.00064515695 -0.025489297, + -0.99967474 -0.00087181677 -0.025490494, + -0.99723238 0.002700951 -0.074299231, + -0.99723577 0.00040414892 -0.074301288, + -0.99723625 0.00040426408 -0.074294612, + -0.99723011 0.0035895405 -0.074291706, + -0.99701309 0.0032577605 -0.077164806, + -0.10280801 0.0031701506 0.99469614, + -0.075925313 -0.00085408217 0.99711323, + -0.025920695 -0.00072750682 0.99966377, + -0.025917394 0.015252196 0.99954778, + -0.02611289 0.015252095 0.99954265, + -0.02611619 -0.00073155074 0.99965864, + 0.023183202 0.0066481209 0.99970913, + -0.25466493 0.0045248591 -0.96701878, + -0.073505826 -0.0090908529 -0.99725336, + -0.073509388 0.0011905398 -0.99729377, + -0.073566861 0.0011882994 -0.99728954, + -0.073563404 -0.0090907905 -0.99724913, + -0.17087506 0.0016485606 -0.98529136, + -0.17091393 0.0016458494 -0.98528463, + -0.17091008 -0.0064645833 -0.98526549, + -0.17087105 -0.0064646713 -0.98527223, + -0.12234592 -0.0075939451 -0.9924584, + -0.12233006 -0.0075939735 -0.99246049, + -0.15862001 -0.018992202 -0.98715711, + -0.15841696 -0.043587789 -0.98640978, + -0.11234593 -0.043865774 -0.9927004, + -0.11199695 -0.074359164 -0.99092251, + -0.066615224 -0.074663728 -0.99498135, + -0.0662935 -0.105228 -0.99223602, + -0.021583 -0.105435 -0.994192, + -0.021444499 -0.13591801 -0.99048799, + 0.022107592 -0.13591595 -0.99047363, + 0.022248307 -0.10548203 -0.99417233, + 0.066987984 -0.10527097 -0.99218476, + 0.067298472 -0.074926764 -0.99491554, + 0.11256297 -0.074619688 -0.99083877, + 0.11290903 -0.044677313 -0.99260038, + 0.15875605 -0.044394612 -0.98631924, + 0.15895206 -0.021403208 -0.98705435, + 0.17396696 -0.0073968382 -0.98472375, + 0.17399108 -0.0073967939 -0.98471946, + 0.17399704 0.0013371804 -0.98474526, + 0.17397308 0.0013388906 -0.9847495, + 0.15389693 0.0047384175 -0.98807549, + 0.12545699 0.00066253095 -0.99209887, + 0.12545294 -0.0078493962 -0.99206853, + 0.12551706 -0.0078492733 -0.99206048, + 0.12552196 0.00066901575 -0.99209064, + 0.12537503 0.00066903018 -0.99210924, + 0.12533601 -0.0241252 -0.99182099, + 0.11306303 -0.019611506 -0.99339426, + 0.11291603 -0.04468631 -0.99259925, + 0.067557693 -0.044871196 -0.99670589, + 0.067344896 -0.074986003 -0.99490798, + 0.022395793 -0.075137772 -0.99692166, + 0.022287905 -0.10553102 -0.99416625, + -0.021661598 -0.10553198 -0.9941799, + -0.021756792 -0.075033873 -0.99694365, + -0.066788107 -0.074884206 -0.9949531, + -0.066991009 -0.044311605 -0.99676913, + -0.112547 -0.0441291 -0.99266601, + -0.11271195 -0.016690692 -0.99348754, + -0.12224504 -0.020198908 -0.99229437, + -0.12227194 0.00046782577 -0.99249655, + -0.12234998 0.00046781794 -0.99248689, + -0.12233497 0.00046626589 -0.99248874, + -0.15389697 0.004686119 -0.98807573, + -0.051477287 0.0047632488 -0.99866277, + 0.029028507 -0.010331702 -0.99952525, + 0.029030293 0.0012539696 -0.99957776, + 0.028964089 0.0012450696 -0.99957967, + 0.028962303 -0.010331801 -0.9995271, + 0.022414295 -0.017607396 -0.99959373, + 0.022384593 -0.044810385 -0.99874467, + -0.022013498 -0.044810798 -0.99875289, + -0.022047305 -0.011284503 -0.99969321, + -0.024504894 -0.014418496 -0.99959576, + 0.0028998293 -0.014422797 -0.99989176, + 0.0029001713 0.0007962794 -0.99999547, + -0.024507809 0.00079604331 -0.99969935, + -0.024775594 0.00083206181 -0.99969274, + -0.02477381 -0.011283504 -0.99962938, + -0.067257114 -0.016383404 -0.99760121, + -0.067166716 -0.044536911 -0.99674726, + -0.021868307 -0.044627115 -0.99876434, + -0.021793807 -0.075080633 -0.99693936, + 0.022349501 -0.075079605 -0.99692714, + 0.022424489 -0.044860978 -0.99874151, + 0.067478783 -0.044769987 -0.99671578, + 0.067575291 -0.018431298 -0.99754387, + 0.076703385 -0.0086024785 -0.99701679, + 0.076579332 -0.0086026331 -0.99702638, + 0.076582693 0.00092539191 -0.99706286, + 0.076706812 0.00092055922 -0.99705327, + 0.051477287 0.0047722389 -0.99866277, + 0 0.0030687412 0.99999535, + 0.022946889 -0.00047594577 0.99973655, + 0.022570102 -0.00046815106 0.99974513, + 0.022567289 0.015013193 0.99963254, + 0.072118118 0.014043104 0.99729723, + 0.072126001 -0.00106484 0.99739498, + 0.07193806 -0.0010648496 0.99740851, + 0.071928486 0.015539196 0.99728876, + 0.071947135 0.015539207 0.99728745, + 0.071956716 -0.0010627002 0.99740726, + 0.10280804 0.0031235912 0.99469638, + 0.25466505 0.0046267407 -0.96701825, + 0.2221151 0.00036321417 -0.97502047, + 0.22210696 -0.0073047089 -0.9749949, + 0.22208592 -0.0073047774 -0.97499967, + 0.22209311 0.00036159519 -0.97502548, + 0.22195707 0.00036161911 -0.97505635, + 0.221853 -0.029888 -0.97462201, + 0.20546605 -0.019029804 -0.97847927, + 0.20518896 -0.04395609 -0.97773474, + 0.15871699 -0.044342496 -0.98632789, + 0.15824607 -0.074033037 -0.98462045, + 0.11247299 -0.074501991 -0.9908579, + 0.11195693 -0.10469494 -0.98818243, + 0.066870272 -0.10512195 -0.99220854, + 0.066450231 -0.13558806 -0.98853445, + 0.022057505 -0.13585503 -0.99048322, + 0.021882305 -0.16657904 -0.98578525, + -0.02125879 -0.16658093 -0.98579854, + -0.021430692 -0.13590096 -0.99049062, + -0.065723397 -0.135639 -0.98857599, + -0.066142619 -0.10503703 -0.99226636, + -0.11128303 -0.10461304 -0.98826736, + -0.11180194 -0.074104764 -0.99096352, + -0.15773402 -0.073638804 -0.98473209, + -0.15821098 -0.043312095 -0.9864549, + -0.20491704 -0.04293371 -0.97783726, + -0.20519893 -0.015559695 -0.97859663, + -0.21892197 -0.024651097 -0.97543091, + -0.2189931 0.0002031801 -0.97572649, + -0.2189569 0.0002031859 -0.97573453, + -0.21905795 0.00021080195 -0.97571176, + -0.21905403 -0.0058582607 -0.97569513, + -0.25166804 -0.019652702 -0.96761411, + -0.26654708 -0.0053102518 -0.96380734, + -0.26655108 0.0021705306 -0.96381837, + -0.26655811 0.0021699208 -0.96381646, + -0.26655293 -0.0053102183 -0.96380562, + -0.31341386 -0.026438586 -0.94924855, + -0.31353012 3.4475711e-006 -0.94957834, + -0.31356102 3.4396005e-006 -0.94956809, + -0.31354389 2.4736391e-006 -0.94957364, + -0.3597081 0.0050520012 -0.93305123, + -0.359707 -0.00416394 -0.933056, + -0.35968691 -0.0041640289 -0.93306375, + -0.35968998 0.0027542498 -0.93306786, + -0.35275203 0.0035367205 -0.93571013, + -0.44708893 0.0036906695 -0.8944819, + -0.44929701 0.0034097901 -0.89337599, + -0.44929412 -0.004154461 -0.89337426, + -0.48123711 -0.016921803 -0.87642723, + -0.480827 -0.035856102 -0.876082, + -0.43579707 -0.036806002 -0.89929211, + -0.43474907 -0.064049408 -0.89827114, + -0.3888 -0.065526702 -0.918989, + -0.38728991 -0.093655579 -0.91718876, + -0.34059215 -0.095509842 -0.93534744, + -0.33869997 -0.12457599 -0.93261087, + -0.29216987 -0.12662496 -0.94794667, + -0.290023 -0.156469 -0.94414198, + -0.24383706 -0.15856205 -0.95676625, + -0.24155691 -0.18904793 -0.95179367, + -0.196052 -0.191036 -0.96180499, + -0.19381095 -0.22200795 -0.95558876, + -0.14903702 -0.22377203 -0.96317911, + -0.14700201 -0.25509903 -0.95567513, + -0.10374796 -0.25650892 -0.96095765, + -0.10210695 -0.28754586 -0.95230854, + -0.060544793 -0.28852597 -0.95555586, + -0.059467569 -0.31918284 -0.94582552, + -0.019256491 -0.31968984 -0.94732654, + -0.018865705 -0.34958908 -0.93671322, + 0.019344991 -0.34958583 -0.93670458, + 0.019728007 -0.31972712 -0.94730437, + 0.059813671 -0.31921586 -0.9457925, + 0.060897283 -0.28847894 -0.95554775, + 0.10255496 -0.28749192 -0.95227665, + 0.10419502 -0.25632906 -0.96095723, + 0.14738202 -0.25491703 -0.95566511, + 0.14942408 -0.2235171 -0.96317846, + 0.194332 -0.221745 -0.95554399, + 0.19657591 -0.1905899 -0.96178651, + 0.24219792 -0.18859492 -0.95172065, + 0.24447106 -0.15805605 -0.95668823, + 0.29056504 -0.15596901 -0.94405812, + 0.29270497 -0.12632298 -0.94782186, + 0.33935311 -0.12427004 -0.93241435, + 0.34120196 -0.095737986 -0.93510187, + 0.387784 -0.093880199 -0.91695702, + 0.38926715 -0.066542722 -0.91871834, + 0.4350878 -0.065044567 -0.89803559, + 0.4361099 -0.03916489 -0.89904076, + 0.48101681 -0.038155984 -0.87588072, + 0.48140377 -0.021605488 -0.87623256, + 0.49540606 -0.0071511809 -0.86863214, + 0.49542099 -0.000195163 -0.868653, + 0.49534705 -0.00019513002 -0.86869514, + 0.49533206 -0.0071808808 -0.8686741, + 0.49548611 -0.0071795019 -0.86858618, + 0.52535206 -0.020580001 -0.85063612, + 0.52495211 -0.036698107 -0.85034019, + 0.48079482 -0.037806284 -0.87601769, + 0.47975013 -0.062768117 -0.87515724, + 0.43468991 -0.064425983 -0.89827275, + 0.4331412 -0.090903245 -0.89673042, + 0.38720191 -0.092987679 -0.91729379, + 0.38519916 -0.12082005 -0.91489029, + 0.33863199 -0.123188 -0.93282002, + 0.3362571 -0.15239602 -0.92935824, + 0.28981498 -0.15487398 -0.94446886, + 0.28720599 -0.184964 -0.93984097, + 0.24134688 -0.18739091 -0.95217454, + 0.2386409 -0.21837293 -0.94623667, + 0.19350603 -0.22061902 -0.95597214, + 0.19090295 -0.25204495 -0.94869876, + 0.14667299 -0.25398999 -0.95602101, + 0.14436997 -0.28529295 -0.94750476, + 0.10200694 -0.28680882 -0.95254141, + 0.10019498 -0.3176789 -0.94288975, + 0.059398092 -0.31872296 -0.9459849, + 0.058217008 -0.34891304 -0.93534511, + 0.019217703 -0.34944108 -0.93676126, + 0.018802702 -0.37907207 -0.92517614, + -0.018316703 -0.37907609 -0.92518425, + -0.018738499 -0.34944397 -0.9367699, + -0.057745598 -0.34892201 -0.93537098, + -0.05894047 -0.31855685 -0.94606954, + -0.099751234 -0.31752011 -0.94299036, + -0.10155798 -0.28686094 -0.95257378, + -0.14403203 -0.28534606 -0.94754022, + -0.14631999 -0.25420898 -0.9560169, + -0.19043605 -0.25227207 -0.94873226, + -0.19304092 -0.22095892 -0.95598763, + -0.23809206 -0.21871805 -0.94629526, + -0.24078993 -0.18796295 -0.95220274, + -0.28666404 -0.18553402 -0.93989414, + -0.28927994 -0.15538597 -0.94454879, + -0.33563191 -0.15290996 -0.92949975, + -0.33802986 -0.12357194 -0.93298757, + -0.38466209 -0.12119803 -0.91506624, + -0.3867079 -0.09276478 -0.91752476, + -0.4326739 -0.090687476 -0.89697778, + -0.43426794 -0.063299894 -0.89855689, + -0.47942394 -0.061669592 -0.87541389, + -0.48050395 -0.035347298 -0.87627989, + -0.52481717 -0.034308311 -0.85052329, + -0.52524078 -0.015545192 -0.8508116, + -0.49264312 -0.0040225908 -0.87022215, + -0.49268913 -0.0040223007 -0.87019616, + -0.49269995 -0.0040178997 -0.87018991, + -0.49270517 -0.00020931807 -0.87019628, + -0.49269381 -0.00020931293 -0.87020272, + -0.49264783 -0.00021134093 -0.87022871, + -0.53475285 0.0034008089 -0.8450017, + -0.53474903 -0.0040988503 -0.8450011, + -0.53466696 -0.0040993993 -0.8450529, + -0.53466994 0.0041211797 -0.84505087, + -0.53668988 0.0038405191 -0.8437708, + -0.62061214 0.004043201 -0.78410721, + -0.61491174 0.0048957481 -0.78858072, + -0.61490488 -0.0055430187 -0.78858185, + -0.6528492 -0.011332802 -0.75740319, + -0.65289521 -0.00015935105 -0.75744832, + -0.65291184 -0.00015936195 -0.75743383, + -0.65299517 -0.00015531004 -0.75736219, + -0.68925399 0.00200768 -0.72451699, + -0.68923503 -0.0069997408 -0.72450405, + -0.72394735 -0.0062013529 -0.68982738, + -0.72396392 -3.7814898e-005 -0.68983793, + -0.69793761 0.0043151472 -0.71614558, + -0.76786715 0.0044018603 -0.64059407, + -0.78819531 0.00012098204 -0.61542523, + -0.78819114 -0.0028401203 -0.61542404, + -0.78804511 -0.0028417502 -0.61561108, + -0.78804964 0.00014823693 -0.61561167, + -0.78806669 0.00014821894 -0.61558974, + -0.78801614 -0.010849501 -0.61555904, + -0.79210937 -0.0087623838 -0.61031628, + -0.79181999 -0.0216118 -0.61037201, + -0.75915885 -0.023032494 -0.65049779, + -0.758349 -0.041065399 -0.650554, + -0.72318667 -0.043509878 -0.68928063, + -0.72181684 -0.063130282 -0.68919879, + -0.68414623 -0.066529222 -0.72630423, + -0.68213105 -0.08780551 -0.72593904, + -0.64260322 -0.092004433 -0.76065528, + -0.63986677 -0.11503196 -0.75982767, + -0.59868407 -0.11989602 -0.79196113, + -0.59519005 -0.14460501 -0.79046714, + -0.55229509 -0.15001501 -0.82004011, + -0.54802704 -0.17638901 -0.81765109, + -0.50360996 -0.18218198 -0.84450388, + -0.49861181 -0.21009792 -0.84097868, + -0.45356405 -0.21601303 -0.86464912, + -0.44797021 -0.24497512 -0.85983139, + -0.40297085 -0.25077391 -0.88018572, + -0.39691091 -0.28078395 -0.87385482, + -0.35193202 -0.28634202 -0.89115214, + -0.34567383 -0.31671885 -0.88328856, + -0.30113405 -0.32185808 -0.89762223, + -0.29481101 -0.35278001 -0.88805002, + -0.25173989 -0.35729882 -0.89942461, + -0.24560393 -0.38843891 -0.88814074, + -0.20456304 -0.39223906 -0.89682913, + -0.19888307 -0.42326516 -0.88390732, + -0.15958305 -0.4263581 -0.89036626, + -0.15456396 -0.45703188 -0.87591773, + -0.11744998 -0.45938894 -0.88043588, + -0.11328803 -0.48959312 -0.86456019, + -0.079127498 -0.49122 -0.86743402, + -0.076050192 -0.52033693 -0.85056788, + -0.044464711 -0.52133113 -0.8521952, + -0.042587914 -0.54901719 -0.83472532, + -0.013509698 -0.54946595 -0.8354069, + -0.012871598 -0.57610697 -0.8172729, + 0.013539798 -0.5761019 -0.81726581, + 0.014178902 -0.54942906 -0.83542013, + 0.043254904 -0.54897004 -0.8347221, + 0.045128677 -0.52131778 -0.85216856, + 0.076733164 -0.52031076 -0.85052258, + 0.079805821 -0.49123013 -0.86736619, + 0.11391903 -0.48959318 -0.86447728, + 0.11806902 -0.45945606 -0.88031811, + 0.15516397 -0.45708889 -0.87578177, + 0.16019005 -0.42635608 -0.89025825, + 0.19929799 -0.423269 -0.88381201, + 0.2049399 -0.39249381 -0.8966316, + 0.24619406 -0.38866308 -0.88787925, + 0.25228688 -0.35768282 -0.8991186, + 0.29515797 -0.35317197 -0.88777888, + 0.30148593 -0.32220992 -0.89737779, + 0.34597582 -0.31706384 -0.88304657, + 0.35228497 -0.28641298 -0.8909899, + 0.397158 -0.28086001 -0.87371802, + 0.40324295 -0.25073597 -0.88007188, + 0.44827685 -0.24492891 -0.85968471, + 0.45393115 -0.21559708 -0.86456031, + 0.498887 -0.209699 -0.84091502, + 0.50396097 -0.18135299 -0.84447289, + 0.54842985 -0.17557295 -0.81755668, + 0.55270797 -0.14905499 -0.81993687, + 0.59561515 -0.14367104 -0.79031718, + 0.59908694 -0.11902399 -0.79178786, + 0.64027303 -0.11418601 -0.7596131, + 0.64295226 -0.091556832 -0.7604143, + 0.68242615 -0.087378621 -0.72571319, + 0.6843822 -0.066766113 -0.72606015, + 0.72201383 -0.063355483 -0.68897182, + 0.72332102 -0.044771001 -0.68905902, + 0.7584421 -0.042257104 -0.65036905, + 0.75921899 -0.025565499 -0.65033299, + 0.7918371 -0.023990303 -0.61026108, + 0.79214531 -0.011401704 -0.61022621, + 0.78997284 -0.012527697 -0.61301386, + 0.79003966 -2.4914987e-005 -0.61305571, + 0.79002011 -2.4895104e-005 -0.61308104, + 0.7899068 -3.7248492e-006 -0.61322689, + 0.76786691 0.0043120794 -0.64059496, + 0.82967281 0.0043707993 -0.5582329, + 0.84637946 0.0001615971 -0.53258032, + 0.8463099 -0.012384998 -0.53254694, + 0.846187 -0.0123903 -0.53274202, + 0.8462562 0.00018830904 -0.53277612, + 0.84633189 0.00018821398 -0.53265595, + 0.84620398 -0.016962901 -0.53258902, + 0.85041809 -0.015671501 -0.52587408, + 0.84975916 -0.032472506 -0.52617013, + 0.82114702 -0.035154801 -0.56963301, + 0.82020873 -0.049764581 -0.5698958, + 0.78915972 -0.053428981 -0.61185974, + 0.78767866 -0.070025772 -0.61209369, + 0.75421786 -0.074633494 -0.65236896, + 0.75206685 -0.093319878 -0.65244681, + 0.71593016 -0.098853923 -0.69113821, + 0.71297991 -0.11967099 -0.69089693, + 0.67426115 -0.12603803 -0.72765815, + 0.67038357 -0.14909391 -0.72688156, + 0.62982774 -0.15606993 -0.7608937, + 0.62496185 -0.18124595 -0.75932384, + 0.5827961 -0.18866804 -0.7904132, + 0.57700568 -0.21540989 -0.78782165, + 0.53339189 -0.22309095 -0.8159188, + 0.52673519 -0.25123608 -0.81205332, + 0.48203799 -0.258957 -0.83700699, + 0.47461212 -0.28837407 -0.83161515, + 0.42990109 -0.29580507 -0.85304415, + 0.42196101 -0.32594699 -0.84599501, + 0.37775484 -0.33288288 -0.86399668, + 0.36944199 -0.36377001 -0.855093, + 0.32598099 -0.37008101 -0.86992902, + 0.31754303 -0.40143007 -0.85908109, + 0.27532983 -0.40697876 -0.87095445, + 0.26708007 -0.43841612 -0.85817218, + 0.22690697 -0.44307595 -0.86729288, + 0.21912906 -0.47427613 -0.85266918, + 0.18142794 -0.47802281 -0.8594057, + 0.17440605 -0.50860614 -0.8431502, + 0.139226 -0.51149201 -0.84793401, + 0.13330694 -0.54067576 -0.83060157, + 0.10085604 -0.54276317 -0.8338083, + 0.096078813 -0.57104903 -0.81527412, + 0.066786282 -0.57242191 -0.81723481, + 0.063299581 -0.59953988 -0.79783779, + 0.036940202 -0.60033506 -0.79889512, + 0.034811005 -0.62630808 -0.7787981, + 0.0112841 -0.62664902 -0.77921999, + 0.010573401 -0.65131706 -0.75873214, + -0.010048099 -0.65132093 -0.7587359, + -0.0107589 -0.62670302 -0.77918398, + -0.034199595 -0.62637293 -0.77877289, + -0.03632639 -0.60043275 -0.7988497, + -0.062638804 -0.59965008 -0.7978071, + -0.06612882 -0.57250619 -0.81722927, + -0.095396899 -0.571145 -0.81528699, + -0.10014503 -0.54303616 -0.83371627, + -0.13257399 -0.54096293 -0.8305319, + -0.13858102 -0.51134515 -0.8481282, + -0.17377599 -0.50847095 -0.84336185, + -0.18077694 -0.47797981 -0.85956669, + -0.21836397 -0.47425893 -0.85287488, + -0.22622597 -0.44277394 -0.86762488, + -0.26646096 -0.43812388 -0.85851383, + -0.2747561 -0.40654916 -0.87133628, + -0.31716108 -0.40099308 -0.8594262, + -0.32556704 -0.36976102 -0.87022012, + -0.36910698 -0.36345196 -0.85537291, + -0.37743405 -0.33252403 -0.8642751, + -0.42168784 -0.32559487 -0.84626669, + -0.429645 -0.29539001 -0.85331702, + -0.47446081 -0.28795791 -0.8318457, + -0.48180813 -0.25882807 -0.83717918, + -0.52659196 -0.25110096 -0.81218791, + -0.53319097 -0.22319797 -0.81602091, + -0.57675815 -0.21552604 -0.7879712, + -0.58250004 -0.18906303 -0.79053712, + -0.62464887 -0.18163696 -0.75948781, + -0.62945783 -0.15683796 -0.76104182, + -0.67002916 -0.14983404 -0.72705621, + -0.67389303 -0.12697001 -0.72783709, + -0.71263397 -0.12056199 -0.69109893, + -0.71560705 -0.099714518 -0.69134909, + -0.7517873 -0.094132841 -0.65265226, + -0.75399065 -0.075076766 -0.65258068, + -0.78748333 -0.070442535 -0.6122973, + -0.78902018 -0.053194713 -0.61206013, + -0.81965297 -0.049600899 -0.57070899, + -0.81836879 -0.064531982 -0.57105887, + -0.78694803 -0.069284797 -0.61311698, + -0.78496915 -0.086892426 -0.61341113, + -0.75106519 -0.09259972 -0.6537022, + -0.74833626 -0.11211403 -0.65377623, + -0.71175581 -0.11872497 -0.69232082, + -0.70814317 -0.14028603 -0.69199216, + -0.66898471 -0.14767893 -0.72845763, + -0.66440582 -0.17121495 -0.72749585, + -0.62341392 -0.17912298 -0.76109791, + -0.61783278 -0.20449792 -0.75925171, + -0.57535601 -0.212715 -0.78975803, + -0.56881368 -0.23963988 -0.78678066, + -0.52500182 -0.24798392 -0.81417269, + -0.517537 -0.27642101 -0.80978203, + -0.47273794 -0.28467196 -0.83395487, + -0.46451899 -0.31426999 -0.827923, + -0.41979015 -0.32209811 -0.84854531, + -0.41095409 -0.35273308 -0.84065217, + -0.36709583 -0.35990083 -0.85773659, + -0.35790682 -0.39124683 -0.84783757, + -0.31516597 -0.39764893 -0.86171091, + -0.30591801 -0.42937699 -0.84973502, + -0.26444691 -0.43494385 -0.86075068, + -0.25542003 -0.46678707 -0.84668213, + -0.21640597 -0.47136095 -0.85497791, + -0.20810707 -0.50228316 -0.83928728, + -0.17189693 -0.50588185 -0.84530169, + -0.16451998 -0.53588295 -0.82810789, + -0.13074398 -0.53862292 -0.8323409, + -0.12446801 -0.56755906 -0.81387013, + -0.093984157 -0.56947571 -0.81661761, + -0.08898858 -0.59725189 -0.7971018, + -0.061577208 -0.59849304 -0.79875809, + -0.0579766 -0.62486899 -0.77857399, + -0.033403181 -0.62557262 -0.77945054, + -0.031203311 -0.65084022 -0.75857329, + -0.009839599 -0.65112597 -0.75890589, + -0.0091036288 -0.67525196 -0.73753095, + 0.009573428 -0.6752488 -0.73752785, + 0.010308397 -0.65106982 -0.75894785, + 0.031755213 -0.65077627 -0.7586053, + 0.033958707 -0.62545216 -0.77952319, + 0.058330186 -0.62474787 -0.7786448, + 0.061975393 -0.59809697 -0.79902387, + 0.08964505 -0.59683633 -0.7973395, + 0.09459462 -0.56929511 -0.81667316, + 0.12533301 -0.56735003 -0.81388313, + 0.13158301 -0.53847098 -0.83230698, + 0.16500293 -0.53574878 -0.8280986, + 0.17237401 -0.50580406 -0.84525114, + 0.20871796 -0.50218087 -0.8391968, + 0.21703297 -0.47117794 -0.85491991, + 0.25606298 -0.46659094 -0.84659588, + 0.26498389 -0.4351058 -0.86050355, + 0.30626503 -0.42955306 -0.8495211, + 0.3154799 -0.3979699 -0.86144781, + 0.3582719 -0.39154691 -0.84754485, + 0.36744508 -0.36024809 -0.85744119, + 0.41125709 -0.35307309 -0.84036118, + 0.42007893 -0.32248098 -0.84825689, + 0.46466488 -0.3146629 -0.82769179, + 0.47288787 -0.28508195 -0.8337298, + 0.5176819 -0.27681494 -0.80955482, + 0.52519095 -0.24820597 -0.8139829, + 0.56901008 -0.23984803 -0.78657514, + 0.57561809 -0.21262603 -0.78959113, + 0.61802006 -0.20442103 -0.75912011, + 0.62368596 -0.17864299 -0.76098788, + 0.66465497 -0.17075299 -0.72737694, + 0.66929483 -0.14684197 -0.72834182, + 0.70844007 -0.13948502 -0.69185007, + 0.71206594 -0.11775298 -0.69216794, + 0.74863875 -0.11118996 -0.65358776, + 0.75134033 -0.091774344 -0.65350229, + 0.78520787 -0.086116493 -0.61321497, + 0.78713864 -0.068855569 -0.6129207, + 0.81853414 -0.064131305 -0.57086706, + 0.81983185 -0.048929788 -0.57050991, + 0.84832817 -0.045244113 -0.52753413, + 0.84727317 -0.058238216 -0.52795511, + 0.81806099 -0.063059703 -0.57166398, + 0.81636018 -0.078937523 -0.57212311, + 0.78458798 -0.084742799 -0.61419898, + 0.78216112 -0.10274202 -0.61454707, + 0.74784917 -0.10946803 -0.65478116, + 0.744528 -0.129786 -0.654854, + 0.70746905 -0.13739702 -0.69326007, + 0.70312017 -0.16000505 -0.69283515, + 0.66352224 -0.16835105 -0.72896922, + 0.65812093 -0.19288097 -0.72778696, + 0.61670178 -0.20166293 -0.76092768, + 0.61026502 -0.227791 -0.75874102, + 0.56750399 -0.236754 -0.788598, + 0.5600329 -0.26447195 -0.78512281, + 0.51600385 -0.27344692 -0.8117677, + 0.50760704 -0.30248004 -0.80674714, + 0.46288395 -0.31119698 -0.82999688, + 0.453686 -0.34145501 -0.82315099, + 0.40939006 -0.34957704 -0.84273112, + 0.39966407 -0.38058406 -0.83392113, + 0.35625592 -0.38794392 -0.85004783, + 0.34620517 -0.4195922 -0.83909744, + 0.30419698 -0.42605495 -0.85202187, + 0.29420304 -0.45779407 -0.83896911, + 0.25397891 -0.46328682 -0.84903473, + 0.24440788 -0.49469978 -0.83398861, + 0.20667295 -0.49915689 -0.8415038, + 0.19792102 -0.52960306 -0.82483214, + 0.16304494 -0.5330618 -0.83021772, + 0.15535405 -0.56232017 -0.8121953, + 0.12338498 -0.56488192 -0.8158949, + 0.11686899 -0.59311694 -0.7965889, + 0.087980144 -0.59489328 -0.79897535, + 0.082755476 -0.62220287 -0.7784698, + 0.0570076 -0.62332898 -0.77987897, + 0.053233091 -0.64929795 -0.7586689, + 0.030875919 -0.64991033 -0.7593835, + 0.028604707 -0.67453218 -0.73769116, + 0.0090597551 -0.67478073 -0.73796266, + 0.0082906643 -0.69850051 -0.71556145, + -0.0081577739 -0.69850135 -0.71556234, + -0.0089133345 -0.67507827 -0.73769236, + -0.02810709 -0.67483777 -0.73743075, + -0.030397596 -0.65004694 -0.75928587, + -0.052938871 -0.64943564 -0.75857151, + -0.056701593 -0.62350196 -0.77976286, + -0.082138494 -0.62239695 -0.77837986, + -0.087323822 -0.59530813 -0.79873818, + -0.11617298 -0.59354496 -0.79637188, + -0.12269504 -0.56531018 -0.81570232, + -0.15462892 -0.56276363 -0.8120265, + -0.16244602 -0.53304005 -0.83034915, + -0.19712709 -0.52961522 -0.82501441, + -0.20592304 -0.49905506 -0.84174812, + -0.24382094 -0.49459288 -0.83422381, + -0.25331399 -0.463447 -0.84914601, + -0.29360712 -0.45795816 -0.83908832, + -0.30375889 -0.42572784 -0.85234171, + -0.34584498 -0.41926795 -0.83940786, + -0.3558909 -0.38764092 -0.85033882, + -0.3993237 -0.38029173 -0.83421743, + -0.40907392 -0.3492099 -0.84303683, + -0.45344514 -0.34108913 -0.82343531, + -0.4626818 -0.31069785 -0.83029658, + -0.50744784 -0.30199289 -0.80702972, + -0.51583189 -0.27299893 -0.81202781, + -0.55980384 -0.26405692 -0.78542572, + -0.56725502 -0.236441 -0.78887099, + -0.61011696 -0.22747497 -0.75895488, + -0.61647773 -0.2016689 -0.76110762, + -0.65793508 -0.19288403 -0.72795403, + -0.66325378 -0.16877393 -0.72911578, + -0.70291418 -0.16040304 -0.69295216, + -0.70718783 -0.13823797 -0.69337982, + -0.74425119 -0.13058802 -0.65500915, + -0.74756062 -0.11042695 -0.65494972, + -0.78189713 -0.10364702 -0.61473107, + -0.78435302 -0.085529797 -0.61439002, + -0.81615919 -0.079671621 -0.57230812, + -0.81790215 -0.063477211 -0.57184505, + -0.8471393 -0.058624323 -0.52812719, + -0.8487829 -0.037570596 -0.52740496, + -0.87525898 -0.034366801 -0.48243201, + -0.87608677 -0.012750497 -0.48198488, + -0.8929559 -0.0065858592 -0.45009595, + -0.89292312 -0.006587211 -0.45016107, + -0.8929441 0.00073833612 -0.45016706, + -0.89297789 0.00072948093 -0.45009995, + -0.91402441 1.6375307e-005 -0.40565917, + -0.91393667 1.6532895e-005 -0.40585685, + -0.91397923 1.9893505e-005 -0.40576109, + -0.91396397 -0.0053644702 -0.40575999, + -0.91392177 -0.0053663687 -0.40585491, + -0.91400987 -0.0053374893 -0.40565693, + -0.89923978 -0.011687997 -0.43729991, + -0.89856678 -0.030610792 -0.43776789, + -0.87473339 -0.033803314 -0.48342425, + -0.87283015 -0.058938514 -0.48445213, + -0.8447119 -0.09099789 -0.52742893, + -0.86896116 -0.084139325 -0.48767513, + -0.87196487 -0.058072291 -0.48611194, + -0.89656669 -0.052537482 -0.43978184, + -0.89813572 -0.03011819 -0.43868586, + -0.91950297 -0.0269239 -0.39216, + -0.92003286 -0.010522799 -0.39169994, + -0.93275911 -0.0041978303 -0.36047602, + -0.93278027 -0.004196771 -0.36042109, + -0.93278956 0.0011098394 -0.36041981, + -0.93276823 0.0011173103 -0.36047509, + -0.94931477 -0.00031260791 -0.31432691, + -0.94935477 -0.00031270392 -0.31420591, + -0.94932365 -0.00031475889 -0.31429988, + -0.94931787 -0.0032487495 -0.31430098, + -0.94934899 -0.00324696 -0.31420699, + -0.94930887 -0.0032585596 -0.31432799, + -0.93844336 -0.0094034234 -0.34530511, + -0.93804097 -0.023316801 -0.34573901, + -0.91916162 -0.026503392 -0.39298785, + -0.91791111 -0.046237104 -0.39408305, + -0.89585412 -0.051779509 -0.44132105, + -0.89338058 -0.07504686 -0.44298878, + -0.86774713 -0.083015211 -0.49002406, + -0.86454487 -0.10393398 -0.49169093, + -0.83602297 -0.113477 -0.53683197, + -0.83284682 -0.13024297 -0.5379619, + -0.80098897 -0.140873 -0.58186901, + -0.796709 -0.159942 -0.58281499, + -0.76198 -0.17138401 -0.624511, + -0.75642312 -0.19275703 -0.62503505, + -0.71895492 -0.20483097 -0.66418993, + -0.71196425 -0.22847608 -0.66400725, + -0.67173982 -0.24102594 -0.70047981, + -0.66317892 -0.26692998 -0.69924396, + -0.620628 -0.279643 -0.732544, + -0.61046195 -0.30763498 -0.72986096, + -0.56672496 -0.32000998 -0.7592209, + -0.55498266 -0.3499068 -0.75469154, + -0.51061285 -0.36166289 -0.78004771, + -0.49745607 -0.39309606 -0.77331311, + -0.45321307 -0.40393206 -0.79463011, + -0.43898973 -0.43635872 -0.78541654, + -0.39546791 -0.44606587 -0.80288881, + -0.38090423 -0.47830731 -0.79128647, + -0.33918691 -0.48663789 -0.80506885, + -0.32445404 -0.51883006 -0.79091412, + -0.28528693 -0.52570885 -0.80139983, + -0.27086896 -0.55735296 -0.78484887, + -0.23457193 -0.56284386 -0.79257983, + -0.22093694 -0.59349787 -0.77391684, + -0.18780905 -0.59770709 -0.77940619, + -0.17522594 -0.62733376 -0.75878072, + -0.14547402 -0.63041407 -0.76250613, + -0.134247 -0.658732 -0.74030399, + -0.108689 -0.66081101 -0.74264097, + -0.098874614 -0.68815404 -0.71879607, + -0.076811709 -0.68949908 -0.72020209, + -0.068978988 -0.71454084 -0.69618481, + -0.050563902 -0.71533 -0.69695503, + -0.044480987 -0.73895878 -0.67228079, + -0.029530188 -0.73936874 -0.67265278, + -0.02525581 -0.76138037 -0.64781332, + -0.023573488 -0.75977665 -0.64975673, + -0.036310513 -0.75948632 -0.64950925, + -0.042483401 -0.73683 -0.67474198, + -0.058705732 -0.7362234 -0.67418742, + -0.066765986 -0.71191084 -0.69908881, + -0.086407207 -0.71083504 -0.69803107, + -0.096338682 -0.68479794 -0.72233695, + -0.11998004 -0.68302822 -0.72047025, + -0.131762 -0.65508097 -0.743981, + -0.15930198 -0.65240294 -0.74094093, + -0.17258792 -0.6230427 -0.76290965, + -0.20388804 -0.61924809 -0.75826216, + -0.21832807 -0.58882022 -0.77821827, + -0.25308397 -0.58373296 -0.77149487, + -0.26834294 -0.5524019 -0.78920484, + -0.30642101 -0.54584903 -0.77984297, + -0.32210401 -0.51385099 -0.79511398, + -0.36286217 -0.50578421 -0.78263235, + -0.3786571 -0.47322112 -0.79541218, + -0.42159379 -0.46363279 -0.77929664, + -0.43687415 -0.43129814 -0.78938133, + -0.48115513 -0.4203251 -0.76929617, + -0.49557477 -0.38842782 -0.77687162, + -0.53991389 -0.3764219 -0.75286084, + -0.55317205 -0.34530202 -0.75813413, + -0.5972811 -0.33243909 -0.72989017, + -0.60879207 -0.30332404 -0.73305309, + -0.651981 -0.289906 -0.700625, + -0.66168392 -0.26303896 -0.70212895, + -0.7026062 -0.24963605 -0.66635317, + -0.71062237 -0.22496811 -0.6666373, + -0.74893492 -0.21188097 -0.62785596, + -0.7552861 -0.18977603 -0.62731808, + -0.79083031 -0.17722006 -0.58581626, + -0.79576784 -0.15745096 -0.58477587, + -0.82840669 -0.14562796 -0.54086483, + -0.83210111 -0.12824202 -0.53959405, + -0.86016113 -0.11793002 -0.49620107, + -0.85746348 -0.13141993 -0.49747869, + -0.82759011 -0.14337002 -0.54271507, + -0.82329285 -0.16153999 -0.54414493, + -0.78985089 -0.17454098 -0.58793795, + -0.78419185 -0.19506496 -0.5890609, + -0.74777395 -0.20871897 -0.63029397, + -0.74044508 -0.23194203 -0.63082808, + -0.70127577 -0.24601191 -0.66909677, + -0.69218707 -0.27160302 -0.66866207, + -0.65048105 -0.28583002 -0.70368707, + -0.639449 -0.31389001 -0.70183903, + -0.59561908 -0.32794803 -0.73327208, + -0.58268499 -0.35809699 -0.72955102, + -0.5380348 -0.37141588 -0.75668269, + -0.5234943 -0.40294924 -0.75072348, + -0.47914094 -0.41510695 -0.77337587, + -0.46339005 -0.44741905 -0.76490915, + -0.41946092 -0.45833489 -0.78356981, + -0.40288693 -0.49096793 -0.77241987, + -0.36054087 -0.50035185 -0.7871837, + -0.34363514 -0.53284723 -0.77329737, + -0.30398285 -0.54054976 -0.78447467, + -0.28708497 -0.57276595 -0.76780289, + -0.25063905 -0.57885009 -0.77595919, + -0.23441792 -0.61004674 -0.75689572, + -0.20136903 -0.61467808 -0.76264113, + -0.18609296 -0.64487582 -0.7412858, + -0.15674701 -0.64822805 -0.74513805, + -0.14285608 -0.67706531 -0.72192436, + -0.117468 -0.67934501 -0.724356, + -0.10532594 -0.7064386 -0.69989359, + -0.084149748 -0.7078706 -0.70131159, + -0.07424064 -0.73238033 -0.67683631, + -0.056171317 -0.73324716 -0.67763817, + -0.04798371 -0.75656116 -0.65216017, + -0.033933494 -0.75699681 -0.65253681, + -0.027574308 -0.77906215 -0.62634015, + -0.019595698 -0.7792089 -0.62645793, + -0.0026407097 -0.79070085 -0.61219692, + -0.0073682088 -0.7906819 -0.61218292, + -0.0023397203 -0.82745314 -0.56153005, + 0.00021297595 -0.82745582 -0.56153089, + 0.0017080903 -0.85741419 -0.51462412, + -0.0017843002 -0.85741413 -0.51462406, + -0.00029650202 -0.82746309 -0.56152004, + 0.0022557296 -0.82746083 -0.56151891, + 0.0072834357 -0.79063952 -0.61223865, + 0.017150203 -0.79054409 -0.61216503, + 0.023541609 -0.7597003 -0.64984721, + 0.036285717 -0.75941038 -0.64959931, + 0.042429812 -0.73685217 -0.67472118, + 0.058674823 -0.73624521 -0.67416626, + 0.06690108 -0.71141773 -0.69957775, + 0.086878091 -0.71031994 -0.69849694, + 0.096895352 -0.68400371 -0.72301465, + 0.120659 -0.68221599 -0.72112602, + 0.132416 -0.65426803 -0.74457997, + 0.159877 -0.65158898 -0.74153298, + 0.17314704 -0.62223113 -0.7634452, + 0.20478095 -0.6183849 -0.75872582, + 0.219161 -0.58802801 -0.77858299, + 0.25399706 -0.58291513 -0.77181315, + 0.2692059 -0.5516358 -0.78944671, + 0.30711004 -0.54510105 -0.7800951, + 0.32272089 -0.51322085 -0.79527068, + 0.36368001 -0.50510401 -0.78269202, + 0.37928092 -0.47289687 -0.79530782, + 0.42235422 -0.4632622 -0.77910537, + 0.43753287 -0.4310869 -0.78913182, + 0.4815217 -0.42017177 -0.7691505, + 0.49591005 -0.38834307 -0.77670014, + 0.54032087 -0.37630591 -0.75262684, + 0.55334181 -0.34573287 -0.75781369, + 0.59741223 -0.33285713 -0.72959226, + 0.60887223 -0.30388212 -0.73275524, + 0.65202898 -0.290445 -0.70035702, + 0.66175008 -0.26354402 -0.70187706, + 0.70262992 -0.25012696 -0.66614395, + 0.71063876 -0.22549193 -0.66644275, + 0.74893606 -0.21237902 -0.62768608, + 0.75532198 -0.190162 -0.62715799, + 0.79083699 -0.17759 -0.58569503, + 0.79580212 -0.15771501 -0.58465809, + 0.82840914 -0.14588101 -0.54079306, + 0.83217841 -0.12814806 -0.53949726, + 0.86130017 -0.11742203 -0.49434212, + 0.8640359 -0.10196499 -0.49299595, + 0.8898176 -0.092421852 -0.44685879, + 0.89096498 -0.0958101 -0.443849, + 0.036809415 -0.7760793 -0.62956023, + 0.045262087 -0.75332081 -0.65609384, + 0.061259493 -0.7526769 -0.65553397, + 0.071460389 -0.72885484 -0.68092883, + 0.090591356 -0.72771865 -0.67986673, + 0.10299101 -0.70164007 -0.70504904, + 0.12632403 -0.69974017 -0.7031402, + 0.14080603 -0.6714462 -0.72755319, + 0.16821496 -0.66853881 -0.72440284, + 0.18420106 -0.63883722 -0.74696523, + 0.21550608 -0.63468623 -0.74211222, + 0.23268503 -0.60367906 -0.76251513, + 0.26786092 -0.59803379 -0.75538468, + 0.28558797 -0.56635594 -0.77309787, + 0.32422614 -0.55904323 -0.76311737, + 0.34230304 -0.52653104 -0.77819914, + 0.38359094 -0.51751596 -0.76487589, + 0.40142307 -0.48476306 -0.77708709, + 0.44500795 -0.47398293 -0.75980788, + 0.46196878 -0.44160178 -0.76913762, + 0.50631595 -0.42937893 -0.74784893, + 0.5221709 -0.39746892 -0.75455683, + 0.56703967 -0.38388377 -0.72876561, + 0.58126128 -0.35324419 -0.73304439, + 0.62560695 -0.33866698 -0.70279497, + 0.63795805 -0.30975202 -0.70502704, + 0.68051922 -0.29473212 -0.67084026, + 0.69080502 -0.26815999 -0.67147499, + 0.73092991 -0.25310698 -0.63378096, + 0.73925996 -0.22897796 -0.63329595, + 0.7765125 -0.21424887 -0.59255862, + 0.78308189 -0.19259797 -0.59134495, + 0.81744117 -0.17838204 -0.5476951, + 0.82241273 -0.15937795 -0.5461098, + 0.85309851 -0.14617109 -0.50085628, + 0.85677713 -0.12956601 -0.49914506, + 0.88387209 -0.11751702 -0.45272505, + 0.88613522 -0.10525303 -0.45131612, + 0.86066979 -0.11563997 -0.49585789, + 0.85748959 -0.13163593 -0.49737677, + 0.82759184 -0.14361797 -0.54264688, + 0.8232767 -0.16184793 -0.54407781, + 0.78984302 -0.174869 -0.58785099, + 0.78412789 -0.19556896 -0.58897895, + 0.74777943 -0.20922913 -0.63011837, + 0.74046415 -0.23240006 -0.63063717, + 0.70129722 -0.24649809 -0.66889524, + 0.69219226 -0.2721231 -0.66844523, + 0.65052909 -0.28636304 -0.70342606, + 0.63954628 -0.31429014 -0.70157135, + 0.59574991 -0.32836097 -0.73298097, + 0.58297986 -0.3581329 -0.72929782, + 0.53848588 -0.3714219 -0.7563588, + 0.524059 -0.40275601 -0.75043303, + 0.47952101 -0.41497901 -0.77320898, + 0.46394011 -0.44695812 -0.76484519, + 0.42017195 -0.45784393 -0.78347588, + 0.40362385 -0.49046981 -0.77235168, + 0.36142918 -0.49983725 -0.78710335, + 0.34463492 -0.53218585 -0.7733078, + 0.30474415 -0.53995126 -0.78459138, + 0.28804183 -0.57184964 -0.7681275, + 0.2515181 -0.57796121 -0.77633733, + 0.23535097 -0.60911691 -0.75735486, + 0.20223904 -0.61377007 -0.76314211, + 0.18699294 -0.64396977 -0.74184674, + 0.15730007 -0.64737231 -0.74576533, + 0.14355098 -0.6759578 -0.7228238, + 0.11796596 -0.67826277 -0.72528875, + 0.10571904 -0.70563626 -0.70064324, + 0.084412105 -0.70708108 -0.70207608, + 0.0741833 -0.73240399 -0.676817, + 0.056140207 -0.73326904 -0.67761707, + 0.047988877 -0.75648266 -0.65225071, + 0.033908408 -0.75692016 -0.65262717, + 0.028344192 -0.77629369 -0.62973374, + 0.0095994994 -0.78855288 -0.61489195, + 0.0122636 -0.78852999 -0.61487401, + 0.003659321 -0.82609016 -0.56352609, + -0.0013834593 -0.82609457 -0.56352973, + -0.0060598888 -0.85692179 -0.5154109, + -0.0032286495 -0.85693288 -0.51541793, + -0.002562579 -0.84404969 -0.53625882, + 0.0025226793 -0.84404981 -0.53625888, + 0.0031896494 -0.8569209 -0.51543796, + 0.0059814737 -0.85690951 -0.5154323, + 0.0012987696 -0.82608783 -0.56353986, + -0.0037432015 -0.82608229 -0.56353718, + -0.010304404 -0.79778033 -0.60286027, + -0.018569704 -0.79768521 -0.60278809, + -0.025035797 -0.77645189 -0.62967896, + -0.0368197 -0.776169 -0.62944901, + -0.045273084 -0.75341773 -0.65598178, + -0.061215706 -0.75277615 -0.65542406, + -0.071487166 -0.72879064 -0.68099469, + -0.090646878 -0.72765183 -0.67993081, + -0.10262398 -0.70248282 -0.70426279, + -0.12582304 -0.70059919 -0.70237416, + -0.14015996 -0.6726408 -0.72657382, + -0.16744795 -0.6697548 -0.7234568, + -0.183466 -0.64005399 -0.746104, + -0.21462592 -0.63593274 -0.74129975, + -0.23187409 -0.60486221 -0.76182431, + -0.26671502 -0.59928405 -0.75479913, + -0.28464797 -0.56731296 -0.77274287, + -0.32321092 -0.56003088 -0.76282382, + -0.341389 -0.527403 -0.77801001, + -0.38282216 -0.5183692 -0.76468331, + -0.40076092 -0.48545989 -0.77699381, + -0.44419494 -0.47472894 -0.7598179, + -0.46138281 -0.44196486 -0.76928073, + -0.50574774 -0.4297508 -0.74801964, + -0.52165097 -0.39778295 -0.75475091, + -0.56664288 -0.38417092 -0.72892284, + -0.58098906 -0.35327303 -0.73324609, + -0.62539417 -0.33868808 -0.7029742, + -0.63788801 -0.309432 -0.70523101, + -0.68039757 -0.29444984 -0.67108756, + -0.69078624 -0.26760608 -0.67171526, + -0.73086792 -0.25260198 -0.63405395, + -0.73921198 -0.22843499 -0.63354802, + -0.77660787 -0.21368296 -0.59263796, + -0.78314734 -0.19210009 -0.59142029, + -0.81747115 -0.17793101 -0.54779708, + -0.82241368 -0.15902694 -0.54621083, + -0.85168719 -0.14649203 -0.50315911, + -0.84816313 -0.16081302 -0.50473607, + -0.81656289 -0.17523898 -0.55001491, + -0.81085688 -0.19510096 -0.55176693, + -0.77551913 -0.21046104 -0.59521109, + -0.76801389 -0.23310196 -0.59650493, + -0.72962719 -0.24890307 -0.63693917, + -0.72009301 -0.27424499 -0.63738197, + -0.67897284 -0.29016694 -0.67438781, + -0.66720879 -0.31813988 -0.67351276, + -0.62378603 -0.33382502 -0.70671904, + -0.60988694 -0.36385396 -0.70402294, + -0.56487894 -0.37885994 -0.73305994, + -0.5490272 -0.41045615 -0.72807622, + -0.5038721 -0.4241941 -0.75244421, + -0.48642612 -0.45675012 -0.74482816, + -0.44215506 -0.46888706 -0.76462013, + -0.4234359 -0.50208086 -0.75406682, + -0.38065809 -0.51249415 -0.7697072, + -0.36127496 -0.54564494 -0.75614285, + -0.32090482 -0.55421865 -0.7680245, + -0.30139402 -0.58693308 -0.75144613, + -0.26428092 -0.59367079 -0.76007271, + -0.24514505 -0.62558818 -0.74063718, + -0.21206497 -0.63060194 -0.74657196, + -0.19389801 -0.661264 -0.72466099, + -0.164804 -0.66483903 -0.72858, + -0.14819999 -0.69372493 -0.70482796, + -0.12311703 -0.69613415 -0.70727617, + -0.108903 -0.722206 -0.68305099, + -0.087953821 -0.72371221 -0.68447417, + -0.07565327 -0.74811476 -0.65924275, + -0.058289476 -0.74898964 -0.66001272, + -0.047761213 -0.77222121 -0.63355619, + -0.033755809 -0.77266318 -0.63391817, + -0.025127104 -0.79461914 -0.60658807, + -0.015682904 -0.79477221 -0.60670513, + -0.006196551 -0.82392913 -0.56665903, + 0.0016532602 -0.82394314 -0.56667006, + 0.0096833883 -0.85552084 -0.5176779, + 0.009909384 -0.85551929 -0.51767617, + 0.0080195889 -0.84351486 -0.53704596, + 0.0040287804 -0.84353513 -0.53705907, + 0.0026821997 -0.81647187 -0.57737893, + -0.0027894115 -0.8164714 -0.57737929, + -0.0041274694 -0.84351486 -0.53708994, + -0.008075797 -0.84349471 -0.53707683, + -0.0099695539 -0.8555373 -0.51764518, + -0.0097634811 -0.85553914 -0.51764607, + -0.0017372805 -0.82395118 -0.56665814, + 0.0060924585 -0.82393682 -0.5666489, + 0.015600803 -0.79468918 -0.60681611, + 0.025358504 -0.79453009 -0.60669506, + 0.03390421 -0.77275431 -0.63379925, + 0.047671381 -0.77231967 -0.63344276, + 0.058304925 -0.74885136 -0.66016829, + 0.075436696 -0.74799001 -0.65940899, + 0.087752931 -0.72356623 -0.68465424, + 0.108948 -0.722045 -0.68321401, + 0.12356895 -0.69519174 -0.70812374, + 0.14879102 -0.69276303 -0.70564908, + 0.16554201 -0.66356099 -0.729577, + 0.194838 -0.659949 -0.72560698, + 0.21293907 -0.62933326 -0.74739325, + 0.24635091 -0.62425476 -0.74136174, + 0.26540902 -0.59237808 -0.76068813, + 0.30241284 -0.58564472 -0.75204164, + 0.3218351 -0.55301315 -0.7685042, + 0.36244583 -0.54437375 -0.75649863, + 0.38147295 -0.51175892 -0.76979285, + 0.42427507 -0.50132507 -0.75409812, + 0.44296211 -0.46812612 -0.76461917, + 0.48724219 -0.45597416 -0.74477023, + 0.50444287 -0.42382491 -0.7522698, + 0.54957086 -0.41008192 -0.72787684, + 0.56530988 -0.37867591 -0.73282284, + 0.61026973 -0.36367083 -0.70378566, + 0.62403405 -0.33391201 -0.70645905, + 0.66741705 -0.31822303 -0.67326707, + 0.6790942 -0.29044706 -0.67414516, + 0.72011399 -0.27454299 -0.63722998, + 0.72963601 -0.24925099 -0.63679302, + 0.76799279 -0.23343994 -0.5963999, + 0.77542889 -0.21103597 -0.59512496, + 0.81082034 -0.1956161 -0.55163825, + 0.81654173 -0.17571694 -0.5498938, + 0.84809691 -0.16127498 -0.50469995, + 0.85234886 -0.14392598 -0.50277895, + 0.88025826 -0.13058503 -0.45617211, + 0.88329309 -0.11574002 -0.45431006, + 0.90771312 -0.10358602 -0.40660405, + 0.90850031 -0.10618503 -0.40416816, + 0.92816633 -0.09456864 -0.35995013, + 0.93118298 -0.074248001 -0.356911, + 0.94953251 -0.063884571 -0.30709386, + 0.95117778 -0.047630988 -0.30494595, + 0.96579379 -0.040017787 -0.25620493, + 0.96657836 -0.02761481 -0.2548801, + 0.97806013 -0.022439202 -0.20711103, + 0.97837454 -0.013227694 -0.20641789, + 0.98718053 -0.010207196 -0.15928093, + 0.98725152 -0.0052097277 -0.15908292, + 0.99279678 -0.0010637097 -0.11980597, + 0.9927544 -0.0010717295 -0.12015592, + 0.99277222 -0.0010787002 -0.12000903, + 0.99277252 -0.00070021168 -0.12000894, + 0.99275476 -0.00070009485 -0.12015597, + 0.99279714 -0.00070818805 -0.11980601, + 0.98568887 0.0017050197 -0.16856599, + 0.98379266 0.0034828188 -0.17927594, + 0.98569661 0.0050809183 -0.16845293, + 0.97624213 -0.00046378205 -0.21668203, + 0.97623736 -0.0029668813 -0.21668407, + 0.97627574 -0.0029628193 -0.21651095, + 0.97628033 -0.00046327917 -0.21651007, + 0.97623575 -0.00046311889 -0.21671095, + 0.96444523 0.0012190603 -0.26428005, + 0.96443689 -0.0040763696 -0.26428196, + 0.96440452 -0.0040791882 -0.26439989, + 0.96439701 0.0060791401 -0.26438901, + 0.95032448 -0.00015811507 -0.31126115, + 0.95031023 -0.0051962612 -0.31126106, + 0.95032865 -0.0051948782 -0.31120488, + 0.95034277 -0.00015689195 -0.31120494, + 0.95028222 -0.00015674304 -0.31139007, + 0.93392015 0.00080536009 -0.35748103, + 0.93389821 0.00081317715 -0.3575381, + 0.93387765 -0.0064352378 -0.35753489, + 0.92002302 -0.01231 -0.391671, + 0.9195196 -0.027400287 -0.39208782, + 0.89816588 -0.030649897 -0.43858695, + 0.89666909 -0.052074607 -0.43962806, + 0.87519878 -0.056904685 -0.48040488, + 0.0073565361 -0.75284064 -0.6581617, + 0.0058045494 -0.75284791 -0.65816891, + 0.0069712289 -0.72080392 -0.69310397, + 0.021966701 -0.72064704 -0.69295406, + 0.024394806 -0.69719017 -0.7164712, + 0.042669702 -0.69676208 -0.71603209, + 0.046733417 -0.67186123 -0.73920125, + 0.068107694 -0.67103493 -0.73829097, + 0.073768817 -0.64481318 -0.76077217, + 0.099004686 -0.64339793 -0.75910288, + 0.10615095 -0.61600971 -0.78055364, + 0.13432795 -0.61389476 -0.77787471, + 0.14282493 -0.5854457 -0.79803163, + 0.17442004 -0.58244312 -0.79393816, + 0.18417694 -0.55270785 -0.8127687, + 0.21902393 -0.54867381 -0.80683672, + 0.22966693 -0.51825088 -0.8238138, + 0.26761416 -0.51306331 -0.81556648, + 0.27902192 -0.48168981 -0.83073568, + 0.3191759 -0.47537488 -0.81984484, + 0.33093387 -0.44355285 -0.83291268, + 0.37286893 -0.43613991 -0.81899381, + 0.38468406 -0.40403706 -0.82992309, + 0.42835507 -0.39552906 -0.81244612, + 0.4395428 -0.36440983 -0.8209796, + 0.48408794 -0.35499597 -0.79977286, + 0.49459311 -0.3245711 -0.80624521, + 0.53883481 -0.31459489 -0.7814647, + 0.54826808 -0.28564304 -0.78600913, + 0.59164798 -0.275361 -0.75771302, + 0.59991604 -0.24798903 -0.7606591, + 0.64223319 -0.23758806 -0.72875816, + 0.64927328 -0.21198511 -0.73041534, + 0.69000864 -0.20174091 -0.69511765, + 0.69582278 -0.17803794 -0.69579679, + 0.73395795 -0.16836599 -0.65799594, + 0.73861718 -0.14664303 -0.65798217, + 0.77402014 -0.13773201 -0.61799908, + 0.77762514 -0.11804602 -0.61754704, + 0.8103748 -0.11000797 -0.57549191, + 0.81301415 -0.092656925 -0.57482409, + 0.8430714 -0.085584536 -0.53094822, + 0.84491891 -0.070485793 -0.53022993, + 0.87133271 -0.064660981 -0.48641381, + 0.86990315 -0.077094704 -0.48716006, + 0.84251529 -0.084198929 -0.53205121, + 0.84023857 -0.10001095 -0.53291374, + 0.8096543 -0.10825404 -0.57683718, + 0.80647564 -0.12636694 -0.57760572, + 0.77311116 -0.13555902 -0.61961514, + 0.76889116 -0.15582404 -0.62010109, + 0.73287737 -0.16581208 -0.65984631, + 0.72750467 -0.18811391 -0.65981072, + 0.68874174 -0.19878092 -0.69722378, + 0.6821 -0.223125 -0.69638699, + 0.64078718 -0.23424906 -0.73110819, + 0.63279682 -0.26057595 -0.72915584, + 0.59003991 -0.27170095 -0.76028383, + 0.58075482 -0.29974389 -0.75688672, + 0.53704292 -0.31059796 -0.78429186, + 0.5264678 -0.34035489 -0.77909571, + 0.48211995 -0.35072798 -0.80283886, + 0.470514 -0.381666 -0.79558003, + 0.426305 -0.39126301 -0.815584, + 0.41384494 -0.42331395 -0.8059389, + 0.3707138 -0.43186975 -0.82222855, + 0.35807988 -0.46373183 -0.8103897, + 0.31686884 -0.47107175 -0.82321656, + 0.30427796 -0.50279194 -0.80908287, + 0.26522696 -0.50891596 -0.8189379, + 0.25309113 -0.54008126 -0.80265635, + 0.21672797 -0.54498792 -0.80994886, + 0.20539297 -0.57534492 -0.79170185, + 0.17215501 -0.57910204 -0.79687113, + 0.1620421 -0.60805035 -0.7771855, + 0.13203593 -0.61079967 -0.78069854, + 0.123097 -0.63893598 -0.75934702, + 0.096896984 -0.64080292 -0.76156586, + 0.08942537 -0.66775876 -0.73898679, + 0.066265635 -0.66897142 -0.74032843, + 0.060448691 -0.69436991 -0.71707493, + 0.040991973 -0.69505757 -0.71778458, + 0.036804795 -0.71922195 -0.69380492, + 0.020780908 -0.71955425 -0.69412524, + 0.017133703 -0.75240219 -0.65848118, + 0.0049556405 -0.7525031 -0.65857005, + 0.0033565483 -0.79215962 -0.61030471, + -0.0034024001 -0.79215997 -0.610304, + -0.0046035093 -0.76276189 -0.64666295, + -0.014861302 -0.76268613 -0.64659804, + -0.017365294 -0.74114275 -0.67112279, + -0.031097285 -0.74089664 -0.67089868, + -0.035319891 -0.71789885 -0.69525081, + -0.052435093 -0.71735793 -0.69472891, + -0.058339715 -0.69305819 -0.71851718, + -0.078950696 -0.69207293 -0.71749693, + -0.086772628 -0.66553521 -0.74130523, + -0.11102601 -0.66392404 -0.73951209, + -0.12032098 -0.63640392 -0.7619139, + -0.14791697 -0.63400984 -0.75904679, + -0.15866196 -0.60517991 -0.78011781, + -0.19030297 -0.60174292 -0.77568686, + -0.20224197 -0.57179195 -0.79507989, + -0.23703803 -0.56721705 -0.78871912, + -0.24996603 -0.53619206 -0.80623513, + -0.28770208 -0.5303582 -0.7974633, + -0.30124104 -0.49855906 -0.81283009, + -0.34149602 -0.49141407 -0.80118209, + -0.35514897 -0.45941094 -0.81413186, + -0.39767492 -0.45091689 -0.79907984, + -0.41122708 -0.41863108 -0.80971617, + -0.45536 -0.40888199 -0.79086202, + -0.46830705 -0.37697905 -0.7991091, + -0.51257306 -0.36634603 -0.77656913, + -0.5244118 -0.33568788 -0.78249973, + -0.56849772 -0.32434186 -0.75605065, + -0.57896501 -0.29536 -0.75997502, + -0.62221795 -0.28358296 -0.72967494, + -0.63126725 -0.25637609 -0.73196524, + -0.67311406 -0.24446604 -0.69796407, + -0.68064421 -0.21947907 -0.69896525, + -0.72015584 -0.20785396 -0.66194582, + -0.72627193 -0.18503399 -0.66203594, + -0.76300919 -0.17399204 -0.6225301, + -0.76781601 -0.15344299 -0.622024, + -0.80186033 -0.14310607 -0.58012128, + -0.80552173 -0.12478796 -0.57927781, + -0.83673012 -0.11532202 -0.53533506, + -0.83914798 -0.100885 -0.53446501, + -0.80944633 -0.10891605 -0.57700431, + -0.80630612 -0.12674302 -0.57776004, + -0.77294517 -0.13595203 -0.61973614, + -0.76879734 -0.15585208 -0.62021029, + -0.73277175 -0.16583894 -0.65995675, + -0.72745466 -0.18791391 -0.65992272, + -0.68860304 -0.19859003 -0.69741505, + -0.68200576 -0.22276393 -0.69659477, + -0.64072526 -0.23385909 -0.73128724, + -0.63279408 -0.26002204 -0.72935605, + -0.58995688 -0.27114195 -0.76054782, + -0.58063787 -0.29929793 -0.7571528, + -0.536865 -0.31014499 -0.78459299, + -0.52626806 -0.33996904 -0.7793991, + -0.48195699 -0.350315 -0.80311698, + -0.47029695 -0.38142094 -0.7958259, + -0.4258242 -0.39105818 -0.81593341, + -0.41333693 -0.42314395 -0.8062889, + -0.37029117 -0.43166521 -0.8225264, + -0.35744202 -0.46405205 -0.8104881, + -0.31635019 -0.47135928 -0.82325149, + -0.30370197 -0.50321895 -0.80903387, + -0.26450488 -0.50935477 -0.81889856, + -0.25238696 -0.54044092 -0.80263591, + -0.21586592 -0.54535383 -0.80993271, + -0.20457298 -0.57554895 -0.79176587, + -0.17135501 -0.57928705 -0.79690909, + -0.16105694 -0.60870874 -0.77687472, + -0.13155694 -0.61139971 -0.78030962, + -0.122628 -0.63950002 -0.75894803, + -0.096306957 -0.64136738 -0.7611655, + -0.08888571 -0.66810703 -0.73873705, + -0.066060424 -0.66929722 -0.74005222, + -0.060158279 -0.69506174 -0.71642876, + -0.041076373 -0.69573557 -0.71712255, + -0.036960002 -0.71953106 -0.69347608, + -0.020771703 -0.71986705 -0.69380105, + -0.018336404 -0.7420162 -0.67013121, + -0.0062289322 -0.74212623 -0.67023122, + -0.0069962093 -0.72084796 -0.69305795, + -0.021670707 -0.72069526 -0.69291323, + -0.024094896 -0.69735694 -0.71631896, + -0.042259105 -0.69693607 -0.71588707, + -0.046315577 -0.67211968 -0.73899263, + -0.067842282 -0.67129183 -0.73808181, + -0.073449798 -0.64530599 -0.76038498, + -0.098376215 -0.64391506 -0.75874615, + -0.10552198 -0.61656195 -0.78020287, + -0.13381502 -0.61444706 -0.77752709, + -0.14232701 -0.58594906 -0.79775113, + -0.17384695 -0.58296084 -0.79368371, + -0.18355501 -0.55337697 -0.81245399, + -0.21835998 -0.54935694 -0.80655187, + -0.22916791 -0.51846385 -0.82381868, + -0.26679295 -0.5133329 -0.81566584, + -0.27826893 -0.48182487 -0.83090985, + -0.318573 -0.475503 -0.820005, + -0.33039698 -0.44351894 -0.83314389, + -0.37252283 -0.43608478 -0.81918061, + -0.38434783 -0.40394083 -0.83012557, + -0.427937 -0.39546201 -0.81269902, + -0.43928799 -0.36388901 -0.821347, + -0.48388094 -0.35448697 -0.80012387, + -0.49437013 -0.32410309 -0.80657017, + -0.53865498 -0.31413901 -0.78177202, + -0.54811388 -0.28509694 -0.78631485, + -0.59157312 -0.27481905 -0.75796819, + -0.59980792 -0.24754797 -0.76088786, + -0.64215583 -0.23716295 -0.72896481, + -0.64915198 -0.21172 -0.7306, + -0.68985015 -0.20150304 -0.69534415, + -0.69560397 -0.17808698 -0.69600296, + -0.73385292 -0.16838999 -0.65810692, + -0.73843724 -0.14703706 -0.65809625, + -0.7738483 -0.13810804 -0.61813027, + -0.77739668 -0.11877996 -0.61769378, + -0.81017911 -0.11069302 -0.57563609, + -0.81279713 -0.093558304 -0.57498509, + -0.84288961 -0.086417757 -0.53110176, + -0.84460831 -0.072514124 -0.53045118, + -0.81559682 -0.078370079 -0.57328886, + -0.81342679 -0.095048778 -0.5738489, + -0.78117788 -0.10201699 -0.61591697, + -0.77820712 -0.12066201 -0.61630708, + -0.74332702 -0.128525 -0.65646499, + -0.73940325 -0.14925106 -0.65651125, + -0.70178896 -0.15792398 -0.69465995, + -0.69678593 -0.18076499 -0.69412792, + -0.65664119 -0.19007005 -0.72986019, + -0.65052497 -0.214792 -0.72847903, + -0.60867709 -0.22438803 -0.7610271, + -0.60138494 -0.25102898 -0.75849891, + -0.55820608 -0.26068804 -0.7876851, + -0.54984009 -0.28883505 -0.78374118, + -0.505665 -0.29833099 -0.80950701, + -0.49624819 -0.32806513 -0.8038103, + -0.45147413 -0.33717209 -0.82612717, + -0.44127995 -0.36793897 -0.81846988, + -0.39722207 -0.37628505 -0.83703309, + -0.38643205 -0.40798905 -0.82717311, + -0.34371096 -0.41540194 -0.84220189, + -0.33264697 -0.44765294 -0.83003187, + -0.29134291 -0.45409384 -0.84197271, + -0.28058296 -0.48581094 -0.82780486, + -0.24165194 -0.49114287 -0.83688885, + -0.23150498 -0.52219695 -0.82080185, + -0.1950011 -0.52647525 -0.82752544, + -0.18573509 -0.55659425 -0.80975634, + -0.15247796 -0.55982786 -0.81445885, + -0.14436898 -0.58872086 -0.79533982, + -0.11419597 -0.59106189 -0.79850185, + -0.10736198 -0.61885089 -0.77813685, + -0.080432981 -0.6204319 -0.78012484, + -0.075011007 -0.64707905 -0.75872409, + -0.051617119 -0.64804226 -0.7598533, + -0.047688693 -0.67354095 -0.73760992, + -0.027296597 -0.67405695 -0.73817492, + -0.024935504 -0.69815004 -0.71551704, + -0.0079813246 -0.69834441 -0.71571743, + -0.0072069126 -0.72102922 -0.69286722, + 0.0072324458 -0.72102958 -0.69286656, + 0.0080108009 -0.69825208 -0.71580708, + 0.025308011 -0.69805038 -0.71560138, + 0.027692292 -0.67365181 -0.7385298, + 0.047963288 -0.67313582 -0.73796183, + 0.051862594 -0.64785296 -0.7599979, + 0.075579397 -0.64687097 -0.75884497, + 0.081005365 -0.62018669 -0.78026062, + 0.10821505 -0.6185773 -0.77823633, + 0.11502997 -0.5908069 -0.79857081, + 0.14504799 -0.58846593 -0.79540485, + 0.15320297 -0.55938387 -0.81462783, + 0.18649904 -0.55613512 -0.80989617, + 0.19567603 -0.52628505 -0.82748711, + 0.23202007 -0.52201509 -0.82077217, + 0.24213491 -0.49108082 -0.83678567, + 0.28134999 -0.48569599 -0.82761198, + 0.29204696 -0.45411593 -0.84171689, + 0.33318388 -0.44768584 -0.8297987, + 0.34411687 -0.41580984 -0.84183472, + 0.38691205 -0.40836507 -0.82676309, + 0.39765993 -0.37676293 -0.8366099, + 0.44152206 -0.36843503 -0.81811613, + 0.45174295 -0.33759397 -0.82580787, + 0.49644807 -0.32848102 -0.8035171, + 0.50583702 -0.29884201 -0.80921102, + 0.5499711 -0.28933406 -0.78346521, + 0.5583899 -0.26101094 -0.78744781, + 0.60144424 -0.2513631 -0.75834131, + 0.60877705 -0.22459503 -0.76088613, + 0.6506142 -0.21498905 -0.72834116, + 0.65679777 -0.18999892 -0.72973776, + 0.69698799 -0.18068001 -0.69394702, + 0.70203274 -0.15760595 -0.69448578, + 0.73962098 -0.148947 -0.656335, + 0.74361902 -0.127753 -0.65628499, + 0.77843899 -0.119941 -0.61615503, + 0.78143013 -0.10108201 -0.61575109, + 0.81365317 -0.094174422 -0.57367212, + 0.81579489 -0.077626795 -0.57310796, + 0.84541351 -0.071690343 -0.52927929, + 0.84687287 -0.057285294 -0.52870095, + 0.87345088 -0.052450594 -0.48407894, + 0.8747741 -0.034391705 -0.48330906, + 0.89859813 -0.031143704 -0.43766606, + 0.89923722 -0.013664103 -0.43724808, + 0.91501403 -0.0079331798 -0.40334401, + 0.9150449 0.00022082197 -0.40335193, + 0.91526777 0.00022042094 -0.40284592, + 0.91523713 -0.0078566512 -0.40283906, + 0.91521823 -0.007857752 -0.4028821, + 0.91524887 0.00021890397 -0.40288895, + 0.92631376 0.0042558792 -0.37672892, + 0.66015768 0.0030902587 0.75112063, + 0.65191585 0.0043570292 0.75827885, + 0.65186495 0.012810598 0.75822687, + 0.68804681 0.012014598 0.7255668, + 0.68810201 -0.00119683 0.725613, + 0.68819594 -0.0011967599 0.72552395, + 0.72253263 0.0004146038 0.69133663, + 0.72287381 0.00043397889 0.69097984, + 0.99966425 0.0029878807 0.025741106, + 0.73387474 0.0033320589 0.67927676, + 0.75590116 -0.00091023423 0.6546852, + 0.75584209 0.012002301 0.65464407, + 0.7558257 0.012002695 0.65466279, + 0.75588489 -0.00090743089 0.65470392, + 0.75596619 -0.00090735621 0.65461016, + 0.75592548 0.0098718852 0.65458339, + 0.7869789 0.011807499 0.61686695, + 0.78703833 5.2319119e-006 0.61690426, + 0.78709573 9.0400763e-006 0.61683077, + 0.78703612 0.011806302 0.61679405, + 0.79200703 0.0092461202 0.61044198, + 0.79123199 0.030778799 0.61074102, + 0.82113332 0.028726311 0.57001317, + 0.82234102 0.00853715 0.56893098, + 0.82162344 0.029026613 0.56929129, + 0.84947711 0.026867203 0.52694106, + 0.86902684 -9.1977781e-005 0.49476489, + 0.86905813 -9.9242017e-005 0.49471006, + 0.86900258 0.010884695 0.49468777, + 0.86897182 0.010885597 0.49474189, + 0.85055882 0.007603528 0.5258249, + 0.84990382 0.027151695 0.52623791, + 0.87527227 0.02492011 0.48298818, + 0.87417167 0.042028487 0.48379481, + 0.89707178 0.038243592 0.44022688, + 0.89556015 0.054872908 0.44154406, + 0.91630721 0.04938931 0.3974191, + 0.91448557 0.065486774 0.39928383, + 0.93327039 0.058131725 0.35443917, + 0.93130022 0.073275812 0.3568061, + 0.94803977 0.064001784 0.31164795, + 0.94604313 0.07811711 0.31448403, + 0.96090311 0.066749305 0.26871902, + 0.95898664 0.079855368 0.27196991, + 0.97207701 0.066110298 0.22515699, + 0.97035313 0.078110211 0.22872204, + 0.98171949 0.061512228 0.1801201, + 0.98033035 0.072000623 0.18376206, + 0.98967248 0.052294627 0.13346806, + 0.98870754 0.060934972 0.13690995, + 0.99577624 0.037333108 0.083880723, + 0.99529076 0.043480787 0.086635478, + 0.99945927 0.014749303 0.029387908, + 0.99938166 0.017258994 0.030631788, + 0.99934089 -0.017818999 -0.031625897, + 0.99930286 -0.018888798 -0.032202195, + 0.99306524 -0.059482016 -0.10140702, + 0.99344426 -0.056236014 -0.09952902, + 0.97980112 -0.098373018 -0.17410502, + 0.98063737 -0.094337739 -0.17161205, + 0.95710546 -0.13957606 -0.25390512, + 0.95818621 -0.13616003 -0.25167406, + 0.92055076 -0.18587495 -0.3435649, + 0.92412764 -0.17790894 -0.33813688, + 0.88068324 -0.22057106 -0.41922009, + 0.88343209 -0.21568303 -0.41596705, + 0.83056718 -0.25635505 -0.49440911, + 0.83289117 -0.25294906 -0.49224913, + 0.77124888 -0.29092798 -0.56615895, + 0.77269191 -0.28913498 -0.56510895, + 0.70376498 -0.323594 -0.63245702, + 0.70383066 -0.32352185 -0.63242072, + 0.63041598 -0.353531 -0.69107997, + 0.62868196 -0.35519698 -0.69180495, + 0.553325 -0.38045701 -0.74100202, + 0.55006909 -0.38330808 -0.74195617, + 0.47521076 -0.40384883 -0.78171664, + 0.47132194 -0.40702394 -0.78242385, + 0.39950305 -0.42307106 -0.81327009, + 0.38850677 -0.43159974 -0.81411552, + 0.32248002 -0.44337007 -0.83631915, + 0.33384201 -0.43468899 -0.83641797, + 0.272212 -0.44373101 -0.85381699, + 0.29000309 -0.42981315 -0.85507828, + 0.23159306 -0.4369041 -0.86918318, + 0.24185807 -0.42856508 -0.87053818, + 0.18744999 -0.43384793 -0.88127089, + 0.19270504 -0.42938006 -0.88232511, + 0.14333104 -0.4330641 -0.88989425, + 0.14451003 -0.43200508 -0.89021826, + 0.10057504 -0.43437314 -0.8951003, + 0.099189401 -0.43570599 -0.89460701, + 0.061137464 -0.43704674 -0.89735848, + 0.058187384 -0.44012389 -0.89604974, + 0.026298495 -0.44071889 -0.89725977, + 0.023164293 -0.44432184 -0.89556772, + -0.0025258902 -0.44444007 -0.89580512, + -0.0048672808 -0.44745311 -0.89429426, + -0.024622999 -0.44732201 -0.89403403, + -0.025622409 -0.44878516 -0.89327228, + -0.039910905 -0.44857407 -0.89285409, + -0.03946761 -0.44782412 -0.89325023, + -0.048685506 -0.44764104 -0.89288712, + -0.046722285 -0.44371584 -0.89494872, + -0.051712811 -0.44360712 -0.89472824, + -0.048275724 -0.43531621 -0.89898241, + -0.049818911 -0.43528309 -0.89891422, + -0.046228684 -0.42456886 -0.90421468, + -0.037233982 -0.42472878 -0.90455461, + -0.043164399 -0.44667801 -0.89365298, + -0.044031605 -0.44666106 -0.89361912, + -0.047824591 -0.45760995 -0.8878659, + -0.045642484 -0.45765686 -0.88795668, + -0.048602622 -0.46457621 -0.88419843, + -0.042681098 -0.46470195 -0.88443786, + -0.04469841 -0.46862212 -0.88226724, + -0.034458824 -0.46881226 -0.88262552, + -0.035378806 -0.47033012 -0.88178122, + -0.020286698 -0.47052795 -0.8821519, + -0.020082893 -0.47023681 -0.8823117, + 0.00019975402 -0.47033107 -0.8824901, + 0.0012521701 -0.46900606 -0.88319415, + 0.027019609 -0.46883518 -0.88287228, + 0.028220214 -0.4674812 -0.88355243, + 0.059616607 -0.46683607 -0.88233215, + 0.059969485 -0.46647388 -0.88249975, + 0.096813284 -0.46511993 -0.87993789, + 0.095482185 -0.46637493 -0.87941891, + 0.13750997 -0.46406487 -0.87506276, + 0.13309099 -0.46794993 -0.87367588, + 0.17986399 -0.46444994 -0.8671419, + 0.17136702 -0.47148806 -0.86506212, + 0.22260703 -0.46655905 -0.85601914, + 0.20752203 -0.47841606 -0.8532601, + 0.26219207 -0.47195411 -0.84173316, + 0.25302693 -0.47888488 -0.84062284, + 0.31219798 -0.47025195 -0.82546687, + 0.323006 -0.462102 -0.82591099, + 0.38928792 -0.44975787 -0.8038488, + 0.39344394 -0.44652995 -0.80362487, + 0.46514487 -0.42996091 -0.77380484, + 0.46948701 -0.42642099 -0.77314103, + 0.54425788 -0.4051609 -0.73459381, + 0.54720271 -0.40258375 -0.73382258, + 0.62282568 -0.37630281 -0.68591869, + 0.62396222 -0.37521014 -0.68548423, + 0.69791198 -0.343871 -0.62822902, + 0.69726682 -0.34456691 -0.62856382, + 0.76711512 -0.30837002 -0.56253207, + 0.7650587 -0.31092089 -0.56392682, + 0.82793415 -0.27078104 -0.49112406, + 0.82485032 -0.27528408 -0.49380219, + 0.87921202 -0.231987 -0.41613501, + 0.87470913 -0.23991403 -0.42110005, + 0.92599088 -0.18689598 -0.32804096, + 0.92529839 -0.18853909 -0.32905316, + 0.95982635 -0.13949804 -0.24346209, + 0.95866847 -0.14337307 -0.24576212, + 0.98093677 -0.097921677 -0.16785195, + 0.98007113 -0.10226502 -0.17030102, + 0.99339062 -0.059091277 -0.098403566, + 0.99379897 -0.055371501 -0.096423797, + 0.99936664 -0.017720794 -0.030859089, + 0.99944866 -0.015108595 -0.029564388, + 0.99947786 0.014703898 0.028772496, + 0.99953353 0.012598295 0.027818987, + 0.99590278 0.037305593 0.08237648, + 0.99626613 0.031958103 0.080203705, + 0.98994088 0.052370593 0.13143198, + 0.99068153 0.044654977 0.12866995, + 0.98212337 0.061717421 0.17783307, + 0.98320687 0.052166391 0.17487998, + 0.97260952 0.066444568 0.2227459, + 0.97394812 0.055459909 0.21988504, + 0.96152747 0.067183733 0.26636711, + 0.96302027 0.054970216 0.26376206, + 0.94871676 0.064497888 0.30947796, + 0.95026463 0.051099982 0.30722287, + 0.93394965 0.058641177 0.35256088, + 0.9354319 0.044181697 0.35073498, + 0.91694415 0.049869508 0.39588705, + 0.91821611 0.034711402 0.39455605, + 0.89759344 0.038632717 0.43912822, + 0.89854378 0.022901794 0.43828589, + 0.87565625 0.025200406 0.48227713, + 0.87624198 0.00674965 0.48182401, + 0.89213371 0.010314397 0.45165384, + 0.8921839 -0.00061240897 0.45167193, + 0.89226079 -0.0006122858 0.45151988, + 0.89220989 0.010327199 0.45150295, + 0.89220124 0.010327603 0.45152012, + 0.89225173 -0.00061301177 0.45153785, + 0.90569532 0.0035861114 0.42391413, + 0.85730779 0.0035662791 0.51479191, + 0.84373617 -0.00033978908 0.53675812, + 0.84367782 0.011354798 0.53672987, + 0.8436929 0.011354399 0.53670591, + 0.81645221 0.0076743118 0.57736212, + 0.81647891 -0.00053884793 0.57737494, + 0.81638485 -0.00053895294 0.57750791, + 0.81632572 0.011620896 0.57747483, + 0.81635112 0.011620201 0.57743907, + 0.81641018 -0.00054393912 0.57747209, + 0.79983413 0.0034821904 0.60021108, + 0.9917171 0.0030721605 0.12840502, + 0.97325909 0.0029726205 0.22969103, + 0.94448388 0.0027979198 0.32854596, + 0.94883925 0.0010122502 0.31575808, + 0.94880462 0.008398097 0.31575188, + 0.94877625 0.0083997715 0.31583709, + 0.93853891 0.0044393195 0.34514496, + 0.93818766 0.018801592 0.34561589, + 0.95392764 0.016297894 0.2995939, + 0.95342809 0.027523104 0.30036202, + 0.96680588 0.023315698 0.25444597, + 0.96621102 0.033578198 0.25555599, + 0.9774155 0.027530087 0.2095259, + 0.97682035 0.036662616 0.21089807, + 0.98599422 0.028564608 0.16431504, + 0.98549837 0.036156513 0.16578805, + 0.99256015 0.025943603 0.11895902, + 0.99222052 0.031816684 0.12035794, + 0.9971621 0.019240601 0.072784111, + 0.99699867 0.023126392 0.073883772, + 0.9996649 0.0077323392 0.024703296, + 0.99964088 0.0091833789 0.025176996, + 0.99962854 -0.0093393056 -0.025604486, + 0.99959576 -0.010998297 -0.026215794, + 0.99613166 -0.03399539 -0.08103177, + 0.99571741 -0.039860677 -0.083414048, + 0.98746026 -0.068067513 -0.14244004, + 0.985816 -0.079868302 -0.147607, + 0.97053289 -0.11467499 -0.21193297, + 0.96579653 -0.13511094 -0.2213189, + 0.93992114 -0.17788501 -0.29138502, + 0.93456489 -0.19339597 -0.29864097, + 0.8960824 -0.24128112 -0.37258518, + 0.89651078 -0.24035494 -0.37215292, + 0.8447302 -0.29036105 -0.44957912, + 0.84215879 -0.29471195 -0.45156789, + 0.77297109 -0.34674904 -0.53130108, + 0.76404691 -0.35858098 -0.53633195, + 0.67342895 -0.41087794 -0.61455095, + 0.67653674 -0.40757185 -0.61333776, + 0.6007567 -0.4424518 -0.6658287, + 0.60232514 -0.44096011 -0.66540116, + 0.52616602 -0.469758 -0.70885599, + 0.52545178 -0.47037777 -0.70897466, + 0.45098007 -0.49343807 -0.74373108, + 0.44827101 -0.495626 -0.74391401, + 0.37750599 -0.51342899 -0.77063602, + 0.373503 -0.51650202 -0.77053303, + 0.30837801 -0.529661 -0.79016602, + 0.30365202 -0.53317904 -0.78963012, + 0.24500585 -0.54254568 -0.8035025, + 0.24050106 -0.54586613 -0.80261415, + 0.1884 -0.55230099 -0.81207699, + 0.18587501 -0.55418503 -0.81137514, + 0.14030196 -0.55843484 -0.81759769, + 0.13378698 -0.56343788 -0.81525379, + 0.095400818 -0.56595606 -0.81889713, + 0.100749 -0.56162798 -0.82123297, + 0.066657692 -0.56324494 -0.82359689, + 0.076204017 -0.55489612 -0.82842219, + 0.045094602 -0.55594802 -0.82999301, + 0.0510897 -0.55021298 -0.83345997, + 0.023512805 -0.55078012 -0.83431917, + 0.027694508 -0.54636019 -0.83709228, + 0.003926022 -0.54656523 -0.83740741, + 0.0071090967 -0.54280978 -0.83982557, + -0.0127306 -0.54277903 -0.83977902, + -0.0098411161 -0.53892285 -0.84229767, + -0.025670003 -0.53877103 -0.8420611, + -0.022818398 -0.53439796 -0.84492487, + -0.034646794 -0.53421587 -0.84463781, + -0.03153079 -0.52862179 -0.84827173, + -0.039560802 -0.52847105 -0.84802914, + -0.036117099 -0.521079 -0.85274398, + -0.04055912 -0.52099025 -0.85259843, + -0.036919504 -0.51140207 -0.8585481, + -0.038069203 -0.51138008 -0.85851109, + -0.034489885 -0.49937776 -0.86569756, + -0.032598507 -0.49941012 -0.86575216, + -0.020577993 -0.51695579 -0.85576469, + -0.025723286 -0.5168947 -0.85566247, + -0.0149324 -0.600214 -0.79970002, + -0.022215907 -0.60013223 -0.79959232, + 0.014821006 -0.59997523 -0.79988128, + 0.022216694 -0.59989285 -0.79977185, + 0.015755802 -0.56349808 -0.82596713, + 0.014826504 -0.56350714 -0.82597816, + 0.010909298 -0.52431285 -0.85145581, + 0.005422438 -0.52433681 -0.85149372, + 0.0041064797 -0.48198494 -0.87616986, + -0.0038639782 -0.48198575 -0.87617058, + -0.0051616998 -0.52439898 -0.851457, + -0.010791404 -0.52437615 -0.85141832, + -0.014693802 -0.56364703 -0.82588512, + -0.015761605 -0.56363714 -0.82587218, + -0.017622001 -0.55899906 -0.8289811, + -0.023964096 -0.55892491 -0.82887191, + -0.017734794 -0.5216378 -0.8529827, + -0.015675198 -0.52165592 -0.85301191, + -0.011885403 -0.48106712 -0.87660325, + -0.0055006319 -0.48109317 -0.8766523, + -0.004250661 -0.4374181 -0.89924824, + 0.0043307412 -0.43741715 -0.8992483, + 0.0055992794 -0.48117095 -0.87660891, + 0.012152198 -0.48114294 -0.87655789, + 0.015941598 -0.52150893 -0.8530969, + 0.017861703 -0.52149212 -0.85306919, + 0.024101397 -0.55870092 -0.82901889, + 0.017680101 -0.55877608 -0.82913011, + -0.53251505 -0.52325106 -0.66530907, + -0.432356 -0.55742699 -0.70876199, + -0.42608204 -0.56239206 -0.70863909, + -0.356639 -0.58076602 -0.73179197, + -0.35533112 -0.58174419 -0.73165125, + -0.29187918 -0.59525937 -0.74864739, + -0.2893489 -0.59709477 -0.74816775, + -0.23231503 -0.60671103 -0.76021814, + -0.22969794 -0.60858786 -0.75951284, + -0.17904806 -0.61520225 -0.76776832, + -0.176962 -0.61671102 -0.76704103, + -0.13259096 -0.62106687 -0.77246082, + -0.13144305 -0.6219213 -0.77196938, + -0.093128271 -0.62463778 -0.77534169, + -0.092550397 -0.62508798 -0.77504802, + -0.0598698 -0.62665701 -0.77699202, + -0.058076184 -0.62813884 -0.77593082, + -0.030817188 -0.62890178 -0.77687371, + -0.028124597 -0.63129592 -0.77503186, + -0.0063319709 -0.63153309 -0.77532309, + -0.013212398 -0.62480396 -0.78066987, + 0.0057480671 -0.62484872 -0.78072464, + -0.0015851103 -0.61680412 -0.78711516, + 0.015127704 -0.61673415 -0.78702617, + 0.0092373323 -0.60940909 -0.79280216, + 0.023319893 -0.60926878 -0.79262072, + 0.018041208 -0.60172927 -0.79849637, + 0.029360296 -0.60156792 -0.79828191, + 0.024583001 -0.59359699 -0.80438697, + 0.033060804 -0.59345204 -0.8041901, + 0.028568393 -0.58452487 -0.81087279, + 0.034139391 -0.58442289 -0.81073081, + 0.029929092 -0.5742029 -0.81816584, + 0.032615609 -0.5741542 -0.81809729, + 0.028732304 -0.56222206 -0.82648712, + 0.022008089 -0.56231874 -0.82662761, + 0.027173504 -0.58299106 -0.81202412, + 0.027029287 -0.58299267 -0.81202763, + 0.031078288 -0.59511179 -0.8030417, + 0.028196108 -0.59516311 -0.80311018, + 0.03269051 -0.60580122 -0.79494429, + 0.027155694 -0.6059019 -0.79507583, + 0.032010894 -0.61531788 -0.78762883, + 0.023878297 -0.61545795 -0.78780788, + 0.029220104 -0.62416106 -0.78074914, + 0.018585108 -0.62431926 -0.78094828, + 0.024414504 -0.63244903 -0.77421713, + 0.011396001 -0.63259608 -0.77439815, + 0.018338298 -0.64101791 -0.76730686, + 0.0032123807 -0.64112216 -0.76743215, + 0.0099955024 -0.64837319 -0.76125717, + -0.0076009198 -0.64838701 -0.76127303, + -0.0082902405 -0.64772505 -0.76182914, + -0.030821597 -0.64743996 -0.76149291, + -0.031067114 -0.64722431 -0.76166636, + -0.058412109 -0.64643109 -0.76073313, + -0.057863809 -0.64687806 -0.76039511, + -0.090119004 -0.64532703 -0.7585721, + -0.090245873 -0.64522976 -0.75863969, + -0.128039 -0.64254099 -0.75547802, + -0.12926804 -0.64164019 -0.7560342, + -0.17306606 -0.63730526 -0.75092632, + -0.17510594 -0.63584977 -0.75168669, + -0.22515804 -0.62924504 -0.74387807, + -0.22752392 -0.62756777 -0.74457479, + -0.28392804 -0.61794806 -0.73316103, + -0.285505 -0.616817 -0.73350102, + -0.348369 -0.60328901 -0.71741301, + -0.35538799 -0.59806699 -0.71834201, + -0.42420909 -0.57941312 -0.6959362, + -0.46090007 -0.54950005 -0.69686508, + -0.5322001 -0.52421612 -0.66480118, + -0.56341231 -0.49496523 -0.66149527, + -0.6520822 -0.45421013 -0.60702711, + -0.6692403 -0.43455121 -0.60272932, + -0.7434212 -0.3911441 -0.54252315, + -0.75198591 -0.37924793 -0.53915495, + -0.8126452 -0.3352811 -0.47664911, + -0.82359791 -0.31662497 -0.47056895, + -0.88030672 -0.26483691 -0.39360085, + -0.96772778 0.0018995395 0.25199094, + -0.96751398 0.013865 0.252437, + -0.97842866 0.011329496 0.20627393, + -0.97816163 0.019692393 0.20691092, + -0.98690009 0.015285602 0.16060701, + -0.98664314 0.022039302 0.16139902, + -0.99320114 0.015750103 0.11534102, + -0.99301225 0.020848406 0.11615503, + -0.99747336 0.012550805 0.069925219, + -0.99737948 0.015844407 0.070591837, + -0.99971014 0.0052728807 0.023492305, + -0.99969625 0.0064683212 0.023785105, + -0.9996891 -0.0065429211 -0.024059303, + -0.99967015 -0.0078899506 -0.024444005, + -0.99687564 -0.024262391 -0.075167671, + -0.99663526 -0.028943608 -0.076683715, + -0.99025601 -0.049175899 -0.13028701, + -0.98933953 -0.058174375 -0.13350295, + -0.97807187 -0.083197691 -0.19092797, + -0.97556853 -0.098012954 -0.19661991, + -0.95745313 -0.12874801 -0.25827804, + -0.95157689 -0.15161099 -0.26742396, + -0.92418265 -0.18837292 -0.33226788, + -0.91174603 -0.221874 -0.34567499, + -0.87144297 -0.26494801 -0.412783, + -0.8595497 -0.28851891 -0.42181885, + -0.80519581 -0.33478791 -0.48946589, + -0.80067348 -0.34187922 -0.49197629, + -0.73181003 -0.38890505 -0.55964905, + -0.72075105 -0.40300906 -0.56400508, + -0.63564199 -0.448816 -0.628111, + -0.61310405 -0.47206405 -0.63345003, + -0.51160997 -0.51342303 -0.68895, + -0.50857913 -0.51601809 -0.68925518, + -0.43446508 -0.5397951 -0.7210142, + -0.433855 -0.54027897 -0.72101903, + -0.36391997 -0.55853695 -0.74538493, + -0.36164802 -0.56025404 -0.74520206, + -0.29759789 -0.57370085 -0.76308769, + -0.29477605 -0.57576913 -0.76262516, + -0.23713006 -0.58535612 -0.77532417, + -0.23445305 -0.58729714 -0.77467018, + -0.18319102 -0.59391207 -0.78339612, + -0.18114701 -0.59541005 -0.7827341, + -0.13620299 -0.59978491 -0.78848386, + -0.13445103 -0.60110611 -0.7877782, + -0.095734246 -0.6038273 -0.79134536, + -0.09240631 -0.60645103 -0.78973311, + -0.059720691 -0.60796994 -0.79171085, + -0.054872572 -0.61201572 -0.78893965, + -0.028341314 -0.61269331 -0.78981239, + -0.03536519 -0.60633475 -0.79442269, + -0.011981297 -0.60667086 -0.79486281, + -0.0198057 -0.598813 -0.80064398, + 0.0010408199 -0.59893095 -0.80079991, + -0.0048632976 -0.59228671 -0.80571264, + 0.013101898 -0.59224296 -0.80565286, + 0.0079602273 -0.58569175 -0.81049472, + 0.022961395 -0.58555585 -0.81030685, + 0.018456703 -0.57896811 -0.8151412, + 0.030270996 -0.57880092 -0.8149069, + 0.026045803 -0.57158107 -0.82013214, + 0.034646116 -0.57143128 -0.81991839, + 0.030582985 -0.56315571 -0.82578456, + 0.035986088 -0.5630548 -0.82563573, + 0.032040097 -0.55322593 -0.83241487, + 0.034352005 -0.55318308 -0.83235115, + 0.030595392 -0.54131991 -0.84025985, + 0.029953515 -0.54133022 -0.84027642, + 0.025018591 -0.52044481 -0.85352868, + 0.032577202 -0.52033103 -0.85334301, + 0.036213998 -0.53214896 -0.84587586, + 0.034421399 -0.53218198 -0.84592998, + 0.038166516 -0.54176319 -0.83966428, + 0.033083893 -0.54186088 -0.83981681, + 0.036772091 -0.54956585 -0.8346408, + 0.028299609 -0.54971719 -0.83487129, + 0.031892795 -0.55600792 -0.83056486, + 0.019857397 -0.55618095 -0.8308239, + 0.023548588 -0.56170774 -0.82700056, + 0.0079156999 -0.56184602 -0.82720399, + 0.011964601 -0.56712604 -0.82354414, + -0.0071745217 -0.5671531 -0.82358116, + -0.0021937802 -0.57289606 -0.81962514, + -0.024628 -0.57272297 -0.81937897, + -0.018606698 -0.57892996 -0.81516486, + -0.044249795 -0.57846391 -0.81450689, + -0.035723493 -0.58639687 -0.80923581, + -0.064084522 -0.58556521 -0.8080883, + -0.056781586 -0.59176689 -0.80410683, + -0.088632196 -0.59038997 -0.80223686, + -0.095833175 -0.58467185 -0.8055898, + -0.13459601 -0.58203101 -0.80194998, + -0.13943003 -0.57834715 -0.80378717, + -0.18488505 -0.57398319 -0.79772228, + -0.18761107 -0.57196319 -0.7985363, + -0.23947085 -0.56535965 -0.78931755, + -0.24214891 -0.56339681 -0.7899037, + -0.30039203 -0.55386007 -0.77653313, + -0.30330718 -0.55170435 -0.7769345, + -0.36789897 -0.53837293 -0.75815886, + -0.37053117 -0.53636622 -0.75829935, + -0.44088694 -0.51831692 -0.73277992, + -0.44254893 -0.51698494 -0.73271894, + -0.51686311 -0.49353412 -0.69948316, + -0.5165168 -0.49383181 -0.69952875, + -0.59293491 -0.46440387 -0.65784281, + -0.59341609 -0.46395013 -0.65772921, + -0.69137257 -0.41645476 -0.59039766, + -0.70635706 -0.39911705 -0.58460706, + -0.7850073 -0.34929112 -0.51162416, + -0.79097915 -0.34062704 -0.50825703, + -0.8520633 -0.2914111 -0.43481916, + -0.85362059 -0.28858685 -0.4336468, + -0.90041459 -0.24101788 -0.36216581, + -0.90843725 -0.22219506 -0.35407808, + -0.9416821 -0.17886502 -0.28503004, + -0.94990277 -0.15170597 -0.27325794, + -0.9713695 -0.11531595 -0.20770989, + -0.97480488 -0.097965285 -0.20039497, + -0.98780787 -0.068372294 -0.13985999, + -0.9890371 -0.058075309 -0.13576801, + -0.99623388 -0.034100197 -0.079719193, + -0.99655074 -0.028858092 -0.077806085, + -0.99963766 -0.0093608759 -0.025238492, + -0.99966288 -0.0078558894 -0.024746496, + -0.99967223 0.007746872 0.024403106, + -0.99969065 0.0064314376 0.024027491, + -0.99721575 0.019281596 0.072035082, + -0.99733979 0.015731197 0.071174487, + -0.99267274 0.026077595 0.11798597, + -0.99292737 0.020668607 0.11691105, + -0.98615879 0.028864993 0.16327195, + -0.98652023 0.021820806 0.16217804, + -0.97760665 0.028061491 0.20856093, + -0.97802186 0.019474298 0.20759097, + -0.96700966 0.023792891 0.2536259, + -0.96739697 0.0137003 0.25289401, + -0.9541201 0.016197301 0.29898602, + -0.95440453 0.0024967089 0.29850584, + -0.96402186 0.0061087892 0.26575297, + -0.96404111 -0.0008133091 0.26575202, + -0.96398813 -0.00081346213 0.26594403, + -0.96396887 0.0061044591 0.26594496, + -0.96400452 0.0061024772 0.26581588, + -0.96402347 -0.00081156142 0.26581612, + -0.97589475 0.0049298485 0.21818596, + -0.97589254 0.0053896271 0.21818489, + -0.97588545 0.0053901128 0.2182171, + -0.97589946 0.0012886206 0.2182171, + -0.98542351 -0.0009092784 0.17011708, + -0.98541254 0.0046265875 0.17011993, + -0.97865838 0.0014123805 0.20548907, + -0.97851002 0.0114702 0.20588, + -0.98715001 0.0088889403 0.159549, + -0.9869855 0.015456907 0.16006507, + -0.99339825 0.011026403 0.11418603, + -0.99326438 0.015906205 0.11477304, + -0.99757373 0.009556978 0.068959385, + -0.99750423 0.012658403 0.069462717, + -0.9997251 0.0042037903 0.023068301, + -0.99971449 0.0053109778 0.023294289, + -0.99970925 -0.0053606015 -0.023512006, + -0.99969488 -0.006581529 -0.023810396, + -0.99712354 -0.020193091 -0.073053963, + -0.99694264 -0.024375191 -0.074237272, + -0.991189 -0.041320302 -0.125845, + -0.99049515 -0.049347408 -0.12839101, + -0.9805479 -0.070418291 -0.18321298, + -0.97868079 -0.083393581 -0.18769495, + -0.96301633 -0.10940204 -0.24623309, + -0.95874637 -0.12890804 -0.2533541, + -0.93554914 -0.16016802 -0.31479204, + -0.92664587 -0.18843397 -0.32529998, + -0.89317697 -0.22541 -0.38913399, + -0.87963891 -0.25666296 -0.40044895, + -0.83928388 -0.29338497 -0.45774195, + -0.82382011 -0.32166103 -0.46674907, + -0.77548599 -0.35826901 -0.51986998, + -0.76086313 -0.38045207 -0.52568406, + -0.69596303 -0.421004 -0.58171397, + -0.68251592 -0.43790793 -0.58515692, + -0.605124 -0.47701001 -0.63740599, + -0.58141088 -0.5018869 -0.64036781, + -0.49171212 -0.53713912 -0.6853472, + -0.45421594 -0.56970793 -0.68492395, + -0.386776 -0.58971202 -0.708974, + -0.34736517 -0.61991328 -0.70359439, + -0.28510299 -0.63364202 -0.71917599, + -0.27788696 -0.63877791 -0.71745497, + -0.22217208 -0.64834923 -0.72820526, + -0.22063994 -0.64941984 -0.7277168, + -0.17120194 -0.65599877 -0.73508877, + -0.16935907 -0.6572963 -0.73435634, + -0.12611598 -0.66160494 -0.73917097, + -0.124919 -0.66246903 -0.73860002, + -0.087649778 -0.66512984 -0.74156582, + -0.087400258 -0.66531771 -0.74142665, + -0.055576492 -0.66684192 -0.74312395, + -0.056548685 -0.66606182 -0.7437498, + -0.029514203 -0.66683906 -0.74461704, + -0.031220604 -0.66536504 -0.74586505, + -0.0086414833 -0.66566432 -0.74620134, + -0.0097543392 -0.66461092 -0.74712592, + 0.0085177589 -0.66461897 -0.74713391, + 0.0075009349 -0.66355342 -0.7480914, + 0.021472702 -0.66342008 -0.74793905, + 0.014782404 -0.65550619 -0.75504518, + 0.026515609 -0.65534723 -0.75486231, + 0.019891502 -0.64633304 -0.7627961, + 0.029664697 -0.64617693 -0.76261085, + 0.023963111 -0.6371063 -0.77040339, + 0.031565811 -0.63697225 -0.77024031, + 0.026318794 -0.62703681 -0.77854484, + 0.031627588 -0.62694079 -0.77842468, + 0.026907699 -0.61603898 -0.787256, + 0.029796597 -0.61598796 -0.78719187, + 0.025572991 -0.60366374 -0.79682869, + 0.019623499 -0.60374498 -0.79693598, + 0.024977716 -0.62408334 -0.78095847, + 0.012740999 -0.64026695 -0.76804686, + 0.020639 -0.64018202 -0.767946, + 0.013955996 -0.6044699 -0.79650581, + 0.013713704 -0.60447222 -0.79650831, + 0.0096692611 -0.56628609 -0.82415211, + 0.005036992 -0.56630516 -0.82418031, + 0.0036769181 -0.52525878 -0.85093457, + -0.0035335105 -0.52525908 -0.8509351, + -0.0048705284 -0.56637579 -0.82413268, + -0.009662101 -0.56635606 -0.82410413, + -0.013689496 -0.60463274 -0.79638672, + -0.014096905 -0.60462922 -0.79638231, + -0.0207546 -0.64034498 -0.76780701, + -0.012995393 -0.64042872 -0.76790762, + 0.55911988 -0.52181387 -0.64427882, + 0.47639206 -0.55337507 -0.68324709, + 0.44626895 -0.58130091 -0.68039197, + 0.38669214 -0.59904021 -0.70115626, + 0.34984583 -0.62988472 -0.69343567, + 0.29448614 -0.64255828 -0.70738733, + 0.24733186 -0.67832756 -0.69188058, + 0.17056999 -0.68981892 -0.70360196, + 0.16225594 -0.69553578 -0.69993079, + 0.12006994 -0.69977665 -0.70419866, + 0.11975208 -0.69999945 -0.70403147, + 0.083371066 -0.70261866 -0.70666564, + 0.083120793 -0.70280093 -0.70651394, + 0.052054413 -0.7042852 -0.7080062, + 0.052451111 -0.70397919 -0.70828116, + 0.026186004 -0.70470804 -0.70901406, + 0.027420796 -0.70368093 -0.70998693, + 0.0055614887 -0.70393485 -0.71024281, + 0.0077997046 -0.7018984 -0.71223444, + -0.010117697 -0.70188373 -0.71221977, + -0.0067453631 -0.69847739 -0.71560037, + -0.021115908 -0.69833738 -0.71545738, + -0.016310498 -0.69286597 -0.72088194, + -0.0276848 -0.69269198 -0.72070199, + -0.023429494 -0.68714982 -0.72613782, + -0.031694911 -0.68699324 -0.72597224, + -0.026279604 -0.67877704 -0.73387408, + -0.03239109 -0.67865479 -0.73374277, + -0.02653311 -0.66807222 -0.74362326, + -0.030961914 -0.66798729 -0.74352837, + -0.025869001 -0.65676099 -0.75365502, + -0.0283757 -0.65671599 -0.75360399, + -0.023947304 -0.64439106 -0.76432115, + -0.018368792 -0.64446676 -0.76441169, + -0.023732105 -0.6639142 -0.74743217, + -0.023432005 -0.66391915 -0.74743718, + -0.028005393 -0.67634779 -0.73604983, + -0.025873195 -0.67638695 -0.73609191, + -0.031221388 -0.68789679 -0.72513676, + -0.027497103 -0.68797207 -0.72521603, + -0.032781206 -0.69729519 -0.71603417, + -0.0270462 -0.69741499 -0.71615702, + -0.031796105 -0.70447206 -0.70901906, + -0.023343898 -0.70463693 -0.70918393, + -0.028584296 -0.71132195 -0.70228493, + -0.017454989 -0.71150458 -0.70246458, + -0.021591689 -0.71611363 -0.69764966, + -0.0073327492 -0.71626097 -0.69779396, + -0.010506596 -0.71940279 -0.69451374, + 0.007257822 -0.71942317 -0.69453418, + 0.0049151583 -0.72151273 -0.69238377, + 0.026613494 -0.72126579 -0.69214684, + 0.025129404 -0.72247607 -0.69093907, + 0.05110018 -0.72176075 -0.69025373, + 0.050337087 -0.7223388 -0.68970484, + 0.081003696 -0.72087896 -0.68831092, + 0.080591455 -0.72117358 -0.68805057, + 0.11636905 -0.71861136 -0.6856063, + 0.12442094 -0.71303862 -0.68999666, + 0.19308691 -0.70509964 -0.68231368, + 0.24067503 -0.66945505 -0.70278406, + 0.29060602 -0.65996206 -0.69281906, + 0.32857314 -0.62899029 -0.70456433, + 0.38352695 -0.61503893 -0.68893695, + 0.41601405 -0.58607209 -0.69530708, + 0.47411093 -0.56745094 -0.67321491, + 0.50029415 -0.54174513 -0.67543918, + 0.55953109 -0.51856613 -0.64654016, + 0.58092111 -0.49525011 -0.6459552, + 0.64984274 -0.46246082 -0.60318679, + 0.6737178 -0.4318639 -0.59966487, + 0.72634482 -0.4016749 -0.55774587, + 0.74904108 -0.36773103 -0.55110008, + 0.79663014 -0.33550802 -0.50280708, + 0.81296611 -0.30634004 -0.49521905, + 0.85449719 -0.27327305 -0.44176513, + 0.865569 -0.249211 -0.434378, + 0.8999806 -0.21693389 -0.37811983, + 0.90938121 -0.19123904 -0.36939609, + 0.93765134 -0.15979806 -0.30866611, + 0.94403726 -0.13594402 -0.30052105, + 0.9640671 -0.10949201 -0.24204603, + 0.96721101 -0.092618398 -0.23648401, + 0.98101765 -0.070717879 -0.18056394, + 0.98241448 -0.059288628 -0.17705008, + 0.9913705 -0.041625682 -0.12430494, + 0.99189079 -0.034488194 -0.12232397, + 0.99717379 -0.020387394 -0.072311185, + 0.99731112 -0.016571902 -0.071385309, + 0.99971354 -0.0054124771 -0.02331489, + 0.99972451 -0.0042638681 -0.023080489, + 0.99972862 0.0042324085 0.022910092, + 0.99973643 0.0031694681 0.022736387, + 0.99759835 0.0095630838 0.068601623, + 0.99764675 0.0066248085 0.068242587, + 0.99344379 0.011046197 0.11378697, + 0.99352539 0.0065321522 0.11342303, + 0.98719567 0.0091713667 0.15924995, + 0.60568577 -0.47637582 -0.63734674, + 0.68298924 -0.43729615 -0.58506227, + 0.69613326 -0.42075816 -0.58168817, + 0.76102114 -0.38020906 -0.52563107, + 0.77683872 -0.35614887 -0.51930684, + 0.82494783 -0.3196739 -0.46612188, + 0.84055227 -0.2909801 -0.45694914, + 0.88069355 -0.25443187 -0.39955384, + 0.89073527 -0.23136809 -0.39122814, + 0.92988479 -0.18724896 -0.31662592, + 0.92461425 -0.18708804 -0.3317931, + 0.95187223 -0.15054102 -0.26697707, + 0.95759702 -0.12818 -0.25802699, + 0.97565776 -0.097564675 -0.19639996, + 0.9781059 -0.083038092 -0.19082297, + 0.98935527 -0.058065016 -0.13343403, + 0.99025875 -0.04918189 -0.13026397, + 0.99663502 -0.028952399 -0.076683797, + 0.99687314 -0.024318803 -0.07518331, + 0.99966979 -0.0079082483 -0.024448894, + 0.99968886 -0.006565779 -0.024065496, + 0.9996959 0.0064908192 0.023790795, + 0.99971002 0.00528542 0.0234956, + 0.99737823 0.015881903 0.070600815, + 0.99747378 0.012527697 0.069921985, + 0.99301314 0.020810902 0.11615402, + 0.99320549 0.015605507 0.11532305, + 0.98664874 0.021839395 0.16139196, + 0.98690236 0.015141706 0.16060705, + 0.97816211 0.019508502 0.20692603, + 0.96770722 0.0028199807 0.25206107, + 0.96749902 0.0141263 0.25248, + 0.97841603 0.0115437 0.206322, + 0.97864538 0.0020949689 0.20554487, + 0.97849989 0.011687899 0.20591597, + 0.98714447 0.0090574948 0.15957408, + 0.98698765 0.015313694 0.16006494, + 0.99340022 0.010923703 0.11417903, + 0.99326813 0.015761001 0.11476102, + 0.99757546 0.0094690546 0.068946928, + 0.99750465 0.012635295 0.069460675, + 0.9997251 0.0041959905 0.023066903, + 0.99971449 0.0053235725 0.023297111, + 0.99970913 -0.0053733406 -0.023514904, + 0.99969453 -0.0066043269 -0.023815889, + 0.99712086 -0.020263199 -0.073071294, + 0.99694037 -0.02443121 -0.074250527, + 0.99118227 -0.04141511 -0.12586702, + 0.99049586 -0.049351592 -0.12838398, + 0.98054421 -0.070433415 -0.18322705, + 0.97870255 -0.083232559 -0.18765292, + 0.96307153 -0.10916594 -0.24612188, + 0.95888233 -0.12834704 -0.25312409, + 0.93576688 -0.15946798 -0.31449997, + 0.92906964 -0.18106894 -0.32255787, + 0.89954811 -0.21382603 -0.38090906, + 0.8911373 -0.23480609 -0.38825315, + 0.85405087 -0.26919696 -0.44511795, + 0.84091169 -0.29549587 -0.45337585, + 0.79627681 -0.33031091 -0.50679189, + 0.77701288 -0.36191696 -0.51504093, + 0.72622621 -0.39524615 -0.56247318, + 0.70632601 -0.422791 -0.56775999, + 0.63866878 -0.45957983 -0.61716175, + 0.62027109 -0.48092005 -0.61966103, + 0.54156089 -0.51542288 -0.6641168, + 0.51328796 -0.54314196 -0.66447896, + 0.44968185 -0.56527483 -0.69155675, + 0.41515177 -0.59539163 -0.6878646, + 0.35435709 -0.61198711 -0.70703816, + 0.30906904 -0.64732504 -0.69674003, + 0.22440594 -0.6632908 -0.71392381, + 0.21630605 -0.66891515 -0.71117115, + 0.16748308 -0.6754573 -0.71812737, + 0.16647999 -0.67615396 -0.71770495, + 0.12370697 -0.6804558 -0.7222718, + 0.12252296 -0.68129873 -0.72167873, + 0.085654996 -0.68394798 -0.72448498, + 0.084947124 -0.68447316 -0.72407216, + 0.053530965 -0.68597156 -0.72565657, + 0.053648572 -0.68587869 -0.72573566, + 0.027091887 -0.68661571 -0.72651565, + 0.0282067 -0.68567199 -0.727364, + 0.0061738677 -0.68593174 -0.72763973, + 0.0085706431 -0.68370926 -0.72970426, + -0.0094816592 -0.68370295 -0.72969896, + -0.0053177886 -0.6794098 -0.73373979, + -0.019975308 -0.67928326 -0.73360425, + -0.0165239 -0.67527503 -0.73738098, + -0.027657287 -0.67510873 -0.73719966, + -0.022252195 -0.66792279 -0.7438978, + -0.031015201 -0.66776699 -0.74372399, + -0.0247548 -0.65803999 -0.75257599, + -0.031724408 -0.65791118 -0.75242716, + -0.026282895 -0.64783996 -0.76132286, + -0.031197218 -0.64774835 -0.76121545, + -0.026352491 -0.63681078 -0.77056968, + -0.02906769 -0.63676274 -0.77051169, + -0.024731694 -0.62439787 -0.78071481, + -0.02513301 -0.62439126 -0.7807073, + -0.019785695 -0.60402489 -0.79671985, + -0.025808405 -0.6039421 -0.79661018, + -0.030042589 -0.61631978 -0.78692269, + -0.027252495 -0.61636889 -0.78698581, + -0.03192322 -0.62716937 -0.77822846, + -0.026644006 -0.62726617 -0.77834916, + -0.031727597 -0.63690293 -0.77029085, + -0.024119699 -0.63703799 -0.770455, + -0.029766204 -0.64602804 -0.7627331, + -0.019936893 -0.64618576 -0.76291972, + -0.02653669 -0.65517175 -0.7550137, + -0.014763207 -0.65533131 -0.75519735, + -0.020058801 -0.66160506 -0.74958408, + -0.0057206065 -0.66172761 -0.7497226, + -0.0080442056 -0.6641686 -0.74753958, + 0.010322398 -0.66415483 -0.74752384, + 0.0070137917 -0.66728318 -0.74477118, + 0.02924842 -0.66701448 -0.74447054, + 0.027981 -0.66810697 -0.74353898, + 0.054767575 -0.66736573 -0.74271363, + 0.05486358 -0.66728878 -0.74277574, + 0.086579174 -0.66578579 -0.74110276, + 0.087654807 -0.66497505 -0.74170405, + 0.12498603 -0.66231018 -0.73873121, + 0.12669501 -0.661075 -0.739546, + 0.17004505 -0.65674019 -0.7346952, + 0.17199704 -0.65536416 -0.73546916, + 0.22150497 -0.64875293 -0.72804892, + 0.22287913 -0.64779037 -0.72848642, + 0.27870005 -0.6381762 -0.71767515, + 0.28599304 -0.63297707 -0.71940804, + 0.37804699 -0.61154503 -0.69504899, + 0.41998485 -0.57734281 -0.70020574, + 0.48558894 -0.55613095 -0.67447895, + 0.5166862 -0.5274142 -0.67444026, + 0.58255488 -0.50068891 -0.64026582, + 0.58224112 -0.50214911 -0.63940716, + 0.49041507 -0.53826404 -0.68539405, + 0.45327801 -0.57045197 -0.68492597, + 0.35506192 -0.59827286 -0.71833181, + 0.34923384 -0.60261172 -0.71756166, + 0.28633597 -0.61617696 -0.73371494, + 0.28494403 -0.61717606 -0.73341703, + 0.22841406 -0.62684721 -0.74490917, + 0.22594993 -0.62859577 -0.74418676, + 0.17582405 -0.6352312 -0.75204217, + 0.17320496 -0.63710183 -0.7510668, + 0.12936904 -0.64144319 -0.75618416, + 0.12717402 -0.64305109 -0.75519013, + 0.089458451 -0.64571565 -0.7583195, + 0.088118032 -0.64674121 -0.75760227, + 0.056121025 -0.64824331 -0.75936234, + 0.056107014 -0.64825517 -0.75935316, + 0.029121183 -0.64900267 -0.76022851, + 0.031400211 -0.64700222 -0.7618413, + 0.0088020386 -0.64729595 -0.7621879, + 0.0097347852 -0.64639872 -0.76293766, + -0.0083001135 -0.64640731 -0.76294738, + -0.0031413704 -0.64088309 -0.76763213, + -0.018315397 -0.64077783 -0.76750779, + -0.011378899 -0.63235897 -0.77459186, + -0.024469294 -0.63221085 -0.77440983, + -0.018752499 -0.62423193 -0.78101391, + -0.029375397 -0.62407392 -0.78081286, + -0.024248006 -0.61571312 -0.78759718, + -0.032325812 -0.61557221 -0.78741729, + -0.027564196 -0.60632795 -0.79473686, + -0.032986294 -0.60622895 -0.79460585, + -0.0284961 -0.595586 -0.80278599, + -0.031226093 -0.59553689 -0.80272084, + -0.027153691 -0.58332384 -0.8117857, + -0.02723269 -0.58332282 -0.81178373, + -0.022079701 -0.56264901 -0.826401, + -0.028785616 -0.56255233 -0.82626045, + -0.032691009 -0.57457715 -0.8177973, + -0.030165203 -0.57462305 -0.81786209, + -0.034404192 -0.58492589 -0.8103568, + -0.028950199 -0.58502698 -0.81049699, + -0.033439409 -0.59395611 -0.80380219, + -0.025075812 -0.59410131 -0.80399936, + -0.029718315 -0.6018523 -0.79805434, + -0.018455297 -0.60201585 -0.79827082, + -0.023472404 -0.60918707 -0.79267913, + -0.0093628401 -0.60932797 -0.79286301, + -0.015093798 -0.61646092 -0.78724086, + 0.001650641 -0.61653036 -0.78732949, + -0.005661028 -0.62455577 -0.78095973, + 0.013356606 -0.62451029 -0.78090239, + 0.0083734123 -0.62939417 -0.7770412, + 0.030609207 -0.62912017 -0.77670521, + 0.031326097 -0.62848091 -0.7771939, + 0.0586759 -0.62770599 -0.776236, + 0.057593577 -0.62860078 -0.77559268, + 0.089924075 -0.62709379 -0.77373582, + 0.091172501 -0.62612498 -0.77437401, + 0.12919697 -0.6234749 -0.7710948, + 0.13177305 -0.62156332 -0.77220136, + 0.17604999 -0.61723691 -0.76682788, + 0.17923102 -0.61493808 -0.76793712, + 0.22991906 -0.6083141 -0.75966519, + 0.23314001 -0.60600197 -0.76053101, + 0.29030204 -0.59633803 -0.74840206, + 0.292916 -0.59443802 -0.74889499, + 0.35644302 -0.58087105 -0.73180407, + 0.3575131 -0.58006912 -0.73191816, + 0.42702809 -0.5616411 -0.70866519, + 0.43080315 -0.55865419 -0.70874125, + 0.53236598 -0.52403003 -0.66481501, + 0.56341136 -0.4949303 -0.66152239, + 0.65207767 -0.45417979 -0.60705471, + 0.66974807 -0.43392006 -0.60262007, + 0.74387306 -0.39052305 -0.54235107, + 0.75215966 -0.37900183 -0.53908575, + 0.81277311 -0.33506203 -0.47658506, + 0.82472068 -0.31465587 -0.46992281, + 0.86831069 -0.2759769 -0.41215685, + 0.88034356 -0.25059289 -0.40273881, + 0.91519475 -0.21291195 -0.34217992, + 0.91583669 -0.21984193 -0.33602488, + 0.86805558 -0.27180588 -0.41545278, + 0.8596409 -0.28832898 -0.42176294, + 0.80532891 -0.33456698 -0.48939794, + 0.80105186 -0.34127897 -0.49177694, + 0.73228294 -0.38826194 -0.55947691, + 0.72073793 -0.40299493 -0.56403196, + 0.63562995 -0.44879693 -0.62813693, + 0.61251074 -0.47262883 -0.63360274, + 0.5109129 -0.51398689 -0.6890468, + 0.50954509 -0.51515806 -0.68918508, + 0.43543491 -0.5389719 -0.72104484, + 0.43499601 -0.53932202 -0.721048, + 0.36504602 -0.55762506 -0.74551708, + 0.36267382 -0.55942076 -0.74532962, + 0.29857183 -0.57290965 -0.76330155, + 0.29510596 -0.57545197 -0.76273686, + 0.23738697 -0.58505893 -0.7754699, + 0.23352009 -0.58786225 -0.77452332, + 0.18233098 -0.59444195 -0.7831949, + 0.17874309 -0.59706432 -0.78202635, + 0.13402405 -0.60136229 -0.78765535, + 0.13149302 -0.60326403 -0.78662711, + 0.0931499 -0.60590202 -0.79006702, + 0.093007691 -0.60601395 -0.78999788, + 0.060237415 -0.6075471 -0.79199618, + 0.057688825 -0.60968029 -0.79054534, + 0.030723808 -0.61040914 -0.7914902, + 0.035602808 -0.60598212 -0.79468119, + 0.012151195 -0.60632169 -0.79512662, + 0.019957801 -0.59847605 -0.80089211, + -0.00095156924 -0.59859514 -0.8010512, + 0.0047865082 -0.59213477 -0.8058247, + -0.013225992 -0.59208965 -0.80576354, + -0.0084476583 -0.58599889 -0.81026781, + -0.023368999 -0.585859 -0.810076, + -0.019056799 -0.57954997 -0.8147139, + -0.030742297 -0.57938093 -0.81447691, + -0.0265209 -0.57216299 -0.81971103, + -0.035001591 -0.57201385 -0.81949681, + -0.0309078 -0.56366801 -0.825423, + -0.036181901 -0.563568 -0.82527697, + -0.032187294 -0.55360389 -0.83215785, + -0.034383088 -0.55356383 -0.8320967, + -0.030607199 -0.54161698 -0.84006798, + -0.029857608 -0.54162914 -0.84008718, + -0.024913499 -0.52065098 -0.85340601, + -0.032524586 -0.52053678 -0.85321957, + -0.036200296 -0.53250092 -0.8456549, + -0.034464788 -0.53253382 -0.8457067, + -0.038261283 -0.54226077 -0.8393386, + -0.033326495 -0.54235697 -0.8394869, + -0.037065417 -0.55017519 -0.83422631, + -0.028706184 -0.55032563 -0.8344565, + -0.032341216 -0.55669326 -0.83008844, + -0.020463198 -0.55686796 -0.83034891, + -0.024133403 -0.56236607 -0.82653612, + -0.0086350208 -0.56250906 -0.82674611, + -0.012439298 -0.56747186 -0.82329881, + 0.0066201324 -0.5675022 -0.8233453, + 0.0021312104 -0.57268012 -0.81977618, + 0.024614591 -0.5725078 -0.81952971, + 0.018793892 -0.57851285 -0.81545669, + 0.044515897 -0.57804191 -0.81479186, + 0.035997096 -0.58597392 -0.8095299, + 0.064439394 -0.58513594 -0.80837089, + 0.059476707 -0.58936006 -0.80567813, + 0.091790333 -0.58791322 -0.80369931, + 0.096329935 -0.58429724 -0.80580229, + 0.13515508 -0.58164036 -0.80213946, + 0.13652098 -0.58060092 -0.80266088, + 0.18160191 -0.5763427 -0.79677463, + 0.18529402 -0.57361805 -0.79789013, + 0.23694594 -0.56710291 -0.78882885, + 0.24128608 -0.56393015 -0.78978729, + 0.29948884 -0.55442679 -0.77647763, + 0.30368713 -0.55132216 -0.77705729, + 0.36831498 -0.53797293 -0.75824088, + 0.37158212 -0.5354802 -0.75841129, + 0.44201413 -0.5173741 -0.73276716, + 0.44368386 -0.51603281 -0.73270375, + 0.51798701 -0.492542 -0.69935101, + 0.51747286 -0.49298587 -0.69941884, + 0.59382308 -0.46354407 -0.65764809, + 0.59277505 -0.46453407 -0.65789509, + 0.69084299 -0.41702801 -0.59061301, + 0.7063368 -0.3991119 -0.5846349, + 0.78498584 -0.3492929 -0.51165587, + 0.79138291 -0.34000498 -0.50804496, + 0.85236371 -0.2908549 -0.43460286, + 0.85371983 -0.28839394 -0.43357992, + 0.90049726 -0.24083605 -0.36208108, + 0.90915322 -0.22046506 -0.35332108, + 0.94215125 -0.17744105 -0.28436905, + 0.95022452 -0.15061793 -0.27274087, + 0.97153747 -0.11451605 -0.20736711, + 0.97489142 -0.097510144 -0.20019588, + 0.98784786 -0.068059295 -0.13972999, + 0.98905051 -0.057963274 -0.13571794, + 0.99623823 -0.034035906 -0.079693019, + 0.99655038 -0.028867083 -0.077806853, + 0.99963754 -0.0093640657 -0.025239488, + 0.99966264 -0.007874297 -0.02475249, + 0.99967188 0.0077646589 0.024407797, + 0.99969035 0.0064541022 0.02403361, + 0.99721241 0.019351589 0.072061256, + 0.99733812 0.015767401 0.071191311, + 0.99266952 0.026134986 0.11800094, + 0.9929285 0.020631291 0.11690695, + 0.98615789 0.028816096 0.16328599, + 0.98652655 0.021621188 0.16216592, + 0.97761399 0.0278069 0.208561, + 0.97802401 0.0192918 0.207598, + 0.96700591 0.023572396 0.25366098, + 0.96737635 0.013953905 0.2529591, + 0.95409489 0.016496398 0.29904997, + 0.95437253 0.0036089083 0.29859686, + 0.96314573 0.0075529781 0.26887393, + 0.96317464 -0.00093462266 0.26887491, + 0.96317351 -0.00093462755 0.26887888, + 0.96314466 0.0075528971 0.26887792, + 0.96315074 0.007552458 0.26885593, + 0.96317965 -0.00093429763 0.26885691, + 0.97518301 0.00433107 0.221358, + 0.97517025 0.0066757514 0.22135606, + 0.97517776 0.0066750785 0.22132294, + 0.97519886 0.0016840597 0.22132397, + 0.98488849 -0.00098321843 0.17318709, + 0.98487163 0.005758428 0.17318994, + 0.98491853 0.0057529374 0.17292291, + 0.98493546 -0.00098522648 0.17292009, + 0.984882 -0.00098546804 0.173224, + 0.99219465 0.0035763488 0.12464695, + 0.99219024 0.0046622911 0.12464703, + 0.99217767 0.0046643582 0.12474696, + 0.99218577 0.0024237696 0.12474597, + 0.99712014 -0.00096518412 0.075831905, + 0.99711466 0.0033884188 0.075834773, + 0.99711013 0.0033897005 0.075894706, + 0.99711555 -0.00096292055 0.075891562, + 0.99711311 -0.00096294814 0.075924709, + 0.99963897 0.0028926299 0.026712401, + 0.99964148 0.0018820909 0.026711613, + 0.99974948 0.0017874908 0.022313211, + 0.99963814 4.5343902e-005 0.026899103, + 0.99963289 0.0032325694 0.026901497, + 0.99976212 -0.0008362821 -0.021794602, + 0.99976248 1.6864407e-005 -0.021793911, + 0.99975353 7.9351266e-006 -0.022202689, + 0.99975312 -0.00086754712 -0.022203403, + 0.99975502 -0.00086761598 -0.022115899, + 0.99975187 -0.00085937389 -0.022257999, + 0.99746335 0.0022539108 -0.071146019, + 0.99746567 -0.00042616186 -0.071148179, + 0.99747014 -0.00042475807 -0.071085908, + 0.99746197 0.00412559 -0.071081698, + 0.9970125 0.0034232817 -0.077164739, + 0.84207714 0.53667408 -0.053731006, + -0.89261347 -0.45081174 0.0031386581, + -0.450762 0.0141545 0.89253199, + -0.4508118 -0.0015851893 0.89261758, + 0.015182205 -0.52255017 -0.85247332, + -0.014481494 -0.52255481 -0.85248268, + 0 0.99999964 0.00079628272, + -0.89259273 -0.45080486 0.0072980574, + -0.17241998 -0.0011597698 0.9850229, + 0.53740287 -0.0072184582 -0.8432948, + -0.075101063 -0.0008541306 0.99717551, + -0.075090967 0.015539794 0.99705565, + 0 0.00079628272 -0.99999964 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 2, 1, -1, + 4, 5, 6, -1, 7, 8, 9, -1, + 10, 11, 12, -1, 11, 10, 13, -1, + 13, 14, 11, -1, 14, 13, 15, -1, + 15, 16, 14, -1, 16, 15, 17, -1, + 17, 18, 16, -1, 18, 17, 19, -1, + 19, 20, 18, -1, 20, 19, 21, -1, + 21, 22, 20, -1, 22, 21, 23, -1, + 23, 24, 22, -1, 24, 23, 25, -1, + 25, 26, 24, -1, 26, 25, 27, -1, + 27, 28, 26, -1, 28, 27, 29, -1, + 29, 30, 28, -1, 30, 29, 31, -1, + 31, 32, 30, -1, 32, 31, 33, -1, + 33, 34, 32, -1, 34, 33, 35, -1, + 35, 36, 34, -1, 36, 35, 37, -1, + 37, 38, 36, -1, 38, 37, 39, -1, + 39, 40, 38, -1, 40, 39, 41, -1, + 41, 42, 40, -1, 42, 41, 43, -1, + 43, 44, 42, -1, 44, 43, 45, -1, + 45, 46, 44, -1, 46, 45, 47, -1, + 47, 48, 46, -1, 48, 47, 49, -1, + 48, 49, 50, -1, 51, 50, 49, -1, + 51, 52, 50, -1, 52, 51, 53, -1, + 53, 54, 52, -1, 54, 55, 56, -1, + 56, 52, 54, -1, 52, 56, 57, -1, + 57, 50, 52, -1, 50, 57, 58, -1, + 59, 58, 57, -1, 57, 60, 59, -1, + 60, 57, 56, -1, 56, 61, 60, -1, + 61, 56, 55, -1, 55, 62, 61, -1, + 63, 64, 65, -1, 63, 65, 66, -1, + 65, 67, 66, -1, 67, 65, 62, -1, + 62, 55, 67, -1, 68, 67, 69, -1, + 67, 70, 69, -1, 70, 67, 55, -1, + 55, 54, 70, -1, 70, 71, 72, -1, + 71, 70, 54, -1, 54, 53, 71, -1, + 73, 74, 75, -1, 76, 71, 74, -1, + 71, 75, 74, -1, 75, 71, 53, -1, + 53, 77, 75, -1, 77, 53, 51, -1, + 51, 78, 77, -1, 78, 51, 49, -1, + 49, 79, 78, -1, 79, 49, 47, -1, + 47, 80, 79, -1, 80, 47, 45, -1, + 45, 81, 80, -1, 81, 45, 43, -1, + 43, 82, 81, -1, 82, 43, 41, -1, + 41, 83, 82, -1, 83, 41, 39, -1, + 39, 84, 83, -1, 84, 39, 37, -1, + 37, 85, 84, -1, 85, 37, 35, -1, + 35, 86, 85, -1, 86, 35, 33, -1, + 33, 87, 86, -1, 87, 33, 31, -1, + 31, 88, 87, -1, 88, 31, 29, -1, + 29, 89, 88, -1, 89, 29, 27, -1, + 27, 90, 89, -1, 90, 27, 25, -1, + 25, 91, 90, -1, 91, 25, 23, -1, + 23, 92, 91, -1, 92, 23, 21, -1, + 21, 93, 92, -1, 93, 21, 19, -1, + 19, 94, 93, -1, 94, 19, 17, -1, + 17, 95, 94, -1, 95, 17, 15, -1, + 15, 96, 95, -1, 96, 15, 13, -1, + 13, 97, 96, -1, 97, 13, 10, -1, + 10, 98, 97, -1, 10, 12, 98, -1, + 99, 98, 12, -1, 99, 100, 98, -1, + 100, 99, 101, -1, 101, 102, 100, -1, + 102, 101, 103, -1, 102, 103, 104, -1, + 104, 105, 102, -1, 105, 104, 106, -1, + 106, 107, 105, -1, 108, 109, 110, -1, + 111, 112, 113, -1, 114, 115, 116, -1, + 116, 117, 114, -1, 117, 116, 118, -1, + 118, 119, 117, -1, 119, 118, 120, -1, + 120, 121, 119, -1, 122, 123, 121, -1, + 121, 120, 122, -1, 124, 122, 120, -1, + 120, 125, 124, -1, 125, 120, 118, -1, + 118, 126, 125, -1, 126, 118, 116, -1, + 116, 127, 126, -1, 127, 116, 115, -1, + 115, 128, 127, -1, 129, 130, 115, -1, + 130, 128, 115, -1, 130, 131, 128, -1, + 130, 129, 131, -1, 132, 131, 129, -1, + 129, 115, 132, -1, 133, 132, 115, -1, + 115, 114, 133, -1, 134, 135, 133, -1, + 133, 136, 134, -1, 136, 133, 114, -1, + 114, 137, 136, -1, 137, 114, 117, -1, + 117, 138, 137, -1, 138, 117, 119, -1, + 119, 139, 138, -1, 139, 119, 121, -1, + 121, 140, 139, -1, 140, 121, 123, -1, + 123, 141, 140, -1, 142, 143, 141, -1, + 143, 142, 144, -1, 144, 145, 143, -1, + 145, 144, 146, -1, 146, 147, 145, -1, + 147, 146, 148, -1, 148, 149, 147, -1, + 149, 148, 150, -1, 150, 151, 149, -1, + 151, 150, 152, -1, 152, 153, 151, -1, + 153, 152, 154, -1, 154, 155, 153, -1, + 155, 154, 156, -1, 156, 157, 155, -1, + 157, 156, 158, -1, 158, 159, 157, -1, + 159, 158, 160, -1, 160, 161, 159, -1, + 161, 160, 162, -1, 162, 163, 161, -1, + 163, 162, 164, -1, 164, 165, 163, -1, + 165, 164, 166, -1, 166, 167, 165, -1, + 167, 166, 168, -1, 168, 169, 167, -1, + 169, 168, 170, -1, 170, 171, 169, -1, + 171, 170, 172, -1, 172, 173, 171, -1, + 173, 172, 174, -1, 174, 175, 173, -1, + 176, 177, 178, -1, 177, 176, 175, -1, + 175, 174, 177, -1, 179, 177, 174, -1, + 174, 180, 179, -1, 180, 174, 172, -1, + 172, 181, 180, -1, 181, 172, 170, -1, + 170, 182, 181, -1, 182, 170, 168, -1, + 168, 183, 182, -1, 183, 168, 166, -1, + 166, 184, 183, -1, 184, 166, 164, -1, + 164, 185, 184, -1, 185, 164, 162, -1, + 162, 186, 185, -1, 186, 162, 160, -1, + 160, 187, 186, -1, 187, 160, 158, -1, + 158, 188, 187, -1, 188, 158, 156, -1, + 156, 189, 188, -1, 189, 156, 154, -1, + 154, 190, 189, -1, 190, 154, 152, -1, + 152, 191, 190, -1, 191, 152, 150, -1, + 150, 192, 191, -1, 192, 150, 148, -1, + 148, 193, 192, -1, 193, 148, 146, -1, + 146, 194, 193, -1, 194, 146, 144, -1, + 144, 195, 194, -1, 195, 144, 142, -1, + 142, 196, 195, -1, 196, 142, 141, -1, + 141, 123, 196, -1, 197, 196, 123, -1, + 196, 197, 198, -1, 198, 195, 196, -1, + 195, 198, 199, -1, 199, 194, 195, -1, + 194, 199, 200, -1, 200, 193, 194, -1, + 193, 200, 201, -1, 201, 192, 193, -1, + 192, 201, 202, -1, 202, 191, 192, -1, + 191, 202, 203, -1, 203, 190, 191, -1, + 190, 203, 204, -1, 204, 189, 190, -1, + 189, 204, 205, -1, 205, 188, 189, -1, + 188, 205, 206, -1, 206, 187, 188, -1, + 187, 206, 207, -1, 207, 186, 187, -1, + 186, 207, 208, -1, 208, 185, 186, -1, + 185, 208, 209, -1, 209, 184, 185, -1, + 184, 209, 210, -1, 210, 183, 184, -1, + 183, 210, 211, -1, 211, 182, 183, -1, + 182, 211, 212, -1, 212, 181, 182, -1, + 181, 212, 213, -1, 213, 180, 181, -1, + 180, 213, 214, -1, 214, 179, 180, -1, + 214, 215, 179, -1, 214, 216, 215, -1, + 216, 214, 213, -1, 213, 217, 216, -1, + 217, 213, 212, -1, 212, 218, 217, -1, + 218, 212, 211, -1, 211, 219, 218, -1, + 219, 211, 210, -1, 210, 220, 219, -1, + 220, 210, 209, -1, 209, 221, 220, -1, + 221, 209, 208, -1, 208, 222, 221, -1, + 222, 208, 207, -1, 207, 223, 222, -1, + 223, 207, 206, -1, 206, 224, 223, -1, + 224, 206, 205, -1, 205, 225, 224, -1, + 225, 205, 204, -1, 204, 226, 225, -1, + 226, 204, 203, -1, 203, 227, 226, -1, + 227, 203, 202, -1, 202, 228, 227, -1, + 228, 202, 201, -1, 201, 229, 228, -1, + 229, 201, 200, -1, 200, 230, 229, -1, + 230, 200, 199, -1, 199, 231, 230, -1, + 231, 199, 198, -1, 198, 232, 231, -1, + 232, 198, 197, -1, 197, 233, 232, -1, + 233, 197, 123, -1, 123, 122, 233, -1, + 234, 235, 233, -1, 234, 233, 122, -1, + 122, 124, 234, -1, 236, 237, 234, -1, + 236, 234, 124, -1, 124, 238, 236, -1, + 238, 124, 125, -1, 125, 239, 238, -1, + 239, 125, 126, -1, 126, 240, 239, -1, + 240, 126, 127, -1, 127, 241, 240, -1, + 241, 242, 243, -1, 242, 241, 127, -1, + 242, 127, 128, -1, 242, 128, 131, -1, + 131, 243, 242, -1, 244, 245, 246, -1, + 247, 244, 248, -1, 247, 245, 244, -1, + 247, 249, 245, -1, 247, 248, 249, -1, + 250, 251, 252, -1, 250, 253, 251, -1, + 250, 254, 253, -1, 250, 252, 254, -1, + 255, 254, 252, -1, 256, 257, 258, -1, + 256, 259, 257, -1, 256, 260, 259, -1, + 256, 258, 260, -1, 261, 260, 258, -1, + 262, 263, 264, -1, 264, 265, 262, -1, + 265, 264, 266, -1, 266, 267, 265, -1, + 267, 266, 268, -1, 268, 269, 267, -1, + 269, 268, 270, -1, 270, 271, 269, -1, + 271, 270, 272, -1, 272, 273, 271, -1, + 273, 272, 274, -1, 274, 275, 273, -1, + 275, 274, 276, -1, 276, 277, 275, -1, + 277, 276, 278, -1, 278, 279, 277, -1, + 279, 278, 280, -1, 280, 281, 279, -1, + 281, 280, 282, -1, 282, 283, 281, -1, + 283, 282, 284, -1, 284, 285, 283, -1, + 285, 284, 286, -1, 286, 287, 285, -1, + 287, 286, 288, -1, 288, 289, 287, -1, + 289, 288, 290, -1, 290, 291, 289, -1, + 291, 290, 292, -1, 292, 293, 291, -1, + 293, 292, 294, -1, 294, 295, 293, -1, + 295, 294, 296, -1, 296, 297, 295, -1, + 297, 296, 298, -1, 298, 299, 297, -1, + 299, 298, 300, -1, 300, 301, 299, -1, + 300, 302, 301, -1, 302, 300, 303, -1, + 303, 304, 302, -1, 304, 303, 305, -1, + 305, 306, 304, -1, 306, 305, 307, -1, + 307, 308, 306, -1, 308, 307, 309, -1, + 309, 310, 308, -1, 310, 309, 311, -1, + 311, 312, 310, -1, 312, 311, 313, -1, + 313, 314, 312, -1, 314, 313, 315, -1, + 315, 316, 314, -1, 316, 315, 317, -1, + 317, 318, 316, -1, 318, 317, 319, -1, + 319, 320, 318, -1, 320, 319, 321, -1, + 321, 322, 320, -1, 322, 321, 323, -1, + 323, 324, 322, -1, 324, 323, 325, -1, + 325, 326, 324, -1, 326, 325, 327, -1, + 327, 328, 326, -1, 328, 327, 329, -1, + 329, 330, 328, -1, 330, 329, 331, -1, + 331, 332, 330, -1, 332, 331, 333, -1, + 333, 334, 332, -1, 334, 333, 335, -1, + 335, 336, 334, -1, 336, 335, 337, -1, + 337, 338, 336, -1, 338, 337, 339, -1, + 339, 261, 338, -1, 339, 260, 261, -1, + 339, 340, 260, -1, 340, 339, 337, -1, + 337, 341, 340, -1, 341, 337, 335, -1, + 335, 342, 341, -1, 342, 335, 333, -1, + 333, 343, 342, -1, 343, 333, 331, -1, + 331, 344, 343, -1, 344, 331, 329, -1, + 329, 345, 344, -1, 345, 329, 327, -1, + 327, 346, 345, -1, 346, 327, 325, -1, + 325, 347, 346, -1, 347, 325, 323, -1, + 323, 348, 347, -1, 348, 323, 321, -1, + 321, 349, 348, -1, 349, 321, 319, -1, + 319, 350, 349, -1, 350, 319, 317, -1, + 317, 351, 350, -1, 351, 317, 315, -1, + 315, 352, 351, -1, 352, 315, 313, -1, + 313, 353, 352, -1, 353, 313, 311, -1, + 311, 354, 353, -1, 354, 311, 309, -1, + 309, 355, 354, -1, 355, 309, 307, -1, + 307, 356, 355, -1, 356, 307, 305, -1, + 305, 357, 356, -1, 357, 305, 303, -1, + 303, 358, 357, -1, 358, 303, 300, -1, + 358, 300, 298, -1, 298, 359, 358, -1, + 359, 298, 296, -1, 296, 360, 359, -1, + 360, 296, 294, -1, 294, 361, 360, -1, + 361, 294, 292, -1, 292, 362, 361, -1, + 362, 292, 290, -1, 290, 363, 362, -1, + 363, 290, 288, -1, 288, 364, 363, -1, + 364, 288, 286, -1, 286, 365, 364, -1, + 365, 286, 284, -1, 284, 366, 365, -1, + 366, 284, 282, -1, 282, 367, 366, -1, + 367, 282, 280, -1, 280, 368, 367, -1, + 368, 280, 278, -1, 278, 369, 368, -1, + 369, 278, 276, -1, 276, 370, 369, -1, + 370, 276, 274, -1, 274, 371, 370, -1, + 371, 274, 272, -1, 272, 372, 371, -1, + 372, 272, 270, -1, 270, 373, 372, -1, + 373, 270, 268, -1, 268, 374, 373, -1, + 374, 268, 266, -1, 266, 375, 374, -1, + 375, 266, 264, -1, 264, 376, 375, -1, + 376, 264, 263, -1, 263, 252, 376, -1, + 263, 255, 252, -1, 263, 262, 255, -1, + 255, 262, 377, -1, 255, 377, 249, -1, + 249, 378, 255, -1, 378, 249, 248, -1, + 378, 248, 244, -1, 378, 244, 379, -1, + 379, 255, 378, -1, 379, 254, 255, -1, + 254, 379, 244, -1, 244, 253, 254, -1, + 246, 380, 243, -1, 131, 381, 382, -1, + 381, 131, 132, -1, 381, 132, 133, -1, + 381, 133, 135, -1, 135, 382, 381, -1, + 135, 383, 382, -1, 383, 135, 134, -1, + 383, 134, 384, -1, 384, 382, 383, -1, + 384, 385, 382, -1, 384, 134, 385, -1, + 386, 385, 134, -1, 134, 387, 386, -1, + 387, 134, 136, -1, 136, 388, 387, -1, + 388, 136, 137, -1, 137, 389, 388, -1, + 389, 137, 138, -1, 138, 390, 389, -1, + 390, 138, 139, -1, 139, 391, 390, -1, + 391, 139, 140, -1, 140, 392, 391, -1, + 392, 140, 141, -1, 141, 393, 392, -1, + 393, 141, 143, -1, 143, 394, 393, -1, + 394, 143, 145, -1, 145, 395, 394, -1, + 395, 145, 147, -1, 147, 396, 395, -1, + 396, 147, 149, -1, 149, 397, 396, -1, + 397, 149, 151, -1, 151, 398, 397, -1, + 398, 151, 153, -1, 153, 399, 398, -1, + 399, 153, 155, -1, 155, 400, 399, -1, + 400, 155, 157, -1, 157, 401, 400, -1, + 401, 157, 159, -1, 159, 402, 401, -1, + 402, 159, 161, -1, 161, 403, 402, -1, + 403, 161, 163, -1, 163, 404, 403, -1, + 404, 163, 165, -1, 165, 405, 404, -1, + 405, 165, 167, -1, 167, 406, 405, -1, + 406, 167, 169, -1, 169, 407, 406, -1, + 407, 169, 171, -1, 171, 408, 407, -1, + 408, 171, 173, -1, 173, 409, 408, -1, + 409, 173, 175, -1, 175, 410, 409, -1, + 410, 175, 176, -1, 176, 411, 410, -1, + 176, 178, 411, -1, 412, 411, 178, -1, + 412, 178, 413, -1, 413, 414, 412, -1, + 414, 413, 415, -1, 415, 416, 414, -1, + 416, 415, 417, -1, 417, 418, 416, -1, + 418, 417, 419, -1, 419, 420, 418, -1, + 419, 421, 420, -1, 421, 419, 422, -1, + 422, 423, 421, -1, 423, 422, 424, -1, + 424, 425, 423, -1, 425, 424, 426, -1, + 426, 427, 425, -1, 427, 428, 429, -1, + 427, 426, 428, -1, 430, 431, 432, -1, + 430, 433, 431, -1, 433, 430, 428, -1, + 428, 434, 433, -1, 434, 428, 426, -1, + 426, 435, 434, -1, 435, 426, 424, -1, + 424, 436, 435, -1, 436, 424, 422, -1, + 422, 437, 436, -1, 437, 422, 419, -1, + 437, 419, 417, -1, 417, 438, 437, -1, + 438, 417, 415, -1, 415, 439, 438, -1, + 439, 415, 413, -1, 413, 440, 439, -1, + 440, 413, 178, -1, 178, 441, 440, -1, + 441, 178, 177, -1, 177, 179, 441, -1, + 441, 179, 215, -1, 441, 215, 442, -1, + 442, 440, 441, -1, 440, 442, 443, -1, + 443, 439, 440, -1, 439, 443, 444, -1, + 444, 438, 439, -1, 438, 444, 445, -1, + 445, 437, 438, -1, 445, 436, 437, -1, + 436, 445, 446, -1, 446, 435, 436, -1, + 435, 446, 447, -1, 447, 434, 435, -1, + 434, 447, 448, -1, 448, 433, 434, -1, + 433, 448, 449, -1, 449, 431, 433, -1, + 431, 449, 450, -1, 450, 451, 431, -1, + 451, 450, 452, -1, 452, 453, 451, -1, + 453, 452, 454, -1, 454, 455, 453, -1, + 455, 454, 456, -1, 456, 457, 455, -1, + 457, 456, 458, -1, 458, 459, 457, -1, + 459, 458, 460, -1, 460, 461, 459, -1, + 461, 460, 462, -1, 462, 463, 461, -1, + 463, 462, 464, -1, 464, 465, 463, -1, + 465, 464, 466, -1, 466, 467, 465, -1, + 467, 466, 468, -1, 468, 469, 467, -1, + 469, 468, 470, -1, 470, 471, 469, -1, + 471, 470, 472, -1, 472, 473, 471, -1, + 473, 472, 474, -1, 474, 475, 473, -1, + 475, 474, 476, -1, 476, 477, 475, -1, + 477, 476, 478, -1, 478, 479, 477, -1, + 479, 478, 480, -1, 480, 481, 479, -1, + 481, 480, 482, -1, 482, 483, 481, -1, + 483, 482, 484, -1, 484, 485, 483, -1, + 485, 484, 486, -1, 485, 486, 487, -1, + 485, 487, 488, -1, 488, 483, 485, -1, + 483, 488, 489, -1, 489, 481, 483, -1, + 481, 489, 490, -1, 490, 479, 481, -1, + 479, 490, 491, -1, 491, 477, 479, -1, + 477, 491, 492, -1, 492, 475, 477, -1, + 475, 492, 493, -1, 493, 473, 475, -1, + 473, 493, 494, -1, 494, 471, 473, -1, + 471, 494, 495, -1, 495, 469, 471, -1, + 469, 495, 496, -1, 496, 467, 469, -1, + 467, 496, 497, -1, 497, 465, 467, -1, + 465, 497, 498, -1, 498, 463, 465, -1, + 463, 498, 499, -1, 499, 461, 463, -1, + 461, 499, 500, -1, 500, 459, 461, -1, + 459, 500, 501, -1, 501, 457, 459, -1, + 457, 501, 502, -1, 502, 455, 457, -1, + 455, 502, 503, -1, 503, 453, 455, -1, + 453, 503, 504, -1, 504, 451, 453, -1, + 451, 504, 505, -1, 505, 431, 451, -1, + 505, 432, 431, -1, 505, 506, 432, -1, + 506, 505, 504, -1, 504, 507, 506, -1, + 507, 504, 503, -1, 503, 508, 507, -1, + 508, 503, 502, -1, 502, 509, 508, -1, + 509, 502, 501, -1, 501, 510, 509, -1, + 510, 501, 500, -1, 500, 511, 510, -1, + 511, 500, 499, -1, 499, 512, 511, -1, + 512, 499, 498, -1, 498, 513, 512, -1, + 513, 498, 497, -1, 497, 514, 513, -1, + 514, 497, 496, -1, 496, 515, 514, -1, + 515, 496, 495, -1, 495, 516, 515, -1, + 516, 495, 494, -1, 494, 517, 516, -1, + 517, 494, 493, -1, 493, 518, 517, -1, + 518, 493, 492, -1, 492, 519, 518, -1, + 519, 492, 491, -1, 491, 520, 519, -1, + 520, 491, 490, -1, 490, 521, 520, -1, + 521, 490, 489, -1, 489, 522, 521, -1, + 522, 489, 488, -1, 488, 487, 522, -1, + 523, 524, 525, -1, 525, 526, 523, -1, + 526, 525, 527, -1, 527, 528, 526, -1, + 528, 527, 529, -1, 529, 530, 528, -1, + 530, 529, 531, -1, 531, 532, 530, -1, + 533, 534, 532, -1, 532, 531, 533, -1, + 535, 536, 537, -1, 537, 538, 535, -1, + 538, 537, 539, -1, 539, 540, 538, -1, + 540, 539, 541, -1, 541, 542, 540, -1, + 542, 541, 543, -1, 543, 544, 542, -1, + 544, 543, 545, -1, 545, 546, 544, -1, + 546, 545, 547, -1, 547, 548, 546, -1, + 548, 547, 549, -1, 549, 550, 548, -1, + 551, 552, 553, -1, 554, 555, 556, -1, + 556, 557, 554, -1, 557, 556, 558, -1, + 558, 559, 557, -1, 559, 558, 560, -1, + 560, 561, 559, -1, 561, 560, 562, -1, + 562, 563, 561, -1, 563, 562, 564, -1, + 564, 565, 563, -1, 565, 564, 566, -1, + 566, 567, 565, -1, 567, 566, 568, -1, + 568, 569, 567, -1, 569, 568, 570, -1, + 570, 571, 569, -1, 571, 570, 572, -1, + 572, 573, 571, -1, 573, 572, 574, -1, + 574, 575, 573, -1, 575, 574, 576, -1, + 576, 577, 575, -1, 577, 576, 578, -1, + 578, 579, 577, -1, 579, 578, 580, -1, + 581, 582, 583, -1, 583, 584, 581, -1, + 584, 583, 585, -1, 585, 586, 584, -1, + 586, 585, 587, -1, 587, 588, 586, -1, + 588, 587, 589, -1, 589, 590, 588, -1, + 590, 589, 591, -1, 591, 592, 590, -1, + 592, 591, 593, -1, 593, 594, 592, -1, + 594, 593, 595, -1, 595, 596, 594, -1, + 596, 595, 597, -1, 597, 598, 596, -1, + 598, 597, 599, -1, 599, 600, 598, -1, + 600, 599, 601, -1, 601, 602, 600, -1, + 602, 601, 603, -1, 603, 604, 602, -1, + 604, 603, 605, -1, 605, 606, 604, -1, + 606, 605, 607, -1, 608, 609, 610, -1, + 609, 608, 611, -1, 611, 612, 609, -1, + 612, 611, 613, -1, 613, 614, 612, -1, + 614, 613, 615, -1, 615, 616, 614, -1, + 616, 615, 617, -1, 617, 618, 616, -1, + 618, 617, 607, -1, 607, 580, 618, -1, + 580, 607, 605, -1, 605, 579, 580, -1, + 579, 605, 603, -1, 603, 577, 579, -1, + 577, 603, 601, -1, 601, 575, 577, -1, + 575, 601, 599, -1, 599, 573, 575, -1, + 573, 599, 597, -1, 597, 571, 573, -1, + 571, 597, 595, -1, 595, 569, 571, -1, + 569, 595, 593, -1, 593, 567, 569, -1, + 567, 593, 591, -1, 591, 565, 567, -1, + 565, 591, 589, -1, 589, 563, 565, -1, + 563, 589, 587, -1, 587, 561, 563, -1, + 561, 587, 585, -1, 585, 559, 561, -1, + 559, 585, 583, -1, 583, 557, 559, -1, + 557, 583, 582, -1, 582, 554, 557, -1, + 582, 619, 554, -1, 582, 581, 619, -1, + 620, 619, 581, -1, 581, 621, 620, -1, + 621, 581, 584, -1, 584, 622, 621, -1, + 622, 584, 586, -1, 586, 623, 622, -1, + 623, 586, 588, -1, 588, 624, 623, -1, + 624, 588, 590, -1, 590, 625, 624, -1, + 625, 590, 592, -1, 592, 626, 625, -1, + 626, 592, 594, -1, 594, 627, 626, -1, + 627, 594, 596, -1, 596, 628, 627, -1, + 628, 596, 598, -1, 598, 629, 628, -1, + 629, 598, 600, -1, 600, 630, 629, -1, + 630, 600, 602, -1, 602, 631, 630, -1, + 631, 602, 604, -1, 604, 632, 631, -1, + 632, 604, 606, -1, 606, 633, 632, -1, + 633, 606, 607, -1, 607, 634, 633, -1, + 634, 607, 617, -1, 617, 635, 634, -1, + 635, 617, 615, -1, 615, 636, 635, -1, + 636, 615, 613, -1, 613, 637, 636, -1, + 637, 613, 611, -1, 611, 638, 637, -1, + 638, 611, 608, -1, 608, 639, 638, -1, + 639, 608, 610, -1, 610, 640, 639, -1, + 640, 610, 641, -1, 641, 642, 640, -1, + 642, 641, 643, -1, 643, 644, 642, -1, + 644, 643, 645, -1, 645, 646, 644, -1, + 646, 645, 647, -1, 647, 648, 646, -1, + 648, 647, 649, -1, 649, 650, 648, -1, + 650, 649, 651, -1, 651, 652, 650, -1, + 652, 651, 653, -1, 653, 654, 652, -1, + 654, 653, 655, -1, 655, 656, 654, -1, + 656, 655, 553, -1, 553, 552, 656, -1, + 657, 656, 552, -1, 552, 658, 657, -1, + 552, 551, 658, -1, 659, 660, 661, -1, + 659, 661, 662, -1, 662, 663, 659, -1, + 663, 662, 664, -1, 664, 665, 663, -1, + 665, 664, 666, -1, 666, 667, 665, -1, + 666, 668, 667, -1, 668, 666, 669, -1, + 669, 670, 668, -1, 670, 669, 671, -1, + 671, 672, 670, -1, 673, 674, 675, -1, + 673, 676, 674, -1, 673, 677, 676, -1, + 673, 675, 677, -1, 675, 678, 677, -1, + 675, 679, 678, -1, 679, 675, 680, -1, + 680, 681, 679, -1, 681, 680, 682, -1, + 682, 683, 681, -1, 683, 682, 684, -1, + 684, 685, 683, -1, 685, 684, 686, -1, + 686, 687, 685, -1, 687, 686, 688, -1, + 688, 689, 687, -1, 689, 688, 690, -1, + 690, 691, 689, -1, 691, 690, 692, -1, + 692, 693, 691, -1, 693, 692, 694, -1, + 694, 695, 693, -1, 695, 694, 696, -1, + 696, 697, 695, -1, 697, 696, 698, -1, + 698, 699, 697, -1, 699, 698, 700, -1, + 700, 701, 699, -1, 701, 700, 702, -1, + 702, 703, 701, -1, 703, 702, 704, -1, + 704, 705, 703, -1, 705, 704, 706, -1, + 706, 707, 705, -1, 707, 706, 708, -1, + 708, 709, 707, -1, 709, 708, 710, -1, + 710, 711, 709, -1, 711, 710, 712, -1, + 712, 713, 711, -1, 714, 715, 716, -1, + 715, 714, 717, -1, 717, 718, 715, -1, + 718, 717, 719, -1, 719, 720, 718, -1, + 720, 719, 721, -1, 721, 722, 720, -1, + 722, 721, 723, -1, 723, 724, 722, -1, + 724, 723, 725, -1, 725, 726, 724, -1, + 726, 725, 727, -1, 727, 728, 726, -1, + 728, 727, 729, -1, 729, 730, 728, -1, + 730, 729, 731, -1, 731, 732, 730, -1, + 732, 731, 733, -1, 733, 734, 732, -1, + 734, 733, 735, -1, 735, 736, 734, -1, + 736, 735, 737, -1, 737, 738, 736, -1, + 738, 737, 739, -1, 739, 740, 738, -1, + 740, 739, 741, -1, 741, 742, 740, -1, + 742, 741, 743, -1, 743, 744, 742, -1, + 744, 743, 745, -1, 745, 746, 744, -1, + 746, 745, 747, -1, 747, 748, 746, -1, + 748, 747, 749, -1, 749, 750, 748, -1, + 751, 752, 750, -1, 750, 749, 751, -1, + 753, 754, 755, -1, 753, 755, 756, -1, + 753, 756, 751, -1, 753, 751, 749, -1, + 749, 754, 753, -1, 754, 749, 747, -1, + 747, 757, 754, -1, 757, 747, 745, -1, + 745, 758, 757, -1, 758, 745, 743, -1, + 743, 759, 758, -1, 759, 743, 741, -1, + 741, 760, 759, -1, 760, 741, 739, -1, + 739, 761, 760, -1, 761, 739, 737, -1, + 737, 762, 761, -1, 762, 737, 735, -1, + 735, 763, 762, -1, 763, 735, 733, -1, + 733, 764, 763, -1, 764, 733, 731, -1, + 731, 765, 764, -1, 765, 731, 729, -1, + 729, 766, 765, -1, 766, 729, 727, -1, + 727, 767, 766, -1, 767, 727, 725, -1, + 725, 768, 767, -1, 768, 725, 723, -1, + 723, 769, 768, -1, 769, 723, 721, -1, + 721, 770, 769, -1, 770, 721, 719, -1, + 719, 771, 770, -1, 771, 719, 717, -1, + 717, 772, 771, -1, 772, 717, 714, -1, + 714, 773, 772, -1, 773, 714, 716, -1, + 716, 774, 773, -1, 774, 716, 713, -1, + 775, 713, 716, -1, 713, 775, 776, -1, + 776, 711, 713, -1, 711, 776, 777, -1, + 777, 709, 711, -1, 709, 777, 778, -1, + 778, 707, 709, -1, 707, 778, 779, -1, + 779, 705, 707, -1, 705, 779, 780, -1, + 780, 703, 705, -1, 703, 780, 781, -1, + 781, 701, 703, -1, 701, 781, 782, -1, + 782, 699, 701, -1, 699, 782, 783, -1, + 783, 697, 699, -1, 697, 783, 784, -1, + 784, 695, 697, -1, 695, 784, 785, -1, + 785, 693, 695, -1, 693, 785, 786, -1, + 786, 691, 693, -1, 691, 786, 787, -1, + 787, 689, 691, -1, 689, 787, 788, -1, + 788, 687, 689, -1, 687, 788, 789, -1, + 789, 685, 687, -1, 685, 789, 790, -1, + 790, 683, 685, -1, 683, 790, 791, -1, + 791, 681, 683, -1, 681, 791, 792, -1, + 792, 679, 681, -1, 679, 792, 793, -1, + 793, 678, 679, -1, 794, 795, 678, -1, + 678, 796, 794, -1, 678, 793, 796, -1, + 797, 798, 799, -1, 800, 801, 798, -1, + 801, 800, 802, -1, 803, 804, 805, -1, + 806, 807, 808, -1, 808, 809, 806, -1, + 809, 808, 810, -1, 810, 811, 809, -1, + 811, 810, 812, -1, 812, 813, 811, -1, + 813, 812, 814, -1, 814, 815, 813, -1, + 815, 814, 816, -1, 816, 817, 815, -1, + 817, 816, 818, -1, 818, 819, 817, -1, + 819, 818, 820, -1, 820, 821, 819, -1, + 821, 820, 822, -1, 822, 823, 821, -1, + 823, 822, 824, -1, 824, 825, 823, -1, + 825, 824, 826, -1, 826, 827, 825, -1, + 827, 826, 828, -1, 828, 829, 827, -1, + 829, 828, 830, -1, 830, 831, 829, -1, + 831, 830, 832, -1, 832, 833, 831, -1, + 833, 832, 834, -1, 834, 835, 833, -1, + 835, 834, 836, -1, 836, 837, 835, -1, + 837, 836, 838, -1, 838, 839, 837, -1, + 839, 838, 840, -1, 840, 841, 839, -1, + 841, 840, 842, -1, 842, 843, 841, -1, + 844, 845, 843, -1, 843, 842, 844, -1, + 846, 844, 842, -1, 842, 847, 846, -1, + 847, 842, 840, -1, 840, 848, 847, -1, + 848, 840, 838, -1, 838, 849, 848, -1, + 849, 838, 836, -1, 836, 850, 849, -1, + 850, 836, 834, -1, 834, 851, 850, -1, + 851, 834, 832, -1, 832, 852, 851, -1, + 852, 832, 830, -1, 830, 853, 852, -1, + 853, 830, 828, -1, 828, 854, 853, -1, + 854, 828, 826, -1, 826, 855, 854, -1, + 855, 826, 824, -1, 824, 856, 855, -1, + 856, 824, 822, -1, 822, 857, 856, -1, + 857, 822, 820, -1, 820, 858, 857, -1, + 858, 820, 818, -1, 818, 859, 858, -1, + 859, 818, 816, -1, 816, 860, 859, -1, + 860, 816, 814, -1, 814, 861, 860, -1, + 861, 814, 812, -1, 812, 862, 861, -1, + 862, 812, 810, -1, 810, 863, 862, -1, + 863, 810, 808, -1, 808, 864, 863, -1, + 864, 808, 807, -1, 807, 865, 864, -1, + 866, 867, 868, -1, 867, 866, 869, -1, + 869, 870, 867, -1, 870, 869, 871, -1, + 871, 872, 870, -1, 872, 871, 873, -1, + 873, 874, 872, -1, 874, 873, 875, -1, + 875, 876, 874, -1, 876, 875, 877, -1, + 877, 878, 876, -1, 878, 877, 879, -1, + 879, 880, 878, -1, 880, 879, 881, -1, + 881, 882, 880, -1, 882, 881, 883, -1, + 883, 884, 882, -1, 884, 883, 885, -1, + 885, 886, 884, -1, 886, 885, 887, -1, + 887, 888, 886, -1, 888, 887, 889, -1, + 889, 890, 888, -1, 890, 889, 891, -1, + 891, 892, 890, -1, 892, 891, 893, -1, + 893, 894, 892, -1, 894, 893, 895, -1, + 895, 896, 894, -1, 896, 895, 897, -1, + 897, 898, 896, -1, 898, 897, 899, -1, + 899, 900, 898, -1, 900, 899, 901, -1, + 901, 902, 900, -1, 902, 901, 903, -1, + 903, 904, 902, -1, 905, 906, 904, -1, + 905, 904, 907, -1, 907, 908, 905, -1, + 908, 907, 909, -1, 909, 910, 908, -1, + 910, 909, 911, -1, 911, 912, 910, -1, + 912, 911, 913, -1, 913, 914, 912, -1, + 913, 915, 914, -1, 915, 913, 916, -1, + 916, 917, 915, -1, 917, 916, 918, -1, + 918, 919, 917, -1, 919, 918, 920, -1, + 920, 921, 919, -1, 922, 923, 924, -1, + 924, 925, 922, -1, 925, 924, 926, -1, + 926, 927, 925, -1, 927, 926, 928, -1, + 928, 929, 927, -1, 929, 928, 930, -1, + 930, 931, 929, -1, 931, 930, 932, -1, + 932, 933, 931, -1, 933, 932, 934, -1, + 934, 935, 933, -1, 935, 934, 936, -1, + 936, 937, 935, -1, 937, 936, 938, -1, + 938, 939, 937, -1, 939, 938, 940, -1, + 940, 941, 939, -1, 941, 940, 942, -1, + 942, 943, 941, -1, 943, 942, 944, -1, + 944, 945, 943, -1, 945, 944, 946, -1, + 946, 947, 945, -1, 947, 946, 948, -1, + 948, 949, 947, -1, 949, 948, 950, -1, + 950, 951, 949, -1, 951, 950, 952, -1, + 952, 953, 951, -1, 953, 952, 954, -1, + 954, 955, 953, -1, 955, 954, 956, -1, + 956, 957, 955, -1, 957, 956, 958, -1, + 958, 959, 957, -1, 959, 958, 960, -1, + 960, 961, 959, -1, 961, 960, 962, -1, + 962, 963, 961, -1, 963, 962, 921, -1, + 921, 920, 963, -1, 920, 964, 963, -1, + 920, 965, 964, -1, 965, 920, 918, -1, + 918, 966, 965, -1, 966, 918, 916, -1, + 916, 967, 966, -1, 967, 916, 913, -1, + 967, 913, 911, -1, 911, 968, 967, -1, + 968, 911, 909, -1, 909, 969, 968, -1, + 969, 909, 907, -1, 907, 970, 969, -1, + 970, 907, 904, -1, 904, 903, 970, -1, + 970, 903, 971, -1, 970, 971, 972, -1, + 972, 969, 970, -1, 969, 972, 973, -1, + 973, 968, 969, -1, 968, 973, 974, -1, + 974, 967, 968, -1, 974, 966, 967, -1, + 966, 974, 975, -1, 975, 965, 966, -1, + 965, 975, 976, -1, 976, 964, 965, -1, + 964, 976, 977, -1, 964, 977, 978, -1, + 979, 980, 981, -1, 979, 977, 980, -1, + 979, 978, 977, -1, 979, 982, 978, -1, + 982, 979, 981, -1, 981, 983, 982, -1, + 983, 981, 984, -1, 984, 985, 983, -1, + 985, 984, 986, -1, 986, 987, 985, -1, + 987, 986, 988, -1, 988, 989, 987, -1, + 989, 988, 990, -1, 990, 991, 989, -1, + 991, 990, 992, -1, 992, 993, 991, -1, + 993, 992, 994, -1, 994, 995, 993, -1, + 995, 994, 996, -1, 996, 997, 995, -1, + 997, 996, 998, -1, 998, 999, 997, -1, + 999, 998, 1000, -1, 1000, 1001, 999, -1, + 1001, 1000, 1002, -1, 1002, 1003, 1001, -1, + 1003, 1002, 1004, -1, 1004, 1005, 1003, -1, + 1005, 1004, 1006, -1, 1006, 1007, 1005, -1, + 1007, 1006, 1008, -1, 1008, 1009, 1007, -1, + 1009, 1008, 1010, -1, 1010, 1011, 1009, -1, + 1011, 1010, 1012, -1, 1012, 1013, 1011, -1, + 1013, 1012, 1014, -1, 1014, 1015, 1013, -1, + 1015, 1014, 1016, -1, 1016, 1017, 1015, -1, + 1017, 1016, 1018, -1, 1018, 1019, 1017, -1, + 1019, 1018, 865, -1, 865, 807, 1019, -1, + 1019, 807, 1020, -1, 1020, 1017, 1019, -1, + 1017, 1020, 1021, -1, 1021, 1015, 1017, -1, + 1015, 1021, 1022, -1, 1022, 1013, 1015, -1, + 1013, 1022, 1023, -1, 1023, 1011, 1013, -1, + 1011, 1023, 1024, -1, 1024, 1009, 1011, -1, + 1009, 1024, 1025, -1, 1025, 1007, 1009, -1, + 1007, 1025, 1026, -1, 1026, 1005, 1007, -1, + 1005, 1026, 1027, -1, 1027, 1003, 1005, -1, + 1003, 1027, 1028, -1, 1028, 1001, 1003, -1, + 1001, 1028, 1029, -1, 1029, 999, 1001, -1, + 999, 1029, 1030, -1, 1030, 997, 999, -1, + 997, 1030, 1031, -1, 1031, 995, 997, -1, + 995, 1031, 1032, -1, 1032, 993, 995, -1, + 993, 1032, 1033, -1, 1033, 991, 993, -1, + 991, 1033, 1034, -1, 1034, 989, 991, -1, + 989, 1034, 1035, -1, 1035, 987, 989, -1, + 987, 1035, 1036, -1, 1036, 985, 987, -1, + 985, 1036, 1037, -1, 1037, 983, 985, -1, + 983, 1037, 1038, -1, 1038, 982, 983, -1, + 982, 1038, 1039, -1, 1039, 978, 982, -1, + 978, 1039, 1040, -1, 1040, 964, 978, -1, + 1040, 963, 964, -1, 1040, 961, 963, -1, + 961, 1040, 1039, -1, 1039, 959, 961, -1, + 959, 1039, 1038, -1, 1038, 957, 959, -1, + 957, 1038, 1037, -1, 1037, 955, 957, -1, + 955, 1037, 1036, -1, 1036, 953, 955, -1, + 953, 1036, 1035, -1, 1035, 951, 953, -1, + 951, 1035, 1034, -1, 1034, 949, 951, -1, + 949, 1034, 1033, -1, 1033, 947, 949, -1, + 947, 1033, 1032, -1, 1032, 945, 947, -1, + 945, 1032, 1031, -1, 1031, 943, 945, -1, + 943, 1031, 1030, -1, 1030, 941, 943, -1, + 941, 1030, 1029, -1, 1029, 939, 941, -1, + 939, 1029, 1028, -1, 1028, 937, 939, -1, + 937, 1028, 1027, -1, 1027, 935, 937, -1, + 935, 1027, 1026, -1, 1026, 933, 935, -1, + 933, 1026, 1025, -1, 1025, 931, 933, -1, + 931, 1025, 1024, -1, 1024, 929, 931, -1, + 929, 1024, 1023, -1, 1023, 927, 929, -1, + 927, 1023, 1022, -1, 1022, 925, 927, -1, + 925, 1022, 1021, -1, 1021, 922, 925, -1, + 922, 1021, 1020, -1, 1020, 923, 922, -1, + 923, 1020, 807, -1, 807, 806, 923, -1, + 1041, 923, 806, -1, 806, 1042, 1041, -1, + 1042, 806, 809, -1, 809, 1043, 1042, -1, + 1043, 809, 811, -1, 811, 1044, 1043, -1, + 1044, 811, 813, -1, 813, 1045, 1044, -1, + 1045, 813, 815, -1, 815, 1046, 1045, -1, + 1046, 815, 817, -1, 817, 1047, 1046, -1, + 1047, 817, 819, -1, 819, 1048, 1047, -1, + 1048, 819, 821, -1, 821, 1049, 1048, -1, + 1049, 821, 823, -1, 823, 1050, 1049, -1, + 1050, 823, 825, -1, 825, 1051, 1050, -1, + 1051, 825, 827, -1, 827, 1052, 1051, -1, + 1052, 827, 829, -1, 829, 1053, 1052, -1, + 1053, 829, 831, -1, 831, 1054, 1053, -1, + 1054, 831, 833, -1, 833, 1055, 1054, -1, + 1055, 833, 835, -1, 835, 1056, 1055, -1, + 1056, 835, 837, -1, 837, 1057, 1056, -1, + 1057, 837, 839, -1, 839, 1058, 1057, -1, + 1058, 839, 841, -1, 841, 1059, 1058, -1, + 1059, 841, 843, -1, 843, 1060, 1059, -1, + 1060, 843, 845, -1, 845, 1061, 1060, -1, + 1061, 845, 803, -1, 803, 805, 1061, -1, + 1062, 1063, 1064, -1, 1065, 1066, 1067, -1, + 1067, 1068, 1065, -1, 1068, 1067, 1069, -1, + 1069, 1070, 1068, -1, 1070, 1069, 1071, -1, + 1071, 1072, 1070, -1, 1072, 1071, 1073, -1, + 1073, 1074, 1072, -1, 1074, 1073, 1075, -1, + 1075, 1076, 1074, -1, 1076, 1075, 1077, -1, + 1077, 1078, 1076, -1, 1078, 1077, 1079, -1, + 1079, 1080, 1078, -1, 1080, 1079, 1081, -1, + 1081, 1082, 1080, -1, 1082, 1081, 1083, -1, + 1083, 1084, 1082, -1, 1084, 1083, 1085, -1, + 1085, 1086, 1084, -1, 1086, 1085, 1087, -1, + 1087, 1088, 1086, -1, 1088, 1087, 1089, -1, + 1089, 1090, 1088, -1, 1090, 1089, 1091, -1, + 1091, 1092, 1090, -1, 1092, 1091, 1093, -1, + 1093, 1094, 1092, -1, 1094, 1093, 1095, -1, + 1095, 1096, 1094, -1, 1096, 1095, 1097, -1, + 1097, 1098, 1096, -1, 1098, 1097, 1099, -1, + 1099, 1100, 1098, -1, 1100, 1099, 1101, -1, + 1101, 1102, 1100, -1, 1102, 1101, 1103, -1, + 1103, 1104, 1102, -1, 1104, 1103, 1105, -1, + 1105, 1106, 1104, -1, 1106, 1105, 1107, -1, + 1107, 1108, 1106, -1, 1108, 1107, 1109, -1, + 1109, 1110, 1108, -1, 1110, 1109, 1111, -1, + 1111, 1112, 1110, -1, 1112, 1111, 1113, -1, + 1113, 1114, 1112, -1, 1114, 1113, 1115, -1, + 1115, 1116, 1114, -1, 1116, 1115, 1117, -1, + 1117, 1118, 1116, -1, 1118, 1117, 1119, -1, + 1119, 1120, 1118, -1, 1120, 1119, 1121, -1, + 1121, 1122, 1120, -1, 1122, 1121, 1123, -1, + 1123, 1124, 1122, -1, 1124, 1123, 1125, -1, + 1125, 1126, 1124, -1, 1126, 1125, 1127, -1, + 1127, 1128, 1126, -1, 1128, 1127, 1129, -1, + 1129, 1130, 1128, -1, 1130, 1129, 1131, -1, + 1131, 1132, 1130, -1, 1132, 1131, 1133, -1, + 1133, 1134, 1132, -1, 1134, 1133, 1135, -1, + 1135, 1136, 1134, -1, 1136, 1135, 1137, -1, + 1137, 1138, 1136, -1, 1138, 1137, 1139, -1, + 1139, 1140, 1138, -1, 1140, 1139, 1141, -1, + 1141, 1142, 1140, -1, 1142, 1141, 1143, -1, + 1143, 1144, 1142, -1, 1144, 1143, 1145, -1, + 1145, 1146, 1144, -1, 1146, 1145, 1147, -1, + 1147, 1148, 1146, -1, 1148, 1147, 1149, -1, + 1149, 1150, 1148, -1, 1150, 1149, 1063, -1, + 1063, 1062, 1150, -1, 1151, 1152, 1062, -1, + 1153, 1154, 1155, -1, 1156, 1157, 1158, -1, + 1157, 1156, 1159, -1, 1157, 1159, 1160, -1, + 1161, 1160, 1159, -1, 1161, 1162, 1160, -1, + 1162, 1161, 1163, -1, 1163, 1164, 1162, -1, + 1165, 1166, 1164, -1, 1164, 1163, 1165, -1, + 1167, 1168, 1169, -1, 1170, 1171, 1172, -1, + 1173, 1174, 1175, -1, 1176, 1177, 1178, -1, + 1179, 1178, 1177, -1, 1180, 1181, 1182, -1, + 1182, 1183, 1180, -1, 1184, 1185, 1186, -1, + 1185, 1184, 1183, -1, 1183, 1182, 1185, -1, + 1185, 1182, 1187, -1, 1185, 1187, 1188, -1, + 1188, 1186, 1185, -1, 1186, 1188, 1189, -1, + 1189, 1190, 1186, -1, 1190, 1189, 1191, -1, + 1191, 1192, 1190, -1, 1192, 1191, 1193, -1, + 1193, 1194, 1192, -1, 1194, 1193, 1195, -1, + 1195, 1196, 1194, -1, 1196, 1195, 1197, -1, + 1197, 1198, 1196, -1, 1198, 1197, 1199, -1, + 1199, 1200, 1198, -1, 1200, 1199, 1201, -1, + 1201, 1202, 1200, -1, 1202, 1201, 1203, -1, + 1203, 1204, 1202, -1, 1204, 1203, 1205, -1, + 1205, 1206, 1204, -1, 1206, 1205, 1207, -1, + 1207, 1208, 1206, -1, 1208, 1207, 1209, -1, + 1209, 1210, 1208, -1, 1210, 1209, 1211, -1, + 1211, 1212, 1210, -1, 1212, 1211, 1213, -1, + 1213, 1214, 1212, -1, 1214, 1213, 1215, -1, + 1215, 1216, 1214, -1, 1216, 1215, 1217, -1, + 1217, 1218, 1216, -1, 1218, 1217, 1219, -1, + 1219, 1220, 1218, -1, 1220, 1219, 1221, -1, + 1221, 1222, 1220, -1, 1222, 1221, 1223, -1, + 1223, 1224, 1222, -1, 1224, 1223, 1225, -1, + 1225, 1226, 1224, -1, 1226, 1225, 1227, -1, + 1227, 1228, 1226, -1, 1228, 1227, 1229, -1, + 1229, 1230, 1228, -1, 1230, 1229, 1231, -1, + 1231, 1232, 1230, -1, 1232, 1231, 1233, -1, + 1233, 1234, 1232, -1, 1234, 1233, 1235, -1, + 1235, 1236, 1234, -1, 1236, 1235, 1237, -1, + 1237, 1238, 1236, -1, 1238, 1237, 1239, -1, + 1239, 1240, 1238, -1, 1240, 1239, 1241, -1, + 1241, 1242, 1240, -1, 1242, 1241, 1243, -1, + 1243, 1244, 1242, -1, 1244, 1243, 1245, -1, + 1245, 1246, 1244, -1, 1246, 1245, 1247, -1, + 1247, 1248, 1246, -1, 1248, 1247, 1249, -1, + 1249, 1250, 1248, -1, 1250, 1249, 1251, -1, + 1251, 1252, 1250, -1, 1252, 1251, 1253, -1, + 1253, 1254, 1252, -1, 1254, 1253, 1255, -1, + 1255, 1256, 1254, -1, 1256, 1255, 1257, -1, + 1257, 1258, 1256, -1, 1258, 1257, 1259, -1, + 1259, 1260, 1258, -1, 1260, 1259, 1261, -1, + 1261, 1262, 1260, -1, 1262, 1261, 1263, -1, + 1263, 1264, 1262, -1, 1264, 1263, 1265, -1, + 1265, 1266, 1264, -1, 1266, 1265, 1267, -1, + 1267, 1268, 1266, -1, 1268, 1267, 1269, -1, + 1269, 1270, 1268, -1, 1270, 1269, 1271, -1, + 1271, 1272, 1270, -1, 1272, 1271, 1273, -1, + 1273, 1274, 1272, -1, 1274, 1273, 1275, -1, + 1275, 1276, 1274, -1, 1276, 1275, 1277, -1, + 1277, 1278, 1276, -1, 1278, 1277, 1279, -1, + 1278, 1279, 1280, -1, 1280, 1281, 1278, -1, + 1281, 1280, 1282, -1, 1282, 1283, 1281, -1, + 1283, 1282, 1284, -1, 1284, 1285, 1283, -1, + 1285, 1284, 1286, -1, 1286, 1287, 1285, -1, + 1287, 1286, 1288, -1, 1288, 1289, 1287, -1, + 1289, 1288, 1290, -1, 1290, 1291, 1289, -1, + 1291, 1290, 1292, -1, 1292, 1293, 1291, -1, + 1293, 1292, 1294, -1, 1294, 1295, 1293, -1, + 1295, 1294, 1296, -1, 1296, 1297, 1295, -1, + 1297, 1296, 1298, -1, 1298, 1299, 1297, -1, + 1299, 1298, 1300, -1, 1300, 1301, 1299, -1, + 1301, 1300, 1302, -1, 1302, 1303, 1301, -1, + 1303, 1302, 1304, -1, 1304, 1305, 1303, -1, + 1305, 1304, 1306, -1, 1306, 1307, 1305, -1, + 1307, 1306, 1308, -1, 1308, 1309, 1307, -1, + 1309, 1308, 1310, -1, 1310, 1311, 1309, -1, + 1311, 1310, 1312, -1, 1312, 1313, 1311, -1, + 1313, 1312, 1314, -1, 1314, 1315, 1313, -1, + 1315, 1314, 1316, -1, 1316, 1317, 1315, -1, + 1317, 1316, 1318, -1, 1318, 1319, 1317, -1, + 1319, 1318, 1320, -1, 1320, 1321, 1319, -1, + 1321, 1320, 1322, -1, 1322, 1323, 1321, -1, + 1323, 1322, 1324, -1, 1324, 1325, 1323, -1, + 1325, 1324, 1326, -1, 1326, 1327, 1325, -1, + 1327, 1326, 1328, -1, 1328, 1329, 1327, -1, + 1329, 1328, 1330, -1, 1330, 1331, 1329, -1, + 1331, 1330, 1332, -1, 1332, 1333, 1331, -1, + 1333, 1332, 1334, -1, 1334, 1335, 1333, -1, + 1335, 1334, 1336, -1, 1336, 1337, 1335, -1, + 1337, 1336, 1338, -1, 1338, 1339, 1337, -1, + 1339, 1338, 1340, -1, 1340, 1341, 1339, -1, + 1341, 1340, 1342, -1, 1342, 1343, 1341, -1, + 1343, 1342, 1344, -1, 1344, 1345, 1343, -1, + 1345, 1344, 1346, -1, 1346, 1347, 1345, -1, + 1347, 1346, 1348, -1, 1348, 1349, 1347, -1, + 1349, 1348, 1350, -1, 1350, 1351, 1349, -1, + 1351, 1350, 1352, -1, 1352, 1353, 1351, -1, + 1353, 1352, 1354, -1, 1354, 1355, 1353, -1, + 1355, 1354, 1356, -1, 1356, 1357, 1355, -1, + 1357, 1356, 1358, -1, 1358, 1359, 1357, -1, + 1360, 1361, 1362, -1, 1361, 1360, 1363, -1, + 1361, 1363, 1364, -1, 1365, 1364, 1363, -1, + 1365, 1366, 1364, -1, 1364, 1367, 1368, -1, + 1367, 1364, 1366, -1, 1366, 1369, 1367, -1, + 1369, 1366, 1370, -1, 1370, 1371, 1369, -1, + 1371, 1370, 1372, -1, 1372, 1373, 1371, -1, + 1373, 1372, 1374, -1, 1374, 1375, 1373, -1, + 1375, 1374, 1376, -1, 1376, 1377, 1375, -1, + 1377, 1376, 1359, -1, 1359, 1358, 1377, -1, + 1358, 1378, 1377, -1, 1378, 1358, 1356, -1, + 1356, 1379, 1378, -1, 1379, 1356, 1354, -1, + 1354, 1380, 1379, -1, 1380, 1354, 1352, -1, + 1352, 1381, 1380, -1, 1381, 1352, 1350, -1, + 1350, 1382, 1381, -1, 1382, 1350, 1348, -1, + 1348, 1383, 1382, -1, 1383, 1348, 1346, -1, + 1346, 1384, 1383, -1, 1384, 1346, 1344, -1, + 1344, 1385, 1384, -1, 1385, 1344, 1342, -1, + 1342, 1386, 1385, -1, 1386, 1342, 1340, -1, + 1340, 1387, 1386, -1, 1387, 1340, 1338, -1, + 1338, 1388, 1387, -1, 1388, 1338, 1336, -1, + 1336, 1389, 1388, -1, 1389, 1336, 1334, -1, + 1334, 1390, 1389, -1, 1390, 1334, 1332, -1, + 1332, 1391, 1390, -1, 1391, 1332, 1330, -1, + 1330, 1392, 1391, -1, 1392, 1330, 1328, -1, + 1328, 1393, 1392, -1, 1393, 1328, 1326, -1, + 1326, 1394, 1393, -1, 1394, 1326, 1324, -1, + 1324, 1395, 1394, -1, 1395, 1324, 1322, -1, + 1322, 1396, 1395, -1, 1396, 1322, 1320, -1, + 1320, 1397, 1396, -1, 1397, 1320, 1318, -1, + 1318, 1398, 1397, -1, 1398, 1318, 1316, -1, + 1316, 1399, 1398, -1, 1399, 1316, 1314, -1, + 1314, 1400, 1399, -1, 1400, 1314, 1312, -1, + 1312, 1401, 1400, -1, 1401, 1312, 1310, -1, + 1310, 1402, 1401, -1, 1402, 1310, 1308, -1, + 1308, 1403, 1402, -1, 1403, 1308, 1306, -1, + 1306, 1404, 1403, -1, 1404, 1306, 1304, -1, + 1304, 1405, 1404, -1, 1405, 1304, 1302, -1, + 1302, 1406, 1405, -1, 1406, 1302, 1300, -1, + 1300, 1407, 1406, -1, 1407, 1300, 1298, -1, + 1298, 1408, 1407, -1, 1408, 1298, 1296, -1, + 1296, 1409, 1408, -1, 1409, 1296, 1294, -1, + 1294, 1410, 1409, -1, 1410, 1294, 1292, -1, + 1292, 1411, 1410, -1, 1411, 1292, 1290, -1, + 1290, 1412, 1411, -1, 1412, 1290, 1288, -1, + 1288, 1413, 1412, -1, 1413, 1288, 1286, -1, + 1286, 1414, 1413, -1, 1414, 1286, 1284, -1, + 1284, 1415, 1414, -1, 1415, 1284, 1282, -1, + 1282, 1416, 1415, -1, 1416, 1282, 1280, -1, + 1280, 1417, 1416, -1, 1417, 1280, 1279, -1, + 1279, 1418, 1417, -1, 1279, 1419, 1418, -1, + 1419, 1279, 1277, -1, 1277, 1420, 1419, -1, + 1420, 1277, 1275, -1, 1275, 1421, 1420, -1, + 1421, 1275, 1273, -1, 1273, 1422, 1421, -1, + 1422, 1273, 1271, -1, 1271, 1423, 1422, -1, + 1423, 1271, 1269, -1, 1269, 1424, 1423, -1, + 1424, 1269, 1267, -1, 1267, 1425, 1424, -1, + 1425, 1267, 1265, -1, 1265, 1426, 1425, -1, + 1426, 1265, 1263, -1, 1263, 1427, 1426, -1, + 1427, 1263, 1261, -1, 1261, 1428, 1427, -1, + 1428, 1261, 1259, -1, 1259, 1429, 1428, -1, + 1429, 1259, 1257, -1, 1257, 1430, 1429, -1, + 1430, 1257, 1255, -1, 1255, 1431, 1430, -1, + 1431, 1255, 1253, -1, 1253, 1432, 1431, -1, + 1432, 1253, 1251, -1, 1251, 1433, 1432, -1, + 1433, 1251, 1249, -1, 1249, 1434, 1433, -1, + 1434, 1249, 1247, -1, 1247, 1435, 1434, -1, + 1435, 1247, 1245, -1, 1245, 1436, 1435, -1, + 1436, 1245, 1243, -1, 1243, 1437, 1436, -1, + 1437, 1243, 1241, -1, 1241, 1438, 1437, -1, + 1438, 1241, 1239, -1, 1239, 1439, 1438, -1, + 1439, 1239, 1237, -1, 1237, 1440, 1439, -1, + 1440, 1237, 1235, -1, 1235, 1441, 1440, -1, + 1441, 1235, 1233, -1, 1233, 1442, 1441, -1, + 1442, 1233, 1231, -1, 1231, 1443, 1442, -1, + 1443, 1231, 1229, -1, 1229, 1444, 1443, -1, + 1444, 1229, 1227, -1, 1227, 1445, 1444, -1, + 1445, 1227, 1225, -1, 1225, 1446, 1445, -1, + 1446, 1225, 1223, -1, 1223, 1447, 1446, -1, + 1447, 1223, 1221, -1, 1221, 1448, 1447, -1, + 1448, 1221, 1219, -1, 1219, 1449, 1448, -1, + 1449, 1219, 1217, -1, 1217, 1450, 1449, -1, + 1450, 1217, 1215, -1, 1215, 1451, 1450, -1, + 1451, 1215, 1213, -1, 1213, 1452, 1451, -1, + 1452, 1213, 1211, -1, 1211, 1453, 1452, -1, + 1453, 1211, 1209, -1, 1209, 1454, 1453, -1, + 1454, 1209, 1207, -1, 1207, 1455, 1454, -1, + 1455, 1207, 1205, -1, 1205, 1456, 1455, -1, + 1456, 1205, 1203, -1, 1203, 1457, 1456, -1, + 1457, 1203, 1201, -1, 1201, 1458, 1457, -1, + 1458, 1201, 1199, -1, 1199, 1459, 1458, -1, + 1459, 1199, 1197, -1, 1197, 1460, 1459, -1, + 1461, 1462, 1463, -1, 1461, 1463, 1464, -1, + 1464, 1465, 1461, -1, 1465, 1464, 1466, -1, + 1466, 1467, 1465, -1, 1467, 1466, 1468, -1, + 1468, 1469, 1467, -1, 1469, 1468, 1470, -1, + 1470, 1471, 1469, -1, 1471, 1470, 1472, -1, + 1472, 1473, 1471, -1, 1473, 1472, 1474, -1, + 1474, 1475, 1473, -1, 1475, 1474, 1460, -1, + 1460, 1197, 1475, -1, 1475, 1197, 1195, -1, + 1195, 1473, 1475, -1, 1473, 1195, 1193, -1, + 1193, 1471, 1473, -1, 1471, 1193, 1191, -1, + 1191, 1469, 1471, -1, 1469, 1191, 1189, -1, + 1189, 1467, 1469, -1, 1467, 1189, 1188, -1, + 1188, 1465, 1467, -1, 1465, 1188, 1187, -1, + 1187, 1461, 1465, -1, 1187, 1476, 1461, -1, + 1477, 1478, 1479, -1, 1477, 1479, 1480, -1, + 1477, 1480, 1481, -1, 1477, 1481, 1482, -1, + 1482, 1478, 1477, -1, 1478, 1482, 1476, -1, + 1476, 1483, 1478, -1, 1483, 1476, 1187, -1, + 1483, 1187, 1182, -1, 1483, 1182, 1181, -1, + 1181, 1478, 1483, -1, 1181, 1479, 1478, -1, + 1181, 1180, 1479, -1, 1479, 1180, 1484, -1, + 1479, 1484, 1485, -1, 1485, 1480, 1479, -1, + 1480, 1485, 1486, -1, 1486, 1487, 1480, -1, + 1487, 1486, 1488, -1, 1488, 1489, 1487, -1, + 1489, 1488, 1178, -1, 1178, 1179, 1489, -1, + 1490, 1491, 1492, -1, 1492, 1493, 1490, -1, + 1493, 1492, 1494, -1, 1494, 1495, 1493, -1, + 1495, 1494, 1496, -1, 1496, 1497, 1495, -1, + 1497, 1496, 1498, -1, 1498, 1496, 1499, -1, + 1498, 1499, 1500, -1, 1500, 1501, 1498, -1, + 1502, 1503, 1504, -1, 1504, 1505, 1502, -1, + 1506, 1502, 1505, -1, 1505, 1501, 1506, -1, + 1507, 1508, 1509, -1, 1506, 1509, 1508, -1, + 1509, 1506, 1501, -1, 1501, 1500, 1509, -1, + 1179, 1509, 1500, -1, 1500, 1489, 1179, -1, + 1489, 1500, 1499, -1, 1499, 1487, 1489, -1, + 1487, 1499, 1510, -1, 1510, 1480, 1487, -1, + 1510, 1481, 1480, -1, 1511, 1481, 1510, -1, + 1481, 1511, 1512, -1, 1512, 1482, 1481, -1, + 1482, 1512, 1513, -1, 1513, 1476, 1482, -1, + 1513, 1461, 1476, -1, 1513, 1462, 1461, -1, + 1462, 1513, 1512, -1, 1512, 1514, 1462, -1, + 1514, 1512, 1511, -1, 1511, 1515, 1514, -1, + 1511, 1510, 1515, -1, 1516, 1515, 1510, -1, + 1516, 1510, 1499, -1, 1516, 1499, 1496, -1, + 1516, 1496, 1494, -1, 1494, 1515, 1516, -1, + 1515, 1494, 1492, -1, 1492, 1514, 1515, -1, + 1514, 1492, 1491, -1, 1491, 1462, 1514, -1, + 1491, 1463, 1462, -1, 1491, 1490, 1463, -1, + 1517, 1463, 1490, -1, 1490, 1518, 1517, -1, + 1518, 1490, 1493, -1, 1493, 1519, 1518, -1, + 1519, 1493, 1495, -1, 1495, 1520, 1519, -1, + 1520, 1495, 1497, -1, 1497, 1521, 1520, -1, + 1497, 1498, 1521, -1, 1522, 1521, 1498, -1, + 1522, 1498, 1501, -1, 1501, 1505, 1522, -1, + 1523, 1524, 1522, -1, 1523, 1522, 1505, -1, + 1505, 1504, 1523, -1, 1525, 1526, 1523, -1, + 1525, 1523, 1504, -1, 1504, 1527, 1525, -1, + 1527, 1504, 1503, -1, 1503, 1528, 1527, -1, + 1528, 1503, 1529, -1, 1530, 1529, 1531, -1, + 1530, 1528, 1529, -1, 1530, 1532, 1528, -1, + 1532, 1530, 1531, -1, 1533, 1534, 1535, -1, + 1534, 1533, 1536, -1, 1536, 1537, 1534, -1, + 1537, 1536, 1538, -1, 1538, 1539, 1537, -1, + 1538, 1540, 1539, -1, 1541, 1542, 1543, -1, + 1541, 1543, 1544, -1, 1543, 1545, 1544, -1, + 1545, 1543, 1546, -1, 1546, 1547, 1545, -1, + 1547, 1546, 1548, -1, 1548, 1549, 1547, -1, + 1549, 1548, 1550, -1, 1550, 1551, 1549, -1, + 1551, 1550, 1552, -1, 1552, 1553, 1551, -1, + 1553, 1554, 1555, -1, 1553, 1552, 1554, -1, + 1556, 1557, 1558, -1, 1559, 1557, 1556, -1, + 1559, 1556, 1560, -1, 1556, 1561, 1560, -1, + 1561, 1556, 1562, -1, 1562, 1563, 1561, -1, + 1563, 1562, 1564, -1, 1564, 1565, 1563, -1, + 1565, 1564, 1566, -1, 1566, 1567, 1565, -1, + 1567, 1566, 1568, -1, 1568, 1569, 1567, -1, + 1569, 1568, 1570, -1, 1570, 1571, 1569, -1, + 1571, 1570, 1572, -1, 1572, 1573, 1571, -1, + 1573, 1572, 1574, -1, 1574, 1575, 1573, -1, + 1575, 1574, 1576, -1, 1576, 1577, 1575, -1, + 1577, 1576, 1578, -1, 1578, 1579, 1577, -1, + 1579, 1578, 1580, -1, 1580, 1581, 1579, -1, + 1581, 1580, 1582, -1, 1582, 1583, 1581, -1, + 1583, 1582, 1584, -1, 1584, 1585, 1583, -1, + 1585, 1584, 1586, -1, 1586, 1587, 1585, -1, + 1587, 1586, 1588, -1, 1588, 1589, 1587, -1, + 1589, 1588, 1590, -1, 1590, 1591, 1589, -1, + 1591, 1590, 1592, -1, 1592, 1593, 1591, -1, + 1593, 1592, 1594, -1, 1594, 1595, 1593, -1, + 1595, 1594, 1596, -1, 1596, 1597, 1595, -1, + 1597, 1596, 1598, -1, 1598, 1599, 1597, -1, + 1599, 1598, 1600, -1, 1600, 1601, 1599, -1, + 1601, 1600, 1602, -1, 1602, 1603, 1601, -1, + 1603, 1602, 1604, -1, 1604, 1605, 1603, -1, + 1605, 1604, 1606, -1, 1606, 1607, 1605, -1, + 1607, 1606, 1608, -1, 1608, 1609, 1607, -1, + 1609, 1608, 1610, -1, 1610, 1611, 1609, -1, + 1611, 1610, 1612, -1, 1612, 1613, 1611, -1, + 1613, 1612, 1614, -1, 1614, 1615, 1613, -1, + 1615, 1614, 1616, -1, 1616, 1617, 1615, -1, + 1617, 1616, 1618, -1, 1618, 1619, 1617, -1, + 1619, 1618, 1620, -1, 1620, 1621, 1619, -1, + 1621, 1620, 1622, -1, 1622, 1623, 1621, -1, + 1623, 1622, 1624, -1, 1624, 1625, 1623, -1, + 1625, 1624, 1626, -1, 1626, 1627, 1625, -1, + 1627, 1626, 1628, -1, 1628, 1629, 1627, -1, + 1629, 1628, 1630, -1, 1630, 1631, 1629, -1, + 1631, 1630, 1632, -1, 1632, 1633, 1631, -1, + 1633, 1632, 1634, -1, 1634, 1635, 1633, -1, + 1635, 1634, 1636, -1, 1636, 1637, 1635, -1, + 1637, 1636, 1638, -1, 1638, 1639, 1637, -1, + 1639, 1638, 1640, -1, 1640, 1641, 1639, -1, + 1641, 1640, 1642, -1, 1642, 1643, 1641, -1, + 1643, 1642, 1644, -1, 1644, 1645, 1643, -1, + 1645, 1644, 1646, -1, 1646, 1647, 1645, -1, + 1647, 1646, 1648, -1, 1648, 1649, 1647, -1, + 1649, 1648, 1650, -1, 1650, 1651, 1649, -1, + 1651, 1650, 1652, -1, 1652, 1653, 1651, -1, + 1653, 1652, 1654, -1, 1654, 1655, 1653, -1, + 1655, 1654, 1656, -1, 1656, 1657, 1655, -1, + 1657, 1656, 1658, -1, 1658, 1659, 1657, -1, + 1659, 1658, 1660, -1, 1660, 1661, 1659, -1, + 1661, 1660, 1662, -1, 1662, 1663, 1661, -1, + 1663, 1662, 1664, -1, 1664, 1665, 1663, -1, + 1665, 1664, 1666, -1, 1666, 1667, 1665, -1, + 1667, 1666, 1668, -1, 1668, 1669, 1667, -1, + 1669, 1670, 1671, -1, 1671, 1667, 1669, -1, + 1667, 1671, 1672, -1, 1672, 1665, 1667, -1, + 1665, 1672, 1673, -1, 1673, 1663, 1665, -1, + 1663, 1673, 1674, -1, 1674, 1661, 1663, -1, + 1661, 1674, 1675, -1, 1675, 1659, 1661, -1, + 1659, 1675, 1676, -1, 1676, 1657, 1659, -1, + 1657, 1676, 1677, -1, 1677, 1655, 1657, -1, + 1655, 1677, 1678, -1, 1678, 1653, 1655, -1, + 1653, 1678, 1679, -1, 1679, 1651, 1653, -1, + 1651, 1679, 1680, -1, 1680, 1649, 1651, -1, + 1649, 1680, 1681, -1, 1681, 1647, 1649, -1, + 1647, 1681, 1682, -1, 1682, 1645, 1647, -1, + 1645, 1682, 1683, -1, 1683, 1643, 1645, -1, + 1643, 1683, 1684, -1, 1684, 1641, 1643, -1, + 1641, 1684, 1685, -1, 1685, 1639, 1641, -1, + 1639, 1685, 1686, -1, 1686, 1637, 1639, -1, + 1637, 1686, 1687, -1, 1687, 1635, 1637, -1, + 1635, 1687, 1688, -1, 1688, 1633, 1635, -1, + 1633, 1688, 1689, -1, 1689, 1631, 1633, -1, + 1631, 1689, 1690, -1, 1690, 1629, 1631, -1, + 1629, 1690, 1691, -1, 1691, 1627, 1629, -1, + 1627, 1691, 1692, -1, 1692, 1625, 1627, -1, + 1625, 1692, 1693, -1, 1693, 1623, 1625, -1, + 1623, 1693, 1694, -1, 1694, 1621, 1623, -1, + 1621, 1694, 1695, -1, 1695, 1619, 1621, -1, + 1619, 1695, 1696, -1, 1696, 1617, 1619, -1, + 1617, 1696, 1697, -1, 1697, 1615, 1617, -1, + 1615, 1697, 1698, -1, 1698, 1613, 1615, -1, + 1613, 1698, 1699, -1, 1699, 1611, 1613, -1, + 1611, 1699, 1700, -1, 1700, 1609, 1611, -1, + 1609, 1700, 1701, -1, 1701, 1607, 1609, -1, + 1607, 1701, 1702, -1, 1702, 1605, 1607, -1, + 1605, 1702, 1703, -1, 1703, 1603, 1605, -1, + 1603, 1703, 1704, -1, 1704, 1601, 1603, -1, + 1601, 1704, 1705, -1, 1705, 1599, 1601, -1, + 1599, 1705, 1706, -1, 1706, 1597, 1599, -1, + 1597, 1706, 1707, -1, 1707, 1595, 1597, -1, + 1595, 1707, 1708, -1, 1708, 1593, 1595, -1, + 1593, 1708, 1709, -1, 1709, 1591, 1593, -1, + 1591, 1709, 1710, -1, 1710, 1589, 1591, -1, + 1589, 1710, 1711, -1, 1711, 1587, 1589, -1, + 1587, 1711, 1712, -1, 1712, 1585, 1587, -1, + 1585, 1712, 1713, -1, 1713, 1583, 1585, -1, + 1583, 1713, 1714, -1, 1714, 1581, 1583, -1, + 1581, 1714, 1715, -1, 1715, 1579, 1581, -1, + 1579, 1715, 1716, -1, 1716, 1577, 1579, -1, + 1577, 1716, 1717, -1, 1717, 1575, 1577, -1, + 1575, 1717, 1718, -1, 1718, 1573, 1575, -1, + 1573, 1718, 1554, -1, 1554, 1571, 1573, -1, + 1571, 1554, 1552, -1, 1552, 1569, 1571, -1, + 1569, 1552, 1550, -1, 1550, 1567, 1569, -1, + 1567, 1550, 1548, -1, 1548, 1565, 1567, -1, + 1565, 1548, 1546, -1, 1546, 1563, 1565, -1, + 1563, 1546, 1543, -1, 1543, 1561, 1563, -1, + 1543, 1542, 1561, -1, 1719, 1561, 1542, -1, + 1542, 1720, 1719, -1, 1542, 1541, 1720, -1, + 1541, 1544, 1720, -1, 1544, 1721, 1720, -1, + 1721, 1544, 1545, -1, 1721, 1545, 1722, -1, + 1545, 1723, 1722, -1, 1723, 1545, 1547, -1, + 1547, 1724, 1723, -1, 1724, 1547, 1549, -1, + 1549, 1725, 1724, -1, 1725, 1549, 1551, -1, + 1551, 1726, 1725, -1, 1726, 1551, 1553, -1, + 1553, 1555, 1726, -1, 1555, 1727, 1540, -1, + 1540, 1726, 1555, -1, 1726, 1540, 1538, -1, + 1538, 1725, 1726, -1, 1725, 1538, 1536, -1, + 1536, 1724, 1725, -1, 1724, 1536, 1533, -1, + 1533, 1723, 1724, -1, 1728, 1729, 1723, -1, + 1723, 1533, 1728, -1, 1730, 1728, 1533, -1, + 1730, 1533, 1535, -1, 1535, 1531, 1730, -1, + 1535, 1731, 1531, -1, 1731, 1535, 1534, -1, + 1731, 1534, 1732, -1, 1732, 1531, 1731, -1, + 1732, 1532, 1531, -1, 1532, 1732, 1534, -1, + 1534, 1528, 1532, -1, 1528, 1534, 1537, -1, + 1537, 1527, 1528, -1, 1527, 1537, 1539, -1, + 1539, 1525, 1527, -1, 1539, 1733, 1525, -1, + 1734, 1735, 1736, -1, 1734, 1736, 1737, -1, + 1734, 1737, 1738, -1, 1734, 1738, 1739, -1, + 1739, 1735, 1734, -1, 1735, 1739, 1733, -1, + 1733, 1740, 1735, -1, 1740, 1733, 1539, -1, + 1740, 1539, 1540, -1, 1740, 1540, 1727, -1, + 1727, 1735, 1740, -1, 1727, 1736, 1735, -1, + 1727, 1555, 1736, -1, 1736, 1555, 1554, -1, + 1736, 1554, 1718, -1, 1718, 1737, 1736, -1, + 1737, 1718, 1717, -1, 1717, 1741, 1737, -1, + 1741, 1717, 1716, -1, 1716, 1742, 1741, -1, + 1742, 1716, 1715, -1, 1715, 1743, 1742, -1, + 1743, 1715, 1714, -1, 1714, 1744, 1743, -1, + 1744, 1714, 1713, -1, 1713, 1745, 1744, -1, + 1745, 1713, 1712, -1, 1712, 1746, 1745, -1, + 1746, 1712, 1711, -1, 1711, 1747, 1746, -1, + 1747, 1711, 1710, -1, 1710, 1748, 1747, -1, + 1748, 1710, 1709, -1, 1709, 1749, 1748, -1, + 1749, 1709, 1708, -1, 1708, 1750, 1749, -1, + 1750, 1708, 1707, -1, 1707, 1751, 1750, -1, + 1751, 1707, 1706, -1, 1706, 1752, 1751, -1, + 1752, 1706, 1705, -1, 1705, 1753, 1752, -1, + 1753, 1705, 1704, -1, 1704, 1754, 1753, -1, + 1754, 1704, 1703, -1, 1703, 1755, 1754, -1, + 1755, 1703, 1702, -1, 1702, 1756, 1755, -1, + 1756, 1702, 1701, -1, 1701, 1757, 1756, -1, + 1757, 1701, 1700, -1, 1700, 1758, 1757, -1, + 1758, 1700, 1699, -1, 1699, 1759, 1758, -1, + 1759, 1699, 1698, -1, 1698, 1760, 1759, -1, + 1760, 1698, 1697, -1, 1697, 1761, 1760, -1, + 1761, 1697, 1696, -1, 1696, 1762, 1761, -1, + 1762, 1696, 1695, -1, 1695, 1763, 1762, -1, + 1763, 1695, 1694, -1, 1694, 1764, 1763, -1, + 1764, 1694, 1693, -1, 1693, 1765, 1764, -1, + 1765, 1693, 1692, -1, 1692, 1766, 1765, -1, + 1766, 1692, 1691, -1, 1691, 1767, 1766, -1, + 1767, 1691, 1690, -1, 1690, 1768, 1767, -1, + 1768, 1690, 1689, -1, 1689, 1769, 1768, -1, + 1769, 1689, 1688, -1, 1688, 1770, 1769, -1, + 1770, 1688, 1687, -1, 1687, 1771, 1770, -1, + 1771, 1687, 1686, -1, 1686, 1772, 1771, -1, + 1772, 1686, 1685, -1, 1685, 1773, 1772, -1, + 1773, 1685, 1684, -1, 1684, 1774, 1773, -1, + 1774, 1684, 1683, -1, 1683, 1775, 1774, -1, + 1775, 1683, 1682, -1, 1682, 1776, 1775, -1, + 1776, 1682, 1681, -1, 1681, 1777, 1776, -1, + 1777, 1681, 1680, -1, 1680, 1778, 1777, -1, + 1778, 1680, 1679, -1, 1679, 1779, 1778, -1, + 1779, 1679, 1678, -1, 1678, 1780, 1779, -1, + 1780, 1678, 1677, -1, 1677, 1781, 1780, -1, + 1781, 1677, 1676, -1, 1676, 1782, 1781, -1, + 1782, 1676, 1675, -1, 1675, 1783, 1782, -1, + 1783, 1675, 1674, -1, 1674, 1784, 1783, -1, + 1784, 1674, 1673, -1, 1673, 1785, 1784, -1, + 1785, 1673, 1672, -1, 1672, 1786, 1785, -1, + 1786, 1672, 1671, -1, 1671, 1787, 1786, -1, + 1787, 1671, 1670, -1, 1670, 1788, 1787, -1, + 1788, 1789, 1790, -1, 1790, 1787, 1788, -1, + 1787, 1790, 1791, -1, 1791, 1786, 1787, -1, + 1786, 1791, 1792, -1, 1792, 1785, 1786, -1, + 1785, 1792, 1793, -1, 1793, 1784, 1785, -1, + 1784, 1793, 1794, -1, 1794, 1783, 1784, -1, + 1783, 1794, 1795, -1, 1795, 1782, 1783, -1, + 1782, 1795, 1796, -1, 1796, 1781, 1782, -1, + 1781, 1796, 1797, -1, 1797, 1780, 1781, -1, + 1780, 1797, 1798, -1, 1798, 1779, 1780, -1, + 1779, 1798, 1799, -1, 1799, 1778, 1779, -1, + 1778, 1799, 1800, -1, 1800, 1777, 1778, -1, + 1777, 1800, 1801, -1, 1801, 1776, 1777, -1, + 1776, 1801, 1802, -1, 1802, 1775, 1776, -1, + 1775, 1802, 1803, -1, 1803, 1774, 1775, -1, + 1774, 1803, 1804, -1, 1804, 1773, 1774, -1, + 1773, 1804, 1805, -1, 1805, 1772, 1773, -1, + 1772, 1805, 1806, -1, 1806, 1771, 1772, -1, + 1771, 1806, 1807, -1, 1807, 1770, 1771, -1, + 1770, 1807, 1808, -1, 1808, 1769, 1770, -1, + 1769, 1808, 1809, -1, 1809, 1768, 1769, -1, + 1768, 1809, 1810, -1, 1810, 1767, 1768, -1, + 1767, 1810, 1811, -1, 1811, 1766, 1767, -1, + 1766, 1811, 1812, -1, 1812, 1765, 1766, -1, + 1765, 1812, 1813, -1, 1813, 1764, 1765, -1, + 1764, 1813, 1814, -1, 1814, 1763, 1764, -1, + 1763, 1814, 1815, -1, 1815, 1762, 1763, -1, + 1762, 1815, 1816, -1, 1816, 1761, 1762, -1, + 1761, 1816, 1817, -1, 1817, 1760, 1761, -1, + 1760, 1817, 1818, -1, 1818, 1759, 1760, -1, + 1759, 1818, 1819, -1, 1819, 1758, 1759, -1, + 1758, 1819, 1820, -1, 1820, 1757, 1758, -1, + 1757, 1820, 1821, -1, 1821, 1756, 1757, -1, + 1756, 1821, 1822, -1, 1822, 1755, 1756, -1, + 1755, 1822, 1823, -1, 1823, 1754, 1755, -1, + 1754, 1823, 1824, -1, 1824, 1753, 1754, -1, + 1753, 1824, 1825, -1, 1825, 1752, 1753, -1, + 1752, 1825, 1826, -1, 1826, 1751, 1752, -1, + 1751, 1826, 1827, -1, 1827, 1750, 1751, -1, + 1750, 1827, 1828, -1, 1828, 1749, 1750, -1, + 1749, 1828, 1829, -1, 1829, 1748, 1749, -1, + 1748, 1829, 1830, -1, 1830, 1747, 1748, -1, + 1747, 1830, 1831, -1, 1831, 1746, 1747, -1, + 1746, 1831, 1832, -1, 1832, 1745, 1746, -1, + 1745, 1832, 1833, -1, 1833, 1744, 1745, -1, + 1744, 1833, 1834, -1, 1834, 1743, 1744, -1, + 1743, 1834, 1175, -1, 1175, 1742, 1743, -1, + 1742, 1175, 1174, -1, 1174, 1741, 1742, -1, + 1741, 1174, 1835, -1, 1835, 1737, 1741, -1, + 1835, 1738, 1737, -1, 1836, 1738, 1835, -1, + 1738, 1836, 1837, -1, 1837, 1739, 1738, -1, + 1739, 1837, 1838, -1, 1838, 1733, 1739, -1, + 1838, 1525, 1733, -1, 1838, 1526, 1525, -1, + 1526, 1838, 1837, -1, 1837, 1839, 1526, -1, + 1839, 1837, 1836, -1, 1836, 1840, 1839, -1, + 1836, 1835, 1840, -1, 1841, 1840, 1835, -1, + 1841, 1835, 1174, -1, 1174, 1173, 1841, -1, + 1841, 1173, 1842, -1, 1842, 1840, 1841, -1, + 1840, 1842, 1843, -1, 1843, 1839, 1840, -1, + 1839, 1843, 1844, -1, 1844, 1526, 1839, -1, + 1844, 1523, 1526, -1, 1844, 1524, 1523, -1, + 1524, 1844, 1843, -1, 1843, 1845, 1524, -1, + 1845, 1843, 1842, -1, 1842, 1846, 1845, -1, + 1847, 1848, 1849, -1, 1848, 1847, 1850, -1, + 1850, 1851, 1848, -1, 1851, 1850, 1846, -1, + 1846, 1842, 1851, -1, 1851, 1842, 1173, -1, + 1173, 1848, 1851, -1, 1848, 1173, 1175, -1, + 1175, 1849, 1848, -1, 1849, 1175, 1834, -1, + 1834, 1852, 1849, -1, 1852, 1834, 1833, -1, + 1833, 1853, 1852, -1, 1853, 1833, 1832, -1, + 1832, 1854, 1853, -1, 1854, 1832, 1831, -1, + 1831, 1855, 1854, -1, 1855, 1831, 1830, -1, + 1830, 1856, 1855, -1, 1856, 1830, 1829, -1, + 1829, 1857, 1856, -1, 1857, 1829, 1828, -1, + 1828, 1858, 1857, -1, 1858, 1828, 1827, -1, + 1827, 1859, 1858, -1, 1859, 1827, 1826, -1, + 1826, 1860, 1859, -1, 1860, 1826, 1825, -1, + 1825, 1861, 1860, -1, 1861, 1825, 1824, -1, + 1824, 1862, 1861, -1, 1862, 1824, 1823, -1, + 1823, 1863, 1862, -1, 1863, 1823, 1822, -1, + 1822, 1864, 1863, -1, 1864, 1822, 1821, -1, + 1821, 1865, 1864, -1, 1865, 1821, 1820, -1, + 1820, 1866, 1865, -1, 1866, 1820, 1819, -1, + 1819, 1867, 1866, -1, 1867, 1819, 1818, -1, + 1818, 1868, 1867, -1, 1868, 1818, 1817, -1, + 1817, 1869, 1868, -1, 1869, 1817, 1816, -1, + 1816, 1870, 1869, -1, 1870, 1816, 1815, -1, + 1815, 1871, 1870, -1, 1871, 1815, 1814, -1, + 1814, 1872, 1871, -1, 1872, 1814, 1813, -1, + 1813, 1873, 1872, -1, 1873, 1813, 1812, -1, + 1812, 1874, 1873, -1, 1874, 1812, 1811, -1, + 1811, 1875, 1874, -1, 1875, 1811, 1810, -1, + 1810, 1876, 1875, -1, 1876, 1810, 1809, -1, + 1809, 1877, 1876, -1, 1877, 1809, 1808, -1, + 1808, 1878, 1877, -1, 1878, 1808, 1807, -1, + 1807, 1879, 1878, -1, 1879, 1807, 1806, -1, + 1806, 1880, 1879, -1, 1880, 1806, 1805, -1, + 1805, 1881, 1880, -1, 1881, 1805, 1804, -1, + 1804, 1882, 1881, -1, 1882, 1804, 1803, -1, + 1803, 1883, 1882, -1, 1883, 1803, 1802, -1, + 1802, 1884, 1883, -1, 1884, 1802, 1801, -1, + 1801, 1885, 1884, -1, 1885, 1801, 1800, -1, + 1800, 1886, 1885, -1, 1886, 1800, 1799, -1, + 1799, 1887, 1886, -1, 1887, 1799, 1798, -1, + 1798, 1888, 1887, -1, 1888, 1798, 1797, -1, + 1797, 1889, 1888, -1, 1889, 1797, 1796, -1, + 1796, 1890, 1889, -1, 1890, 1796, 1795, -1, + 1795, 1891, 1890, -1, 1891, 1795, 1794, -1, + 1794, 1892, 1891, -1, 1892, 1794, 1793, -1, + 1793, 1893, 1892, -1, 1893, 1793, 1792, -1, + 1792, 1894, 1893, -1, 1894, 1792, 1791, -1, + 1791, 1895, 1894, -1, 1895, 1791, 1790, -1, + 1790, 1896, 1895, -1, 1896, 1790, 1789, -1, + 1789, 1897, 1896, -1, 1898, 1899, 1900, -1, + 1901, 1900, 1899, -1, 1900, 1901, 1897, -1, + 1897, 1789, 1900, -1, 1902, 1900, 1789, -1, + 1789, 1788, 1902, -1, 1903, 1904, 1905, -1, + 1905, 1904, 1902, -1, 1905, 1902, 1788, -1, + 1788, 1670, 1905, -1, 1906, 1905, 1670, -1, + 1670, 1669, 1906, -1, 1907, 1908, 1906, -1, + 1907, 1906, 1669, -1, 1669, 1668, 1907, -1, + 1907, 1909, 1910, -1, 1909, 1907, 1668, -1, + 1668, 1911, 1909, -1, 1911, 1668, 1666, -1, + 1666, 1912, 1911, -1, 1912, 1666, 1664, -1, + 1664, 1913, 1912, -1, 1913, 1664, 1662, -1, + 1662, 1914, 1913, -1, 1914, 1662, 1660, -1, + 1660, 1915, 1914, -1, 1915, 1660, 1658, -1, + 1658, 1916, 1915, -1, 1916, 1658, 1656, -1, + 1656, 1917, 1916, -1, 1917, 1656, 1654, -1, + 1654, 1918, 1917, -1, 1918, 1654, 1652, -1, + 1652, 1919, 1918, -1, 1919, 1652, 1650, -1, + 1650, 1920, 1919, -1, 1920, 1650, 1648, -1, + 1648, 1921, 1920, -1, 1921, 1648, 1646, -1, + 1646, 1922, 1921, -1, 1922, 1646, 1644, -1, + 1644, 1923, 1922, -1, 1923, 1644, 1642, -1, + 1642, 1924, 1923, -1, 1924, 1642, 1640, -1, + 1640, 1925, 1924, -1, 1925, 1640, 1638, -1, + 1638, 1926, 1925, -1, 1926, 1638, 1636, -1, + 1636, 1927, 1926, -1, 1927, 1636, 1634, -1, + 1634, 1928, 1927, -1, 1928, 1634, 1632, -1, + 1632, 1929, 1928, -1, 1929, 1632, 1630, -1, + 1630, 1930, 1929, -1, 1930, 1630, 1628, -1, + 1628, 1931, 1930, -1, 1931, 1628, 1626, -1, + 1626, 1932, 1931, -1, 1932, 1626, 1624, -1, + 1624, 1933, 1932, -1, 1933, 1624, 1622, -1, + 1622, 1934, 1933, -1, 1934, 1622, 1620, -1, + 1620, 1935, 1934, -1, 1935, 1620, 1618, -1, + 1618, 1936, 1935, -1, 1936, 1618, 1616, -1, + 1616, 1937, 1936, -1, 1937, 1616, 1614, -1, + 1614, 1938, 1937, -1, 1938, 1614, 1612, -1, + 1612, 1939, 1938, -1, 1939, 1612, 1610, -1, + 1610, 1940, 1939, -1, 1940, 1610, 1608, -1, + 1608, 1941, 1940, -1, 1941, 1608, 1606, -1, + 1606, 1942, 1941, -1, 1942, 1606, 1604, -1, + 1604, 1943, 1942, -1, 1943, 1604, 1602, -1, + 1602, 1944, 1943, -1, 1944, 1602, 1600, -1, + 1600, 1945, 1944, -1, 1945, 1600, 1598, -1, + 1598, 1946, 1945, -1, 1946, 1598, 1596, -1, + 1596, 1947, 1946, -1, 1947, 1596, 1594, -1, + 1594, 1948, 1947, -1, 1948, 1594, 1592, -1, + 1592, 1949, 1948, -1, 1949, 1592, 1590, -1, + 1590, 1950, 1949, -1, 1950, 1590, 1588, -1, + 1588, 1951, 1950, -1, 1951, 1588, 1586, -1, + 1586, 1952, 1951, -1, 1952, 1586, 1584, -1, + 1584, 1953, 1952, -1, 1953, 1584, 1582, -1, + 1582, 1954, 1953, -1, 1954, 1582, 1580, -1, + 1580, 1955, 1954, -1, 1955, 1580, 1578, -1, + 1578, 1956, 1955, -1, 1956, 1578, 1576, -1, + 1576, 1957, 1956, -1, 1957, 1576, 1574, -1, + 1574, 1958, 1957, -1, 1958, 1574, 1572, -1, + 1572, 1959, 1958, -1, 1959, 1572, 1570, -1, + 1570, 1960, 1959, -1, 1960, 1570, 1568, -1, + 1568, 1961, 1960, -1, 1961, 1568, 1566, -1, + 1566, 1962, 1961, -1, 1962, 1566, 1564, -1, + 1564, 1963, 1962, -1, 1963, 1564, 1562, -1, + 1562, 1964, 1963, -1, 1964, 1562, 1556, -1, + 1556, 1558, 1964, -1, 1171, 1965, 1966, -1, + 1966, 1967, 1171, -1, 1968, 1969, 1970, -1, + 1971, 1970, 1969, -1, 1971, 1972, 1970, -1, + 1558, 1973, 1970, -1, 1970, 1974, 1558, -1, + 1974, 1970, 1972, -1, 1972, 1975, 1974, -1, + 1975, 1972, 1976, -1, 1976, 1977, 1975, -1, + 1977, 1976, 1978, -1, 1978, 1979, 1977, -1, + 1979, 1978, 1980, -1, 1980, 1981, 1979, -1, + 1981, 1980, 1982, -1, 1982, 1983, 1981, -1, + 1983, 1982, 1984, -1, 1984, 1985, 1983, -1, + 1985, 1984, 1986, -1, 1986, 1987, 1985, -1, + 1987, 1986, 1988, -1, 1988, 1989, 1987, -1, + 1989, 1988, 1990, -1, 1990, 1991, 1989, -1, + 1991, 1990, 1992, -1, 1992, 1993, 1991, -1, + 1993, 1992, 1994, -1, 1994, 1995, 1993, -1, + 1995, 1994, 1996, -1, 1996, 1997, 1995, -1, + 1997, 1996, 1998, -1, 1998, 1999, 1997, -1, + 1999, 1998, 2000, -1, 2000, 2001, 1999, -1, + 2001, 2000, 2002, -1, 2002, 2003, 2001, -1, + 2003, 2002, 2004, -1, 2004, 2005, 2003, -1, + 2005, 2004, 2006, -1, 2006, 2007, 2005, -1, + 2007, 2006, 2008, -1, 2008, 2009, 2007, -1, + 2009, 2008, 2010, -1, 2010, 2011, 2009, -1, + 2011, 2010, 2012, -1, 2012, 2013, 2011, -1, + 2013, 2012, 2014, -1, 2014, 2015, 2013, -1, + 2015, 2014, 2016, -1, 2016, 2017, 2015, -1, + 2017, 2016, 2018, -1, 2018, 2019, 2017, -1, + 2019, 2018, 2020, -1, 2020, 2021, 2019, -1, + 2021, 2020, 2022, -1, 2022, 2023, 2021, -1, + 2023, 2022, 2024, -1, 2024, 2025, 2023, -1, + 2025, 2024, 2026, -1, 2026, 2027, 2025, -1, + 2027, 2026, 2028, -1, 2028, 2029, 2027, -1, + 2029, 2028, 2030, -1, 2030, 2031, 2029, -1, + 2031, 2030, 2032, -1, 2032, 2033, 2031, -1, + 2033, 2032, 2034, -1, 2034, 2035, 2033, -1, + 2035, 2034, 2036, -1, 2036, 2037, 2035, -1, + 2037, 2036, 2038, -1, 2038, 2039, 2037, -1, + 2039, 2038, 2040, -1, 2040, 2041, 2039, -1, + 2041, 2040, 2042, -1, 2042, 2043, 2041, -1, + 2043, 2042, 2044, -1, 2044, 2045, 2043, -1, + 2045, 2044, 2046, -1, 2046, 2047, 2045, -1, + 2047, 2046, 2048, -1, 2048, 2049, 2047, -1, + 2049, 2048, 2050, -1, 2050, 2051, 2049, -1, + 2051, 2050, 2052, -1, 2052, 2053, 2051, -1, + 2053, 2052, 2054, -1, 2054, 2055, 2053, -1, + 2055, 2054, 2056, -1, 2056, 2057, 2055, -1, + 2057, 2056, 2058, -1, 2058, 2059, 2057, -1, + 2059, 2058, 2060, -1, 2060, 2061, 2059, -1, + 2061, 2060, 2062, -1, 2062, 2063, 2061, -1, + 2063, 2062, 2064, -1, 2064, 2065, 2063, -1, + 2065, 2064, 2066, -1, 2066, 2067, 2065, -1, + 2067, 2066, 2068, -1, 2068, 2069, 2067, -1, + 2069, 2068, 2070, -1, 2070, 2071, 2069, -1, + 2071, 2070, 2072, -1, 2072, 2073, 2071, -1, + 2073, 2072, 2074, -1, 2074, 2075, 2073, -1, + 2075, 2074, 2076, -1, 2076, 2077, 2075, -1, + 2077, 2076, 2078, -1, 2078, 2079, 2077, -1, + 2079, 2078, 1967, -1, 1967, 1966, 2079, -1, + 1966, 2080, 2081, -1, 2081, 2079, 1966, -1, + 2079, 2081, 2082, -1, 2082, 2077, 2079, -1, + 2077, 2082, 2083, -1, 2083, 2075, 2077, -1, + 2075, 2083, 2084, -1, 2084, 2073, 2075, -1, + 2073, 2084, 2085, -1, 2085, 2071, 2073, -1, + 2071, 2085, 2086, -1, 2086, 2069, 2071, -1, + 2069, 2086, 2087, -1, 2087, 2067, 2069, -1, + 2067, 2087, 2088, -1, 2088, 2065, 2067, -1, + 2065, 2088, 2089, -1, 2089, 2063, 2065, -1, + 2063, 2089, 2090, -1, 2090, 2061, 2063, -1, + 2061, 2090, 2091, -1, 2091, 2059, 2061, -1, + 2059, 2091, 2092, -1, 2092, 2057, 2059, -1, + 2057, 2092, 2093, -1, 2093, 2055, 2057, -1, + 2055, 2093, 2094, -1, 2094, 2053, 2055, -1, + 2053, 2094, 2095, -1, 2095, 2051, 2053, -1, + 2051, 2095, 2096, -1, 2096, 2049, 2051, -1, + 2049, 2096, 2097, -1, 2097, 2047, 2049, -1, + 2047, 2097, 2098, -1, 2098, 2045, 2047, -1, + 2045, 2098, 2099, -1, 2099, 2043, 2045, -1, + 2043, 2099, 2100, -1, 2100, 2041, 2043, -1, + 2041, 2100, 2101, -1, 2101, 2039, 2041, -1, + 2039, 2101, 2102, -1, 2102, 2037, 2039, -1, + 2037, 2102, 2103, -1, 2103, 2035, 2037, -1, + 2035, 2103, 2104, -1, 2104, 2033, 2035, -1, + 2033, 2104, 2105, -1, 2105, 2031, 2033, -1, + 2031, 2105, 2106, -1, 2106, 2029, 2031, -1, + 2029, 2106, 2107, -1, 2107, 2027, 2029, -1, + 2027, 2107, 2108, -1, 2108, 2025, 2027, -1, + 2025, 2108, 2109, -1, 2109, 2023, 2025, -1, + 2023, 2109, 2110, -1, 2110, 2021, 2023, -1, + 2021, 2110, 2111, -1, 2111, 2019, 2021, -1, + 2019, 2111, 2112, -1, 2112, 2017, 2019, -1, + 2017, 2112, 2113, -1, 2113, 2015, 2017, -1, + 2015, 2113, 2114, -1, 2114, 2013, 2015, -1, + 2013, 2114, 2115, -1, 2115, 2011, 2013, -1, + 2011, 2115, 2116, -1, 2116, 2009, 2011, -1, + 2009, 2116, 2117, -1, 2117, 2007, 2009, -1, + 2007, 2117, 2118, -1, 2118, 2005, 2007, -1, + 2005, 2118, 2119, -1, 2119, 2003, 2005, -1, + 2003, 2119, 2120, -1, 2120, 2001, 2003, -1, + 2001, 2120, 2121, -1, 2121, 1999, 2001, -1, + 1999, 2121, 2122, -1, 2122, 1997, 1999, -1, + 1997, 2122, 2123, -1, 2123, 1995, 1997, -1, + 1995, 2123, 2124, -1, 2124, 1993, 1995, -1, + 1993, 2124, 2125, -1, 2125, 1991, 1993, -1, + 1991, 2125, 2126, -1, 2126, 1989, 1991, -1, + 1989, 2126, 2127, -1, 2127, 1987, 1989, -1, + 1987, 2127, 2128, -1, 2128, 1985, 1987, -1, + 1985, 2128, 2129, -1, 2129, 1983, 1985, -1, + 1983, 2129, 2130, -1, 2130, 1981, 1983, -1, + 1981, 2130, 2131, -1, 2131, 1979, 1981, -1, + 1979, 2131, 2132, -1, 2132, 1977, 1979, -1, + 1977, 2132, 2133, -1, 2133, 1975, 1977, -1, + 1975, 2133, 2134, -1, 2134, 1974, 1975, -1, + 1974, 2134, 2135, -1, 2135, 1558, 1974, -1, + 2135, 1964, 1558, -1, 1964, 2135, 2136, -1, + 2136, 1963, 1964, -1, 1963, 2136, 2137, -1, + 2137, 1962, 1963, -1, 1962, 2137, 2138, -1, + 2138, 1961, 1962, -1, 1961, 2138, 2139, -1, + 2139, 1960, 1961, -1, 1960, 2139, 2140, -1, + 2140, 1959, 1960, -1, 1959, 2140, 2141, -1, + 2141, 1958, 1959, -1, 1958, 2141, 2142, -1, + 2142, 1957, 1958, -1, 1957, 2142, 2143, -1, + 2143, 1956, 1957, -1, 1956, 2143, 2144, -1, + 2144, 1955, 1956, -1, 1955, 2144, 2145, -1, + 2145, 1954, 1955, -1, 1954, 2145, 2146, -1, + 2146, 1953, 1954, -1, 1953, 2146, 2147, -1, + 2147, 1952, 1953, -1, 1952, 2147, 2148, -1, + 2148, 1951, 1952, -1, 1951, 2148, 2149, -1, + 2149, 1950, 1951, -1, 1950, 2149, 2150, -1, + 2150, 1949, 1950, -1, 1949, 2150, 2151, -1, + 2151, 1948, 1949, -1, 1948, 2151, 2152, -1, + 2152, 1947, 1948, -1, 1947, 2152, 2153, -1, + 2153, 1946, 1947, -1, 1946, 2153, 2154, -1, + 2154, 1945, 1946, -1, 1945, 2154, 2155, -1, + 2155, 1944, 1945, -1, 1944, 2155, 2156, -1, + 2156, 1943, 1944, -1, 1943, 2156, 2157, -1, + 2157, 1942, 1943, -1, 1942, 2157, 2158, -1, + 2158, 1941, 1942, -1, 1941, 2158, 2159, -1, + 2159, 1940, 1941, -1, 1940, 2159, 2160, -1, + 2160, 1939, 1940, -1, 1939, 2160, 2161, -1, + 2161, 1938, 1939, -1, 1938, 2161, 2162, -1, + 2162, 1937, 1938, -1, 1937, 2162, 2163, -1, + 2163, 1936, 1937, -1, 1936, 2163, 2164, -1, + 2164, 1935, 1936, -1, 1935, 2164, 2165, -1, + 2165, 1934, 1935, -1, 1934, 2165, 2166, -1, + 2166, 1933, 1934, -1, 1933, 2166, 2167, -1, + 2167, 1932, 1933, -1, 1932, 2167, 2168, -1, + 2168, 1931, 1932, -1, 1931, 2168, 2169, -1, + 2169, 1930, 1931, -1, 1930, 2169, 2170, -1, + 2170, 1929, 1930, -1, 1929, 2170, 2171, -1, + 2171, 1928, 1929, -1, 1928, 2171, 2172, -1, + 2172, 1927, 1928, -1, 1927, 2172, 2173, -1, + 2173, 1926, 1927, -1, 1926, 2173, 2174, -1, + 2174, 1925, 1926, -1, 1925, 2174, 2175, -1, + 2175, 1924, 1925, -1, 1924, 2175, 2176, -1, + 2176, 1923, 1924, -1, 1923, 2176, 2177, -1, + 2177, 1922, 1923, -1, 1922, 2177, 2178, -1, + 2178, 1921, 1922, -1, 1921, 2178, 2179, -1, + 2179, 1920, 1921, -1, 1920, 2179, 2180, -1, + 2180, 1919, 1920, -1, 1919, 2180, 2181, -1, + 2181, 1918, 1919, -1, 1918, 2181, 2182, -1, + 2182, 1917, 1918, -1, 1917, 2182, 2183, -1, + 2183, 1916, 1917, -1, 1916, 2183, 2184, -1, + 2184, 1915, 1916, -1, 1915, 2184, 2185, -1, + 2185, 1914, 1915, -1, 1914, 2185, 2186, -1, + 2186, 1913, 1914, -1, 1913, 2186, 2187, -1, + 2187, 1912, 1913, -1, 1912, 2187, 2188, -1, + 2188, 1911, 1912, -1, 1911, 2188, 2189, -1, + 2189, 1909, 1911, -1, 1909, 2189, 2190, -1, + 2191, 2192, 2189, -1, 2192, 2190, 2189, -1, + 2192, 2193, 2190, -1, 2192, 2191, 2193, -1, + 2194, 2193, 2195, -1, 2196, 2197, 2194, -1, + 2198, 2199, 2200, -1, 2199, 2198, 2201, -1, + 2201, 2202, 2199, -1, 2202, 2201, 2203, -1, + 2203, 2204, 2202, -1, 2204, 2203, 2205, -1, + 2205, 2206, 2204, -1, 2206, 2205, 2207, -1, + 2207, 2208, 2206, -1, 2208, 2207, 2209, -1, + 2209, 2210, 2208, -1, 2210, 2209, 2211, -1, + 2211, 2212, 2210, -1, 2212, 2211, 2213, -1, + 2213, 2214, 2212, -1, 2214, 2213, 2215, -1, + 2215, 2216, 2214, -1, 2216, 2215, 2217, -1, + 2217, 2218, 2216, -1, 2218, 2217, 2219, -1, + 2219, 2220, 2218, -1, 2220, 2219, 2221, -1, + 2221, 2222, 2220, -1, 2222, 2221, 2223, -1, + 2223, 2224, 2222, -1, 2224, 2223, 2225, -1, + 2225, 2226, 2224, -1, 2226, 2225, 2227, -1, + 2227, 2228, 2226, -1, 2228, 2227, 2229, -1, + 2229, 2230, 2228, -1, 2230, 2229, 2231, -1, + 2231, 2232, 2230, -1, 2232, 2231, 2233, -1, + 2233, 2234, 2232, -1, 2235, 2236, 2237, -1, + 2237, 2236, 2238, -1, 2237, 2238, 2239, -1, + 2239, 2240, 2237, -1, 2240, 2239, 2241, -1, + 2241, 2242, 2240, -1, 2242, 2241, 2243, -1, + 2243, 2244, 2242, -1, 2244, 2243, 2245, -1, + 2245, 2246, 2244, -1, 2246, 2245, 2247, -1, + 2247, 2248, 2246, -1, 2248, 2247, 2249, -1, + 2249, 2250, 2248, -1, 2250, 2249, 2251, -1, + 2251, 2252, 2250, -1, 2252, 2251, 2253, -1, + 2253, 2254, 2252, -1, 2254, 2253, 2255, -1, + 2255, 2256, 2254, -1, 2256, 2255, 2257, -1, + 2257, 2258, 2256, -1, 2258, 2257, 2259, -1, + 2259, 2260, 2258, -1, 2260, 2259, 2261, -1, + 2261, 2262, 2260, -1, 2262, 2261, 2263, -1, + 2263, 2264, 2262, -1, 2264, 2263, 2265, -1, + 2265, 2266, 2264, -1, 2266, 2265, 2267, -1, + 2267, 2268, 2266, -1, 2269, 2266, 2268, -1, + 2268, 2270, 2269, -1, 2270, 2268, 2271, -1, + 2271, 2272, 2270, -1, 2273, 2274, 2275, -1, + 2275, 2276, 2273, -1, 2276, 2275, 2277, -1, + 2277, 2278, 2276, -1, 2278, 2277, 2279, -1, + 2279, 2280, 2278, -1, 2280, 2279, 2281, -1, + 2281, 2282, 2280, -1, 2282, 2281, 2283, -1, + 2283, 2284, 2282, -1, 2284, 2283, 2285, -1, + 2285, 2286, 2284, -1, 2286, 2285, 2287, -1, + 2287, 2288, 2286, -1, 2288, 2287, 2272, -1, + 2272, 2271, 2288, -1, 2289, 2288, 2271, -1, + 2271, 2234, 2289, -1, 2234, 2271, 2268, -1, + 2268, 2232, 2234, -1, 2232, 2268, 2267, -1, + 2267, 2230, 2232, -1, 2230, 2267, 2265, -1, + 2265, 2228, 2230, -1, 2228, 2265, 2263, -1, + 2263, 2226, 2228, -1, 2226, 2263, 2261, -1, + 2261, 2224, 2226, -1, 2224, 2261, 2259, -1, + 2259, 2222, 2224, -1, 2222, 2259, 2257, -1, + 2257, 2220, 2222, -1, 2220, 2257, 2255, -1, + 2255, 2218, 2220, -1, 2218, 2255, 2253, -1, + 2253, 2216, 2218, -1, 2216, 2253, 2251, -1, + 2251, 2214, 2216, -1, 2214, 2251, 2249, -1, + 2249, 2212, 2214, -1, 2212, 2249, 2247, -1, + 2247, 2210, 2212, -1, 2210, 2247, 2245, -1, + 2245, 2208, 2210, -1, 2208, 2245, 2243, -1, + 2243, 2206, 2208, -1, 2206, 2243, 2241, -1, + 2241, 2204, 2206, -1, 2204, 2241, 2239, -1, + 2239, 2202, 2204, -1, 2202, 2239, 2238, -1, + 2238, 2199, 2202, -1, 2199, 2238, 2290, -1, + 2291, 2290, 2238, -1, 2290, 2291, 2194, -1, + 2290, 2194, 2197, -1, 2197, 2199, 2290, -1, + 2197, 2196, 2199, -1, 2196, 2200, 2199, -1, + 2196, 2194, 2200, -1, 2200, 2194, 2195, -1, + 2195, 2198, 2200, -1, 2195, 2292, 2198, -1, + 2292, 2195, 2193, -1, 2292, 2193, 2191, -1, + 2191, 2189, 2292, -1, 2189, 2198, 2292, -1, + 2198, 2189, 2188, -1, 2188, 2201, 2198, -1, + 2201, 2188, 2187, -1, 2187, 2203, 2201, -1, + 2203, 2187, 2186, -1, 2186, 2205, 2203, -1, + 2205, 2186, 2185, -1, 2185, 2207, 2205, -1, + 2207, 2185, 2184, -1, 2184, 2209, 2207, -1, + 2209, 2184, 2183, -1, 2183, 2211, 2209, -1, + 2211, 2183, 2182, -1, 2182, 2213, 2211, -1, + 2213, 2182, 2181, -1, 2181, 2215, 2213, -1, + 2215, 2181, 2180, -1, 2180, 2217, 2215, -1, + 2217, 2180, 2179, -1, 2179, 2219, 2217, -1, + 2219, 2179, 2178, -1, 2178, 2221, 2219, -1, + 2221, 2178, 2177, -1, 2177, 2223, 2221, -1, + 2223, 2177, 2176, -1, 2176, 2225, 2223, -1, + 2225, 2176, 2175, -1, 2175, 2227, 2225, -1, + 2227, 2175, 2174, -1, 2174, 2229, 2227, -1, + 2229, 2174, 2173, -1, 2173, 2231, 2229, -1, + 2231, 2173, 2172, -1, 2172, 2233, 2231, -1, + 2233, 2172, 2171, -1, 2171, 2234, 2233, -1, + 2234, 2171, 2170, -1, 2170, 2289, 2234, -1, + 2289, 2170, 2169, -1, 2169, 2288, 2289, -1, + 2288, 2169, 2168, -1, 2168, 2286, 2288, -1, + 2286, 2168, 2167, -1, 2167, 2284, 2286, -1, + 2284, 2167, 2166, -1, 2166, 2282, 2284, -1, + 2282, 2166, 2165, -1, 2165, 2280, 2282, -1, + 2280, 2165, 2164, -1, 2164, 2278, 2280, -1, + 2278, 2164, 2163, -1, 2163, 2276, 2278, -1, + 2276, 2163, 2162, -1, 2162, 2273, 2276, -1, + 2273, 2162, 2161, -1, 2161, 2274, 2273, -1, + 2274, 2161, 2160, -1, 2160, 2293, 2274, -1, + 2293, 2160, 2159, -1, 2159, 2294, 2293, -1, + 2294, 2159, 2158, -1, 2158, 2295, 2294, -1, + 2295, 2158, 2157, -1, 2157, 2296, 2295, -1, + 2296, 2157, 2156, -1, 2156, 2297, 2296, -1, + 2297, 2156, 2155, -1, 2155, 2298, 2297, -1, + 2298, 2155, 2154, -1, 2154, 2299, 2298, -1, + 2299, 2154, 2153, -1, 2153, 2300, 2299, -1, + 2300, 2153, 2152, -1, 2152, 2301, 2300, -1, + 2301, 2152, 2151, -1, 2151, 2302, 2301, -1, + 2302, 2151, 2150, -1, 2150, 2303, 2302, -1, + 2303, 2150, 2149, -1, 2149, 2304, 2303, -1, + 2304, 2149, 2148, -1, 2148, 2305, 2304, -1, + 2305, 2148, 2147, -1, 2147, 2306, 2305, -1, + 2306, 2147, 2146, -1, 2146, 2307, 2306, -1, + 2307, 2146, 2145, -1, 2145, 2308, 2307, -1, + 2308, 2145, 2144, -1, 2144, 2309, 2308, -1, + 2309, 2144, 2143, -1, 2143, 2310, 2309, -1, + 2310, 2143, 2142, -1, 2142, 2311, 2310, -1, + 2311, 2142, 2141, -1, 2141, 2312, 2311, -1, + 2312, 2141, 2140, -1, 2140, 2313, 2312, -1, + 2313, 2140, 2139, -1, 2139, 2314, 2313, -1, + 2314, 2139, 2138, -1, 2138, 2315, 2314, -1, + 2315, 2138, 2137, -1, 2137, 2316, 2315, -1, + 2316, 2137, 2136, -1, 2136, 2317, 2316, -1, + 2317, 2136, 2135, -1, 2317, 2135, 2134, -1, + 2134, 2318, 2317, -1, 2318, 2134, 2133, -1, + 2133, 2319, 2318, -1, 2319, 2133, 2132, -1, + 2132, 2320, 2319, -1, 2320, 2132, 2131, -1, + 2131, 2321, 2320, -1, 2321, 2131, 2130, -1, + 2130, 2322, 2321, -1, 2322, 2130, 2129, -1, + 2129, 2323, 2322, -1, 2323, 2129, 2128, -1, + 2128, 2324, 2323, -1, 2324, 2128, 2127, -1, + 2127, 2325, 2324, -1, 2325, 2127, 2126, -1, + 2126, 2326, 2325, -1, 2326, 2126, 2125, -1, + 2125, 2327, 2326, -1, 2327, 2125, 2124, -1, + 2124, 2328, 2327, -1, 2328, 2124, 2123, -1, + 2123, 2329, 2328, -1, 2329, 2123, 2122, -1, + 2122, 2330, 2329, -1, 2330, 2122, 2121, -1, + 2121, 2331, 2330, -1, 2331, 2121, 2120, -1, + 2120, 2332, 2331, -1, 2332, 2120, 2119, -1, + 2119, 2333, 2332, -1, 2333, 2119, 2118, -1, + 2118, 2334, 2333, -1, 2334, 2118, 2117, -1, + 2117, 2335, 2334, -1, 2335, 2117, 2116, -1, + 2116, 2336, 2335, -1, 2336, 2116, 2115, -1, + 2115, 2337, 2336, -1, 2337, 2115, 2114, -1, + 2114, 2338, 2337, -1, 2338, 2114, 2113, -1, + 2113, 2339, 2338, -1, 2339, 2113, 2112, -1, + 2112, 2340, 2339, -1, 2340, 2112, 2111, -1, + 2111, 2341, 2340, -1, 2341, 2111, 2110, -1, + 2110, 2342, 2341, -1, 2342, 2110, 2109, -1, + 2109, 2343, 2342, -1, 2343, 2109, 2108, -1, + 2108, 2344, 2343, -1, 2344, 2108, 2107, -1, + 2107, 2345, 2344, -1, 2345, 2107, 2106, -1, + 2106, 2346, 2345, -1, 2346, 2106, 2105, -1, + 2105, 2347, 2346, -1, 2347, 2105, 2104, -1, + 2104, 2348, 2347, -1, 2348, 2104, 2103, -1, + 2103, 2349, 2348, -1, 2349, 2103, 2102, -1, + 2102, 2350, 2349, -1, 2350, 2102, 2101, -1, + 2101, 2351, 2350, -1, 2351, 2101, 2100, -1, + 2100, 2352, 2351, -1, 2352, 2100, 2099, -1, + 2099, 2353, 2352, -1, 2353, 2099, 2098, -1, + 2098, 2354, 2353, -1, 2354, 2098, 2097, -1, + 2097, 2355, 2354, -1, 2355, 2097, 2096, -1, + 2096, 2356, 2355, -1, 2356, 2096, 2095, -1, + 2095, 2357, 2356, -1, 2357, 2095, 2094, -1, + 2094, 2358, 2357, -1, 2358, 2094, 2093, -1, + 2093, 2359, 2358, -1, 2359, 2093, 2092, -1, + 2092, 2360, 2359, -1, 2360, 2092, 2091, -1, + 2091, 2361, 2360, -1, 2361, 2091, 2090, -1, + 2090, 2362, 2361, -1, 2362, 2090, 2089, -1, + 2089, 2363, 2362, -1, 2363, 2089, 2088, -1, + 2088, 2364, 2363, -1, 2364, 2088, 2087, -1, + 2087, 2365, 2364, -1, 2365, 2087, 2086, -1, + 2086, 2366, 2365, -1, 2366, 2086, 2085, -1, + 2085, 2367, 2366, -1, 2367, 2085, 2084, -1, + 2084, 2368, 2367, -1, 2368, 2084, 2083, -1, + 2083, 2369, 2368, -1, 2369, 2083, 2082, -1, + 2082, 2370, 2369, -1, 2370, 2082, 2081, -1, + 2081, 2371, 2370, -1, 2372, 2373, 2374, -1, + 2375, 2376, 2377, -1, 2376, 2375, 2378, -1, + 2378, 2379, 2376, -1, 2379, 2378, 2380, -1, + 2380, 2381, 2379, -1, 2381, 2380, 2382, -1, + 2382, 2383, 2381, -1, 2383, 2382, 2384, -1, + 2384, 2385, 2383, -1, 2385, 2384, 2386, -1, + 2386, 2387, 2385, -1, 2387, 2386, 2388, -1, + 2388, 2389, 2387, -1, 2389, 2388, 2390, -1, + 2390, 2391, 2389, -1, 2391, 2390, 2392, -1, + 2392, 2393, 2391, -1, 2393, 2392, 2394, -1, + 2394, 2395, 2393, -1, 2395, 2394, 2396, -1, + 2396, 2397, 2395, -1, 2397, 2396, 2398, -1, + 2398, 2399, 2397, -1, 2399, 2398, 2400, -1, + 2400, 2401, 2399, -1, 2402, 2403, 2404, -1, + 2401, 2404, 2403, -1, 2401, 2400, 2404, -1, + 2405, 2406, 2407, -1, 2405, 2408, 2406, -1, + 2409, 2410, 2411, -1, 2410, 2409, 2412, -1, + 2412, 2413, 2410, -1, 2413, 2412, 2414, -1, + 2414, 2415, 2413, -1, 2415, 2414, 2416, -1, + 2416, 2417, 2415, -1, 2417, 2416, 2418, -1, + 2418, 2419, 2417, -1, 2419, 2418, 2420, -1, + 2420, 2421, 2419, -1, 2421, 2420, 2422, -1, + 2422, 2423, 2421, -1, 2423, 2422, 2424, -1, + 2424, 2425, 2423, -1, 2425, 2424, 2426, -1, + 2426, 2427, 2425, -1, 2427, 2426, 2428, -1, + 2428, 2429, 2427, -1, 2429, 2428, 2430, -1, + 2430, 2431, 2429, -1, 2431, 2430, 2432, -1, + 2432, 2433, 2431, -1, 2433, 2432, 2434, -1, + 2434, 2435, 2433, -1, 2435, 2434, 2436, -1, + 2436, 2437, 2435, -1, 2437, 2436, 2408, -1, + 2408, 2405, 2437, -1, 2405, 2438, 2404, -1, + 2404, 2437, 2405, -1, 2437, 2404, 2400, -1, + 2400, 2435, 2437, -1, 2435, 2400, 2398, -1, + 2398, 2433, 2435, -1, 2433, 2398, 2396, -1, + 2396, 2431, 2433, -1, 2431, 2396, 2394, -1, + 2394, 2429, 2431, -1, 2429, 2394, 2392, -1, + 2392, 2427, 2429, -1, 2427, 2392, 2390, -1, + 2390, 2425, 2427, -1, 2425, 2390, 2388, -1, + 2388, 2423, 2425, -1, 2423, 2388, 2386, -1, + 2386, 2421, 2423, -1, 2421, 2386, 2384, -1, + 2384, 2419, 2421, -1, 2419, 2384, 2382, -1, + 2382, 2417, 2419, -1, 2417, 2382, 2380, -1, + 2380, 2415, 2417, -1, 2415, 2380, 2378, -1, + 2378, 2413, 2415, -1, 2413, 2378, 2375, -1, + 2375, 2410, 2413, -1, 2410, 2375, 2377, -1, + 2377, 2411, 2410, -1, 2411, 2377, 2439, -1, + 2439, 2440, 2411, -1, 2440, 2439, 2441, -1, + 2442, 2443, 2444, -1, 2444, 2445, 2442, -1, + 2445, 2444, 2446, -1, 2446, 2447, 2445, -1, + 2447, 2446, 2448, -1, 2448, 2449, 2447, -1, + 2449, 2448, 2450, -1, 2450, 2451, 2449, -1, + 2451, 2450, 2452, -1, 2452, 2453, 2451, -1, + 2453, 2452, 2454, -1, 2454, 2455, 2453, -1, + 2456, 2457, 2458, -1, 2457, 2456, 2455, -1, + 2455, 2454, 2457, -1, 2459, 2457, 2454, -1, + 2454, 2460, 2459, -1, 2460, 2454, 2452, -1, + 2452, 2461, 2460, -1, 2461, 2452, 2450, -1, + 2450, 2462, 2461, -1, 2462, 2450, 2448, -1, + 2448, 2463, 2462, -1, 2463, 2448, 2446, -1, + 2446, 2464, 2463, -1, 2464, 2446, 2444, -1, + 2444, 2465, 2464, -1, 2465, 2444, 2443, -1, + 2443, 2466, 2465, -1, 2466, 2443, 2467, -1, + 2467, 2468, 2466, -1, 2468, 2467, 2469, -1, + 2469, 2470, 2468, -1, 2470, 2469, 2471, -1, + 2471, 2472, 2470, -1, 2472, 2471, 2473, -1, + 2473, 2474, 2472, -1, 2474, 2473, 2475, -1, + 2475, 2476, 2474, -1, 2476, 2475, 2477, -1, + 2477, 2478, 2476, -1, 2478, 2477, 2479, -1, + 2479, 2480, 2478, -1, 2480, 2479, 2481, -1, + 2481, 2482, 2480, -1, 2482, 2481, 2483, -1, + 2483, 2484, 2482, -1, 2484, 2483, 2485, -1, + 2485, 2486, 2484, -1, 2486, 2485, 2487, -1, + 2487, 2488, 2486, -1, 2488, 2487, 2489, -1, + 2489, 2490, 2488, -1, 2490, 2489, 2491, -1, + 2491, 2492, 2490, -1, 2492, 2491, 2493, -1, + 2493, 802, 2492, -1, 802, 2493, 2494, -1, + 2494, 2495, 2496, -1, 2494, 2497, 2495, -1, + 2497, 2494, 2493, -1, 2493, 2498, 2497, -1, + 2498, 2493, 2491, -1, 2491, 2499, 2498, -1, + 2499, 2491, 2489, -1, 2489, 2500, 2499, -1, + 2500, 2489, 2487, -1, 2487, 2501, 2500, -1, + 2501, 2487, 2485, -1, 2485, 2502, 2501, -1, + 2502, 2485, 2483, -1, 2483, 2503, 2502, -1, + 2503, 2483, 2481, -1, 2481, 2504, 2503, -1, + 2504, 2481, 2479, -1, 2479, 2505, 2504, -1, + 2505, 2479, 2477, -1, 2477, 2506, 2505, -1, + 2506, 2477, 2475, -1, 2475, 2507, 2506, -1, + 2507, 2475, 2473, -1, 2473, 2508, 2507, -1, + 2508, 2473, 2471, -1, 2471, 2509, 2508, -1, + 2509, 2471, 2469, -1, 2469, 2510, 2509, -1, + 2510, 2469, 2467, -1, 2467, 2511, 2510, -1, + 2511, 2467, 2443, -1, 2443, 2442, 2511, -1, + 2512, 2511, 2442, -1, 2511, 2512, 2441, -1, + 2441, 2510, 2511, -1, 2510, 2441, 2439, -1, + 2439, 2509, 2510, -1, 2509, 2439, 2377, -1, + 2377, 2508, 2509, -1, 2508, 2377, 2376, -1, + 2376, 2507, 2508, -1, 2507, 2376, 2379, -1, + 2379, 2506, 2507, -1, 2506, 2379, 2381, -1, + 2381, 2505, 2506, -1, 2505, 2381, 2383, -1, + 2383, 2504, 2505, -1, 2504, 2383, 2385, -1, + 2385, 2503, 2504, -1, 2503, 2385, 2387, -1, + 2387, 2502, 2503, -1, 2502, 2387, 2389, -1, + 2389, 2501, 2502, -1, 2501, 2389, 2391, -1, + 2391, 2500, 2501, -1, 2500, 2391, 2393, -1, + 2393, 2499, 2500, -1, 2499, 2393, 2395, -1, + 2395, 2498, 2499, -1, 2498, 2395, 2397, -1, + 2397, 2497, 2498, -1, 2497, 2397, 2399, -1, + 2399, 2495, 2497, -1, 2495, 2399, 2401, -1, + 2401, 2513, 2495, -1, 2514, 2495, 2513, -1, + 2513, 2372, 2514, -1, 2513, 2515, 2372, -1, + 2515, 2513, 2401, -1, 2515, 2401, 2403, -1, + 2403, 2372, 2515, -1, 2403, 2402, 2372, -1, + 2402, 2373, 2372, -1, 2373, 2402, 2404, -1, + 2373, 2404, 2438, -1, 2438, 2374, 2373, -1, + 2438, 2516, 2374, -1, 2516, 2438, 2405, -1, + 2516, 2405, 2407, -1, 2407, 2374, 2516, -1, + 2407, 2517, 2374, -1, 2517, 2407, 2406, -1, + 2518, 2519, 2520, -1, 2520, 2519, 2521, -1, + 2521, 2406, 2520, -1, 2521, 2517, 2406, -1, + 2521, 2374, 2517, -1, 2374, 2521, 2519, -1, + 2522, 2523, 2524, -1, 2522, 2525, 2526, -1, + 2522, 2524, 2525, -1, 2527, 2525, 2524, -1, + 2527, 2528, 2525, -1, 2528, 2527, 2529, -1, + 2529, 2530, 2528, -1, 2530, 2529, 2531, -1, + 2531, 2532, 2530, -1, 2532, 2531, 2533, -1, + 2533, 2534, 2532, -1, 2534, 2533, 2535, -1, + 2535, 2536, 2534, -1, 2536, 2535, 2537, -1, + 2537, 2538, 2536, -1, 2538, 2537, 2539, -1, + 2539, 2540, 2538, -1, 2540, 2539, 2541, -1, + 2542, 2543, 2544, -1, 2544, 2543, 2545, -1, + 2545, 2546, 2544, -1, 2546, 2545, 2547, -1, + 2547, 2548, 2546, -1, 2548, 2547, 2549, -1, + 2549, 2550, 2548, -1, 2550, 2549, 2551, -1, + 2551, 2552, 2550, -1, 2552, 2551, 2553, -1, + 2553, 2554, 2552, -1, 2554, 2553, 2555, -1, + 2555, 2556, 2554, -1, 2556, 2555, 2557, -1, + 2557, 2558, 2556, -1, 2558, 2557, 2559, -1, + 2559, 2560, 2558, -1, 2560, 2559, 2561, -1, + 2561, 2562, 2560, -1, 2562, 2561, 2563, -1, + 2563, 2564, 2562, -1, 2564, 2563, 2565, -1, + 2565, 2566, 2564, -1, 2566, 2565, 2567, -1, + 2567, 2568, 2566, -1, 2568, 2567, 2569, -1, + 2569, 2570, 2568, -1, 2570, 2569, 2571, -1, + 2571, 2572, 2570, -1, 2572, 2571, 2573, -1, + 2573, 2574, 2572, -1, 2574, 2573, 2575, -1, + 2575, 2576, 2574, -1, 2576, 2575, 2577, -1, + 2577, 2578, 2576, -1, 2578, 2577, 2579, -1, + 2579, 2580, 2578, -1, 2580, 2579, 2581, -1, + 2581, 2582, 2580, -1, 2582, 2581, 2583, -1, + 2583, 2584, 2582, -1, 2584, 2583, 2585, -1, + 2585, 2586, 2584, -1, 2586, 2585, 2587, -1, + 2587, 2588, 2586, -1, 2588, 2587, 2589, -1, + 2589, 2590, 2588, -1, 2590, 2589, 2591, -1, + 2591, 2592, 2590, -1, 2592, 2591, 2593, -1, + 2593, 2594, 2592, -1, 2594, 2593, 2595, -1, + 2595, 2596, 2594, -1, 2596, 2595, 2597, -1, + 2597, 2598, 2596, -1, 2598, 2597, 2599, -1, + 2599, 2600, 2598, -1, 2600, 2599, 2601, -1, + 2601, 2602, 2600, -1, 2602, 2601, 2603, -1, + 2603, 2604, 2602, -1, 2604, 2603, 2605, -1, + 2605, 2606, 2604, -1, 2606, 2605, 2607, -1, + 2607, 2608, 2606, -1, 2608, 2607, 2609, -1, + 2609, 2610, 2608, -1, 2610, 2609, 2611, -1, + 2611, 2612, 2610, -1, 2612, 2611, 2613, -1, + 2613, 2614, 2612, -1, 2614, 2613, 2615, -1, + 2615, 2616, 2614, -1, 2616, 2615, 2617, -1, + 2617, 2618, 2616, -1, 2618, 2617, 2619, -1, + 2619, 2620, 2618, -1, 2620, 2619, 2621, -1, + 2621, 2622, 2620, -1, 2622, 2621, 2623, -1, + 2623, 2624, 2622, -1, 2624, 2623, 2541, -1, + 2541, 2625, 2624, -1, 2625, 2541, 2539, -1, + 2539, 2626, 2625, -1, 2626, 2539, 2537, -1, + 2537, 2627, 2626, -1, 2627, 2537, 2535, -1, + 2535, 2628, 2627, -1, 2628, 2535, 2533, -1, + 2533, 2629, 2628, -1, 2629, 2533, 2531, -1, + 2531, 2630, 2629, -1, 2630, 2531, 2529, -1, + 2529, 2631, 2630, -1, 2631, 2529, 2527, -1, + 2631, 2527, 2632, -1, 2633, 2634, 2635, -1, + 2636, 2637, 2638, -1, 2639, 2637, 2636, -1, + 2636, 2640, 2639, -1, 2636, 2638, 2640, -1, + 2640, 2638, 2641, -1, 2641, 2642, 2640, -1, + 2642, 2641, 2643, -1, 2643, 2644, 2642, -1, + 2645, 2642, 2644, -1, 2642, 2645, 2646, -1, + 2646, 2640, 2642, -1, 2640, 2646, 2647, -1, + 2647, 2639, 2640, -1, 2639, 2647, 2648, -1, + 2648, 2637, 2639, -1, 2648, 2649, 2637, -1, + 2649, 2648, 2647, -1, 2649, 2647, 2650, -1, + 2650, 2637, 2649, -1, 2650, 2651, 2637, -1, + 2652, 2637, 2651, -1, 2651, 2653, 2652, -1, + 2651, 2654, 2653, -1, 2651, 2650, 2654, -1, + 2654, 2650, 2647, -1, 2647, 2655, 2654, -1, + 2655, 2647, 2646, -1, 2646, 2656, 2655, -1, + 2656, 2646, 2645, -1, 2657, 2658, 2659, -1, + 2657, 2660, 2658, -1, 2660, 2657, 2661, -1, + 2661, 2662, 2660, -1, 2662, 2661, 2663, -1, + 2663, 2664, 2662, -1, 2664, 2663, 2665, -1, + 2665, 2666, 2664, -1, 2666, 2665, 2667, -1, + 2667, 2668, 2666, -1, 2668, 2667, 2669, -1, + 2669, 2670, 2668, -1, 2670, 2669, 2671, -1, + 2671, 2672, 2670, -1, 2672, 2671, 2673, -1, + 2673, 2674, 2672, -1, 2674, 2673, 2675, -1, + 2675, 2676, 2674, -1, 2676, 2675, 2677, -1, + 2677, 2678, 2676, -1, 2678, 2677, 2679, -1, + 2679, 2680, 2678, -1, 2680, 2679, 2681, -1, + 2681, 2682, 2680, -1, 2682, 2681, 2683, -1, + 2683, 2684, 2682, -1, 2684, 2683, 2685, -1, + 2685, 2686, 2684, -1, 2686, 2685, 2687, -1, + 2687, 2688, 2686, -1, 2688, 2687, 2689, -1, + 2689, 2690, 2688, -1, 2690, 2689, 2691, -1, + 2691, 2692, 2690, -1, 2692, 2691, 2693, -1, + 2693, 2694, 2692, -1, 2694, 2693, 2695, -1, + 2695, 2696, 2694, -1, 2696, 2695, 2697, -1, + 2697, 2698, 2696, -1, 2698, 2697, 2699, -1, + 2699, 2700, 2698, -1, 2700, 2699, 2701, -1, + 2701, 2702, 2700, -1, 2702, 2701, 2703, -1, + 2703, 2704, 2702, -1, 2704, 2703, 2705, -1, + 2705, 2706, 2704, -1, 2706, 2705, 2707, -1, + 2707, 2708, 2706, -1, 2708, 2707, 2709, -1, + 2709, 2710, 2708, -1, 2710, 2709, 2711, -1, + 2711, 2712, 2710, -1, 2712, 2711, 2713, -1, + 2713, 2714, 2712, -1, 2714, 2713, 2715, -1, + 2715, 2716, 2714, -1, 2716, 2715, 2717, -1, + 2717, 2718, 2716, -1, 2718, 2717, 2719, -1, + 2719, 2720, 2718, -1, 2720, 2719, 2721, -1, + 2721, 2722, 2720, -1, 2722, 2721, 2723, -1, + 2723, 2724, 2722, -1, 2724, 2723, 2725, -1, + 2725, 2726, 2724, -1, 2726, 2725, 2727, -1, + 2727, 2728, 2726, -1, 2728, 2727, 2729, -1, + 2729, 2730, 2728, -1, 2730, 2729, 2731, -1, + 2731, 2732, 2730, -1, 2732, 2731, 2733, -1, + 2733, 2734, 2732, -1, 2734, 2733, 2735, -1, + 2735, 2736, 2734, -1, 2736, 2735, 2737, -1, + 2737, 2738, 2736, -1, 2738, 2737, 2739, -1, + 2739, 2740, 2738, -1, 2740, 2739, 2741, -1, + 2741, 2742, 2740, -1, 2742, 2741, 2743, -1, + 2743, 2744, 2742, -1, 2744, 2743, 2745, -1, + 2745, 2746, 2744, -1, 2746, 2745, 2747, -1, + 2747, 2748, 2746, -1, 2748, 2747, 2749, -1, + 2749, 2750, 2748, -1, 2750, 2749, 2751, -1, + 2751, 2752, 2750, -1, 2752, 2751, 2753, -1, + 2753, 2754, 2752, -1, 2754, 2753, 2755, -1, + 2755, 2756, 2754, -1, 2756, 2755, 2757, -1, + 2757, 2758, 2756, -1, 2759, 2760, 2758, -1, + 2758, 2757, 2759, -1, 2761, 2762, 2763, -1, + 2763, 2764, 2761, -1, 2765, 2766, 2761, -1, + 2761, 2767, 2765, -1, 2767, 2761, 2764, -1, + 2764, 2768, 2767, -1, 2768, 2764, 2769, -1, + 2769, 2770, 2768, -1, 2770, 2769, 2771, -1, + 2771, 2772, 2770, -1, 2772, 2771, 2773, -1, + 2773, 2774, 2772, -1, 2774, 2773, 2775, -1, + 2775, 2776, 2774, -1, 2776, 2775, 2777, -1, + 2777, 2778, 2776, -1, 2778, 2777, 2779, -1, + 2779, 2780, 2778, -1, 2780, 2779, 2781, -1, + 2781, 2782, 2780, -1, 2782, 2781, 2783, -1, + 2783, 2784, 2782, -1, 2784, 2783, 2785, -1, + 2785, 2786, 2784, -1, 2786, 2785, 2787, -1, + 2787, 2788, 2786, -1, 2788, 2787, 2789, -1, + 2789, 2790, 2788, -1, 2790, 2789, 2791, -1, + 2791, 2792, 2790, -1, 2792, 2791, 2793, -1, + 2793, 2794, 2792, -1, 2794, 2793, 2795, -1, + 2795, 2796, 2794, -1, 2796, 2795, 2797, -1, + 2797, 2798, 2796, -1, 2798, 2797, 2799, -1, + 2799, 2800, 2798, -1, 2800, 2799, 2801, -1, + 2801, 2802, 2800, -1, 2802, 2801, 2803, -1, + 2803, 2804, 2802, -1, 2804, 2803, 2805, -1, + 2805, 2806, 2804, -1, 2806, 2805, 2807, -1, + 2807, 2808, 2806, -1, 2808, 2807, 2809, -1, + 2809, 2810, 2808, -1, 2810, 2809, 2811, -1, + 2811, 2812, 2810, -1, 2812, 2811, 2813, -1, + 2813, 2814, 2812, -1, 2814, 2813, 2815, -1, + 2815, 2816, 2814, -1, 2816, 2815, 2817, -1, + 2817, 2818, 2816, -1, 2818, 2817, 2819, -1, + 2819, 2820, 2818, -1, 2820, 2819, 2821, -1, + 2821, 2822, 2820, -1, 2822, 2821, 2823, -1, + 2823, 2824, 2822, -1, 2824, 2823, 2825, -1, + 2825, 2826, 2824, -1, 2826, 2825, 2827, -1, + 2827, 2828, 2826, -1, 2828, 2827, 2829, -1, + 2829, 2830, 2828, -1, 2830, 2829, 2831, -1, + 2831, 2832, 2830, -1, 2832, 2831, 2833, -1, + 2833, 2834, 2832, -1, 2834, 2833, 2835, -1, + 2835, 2836, 2834, -1, 2836, 2835, 2837, -1, + 2837, 2838, 2836, -1, 2838, 2837, 2839, -1, + 2839, 2840, 2838, -1, 2840, 2839, 2841, -1, + 2841, 2842, 2840, -1, 2842, 2841, 2843, -1, + 2843, 2844, 2842, -1, 2844, 2843, 2845, -1, + 2845, 2846, 2844, -1, 2846, 2845, 2847, -1, + 2847, 2848, 2846, -1, 2848, 2847, 2849, -1, + 2849, 2850, 2848, -1, 2850, 2849, 2851, -1, + 2851, 2852, 2850, -1, 2852, 2851, 2853, -1, + 2853, 2854, 2852, -1, 2854, 2853, 2855, -1, + 2855, 2856, 2854, -1, 2856, 2855, 2857, -1, + 2857, 2858, 2856, -1, 2858, 2857, 2859, -1, + 2859, 2860, 2858, -1, 2860, 2859, 2861, -1, + 2861, 2862, 2860, -1, 2862, 2863, 2864, -1, + 2862, 2861, 2863, -1, 2863, 2865, 2866, -1, + 2863, 2867, 2865, -1, 2867, 2863, 2861, -1, + 2861, 2868, 2867, -1, 2868, 2861, 2859, -1, + 2859, 2869, 2868, -1, 2869, 2859, 2857, -1, + 2857, 2870, 2869, -1, 2870, 2857, 2855, -1, + 2855, 2871, 2870, -1, 2871, 2855, 2853, -1, + 2853, 2872, 2871, -1, 2872, 2853, 2851, -1, + 2851, 2873, 2872, -1, 2873, 2851, 2849, -1, + 2849, 2874, 2873, -1, 2874, 2849, 2847, -1, + 2847, 2875, 2874, -1, 2875, 2847, 2845, -1, + 2845, 2876, 2875, -1, 2876, 2845, 2843, -1, + 2843, 2877, 2876, -1, 2877, 2843, 2841, -1, + 2841, 2878, 2877, -1, 2878, 2841, 2839, -1, + 2839, 2879, 2878, -1, 2879, 2839, 2837, -1, + 2837, 2880, 2879, -1, 2880, 2837, 2835, -1, + 2835, 2881, 2880, -1, 2881, 2835, 2833, -1, + 2833, 2882, 2881, -1, 2882, 2833, 2831, -1, + 2831, 2883, 2882, -1, 2883, 2831, 2829, -1, + 2829, 2884, 2883, -1, 2884, 2829, 2827, -1, + 2827, 2885, 2884, -1, 2885, 2827, 2825, -1, + 2825, 2886, 2885, -1, 2886, 2825, 2823, -1, + 2823, 2887, 2886, -1, 2887, 2823, 2821, -1, + 2821, 2888, 2887, -1, 2888, 2821, 2819, -1, + 2819, 2889, 2888, -1, 2889, 2819, 2817, -1, + 2817, 2890, 2889, -1, 2890, 2817, 2815, -1, + 2815, 2891, 2890, -1, 2891, 2815, 2813, -1, + 2813, 2892, 2891, -1, 2892, 2813, 2811, -1, + 2811, 2893, 2892, -1, 2893, 2811, 2809, -1, + 2809, 2894, 2893, -1, 2894, 2809, 2807, -1, + 2807, 2895, 2894, -1, 2895, 2807, 2805, -1, + 2805, 2896, 2895, -1, 2896, 2805, 2803, -1, + 2803, 2897, 2896, -1, 2897, 2803, 2801, -1, + 2801, 2898, 2897, -1, 2898, 2801, 2799, -1, + 2799, 2899, 2898, -1, 2899, 2799, 2797, -1, + 2797, 2900, 2899, -1, 2900, 2797, 2795, -1, + 2795, 2901, 2900, -1, 2901, 2795, 2793, -1, + 2793, 2902, 2901, -1, 2902, 2793, 2791, -1, + 2791, 2903, 2902, -1, 2903, 2791, 2789, -1, + 2789, 2904, 2903, -1, 2904, 2789, 2787, -1, + 2787, 2905, 2904, -1, 2905, 2787, 2785, -1, + 2785, 2906, 2905, -1, 2906, 2785, 2783, -1, + 2783, 2907, 2906, -1, 2907, 2783, 2781, -1, + 2781, 2908, 2907, -1, 2908, 2781, 2779, -1, + 2779, 2909, 2908, -1, 2909, 2779, 2777, -1, + 2777, 2910, 2909, -1, 2910, 2777, 2775, -1, + 2775, 2911, 2910, -1, 2911, 2775, 2773, -1, + 2773, 2912, 2911, -1, 2912, 2773, 2771, -1, + 2771, 2913, 2912, -1, 2913, 2771, 2769, -1, + 2769, 2914, 2913, -1, 2914, 2769, 2764, -1, + 2764, 2763, 2914, -1, 2759, 2763, 2915, -1, + 2759, 2914, 2763, -1, 2914, 2759, 2757, -1, + 2757, 2913, 2914, -1, 2913, 2757, 2755, -1, + 2755, 2912, 2913, -1, 2912, 2755, 2753, -1, + 2753, 2911, 2912, -1, 2911, 2753, 2751, -1, + 2751, 2910, 2911, -1, 2910, 2751, 2749, -1, + 2749, 2909, 2910, -1, 2909, 2749, 2747, -1, + 2747, 2908, 2909, -1, 2908, 2747, 2745, -1, + 2745, 2907, 2908, -1, 2907, 2745, 2743, -1, + 2743, 2906, 2907, -1, 2906, 2743, 2741, -1, + 2741, 2905, 2906, -1, 2905, 2741, 2739, -1, + 2739, 2904, 2905, -1, 2904, 2739, 2737, -1, + 2737, 2903, 2904, -1, 2903, 2737, 2735, -1, + 2735, 2902, 2903, -1, 2902, 2735, 2733, -1, + 2733, 2901, 2902, -1, 2901, 2733, 2731, -1, + 2731, 2900, 2901, -1, 2900, 2731, 2729, -1, + 2729, 2899, 2900, -1, 2899, 2729, 2727, -1, + 2727, 2898, 2899, -1, 2898, 2727, 2725, -1, + 2725, 2897, 2898, -1, 2897, 2725, 2723, -1, + 2723, 2896, 2897, -1, 2896, 2723, 2721, -1, + 2721, 2895, 2896, -1, 2895, 2721, 2719, -1, + 2719, 2894, 2895, -1, 2894, 2719, 2717, -1, + 2717, 2893, 2894, -1, 2893, 2717, 2715, -1, + 2715, 2892, 2893, -1, 2892, 2715, 2713, -1, + 2713, 2891, 2892, -1, 2891, 2713, 2711, -1, + 2711, 2890, 2891, -1, 2890, 2711, 2709, -1, + 2709, 2889, 2890, -1, 2889, 2709, 2707, -1, + 2707, 2888, 2889, -1, 2888, 2707, 2705, -1, + 2705, 2887, 2888, -1, 2887, 2705, 2703, -1, + 2703, 2886, 2887, -1, 2886, 2703, 2701, -1, + 2701, 2885, 2886, -1, 2885, 2701, 2699, -1, + 2699, 2884, 2885, -1, 2884, 2699, 2697, -1, + 2697, 2883, 2884, -1, 2883, 2697, 2695, -1, + 2695, 2882, 2883, -1, 2882, 2695, 2693, -1, + 2693, 2881, 2882, -1, 2881, 2693, 2691, -1, + 2691, 2880, 2881, -1, 2880, 2691, 2689, -1, + 2689, 2879, 2880, -1, 2879, 2689, 2687, -1, + 2687, 2878, 2879, -1, 2878, 2687, 2685, -1, + 2685, 2877, 2878, -1, 2877, 2685, 2683, -1, + 2683, 2876, 2877, -1, 2876, 2683, 2681, -1, + 2681, 2875, 2876, -1, 2875, 2681, 2679, -1, + 2679, 2874, 2875, -1, 2874, 2679, 2677, -1, + 2677, 2873, 2874, -1, 2873, 2677, 2675, -1, + 2675, 2872, 2873, -1, 2872, 2675, 2673, -1, + 2673, 2871, 2872, -1, 2871, 2673, 2671, -1, + 2671, 2870, 2871, -1, 2870, 2671, 2669, -1, + 2669, 2869, 2870, -1, 2869, 2669, 2667, -1, + 2667, 2868, 2869, -1, 2868, 2667, 2665, -1, + 2665, 2867, 2868, -1, 2867, 2665, 2663, -1, + 2663, 2865, 2867, -1, 2865, 2663, 2661, -1, + 2865, 2661, 2916, -1, 2917, 2918, 2656, -1, + 2917, 2919, 2918, -1, 2919, 2917, 2920, -1, + 2920, 2916, 2919, -1, 2916, 2920, 2921, -1, + 2921, 2865, 2916, -1, 2921, 2866, 2865, -1, + 2921, 2922, 2866, -1, 2922, 2921, 2920, -1, + 2920, 2923, 2922, -1, 2923, 2920, 2917, -1, + 2917, 2656, 2923, -1, 2656, 2645, 2923, -1, + 2924, 2923, 2645, -1, 2924, 2922, 2923, -1, + 2922, 2924, 2925, -1, 2925, 2866, 2922, -1, + 2866, 2925, 2926, -1, 2926, 2863, 2866, -1, + 2926, 2864, 2863, -1, 2926, 2927, 2864, -1, + 2927, 2926, 2925, -1, 2925, 2928, 2927, -1, + 2928, 2925, 2924, -1, 2924, 2645, 2928, -1, + 2645, 2644, 2928, -1, 2929, 2928, 2644, -1, + 2929, 2927, 2928, -1, 2927, 2929, 2930, -1, + 2930, 2864, 2927, -1, 2864, 2930, 2931, -1, + 2931, 2862, 2864, -1, 2931, 2932, 2862, -1, + 2931, 2933, 2932, -1, 2933, 2931, 2930, -1, + 2930, 2934, 2933, -1, 2934, 2930, 2929, -1, + 2929, 2644, 2934, -1, 2644, 2935, 2934, -1, + 2644, 2643, 2935, -1, 2936, 2937, 2938, -1, + 2936, 2939, 2937, -1, 2937, 2940, 2941, -1, + 2937, 2942, 2940, -1, 2942, 2937, 2939, -1, + 2939, 2943, 2942, -1, 2944, 2945, 2943, -1, + 2943, 2939, 2944, -1, 2946, 2947, 2948, -1, + 2946, 2949, 2947, -1, 2946, 2950, 2949, -1, + 2946, 2948, 2950, -1, 2950, 2948, 2944, -1, + 2944, 2951, 2950, -1, 2951, 2944, 2939, -1, + 2939, 2936, 2951, -1, 2935, 2936, 2952, -1, + 2935, 2951, 2936, -1, 2951, 2935, 2643, -1, + 2643, 2950, 2951, -1, 2950, 2643, 2641, -1, + 2641, 2949, 2950, -1, 2949, 2641, 2953, -1, + 2953, 2947, 2949, -1, 2953, 2954, 2947, -1, + 2954, 2953, 2641, -1, 2954, 2641, 2638, -1, + 2638, 2947, 2954, -1, 2947, 2638, 2637, -1, + 2955, 2956, 2957, -1, 2958, 2959, 2960, -1, + 2958, 2960, 2961, -1, 2961, 2962, 2958, -1, + 2962, 2961, 2963, -1, 2963, 2964, 2962, -1, + 2965, 2966, 2967, -1, 2967, 2968, 2965, -1, + 2968, 2967, 2969, -1, 2969, 2970, 2968, -1, + 2970, 2969, 2971, -1, 2971, 2972, 2970, -1, + 2972, 2971, 2973, -1, 2973, 2974, 2972, -1, + 2974, 2973, 2975, -1, 2975, 2976, 2974, -1, + 2976, 2975, 2977, -1, 2977, 2978, 2976, -1, + 2978, 2977, 2979, -1, 2979, 2980, 2978, -1, + 2980, 2979, 2981, -1, 2981, 2982, 2980, -1, + 2982, 2981, 2983, -1, 2983, 2984, 2982, -1, + 2984, 2983, 2985, -1, 2985, 2986, 2984, -1, + 2986, 2985, 2987, -1, 2987, 2988, 2986, -1, + 2988, 2987, 2989, -1, 2989, 2990, 2988, -1, + 2990, 2989, 2991, -1, 2991, 2992, 2990, -1, + 2992, 2991, 2993, -1, 2993, 2994, 2992, -1, + 2994, 2993, 2995, -1, 2995, 2996, 2994, -1, + 2996, 2995, 2997, -1, 2997, 2998, 2996, -1, + 2998, 2997, 2999, -1, 2999, 3000, 2998, -1, + 3000, 2999, 3001, -1, 3001, 3002, 3000, -1, + 3002, 3001, 3003, -1, 3003, 3004, 3002, -1, + 3004, 3003, 3005, -1, 3005, 3006, 3004, -1, + 3006, 3005, 3007, -1, 3007, 3008, 3006, -1, + 3008, 3007, 3009, -1, 3009, 3010, 3008, -1, + 3010, 3009, 3011, -1, 3011, 3012, 3010, -1, + 3012, 3011, 3013, -1, 3012, 3013, 3014, -1, + 3014, 3015, 3012, -1, 3015, 3014, 3016, -1, + 3016, 3017, 3015, -1, 3017, 3016, 3018, -1, + 3018, 3019, 3017, -1, 3019, 3018, 3020, -1, + 3020, 3021, 3019, -1, 3021, 3020, 3022, -1, + 3022, 3023, 3021, -1, 3023, 3022, 3024, -1, + 3024, 3025, 3023, -1, 3025, 3024, 3026, -1, + 3026, 3027, 3025, -1, 3027, 3026, 3028, -1, + 3028, 3029, 3027, -1, 3029, 3028, 3030, -1, + 3030, 3031, 3029, -1, 3031, 3030, 3032, -1, + 3032, 3033, 3031, -1, 3033, 3032, 3034, -1, + 3034, 3035, 3033, -1, 3035, 3034, 3036, -1, + 3036, 3037, 3035, -1, 3037, 3036, 3038, -1, + 3038, 3039, 3037, -1, 3039, 3038, 3040, -1, + 3040, 3041, 3039, -1, 3041, 3040, 3042, -1, + 3042, 3043, 3041, -1, 3043, 3042, 3044, -1, + 3044, 3045, 3043, -1, 3045, 3044, 3046, -1, + 3046, 3047, 3045, -1, 3047, 3046, 3048, -1, + 3048, 3049, 3047, -1, 3049, 3048, 3050, -1, + 3050, 3051, 3049, -1, 3051, 3050, 3052, -1, + 3052, 3053, 3051, -1, 3053, 3052, 3054, -1, + 3054, 3055, 3053, -1, 3055, 3054, 3056, -1, + 3056, 3057, 3055, -1, 3057, 3056, 3058, -1, + 3058, 3059, 3057, -1, 3059, 3058, 3060, -1, + 3060, 3061, 3059, -1, 3062, 3063, 3064, -1, + 3065, 3066, 3067, -1, 3067, 3068, 3065, -1, + 3068, 3067, 3069, -1, 3069, 3070, 3068, -1, + 3070, 3069, 3071, -1, 3071, 3072, 3070, -1, + 3073, 3074, 3062, -1, 3073, 3062, 3075, -1, + 3075, 3076, 3073, -1, 3076, 3075, 3077, -1, + 3077, 3078, 3076, -1, 3078, 3077, 3079, -1, + 3079, 3080, 3078, -1, 3080, 3079, 3081, -1, + 3081, 3082, 3080, -1, 3082, 3081, 3083, -1, + 3083, 3084, 3082, -1, 3084, 3083, 3072, -1, + 3072, 3071, 3084, -1, 3071, 3085, 3084, -1, + 3085, 3071, 3069, -1, 3069, 3086, 3085, -1, + 3086, 3069, 3067, -1, 3067, 3087, 3086, -1, + 3087, 3067, 3066, -1, 3066, 3088, 3087, -1, + 3088, 3066, 3089, -1, 3089, 3090, 3088, -1, + 3091, 3092, 3093, -1, 3092, 3091, 3090, -1, + 3092, 3090, 3089, -1, 3089, 3066, 3092, -1, + 3066, 3093, 3092, -1, 3066, 3065, 3093, -1, + 3093, 3094, 3095, -1, 3094, 3093, 3065, -1, + 3065, 3096, 3094, -1, 3096, 3065, 3068, -1, + 3068, 3097, 3096, -1, 3097, 3068, 3070, -1, + 3070, 3098, 3097, -1, 3098, 3070, 3072, -1, + 3072, 3099, 3098, -1, 3099, 3072, 3083, -1, + 3083, 3100, 3099, -1, 3100, 3083, 3081, -1, + 3081, 3101, 3100, -1, 3101, 3081, 3079, -1, + 3079, 3102, 3101, -1, 3102, 3079, 3077, -1, + 3077, 3103, 3102, -1, 3103, 3077, 3075, -1, + 3075, 3104, 3103, -1, 3104, 3075, 3062, -1, + 3062, 3064, 3104, -1, 3064, 3061, 3105, -1, + 3105, 3104, 3064, -1, 3104, 3105, 3106, -1, + 3106, 3103, 3104, -1, 3103, 3106, 3107, -1, + 3107, 3102, 3103, -1, 3102, 3107, 3108, -1, + 3108, 3101, 3102, -1, 3101, 3108, 3109, -1, + 3109, 3100, 3101, -1, 3100, 3109, 3110, -1, + 3110, 3099, 3100, -1, 3099, 3110, 3111, -1, + 3111, 3098, 3099, -1, 3098, 3111, 3112, -1, + 3112, 3097, 3098, -1, 3097, 3112, 3113, -1, + 3113, 3096, 3097, -1, 3096, 3113, 3114, -1, + 3114, 3094, 3096, -1, 3094, 3114, 3115, -1, + 3115, 3095, 3094, -1, 3095, 3116, 3117, -1, + 3095, 3115, 3116, -1, 3118, 3119, 3120, -1, + 3121, 3122, 3123, -1, 3123, 3124, 3121, -1, + 3124, 3123, 3125, -1, 3125, 3126, 3124, -1, + 3126, 3125, 3127, -1, 3127, 3128, 3126, -1, + 3128, 3127, 3129, -1, 3129, 3130, 3128, -1, + 3130, 3129, 3131, -1, 3131, 3132, 3130, -1, + 3132, 3131, 3133, -1, 3133, 3134, 3132, -1, + 3134, 3133, 3135, -1, 3135, 3136, 3134, -1, + 3136, 3135, 3137, -1, 3137, 3138, 3136, -1, + 3138, 3137, 3139, -1, 3139, 3140, 3138, -1, + 3140, 3139, 3141, -1, 3141, 3142, 3140, -1, + 3142, 3141, 3143, -1, 3143, 3144, 3142, -1, + 3144, 3143, 3145, -1, 3145, 3146, 3144, -1, + 3146, 3145, 3147, -1, 3147, 3148, 3146, -1, + 3148, 3147, 3149, -1, 3149, 3150, 3148, -1, + 3151, 3152, 3153, -1, 3151, 3153, 3154, -1, + 3154, 3155, 3151, -1, 3155, 3154, 3156, -1, + 3156, 3157, 3155, -1, 3157, 3156, 3158, -1, + 3158, 3159, 3157, -1, 3159, 3158, 3160, -1, + 3160, 3161, 3159, -1, 3161, 3160, 3162, -1, + 3162, 3163, 3161, -1, 3163, 3162, 3164, -1, + 3164, 3165, 3163, -1, 3165, 3164, 3166, -1, + 3166, 3167, 3165, -1, 3166, 3168, 3167, -1, + 3168, 3166, 3169, -1, 3169, 3170, 3168, -1, + 3170, 3169, 3171, -1, 3171, 3172, 3170, -1, + 3172, 3171, 3173, -1, 3173, 3174, 3172, -1, + 3174, 3173, 3175, -1, 3175, 3176, 3174, -1, + 3176, 3175, 3177, -1, 3177, 3178, 3176, -1, + 3178, 3177, 3179, -1, 3179, 3180, 3178, -1, + 3180, 3179, 3181, -1, 3181, 3182, 3180, -1, + 3182, 3181, 3183, -1, 3183, 3184, 3182, -1, + 3185, 3186, 3187, -1, 3187, 3188, 3185, -1, + 3188, 3187, 3189, -1, 3189, 3190, 3188, -1, + 3190, 3189, 3191, -1, 3191, 3192, 3190, -1, + 3192, 3191, 3193, -1, 3193, 3194, 3192, -1, + 3194, 3193, 3195, -1, 3195, 3196, 3194, -1, + 3196, 3195, 3197, -1, 3197, 3198, 3196, -1, + 3198, 3197, 3199, -1, 3199, 3200, 3198, -1, + 3200, 3199, 3201, -1, 3201, 3202, 3200, -1, + 3202, 3201, 3203, -1, 3203, 3204, 3202, -1, + 3204, 3203, 3205, -1, 3205, 3206, 3204, -1, + 3207, 3208, 3209, -1, 3208, 3207, 3210, -1, + 3210, 3211, 3208, -1, 3211, 3210, 3212, -1, + 3212, 3213, 3211, -1, 3213, 3212, 3214, -1, + 3214, 3215, 3213, -1, 3215, 3214, 3216, -1, + 3216, 3217, 3215, -1, 3217, 3216, 3218, -1, + 3218, 3219, 3217, -1, 3219, 3218, 3220, -1, + 3220, 3221, 3219, -1, 3221, 3220, 3222, -1, + 3222, 3223, 3221, -1, 3223, 3222, 3224, -1, + 3224, 3225, 3223, -1, 3225, 3224, 3226, -1, + 3226, 3227, 3225, -1, 3227, 3226, 3228, -1, + 3228, 3229, 3227, -1, 3229, 3228, 3230, -1, + 3230, 3231, 3229, -1, 3231, 3230, 3232, -1, + 3232, 3233, 3231, -1, 3233, 3232, 3234, -1, + 3234, 3235, 3233, -1, 3235, 3234, 3236, -1, + 3237, 3238, 3239, -1, 3240, 3241, 3242, -1, + 3240, 3242, 3243, -1, 3244, 3245, 3246, -1, + 3246, 3247, 3244, -1, 3247, 3246, 3248, -1, + 3248, 3249, 3247, -1, 3249, 3248, 3250, -1, + 3250, 3251, 3249, -1, 3251, 3250, 3252, -1, + 3252, 3253, 3251, -1, 3253, 3252, 3254, -1, + 3254, 3255, 3253, -1, 3255, 3254, 3256, -1, + 3256, 3257, 3255, -1, 3257, 3256, 3258, -1, + 3258, 3259, 3257, -1, 3259, 3258, 3260, -1, + 3260, 3261, 3259, -1, 3261, 3260, 3262, -1, + 3262, 3263, 3261, -1, 3263, 3262, 3264, -1, + 3264, 3265, 3263, -1, 3265, 3264, 3266, -1, + 3266, 3267, 3265, -1, 3267, 3266, 3268, -1, + 3268, 3269, 3267, -1, 3269, 3268, 3270, -1, + 3270, 3271, 3269, -1, 3271, 3270, 3272, -1, + 3272, 3273, 3271, -1, 3273, 3272, 3274, -1, + 3274, 3275, 3273, -1, 3275, 3274, 3276, -1, + 3276, 3277, 3275, -1, 3277, 3276, 3243, -1, + 3277, 3243, 3242, -1, 3277, 3242, 3278, -1, + 3278, 3275, 3277, -1, 3275, 3278, 3279, -1, + 3279, 3273, 3275, -1, 3273, 3279, 3280, -1, + 3280, 3271, 3273, -1, 3271, 3280, 3281, -1, + 3281, 3269, 3271, -1, 3269, 3281, 3282, -1, + 3282, 3267, 3269, -1, 3267, 3282, 3283, -1, + 3283, 3265, 3267, -1, 3265, 3283, 3284, -1, + 3284, 3263, 3265, -1, 3263, 3284, 3285, -1, + 3285, 3261, 3263, -1, 3261, 3285, 3286, -1, + 3286, 3259, 3261, -1, 3259, 3286, 3287, -1, + 3287, 3257, 3259, -1, 3257, 3287, 3288, -1, + 3288, 3255, 3257, -1, 3255, 3288, 3289, -1, + 3289, 3253, 3255, -1, 3253, 3289, 3290, -1, + 3290, 3251, 3253, -1, 3251, 3290, 3291, -1, + 3291, 3249, 3251, -1, 3249, 3291, 3292, -1, + 3292, 3247, 3249, -1, 3247, 3292, 3293, -1, + 3293, 3244, 3247, -1, 3244, 3293, 3294, -1, + 3294, 3245, 3244, -1, 3295, 3296, 3297, -1, + 3297, 3298, 3295, -1, 3298, 3297, 3299, -1, + 3299, 3300, 3298, -1, 3300, 3299, 3301, -1, + 3301, 3302, 3300, -1, 3302, 3301, 3303, -1, + 3303, 3304, 3302, -1, 3304, 3303, 3305, -1, + 3305, 3306, 3304, -1, 3306, 3305, 3307, -1, + 3307, 3308, 3306, -1, 3308, 3307, 3309, -1, + 3309, 3310, 3308, -1, 3310, 3309, 3311, -1, + 3311, 3312, 3310, -1, 3312, 3311, 3313, -1, + 3313, 3314, 3312, -1, 3314, 3313, 3315, -1, + 3315, 3316, 3314, -1, 3316, 3315, 3317, -1, + 3317, 3318, 3316, -1, 3318, 3317, 3319, -1, + 3319, 3320, 3318, -1, 3320, 3319, 3321, -1, + 3321, 3322, 3320, -1, 3322, 3321, 3245, -1, + 3245, 3294, 3322, -1, 3323, 3322, 3294, -1, + 3294, 3324, 3323, -1, 3324, 3294, 3293, -1, + 3293, 3325, 3324, -1, 3325, 3293, 3292, -1, + 3292, 3326, 3325, -1, 3326, 3292, 3291, -1, + 3291, 3327, 3326, -1, 3327, 3291, 3290, -1, + 3290, 3328, 3327, -1, 3328, 3290, 3289, -1, + 3289, 3329, 3328, -1, 3329, 3289, 3288, -1, + 3288, 3330, 3329, -1, 3330, 3288, 3287, -1, + 3287, 3331, 3330, -1, 3331, 3287, 3286, -1, + 3286, 3332, 3331, -1, 3332, 3286, 3285, -1, + 3285, 3333, 3332, -1, 3333, 3285, 3284, -1, + 3284, 3334, 3333, -1, 3334, 3284, 3283, -1, + 3283, 3335, 3334, -1, 3335, 3283, 3282, -1, + 3282, 3336, 3335, -1, 3336, 3282, 3281, -1, + 3281, 3337, 3336, -1, 3337, 3281, 3280, -1, + 3280, 3338, 3337, -1, 3338, 3280, 3279, -1, + 3279, 3339, 3338, -1, 3339, 3279, 3278, -1, + 3278, 3340, 3339, -1, 3340, 3278, 3242, -1, + 3242, 3341, 3340, -1, 3341, 3242, 3241, -1, + 3241, 3342, 3341, -1, 3342, 3241, 3343, -1, + 3343, 3344, 3342, -1, 3344, 3343, 3345, -1, + 3345, 3346, 3344, -1, 3346, 3345, 3347, -1, + 3347, 3348, 3346, -1, 3348, 3347, 3349, -1, + 3349, 3350, 3348, -1, 3350, 3349, 3351, -1, + 3351, 3352, 3350, -1, 3352, 3351, 3353, -1, + 3352, 3353, 3354, -1, 3354, 3355, 3352, -1, + 3355, 3354, 3356, -1, 3356, 3357, 3355, -1, + 3357, 3356, 3358, -1, 3358, 3359, 3357, -1, + 3359, 3358, 3360, -1, 3360, 3361, 3359, -1, + 3361, 3360, 3362, -1, 3362, 3363, 3361, -1, + 3363, 3362, 3364, -1, 3364, 3365, 3363, -1, + 3366, 3367, 3368, -1, 3367, 3366, 3369, -1, + 3369, 3370, 3367, -1, 3370, 3369, 3371, -1, + 3371, 3372, 3370, -1, 3372, 3371, 3373, -1, + 3373, 3374, 3372, -1, 3374, 3373, 3375, -1, + 3375, 3376, 3374, -1, 3376, 3375, 3377, -1, + 3377, 3378, 3376, -1, 3378, 3377, 3379, -1, + 3379, 3380, 3378, -1, 3380, 3379, 3381, -1, + 3381, 3382, 3380, -1, 3382, 3381, 3383, -1, + 3383, 3384, 3382, -1, 3384, 3383, 3385, -1, + 3385, 3386, 3384, -1, 3386, 3385, 3387, -1, + 3387, 3388, 3386, -1, 3388, 3387, 3389, -1, + 3389, 3390, 3388, -1, 3390, 3389, 3391, -1, + 3391, 3392, 3390, -1, 3392, 3391, 3393, -1, + 3393, 3394, 3392, -1, 3394, 3393, 3395, -1, + 3395, 3396, 3394, -1, 3396, 3395, 3397, -1, + 3397, 3398, 3396, -1, 3398, 3397, 3399, -1, + 3399, 3400, 3398, -1, 3400, 3399, 3401, -1, + 3401, 3402, 3400, -1, 3402, 3401, 3365, -1, + 3365, 3364, 3402, -1, 3403, 3402, 3364, -1, + 3403, 3404, 3402, -1, 3405, 3406, 3407, -1, + 3406, 3405, 3408, -1, 3408, 3409, 3406, -1, + 3409, 3408, 3410, -1, 3410, 3411, 3409, -1, + 3411, 3410, 3412, -1, 3412, 3413, 3411, -1, + 3413, 3412, 3414, -1, 3414, 3415, 3413, -1, + 3415, 3414, 3416, -1, 3416, 3417, 3415, -1, + 3417, 3416, 3418, -1, 3418, 3419, 3417, -1, + 3419, 3418, 3420, -1, 3420, 3421, 3419, -1, + 3421, 3420, 3422, -1, 3422, 3423, 3421, -1, + 3423, 3422, 3424, -1, 3424, 3425, 3423, -1, + 3425, 3424, 3426, -1, 3426, 3427, 3425, -1, + 3427, 3426, 3428, -1, 3428, 3429, 3427, -1, + 3429, 3428, 3430, -1, 3430, 3431, 3429, -1, + 3431, 3430, 3432, -1, 3432, 3433, 3431, -1, + 3433, 3432, 3434, -1, 3434, 3435, 3433, -1, + 3435, 3434, 3436, -1, 3436, 3437, 3435, -1, + 3437, 3436, 3438, -1, 3438, 3404, 3437, -1, + 3438, 3402, 3404, -1, 3438, 3400, 3402, -1, + 3400, 3438, 3436, -1, 3436, 3398, 3400, -1, + 3398, 3436, 3434, -1, 3434, 3396, 3398, -1, + 3396, 3434, 3432, -1, 3432, 3394, 3396, -1, + 3394, 3432, 3430, -1, 3430, 3392, 3394, -1, + 3392, 3430, 3428, -1, 3428, 3390, 3392, -1, + 3390, 3428, 3426, -1, 3426, 3388, 3390, -1, + 3388, 3426, 3424, -1, 3424, 3386, 3388, -1, + 3386, 3424, 3422, -1, 3422, 3384, 3386, -1, + 3384, 3422, 3420, -1, 3420, 3382, 3384, -1, + 3382, 3420, 3418, -1, 3418, 3380, 3382, -1, + 3380, 3418, 3416, -1, 3416, 3378, 3380, -1, + 3378, 3416, 3414, -1, 3414, 3376, 3378, -1, + 3376, 3414, 3412, -1, 3412, 3374, 3376, -1, + 3374, 3412, 3410, -1, 3410, 3372, 3374, -1, + 3372, 3410, 3408, -1, 3408, 3370, 3372, -1, + 3370, 3408, 3405, -1, 3405, 3367, 3370, -1, + 3367, 3405, 3407, -1, 3407, 3368, 3367, -1, + 3368, 3407, 3439, -1, 3439, 3440, 3368, -1, + 3440, 3439, 3441, -1, 3441, 3442, 3440, -1, + 3442, 3441, 3443, -1, 3443, 3444, 3442, -1, + 3444, 3443, 3445, -1, 3445, 3446, 3444, -1, + 3446, 3445, 3447, -1, 3447, 3448, 3446, -1, + 3448, 3447, 3449, -1, 3449, 3450, 3448, -1, + 3450, 3449, 3451, -1, 3451, 3452, 3450, -1, + 3452, 3451, 3453, -1, 3453, 3454, 3452, -1, + 3454, 3453, 3455, -1, 3455, 3456, 3454, -1, + 3456, 3455, 3457, -1, 3457, 3458, 3456, -1, + 3458, 3457, 3459, -1, 3459, 3460, 3458, -1, + 3460, 3459, 3461, -1, 3461, 3462, 3460, -1, + 3462, 3461, 3463, -1, 3463, 3238, 3462, -1, + 3238, 3463, 3464, -1, 3464, 3239, 3238, -1, + 3465, 3466, 3239, -1, 3239, 3464, 3465, -1, + 3465, 3467, 3468, -1, 3465, 3469, 3467, -1, + 3469, 3465, 3464, -1, 3464, 3470, 3469, -1, + 3470, 3464, 3463, -1, 3463, 3471, 3470, -1, + 3471, 3463, 3461, -1, 3461, 3472, 3471, -1, + 3472, 3461, 3459, -1, 3459, 3473, 3472, -1, + 3473, 3459, 3457, -1, 3457, 3474, 3473, -1, + 3474, 3457, 3455, -1, 3455, 3475, 3474, -1, + 3475, 3455, 3453, -1, 3453, 3476, 3475, -1, + 3476, 3453, 3451, -1, 3451, 3477, 3476, -1, + 3477, 3451, 3449, -1, 3449, 3478, 3477, -1, + 3478, 3449, 3447, -1, 3447, 3479, 3478, -1, + 3479, 3447, 3445, -1, 3445, 3480, 3479, -1, + 3480, 3445, 3443, -1, 3443, 3481, 3480, -1, + 3481, 3443, 3441, -1, 3441, 3482, 3481, -1, + 3482, 3441, 3439, -1, 3439, 3483, 3482, -1, + 3483, 3439, 3407, -1, 3407, 3236, 3483, -1, + 3236, 3407, 3406, -1, 3406, 3235, 3236, -1, + 3235, 3406, 3409, -1, 3409, 3233, 3235, -1, + 3233, 3409, 3411, -1, 3411, 3231, 3233, -1, + 3231, 3411, 3413, -1, 3413, 3229, 3231, -1, + 3229, 3413, 3415, -1, 3415, 3227, 3229, -1, + 3227, 3415, 3417, -1, 3417, 3225, 3227, -1, + 3225, 3417, 3419, -1, 3419, 3223, 3225, -1, + 3223, 3419, 3421, -1, 3421, 3221, 3223, -1, + 3221, 3421, 3423, -1, 3423, 3219, 3221, -1, + 3219, 3423, 3425, -1, 3425, 3217, 3219, -1, + 3217, 3425, 3427, -1, 3427, 3215, 3217, -1, + 3215, 3427, 3429, -1, 3429, 3213, 3215, -1, + 3213, 3429, 3431, -1, 3431, 3211, 3213, -1, + 3211, 3431, 3433, -1, 3433, 3208, 3211, -1, + 3208, 3433, 3435, -1, 3435, 3209, 3208, -1, + 3209, 3435, 3437, -1, 3437, 3484, 3209, -1, + 3484, 3437, 3404, -1, 3404, 3485, 3484, -1, + 3485, 3404, 3403, -1, 3403, 3486, 3485, -1, + 3403, 3364, 3486, -1, 3487, 3486, 3364, -1, + 3487, 3364, 3362, -1, 3362, 3488, 3487, -1, + 3488, 3362, 3360, -1, 3360, 3489, 3488, -1, + 3489, 3360, 3358, -1, 3358, 3490, 3489, -1, + 3490, 3358, 3356, -1, 3356, 3491, 3490, -1, + 3491, 3356, 3354, -1, 3354, 3492, 3491, -1, + 3492, 3354, 3353, -1, 3353, 3493, 3492, -1, + 3353, 3494, 3493, -1, 3494, 3353, 3351, -1, + 3351, 3495, 3494, -1, 3495, 3351, 3349, -1, + 3349, 3496, 3495, -1, 3496, 3349, 3347, -1, + 3347, 3497, 3496, -1, 3497, 3347, 3345, -1, + 3345, 3498, 3497, -1, 3498, 3345, 3343, -1, + 3343, 3499, 3498, -1, 3499, 3343, 3241, -1, + 3241, 3240, 3499, -1, 3500, 3240, 3501, -1, + 3500, 3499, 3240, -1, 3499, 3500, 3502, -1, + 3502, 3498, 3499, -1, 3498, 3502, 3503, -1, + 3503, 3497, 3498, -1, 3497, 3503, 3504, -1, + 3504, 3496, 3497, -1, 3496, 3504, 3505, -1, + 3505, 3495, 3496, -1, 3495, 3505, 3506, -1, + 3506, 3494, 3495, -1, 3494, 3506, 3507, -1, + 3507, 3493, 3494, -1, 3493, 3507, 3508, -1, + 3493, 3508, 3509, -1, 3509, 3492, 3493, -1, + 3492, 3509, 3510, -1, 3510, 3491, 3492, -1, + 3491, 3510, 3511, -1, 3511, 3490, 3491, -1, + 3490, 3511, 3512, -1, 3512, 3489, 3490, -1, + 3489, 3512, 3513, -1, 3513, 3488, 3489, -1, + 3488, 3513, 3514, -1, 3514, 3487, 3488, -1, + 3514, 3515, 3487, -1, 3516, 3517, 3518, -1, + 3517, 3516, 3519, -1, 3519, 3520, 3517, -1, + 3520, 3519, 3521, -1, 3521, 3522, 3520, -1, + 3522, 3521, 3523, -1, 3523, 3524, 3522, -1, + 3524, 3523, 3525, -1, 3525, 3526, 3524, -1, + 3526, 3525, 3527, -1, 3527, 3528, 3526, -1, + 3528, 3527, 3515, -1, 3515, 3529, 3528, -1, + 3529, 3515, 3514, -1, 3514, 3530, 3529, -1, + 3530, 3514, 3513, -1, 3513, 3531, 3530, -1, + 3531, 3513, 3512, -1, 3512, 3532, 3531, -1, + 3532, 3512, 3511, -1, 3511, 3533, 3532, -1, + 3533, 3511, 3510, -1, 3510, 3534, 3533, -1, + 3534, 3510, 3509, -1, 3509, 3535, 3534, -1, + 3535, 3509, 3508, -1, 3508, 3536, 3535, -1, + 3508, 3537, 3536, -1, 3537, 3508, 3507, -1, + 3507, 3538, 3537, -1, 3538, 3507, 3506, -1, + 3506, 3539, 3538, -1, 3539, 3506, 3505, -1, + 3505, 3540, 3539, -1, 3540, 3505, 3504, -1, + 3504, 3541, 3540, -1, 3541, 3504, 3503, -1, + 3503, 3542, 3541, -1, 3542, 3503, 3502, -1, + 3502, 3543, 3542, -1, 3543, 3502, 3500, -1, + 3500, 3544, 3543, -1, 3544, 3500, 3501, -1, + 3501, 3545, 3544, -1, 3545, 3501, 3546, -1, + 3546, 3547, 3545, -1, 3547, 3546, 3548, -1, + 3548, 3549, 3547, -1, 3549, 3548, 3550, -1, + 3550, 3551, 3549, -1, 3551, 3550, 3552, -1, + 3552, 3553, 3551, -1, 3553, 3552, 3554, -1, + 3554, 3555, 3553, -1, 3555, 3554, 3556, -1, + 3556, 3557, 3555, -1, 3557, 3556, 3558, -1, + 3558, 3559, 3557, -1, 3559, 3558, 3560, -1, + 3560, 3561, 3559, -1, 3561, 3560, 3562, -1, + 3562, 3563, 3561, -1, 3563, 3562, 3564, -1, + 3564, 3565, 3563, -1, 3565, 3564, 3566, -1, + 3566, 3567, 3565, -1, 3567, 3566, 3568, -1, + 3568, 3569, 3567, -1, 3569, 3568, 3570, -1, + 3570, 3571, 3569, -1, 3571, 3570, 3572, -1, + 3572, 3573, 3571, -1, 3573, 3572, 3574, -1, + 3574, 3575, 3573, -1, 3575, 3574, 3576, -1, + 3576, 3577, 3575, -1, 3575, 3577, 3206, -1, + 3206, 3573, 3575, -1, 3573, 3206, 3205, -1, + 3205, 3571, 3573, -1, 3571, 3205, 3203, -1, + 3203, 3569, 3571, -1, 3569, 3203, 3201, -1, + 3201, 3567, 3569, -1, 3567, 3201, 3199, -1, + 3199, 3565, 3567, -1, 3565, 3199, 3197, -1, + 3197, 3563, 3565, -1, 3563, 3197, 3195, -1, + 3195, 3561, 3563, -1, 3561, 3195, 3193, -1, + 3193, 3559, 3561, -1, 3559, 3193, 3191, -1, + 3191, 3557, 3559, -1, 3557, 3191, 3189, -1, + 3189, 3555, 3557, -1, 3555, 3189, 3187, -1, + 3187, 3553, 3555, -1, 3553, 3187, 3186, -1, + 3186, 3551, 3553, -1, 3551, 3186, 3578, -1, + 3578, 3549, 3551, -1, 3549, 3578, 3579, -1, + 3579, 3547, 3549, -1, 3547, 3579, 3580, -1, + 3580, 3545, 3547, -1, 3545, 3580, 3581, -1, + 3581, 3544, 3545, -1, 3581, 3582, 3544, -1, + 3581, 3583, 3582, -1, 3583, 3581, 3580, -1, + 3580, 3584, 3583, -1, 3584, 3580, 3579, -1, + 3579, 3585, 3584, -1, 3585, 3579, 3578, -1, + 3578, 3586, 3585, -1, 3586, 3578, 3186, -1, + 3186, 3185, 3586, -1, 3586, 3185, 3587, -1, + 3587, 3585, 3586, -1, 3585, 3587, 3588, -1, + 3588, 3584, 3585, -1, 3584, 3588, 3589, -1, + 3589, 3583, 3584, -1, 3583, 3589, 3590, -1, + 3590, 3582, 3583, -1, 3582, 3590, 3184, -1, + 3184, 3183, 3582, -1, 3183, 3544, 3582, -1, + 3183, 3543, 3544, -1, 3543, 3183, 3181, -1, + 3181, 3542, 3543, -1, 3542, 3181, 3179, -1, + 3179, 3541, 3542, -1, 3541, 3179, 3177, -1, + 3177, 3540, 3541, -1, 3540, 3177, 3175, -1, + 3175, 3539, 3540, -1, 3539, 3175, 3173, -1, + 3173, 3538, 3539, -1, 3538, 3173, 3171, -1, + 3171, 3537, 3538, -1, 3537, 3171, 3169, -1, + 3169, 3536, 3537, -1, 3536, 3169, 3166, -1, + 3536, 3166, 3164, -1, 3164, 3535, 3536, -1, + 3535, 3164, 3162, -1, 3162, 3534, 3535, -1, + 3534, 3162, 3160, -1, 3160, 3533, 3534, -1, + 3533, 3160, 3158, -1, 3158, 3532, 3533, -1, + 3532, 3158, 3156, -1, 3156, 3531, 3532, -1, + 3531, 3156, 3154, -1, 3154, 3530, 3531, -1, + 3530, 3154, 3153, -1, 3153, 3529, 3530, -1, + 3153, 3591, 3529, -1, 3592, 3593, 3594, -1, + 3593, 3592, 3595, -1, 3595, 3596, 3593, -1, + 3596, 3595, 3597, -1, 3597, 3598, 3596, -1, + 3598, 3597, 3599, -1, 3599, 3600, 3598, -1, + 3600, 3599, 3601, -1, 3601, 3602, 3600, -1, + 3602, 3601, 3603, -1, 3603, 3604, 3602, -1, + 3604, 3603, 3591, -1, 3591, 3605, 3604, -1, + 3605, 3591, 3153, -1, 3605, 3153, 3152, -1, + 3605, 3152, 3606, -1, 3606, 3604, 3605, -1, + 3604, 3606, 3607, -1, 3607, 3602, 3604, -1, + 3602, 3607, 3608, -1, 3608, 3600, 3602, -1, + 3600, 3608, 3609, -1, 3609, 3598, 3600, -1, + 3598, 3609, 3610, -1, 3610, 3596, 3598, -1, + 3596, 3610, 3611, -1, 3611, 3593, 3596, -1, + 3593, 3611, 3612, -1, 3612, 3594, 3593, -1, + 3594, 3612, 3613, -1, 3613, 3614, 3594, -1, + 3614, 3613, 3615, -1, 3615, 3616, 3614, -1, + 3616, 3615, 3617, -1, 3617, 3618, 3616, -1, + 3618, 3617, 3619, -1, 3619, 3620, 3618, -1, + 3620, 3619, 3621, -1, 3621, 3622, 3620, -1, + 3622, 3621, 3623, -1, 3623, 3624, 3622, -1, + 3624, 3623, 3625, -1, 3625, 3626, 3624, -1, + 3626, 3625, 3627, -1, 3627, 3628, 3626, -1, + 3628, 3627, 3629, -1, 3629, 3630, 3628, -1, + 3631, 3630, 3150, -1, 3630, 3631, 3632, -1, + 3632, 3628, 3630, -1, 3628, 3632, 3633, -1, + 3633, 3626, 3628, -1, 3626, 3633, 3634, -1, + 3634, 3624, 3626, -1, 3624, 3634, 3635, -1, + 3635, 3622, 3624, -1, 3622, 3635, 3636, -1, + 3636, 3620, 3622, -1, 3620, 3636, 3637, -1, + 3637, 3618, 3620, -1, 3618, 3637, 3638, -1, + 3638, 3616, 3618, -1, 3616, 3638, 3639, -1, + 3639, 3614, 3616, -1, 3614, 3639, 3640, -1, + 3640, 3594, 3614, -1, 3594, 3640, 3641, -1, + 3641, 3592, 3594, -1, 3592, 3641, 3642, -1, + 3642, 3595, 3592, -1, 3595, 3642, 3643, -1, + 3643, 3597, 3595, -1, 3597, 3643, 3644, -1, + 3644, 3599, 3597, -1, 3599, 3644, 3645, -1, + 3645, 3601, 3599, -1, 3601, 3645, 3646, -1, + 3646, 3603, 3601, -1, 3603, 3646, 3647, -1, + 3647, 3591, 3603, -1, 3647, 3529, 3591, -1, + 3647, 3528, 3529, -1, 3528, 3647, 3646, -1, + 3646, 3526, 3528, -1, 3526, 3646, 3645, -1, + 3645, 3524, 3526, -1, 3524, 3645, 3644, -1, + 3644, 3522, 3524, -1, 3522, 3644, 3643, -1, + 3643, 3520, 3522, -1, 3520, 3643, 3642, -1, + 3642, 3517, 3520, -1, 3517, 3642, 3641, -1, + 3641, 3518, 3517, -1, 3518, 3641, 3640, -1, + 3640, 3648, 3518, -1, 3648, 3640, 3639, -1, + 3639, 3649, 3648, -1, 3649, 3639, 3638, -1, + 3638, 3650, 3649, -1, 3650, 3638, 3637, -1, + 3637, 3651, 3650, -1, 3651, 3637, 3636, -1, + 3636, 3652, 3651, -1, 3652, 3636, 3635, -1, + 3635, 3653, 3652, -1, 3653, 3635, 3634, -1, + 3634, 3654, 3653, -1, 3654, 3634, 3633, -1, + 3633, 3655, 3654, -1, 3655, 3633, 3632, -1, + 3632, 3656, 3655, -1, 3656, 3632, 3631, -1, + 3631, 3657, 3656, -1, 3657, 3631, 3150, -1, + 3150, 3149, 3657, -1, 3658, 3657, 3149, -1, + 3657, 3658, 3659, -1, 3659, 3656, 3657, -1, + 3656, 3659, 3660, -1, 3660, 3655, 3656, -1, + 3655, 3660, 3661, -1, 3661, 3654, 3655, -1, + 3654, 3661, 3662, -1, 3662, 3653, 3654, -1, + 3653, 3662, 3663, -1, 3663, 3652, 3653, -1, + 3652, 3663, 3664, -1, 3664, 3651, 3652, -1, + 3651, 3664, 3665, -1, 3665, 3650, 3651, -1, + 3650, 3665, 3666, -1, 3666, 3649, 3650, -1, + 3649, 3666, 3667, -1, 3667, 3648, 3649, -1, + 3648, 3667, 3668, -1, 3668, 3518, 3648, -1, + 3518, 3668, 3669, -1, 3669, 3516, 3518, -1, + 3516, 3669, 3670, -1, 3670, 3519, 3516, -1, + 3519, 3670, 3671, -1, 3671, 3521, 3519, -1, + 3521, 3671, 3672, -1, 3672, 3523, 3521, -1, + 3523, 3672, 3673, -1, 3673, 3525, 3523, -1, + 3525, 3673, 3674, -1, 3674, 3527, 3525, -1, + 3527, 3674, 3675, -1, 3675, 3515, 3527, -1, + 3675, 3487, 3515, -1, 3675, 3486, 3487, -1, + 3486, 3675, 3674, -1, 3674, 3485, 3486, -1, + 3485, 3674, 3673, -1, 3673, 3484, 3485, -1, + 3484, 3673, 3672, -1, 3672, 3209, 3484, -1, + 3209, 3672, 3671, -1, 3671, 3207, 3209, -1, + 3207, 3671, 3670, -1, 3670, 3210, 3207, -1, + 3210, 3670, 3669, -1, 3669, 3212, 3210, -1, + 3212, 3669, 3668, -1, 3668, 3214, 3212, -1, + 3214, 3668, 3667, -1, 3667, 3216, 3214, -1, + 3216, 3667, 3666, -1, 3666, 3218, 3216, -1, + 3218, 3666, 3665, -1, 3665, 3220, 3218, -1, + 3220, 3665, 3664, -1, 3664, 3222, 3220, -1, + 3222, 3664, 3663, -1, 3663, 3224, 3222, -1, + 3224, 3663, 3662, -1, 3662, 3226, 3224, -1, + 3226, 3662, 3661, -1, 3661, 3228, 3226, -1, + 3228, 3661, 3660, -1, 3660, 3230, 3228, -1, + 3230, 3660, 3659, -1, 3659, 3232, 3230, -1, + 3232, 3659, 3658, -1, 3658, 3234, 3232, -1, + 3234, 3658, 3149, -1, 3149, 3236, 3234, -1, + 3236, 3149, 3147, -1, 3147, 3483, 3236, -1, + 3483, 3147, 3145, -1, 3145, 3482, 3483, -1, + 3482, 3145, 3143, -1, 3143, 3481, 3482, -1, + 3481, 3143, 3141, -1, 3141, 3480, 3481, -1, + 3480, 3141, 3139, -1, 3139, 3479, 3480, -1, + 3479, 3139, 3137, -1, 3137, 3478, 3479, -1, + 3478, 3137, 3135, -1, 3135, 3477, 3478, -1, + 3477, 3135, 3133, -1, 3133, 3476, 3477, -1, + 3476, 3133, 3131, -1, 3131, 3475, 3476, -1, + 3475, 3131, 3129, -1, 3129, 3474, 3475, -1, + 3474, 3129, 3127, -1, 3127, 3473, 3474, -1, + 3473, 3127, 3125, -1, 3125, 3472, 3473, -1, + 3472, 3125, 3123, -1, 3123, 3471, 3472, -1, + 3471, 3123, 3122, -1, 3122, 3470, 3471, -1, + 3470, 3122, 3676, -1, 3676, 3469, 3470, -1, + 3469, 3676, 3677, -1, 3677, 3467, 3469, -1, + 3467, 3677, 3120, -1, 3120, 3119, 3467, -1, + 3678, 3467, 3119, -1, 3119, 3679, 3678, -1, + 3119, 3118, 3679, -1, 3680, 3681, 3682, -1, + 3681, 3680, 3679, -1, 3681, 3679, 3118, -1, + 3118, 3120, 3681, -1, 3120, 3682, 3681, -1, + 3120, 3683, 3682, -1, 3683, 3120, 3677, -1, + 3677, 3684, 3683, -1, 3684, 3677, 3676, -1, + 3676, 3685, 3684, -1, 3685, 3676, 3122, -1, + 3122, 3121, 3685, -1, 3686, 3685, 3121, -1, + 3685, 3686, 3687, -1, 3687, 3684, 3685, -1, + 3684, 3687, 3688, -1, 3688, 3683, 3684, -1, + 3683, 3688, 3689, -1, 3689, 3682, 3683, -1, + 3690, 3691, 3682, -1, 3682, 3689, 3690, -1, + 3692, 3693, 3694, -1, 3695, 3696, 3697, -1, + 3697, 3698, 3695, -1, 3698, 3697, 3699, -1, + 3699, 3700, 3698, -1, 3700, 3699, 3701, -1, + 3701, 3702, 3700, -1, 3702, 3701, 3703, -1, + 3703, 3704, 3702, -1, 3704, 3703, 3705, -1, + 3705, 3706, 3704, -1, 3706, 3705, 3692, -1, + 3692, 3694, 3706, -1, 3707, 3708, 3709, -1, + 3710, 3711, 3712, -1, 3712, 3713, 3710, -1, + 3713, 3712, 3714, -1, 3714, 3715, 3713, -1, + 3715, 3714, 3716, -1, 3716, 3717, 3715, -1, + 3717, 3716, 3718, -1, 3718, 3719, 3717, -1, + 3720, 3721, 3722, -1, 3722, 3723, 3720, -1, + 3723, 3722, 3719, -1, 3719, 3718, 3723, -1, + 3718, 3724, 3723, -1, 3724, 3718, 3716, -1, + 3716, 3725, 3724, -1, 3725, 3716, 3714, -1, + 3714, 3726, 3725, -1, 3726, 3714, 3712, -1, + 3712, 3727, 3726, -1, 3727, 3712, 3711, -1, + 3711, 3728, 3727, -1, 3728, 3711, 3729, -1, + 3729, 3730, 3728, -1, 3730, 3729, 3731, -1, + 3731, 3732, 3730, -1, 3732, 3731, 3733, -1, + 3733, 3734, 3732, -1, 3735, 3736, 3737, -1, + 3737, 3738, 3735, -1, 3739, 3740, 3741, -1, + 3741, 3742, 3739, -1, 3742, 3741, 3743, -1, + 3743, 3741, 3744, -1, 3743, 3744, 3745, -1, + 3745, 3746, 3743, -1, 3746, 3745, 3738, -1, + 3738, 3737, 3746, -1, 3747, 3746, 3737, -1, + 3737, 3748, 3747, -1, 3748, 3737, 3736, -1, + 3736, 3749, 3748, -1, 3750, 3751, 3709, -1, + 3750, 3709, 3749, -1, 3749, 3736, 3750, -1, + 3752, 3753, 3754, -1, 3750, 3754, 3753, -1, + 3754, 3750, 3736, -1, 3736, 3735, 3754, -1, + 3755, 3756, 3757, -1, 3757, 3756, 3754, -1, + 3757, 3754, 3735, -1, 3735, 3758, 3757, -1, + 3758, 3735, 3738, -1, 3738, 3759, 3758, -1, + 3759, 3738, 3745, -1, 3745, 3760, 3759, -1, + 3760, 3745, 3744, -1, 3744, 3761, 3760, -1, + 3762, 3763, 3764, -1, 3764, 3765, 3762, -1, + 3765, 3764, 3766, -1, 3766, 3767, 3765, -1, + 3767, 3766, 3768, -1, 3768, 3769, 3767, -1, + 3769, 3768, 3761, -1, 3761, 3770, 3769, -1, + 3770, 3761, 3744, -1, 3770, 3744, 3741, -1, + 3770, 3741, 3740, -1, 3740, 3769, 3770, -1, + 3769, 3740, 3771, -1, 3771, 3767, 3769, -1, + 3767, 3771, 3772, -1, 3772, 3765, 3767, -1, + 3765, 3772, 3773, -1, 3773, 3762, 3765, -1, + 3762, 3773, 3774, -1, 3774, 3763, 3762, -1, + 3763, 3774, 3775, -1, 3775, 3776, 3763, -1, + 3776, 3775, 3777, -1, 3777, 3778, 3776, -1, + 3778, 3777, 3779, -1, 3779, 3780, 3778, -1, + 3780, 3779, 3781, -1, 3781, 3782, 3780, -1, + 3782, 3781, 3783, -1, 3783, 3784, 3782, -1, + 3784, 3783, 3785, -1, 3785, 3786, 3784, -1, + 3786, 3785, 3787, -1, 3787, 3788, 3786, -1, + 3788, 3787, 3789, -1, 3789, 3790, 3788, -1, + 3790, 3789, 3791, -1, 3791, 3792, 3790, -1, + 3792, 3791, 3793, -1, 3793, 3794, 3792, -1, + 3794, 3793, 3795, -1, 3795, 3796, 3794, -1, + 3796, 3795, 3797, -1, 3797, 3798, 3796, -1, + 3798, 3797, 3799, -1, 3799, 3800, 3798, -1, + 3800, 3799, 3801, -1, 3801, 3802, 3800, -1, + 3803, 3804, 3805, -1, 3804, 3803, 3806, -1, + 3806, 3807, 3804, -1, 3807, 3806, 3808, -1, + 3808, 3809, 3807, -1, 3809, 3808, 3810, -1, + 3810, 3811, 3809, -1, 3811, 3810, 3812, -1, + 3812, 3813, 3811, -1, 3813, 3812, 3814, -1, + 3814, 3815, 3813, -1, 3815, 3814, 3816, -1, + 3816, 3817, 3815, -1, 3817, 3816, 3818, -1, + 3818, 3819, 3817, -1, 3819, 3818, 3820, -1, + 3820, 3821, 3819, -1, 3821, 3820, 3822, -1, + 3822, 3823, 3821, -1, 3823, 3822, 3824, -1, + 3824, 3825, 3823, -1, 3825, 3824, 3826, -1, + 3826, 3827, 3825, -1, 3827, 3826, 3828, -1, + 3828, 3829, 3827, -1, 3829, 3828, 3830, -1, + 3830, 3831, 3829, -1, 3830, 3832, 3831, -1, + 3832, 3830, 3833, -1, 3833, 3834, 3832, -1, + 3834, 3833, 3835, -1, 3835, 3836, 3834, -1, + 3836, 3835, 3837, -1, 3837, 3838, 3836, -1, + 3838, 3837, 3839, -1, 3839, 3840, 3838, -1, + 3840, 3839, 3841, -1, 3841, 3842, 3840, -1, + 3842, 3841, 3843, -1, 3843, 3844, 3842, -1, + 3844, 3843, 3845, -1, 3845, 3846, 3844, -1, + 3846, 3845, 3847, -1, 3847, 3848, 3846, -1, + 3848, 3847, 3849, -1, 3849, 3850, 3848, -1, + 3850, 3849, 3851, -1, 3851, 3852, 3850, -1, + 3852, 3851, 3853, -1, 3853, 3854, 3852, -1, + 3854, 3853, 3855, -1, 3855, 3856, 3854, -1, + 3856, 3855, 3857, -1, 3857, 3858, 3856, -1, + 3858, 3857, 3859, -1, 3859, 3860, 3858, -1, + 3860, 3859, 3861, -1, 3861, 3862, 3860, -1, + 3862, 3861, 3863, -1, 3863, 3864, 3862, -1, + 3864, 3863, 3865, -1, 3865, 3866, 3864, -1, + 3866, 3865, 3867, -1, 3867, 3868, 3866, -1, + 3868, 3867, 3869, -1, 3869, 3870, 3868, -1, + 3870, 3869, 3871, -1, 3871, 3872, 3870, -1, + 3872, 3871, 3873, -1, 3873, 3874, 3872, -1, + 3874, 3873, 3875, -1, 3875, 3876, 3874, -1, + 3876, 3875, 3802, -1, 3802, 3801, 3876, -1, + 3876, 3801, 3877, -1, 3877, 3874, 3876, -1, + 3874, 3877, 3878, -1, 3878, 3872, 3874, -1, + 3872, 3878, 3879, -1, 3879, 3870, 3872, -1, + 3870, 3879, 3880, -1, 3880, 3868, 3870, -1, + 3868, 3880, 3881, -1, 3881, 3866, 3868, -1, + 3866, 3881, 3882, -1, 3882, 3864, 3866, -1, + 3864, 3882, 3883, -1, 3883, 3862, 3864, -1, + 3862, 3883, 3884, -1, 3884, 3860, 3862, -1, + 3860, 3884, 3885, -1, 3885, 3858, 3860, -1, + 3858, 3885, 3886, -1, 3886, 3856, 3858, -1, + 3856, 3886, 3887, -1, 3887, 3854, 3856, -1, + 3854, 3887, 3888, -1, 3888, 3852, 3854, -1, + 3852, 3888, 3889, -1, 3889, 3850, 3852, -1, + 3850, 3889, 3890, -1, 3890, 3848, 3850, -1, + 3848, 3890, 3891, -1, 3891, 3846, 3848, -1, + 3846, 3891, 3892, -1, 3892, 3844, 3846, -1, + 3844, 3892, 3893, -1, 3893, 3842, 3844, -1, + 3842, 3893, 3894, -1, 3894, 3840, 3842, -1, + 3840, 3894, 3895, -1, 3895, 3838, 3840, -1, + 3838, 3895, 3896, -1, 3896, 3836, 3838, -1, + 3836, 3896, 3897, -1, 3897, 3834, 3836, -1, + 3834, 3897, 3898, -1, 3898, 3832, 3834, -1, + 3832, 3898, 3899, -1, 3899, 3831, 3832, -1, + 3831, 3899, 3900, -1, 3831, 3900, 3901, -1, + 3901, 3829, 3831, -1, 3829, 3901, 3902, -1, + 3902, 3827, 3829, -1, 3827, 3902, 3903, -1, + 3903, 3825, 3827, -1, 3825, 3903, 3904, -1, + 3904, 3823, 3825, -1, 3823, 3904, 3905, -1, + 3905, 3821, 3823, -1, 3821, 3905, 3906, -1, + 3906, 3819, 3821, -1, 3819, 3906, 3907, -1, + 3907, 3817, 3819, -1, 3817, 3907, 3908, -1, + 3908, 3815, 3817, -1, 3815, 3908, 3909, -1, + 3909, 3813, 3815, -1, 3813, 3909, 3910, -1, + 3910, 3811, 3813, -1, 3811, 3910, 3911, -1, + 3911, 3809, 3811, -1, 3809, 3911, 3912, -1, + 3912, 3807, 3809, -1, 3807, 3912, 3913, -1, + 3913, 3804, 3807, -1, 3804, 3913, 3914, -1, + 3914, 3805, 3804, -1, 3805, 3914, 3734, -1, + 3734, 3733, 3805, -1, 3915, 3805, 3733, -1, + 3805, 3915, 3916, -1, 3916, 3803, 3805, -1, + 3803, 3916, 3917, -1, 3917, 3806, 3803, -1, + 3806, 3917, 3918, -1, 3918, 3808, 3806, -1, + 3808, 3918, 3919, -1, 3919, 3810, 3808, -1, + 3810, 3919, 3920, -1, 3920, 3812, 3810, -1, + 3812, 3920, 3921, -1, 3921, 3814, 3812, -1, + 3814, 3921, 3922, -1, 3922, 3816, 3814, -1, + 3816, 3922, 3923, -1, 3923, 3818, 3816, -1, + 3818, 3923, 3924, -1, 3924, 3820, 3818, -1, + 3820, 3924, 3925, -1, 3925, 3822, 3820, -1, + 3822, 3925, 3926, -1, 3926, 3824, 3822, -1, + 3824, 3926, 3927, -1, 3927, 3826, 3824, -1, + 3826, 3927, 3928, -1, 3928, 3828, 3826, -1, + 3828, 3928, 3929, -1, 3929, 3830, 3828, -1, + 3929, 3833, 3830, -1, 3833, 3929, 3930, -1, + 3930, 3835, 3833, -1, 3835, 3930, 3931, -1, + 3931, 3837, 3835, -1, 3837, 3931, 3932, -1, + 3932, 3839, 3837, -1, 3839, 3932, 3933, -1, + 3933, 3841, 3839, -1, 3841, 3933, 3934, -1, + 3934, 3843, 3841, -1, 3843, 3934, 3935, -1, + 3935, 3845, 3843, -1, 3845, 3935, 3936, -1, + 3936, 3847, 3845, -1, 3847, 3936, 3937, -1, + 3937, 3849, 3847, -1, 3849, 3937, 3938, -1, + 3938, 3851, 3849, -1, 3851, 3938, 3939, -1, + 3939, 3853, 3851, -1, 3853, 3939, 3940, -1, + 3940, 3855, 3853, -1, 3855, 3940, 3941, -1, + 3941, 3857, 3855, -1, 3857, 3941, 3942, -1, + 3942, 3859, 3857, -1, 3859, 3942, 3943, -1, + 3943, 3861, 3859, -1, 3861, 3943, 3944, -1, + 3944, 3863, 3861, -1, 3863, 3944, 3945, -1, + 3945, 3865, 3863, -1, 3865, 3945, 3946, -1, + 3946, 3867, 3865, -1, 3867, 3946, 3947, -1, + 3947, 3869, 3867, -1, 3869, 3947, 3948, -1, + 3948, 3871, 3869, -1, 3871, 3948, 3949, -1, + 3949, 3873, 3871, -1, 3873, 3949, 3950, -1, + 3950, 3875, 3873, -1, 3875, 3950, 3951, -1, + 3951, 3802, 3875, -1, 3802, 3951, 3952, -1, + 3952, 3800, 3802, -1, 3953, 3800, 3952, -1, + 3952, 3954, 3953, -1, 3954, 3952, 3951, -1, + 3951, 3955, 3954, -1, 3955, 3951, 3950, -1, + 3950, 3956, 3955, -1, 3956, 3950, 3949, -1, + 3949, 3957, 3956, -1, 3958, 3959, 3960, -1, + 3960, 3961, 3958, -1, 3961, 3960, 3962, -1, + 3962, 3963, 3961, -1, 3963, 3962, 3964, -1, + 3964, 3965, 3963, -1, 3966, 3963, 3965, -1, + 3965, 3967, 3966, -1, 3967, 3965, 3968, -1, + 3968, 3969, 3967, -1, 3969, 3968, 3970, -1, + 3970, 3971, 3969, -1, 3971, 3970, 3972, -1, + 3972, 3973, 3971, -1, 3973, 3972, 3974, -1, + 3974, 3975, 3973, -1, 3975, 3974, 3957, -1, + 3957, 3949, 3975, -1, 3975, 3949, 3948, -1, + 3948, 3973, 3975, -1, 3973, 3948, 3947, -1, + 3947, 3971, 3973, -1, 3971, 3947, 3946, -1, + 3946, 3969, 3971, -1, 3969, 3946, 3945, -1, + 3945, 3967, 3969, -1, 3967, 3945, 3944, -1, + 3944, 3966, 3967, -1, 3966, 3944, 3943, -1, + 3943, 3976, 3966, -1, 3977, 3978, 3979, -1, + 3978, 3977, 3980, -1, 3980, 3981, 3978, -1, + 3981, 3980, 3982, -1, 3982, 3983, 3981, -1, + 3983, 3982, 3984, -1, 3984, 3985, 3983, -1, + 3985, 3984, 3986, -1, 3987, 3986, 3988, -1, + 3986, 3987, 3989, -1, 3989, 3985, 3986, -1, + 3985, 3989, 3990, -1, 3990, 3983, 3985, -1, + 3983, 3990, 3991, -1, 3991, 3981, 3983, -1, + 3981, 3991, 3992, -1, 3992, 3978, 3981, -1, + 3978, 3992, 3993, -1, 3993, 3979, 3978, -1, + 3979, 3993, 3994, -1, 3994, 3995, 3979, -1, + 3995, 3994, 3996, -1, 3996, 3997, 3995, -1, + 3997, 3996, 3998, -1, 3998, 3999, 3997, -1, + 3999, 3998, 4000, -1, 4000, 4001, 3999, -1, + 4001, 4000, 4002, -1, 4002, 4003, 4001, -1, + 4003, 4002, 4004, -1, 4004, 4005, 4003, -1, + 4005, 4004, 4006, -1, 4006, 4007, 4005, -1, + 4007, 4006, 4008, -1, 4008, 4009, 4007, -1, + 4009, 4008, 4010, -1, 4010, 4011, 4009, -1, + 4011, 4010, 4012, -1, 4012, 4013, 4011, -1, + 4012, 4014, 4013, -1, 4014, 4012, 4015, -1, + 4015, 4016, 4014, -1, 4016, 4015, 4017, -1, + 4017, 4018, 4016, -1, 4018, 4017, 4019, -1, + 4019, 4020, 4018, -1, 4020, 4019, 4021, -1, + 4021, 4022, 4020, -1, 4022, 4021, 4023, -1, + 4023, 4024, 4022, -1, 4024, 4023, 4025, -1, + 4025, 4026, 4024, -1, 4026, 4025, 4027, -1, + 4027, 4028, 4026, -1, 4028, 4027, 4029, -1, + 4029, 4030, 4028, -1, 4030, 4029, 4031, -1, + 4031, 4032, 4030, -1, 4032, 4031, 4033, -1, + 4033, 4034, 4032, -1, 4034, 4033, 4035, -1, + 4035, 4036, 4034, -1, 4036, 4035, 4037, -1, + 4037, 4038, 4036, -1, 4038, 4037, 3976, -1, + 3976, 3943, 4038, -1, 4038, 3943, 3942, -1, + 3942, 4036, 4038, -1, 4036, 3942, 3941, -1, + 3941, 4034, 4036, -1, 4034, 3941, 3940, -1, + 3940, 4032, 4034, -1, 4032, 3940, 3939, -1, + 3939, 4030, 4032, -1, 4030, 3939, 3938, -1, + 3938, 4028, 4030, -1, 4028, 3938, 3937, -1, + 3937, 4026, 4028, -1, 4026, 3937, 3936, -1, + 3936, 4024, 4026, -1, 4024, 3936, 3935, -1, + 3935, 4022, 4024, -1, 4022, 3935, 3934, -1, + 3934, 4020, 4022, -1, 4020, 3934, 3933, -1, + 3933, 4018, 4020, -1, 4018, 3933, 3932, -1, + 3932, 4016, 4018, -1, 4016, 3932, 3931, -1, + 3931, 4014, 4016, -1, 4014, 3931, 3930, -1, + 3930, 4013, 4014, -1, 4013, 3930, 3929, -1, + 4013, 3929, 3928, -1, 3928, 4011, 4013, -1, + 4011, 3928, 3927, -1, 3927, 4009, 4011, -1, + 4009, 3927, 3926, -1, 3926, 4007, 4009, -1, + 4007, 3926, 3925, -1, 3925, 4005, 4007, -1, + 4005, 3925, 3924, -1, 3924, 4003, 4005, -1, + 4003, 3924, 3923, -1, 3923, 4001, 4003, -1, + 4001, 3923, 3922, -1, 3922, 3999, 4001, -1, + 3999, 3922, 3921, -1, 3921, 3997, 3999, -1, + 3997, 3921, 3920, -1, 3920, 3995, 3997, -1, + 3995, 3920, 3919, -1, 3919, 3979, 3995, -1, + 3979, 3919, 3918, -1, 3918, 3977, 3979, -1, + 3977, 3918, 3917, -1, 3917, 3980, 3977, -1, + 3980, 3917, 3916, -1, 3916, 3982, 3980, -1, + 3982, 3916, 3915, -1, 3915, 3984, 3982, -1, + 3984, 3915, 3733, -1, 3733, 3986, 3984, -1, + 3986, 3733, 3731, -1, 3731, 3988, 3986, -1, + 3988, 3731, 3729, -1, 3729, 4039, 3988, -1, + 4039, 3729, 3711, -1, 3711, 3710, 4039, -1, + 4040, 4039, 3710, -1, 3710, 4041, 4040, -1, + 4041, 3710, 3713, -1, 3713, 4042, 4041, -1, + 4042, 3713, 3715, -1, 3715, 4043, 4042, -1, + 4043, 3715, 3717, -1, 3717, 4044, 4043, -1, + 4044, 3717, 3719, -1, 3719, 4045, 4044, -1, + 4045, 3719, 3722, -1, 3722, 4046, 4045, -1, + 4046, 3722, 3721, -1, 3721, 4047, 4046, -1, + 4047, 3721, 4048, -1, 4049, 4050, 4051, -1, + 4049, 4052, 4050, -1, 4053, 4054, 4055, -1, + 4053, 4056, 4054, -1, 4057, 4058, 4059, -1, + 4059, 4060, 4057, -1, 4060, 4059, 4061, -1, + 4061, 4062, 4060, -1, 4062, 4061, 4063, -1, + 4063, 4064, 4062, -1, 4064, 4063, 4056, -1, + 4056, 4053, 4064, -1, 4065, 4053, 4066, -1, + 4065, 4064, 4053, -1, 4064, 4065, 4050, -1, + 4050, 4062, 4064, -1, 4062, 4050, 4052, -1, + 4052, 4060, 4062, -1, 4060, 4052, 4067, -1, + 4067, 4057, 4060, -1, 4057, 4067, 4068, -1, + 4068, 4069, 4057, -1, 4070, 4071, 2635, -1, + 2635, 4072, 4070, -1, 4073, 4074, 4072, -1, + 4074, 4070, 4072, -1, 4074, 4068, 4070, -1, + 4074, 4073, 4068, -1, 4073, 4069, 4068, -1, + 4069, 4073, 4072, -1, 4069, 4072, 4075, -1, + 4075, 4057, 4069, -1, 4075, 4058, 4057, -1, + 4058, 4075, 4072, -1, 4072, 4076, 4058, -1, + 4077, 4078, 4079, -1, 4080, 4081, 4082, -1, + 4080, 4082, 4078, -1, 4082, 4079, 4078, -1, + 4082, 4083, 4079, -1, 4084, 4085, 4086, -1, + 4086, 4087, 4084, -1, 4087, 4086, 4088, -1, + 4088, 4089, 4087, -1, 4090, 4091, 4092, -1, + 4091, 4090, 4089, -1, 4089, 4088, 4091, -1, + 4088, 4093, 4091, -1, 4093, 4088, 4086, -1, + 4086, 4094, 4093, -1, 4094, 4086, 4085, -1, + 4085, 4095, 4094, -1, 4095, 4085, 4096, -1, + 4096, 4097, 4095, -1, 4097, 4096, 4098, -1, + 4098, 4099, 4097, -1, 4099, 4098, 4100, -1, + 4100, 4101, 4099, -1, 4101, 4100, 4083, -1, + 4083, 4082, 4101, -1, 4102, 4101, 4082, -1, + 4082, 4081, 4102, -1, 4103, 4102, 4081, -1, + 4081, 4104, 4103, -1, 4081, 4080, 4104, -1, + 4080, 4078, 4104, -1, 4078, 4077, 4104, -1, + 4076, 4104, 4077, -1, 4077, 4105, 4076, -1, + 4077, 4079, 4105, -1, 4105, 4079, 4106, -1, + 4106, 4076, 4105, -1, 4106, 4107, 4076, -1, + 4107, 4108, 4076, -1, 4108, 4058, 4076, -1, + 4108, 4059, 4058, -1, 4108, 4107, 4059, -1, + 4107, 4106, 4059, -1, 4059, 4106, 4079, -1, + 4079, 4061, 4059, -1, 4061, 4079, 4083, -1, + 4083, 4063, 4061, -1, 4063, 4083, 4100, -1, + 4100, 4056, 4063, -1, 4056, 4100, 4098, -1, + 4098, 4054, 4056, -1, 4054, 4098, 4096, -1, + 4096, 4109, 4054, -1, 4109, 4096, 4085, -1, + 4085, 4084, 4109, -1, 4110, 4109, 4084, -1, + 4109, 4110, 4111, -1, 4111, 4054, 4109, -1, + 4111, 4055, 4054, -1, 4111, 4112, 4055, -1, + 4112, 4111, 4110, -1, 4110, 4113, 4112, -1, + 4113, 4110, 4084, -1, 4084, 4114, 4113, -1, + 4114, 4084, 4087, -1, 4087, 4115, 4114, -1, + 4115, 4087, 4089, -1, 4089, 4116, 4115, -1, + 4116, 4089, 4090, -1, 4090, 4117, 4116, -1, + 4117, 4090, 4092, -1, 4092, 4118, 4117, -1, + 4118, 4092, 4119, -1, 4119, 4120, 4118, -1, + 4120, 4119, 4121, -1, 4121, 4122, 4120, -1, + 4122, 4121, 4123, -1, 4123, 4124, 4122, -1, + 4124, 4123, 4125, -1, 4125, 4126, 4124, -1, + 4126, 4125, 4127, -1, 4127, 4128, 4126, -1, + 4128, 4127, 4129, -1, 4129, 4130, 4128, -1, + 4130, 4129, 4131, -1, 4131, 4132, 4130, -1, + 4132, 4131, 4133, -1, 4133, 4134, 4132, -1, + 4134, 4133, 4135, -1, 4135, 4136, 4134, -1, + 4136, 4135, 4137, -1, 4137, 4138, 4136, -1, + 4138, 4137, 4139, -1, 4139, 4140, 4138, -1, + 4140, 4139, 4141, -1, 4141, 4142, 4140, -1, + 4142, 4141, 4048, -1, 4048, 4143, 4142, -1, + 4143, 4048, 3721, -1, 3721, 3720, 4143, -1, + 3720, 4144, 4143, -1, 4144, 3720, 3723, -1, + 3723, 4145, 4144, -1, 4145, 3723, 3724, -1, + 3724, 4146, 4145, -1, 4146, 3724, 3725, -1, + 3725, 4147, 4146, -1, 4147, 3725, 3726, -1, + 3726, 4148, 4147, -1, 4148, 3726, 3727, -1, + 3727, 4149, 4148, -1, 4149, 3727, 3728, -1, + 3728, 4150, 4149, -1, 4150, 3728, 3730, -1, + 3730, 4151, 4150, -1, 4151, 3730, 3732, -1, + 3732, 4152, 4151, -1, 4152, 3732, 3734, -1, + 3734, 4153, 4152, -1, 4153, 3734, 3914, -1, + 3914, 4154, 4153, -1, 4154, 3914, 3913, -1, + 3913, 4155, 4154, -1, 4155, 3913, 3912, -1, + 3912, 4156, 4155, -1, 4156, 3912, 3911, -1, + 3911, 4157, 4156, -1, 4157, 3911, 3910, -1, + 3910, 4158, 4157, -1, 4158, 3910, 3909, -1, + 3909, 4159, 4158, -1, 4159, 3909, 3908, -1, + 3908, 4160, 4159, -1, 4160, 3908, 3907, -1, + 3907, 4161, 4160, -1, 4161, 3907, 3906, -1, + 3906, 4162, 4161, -1, 4162, 3906, 3905, -1, + 3905, 4163, 4162, -1, 4163, 3905, 3904, -1, + 3904, 4164, 4163, -1, 4164, 3904, 3903, -1, + 3903, 4165, 4164, -1, 4165, 3903, 3902, -1, + 3902, 4166, 4165, -1, 4166, 3902, 3901, -1, + 3901, 4167, 4166, -1, 4167, 3901, 3900, -1, + 3900, 4168, 4167, -1, 3900, 4169, 4168, -1, + 4169, 3900, 3899, -1, 3899, 4170, 4169, -1, + 4170, 3899, 3898, -1, 3898, 4171, 4170, -1, + 4171, 3898, 3897, -1, 3897, 4172, 4171, -1, + 4172, 3897, 3896, -1, 3896, 4173, 4172, -1, + 4173, 3896, 3895, -1, 3895, 4174, 4173, -1, + 4174, 3895, 3894, -1, 3894, 4175, 4174, -1, + 4175, 3894, 3893, -1, 3893, 4176, 4175, -1, + 4176, 3893, 3892, -1, 3892, 4177, 4176, -1, + 4177, 3892, 3891, -1, 3891, 4178, 4177, -1, + 4178, 3891, 3890, -1, 3890, 4179, 4178, -1, + 4179, 3890, 3889, -1, 3889, 4180, 4179, -1, + 4180, 3889, 3888, -1, 3888, 4181, 4180, -1, + 4181, 3888, 3887, -1, 3887, 4182, 4181, -1, + 4182, 3887, 3886, -1, 3886, 4183, 4182, -1, + 4183, 3886, 3885, -1, 3885, 4184, 4183, -1, + 4184, 3885, 3884, -1, 3884, 4185, 4184, -1, + 4185, 3884, 3883, -1, 3883, 4186, 4185, -1, + 4186, 3883, 3882, -1, 3882, 4187, 4186, -1, + 4187, 3882, 3881, -1, 3881, 4188, 4187, -1, + 4188, 3881, 3880, -1, 3880, 4189, 4188, -1, + 4189, 3880, 3879, -1, 3879, 4190, 4189, -1, + 4190, 3879, 3878, -1, 3878, 4191, 4190, -1, + 4191, 3878, 3877, -1, 3877, 4192, 4191, -1, + 4192, 3877, 3801, -1, 3801, 4193, 4192, -1, + 4193, 3801, 3799, -1, 3799, 4194, 4193, -1, + 4194, 3799, 3797, -1, 3797, 4195, 4194, -1, + 4195, 3797, 3795, -1, 3795, 4196, 4195, -1, + 4196, 3795, 3793, -1, 3793, 4197, 4196, -1, + 4197, 3793, 3791, -1, 3791, 4198, 4197, -1, + 4198, 3791, 3789, -1, 3789, 4199, 4198, -1, + 4199, 3789, 3787, -1, 3787, 4200, 4199, -1, + 4200, 3787, 3785, -1, 3785, 4201, 4200, -1, + 4201, 3785, 3783, -1, 3783, 4202, 4201, -1, + 4202, 3783, 3781, -1, 3781, 4203, 4202, -1, + 4203, 3781, 3779, -1, 3779, 4204, 4203, -1, + 4204, 3779, 3777, -1, 3777, 4205, 4204, -1, + 4205, 3777, 3775, -1, 3775, 4206, 4205, -1, + 4206, 3775, 3774, -1, 3774, 4207, 4206, -1, + 4207, 3774, 3773, -1, 3773, 4208, 4207, -1, + 4208, 3773, 3772, -1, 3772, 4209, 4208, -1, + 4209, 3772, 3771, -1, 3771, 4210, 4209, -1, + 4210, 3771, 3740, -1, 3740, 3739, 4210, -1, + 3739, 4211, 4210, -1, 4211, 3739, 3742, -1, + 3742, 4212, 4211, -1, 3742, 3743, 4212, -1, + 4213, 4212, 3743, -1, 4213, 3743, 3746, -1, + 3746, 3747, 4213, -1, 4214, 4215, 4213, -1, + 4214, 4213, 3747, -1, 3747, 4216, 4214, -1, + 4216, 3747, 3748, -1, 3748, 4217, 4216, -1, + 4217, 3748, 3749, -1, 3749, 4218, 4217, -1, + 4218, 3749, 3709, -1, 3709, 4219, 4218, -1, + 4219, 3709, 3708, -1, 4220, 4221, 4222, -1, + 4223, 4224, 4220, -1, 4225, 4226, 4227, -1, + 4228, 4229, 4225, -1, 4227, 4230, 4223, -1, + 4231, 4223, 4230, -1, 4231, 4230, 4219, -1, + 4231, 4219, 3708, -1, 3708, 4223, 4231, -1, + 3708, 3707, 4223, -1, 3707, 4224, 4223, -1, + 4224, 3707, 3709, -1, 4224, 3709, 3751, -1, + 3751, 4220, 4224, -1, 3751, 4232, 4220, -1, + 4232, 3751, 3750, -1, 4232, 3750, 3753, -1, + 3753, 4220, 4232, -1, 3753, 3752, 4220, -1, + 3752, 4221, 4220, -1, 4221, 3752, 3754, -1, + 4221, 3754, 3756, -1, 3756, 4222, 4221, -1, + 3756, 3755, 4222, -1, 4233, 4234, 3694, -1, + 4234, 4233, 4222, -1, 4234, 4222, 3755, -1, + 3755, 3757, 4234, -1, 3757, 3694, 4234, -1, + 3694, 3757, 3758, -1, 3758, 3706, 3694, -1, + 3706, 3758, 3759, -1, 3759, 3704, 3706, -1, + 3704, 3759, 3760, -1, 3760, 3702, 3704, -1, + 3702, 3760, 3761, -1, 3761, 3700, 3702, -1, + 3700, 3761, 3768, -1, 3768, 3698, 3700, -1, + 3698, 3768, 3766, -1, 3766, 3695, 3698, -1, + 3695, 3766, 3764, -1, 3764, 3696, 3695, -1, + 3696, 3764, 3763, -1, 3763, 4235, 3696, -1, + 4235, 3763, 3776, -1, 3776, 4236, 4235, -1, + 4236, 3776, 3778, -1, 3778, 4237, 4236, -1, + 4237, 3778, 3780, -1, 3780, 4238, 4237, -1, + 4238, 3780, 3782, -1, 3782, 4239, 4238, -1, + 4239, 3782, 3784, -1, 3784, 4240, 4239, -1, + 4240, 3784, 3786, -1, 3786, 4241, 4240, -1, + 4241, 3786, 3788, -1, 3788, 4242, 4241, -1, + 4242, 3788, 3790, -1, 3790, 4243, 4242, -1, + 4243, 3790, 3792, -1, 3792, 4244, 4243, -1, + 4244, 3792, 3794, -1, 3794, 4245, 4244, -1, + 4245, 3794, 3796, -1, 3796, 4246, 4245, -1, + 4246, 3796, 3798, -1, 3798, 4247, 4246, -1, + 4247, 3798, 3800, -1, 3800, 3953, 4247, -1, + 4248, 4247, 3953, -1, 3953, 4249, 4248, -1, + 4249, 3953, 3954, -1, 3954, 4250, 4249, -1, + 4250, 3954, 3955, -1, 3955, 4251, 4250, -1, + 4251, 3955, 3956, -1, 3956, 4252, 4251, -1, + 4252, 3956, 3957, -1, 3957, 4253, 4252, -1, + 4253, 3957, 3974, -1, 3974, 4254, 4253, -1, + 4254, 3974, 3972, -1, 3972, 4255, 4254, -1, + 4255, 3972, 3970, -1, 3970, 4256, 4255, -1, + 4256, 3970, 3968, -1, 3968, 4257, 4256, -1, + 4258, 4259, 4260, -1, 4260, 4261, 4258, -1, + 4261, 4260, 4262, -1, 4262, 4263, 4261, -1, + 4263, 4262, 4264, -1, 4264, 4265, 4263, -1, + 4265, 4264, 4266, -1, 4266, 4267, 4265, -1, + 4267, 4266, 4257, -1, 4257, 3968, 4267, -1, + 4267, 3968, 3965, -1, 3965, 4265, 4267, -1, + 4265, 3965, 3964, -1, 3964, 4263, 4265, -1, + 4263, 3964, 3962, -1, 3962, 4261, 4263, -1, + 4261, 3962, 3960, -1, 3960, 4258, 4261, -1, + 4258, 3960, 3959, -1, 3959, 4259, 4258, -1, + 4259, 3959, 4268, -1, 4268, 4269, 4259, -1, + 4269, 4268, 4270, -1, 4270, 4271, 4269, -1, + 4271, 4270, 4272, -1, 4272, 4273, 4271, -1, + 4273, 4272, 4274, -1, 4274, 4275, 4273, -1, + 4275, 4274, 4276, -1, 4276, 4277, 4275, -1, + 4277, 4276, 4278, -1, 4278, 4279, 4277, -1, + 4279, 4278, 4280, -1, 4280, 4281, 4279, -1, + 4281, 4280, 4282, -1, 4282, 4283, 4281, -1, + 4283, 4282, 4284, -1, 4284, 4285, 4283, -1, + 4285, 4284, 4286, -1, 4285, 4286, 4287, -1, + 4287, 4288, 4285, -1, 4288, 4287, 4289, -1, + 4289, 4290, 4288, -1, 4290, 4289, 4291, -1, + 4291, 4292, 4290, -1, 4292, 4291, 4293, -1, + 4293, 4294, 4292, -1, 4294, 4293, 4295, -1, + 4295, 4296, 4294, -1, 4296, 4295, 4297, -1, + 4297, 4298, 4296, -1, 4298, 4297, 4299, -1, + 4299, 4300, 4298, -1, 4300, 4299, 4301, -1, + 4301, 4302, 4300, -1, 4301, 4303, 4302, -1, + 4304, 4305, 4306, -1, 4305, 4304, 4307, -1, + 4307, 4308, 4305, -1, 4308, 4307, 4309, -1, + 4309, 4310, 4308, -1, 4310, 4309, 4311, -1, + 4311, 4312, 4310, -1, 4312, 4311, 4313, -1, + 4313, 4314, 4312, -1, 4314, 4313, 4315, -1, + 4315, 4316, 4314, -1, 4316, 4315, 4303, -1, + 4303, 4317, 4316, -1, 4317, 4303, 4301, -1, + 4301, 4318, 4317, -1, 4318, 4301, 4299, -1, + 4299, 4319, 4318, -1, 4319, 4299, 4297, -1, + 4297, 4320, 4319, -1, 4320, 4297, 4295, -1, + 4295, 4321, 4320, -1, 4321, 4295, 4293, -1, + 4293, 4322, 4321, -1, 4322, 4293, 4291, -1, + 4291, 4323, 4322, -1, 4323, 4291, 4289, -1, + 4289, 4324, 4323, -1, 4324, 4289, 4287, -1, + 4287, 4325, 4324, -1, 4325, 4287, 4286, -1, + 4286, 4326, 4325, -1, 4286, 4327, 4326, -1, + 4327, 4286, 4284, -1, 4284, 4328, 4327, -1, + 4328, 4284, 4282, -1, 4282, 4329, 4328, -1, + 4329, 4282, 4280, -1, 4280, 4330, 4329, -1, + 4330, 4280, 4278, -1, 4278, 4331, 4330, -1, + 4331, 4278, 4276, -1, 4276, 4332, 4331, -1, + 4332, 4276, 4274, -1, 4274, 4333, 4332, -1, + 4333, 4274, 4272, -1, 4272, 4334, 4333, -1, + 4334, 4272, 4270, -1, 4270, 4335, 4334, -1, + 4335, 4270, 4268, -1, 4268, 4336, 4335, -1, + 4336, 4268, 3959, -1, 3959, 3958, 4336, -1, + 4337, 4336, 3958, -1, 3958, 4338, 4337, -1, + 4338, 3958, 3961, -1, 3961, 4339, 4338, -1, + 4339, 3961, 3963, -1, 3963, 3966, 4339, -1, + 4339, 3966, 3976, -1, 3976, 4338, 4339, -1, + 4338, 3976, 4037, -1, 4037, 4337, 4338, -1, + 4337, 4037, 4035, -1, 4035, 4336, 4337, -1, + 4336, 4035, 4033, -1, 4033, 4335, 4336, -1, + 4335, 4033, 4031, -1, 4031, 4334, 4335, -1, + 4334, 4031, 4029, -1, 4029, 4333, 4334, -1, + 4333, 4029, 4027, -1, 4027, 4332, 4333, -1, + 4332, 4027, 4025, -1, 4025, 4331, 4332, -1, + 4331, 4025, 4023, -1, 4023, 4330, 4331, -1, + 4330, 4023, 4021, -1, 4021, 4329, 4330, -1, + 4329, 4021, 4019, -1, 4019, 4328, 4329, -1, + 4328, 4019, 4017, -1, 4017, 4327, 4328, -1, + 4327, 4017, 4015, -1, 4015, 4326, 4327, -1, + 4326, 4015, 4012, -1, 4326, 4012, 4010, -1, + 4010, 4325, 4326, -1, 4325, 4010, 4008, -1, + 4008, 4324, 4325, -1, 4324, 4008, 4006, -1, + 4006, 4323, 4324, -1, 4323, 4006, 4004, -1, + 4004, 4322, 4323, -1, 4322, 4004, 4002, -1, + 4002, 4321, 4322, -1, 4321, 4002, 4000, -1, + 4000, 4320, 4321, -1, 4320, 4000, 3998, -1, + 3998, 4319, 4320, -1, 4319, 3998, 3996, -1, + 3996, 4318, 4319, -1, 4318, 3996, 3994, -1, + 3994, 4317, 4318, -1, 4317, 3994, 3993, -1, + 3993, 4316, 4317, -1, 4316, 3993, 3992, -1, + 3992, 4314, 4316, -1, 4314, 3992, 3991, -1, + 3991, 4312, 4314, -1, 4312, 3991, 3990, -1, + 3990, 4310, 4312, -1, 4310, 3990, 3989, -1, + 3989, 4308, 4310, -1, 4308, 3989, 3987, -1, + 3987, 4305, 4308, -1, 4305, 3987, 3988, -1, + 3988, 4306, 4305, -1, 4306, 3988, 4039, -1, + 4039, 4040, 4306, -1, 4340, 4306, 4040, -1, + 4306, 4340, 4341, -1, 4341, 4304, 4306, -1, + 4304, 4341, 4342, -1, 4342, 4307, 4304, -1, + 4307, 4342, 4343, -1, 4343, 4309, 4307, -1, + 4309, 4343, 4344, -1, 4344, 4311, 4309, -1, + 4311, 4344, 4345, -1, 4345, 4313, 4311, -1, + 4313, 4345, 4346, -1, 4346, 4315, 4313, -1, + 4315, 4346, 4347, -1, 4347, 4303, 4315, -1, + 4347, 4302, 4303, -1, 4347, 4348, 4302, -1, + 4348, 4347, 4346, -1, 4346, 4349, 4348, -1, + 4349, 4346, 4345, -1, 4345, 4350, 4349, -1, + 4350, 4345, 4344, -1, 4344, 4351, 4350, -1, + 4351, 4344, 4343, -1, 4343, 4352, 4351, -1, + 4352, 4343, 4342, -1, 4342, 4353, 4352, -1, + 4353, 4342, 4341, -1, 4341, 4354, 4353, -1, + 4354, 4341, 4340, -1, 4340, 4355, 4354, -1, + 4355, 4340, 4040, -1, 4040, 4356, 4355, -1, + 4356, 4040, 4041, -1, 4041, 4357, 4356, -1, + 4357, 4041, 4042, -1, 4042, 4358, 4357, -1, + 4358, 4042, 4043, -1, 4043, 4359, 4358, -1, + 4359, 4043, 4044, -1, 4044, 4360, 4359, -1, + 4360, 4044, 4045, -1, 4045, 4361, 4360, -1, + 4361, 4045, 4046, -1, 4046, 4362, 4361, -1, + 4362, 4046, 4047, -1, 4047, 4363, 4362, -1, + 4363, 4047, 4048, -1, 4048, 4364, 4363, -1, + 4364, 4048, 4141, -1, 4141, 4365, 4364, -1, + 4365, 4141, 4139, -1, 4139, 4366, 4365, -1, + 4366, 4139, 4137, -1, 4137, 4367, 4366, -1, + 4367, 4137, 4135, -1, 4135, 4368, 4367, -1, + 4368, 4135, 4133, -1, 4133, 4369, 4368, -1, + 4369, 4133, 4131, -1, 4131, 4370, 4369, -1, + 4370, 4131, 4129, -1, 4129, 4371, 4370, -1, + 4371, 4129, 4127, -1, 4127, 4372, 4371, -1, + 4372, 4127, 4125, -1, 4125, 4373, 4372, -1, + 4373, 4125, 4123, -1, 4123, 4374, 4373, -1, + 4374, 4123, 4121, -1, 4121, 4375, 4374, -1, + 4375, 4121, 4119, -1, 4119, 4376, 4375, -1, + 4376, 4119, 4092, -1, 4092, 4377, 4376, -1, + 4377, 4092, 4091, -1, 4091, 4378, 4377, -1, + 4378, 4091, 4093, -1, 4093, 4379, 4378, -1, + 4379, 4093, 4094, -1, 4094, 4380, 4379, -1, + 4380, 4094, 4095, -1, 4095, 4381, 4380, -1, + 4381, 4095, 4097, -1, 4097, 4382, 4381, -1, + 4382, 4097, 4099, -1, 4099, 4383, 4382, -1, + 4383, 4099, 4101, -1, 4101, 4102, 4383, -1, + 3690, 4102, 4384, -1, 3690, 4383, 4102, -1, + 4383, 3690, 3689, -1, 3689, 4382, 4383, -1, + 4382, 3689, 3688, -1, 3688, 4381, 4382, -1, + 4381, 3688, 3687, -1, 3687, 4380, 4381, -1, + 4380, 3687, 3686, -1, 3686, 4379, 4380, -1, + 4379, 3686, 3121, -1, 3121, 4378, 4379, -1, + 4378, 3121, 3124, -1, 3124, 4377, 4378, -1, + 4377, 3124, 3126, -1, 3126, 4376, 4377, -1, + 4376, 3126, 3128, -1, 3128, 4375, 4376, -1, + 4375, 3128, 3130, -1, 3130, 4374, 4375, -1, + 4374, 3130, 3132, -1, 3132, 4373, 4374, -1, + 4373, 3132, 3134, -1, 3134, 4372, 4373, -1, + 4372, 3134, 3136, -1, 3136, 4371, 4372, -1, + 4371, 3136, 3138, -1, 3138, 4370, 4371, -1, + 4370, 3138, 3140, -1, 3140, 4369, 4370, -1, + 4369, 3140, 3142, -1, 3142, 4368, 4369, -1, + 4368, 3142, 3144, -1, 3144, 4367, 4368, -1, + 4367, 3144, 3146, -1, 3146, 4366, 4367, -1, + 4366, 3146, 3148, -1, 3148, 4365, 4366, -1, + 4365, 3148, 3150, -1, 3150, 4364, 4365, -1, + 4364, 3150, 3630, -1, 3630, 3629, 4364, -1, + 3629, 4363, 4364, -1, 4363, 3629, 3627, -1, + 3627, 4362, 4363, -1, 4362, 3627, 3625, -1, + 3625, 4361, 4362, -1, 4361, 3625, 3623, -1, + 3623, 4360, 4361, -1, 4360, 3623, 3621, -1, + 3621, 4359, 4360, -1, 4359, 3621, 3619, -1, + 3619, 4358, 4359, -1, 4358, 3619, 3617, -1, + 3617, 4357, 4358, -1, 4357, 3617, 3615, -1, + 3615, 4356, 4357, -1, 4356, 3615, 3613, -1, + 3613, 4355, 4356, -1, 4355, 3613, 3612, -1, + 3612, 4354, 4355, -1, 4354, 3612, 3611, -1, + 3611, 4353, 4354, -1, 4353, 3611, 3610, -1, + 3610, 4352, 4353, -1, 4352, 3610, 3609, -1, + 3609, 4351, 4352, -1, 4351, 3609, 3608, -1, + 3608, 4350, 4351, -1, 4350, 3608, 3607, -1, + 3607, 4349, 4350, -1, 4349, 3607, 3606, -1, + 3606, 4348, 4349, -1, 4348, 3606, 3152, -1, + 3152, 4302, 4348, -1, 4302, 3152, 3151, -1, + 3151, 4300, 4302, -1, 4300, 3151, 3155, -1, + 3155, 4298, 4300, -1, 4298, 3155, 3157, -1, + 3157, 4296, 4298, -1, 4296, 3157, 3159, -1, + 3159, 4294, 4296, -1, 4294, 3159, 3161, -1, + 3161, 4292, 4294, -1, 4292, 3161, 3163, -1, + 3163, 4290, 4292, -1, 4290, 3163, 3165, -1, + 3165, 4288, 4290, -1, 4288, 3165, 3167, -1, + 3167, 4285, 4288, -1, 3167, 4283, 4285, -1, + 4283, 3167, 3168, -1, 3168, 4281, 4283, -1, + 4281, 3168, 3170, -1, 3170, 4279, 4281, -1, + 4279, 3170, 3172, -1, 3172, 4277, 4279, -1, + 4277, 3172, 3174, -1, 3174, 4275, 4277, -1, + 4275, 3174, 3176, -1, 3176, 4273, 4275, -1, + 4273, 3176, 3178, -1, 3178, 4271, 4273, -1, + 4271, 3178, 3180, -1, 3180, 4269, 4271, -1, + 4269, 3180, 3182, -1, 3182, 4259, 4269, -1, + 4259, 3182, 3184, -1, 3184, 4260, 4259, -1, + 4260, 3184, 3590, -1, 3590, 4262, 4260, -1, + 4262, 3590, 3589, -1, 3589, 4264, 4262, -1, + 4264, 3589, 3588, -1, 3588, 4266, 4264, -1, + 4266, 3588, 3587, -1, 3587, 4257, 4266, -1, + 4257, 3587, 3185, -1, 3185, 4256, 4257, -1, + 4256, 3185, 3188, -1, 3188, 4255, 4256, -1, + 4255, 3188, 3190, -1, 3190, 4254, 4255, -1, + 4254, 3190, 3192, -1, 3192, 4253, 4254, -1, + 4253, 3192, 3194, -1, 3194, 4252, 4253, -1, + 4252, 3194, 3196, -1, 3196, 4251, 4252, -1, + 4251, 3196, 3198, -1, 3198, 4250, 4251, -1, + 4250, 3198, 3200, -1, 3200, 4249, 4250, -1, + 4249, 3200, 3202, -1, 3202, 4248, 4249, -1, + 4248, 3202, 3204, -1, 3204, 4247, 4248, -1, + 4247, 3204, 3206, -1, 3206, 4246, 4247, -1, + 4246, 3206, 3577, -1, 3577, 4245, 4246, -1, + 4245, 3577, 4385, -1, 4385, 4244, 4245, -1, + 4244, 4385, 4386, -1, 4386, 4243, 4244, -1, + 4243, 4386, 4387, -1, 4387, 4242, 4243, -1, + 4242, 4387, 4388, -1, 4388, 4241, 4242, -1, + 4241, 4388, 4389, -1, 4389, 4240, 4241, -1, + 4240, 4389, 4390, -1, 4390, 4239, 4240, -1, + 4239, 4390, 4391, -1, 4391, 4238, 4239, -1, + 4238, 4391, 4392, -1, 4392, 4237, 4238, -1, + 4237, 4392, 4393, -1, 4393, 4236, 4237, -1, + 4236, 4393, 4394, -1, 4394, 4235, 4236, -1, + 4235, 4394, 4395, -1, 4395, 3696, 4235, -1, + 3696, 4395, 4396, -1, 4396, 3697, 3696, -1, + 3697, 4396, 4397, -1, 4397, 3699, 3697, -1, + 3699, 4397, 4398, -1, 4398, 3701, 3699, -1, + 3701, 4398, 4399, -1, 4399, 3703, 3701, -1, + 3703, 4399, 4400, -1, 4400, 3705, 3703, -1, + 3705, 4400, 4401, -1, 4401, 3692, 3705, -1, + 4401, 4402, 3692, -1, 4403, 3692, 4402, -1, + 4403, 4402, 4404, -1, 4403, 4404, 4405, -1, + 4405, 3692, 4403, -1, 4405, 3693, 3692, -1, + 4405, 4404, 3693, -1, 3693, 4404, 4406, -1, + 4406, 4222, 4233, -1, 4222, 4406, 4404, -1, + 4404, 4407, 4408, -1, 4407, 4404, 4402, -1, + 4407, 4402, 4401, -1, 4407, 4401, 4409, -1, + 4409, 4408, 4407, -1, 4410, 4408, 4409, -1, + 4411, 4412, 4413, -1, 4411, 4413, 4408, -1, + 4411, 4408, 4410, -1, 4410, 4412, 4411, -1, + 4410, 4409, 4412, -1, 4412, 4409, 4401, -1, + 4412, 4401, 4400, -1, 4400, 4414, 4412, -1, + 4414, 4400, 4399, -1, 4399, 4415, 4414, -1, + 4415, 4399, 4398, -1, 4398, 4416, 4415, -1, + 4416, 4398, 4397, -1, 4397, 4417, 4416, -1, + 4417, 4397, 4396, -1, 4396, 4418, 4417, -1, + 4418, 4396, 4395, -1, 4395, 4419, 4418, -1, + 4419, 4395, 4394, -1, 4394, 4420, 4419, -1, + 4420, 4394, 4393, -1, 4393, 4421, 4420, -1, + 4421, 4393, 4392, -1, 4392, 4422, 4421, -1, + 4422, 4392, 4391, -1, 4391, 4423, 4422, -1, + 4423, 4391, 4390, -1, 4390, 4424, 4423, -1, + 4424, 4390, 4389, -1, 4389, 4425, 4424, -1, + 4425, 4389, 4388, -1, 4388, 4426, 4425, -1, + 4426, 4388, 4387, -1, 4387, 4427, 4426, -1, + 4427, 4387, 4386, -1, 4386, 4428, 4427, -1, + 4428, 4386, 4385, -1, 4385, 4429, 4428, -1, + 4429, 4385, 3577, -1, 3577, 3576, 4429, -1, + 4430, 4429, 3576, -1, 3576, 4431, 4430, -1, + 4431, 3576, 3574, -1, 3574, 4432, 4431, -1, + 4432, 3574, 3572, -1, 3572, 4433, 4432, -1, + 4433, 3572, 3570, -1, 3570, 4434, 4433, -1, + 4434, 3570, 3568, -1, 3568, 4435, 4434, -1, + 4435, 3568, 3566, -1, 3566, 4436, 4435, -1, + 4436, 3566, 3564, -1, 3564, 4437, 4436, -1, + 4437, 3564, 3562, -1, 3562, 4438, 4437, -1, + 4438, 3562, 3560, -1, 3560, 4439, 4438, -1, + 4439, 3560, 3558, -1, 3558, 4440, 4439, -1, + 4440, 3558, 3556, -1, 3556, 4441, 4440, -1, + 4441, 3556, 3554, -1, 3554, 4442, 4441, -1, + 4442, 3554, 3552, -1, 3552, 4443, 4442, -1, + 4443, 3552, 3550, -1, 3550, 4444, 4443, -1, + 4444, 3550, 3548, -1, 3548, 4445, 4444, -1, + 4445, 3548, 3546, -1, 3546, 4446, 4445, -1, + 4446, 3546, 3501, -1, 4446, 3501, 3240, -1, + 4446, 3240, 3243, -1, 3243, 4445, 4446, -1, + 4445, 3243, 3276, -1, 3276, 4444, 4445, -1, + 4444, 3276, 3274, -1, 3274, 4443, 4444, -1, + 4443, 3274, 3272, -1, 3272, 4442, 4443, -1, + 4442, 3272, 3270, -1, 3270, 4441, 4442, -1, + 4441, 3270, 3268, -1, 3268, 4440, 4441, -1, + 4440, 3268, 3266, -1, 3266, 4439, 4440, -1, + 4439, 3266, 3264, -1, 3264, 4438, 4439, -1, + 4438, 3264, 3262, -1, 3262, 4437, 4438, -1, + 4437, 3262, 3260, -1, 3260, 4436, 4437, -1, + 4436, 3260, 3258, -1, 3258, 4435, 4436, -1, + 4435, 3258, 3256, -1, 3256, 4434, 4435, -1, + 4434, 3256, 3254, -1, 3254, 4433, 4434, -1, + 4433, 3254, 3252, -1, 3252, 4432, 4433, -1, + 4432, 3252, 3250, -1, 3250, 4431, 4432, -1, + 4431, 3250, 3248, -1, 3248, 4430, 4431, -1, + 4430, 3248, 3246, -1, 3246, 4429, 4430, -1, + 4429, 3246, 3245, -1, 3245, 4428, 4429, -1, + 4428, 3245, 3321, -1, 3321, 4427, 4428, -1, + 4427, 3321, 3319, -1, 3319, 4426, 4427, -1, + 4426, 3319, 3317, -1, 3317, 4425, 4426, -1, + 4425, 3317, 3315, -1, 3315, 4424, 4425, -1, + 4424, 3315, 3313, -1, 3313, 4423, 4424, -1, + 4423, 3313, 3311, -1, 3311, 4422, 4423, -1, + 4422, 3311, 3309, -1, 3309, 4421, 4422, -1, + 4421, 3309, 3307, -1, 3307, 4420, 4421, -1, + 4420, 3307, 3305, -1, 3305, 4419, 4420, -1, + 4419, 3305, 3303, -1, 3303, 4418, 4419, -1, + 4418, 3303, 3301, -1, 3301, 4417, 4418, -1, + 4417, 3301, 3299, -1, 3299, 4416, 4417, -1, + 4416, 3299, 3297, -1, 3297, 4415, 4416, -1, + 4415, 3297, 3296, -1, 3296, 4414, 4415, -1, + 4414, 3296, 4447, -1, 4447, 4412, 4414, -1, + 4447, 4413, 4412, -1, 4448, 4413, 4447, -1, + 4448, 4408, 4413, -1, 4448, 4449, 4408, -1, + 4448, 4447, 4449, -1, 4450, 4449, 4447, -1, + 4450, 4447, 3296, -1, 3296, 3295, 4450, -1, + 4450, 4451, 4452, -1, 4451, 4450, 3295, -1, + 3295, 4453, 4451, -1, 4453, 3295, 3298, -1, + 3298, 4454, 4453, -1, 4454, 3298, 3300, -1, + 3300, 4455, 4454, -1, 4455, 3300, 3302, -1, + 3302, 4456, 4455, -1, 4456, 3302, 3304, -1, + 3304, 4457, 4456, -1, 4457, 3304, 3306, -1, + 3306, 4458, 4457, -1, 4458, 3306, 3308, -1, + 3308, 4459, 4458, -1, 4459, 3308, 3310, -1, + 3310, 4460, 4459, -1, 4460, 3310, 3312, -1, + 3312, 4461, 4460, -1, 4461, 3312, 3314, -1, + 3314, 4462, 4461, -1, 4462, 3314, 3316, -1, + 3316, 4463, 4462, -1, 4463, 3316, 3318, -1, + 3318, 4464, 4463, -1, 4464, 3318, 3320, -1, + 3320, 4465, 4464, -1, 4465, 3320, 3322, -1, + 3322, 4466, 4465, -1, 4466, 3322, 3323, -1, + 3323, 4467, 4466, -1, 4467, 3323, 3324, -1, + 3324, 4468, 4467, -1, 4468, 3324, 3325, -1, + 3325, 4469, 4468, -1, 4469, 3325, 3326, -1, + 3326, 4470, 4469, -1, 4470, 3326, 3327, -1, + 3327, 4471, 4470, -1, 4471, 3327, 3328, -1, + 3328, 4472, 4471, -1, 4472, 3328, 3329, -1, + 3329, 4473, 4472, -1, 4473, 3329, 3330, -1, + 3330, 4474, 4473, -1, 4474, 3330, 3331, -1, + 3331, 4475, 4474, -1, 4475, 3331, 3332, -1, + 3332, 4476, 4475, -1, 4476, 3332, 3333, -1, + 3333, 4477, 4476, -1, 4477, 3333, 3334, -1, + 3334, 4478, 4477, -1, 4478, 3334, 3335, -1, + 3335, 4479, 4478, -1, 4479, 3335, 3336, -1, + 3336, 4480, 4479, -1, 4480, 3336, 3337, -1, + 3337, 4481, 4480, -1, 4481, 3337, 3338, -1, + 3338, 4482, 4481, -1, 4482, 3338, 3339, -1, + 3339, 4483, 4482, -1, 4483, 3339, 3340, -1, + 3340, 4484, 4483, -1, 4484, 3340, 3341, -1, + 3341, 4485, 4484, -1, 4485, 3341, 3342, -1, + 3342, 4486, 4485, -1, 4486, 3342, 3344, -1, + 3344, 4487, 4486, -1, 4487, 3344, 3346, -1, + 3346, 4488, 4487, -1, 4488, 3346, 3348, -1, + 3348, 4489, 4488, -1, 4489, 3348, 3350, -1, + 3350, 4490, 4489, -1, 4490, 3350, 3352, -1, + 4490, 3352, 3355, -1, 3355, 4491, 4490, -1, + 4491, 3355, 3357, -1, 3357, 4492, 4491, -1, + 4492, 3357, 3359, -1, 3359, 4493, 4492, -1, + 4493, 3359, 3361, -1, 3361, 4494, 4493, -1, + 4494, 3361, 3363, -1, 3363, 4495, 4494, -1, + 4495, 3363, 3365, -1, 3365, 4496, 4495, -1, + 4496, 3365, 3401, -1, 3401, 4497, 4496, -1, + 4497, 3401, 3399, -1, 3399, 4498, 4497, -1, + 4498, 3399, 3397, -1, 3397, 4499, 4498, -1, + 4499, 3397, 3395, -1, 3395, 4500, 4499, -1, + 4500, 3395, 3393, -1, 3393, 4501, 4500, -1, + 4501, 3393, 3391, -1, 3391, 4502, 4501, -1, + 4502, 3391, 3389, -1, 3389, 4503, 4502, -1, + 4503, 3389, 3387, -1, 3387, 4504, 4503, -1, + 4504, 3387, 3385, -1, 3385, 4505, 4504, -1, + 4505, 3385, 3383, -1, 3383, 4506, 4505, -1, + 4506, 3383, 3381, -1, 3381, 4507, 4506, -1, + 4507, 3381, 3379, -1, 3379, 4508, 4507, -1, + 4508, 3379, 3377, -1, 3377, 4509, 4508, -1, + 4509, 3377, 3375, -1, 3375, 4510, 4509, -1, + 4510, 3375, 3373, -1, 3373, 4511, 4510, -1, + 4511, 3373, 3371, -1, 3371, 4512, 4511, -1, + 4512, 3371, 3369, -1, 3369, 4513, 4512, -1, + 4513, 3369, 3366, -1, 3366, 4514, 4513, -1, + 4514, 3366, 3368, -1, 3368, 4515, 4514, -1, + 4515, 3368, 3440, -1, 3440, 4516, 4515, -1, + 4516, 3440, 3442, -1, 3442, 4517, 4516, -1, + 4517, 3442, 3444, -1, 3444, 4518, 4517, -1, + 4518, 3444, 3446, -1, 3446, 4519, 4518, -1, + 4519, 3446, 3448, -1, 3448, 4520, 4519, -1, + 4520, 3448, 3450, -1, 3450, 4521, 4520, -1, + 4521, 3450, 3452, -1, 3452, 4522, 4521, -1, + 4522, 3452, 3454, -1, 3454, 4523, 4522, -1, + 4523, 3454, 3456, -1, 3456, 4524, 4523, -1, + 4524, 3456, 3458, -1, 3458, 4525, 4524, -1, + 4525, 3458, 3460, -1, 3460, 4526, 4525, -1, + 4526, 3460, 3462, -1, 3462, 4527, 4526, -1, + 4527, 3462, 3238, -1, 3238, 3237, 4527, -1, + 3116, 4528, 4529, -1, 4530, 4529, 4528, -1, + 4530, 4531, 4529, -1, 4532, 4531, 4530, -1, + 4530, 4528, 4532, -1, 4532, 4528, 4533, -1, + 4533, 4531, 4532, -1, 4533, 4534, 4531, -1, + 4534, 4533, 3237, -1, 3237, 4533, 4528, -1, + 4528, 4527, 3237, -1, 4527, 4528, 3116, -1, + 3116, 4526, 4527, -1, 4526, 3116, 3115, -1, + 3115, 4525, 4526, -1, 4525, 3115, 3114, -1, + 3114, 4524, 4525, -1, 4524, 3114, 3113, -1, + 3113, 4523, 4524, -1, 4523, 3113, 3112, -1, + 3112, 4522, 4523, -1, 4522, 3112, 3111, -1, + 3111, 4521, 4522, -1, 4521, 3111, 3110, -1, + 3110, 4520, 4521, -1, 4520, 3110, 3109, -1, + 3109, 4519, 4520, -1, 4519, 3109, 3108, -1, + 3108, 4518, 4519, -1, 4518, 3108, 3107, -1, + 3107, 4517, 4518, -1, 4517, 3107, 3106, -1, + 3106, 4516, 4517, -1, 4516, 3106, 3105, -1, + 3105, 4515, 4516, -1, 4515, 3105, 3061, -1, + 3061, 3060, 4515, -1, 3060, 4514, 4515, -1, + 4514, 3060, 3058, -1, 3058, 4513, 4514, -1, + 4513, 3058, 3056, -1, 3056, 4512, 4513, -1, + 4512, 3056, 3054, -1, 3054, 4511, 4512, -1, + 4511, 3054, 3052, -1, 3052, 4510, 4511, -1, + 4510, 3052, 3050, -1, 3050, 4509, 4510, -1, + 4509, 3050, 3048, -1, 3048, 4508, 4509, -1, + 4508, 3048, 3046, -1, 3046, 4507, 4508, -1, + 4507, 3046, 3044, -1, 3044, 4506, 4507, -1, + 4506, 3044, 3042, -1, 3042, 4505, 4506, -1, + 4505, 3042, 3040, -1, 3040, 4504, 4505, -1, + 4504, 3040, 3038, -1, 3038, 4503, 4504, -1, + 4503, 3038, 3036, -1, 3036, 4502, 4503, -1, + 4502, 3036, 3034, -1, 3034, 4501, 4502, -1, + 4501, 3034, 3032, -1, 3032, 4500, 4501, -1, + 4500, 3032, 3030, -1, 3030, 4499, 4500, -1, + 4499, 3030, 3028, -1, 3028, 4498, 4499, -1, + 4498, 3028, 3026, -1, 3026, 4497, 4498, -1, + 4497, 3026, 3024, -1, 3024, 4496, 4497, -1, + 4496, 3024, 3022, -1, 3022, 4495, 4496, -1, + 4495, 3022, 3020, -1, 3020, 4494, 4495, -1, + 4494, 3020, 3018, -1, 3018, 4493, 4494, -1, + 4493, 3018, 3016, -1, 3016, 4492, 4493, -1, + 4492, 3016, 3014, -1, 3014, 4491, 4492, -1, + 4491, 3014, 3013, -1, 3013, 4490, 4491, -1, + 3013, 4489, 4490, -1, 4489, 3013, 3011, -1, + 3011, 4488, 4489, -1, 4488, 3011, 3009, -1, + 3009, 4487, 4488, -1, 4487, 3009, 3007, -1, + 3007, 4486, 4487, -1, 4486, 3007, 3005, -1, + 3005, 4485, 4486, -1, 4485, 3005, 3003, -1, + 3003, 4484, 4485, -1, 4484, 3003, 3001, -1, + 3001, 4483, 4484, -1, 4483, 3001, 2999, -1, + 2999, 4482, 4483, -1, 4482, 2999, 2997, -1, + 2997, 4481, 4482, -1, 4481, 2997, 2995, -1, + 2995, 4480, 4481, -1, 4480, 2995, 2993, -1, + 2993, 4479, 4480, -1, 4479, 2993, 2991, -1, + 2991, 4478, 4479, -1, 4478, 2991, 2989, -1, + 2989, 4477, 4478, -1, 4477, 2989, 2987, -1, + 2987, 4476, 4477, -1, 4476, 2987, 2985, -1, + 2985, 4475, 4476, -1, 4475, 2985, 2983, -1, + 2983, 4474, 4475, -1, 4474, 2983, 2981, -1, + 2981, 4473, 4474, -1, 4473, 2981, 2979, -1, + 2979, 4472, 4473, -1, 4472, 2979, 2977, -1, + 2977, 4471, 4472, -1, 4471, 2977, 2975, -1, + 2975, 4470, 4471, -1, 4470, 2975, 2973, -1, + 2973, 4469, 4470, -1, 4469, 2973, 2971, -1, + 2971, 4468, 4469, -1, 4468, 2971, 2969, -1, + 2969, 4467, 4468, -1, 4467, 2969, 2967, -1, + 2967, 4466, 4467, -1, 4466, 2967, 2966, -1, + 2966, 4465, 4466, -1, 4465, 2966, 4535, -1, + 4535, 4464, 4465, -1, 4464, 4535, 4536, -1, + 4536, 4463, 4464, -1, 4463, 4536, 4537, -1, + 4537, 4462, 4463, -1, 4462, 4537, 4538, -1, + 4538, 4461, 4462, -1, 4461, 4538, 4539, -1, + 4539, 4460, 4461, -1, 4460, 4539, 4540, -1, + 4540, 4459, 4460, -1, 4459, 4540, 4541, -1, + 4541, 4458, 4459, -1, 4458, 4541, 4542, -1, + 4542, 4457, 4458, -1, 4457, 4542, 4543, -1, + 4543, 4456, 4457, -1, 4456, 4543, 2964, -1, + 2964, 4455, 4456, -1, 4455, 2964, 2963, -1, + 2963, 4454, 4455, -1, 4454, 2963, 2961, -1, + 2961, 4453, 4454, -1, 4453, 2961, 2960, -1, + 2960, 4451, 4453, -1, 2960, 4544, 4451, -1, + 4545, 4546, 4547, -1, 4546, 4544, 4547, -1, + 4546, 4451, 4544, -1, 4546, 4545, 4451, -1, + 4545, 4452, 4451, -1, 4452, 4545, 4547, -1, + 4452, 4547, 4548, -1, 4548, 4450, 4452, -1, + 4548, 4449, 4450, -1, 4548, 4547, 4449, -1, + 4547, 4408, 4449, -1, 4549, 4547, 4544, -1, + 4550, 4549, 4544, -1, 4550, 4544, 2960, -1, + 4550, 2960, 2959, -1, 2959, 4549, 4550, -1, + 2959, 4551, 4549, -1, 4551, 2959, 2958, -1, + 4552, 2958, 4553, -1, 4552, 4551, 2958, -1, + 4552, 4549, 4551, -1, 4552, 4553, 4549, -1, + 4554, 2957, 4553, -1, 2957, 4549, 4553, -1, + 4555, 4556, 4557, -1, 4555, 4558, 4556, -1, + 4556, 4559, 4560, -1, 4556, 4561, 4559, -1, + 4561, 4556, 4558, -1, 4558, 4562, 4561, -1, + 4562, 4558, 4563, -1, 4563, 4564, 4562, -1, + 4564, 4563, 4565, -1, 4565, 4566, 4564, -1, + 4566, 4565, 4567, -1, 4567, 4568, 4566, -1, + 4568, 4567, 4569, -1, 4569, 4570, 4568, -1, + 4570, 4569, 4571, -1, 4571, 4572, 4570, -1, + 4572, 4571, 4573, -1, 4573, 4574, 4572, -1, + 4574, 4573, 4575, -1, 4575, 4576, 4574, -1, + 4576, 4575, 4577, -1, 4577, 4578, 4576, -1, + 4578, 4577, 4579, -1, 4579, 4580, 4578, -1, + 4581, 4582, 4583, -1, 4581, 4583, 4580, -1, + 4580, 4579, 4581, -1, 4584, 4585, 4586, -1, + 4586, 4587, 4584, -1, 4587, 4586, 4588, -1, + 4588, 4589, 4587, -1, 4589, 4588, 4590, -1, + 4590, 4591, 4589, -1, 4590, 4592, 4591, -1, + 4593, 4594, 4595, -1, 4592, 4594, 4593, -1, + 4593, 4591, 4592, -1, 4593, 4595, 4591, -1, + 4591, 4595, 4581, -1, 4591, 4581, 4579, -1, + 4579, 4589, 4591, -1, 4589, 4579, 4577, -1, + 4577, 4587, 4589, -1, 4587, 4577, 4575, -1, + 4575, 4584, 4587, -1, 4584, 4575, 4573, -1, + 4573, 4585, 4584, -1, 4585, 4573, 4571, -1, + 4571, 4596, 4585, -1, 4596, 4571, 4569, -1, + 4569, 4597, 4596, -1, 4597, 4569, 4567, -1, + 4567, 4598, 4597, -1, 4598, 4567, 4565, -1, + 4565, 4599, 4598, -1, 4599, 4565, 4563, -1, + 4563, 4600, 4599, -1, 4600, 4563, 4558, -1, + 4558, 4555, 4600, -1, 4601, 4602, 4603, -1, + 4601, 4604, 4602, -1, 4604, 4601, 4605, -1, + 4605, 4606, 4604, -1, 4606, 4605, 4607, -1, + 4607, 4608, 4606, -1, 4608, 4607, 4609, -1, + 4609, 4610, 4608, -1, 4610, 4609, 4611, -1, + 4611, 4612, 4610, -1, 4612, 4611, 4613, -1, + 4613, 4614, 4612, -1, 4613, 4615, 4614, -1, + 4615, 4613, 4616, -1, 4616, 4617, 4615, -1, + 4617, 4618, 4619, -1, 4617, 4616, 4618, -1, + 4620, 4621, 4622, -1, 4620, 4623, 4621, -1, + 4624, 4625, 4621, -1, 4621, 4626, 4624, -1, + 4626, 4621, 4623, -1, 4623, 4627, 4626, -1, + 4627, 4623, 4628, -1, 4628, 4629, 4627, -1, + 4628, 4630, 4629, -1, 4628, 4631, 4630, -1, + 4631, 4628, 4623, -1, 4623, 4620, 4631, -1, + 4620, 4632, 4618, -1, 4618, 4631, 4620, -1, + 4631, 4618, 4616, -1, 4616, 4630, 4631, -1, + 4630, 4616, 4613, -1, 4630, 4613, 4611, -1, + 4611, 4629, 4630, -1, 4629, 4611, 4609, -1, + 4609, 4633, 4629, -1, 4633, 4609, 4607, -1, + 4607, 4634, 4633, -1, 4634, 4607, 4605, -1, + 4605, 4635, 4634, -1, 4635, 4605, 4601, -1, + 4601, 4603, 4635, -1, 4636, 4637, 4638, -1, + 4637, 4636, 4639, -1, 4639, 4640, 4637, -1, + 4641, 4637, 4640, -1, 4641, 4642, 4637, -1, + 4642, 4641, 4643, -1, 4641, 4640, 4643, -1, + 4644, 4645, 4646, -1, 4644, 4647, 4645, -1, + 4647, 4644, 4648, -1, 4644, 4646, 4648, -1, + 4649, 4650, 4646, -1, 4650, 4648, 4646, -1, + 4651, 4652, 4648, -1, 4651, 4648, 4653, -1, + 4653, 4654, 4651, -1, 4653, 4655, 4654, -1, + 4655, 4653, 4656, -1, 4656, 4653, 4648, -1, + 4657, 4658, 4656, -1, 4657, 4656, 4659, -1, + 4659, 4660, 4657, -1, 4659, 4661, 4660, -1, + 4661, 4659, 4662, -1, 4662, 4659, 4656, -1, + 4663, 4664, 4665, -1, 4664, 4663, 4662, -1, + 4666, 4667, 4668, -1, 4668, 4667, 4669, -1, + 4669, 4670, 4668, -1, 4671, 4672, 4673, -1, + 4673, 4674, 4671, -1, 4673, 4675, 4674, -1, + 4673, 4672, 4675, -1, 4676, 4677, 4678, -1, + 4677, 4676, 4679, -1, 4680, 4679, 4676, -1, + 4676, 4681, 4680, -1, 4676, 4678, 4681, -1, + 4682, 4678, 4683, -1, 4682, 4681, 4678, -1, + 4682, 4680, 4681, -1, 4682, 4683, 4680, -1, + 4684, 4680, 4683, -1, 4685, 4686, 4687, -1, + 4686, 4685, 4684, -1, 4686, 4684, 4683, -1, + 4683, 4687, 4686, -1, 4687, 4683, 4678, -1, + 4678, 4675, 4672, -1, 4675, 4678, 4677, -1, + 4677, 4679, 4675, -1, 4679, 4674, 4675, -1, + 4679, 4688, 4674, -1, 4688, 4679, 4680, -1, + 4680, 4689, 4688, -1, 4689, 4680, 4684, -1, + 4689, 4684, 4690, -1, 4690, 4691, 4689, -1, + 4691, 4690, 4692, -1, 4692, 4693, 4691, -1, + 4692, 4694, 4693, -1, 4692, 4695, 4694, -1, + 4695, 4692, 4690, -1, 4690, 4696, 4695, -1, + 4696, 4690, 4684, -1, 4684, 4697, 4696, -1, + 4697, 4684, 4685, -1, 4698, 4697, 4685, -1, + 4698, 4685, 4687, -1, 4698, 4687, 4699, -1, + 4699, 4697, 4698, -1, 4699, 4700, 4697, -1, + 4699, 4687, 4700, -1, 4687, 4701, 4700, -1, + 4702, 4703, 4701, -1, 4704, 4705, 4706, -1, + 4704, 4707, 4705, -1, 4704, 4708, 4707, -1, + 4704, 4706, 4708, -1, 4709, 4710, 4711, -1, + 4709, 4711, 4712, -1, 4712, 4713, 4709, -1, + 4714, 4715, 4716, -1, 4717, 4718, 4719, -1, + 4717, 4720, 4718, -1, 4717, 4721, 4720, -1, + 4717, 4719, 4721, -1, 4722, 4723, 4724, -1, + 4722, 4724, 4719, -1, 4724, 4721, 4719, -1, + 4721, 4724, 4725, -1, 4725, 4726, 4721, -1, + 4726, 4725, 4727, -1, 4727, 4728, 4726, -1, + 4728, 4727, 4729, -1, 4729, 4730, 4728, -1, + 4730, 4729, 4731, -1, 4731, 4732, 4730, -1, + 4732, 4731, 4733, -1, 4733, 4734, 4732, -1, + 4734, 4733, 4735, -1, 4735, 4736, 4734, -1, + 4736, 4735, 4715, -1, 4715, 4714, 4736, -1, + 4737, 4738, 4739, -1, 4737, 4713, 4740, -1, + 4713, 4737, 4741, -1, 4741, 4742, 4713, -1, + 4742, 4741, 4743, -1, 4743, 4744, 4742, -1, + 4743, 4745, 4744, -1, 4743, 4746, 4745, -1, + 4746, 4743, 4741, -1, 4741, 4747, 4746, -1, + 4747, 4741, 4737, -1, 4737, 4739, 4747, -1, + 4748, 4749, 4750, -1, 4751, 4739, 4752, -1, + 4753, 4752, 4739, -1, 4752, 4753, 4750, -1, + 4752, 4750, 4749, -1, 4749, 4751, 4752, -1, + 4749, 4748, 4751, -1, 4748, 4754, 4751, -1, + 4748, 4750, 4754, -1, 4755, 4756, 4757, -1, + 4758, 4759, 4760, -1, 4759, 4758, 4761, -1, + 4761, 4762, 4759, -1, 4762, 4761, 4763, -1, + 4763, 4764, 4762, -1, 4764, 4763, 4765, -1, + 4765, 4766, 4764, -1, 4766, 4765, 4767, -1, + 4767, 4768, 4766, -1, 4768, 4767, 4769, -1, + 4769, 4770, 4768, -1, 4771, 4772, 4770, -1, + 4771, 4770, 4773, -1, 4770, 4769, 4773, -1, + 4774, 4769, 4775, -1, 4774, 4773, 4769, -1, + 4774, 4776, 4773, -1, 4774, 4775, 4776, -1, + 4777, 4778, 4779, -1, 4780, 4781, 4782, -1, + 4780, 4782, 4783, -1, 4783, 4784, 4780, -1, + 4784, 4783, 4785, -1, 4785, 4786, 4784, -1, + 4786, 4785, 4787, -1, 4787, 4788, 4786, -1, + 4788, 4787, 4779, -1, 4779, 4789, 4788, -1, + 4789, 4779, 4778, -1, 4790, 4789, 4778, -1, + 4790, 4791, 4789, -1, 4791, 4790, 4792, -1, + 4790, 4778, 4792, -1, 4778, 4777, 4792, -1, + 4793, 4792, 4777, -1, 4794, 4793, 4777, -1, + 4777, 4779, 4794, -1, 4779, 4795, 4794, -1, + 4795, 4779, 4787, -1, 4787, 4796, 4795, -1, + 4796, 4787, 4785, -1, 4785, 4797, 4796, -1, + 4797, 4785, 4783, -1, 4783, 4798, 4797, -1, + 4798, 4783, 4782, -1, 4782, 4799, 4798, -1, + 4782, 4800, 4799, -1, 4800, 4782, 4781, -1, + 4781, 4801, 4800, -1, 4781, 4802, 4801, -1, + 4781, 4780, 4802, -1, 4803, 4804, 4805, -1, + 4804, 4803, 4806, -1, 4806, 4807, 4804, -1, + 4807, 4806, 4808, -1, 4808, 4809, 4807, -1, + 4809, 4808, 4810, -1, 4810, 4811, 4809, -1, + 4811, 4810, 4812, -1, 4812, 4813, 4811, -1, + 4813, 4812, 4802, -1, 4813, 4802, 4780, -1, + 4813, 4780, 4784, -1, 4784, 4811, 4813, -1, + 4811, 4784, 4786, -1, 4786, 4809, 4811, -1, + 4809, 4786, 4788, -1, 4788, 4807, 4809, -1, + 4807, 4788, 4789, -1, 4789, 4804, 4807, -1, + 4789, 4791, 4804, -1, 4814, 4804, 4791, -1, + 4791, 4792, 4814, -1, 4815, 4814, 4792, -1, + 4815, 4804, 4814, -1, 4815, 4805, 4804, -1, + 4815, 4792, 4805, -1, 4776, 4805, 4792, -1, + 4816, 4805, 4776, -1, 4816, 4803, 4805, -1, + 4816, 4817, 4803, -1, 4817, 4816, 4776, -1, + 4817, 4776, 4775, -1, 4775, 4769, 4817, -1, + 4769, 4803, 4817, -1, 4803, 4769, 4767, -1, + 4767, 4806, 4803, -1, 4806, 4767, 4765, -1, + 4765, 4808, 4806, -1, 4808, 4765, 4763, -1, + 4763, 4810, 4808, -1, 4810, 4763, 4761, -1, + 4761, 4812, 4810, -1, 4812, 4761, 4758, -1, + 4758, 4802, 4812, -1, 4758, 4760, 4802, -1, + 4818, 4802, 4760, -1, 4818, 4801, 4802, -1, + 4819, 4801, 4818, -1, 4801, 4819, 4820, -1, + 4820, 4800, 4801, -1, 4800, 4820, 4821, -1, + 4821, 4799, 4800, -1, 4799, 4821, 4822, -1, + 4799, 4822, 4823, -1, 4823, 4798, 4799, -1, + 4798, 4823, 4824, -1, 4824, 4797, 4798, -1, + 4797, 4824, 4825, -1, 4825, 4796, 4797, -1, + 4796, 4825, 4757, -1, 4757, 4795, 4796, -1, + 4795, 4757, 4756, -1, 4826, 4795, 4756, -1, + 4826, 4827, 4795, -1, 4827, 4794, 4795, -1, + 4827, 4793, 4794, -1, 4827, 4826, 4793, -1, + 4826, 4756, 4793, -1, 4756, 4755, 4793, -1, + 4750, 4793, 4755, -1, 4755, 4754, 4750, -1, + 4755, 4757, 4754, -1, 4757, 4751, 4754, -1, + 4751, 4757, 4825, -1, 4825, 4739, 4751, -1, + 4739, 4825, 4824, -1, 4824, 4747, 4739, -1, + 4747, 4824, 4823, -1, 4823, 4746, 4747, -1, + 4746, 4823, 4822, -1, 4822, 4745, 4746, -1, + 4822, 4828, 4745, -1, 4828, 4822, 4821, -1, + 4821, 4829, 4828, -1, 4829, 4821, 4820, -1, + 4820, 4830, 4829, -1, 4830, 4820, 4819, -1, + 4819, 4831, 4830, -1, 4819, 4818, 4831, -1, + 4832, 4831, 4818, -1, 4818, 4760, 4832, -1, + 4714, 4832, 4760, -1, 4760, 4736, 4714, -1, + 4736, 4760, 4759, -1, 4759, 4734, 4736, -1, + 4734, 4759, 4762, -1, 4762, 4732, 4734, -1, + 4732, 4762, 4764, -1, 4764, 4730, 4732, -1, + 4730, 4764, 4766, -1, 4766, 4728, 4730, -1, + 4728, 4766, 4768, -1, 4768, 4726, 4728, -1, + 4726, 4768, 4770, -1, 4770, 4721, 4726, -1, + 4721, 4770, 4772, -1, 4772, 4720, 4721, -1, + 4772, 4718, 4720, -1, 4772, 4771, 4718, -1, + 4771, 4773, 4718, -1, 4718, 4773, 4776, -1, + 4833, 4750, 4753, -1, 4753, 4834, 4833, -1, + 4753, 4739, 4834, -1, 4834, 4739, 4738, -1, + 4738, 4833, 4834, -1, 4738, 4835, 4833, -1, + 4835, 4738, 4737, -1, 4835, 4737, 4740, -1, + 4740, 4833, 4835, -1, 4740, 4836, 4833, -1, + 4836, 4740, 4713, -1, 4836, 4713, 4712, -1, + 4712, 4711, 4836, -1, 4711, 4833, 4836, -1, + 4708, 4711, 4837, -1, 4838, 4708, 4706, -1, + 4706, 4839, 4838, -1, 4840, 4841, 4842, -1, + 4840, 4842, 4843, -1, 4843, 4844, 4840, -1, + 4844, 4843, 4845, -1, 4844, 4845, 4846, -1, + 4844, 4846, 4847, -1, 4847, 4840, 4844, -1, + 4847, 4848, 4840, -1, 4849, 4838, 4850, -1, + 4849, 4848, 4838, -1, 4849, 4840, 4848, -1, + 4849, 4850, 4840, -1, 4850, 4841, 4840, -1, + 4841, 4850, 4838, -1, 4841, 4838, 4839, -1, + 4839, 4842, 4841, -1, 4839, 4706, 4842, -1, + 4842, 4706, 4705, -1, 4842, 4705, 4851, -1, + 4851, 4843, 4842, -1, 4843, 4851, 4852, -1, + 4852, 4845, 4843, -1, 4852, 4853, 4845, -1, + 4853, 4852, 4854, -1, 4854, 4855, 4853, -1, + 4855, 4854, 4856, -1, 4856, 4857, 4855, -1, + 4857, 4856, 4858, -1, 4858, 4859, 4857, -1, + 4859, 4858, 4860, -1, 4860, 4861, 4859, -1, + 4861, 4860, 4862, -1, 4862, 4863, 4861, -1, + 4863, 4862, 4864, -1, 4864, 4865, 4863, -1, + 4866, 4865, 4867, -1, 4866, 4863, 4865, -1, + 4863, 4866, 4868, -1, 4868, 4861, 4863, -1, + 4861, 4868, 4869, -1, 4869, 4859, 4861, -1, + 4859, 4869, 4870, -1, 4870, 4857, 4859, -1, + 4857, 4870, 4871, -1, 4871, 4855, 4857, -1, + 4855, 4871, 4872, -1, 4872, 4853, 4855, -1, + 4853, 4872, 4873, -1, 4873, 4845, 4853, -1, + 4845, 4873, 4874, -1, 4874, 4846, 4845, -1, + 4846, 4874, 4875, -1, 4846, 4875, 4876, -1, + 4876, 4847, 4846, -1, 4876, 4877, 4847, -1, + 4878, 4879, 4880, -1, 4881, 4879, 4878, -1, + 4878, 4876, 4881, -1, 4878, 4880, 4876, -1, + 4880, 4877, 4876, -1, 4877, 4880, 4879, -1, + 4877, 4879, 4882, -1, 4882, 4847, 4877, -1, + 4882, 4848, 4847, -1, 4882, 4879, 4848, -1, + 4879, 4838, 4848, -1, 4879, 4881, 4883, -1, + 4884, 4883, 4881, -1, 4884, 4885, 4883, -1, + 4884, 4886, 4885, -1, 4884, 4881, 4886, -1, + 4886, 4881, 4876, -1, 4886, 4876, 4875, -1, + 4875, 4887, 4886, -1, 4875, 4888, 4887, -1, + 4888, 4875, 4874, -1, 4874, 4889, 4888, -1, + 4889, 4874, 4873, -1, 4873, 4890, 4889, -1, + 4890, 4873, 4872, -1, 4872, 4891, 4890, -1, + 4891, 4872, 4871, -1, 4871, 4892, 4891, -1, + 4892, 4871, 4870, -1, 4870, 4893, 4892, -1, + 4893, 4870, 4869, -1, 4869, 4894, 4893, -1, + 4894, 4869, 4868, -1, 4868, 4895, 4894, -1, + 4895, 4868, 4866, -1, 4866, 4867, 4895, -1, + 4896, 4897, 4898, -1, 4899, 4900, 4901, -1, + 4901, 4902, 4899, -1, 4902, 4901, 4903, -1, + 4903, 4904, 4902, -1, 4905, 4906, 4907, -1, + 4907, 4908, 4905, -1, 4908, 4907, 4909, -1, + 4909, 4910, 4908, -1, 4910, 4909, 4911, -1, + 4911, 4912, 4910, -1, 4912, 4911, 4913, -1, + 4913, 4914, 4912, -1, 4914, 4913, 4904, -1, + 4904, 4903, 4914, -1, 4915, 4914, 4903, -1, + 4903, 4916, 4915, -1, 4916, 4903, 4901, -1, + 4901, 4917, 4916, -1, 4917, 4901, 4900, -1, + 4900, 4918, 4917, -1, 4900, 4919, 4918, -1, + 4900, 4899, 4919, -1, 4920, 4921, 4922, -1, + 4923, 4924, 4925, -1, 4923, 4925, 4926, -1, + 4927, 4926, 4925, -1, 4928, 4927, 4925, -1, + 4928, 4929, 4927, -1, 4929, 4928, 4930, -1, + 4930, 4931, 4929, -1, 4931, 4930, 4932, -1, + 4932, 4933, 4931, -1, 4933, 4932, 4934, -1, + 4934, 4935, 4933, -1, 4935, 4934, 4936, -1, + 4936, 4937, 4935, -1, 4937, 4936, 4938, -1, + 4938, 4939, 4937, -1, 4939, 4938, 4940, -1, + 4940, 4941, 4939, -1, 4941, 4940, 4942, -1, + 4942, 4943, 4941, -1, 4943, 4942, 4944, -1, + 4944, 4945, 4943, -1, 4945, 4944, 4946, -1, + 4946, 4947, 4945, -1, 4946, 4948, 4947, -1, + 4946, 4949, 4948, -1, 4949, 4946, 4944, -1, + 4944, 4950, 4949, -1, 4950, 4944, 4942, -1, + 4942, 4951, 4950, -1, 4951, 4942, 4940, -1, + 4940, 4952, 4951, -1, 4952, 4940, 4938, -1, + 4938, 4953, 4952, -1, 4953, 4938, 4936, -1, + 4936, 4954, 4953, -1, 4954, 4936, 4934, -1, + 4934, 4955, 4954, -1, 4955, 4934, 4932, -1, + 4932, 4956, 4955, -1, 4956, 4932, 4930, -1, + 4930, 4957, 4956, -1, 4957, 4930, 4928, -1, + 4928, 4925, 4957, -1, 4958, 4959, 4960, -1, + 4958, 4960, 4961, -1, 4962, 4921, 4961, -1, + 4962, 4963, 4921, -1, 4962, 4964, 4963, -1, + 4962, 4961, 4964, -1, 4964, 4961, 4960, -1, + 4964, 4960, 4957, -1, 4964, 4957, 4925, -1, + 4925, 4963, 4964, -1, 4963, 4925, 4924, -1, + 4924, 4921, 4963, -1, 4924, 4923, 4921, -1, + 4923, 4926, 4921, -1, 4926, 4922, 4921, -1, + 4922, 4926, 4927, -1, 4922, 4927, 4965, -1, + 4965, 4920, 4922, -1, 4920, 4966, 4967, -1, + 4968, 4969, 4970, -1, 4968, 4967, 4969, -1, + 4967, 4968, 4971, -1, 4972, 4971, 4968, -1, + 4968, 4970, 4972, -1, 4973, 4974, 4975, -1, + 4975, 4976, 4973, -1, 4976, 4975, 4977, -1, + 4977, 4978, 4976, -1, 4978, 4977, 4979, -1, + 4979, 4980, 4978, -1, 4980, 4979, 4981, -1, + 4981, 4982, 4980, -1, 4982, 4981, 4983, -1, + 4983, 4984, 4982, -1, 4984, 4983, 4985, -1, + 4985, 4986, 4984, -1, 4986, 4985, 4987, -1, + 4987, 4988, 4986, -1, 4988, 4987, 4989, -1, + 4989, 4990, 4988, -1, 4989, 4991, 4990, -1, + 4989, 4992, 4991, -1, 4992, 4989, 4987, -1, + 4987, 4993, 4992, -1, 4993, 4987, 4985, -1, + 4985, 4994, 4993, -1, 4994, 4985, 4983, -1, + 4983, 4995, 4994, -1, 4995, 4983, 4981, -1, + 4981, 4996, 4995, -1, 4996, 4981, 4979, -1, + 4979, 4997, 4996, -1, 4997, 4979, 4977, -1, + 4977, 4998, 4997, -1, 4998, 4977, 4975, -1, + 4975, 4999, 4998, -1, 4999, 4975, 4974, -1, + 4974, 5000, 4999, -1, 5001, 5002, 5003, -1, + 5002, 5001, 5004, -1, 5002, 5004, 5005, -1, + 5002, 5005, 5006, -1, 5006, 5003, 5002, -1, + 5006, 5007, 5003, -1, 5006, 5008, 5007, -1, + 5008, 5006, 5005, -1, 5005, 5009, 5008, -1, + 5005, 5010, 5009, -1, 5010, 5005, 5004, -1, + 5004, 5011, 5010, -1, 5004, 5012, 5011, -1, + 5012, 5004, 5001, -1, 5001, 5013, 5012, -1, + 5001, 5003, 5013, -1, 5014, 5015, 5016, -1, + 5016, 5017, 5014, -1, 5017, 5016, 5018, -1, + 5018, 5019, 5017, -1, 5019, 5018, 5020, -1, + 5020, 5021, 5019, -1, 5020, 5022, 5021, -1, + 5020, 5023, 5022, -1, 5023, 5020, 5018, -1, + 5018, 5024, 5023, -1, 5024, 5018, 5016, -1, + 5016, 5025, 5024, -1, 5025, 5016, 5015, -1, + 5025, 5015, 5026, -1, 5026, 5027, 5025, -1, + 5027, 5026, 5028, -1, 5028, 5029, 5027, -1, + 5029, 5028, 5030, -1, 5029, 5030, 5013, -1, + 5029, 5013, 5003, -1, 5003, 5027, 5029, -1, + 5027, 5003, 5007, -1, 5007, 5025, 5027, -1, + 5007, 5024, 5025, -1, 5024, 5007, 5008, -1, + 5008, 5023, 5024, -1, 5023, 5008, 5009, -1, + 5009, 5022, 5023, -1, 5009, 5031, 5022, -1, + 5031, 5009, 5010, -1, 5010, 5032, 5031, -1, + 5032, 5010, 5011, -1, 5011, 5033, 5032, -1, + 5011, 5034, 5033, -1, 5034, 5011, 5012, -1, + 5012, 5035, 5034, -1, 5035, 5012, 5013, -1, + 5013, 5036, 5035, -1, 5036, 5013, 5030, -1, + 5030, 5037, 5036, -1, 5030, 5038, 5037, -1, + 5038, 5030, 5028, -1, 5028, 5039, 5038, -1, + 5039, 5028, 5026, -1, 5026, 5040, 5039, -1, + 5040, 5026, 5015, -1, 5015, 5041, 5040, -1, + 5015, 5014, 5041, -1, 5042, 5041, 5014, -1, + 5014, 5043, 5042, -1, 5043, 5014, 5017, -1, + 5017, 5044, 5043, -1, 5044, 5017, 5019, -1, + 5019, 5045, 5044, -1, 5045, 5019, 5021, -1, + 5021, 5046, 5045, -1, 5021, 5047, 5046, -1, + 5047, 5021, 5022, -1, 5022, 5048, 5047, -1, + 5048, 5022, 5031, -1, 5031, 5049, 5048, -1, + 5049, 5031, 5032, -1, 5032, 5050, 5049, -1, + 5050, 5032, 5033, -1, 5033, 5051, 5050, -1, + 5033, 5052, 5051, -1, 5052, 5033, 5034, -1, + 5034, 5053, 5052, -1, 5053, 5034, 5035, -1, + 5035, 5054, 5053, -1, 5054, 5035, 5036, -1, + 5036, 5055, 5054, -1, 5055, 5036, 5037, -1, + 5037, 5056, 5055, -1, 5037, 5057, 5056, -1, + 5057, 5037, 5038, -1, 5038, 5058, 5057, -1, + 5058, 5038, 5039, -1, 5039, 5059, 5058, -1, + 5059, 5039, 5040, -1, 5040, 5060, 5059, -1, + 5060, 5040, 5041, -1, 5041, 5061, 5060, -1, + 5041, 5042, 5061, -1, 5062, 5061, 5042, -1, + 5042, 5063, 5062, -1, 5063, 5042, 5043, -1, + 5043, 5064, 5063, -1, 5064, 5043, 5044, -1, + 5044, 5065, 5064, -1, 5065, 5044, 5045, -1, + 5045, 5066, 5065, -1, 5066, 5045, 5046, -1, + 5046, 5067, 5066, -1, 5046, 5068, 5067, -1, + 5068, 5046, 5047, -1, 5047, 5069, 5068, -1, + 5069, 5047, 5048, -1, 5048, 5070, 5069, -1, + 5070, 5048, 5049, -1, 5049, 5071, 5070, -1, + 5071, 5049, 5050, -1, 5050, 5072, 5071, -1, + 5072, 5050, 5051, -1, 5051, 5073, 5072, -1, + 5051, 5074, 5073, -1, 5074, 5051, 5052, -1, + 5052, 5075, 5074, -1, 5075, 5052, 5053, -1, + 5053, 5076, 5075, -1, 5076, 5053, 5054, -1, + 5054, 5077, 5076, -1, 5077, 5054, 5055, -1, + 5055, 5078, 5077, -1, 5078, 5055, 5056, -1, + 5056, 5079, 5078, -1, 5056, 5080, 5079, -1, + 5080, 5056, 5057, -1, 5057, 5081, 5080, -1, + 5081, 5057, 5058, -1, 5058, 5082, 5081, -1, + 5082, 5058, 5059, -1, 5059, 5083, 5082, -1, + 5083, 5059, 5060, -1, 5060, 5084, 5083, -1, + 5084, 5060, 5061, -1, 5061, 5085, 5084, -1, + 5061, 5062, 5085, -1, 5086, 5085, 5062, -1, + 5062, 5087, 5086, -1, 5087, 5062, 5063, -1, + 5063, 5088, 5087, -1, 5088, 5063, 5064, -1, + 5064, 5089, 5088, -1, 5089, 5064, 5065, -1, + 5065, 5090, 5089, -1, 5090, 5065, 5066, -1, + 5066, 5091, 5090, -1, 5091, 5066, 5067, -1, + 5067, 5092, 5091, -1, 5067, 5093, 5092, -1, + 5093, 5067, 5068, -1, 5068, 5094, 5093, -1, + 5094, 5068, 5069, -1, 5069, 5095, 5094, -1, + 5095, 5069, 5070, -1, 5070, 5096, 5095, -1, + 5096, 5070, 5071, -1, 5071, 5097, 5096, -1, + 5097, 5071, 5072, -1, 5072, 5098, 5097, -1, + 5098, 5072, 5073, -1, 5073, 5099, 5098, -1, + 5073, 5100, 5099, -1, 5100, 5073, 5074, -1, + 5074, 5101, 5100, -1, 5101, 5074, 5075, -1, + 5075, 5102, 5101, -1, 5102, 5075, 5076, -1, + 5076, 5103, 5102, -1, 5103, 5076, 5077, -1, + 5077, 5104, 5103, -1, 5104, 5077, 5078, -1, + 5078, 5105, 5104, -1, 5105, 5078, 5079, -1, + 5079, 5106, 5105, -1, 5079, 5107, 5106, -1, + 5107, 5079, 5080, -1, 5080, 5108, 5107, -1, + 5108, 5080, 5081, -1, 5081, 5109, 5108, -1, + 5109, 5081, 5082, -1, 5082, 5110, 5109, -1, + 5110, 5082, 5083, -1, 5083, 5111, 5110, -1, + 5111, 5083, 5084, -1, 5084, 5112, 5111, -1, + 5112, 5084, 5085, -1, 5085, 5113, 5112, -1, + 5085, 5086, 5113, -1, 5114, 5113, 5086, -1, + 5086, 5115, 5114, -1, 5115, 5086, 5087, -1, + 5087, 5116, 5115, -1, 5116, 5087, 5088, -1, + 5088, 5117, 5116, -1, 5117, 5088, 5089, -1, + 5089, 5118, 5117, -1, 5118, 5089, 5090, -1, + 5090, 5119, 5118, -1, 5119, 5090, 5091, -1, + 5091, 5120, 5119, -1, 5120, 5091, 5092, -1, + 5092, 5121, 5120, -1, 5092, 5122, 5121, -1, + 5122, 5092, 5093, -1, 5093, 5123, 5122, -1, + 5123, 5093, 5094, -1, 5094, 5124, 5123, -1, + 5124, 5094, 5095, -1, 5095, 5125, 5124, -1, + 5125, 5095, 5096, -1, 5096, 5126, 5125, -1, + 5126, 5096, 5097, -1, 5097, 5127, 5126, -1, + 5127, 5097, 5098, -1, 5098, 5128, 5127, -1, + 5128, 5098, 5099, -1, 5099, 5129, 5128, -1, + 5099, 5130, 5129, -1, 5130, 5099, 5100, -1, + 5100, 5131, 5130, -1, 5131, 5100, 5101, -1, + 5101, 5132, 5131, -1, 5132, 5101, 5102, -1, + 5102, 5133, 5132, -1, 5133, 5102, 5103, -1, + 5103, 5134, 5133, -1, 5134, 5103, 5104, -1, + 5104, 5135, 5134, -1, 5135, 5104, 5105, -1, + 5105, 5136, 5135, -1, 5136, 5105, 5106, -1, + 5106, 5137, 5136, -1, 5106, 5138, 5137, -1, + 5138, 5106, 5107, -1, 5107, 5139, 5138, -1, + 5139, 5107, 5108, -1, 5108, 5140, 5139, -1, + 5140, 5108, 5109, -1, 5109, 5141, 5140, -1, + 5141, 5109, 5110, -1, 5110, 5142, 5141, -1, + 5142, 5110, 5111, -1, 5111, 5143, 5142, -1, + 5143, 5111, 5112, -1, 5112, 5144, 5143, -1, + 5144, 5112, 5113, -1, 5113, 5145, 5144, -1, + 5113, 5114, 5145, -1, 5146, 5145, 5114, -1, + 5114, 5147, 5146, -1, 5147, 5114, 5115, -1, + 5115, 5148, 5147, -1, 5148, 5115, 5116, -1, + 5116, 5149, 5148, -1, 5149, 5116, 5117, -1, + 5117, 5150, 5149, -1, 5150, 5117, 5118, -1, + 5118, 5151, 5150, -1, 5151, 5118, 5119, -1, + 5119, 5152, 5151, -1, 5152, 5119, 5120, -1, + 5120, 5153, 5152, -1, 5153, 5120, 5121, -1, + 5121, 5154, 5153, -1, 5121, 5155, 5154, -1, + 5155, 5121, 5122, -1, 5122, 5156, 5155, -1, + 5156, 5122, 5123, -1, 5123, 5157, 5156, -1, + 5157, 5123, 5124, -1, 5124, 5158, 5157, -1, + 5158, 5124, 5125, -1, 5125, 5159, 5158, -1, + 5159, 5125, 5126, -1, 5126, 5160, 5159, -1, + 5160, 5126, 5127, -1, 5127, 5161, 5160, -1, + 5161, 5127, 5128, -1, 5128, 5162, 5161, -1, + 5162, 5128, 5129, -1, 5129, 5163, 5162, -1, + 5129, 5164, 5163, -1, 5164, 5129, 5130, -1, + 5130, 5165, 5164, -1, 5165, 5130, 5131, -1, + 5131, 5166, 5165, -1, 5166, 5131, 5132, -1, + 5132, 5167, 5166, -1, 5167, 5132, 5133, -1, + 5133, 5168, 5167, -1, 5168, 5133, 5134, -1, + 5134, 5169, 5168, -1, 5169, 5134, 5135, -1, + 5135, 5170, 5169, -1, 5170, 5135, 5136, -1, + 5136, 5171, 5170, -1, 5171, 5136, 5137, -1, + 5137, 5172, 5171, -1, 5137, 5173, 5172, -1, + 5173, 5137, 5138, -1, 5138, 5174, 5173, -1, + 5174, 5138, 5139, -1, 5139, 5175, 5174, -1, + 5175, 5139, 5140, -1, 5140, 5176, 5175, -1, + 5176, 5140, 5141, -1, 5141, 5177, 5176, -1, + 5177, 5141, 5142, -1, 5142, 5178, 5177, -1, + 5178, 5142, 5143, -1, 5143, 5179, 5178, -1, + 5179, 5143, 5144, -1, 5144, 5180, 5179, -1, + 5180, 5144, 5145, -1, 5145, 5181, 5180, -1, + 5145, 5146, 5181, -1, 5000, 5181, 5146, -1, + 5146, 4999, 5000, -1, 4999, 5146, 5147, -1, + 5147, 4998, 4999, -1, 4998, 5147, 5148, -1, + 5148, 4997, 4998, -1, 4997, 5148, 5149, -1, + 5149, 4996, 4997, -1, 4996, 5149, 5150, -1, + 5150, 4995, 4996, -1, 4995, 5150, 5151, -1, + 5151, 4994, 4995, -1, 4994, 5151, 5152, -1, + 5152, 4993, 4994, -1, 4993, 5152, 5153, -1, + 5153, 4992, 4993, -1, 4992, 5153, 5154, -1, + 5154, 4991, 4992, -1, 5154, 5182, 4991, -1, + 5182, 5154, 5155, -1, 5155, 5183, 5182, -1, + 5183, 5155, 5156, -1, 5156, 5184, 5183, -1, + 5184, 5156, 5157, -1, 5157, 5185, 5184, -1, + 5185, 5157, 5158, -1, 5158, 5186, 5185, -1, + 5186, 5158, 5159, -1, 5159, 5187, 5186, -1, + 5187, 5159, 5160, -1, 5160, 5188, 5187, -1, + 5188, 5160, 5161, -1, 5161, 5189, 5188, -1, + 5189, 5161, 5162, -1, 5162, 5190, 5189, -1, + 5190, 5162, 5163, -1, 5163, 5191, 5190, -1, + 5163, 5192, 5191, -1, 5192, 5163, 5164, -1, + 5164, 5193, 5192, -1, 5193, 5164, 5165, -1, + 5165, 5194, 5193, -1, 5194, 5165, 5166, -1, + 5166, 5195, 5194, -1, 5195, 5166, 5167, -1, + 5167, 5196, 5195, -1, 5196, 5167, 5168, -1, + 5168, 5197, 5196, -1, 5197, 5168, 5169, -1, + 5169, 5198, 5197, -1, 5198, 5169, 5170, -1, + 5170, 5199, 5198, -1, 5199, 5170, 5171, -1, + 5171, 5200, 5199, -1, 5200, 5171, 5172, -1, + 5172, 5201, 5200, -1, 5172, 5202, 5201, -1, + 5202, 5172, 5173, -1, 5173, 5203, 5202, -1, + 5203, 5173, 5174, -1, 5174, 5204, 5203, -1, + 5204, 5174, 5175, -1, 5175, 5205, 5204, -1, + 5205, 5175, 5176, -1, 5176, 5206, 5205, -1, + 5206, 5176, 5177, -1, 5177, 5207, 5206, -1, + 5207, 5177, 5178, -1, 5178, 5208, 5207, -1, + 5208, 5178, 5179, -1, 5179, 5209, 5208, -1, + 5209, 5179, 5180, -1, 5180, 5210, 5209, -1, + 5210, 5180, 5181, -1, 5181, 5211, 5210, -1, + 5181, 5000, 5211, -1, 5212, 5211, 5000, -1, + 5000, 4974, 5212, -1, 5213, 5214, 5212, -1, + 5213, 5212, 4974, -1, 4974, 4973, 5213, -1, + 5215, 5216, 5217, -1, 5213, 5217, 5216, -1, + 5217, 5213, 4973, -1, 4973, 5218, 5217, -1, + 5218, 4973, 4976, -1, 4976, 5219, 5218, -1, + 5219, 4976, 4978, -1, 4978, 5220, 5219, -1, + 5220, 4978, 4980, -1, 4980, 5221, 5220, -1, + 5221, 4980, 4982, -1, 4982, 5222, 5221, -1, + 5222, 4982, 4984, -1, 4984, 5223, 5222, -1, + 5223, 4984, 4986, -1, 4986, 5224, 5223, -1, + 5224, 4986, 4988, -1, 4988, 5225, 5224, -1, + 5225, 4988, 4990, -1, 4990, 5226, 5225, -1, + 4990, 5227, 5226, -1, 5227, 4990, 4991, -1, + 4991, 5228, 5227, -1, 5228, 4991, 5182, -1, + 5182, 5229, 5228, -1, 5229, 5182, 5183, -1, + 5183, 5230, 5229, -1, 5230, 5183, 5184, -1, + 5184, 5231, 5230, -1, 5231, 5184, 5185, -1, + 5185, 5232, 5231, -1, 5232, 5185, 5186, -1, + 5186, 5233, 5232, -1, 5233, 5186, 5187, -1, + 5187, 5234, 5233, -1, 5234, 5187, 5188, -1, + 5188, 5235, 5234, -1, 5235, 5188, 5189, -1, + 5189, 5236, 5235, -1, 5236, 5189, 5190, -1, + 5190, 5237, 5236, -1, 5237, 5190, 5191, -1, + 5191, 5238, 5237, -1, 5191, 5239, 5238, -1, + 5239, 5191, 5192, -1, 5192, 5240, 5239, -1, + 5240, 5192, 5193, -1, 5193, 5241, 5240, -1, + 5241, 5193, 5194, -1, 5194, 5242, 5241, -1, + 5242, 5194, 5195, -1, 5195, 5243, 5242, -1, + 5243, 5195, 5196, -1, 5196, 5244, 5243, -1, + 5244, 5196, 5197, -1, 5197, 5245, 5244, -1, + 5245, 5197, 5198, -1, 5198, 5246, 5245, -1, + 5246, 5198, 5199, -1, 5199, 5247, 5246, -1, + 5247, 5199, 5200, -1, 5200, 5248, 5247, -1, + 5248, 5200, 5201, -1, 5201, 5249, 5248, -1, + 5249, 5201, 5250, -1, 5250, 5251, 5249, -1, + 5250, 5252, 5251, -1, 5252, 5250, 5253, -1, + 5253, 5254, 5252, -1, 5254, 5253, 5255, -1, + 5255, 5256, 5254, -1, 5256, 5255, 5257, -1, + 5257, 5258, 5256, -1, 5258, 5257, 5259, -1, + 5259, 5260, 5258, -1, 5260, 5259, 5261, -1, + 5261, 5262, 5260, -1, 5262, 5261, 5263, -1, + 5263, 5264, 5262, -1, 5264, 5263, 5265, -1, + 5265, 5266, 5264, -1, 5266, 5265, 5267, -1, + 5267, 5268, 5266, -1, 5268, 5267, 5269, -1, + 5269, 4970, 5268, -1, 4970, 5269, 5270, -1, + 5270, 4972, 4970, -1, 5271, 4972, 5270, -1, + 5271, 4971, 4972, -1, 5272, 5273, 5274, -1, + 5273, 5272, 4971, -1, 5273, 4971, 5271, -1, + 5271, 5270, 5273, -1, 5270, 5274, 5273, -1, + 5270, 5275, 5274, -1, 5275, 5270, 5269, -1, + 5269, 5276, 5275, -1, 5276, 5269, 5267, -1, + 5267, 5277, 5276, -1, 5277, 5267, 5265, -1, + 5265, 5278, 5277, -1, 5278, 5265, 5263, -1, + 5263, 5279, 5278, -1, 5279, 5263, 5261, -1, + 5261, 5280, 5279, -1, 5280, 5261, 5259, -1, + 5259, 5281, 5280, -1, 5281, 5259, 5257, -1, + 5257, 5282, 5281, -1, 5282, 5257, 5255, -1, + 5255, 5283, 5282, -1, 5283, 5255, 5253, -1, + 5253, 5284, 5283, -1, 5284, 5253, 5250, -1, + 5284, 5250, 5201, -1, 5284, 5201, 5202, -1, + 5202, 5283, 5284, -1, 5283, 5202, 5203, -1, + 5203, 5282, 5283, -1, 5282, 5203, 5204, -1, + 5204, 5281, 5282, -1, 5281, 5204, 5205, -1, + 5205, 5280, 5281, -1, 5280, 5205, 5206, -1, + 5206, 5279, 5280, -1, 5279, 5206, 5207, -1, + 5207, 5278, 5279, -1, 5278, 5207, 5208, -1, + 5208, 5277, 5278, -1, 5277, 5208, 5209, -1, + 5209, 5276, 5277, -1, 5276, 5209, 5210, -1, + 5210, 5275, 5276, -1, 5275, 5210, 5211, -1, + 5211, 5274, 5275, -1, 5211, 5212, 5274, -1, + 5212, 5285, 5274, -1, 5286, 5274, 5285, -1, + 5286, 5272, 5274, -1, 5286, 4971, 5272, -1, + 5286, 5285, 4971, -1, 5287, 4971, 5285, -1, + 5288, 5287, 5285, -1, 5285, 5212, 5288, -1, + 5288, 5212, 5214, -1, 5214, 5287, 5288, -1, + 5214, 5289, 5287, -1, 5289, 5214, 5213, -1, + 5289, 5213, 5216, -1, 5216, 5287, 5289, -1, + 5216, 5215, 5287, -1, 5290, 5287, 5215, -1, + 5291, 5292, 5293, -1, 5293, 5294, 5291, -1, + 5294, 5293, 5295, -1, 5295, 5296, 5294, -1, + 5296, 5295, 5297, -1, 5297, 5298, 5296, -1, + 5298, 5297, 5299, -1, 5299, 5300, 5298, -1, + 5300, 5299, 5301, -1, 5301, 5302, 5300, -1, + 5302, 5301, 5303, -1, 5303, 5304, 5302, -1, + 5304, 5303, 5305, -1, 5305, 5306, 5304, -1, + 5307, 5308, 5309, -1, 5308, 5307, 5306, -1, + 5306, 5305, 5308, -1, 5310, 5308, 5311, -1, + 5308, 4896, 5311, -1, 4896, 5308, 5305, -1, + 5305, 5312, 4896, -1, 5312, 5305, 5303, -1, + 5303, 5313, 5312, -1, 5313, 5303, 5301, -1, + 5301, 5314, 5313, -1, 5314, 5301, 5299, -1, + 5299, 5315, 5314, -1, 5315, 5299, 5297, -1, + 5297, 5316, 5315, -1, 5316, 5297, 5295, -1, + 5295, 5317, 5316, -1, 5317, 5295, 5293, -1, + 5293, 5318, 5317, -1, 5318, 5293, 5292, -1, + 5292, 5319, 5318, -1, 5292, 5320, 5319, -1, + 5292, 5291, 5320, -1, 5321, 5322, 5323, -1, + 5323, 5324, 5325, -1, 5325, 5326, 5323, -1, + 5326, 5325, 5327, -1, 5327, 5328, 5326, -1, + 5328, 5327, 5329, -1, 5329, 5330, 5328, -1, + 5330, 5329, 5331, -1, 5331, 5332, 5330, -1, + 5332, 5331, 5333, -1, 5333, 5334, 5332, -1, + 5334, 5333, 5335, -1, 5335, 5336, 5334, -1, + 5336, 5335, 5337, -1, 5337, 5338, 5336, -1, + 5338, 5337, 5339, -1, 5339, 5340, 5338, -1, + 5340, 5339, 5341, -1, 5341, 5342, 5340, -1, + 5342, 5341, 5343, -1, 5343, 5344, 5342, -1, + 5344, 5343, 5345, -1, 5344, 5345, 5346, -1, + 5344, 5346, 5347, -1, 5347, 5342, 5344, -1, + 5342, 5347, 5348, -1, 5348, 5340, 5342, -1, + 5340, 5348, 5349, -1, 5349, 5338, 5340, -1, + 5338, 5349, 5350, -1, 5350, 5336, 5338, -1, + 5336, 5350, 5351, -1, 5351, 5334, 5336, -1, + 5334, 5351, 5352, -1, 5352, 5332, 5334, -1, + 5332, 5352, 5353, -1, 5353, 5330, 5332, -1, + 5330, 5353, 5354, -1, 5354, 5328, 5330, -1, + 5328, 5354, 5355, -1, 5355, 5326, 5328, -1, + 5326, 5355, 5356, -1, 5356, 5323, 5326, -1, + 5356, 5321, 5323, -1, 5356, 5357, 5321, -1, + 5357, 5356, 5355, -1, 5355, 5358, 5357, -1, + 5358, 5355, 5354, -1, 5354, 5359, 5358, -1, + 5359, 5354, 5353, -1, 5353, 5360, 5359, -1, + 5360, 5353, 5352, -1, 5352, 5361, 5360, -1, + 5361, 5352, 5351, -1, 5351, 5362, 5361, -1, + 5362, 5351, 5350, -1, 5350, 5363, 5362, -1, + 5363, 5350, 5349, -1, 5349, 5364, 5363, -1, + 5364, 5349, 5348, -1, 5348, 5365, 5364, -1, + 5365, 5348, 5347, -1, 5347, 5366, 5365, -1, + 5366, 5347, 5346, -1, 5366, 5346, 5367, -1, + 5367, 5368, 5366, -1, 5368, 5367, 5369, -1, + 5369, 5370, 5368, -1, 5370, 5369, 5371, -1, + 5371, 5372, 5370, -1, 5372, 5371, 5373, -1, + 5373, 5374, 5372, -1, 5374, 5373, 5375, -1, + 5375, 5376, 5374, -1, 5376, 5375, 5377, -1, + 5377, 5378, 5376, -1, 5378, 5377, 5379, -1, + 5379, 5380, 5378, -1, 5380, 5379, 5381, -1, + 5381, 5382, 5380, -1, 5382, 5381, 5383, -1, + 5383, 5384, 5382, -1, 5384, 5383, 5385, -1, + 5385, 5386, 5384, -1, 5386, 5385, 5387, -1, + 5387, 5388, 5386, -1, 5388, 5387, 5389, -1, + 5389, 5390, 5388, -1, 5390, 5389, 5391, -1, + 5391, 5392, 5390, -1, 5392, 5391, 5393, -1, + 5392, 5393, 5394, -1, 5394, 5395, 5392, -1, + 5395, 5394, 5396, -1, 5396, 5397, 5395, -1, + 5397, 5396, 5398, -1, 5398, 5399, 5397, -1, + 5399, 5398, 5400, -1, 5400, 5401, 5399, -1, + 5401, 5400, 5402, -1, 5402, 5403, 5401, -1, + 5403, 5402, 5404, -1, 5404, 5405, 5403, -1, + 5405, 5404, 5406, -1, 5406, 5407, 5405, -1, + 5407, 5406, 5408, -1, 5408, 5409, 5407, -1, + 5409, 5408, 5410, -1, 5410, 5411, 5409, -1, + 5411, 5410, 5412, -1, 5412, 5413, 5411, -1, + 5413, 5412, 5414, -1, 5414, 5415, 5413, -1, + 5415, 5414, 5416, -1, 5416, 5417, 5415, -1, + 5417, 5416, 5418, -1, 5418, 5419, 5417, -1, + 5419, 5418, 5320, -1, 5419, 5320, 5291, -1, + 5291, 5420, 5419, -1, 5420, 5291, 5294, -1, + 5294, 5421, 5420, -1, 5421, 5294, 5296, -1, + 5296, 5422, 5421, -1, 5422, 5296, 5298, -1, + 5298, 5423, 5422, -1, 5423, 5298, 5300, -1, + 5300, 5424, 5423, -1, 5424, 5300, 5302, -1, + 5302, 5425, 5424, -1, 5425, 5302, 5304, -1, + 5304, 5426, 5425, -1, 5426, 5304, 5306, -1, + 5306, 5427, 5426, -1, 5427, 5306, 5307, -1, + 5307, 5428, 5427, -1, 5428, 5307, 5429, -1, + 5430, 5431, 5290, -1, 5431, 5429, 5290, -1, + 5431, 5428, 5429, -1, 5431, 5430, 5428, -1, + 5430, 5432, 5428, -1, 5430, 5290, 5432, -1, + 5432, 5290, 5215, -1, 5215, 5217, 5432, -1, + 5217, 5428, 5432, -1, 5428, 5217, 5218, -1, + 5218, 5427, 5428, -1, 5427, 5218, 5219, -1, + 5219, 5426, 5427, -1, 5426, 5219, 5220, -1, + 5220, 5425, 5426, -1, 5425, 5220, 5221, -1, + 5221, 5424, 5425, -1, 5424, 5221, 5222, -1, + 5222, 5423, 5424, -1, 5423, 5222, 5223, -1, + 5223, 5422, 5423, -1, 5422, 5223, 5224, -1, + 5224, 5421, 5422, -1, 5421, 5224, 5225, -1, + 5225, 5420, 5421, -1, 5420, 5225, 5226, -1, + 5226, 5419, 5420, -1, 5226, 5417, 5419, -1, + 5417, 5226, 5227, -1, 5227, 5415, 5417, -1, + 5415, 5227, 5228, -1, 5228, 5413, 5415, -1, + 5413, 5228, 5229, -1, 5229, 5411, 5413, -1, + 5411, 5229, 5230, -1, 5230, 5409, 5411, -1, + 5409, 5230, 5231, -1, 5231, 5407, 5409, -1, + 5407, 5231, 5232, -1, 5232, 5405, 5407, -1, + 5405, 5232, 5233, -1, 5233, 5403, 5405, -1, + 5403, 5233, 5234, -1, 5234, 5401, 5403, -1, + 5401, 5234, 5235, -1, 5235, 5399, 5401, -1, + 5399, 5235, 5236, -1, 5236, 5397, 5399, -1, + 5397, 5236, 5237, -1, 5237, 5395, 5397, -1, + 5395, 5237, 5238, -1, 5238, 5392, 5395, -1, + 5238, 5390, 5392, -1, 5390, 5238, 5239, -1, + 5239, 5388, 5390, -1, 5388, 5239, 5240, -1, + 5240, 5386, 5388, -1, 5386, 5240, 5241, -1, + 5241, 5384, 5386, -1, 5384, 5241, 5242, -1, + 5242, 5382, 5384, -1, 5382, 5242, 5243, -1, + 5243, 5380, 5382, -1, 5380, 5243, 5244, -1, + 5244, 5378, 5380, -1, 5378, 5244, 5245, -1, + 5245, 5376, 5378, -1, 5376, 5245, 5246, -1, + 5246, 5374, 5376, -1, 5374, 5246, 5247, -1, + 5247, 5372, 5374, -1, 5372, 5247, 5248, -1, + 5248, 5370, 5372, -1, 5370, 5248, 5249, -1, + 5249, 5368, 5370, -1, 5368, 5249, 5251, -1, + 5251, 5366, 5368, -1, 5251, 5365, 5366, -1, + 5365, 5251, 5252, -1, 5252, 5364, 5365, -1, + 5364, 5252, 5254, -1, 5254, 5363, 5364, -1, + 5363, 5254, 5256, -1, 5256, 5362, 5363, -1, + 5362, 5256, 5258, -1, 5258, 5361, 5362, -1, + 5361, 5258, 5260, -1, 5260, 5360, 5361, -1, + 5360, 5260, 5262, -1, 5262, 5359, 5360, -1, + 5359, 5262, 5264, -1, 5264, 5358, 5359, -1, + 5358, 5264, 5266, -1, 5266, 5357, 5358, -1, + 5357, 5266, 5268, -1, 5268, 5321, 5357, -1, + 5321, 5268, 4970, -1, 4970, 4969, 5321, -1, + 5433, 5321, 4969, -1, 5433, 4969, 4967, -1, + 5433, 4967, 5434, -1, 5434, 5321, 5433, -1, + 5434, 5322, 5321, -1, 5434, 4967, 5322, -1, + 5322, 4967, 4966, -1, 4966, 5323, 5322, -1, + 4966, 5324, 5323, -1, 5324, 4966, 4920, -1, + 5435, 5324, 4920, -1, 5435, 5325, 5324, -1, + 5435, 5436, 5325, -1, 5436, 5435, 4920, -1, + 5436, 4920, 4965, -1, 4965, 5325, 5436, -1, + 5325, 4965, 4927, -1, 4927, 5327, 5325, -1, + 5327, 4927, 4929, -1, 4929, 5329, 5327, -1, + 5329, 4929, 4931, -1, 4931, 5331, 5329, -1, + 5331, 4931, 4933, -1, 4933, 5333, 5331, -1, + 5333, 4933, 4935, -1, 4935, 5335, 5333, -1, + 5335, 4935, 4937, -1, 4937, 5337, 5335, -1, + 5337, 4937, 4939, -1, 4939, 5339, 5337, -1, + 5339, 4939, 4941, -1, 4941, 5341, 5339, -1, + 5341, 4941, 4943, -1, 4943, 5343, 5341, -1, + 5343, 4943, 4945, -1, 4945, 5345, 5343, -1, + 5345, 4945, 4947, -1, 5345, 4947, 5437, -1, + 5437, 5346, 5345, -1, 5346, 5437, 5438, -1, + 5438, 5367, 5346, -1, 5367, 5438, 5439, -1, + 5439, 5369, 5367, -1, 5369, 5439, 5440, -1, + 5440, 5371, 5369, -1, 5371, 5440, 5441, -1, + 5441, 5373, 5371, -1, 5373, 5441, 5442, -1, + 5442, 5375, 5373, -1, 5375, 5442, 5443, -1, + 5443, 5377, 5375, -1, 5377, 5443, 5444, -1, + 5444, 5379, 5377, -1, 5379, 5444, 5445, -1, + 5445, 5381, 5379, -1, 5381, 5445, 5446, -1, + 5446, 5383, 5381, -1, 5383, 5446, 5447, -1, + 5447, 5385, 5383, -1, 5385, 5447, 5448, -1, + 5448, 5387, 5385, -1, 5387, 5448, 5449, -1, + 5449, 5389, 5387, -1, 5389, 5449, 5450, -1, + 5450, 5391, 5389, -1, 5391, 5450, 5451, -1, + 5451, 5393, 5391, -1, 5393, 5451, 5452, -1, + 5393, 5452, 5453, -1, 5453, 5394, 5393, -1, + 5394, 5453, 5454, -1, 5454, 5396, 5394, -1, + 5396, 5454, 5455, -1, 5455, 5398, 5396, -1, + 5398, 5455, 5456, -1, 5456, 5400, 5398, -1, + 5400, 5456, 5457, -1, 5457, 5402, 5400, -1, + 5402, 5457, 5458, -1, 5458, 5404, 5402, -1, + 5404, 5458, 5459, -1, 5459, 5406, 5404, -1, + 5406, 5459, 5460, -1, 5460, 5408, 5406, -1, + 5408, 5460, 5461, -1, 5461, 5410, 5408, -1, + 5410, 5461, 5462, -1, 5462, 5412, 5410, -1, + 5412, 5462, 5463, -1, 5463, 5414, 5412, -1, + 5414, 5463, 5464, -1, 5464, 5416, 5414, -1, + 5416, 5464, 5465, -1, 5465, 5418, 5416, -1, + 5418, 5465, 5466, -1, 5466, 5320, 5418, -1, + 5320, 5466, 5467, -1, 5467, 5319, 5320, -1, + 5319, 5467, 4919, -1, 5319, 4919, 4899, -1, + 4899, 5318, 5319, -1, 5318, 4899, 4902, -1, + 4902, 5317, 5318, -1, 5317, 4902, 4904, -1, + 4904, 5316, 5317, -1, 5316, 4904, 4913, -1, + 4913, 5315, 5316, -1, 5315, 4913, 4911, -1, + 4911, 5314, 5315, -1, 5314, 4911, 4909, -1, + 4909, 5313, 5314, -1, 5313, 4909, 4907, -1, + 4907, 5312, 5313, -1, 5312, 4907, 4906, -1, + 4906, 4896, 5312, -1, 4906, 4897, 4896, -1, + 4906, 4905, 4897, -1, 5468, 4897, 4905, -1, + 4905, 5469, 5468, -1, 5469, 4905, 4908, -1, + 4908, 5470, 5469, -1, 5470, 4908, 4910, -1, + 4910, 5471, 5470, -1, 5471, 4910, 4912, -1, + 4912, 5472, 5471, -1, 5472, 4912, 4914, -1, + 4914, 4915, 5472, -1, 5473, 5472, 4915, -1, + 4915, 5474, 5473, -1, 5474, 4915, 4916, -1, + 4916, 5475, 5474, -1, 5475, 4916, 4917, -1, + 4917, 5476, 5475, -1, 5476, 4917, 4918, -1, + 4918, 5477, 5476, -1, 4918, 5478, 5477, -1, + 5478, 4918, 4919, -1, 4919, 5479, 5478, -1, + 5479, 4919, 5467, -1, 5467, 5480, 5479, -1, + 5480, 5467, 5466, -1, 5466, 5481, 5480, -1, + 5481, 5466, 5465, -1, 5465, 5482, 5481, -1, + 5482, 5465, 5464, -1, 5464, 5483, 5482, -1, + 5483, 5464, 5463, -1, 5463, 5484, 5483, -1, + 5484, 5463, 5462, -1, 5462, 5485, 5484, -1, + 5485, 5462, 5461, -1, 5461, 5486, 5485, -1, + 5486, 5461, 5460, -1, 5460, 5487, 5486, -1, + 5487, 5460, 5459, -1, 5459, 5488, 5487, -1, + 5488, 5459, 5458, -1, 5458, 5489, 5488, -1, + 5489, 5458, 5457, -1, 5457, 5490, 5489, -1, + 5490, 5457, 5456, -1, 5456, 5491, 5490, -1, + 5491, 5456, 5455, -1, 5455, 5492, 5491, -1, + 5492, 5455, 5454, -1, 5454, 5493, 5492, -1, + 5493, 5454, 5453, -1, 5453, 5494, 5493, -1, + 5494, 5453, 5452, -1, 5452, 5495, 5494, -1, + 5452, 5496, 5495, -1, 5496, 5452, 5451, -1, + 5451, 5497, 5496, -1, 5497, 5451, 5450, -1, + 5450, 5498, 5497, -1, 5498, 5450, 5449, -1, + 5449, 5499, 5498, -1, 5499, 5449, 5448, -1, + 5448, 5500, 5499, -1, 5500, 5448, 5447, -1, + 5447, 5501, 5500, -1, 5501, 5447, 5446, -1, + 5446, 5502, 5501, -1, 5502, 5446, 5445, -1, + 5445, 5503, 5502, -1, 5503, 5445, 5444, -1, + 5444, 5504, 5503, -1, 5504, 5444, 5443, -1, + 5443, 5505, 5504, -1, 5505, 5443, 5442, -1, + 5442, 5506, 5505, -1, 5506, 5442, 5441, -1, + 5441, 5507, 5506, -1, 5507, 5441, 5440, -1, + 5440, 5508, 5507, -1, 5508, 5440, 5439, -1, + 5439, 5509, 5508, -1, 5509, 5439, 5438, -1, + 5438, 5510, 5509, -1, 5510, 5438, 5437, -1, + 5437, 5511, 5510, -1, 5511, 5437, 4947, -1, + 4947, 5512, 5511, -1, 5512, 4947, 4948, -1, + 4948, 4867, 5512, -1, 4948, 4895, 4867, -1, + 4895, 4948, 4949, -1, 4949, 4894, 4895, -1, + 4894, 4949, 4950, -1, 4950, 4893, 4894, -1, + 4893, 4950, 4951, -1, 4951, 4892, 4893, -1, + 4892, 4951, 4952, -1, 4952, 4891, 4892, -1, + 4891, 4952, 4953, -1, 4953, 4890, 4891, -1, + 4890, 4953, 4954, -1, 4954, 4889, 4890, -1, + 4889, 4954, 4955, -1, 4955, 4888, 4889, -1, + 4888, 4955, 4956, -1, 4956, 4887, 4888, -1, + 4887, 4956, 4957, -1, 4887, 4957, 4960, -1, + 4960, 4886, 4887, -1, 4960, 4885, 4886, -1, + 4885, 4960, 4959, -1, 4959, 4883, 4885, -1, + 4959, 4958, 4883, -1, 4958, 4961, 4883, -1, + 4883, 4961, 4921, -1, 5290, 5513, 4702, -1, + 5513, 5290, 5429, -1, 5513, 5429, 5307, -1, + 5513, 5307, 5309, -1, 5309, 4702, 5513, -1, + 5514, 4702, 5309, -1, 5514, 5309, 5308, -1, + 5514, 5308, 5310, -1, 5310, 4702, 5514, -1, + 5310, 5311, 4702, -1, 5311, 4703, 4702, -1, + 4703, 5311, 4896, -1, 4703, 4896, 4898, -1, + 4898, 4701, 4703, -1, 5515, 4701, 4898, -1, + 5515, 4898, 4897, -1, 5515, 4897, 5516, -1, + 5516, 4701, 5515, -1, 5516, 5517, 4701, -1, + 5516, 4897, 5517, -1, 4897, 5468, 5517, -1, + 5518, 5517, 5468, -1, 5518, 4701, 5517, -1, + 5518, 4700, 4701, -1, 5518, 5468, 4700, -1, + 5468, 4697, 4700, -1, 4697, 5468, 5469, -1, + 5469, 4696, 4697, -1, 4696, 5469, 5470, -1, + 5470, 4695, 4696, -1, 4695, 5470, 5471, -1, + 5471, 4694, 4695, -1, 4694, 5471, 5472, -1, + 5472, 5473, 4694, -1, 5473, 4693, 4694, -1, + 5473, 5519, 4693, -1, 5519, 5473, 5474, -1, + 5474, 5520, 5519, -1, 5520, 5474, 5475, -1, + 5475, 5521, 5520, -1, 5521, 5475, 5476, -1, + 5476, 5522, 5521, -1, 5522, 5476, 5477, -1, + 5522, 5477, 5523, -1, 5522, 5523, 5524, -1, + 5524, 5521, 5522, -1, 5521, 5524, 5525, -1, + 5525, 5520, 5521, -1, 5520, 5525, 5526, -1, + 5526, 5519, 5520, -1, 5519, 5526, 5527, -1, + 5527, 4693, 5519, -1, 4693, 5527, 5528, -1, + 5528, 4691, 4693, -1, 4691, 5528, 5529, -1, + 5529, 4689, 4691, -1, 5529, 4688, 4689, -1, + 4688, 5529, 5530, -1, 5530, 4674, 4688, -1, + 4674, 5530, 4670, -1, 4674, 4670, 5531, -1, + 5531, 4671, 4674, -1, 5531, 4672, 4671, -1, + 5531, 5532, 4672, -1, 5532, 5531, 4670, -1, + 5532, 4670, 4669, -1, 4669, 4672, 5532, -1, + 4672, 4669, 4667, -1, 5533, 4667, 5534, -1, + 4667, 5533, 4664, -1, 5535, 4643, 4640, -1, + 5536, 5535, 4640, -1, 5536, 4640, 4639, -1, + 5536, 4639, 5537, -1, 5537, 5535, 5536, -1, + 5537, 5538, 5535, -1, 5537, 5539, 5538, -1, + 5539, 5537, 4639, -1, 4639, 5540, 5539, -1, + 5540, 4639, 4636, -1, 4636, 5541, 5540, -1, + 5541, 4636, 4638, -1, 4638, 5542, 5541, -1, + 5542, 4638, 5543, -1, 5543, 5544, 5542, -1, + 5544, 5543, 5545, -1, 5545, 5546, 5544, -1, + 5546, 5545, 5547, -1, 5547, 5548, 5546, -1, + 5548, 5547, 5549, -1, 5549, 5550, 5548, -1, + 5551, 5552, 5553, -1, 5551, 5553, 5550, -1, + 5550, 5549, 5551, -1, 5551, 5554, 5555, -1, + 5554, 5551, 5549, -1, 5554, 5549, 5556, -1, + 5556, 5557, 5554, -1, 5556, 5558, 5557, -1, + 5558, 5556, 5559, -1, 5559, 5560, 5558, -1, + 5560, 5559, 5561, -1, 5561, 5562, 5560, -1, + 5562, 5561, 5563, -1, 5563, 5564, 5562, -1, + 5564, 5565, 5566, -1, 5564, 5563, 5565, -1, + 5567, 5568, 5565, -1, 5565, 5569, 5567, -1, + 5569, 5565, 5563, -1, 5563, 5570, 5569, -1, + 5570, 5563, 5561, -1, 5561, 5571, 5570, -1, + 5571, 5561, 5559, -1, 5559, 5572, 5571, -1, + 5572, 5559, 5556, -1, 5572, 5556, 5549, -1, + 5572, 5549, 5547, -1, 5547, 5571, 5572, -1, + 5571, 5547, 5545, -1, 5545, 5570, 5571, -1, + 5570, 5545, 5543, -1, 5543, 5569, 5570, -1, + 5569, 5543, 4638, -1, 4638, 5567, 5569, -1, + 5567, 4638, 4637, -1, 4637, 5573, 5567, -1, + 5573, 4637, 4642, -1, 5573, 4642, 4643, -1, + 5573, 4643, 5574, -1, 5574, 5567, 5573, -1, + 5574, 5568, 5567, -1, 5568, 5574, 4643, -1, + 4643, 4650, 5568, -1, 5575, 5576, 4650, -1, + 5576, 5568, 4650, -1, 5576, 5565, 5568, -1, + 5576, 5575, 5565, -1, 5575, 5566, 5565, -1, + 5566, 5575, 4650, -1, 5566, 4650, 4649, -1, + 4649, 5564, 5566, -1, 4649, 4646, 5564, -1, + 5564, 4646, 4645, -1, 4645, 5562, 5564, -1, + 5562, 4645, 5577, -1, 5577, 5560, 5562, -1, + 5560, 5577, 5578, -1, 5578, 5558, 5560, -1, + 5558, 5578, 5579, -1, 5579, 5557, 5558, -1, + 5579, 5580, 5557, -1, 5579, 5581, 5580, -1, + 5581, 5579, 5578, -1, 5578, 5582, 5581, -1, + 5582, 5578, 5577, -1, 5577, 5583, 5582, -1, + 5583, 5577, 4645, -1, 4645, 4647, 5583, -1, + 5584, 5583, 4647, -1, 5584, 4647, 4648, -1, + 5584, 4648, 4652, -1, 4652, 5583, 5584, -1, + 4652, 4651, 5583, -1, 5583, 4651, 4654, -1, + 4654, 5582, 5583, -1, 5582, 4654, 5585, -1, + 5585, 5581, 5582, -1, 5581, 5585, 5586, -1, + 5586, 5580, 5581, -1, 5580, 5586, 5587, -1, + 5580, 5587, 5588, -1, 5588, 5557, 5580, -1, + 5557, 5588, 5589, -1, 5589, 5554, 5557, -1, + 5589, 5555, 5554, -1, 5589, 5590, 5555, -1, + 5590, 5589, 5588, -1, 5588, 5591, 5590, -1, + 5591, 5588, 5587, -1, 5587, 5592, 5591, -1, + 5587, 5593, 5592, -1, 5593, 5587, 5586, -1, + 5586, 5594, 5593, -1, 5594, 5586, 5585, -1, + 5585, 5595, 5594, -1, 5595, 5585, 4654, -1, + 4654, 4655, 5595, -1, 4658, 4657, 5595, -1, + 5595, 4657, 4660, -1, 4660, 5594, 5595, -1, + 5594, 4660, 5596, -1, 5596, 5593, 5594, -1, + 5593, 5596, 5597, -1, 5597, 5592, 5593, -1, + 5592, 5597, 5598, -1, 5592, 5598, 5599, -1, + 5599, 5591, 5592, -1, 5591, 5599, 5600, -1, + 5600, 5590, 5591, -1, 5590, 5600, 5601, -1, + 5601, 5555, 5590, -1, 5601, 4603, 5555, -1, + 5601, 4635, 4603, -1, 4635, 5601, 5600, -1, + 5600, 4634, 4635, -1, 4634, 5600, 5599, -1, + 5599, 4633, 4634, -1, 4633, 5599, 5598, -1, + 5598, 4629, 4633, -1, 5598, 4627, 4629, -1, + 4627, 5598, 5597, -1, 5597, 4626, 4627, -1, + 4626, 5597, 5596, -1, 5596, 4624, 4626, -1, + 4624, 5596, 4660, -1, 4660, 4661, 4624, -1, + 5602, 4624, 4661, -1, 5602, 4661, 4662, -1, + 5602, 4662, 5603, -1, 5603, 4624, 5602, -1, + 5603, 4625, 4624, -1, 5603, 4662, 4625, -1, + 4625, 4662, 4663, -1, 4663, 4621, 4625, -1, + 4663, 4665, 4621, -1, 4665, 4622, 4621, -1, + 4622, 4665, 4664, -1, 4622, 4664, 5604, -1, + 5604, 4620, 4622, -1, 5604, 4632, 4620, -1, + 5604, 4664, 4632, -1, 4632, 4664, 5533, -1, + 5533, 4618, 4632, -1, 5533, 5534, 4618, -1, + 5534, 4619, 4618, -1, 4619, 5534, 4667, -1, + 4619, 4667, 4666, -1, 4666, 4617, 4619, -1, + 4666, 4668, 4617, -1, 4617, 4668, 4670, -1, + 4670, 4615, 4617, -1, 4615, 4670, 5530, -1, + 5530, 4614, 4615, -1, 4614, 5530, 5529, -1, + 4614, 5529, 5528, -1, 5528, 4612, 4614, -1, + 4612, 5528, 5527, -1, 5527, 4610, 4612, -1, + 4610, 5527, 5526, -1, 5526, 4608, 4610, -1, + 4608, 5526, 5525, -1, 5525, 4606, 4608, -1, + 4606, 5525, 5524, -1, 5524, 4604, 4606, -1, + 4604, 5524, 5523, -1, 5523, 4602, 4604, -1, + 5523, 5605, 4602, -1, 5605, 5523, 5477, -1, + 5477, 5606, 5605, -1, 5606, 5477, 5478, -1, + 5478, 5607, 5606, -1, 5607, 5478, 5479, -1, + 5479, 5608, 5607, -1, 5608, 5479, 5480, -1, + 5480, 5609, 5608, -1, 5609, 5480, 5481, -1, + 5481, 5610, 5609, -1, 5610, 5481, 5482, -1, + 5482, 5611, 5610, -1, 5611, 5482, 5483, -1, + 5483, 5612, 5611, -1, 5612, 5483, 5484, -1, + 5484, 5613, 5612, -1, 5613, 5484, 5485, -1, + 5485, 5614, 5613, -1, 5614, 5485, 5486, -1, + 5486, 5615, 5614, -1, 5615, 5486, 5487, -1, + 5487, 5616, 5615, -1, 5616, 5487, 5488, -1, + 5488, 5617, 5616, -1, 5617, 5488, 5489, -1, + 5489, 5618, 5617, -1, 5618, 5489, 5490, -1, + 5490, 5619, 5618, -1, 5619, 5490, 5491, -1, + 5491, 5620, 5619, -1, 5620, 5491, 5492, -1, + 5492, 5621, 5620, -1, 5621, 5492, 5493, -1, + 5493, 5622, 5621, -1, 5622, 5493, 5494, -1, + 5494, 5623, 5622, -1, 5623, 5494, 5495, -1, + 5495, 5624, 5623, -1, 5495, 5625, 5624, -1, + 5625, 5495, 5496, -1, 5496, 5626, 5625, -1, + 5626, 5496, 5497, -1, 5497, 5627, 5626, -1, + 5627, 5497, 5498, -1, 5498, 5628, 5627, -1, + 5628, 5498, 5499, -1, 5499, 5629, 5628, -1, + 5629, 5499, 5500, -1, 5500, 5630, 5629, -1, + 5630, 5500, 5501, -1, 5501, 5631, 5630, -1, + 5631, 5501, 5502, -1, 5502, 5632, 5631, -1, + 5632, 5502, 5503, -1, 5503, 5633, 5632, -1, + 5633, 5503, 5504, -1, 5504, 5634, 5633, -1, + 5634, 5504, 5505, -1, 5505, 5635, 5634, -1, + 5635, 5505, 5506, -1, 5506, 5636, 5635, -1, + 5636, 5506, 5507, -1, 5507, 5637, 5636, -1, + 5637, 5507, 5508, -1, 5508, 5638, 5637, -1, + 5638, 5508, 5509, -1, 5509, 5639, 5638, -1, + 5639, 5509, 5510, -1, 5510, 5640, 5639, -1, + 5640, 5510, 5511, -1, 5511, 5641, 5640, -1, + 5641, 5511, 5512, -1, 5512, 5642, 5641, -1, + 5642, 5512, 4867, -1, 4867, 5643, 5642, -1, + 5643, 4867, 4865, -1, 4865, 5644, 5643, -1, + 4865, 4864, 5644, -1, 5645, 5646, 5647, -1, + 5646, 5645, 5648, -1, 5648, 5649, 5646, -1, + 5649, 5648, 5650, -1, 5650, 5651, 5649, -1, + 5650, 5652, 5651, -1, 5652, 5650, 5653, -1, + 5653, 5654, 5652, -1, 5654, 5653, 5655, -1, + 5655, 5656, 5654, -1, 5656, 5655, 5657, -1, + 5657, 5658, 5656, -1, 5658, 5657, 5659, -1, + 5659, 5660, 5658, -1, 5660, 5659, 5661, -1, + 5661, 5662, 5660, -1, 5662, 5661, 5663, -1, + 5662, 5663, 5644, -1, 5662, 5644, 4864, -1, + 4864, 5660, 5662, -1, 5660, 4864, 4862, -1, + 4862, 5658, 5660, -1, 5658, 4862, 4860, -1, + 4860, 5656, 5658, -1, 5656, 4860, 4858, -1, + 4858, 5654, 5656, -1, 5654, 4858, 4856, -1, + 4856, 5652, 5654, -1, 5652, 4856, 4854, -1, + 4854, 5651, 5652, -1, 5651, 4854, 4852, -1, + 5651, 4852, 4851, -1, 4851, 5649, 5651, -1, + 5649, 4851, 4705, -1, 4705, 5646, 5649, -1, + 4705, 5664, 5646, -1, 5664, 4705, 4707, -1, + 5664, 4707, 4708, -1, 5664, 4708, 4837, -1, + 4837, 5646, 5664, -1, 4837, 5647, 5646, -1, + 5647, 4837, 4711, -1, 5647, 4711, 4710, -1, + 4710, 5645, 5647, -1, 4710, 4709, 5645, -1, + 5645, 4709, 4713, -1, 5645, 4713, 4742, -1, + 4742, 5648, 5645, -1, 5648, 4742, 4744, -1, + 4744, 5650, 5648, -1, 4744, 5653, 5650, -1, + 5653, 4744, 4745, -1, 4745, 5655, 5653, -1, + 5655, 4745, 4828, -1, 4828, 5657, 5655, -1, + 5657, 4828, 4829, -1, 4829, 5659, 5657, -1, + 5659, 4829, 4830, -1, 4830, 5661, 5659, -1, + 5661, 4830, 4831, -1, 4831, 5663, 5661, -1, + 5663, 4831, 4832, -1, 5663, 4832, 5665, -1, + 5665, 5644, 5663, -1, 5644, 5665, 5666, -1, + 5666, 5643, 5644, -1, 5643, 5666, 5667, -1, + 5667, 5642, 5643, -1, 5642, 5667, 5668, -1, + 5668, 5641, 5642, -1, 5641, 5668, 5669, -1, + 5669, 5640, 5641, -1, 5640, 5669, 5670, -1, + 5670, 5639, 5640, -1, 5639, 5670, 5671, -1, + 5671, 5638, 5639, -1, 5638, 5671, 5672, -1, + 5672, 5637, 5638, -1, 5637, 5672, 5673, -1, + 5673, 5636, 5637, -1, 5636, 5673, 5674, -1, + 5674, 5635, 5636, -1, 5635, 5674, 5675, -1, + 5675, 5634, 5635, -1, 5634, 5675, 5676, -1, + 5676, 5633, 5634, -1, 5633, 5676, 5677, -1, + 5677, 5632, 5633, -1, 5632, 5677, 5678, -1, + 5678, 5631, 5632, -1, 5631, 5678, 5679, -1, + 5679, 5630, 5631, -1, 5630, 5679, 5680, -1, + 5680, 5629, 5630, -1, 5629, 5680, 5681, -1, + 5681, 5628, 5629, -1, 5628, 5681, 5682, -1, + 5682, 5627, 5628, -1, 5627, 5682, 5683, -1, + 5683, 5626, 5627, -1, 5626, 5683, 5684, -1, + 5684, 5625, 5626, -1, 5625, 5684, 5685, -1, + 5685, 5624, 5625, -1, 5624, 5685, 5686, -1, + 5624, 5686, 5687, -1, 5687, 5623, 5624, -1, + 5623, 5687, 5688, -1, 5688, 5622, 5623, -1, + 5622, 5688, 5689, -1, 5689, 5621, 5622, -1, + 5621, 5689, 5690, -1, 5690, 5620, 5621, -1, + 5620, 5690, 5691, -1, 5691, 5619, 5620, -1, + 5619, 5691, 5692, -1, 5692, 5618, 5619, -1, + 5618, 5692, 5693, -1, 5693, 5617, 5618, -1, + 5617, 5693, 5694, -1, 5694, 5616, 5617, -1, + 5616, 5694, 5695, -1, 5695, 5615, 5616, -1, + 5615, 5695, 5696, -1, 5696, 5614, 5615, -1, + 5614, 5696, 5697, -1, 5697, 5613, 5614, -1, + 5613, 5697, 5698, -1, 5698, 5612, 5613, -1, + 5612, 5698, 5699, -1, 5699, 5611, 5612, -1, + 5611, 5699, 5700, -1, 5700, 5610, 5611, -1, + 5610, 5700, 5701, -1, 5701, 5609, 5610, -1, + 5609, 5701, 5702, -1, 5702, 5608, 5609, -1, + 5608, 5702, 5703, -1, 5703, 5607, 5608, -1, + 5607, 5703, 5704, -1, 5704, 5606, 5607, -1, + 5606, 5704, 5705, -1, 5705, 5605, 5606, -1, + 5605, 5705, 5706, -1, 5706, 4602, 5605, -1, + 4602, 5706, 5707, -1, 5707, 4603, 4602, -1, + 4603, 5707, 5708, -1, 5708, 5555, 4603, -1, + 5708, 5551, 5555, -1, 5708, 5552, 5551, -1, + 5552, 5708, 5707, -1, 5707, 5709, 5552, -1, + 5709, 5707, 5706, -1, 5706, 5710, 5709, -1, + 5710, 5706, 5705, -1, 5705, 5711, 5710, -1, + 5711, 5705, 5704, -1, 5704, 5712, 5711, -1, + 5712, 5704, 5703, -1, 5703, 5713, 5712, -1, + 5713, 5703, 5702, -1, 5702, 5714, 5713, -1, + 5714, 5702, 5701, -1, 5701, 5715, 5714, -1, + 5715, 5701, 5700, -1, 5700, 5716, 5715, -1, + 5716, 5700, 5699, -1, 5699, 5717, 5716, -1, + 5717, 5699, 5698, -1, 5698, 5718, 5717, -1, + 5718, 5698, 5697, -1, 5697, 5719, 5718, -1, + 5719, 5697, 5696, -1, 5696, 5720, 5719, -1, + 5720, 5696, 5695, -1, 5695, 5721, 5720, -1, + 5721, 5695, 5694, -1, 5694, 5722, 5721, -1, + 5722, 5694, 5693, -1, 5693, 5723, 5722, -1, + 5723, 5693, 5692, -1, 5692, 5724, 5723, -1, + 5724, 5692, 5691, -1, 5691, 5725, 5724, -1, + 5725, 5691, 5690, -1, 5690, 5726, 5725, -1, + 5726, 5690, 5689, -1, 5689, 5727, 5726, -1, + 5727, 5689, 5688, -1, 5688, 5728, 5727, -1, + 5728, 5688, 5687, -1, 5687, 5729, 5728, -1, + 5729, 5687, 5686, -1, 5686, 5730, 5729, -1, + 5686, 5731, 5730, -1, 5731, 5686, 5685, -1, + 5685, 5732, 5731, -1, 5732, 5685, 5684, -1, + 5684, 5733, 5732, -1, 5733, 5684, 5683, -1, + 5683, 5734, 5733, -1, 5734, 5683, 5682, -1, + 5682, 5735, 5734, -1, 5735, 5682, 5681, -1, + 5681, 5736, 5735, -1, 5736, 5681, 5680, -1, + 5680, 5737, 5736, -1, 5737, 5680, 5679, -1, + 5679, 5738, 5737, -1, 5738, 5679, 5678, -1, + 5678, 5739, 5738, -1, 5739, 5678, 5677, -1, + 5677, 5740, 5739, -1, 5740, 5677, 5676, -1, + 5676, 5741, 5740, -1, 5741, 5676, 5675, -1, + 5675, 5742, 5741, -1, 5742, 5675, 5674, -1, + 5674, 5743, 5742, -1, 5743, 5674, 5673, -1, + 5673, 5744, 5743, -1, 5744, 5673, 5672, -1, + 5672, 5745, 5744, -1, 5745, 5672, 5671, -1, + 5671, 5746, 5745, -1, 5746, 5671, 5670, -1, + 5670, 5747, 5746, -1, 5747, 5670, 5669, -1, + 5669, 5748, 5747, -1, 5748, 5669, 5668, -1, + 5668, 5749, 5748, -1, 5749, 5668, 5667, -1, + 5667, 5750, 5749, -1, 5750, 5667, 5666, -1, + 5666, 5751, 5750, -1, 5751, 5666, 5665, -1, + 5665, 5752, 5751, -1, 5752, 5665, 4832, -1, + 4832, 4714, 5752, -1, 4714, 4716, 5752, -1, + 5753, 5752, 4716, -1, 5753, 5751, 5752, -1, + 5751, 5753, 5754, -1, 5754, 5750, 5751, -1, + 5750, 5754, 5755, -1, 5755, 5749, 5750, -1, + 5749, 5755, 5756, -1, 5756, 5748, 5749, -1, + 5748, 5756, 5757, -1, 5757, 5747, 5748, -1, + 5747, 5757, 5758, -1, 5758, 5746, 5747, -1, + 5746, 5758, 5759, -1, 5759, 5745, 5746, -1, + 5745, 5759, 5760, -1, 5760, 5744, 5745, -1, + 5744, 5760, 5761, -1, 5761, 5743, 5744, -1, + 5743, 5761, 5762, -1, 5762, 5742, 5743, -1, + 5742, 5762, 5763, -1, 5763, 5741, 5742, -1, + 5741, 5763, 5764, -1, 5764, 5740, 5741, -1, + 5740, 5764, 5765, -1, 5765, 5739, 5740, -1, + 5739, 5765, 5766, -1, 5766, 5738, 5739, -1, + 5738, 5766, 5767, -1, 5767, 5737, 5738, -1, + 5737, 5767, 5768, -1, 5768, 5736, 5737, -1, + 5736, 5768, 5769, -1, 5769, 5735, 5736, -1, + 5735, 5769, 5770, -1, 5770, 5734, 5735, -1, + 5734, 5770, 5771, -1, 5771, 5733, 5734, -1, + 5733, 5771, 5772, -1, 5772, 5732, 5733, -1, + 5732, 5772, 5773, -1, 5773, 5731, 5732, -1, + 5731, 5773, 5774, -1, 5774, 5730, 5731, -1, + 5730, 5774, 5775, -1, 5730, 5775, 5776, -1, + 5776, 5729, 5730, -1, 5729, 5776, 5777, -1, + 5777, 5728, 5729, -1, 5728, 5777, 5778, -1, + 5778, 5727, 5728, -1, 5727, 5778, 5779, -1, + 5779, 5726, 5727, -1, 5726, 5779, 5780, -1, + 5780, 5725, 5726, -1, 5725, 5780, 5781, -1, + 5781, 5724, 5725, -1, 5724, 5781, 5782, -1, + 5782, 5723, 5724, -1, 5723, 5782, 5783, -1, + 5783, 5722, 5723, -1, 5722, 5783, 5784, -1, + 5784, 5721, 5722, -1, 5721, 5784, 5785, -1, + 5785, 5720, 5721, -1, 5720, 5785, 5786, -1, + 5786, 5719, 5720, -1, 5719, 5786, 5787, -1, + 5787, 5718, 5719, -1, 5718, 5787, 5788, -1, + 5788, 5717, 5718, -1, 5717, 5788, 5789, -1, + 5789, 5716, 5717, -1, 5716, 5789, 5790, -1, + 5790, 5715, 5716, -1, 5715, 5790, 5791, -1, + 5791, 5714, 5715, -1, 5714, 5791, 5792, -1, + 5792, 5713, 5714, -1, 5713, 5792, 5793, -1, + 5793, 5712, 5713, -1, 5712, 5793, 5794, -1, + 5794, 5711, 5712, -1, 5711, 5794, 5795, -1, + 5795, 5710, 5711, -1, 5710, 5795, 5796, -1, + 5796, 5709, 5710, -1, 5709, 5796, 5797, -1, + 5797, 5552, 5709, -1, 5797, 5553, 5552, -1, + 5797, 5798, 5553, -1, 5798, 5797, 5796, -1, + 5796, 5799, 5798, -1, 5799, 5796, 5795, -1, + 5795, 5800, 5799, -1, 5800, 5795, 5794, -1, + 5794, 5801, 5800, -1, 5801, 5794, 5793, -1, + 5793, 5802, 5801, -1, 5802, 5793, 5792, -1, + 5792, 5803, 5802, -1, 5803, 5792, 5791, -1, + 5791, 5804, 5803, -1, 5804, 5791, 5790, -1, + 5790, 5805, 5804, -1, 5805, 5790, 5789, -1, + 5789, 5806, 5805, -1, 5806, 5789, 5788, -1, + 5788, 5807, 5806, -1, 5807, 5788, 5787, -1, + 5787, 5808, 5807, -1, 5808, 5787, 5786, -1, + 5786, 5809, 5808, -1, 5809, 5786, 5785, -1, + 5785, 5810, 5809, -1, 5810, 5785, 5784, -1, + 5784, 5811, 5810, -1, 5811, 5784, 5783, -1, + 5783, 5812, 5811, -1, 5812, 5783, 5782, -1, + 5782, 5813, 5812, -1, 5813, 5782, 5781, -1, + 5781, 5814, 5813, -1, 5814, 5781, 5780, -1, + 5780, 5815, 5814, -1, 5815, 5780, 5779, -1, + 5779, 5816, 5815, -1, 5816, 5779, 5778, -1, + 5778, 5817, 5816, -1, 5817, 5778, 5777, -1, + 5777, 5818, 5817, -1, 5818, 5777, 5776, -1, + 5776, 5819, 5818, -1, 5819, 5776, 5775, -1, + 5775, 5820, 5819, -1, 5775, 5821, 5820, -1, + 5821, 5775, 5774, -1, 5774, 5822, 5821, -1, + 5822, 5774, 5773, -1, 5773, 5823, 5822, -1, + 5823, 5773, 5772, -1, 5772, 5824, 5823, -1, + 5824, 5772, 5771, -1, 5771, 5825, 5824, -1, + 5825, 5771, 5770, -1, 5770, 5826, 5825, -1, + 5826, 5770, 5769, -1, 5769, 5827, 5826, -1, + 5827, 5769, 5768, -1, 5768, 5828, 5827, -1, + 5828, 5768, 5767, -1, 5767, 5829, 5828, -1, + 5829, 5767, 5766, -1, 5766, 5830, 5829, -1, + 5830, 5766, 5765, -1, 5765, 5831, 5830, -1, + 5831, 5765, 5764, -1, 5764, 5832, 5831, -1, + 5832, 5764, 5763, -1, 5763, 5833, 5832, -1, + 5833, 5763, 5762, -1, 5762, 5834, 5833, -1, + 5834, 5762, 5761, -1, 5761, 5835, 5834, -1, + 5835, 5761, 5760, -1, 5760, 5836, 5835, -1, + 5836, 5760, 5759, -1, 5759, 5837, 5836, -1, + 5837, 5759, 5758, -1, 5758, 5838, 5837, -1, + 5838, 5758, 5757, -1, 5757, 5839, 5838, -1, + 5839, 5757, 5756, -1, 5756, 5840, 5839, -1, + 5840, 5756, 5755, -1, 5755, 5841, 5840, -1, + 5841, 5755, 5754, -1, 5754, 5842, 5841, -1, + 5842, 5754, 5753, -1, 5753, 4716, 5842, -1, + 4716, 4555, 5842, -1, 4716, 4600, 4555, -1, + 4600, 4716, 4715, -1, 4715, 4599, 4600, -1, + 4599, 4715, 4735, -1, 4735, 4598, 4599, -1, + 4598, 4735, 4733, -1, 4733, 4597, 4598, -1, + 4597, 4733, 4731, -1, 4731, 4596, 4597, -1, + 4596, 4731, 4729, -1, 4729, 4585, 4596, -1, + 4585, 4729, 4727, -1, 4727, 4586, 4585, -1, + 4586, 4727, 4725, -1, 4725, 4588, 4586, -1, + 4588, 4725, 4724, -1, 4724, 4590, 4588, -1, + 4590, 4724, 4723, -1, 4723, 4592, 4590, -1, + 4723, 4594, 4592, -1, 4723, 4722, 4594, -1, + 4722, 4719, 4594, -1, 4594, 4719, 4718, -1, + 2957, 4595, 4594, -1, 4595, 2957, 2956, -1, + 2956, 4581, 4595, -1, 2956, 2955, 4581, -1, + 2955, 4582, 4581, -1, 4582, 2955, 2957, -1, + 4582, 2957, 4554, -1, 4554, 4583, 4582, -1, + 4554, 4553, 4583, -1, 4583, 4553, 2958, -1, + 4583, 2958, 2962, -1, 2962, 4580, 4583, -1, + 4580, 2962, 2964, -1, 2964, 4578, 4580, -1, + 4578, 2964, 4543, -1, 4543, 4576, 4578, -1, + 4576, 4543, 4542, -1, 4542, 4574, 4576, -1, + 4574, 4542, 4541, -1, 4541, 4572, 4574, -1, + 4572, 4541, 4540, -1, 4540, 4570, 4572, -1, + 4570, 4540, 4539, -1, 4539, 4568, 4570, -1, + 4568, 4539, 4538, -1, 4538, 4566, 4568, -1, + 4566, 4538, 4537, -1, 4537, 4564, 4566, -1, + 4564, 4537, 4536, -1, 4536, 4562, 4564, -1, + 4562, 4536, 4535, -1, 4535, 4561, 4562, -1, + 4561, 4535, 2966, -1, 2966, 4559, 4561, -1, + 4559, 2966, 2965, -1, 2965, 5843, 4559, -1, + 5843, 2965, 2968, -1, 2968, 5844, 5843, -1, + 5844, 2968, 2970, -1, 2970, 5845, 5844, -1, + 5845, 2970, 2972, -1, 2972, 5846, 5845, -1, + 5846, 2972, 2974, -1, 2974, 5847, 5846, -1, + 5847, 2974, 2976, -1, 2976, 5848, 5847, -1, + 5848, 2976, 2978, -1, 2978, 5849, 5848, -1, + 5849, 2978, 2980, -1, 2980, 5850, 5849, -1, + 5850, 2980, 2982, -1, 2982, 5851, 5850, -1, + 5851, 2982, 2984, -1, 2984, 5852, 5851, -1, + 5852, 2984, 2986, -1, 2986, 5853, 5852, -1, + 5853, 2986, 2988, -1, 2988, 5854, 5853, -1, + 5854, 2988, 2990, -1, 2990, 5855, 5854, -1, + 5855, 2990, 2992, -1, 2992, 5856, 5855, -1, + 5856, 2992, 2994, -1, 2994, 5857, 5856, -1, + 5857, 2994, 2996, -1, 2996, 5858, 5857, -1, + 5858, 2996, 2998, -1, 2998, 5859, 5858, -1, + 5859, 2998, 3000, -1, 3000, 5860, 5859, -1, + 5860, 3000, 3002, -1, 3002, 5861, 5860, -1, + 5861, 3002, 3004, -1, 3004, 5862, 5861, -1, + 5862, 3004, 3006, -1, 3006, 5863, 5862, -1, + 5863, 3006, 3008, -1, 3008, 5864, 5863, -1, + 5864, 3008, 3010, -1, 3010, 5865, 5864, -1, + 5865, 3010, 3012, -1, 5865, 3012, 3015, -1, + 3015, 5866, 5865, -1, 5866, 3015, 3017, -1, + 3017, 5867, 5866, -1, 5867, 3017, 3019, -1, + 3019, 5868, 5867, -1, 5868, 3019, 3021, -1, + 3021, 5869, 5868, -1, 5869, 3021, 3023, -1, + 3023, 5870, 5869, -1, 5870, 3023, 3025, -1, + 3025, 5871, 5870, -1, 5871, 3025, 3027, -1, + 3027, 5872, 5871, -1, 5872, 3027, 3029, -1, + 3029, 5873, 5872, -1, 5873, 3029, 3031, -1, + 3031, 5874, 5873, -1, 5874, 3031, 3033, -1, + 3033, 5875, 5874, -1, 5875, 3033, 3035, -1, + 3035, 5876, 5875, -1, 5876, 3035, 3037, -1, + 3037, 5877, 5876, -1, 5877, 3037, 3039, -1, + 3039, 5878, 5877, -1, 5878, 3039, 3041, -1, + 3041, 5879, 5878, -1, 5879, 3041, 3043, -1, + 3043, 5880, 5879, -1, 5880, 3043, 3045, -1, + 3045, 5881, 5880, -1, 5881, 3045, 3047, -1, + 3047, 5882, 5881, -1, 5882, 3047, 3049, -1, + 3049, 5883, 5882, -1, 5883, 3049, 3051, -1, + 3051, 5884, 5883, -1, 5884, 3051, 3053, -1, + 3053, 5885, 5884, -1, 5885, 3053, 3055, -1, + 3055, 5886, 5885, -1, 5886, 3055, 3057, -1, + 3057, 5887, 5886, -1, 5887, 3057, 3059, -1, + 3059, 5888, 5887, -1, 5888, 3059, 3061, -1, + 3061, 3064, 5888, -1, 5889, 5888, 3064, -1, + 5888, 5889, 5890, -1, 5890, 5887, 5888, -1, + 5887, 5890, 5891, -1, 5891, 5886, 5887, -1, + 5886, 5891, 5892, -1, 5892, 5885, 5886, -1, + 5885, 5892, 5893, -1, 5893, 5884, 5885, -1, + 5884, 5893, 5894, -1, 5894, 5883, 5884, -1, + 5883, 5894, 5895, -1, 5895, 5882, 5883, -1, + 5882, 5895, 5896, -1, 5896, 5881, 5882, -1, + 5881, 5896, 5897, -1, 5897, 5880, 5881, -1, + 5880, 5897, 5898, -1, 5898, 5879, 5880, -1, + 5879, 5898, 5899, -1, 5899, 5878, 5879, -1, + 5878, 5899, 5900, -1, 5900, 5877, 5878, -1, + 5877, 5900, 5901, -1, 5901, 5876, 5877, -1, + 5876, 5901, 5902, -1, 5902, 5875, 5876, -1, + 5875, 5902, 5903, -1, 5903, 5874, 5875, -1, + 5874, 5903, 5904, -1, 5904, 5873, 5874, -1, + 5873, 5904, 5905, -1, 5905, 5872, 5873, -1, + 5872, 5905, 5906, -1, 5906, 5871, 5872, -1, + 5871, 5906, 5907, -1, 5907, 5870, 5871, -1, + 5870, 5907, 5908, -1, 5908, 5869, 5870, -1, + 5869, 5908, 5909, -1, 5909, 5868, 5869, -1, + 5868, 5909, 5910, -1, 5910, 5867, 5868, -1, + 5867, 5910, 5911, -1, 5911, 5866, 5867, -1, + 5866, 5911, 5912, -1, 5912, 5865, 5866, -1, + 5912, 5864, 5865, -1, 5864, 5912, 5913, -1, + 5913, 5863, 5864, -1, 5863, 5913, 5914, -1, + 5914, 5862, 5863, -1, 5862, 5914, 5915, -1, + 5915, 5861, 5862, -1, 5861, 5915, 5916, -1, + 5916, 5860, 5861, -1, 5860, 5916, 5917, -1, + 5917, 5859, 5860, -1, 5859, 5917, 5918, -1, + 5918, 5858, 5859, -1, 5858, 5918, 5919, -1, + 5919, 5857, 5858, -1, 5857, 5919, 5920, -1, + 5920, 5856, 5857, -1, 5856, 5920, 5921, -1, + 5921, 5855, 5856, -1, 5855, 5921, 5922, -1, + 5922, 5854, 5855, -1, 5854, 5922, 5923, -1, + 5923, 5853, 5854, -1, 5853, 5923, 5924, -1, + 5924, 5852, 5853, -1, 5852, 5924, 5925, -1, + 5925, 5851, 5852, -1, 5851, 5925, 5926, -1, + 5926, 5850, 5851, -1, 5850, 5926, 5927, -1, + 5927, 5849, 5850, -1, 5849, 5927, 5928, -1, + 5928, 5848, 5849, -1, 5848, 5928, 5929, -1, + 5929, 5847, 5848, -1, 5847, 5929, 5930, -1, + 5930, 5846, 5847, -1, 5846, 5930, 5931, -1, + 5931, 5845, 5846, -1, 5845, 5931, 5932, -1, + 5932, 5844, 5845, -1, 5844, 5932, 5933, -1, + 5933, 5843, 5844, -1, 5843, 5933, 5934, -1, + 5934, 4559, 5843, -1, 5934, 4560, 4559, -1, + 5934, 5935, 4560, -1, 5935, 5934, 5933, -1, + 5933, 5936, 5935, -1, 5936, 5933, 5932, -1, + 5932, 5937, 5936, -1, 5937, 5932, 5931, -1, + 5931, 5938, 5937, -1, 5938, 5931, 5930, -1, + 5930, 5939, 5938, -1, 5939, 5930, 5929, -1, + 5929, 5940, 5939, -1, 5940, 5929, 5928, -1, + 5928, 5941, 5940, -1, 5941, 5928, 5927, -1, + 5927, 5942, 5941, -1, 5942, 5927, 5926, -1, + 5926, 5943, 5942, -1, 5943, 5926, 5925, -1, + 5925, 5944, 5943, -1, 5944, 5925, 5924, -1, + 5924, 5945, 5944, -1, 5945, 5924, 5923, -1, + 5923, 5946, 5945, -1, 5946, 5923, 5922, -1, + 5922, 5947, 5946, -1, 5947, 5922, 5921, -1, + 5921, 5948, 5947, -1, 5948, 5921, 5920, -1, + 5920, 5949, 5948, -1, 5949, 5920, 5919, -1, + 5919, 5950, 5949, -1, 5950, 5919, 5918, -1, + 5918, 5951, 5950, -1, 5951, 5918, 5917, -1, + 5917, 5952, 5951, -1, 5952, 5917, 5916, -1, + 5916, 5953, 5952, -1, 5953, 5916, 5915, -1, + 5915, 5954, 5953, -1, 5954, 5915, 5914, -1, + 5914, 5955, 5954, -1, 5955, 5914, 5913, -1, + 5913, 5956, 5955, -1, 5956, 5913, 5912, -1, + 5956, 5912, 5911, -1, 5911, 5957, 5956, -1, + 5957, 5911, 5910, -1, 5910, 5958, 5957, -1, + 5958, 5910, 5909, -1, 5909, 5959, 5958, -1, + 5959, 5909, 5908, -1, 5908, 5960, 5959, -1, + 5960, 5908, 5907, -1, 5907, 5961, 5960, -1, + 5961, 5907, 5906, -1, 5906, 5962, 5961, -1, + 5962, 5906, 5905, -1, 5905, 5963, 5962, -1, + 5963, 5905, 5904, -1, 5904, 5964, 5963, -1, + 5964, 5904, 5903, -1, 5903, 5965, 5964, -1, + 5965, 5903, 5902, -1, 5902, 5966, 5965, -1, + 5966, 5902, 5901, -1, 5901, 5967, 5966, -1, + 5967, 5901, 5900, -1, 5900, 5968, 5967, -1, + 5968, 5900, 5899, -1, 5899, 5969, 5968, -1, + 5969, 5899, 5898, -1, 5898, 5970, 5969, -1, + 5970, 5898, 5897, -1, 5897, 5971, 5970, -1, + 5971, 5897, 5896, -1, 5896, 5972, 5971, -1, + 5972, 5896, 5895, -1, 5895, 5973, 5972, -1, + 5973, 5895, 5894, -1, 5894, 5974, 5973, -1, + 5974, 5894, 5893, -1, 5893, 5975, 5974, -1, + 5975, 5893, 5892, -1, 5892, 5976, 5975, -1, + 5976, 5892, 5891, -1, 5891, 5977, 5976, -1, + 5977, 5891, 5890, -1, 5890, 5978, 5977, -1, + 5978, 5890, 5889, -1, 5889, 5979, 5978, -1, + 5979, 5889, 3064, -1, 5979, 3064, 3063, -1, + 5979, 3063, 5980, -1, 5980, 5978, 5979, -1, + 5978, 5980, 5981, -1, 5981, 5977, 5978, -1, + 5977, 5981, 5982, -1, 5982, 5976, 5977, -1, + 5976, 5982, 5983, -1, 5983, 5975, 5976, -1, + 5975, 5983, 5984, -1, 5984, 5974, 5975, -1, + 5974, 5984, 5985, -1, 5985, 5973, 5974, -1, + 5973, 5985, 5986, -1, 5986, 5972, 5973, -1, + 5972, 5986, 5987, -1, 5987, 5971, 5972, -1, + 5971, 5987, 5988, -1, 5988, 5970, 5971, -1, + 5970, 5988, 5989, -1, 5989, 5969, 5970, -1, + 5969, 5989, 5990, -1, 5990, 5968, 5969, -1, + 5968, 5990, 5991, -1, 5991, 5967, 5968, -1, + 5967, 5991, 5992, -1, 5992, 5966, 5967, -1, + 5966, 5992, 5993, -1, 5993, 5965, 5966, -1, + 5965, 5993, 5994, -1, 5994, 5964, 5965, -1, + 5964, 5994, 5995, -1, 5995, 5963, 5964, -1, + 5963, 5995, 5996, -1, 5996, 5962, 5963, -1, + 5962, 5996, 5997, -1, 5997, 5961, 5962, -1, + 5961, 5997, 5998, -1, 5998, 5960, 5961, -1, + 5960, 5998, 5999, -1, 5999, 5959, 5960, -1, + 5959, 5999, 6000, -1, 6000, 5958, 5959, -1, + 5958, 6000, 6001, -1, 6001, 5957, 5958, -1, + 5957, 6001, 6002, -1, 6002, 5956, 5957, -1, + 6002, 5955, 5956, -1, 5955, 6002, 6003, -1, + 6003, 5954, 5955, -1, 5954, 6003, 6004, -1, + 6004, 5953, 5954, -1, 5953, 6004, 6005, -1, + 6005, 5952, 5953, -1, 5952, 6005, 6006, -1, + 6006, 5951, 5952, -1, 5951, 6006, 6007, -1, + 6007, 5950, 5951, -1, 5950, 6007, 6008, -1, + 6008, 5949, 5950, -1, 5949, 6008, 6009, -1, + 6009, 5948, 5949, -1, 5948, 6009, 6010, -1, + 6010, 5947, 5948, -1, 5947, 6010, 6011, -1, + 6011, 5946, 5947, -1, 5946, 6011, 6012, -1, + 6012, 5945, 5946, -1, 5945, 6012, 6013, -1, + 6013, 5944, 5945, -1, 5944, 6013, 6014, -1, + 6014, 5943, 5944, -1, 5943, 6014, 6015, -1, + 6015, 5942, 5943, -1, 5942, 6015, 6016, -1, + 6016, 5941, 5942, -1, 5941, 6016, 6017, -1, + 6017, 5940, 5941, -1, 5940, 6017, 6018, -1, + 6018, 5939, 5940, -1, 5939, 6018, 6019, -1, + 6019, 5938, 5939, -1, 5938, 6019, 6020, -1, + 6020, 5937, 5938, -1, 5937, 6020, 6021, -1, + 6021, 5936, 5937, -1, 5936, 6021, 6022, -1, + 6022, 5935, 5936, -1, 5935, 6022, 6023, -1, + 6023, 4560, 5935, -1, 4560, 6023, 6024, -1, + 6024, 4556, 4560, -1, 6024, 4557, 4556, -1, + 6024, 6025, 4557, -1, 6025, 6024, 6023, -1, + 6023, 6026, 6025, -1, 6026, 6023, 6022, -1, + 6022, 6027, 6026, -1, 6027, 6022, 6021, -1, + 6021, 6028, 6027, -1, 6028, 6021, 6020, -1, + 6020, 6029, 6028, -1, 6029, 6020, 6019, -1, + 6019, 6030, 6029, -1, 6030, 6019, 6018, -1, + 6018, 6031, 6030, -1, 6031, 6018, 6017, -1, + 6017, 6032, 6031, -1, 6032, 6017, 6016, -1, + 6016, 6033, 6032, -1, 6033, 6016, 6015, -1, + 6015, 6034, 6033, -1, 6034, 6015, 6014, -1, + 6014, 6035, 6034, -1, 6035, 6014, 6013, -1, + 6013, 6036, 6035, -1, 6036, 6013, 6012, -1, + 6012, 6037, 6036, -1, 6037, 6012, 6011, -1, + 6011, 6038, 6037, -1, 6038, 6011, 6010, -1, + 6010, 6039, 6038, -1, 6039, 6010, 6009, -1, + 6009, 6040, 6039, -1, 6040, 6009, 6008, -1, + 6008, 6041, 6040, -1, 6041, 6008, 6007, -1, + 6007, 6042, 6041, -1, 6042, 6007, 6006, -1, + 6006, 6043, 6042, -1, 6043, 6006, 6005, -1, + 6005, 6044, 6043, -1, 6044, 6005, 6004, -1, + 6004, 6045, 6044, -1, 6045, 6004, 6003, -1, + 6003, 6046, 6045, -1, 6046, 6003, 6002, -1, + 6046, 6002, 6001, -1, 6001, 6047, 6046, -1, + 6047, 6001, 6000, -1, 6000, 6048, 6047, -1, + 6048, 6000, 5999, -1, 5999, 6049, 6048, -1, + 6049, 5999, 5998, -1, 5998, 6050, 6049, -1, + 6050, 5998, 5997, -1, 5997, 6051, 6050, -1, + 6051, 5997, 5996, -1, 5996, 6052, 6051, -1, + 6052, 5996, 5995, -1, 5995, 6053, 6052, -1, + 6053, 5995, 5994, -1, 5994, 6054, 6053, -1, + 6054, 5994, 5993, -1, 5993, 6055, 6054, -1, + 6055, 5993, 5992, -1, 5992, 6056, 6055, -1, + 6056, 5992, 5991, -1, 5991, 6057, 6056, -1, + 6057, 5991, 5990, -1, 5990, 6058, 6057, -1, + 6058, 5990, 5989, -1, 5989, 6059, 6058, -1, + 6059, 5989, 5988, -1, 5988, 6060, 6059, -1, + 6060, 5988, 5987, -1, 5987, 6061, 6060, -1, + 6061, 5987, 5986, -1, 5986, 6062, 6061, -1, + 6062, 5986, 5985, -1, 5985, 6063, 6062, -1, + 6063, 5985, 5984, -1, 5984, 6064, 6063, -1, + 6064, 5984, 5983, -1, 5983, 6065, 6064, -1, + 6065, 5983, 5982, -1, 5982, 6066, 6065, -1, + 6066, 5982, 5981, -1, 5981, 6067, 6066, -1, + 6067, 5981, 5980, -1, 5980, 6068, 6067, -1, + 6068, 5980, 3063, -1, 3063, 6069, 6068, -1, + 6069, 3063, 3062, -1, 6069, 3062, 3074, -1, + 6069, 3074, 6070, -1, 6070, 6068, 6069, -1, + 6068, 6070, 6071, -1, 6071, 6067, 6068, -1, + 6067, 6071, 6072, -1, 6072, 6066, 6067, -1, + 6066, 6072, 6073, -1, 6073, 6065, 6066, -1, + 6065, 6073, 6074, -1, 6074, 6064, 6065, -1, + 6064, 6074, 6075, -1, 6075, 6063, 6064, -1, + 6063, 6075, 6076, -1, 6076, 6062, 6063, -1, + 6062, 6076, 6077, -1, 6077, 6061, 6062, -1, + 6061, 6077, 6078, -1, 6078, 6060, 6061, -1, + 6060, 6078, 6079, -1, 6079, 6059, 6060, -1, + 6059, 6079, 6080, -1, 6080, 6058, 6059, -1, + 6058, 6080, 6081, -1, 6081, 6057, 6058, -1, + 6057, 6081, 6082, -1, 6082, 6056, 6057, -1, + 6056, 6082, 6083, -1, 6083, 6055, 6056, -1, + 6055, 6083, 6084, -1, 6084, 6054, 6055, -1, + 6054, 6084, 6085, -1, 6085, 6053, 6054, -1, + 6053, 6085, 6086, -1, 6086, 6052, 6053, -1, + 6052, 6086, 6087, -1, 6087, 6051, 6052, -1, + 6051, 6087, 6088, -1, 6088, 6050, 6051, -1, + 6050, 6088, 6089, -1, 6089, 6049, 6050, -1, + 6049, 6089, 6090, -1, 6090, 6048, 6049, -1, + 6048, 6090, 6091, -1, 6091, 6047, 6048, -1, + 6047, 6091, 6092, -1, 6092, 6046, 6047, -1, + 6092, 6045, 6046, -1, 6045, 6092, 6093, -1, + 6093, 6044, 6045, -1, 6044, 6093, 6094, -1, + 6094, 6043, 6044, -1, 6043, 6094, 6095, -1, + 6095, 6042, 6043, -1, 6042, 6095, 6096, -1, + 6096, 6041, 6042, -1, 6041, 6096, 6097, -1, + 6097, 6040, 6041, -1, 6040, 6097, 6098, -1, + 6098, 6039, 6040, -1, 6039, 6098, 6099, -1, + 6099, 6038, 6039, -1, 6038, 6099, 6100, -1, + 6100, 6037, 6038, -1, 6037, 6100, 6101, -1, + 6101, 6036, 6037, -1, 6036, 6101, 6102, -1, + 6102, 6035, 6036, -1, 6035, 6102, 6103, -1, + 6103, 6034, 6035, -1, 6034, 6103, 6104, -1, + 6104, 6033, 6034, -1, 6033, 6104, 6105, -1, + 6105, 6032, 6033, -1, 6032, 6105, 6106, -1, + 6106, 6031, 6032, -1, 6031, 6106, 6107, -1, + 6107, 6030, 6031, -1, 6030, 6107, 6108, -1, + 6108, 6029, 6030, -1, 6029, 6108, 6109, -1, + 6109, 6028, 6029, -1, 6028, 6109, 6110, -1, + 6110, 6027, 6028, -1, 6027, 6110, 6111, -1, + 6111, 6026, 6027, -1, 6026, 6111, 6112, -1, + 6112, 6025, 6026, -1, 6025, 6112, 6113, -1, + 6113, 4557, 6025, -1, 4557, 6113, 6114, -1, + 6114, 4555, 4557, -1, 6114, 5842, 4555, -1, + 6114, 5841, 5842, -1, 5841, 6114, 6113, -1, + 6113, 5840, 5841, -1, 5840, 6113, 6112, -1, + 6112, 5839, 5840, -1, 5839, 6112, 6111, -1, + 6111, 5838, 5839, -1, 5838, 6111, 6110, -1, + 6110, 5837, 5838, -1, 5837, 6110, 6109, -1, + 6109, 5836, 5837, -1, 5836, 6109, 6108, -1, + 6108, 5835, 5836, -1, 5835, 6108, 6107, -1, + 6107, 5834, 5835, -1, 5834, 6107, 6106, -1, + 6106, 5833, 5834, -1, 5833, 6106, 6105, -1, + 6105, 5832, 5833, -1, 5832, 6105, 6104, -1, + 6104, 5831, 5832, -1, 5831, 6104, 6103, -1, + 6103, 5830, 5831, -1, 5830, 6103, 6102, -1, + 6102, 5829, 5830, -1, 5829, 6102, 6101, -1, + 6101, 5828, 5829, -1, 5828, 6101, 6100, -1, + 6100, 5827, 5828, -1, 5827, 6100, 6099, -1, + 6099, 5826, 5827, -1, 5826, 6099, 6098, -1, + 6098, 5825, 5826, -1, 5825, 6098, 6097, -1, + 6097, 5824, 5825, -1, 5824, 6097, 6096, -1, + 6096, 5823, 5824, -1, 5823, 6096, 6095, -1, + 6095, 5822, 5823, -1, 5822, 6095, 6094, -1, + 6094, 5821, 5822, -1, 5821, 6094, 6093, -1, + 6093, 5820, 5821, -1, 5820, 6093, 6092, -1, + 5820, 6092, 6091, -1, 6091, 5819, 5820, -1, + 5819, 6091, 6090, -1, 6090, 5818, 5819, -1, + 5818, 6090, 6089, -1, 6089, 5817, 5818, -1, + 5817, 6089, 6088, -1, 6088, 5816, 5817, -1, + 5816, 6088, 6087, -1, 6087, 5815, 5816, -1, + 5815, 6087, 6086, -1, 6086, 5814, 5815, -1, + 5814, 6086, 6085, -1, 6085, 5813, 5814, -1, + 5813, 6085, 6084, -1, 6084, 5812, 5813, -1, + 5812, 6084, 6083, -1, 6083, 5811, 5812, -1, + 5811, 6083, 6082, -1, 6082, 5810, 5811, -1, + 5810, 6082, 6081, -1, 6081, 5809, 5810, -1, + 5809, 6081, 6080, -1, 6080, 5808, 5809, -1, + 5808, 6080, 6079, -1, 6079, 5807, 5808, -1, + 5807, 6079, 6078, -1, 6078, 5806, 5807, -1, + 5806, 6078, 6077, -1, 6077, 5805, 5806, -1, + 5805, 6077, 6076, -1, 6076, 5804, 5805, -1, + 5804, 6076, 6075, -1, 6075, 5803, 5804, -1, + 5803, 6075, 6074, -1, 6074, 5802, 5803, -1, + 5802, 6074, 6073, -1, 6073, 5801, 5802, -1, + 5801, 6073, 6072, -1, 6072, 5800, 5801, -1, + 5800, 6072, 6071, -1, 6071, 5799, 5800, -1, + 5799, 6071, 6070, -1, 6070, 5798, 5799, -1, + 5798, 6070, 3074, -1, 3074, 5553, 5798, -1, + 5553, 3074, 3073, -1, 3073, 5550, 5553, -1, + 5550, 3073, 3076, -1, 3076, 5548, 5550, -1, + 5548, 3076, 3078, -1, 3078, 5546, 5548, -1, + 5546, 3078, 3080, -1, 3080, 5544, 5546, -1, + 5544, 3080, 3082, -1, 3082, 5542, 5544, -1, + 5542, 3082, 3084, -1, 3084, 5541, 5542, -1, + 5541, 3084, 3085, -1, 3085, 5540, 5541, -1, + 5540, 3085, 3086, -1, 3086, 5539, 5540, -1, + 5539, 3086, 3087, -1, 3087, 6115, 5539, -1, + 6116, 5539, 6115, -1, 6116, 5538, 5539, -1, + 6116, 5535, 5538, -1, 6116, 6115, 5535, -1, + 6115, 6117, 5535, -1, 6117, 6115, 3087, -1, + 6117, 3087, 3088, -1, 6117, 3088, 3090, -1, + 3090, 5535, 6117, -1, 3090, 6118, 6119, -1, + 6118, 3090, 3091, -1, 3091, 3093, 6118, -1, + 3093, 3095, 6118, -1, 6120, 6118, 3095, -1, + 6120, 6119, 6118, -1, 6121, 6119, 6120, -1, + 6120, 3095, 6121, -1, 6121, 3095, 3117, -1, + 3117, 6119, 6121, -1, 3117, 6122, 6119, -1, + 6122, 3117, 3116, -1, 6122, 3116, 4529, -1, + 4529, 6119, 6122, -1, 6119, 4529, 4531, -1, + 4531, 6123, 6124, -1, 6123, 4531, 4534, -1, + 4534, 3237, 6123, -1, 3237, 3239, 6123, -1, + 6125, 6123, 3239, -1, 6125, 6124, 6123, -1, + 6126, 6124, 6125, -1, 6125, 3239, 6126, -1, + 6126, 3239, 3466, -1, 3466, 6124, 6126, -1, + 3466, 6127, 6124, -1, 6127, 3466, 3465, -1, + 6127, 3465, 3468, -1, 3468, 6124, 6127, -1, + 3468, 6128, 6124, -1, 6128, 3468, 3467, -1, + 6128, 3467, 3678, -1, 3678, 3679, 6128, -1, + 3679, 6124, 6128, -1, 6129, 3679, 3680, -1, + 3680, 6130, 6129, -1, 3680, 3682, 6130, -1, + 6130, 3682, 3691, -1, 3691, 6129, 6130, -1, + 3691, 6131, 6129, -1, 6131, 3691, 3690, -1, + 6131, 3690, 4384, -1, 4384, 6129, 6131, -1, + 4384, 6132, 6129, -1, 6132, 4384, 4102, -1, + 6132, 4102, 4103, -1, 4103, 4104, 6132, -1, + 4104, 6129, 6132, -1, 2635, 2948, 2947, -1, + 2948, 2635, 2634, -1, 2634, 2944, 2948, -1, + 2634, 2633, 2944, -1, 2633, 2945, 2944, -1, + 2945, 2633, 2635, -1, 2945, 2635, 4071, -1, + 4071, 2943, 2945, -1, 4071, 4070, 2943, -1, + 2943, 4070, 4068, -1, 4068, 2942, 2943, -1, + 2942, 4068, 4067, -1, 4067, 2940, 2942, -1, + 2940, 4067, 4052, -1, 4052, 4049, 2940, -1, + 6133, 4049, 6134, -1, 6133, 2940, 4049, -1, + 6133, 2941, 2940, -1, 6133, 6135, 2941, -1, + 6135, 6133, 6134, -1, 6134, 6136, 6135, -1, + 6136, 6134, 6137, -1, 6137, 6138, 6136, -1, + 6138, 6137, 6139, -1, 6138, 6139, 2631, -1, + 6138, 2631, 2632, -1, 2632, 6136, 6138, -1, + 6136, 2632, 6140, -1, 6140, 6135, 6136, -1, + 6135, 6140, 6141, -1, 6141, 2941, 6135, -1, + 2941, 6141, 6142, -1, 6142, 2937, 2941, -1, + 6142, 2938, 2937, -1, 6142, 6143, 2938, -1, + 6143, 6142, 6141, -1, 6141, 6144, 6143, -1, + 6144, 6141, 6140, -1, 6140, 6145, 6144, -1, + 6145, 6140, 2632, -1, 6145, 2632, 2527, -1, + 6145, 2527, 2524, -1, 2524, 6144, 6145, -1, + 6144, 2524, 2523, -1, 2523, 6143, 6144, -1, + 6143, 2523, 6146, -1, 6146, 2938, 6143, -1, + 2938, 6146, 6147, -1, 6147, 2936, 2938, -1, + 6147, 2952, 2936, -1, 6147, 6148, 2952, -1, + 6148, 6147, 6146, -1, 6146, 6149, 6148, -1, + 6149, 6146, 2523, -1, 2523, 2522, 6149, -1, + 2522, 2526, 6149, -1, 6150, 6149, 2526, -1, + 6150, 6148, 6149, -1, 6148, 6150, 6151, -1, + 6151, 2952, 6148, -1, 2952, 6151, 6152, -1, + 6152, 2935, 2952, -1, 6152, 2934, 2935, -1, + 6152, 2933, 2934, -1, 2933, 6152, 6151, -1, + 6151, 2932, 2933, -1, 2932, 6151, 6150, -1, + 6150, 2526, 2932, -1, 2526, 2862, 2932, -1, + 2526, 2860, 2862, -1, 2860, 2526, 2525, -1, + 2525, 2858, 2860, -1, 2858, 2525, 2528, -1, + 2528, 2856, 2858, -1, 2856, 2528, 2530, -1, + 2530, 2854, 2856, -1, 2854, 2530, 2532, -1, + 2532, 2852, 2854, -1, 2852, 2532, 2534, -1, + 2534, 2850, 2852, -1, 2850, 2534, 2536, -1, + 2536, 2848, 2850, -1, 2848, 2536, 2538, -1, + 2538, 2846, 2848, -1, 2846, 2538, 2540, -1, + 2540, 2844, 2846, -1, 2844, 2540, 2541, -1, + 2541, 2842, 2844, -1, 2842, 2541, 2623, -1, + 2623, 2840, 2842, -1, 2840, 2623, 2621, -1, + 2621, 2838, 2840, -1, 2838, 2621, 2619, -1, + 2619, 2836, 2838, -1, 2836, 2619, 2617, -1, + 2617, 2834, 2836, -1, 2834, 2617, 2615, -1, + 2615, 2832, 2834, -1, 2832, 2615, 2613, -1, + 2613, 2830, 2832, -1, 2830, 2613, 2611, -1, + 2611, 2828, 2830, -1, 2828, 2611, 2609, -1, + 2609, 2826, 2828, -1, 2826, 2609, 2607, -1, + 2607, 2824, 2826, -1, 2824, 2607, 2605, -1, + 2605, 2822, 2824, -1, 2822, 2605, 2603, -1, + 2603, 2820, 2822, -1, 2820, 2603, 2601, -1, + 2601, 2818, 2820, -1, 2818, 2601, 2599, -1, + 2599, 2816, 2818, -1, 2816, 2599, 2597, -1, + 2597, 2814, 2816, -1, 2814, 2597, 2595, -1, + 2595, 2812, 2814, -1, 2812, 2595, 2593, -1, + 2593, 2810, 2812, -1, 2810, 2593, 2591, -1, + 2591, 2808, 2810, -1, 2808, 2591, 2589, -1, + 2589, 2806, 2808, -1, 2806, 2589, 2587, -1, + 2587, 2804, 2806, -1, 2804, 2587, 2585, -1, + 2585, 2802, 2804, -1, 2802, 2585, 2583, -1, + 2583, 2800, 2802, -1, 2800, 2583, 2581, -1, + 2581, 2798, 2800, -1, 2798, 2581, 2579, -1, + 2579, 2796, 2798, -1, 2796, 2579, 2577, -1, + 2577, 2794, 2796, -1, 2794, 2577, 2575, -1, + 2575, 2792, 2794, -1, 2792, 2575, 2573, -1, + 2573, 2790, 2792, -1, 2790, 2573, 2571, -1, + 2571, 2788, 2790, -1, 2788, 2571, 2569, -1, + 2569, 2786, 2788, -1, 2786, 2569, 2567, -1, + 2567, 2784, 2786, -1, 2784, 2567, 2565, -1, + 2565, 2782, 2784, -1, 2782, 2565, 2563, -1, + 2563, 2780, 2782, -1, 2780, 2563, 2561, -1, + 2561, 2778, 2780, -1, 2778, 2561, 2559, -1, + 2559, 2776, 2778, -1, 2776, 2559, 2557, -1, + 2557, 2774, 2776, -1, 2774, 2557, 2555, -1, + 2555, 2772, 2774, -1, 2772, 2555, 2553, -1, + 2553, 2770, 2772, -1, 2770, 2553, 2551, -1, + 2551, 2768, 2770, -1, 2768, 2551, 2549, -1, + 2549, 2767, 2768, -1, 2767, 2549, 2547, -1, + 2547, 2765, 2767, -1, 2765, 2547, 2545, -1, + 2545, 6153, 2765, -1, 6154, 6155, 6156, -1, + 6155, 6153, 6156, -1, 6155, 2765, 6153, -1, + 6155, 6154, 2765, -1, 6154, 2766, 2765, -1, + 2766, 6154, 6156, -1, 6157, 2761, 2766, -1, + 6157, 2762, 2761, -1, 6156, 6158, 2762, -1, + 6159, 6160, 6158, -1, 6160, 2762, 6158, -1, + 6160, 2763, 2762, -1, 6160, 6159, 2763, -1, + 6159, 2915, 2763, -1, 2915, 6159, 6158, -1, + 2915, 6158, 6161, -1, 6161, 2759, 2915, -1, + 6161, 2760, 2759, -1, 2760, 6161, 6158, -1, + 6158, 6162, 2760, -1, 6163, 6164, 6162, -1, + 2519, 6165, 6163, -1, 6166, 6165, 2519, -1, + 6165, 6166, 2370, -1, 6165, 2370, 2371, -1, + 2371, 6163, 6165, -1, 2371, 6167, 6163, -1, + 6167, 2371, 2081, -1, 2080, 6164, 6163, -1, + 6164, 2080, 1966, -1, 6164, 1966, 1965, -1, + 1965, 6162, 6164, -1, 6168, 6162, 1965, -1, + 6168, 1965, 1171, -1, 6168, 1171, 1170, -1, + 1170, 6162, 6168, -1, 1170, 1172, 6162, -1, + 1172, 6169, 6162, -1, 6169, 2760, 6162, -1, + 6169, 2758, 2760, -1, 6169, 1172, 2758, -1, + 2758, 1172, 1171, -1, 1171, 2756, 2758, -1, + 2756, 1171, 1967, -1, 1967, 2754, 2756, -1, + 2754, 1967, 2078, -1, 2078, 2752, 2754, -1, + 2752, 2078, 2076, -1, 2076, 2750, 2752, -1, + 2750, 2076, 2074, -1, 2074, 2748, 2750, -1, + 2748, 2074, 2072, -1, 2072, 2746, 2748, -1, + 2746, 2072, 2070, -1, 2070, 2744, 2746, -1, + 2744, 2070, 2068, -1, 2068, 2742, 2744, -1, + 2742, 2068, 2066, -1, 2066, 2740, 2742, -1, + 2740, 2066, 2064, -1, 2064, 2738, 2740, -1, + 2738, 2064, 2062, -1, 2062, 2736, 2738, -1, + 2736, 2062, 2060, -1, 2060, 2734, 2736, -1, + 2734, 2060, 2058, -1, 2058, 2732, 2734, -1, + 2732, 2058, 2056, -1, 2056, 2730, 2732, -1, + 2730, 2056, 2054, -1, 2054, 2728, 2730, -1, + 2728, 2054, 2052, -1, 2052, 2726, 2728, -1, + 2726, 2052, 2050, -1, 2050, 2724, 2726, -1, + 2724, 2050, 2048, -1, 2048, 2722, 2724, -1, + 2722, 2048, 2046, -1, 2046, 2720, 2722, -1, + 2720, 2046, 2044, -1, 2044, 2718, 2720, -1, + 2718, 2044, 2042, -1, 2042, 2716, 2718, -1, + 2716, 2042, 2040, -1, 2040, 2714, 2716, -1, + 2714, 2040, 2038, -1, 2038, 2712, 2714, -1, + 2712, 2038, 2036, -1, 2036, 2710, 2712, -1, + 2710, 2036, 2034, -1, 2034, 2708, 2710, -1, + 2708, 2034, 2032, -1, 2032, 2706, 2708, -1, + 2706, 2032, 2030, -1, 2030, 2704, 2706, -1, + 2704, 2030, 2028, -1, 2028, 2702, 2704, -1, + 2702, 2028, 2026, -1, 2026, 2700, 2702, -1, + 2700, 2026, 2024, -1, 2024, 2698, 2700, -1, + 2698, 2024, 2022, -1, 2022, 2696, 2698, -1, + 2696, 2022, 2020, -1, 2020, 2694, 2696, -1, + 2694, 2020, 2018, -1, 2018, 2692, 2694, -1, + 2692, 2018, 2016, -1, 2016, 2690, 2692, -1, + 2690, 2016, 2014, -1, 2014, 2688, 2690, -1, + 2688, 2014, 2012, -1, 2012, 2686, 2688, -1, + 2686, 2012, 2010, -1, 2010, 2684, 2686, -1, + 2684, 2010, 2008, -1, 2008, 2682, 2684, -1, + 2682, 2008, 2006, -1, 2006, 2680, 2682, -1, + 2680, 2006, 2004, -1, 2004, 2678, 2680, -1, + 2678, 2004, 2002, -1, 2002, 2676, 2678, -1, + 2676, 2002, 2000, -1, 2000, 2674, 2676, -1, + 2674, 2000, 1998, -1, 1998, 2672, 2674, -1, + 2672, 1998, 1996, -1, 1996, 2670, 2672, -1, + 2670, 1996, 1994, -1, 1994, 2668, 2670, -1, + 2668, 1994, 1992, -1, 1992, 2666, 2668, -1, + 2666, 1992, 1990, -1, 1990, 2664, 2666, -1, + 2664, 1990, 1988, -1, 1988, 2662, 2664, -1, + 2662, 1988, 1986, -1, 1986, 2660, 2662, -1, + 2660, 1986, 1984, -1, 1984, 2658, 2660, -1, + 2658, 1984, 1982, -1, 1982, 6170, 2658, -1, + 6170, 1982, 1980, -1, 1980, 6171, 6170, -1, + 6171, 1980, 1978, -1, 1978, 6172, 6171, -1, + 6172, 1978, 1976, -1, 1976, 6173, 6172, -1, + 6173, 1976, 1972, -1, 1972, 1971, 6173, -1, + 1971, 6174, 6175, -1, 6175, 6173, 1971, -1, + 6173, 6175, 6176, -1, 6176, 6172, 6173, -1, + 6172, 6176, 6177, -1, 6177, 6171, 6172, -1, + 6171, 6177, 6178, -1, 6178, 6170, 6171, -1, + 6170, 6178, 6179, -1, 6179, 2658, 6170, -1, + 6179, 2659, 2658, -1, 6179, 6180, 2659, -1, + 6180, 6179, 6178, -1, 6178, 6181, 6180, -1, + 6181, 6178, 6177, -1, 6177, 6182, 6181, -1, + 6182, 6177, 6176, -1, 6176, 6183, 6182, -1, + 6183, 6176, 6175, -1, 6175, 6184, 6183, -1, + 6185, 6183, 6184, -1, 6185, 6184, 1169, -1, + 6185, 1169, 1168, -1, 1168, 6183, 6185, -1, + 1168, 1167, 6183, -1, 6183, 1167, 1165, -1, + 1165, 6182, 6183, -1, 6182, 1165, 1163, -1, + 1163, 6181, 6182, -1, 6181, 1163, 1161, -1, + 1161, 6180, 6181, -1, 6180, 1161, 1159, -1, + 1159, 2659, 6180, -1, 2659, 1159, 1156, -1, + 1156, 2657, 2659, -1, 1156, 1158, 2657, -1, + 6186, 2657, 1158, -1, 6186, 2661, 2657, -1, + 6186, 2916, 2661, -1, 6186, 2919, 2916, -1, + 2919, 6186, 1158, -1, 1158, 2918, 2919, -1, + 2918, 1158, 1157, -1, 1157, 1160, 2918, -1, + 1160, 2656, 2918, -1, 1160, 2655, 2656, -1, + 2655, 1160, 1162, -1, 1162, 2654, 2655, -1, + 2654, 1162, 1164, -1, 1164, 2653, 2654, -1, + 2653, 1164, 6187, -1, 6187, 2652, 2653, -1, + 6187, 6188, 2652, -1, 6188, 6187, 1164, -1, + 6188, 1164, 1166, -1, 1166, 2652, 6188, -1, + 1166, 6189, 2652, -1, 6189, 1166, 1165, -1, + 6189, 1165, 1167, -1, 1167, 1169, 6189, -1, + 1169, 2652, 6189, -1, 6190, 6191, 6192, -1, + 1169, 6193, 6190, -1, 6193, 1169, 6184, -1, + 6193, 6184, 6175, -1, 6193, 6175, 6174, -1, + 6174, 6190, 6193, -1, 6174, 6194, 6190, -1, + 6194, 6174, 1971, -1, 6194, 1971, 1969, -1, + 1969, 6190, 6194, -1, 1969, 1968, 6190, -1, + 1968, 6191, 6190, -1, 6191, 1968, 1970, -1, + 6191, 1970, 1973, -1, 1973, 6192, 6191, -1, + 1973, 6195, 6192, -1, 6195, 1973, 1558, -1, + 6195, 1558, 1557, -1, 1557, 6192, 6195, -1, + 1557, 1559, 6192, -1, 1559, 1560, 6192, -1, + 1560, 6196, 6192, -1, 6196, 1560, 1561, -1, + 6196, 1561, 1719, -1, 6196, 1719, 1720, -1, + 1720, 6192, 6196, -1, 6197, 1720, 1721, -1, + 1721, 1722, 6197, -1, 1722, 6198, 6197, -1, + 6198, 1722, 1723, -1, 6198, 1723, 1729, -1, + 1729, 6197, 6198, -1, 1729, 1728, 6197, -1, + 1728, 1730, 6197, -1, 6197, 1730, 1531, -1, + 4228, 1531, 1529, -1, 1529, 6199, 4228, -1, + 6199, 1529, 1503, -1, 6199, 1503, 6200, -1, + 6200, 4228, 6199, -1, 6200, 6201, 4228, -1, + 6201, 6200, 1503, -1, 1503, 1502, 6201, -1, + 6202, 6201, 1502, -1, 6202, 4228, 6201, -1, + 6202, 4229, 4228, -1, 6202, 1502, 4229, -1, + 1502, 1506, 4229, -1, 6203, 4229, 1506, -1, + 6203, 4225, 4229, -1, 6203, 6204, 4225, -1, + 6203, 1506, 6204, -1, 6204, 1506, 1508, -1, + 1508, 4225, 6204, -1, 1508, 1507, 4225, -1, + 1507, 4226, 4225, -1, 1507, 1509, 4226, -1, + 1509, 1179, 4226, -1, 6205, 4226, 1179, -1, + 6205, 4227, 4226, -1, 6205, 6206, 4227, -1, + 6205, 1179, 6206, -1, 6206, 1179, 1177, -1, + 1177, 4227, 6206, -1, 1177, 1176, 4227, -1, + 1176, 4230, 4227, -1, 1176, 1178, 4230, -1, + 1178, 4219, 4230, -1, 4219, 1178, 1488, -1, + 1488, 4218, 4219, -1, 4218, 1488, 1486, -1, + 1486, 4217, 4218, -1, 4217, 1486, 1485, -1, + 1485, 4216, 4217, -1, 4216, 1485, 1484, -1, + 1484, 4214, 4216, -1, 1484, 6207, 4214, -1, + 6208, 6209, 6210, -1, 6209, 6208, 6211, -1, + 6211, 6212, 6209, -1, 6212, 6211, 6207, -1, + 6207, 6213, 6212, -1, 6213, 6207, 1484, -1, + 6213, 1484, 1180, -1, 6213, 1180, 1183, -1, + 1183, 6212, 6213, -1, 6212, 1183, 1184, -1, + 1184, 6209, 6212, -1, 6209, 1184, 1186, -1, + 1186, 6210, 6209, -1, 6210, 1186, 1190, -1, + 1190, 6214, 6210, -1, 6214, 1190, 1192, -1, + 1192, 6215, 6214, -1, 6215, 1192, 1194, -1, + 1194, 6216, 6215, -1, 6216, 1194, 1196, -1, + 1196, 6217, 6216, -1, 6217, 1196, 1198, -1, + 1198, 6218, 6217, -1, 6218, 1198, 1200, -1, + 1200, 6219, 6218, -1, 6219, 1200, 1202, -1, + 1202, 6220, 6219, -1, 6220, 1202, 1204, -1, + 1204, 6221, 6220, -1, 6221, 1204, 1206, -1, + 1206, 6222, 6221, -1, 6222, 1206, 1208, -1, + 1208, 6223, 6222, -1, 6223, 1208, 1210, -1, + 1210, 6224, 6223, -1, 6224, 1210, 1212, -1, + 1212, 6225, 6224, -1, 6225, 1212, 1214, -1, + 1214, 6226, 6225, -1, 6226, 1214, 1216, -1, + 1216, 6227, 6226, -1, 6227, 1216, 1218, -1, + 1218, 6228, 6227, -1, 6228, 1218, 1220, -1, + 1220, 6229, 6228, -1, 6229, 1220, 1222, -1, + 1222, 6230, 6229, -1, 6230, 1222, 1224, -1, + 1224, 6231, 6230, -1, 6231, 1224, 1226, -1, + 1226, 6232, 6231, -1, 6232, 1226, 1228, -1, + 1228, 6233, 6232, -1, 6233, 1228, 1230, -1, + 1230, 6234, 6233, -1, 6234, 1230, 1232, -1, + 1232, 6235, 6234, -1, 6235, 1232, 1234, -1, + 1234, 6236, 6235, -1, 6236, 1234, 1236, -1, + 1236, 6237, 6236, -1, 6237, 1236, 1238, -1, + 1238, 6238, 6237, -1, 6238, 1238, 1240, -1, + 1240, 6239, 6238, -1, 6239, 1240, 1242, -1, + 1242, 6240, 6239, -1, 6240, 1242, 1244, -1, + 1244, 6241, 6240, -1, 6241, 1244, 1246, -1, + 1246, 6242, 6241, -1, 6242, 1246, 1248, -1, + 1248, 6243, 6242, -1, 6243, 1248, 1250, -1, + 1250, 6244, 6243, -1, 6244, 1250, 1252, -1, + 1252, 6245, 6244, -1, 6245, 1252, 1254, -1, + 1254, 6246, 6245, -1, 6246, 1254, 1256, -1, + 1256, 6247, 6246, -1, 6247, 1256, 1258, -1, + 1258, 6248, 6247, -1, 6248, 1258, 1260, -1, + 1260, 6249, 6248, -1, 6249, 1260, 1262, -1, + 1262, 6250, 6249, -1, 6250, 1262, 1264, -1, + 1264, 6251, 6250, -1, 6251, 1264, 1266, -1, + 1266, 6252, 6251, -1, 6252, 1266, 1268, -1, + 1268, 6253, 6252, -1, 6253, 1268, 1270, -1, + 1270, 6254, 6253, -1, 6254, 1270, 1272, -1, + 1272, 6255, 6254, -1, 6255, 1272, 1274, -1, + 1274, 6256, 6255, -1, 6256, 1274, 1276, -1, + 1276, 6257, 6256, -1, 6257, 1276, 1278, -1, + 6257, 1278, 1281, -1, 1281, 6258, 6257, -1, + 6258, 1281, 1283, -1, 1283, 6259, 6258, -1, + 6259, 1283, 1285, -1, 1285, 6260, 6259, -1, + 6260, 1285, 1287, -1, 1287, 6261, 6260, -1, + 6261, 1287, 1289, -1, 1289, 6262, 6261, -1, + 6262, 1289, 1291, -1, 1291, 6263, 6262, -1, + 6263, 1291, 1293, -1, 1293, 6264, 6263, -1, + 6264, 1293, 1295, -1, 1295, 6265, 6264, -1, + 6265, 1295, 1297, -1, 1297, 6266, 6265, -1, + 6266, 1297, 1299, -1, 1299, 6267, 6266, -1, + 6267, 1299, 1301, -1, 1301, 6268, 6267, -1, + 6268, 1301, 1303, -1, 1303, 6269, 6268, -1, + 6269, 1303, 1305, -1, 1305, 6270, 6269, -1, + 6270, 1305, 1307, -1, 1307, 6271, 6270, -1, + 6271, 1307, 1309, -1, 1309, 6272, 6271, -1, + 6272, 1309, 1311, -1, 1311, 6273, 6272, -1, + 6273, 1311, 1313, -1, 1313, 6274, 6273, -1, + 6274, 1313, 1315, -1, 1315, 6275, 6274, -1, + 6275, 1315, 1317, -1, 1317, 6276, 6275, -1, + 6276, 1317, 1319, -1, 1319, 6277, 6276, -1, + 6277, 1319, 1321, -1, 1321, 6278, 6277, -1, + 6278, 1321, 1323, -1, 1323, 6279, 6278, -1, + 6279, 1323, 1325, -1, 1325, 6280, 6279, -1, + 6280, 1325, 1327, -1, 1327, 6281, 6280, -1, + 6281, 1327, 1329, -1, 1329, 6282, 6281, -1, + 6282, 1329, 1331, -1, 1331, 6283, 6282, -1, + 6283, 1331, 1333, -1, 1333, 6284, 6283, -1, + 6284, 1333, 1335, -1, 1335, 6285, 6284, -1, + 6285, 1335, 1337, -1, 1337, 6286, 6285, -1, + 6286, 1337, 1339, -1, 1339, 6287, 6286, -1, + 6287, 1339, 1341, -1, 1341, 6288, 6287, -1, + 6288, 1341, 1343, -1, 1343, 6289, 6288, -1, + 6289, 1343, 1345, -1, 1345, 6290, 6289, -1, + 6290, 1345, 1347, -1, 1347, 6291, 6290, -1, + 6291, 1347, 1349, -1, 1349, 6292, 6291, -1, + 6292, 1349, 1351, -1, 1351, 6293, 6292, -1, + 6293, 1351, 1353, -1, 1353, 6294, 6293, -1, + 6294, 1353, 1355, -1, 1355, 6295, 6294, -1, + 6295, 1355, 1357, -1, 1357, 6296, 6295, -1, + 6296, 1357, 1359, -1, 1359, 6297, 6296, -1, + 6297, 1359, 1376, -1, 1376, 6298, 6297, -1, + 6298, 1376, 1374, -1, 1374, 6299, 6298, -1, + 6299, 1374, 1372, -1, 1372, 6300, 6299, -1, + 6300, 1372, 1370, -1, 1370, 6301, 6300, -1, + 6301, 1370, 1366, -1, 1366, 1365, 6301, -1, + 6302, 1365, 6303, -1, 6302, 6301, 1365, -1, + 6301, 6302, 6304, -1, 6304, 6300, 6301, -1, + 6300, 6304, 6305, -1, 6305, 6299, 6300, -1, + 6299, 6305, 6306, -1, 6306, 6298, 6299, -1, + 6298, 6306, 6307, -1, 6307, 6297, 6298, -1, + 6297, 6307, 6308, -1, 6308, 6296, 6297, -1, + 6296, 6308, 6309, -1, 6309, 6295, 6296, -1, + 6295, 6309, 6310, -1, 6310, 6294, 6295, -1, + 6294, 6310, 6311, -1, 6311, 6293, 6294, -1, + 6293, 6311, 6312, -1, 6312, 6292, 6293, -1, + 6292, 6312, 6313, -1, 6313, 6291, 6292, -1, + 6291, 6313, 6314, -1, 6314, 6290, 6291, -1, + 6290, 6314, 6315, -1, 6315, 6289, 6290, -1, + 6289, 6315, 6316, -1, 6316, 6288, 6289, -1, + 6288, 6316, 6317, -1, 6317, 6287, 6288, -1, + 6287, 6317, 6318, -1, 6318, 6286, 6287, -1, + 6286, 6318, 6319, -1, 6319, 6285, 6286, -1, + 6285, 6319, 6320, -1, 6320, 6284, 6285, -1, + 6284, 6320, 6321, -1, 6321, 6283, 6284, -1, + 6283, 6321, 6322, -1, 6322, 6282, 6283, -1, + 6282, 6322, 6323, -1, 6323, 6281, 6282, -1, + 6281, 6323, 6324, -1, 6324, 6280, 6281, -1, + 6280, 6324, 6325, -1, 6325, 6279, 6280, -1, + 6279, 6325, 6326, -1, 6326, 6278, 6279, -1, + 6278, 6326, 6327, -1, 6327, 6277, 6278, -1, + 6277, 6327, 6328, -1, 6328, 6276, 6277, -1, + 6276, 6328, 6329, -1, 6329, 6275, 6276, -1, + 6275, 6329, 6330, -1, 6330, 6274, 6275, -1, + 6274, 6330, 6331, -1, 6331, 6273, 6274, -1, + 6273, 6331, 6332, -1, 6332, 6272, 6273, -1, + 6272, 6332, 6333, -1, 6333, 6271, 6272, -1, + 6271, 6333, 6334, -1, 6334, 6270, 6271, -1, + 6270, 6334, 6335, -1, 6335, 6269, 6270, -1, + 6269, 6335, 6336, -1, 6336, 6268, 6269, -1, + 6268, 6336, 6337, -1, 6337, 6267, 6268, -1, + 6267, 6337, 6338, -1, 6338, 6266, 6267, -1, + 6266, 6338, 6339, -1, 6339, 6265, 6266, -1, + 6265, 6339, 6340, -1, 6340, 6264, 6265, -1, + 6264, 6340, 6341, -1, 6341, 6263, 6264, -1, + 6263, 6341, 6342, -1, 6342, 6262, 6263, -1, + 6262, 6342, 6343, -1, 6343, 6261, 6262, -1, + 6261, 6343, 6344, -1, 6344, 6260, 6261, -1, + 6260, 6344, 6345, -1, 6345, 6259, 6260, -1, + 6259, 6345, 6346, -1, 6346, 6258, 6259, -1, + 6258, 6346, 6347, -1, 6347, 6257, 6258, -1, + 6347, 6256, 6257, -1, 6256, 6347, 6348, -1, + 6348, 6255, 6256, -1, 6255, 6348, 6349, -1, + 6349, 6254, 6255, -1, 6254, 6349, 6350, -1, + 6350, 6253, 6254, -1, 6253, 6350, 6351, -1, + 6351, 6252, 6253, -1, 6252, 6351, 6352, -1, + 6352, 6251, 6252, -1, 6251, 6352, 6353, -1, + 6353, 6250, 6251, -1, 6250, 6353, 6354, -1, + 6354, 6249, 6250, -1, 6249, 6354, 6355, -1, + 6355, 6248, 6249, -1, 6248, 6355, 6356, -1, + 6356, 6247, 6248, -1, 6247, 6356, 6357, -1, + 6357, 6246, 6247, -1, 6246, 6357, 6358, -1, + 6358, 6245, 6246, -1, 6245, 6358, 6359, -1, + 6359, 6244, 6245, -1, 6244, 6359, 6360, -1, + 6360, 6243, 6244, -1, 6243, 6360, 6361, -1, + 6361, 6242, 6243, -1, 6242, 6361, 6362, -1, + 6362, 6241, 6242, -1, 6241, 6362, 6363, -1, + 6363, 6240, 6241, -1, 6240, 6363, 6364, -1, + 6364, 6239, 6240, -1, 6239, 6364, 6365, -1, + 6365, 6238, 6239, -1, 6238, 6365, 6366, -1, + 6366, 6237, 6238, -1, 6237, 6366, 6367, -1, + 6367, 6236, 6237, -1, 6236, 6367, 6368, -1, + 6368, 6235, 6236, -1, 6235, 6368, 6369, -1, + 6369, 6234, 6235, -1, 6234, 6369, 6370, -1, + 6370, 6233, 6234, -1, 6233, 6370, 6371, -1, + 6371, 6232, 6233, -1, 6232, 6371, 6372, -1, + 6372, 6231, 6232, -1, 6231, 6372, 6373, -1, + 6373, 6230, 6231, -1, 6230, 6373, 6374, -1, + 6374, 6229, 6230, -1, 6229, 6374, 6375, -1, + 6375, 6228, 6229, -1, 6228, 6375, 6376, -1, + 6376, 6227, 6228, -1, 6227, 6376, 6377, -1, + 6377, 6226, 6227, -1, 6226, 6377, 6378, -1, + 6378, 6225, 6226, -1, 6225, 6378, 6379, -1, + 6379, 6224, 6225, -1, 6224, 6379, 6380, -1, + 6380, 6223, 6224, -1, 6223, 6380, 6381, -1, + 6381, 6222, 6223, -1, 6222, 6381, 6382, -1, + 6382, 6221, 6222, -1, 6221, 6382, 6383, -1, + 6383, 6220, 6221, -1, 6220, 6383, 6384, -1, + 6384, 6219, 6220, -1, 6219, 6384, 6385, -1, + 6385, 6218, 6219, -1, 6218, 6385, 6386, -1, + 6386, 6217, 6218, -1, 6217, 6386, 6387, -1, + 6387, 6216, 6217, -1, 6216, 6387, 6388, -1, + 6388, 6215, 6216, -1, 6215, 6388, 6389, -1, + 6389, 6214, 6215, -1, 6214, 6389, 1155, -1, + 1155, 6210, 6214, -1, 6210, 1155, 1154, -1, + 1154, 6208, 6210, -1, 6208, 1154, 6390, -1, + 6390, 6211, 6208, -1, 6211, 6390, 6391, -1, + 6391, 6207, 6211, -1, 6391, 4214, 6207, -1, + 6391, 4215, 4214, -1, 4215, 6391, 6390, -1, + 6390, 6392, 4215, -1, 6392, 6390, 1154, -1, + 1154, 1153, 6392, -1, 6392, 1153, 6393, -1, + 6393, 4215, 6392, -1, 6393, 4213, 4215, -1, + 6393, 4212, 4213, -1, 4212, 6393, 1153, -1, + 1153, 4211, 4212, -1, 4211, 1153, 1155, -1, + 1155, 4210, 4211, -1, 4210, 1155, 6389, -1, + 6389, 4209, 4210, -1, 4209, 6389, 6388, -1, + 6388, 4208, 4209, -1, 4208, 6388, 6387, -1, + 6387, 4207, 4208, -1, 4207, 6387, 6386, -1, + 6386, 4206, 4207, -1, 4206, 6386, 6385, -1, + 6385, 4205, 4206, -1, 4205, 6385, 6384, -1, + 6384, 4204, 4205, -1, 4204, 6384, 6383, -1, + 6383, 4203, 4204, -1, 4203, 6383, 6382, -1, + 6382, 4202, 4203, -1, 4202, 6382, 6381, -1, + 6381, 4201, 4202, -1, 4201, 6381, 6380, -1, + 6380, 4200, 4201, -1, 4200, 6380, 6379, -1, + 6379, 4199, 4200, -1, 4199, 6379, 6378, -1, + 6378, 4198, 4199, -1, 4198, 6378, 6377, -1, + 6377, 4197, 4198, -1, 4197, 6377, 6376, -1, + 6376, 4196, 4197, -1, 4196, 6376, 6375, -1, + 6375, 4195, 4196, -1, 4195, 6375, 6374, -1, + 6374, 4194, 4195, -1, 4194, 6374, 6373, -1, + 6373, 4193, 4194, -1, 4193, 6373, 6372, -1, + 6372, 4192, 4193, -1, 4192, 6372, 6371, -1, + 6371, 4191, 4192, -1, 4191, 6371, 6370, -1, + 6370, 4190, 4191, -1, 4190, 6370, 6369, -1, + 6369, 4189, 4190, -1, 4189, 6369, 6368, -1, + 6368, 4188, 4189, -1, 4188, 6368, 6367, -1, + 6367, 4187, 4188, -1, 4187, 6367, 6366, -1, + 6366, 4186, 4187, -1, 4186, 6366, 6365, -1, + 6365, 4185, 4186, -1, 4185, 6365, 6364, -1, + 6364, 4184, 4185, -1, 4184, 6364, 6363, -1, + 6363, 4183, 4184, -1, 4183, 6363, 6362, -1, + 6362, 4182, 4183, -1, 4182, 6362, 6361, -1, + 6361, 4181, 4182, -1, 4181, 6361, 6360, -1, + 6360, 4180, 4181, -1, 4180, 6360, 6359, -1, + 6359, 4179, 4180, -1, 4179, 6359, 6358, -1, + 6358, 4178, 4179, -1, 4178, 6358, 6357, -1, + 6357, 4177, 4178, -1, 4177, 6357, 6356, -1, + 6356, 4176, 4177, -1, 4176, 6356, 6355, -1, + 6355, 4175, 4176, -1, 4175, 6355, 6354, -1, + 6354, 4174, 4175, -1, 4174, 6354, 6353, -1, + 6353, 4173, 4174, -1, 4173, 6353, 6352, -1, + 6352, 4172, 4173, -1, 4172, 6352, 6351, -1, + 6351, 4171, 4172, -1, 4171, 6351, 6350, -1, + 6350, 4170, 4171, -1, 4170, 6350, 6349, -1, + 6349, 4169, 4170, -1, 4169, 6349, 6348, -1, + 6348, 4168, 4169, -1, 4168, 6348, 6347, -1, + 4168, 6347, 6346, -1, 6346, 4167, 4168, -1, + 4167, 6346, 6345, -1, 6345, 4166, 4167, -1, + 4166, 6345, 6344, -1, 6344, 4165, 4166, -1, + 4165, 6344, 6343, -1, 6343, 4164, 4165, -1, + 4164, 6343, 6342, -1, 6342, 4163, 4164, -1, + 4163, 6342, 6341, -1, 6341, 4162, 4163, -1, + 4162, 6341, 6340, -1, 6340, 4161, 4162, -1, + 4161, 6340, 6339, -1, 6339, 4160, 4161, -1, + 4160, 6339, 6338, -1, 6338, 4159, 4160, -1, + 4159, 6338, 6337, -1, 6337, 4158, 4159, -1, + 4158, 6337, 6336, -1, 6336, 4157, 4158, -1, + 4157, 6336, 6335, -1, 6335, 4156, 4157, -1, + 4156, 6335, 6334, -1, 6334, 4155, 4156, -1, + 4155, 6334, 6333, -1, 6333, 4154, 4155, -1, + 4154, 6333, 6332, -1, 6332, 4153, 4154, -1, + 4153, 6332, 6331, -1, 6331, 4152, 4153, -1, + 4152, 6331, 6330, -1, 6330, 4151, 4152, -1, + 4151, 6330, 6329, -1, 6329, 4150, 4151, -1, + 4150, 6329, 6328, -1, 6328, 4149, 4150, -1, + 4149, 6328, 6327, -1, 6327, 4148, 4149, -1, + 4148, 6327, 6326, -1, 6326, 4147, 4148, -1, + 4147, 6326, 6325, -1, 6325, 4146, 4147, -1, + 4146, 6325, 6324, -1, 6324, 4145, 4146, -1, + 4145, 6324, 6323, -1, 6323, 4144, 4145, -1, + 4144, 6323, 6322, -1, 6322, 4143, 4144, -1, + 4143, 6322, 6321, -1, 6321, 4142, 4143, -1, + 4142, 6321, 6320, -1, 6320, 4140, 4142, -1, + 4140, 6320, 6319, -1, 6319, 4138, 4140, -1, + 4138, 6319, 6318, -1, 6318, 4136, 4138, -1, + 4136, 6318, 6317, -1, 6317, 4134, 4136, -1, + 4134, 6317, 6316, -1, 6316, 4132, 4134, -1, + 4132, 6316, 6315, -1, 6315, 4130, 4132, -1, + 4130, 6315, 6314, -1, 6314, 4128, 4130, -1, + 4128, 6314, 6313, -1, 6313, 4126, 4128, -1, + 4126, 6313, 6312, -1, 6312, 4124, 4126, -1, + 4124, 6312, 6311, -1, 6311, 4122, 4124, -1, + 4122, 6311, 6310, -1, 6310, 4120, 4122, -1, + 4120, 6310, 6309, -1, 6309, 4118, 4120, -1, + 4118, 6309, 6308, -1, 6308, 4117, 4118, -1, + 4117, 6308, 6307, -1, 6307, 4116, 4117, -1, + 4116, 6307, 6306, -1, 6306, 4115, 4116, -1, + 4115, 6306, 6305, -1, 6305, 4114, 4115, -1, + 4114, 6305, 6304, -1, 6304, 4113, 4114, -1, + 4113, 6304, 6302, -1, 6302, 4112, 4113, -1, + 4112, 6302, 6303, -1, 6303, 4055, 4112, -1, + 4055, 6303, 6394, -1, 6394, 4053, 4055, -1, + 6394, 4066, 4053, -1, 6394, 6395, 4066, -1, + 6395, 6394, 6303, -1, 6395, 6303, 1365, -1, + 6395, 1365, 1363, -1, 1363, 4066, 6395, -1, + 4066, 1363, 1360, -1, 1360, 4065, 4066, -1, + 1360, 1362, 4065, -1, 6396, 4065, 1362, -1, + 6396, 4050, 4065, -1, 6396, 4051, 4050, -1, + 6396, 6397, 4051, -1, 6397, 6396, 1362, -1, + 1362, 6398, 6397, -1, 6398, 1362, 1361, -1, + 1361, 1364, 6398, -1, 1364, 1368, 6398, -1, + 6399, 6398, 1368, -1, 6399, 6397, 6398, -1, + 6397, 6399, 6400, -1, 6400, 4051, 6397, -1, + 4051, 6400, 6401, -1, 6401, 4049, 4051, -1, + 6401, 6134, 4049, -1, 6401, 6137, 6134, -1, + 6137, 6401, 6400, -1, 6400, 6139, 6137, -1, + 6139, 6400, 6399, -1, 6399, 1368, 6139, -1, + 1368, 2631, 6139, -1, 1368, 2630, 2631, -1, + 2630, 1368, 1367, -1, 1367, 2629, 2630, -1, + 2629, 1367, 1369, -1, 1369, 2628, 2629, -1, + 2628, 1369, 1371, -1, 1371, 2627, 2628, -1, + 2627, 1371, 1373, -1, 1373, 2626, 2627, -1, + 2626, 1373, 1375, -1, 1375, 2625, 2626, -1, + 2625, 1375, 1377, -1, 1377, 2624, 2625, -1, + 2624, 1377, 1378, -1, 1378, 2622, 2624, -1, + 2622, 1378, 1379, -1, 1379, 2620, 2622, -1, + 2620, 1379, 1380, -1, 1380, 2618, 2620, -1, + 2618, 1380, 1381, -1, 1381, 2616, 2618, -1, + 2616, 1381, 1382, -1, 1382, 2614, 2616, -1, + 2614, 1382, 1383, -1, 1383, 2612, 2614, -1, + 2612, 1383, 1384, -1, 1384, 2610, 2612, -1, + 2610, 1384, 1385, -1, 1385, 2608, 2610, -1, + 2608, 1385, 1386, -1, 1386, 2606, 2608, -1, + 2606, 1386, 1387, -1, 1387, 2604, 2606, -1, + 2604, 1387, 1388, -1, 1388, 2602, 2604, -1, + 2602, 1388, 1389, -1, 1389, 2600, 2602, -1, + 2600, 1389, 1390, -1, 1390, 2598, 2600, -1, + 2598, 1390, 1391, -1, 1391, 2596, 2598, -1, + 2596, 1391, 1392, -1, 1392, 2594, 2596, -1, + 2594, 1392, 1393, -1, 1393, 2592, 2594, -1, + 2592, 1393, 1394, -1, 1394, 2590, 2592, -1, + 2590, 1394, 1395, -1, 1395, 2588, 2590, -1, + 2588, 1395, 1396, -1, 1396, 2586, 2588, -1, + 2586, 1396, 1397, -1, 1397, 2584, 2586, -1, + 2584, 1397, 1398, -1, 1398, 2582, 2584, -1, + 2582, 1398, 1399, -1, 1399, 2580, 2582, -1, + 2580, 1399, 1400, -1, 1400, 2578, 2580, -1, + 2578, 1400, 1401, -1, 1401, 2576, 2578, -1, + 2576, 1401, 1402, -1, 1402, 2574, 2576, -1, + 2574, 1402, 1403, -1, 1403, 2572, 2574, -1, + 2572, 1403, 1404, -1, 1404, 2570, 2572, -1, + 2570, 1404, 1405, -1, 1405, 2568, 2570, -1, + 2568, 1405, 1406, -1, 1406, 2566, 2568, -1, + 2566, 1406, 1407, -1, 1407, 2564, 2566, -1, + 2564, 1407, 1408, -1, 1408, 2562, 2564, -1, + 2562, 1408, 1409, -1, 1409, 2560, 2562, -1, + 2560, 1409, 1410, -1, 1410, 2558, 2560, -1, + 2558, 1410, 1411, -1, 1411, 2556, 2558, -1, + 2556, 1411, 1412, -1, 1412, 2554, 2556, -1, + 2554, 1412, 1413, -1, 1413, 2552, 2554, -1, + 2552, 1413, 1414, -1, 1414, 2550, 2552, -1, + 2550, 1414, 1415, -1, 1415, 2548, 2550, -1, + 2548, 1415, 1416, -1, 1416, 2546, 2548, -1, + 2546, 1416, 1417, -1, 1417, 2544, 2546, -1, + 2544, 1417, 1418, -1, 1418, 6402, 2544, -1, + 1152, 6402, 1418, -1, 1418, 1062, 1152, -1, + 1062, 1418, 1419, -1, 1419, 1150, 1062, -1, + 1150, 1419, 1420, -1, 1420, 1148, 1150, -1, + 1148, 1420, 1421, -1, 1421, 1146, 1148, -1, + 1146, 1421, 1422, -1, 1422, 1144, 1146, -1, + 1144, 1422, 1423, -1, 1423, 1142, 1144, -1, + 1142, 1423, 1424, -1, 1424, 1140, 1142, -1, + 1140, 1424, 1425, -1, 1425, 1138, 1140, -1, + 1138, 1425, 1426, -1, 1426, 1136, 1138, -1, + 1136, 1426, 1427, -1, 1427, 1134, 1136, -1, + 1134, 1427, 1428, -1, 1428, 1132, 1134, -1, + 1132, 1428, 1429, -1, 1429, 1130, 1132, -1, + 1130, 1429, 1430, -1, 1430, 1128, 1130, -1, + 1128, 1430, 1431, -1, 1431, 1126, 1128, -1, + 1126, 1431, 1432, -1, 1432, 1124, 1126, -1, + 1124, 1432, 1433, -1, 1433, 1122, 1124, -1, + 1122, 1433, 1434, -1, 1434, 1120, 1122, -1, + 1120, 1434, 1435, -1, 1435, 1118, 1120, -1, + 1118, 1435, 1436, -1, 1436, 1116, 1118, -1, + 1116, 1436, 1437, -1, 1437, 1114, 1116, -1, + 1114, 1437, 1438, -1, 1438, 1112, 1114, -1, + 1112, 1438, 1439, -1, 1439, 1110, 1112, -1, + 1110, 1439, 1440, -1, 1440, 1108, 1110, -1, + 1108, 1440, 1441, -1, 1441, 1106, 1108, -1, + 1106, 1441, 1442, -1, 1442, 1104, 1106, -1, + 1104, 1442, 1443, -1, 1443, 1102, 1104, -1, + 1102, 1443, 1444, -1, 1444, 1100, 1102, -1, + 1100, 1444, 1445, -1, 1445, 1098, 1100, -1, + 1098, 1445, 1446, -1, 1446, 1096, 1098, -1, + 1096, 1446, 1447, -1, 1447, 1094, 1096, -1, + 1094, 1447, 1448, -1, 1448, 1092, 1094, -1, + 1092, 1448, 1449, -1, 1449, 1090, 1092, -1, + 1090, 1449, 1450, -1, 1450, 1088, 1090, -1, + 1088, 1450, 1451, -1, 1451, 1086, 1088, -1, + 1086, 1451, 1452, -1, 1452, 1084, 1086, -1, + 1084, 1452, 1453, -1, 1453, 1082, 1084, -1, + 1082, 1453, 1454, -1, 1454, 1080, 1082, -1, + 1080, 1454, 1455, -1, 1455, 1078, 1080, -1, + 1078, 1455, 1456, -1, 1456, 1076, 1078, -1, + 1076, 1456, 1457, -1, 1457, 1074, 1076, -1, + 1074, 1457, 1458, -1, 1458, 1072, 1074, -1, + 1072, 1458, 1459, -1, 1459, 1070, 1072, -1, + 1070, 1459, 1460, -1, 1460, 1068, 1070, -1, + 1068, 1460, 1474, -1, 1474, 1065, 1068, -1, + 1065, 1474, 1472, -1, 1472, 1066, 1065, -1, + 1066, 1472, 1470, -1, 1470, 6403, 1066, -1, + 6403, 1470, 1468, -1, 1468, 6404, 6403, -1, + 6404, 1468, 1466, -1, 1466, 6405, 6404, -1, + 6405, 1466, 1464, -1, 1464, 6406, 6405, -1, + 6406, 1464, 1463, -1, 1463, 1517, 6406, -1, + 1517, 6407, 6406, -1, 6407, 1517, 1518, -1, + 1518, 6408, 6407, -1, 6408, 1518, 1519, -1, + 1519, 6409, 6408, -1, 6409, 1519, 1520, -1, + 1520, 6410, 6409, -1, 6410, 1520, 1521, -1, + 1521, 6411, 6410, -1, 6411, 1521, 1522, -1, + 6411, 1522, 1524, -1, 6411, 1524, 1845, -1, + 1845, 6410, 6411, -1, 6410, 1845, 1846, -1, + 1846, 6409, 6410, -1, 6409, 1846, 1850, -1, + 1850, 6408, 6409, -1, 6408, 1850, 1847, -1, + 1847, 6407, 6408, -1, 6407, 1847, 1849, -1, + 1849, 6406, 6407, -1, 6406, 1849, 1852, -1, + 1852, 6405, 6406, -1, 6405, 1852, 1853, -1, + 1853, 6404, 6405, -1, 6404, 1853, 1854, -1, + 1854, 6403, 6404, -1, 6403, 1854, 1855, -1, + 1855, 1066, 6403, -1, 1066, 1855, 1856, -1, + 1856, 1067, 1066, -1, 1067, 1856, 1857, -1, + 1857, 1069, 1067, -1, 1069, 1857, 1858, -1, + 1858, 1071, 1069, -1, 1071, 1858, 1859, -1, + 1859, 1073, 1071, -1, 1073, 1859, 1860, -1, + 1860, 1075, 1073, -1, 1075, 1860, 1861, -1, + 1861, 1077, 1075, -1, 1077, 1861, 1862, -1, + 1862, 1079, 1077, -1, 1079, 1862, 1863, -1, + 1863, 1081, 1079, -1, 1081, 1863, 1864, -1, + 1864, 1083, 1081, -1, 1083, 1864, 1865, -1, + 1865, 1085, 1083, -1, 1085, 1865, 1866, -1, + 1866, 1087, 1085, -1, 1087, 1866, 1867, -1, + 1867, 1089, 1087, -1, 1089, 1867, 1868, -1, + 1868, 1091, 1089, -1, 1091, 1868, 1869, -1, + 1869, 1093, 1091, -1, 1093, 1869, 1870, -1, + 1870, 1095, 1093, -1, 1095, 1870, 1871, -1, + 1871, 1097, 1095, -1, 1097, 1871, 1872, -1, + 1872, 1099, 1097, -1, 1099, 1872, 1873, -1, + 1873, 1101, 1099, -1, 1101, 1873, 1874, -1, + 1874, 1103, 1101, -1, 1103, 1874, 1875, -1, + 1875, 1105, 1103, -1, 1105, 1875, 1876, -1, + 1876, 1107, 1105, -1, 1107, 1876, 1877, -1, + 1877, 1109, 1107, -1, 1109, 1877, 1878, -1, + 1878, 1111, 1109, -1, 1111, 1878, 1879, -1, + 1879, 1113, 1111, -1, 1113, 1879, 1880, -1, + 1880, 1115, 1113, -1, 1115, 1880, 1881, -1, + 1881, 1117, 1115, -1, 1117, 1881, 1882, -1, + 1882, 1119, 1117, -1, 1119, 1882, 1883, -1, + 1883, 1121, 1119, -1, 1121, 1883, 1884, -1, + 1884, 1123, 1121, -1, 1123, 1884, 1885, -1, + 1885, 1125, 1123, -1, 1125, 1885, 1886, -1, + 1886, 1127, 1125, -1, 1127, 1886, 1887, -1, + 1887, 1129, 1127, -1, 1129, 1887, 1888, -1, + 1888, 1131, 1129, -1, 1131, 1888, 1889, -1, + 1889, 1133, 1131, -1, 1133, 1889, 1890, -1, + 1890, 1135, 1133, -1, 1135, 1890, 1891, -1, + 1891, 1137, 1135, -1, 1137, 1891, 1892, -1, + 1892, 1139, 1137, -1, 1139, 1892, 1893, -1, + 1893, 1141, 1139, -1, 1141, 1893, 1894, -1, + 1894, 1143, 1141, -1, 1143, 1894, 1895, -1, + 1895, 1145, 1143, -1, 1145, 1895, 1896, -1, + 1896, 1147, 1145, -1, 1147, 1896, 1897, -1, + 1897, 1149, 1147, -1, 1149, 1897, 1901, -1, + 1901, 1063, 1149, -1, 1063, 1901, 6412, -1, + 6413, 6412, 1901, -1, 6413, 6414, 6412, -1, + 6415, 6414, 6413, -1, 6413, 1901, 6415, -1, + 6415, 1901, 1899, -1, 1899, 6414, 6415, -1, + 1899, 1898, 6414, -1, 6416, 6417, 6418, -1, + 6418, 6419, 6416, -1, 6419, 6418, 6420, -1, + 6420, 6421, 6419, -1, 6421, 6420, 6422, -1, + 6422, 6423, 6421, -1, 6423, 6422, 6424, -1, + 6424, 6425, 6423, -1, 6425, 6424, 6426, -1, + 6426, 6427, 6425, -1, 6427, 6426, 6428, -1, + 6428, 6429, 6427, -1, 6429, 6428, 6430, -1, + 6429, 6430, 6431, -1, 6431, 6432, 6429, -1, + 6432, 6431, 6433, -1, 6433, 6434, 6432, -1, + 6434, 6433, 6435, -1, 6435, 6436, 6434, -1, + 6436, 6435, 6437, -1, 6437, 6438, 6436, -1, + 6438, 6437, 6439, -1, 6439, 6440, 6438, -1, + 6440, 6439, 6441, -1, 6441, 6442, 6440, -1, + 6442, 6441, 6443, -1, 6443, 6444, 6442, -1, + 6445, 6442, 6444, -1, 6444, 6446, 6445, -1, + 6447, 6446, 6444, -1, 6447, 6444, 6448, -1, + 6444, 6449, 6448, -1, 6444, 6443, 6449, -1, + 6450, 6451, 6452, -1, 6453, 6454, 6455, -1, + 6456, 6457, 6458, -1, 6456, 6458, 6459, -1, + 6459, 6460, 6456, -1, 6460, 6459, 6461, -1, + 6461, 6462, 6460, -1, 6462, 6461, 6463, -1, + 6463, 6464, 6462, -1, 6464, 6463, 6465, -1, + 6465, 6466, 6464, -1, 6466, 6465, 6467, -1, + 6467, 6468, 6466, -1, 6468, 6467, 6469, -1, + 6469, 6470, 6468, -1, 6470, 6469, 6471, -1, + 6471, 6472, 6470, -1, 6472, 6471, 6473, -1, + 6473, 6474, 6472, -1, 6474, 6473, 6475, -1, + 6475, 6476, 6474, -1, 6476, 6475, 6477, -1, + 6477, 6478, 6476, -1, 6478, 6477, 6479, -1, + 6479, 6480, 6478, -1, 6480, 6479, 6481, -1, + 6481, 6482, 6480, -1, 6482, 6481, 6483, -1, + 6483, 6484, 6482, -1, 6484, 6483, 6485, -1, + 6484, 6485, 6486, -1, 6486, 6487, 6484, -1, + 6487, 6486, 6488, -1, 6488, 6489, 6487, -1, + 6489, 6488, 6490, -1, 6490, 6491, 6489, -1, + 6491, 6490, 6492, -1, 6492, 6493, 6491, -1, + 6493, 6492, 6494, -1, 6494, 6495, 6493, -1, + 6495, 6494, 6496, -1, 6496, 6497, 6495, -1, + 6497, 6496, 6498, -1, 6498, 6499, 6497, -1, + 6499, 6498, 6500, -1, 6500, 6501, 6499, -1, + 6501, 6500, 6502, -1, 6502, 6503, 6501, -1, + 6503, 6502, 6504, -1, 6504, 6505, 6503, -1, + 6505, 6504, 6506, -1, 6506, 6507, 6505, -1, + 6507, 6506, 6508, -1, 6508, 6509, 6507, -1, + 6509, 6508, 6510, -1, 6510, 6511, 6509, -1, + 6511, 6510, 6512, -1, 6511, 6512, 6513, -1, + 6514, 6513, 6512, -1, 6513, 6514, 6515, -1, + 6516, 6517, 6518, -1, 6518, 6515, 6516, -1, + 6518, 6519, 6515, -1, 6519, 6513, 6515, -1, + 6519, 6511, 6513, -1, 6519, 6518, 6511, -1, + 6511, 6518, 6517, -1, 6517, 6509, 6511, -1, + 6509, 6517, 6520, -1, 6520, 6507, 6509, -1, + 6507, 6520, 6521, -1, 6521, 6505, 6507, -1, + 6505, 6521, 6522, -1, 6522, 6503, 6505, -1, + 6503, 6522, 6523, -1, 6523, 6501, 6503, -1, + 6501, 6523, 6524, -1, 6524, 6499, 6501, -1, + 6499, 6524, 6525, -1, 6525, 6497, 6499, -1, + 6497, 6525, 6526, -1, 6526, 6495, 6497, -1, + 6495, 6526, 6527, -1, 6527, 6493, 6495, -1, + 6493, 6527, 6528, -1, 6528, 6491, 6493, -1, + 6491, 6528, 6529, -1, 6529, 6489, 6491, -1, + 6489, 6529, 6530, -1, 6530, 6487, 6489, -1, + 6487, 6530, 6531, -1, 6531, 6484, 6487, -1, + 6531, 6482, 6484, -1, 6482, 6531, 6532, -1, + 6532, 6480, 6482, -1, 6480, 6532, 6533, -1, + 6533, 6478, 6480, -1, 6478, 6533, 6534, -1, + 6534, 6476, 6478, -1, 6476, 6534, 6535, -1, + 6535, 6474, 6476, -1, 6474, 6535, 6536, -1, + 6536, 6472, 6474, -1, 6472, 6536, 6537, -1, + 6537, 6470, 6472, -1, 6470, 6537, 6538, -1, + 6538, 6468, 6470, -1, 6468, 6538, 6539, -1, + 6539, 6466, 6468, -1, 6466, 6539, 6540, -1, + 6540, 6464, 6466, -1, 6464, 6540, 6541, -1, + 6541, 6462, 6464, -1, 6462, 6541, 6542, -1, + 6542, 6460, 6462, -1, 6460, 6542, 6543, -1, + 6543, 6456, 6460, -1, 6456, 6543, 6544, -1, + 6545, 6546, 6547, -1, 6547, 6546, 6548, -1, + 6549, 6548, 6550, -1, 6550, 6548, 6546, -1, + 6545, 6544, 6543, -1, 6544, 6545, 6547, -1, + 6544, 6547, 6551, -1, 6551, 6456, 6544, -1, + 6551, 6457, 6456, -1, 6457, 6551, 6547, -1, + 6457, 6547, 6552, -1, 6552, 6458, 6457, -1, + 6552, 6553, 6458, -1, 6553, 6554, 6458, -1, + 6453, 6458, 6554, -1, 6458, 6453, 6555, -1, + 6555, 6459, 6458, -1, 6459, 6555, 6556, -1, + 6556, 6461, 6459, -1, 6461, 6556, 6557, -1, + 6557, 6463, 6461, -1, 6463, 6557, 6558, -1, + 6558, 6465, 6463, -1, 6465, 6558, 6559, -1, + 6559, 6467, 6465, -1, 6467, 6559, 6560, -1, + 6560, 6469, 6467, -1, 6469, 6560, 6561, -1, + 6561, 6471, 6469, -1, 6471, 6561, 6562, -1, + 6562, 6473, 6471, -1, 6473, 6562, 6563, -1, + 6563, 6475, 6473, -1, 6475, 6563, 6564, -1, + 6564, 6477, 6475, -1, 6477, 6564, 6565, -1, + 6565, 6479, 6477, -1, 6479, 6565, 6566, -1, + 6566, 6481, 6479, -1, 6481, 6566, 6567, -1, + 6567, 6483, 6481, -1, 6483, 6567, 6568, -1, + 6568, 6485, 6483, -1, 6485, 6568, 6569, -1, + 6485, 6569, 6570, -1, 6570, 6486, 6485, -1, + 6486, 6570, 6571, -1, 6571, 6488, 6486, -1, + 6488, 6571, 6572, -1, 6572, 6490, 6488, -1, + 6490, 6572, 6573, -1, 6573, 6492, 6490, -1, + 6492, 6573, 6574, -1, 6574, 6494, 6492, -1, + 6494, 6574, 6575, -1, 6575, 6496, 6494, -1, + 6496, 6575, 6576, -1, 6576, 6498, 6496, -1, + 6498, 6576, 6577, -1, 6577, 6500, 6498, -1, + 6500, 6577, 6578, -1, 6578, 6502, 6500, -1, + 6502, 6578, 6579, -1, 6579, 6504, 6502, -1, + 6504, 6579, 6580, -1, 6580, 6506, 6504, -1, + 6506, 6580, 6581, -1, 6581, 6508, 6506, -1, + 6508, 6581, 6582, -1, 6582, 6510, 6508, -1, + 6510, 6582, 6583, -1, 6583, 6512, 6510, -1, + 6512, 6583, 6584, -1, 6584, 6585, 6512, -1, + 6586, 6585, 6584, -1, 6586, 6584, 6587, -1, + 6584, 6588, 6587, -1, 6584, 6589, 6588, -1, + 6589, 6584, 6583, -1, 6583, 6590, 6589, -1, + 6590, 6583, 6582, -1, 6582, 6591, 6590, -1, + 6591, 6582, 6581, -1, 6581, 6592, 6591, -1, + 6592, 6581, 6580, -1, 6580, 6593, 6592, -1, + 6593, 6580, 6579, -1, 6579, 6594, 6593, -1, + 6594, 6579, 6578, -1, 6578, 6595, 6594, -1, + 6595, 6578, 6577, -1, 6577, 6596, 6595, -1, + 6596, 6577, 6576, -1, 6576, 6597, 6596, -1, + 6597, 6576, 6575, -1, 6575, 6598, 6597, -1, + 6598, 6575, 6574, -1, 6574, 6599, 6598, -1, + 6599, 6574, 6573, -1, 6573, 6600, 6599, -1, + 6600, 6573, 6572, -1, 6572, 6601, 6600, -1, + 6601, 6572, 6571, -1, 6571, 6602, 6601, -1, + 6602, 6571, 6570, -1, 6570, 6603, 6602, -1, + 6603, 6570, 6569, -1, 6569, 6604, 6603, -1, + 6569, 6605, 6604, -1, 6605, 6569, 6568, -1, + 6568, 6606, 6605, -1, 6606, 6568, 6567, -1, + 6567, 6607, 6606, -1, 6607, 6567, 6566, -1, + 6566, 6608, 6607, -1, 6608, 6566, 6565, -1, + 6565, 6609, 6608, -1, 6609, 6565, 6564, -1, + 6564, 6610, 6609, -1, 6610, 6564, 6563, -1, + 6563, 6611, 6610, -1, 6611, 6563, 6562, -1, + 6562, 6612, 6611, -1, 6612, 6562, 6561, -1, + 6561, 6613, 6612, -1, 6613, 6561, 6560, -1, + 6560, 6614, 6613, -1, 6614, 6560, 6559, -1, + 6559, 6615, 6614, -1, 6615, 6559, 6558, -1, + 6558, 6616, 6615, -1, 6616, 6558, 6557, -1, + 6557, 6617, 6616, -1, 6617, 6557, 6556, -1, + 6556, 6618, 6617, -1, 6618, 6556, 6555, -1, + 6555, 6619, 6618, -1, 6619, 6555, 6453, -1, + 6453, 6455, 6619, -1, 6620, 6621, 6455, -1, + 6622, 6455, 6621, -1, 6455, 6622, 6623, -1, + 6623, 6619, 6455, -1, 6619, 6623, 6624, -1, + 6624, 6618, 6619, -1, 6618, 6624, 6625, -1, + 6625, 6617, 6618, -1, 6617, 6625, 6626, -1, + 6626, 6616, 6617, -1, 6616, 6626, 6627, -1, + 6627, 6615, 6616, -1, 6615, 6627, 6628, -1, + 6628, 6614, 6615, -1, 6614, 6628, 6629, -1, + 6629, 6613, 6614, -1, 6613, 6629, 6630, -1, + 6630, 6612, 6613, -1, 6612, 6630, 6631, -1, + 6631, 6611, 6612, -1, 6611, 6631, 6632, -1, + 6632, 6610, 6611, -1, 6610, 6632, 6633, -1, + 6633, 6609, 6610, -1, 6609, 6633, 6634, -1, + 6634, 6608, 6609, -1, 6608, 6634, 6635, -1, + 6635, 6607, 6608, -1, 6607, 6635, 6636, -1, + 6636, 6606, 6607, -1, 6606, 6636, 6637, -1, + 6637, 6605, 6606, -1, 6605, 6637, 6638, -1, + 6638, 6604, 6605, -1, 6639, 6603, 6604, -1, + 6603, 6639, 6640, -1, 6640, 6602, 6603, -1, + 6602, 6640, 6641, -1, 6641, 6601, 6602, -1, + 6601, 6641, 6642, -1, 6642, 6600, 6601, -1, + 6600, 6642, 6643, -1, 6643, 6599, 6600, -1, + 6599, 6643, 6644, -1, 6644, 6598, 6599, -1, + 6598, 6644, 6645, -1, 6645, 6597, 6598, -1, + 6597, 6645, 6646, -1, 6646, 6596, 6597, -1, + 6596, 6646, 6647, -1, 6647, 6595, 6596, -1, + 6595, 6647, 6648, -1, 6648, 6594, 6595, -1, + 6594, 6648, 6649, -1, 6649, 6593, 6594, -1, + 6593, 6649, 6650, -1, 6650, 6592, 6593, -1, + 6592, 6650, 6651, -1, 6651, 6591, 6592, -1, + 6591, 6651, 6652, -1, 6652, 6590, 6591, -1, + 6590, 6652, 6653, -1, 6653, 6589, 6590, -1, + 6589, 6653, 6654, -1, 6654, 6588, 6589, -1, + 6588, 6654, 6655, -1, 6655, 6656, 6588, -1, + 6656, 6657, 6658, -1, 6656, 6655, 6657, -1, + 6659, 6657, 6655, -1, 6659, 6658, 6657, -1, + 6659, 6660, 6658, -1, 6659, 6655, 6660, -1, + 6661, 6660, 6655, -1, 6655, 6662, 6661, -1, + 6662, 6655, 6654, -1, 6654, 6663, 6662, -1, + 6663, 6654, 6653, -1, 6653, 6664, 6663, -1, + 6664, 6653, 6652, -1, 6652, 6665, 6664, -1, + 6665, 6652, 6651, -1, 6651, 6666, 6665, -1, + 6666, 6651, 6650, -1, 6650, 6667, 6666, -1, + 6667, 6650, 6649, -1, 6649, 6668, 6667, -1, + 6668, 6649, 6648, -1, 6648, 6669, 6668, -1, + 6669, 6648, 6647, -1, 6647, 6670, 6669, -1, + 6670, 6647, 6646, -1, 6646, 6671, 6670, -1, + 6671, 6646, 6645, -1, 6645, 6672, 6671, -1, + 6672, 6645, 6644, -1, 6644, 6673, 6672, -1, + 6673, 6644, 6643, -1, 6643, 6674, 6673, -1, + 6674, 6643, 6642, -1, 6642, 6675, 6674, -1, + 6675, 6642, 6641, -1, 6641, 6676, 6675, -1, + 6676, 6641, 6640, -1, 6640, 6677, 6676, -1, + 6677, 6640, 6639, -1, 6639, 6678, 6677, -1, + 6679, 6680, 6678, -1, 6679, 6681, 6680, -1, + 6638, 6682, 6681, -1, 6682, 6638, 6637, -1, + 6637, 6683, 6682, -1, 6683, 6637, 6636, -1, + 6636, 6684, 6683, -1, 6684, 6636, 6635, -1, + 6635, 6685, 6684, -1, 6685, 6635, 6634, -1, + 6634, 6686, 6685, -1, 6686, 6634, 6633, -1, + 6633, 6687, 6686, -1, 6687, 6633, 6632, -1, + 6632, 6688, 6687, -1, 6688, 6632, 6631, -1, + 6631, 6689, 6688, -1, 6689, 6631, 6630, -1, + 6630, 6690, 6689, -1, 6690, 6630, 6629, -1, + 6629, 6691, 6690, -1, 6691, 6629, 6628, -1, + 6628, 6692, 6691, -1, 6692, 6628, 6627, -1, + 6627, 6693, 6692, -1, 6693, 6627, 6626, -1, + 6626, 6694, 6693, -1, 6694, 6626, 6625, -1, + 6625, 6695, 6694, -1, 6695, 6625, 6624, -1, + 6624, 6696, 6695, -1, 6696, 6624, 6623, -1, + 6623, 6697, 6696, -1, 6697, 6623, 6622, -1, + 6622, 6698, 6697, -1, 6699, 6700, 6698, -1, + 6699, 6698, 6701, -1, 6698, 6622, 6701, -1, + 6702, 6450, 6701, -1, 6702, 6701, 6622, -1, + 6702, 6622, 6621, -1, 6621, 6450, 6702, -1, + 6621, 6620, 6450, -1, 6620, 6451, 6450, -1, + 6451, 6620, 6455, -1, 6451, 6455, 6454, -1, + 6454, 6452, 6451, -1, 6454, 6703, 6452, -1, + 6703, 6454, 6453, -1, 6703, 6453, 6554, -1, + 6554, 6452, 6703, -1, 6554, 6553, 6452, -1, + 6553, 6552, 6452, -1, 6452, 6552, 6547, -1, + 6548, 6704, 6705, -1, 6706, 6704, 6548, -1, + 6704, 6706, 6707, -1, 6704, 6707, 6708, -1, + 6708, 6705, 6704, -1, 6708, 6709, 6705, -1, + 6710, 6711, 6712, -1, 6710, 6712, 6705, -1, + 6710, 6705, 6709, -1, 6709, 6711, 6710, -1, + 6709, 6708, 6711, -1, 6711, 6708, 6707, -1, + 6711, 6707, 6713, -1, 6713, 6714, 6711, -1, + 6714, 6713, 6715, -1, 6715, 6716, 6714, -1, + 6716, 6715, 6717, -1, 6717, 6718, 6716, -1, + 6718, 6717, 6719, -1, 6719, 6720, 6718, -1, + 6720, 6719, 6721, -1, 6721, 6722, 6720, -1, + 6722, 6721, 6723, -1, 6723, 6724, 6722, -1, + 6724, 6723, 6725, -1, 6725, 6726, 6724, -1, + 6726, 6725, 6727, -1, 6727, 6728, 6726, -1, + 6728, 6727, 6729, -1, 6729, 6730, 6728, -1, + 6730, 6729, 6731, -1, 6730, 6731, 6732, -1, + 6732, 6733, 6730, -1, 6733, 6732, 6734, -1, + 6734, 6735, 6733, -1, 6735, 6734, 6736, -1, + 6736, 6737, 6735, -1, 6737, 6736, 6738, -1, + 6738, 6739, 6737, -1, 6739, 6738, 6740, -1, + 6740, 6741, 6739, -1, 6741, 6740, 6742, -1, + 6742, 6743, 6741, -1, 6743, 6742, 6744, -1, + 6744, 6745, 6743, -1, 6745, 6744, 6746, -1, + 6746, 6747, 6745, -1, 6747, 6746, 6748, -1, + 6748, 6749, 6747, -1, 6749, 6748, 6750, -1, + 6749, 6750, 6751, -1, 6752, 6751, 6750, -1, + 6751, 6752, 6753, -1, 6754, 6753, 6755, -1, + 6754, 6756, 6753, -1, 6756, 6751, 6753, -1, + 6756, 6749, 6751, -1, 6756, 6754, 6749, -1, + 6754, 6755, 6749, -1, 6449, 6749, 6755, -1, + 6449, 6747, 6749, -1, 6747, 6449, 6443, -1, + 6443, 6745, 6747, -1, 6745, 6443, 6441, -1, + 6441, 6743, 6745, -1, 6743, 6441, 6439, -1, + 6439, 6741, 6743, -1, 6741, 6439, 6437, -1, + 6437, 6739, 6741, -1, 6739, 6437, 6435, -1, + 6435, 6737, 6739, -1, 6737, 6435, 6433, -1, + 6433, 6735, 6737, -1, 6735, 6433, 6431, -1, + 6431, 6733, 6735, -1, 6733, 6431, 6430, -1, + 6430, 6730, 6733, -1, 6430, 6728, 6730, -1, + 6728, 6430, 6428, -1, 6428, 6726, 6728, -1, + 6726, 6428, 6426, -1, 6426, 6724, 6726, -1, + 6724, 6426, 6424, -1, 6424, 6722, 6724, -1, + 6722, 6424, 6422, -1, 6422, 6720, 6722, -1, + 6720, 6422, 6420, -1, 6420, 6718, 6720, -1, + 6718, 6420, 6418, -1, 6418, 6716, 6718, -1, + 6716, 6418, 6417, -1, 6417, 6714, 6716, -1, + 6714, 6417, 6757, -1, 6757, 6711, 6714, -1, + 6757, 6712, 6711, -1, 6758, 6712, 6757, -1, + 6758, 6705, 6712, -1, 6758, 6759, 6705, -1, + 6758, 6757, 6759, -1, 6760, 6759, 6757, -1, + 6760, 6757, 6417, -1, 6417, 6416, 6760, -1, + 6760, 6761, 6762, -1, 6761, 6760, 6416, -1, + 6416, 6763, 6761, -1, 6763, 6416, 6419, -1, + 6419, 6764, 6763, -1, 6764, 6419, 6421, -1, + 6421, 6765, 6764, -1, 6765, 6421, 6423, -1, + 6423, 6766, 6765, -1, 6766, 6423, 6425, -1, + 6425, 6767, 6766, -1, 6767, 6425, 6427, -1, + 6427, 6768, 6767, -1, 6768, 6427, 6429, -1, + 6768, 6429, 6432, -1, 6432, 6769, 6768, -1, + 6769, 6432, 6434, -1, 6434, 6770, 6769, -1, + 6770, 6434, 6436, -1, 6436, 6771, 6770, -1, + 6771, 6436, 6438, -1, 6438, 6772, 6771, -1, + 6772, 6438, 6440, -1, 6440, 6773, 6772, -1, + 6773, 6440, 6442, -1, 6442, 6445, 6773, -1, + 113, 6773, 6445, -1, 6773, 113, 6774, -1, + 6774, 6772, 6773, -1, 6772, 6774, 6775, -1, + 6775, 6771, 6772, -1, 6771, 6775, 6776, -1, + 6776, 6770, 6771, -1, 6770, 6776, 6777, -1, + 6777, 6769, 6770, -1, 6769, 6777, 6778, -1, + 6778, 6768, 6769, -1, 6778, 6767, 6768, -1, + 6767, 6778, 6779, -1, 6779, 6766, 6767, -1, + 6766, 6779, 6780, -1, 6780, 6765, 6766, -1, + 6765, 6780, 6781, -1, 6781, 6764, 6765, -1, + 6764, 6781, 6782, -1, 6782, 6763, 6764, -1, + 6763, 6782, 6783, -1, 6783, 6761, 6763, -1, + 6783, 6784, 6761, -1, 6785, 6786, 6787, -1, + 6785, 6784, 6786, -1, 6785, 6761, 6784, -1, + 6785, 6787, 6761, -1, 6787, 6762, 6761, -1, + 6762, 6787, 6786, -1, 6762, 6786, 6788, -1, + 6788, 6760, 6762, -1, 6788, 6759, 6760, -1, + 6759, 6788, 6786, -1, 6786, 6705, 6759, -1, + 6414, 6789, 6790, -1, 6789, 6414, 1898, -1, + 1898, 1900, 6789, -1, 1900, 1902, 6789, -1, + 6791, 6789, 1902, -1, 6791, 6790, 6789, -1, + 6792, 6790, 6791, -1, 6791, 1902, 6792, -1, + 6792, 1902, 1904, -1, 1904, 6790, 6792, -1, + 1904, 1903, 6790, -1, 6793, 6794, 6795, -1, + 6793, 6796, 6794, -1, 6796, 6793, 6797, -1, + 6798, 6799, 6800, -1, 6798, 6793, 6799, -1, + 6798, 6797, 6793, -1, 6798, 6800, 6797, -1, + 6801, 6797, 6800, -1, 6801, 6796, 6797, -1, + 6801, 6802, 6796, -1, 6802, 6801, 6800, -1, + 6800, 6803, 6802, -1, 6790, 6804, 6805, -1, + 6804, 6790, 1903, -1, 1903, 1905, 6804, -1, + 1905, 1906, 6804, -1, 6806, 6804, 1906, -1, + 6806, 6805, 6804, -1, 6807, 6805, 6806, -1, + 6806, 1906, 6807, -1, 6807, 1906, 1908, -1, + 1908, 6805, 6807, -1, 1908, 6808, 6805, -1, + 6808, 1908, 1907, -1, 6808, 1907, 1910, -1, + 1910, 6805, 6808, -1, 1910, 6809, 6805, -1, + 6809, 1910, 1909, -1, 6809, 1909, 2190, -1, + 2190, 2193, 6809, -1, 2193, 6805, 6809, -1, + 6810, 2194, 2291, -1, 6811, 6810, 2291, -1, + 2291, 2238, 6811, -1, 6811, 2238, 2236, -1, + 2236, 6810, 6811, -1, 2236, 2235, 6810, -1, + 6812, 6813, 6814, -1, 6813, 6812, 6810, -1, + 6813, 6810, 2235, -1, 2235, 2237, 6813, -1, + 2237, 6814, 6813, -1, 6814, 2237, 2240, -1, + 2240, 6815, 6814, -1, 6815, 2240, 2242, -1, + 2242, 6816, 6815, -1, 6816, 2242, 2244, -1, + 2244, 6817, 6816, -1, 6817, 2244, 2246, -1, + 2246, 6818, 6817, -1, 6818, 2246, 2248, -1, + 2248, 6819, 6818, -1, 6819, 2248, 2250, -1, + 2250, 6820, 6819, -1, 6820, 2250, 2252, -1, + 2252, 6821, 6820, -1, 6821, 2252, 2254, -1, + 2254, 6822, 6821, -1, 6822, 2254, 2256, -1, + 2256, 6823, 6822, -1, 6823, 2256, 2258, -1, + 2258, 6824, 6823, -1, 6824, 2258, 2260, -1, + 2260, 6825, 6824, -1, 6825, 2260, 2262, -1, + 2262, 6826, 6825, -1, 6826, 2262, 2264, -1, + 2264, 6827, 6826, -1, 6827, 2264, 2266, -1, + 2266, 2269, 6827, -1, 6827, 2269, 6828, -1, + 6828, 6826, 6827, -1, 6826, 6828, 6829, -1, + 6829, 6825, 6826, -1, 6825, 6829, 6830, -1, + 6830, 6824, 6825, -1, 6824, 6830, 6831, -1, + 6831, 6823, 6824, -1, 6823, 6831, 6832, -1, + 6832, 6822, 6823, -1, 6822, 6832, 6833, -1, + 6833, 6821, 6822, -1, 6821, 6833, 6834, -1, + 6834, 6820, 6821, -1, 6820, 6834, 6835, -1, + 6835, 6819, 6820, -1, 6819, 6835, 6836, -1, + 6836, 6818, 6819, -1, 6818, 6836, 6837, -1, + 6837, 6817, 6818, -1, 6817, 6837, 6838, -1, + 6838, 6816, 6817, -1, 6816, 6838, 6839, -1, + 6839, 6815, 6816, -1, 6815, 6839, 6840, -1, + 6840, 6814, 6815, -1, 6840, 6841, 6814, -1, + 6842, 6841, 6840, -1, 6843, 6842, 6840, -1, + 6843, 6840, 6844, -1, 805, 6844, 6840, -1, + 805, 6840, 6839, -1, 6839, 1061, 805, -1, + 1061, 6839, 6838, -1, 6838, 1060, 1061, -1, + 1060, 6838, 6837, -1, 6837, 1059, 1060, -1, + 1059, 6837, 6836, -1, 6836, 1058, 1059, -1, + 1058, 6836, 6835, -1, 6835, 1057, 1058, -1, + 1057, 6835, 6834, -1, 6834, 1056, 1057, -1, + 1056, 6834, 6833, -1, 6833, 1055, 1056, -1, + 1055, 6833, 6832, -1, 6832, 1054, 1055, -1, + 1054, 6832, 6831, -1, 6831, 1053, 1054, -1, + 1053, 6831, 6830, -1, 6830, 1052, 1053, -1, + 1052, 6830, 6829, -1, 6829, 1051, 1052, -1, + 1051, 6829, 6828, -1, 6828, 1050, 1051, -1, + 1050, 6828, 2269, -1, 2269, 1049, 1050, -1, + 1049, 2269, 2270, -1, 2270, 1048, 1049, -1, + 1048, 2270, 2272, -1, 2272, 1047, 1048, -1, + 1047, 2272, 2287, -1, 2287, 1046, 1047, -1, + 1046, 2287, 2285, -1, 2285, 1045, 1046, -1, + 1045, 2285, 2283, -1, 2283, 1044, 1045, -1, + 1044, 2283, 2281, -1, 2281, 1043, 1044, -1, + 1043, 2281, 2279, -1, 2279, 1042, 1043, -1, + 1042, 2279, 2277, -1, 2277, 1041, 1042, -1, + 1041, 2277, 2275, -1, 2275, 923, 1041, -1, + 923, 2275, 2274, -1, 2274, 924, 923, -1, + 924, 2274, 2293, -1, 2293, 926, 924, -1, + 926, 2293, 2294, -1, 2294, 928, 926, -1, + 928, 2294, 2295, -1, 2295, 930, 928, -1, + 930, 2295, 2296, -1, 2296, 932, 930, -1, + 932, 2296, 2297, -1, 2297, 934, 932, -1, + 934, 2297, 2298, -1, 2298, 936, 934, -1, + 936, 2298, 2299, -1, 2299, 938, 936, -1, + 938, 2299, 2300, -1, 2300, 940, 938, -1, + 940, 2300, 2301, -1, 2301, 942, 940, -1, + 942, 2301, 2302, -1, 2302, 944, 942, -1, + 944, 2302, 2303, -1, 2303, 946, 944, -1, + 946, 2303, 2304, -1, 2304, 948, 946, -1, + 948, 2304, 2305, -1, 2305, 950, 948, -1, + 950, 2305, 2306, -1, 2306, 952, 950, -1, + 952, 2306, 2307, -1, 2307, 954, 952, -1, + 954, 2307, 2308, -1, 2308, 956, 954, -1, + 956, 2308, 2309, -1, 2309, 958, 956, -1, + 958, 2309, 2310, -1, 2310, 960, 958, -1, + 960, 2310, 2311, -1, 2311, 962, 960, -1, + 962, 2311, 2312, -1, 2312, 921, 962, -1, + 921, 2312, 2313, -1, 2313, 919, 921, -1, + 919, 2313, 2314, -1, 2314, 917, 919, -1, + 917, 2314, 2315, -1, 2315, 915, 917, -1, + 915, 2315, 2316, -1, 2316, 914, 915, -1, + 914, 2316, 2317, -1, 914, 2317, 2318, -1, + 2318, 912, 914, -1, 912, 2318, 2319, -1, + 2319, 910, 912, -1, 910, 2319, 2320, -1, + 2320, 908, 910, -1, 908, 2320, 2321, -1, + 2321, 905, 908, -1, 905, 2321, 2322, -1, + 2322, 906, 905, -1, 906, 2322, 2323, -1, + 2323, 6845, 906, -1, 6845, 2323, 2324, -1, + 2324, 6846, 6845, -1, 6846, 2324, 2325, -1, + 2325, 6847, 6846, -1, 6847, 2325, 2326, -1, + 2326, 6848, 6847, -1, 6848, 2326, 2327, -1, + 2327, 6849, 6848, -1, 6849, 2327, 2328, -1, + 2328, 6850, 6849, -1, 6850, 2328, 2329, -1, + 2329, 6851, 6850, -1, 6851, 2329, 2330, -1, + 2330, 6852, 6851, -1, 6852, 2330, 2331, -1, + 2331, 6853, 6852, -1, 6853, 2331, 2332, -1, + 2332, 6854, 6853, -1, 6854, 2332, 2333, -1, + 2333, 6855, 6854, -1, 6855, 2333, 2334, -1, + 2334, 6856, 6855, -1, 6856, 2334, 2335, -1, + 2335, 6857, 6856, -1, 6857, 2335, 2336, -1, + 2336, 6858, 6857, -1, 6858, 2336, 2337, -1, + 2337, 6859, 6858, -1, 6859, 2337, 2338, -1, + 2338, 6860, 6859, -1, 6860, 2338, 2339, -1, + 2339, 6861, 6860, -1, 6861, 2339, 2340, -1, + 2340, 6862, 6861, -1, 6862, 2340, 2341, -1, + 2341, 6863, 6862, -1, 6863, 2341, 2342, -1, + 2342, 6864, 6863, -1, 6864, 2342, 2343, -1, + 2343, 6865, 6864, -1, 6865, 2343, 2344, -1, + 2344, 6866, 6865, -1, 6866, 2344, 2345, -1, + 2345, 6867, 6866, -1, 6867, 2345, 2346, -1, + 2346, 6868, 6867, -1, 6868, 2346, 2347, -1, + 2347, 6869, 6868, -1, 6869, 2347, 2348, -1, + 2348, 6870, 6869, -1, 6870, 2348, 2349, -1, + 2349, 6871, 6870, -1, 6871, 2349, 2350, -1, + 2350, 6872, 6871, -1, 6872, 2350, 2351, -1, + 2351, 6873, 6872, -1, 6873, 2351, 2352, -1, + 2352, 6874, 6873, -1, 6874, 2352, 2353, -1, + 2353, 6875, 6874, -1, 6875, 2353, 2354, -1, + 2354, 6876, 6875, -1, 6876, 2354, 2355, -1, + 2355, 6877, 6876, -1, 6877, 2355, 2356, -1, + 2356, 6878, 6877, -1, 6878, 2356, 2357, -1, + 2357, 6879, 6878, -1, 6879, 2357, 2358, -1, + 2358, 6880, 6879, -1, 6880, 2358, 2359, -1, + 2359, 6881, 6880, -1, 6881, 2359, 2360, -1, + 2360, 6882, 6881, -1, 6882, 2360, 2361, -1, + 2361, 6883, 6882, -1, 6883, 2361, 2362, -1, + 2362, 6884, 6883, -1, 6884, 2362, 2363, -1, + 2363, 6885, 6884, -1, 6885, 2363, 2364, -1, + 2364, 6886, 6885, -1, 6886, 2364, 2365, -1, + 2365, 6887, 6886, -1, 6887, 2365, 2366, -1, + 2366, 6888, 6887, -1, 6888, 2366, 2367, -1, + 2367, 6889, 6888, -1, 6889, 2367, 2368, -1, + 2368, 6890, 6889, -1, 6890, 2368, 2369, -1, + 2369, 6891, 6890, -1, 6891, 2369, 2370, -1, + 2370, 6166, 6891, -1, 6892, 6891, 6166, -1, + 6892, 6166, 2519, -1, 6892, 2519, 2518, -1, + 2518, 6891, 6892, -1, 2518, 2520, 6891, -1, + 6891, 2520, 2406, -1, 2406, 6890, 6891, -1, + 6890, 2406, 2408, -1, 2408, 6889, 6890, -1, + 6889, 2408, 2436, -1, 2436, 6888, 6889, -1, + 6888, 2436, 2434, -1, 2434, 6887, 6888, -1, + 6887, 2434, 2432, -1, 2432, 6886, 6887, -1, + 6886, 2432, 2430, -1, 2430, 6885, 6886, -1, + 6885, 2430, 2428, -1, 2428, 6884, 6885, -1, + 6884, 2428, 2426, -1, 2426, 6883, 6884, -1, + 6883, 2426, 2424, -1, 2424, 6882, 6883, -1, + 6882, 2424, 2422, -1, 2422, 6881, 6882, -1, + 6881, 2422, 2420, -1, 2420, 6880, 6881, -1, + 6880, 2420, 2418, -1, 2418, 6879, 6880, -1, + 6879, 2418, 2416, -1, 2416, 6878, 6879, -1, + 6878, 2416, 2414, -1, 2414, 6877, 6878, -1, + 6877, 2414, 2412, -1, 2412, 6876, 6877, -1, + 6876, 2412, 2409, -1, 2409, 6875, 6876, -1, + 6875, 2409, 2411, -1, 2411, 6874, 6875, -1, + 6874, 2411, 2440, -1, 2440, 6873, 6874, -1, + 6873, 2440, 2441, -1, 2441, 6872, 6873, -1, + 6872, 2441, 2512, -1, 2512, 6871, 6872, -1, + 6871, 2512, 2442, -1, 2442, 6870, 6871, -1, + 6870, 2442, 2445, -1, 2445, 6869, 6870, -1, + 6869, 2445, 2447, -1, 2447, 6868, 6869, -1, + 6868, 2447, 2449, -1, 2449, 6867, 6868, -1, + 6867, 2449, 2451, -1, 2451, 6866, 6867, -1, + 6866, 2451, 2453, -1, 2453, 6865, 6866, -1, + 6865, 2453, 2455, -1, 2455, 6864, 6865, -1, + 6864, 2455, 2456, -1, 2456, 6863, 6864, -1, + 6863, 2456, 2458, -1, 2458, 6862, 6863, -1, + 6862, 2458, 6893, -1, 6893, 6861, 6862, -1, + 6861, 6893, 6894, -1, 6894, 6860, 6861, -1, + 6860, 6894, 6895, -1, 6895, 6859, 6860, -1, + 6859, 6895, 6896, -1, 6896, 6858, 6859, -1, + 6858, 6896, 6897, -1, 6897, 6857, 6858, -1, + 6857, 6897, 6898, -1, 6898, 6856, 6857, -1, + 6856, 6898, 6899, -1, 6899, 6855, 6856, -1, + 6855, 6899, 6900, -1, 6900, 6854, 6855, -1, + 6854, 6900, 6901, -1, 6901, 6853, 6854, -1, + 6853, 6901, 6902, -1, 6902, 6852, 6853, -1, + 6852, 6902, 6903, -1, 6903, 6851, 6852, -1, + 6851, 6903, 6904, -1, 6904, 6850, 6851, -1, + 6850, 6904, 6905, -1, 6905, 6849, 6850, -1, + 6849, 6905, 6906, -1, 6906, 6848, 6849, -1, + 6848, 6906, 6907, -1, 6907, 6847, 6848, -1, + 6847, 6907, 6908, -1, 6908, 6846, 6847, -1, + 6846, 6908, 6909, -1, 6909, 6845, 6846, -1, + 6845, 6909, 6910, -1, 6910, 906, 6845, -1, + 6910, 904, 906, -1, 6910, 902, 904, -1, + 902, 6910, 6909, -1, 6909, 900, 902, -1, + 900, 6909, 6908, -1, 6908, 898, 900, -1, + 898, 6908, 6907, -1, 6907, 896, 898, -1, + 896, 6907, 6906, -1, 6906, 894, 896, -1, + 894, 6906, 6905, -1, 6905, 892, 894, -1, + 892, 6905, 6904, -1, 6904, 890, 892, -1, + 890, 6904, 6903, -1, 6903, 888, 890, -1, + 888, 6903, 6902, -1, 6902, 886, 888, -1, + 886, 6902, 6901, -1, 6901, 884, 886, -1, + 884, 6901, 6900, -1, 6900, 882, 884, -1, + 882, 6900, 6899, -1, 6899, 880, 882, -1, + 880, 6899, 6898, -1, 6898, 878, 880, -1, + 878, 6898, 6897, -1, 6897, 876, 878, -1, + 876, 6897, 6896, -1, 6896, 874, 876, -1, + 874, 6896, 6895, -1, 6895, 872, 874, -1, + 872, 6895, 6894, -1, 6894, 870, 872, -1, + 870, 6894, 6893, -1, 6893, 867, 870, -1, + 867, 6893, 2458, -1, 2458, 868, 867, -1, + 868, 2458, 2457, -1, 2457, 2459, 868, -1, + 2459, 6911, 868, -1, 6911, 2459, 2460, -1, + 2460, 6912, 6911, -1, 6912, 2460, 2461, -1, + 2461, 6913, 6912, -1, 6913, 2461, 2462, -1, + 2462, 6914, 6913, -1, 6914, 2462, 2463, -1, + 2463, 6915, 6914, -1, 6915, 2463, 2464, -1, + 2464, 6916, 6915, -1, 6916, 2464, 2465, -1, + 2465, 6917, 6916, -1, 6917, 2465, 2466, -1, + 2466, 6918, 6917, -1, 6918, 2466, 2468, -1, + 2468, 6919, 6918, -1, 6919, 2468, 2470, -1, + 2470, 6920, 6919, -1, 6920, 2470, 2472, -1, + 2472, 6921, 6920, -1, 6921, 2472, 2474, -1, + 2474, 6922, 6921, -1, 6922, 2474, 2476, -1, + 2476, 6923, 6922, -1, 6923, 2476, 2478, -1, + 2478, 6924, 6923, -1, 6924, 2478, 2480, -1, + 2480, 6925, 6924, -1, 6925, 2480, 2482, -1, + 2482, 6926, 6925, -1, 6926, 2482, 2484, -1, + 2484, 6927, 6926, -1, 6927, 2484, 2486, -1, + 2486, 6928, 6927, -1, 6928, 2486, 2488, -1, + 2488, 6929, 6928, -1, 6929, 2488, 2490, -1, + 2490, 6930, 6929, -1, 6930, 2490, 2492, -1, + 2492, 6931, 6930, -1, 6931, 2492, 802, -1, + 6931, 802, 800, -1, 6932, 6931, 800, -1, + 800, 798, 6932, -1, 6932, 798, 797, -1, + 797, 6931, 6932, -1, 797, 799, 6931, -1, + 796, 6931, 799, -1, 796, 6930, 6931, -1, + 6930, 796, 793, -1, 793, 6929, 6930, -1, + 6929, 793, 792, -1, 792, 6928, 6929, -1, + 6928, 792, 791, -1, 791, 6927, 6928, -1, + 6927, 791, 790, -1, 790, 6926, 6927, -1, + 6926, 790, 789, -1, 789, 6925, 6926, -1, + 6925, 789, 788, -1, 788, 6924, 6925, -1, + 6924, 788, 787, -1, 787, 6923, 6924, -1, + 6923, 787, 786, -1, 786, 6922, 6923, -1, + 6922, 786, 785, -1, 785, 6921, 6922, -1, + 6921, 785, 784, -1, 784, 6920, 6921, -1, + 6920, 784, 783, -1, 783, 6919, 6920, -1, + 6919, 783, 782, -1, 782, 6918, 6919, -1, + 6918, 782, 781, -1, 781, 6917, 6918, -1, + 6917, 781, 780, -1, 780, 6916, 6917, -1, + 6916, 780, 779, -1, 779, 6915, 6916, -1, + 6915, 779, 778, -1, 778, 6914, 6915, -1, + 6914, 778, 777, -1, 777, 6913, 6914, -1, + 6913, 777, 776, -1, 776, 6912, 6913, -1, + 6912, 776, 775, -1, 775, 6911, 6912, -1, + 6911, 775, 716, -1, 716, 868, 6911, -1, + 868, 716, 715, -1, 715, 866, 868, -1, + 866, 715, 718, -1, 718, 869, 866, -1, + 869, 718, 720, -1, 720, 871, 869, -1, + 871, 720, 722, -1, 722, 873, 871, -1, + 873, 722, 724, -1, 724, 875, 873, -1, + 875, 724, 726, -1, 726, 877, 875, -1, + 877, 726, 728, -1, 728, 879, 877, -1, + 879, 728, 730, -1, 730, 881, 879, -1, + 881, 730, 732, -1, 732, 883, 881, -1, + 883, 732, 734, -1, 734, 885, 883, -1, + 885, 734, 736, -1, 736, 887, 885, -1, + 887, 736, 738, -1, 738, 889, 887, -1, + 889, 738, 740, -1, 740, 891, 889, -1, + 891, 740, 742, -1, 742, 893, 891, -1, + 893, 742, 744, -1, 744, 895, 893, -1, + 895, 744, 746, -1, 746, 897, 895, -1, + 897, 746, 748, -1, 748, 899, 897, -1, + 899, 748, 750, -1, 750, 901, 899, -1, + 901, 750, 752, -1, 752, 903, 901, -1, + 752, 971, 903, -1, 752, 751, 971, -1, + 971, 751, 756, -1, 971, 756, 6933, -1, + 6933, 972, 971, -1, 972, 6933, 6934, -1, + 6934, 973, 972, -1, 973, 6934, 6935, -1, + 6935, 974, 973, -1, 6935, 975, 974, -1, + 975, 6935, 6936, -1, 6936, 976, 975, -1, + 976, 6936, 6937, -1, 6937, 977, 976, -1, + 977, 6937, 6938, -1, 6938, 980, 977, -1, + 6939, 6940, 6941, -1, 6942, 6943, 6940, -1, + 6944, 6945, 6940, -1, 6944, 6940, 6943, -1, + 6943, 6946, 6944, -1, 6943, 6942, 6946, -1, + 6947, 6948, 672, -1, 6947, 6949, 6948, -1, + 6949, 6947, 6950, -1, 6950, 6951, 6949, -1, + 6951, 6950, 6952, -1, 6952, 6953, 6951, -1, + 6953, 6952, 6954, -1, 6954, 6955, 6953, -1, + 6955, 6954, 6956, -1, 6956, 6957, 6955, -1, + 6957, 6956, 6958, -1, 6958, 6959, 6957, -1, + 6959, 6958, 6960, -1, 6960, 6961, 6959, -1, + 6961, 6960, 6962, -1, 6962, 6963, 6961, -1, + 6963, 6962, 6964, -1, 6964, 6965, 6963, -1, + 6965, 6964, 6966, -1, 6966, 6967, 6965, -1, + 6967, 6966, 6968, -1, 6968, 6969, 6967, -1, + 6969, 6968, 6970, -1, 6970, 6971, 6969, -1, + 6971, 6970, 6972, -1, 6972, 6973, 6971, -1, + 6973, 6972, 6974, -1, 6974, 6975, 6973, -1, + 6975, 6974, 6976, -1, 6976, 6977, 6975, -1, + 6977, 6976, 6978, -1, 6978, 6979, 6977, -1, + 6979, 6978, 6980, -1, 6980, 6981, 6979, -1, + 6981, 6980, 6982, -1, 6982, 6983, 6981, -1, + 6983, 6982, 6984, -1, 6984, 6985, 6983, -1, + 6985, 6984, 6986, -1, 6986, 6987, 6985, -1, + 6987, 6986, 6988, -1, 6988, 6989, 6987, -1, + 6989, 6988, 6990, -1, 6990, 6991, 6989, -1, + 6991, 6990, 6992, -1, 6992, 6993, 6991, -1, + 6993, 6992, 6994, -1, 6994, 6995, 6993, -1, + 6995, 6994, 6996, -1, 6996, 6997, 6995, -1, + 6997, 6996, 6998, -1, 6998, 6999, 6997, -1, + 6999, 6998, 7000, -1, 7000, 7001, 6999, -1, + 7001, 7000, 7002, -1, 7002, 7003, 7001, -1, + 7003, 7002, 7004, -1, 7004, 7005, 7003, -1, + 7005, 7004, 7006, -1, 7006, 7007, 7005, -1, + 7007, 7006, 7008, -1, 7008, 7009, 7007, -1, + 7009, 7008, 7010, -1, 7010, 7011, 7009, -1, + 7011, 7010, 7012, -1, 7012, 7013, 7011, -1, + 7013, 7012, 7014, -1, 7014, 7015, 7013, -1, + 7015, 7014, 7016, -1, 7016, 7017, 7015, -1, + 7017, 7016, 7018, -1, 7018, 7019, 7017, -1, + 7019, 7018, 6946, -1, 6946, 7020, 7019, -1, + 6946, 7021, 7020, -1, 7021, 6946, 6942, -1, + 6942, 6940, 7021, -1, 7021, 6940, 6939, -1, + 6939, 7020, 7021, -1, 6939, 6941, 7020, -1, + 7020, 6941, 7022, -1, 7020, 7022, 7023, -1, + 7023, 7019, 7020, -1, 7019, 7023, 7024, -1, + 7024, 7017, 7019, -1, 7017, 7024, 7025, -1, + 7025, 7015, 7017, -1, 7015, 7025, 7026, -1, + 7026, 7013, 7015, -1, 7013, 7026, 7027, -1, + 7027, 7011, 7013, -1, 7011, 7027, 7028, -1, + 7028, 7009, 7011, -1, 7009, 7028, 7029, -1, + 7029, 7007, 7009, -1, 7007, 7029, 7030, -1, + 7030, 7005, 7007, -1, 7005, 7030, 7031, -1, + 7031, 7003, 7005, -1, 7003, 7031, 7032, -1, + 7032, 7001, 7003, -1, 7001, 7032, 7033, -1, + 7033, 6999, 7001, -1, 6999, 7033, 7034, -1, + 7034, 6997, 6999, -1, 6997, 7034, 7035, -1, + 7035, 6995, 6997, -1, 6995, 7035, 7036, -1, + 7036, 6993, 6995, -1, 6993, 7036, 7037, -1, + 7037, 6991, 6993, -1, 6991, 7037, 7038, -1, + 7038, 6989, 6991, -1, 6989, 7038, 7039, -1, + 7039, 6987, 6989, -1, 6987, 7039, 7040, -1, + 7040, 6985, 6987, -1, 6985, 7040, 7041, -1, + 7041, 6983, 6985, -1, 6983, 7041, 7042, -1, + 7042, 6981, 6983, -1, 6981, 7042, 7043, -1, + 7043, 6979, 6981, -1, 6979, 7043, 7044, -1, + 7044, 6977, 6979, -1, 6977, 7044, 7045, -1, + 7045, 6975, 6977, -1, 6975, 7045, 7046, -1, + 7046, 6973, 6975, -1, 6973, 7046, 7047, -1, + 7047, 6971, 6973, -1, 6971, 7047, 7048, -1, + 7048, 6969, 6971, -1, 6969, 7048, 7049, -1, + 7049, 6967, 6969, -1, 6967, 7049, 7050, -1, + 7050, 6965, 6967, -1, 6965, 7050, 7051, -1, + 7051, 6963, 6965, -1, 6963, 7051, 7052, -1, + 7052, 6961, 6963, -1, 6961, 7052, 7053, -1, + 7053, 6959, 6961, -1, 6959, 7053, 7054, -1, + 7054, 6957, 6959, -1, 6957, 7054, 7055, -1, + 7055, 6955, 6957, -1, 6955, 7055, 7056, -1, + 7056, 6953, 6955, -1, 6953, 7056, 7057, -1, + 7057, 6951, 6953, -1, 6951, 7057, 7058, -1, + 7058, 6949, 6951, -1, 6949, 7058, 7059, -1, + 7059, 6948, 6949, -1, 6948, 7059, 980, -1, + 980, 6938, 6948, -1, 6938, 672, 6948, -1, + 6938, 670, 672, -1, 670, 6938, 6937, -1, + 6937, 668, 670, -1, 668, 6937, 6936, -1, + 6936, 667, 668, -1, 667, 6936, 6935, -1, + 667, 6935, 6934, -1, 6934, 665, 667, -1, + 665, 6934, 6933, -1, 6933, 663, 665, -1, + 663, 6933, 756, -1, 756, 659, 663, -1, + 659, 756, 755, -1, 755, 660, 659, -1, + 660, 755, 7060, -1, 7060, 7061, 660, -1, + 7061, 7060, 7062, -1, 7062, 7063, 7061, -1, + 7063, 7062, 7064, -1, 7064, 7065, 7063, -1, + 7065, 7064, 7066, -1, 7066, 7067, 7065, -1, + 7067, 7066, 7068, -1, 7068, 7069, 7067, -1, + 7069, 7068, 7070, -1, 7070, 7071, 7069, -1, + 7071, 7070, 7072, -1, 7072, 7073, 7071, -1, + 7073, 7072, 7074, -1, 7074, 7075, 7073, -1, + 7075, 7074, 7076, -1, 7076, 7077, 7075, -1, + 7077, 7076, 7078, -1, 7078, 7079, 7077, -1, + 7079, 7078, 7080, -1, 7080, 7081, 7079, -1, + 7081, 7080, 7082, -1, 7082, 7083, 7081, -1, + 7083, 7082, 7084, -1, 7084, 7085, 7083, -1, + 7085, 7084, 7086, -1, 7086, 7087, 7085, -1, + 7087, 7086, 7088, -1, 7088, 7089, 7087, -1, + 7089, 7088, 7090, -1, 7090, 7091, 7089, -1, + 7091, 7090, 7092, -1, 7092, 7093, 7091, -1, + 7093, 7092, 7094, -1, 7094, 7095, 7093, -1, + 7095, 7094, 7096, -1, 7096, 7097, 7095, -1, + 7098, 7099, 7100, -1, 7098, 7101, 7099, -1, + 7101, 7098, 7102, -1, 7102, 7103, 7101, -1, + 7103, 7102, 7104, -1, 7104, 7105, 7103, -1, + 7105, 7104, 7106, -1, 7106, 7107, 7105, -1, + 7107, 7106, 7108, -1, 7108, 7109, 7107, -1, + 7109, 7108, 7110, -1, 7110, 7111, 7109, -1, + 7111, 7110, 7112, -1, 7112, 7113, 7111, -1, + 7113, 7112, 7114, -1, 7114, 7115, 7113, -1, + 7115, 7114, 7116, -1, 7116, 7117, 7115, -1, + 7117, 7116, 7118, -1, 7118, 7119, 7117, -1, + 7119, 7118, 7120, -1, 7120, 7121, 7119, -1, + 7121, 7120, 7122, -1, 7122, 7123, 7121, -1, + 7123, 7122, 7124, -1, 7124, 7125, 7123, -1, + 7125, 7124, 7126, -1, 7126, 7127, 7125, -1, + 7127, 7126, 7128, -1, 7128, 7129, 7127, -1, + 7129, 7128, 7130, -1, 7130, 7131, 7129, -1, + 7131, 7130, 7097, -1, 7097, 7096, 7131, -1, + 7096, 7132, 7131, -1, 7132, 7096, 7094, -1, + 7094, 7133, 7132, -1, 7133, 7094, 7092, -1, + 7092, 7134, 7133, -1, 7134, 7092, 7090, -1, + 7090, 7135, 7134, -1, 7135, 7090, 7088, -1, + 7088, 7136, 7135, -1, 7136, 7088, 7086, -1, + 7086, 7137, 7136, -1, 7137, 7086, 7084, -1, + 7084, 7138, 7137, -1, 7138, 7084, 7082, -1, + 7082, 7139, 7138, -1, 7139, 7082, 7080, -1, + 7080, 7140, 7139, -1, 7140, 7080, 7078, -1, + 7078, 7141, 7140, -1, 7141, 7078, 7076, -1, + 7076, 7142, 7141, -1, 7142, 7076, 7074, -1, + 7074, 7143, 7142, -1, 7143, 7074, 7072, -1, + 7072, 7144, 7143, -1, 7144, 7072, 7070, -1, + 7070, 7145, 7144, -1, 7145, 7070, 7068, -1, + 7068, 7146, 7145, -1, 7146, 7068, 7066, -1, + 7066, 7147, 7146, -1, 7147, 7066, 7064, -1, + 7064, 7148, 7147, -1, 7148, 7064, 7062, -1, + 7062, 7149, 7148, -1, 7149, 7062, 7060, -1, + 7060, 7150, 7149, -1, 7150, 7060, 755, -1, + 7150, 755, 754, -1, 7150, 754, 757, -1, + 757, 7149, 7150, -1, 7149, 757, 758, -1, + 758, 7148, 7149, -1, 7148, 758, 759, -1, + 759, 7147, 7148, -1, 7147, 759, 760, -1, + 760, 7146, 7147, -1, 7146, 760, 761, -1, + 761, 7145, 7146, -1, 7145, 761, 762, -1, + 762, 7144, 7145, -1, 7144, 762, 763, -1, + 763, 7143, 7144, -1, 7143, 763, 764, -1, + 764, 7142, 7143, -1, 7142, 764, 765, -1, + 765, 7141, 7142, -1, 7141, 765, 766, -1, + 766, 7140, 7141, -1, 7140, 766, 767, -1, + 767, 7139, 7140, -1, 7139, 767, 768, -1, + 768, 7138, 7139, -1, 7138, 768, 769, -1, + 769, 7137, 7138, -1, 7137, 769, 770, -1, + 770, 7136, 7137, -1, 7136, 770, 771, -1, + 771, 7135, 7136, -1, 7135, 771, 772, -1, + 772, 7134, 7135, -1, 7134, 772, 773, -1, + 773, 7133, 7134, -1, 7133, 773, 774, -1, + 774, 7132, 7133, -1, 7132, 774, 713, -1, + 713, 712, 7132, -1, 712, 7131, 7132, -1, + 7131, 712, 710, -1, 710, 7129, 7131, -1, + 7129, 710, 708, -1, 708, 7127, 7129, -1, + 7127, 708, 706, -1, 706, 7125, 7127, -1, + 7125, 706, 704, -1, 704, 7123, 7125, -1, + 7123, 704, 702, -1, 702, 7121, 7123, -1, + 7121, 702, 700, -1, 700, 7119, 7121, -1, + 7119, 700, 698, -1, 698, 7117, 7119, -1, + 7117, 698, 696, -1, 696, 7115, 7117, -1, + 7115, 696, 694, -1, 694, 7113, 7115, -1, + 7113, 694, 692, -1, 692, 7111, 7113, -1, + 7111, 692, 690, -1, 690, 7109, 7111, -1, + 7109, 690, 688, -1, 688, 7107, 7109, -1, + 7107, 688, 686, -1, 686, 7105, 7107, -1, + 7105, 686, 684, -1, 684, 7103, 7105, -1, + 7103, 684, 682, -1, 682, 7101, 7103, -1, + 7101, 682, 680, -1, 680, 7099, 7101, -1, + 7099, 680, 675, -1, 7099, 675, 674, -1, + 674, 7151, 7099, -1, 7151, 674, 676, -1, + 7151, 676, 7152, -1, 7152, 7099, 7151, -1, + 7152, 7100, 7099, -1, 7100, 7152, 676, -1, + 7100, 676, 7153, -1, 7153, 7098, 7100, -1, + 7153, 7154, 7098, -1, 7153, 7155, 7154, -1, + 7155, 7153, 676, -1, 7156, 676, 677, -1, + 677, 7157, 7156, -1, 7157, 677, 678, -1, + 7157, 678, 795, -1, 795, 7156, 7157, -1, + 795, 794, 7156, -1, 7158, 7156, 794, -1, + 7158, 794, 796, -1, 7158, 796, 799, -1, + 799, 7156, 7158, -1, 7156, 799, 798, -1, + 798, 7159, 7160, -1, 7159, 798, 801, -1, + 801, 802, 7159, -1, 802, 2494, 7159, -1, + 7161, 7159, 2494, -1, 7161, 7160, 7159, -1, + 7162, 7160, 7161, -1, 7161, 2494, 7162, -1, + 7162, 2494, 2496, -1, 2496, 7160, 7162, -1, + 2496, 7163, 7160, -1, 7163, 2496, 2495, -1, + 7163, 2495, 2514, -1, 2514, 7160, 7163, -1, + 7160, 2514, 2372, -1, 7164, 7165, 7155, -1, + 7164, 658, 7166, -1, 7167, 7168, 7169, -1, + 7168, 7167, 7170, -1, 7170, 7171, 7168, -1, + 7171, 7170, 7172, -1, 7172, 7173, 7171, -1, + 7173, 7172, 7174, -1, 7174, 7175, 7173, -1, + 7175, 7174, 7176, -1, 7176, 7177, 7175, -1, + 7177, 7176, 7178, -1, 7178, 7179, 7177, -1, + 7179, 7178, 7180, -1, 7180, 7181, 7179, -1, + 7181, 7180, 7182, -1, 7182, 7183, 7181, -1, + 7183, 7182, 7184, -1, 7184, 7185, 7183, -1, + 7185, 7184, 7186, -1, 7186, 7187, 7185, -1, + 7187, 7186, 7188, -1, 7188, 7189, 7187, -1, + 7189, 7188, 7190, -1, 7190, 7191, 7189, -1, + 7191, 7190, 7192, -1, 7192, 7193, 7191, -1, + 7193, 7192, 7194, -1, 7194, 7195, 7193, -1, + 7195, 7194, 7196, -1, 7196, 7197, 7195, -1, + 7197, 7196, 7198, -1, 7198, 7199, 7197, -1, + 7200, 7201, 7199, -1, 7199, 7198, 7200, -1, + 7202, 7203, 7204, -1, 7202, 7205, 7203, -1, + 7206, 7207, 7208, -1, 7206, 7208, 7209, -1, + 7209, 7210, 7206, -1, 7210, 7209, 7211, -1, + 7211, 7212, 7210, -1, 7212, 7211, 7213, -1, + 7213, 7214, 7212, -1, 7213, 7215, 7214, -1, + 7215, 7213, 7216, -1, 7216, 7217, 7215, -1, + 7217, 7216, 7218, -1, 7218, 7219, 7217, -1, + 7219, 7218, 7205, -1, 7205, 7202, 7219, -1, + 7220, 7221, 7222, -1, 7223, 7224, 7225, -1, + 7225, 7226, 7223, -1, 7226, 7225, 7227, -1, + 7227, 7228, 7226, -1, 7228, 7227, 7229, -1, + 7229, 7230, 7228, -1, 7230, 7229, 7231, -1, + 7231, 7232, 7230, -1, 7232, 7231, 7233, -1, + 7233, 7234, 7232, -1, 7234, 7233, 7235, -1, + 7235, 7236, 7234, -1, 7236, 7235, 7237, -1, + 7237, 7238, 7236, -1, 7238, 7237, 7239, -1, + 7239, 7240, 7238, -1, 7240, 7239, 7241, -1, + 7241, 7242, 7240, -1, 7242, 7241, 7243, -1, + 7243, 7244, 7242, -1, 7244, 7243, 7245, -1, + 7245, 7246, 7244, -1, 7246, 7245, 7247, -1, + 7247, 7248, 7246, -1, 7248, 7247, 7249, -1, + 7249, 7250, 7248, -1, 7250, 7249, 7251, -1, + 7251, 7252, 7250, -1, 7252, 7251, 7253, -1, + 7253, 7254, 7252, -1, 7254, 7253, 7255, -1, + 7255, 7256, 7254, -1, 7256, 7255, 7257, -1, + 7257, 7258, 7256, -1, 7258, 7257, 7259, -1, + 7259, 7260, 7258, -1, 7260, 7259, 7261, -1, + 7261, 7262, 7260, -1, 7262, 7261, 7263, -1, + 7263, 7264, 7262, -1, 7264, 7263, 7221, -1, + 7221, 7220, 7264, -1, 7220, 7202, 7264, -1, + 7220, 7219, 7202, -1, 7220, 7222, 7219, -1, + 7265, 7219, 7222, -1, 7265, 7217, 7219, -1, + 7217, 7265, 7266, -1, 7266, 7215, 7217, -1, + 7215, 7266, 7267, -1, 7267, 7214, 7215, -1, + 7214, 7267, 7268, -1, 7214, 7268, 7269, -1, + 7269, 7212, 7214, -1, 7212, 7269, 7270, -1, + 7270, 7210, 7212, -1, 7210, 7270, 7271, -1, + 7271, 7206, 7210, -1, 7271, 7272, 7206, -1, + 7273, 7274, 7275, -1, 7274, 7273, 7276, -1, + 7276, 7277, 7274, -1, 7277, 7276, 7278, -1, + 7278, 7279, 7277, -1, 7279, 7278, 7280, -1, + 7280, 7281, 7279, -1, 7281, 7280, 7282, -1, + 7282, 7283, 7281, -1, 7283, 7282, 7284, -1, + 7284, 7285, 7283, -1, 7285, 7284, 7286, -1, + 7286, 7287, 7285, -1, 7287, 7286, 7288, -1, + 7288, 7289, 7287, -1, 7289, 7288, 7290, -1, + 7290, 7291, 7289, -1, 7291, 7290, 7292, -1, + 7292, 7293, 7291, -1, 7293, 7292, 7294, -1, + 7294, 7295, 7293, -1, 7295, 7294, 7296, -1, + 7296, 7297, 7295, -1, 7297, 7296, 7298, -1, + 7298, 7299, 7297, -1, 7299, 7298, 7300, -1, + 7300, 7301, 7299, -1, 7301, 7300, 7302, -1, + 7302, 7303, 7301, -1, 7303, 7302, 7304, -1, + 7304, 7305, 7303, -1, 7305, 7304, 7306, -1, + 7306, 7307, 7305, -1, 7307, 7306, 7308, -1, + 7308, 7309, 7307, -1, 7309, 7308, 7310, -1, + 7310, 7311, 7309, -1, 7311, 7310, 7312, -1, + 7312, 7313, 7311, -1, 7313, 7312, 7272, -1, + 7272, 7314, 7313, -1, 7314, 7272, 7271, -1, + 7314, 7271, 7200, -1, 7314, 7200, 7198, -1, + 7198, 7313, 7314, -1, 7313, 7198, 7196, -1, + 7196, 7311, 7313, -1, 7311, 7196, 7194, -1, + 7194, 7309, 7311, -1, 7309, 7194, 7192, -1, + 7192, 7307, 7309, -1, 7307, 7192, 7190, -1, + 7190, 7305, 7307, -1, 7305, 7190, 7188, -1, + 7188, 7303, 7305, -1, 7303, 7188, 7186, -1, + 7186, 7301, 7303, -1, 7301, 7186, 7184, -1, + 7184, 7299, 7301, -1, 7299, 7184, 7182, -1, + 7182, 7297, 7299, -1, 7297, 7182, 7180, -1, + 7180, 7295, 7297, -1, 7295, 7180, 7178, -1, + 7178, 7293, 7295, -1, 7293, 7178, 7176, -1, + 7176, 7291, 7293, -1, 7291, 7176, 7174, -1, + 7174, 7289, 7291, -1, 7289, 7174, 7172, -1, + 7172, 7287, 7289, -1, 7287, 7172, 7170, -1, + 7170, 7285, 7287, -1, 7285, 7170, 7167, -1, + 7167, 7283, 7285, -1, 7283, 7167, 7169, -1, + 7169, 7281, 7283, -1, 7281, 7169, 7315, -1, + 7315, 7279, 7281, -1, 7279, 7315, 7316, -1, + 7316, 7277, 7279, -1, 7277, 7316, 7317, -1, + 7317, 7274, 7277, -1, 7274, 7317, 7318, -1, + 7318, 7275, 7274, -1, 7275, 7318, 7319, -1, + 7319, 7320, 7275, -1, 7320, 7319, 7321, -1, + 7321, 7322, 7320, -1, 7322, 7321, 7323, -1, + 7323, 7324, 7322, -1, 7324, 7323, 7325, -1, + 7325, 7326, 7324, -1, 7326, 7325, 7327, -1, + 7327, 7328, 7326, -1, 7328, 7327, 7329, -1, + 7329, 7330, 7328, -1, 7330, 7329, 7331, -1, + 7331, 7332, 7330, -1, 7332, 7331, 7333, -1, + 7333, 7334, 7332, -1, 7334, 7333, 7335, -1, + 7335, 7336, 7334, -1, 7336, 7335, 7337, -1, + 7337, 7338, 7336, -1, 7338, 7337, 7339, -1, + 7338, 7339, 7340, -1, 7341, 7342, 7164, -1, + 7342, 7341, 7339, -1, 7341, 7340, 7339, -1, + 7341, 7164, 7340, -1, 7340, 7164, 7166, -1, + 7166, 7338, 7340, -1, 7166, 7343, 7338, -1, + 7343, 7166, 658, -1, 7343, 658, 551, -1, + 551, 553, 7343, -1, 553, 7338, 7343, -1, + 553, 7336, 7338, -1, 7336, 553, 655, -1, + 655, 7334, 7336, -1, 7334, 655, 653, -1, + 653, 7332, 7334, -1, 7332, 653, 651, -1, + 651, 7330, 7332, -1, 7330, 651, 649, -1, + 649, 7328, 7330, -1, 7328, 649, 647, -1, + 647, 7326, 7328, -1, 7326, 647, 645, -1, + 645, 7324, 7326, -1, 7324, 645, 643, -1, + 643, 7322, 7324, -1, 7322, 643, 641, -1, + 641, 7320, 7322, -1, 7320, 641, 610, -1, + 610, 7275, 7320, -1, 7275, 610, 609, -1, + 609, 7273, 7275, -1, 7273, 609, 612, -1, + 612, 7276, 7273, -1, 7276, 612, 614, -1, + 614, 7278, 7276, -1, 7278, 614, 616, -1, + 616, 7280, 7278, -1, 7280, 616, 618, -1, + 618, 7282, 7280, -1, 7282, 618, 580, -1, + 580, 7284, 7282, -1, 7284, 580, 578, -1, + 578, 7286, 7284, -1, 7286, 578, 576, -1, + 576, 7288, 7286, -1, 7288, 576, 574, -1, + 574, 7290, 7288, -1, 7290, 574, 572, -1, + 572, 7292, 7290, -1, 7292, 572, 570, -1, + 570, 7294, 7292, -1, 7294, 570, 568, -1, + 568, 7296, 7294, -1, 7296, 568, 566, -1, + 566, 7298, 7296, -1, 7298, 566, 564, -1, + 564, 7300, 7298, -1, 7300, 564, 562, -1, + 562, 7302, 7300, -1, 7302, 562, 560, -1, + 560, 7304, 7302, -1, 7304, 560, 558, -1, + 558, 7306, 7304, -1, 7306, 558, 556, -1, + 556, 7308, 7306, -1, 7308, 556, 555, -1, + 555, 7310, 7308, -1, 7310, 555, 7344, -1, + 7344, 7312, 7310, -1, 7312, 7344, 7345, -1, + 7345, 7272, 7312, -1, 7345, 7206, 7272, -1, + 7345, 7207, 7206, -1, 7207, 7345, 7344, -1, + 7344, 7346, 7207, -1, 7346, 7344, 555, -1, + 555, 554, 7346, -1, 7346, 554, 619, -1, + 7346, 619, 7347, -1, 7347, 7207, 7346, -1, + 7347, 7208, 7207, -1, 7347, 7348, 7208, -1, + 7348, 7347, 619, -1, 619, 620, 7348, -1, + 7348, 620, 7349, -1, 7348, 7349, 7350, -1, + 7350, 7208, 7348, -1, 7208, 7350, 7351, -1, + 7351, 7209, 7208, -1, 7209, 7351, 7352, -1, + 7352, 7211, 7209, -1, 7211, 7352, 7353, -1, + 7353, 7213, 7211, -1, 7353, 7216, 7213, -1, + 7216, 7353, 7354, -1, 7354, 7218, 7216, -1, + 7218, 7354, 7355, -1, 7355, 7205, 7218, -1, + 7205, 7355, 7356, -1, 7356, 7203, 7205, -1, + 7203, 7356, 7357, -1, 7203, 7357, 7358, -1, + 7359, 7358, 7357, -1, 7359, 7360, 7358, -1, + 7360, 7359, 7361, -1, 7361, 7362, 7360, -1, + 7362, 7361, 7363, -1, 7363, 7364, 7362, -1, + 7364, 7363, 7365, -1, 7365, 7366, 7364, -1, + 7366, 7365, 7367, -1, 7367, 7368, 7366, -1, + 7368, 7367, 7369, -1, 7369, 7370, 7368, -1, + 7370, 7369, 7371, -1, 7371, 7372, 7370, -1, + 7372, 7371, 7373, -1, 7373, 7374, 7372, -1, + 7374, 7373, 7375, -1, 7375, 7376, 7374, -1, + 7376, 7375, 7377, -1, 7377, 7378, 7376, -1, + 7378, 7377, 7379, -1, 7379, 7380, 7378, -1, + 7380, 7379, 7381, -1, 7381, 7382, 7380, -1, + 7382, 7381, 7383, -1, 7383, 7384, 7382, -1, + 7384, 7383, 7385, -1, 7385, 7386, 7384, -1, + 7386, 7385, 7387, -1, 7387, 7388, 7386, -1, + 7388, 7387, 7389, -1, 7389, 7390, 7388, -1, + 7390, 7389, 7391, -1, 7391, 7392, 7390, -1, + 7392, 7391, 7393, -1, 7393, 7394, 7392, -1, + 7394, 7393, 7395, -1, 7395, 7396, 7394, -1, + 7396, 7395, 7397, -1, 7397, 7398, 7396, -1, + 7398, 7397, 7399, -1, 7399, 7400, 7398, -1, + 7401, 7402, 7403, -1, 7403, 7404, 7401, -1, + 7404, 7403, 7405, -1, 7405, 7406, 7404, -1, + 7406, 7405, 7407, -1, 7407, 7408, 7406, -1, + 7408, 7407, 7409, -1, 7409, 7410, 7408, -1, + 7410, 7409, 7411, -1, 7411, 7412, 7410, -1, + 7412, 7411, 7413, -1, 7413, 7400, 7412, -1, + 7400, 7413, 550, -1, 550, 7398, 7400, -1, + 7398, 550, 549, -1, 549, 7396, 7398, -1, + 7396, 549, 547, -1, 547, 7394, 7396, -1, + 7394, 547, 545, -1, 545, 7392, 7394, -1, + 7392, 545, 543, -1, 543, 7390, 7392, -1, + 7390, 543, 541, -1, 541, 7388, 7390, -1, + 7388, 541, 539, -1, 539, 7386, 7388, -1, + 7386, 539, 537, -1, 537, 7384, 7386, -1, + 7384, 537, 536, -1, 536, 7382, 7384, -1, + 7382, 536, 7414, -1, 7414, 7380, 7382, -1, + 7380, 7414, 7415, -1, 7415, 7378, 7380, -1, + 7378, 7415, 7416, -1, 7416, 7376, 7378, -1, + 7376, 7416, 7417, -1, 7417, 7374, 7376, -1, + 7374, 7417, 7418, -1, 7418, 7372, 7374, -1, + 7372, 7418, 7419, -1, 7419, 7370, 7372, -1, + 7370, 7419, 7420, -1, 7420, 7368, 7370, -1, + 7368, 7420, 7421, -1, 7421, 7366, 7368, -1, + 7366, 7421, 7422, -1, 7422, 7364, 7366, -1, + 7364, 7422, 7423, -1, 7423, 7362, 7364, -1, + 7362, 7423, 7424, -1, 7424, 7360, 7362, -1, + 7360, 7424, 7425, -1, 7425, 7358, 7360, -1, + 7358, 7425, 7426, -1, 7426, 7203, 7358, -1, + 7426, 7204, 7203, -1, 7426, 7427, 7204, -1, + 7427, 7426, 7425, -1, 7425, 7428, 7427, -1, + 7428, 7425, 7424, -1, 7424, 7429, 7428, -1, + 7429, 7424, 7423, -1, 7423, 7430, 7429, -1, + 7430, 7423, 7422, -1, 7422, 7431, 7430, -1, + 7431, 7422, 7421, -1, 7421, 7432, 7431, -1, + 7432, 7421, 7420, -1, 7420, 7433, 7432, -1, + 7433, 7420, 7419, -1, 7419, 7434, 7433, -1, + 7434, 7419, 7418, -1, 7418, 7435, 7434, -1, + 7435, 7418, 7417, -1, 7417, 7436, 7435, -1, + 7436, 7417, 7416, -1, 7416, 7437, 7436, -1, + 7437, 7416, 7415, -1, 7415, 7438, 7437, -1, + 7438, 7415, 7414, -1, 7414, 7439, 7438, -1, + 7439, 7414, 536, -1, 536, 535, 7439, -1, + 7439, 535, 7440, -1, 7440, 7438, 7439, -1, + 7438, 7440, 7441, -1, 7441, 7437, 7438, -1, + 7437, 7441, 7442, -1, 7442, 7436, 7437, -1, + 7436, 7442, 7443, -1, 7443, 7435, 7436, -1, + 7435, 7443, 7444, -1, 7444, 7434, 7435, -1, + 7434, 7444, 7445, -1, 7445, 7433, 7434, -1, + 7433, 7445, 7446, -1, 7446, 7432, 7433, -1, + 7432, 7446, 7447, -1, 7447, 7431, 7432, -1, + 7431, 7447, 7448, -1, 7448, 7430, 7431, -1, + 7430, 7448, 7449, -1, 7449, 7429, 7430, -1, + 7429, 7449, 7450, -1, 7450, 7428, 7429, -1, + 7428, 7450, 7451, -1, 7451, 7427, 7428, -1, + 7427, 7451, 7452, -1, 7452, 7204, 7427, -1, + 7204, 7452, 7453, -1, 7453, 7202, 7204, -1, + 7453, 7264, 7202, -1, 7453, 7262, 7264, -1, + 7262, 7453, 7452, -1, 7452, 7260, 7262, -1, + 7260, 7452, 7451, -1, 7451, 7258, 7260, -1, + 7258, 7451, 7450, -1, 7450, 7256, 7258, -1, + 7256, 7450, 7449, -1, 7449, 7254, 7256, -1, + 7254, 7449, 7448, -1, 7448, 7252, 7254, -1, + 7252, 7448, 7447, -1, 7447, 7250, 7252, -1, + 7250, 7447, 7446, -1, 7446, 7248, 7250, -1, + 7248, 7446, 7445, -1, 7445, 7246, 7248, -1, + 7246, 7445, 7444, -1, 7444, 7244, 7246, -1, + 7244, 7444, 7443, -1, 7443, 7242, 7244, -1, + 7242, 7443, 7442, -1, 7442, 7240, 7242, -1, + 7240, 7442, 7441, -1, 7441, 7238, 7240, -1, + 7238, 7441, 7440, -1, 7440, 7236, 7238, -1, + 7236, 7440, 535, -1, 535, 7234, 7236, -1, + 7234, 535, 538, -1, 538, 7232, 7234, -1, + 7232, 538, 540, -1, 540, 7230, 7232, -1, + 7230, 540, 542, -1, 542, 7228, 7230, -1, + 7228, 542, 544, -1, 544, 7226, 7228, -1, + 7226, 544, 546, -1, 546, 7223, 7226, -1, + 7223, 546, 548, -1, 548, 7224, 7223, -1, + 7224, 548, 550, -1, 550, 7454, 7224, -1, + 7454, 550, 7413, -1, 7413, 7455, 7454, -1, + 7455, 7413, 7411, -1, 7411, 7456, 7455, -1, + 7456, 7411, 7409, -1, 7409, 7457, 7456, -1, + 7457, 7409, 7407, -1, 7407, 7458, 7457, -1, + 7458, 7407, 7405, -1, 7405, 7459, 7458, -1, + 7459, 7405, 7403, -1, 7403, 7460, 7459, -1, + 7460, 7403, 7402, -1, 7402, 7461, 7460, -1, + 7462, 7463, 3, -1, 7462, 3, 7461, -1, + 7461, 7402, 7462, -1, 7464, 7465, 7466, -1, + 7462, 7466, 7465, -1, 7466, 7462, 7402, -1, + 7402, 7401, 7466, -1, 7467, 7466, 7401, -1, + 7401, 7468, 7467, -1, 7468, 7401, 7404, -1, + 7404, 7469, 7468, -1, 7469, 7404, 7406, -1, + 7406, 7470, 7469, -1, 7470, 7406, 7408, -1, + 7408, 7471, 7470, -1, 7471, 7408, 7410, -1, + 7410, 7472, 7471, -1, 7472, 7410, 7412, -1, + 7412, 7473, 7472, -1, 7473, 7412, 7400, -1, + 7400, 7399, 7473, -1, 7399, 7474, 533, -1, + 533, 7473, 7399, -1, 7473, 533, 531, -1, + 531, 7472, 7473, -1, 7472, 531, 529, -1, + 529, 7471, 7472, -1, 7471, 529, 527, -1, + 527, 7470, 7471, -1, 7470, 527, 525, -1, + 525, 7469, 7470, -1, 7469, 525, 524, -1, + 524, 7468, 7469, -1, 7468, 524, 7475, -1, + 7475, 7467, 7468, -1, 7475, 7476, 7467, -1, + 7477, 7476, 7475, -1, 7477, 7475, 7478, -1, + 7475, 7479, 7478, -1, 7479, 7475, 524, -1, + 524, 523, 7479, -1, 7479, 7480, 7481, -1, + 7480, 7479, 523, -1, 523, 7482, 7480, -1, + 7482, 523, 526, -1, 526, 7483, 7482, -1, + 7483, 526, 528, -1, 528, 7484, 7483, -1, + 7484, 528, 530, -1, 530, 7485, 7484, -1, + 7485, 530, 532, -1, 532, 487, 7485, -1, + 487, 532, 534, -1, 534, 522, 487, -1, + 522, 534, 7486, -1, 7486, 521, 522, -1, + 521, 7486, 7487, -1, 7487, 520, 521, -1, + 520, 7487, 7488, -1, 7488, 519, 520, -1, + 519, 7488, 7489, -1, 7489, 518, 519, -1, + 518, 7489, 7490, -1, 7490, 517, 518, -1, + 517, 7490, 7491, -1, 7491, 516, 517, -1, + 516, 7491, 7492, -1, 7492, 515, 516, -1, + 515, 7492, 7493, -1, 7493, 514, 515, -1, + 514, 7493, 7494, -1, 7494, 513, 514, -1, + 513, 7494, 7495, -1, 7495, 512, 513, -1, + 512, 7495, 7496, -1, 7496, 511, 512, -1, + 511, 7496, 7497, -1, 7497, 510, 511, -1, + 510, 7497, 7498, -1, 7498, 509, 510, -1, + 509, 7498, 7499, -1, 7499, 508, 509, -1, + 508, 7499, 7500, -1, 7500, 507, 508, -1, + 507, 7500, 7501, -1, 7501, 506, 507, -1, + 506, 7501, 7502, -1, 7502, 432, 506, -1, + 432, 7502, 7503, -1, 7503, 430, 432, -1, + 430, 7503, 7504, -1, 7504, 428, 430, -1, + 7504, 429, 428, -1, 7504, 7505, 429, -1, + 7505, 7504, 7503, -1, 7503, 7506, 7505, -1, + 7506, 7503, 7502, -1, 7502, 7507, 7506, -1, + 7507, 7502, 7501, -1, 7501, 7508, 7507, -1, + 7508, 7501, 7500, -1, 7500, 7509, 7508, -1, + 7509, 7500, 7499, -1, 7499, 7510, 7509, -1, + 7510, 7499, 7498, -1, 7498, 7511, 7510, -1, + 7511, 7498, 7497, -1, 7497, 7512, 7511, -1, + 7512, 7497, 7496, -1, 7496, 7513, 7512, -1, + 7513, 7496, 7495, -1, 7495, 7514, 7513, -1, + 7514, 7495, 7494, -1, 7494, 7515, 7514, -1, + 7515, 7494, 7493, -1, 7493, 7516, 7515, -1, + 7516, 7493, 7492, -1, 7492, 7517, 7516, -1, + 7517, 7492, 7491, -1, 7491, 7518, 7517, -1, + 7518, 7491, 7490, -1, 7490, 7519, 7518, -1, + 7519, 7490, 7489, -1, 7489, 7520, 7519, -1, + 7520, 7489, 7488, -1, 7488, 7521, 7520, -1, + 7521, 7488, 7487, -1, 7487, 7522, 7521, -1, + 7522, 7487, 7486, -1, 7486, 7523, 7522, -1, + 7523, 7486, 534, -1, 534, 533, 7523, -1, + 7523, 533, 7474, -1, 7474, 7522, 7523, -1, + 7522, 7474, 7524, -1, 7524, 7521, 7522, -1, + 7521, 7524, 7525, -1, 7525, 7520, 7521, -1, + 7520, 7525, 7526, -1, 7526, 7519, 7520, -1, + 7519, 7526, 7527, -1, 7527, 7518, 7519, -1, + 7518, 7527, 7528, -1, 7528, 7517, 7518, -1, + 7517, 7528, 7529, -1, 7529, 7516, 7517, -1, + 7516, 7529, 7530, -1, 7530, 7515, 7516, -1, + 7515, 7530, 7531, -1, 7531, 7514, 7515, -1, + 7514, 7531, 7532, -1, 7532, 7513, 7514, -1, + 7513, 7532, 7533, -1, 7533, 7512, 7513, -1, + 7512, 7533, 7534, -1, 7534, 7511, 7512, -1, + 7511, 7534, 7535, -1, 7535, 7510, 7511, -1, + 7510, 7535, 7536, -1, 7536, 7509, 7510, -1, + 7509, 7536, 7537, -1, 7537, 7508, 7509, -1, + 7508, 7537, 7538, -1, 7538, 7507, 7508, -1, + 7507, 7538, 7539, -1, 7539, 7506, 7507, -1, + 7506, 7539, 7540, -1, 7540, 7505, 7506, -1, + 7505, 7540, 7541, -1, 7541, 429, 7505, -1, + 429, 7541, 7542, -1, 7542, 427, 429, -1, + 7542, 7543, 427, -1, 7542, 7544, 7543, -1, + 7544, 7542, 7541, -1, 7541, 7545, 7544, -1, + 7545, 7541, 7540, -1, 7540, 7546, 7545, -1, + 7546, 7540, 7539, -1, 7539, 7547, 7546, -1, + 7547, 7539, 7538, -1, 7538, 7548, 7547, -1, + 7548, 7538, 7537, -1, 7537, 7549, 7548, -1, + 7549, 7537, 7536, -1, 7536, 7550, 7549, -1, + 7550, 7536, 7535, -1, 7535, 7551, 7550, -1, + 7551, 7535, 7534, -1, 7534, 7552, 7551, -1, + 7552, 7534, 7533, -1, 7533, 7553, 7552, -1, + 7553, 7533, 7532, -1, 7532, 7554, 7553, -1, + 7554, 7532, 7531, -1, 7531, 7555, 7554, -1, + 7555, 7531, 7530, -1, 7530, 7556, 7555, -1, + 7556, 7530, 7529, -1, 7529, 7557, 7556, -1, + 7557, 7529, 7528, -1, 7528, 7558, 7557, -1, + 7558, 7528, 7527, -1, 7527, 7559, 7558, -1, + 7559, 7527, 7526, -1, 7526, 7560, 7559, -1, + 7560, 7526, 7525, -1, 7525, 7561, 7560, -1, + 7561, 7525, 7524, -1, 7524, 7562, 7561, -1, + 7562, 7524, 7474, -1, 7474, 7399, 7562, -1, + 7562, 7399, 7397, -1, 7397, 7561, 7562, -1, + 7561, 7397, 7395, -1, 7395, 7560, 7561, -1, + 7560, 7395, 7393, -1, 7393, 7559, 7560, -1, + 7559, 7393, 7391, -1, 7391, 7558, 7559, -1, + 7558, 7391, 7389, -1, 7389, 7557, 7558, -1, + 7557, 7389, 7387, -1, 7387, 7556, 7557, -1, + 7556, 7387, 7385, -1, 7385, 7555, 7556, -1, + 7555, 7385, 7383, -1, 7383, 7554, 7555, -1, + 7554, 7383, 7381, -1, 7381, 7553, 7554, -1, + 7553, 7381, 7379, -1, 7379, 7552, 7553, -1, + 7552, 7379, 7377, -1, 7377, 7551, 7552, -1, + 7551, 7377, 7375, -1, 7375, 7550, 7551, -1, + 7550, 7375, 7373, -1, 7373, 7549, 7550, -1, + 7549, 7373, 7371, -1, 7371, 7548, 7549, -1, + 7548, 7371, 7369, -1, 7369, 7547, 7548, -1, + 7547, 7369, 7367, -1, 7367, 7546, 7547, -1, + 7546, 7367, 7365, -1, 7365, 7545, 7546, -1, + 7545, 7365, 7363, -1, 7363, 7544, 7545, -1, + 7544, 7363, 7361, -1, 7361, 7543, 7544, -1, + 7543, 7361, 7359, -1, 7359, 7357, 7543, -1, + 7357, 427, 7543, -1, 7357, 425, 427, -1, + 425, 7357, 7356, -1, 7356, 423, 425, -1, + 423, 7356, 7355, -1, 7355, 421, 423, -1, + 421, 7355, 7354, -1, 7354, 420, 421, -1, + 420, 7354, 7353, -1, 420, 7353, 7352, -1, + 7352, 418, 420, -1, 418, 7352, 7351, -1, + 7351, 416, 418, -1, 416, 7351, 7350, -1, + 7350, 414, 416, -1, 414, 7350, 7349, -1, + 7349, 412, 414, -1, 7349, 7563, 412, -1, + 7564, 7565, 7566, -1, 7565, 7564, 7567, -1, + 7567, 7568, 7565, -1, 7568, 7567, 7569, -1, + 7569, 7570, 7568, -1, 7570, 7569, 7571, -1, + 7571, 7572, 7570, -1, 7572, 7571, 7573, -1, + 7573, 7574, 7572, -1, 7574, 7573, 7575, -1, + 7575, 7576, 7574, -1, 7576, 7575, 7577, -1, + 7577, 7578, 7576, -1, 7578, 7577, 7579, -1, + 7579, 7580, 7578, -1, 7580, 7579, 7581, -1, + 7581, 7582, 7580, -1, 7582, 7581, 7583, -1, + 7583, 7584, 7582, -1, 7584, 7583, 7585, -1, + 7585, 7586, 7584, -1, 7586, 7585, 7587, -1, + 7587, 7588, 7586, -1, 7588, 7587, 7589, -1, + 7589, 7590, 7588, -1, 7590, 7589, 7591, -1, + 7591, 7592, 7590, -1, 7592, 7591, 7593, -1, + 7593, 7594, 7592, -1, 7595, 7594, 7596, -1, + 7594, 7595, 7597, -1, 7597, 7592, 7594, -1, + 7592, 7597, 7598, -1, 7598, 7590, 7592, -1, + 7590, 7598, 7599, -1, 7599, 7588, 7590, -1, + 7588, 7599, 7600, -1, 7600, 7586, 7588, -1, + 7586, 7600, 7601, -1, 7601, 7584, 7586, -1, + 7584, 7601, 7602, -1, 7602, 7582, 7584, -1, + 7582, 7602, 7603, -1, 7603, 7580, 7582, -1, + 7580, 7603, 7604, -1, 7604, 7578, 7580, -1, + 7578, 7604, 7605, -1, 7605, 7576, 7578, -1, + 7576, 7605, 7606, -1, 7606, 7574, 7576, -1, + 7574, 7606, 7607, -1, 7607, 7572, 7574, -1, + 7572, 7607, 7608, -1, 7608, 7570, 7572, -1, + 7570, 7608, 7609, -1, 7609, 7568, 7570, -1, + 7568, 7609, 7610, -1, 7610, 7565, 7568, -1, + 7565, 7610, 7611, -1, 7611, 7566, 7565, -1, + 7566, 7611, 7612, -1, 7612, 7613, 7566, -1, + 7613, 7612, 7614, -1, 7614, 7615, 7613, -1, + 7615, 7614, 7616, -1, 7616, 7563, 7615, -1, + 7616, 412, 7563, -1, 7616, 411, 412, -1, + 411, 7616, 7614, -1, 7614, 410, 411, -1, + 410, 7614, 7612, -1, 7612, 409, 410, -1, + 409, 7612, 7611, -1, 7611, 408, 409, -1, + 408, 7611, 7610, -1, 7610, 407, 408, -1, + 407, 7610, 7609, -1, 7609, 406, 407, -1, + 406, 7609, 7608, -1, 7608, 405, 406, -1, + 405, 7608, 7607, -1, 7607, 404, 405, -1, + 404, 7607, 7606, -1, 7606, 403, 404, -1, + 403, 7606, 7605, -1, 7605, 402, 403, -1, + 402, 7605, 7604, -1, 7604, 401, 402, -1, + 401, 7604, 7603, -1, 7603, 400, 401, -1, + 400, 7603, 7602, -1, 7602, 399, 400, -1, + 399, 7602, 7601, -1, 7601, 398, 399, -1, + 398, 7601, 7600, -1, 7600, 397, 398, -1, + 397, 7600, 7599, -1, 7599, 396, 397, -1, + 396, 7599, 7598, -1, 7598, 395, 396, -1, + 395, 7598, 7597, -1, 7597, 394, 395, -1, + 394, 7597, 7595, -1, 7595, 393, 394, -1, + 393, 7595, 7596, -1, 7596, 392, 393, -1, + 392, 7596, 7617, -1, 7617, 391, 392, -1, + 391, 7617, 7618, -1, 7618, 390, 391, -1, + 390, 7618, 7619, -1, 7619, 389, 390, -1, + 389, 7619, 7620, -1, 7620, 388, 389, -1, + 388, 7620, 7621, -1, 7621, 387, 388, -1, + 387, 7621, 7622, -1, 7622, 386, 387, -1, + 7623, 7624, 386, -1, 386, 7622, 7623, -1, + 7623, 7625, 7626, -1, 7623, 7627, 7625, -1, + 7627, 7623, 7622, -1, 7622, 7628, 7627, -1, + 7628, 7622, 7621, -1, 7621, 7629, 7628, -1, + 7629, 7621, 7620, -1, 7620, 7630, 7629, -1, + 7630, 7620, 7619, -1, 7619, 7631, 7630, -1, + 7631, 7619, 7618, -1, 7618, 7632, 7631, -1, + 7632, 7618, 7617, -1, 7617, 7633, 7632, -1, + 7633, 7617, 7596, -1, 7596, 7634, 7633, -1, + 7634, 7596, 7594, -1, 7594, 7593, 7634, -1, + 7593, 7635, 7634, -1, 7635, 7593, 7591, -1, + 7591, 7636, 7635, -1, 7636, 7591, 7589, -1, + 7589, 7637, 7636, -1, 7637, 7589, 7587, -1, + 7587, 7638, 7637, -1, 7638, 7587, 7585, -1, + 7585, 7639, 7638, -1, 7639, 7585, 7583, -1, + 7583, 7640, 7639, -1, 7640, 7583, 7581, -1, + 7581, 7641, 7640, -1, 7641, 7581, 7579, -1, + 7579, 7642, 7641, -1, 7642, 7579, 7577, -1, + 7577, 7643, 7642, -1, 7643, 7577, 7575, -1, + 7575, 7644, 7643, -1, 7644, 7575, 7573, -1, + 7573, 7645, 7644, -1, 7645, 7573, 7571, -1, + 7571, 7646, 7645, -1, 7646, 7571, 7569, -1, + 7569, 7647, 7646, -1, 7647, 7569, 7567, -1, + 7567, 7648, 7647, -1, 7648, 7567, 7564, -1, + 7564, 7649, 7648, -1, 7649, 7564, 7566, -1, + 7566, 7650, 7649, -1, 7650, 7566, 7613, -1, + 7613, 7651, 7650, -1, 7651, 7613, 7615, -1, + 7615, 7652, 7651, -1, 7652, 7615, 7563, -1, + 7563, 7653, 7652, -1, 7653, 7563, 7349, -1, + 7653, 7349, 620, -1, 7653, 620, 621, -1, + 621, 7652, 7653, -1, 7652, 621, 622, -1, + 622, 7651, 7652, -1, 7651, 622, 623, -1, + 623, 7650, 7651, -1, 7650, 623, 624, -1, + 624, 7649, 7650, -1, 7649, 624, 625, -1, + 625, 7648, 7649, -1, 7648, 625, 626, -1, + 626, 7647, 7648, -1, 7647, 626, 627, -1, + 627, 7646, 7647, -1, 7646, 627, 628, -1, + 628, 7645, 7646, -1, 7645, 628, 629, -1, + 629, 7644, 7645, -1, 7644, 629, 630, -1, + 630, 7643, 7644, -1, 7643, 630, 631, -1, + 631, 7642, 7643, -1, 7642, 631, 632, -1, + 632, 7641, 7642, -1, 7641, 632, 633, -1, + 633, 7640, 7641, -1, 7640, 633, 634, -1, + 634, 7639, 7640, -1, 7639, 634, 635, -1, + 635, 7638, 7639, -1, 7638, 635, 636, -1, + 636, 7637, 7638, -1, 7637, 636, 637, -1, + 637, 7636, 7637, -1, 7636, 637, 638, -1, + 638, 7635, 7636, -1, 7635, 638, 639, -1, + 639, 7634, 7635, -1, 7634, 639, 640, -1, + 640, 7633, 7634, -1, 7633, 640, 642, -1, + 642, 7632, 7633, -1, 7632, 642, 644, -1, + 644, 7631, 7632, -1, 7631, 644, 646, -1, + 646, 7630, 7631, -1, 7630, 646, 648, -1, + 648, 7629, 7630, -1, 7629, 648, 650, -1, + 650, 7628, 7629, -1, 7628, 650, 652, -1, + 652, 7627, 7628, -1, 7627, 652, 654, -1, + 654, 7625, 7627, -1, 7625, 654, 656, -1, + 656, 7654, 7625, -1, 7654, 656, 657, -1, + 657, 658, 7654, -1, 658, 7655, 7654, -1, + 7656, 7655, 7657, -1, 7656, 7654, 7655, -1, + 7656, 7625, 7654, -1, 7656, 7657, 7625, -1, + 7657, 7626, 7625, -1, 7626, 7657, 7655, -1, + 7626, 7655, 7658, -1, 7658, 7623, 7626, -1, + 7658, 7624, 7623, -1, 7624, 7658, 7655, -1, + 7624, 7655, 7659, -1, 7659, 386, 7624, -1, + 7659, 385, 386, -1, 7659, 382, 385, -1, + 382, 7659, 7655, -1, 7660, 6156, 6153, -1, + 2543, 2542, 7660, -1, 7661, 7660, 2542, -1, + 7661, 2542, 2544, -1, 7661, 2544, 6402, -1, + 6402, 7660, 7661, -1, 6402, 1152, 7660, -1, + 7662, 7663, 7664, -1, 7665, 7666, 7667, -1, + 7665, 7668, 7666, -1, 7665, 7669, 7668, -1, + 7665, 7667, 7669, -1, 7670, 7662, 7671, -1, + 7670, 7672, 7662, -1, 7670, 7673, 7672, -1, + 7670, 7671, 7673, -1, 7674, 7675, 7676, -1, + 7674, 7676, 7671, -1, 7676, 7673, 7671, -1, + 7676, 7677, 7673, -1, 7677, 7676, 7678, -1, + 7678, 7679, 7677, -1, 7679, 7678, 7680, -1, + 7680, 7681, 7679, -1, 7681, 7680, 7682, -1, + 7682, 7683, 7681, -1, 7682, 7684, 7683, -1, + 7684, 7682, 7685, -1, 7685, 7686, 7684, -1, + 7686, 7685, 7687, -1, 7687, 7688, 7686, -1, + 7688, 7687, 7689, -1, 7689, 7690, 7688, -1, + 7689, 7691, 7690, -1, 7692, 7690, 7691, -1, + 7692, 7693, 7690, -1, 7693, 7692, 7694, -1, + 7692, 7691, 7694, -1, 7695, 7694, 7691, -1, + 7696, 7695, 7691, -1, 7696, 7691, 7689, -1, + 7696, 7689, 7697, -1, 7697, 7695, 7696, -1, + 7697, 7698, 7695, -1, 7697, 7699, 7698, -1, + 7699, 7697, 7689, -1, 7699, 7689, 7687, -1, + 7687, 7700, 7699, -1, 7700, 7687, 7685, -1, + 7685, 7701, 7700, -1, 7701, 7685, 7682, -1, + 7701, 7682, 7680, -1, 7680, 7702, 7701, -1, + 7702, 7680, 7678, -1, 7678, 7667, 7702, -1, + 7667, 7678, 7676, -1, 7667, 7676, 7675, -1, + 7675, 7669, 7667, -1, 7675, 7668, 7669, -1, + 7675, 7674, 7668, -1, 7674, 7671, 7668, -1, + 7668, 7671, 7662, -1, 7703, 7666, 7668, -1, + 7704, 7705, 7706, -1, 7704, 7703, 7705, -1, + 7704, 7707, 7703, -1, 7704, 7706, 7707, -1, + 7708, 7707, 7706, -1, 7708, 7706, 7709, -1, + 7708, 7709, 7710, -1, 7710, 7711, 7708, -1, + 7712, 7708, 7711, -1, 7712, 7707, 7708, -1, + 7712, 7703, 7707, -1, 7712, 7711, 7703, -1, + 7711, 7666, 7703, -1, 7711, 7710, 7666, -1, + 7710, 7667, 7666, -1, 7710, 7702, 7667, -1, + 7702, 7710, 7709, -1, 7709, 7701, 7702, -1, + 7709, 7700, 7701, -1, 7700, 7709, 7706, -1, + 7706, 7699, 7700, -1, 7706, 7705, 7699, -1, + 7713, 7699, 7705, -1, 7713, 7698, 7699, -1, + 7713, 7695, 7698, -1, 7713, 7705, 7695, -1, + 7695, 7705, 7703, -1, 7714, 7660, 1152, -1, + 1152, 1151, 7714, -1, 7715, 7714, 1151, -1, + 1151, 1062, 7715, -1, 7715, 1062, 1064, -1, + 1064, 7714, 7715, -1, 1064, 7716, 7714, -1, + 7716, 1064, 1063, -1, 7716, 1063, 6412, -1, + 6412, 7714, 7716, -1, 7714, 6412, 6414, -1, + 7694, 6786, 6784, -1, 7717, 7694, 6784, -1, + 7717, 6784, 6783, -1, 7717, 6783, 7718, -1, + 7718, 7694, 7717, -1, 7718, 7693, 7694, -1, + 7718, 7690, 7693, -1, 7690, 7718, 6783, -1, + 7690, 6783, 6782, -1, 6782, 7688, 7690, -1, + 7688, 6782, 6781, -1, 6781, 7686, 7688, -1, + 7686, 6781, 6780, -1, 6780, 7684, 7686, -1, + 7684, 6780, 6779, -1, 6779, 7683, 7684, -1, + 7683, 6779, 6778, -1, 7683, 6778, 6777, -1, + 6777, 7681, 7683, -1, 7681, 6777, 6776, -1, + 6776, 7679, 7681, -1, 7679, 6776, 6775, -1, + 6775, 7677, 7679, -1, 7677, 6775, 6774, -1, + 6774, 7673, 7677, -1, 7673, 6774, 113, -1, + 7673, 113, 112, -1, 112, 7672, 7673, -1, + 112, 7662, 7672, -1, 112, 111, 7662, -1, + 111, 7663, 7662, -1, 111, 113, 7663, -1, + 113, 6445, 7663, -1, 7719, 7663, 6445, -1, + 7719, 7664, 7663, -1, 7719, 7720, 7664, -1, + 7719, 6445, 7720, -1, 7720, 6445, 6446, -1, + 6446, 7664, 7720, -1, 6446, 6447, 7664, -1, + 6447, 6448, 7664, -1, 6448, 7721, 7664, -1, + 7721, 6448, 6449, -1, 7721, 6449, 6755, -1, + 7721, 6755, 6753, -1, 6753, 7664, 7721, -1, + 7722, 6753, 6752, -1, 6752, 7723, 7722, -1, + 6752, 6750, 7723, -1, 6750, 7724, 7723, -1, + 6750, 7725, 7724, -1, 7725, 6750, 6748, -1, + 6748, 7726, 7725, -1, 7726, 6748, 6746, -1, + 6746, 7727, 7726, -1, 7727, 6746, 6744, -1, + 6744, 7728, 7727, -1, 7728, 6744, 6742, -1, + 6742, 7729, 7728, -1, 7729, 6742, 6740, -1, + 6740, 7730, 7729, -1, 7730, 6740, 6738, -1, + 6738, 7731, 7730, -1, 7731, 6738, 6736, -1, + 6736, 7732, 7731, -1, 7732, 6736, 6734, -1, + 6734, 7733, 7732, -1, 7733, 6734, 6732, -1, + 6732, 7734, 7733, -1, 7734, 6732, 6731, -1, + 6731, 7735, 7734, -1, 6731, 7736, 7735, -1, + 7736, 6731, 6729, -1, 6729, 7737, 7736, -1, + 7737, 6729, 6727, -1, 6727, 7738, 7737, -1, + 7738, 6727, 6725, -1, 6725, 7739, 7738, -1, + 7739, 6725, 6723, -1, 6723, 7740, 7739, -1, + 7740, 6723, 6721, -1, 6721, 7741, 7740, -1, + 7741, 6721, 6719, -1, 6719, 7742, 7741, -1, + 7742, 6719, 6717, -1, 6717, 7743, 7742, -1, + 7743, 6717, 6715, -1, 6715, 7744, 7743, -1, + 7744, 6715, 6713, -1, 6713, 7745, 7744, -1, + 7745, 6713, 6707, -1, 6707, 7746, 7745, -1, + 6707, 6706, 7746, -1, 7747, 7746, 6706, -1, + 7747, 6706, 6548, -1, 7747, 6548, 6549, -1, + 6549, 7746, 7747, -1, 6549, 6550, 7746, -1, + 7746, 6550, 6543, -1, 7746, 6543, 6542, -1, + 6542, 7745, 7746, -1, 7745, 6542, 6541, -1, + 6541, 7744, 7745, -1, 7744, 6541, 6540, -1, + 6540, 7743, 7744, -1, 7743, 6540, 6539, -1, + 6539, 7742, 7743, -1, 7742, 6539, 6538, -1, + 6538, 7741, 7742, -1, 7741, 6538, 6537, -1, + 6537, 7740, 7741, -1, 7740, 6537, 6536, -1, + 6536, 7739, 7740, -1, 7739, 6536, 6535, -1, + 6535, 7738, 7739, -1, 7738, 6535, 6534, -1, + 6534, 7737, 7738, -1, 7737, 6534, 6533, -1, + 6533, 7736, 7737, -1, 7736, 6533, 6532, -1, + 6532, 7735, 7736, -1, 7735, 6532, 6531, -1, + 7735, 6531, 6530, -1, 6530, 7734, 7735, -1, + 7734, 6530, 6529, -1, 6529, 7733, 7734, -1, + 7733, 6529, 6528, -1, 6528, 7732, 7733, -1, + 7732, 6528, 6527, -1, 6527, 7731, 7732, -1, + 7731, 6527, 6526, -1, 6526, 7730, 7731, -1, + 7730, 6526, 6525, -1, 6525, 7729, 7730, -1, + 7729, 6525, 6524, -1, 6524, 7728, 7729, -1, + 7728, 6524, 6523, -1, 6523, 7727, 7728, -1, + 7727, 6523, 6522, -1, 6522, 7726, 7727, -1, + 7726, 6522, 6521, -1, 6521, 7725, 7726, -1, + 7725, 6521, 6520, -1, 6520, 7724, 7725, -1, + 7724, 6520, 6517, -1, 7724, 6517, 7748, -1, + 7749, 7724, 7748, -1, 7749, 7750, 7724, -1, + 7750, 7723, 7724, -1, 7750, 7722, 7723, -1, + 7750, 7749, 7722, -1, 7749, 7748, 7722, -1, + 7748, 7751, 7722, -1, 7751, 7748, 6517, -1, + 7751, 6517, 6516, -1, 7751, 6516, 6515, -1, + 6515, 7722, 7751, -1, 7752, 6515, 6514, -1, + 6514, 7753, 7752, -1, 6514, 6512, 7753, -1, + 7753, 6512, 6585, -1, 6585, 7752, 7753, -1, + 6585, 6586, 7752, -1, 6586, 6587, 7752, -1, + 6587, 7754, 7752, -1, 7754, 6587, 6588, -1, + 7754, 6588, 6656, -1, 6656, 6658, 7754, -1, + 6658, 7752, 7754, -1, 253, 6658, 6660, -1, + 6660, 7755, 253, -1, 7755, 6660, 6661, -1, + 7755, 6661, 7756, -1, 7756, 253, 7755, -1, + 7756, 251, 253, -1, 7756, 252, 251, -1, + 252, 7756, 6661, -1, 6661, 376, 252, -1, + 376, 6661, 6662, -1, 6662, 375, 376, -1, + 375, 6662, 6663, -1, 6663, 374, 375, -1, + 374, 6663, 6664, -1, 6664, 373, 374, -1, + 373, 6664, 6665, -1, 6665, 372, 373, -1, + 372, 6665, 6666, -1, 6666, 371, 372, -1, + 371, 6666, 6667, -1, 6667, 370, 371, -1, + 370, 6667, 6668, -1, 6668, 369, 370, -1, + 369, 6668, 6669, -1, 6669, 368, 369, -1, + 368, 6669, 6670, -1, 6670, 367, 368, -1, + 367, 6670, 6671, -1, 6671, 366, 367, -1, + 366, 6671, 6672, -1, 6672, 365, 366, -1, + 365, 6672, 6673, -1, 6673, 364, 365, -1, + 364, 6673, 6674, -1, 6674, 363, 364, -1, + 363, 6674, 6675, -1, 6675, 362, 363, -1, + 362, 6675, 6676, -1, 6676, 361, 362, -1, + 361, 6676, 6677, -1, 6677, 360, 361, -1, + 360, 6677, 6678, -1, 6678, 359, 360, -1, + 359, 6678, 6680, -1, 6680, 358, 359, -1, + 6680, 357, 358, -1, 357, 6680, 6681, -1, + 6681, 356, 357, -1, 356, 6681, 6682, -1, + 6682, 355, 356, -1, 355, 6682, 6683, -1, + 6683, 354, 355, -1, 354, 6683, 6684, -1, + 6684, 353, 354, -1, 353, 6684, 6685, -1, + 6685, 352, 353, -1, 352, 6685, 6686, -1, + 6686, 351, 352, -1, 351, 6686, 6687, -1, + 6687, 350, 351, -1, 350, 6687, 6688, -1, + 6688, 349, 350, -1, 349, 6688, 6689, -1, + 6689, 348, 349, -1, 348, 6689, 6690, -1, + 6690, 347, 348, -1, 347, 6690, 6691, -1, + 6691, 346, 347, -1, 346, 6691, 6692, -1, + 6692, 345, 346, -1, 345, 6692, 6693, -1, + 6693, 344, 345, -1, 344, 6693, 6694, -1, + 6694, 343, 344, -1, 343, 6694, 6695, -1, + 6695, 342, 343, -1, 342, 6695, 6696, -1, + 6696, 341, 342, -1, 341, 6696, 6697, -1, + 6697, 340, 341, -1, 340, 6697, 6698, -1, + 6698, 260, 340, -1, 260, 6698, 6700, -1, + 6700, 259, 260, -1, 6700, 257, 259, -1, + 6700, 6699, 257, -1, 6699, 6701, 257, -1, + 257, 6701, 6450, -1, 6800, 258, 257, -1, + 7757, 258, 6800, -1, 7757, 261, 258, -1, + 7757, 7758, 261, -1, 7758, 7757, 6800, -1, + 7758, 6800, 6799, -1, 7758, 6799, 6793, -1, + 6793, 261, 7758, -1, 261, 6793, 6795, -1, + 6795, 338, 261, -1, 338, 6795, 7759, -1, + 7759, 336, 338, -1, 336, 7759, 7760, -1, + 7760, 334, 336, -1, 334, 7760, 7761, -1, + 7761, 332, 334, -1, 332, 7761, 7762, -1, + 7762, 330, 332, -1, 330, 7762, 7763, -1, + 7763, 328, 330, -1, 328, 7763, 7764, -1, + 7764, 326, 328, -1, 326, 7764, 7765, -1, + 7765, 324, 326, -1, 324, 7765, 7766, -1, + 7766, 322, 324, -1, 322, 7766, 7767, -1, + 7767, 320, 322, -1, 320, 7767, 7768, -1, + 7768, 318, 320, -1, 318, 7768, 7769, -1, + 7769, 316, 318, -1, 316, 7769, 7770, -1, + 7770, 314, 316, -1, 314, 7770, 7771, -1, + 7771, 312, 314, -1, 312, 7771, 7772, -1, + 7772, 310, 312, -1, 310, 7772, 7773, -1, + 7773, 308, 310, -1, 308, 7773, 7774, -1, + 7774, 306, 308, -1, 306, 7774, 7775, -1, + 7775, 304, 306, -1, 304, 7775, 7776, -1, + 7776, 302, 304, -1, 302, 7776, 7777, -1, + 7777, 301, 302, -1, 301, 7777, 7778, -1, + 301, 7778, 7779, -1, 7779, 299, 301, -1, + 299, 7779, 7780, -1, 7780, 297, 299, -1, + 297, 7780, 7781, -1, 7781, 295, 297, -1, + 295, 7781, 7782, -1, 7782, 293, 295, -1, + 293, 7782, 7783, -1, 7783, 291, 293, -1, + 291, 7783, 7784, -1, 7784, 289, 291, -1, + 289, 7784, 7785, -1, 7785, 287, 289, -1, + 287, 7785, 7786, -1, 7786, 285, 287, -1, + 285, 7786, 7787, -1, 7787, 283, 285, -1, + 283, 7787, 7788, -1, 7788, 281, 283, -1, + 281, 7788, 7789, -1, 7789, 279, 281, -1, + 279, 7789, 7790, -1, 7790, 277, 279, -1, + 277, 7790, 7791, -1, 7791, 275, 277, -1, + 275, 7791, 7792, -1, 7792, 273, 275, -1, + 273, 7792, 7793, -1, 7793, 271, 273, -1, + 271, 7793, 7794, -1, 7794, 269, 271, -1, + 269, 7794, 7795, -1, 7795, 267, 269, -1, + 267, 7795, 7796, -1, 7796, 265, 267, -1, + 265, 7796, 7797, -1, 7797, 262, 265, -1, + 7797, 377, 262, -1, 7797, 7798, 377, -1, + 7798, 7797, 7796, -1, 7796, 7799, 7798, -1, + 7799, 7796, 7795, -1, 7795, 7800, 7799, -1, + 7800, 7795, 7794, -1, 7794, 7801, 7800, -1, + 7801, 7794, 7793, -1, 7793, 7802, 7801, -1, + 7802, 7793, 7792, -1, 7792, 7803, 7802, -1, + 7803, 7792, 7791, -1, 7791, 7804, 7803, -1, + 7804, 7791, 7790, -1, 7790, 7805, 7804, -1, + 7805, 7790, 7789, -1, 7789, 7806, 7805, -1, + 7806, 7789, 7788, -1, 7788, 7807, 7806, -1, + 7807, 7788, 7787, -1, 7787, 7808, 7807, -1, + 7808, 7787, 7786, -1, 7786, 7809, 7808, -1, + 7809, 7786, 7785, -1, 7785, 7810, 7809, -1, + 7810, 7785, 7784, -1, 7784, 7811, 7810, -1, + 7811, 7784, 7783, -1, 7783, 7812, 7811, -1, + 7812, 7783, 7782, -1, 7782, 7813, 7812, -1, + 7813, 7782, 7781, -1, 7781, 7814, 7813, -1, + 7814, 7781, 7780, -1, 7780, 7815, 7814, -1, + 7815, 7780, 7779, -1, 7779, 7816, 7815, -1, + 7816, 7779, 7778, -1, 7778, 7817, 7816, -1, + 7778, 7818, 7817, -1, 7818, 7778, 7777, -1, + 7777, 7819, 7818, -1, 7819, 7777, 7776, -1, + 7776, 7820, 7819, -1, 7820, 7776, 7775, -1, + 7775, 7821, 7820, -1, 7821, 7775, 7774, -1, + 7774, 7822, 7821, -1, 7822, 7774, 7773, -1, + 7773, 7823, 7822, -1, 7823, 7773, 7772, -1, + 7772, 7824, 7823, -1, 7824, 7772, 7771, -1, + 7771, 7825, 7824, -1, 7825, 7771, 7770, -1, + 7770, 7826, 7825, -1, 7826, 7770, 7769, -1, + 7769, 7827, 7826, -1, 7827, 7769, 7768, -1, + 7768, 7828, 7827, -1, 7828, 7768, 7767, -1, + 7767, 7829, 7828, -1, 7829, 7767, 7766, -1, + 7766, 7830, 7829, -1, 7830, 7766, 7765, -1, + 7765, 7831, 7830, -1, 7831, 7765, 7764, -1, + 7764, 7832, 7831, -1, 7832, 7764, 7763, -1, + 7763, 7833, 7832, -1, 7833, 7763, 7762, -1, + 7762, 7834, 7833, -1, 7834, 7762, 7761, -1, + 7761, 7835, 7834, -1, 7835, 7761, 7760, -1, + 7760, 7836, 7835, -1, 7836, 7760, 7759, -1, + 7759, 7837, 7836, -1, 7837, 7759, 6795, -1, + 7837, 6795, 6794, -1, 7837, 6794, 7838, -1, + 7838, 7836, 7837, -1, 7836, 7838, 7839, -1, + 7839, 7835, 7836, -1, 7835, 7839, 7840, -1, + 7840, 7834, 7835, -1, 7834, 7840, 7841, -1, + 7841, 7833, 7834, -1, 7833, 7841, 7842, -1, + 7842, 7832, 7833, -1, 7832, 7842, 7843, -1, + 7843, 7831, 7832, -1, 7831, 7843, 7844, -1, + 7844, 7830, 7831, -1, 7830, 7844, 7845, -1, + 7845, 7829, 7830, -1, 7829, 7845, 7846, -1, + 7846, 7828, 7829, -1, 7828, 7846, 7847, -1, + 7847, 7827, 7828, -1, 7827, 7847, 7848, -1, + 7848, 7826, 7827, -1, 7826, 7848, 7849, -1, + 7849, 7825, 7826, -1, 7825, 7849, 7850, -1, + 7850, 7824, 7825, -1, 7824, 7850, 7851, -1, + 7851, 7823, 7824, -1, 7823, 7851, 7852, -1, + 7852, 7822, 7823, -1, 7822, 7852, 7853, -1, + 7853, 7821, 7822, -1, 7821, 7853, 7854, -1, + 7854, 7820, 7821, -1, 7820, 7854, 7855, -1, + 7855, 7819, 7820, -1, 7819, 7855, 7856, -1, + 7856, 7818, 7819, -1, 7818, 7856, 7857, -1, + 7857, 7817, 7818, -1, 7817, 7857, 7858, -1, + 7817, 7858, 7859, -1, 7859, 7816, 7817, -1, + 7816, 7859, 7860, -1, 7860, 7815, 7816, -1, + 7815, 7860, 7861, -1, 7861, 7814, 7815, -1, + 7814, 7861, 7862, -1, 7862, 7813, 7814, -1, + 7813, 7862, 7863, -1, 7863, 7812, 7813, -1, + 7812, 7863, 7864, -1, 7864, 7811, 7812, -1, + 7811, 7864, 7865, -1, 7865, 7810, 7811, -1, + 7810, 7865, 7866, -1, 7866, 7809, 7810, -1, + 7809, 7866, 7867, -1, 7867, 7808, 7809, -1, + 7808, 7867, 7868, -1, 7868, 7807, 7808, -1, + 7807, 7868, 7869, -1, 7869, 7806, 7807, -1, + 7806, 7869, 7870, -1, 7870, 7805, 7806, -1, + 7805, 7870, 7871, -1, 7871, 7804, 7805, -1, + 7804, 7871, 7872, -1, 7872, 7803, 7804, -1, + 7803, 7872, 7873, -1, 7873, 7802, 7803, -1, + 7802, 7873, 7874, -1, 7874, 7801, 7802, -1, + 7801, 7874, 7875, -1, 7875, 7800, 7801, -1, + 7800, 7875, 7876, -1, 7876, 7799, 7800, -1, + 7799, 7876, 7877, -1, 7877, 7798, 7799, -1, + 7798, 7877, 109, -1, 109, 377, 7798, -1, + 377, 109, 108, -1, 108, 249, 377, -1, + 249, 108, 7878, -1, 7878, 245, 249, -1, + 7879, 7878, 7880, -1, 7879, 245, 7878, -1, + 7879, 246, 245, -1, 7879, 7880, 246, -1, + 7881, 246, 7880, -1, 7881, 7882, 246, -1, + 7882, 380, 246, -1, 7882, 7883, 380, -1, + 7882, 7881, 7883, -1, 7881, 7880, 7883, -1, + 7883, 7880, 7878, -1, 7878, 7884, 7883, -1, + 7884, 7878, 108, -1, 108, 110, 7884, -1, + 110, 7885, 7886, -1, 110, 7886, 7887, -1, + 7887, 7884, 110, -1, 7884, 7887, 7888, -1, + 7888, 7883, 7884, -1, 7883, 7888, 7889, -1, + 7889, 380, 7883, -1, 7890, 7889, 7891, -1, + 7890, 380, 7889, -1, 7890, 243, 380, -1, + 7890, 7891, 243, -1, 7892, 243, 7891, -1, + 7892, 7893, 243, -1, 7893, 241, 243, -1, + 7893, 240, 241, -1, 7893, 7892, 240, -1, + 7892, 7891, 240, -1, 240, 7891, 7889, -1, + 7889, 239, 240, -1, 239, 7889, 7888, -1, + 7888, 238, 239, -1, 238, 7888, 7887, -1, + 7887, 236, 238, -1, 236, 7887, 7886, -1, + 7886, 237, 236, -1, 237, 7886, 7894, -1, + 7894, 7895, 237, -1, 7895, 7894, 7896, -1, + 7896, 7897, 7895, -1, 7897, 7896, 7898, -1, + 7898, 7899, 7897, -1, 7899, 7898, 7900, -1, + 7900, 7901, 7899, -1, 7901, 7900, 7902, -1, + 7902, 7903, 7901, -1, 7903, 7902, 7904, -1, + 7904, 7905, 7903, -1, 7905, 7904, 7906, -1, + 7906, 7907, 7905, -1, 7907, 7906, 7908, -1, + 7908, 7909, 7907, -1, 7909, 7908, 7910, -1, + 7910, 7911, 7909, -1, 7911, 7910, 7912, -1, + 7912, 7913, 7911, -1, 7913, 7912, 7914, -1, + 7914, 7915, 7913, -1, 7915, 7914, 7916, -1, + 7916, 7917, 7915, -1, 7917, 7916, 7918, -1, + 7918, 7919, 7917, -1, 7919, 7918, 7920, -1, + 7920, 7921, 7919, -1, 7921, 7920, 7922, -1, + 7922, 7923, 7921, -1, 7923, 7922, 7924, -1, + 7924, 7925, 7923, -1, 7925, 7924, 7926, -1, + 7926, 7927, 7925, -1, 7927, 7926, 7928, -1, + 7928, 7929, 7927, -1, 7929, 7928, 107, -1, + 107, 106, 7929, -1, 7930, 7929, 106, -1, + 7929, 7930, 7931, -1, 7931, 7927, 7929, -1, + 7927, 7931, 7932, -1, 7932, 7925, 7927, -1, + 7925, 7932, 7933, -1, 7933, 7923, 7925, -1, + 7923, 7933, 7934, -1, 7934, 7921, 7923, -1, + 7921, 7934, 7935, -1, 7935, 7919, 7921, -1, + 7919, 7935, 7936, -1, 7936, 7917, 7919, -1, + 7917, 7936, 7937, -1, 7937, 7915, 7917, -1, + 7915, 7937, 7938, -1, 7938, 7913, 7915, -1, + 7913, 7938, 7939, -1, 7939, 7911, 7913, -1, + 7911, 7939, 7940, -1, 7940, 7909, 7911, -1, + 7909, 7940, 7941, -1, 7941, 7907, 7909, -1, + 7907, 7941, 7942, -1, 7942, 7905, 7907, -1, + 7905, 7942, 7943, -1, 7943, 7903, 7905, -1, + 7903, 7943, 7944, -1, 7944, 7901, 7903, -1, + 7901, 7944, 7945, -1, 7945, 7899, 7901, -1, + 7899, 7945, 7946, -1, 7946, 7897, 7899, -1, + 7897, 7946, 7947, -1, 7947, 7895, 7897, -1, + 7895, 7947, 7948, -1, 7948, 237, 7895, -1, + 7948, 234, 237, -1, 7948, 235, 234, -1, + 235, 7948, 7947, -1, 7947, 7949, 235, -1, + 7949, 7947, 7946, -1, 7946, 7950, 7949, -1, + 7950, 7946, 7945, -1, 7945, 7951, 7950, -1, + 7951, 7945, 7944, -1, 7944, 7952, 7951, -1, + 7952, 7944, 7943, -1, 7943, 7953, 7952, -1, + 7953, 7943, 7942, -1, 7942, 7954, 7953, -1, + 7954, 7942, 7941, -1, 7941, 7955, 7954, -1, + 7955, 7941, 7940, -1, 7940, 7956, 7955, -1, + 7956, 7940, 7939, -1, 7939, 7957, 7956, -1, + 7957, 7939, 7938, -1, 7938, 7958, 7957, -1, + 7958, 7938, 7937, -1, 7937, 7959, 7958, -1, + 7959, 7937, 7936, -1, 7936, 7960, 7959, -1, + 7960, 7936, 7935, -1, 7935, 7961, 7960, -1, + 7961, 7935, 7934, -1, 7934, 7962, 7961, -1, + 7962, 7934, 7933, -1, 7933, 7963, 7962, -1, + 7963, 7933, 7932, -1, 7932, 7964, 7963, -1, + 7964, 7932, 7931, -1, 7931, 7965, 7964, -1, + 7965, 7931, 7930, -1, 7930, 7966, 7965, -1, + 7930, 106, 7966, -1, 7967, 7966, 106, -1, + 7967, 106, 104, -1, 104, 7968, 7967, -1, + 7968, 104, 103, -1, 103, 7969, 7968, -1, + 103, 7970, 7969, -1, 7970, 103, 101, -1, + 101, 7971, 7970, -1, 7971, 101, 99, -1, + 99, 7972, 7971, -1, 7972, 99, 12, -1, + 12, 7973, 7972, -1, 7973, 12, 11, -1, + 11, 7974, 7973, -1, 7974, 11, 14, -1, + 14, 7975, 7974, -1, 7975, 14, 16, -1, + 16, 7976, 7975, -1, 7976, 16, 18, -1, + 18, 7977, 7976, -1, 7977, 18, 20, -1, + 20, 7978, 7977, -1, 7978, 20, 22, -1, + 22, 7979, 7978, -1, 7979, 22, 24, -1, + 24, 7980, 7979, -1, 7980, 24, 26, -1, + 26, 7981, 7980, -1, 7981, 26, 28, -1, + 28, 7982, 7981, -1, 7982, 28, 30, -1, + 30, 7983, 7982, -1, 7983, 30, 32, -1, + 32, 7984, 7983, -1, 7984, 32, 34, -1, + 34, 7985, 7984, -1, 7985, 34, 36, -1, + 36, 7986, 7985, -1, 7986, 36, 38, -1, + 38, 7987, 7986, -1, 7987, 38, 40, -1, + 40, 7988, 7987, -1, 7988, 40, 42, -1, + 42, 7989, 7988, -1, 7989, 42, 44, -1, + 44, 7990, 7989, -1, 7990, 44, 46, -1, + 46, 7991, 7990, -1, 7991, 46, 48, -1, + 48, 50, 7991, -1, 50, 58, 7991, -1, + 7992, 7993, 7994, -1, 7993, 7992, 7995, -1, + 7995, 7996, 7993, -1, 7996, 7995, 7997, -1, + 7997, 7998, 7996, -1, 7998, 7997, 7999, -1, + 7999, 8000, 7998, -1, 8000, 7999, 8001, -1, + 8001, 8002, 8000, -1, 8002, 8001, 8003, -1, + 8003, 8004, 8002, -1, 8004, 8003, 8005, -1, + 8005, 8006, 8004, -1, 8006, 8005, 8007, -1, + 8007, 8008, 8006, -1, 8008, 8007, 8009, -1, + 8009, 8010, 8008, -1, 8010, 8009, 8011, -1, + 8011, 8012, 8010, -1, 8012, 8011, 8013, -1, + 8013, 8014, 8012, -1, 8014, 8013, 8015, -1, + 8015, 8016, 8014, -1, 8016, 8015, 8017, -1, + 8017, 8018, 8016, -1, 8018, 8017, 8019, -1, + 8019, 8020, 8018, -1, 8020, 8019, 8021, -1, + 8021, 8022, 8020, -1, 8022, 8021, 8023, -1, + 8023, 8024, 8022, -1, 8024, 8023, 8025, -1, + 8025, 8026, 8024, -1, 8026, 8025, 8027, -1, + 8027, 8028, 8026, -1, 8028, 8027, 8029, -1, + 8029, 58, 8028, -1, 8029, 7991, 58, -1, + 8029, 7990, 7991, -1, 7990, 8029, 8027, -1, + 8027, 7989, 7990, -1, 7989, 8027, 8025, -1, + 8025, 7988, 7989, -1, 7988, 8025, 8023, -1, + 8023, 7987, 7988, -1, 7987, 8023, 8021, -1, + 8021, 7986, 7987, -1, 7986, 8021, 8019, -1, + 8019, 7985, 7986, -1, 7985, 8019, 8017, -1, + 8017, 7984, 7985, -1, 7984, 8017, 8015, -1, + 8015, 7983, 7984, -1, 7983, 8015, 8013, -1, + 8013, 7982, 7983, -1, 7982, 8013, 8011, -1, + 8011, 7981, 7982, -1, 7981, 8011, 8009, -1, + 8009, 7980, 7981, -1, 7980, 8009, 8007, -1, + 8007, 7979, 7980, -1, 7979, 8007, 8005, -1, + 8005, 7978, 7979, -1, 7978, 8005, 8003, -1, + 8003, 7977, 7978, -1, 7977, 8003, 8001, -1, + 8001, 7976, 7977, -1, 7976, 8001, 7999, -1, + 7999, 7975, 7976, -1, 7975, 7999, 7997, -1, + 7997, 7974, 7975, -1, 7974, 7997, 7995, -1, + 7995, 7973, 7974, -1, 7973, 7995, 7992, -1, + 7992, 7972, 7973, -1, 7992, 7994, 7972, -1, + 8030, 7972, 7994, -1, 8030, 7971, 7972, -1, + 7971, 8030, 8031, -1, 8031, 7970, 7971, -1, + 7970, 8031, 8032, -1, 8032, 7969, 7970, -1, + 7969, 8032, 8033, -1, 7969, 8033, 8034, -1, + 8034, 7968, 7969, -1, 7968, 8034, 8035, -1, + 8035, 7967, 7968, -1, 7967, 8035, 8036, -1, + 8036, 7966, 7967, -1, 7966, 8036, 8037, -1, + 8037, 7965, 7966, -1, 7965, 8037, 8038, -1, + 8038, 7964, 7965, -1, 7964, 8038, 8039, -1, + 8039, 7963, 7964, -1, 7963, 8039, 8040, -1, + 8040, 7962, 7963, -1, 7962, 8040, 8041, -1, + 8041, 7961, 7962, -1, 7961, 8041, 8042, -1, + 8042, 7960, 7961, -1, 7960, 8042, 8043, -1, + 8043, 7959, 7960, -1, 7959, 8043, 8044, -1, + 8044, 7958, 7959, -1, 7958, 8044, 8045, -1, + 8045, 7957, 7958, -1, 7957, 8045, 8046, -1, + 8046, 7956, 7957, -1, 7956, 8046, 8047, -1, + 8047, 7955, 7956, -1, 7955, 8047, 8048, -1, + 8048, 7954, 7955, -1, 7954, 8048, 8049, -1, + 8049, 7953, 7954, -1, 7953, 8049, 8050, -1, + 8050, 7952, 7953, -1, 7952, 8050, 8051, -1, + 8051, 7951, 7952, -1, 7951, 8051, 8052, -1, + 8052, 7950, 7951, -1, 7950, 8052, 8053, -1, + 8053, 7949, 7950, -1, 7949, 8053, 8054, -1, + 8054, 235, 7949, -1, 8054, 233, 235, -1, + 8054, 232, 233, -1, 232, 8054, 8053, -1, + 8053, 231, 232, -1, 231, 8053, 8052, -1, + 8052, 230, 231, -1, 230, 8052, 8051, -1, + 8051, 229, 230, -1, 229, 8051, 8050, -1, + 8050, 228, 229, -1, 228, 8050, 8049, -1, + 8049, 227, 228, -1, 227, 8049, 8048, -1, + 8048, 226, 227, -1, 226, 8048, 8047, -1, + 8047, 225, 226, -1, 225, 8047, 8046, -1, + 8046, 224, 225, -1, 224, 8046, 8045, -1, + 8045, 223, 224, -1, 223, 8045, 8044, -1, + 8044, 222, 223, -1, 222, 8044, 8043, -1, + 8043, 221, 222, -1, 221, 8043, 8042, -1, + 8042, 220, 221, -1, 220, 8042, 8041, -1, + 8041, 219, 220, -1, 219, 8041, 8040, -1, + 8040, 218, 219, -1, 218, 8040, 8039, -1, + 8039, 217, 218, -1, 217, 8039, 8038, -1, + 8038, 216, 217, -1, 216, 8038, 8037, -1, + 8037, 215, 216, -1, 215, 8037, 8036, -1, + 8036, 442, 215, -1, 442, 8036, 8035, -1, + 8035, 443, 442, -1, 443, 8035, 8034, -1, + 8034, 444, 443, -1, 444, 8034, 8033, -1, + 8033, 445, 444, -1, 8033, 446, 445, -1, + 446, 8033, 8032, -1, 8032, 447, 446, -1, + 447, 8032, 8031, -1, 8031, 448, 447, -1, + 448, 8031, 8030, -1, 8030, 449, 448, -1, + 449, 8030, 7994, -1, 7994, 450, 449, -1, + 450, 7994, 7993, -1, 7993, 452, 450, -1, + 452, 7993, 7996, -1, 7996, 454, 452, -1, + 454, 7996, 7998, -1, 7998, 456, 454, -1, + 456, 7998, 8000, -1, 8000, 458, 456, -1, + 458, 8000, 8002, -1, 8002, 460, 458, -1, + 460, 8002, 8004, -1, 8004, 462, 460, -1, + 462, 8004, 8006, -1, 8006, 464, 462, -1, + 464, 8006, 8008, -1, 8008, 466, 464, -1, + 466, 8008, 8010, -1, 8010, 468, 466, -1, + 468, 8010, 8012, -1, 8012, 470, 468, -1, + 470, 8012, 8014, -1, 8014, 472, 470, -1, + 472, 8014, 8016, -1, 8016, 474, 472, -1, + 474, 8016, 8018, -1, 8018, 476, 474, -1, + 476, 8018, 8020, -1, 8020, 478, 476, -1, + 478, 8020, 8022, -1, 8022, 480, 478, -1, + 480, 8022, 8024, -1, 8024, 482, 480, -1, + 482, 8024, 8026, -1, 8026, 484, 482, -1, + 484, 8026, 8028, -1, 8028, 486, 484, -1, + 486, 8028, 58, -1, 58, 59, 486, -1, + 59, 487, 486, -1, 59, 7485, 487, -1, + 7485, 59, 60, -1, 60, 7484, 7485, -1, + 7484, 60, 61, -1, 61, 7483, 7484, -1, + 7483, 61, 62, -1, 62, 7482, 7483, -1, + 7482, 62, 65, -1, 65, 7480, 7482, -1, + 7480, 65, 64, -1, 8055, 7480, 64, -1, + 8055, 8056, 7480, -1, 8056, 7481, 7480, -1, + 8056, 8057, 7481, -1, 8056, 8055, 8057, -1, + 8055, 64, 8057, -1, 64, 63, 8057, -1, + 7, 8057, 63, -1, 63, 66, 7, -1, + 66, 8058, 7, -1, 8058, 66, 67, -1, + 8058, 67, 68, -1, 68, 7, 8058, -1, + 68, 69, 7, -1, 69, 8, 7, -1, + 8, 69, 70, -1, 8, 70, 72, -1, + 72, 9, 8, -1, 72, 8059, 9, -1, + 8059, 72, 71, -1, 8059, 71, 76, -1, + 76, 9, 8059, -1, 76, 74, 9, -1, + 74, 73, 9, -1, 73, 8060, 9, -1, + 73, 75, 8060, -1, 75, 8061, 8060, -1, + 8061, 75, 77, -1, 77, 8062, 8061, -1, + 8062, 77, 78, -1, 8062, 78, 8063, -1, + 8064, 8065, 8066, -1, 8066, 8067, 8064, -1, + 8067, 8066, 8068, -1, 8068, 8069, 8067, -1, + 8069, 8068, 8070, -1, 8070, 8071, 8069, -1, + 8071, 8070, 8072, -1, 8072, 8073, 8071, -1, + 8073, 8072, 8074, -1, 8074, 8075, 8073, -1, + 8075, 8074, 8076, -1, 8076, 8077, 8075, -1, + 8077, 8076, 8078, -1, 8078, 8079, 8077, -1, + 8079, 8078, 8080, -1, 8080, 8081, 8079, -1, + 8081, 8080, 8082, -1, 8082, 8083, 8081, -1, + 8083, 8082, 8084, -1, 8084, 8085, 8083, -1, + 8085, 8084, 8086, -1, 8086, 8087, 8085, -1, + 8087, 8086, 8088, -1, 8088, 8089, 8087, -1, + 8089, 8088, 8090, -1, 8090, 8091, 8089, -1, + 8091, 8090, 8092, -1, 8092, 8093, 8091, -1, + 8093, 8092, 8094, -1, 8094, 8095, 8093, -1, + 8095, 8094, 8096, -1, 8096, 8097, 8095, -1, + 8097, 8096, 8098, -1, 8098, 8099, 8097, -1, + 8099, 8098, 8100, -1, 8100, 8101, 8099, -1, + 8101, 8100, 8102, -1, 8102, 8103, 8101, -1, + 8103, 8102, 8104, -1, 8104, 8105, 8103, -1, + 8105, 8104, 8106, -1, 8106, 8107, 8105, -1, + 8107, 8106, 8063, -1, 8107, 8063, 78, -1, + 8107, 78, 79, -1, 79, 8105, 8107, -1, + 8105, 79, 80, -1, 80, 8103, 8105, -1, + 8103, 80, 81, -1, 81, 8101, 8103, -1, + 8101, 81, 82, -1, 82, 8099, 8101, -1, + 8099, 82, 83, -1, 83, 8097, 8099, -1, + 8097, 83, 84, -1, 84, 8095, 8097, -1, + 8095, 84, 85, -1, 85, 8093, 8095, -1, + 8093, 85, 86, -1, 86, 8091, 8093, -1, + 8091, 86, 87, -1, 87, 8089, 8091, -1, + 8089, 87, 88, -1, 88, 8087, 8089, -1, + 8087, 88, 89, -1, 89, 8085, 8087, -1, + 8085, 89, 90, -1, 90, 8083, 8085, -1, + 8083, 90, 91, -1, 91, 8081, 8083, -1, + 8081, 91, 92, -1, 92, 8079, 8081, -1, + 8079, 92, 93, -1, 93, 8077, 8079, -1, + 8077, 93, 94, -1, 94, 8075, 8077, -1, + 8075, 94, 95, -1, 95, 8073, 8075, -1, + 8073, 95, 96, -1, 96, 8071, 8073, -1, + 8071, 96, 97, -1, 97, 8069, 8071, -1, + 8069, 97, 98, -1, 98, 8067, 8069, -1, + 8067, 98, 100, -1, 100, 8064, 8067, -1, + 8064, 100, 102, -1, 8064, 102, 105, -1, + 105, 8065, 8064, -1, 8065, 105, 107, -1, + 107, 8108, 8065, -1, 8108, 107, 7928, -1, + 7928, 8109, 8108, -1, 8109, 7928, 7926, -1, + 7926, 8110, 8109, -1, 8110, 7926, 7924, -1, + 7924, 8111, 8110, -1, 8111, 7924, 7922, -1, + 7922, 8112, 8111, -1, 8112, 7922, 7920, -1, + 7920, 8113, 8112, -1, 8113, 7920, 7918, -1, + 7918, 8114, 8113, -1, 8114, 7918, 7916, -1, + 7916, 8115, 8114, -1, 8115, 7916, 7914, -1, + 7914, 8116, 8115, -1, 8116, 7914, 7912, -1, + 7912, 8117, 8116, -1, 8117, 7912, 7910, -1, + 7910, 8118, 8117, -1, 8118, 7910, 7908, -1, + 7908, 8119, 8118, -1, 8119, 7908, 7906, -1, + 7906, 8120, 8119, -1, 8120, 7906, 7904, -1, + 7904, 8121, 8120, -1, 8121, 7904, 7902, -1, + 7902, 8122, 8121, -1, 8122, 7902, 7900, -1, + 7900, 8123, 8122, -1, 8123, 7900, 7898, -1, + 7898, 8124, 8123, -1, 8124, 7898, 7896, -1, + 7896, 8125, 8124, -1, 8125, 7896, 7894, -1, + 7894, 8126, 8125, -1, 8126, 7894, 7886, -1, + 8126, 7886, 7885, -1, 8126, 7885, 8127, -1, + 8127, 8125, 8126, -1, 8125, 8127, 8128, -1, + 8128, 8124, 8125, -1, 8124, 8128, 8129, -1, + 8129, 8123, 8124, -1, 8123, 8129, 8130, -1, + 8130, 8122, 8123, -1, 8122, 8130, 8131, -1, + 8131, 8121, 8122, -1, 8121, 8131, 8132, -1, + 8132, 8120, 8121, -1, 8120, 8132, 8133, -1, + 8133, 8119, 8120, -1, 8119, 8133, 8134, -1, + 8134, 8118, 8119, -1, 8118, 8134, 8135, -1, + 8135, 8117, 8118, -1, 8117, 8135, 8136, -1, + 8136, 8116, 8117, -1, 8116, 8136, 8137, -1, + 8137, 8115, 8116, -1, 8115, 8137, 8138, -1, + 8138, 8114, 8115, -1, 8114, 8138, 8139, -1, + 8139, 8113, 8114, -1, 8113, 8139, 8140, -1, + 8140, 8112, 8113, -1, 8112, 8140, 8141, -1, + 8141, 8111, 8112, -1, 8111, 8141, 8142, -1, + 8142, 8110, 8111, -1, 8110, 8142, 8143, -1, + 8143, 8109, 8110, -1, 8109, 8143, 8144, -1, + 8144, 8108, 8109, -1, 8108, 8144, 8145, -1, + 8145, 8065, 8108, -1, 8145, 8066, 8065, -1, + 8145, 8146, 8066, -1, 8146, 8145, 8144, -1, + 8144, 8147, 8146, -1, 8147, 8144, 8143, -1, + 8143, 8148, 8147, -1, 8148, 8143, 8142, -1, + 8142, 8149, 8148, -1, 8149, 8142, 8141, -1, + 8141, 8150, 8149, -1, 8150, 8141, 8140, -1, + 8140, 8151, 8150, -1, 8151, 8140, 8139, -1, + 8139, 8152, 8151, -1, 8152, 8139, 8138, -1, + 8138, 8153, 8152, -1, 8153, 8138, 8137, -1, + 8137, 8154, 8153, -1, 8154, 8137, 8136, -1, + 8136, 8155, 8154, -1, 8155, 8136, 8135, -1, + 8135, 8156, 8155, -1, 8156, 8135, 8134, -1, + 8134, 8157, 8156, -1, 8157, 8134, 8133, -1, + 8133, 8158, 8157, -1, 8158, 8133, 8132, -1, + 8132, 8159, 8158, -1, 8159, 8132, 8131, -1, + 8131, 8160, 8159, -1, 8160, 8131, 8130, -1, + 8130, 8161, 8160, -1, 8161, 8130, 8129, -1, + 8129, 8162, 8161, -1, 8162, 8129, 8128, -1, + 8128, 8163, 8162, -1, 8163, 8128, 8127, -1, + 8127, 8164, 8163, -1, 8164, 8127, 7885, -1, + 7885, 8165, 8164, -1, 8165, 7885, 110, -1, + 8165, 110, 109, -1, 8165, 109, 7877, -1, + 7877, 8164, 8165, -1, 8164, 7877, 7876, -1, + 7876, 8163, 8164, -1, 8163, 7876, 7875, -1, + 7875, 8162, 8163, -1, 8162, 7875, 7874, -1, + 7874, 8161, 8162, -1, 8161, 7874, 7873, -1, + 7873, 8160, 8161, -1, 8160, 7873, 7872, -1, + 7872, 8159, 8160, -1, 8159, 7872, 7871, -1, + 7871, 8158, 8159, -1, 8158, 7871, 7870, -1, + 7870, 8157, 8158, -1, 8157, 7870, 7869, -1, + 7869, 8156, 8157, -1, 8156, 7869, 7868, -1, + 7868, 8155, 8156, -1, 8155, 7868, 7867, -1, + 7867, 8154, 8155, -1, 8154, 7867, 7866, -1, + 7866, 8153, 8154, -1, 8153, 7866, 7865, -1, + 7865, 8152, 8153, -1, 8152, 7865, 7864, -1, + 7864, 8151, 8152, -1, 8151, 7864, 7863, -1, + 7863, 8150, 8151, -1, 8150, 7863, 7862, -1, + 7862, 8149, 8150, -1, 8149, 7862, 7861, -1, + 7861, 8148, 8149, -1, 8148, 7861, 7860, -1, + 7860, 8147, 8148, -1, 8147, 7860, 7859, -1, + 7859, 8146, 8147, -1, 8146, 7859, 7858, -1, + 7858, 8066, 8146, -1, 7858, 8068, 8066, -1, + 8068, 7858, 7857, -1, 7857, 8070, 8068, -1, + 8070, 7857, 7856, -1, 7856, 8072, 8070, -1, + 8072, 7856, 7855, -1, 7855, 8074, 8072, -1, + 8074, 7855, 7854, -1, 7854, 8076, 8074, -1, + 8076, 7854, 7853, -1, 7853, 8078, 8076, -1, + 8078, 7853, 7852, -1, 7852, 8080, 8078, -1, + 8080, 7852, 7851, -1, 7851, 8082, 8080, -1, + 8082, 7851, 7850, -1, 7850, 8084, 8082, -1, + 8084, 7850, 7849, -1, 7849, 8086, 8084, -1, + 8086, 7849, 7848, -1, 7848, 8088, 8086, -1, + 8088, 7848, 7847, -1, 7847, 8090, 8088, -1, + 8090, 7847, 7846, -1, 7846, 8092, 8090, -1, + 8092, 7846, 7845, -1, 7845, 8094, 8092, -1, + 8094, 7845, 7844, -1, 7844, 8096, 8094, -1, + 8096, 7844, 7843, -1, 7843, 8098, 8096, -1, + 8098, 7843, 7842, -1, 7842, 8100, 8098, -1, + 8100, 7842, 7841, -1, 7841, 8102, 8100, -1, + 8102, 7841, 7840, -1, 7840, 8104, 8102, -1, + 8104, 7840, 7839, -1, 7839, 8106, 8104, -1, + 8106, 7839, 7838, -1, 7838, 8063, 8106, -1, + 8063, 7838, 6794, -1, 6794, 8062, 8063, -1, + 8062, 6794, 6796, -1, 6796, 8061, 8062, -1, + 8061, 6796, 6802, -1, 8166, 8061, 6802, -1, + 8166, 6802, 6803, -1, 8166, 6803, 8167, -1, + 8167, 8061, 8166, -1, 8167, 8060, 8061, -1, + 8167, 6803, 8060, -1, 6803, 9, 8060, -1, + 8168, 6810, 6812, -1, 8169, 8168, 6812, -1, + 6812, 6814, 8169, -1, 8169, 6814, 6841, -1, + 6841, 8168, 8169, -1, 6841, 6842, 8168, -1, + 6842, 6843, 8168, -1, 6843, 6844, 8168, -1, + 8170, 8171, 8172, -1, 8173, 8168, 6844, -1, + 6844, 8174, 8173, -1, 8174, 6844, 805, -1, + 8174, 805, 804, -1, 804, 8173, 8174, -1, + 804, 8175, 8173, -1, 8175, 804, 803, -1, + 8176, 8175, 803, -1, 8176, 8173, 8175, -1, + 8176, 8177, 8173, -1, 8176, 803, 8177, -1, + 8178, 8177, 803, -1, 8178, 803, 845, -1, + 845, 844, 8178, -1, 8179, 8180, 8178, -1, + 8179, 8178, 844, -1, 844, 846, 8179, -1, + 8181, 8182, 8183, -1, 8184, 8182, 8181, -1, + 8181, 8185, 8184, -1, 8181, 8183, 8185, -1, + 8185, 8183, 8179, -1, 8185, 8179, 846, -1, + 846, 8186, 8185, -1, 8186, 846, 847, -1, + 847, 8187, 8186, -1, 8187, 847, 848, -1, + 848, 8188, 8187, -1, 8188, 848, 849, -1, + 849, 8189, 8188, -1, 8189, 849, 850, -1, + 850, 8190, 8189, -1, 8190, 850, 851, -1, + 851, 8191, 8190, -1, 8191, 851, 852, -1, + 852, 8192, 8191, -1, 8192, 852, 853, -1, + 853, 8193, 8192, -1, 8193, 853, 854, -1, + 854, 8194, 8193, -1, 8194, 854, 855, -1, + 855, 8195, 8194, -1, 8195, 855, 856, -1, + 856, 8196, 8195, -1, 8196, 856, 857, -1, + 857, 8197, 8196, -1, 8197, 857, 858, -1, + 858, 8198, 8197, -1, 8198, 858, 859, -1, + 859, 8199, 8198, -1, 8199, 859, 860, -1, + 860, 8200, 8199, -1, 8200, 860, 861, -1, + 861, 8201, 8200, -1, 8201, 861, 862, -1, + 862, 8202, 8201, -1, 8202, 862, 863, -1, + 863, 8203, 8202, -1, 8203, 863, 864, -1, + 864, 8204, 8203, -1, 8204, 864, 865, -1, + 865, 8205, 8204, -1, 8205, 865, 1018, -1, + 1018, 8206, 8205, -1, 8206, 1018, 1016, -1, + 1016, 8207, 8206, -1, 8207, 1016, 1014, -1, + 1014, 8208, 8207, -1, 8208, 1014, 1012, -1, + 1012, 8209, 8208, -1, 8209, 1012, 1010, -1, + 1010, 8210, 8209, -1, 8210, 1010, 1008, -1, + 1008, 8211, 8210, -1, 8211, 1008, 1006, -1, + 1006, 8212, 8211, -1, 8212, 1006, 1004, -1, + 1004, 8213, 8212, -1, 8213, 1004, 1002, -1, + 1002, 8214, 8213, -1, 8214, 1002, 1000, -1, + 1000, 8215, 8214, -1, 8215, 1000, 998, -1, + 998, 8216, 8215, -1, 8216, 998, 996, -1, + 996, 8217, 8216, -1, 8217, 996, 994, -1, + 994, 8218, 8217, -1, 8218, 994, 992, -1, + 992, 8219, 8218, -1, 8219, 992, 990, -1, + 990, 8220, 8219, -1, 8220, 990, 988, -1, + 988, 8221, 8220, -1, 8221, 988, 986, -1, + 986, 8222, 8221, -1, 8222, 986, 984, -1, + 984, 8223, 8222, -1, 8223, 984, 981, -1, + 8223, 981, 980, -1, 8223, 980, 7059, -1, + 7059, 8222, 8223, -1, 8222, 7059, 7058, -1, + 7058, 8221, 8222, -1, 8221, 7058, 7057, -1, + 7057, 8220, 8221, -1, 8220, 7057, 7056, -1, + 7056, 8219, 8220, -1, 8219, 7056, 7055, -1, + 7055, 8218, 8219, -1, 8218, 7055, 7054, -1, + 7054, 8217, 8218, -1, 8217, 7054, 7053, -1, + 7053, 8216, 8217, -1, 8216, 7053, 7052, -1, + 7052, 8215, 8216, -1, 8215, 7052, 7051, -1, + 7051, 8214, 8215, -1, 8214, 7051, 7050, -1, + 7050, 8213, 8214, -1, 8213, 7050, 7049, -1, + 7049, 8212, 8213, -1, 8212, 7049, 7048, -1, + 7048, 8211, 8212, -1, 8211, 7048, 7047, -1, + 7047, 8210, 8211, -1, 8210, 7047, 7046, -1, + 7046, 8209, 8210, -1, 8209, 7046, 7045, -1, + 7045, 8208, 8209, -1, 8208, 7045, 7044, -1, + 7044, 8207, 8208, -1, 8207, 7044, 7043, -1, + 7043, 8206, 8207, -1, 8206, 7043, 7042, -1, + 7042, 8205, 8206, -1, 8205, 7042, 7041, -1, + 7041, 8204, 8205, -1, 8204, 7041, 7040, -1, + 7040, 8203, 8204, -1, 8203, 7040, 7039, -1, + 7039, 8202, 8203, -1, 8202, 7039, 7038, -1, + 7038, 8201, 8202, -1, 8201, 7038, 7037, -1, + 7037, 8200, 8201, -1, 8200, 7037, 7036, -1, + 7036, 8199, 8200, -1, 8199, 7036, 7035, -1, + 7035, 8198, 8199, -1, 8198, 7035, 7034, -1, + 7034, 8197, 8198, -1, 8197, 7034, 7033, -1, + 7033, 8196, 8197, -1, 8196, 7033, 7032, -1, + 7032, 8195, 8196, -1, 8195, 7032, 7031, -1, + 7031, 8194, 8195, -1, 8194, 7031, 7030, -1, + 7030, 8193, 8194, -1, 8193, 7030, 7029, -1, + 7029, 8192, 8193, -1, 8192, 7029, 7028, -1, + 7028, 8191, 8192, -1, 8191, 7028, 7027, -1, + 7027, 8190, 8191, -1, 8190, 7027, 7026, -1, + 7026, 8189, 8190, -1, 8189, 7026, 7025, -1, + 7025, 8188, 8189, -1, 8188, 7025, 7024, -1, + 7024, 8187, 8188, -1, 8187, 7024, 7023, -1, + 7023, 8186, 8187, -1, 8186, 7023, 7022, -1, + 7022, 8185, 8186, -1, 7022, 8184, 8185, -1, + 8184, 7022, 8224, -1, 8224, 8182, 8184, -1, + 8224, 8225, 8182, -1, 8225, 8224, 7022, -1, + 8225, 7022, 6941, -1, 6941, 8182, 8225, -1, + 8182, 6941, 6940, -1, 5, 8183, 8182, -1, + 8183, 5, 4, -1, 4, 8179, 8183, -1, + 4, 6, 8179, -1, 6, 8180, 8179, -1, + 8180, 6, 5, -1, 8180, 5, 8226, -1, + 8226, 8178, 8180, -1, 8226, 8177, 8178, -1, + 8226, 5, 8177, -1, 5, 8173, 8177, -1, + 8227, 8228, 8170, -1, 8227, 8229, 8230, -1, + 8229, 6940, 6945, -1, 8231, 8229, 6945, -1, + 6945, 8232, 8231, -1, 6945, 6944, 8232, -1, + 8232, 6944, 6946, -1, 8232, 6946, 7018, -1, + 7018, 8233, 8232, -1, 8233, 7018, 7016, -1, + 7016, 8234, 8233, -1, 8234, 7016, 7014, -1, + 7014, 8235, 8234, -1, 8235, 7014, 7012, -1, + 7012, 8236, 8235, -1, 8236, 7012, 7010, -1, + 7010, 8237, 8236, -1, 8237, 7010, 7008, -1, + 7008, 8238, 8237, -1, 8238, 7008, 7006, -1, + 7006, 8239, 8238, -1, 8239, 7006, 7004, -1, + 7004, 8240, 8239, -1, 8240, 7004, 7002, -1, + 7002, 8241, 8240, -1, 8241, 7002, 7000, -1, + 7000, 8242, 8241, -1, 8242, 7000, 6998, -1, + 6998, 8243, 8242, -1, 8243, 6998, 6996, -1, + 6996, 8244, 8243, -1, 8244, 6996, 6994, -1, + 6994, 8245, 8244, -1, 8245, 6994, 6992, -1, + 6992, 8246, 8245, -1, 8246, 6992, 6990, -1, + 6990, 8247, 8246, -1, 8247, 6990, 6988, -1, + 6988, 8248, 8247, -1, 8248, 6988, 6986, -1, + 6986, 8249, 8248, -1, 8249, 6986, 6984, -1, + 6984, 8250, 8249, -1, 8250, 6984, 6982, -1, + 6982, 8251, 8250, -1, 8251, 6982, 6980, -1, + 6980, 8252, 8251, -1, 8252, 6980, 6978, -1, + 6978, 8253, 8252, -1, 8253, 6978, 6976, -1, + 6976, 8254, 8253, -1, 8254, 6976, 6974, -1, + 6974, 8255, 8254, -1, 8255, 6974, 6972, -1, + 6972, 8256, 8255, -1, 8256, 6972, 6970, -1, + 6970, 8257, 8256, -1, 8257, 6970, 6968, -1, + 6968, 8258, 8257, -1, 8258, 6968, 6966, -1, + 6966, 8259, 8258, -1, 8259, 6966, 6964, -1, + 6964, 8260, 8259, -1, 8260, 6964, 6962, -1, + 6962, 8261, 8260, -1, 8261, 6962, 6960, -1, + 6960, 8262, 8261, -1, 8262, 6960, 6958, -1, + 6958, 8263, 8262, -1, 8263, 6958, 6956, -1, + 6956, 8264, 8263, -1, 8264, 6956, 6954, -1, + 6954, 8265, 8264, -1, 8265, 6954, 6952, -1, + 6952, 8266, 8265, -1, 8266, 6952, 6950, -1, + 6950, 8267, 8266, -1, 8267, 6950, 6947, -1, + 6947, 672, 8267, -1, 672, 8268, 8267, -1, + 672, 671, 8268, -1, 8269, 8270, 8271, -1, + 8269, 8272, 8270, -1, 8273, 8274, 8275, -1, + 8273, 8275, 8276, -1, 8276, 8277, 8273, -1, + 8277, 8276, 8278, -1, 8278, 8279, 8277, -1, + 8279, 8278, 8280, -1, 8280, 8281, 8279, -1, + 8280, 8282, 8281, -1, 8282, 8280, 8283, -1, + 8283, 8284, 8282, -1, 8284, 8283, 8272, -1, + 8272, 8269, 8284, -1, 8268, 8269, 8285, -1, + 8268, 8284, 8269, -1, 8284, 8268, 671, -1, + 671, 8282, 8284, -1, 8282, 671, 669, -1, + 669, 8281, 8282, -1, 8281, 669, 666, -1, + 8281, 666, 664, -1, 664, 8279, 8281, -1, + 8279, 664, 662, -1, 662, 8277, 8279, -1, + 8277, 662, 661, -1, 661, 8273, 8277, -1, + 661, 8286, 8273, -1, 8287, 8288, 8289, -1, + 8288, 8287, 8290, -1, 8290, 8291, 8288, -1, + 8291, 8290, 8292, -1, 8292, 8293, 8291, -1, + 8293, 8292, 8294, -1, 8294, 8295, 8293, -1, + 8295, 8294, 8296, -1, 8296, 8297, 8295, -1, + 8297, 8296, 8298, -1, 8298, 8299, 8297, -1, + 8299, 8298, 8300, -1, 8300, 8301, 8299, -1, + 8301, 8300, 8302, -1, 8302, 8303, 8301, -1, + 8303, 8302, 8304, -1, 8304, 8305, 8303, -1, + 8305, 8304, 8306, -1, 8306, 8307, 8305, -1, + 8307, 8306, 8308, -1, 8308, 8309, 8307, -1, + 8309, 8308, 8310, -1, 8310, 8311, 8309, -1, + 8311, 8310, 8312, -1, 8312, 8313, 8311, -1, + 8313, 8312, 8314, -1, 8314, 8315, 8313, -1, + 8315, 8314, 8316, -1, 8316, 8317, 8315, -1, + 8317, 8316, 8318, -1, 8318, 8319, 8317, -1, + 8319, 8318, 8320, -1, 8320, 8321, 8319, -1, + 8321, 8320, 8322, -1, 8322, 8286, 8321, -1, + 8322, 8273, 8286, -1, 8322, 8274, 8273, -1, + 8274, 8322, 8320, -1, 8320, 8323, 8274, -1, + 8323, 8320, 8318, -1, 8318, 8324, 8323, -1, + 8324, 8318, 8316, -1, 8316, 8325, 8324, -1, + 8325, 8316, 8314, -1, 8314, 8326, 8325, -1, + 8326, 8314, 8312, -1, 8312, 8327, 8326, -1, + 8327, 8312, 8310, -1, 8310, 8328, 8327, -1, + 8328, 8310, 8308, -1, 8308, 8329, 8328, -1, + 8329, 8308, 8306, -1, 8306, 8330, 8329, -1, + 8330, 8306, 8304, -1, 8304, 8331, 8330, -1, + 8331, 8304, 8302, -1, 8302, 8332, 8331, -1, + 8332, 8302, 8300, -1, 8300, 8333, 8332, -1, + 8333, 8300, 8298, -1, 8298, 8334, 8333, -1, + 8334, 8298, 8296, -1, 8296, 8335, 8334, -1, + 8335, 8296, 8294, -1, 8294, 8336, 8335, -1, + 8336, 8294, 8292, -1, 8292, 8337, 8336, -1, + 8337, 8292, 8290, -1, 8290, 8338, 8337, -1, + 8338, 8290, 8287, -1, 8287, 8339, 8338, -1, + 8339, 8287, 8289, -1, 8289, 8340, 8339, -1, + 8340, 8289, 8341, -1, 8341, 8342, 8340, -1, + 8342, 8341, 8343, -1, 8343, 8344, 8342, -1, + 8344, 8343, 8345, -1, 8345, 8346, 8344, -1, + 8346, 8345, 8347, -1, 8348, 8349, 8350, -1, + 8348, 8351, 8349, -1, 8351, 8348, 8352, -1, + 8352, 8353, 8351, -1, 8353, 8352, 8354, -1, + 8354, 8355, 8353, -1, 8355, 8354, 8356, -1, + 8356, 8357, 8355, -1, 8357, 8356, 8358, -1, + 8358, 8359, 8357, -1, 8359, 8358, 8360, -1, + 8360, 8361, 8359, -1, 8361, 8360, 8362, -1, + 8362, 8363, 8361, -1, 8363, 8362, 8364, -1, + 8364, 8365, 8363, -1, 8365, 8364, 8366, -1, + 8366, 8367, 8365, -1, 8367, 8366, 8368, -1, + 8368, 8369, 8367, -1, 8369, 8368, 8370, -1, + 8370, 8371, 8369, -1, 8371, 8370, 8347, -1, + 8347, 8372, 8371, -1, 8372, 8347, 8345, -1, + 8345, 8373, 8372, -1, 8373, 8345, 8343, -1, + 8343, 8374, 8373, -1, 8343, 8341, 8374, -1, + 8375, 8374, 8341, -1, 8375, 8341, 8289, -1, + 8289, 8376, 8375, -1, 8376, 8289, 8288, -1, + 8288, 8377, 8376, -1, 8377, 8288, 8291, -1, + 8291, 8378, 8377, -1, 8378, 8291, 8293, -1, + 8293, 8379, 8378, -1, 8379, 8293, 8295, -1, + 8295, 8380, 8379, -1, 8380, 8295, 8297, -1, + 8297, 8381, 8380, -1, 8381, 8297, 8299, -1, + 8299, 8382, 8381, -1, 8382, 8299, 8301, -1, + 8301, 8383, 8382, -1, 8383, 8301, 8303, -1, + 8303, 8384, 8383, -1, 8384, 8303, 8305, -1, + 8305, 8385, 8384, -1, 8385, 8305, 8307, -1, + 8307, 8386, 8385, -1, 8386, 8307, 8309, -1, + 8309, 8387, 8386, -1, 8387, 8309, 8311, -1, + 8311, 8388, 8387, -1, 8388, 8311, 8313, -1, + 8313, 8389, 8388, -1, 8389, 8313, 8315, -1, + 8315, 8390, 8389, -1, 8390, 8315, 8317, -1, + 8317, 8391, 8390, -1, 8391, 8317, 8319, -1, + 8319, 8392, 8391, -1, 8392, 8319, 8321, -1, + 8321, 8393, 8392, -1, 8393, 8321, 8286, -1, + 8286, 8394, 8393, -1, 8394, 8286, 661, -1, + 8394, 661, 660, -1, 8394, 660, 7061, -1, + 7061, 8393, 8394, -1, 8393, 7061, 7063, -1, + 7063, 8392, 8393, -1, 8392, 7063, 7065, -1, + 7065, 8391, 8392, -1, 8391, 7065, 7067, -1, + 7067, 8390, 8391, -1, 8390, 7067, 7069, -1, + 7069, 8389, 8390, -1, 8389, 7069, 7071, -1, + 7071, 8388, 8389, -1, 8388, 7071, 7073, -1, + 7073, 8387, 8388, -1, 8387, 7073, 7075, -1, + 7075, 8386, 8387, -1, 8386, 7075, 7077, -1, + 7077, 8385, 8386, -1, 8385, 7077, 7079, -1, + 7079, 8384, 8385, -1, 8384, 7079, 7081, -1, + 7081, 8383, 8384, -1, 8383, 7081, 7083, -1, + 7083, 8382, 8383, -1, 8382, 7083, 7085, -1, + 7085, 8381, 8382, -1, 8381, 7085, 7087, -1, + 7087, 8380, 8381, -1, 8380, 7087, 7089, -1, + 7089, 8379, 8380, -1, 8379, 7089, 7091, -1, + 7091, 8378, 8379, -1, 8378, 7091, 7093, -1, + 7093, 8377, 8378, -1, 8377, 7093, 7095, -1, + 7095, 8376, 8377, -1, 8376, 7095, 7097, -1, + 7097, 8375, 8376, -1, 8375, 7097, 7130, -1, + 7130, 8374, 8375, -1, 8374, 7130, 7128, -1, + 7128, 8373, 8374, -1, 8373, 7128, 7126, -1, + 7126, 8372, 8373, -1, 8372, 7126, 7124, -1, + 7124, 8371, 8372, -1, 8371, 7124, 7122, -1, + 7122, 8369, 8371, -1, 8369, 7122, 7120, -1, + 7120, 8367, 8369, -1, 8367, 7120, 7118, -1, + 7118, 8365, 8367, -1, 8365, 7118, 7116, -1, + 7116, 8363, 8365, -1, 8363, 7116, 7114, -1, + 7114, 8361, 8363, -1, 8361, 7114, 7112, -1, + 7112, 8359, 8361, -1, 8359, 7112, 7110, -1, + 7110, 8357, 8359, -1, 8357, 7110, 7108, -1, + 7108, 8355, 8357, -1, 8355, 7108, 7106, -1, + 7106, 8353, 8355, -1, 8353, 7106, 7104, -1, + 7104, 8351, 8353, -1, 8351, 7104, 7102, -1, + 7102, 8349, 8351, -1, 8349, 7102, 7098, -1, + 8349, 7098, 7154, -1, 7154, 8395, 8349, -1, + 8395, 7154, 7155, -1, 8395, 7155, 8396, -1, + 8396, 8349, 8395, -1, 8396, 8350, 8349, -1, + 8396, 7155, 8350, -1, 8350, 7155, 7165, -1, + 7165, 8348, 8350, -1, 7165, 8397, 8348, -1, + 7165, 7164, 8397, -1, 8397, 7164, 7342, -1, + 7342, 7339, 8397, -1, 7339, 8348, 8397, -1, + 7339, 8352, 8348, -1, 8352, 7339, 7337, -1, + 7337, 8354, 8352, -1, 8354, 7337, 7335, -1, + 7335, 8356, 8354, -1, 8356, 7335, 7333, -1, + 7333, 8358, 8356, -1, 8358, 7333, 7331, -1, + 7331, 8360, 8358, -1, 8360, 7331, 7329, -1, + 7329, 8362, 8360, -1, 8362, 7329, 7327, -1, + 7327, 8364, 8362, -1, 8364, 7327, 7325, -1, + 7325, 8366, 8364, -1, 8366, 7325, 7323, -1, + 7323, 8368, 8366, -1, 8368, 7323, 7321, -1, + 7321, 8370, 8368, -1, 8370, 7321, 7319, -1, + 7319, 8347, 8370, -1, 8347, 7319, 7318, -1, + 7318, 8346, 8347, -1, 8346, 7318, 7317, -1, + 7317, 8344, 8346, -1, 8344, 7317, 7316, -1, + 7316, 8342, 8344, -1, 8342, 7316, 7315, -1, + 7315, 8340, 8342, -1, 8340, 7315, 7169, -1, + 7169, 8339, 8340, -1, 8339, 7169, 7168, -1, + 7168, 8338, 8339, -1, 8338, 7168, 7171, -1, + 7171, 8337, 8338, -1, 8337, 7171, 7173, -1, + 7173, 8336, 8337, -1, 8336, 7173, 7175, -1, + 7175, 8335, 8336, -1, 8335, 7175, 7177, -1, + 7177, 8334, 8335, -1, 8334, 7177, 7179, -1, + 7179, 8333, 8334, -1, 8333, 7179, 7181, -1, + 7181, 8332, 8333, -1, 8332, 7181, 7183, -1, + 7183, 8331, 8332, -1, 8331, 7183, 7185, -1, + 7185, 8330, 8331, -1, 8330, 7185, 7187, -1, + 7187, 8329, 8330, -1, 8329, 7187, 7189, -1, + 7189, 8328, 8329, -1, 8328, 7189, 7191, -1, + 7191, 8327, 8328, -1, 8327, 7191, 7193, -1, + 7193, 8326, 8327, -1, 8326, 7193, 7195, -1, + 7195, 8325, 8326, -1, 8325, 7195, 7197, -1, + 7197, 8324, 8325, -1, 8324, 7197, 7199, -1, + 7199, 8323, 8324, -1, 8323, 7199, 7201, -1, + 7201, 8274, 8323, -1, 7201, 8275, 8274, -1, + 7201, 7200, 8275, -1, 8275, 7200, 7271, -1, + 8275, 7271, 7270, -1, 7270, 8276, 8275, -1, + 8276, 7270, 7269, -1, 7269, 8278, 8276, -1, + 8278, 7269, 7268, -1, 7268, 8280, 8278, -1, + 7268, 8283, 8280, -1, 8283, 7268, 7267, -1, + 7267, 8272, 8283, -1, 8272, 7267, 7266, -1, + 7266, 8270, 8272, -1, 8270, 7266, 7265, -1, + 8270, 7265, 8398, -1, 8399, 8400, 8401, -1, + 8401, 8402, 8399, -1, 8402, 8401, 8403, -1, + 8403, 8404, 8402, -1, 8404, 8403, 8405, -1, + 8405, 8406, 8404, -1, 8406, 8405, 8407, -1, + 8407, 8408, 8406, -1, 8408, 8407, 8409, -1, + 8409, 8410, 8408, -1, 8410, 8409, 8411, -1, + 8411, 8412, 8410, -1, 8412, 8411, 8413, -1, + 8413, 8414, 8412, -1, 8414, 8413, 8415, -1, + 8415, 8416, 8414, -1, 8416, 8415, 8417, -1, + 8417, 8418, 8416, -1, 8418, 8417, 8419, -1, + 8419, 8420, 8418, -1, 8420, 8419, 8421, -1, + 8421, 8422, 8420, -1, 8422, 8421, 8423, -1, + 8423, 8424, 8422, -1, 8424, 8423, 8425, -1, + 8425, 8426, 8424, -1, 8426, 8425, 8427, -1, + 8427, 8428, 8426, -1, 8428, 8427, 8429, -1, + 8429, 8430, 8428, -1, 8430, 8429, 8431, -1, + 8431, 8432, 8430, -1, 8432, 8431, 8398, -1, + 8432, 8398, 7265, -1, 8432, 7265, 7222, -1, + 7222, 8430, 8432, -1, 8430, 7222, 7221, -1, + 7221, 8428, 8430, -1, 8428, 7221, 7263, -1, + 7263, 8426, 8428, -1, 8426, 7263, 7261, -1, + 7261, 8424, 8426, -1, 8424, 7261, 7259, -1, + 7259, 8422, 8424, -1, 8422, 7259, 7257, -1, + 7257, 8420, 8422, -1, 8420, 7257, 7255, -1, + 7255, 8418, 8420, -1, 8418, 7255, 7253, -1, + 7253, 8416, 8418, -1, 8416, 7253, 7251, -1, + 7251, 8414, 8416, -1, 8414, 7251, 7249, -1, + 7249, 8412, 8414, -1, 8412, 7249, 7247, -1, + 7247, 8410, 8412, -1, 8410, 7247, 7245, -1, + 7245, 8408, 8410, -1, 8408, 7245, 7243, -1, + 7243, 8406, 8408, -1, 8406, 7243, 7241, -1, + 7241, 8404, 8406, -1, 8404, 7241, 7239, -1, + 7239, 8402, 8404, -1, 8402, 7239, 7237, -1, + 7237, 8399, 8402, -1, 8399, 7237, 7235, -1, + 7235, 8400, 8399, -1, 8400, 7235, 7233, -1, + 7233, 8433, 8400, -1, 8433, 7233, 7231, -1, + 7231, 8434, 8433, -1, 8434, 7231, 7229, -1, + 7229, 8435, 8434, -1, 8435, 7229, 7227, -1, + 7227, 8436, 8435, -1, 8436, 7227, 7225, -1, + 7225, 8437, 8436, -1, 8437, 7225, 7224, -1, + 7224, 8438, 8437, -1, 8438, 7224, 7454, -1, + 7454, 8439, 8438, -1, 8439, 7454, 7455, -1, + 7455, 8440, 8439, -1, 8440, 7455, 7456, -1, + 7456, 8441, 8440, -1, 8441, 7456, 7457, -1, + 7457, 8442, 8441, -1, 8442, 7457, 7458, -1, + 7458, 8443, 8442, -1, 8443, 7458, 7459, -1, + 7459, 8444, 8443, -1, 8444, 7459, 7460, -1, + 7460, 8445, 8444, -1, 8445, 7460, 7461, -1, + 7461, 8446, 8445, -1, 8446, 7461, 3, -1, + 3, 1, 8446, -1, 8447, 8448, 8449, -1, + 8449, 8450, 8447, -1, 8450, 8449, 8451, -1, + 8451, 8452, 8450, -1, 8452, 8451, 8453, -1, + 8453, 8454, 8452, -1, 8454, 8453, 8455, -1, + 8455, 8456, 8454, -1, 8456, 8455, 8457, -1, + 8457, 8458, 8456, -1, 8459, 8456, 8458, -1, + 8458, 8460, 8459, -1, 8460, 8458, 8461, -1, + 8461, 8462, 8460, -1, 8462, 8461, 8463, -1, + 8463, 8464, 8462, -1, 8464, 8463, 8465, -1, + 8465, 8466, 8464, -1, 8466, 8465, 8467, -1, + 8467, 8468, 8466, -1, 8468, 8467, 8469, -1, + 8469, 8470, 8468, -1, 8470, 8469, 8471, -1, + 8471, 8472, 8470, -1, 8472, 8471, 8473, -1, + 8473, 8474, 8472, -1, 8474, 8473, 8475, -1, + 8475, 8476, 8474, -1, 8476, 8475, 8477, -1, + 8477, 8478, 8476, -1, 8479, 8480, 8481, -1, + 8479, 8481, 8478, -1, 8478, 8477, 8479, -1, + 1, 8482, 8479, -1, 1, 8479, 8477, -1, + 8477, 8446, 1, -1, 8446, 8477, 8475, -1, + 8475, 8445, 8446, -1, 8445, 8475, 8473, -1, + 8473, 8444, 8445, -1, 8444, 8473, 8471, -1, + 8471, 8443, 8444, -1, 8443, 8471, 8469, -1, + 8469, 8442, 8443, -1, 8442, 8469, 8467, -1, + 8467, 8441, 8442, -1, 8441, 8467, 8465, -1, + 8465, 8440, 8441, -1, 8440, 8465, 8463, -1, + 8463, 8439, 8440, -1, 8439, 8463, 8461, -1, + 8461, 8438, 8439, -1, 8438, 8461, 8458, -1, + 8458, 8437, 8438, -1, 8437, 8458, 8457, -1, + 8457, 8436, 8437, -1, 8436, 8457, 8455, -1, + 8455, 8435, 8436, -1, 8435, 8455, 8453, -1, + 8453, 8434, 8435, -1, 8434, 8453, 8451, -1, + 8451, 8433, 8434, -1, 8433, 8451, 8449, -1, + 8449, 8400, 8433, -1, 8400, 8449, 8448, -1, + 8448, 8401, 8400, -1, 8401, 8448, 8483, -1, + 8483, 8403, 8401, -1, 8403, 8483, 8484, -1, + 8484, 8405, 8403, -1, 8405, 8484, 8485, -1, + 8485, 8407, 8405, -1, 8407, 8485, 8486, -1, + 8486, 8409, 8407, -1, 8409, 8486, 8487, -1, + 8487, 8411, 8409, -1, 8411, 8487, 8488, -1, + 8488, 8413, 8411, -1, 8413, 8488, 8489, -1, + 8489, 8415, 8413, -1, 8415, 8489, 8490, -1, + 8490, 8417, 8415, -1, 8417, 8490, 8491, -1, + 8491, 8419, 8417, -1, 8419, 8491, 8492, -1, + 8492, 8421, 8419, -1, 8421, 8492, 8493, -1, + 8493, 8423, 8421, -1, 8423, 8493, 8494, -1, + 8494, 8425, 8423, -1, 8425, 8494, 8495, -1, + 8495, 8427, 8425, -1, 8427, 8495, 8496, -1, + 8496, 8429, 8427, -1, 8429, 8496, 8497, -1, + 8497, 8431, 8429, -1, 8431, 8497, 8498, -1, + 8498, 8398, 8431, -1, 8398, 8498, 8499, -1, + 8499, 8270, 8398, -1, 8499, 8271, 8270, -1, + 8499, 8500, 8271, -1, 8500, 8499, 8498, -1, + 8498, 8501, 8500, -1, 8501, 8498, 8497, -1, + 8497, 8502, 8501, -1, 8502, 8497, 8496, -1, + 8496, 8503, 8502, -1, 8503, 8496, 8495, -1, + 8495, 8504, 8503, -1, 8504, 8495, 8494, -1, + 8494, 8505, 8504, -1, 8505, 8494, 8493, -1, + 8493, 8506, 8505, -1, 8506, 8493, 8492, -1, + 8492, 8507, 8506, -1, 8507, 8492, 8491, -1, + 8491, 8508, 8507, -1, 8508, 8491, 8490, -1, + 8490, 8509, 8508, -1, 8509, 8490, 8489, -1, + 8489, 8510, 8509, -1, 8510, 8489, 8488, -1, + 8488, 8511, 8510, -1, 8511, 8488, 8487, -1, + 8487, 8512, 8511, -1, 8512, 8487, 8486, -1, + 8486, 8513, 8512, -1, 8513, 8486, 8485, -1, + 8485, 8514, 8513, -1, 8514, 8485, 8484, -1, + 8484, 8515, 8514, -1, 8515, 8484, 8483, -1, + 8483, 8516, 8515, -1, 8516, 8483, 8448, -1, + 8448, 8447, 8516, -1, 8516, 8447, 8517, -1, + 8517, 8515, 8516, -1, 8515, 8517, 8518, -1, + 8518, 8514, 8515, -1, 8514, 8518, 8519, -1, + 8519, 8513, 8514, -1, 8513, 8519, 8520, -1, + 8520, 8512, 8513, -1, 8512, 8520, 8521, -1, + 8521, 8511, 8512, -1, 8511, 8521, 8522, -1, + 8522, 8510, 8511, -1, 8510, 8522, 8523, -1, + 8523, 8509, 8510, -1, 8509, 8523, 8524, -1, + 8524, 8508, 8509, -1, 8508, 8524, 8525, -1, + 8525, 8507, 8508, -1, 8507, 8525, 8526, -1, + 8526, 8506, 8507, -1, 8506, 8526, 8527, -1, + 8527, 8505, 8506, -1, 8505, 8527, 8528, -1, + 8528, 8504, 8505, -1, 8504, 8528, 8529, -1, + 8529, 8503, 8504, -1, 8503, 8529, 8530, -1, + 8530, 8502, 8503, -1, 8502, 8530, 8531, -1, + 8531, 8501, 8502, -1, 8501, 8531, 8532, -1, + 8532, 8500, 8501, -1, 8500, 8532, 8533, -1, + 8533, 8271, 8500, -1, 8271, 8533, 8534, -1, + 8534, 8269, 8271, -1, 8534, 8285, 8269, -1, + 8534, 8535, 8285, -1, 8535, 8534, 8533, -1, + 8533, 8536, 8535, -1, 8536, 8533, 8532, -1, + 8532, 8537, 8536, -1, 8537, 8532, 8531, -1, + 8531, 8538, 8537, -1, 8538, 8531, 8530, -1, + 8530, 8539, 8538, -1, 8539, 8530, 8529, -1, + 8529, 8540, 8539, -1, 8540, 8529, 8528, -1, + 8528, 8541, 8540, -1, 8541, 8528, 8527, -1, + 8527, 8542, 8541, -1, 8542, 8527, 8526, -1, + 8526, 8543, 8542, -1, 8543, 8526, 8525, -1, + 8525, 8544, 8543, -1, 8544, 8525, 8524, -1, + 8524, 8545, 8544, -1, 8545, 8524, 8523, -1, + 8523, 8546, 8545, -1, 8546, 8523, 8522, -1, + 8522, 8547, 8546, -1, 8547, 8522, 8521, -1, + 8521, 8548, 8547, -1, 8548, 8521, 8520, -1, + 8520, 8549, 8548, -1, 8549, 8520, 8519, -1, + 8519, 8550, 8549, -1, 8550, 8519, 8518, -1, + 8518, 8551, 8550, -1, 8551, 8518, 8517, -1, + 8517, 8552, 8551, -1, 8552, 8517, 8447, -1, + 8447, 8553, 8552, -1, 8553, 8447, 8450, -1, + 8450, 8554, 8553, -1, 8554, 8450, 8452, -1, + 8452, 8555, 8554, -1, 8555, 8452, 8454, -1, + 8454, 8556, 8555, -1, 8556, 8454, 8456, -1, + 8456, 8459, 8556, -1, 8556, 8459, 8557, -1, + 8557, 8555, 8556, -1, 8555, 8557, 8558, -1, + 8558, 8554, 8555, -1, 8554, 8558, 8559, -1, + 8559, 8553, 8554, -1, 8553, 8559, 8560, -1, + 8560, 8552, 8553, -1, 8552, 8560, 8561, -1, + 8561, 8551, 8552, -1, 8551, 8561, 8562, -1, + 8562, 8550, 8551, -1, 8550, 8562, 8563, -1, + 8563, 8549, 8550, -1, 8549, 8563, 8564, -1, + 8564, 8548, 8549, -1, 8548, 8564, 8565, -1, + 8565, 8547, 8548, -1, 8547, 8565, 8566, -1, + 8566, 8546, 8547, -1, 8546, 8566, 8567, -1, + 8567, 8545, 8546, -1, 8545, 8567, 8568, -1, + 8568, 8544, 8545, -1, 8544, 8568, 8569, -1, + 8569, 8543, 8544, -1, 8543, 8569, 8570, -1, + 8570, 8542, 8543, -1, 8542, 8570, 8571, -1, + 8571, 8541, 8542, -1, 8541, 8571, 8572, -1, + 8572, 8540, 8541, -1, 8540, 8572, 8573, -1, + 8573, 8539, 8540, -1, 8539, 8573, 8574, -1, + 8574, 8538, 8539, -1, 8538, 8574, 8575, -1, + 8575, 8537, 8538, -1, 8537, 8575, 8576, -1, + 8576, 8536, 8537, -1, 8536, 8576, 8577, -1, + 8577, 8535, 8536, -1, 8535, 8577, 8578, -1, + 8578, 8285, 8535, -1, 8285, 8578, 8579, -1, + 8579, 8268, 8285, -1, 8579, 8267, 8268, -1, + 8579, 8266, 8267, -1, 8266, 8579, 8578, -1, + 8578, 8265, 8266, -1, 8265, 8578, 8577, -1, + 8577, 8264, 8265, -1, 8264, 8577, 8576, -1, + 8576, 8263, 8264, -1, 8263, 8576, 8575, -1, + 8575, 8262, 8263, -1, 8262, 8575, 8574, -1, + 8574, 8261, 8262, -1, 8261, 8574, 8573, -1, + 8573, 8260, 8261, -1, 8260, 8573, 8572, -1, + 8572, 8259, 8260, -1, 8259, 8572, 8571, -1, + 8571, 8258, 8259, -1, 8258, 8571, 8570, -1, + 8570, 8257, 8258, -1, 8257, 8570, 8569, -1, + 8569, 8256, 8257, -1, 8256, 8569, 8568, -1, + 8568, 8255, 8256, -1, 8255, 8568, 8567, -1, + 8567, 8254, 8255, -1, 8254, 8567, 8566, -1, + 8566, 8253, 8254, -1, 8253, 8566, 8565, -1, + 8565, 8252, 8253, -1, 8252, 8565, 8564, -1, + 8564, 8251, 8252, -1, 8251, 8564, 8563, -1, + 8563, 8250, 8251, -1, 8250, 8563, 8562, -1, + 8562, 8249, 8250, -1, 8249, 8562, 8561, -1, + 8561, 8248, 8249, -1, 8248, 8561, 8560, -1, + 8560, 8247, 8248, -1, 8247, 8560, 8559, -1, + 8559, 8246, 8247, -1, 8246, 8559, 8558, -1, + 8558, 8245, 8246, -1, 8245, 8558, 8557, -1, + 8557, 8244, 8245, -1, 8244, 8557, 8459, -1, + 8459, 8243, 8244, -1, 8243, 8459, 8460, -1, + 8460, 8242, 8243, -1, 8242, 8460, 8462, -1, + 8462, 8241, 8242, -1, 8241, 8462, 8464, -1, + 8464, 8240, 8241, -1, 8240, 8464, 8466, -1, + 8466, 8239, 8240, -1, 8239, 8466, 8468, -1, + 8468, 8238, 8239, -1, 8238, 8468, 8470, -1, + 8470, 8237, 8238, -1, 8237, 8470, 8472, -1, + 8472, 8236, 8237, -1, 8236, 8472, 8474, -1, + 8474, 8235, 8236, -1, 8235, 8474, 8476, -1, + 8476, 8234, 8235, -1, 8234, 8476, 8478, -1, + 8478, 8233, 8234, -1, 8233, 8478, 8481, -1, + 8481, 8232, 8233, -1, 8481, 8231, 8232, -1, + 8231, 8481, 8580, -1, 8580, 8229, 8231, -1, + 8580, 8581, 8229, -1, 8581, 8580, 8481, -1, + 8581, 8481, 8480, -1, 8480, 8229, 8581, -1, + 8480, 8230, 8229, -1, 8230, 8480, 8479, -1, + 8230, 8479, 8482, -1, 8482, 8227, 8230, -1, + 8582, 8227, 8482, -1, 8582, 8482, 1, -1, + 8582, 1, 0, -1, 0, 8227, 8582, -1, + 0, 2, 8227, -1, 2, 8228, 8227, -1, + 8228, 2, 3, -1, 8228, 3, 7463, -1, + 7463, 8170, 8228, -1, 8583, 8170, 7463, -1, + 8583, 7463, 7462, -1, 8583, 7462, 7465, -1, + 7465, 8170, 8583, -1, 7465, 7464, 8170, -1, + 7464, 8171, 8170, -1, 8171, 7464, 7466, -1, + 7466, 7467, 8171, -1, 8584, 8171, 7467, -1, + 8584, 8172, 8171, -1, 8584, 8585, 8172, -1, + 8585, 8584, 7467, -1, 8585, 7467, 7476, -1, + 7476, 8172, 8585, -1, 7476, 7477, 8172, -1, + 7477, 7478, 8172, -1, 7478, 8586, 8172, -1, + 8586, 7478, 7479, -1, 8586, 7479, 7481, -1, + 8586, 7481, 8057, -1, 8057, 8172, 8586, -1, + 3693, 4406, 3694, -1, 3694, 4406, 4233, -1, + 4655, 4656, 8587, -1, 8587, 4656, 4658, -1, + 2080, 8588, 2081, -1, 2081, 8588, 6167, -1, + 6167, 8588, 6163, -1, 6163, 8588, 2080, -1, + 6604, 6638, 6679, -1, 6679, 6638, 6681, -1, + 6604, 6679, 6639, -1, 6639, 6679, 6678, -1, + 798, 7160, 7156, -1, 7156, 7160, 676, -1, + 676, 7160, 7155, -1, 7155, 7160, 2372, -1, + 7155, 2372, 7164, -1, 7164, 2372, 658, -1, + 658, 2372, 7655, -1, 7655, 2372, 2374, -1, + 7655, 2374, 2519, -1, 2519, 6163, 7655, -1, + 7655, 6163, 6162, -1, 7655, 6162, 6158, -1, + 6158, 6156, 7655, -1, 7655, 6156, 7660, -1, + 7655, 7660, 382, -1, 382, 7660, 131, -1, + 131, 7660, 243, -1, 243, 7660, 246, -1, + 246, 7660, 244, -1, 244, 7660, 253, -1, + 253, 7660, 6658, -1, 6658, 7660, 7752, -1, + 7752, 7660, 6515, -1, 6515, 7660, 7722, -1, + 7722, 7660, 6753, -1, 6753, 7660, 7664, -1, + 7664, 7660, 7662, -1, 7662, 7660, 7668, -1, + 7668, 7660, 7703, -1, 7703, 7660, 7714, -1, + 7703, 7714, 7695, -1, 7695, 7714, 7694, -1, + 7694, 7714, 6786, -1, 6786, 7714, 6414, -1, + 6786, 6414, 6790, -1, 6786, 6790, 6705, -1, + 6705, 6790, 6548, -1, 6548, 6790, 6547, -1, + 6547, 6790, 6452, -1, 6452, 6790, 6450, -1, + 6450, 6790, 257, -1, 257, 6790, 6800, -1, + 6800, 6790, 6803, -1, 6790, 6805, 6803, -1, + 6803, 6805, 2193, -1, 6803, 2193, 2194, -1, + 2194, 6810, 6803, -1, 6803, 6810, 8168, -1, + 6803, 8168, 9, -1, 9, 8168, 7, -1, + 7, 8168, 8057, -1, 8057, 8168, 8172, -1, + 8172, 8168, 8170, -1, 8170, 8168, 8173, -1, + 8170, 8173, 5, -1, 8170, 5, 8227, -1, + 8227, 5, 8229, -1, 8229, 5, 6940, -1, + 6940, 5, 8182, -1, 4655, 8587, 5595, -1, + 5595, 8587, 4658, -1, 2766, 6156, 6157, -1, + 6157, 6156, 2762, -1, 6550, 6546, 6543, -1, + 6543, 6546, 6545, -1, 6153, 8589, 7660, -1, + 7660, 8589, 2543, -1, 6153, 2545, 8589, -1, + 8589, 2545, 2543, -1, 8590, 8591, 2652, -1, + 2652, 8591, 2637, -1, 8591, 8592, 2637, -1, + 2637, 8592, 2947, -1, 8592, 8593, 2947, -1, + 2947, 8593, 2635, -1, 8593, 8594, 2635, -1, + 2635, 8594, 4072, -1, 8594, 8595, 4072, -1, + 4072, 8595, 4076, -1, 8595, 8596, 4076, -1, + 4076, 8596, 4104, -1, 4104, 8596, 6129, -1, + 6129, 8596, 8597, -1, 6129, 8597, 3679, -1, + 3679, 8597, 8598, -1, 3679, 8598, 6124, -1, + 6124, 8598, 8599, -1, 6124, 8599, 4531, -1, + 4531, 8599, 8600, -1, 4531, 8600, 6119, -1, + 6119, 8600, 8601, -1, 6119, 8601, 3090, -1, + 3090, 8601, 8602, -1, 3090, 8602, 5535, -1, + 5535, 8602, 8603, -1, 5535, 8603, 4643, -1, + 4643, 8603, 8604, -1, 4643, 8604, 4650, -1, + 4650, 8604, 8605, -1, 4650, 8605, 4648, -1, + 4648, 8605, 8606, -1, 4648, 8606, 4656, -1, + 4656, 8606, 8607, -1, 4656, 8607, 4662, -1, + 4662, 8607, 8608, -1, 4662, 8608, 4664, -1, + 4664, 8608, 4667, -1, 8608, 8609, 4667, -1, + 4667, 8609, 4672, -1, 8609, 8610, 4672, -1, + 4672, 8610, 4678, -1, 8610, 8611, 4678, -1, + 4678, 8611, 4687, -1, 8611, 8612, 4687, -1, + 4687, 8612, 4701, -1, 8612, 8613, 4701, -1, + 4701, 8613, 4702, -1, 8613, 8614, 4702, -1, + 4702, 8614, 5290, -1, 8614, 8615, 5290, -1, + 5290, 8615, 5287, -1, 8615, 8616, 5287, -1, + 5287, 8616, 4971, -1, 8616, 8617, 4971, -1, + 4971, 8617, 4967, -1, 8617, 8618, 4967, -1, + 4967, 8618, 4920, -1, 8618, 8619, 4920, -1, + 4920, 8619, 4921, -1, 4921, 8619, 4883, -1, + 4883, 8619, 8620, -1, 4883, 8620, 4879, -1, + 4879, 8620, 8621, -1, 4879, 8621, 4838, -1, + 4838, 8621, 8622, -1, 4838, 8622, 4708, -1, + 4708, 8622, 8623, -1, 4708, 8623, 4711, -1, + 4711, 8623, 8624, -1, 4711, 8624, 4833, -1, + 4833, 8624, 8625, -1, 4833, 8625, 4750, -1, + 4750, 8625, 8626, -1, 4750, 8626, 4793, -1, + 4793, 8626, 8627, -1, 4793, 8627, 4792, -1, + 4792, 8627, 8628, -1, 4792, 8628, 4776, -1, + 4776, 8628, 8629, -1, 4776, 8629, 4718, -1, + 4718, 8629, 8630, -1, 4718, 8630, 4594, -1, + 4594, 8630, 2957, -1, 8630, 8631, 2957, -1, + 2957, 8631, 4549, -1, 8631, 8632, 4549, -1, + 4549, 8632, 4547, -1, 8632, 8633, 4547, -1, + 4547, 8633, 4408, -1, 8633, 8634, 4408, -1, + 4408, 8634, 4404, -1, 8634, 8635, 4404, -1, + 4404, 8635, 4222, -1, 8635, 8636, 4222, -1, + 4222, 8636, 4220, -1, 8636, 8637, 4220, -1, + 4220, 8637, 4223, -1, 8637, 8638, 4223, -1, + 4223, 8638, 4227, -1, 8638, 8639, 4227, -1, + 4227, 8639, 4225, -1, 8639, 8640, 4225, -1, + 4225, 8640, 4228, -1, 8640, 8641, 4228, -1, + 4228, 8641, 1531, -1, 1531, 8641, 6197, -1, + 6197, 8641, 8642, -1, 6197, 8642, 1720, -1, + 1720, 8642, 8643, -1, 1720, 8643, 6192, -1, + 6192, 8643, 8644, -1, 6192, 8644, 6190, -1, + 6190, 8644, 8645, -1, 6190, 8645, 1169, -1, + 1169, 8645, 8590, -1, 1169, 8590, 2652, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5712, 5712, 5712, -1, 5713, 5713, 5713, -1, + 5714, 5714, 5714, -1, 5715, 5715, 5715, -1, + 5716, 5716, 5716, -1, 5717, 5717, 5717, -1, + 5718, 5718, 5718, -1, 5719, 5719, 5719, -1, + 5720, 5720, 5720, -1, 5721, 5721, 5721, -1, + 5722, 5722, 5722, -1, 5723, 5723, 5723, -1, + 5724, 5724, 5724, -1, 5725, 5725, 5725, -1, + 5726, 5726, 5726, -1, 5727, 5727, 5727, -1, + 5728, 5728, 5728, -1, 5729, 5729, 5729, -1, + 5730, 5730, 5730, -1, 5731, 5731, 5731, -1, + 5732, 5732, 5732, -1, 5733, 5733, 5733, -1, + 5734, 5734, 5734, -1, 5735, 5735, 5735, -1, + 5736, 5736, 5736, -1, 5737, 5737, 5737, -1, + 5738, 5738, 5738, -1, 5739, 5739, 5739, -1, + 5740, 5740, 5740, -1, 5741, 5741, 5741, -1, + 5742, 5742, 5742, -1, 5743, 5743, 5743, -1, + 5744, 5744, 5744, -1, 5745, 5745, 5745, -1, + 5746, 5746, 5746, -1, 5747, 5747, 5747, -1, + 5748, 5748, 5748, -1, 5749, 5749, 5749, -1, + 5750, 5750, 5750, -1, 5751, 5751, 5751, -1, + 5752, 5752, 5752, -1, 5753, 5753, 5753, -1, + 5754, 5754, 5754, -1, 5755, 5755, 5755, -1, + 5756, 5756, 5756, -1, 5757, 5757, 5757, -1, + 5758, 5758, 5758, -1, 5759, 5759, 5759, -1, + 5760, 5760, 5760, -1, 5761, 5761, 5761, -1, + 5762, 5762, 5762, -1, 5763, 5763, 5763, -1, + 5764, 5764, 5764, -1, 5765, 5765, 5765, -1, + 5766, 5766, 5766, -1, 5767, 5767, 5767, -1, + 5768, 5768, 5768, -1, 5769, 5769, 5769, -1, + 5770, 5770, 5770, -1, 5771, 5771, 5771, -1, + 5772, 5772, 5772, -1, 5773, 5773, 5773, -1, + 5774, 5774, 5774, -1, 5775, 5775, 5775, -1, + 5776, 5776, 5776, -1, 5777, 5777, 5777, -1, + 5778, 5778, 5778, -1, 5779, 5779, 5779, -1, + 5780, 5780, 5780, -1, 5781, 5781, 5781, -1, + 5782, 5782, 5782, -1, 5783, 5783, 5783, -1, + 5784, 5784, 5784, -1, 5785, 5785, 5785, -1, + 5786, 5786, 5786, -1, 5787, 5787, 5787, -1, + 5788, 5788, 5788, -1, 5789, 5789, 5789, -1, + 5790, 5790, 5790, -1, 5791, 5791, 5791, -1, + 5792, 5792, 5792, -1, 5793, 5793, 5793, -1, + 5794, 5794, 5794, -1, 5795, 5795, 5795, -1, + 5796, 5796, 5796, -1, 5797, 5797, 5797, -1, + 5798, 5798, 5798, -1, 5799, 5799, 5799, -1, + 5800, 5800, 5800, -1, 5801, 5801, 5801, -1, + 5802, 5802, 5802, -1, 5803, 5803, 5803, -1, + 5804, 5804, 5804, -1, 5805, 5805, 5805, -1, + 5806, 5806, 5806, -1, 5807, 5807, 5807, -1, + 5808, 5808, 5808, -1, 5809, 5809, 5809, -1, + 5810, 5810, 5810, -1, 5811, 5811, 5811, -1, + 5812, 5812, 5812, -1, 5813, 5813, 5813, -1, + 5814, 5814, 5814, -1, 5815, 5815, 5815, -1, + 5816, 5816, 5816, -1, 5817, 5817, 5817, -1, + 5818, 5818, 5818, -1, 5819, 5819, 5819, -1, + 5820, 5820, 5820, -1, 5821, 5821, 5821, -1, + 5822, 5822, 5822, -1, 5823, 5823, 5823, -1, + 5824, 5824, 5824, -1, 5825, 5825, 5825, -1, + 5826, 5826, 5826, -1, 5827, 5827, 5827, -1, + 5828, 5828, 5828, -1, 5829, 5829, 5829, -1, + 5830, 5830, 5830, -1, 5831, 5831, 5831, -1, + 5832, 5832, 5832, -1, 5833, 5833, 5833, -1, + 5834, 5834, 5834, -1, 5835, 5835, 5835, -1, + 5836, 5836, 5836, -1, 5837, 5837, 5837, -1, + 5838, 5838, 5838, -1, 5839, 5839, 5839, -1, + 5840, 5840, 5840, -1, 5841, 5841, 5841, -1, + 5842, 5842, 5842, -1, 5843, 5843, 5843, -1, + 5844, 5844, 5844, -1, 5845, 5845, 5845, -1, + 5846, 5846, 5846, -1, 5847, 5847, 5847, -1, + 5848, 5848, 5848, -1, 5849, 5849, 5849, -1, + 5850, 5850, 5850, -1, 5851, 5851, 5851, -1, + 5852, 5852, 5852, -1, 5853, 5853, 5853, -1, + 5854, 5854, 5854, -1, 5855, 5855, 5855, -1, + 5856, 5856, 5856, -1, 5857, 5857, 5857, -1, + 5858, 5858, 5858, -1, 5859, 5859, 5859, -1, + 5860, 5860, 5860, -1, 5861, 5861, 5861, -1, + 5862, 5862, 5862, -1, 5863, 5863, 5863, -1, + 5864, 5864, 5864, -1, 5865, 5865, 5865, -1, + 5866, 5866, 5866, -1, 5867, 5867, 5867, -1, + 5868, 5868, 5868, -1, 5869, 5869, 5869, -1, + 5870, 5870, 5870, -1, 5871, 5871, 5871, -1, + 5872, 5872, 5872, -1, 5873, 5873, 5873, -1, + 5874, 5874, 5874, -1, 5875, 5875, 5875, -1, + 5876, 5876, 5876, -1, 5877, 5877, 5877, -1, + 5878, 5878, 5878, -1, 5879, 5879, 5879, -1, + 5880, 5880, 5880, -1, 5881, 5881, 5881, -1, + 5882, 5882, 5882, -1, 5883, 5883, 5883, -1, + 5884, 5884, 5884, -1, 5885, 5885, 5885, -1, + 5886, 5886, 5886, -1, 5887, 5887, 5887, -1, + 5888, 5888, 5888, -1, 5889, 5889, 5889, -1, + 5890, 5890, 5890, -1, 5891, 5891, 5891, -1, + 5892, 5892, 5892, -1, 5893, 5893, 5893, -1, + 5894, 5894, 5894, -1, 5895, 5895, 5895, -1, + 5896, 5896, 5896, -1, 5897, 5897, 5897, -1, + 5898, 5898, 5898, -1, 5899, 5899, 5899, -1, + 5900, 5900, 5900, -1, 5901, 5901, 5901, -1, + 5902, 5902, 5902, -1, 5903, 5903, 5903, -1, + 5904, 5904, 5904, -1, 5905, 5905, 5905, -1, + 5906, 5906, 5906, -1, 5907, 5907, 5907, -1, + 5908, 5908, 5908, -1, 5909, 5909, 5909, -1, + 5910, 5910, 5910, -1, 5911, 5911, 5911, -1, + 5912, 5912, 5912, -1, 5913, 5913, 5913, -1, + 5914, 5914, 5914, -1, 5915, 5915, 5915, -1, + 5916, 5916, 5916, -1, 5917, 5917, 5917, -1, + 5918, 5918, 5918, -1, 5919, 5919, 5919, -1, + 5920, 5920, 5920, -1, 5921, 5921, 5921, -1, + 5922, 5922, 5922, -1, 5923, 5923, 5923, -1, + 5924, 5924, 5924, -1, 5925, 5925, 5925, -1, + 5926, 5926, 5926, -1, 5927, 5927, 5927, -1, + 5928, 5928, 5928, -1, 5929, 5929, 5929, -1, + 5930, 5930, 5930, -1, 5931, 5931, 5931, -1, + 5932, 5932, 5932, -1, 5933, 5933, 5933, -1, + 5934, 5934, 5934, -1, 5935, 5935, 5935, -1, + 5936, 5936, 5936, -1, 5937, 5937, 5937, -1, + 5938, 5938, 5938, -1, 5939, 5939, 5939, -1, + 5940, 5940, 5940, -1, 5941, 5941, 5941, -1, + 5942, 5942, 5942, -1, 5943, 5943, 5943, -1, + 5944, 5944, 5944, -1, 5945, 5945, 5945, -1, + 5946, 5946, 5946, -1, 5947, 5947, 5947, -1, + 5948, 5948, 5948, -1, 5949, 5949, 5949, -1, + 5950, 5950, 5950, -1, 5951, 5951, 5951, -1, + 5952, 5952, 5952, -1, 5953, 5953, 5953, -1, + 5954, 5954, 5954, -1, 5955, 5955, 5955, -1, + 5956, 5956, 5956, -1, 5957, 5957, 5957, -1, + 5958, 5958, 5958, -1, 5959, 5959, 5959, -1, + 5960, 5960, 5960, -1, 5961, 5961, 5961, -1, + 5962, 5962, 5962, -1, 5963, 5963, 5963, -1, + 5964, 5964, 5964, -1, 5965, 5965, 5965, -1, + 5966, 5966, 5966, -1, 5967, 5967, 5967, -1, + 5968, 5968, 5968, -1, 5969, 5969, 5969, -1, + 5970, 5970, 5970, -1, 5971, 5971, 5971, -1, + 5972, 5972, 5972, -1, 5973, 5973, 5973, -1, + 5974, 5974, 5974, -1, 5975, 5975, 5975, -1, + 5976, 5976, 5976, -1, 5977, 5977, 5977, -1, + 5978, 5978, 5978, -1, 5979, 5979, 5979, -1, + 5980, 5980, 5980, -1, 5981, 5981, 5981, -1, + 5982, 5982, 5982, -1, 5983, 5983, 5983, -1, + 5984, 5984, 5984, -1, 5985, 5985, 5985, -1, + 5986, 5986, 5986, -1, 5987, 5987, 5987, -1, + 5988, 5988, 5988, -1, 5989, 5989, 5989, -1, + 5990, 5990, 5990, -1, 5991, 5991, 5991, -1, + 5992, 5992, 5992, -1, 5993, 5993, 5993, -1, + 5994, 5994, 5994, -1, 5995, 5995, 5995, -1, + 5996, 5996, 5996, -1, 5997, 5997, 5997, -1, + 5998, 5998, 5998, -1, 5999, 5999, 5999, -1, + 6000, 6000, 6000, -1, 6001, 6001, 6001, -1, + 6002, 6002, 6002, -1, 6003, 6003, 6003, -1, + 6004, 6004, 6004, -1, 6005, 6005, 6005, -1, + 6006, 6006, 6006, -1, 6007, 6007, 6007, -1, + 6008, 6008, 6008, -1, 6009, 6009, 6009, -1, + 6010, 6010, 6010, -1, 6011, 6011, 6011, -1, + 6012, 6012, 6012, -1, 6013, 6013, 6013, -1, + 6014, 6014, 6014, -1, 6015, 6015, 6015, -1, + 6016, 6016, 6016, -1, 6017, 6017, 6017, -1, + 6018, 6018, 6018, -1, 6019, 6019, 6019, -1, + 6020, 6020, 6020, -1, 6021, 6021, 6021, -1, + 6022, 6022, 6022, -1, 6023, 6023, 6023, -1, + 6024, 6024, 6024, -1, 6025, 6025, 6025, -1, + 6026, 6026, 6026, -1, 6027, 6027, 6027, -1, + 6028, 6028, 6028, -1, 6029, 6029, 6029, -1, + 6030, 6030, 6030, -1, 6031, 6031, 6031, -1, + 6032, 6032, 6032, -1, 6033, 6033, 6033, -1, + 6034, 6034, 6034, -1, 6035, 6035, 6035, -1, + 6036, 6036, 6036, -1, 6037, 6037, 6037, -1, + 6038, 6038, 6038, -1, 6039, 6039, 6039, -1, + 6040, 6040, 6040, -1, 6041, 6041, 6041, -1, + 6042, 6042, 6042, -1, 6043, 6043, 6043, -1, + 6044, 6044, 6044, -1, 6045, 6045, 6045, -1, + 6046, 6046, 6046, -1, 6047, 6047, 6047, -1, + 6048, 6048, 6048, -1, 6049, 6049, 6049, -1, + 6050, 6050, 6050, -1, 6051, 6051, 6051, -1, + 6052, 6052, 6052, -1, 6053, 6053, 6053, -1, + 6054, 6054, 6054, -1, 6055, 6055, 6055, -1, + 6056, 6056, 6056, -1, 6057, 6057, 6057, -1, + 6058, 6058, 6058, -1, 6059, 6059, 6059, -1, + 6060, 6060, 6060, -1, 6061, 6061, 6061, -1, + 6062, 6062, 6062, -1, 6063, 6063, 6063, -1, + 6064, 6064, 6064, -1, 6065, 6065, 6065, -1, + 6066, 6066, 6066, -1, 6067, 6067, 6067, -1, + 6068, 6068, 6068, -1, 6069, 6069, 6069, -1, + 6070, 6070, 6070, -1, 6071, 6071, 6071, -1, + 6072, 6072, 6072, -1, 6073, 6073, 6073, -1, + 6074, 6074, 6074, -1, 6075, 6075, 6075, -1, + 6076, 6076, 6076, -1, 6077, 6077, 6077, -1, + 6078, 6078, 6078, -1, 6079, 6079, 6079, -1, + 6080, 6080, 6080, -1, 6081, 6081, 6081, -1, + 6082, 6082, 6082, -1, 6083, 6083, 6083, -1, + 6084, 6084, 6084, -1, 6085, 6085, 6085, -1, + 6086, 6086, 6086, -1, 6087, 6087, 6087, -1, + 6088, 6088, 6088, -1, 6089, 6089, 6089, -1, + 6090, 6090, 6090, -1, 6091, 6091, 6091, -1, + 6092, 6092, 6092, -1, 6093, 6093, 6093, -1, + 6094, 6094, 6094, -1, 6095, 6095, 6095, -1, + 6096, 6096, 6096, -1, 6097, 6097, 6097, -1, + 6098, 6098, 6098, -1, 6099, 6099, 6099, -1, + 6100, 6100, 6100, -1, 6101, 6101, 6101, -1, + 6102, 6102, 6102, -1, 6103, 6103, 6103, -1, + 6104, 6104, 6104, -1, 6105, 6105, 6105, -1, + 6106, 6106, 6106, -1, 6107, 6107, 6107, -1, + 6108, 6108, 6108, -1, 6109, 6109, 6109, -1, + 6110, 6110, 6110, -1, 6111, 6111, 6111, -1, + 6112, 6112, 6112, -1, 6113, 6113, 6113, -1, + 6114, 6114, 6114, -1, 6115, 6115, 6115, -1, + 6116, 6116, 6116, -1, 6117, 6117, 6117, -1, + 6118, 6118, 6118, -1, 6119, 6119, 6119, -1, + 6120, 6120, 6120, -1, 6121, 6121, 6121, -1, + 6122, 6122, 6122, -1, 6123, 6123, 6123, -1, + 6124, 6124, 6124, -1, 6125, 6125, 6125, -1, + 6126, 6126, 6126, -1, 6127, 6127, 6127, -1, + 6128, 6128, 6128, -1, 6129, 6129, 6129, -1, + 6130, 6130, 6130, -1, 6131, 6131, 6131, -1, + 6132, 6132, 6132, -1, 6133, 6133, 6133, -1, + 6134, 6134, 6134, -1, 6135, 6135, 6135, -1, + 6136, 6136, 6136, -1, 6137, 6137, 6137, -1, + 6138, 6138, 6138, -1, 6139, 6139, 6139, -1, + 6140, 6140, 6140, -1, 6141, 6141, 6141, -1, + 6142, 6142, 6142, -1, 6143, 6143, 6143, -1, + 6144, 6144, 6144, -1, 6145, 6145, 6145, -1, + 6146, 6146, 6146, -1, 6147, 6147, 6147, -1, + 6148, 6148, 6148, -1, 6149, 6149, 6149, -1, + 6150, 6150, 6150, -1, 6151, 6151, 6151, -1, + 6152, 6152, 6152, -1, 6153, 6153, 6153, -1, + 6154, 6154, 6154, -1, 6155, 6155, 6155, -1, + 6156, 6156, 6156, -1, 6157, 6157, 6157, -1, + 6158, 6158, 6158, -1, 6159, 6159, 6159, -1, + 6160, 6160, 6160, -1, 6161, 6161, 6161, -1, + 6162, 6162, 6162, -1, 6163, 6163, 6163, -1, + 6164, 6164, 6164, -1, 6165, 6165, 6165, -1, + 6166, 6166, 6166, -1, 6167, 6167, 6167, -1, + 6168, 6168, 6168, -1, 6169, 6169, 6169, -1, + 6170, 6170, 6170, -1, 6171, 6171, 6171, -1, + 6172, 6172, 6172, -1, 6173, 6173, 6173, -1, + 6174, 6174, 6174, -1, 6175, 6175, 6175, -1, + 6176, 6176, 6176, -1, 6177, 6177, 6177, -1, + 6178, 6178, 6178, -1, 6179, 6179, 6179, -1, + 6180, 6180, 6180, -1, 6181, 6181, 6181, -1, + 6182, 6182, 6182, -1, 6183, 6183, 6183, -1, + 6184, 6184, 6184, -1, 6185, 6185, 6185, -1, + 6186, 6186, 6186, -1, 6187, 6187, 6187, -1, + 6188, 6188, 6188, -1, 6189, 6189, 6189, -1, + 6190, 6190, 6190, -1, 6191, 6191, 6191, -1, + 6192, 6192, 6192, -1, 6193, 6193, 6193, -1, + 6194, 6194, 6194, -1, 6195, 6195, 6195, -1, + 6196, 6196, 6196, -1, 6197, 6197, 6197, -1, + 6198, 6198, 6198, -1, 6199, 6199, 6199, -1, + 6200, 6200, 6200, -1, 6201, 6201, 6201, -1, + 6202, 6202, 6202, -1, 6203, 6203, 6203, -1, + 6204, 6204, 6204, -1, 6205, 6205, 6205, -1, + 6206, 6206, 6206, -1, 6207, 6207, 6207, -1, + 6208, 6208, 6208, -1, 6209, 6209, 6209, -1, + 6210, 6210, 6210, -1, 6211, 6211, 6211, -1, + 6212, 6212, 6212, -1, 6213, 6213, 6213, -1, + 6214, 6214, 6214, -1, 6215, 6215, 6215, -1, + 6216, 6216, 6216, -1, 6217, 6217, 6217, -1, + 6218, 6218, 6218, -1, 6219, 6219, 6219, -1, + 6220, 6220, 6220, -1, 6221, 6221, 6221, -1, + 6222, 6222, 6222, -1, 6223, 6223, 6223, -1, + 6224, 6224, 6224, -1, 6225, 6225, 6225, -1, + 6226, 6226, 6226, -1, 6227, 6227, 6227, -1, + 6228, 6228, 6228, -1, 6229, 6229, 6229, -1, + 6230, 6230, 6230, -1, 6231, 6231, 6231, -1, + 6232, 6232, 6232, -1, 6233, 6233, 6233, -1, + 6234, 6234, 6234, -1, 6235, 6235, 6235, -1, + 6236, 6236, 6236, -1, 6237, 6237, 6237, -1, + 6238, 6238, 6238, -1, 6239, 6239, 6239, -1, + 6240, 6240, 6240, -1, 6241, 6241, 6241, -1, + 6242, 6242, 6242, -1, 6243, 6243, 6243, -1, + 6244, 6244, 6244, -1, 6245, 6245, 6245, -1, + 6246, 6246, 6246, -1, 6247, 6247, 6247, -1, + 6248, 6248, 6248, -1, 6249, 6249, 6249, -1, + 6250, 6250, 6250, -1, 6251, 6251, 6251, -1, + 6252, 6252, 6252, -1, 6253, 6253, 6253, -1, + 6254, 6254, 6254, -1, 6255, 6255, 6255, -1, + 6256, 6256, 6256, -1, 6257, 6257, 6257, -1, + 6258, 6258, 6258, -1, 6259, 6259, 6259, -1, + 6260, 6260, 6260, -1, 6261, 6261, 6261, -1, + 6262, 6262, 6262, -1, 6263, 6263, 6263, -1, + 6264, 6264, 6264, -1, 6265, 6265, 6265, -1, + 6266, 6266, 6266, -1, 6267, 6267, 6267, -1, + 6268, 6268, 6268, -1, 6269, 6269, 6269, -1, + 6270, 6270, 6270, -1, 6271, 6271, 6271, -1, + 6272, 6272, 6272, -1, 6273, 6273, 6273, -1, + 6274, 6274, 6274, -1, 6275, 6275, 6275, -1, + 6276, 6276, 6276, -1, 6277, 6277, 6277, -1, + 6278, 6278, 6278, -1, 6279, 6279, 6279, -1, + 6280, 6280, 6280, -1, 6281, 6281, 6281, -1, + 6282, 6282, 6282, -1, 6283, 6283, 6283, -1, + 6284, 6284, 6284, -1, 6285, 6285, 6285, -1, + 6286, 6286, 6286, -1, 6287, 6287, 6287, -1, + 6288, 6288, 6288, -1, 6289, 6289, 6289, -1, + 6290, 6290, 6290, -1, 6291, 6291, 6291, -1, + 6292, 6292, 6292, -1, 6293, 6293, 6293, -1, + 6294, 6294, 6294, -1, 6295, 6295, 6295, -1, + 6296, 6296, 6296, -1, 6297, 6297, 6297, -1, + 6298, 6298, 6298, -1, 6299, 6299, 6299, -1, + 6300, 6300, 6300, -1, 6301, 6301, 6301, -1, + 6302, 6302, 6302, -1, 6303, 6303, 6303, -1, + 6304, 6304, 6304, -1, 6305, 6305, 6305, -1, + 6306, 6306, 6306, -1, 6307, 6307, 6307, -1, + 6308, 6308, 6308, -1, 6309, 6309, 6309, -1, + 6310, 6310, 6310, -1, 6311, 6311, 6311, -1, + 6312, 6312, 6312, -1, 6313, 6313, 6313, -1, + 6314, 6314, 6314, -1, 6315, 6315, 6315, -1, + 6316, 6316, 6316, -1, 6317, 6317, 6317, -1, + 6318, 6318, 6318, -1, 6319, 6319, 6319, -1, + 6320, 6320, 6320, -1, 6321, 6321, 6321, -1, + 6322, 6322, 6322, -1, 6323, 6323, 6323, -1, + 6324, 6324, 6324, -1, 6325, 6325, 6325, -1, + 6326, 6326, 6326, -1, 6327, 6327, 6327, -1, + 6328, 6328, 6328, -1, 6329, 6329, 6329, -1, + 6330, 6330, 6330, -1, 6331, 6331, 6331, -1, + 6332, 6332, 6332, -1, 6333, 6333, 6333, -1, + 6334, 6334, 6334, -1, 6335, 6335, 6335, -1, + 6336, 6336, 6336, -1, 6337, 6337, 6337, -1, + 6338, 6338, 6338, -1, 6339, 6339, 6339, -1, + 6340, 6340, 6340, -1, 6341, 6341, 6341, -1, + 6342, 6342, 6342, -1, 6343, 6343, 6343, -1, + 6344, 6344, 6344, -1, 6345, 6345, 6345, -1, + 6346, 6346, 6346, -1, 6347, 6347, 6347, -1, + 6348, 6348, 6348, -1, 6349, 6349, 6349, -1, + 6350, 6350, 6350, -1, 6351, 6351, 6351, -1, + 6352, 6352, 6352, -1, 6353, 6353, 6353, -1, + 6354, 6354, 6354, -1, 6355, 6355, 6355, -1, + 6356, 6356, 6356, -1, 6357, 6357, 6357, -1, + 6358, 6358, 6358, -1, 6359, 6359, 6359, -1, + 6360, 6360, 6360, -1, 6361, 6361, 6361, -1, + 6362, 6362, 6362, -1, 6363, 6363, 6363, -1, + 6364, 6364, 6364, -1, 6365, 6365, 6365, -1, + 6366, 6366, 6366, -1, 6367, 6367, 6367, -1, + 6368, 6368, 6368, -1, 6369, 6369, 6369, -1, + 6370, 6370, 6370, -1, 6371, 6371, 6371, -1, + 6372, 6372, 6372, -1, 6373, 6373, 6373, -1, + 6374, 6374, 6374, -1, 6375, 6375, 6375, -1, + 6376, 6376, 6376, -1, 6377, 6377, 6377, -1, + 6378, 6378, 6378, -1, 6379, 6379, 6379, -1, + 6380, 6380, 6380, -1, 6381, 6381, 6381, -1, + 6382, 6382, 6382, -1, 6383, 6383, 6383, -1, + 6384, 6384, 6384, -1, 6385, 6385, 6385, -1, + 6386, 6386, 6386, -1, 6387, 6387, 6387, -1, + 6388, 6388, 6388, -1, 6389, 6389, 6389, -1, + 6390, 6390, 6390, -1, 6391, 6391, 6391, -1, + 6392, 6392, 6392, -1, 6393, 6393, 6393, -1, + 6394, 6394, 6394, -1, 6395, 6395, 6395, -1, + 6396, 6396, 6396, -1, 6397, 6397, 6397, -1, + 6398, 6398, 6398, -1, 6399, 6399, 6399, -1, + 6400, 6400, 6400, -1, 6401, 6401, 6401, -1, + 6402, 6402, 6402, -1, 6403, 6403, 6403, -1, + 6404, 6404, 6404, -1, 6405, 6405, 6405, -1, + 6406, 6406, 6406, -1, 6407, 6407, 6407, -1, + 6408, 6408, 6408, -1, 6409, 6409, 6409, -1, + 6410, 6410, 6410, -1, 6411, 6411, 6411, -1, + 6412, 6412, 6412, -1, 6413, 6413, 6413, -1, + 6414, 6414, 6414, -1, 6415, 6415, 6415, -1, + 6416, 6416, 6416, -1, 6417, 6417, 6417, -1, + 6418, 6418, 6418, -1, 6419, 6419, 6419, -1, + 6420, 6420, 6420, -1, 6421, 6421, 6421, -1, + 6422, 6422, 6422, -1, 6423, 6423, 6423, -1, + 6424, 6424, 6424, -1, 6425, 6425, 6425, -1, + 6426, 6426, 6426, -1, 6427, 6427, 6427, -1, + 6428, 6428, 6428, -1, 6429, 6429, 6429, -1, + 6430, 6430, 6430, -1, 6431, 6431, 6431, -1, + 6432, 6432, 6432, -1, 6433, 6433, 6433, -1, + 6434, 6434, 6434, -1, 6435, 6435, 6435, -1, + 6436, 6436, 6436, -1, 6437, 6437, 6437, -1, + 6438, 6438, 6438, -1, 6439, 6439, 6439, -1, + 6440, 6440, 6440, -1, 6441, 6441, 6441, -1, + 6442, 6442, 6442, -1, 6443, 6443, 6443, -1, + 6444, 6444, 6444, -1, 6445, 6445, 6445, -1, + 6446, 6446, 6446, -1, 6447, 6447, 6447, -1, + 6448, 6448, 6448, -1, 6449, 6449, 6449, -1, + 6450, 6450, 6450, -1, 6451, 6451, 6451, -1, + 6452, 6452, 6452, -1, 6453, 6453, 6453, -1, + 6454, 6454, 6454, -1, 6455, 6455, 6455, -1, + 6456, 6456, 6456, -1, 6457, 6457, 6457, -1, + 6458, 6458, 6458, -1, 6459, 6459, 6459, -1, + 6460, 6460, 6460, -1, 6461, 6461, 6461, -1, + 6462, 6462, 6462, -1, 6463, 6463, 6463, -1, + 6464, 6464, 6464, -1, 6465, 6465, 6465, -1, + 6466, 6466, 6466, -1, 6467, 6467, 6467, -1, + 6468, 6468, 6468, -1, 6469, 6469, 6469, -1, + 6470, 6470, 6470, -1, 6471, 6471, 6471, -1, + 6472, 6472, 6472, -1, 6473, 6473, 6473, -1, + 6474, 6474, 6474, -1, 6475, 6475, 6475, -1, + 6476, 6476, 6476, -1, 6477, 6477, 6477, -1, + 6478, 6478, 6478, -1, 6479, 6479, 6479, -1, + 6480, 6480, 6480, -1, 6481, 6481, 6481, -1, + 6482, 6482, 6482, -1, 6483, 6483, 6483, -1, + 6484, 6484, 6484, -1, 6485, 6485, 6485, -1, + 6486, 6486, 6486, -1, 6487, 6487, 6487, -1, + 6488, 6488, 6488, -1, 6489, 6489, 6489, -1, + 6490, 6490, 6490, -1, 6491, 6491, 6491, -1, + 6492, 6492, 6492, -1, 6493, 6493, 6493, -1, + 6494, 6494, 6494, -1, 6495, 6495, 6495, -1, + 6496, 6496, 6496, -1, 6497, 6497, 6497, -1, + 6498, 6498, 6498, -1, 6499, 6499, 6499, -1, + 6500, 6500, 6500, -1, 6501, 6501, 6501, -1, + 6502, 6502, 6502, -1, 6503, 6503, 6503, -1, + 6504, 6504, 6504, -1, 6505, 6505, 6505, -1, + 6506, 6506, 6506, -1, 6507, 6507, 6507, -1, + 6508, 6508, 6508, -1, 6509, 6509, 6509, -1, + 6510, 6510, 6510, -1, 6511, 6511, 6511, -1, + 6512, 6512, 6512, -1, 6513, 6513, 6513, -1, + 6514, 6514, 6514, -1, 6515, 6515, 6515, -1, + 6516, 6516, 6516, -1, 6517, 6517, 6517, -1, + 6518, 6518, 6518, -1, 6519, 6519, 6519, -1, + 6520, 6520, 6520, -1, 6521, 6521, 6521, -1, + 6522, 6522, 6522, -1, 6523, 6523, 6523, -1, + 6524, 6524, 6524, -1, 6525, 6525, 6525, -1, + 6526, 6526, 6526, -1, 6527, 6527, 6527, -1, + 6528, 6528, 6528, -1, 6529, 6529, 6529, -1, + 6530, 6530, 6530, -1, 6531, 6531, 6531, -1, + 6532, 6532, 6532, -1, 6533, 6533, 6533, -1, + 6534, 6534, 6534, -1, 6535, 6535, 6535, -1, + 6536, 6536, 6536, -1, 6537, 6537, 6537, -1, + 6538, 6538, 6538, -1, 6539, 6539, 6539, -1, + 6540, 6540, 6540, -1, 6541, 6541, 6541, -1, + 6542, 6542, 6542, -1, 6543, 6543, 6543, -1, + 6544, 6544, 6544, -1, 6545, 6545, 6545, -1, + 6546, 6546, 6546, -1, 6547, 6547, 6547, -1, + 6548, 6548, 6548, -1, 6549, 6549, 6549, -1, + 6550, 6550, 6550, -1, 6551, 6551, 6551, -1, + 6552, 6552, 6552, -1, 6553, 6553, 6553, -1, + 6554, 6554, 6554, -1, 6555, 6555, 6555, -1, + 6556, 6556, 6556, -1, 6557, 6557, 6557, -1, + 6558, 6558, 6558, -1, 6559, 6559, 6559, -1, + 6560, 6560, 6560, -1, 6561, 6561, 6561, -1, + 6562, 6562, 6562, -1, 6563, 6563, 6563, -1, + 6564, 6564, 6564, -1, 6565, 6565, 6565, -1, + 6566, 6566, 6566, -1, 6567, 6567, 6567, -1, + 6568, 6568, 6568, -1, 6569, 6569, 6569, -1, + 6570, 6570, 6570, -1, 6571, 6571, 6571, -1, + 6572, 6572, 6572, -1, 6573, 6573, 6573, -1, + 6574, 6574, 6574, -1, 6575, 6575, 6575, -1, + 6576, 6576, 6576, -1, 6577, 6577, 6577, -1, + 6578, 6578, 6578, -1, 6579, 6579, 6579, -1, + 6580, 6580, 6580, -1, 6581, 6581, 6581, -1, + 6582, 6582, 6582, -1, 6583, 6583, 6583, -1, + 6584, 6584, 6584, -1, 6585, 6585, 6585, -1, + 6586, 6586, 6586, -1, 6587, 6587, 6587, -1, + 6588, 6588, 6588, -1, 6589, 6589, 6589, -1, + 6590, 6590, 6590, -1, 6591, 6591, 6591, -1, + 6592, 6592, 6592, -1, 6593, 6593, 6593, -1, + 6594, 6594, 6594, -1, 6595, 6595, 6595, -1, + 6596, 6596, 6596, -1, 6597, 6597, 6597, -1, + 6598, 6598, 6598, -1, 6599, 6599, 6599, -1, + 6600, 6600, 6600, -1, 6601, 6601, 6601, -1, + 6602, 6602, 6602, -1, 6603, 6603, 6603, -1, + 6604, 6604, 6604, -1, 6605, 6605, 6605, -1, + 6606, 6606, 6606, -1, 6607, 6607, 6607, -1, + 6608, 6608, 6608, -1, 6609, 6609, 6609, -1, + 6610, 6610, 6610, -1, 6611, 6611, 6611, -1, + 6612, 6612, 6612, -1, 6613, 6613, 6613, -1, + 6614, 6614, 6614, -1, 6615, 6615, 6615, -1, + 6616, 6616, 6616, -1, 6617, 6617, 6617, -1, + 6618, 6618, 6618, -1, 6619, 6619, 6619, -1, + 6620, 6620, 6620, -1, 6621, 6621, 6621, -1, + 6622, 6622, 6622, -1, 6623, 6623, 6623, -1, + 6624, 6624, 6624, -1, 6625, 6625, 6625, -1, + 6626, 6626, 6626, -1, 6627, 6627, 6627, -1, + 6628, 6628, 6628, -1, 6629, 6629, 6629, -1, + 6630, 6630, 6630, -1, 6631, 6631, 6631, -1, + 6632, 6632, 6632, -1, 6633, 6633, 6633, -1, + 6634, 6634, 6634, -1, 6635, 6635, 6635, -1, + 6636, 6636, 6636, -1, 6637, 6637, 6637, -1, + 6638, 6638, 6638, -1, 6639, 6639, 6639, -1, + 6640, 6640, 6640, -1, 6641, 6641, 6641, -1, + 6642, 6642, 6642, -1, 6643, 6643, 6643, -1, + 6644, 6644, 6644, -1, 6645, 6645, 6645, -1, + 6646, 6646, 6646, -1, 6647, 6647, 6647, -1, + 6648, 6648, 6648, -1, 6649, 6649, 6649, -1, + 6650, 6650, 6650, -1, 6651, 6651, 6651, -1, + 6652, 6652, 6652, -1, 6653, 6653, 6653, -1, + 6654, 6654, 6654, -1, 6655, 6655, 6655, -1, + 6656, 6656, 6656, -1, 6657, 6657, 6657, -1, + 6658, 6658, 6658, -1, 6659, 6659, 6659, -1, + 6660, 6660, 6660, -1, 6661, 6661, 6661, -1, + 6662, 6662, 6662, -1, 6663, 6663, 6663, -1, + 6664, 6664, 6664, -1, 6665, 6665, 6665, -1, + 6666, 6666, 6666, -1, 6667, 6667, 6667, -1, + 6668, 6668, 6668, -1, 6669, 6669, 6669, -1, + 6670, 6670, 6670, -1, 6671, 6671, 6671, -1, + 6672, 6672, 6672, -1, 6673, 6673, 6673, -1, + 6674, 6674, 6674, -1, 6675, 6675, 6675, -1, + 6676, 6676, 6676, -1, 6677, 6677, 6677, -1, + 6678, 6678, 6678, -1, 6679, 6679, 6679, -1, + 6680, 6680, 6680, -1, 6681, 6681, 6681, -1, + 6682, 6682, 6682, -1, 6683, 6683, 6683, -1, + 6684, 6684, 6684, -1, 6685, 6685, 6685, -1, + 6686, 6686, 6686, -1, 6687, 6687, 6687, -1, + 6688, 6688, 6688, -1, 6689, 6689, 6689, -1, + 6690, 6690, 6690, -1, 6691, 6691, 6691, -1, + 6692, 6692, 6692, -1, 6693, 6693, 6693, -1, + 6694, 6694, 6694, -1, 6695, 6695, 6695, -1, + 6696, 6696, 6696, -1, 6697, 6697, 6697, -1, + 6698, 6698, 6698, -1, 6699, 6699, 6699, -1, + 6700, 6700, 6700, -1, 6701, 6701, 6701, -1, + 6702, 6702, 6702, -1, 6703, 6703, 6703, -1, + 6704, 6704, 6704, -1, 6705, 6705, 6705, -1, + 6706, 6706, 6706, -1, 6707, 6707, 6707, -1, + 6708, 6708, 6708, -1, 6709, 6709, 6709, -1, + 6710, 6710, 6710, -1, 6711, 6711, 6711, -1, + 6712, 6712, 6712, -1, 6713, 6713, 6713, -1, + 6714, 6714, 6714, -1, 6715, 6715, 6715, -1, + 6716, 6716, 6716, -1, 6717, 6717, 6717, -1, + 6718, 6718, 6718, -1, 6719, 6719, 6719, -1, + 6720, 6720, 6720, -1, 6721, 6721, 6721, -1, + 6722, 6722, 6722, -1, 6723, 6723, 6723, -1, + 6724, 6724, 6724, -1, 6725, 6725, 6725, -1, + 6726, 6726, 6726, -1, 6727, 6727, 6727, -1, + 6728, 6728, 6728, -1, 6729, 6729, 6729, -1, + 6730, 6730, 6730, -1, 6731, 6731, 6731, -1, + 6732, 6732, 6732, -1, 6733, 6733, 6733, -1, + 6734, 6734, 6734, -1, 6735, 6735, 6735, -1, + 6736, 6736, 6736, -1, 6737, 6737, 6737, -1, + 6738, 6738, 6738, -1, 6739, 6739, 6739, -1, + 6740, 6740, 6740, -1, 6741, 6741, 6741, -1, + 6742, 6742, 6742, -1, 6743, 6743, 6743, -1, + 6744, 6744, 6744, -1, 6745, 6745, 6745, -1, + 6746, 6746, 6746, -1, 6747, 6747, 6747, -1, + 6748, 6748, 6748, -1, 6749, 6749, 6749, -1, + 6750, 6750, 6750, -1, 6751, 6751, 6751, -1, + 6752, 6752, 6752, -1, 6753, 6753, 6753, -1, + 6754, 6754, 6754, -1, 6755, 6755, 6755, -1, + 6756, 6756, 6756, -1, 6757, 6757, 6757, -1, + 6758, 6758, 6758, -1, 6759, 6759, 6759, -1, + 6760, 6760, 6760, -1, 6761, 6761, 6761, -1, + 6762, 6762, 6762, -1, 6763, 6763, 6763, -1, + 6764, 6764, 6764, -1, 6765, 6765, 6765, -1, + 6766, 6766, 6766, -1, 6767, 6767, 6767, -1, + 6768, 6768, 6768, -1, 6769, 6769, 6769, -1, + 6770, 6770, 6770, -1, 6771, 6771, 6771, -1, + 6772, 6772, 6772, -1, 6773, 6773, 6773, -1, + 6774, 6774, 6774, -1, 6775, 6775, 6775, -1, + 6776, 6776, 6776, -1, 6777, 6777, 6777, -1, + 6778, 6778, 6778, -1, 6779, 6779, 6779, -1, + 6780, 6780, 6780, -1, 6781, 6781, 6781, -1, + 6782, 6782, 6782, -1, 6783, 6783, 6783, -1, + 6784, 6784, 6784, -1, 6785, 6785, 6785, -1, + 6786, 6786, 6786, -1, 6787, 6787, 6787, -1, + 6788, 6788, 6788, -1, 6789, 6789, 6789, -1, + 6790, 6790, 6790, -1, 6791, 6791, 6791, -1, + 6792, 6792, 6792, -1, 6793, 6793, 6793, -1, + 6794, 6794, 6794, -1, 6795, 6795, 6795, -1, + 6796, 6796, 6796, -1, 6797, 6797, 6797, -1, + 6798, 6798, 6798, -1, 6799, 6799, 6799, -1, + 6800, 6800, 6800, -1, 6801, 6801, 6801, -1, + 6802, 6802, 6802, -1, 6803, 6803, 6803, -1, + 6804, 6804, 6804, -1, 6805, 6805, 6805, -1, + 6806, 6806, 6806, -1, 6807, 6807, 6807, -1, + 6808, 6808, 6808, -1, 6809, 6809, 6809, -1, + 6810, 6810, 6810, -1, 6811, 6811, 6811, -1, + 6812, 6812, 6812, -1, 6813, 6813, 6813, -1, + 6814, 6814, 6814, -1, 6815, 6815, 6815, -1, + 6816, 6816, 6816, -1, 6817, 6817, 6817, -1, + 6818, 6818, 6818, -1, 6819, 6819, 6819, -1, + 6820, 6820, 6820, -1, 6821, 6821, 6821, -1, + 6822, 6822, 6822, -1, 6823, 6823, 6823, -1, + 6824, 6824, 6824, -1, 6825, 6825, 6825, -1, + 6826, 6826, 6826, -1, 6827, 6827, 6827, -1, + 6828, 6828, 6828, -1, 6829, 6829, 6829, -1, + 6830, 6830, 6830, -1, 6831, 6831, 6831, -1, + 6832, 6832, 6832, -1, 6833, 6833, 6833, -1, + 6834, 6834, 6834, -1, 6835, 6835, 6835, -1, + 6836, 6836, 6836, -1, 6837, 6837, 6837, -1, + 6838, 6838, 6838, -1, 6839, 6839, 6839, -1, + 6840, 6840, 6840, -1, 6841, 6841, 6841, -1, + 6842, 6842, 6842, -1, 6843, 6843, 6843, -1, + 6844, 6844, 6844, -1, 6845, 6845, 6845, -1, + 6846, 6846, 6846, -1, 6847, 6847, 6847, -1, + 6848, 6848, 6848, -1, 6849, 6849, 6849, -1, + 6850, 6850, 6850, -1, 6851, 6851, 6851, -1, + 6852, 6852, 6852, -1, 6853, 6853, 6853, -1, + 6854, 6854, 6854, -1, 6855, 6855, 6855, -1, + 6856, 6856, 6856, -1, 6857, 6857, 6857, -1, + 6858, 6858, 6858, -1, 6859, 6859, 6859, -1, + 6860, 6860, 6860, -1, 6861, 6861, 6861, -1, + 6862, 6862, 6862, -1, 6863, 6863, 6863, -1, + 6864, 6864, 6864, -1, 6865, 6865, 6865, -1, + 6866, 6866, 6866, -1, 6867, 6867, 6867, -1, + 6868, 6868, 6868, -1, 6869, 6869, 6869, -1, + 6870, 6870, 6870, -1, 6871, 6871, 6871, -1, + 6872, 6872, 6872, -1, 6873, 6873, 6873, -1, + 6874, 6874, 6874, -1, 6875, 6875, 6875, -1, + 6876, 6876, 6876, -1, 6877, 6877, 6877, -1, + 6878, 6878, 6878, -1, 6879, 6879, 6879, -1, + 6880, 6880, 6880, -1, 6881, 6881, 6881, -1, + 6882, 6882, 6882, -1, 6883, 6883, 6883, -1, + 6884, 6884, 6884, -1, 6885, 6885, 6885, -1, + 6886, 6886, 6886, -1, 6887, 6887, 6887, -1, + 6888, 6888, 6888, -1, 6889, 6889, 6889, -1, + 6890, 6890, 6890, -1, 6891, 6891, 6891, -1, + 6892, 6892, 6892, -1, 6893, 6893, 6893, -1, + 6894, 6894, 6894, -1, 6895, 6895, 6895, -1, + 6896, 6896, 6896, -1, 6897, 6897, 6897, -1, + 6898, 6898, 6898, -1, 6899, 6899, 6899, -1, + 6900, 6900, 6900, -1, 6901, 6901, 6901, -1, + 6902, 6902, 6902, -1, 6903, 6903, 6903, -1, + 6904, 6904, 6904, -1, 6905, 6905, 6905, -1, + 6906, 6906, 6906, -1, 6907, 6907, 6907, -1, + 6908, 6908, 6908, -1, 6909, 6909, 6909, -1, + 6910, 6910, 6910, -1, 6911, 6911, 6911, -1, + 6912, 6912, 6912, -1, 6913, 6913, 6913, -1, + 6914, 6914, 6914, -1, 6915, 6915, 6915, -1, + 6916, 6916, 6916, -1, 6917, 6917, 6917, -1, + 6918, 6918, 6918, -1, 6919, 6919, 6919, -1, + 6920, 6920, 6920, -1, 6921, 6921, 6921, -1, + 6922, 6922, 6922, -1, 6923, 6923, 6923, -1, + 6924, 6924, 6924, -1, 6925, 6925, 6925, -1, + 6926, 6926, 6926, -1, 6927, 6927, 6927, -1, + 6928, 6928, 6928, -1, 6929, 6929, 6929, -1, + 6930, 6930, 6930, -1, 6931, 6931, 6931, -1, + 6932, 6932, 6932, -1, 6933, 6933, 6933, -1, + 6934, 6934, 6934, -1, 6935, 6935, 6935, -1, + 6936, 6936, 6936, -1, 6937, 6937, 6937, -1, + 6938, 6938, 6938, -1, 6939, 6939, 6939, -1, + 6940, 6940, 6940, -1, 6941, 6941, 6941, -1, + 6942, 6942, 6942, -1, 6943, 6943, 6943, -1, + 6944, 6944, 6944, -1, 6945, 6945, 6945, -1, + 6946, 6946, 6946, -1, 6947, 6947, 6947, -1, + 6948, 6948, 6948, -1, 6949, 6949, 6949, -1, + 6950, 6950, 6950, -1, 6951, 6951, 6951, -1, + 6952, 6952, 6952, -1, 6953, 6953, 6953, -1, + 6954, 6954, 6954, -1, 6955, 6955, 6955, -1, + 6956, 6956, 6956, -1, 6957, 6957, 6957, -1, + 6958, 6958, 6958, -1, 6959, 6959, 6959, -1, + 6960, 6960, 6960, -1, 6961, 6961, 6961, -1, + 6962, 6962, 6962, -1, 6963, 6963, 6963, -1, + 6964, 6964, 6964, -1, 6965, 6965, 6965, -1, + 6966, 6966, 6966, -1, 6967, 6967, 6967, -1, + 6968, 6968, 6968, -1, 6969, 6969, 6969, -1, + 6970, 6970, 6970, -1, 6971, 6971, 6971, -1, + 6972, 6972, 6972, -1, 6973, 6973, 6973, -1, + 6974, 6974, 6974, -1, 6975, 6975, 6975, -1, + 6976, 6976, 6976, -1, 6977, 6977, 6977, -1, + 6978, 6978, 6978, -1, 6979, 6979, 6979, -1, + 6980, 6980, 6980, -1, 6981, 6981, 6981, -1, + 6982, 6982, 6982, -1, 6983, 6983, 6983, -1, + 6984, 6984, 6984, -1, 6985, 6985, 6985, -1, + 6986, 6986, 6986, -1, 6987, 6987, 6987, -1, + 6988, 6988, 6988, -1, 6989, 6989, 6989, -1, + 6990, 6990, 6990, -1, 6991, 6991, 6991, -1, + 6992, 6992, 6992, -1, 6993, 6993, 6993, -1, + 6994, 6994, 6994, -1, 6995, 6995, 6995, -1, + 6996, 6996, 6996, -1, 6997, 6997, 6997, -1, + 6998, 6998, 6998, -1, 6999, 6999, 6999, -1, + 7000, 7000, 7000, -1, 7001, 7001, 7001, -1, + 7002, 7002, 7002, -1, 7003, 7003, 7003, -1, + 7004, 7004, 7004, -1, 7005, 7005, 7005, -1, + 7006, 7006, 7006, -1, 7007, 7007, 7007, -1, + 7008, 7008, 7008, -1, 7009, 7009, 7009, -1, + 7010, 7010, 7010, -1, 7011, 7011, 7011, -1, + 7012, 7012, 7012, -1, 7013, 7013, 7013, -1, + 7014, 7014, 7014, -1, 7015, 7015, 7015, -1, + 7016, 7016, 7016, -1, 7017, 7017, 7017, -1, + 7018, 7018, 7018, -1, 7019, 7019, 7019, -1, + 7020, 7020, 7020, -1, 7021, 7021, 7021, -1, + 7022, 7022, 7022, -1, 7023, 7023, 7023, -1, + 7024, 7024, 7024, -1, 7025, 7025, 7025, -1, + 7026, 7026, 7026, -1, 7027, 7027, 7027, -1, + 7028, 7028, 7028, -1, 7029, 7029, 7029, -1, + 7030, 7030, 7030, -1, 7031, 7031, 7031, -1, + 7032, 7032, 7032, -1, 7033, 7033, 7033, -1, + 7034, 7034, 7034, -1, 7035, 7035, 7035, -1, + 7036, 7036, 7036, -1, 7037, 7037, 7037, -1, + 7038, 7038, 7038, -1, 7039, 7039, 7039, -1, + 7040, 7040, 7040, -1, 7041, 7041, 7041, -1, + 7042, 7042, 7042, -1, 7043, 7043, 7043, -1, + 7044, 7044, 7044, -1, 7045, 7045, 7045, -1, + 7046, 7046, 7046, -1, 7047, 7047, 7047, -1, + 7048, 7048, 7048, -1, 7049, 7049, 7049, -1, + 7050, 7050, 7050, -1, 7051, 7051, 7051, -1, + 7052, 7052, 7052, -1, 7053, 7053, 7053, -1, + 7054, 7054, 7054, -1, 7055, 7055, 7055, -1, + 7056, 7056, 7056, -1, 7057, 7057, 7057, -1, + 7058, 7058, 7058, -1, 7059, 7059, 7059, -1, + 7060, 7060, 7060, -1, 7061, 7061, 7061, -1, + 7062, 7062, 7062, -1, 7063, 7063, 7063, -1, + 7064, 7064, 7064, -1, 7065, 7065, 7065, -1, + 7066, 7066, 7066, -1, 7067, 7067, 7067, -1, + 7068, 7068, 7068, -1, 7069, 7069, 7069, -1, + 7070, 7070, 7070, -1, 7071, 7071, 7071, -1, + 7072, 7072, 7072, -1, 7073, 7073, 7073, -1, + 7074, 7074, 7074, -1, 7075, 7075, 7075, -1, + 7076, 7076, 7076, -1, 7077, 7077, 7077, -1, + 7078, 7078, 7078, -1, 7079, 7079, 7079, -1, + 7080, 7080, 7080, -1, 7081, 7081, 7081, -1, + 7082, 7082, 7082, -1, 7083, 7083, 7083, -1, + 7084, 7084, 7084, -1, 7085, 7085, 7085, -1, + 7086, 7086, 7086, -1, 7087, 7087, 7087, -1, + 7088, 7088, 7088, -1, 7089, 7089, 7089, -1, + 7090, 7090, 7090, -1, 7091, 7091, 7091, -1, + 7092, 7092, 7092, -1, 7093, 7093, 7093, -1, + 7094, 7094, 7094, -1, 7095, 7095, 7095, -1, + 7096, 7096, 7096, -1, 7097, 7097, 7097, -1, + 7098, 7098, 7098, -1, 7099, 7099, 7099, -1, + 7100, 7100, 7100, -1, 7101, 7101, 7101, -1, + 7102, 7102, 7102, -1, 7103, 7103, 7103, -1, + 7104, 7104, 7104, -1, 7105, 7105, 7105, -1, + 7106, 7106, 7106, -1, 7107, 7107, 7107, -1, + 7108, 7108, 7108, -1, 7109, 7109, 7109, -1, + 7110, 7110, 7110, -1, 7111, 7111, 7111, -1, + 7112, 7112, 7112, -1, 7113, 7113, 7113, -1, + 7114, 7114, 7114, -1, 7115, 7115, 7115, -1, + 7116, 7116, 7116, -1, 7117, 7117, 7117, -1, + 7118, 7118, 7118, -1, 7119, 7119, 7119, -1, + 7120, 7120, 7120, -1, 7121, 7121, 7121, -1, + 7122, 7122, 7122, -1, 7123, 7123, 7123, -1, + 7124, 7124, 7124, -1, 7125, 7125, 7125, -1, + 7126, 7126, 7126, -1, 7127, 7127, 7127, -1, + 7128, 7128, 7128, -1, 7129, 7129, 7129, -1, + 7130, 7130, 7130, -1, 7131, 7131, 7131, -1, + 7132, 7132, 7132, -1, 7133, 7133, 7133, -1, + 7134, 7134, 7134, -1, 7135, 7135, 7135, -1, + 7136, 7136, 7136, -1, 7137, 7137, 7137, -1, + 7138, 7138, 7138, -1, 7139, 7139, 7139, -1, + 7140, 7140, 7140, -1, 7141, 7141, 7141, -1, + 7142, 7142, 7142, -1, 7143, 7143, 7143, -1, + 7144, 7144, 7144, -1, 7145, 7145, 7145, -1, + 7146, 7146, 7146, -1, 7147, 7147, 7147, -1, + 7148, 7148, 7148, -1, 7149, 7149, 7149, -1, + 7150, 7150, 7150, -1, 7151, 7151, 7151, -1, + 7152, 7152, 7152, -1, 7153, 7153, 7153, -1, + 7154, 7154, 7154, -1, 7155, 7155, 7155, -1, + 7156, 7156, 7156, -1, 7157, 7157, 7157, -1, + 7158, 7158, 7158, -1, 7159, 7159, 7159, -1, + 7160, 7160, 7160, -1, 7161, 7161, 7161, -1, + 7162, 7162, 7162, -1, 7163, 7163, 7163, -1, + 7164, 7164, 7164, -1, 7165, 7165, 7165, -1, + 7166, 7166, 7166, -1, 7167, 7167, 7167, -1, + 7168, 7168, 7168, -1, 7169, 7169, 7169, -1, + 7170, 7170, 7170, -1, 7171, 7171, 7171, -1, + 7172, 7172, 7172, -1, 7173, 7173, 7173, -1, + 7174, 7174, 7174, -1, 7175, 7175, 7175, -1, + 7176, 7176, 7176, -1, 7177, 7177, 7177, -1, + 7178, 7178, 7178, -1, 7179, 7179, 7179, -1, + 7180, 7180, 7180, -1, 7181, 7181, 7181, -1, + 7182, 7182, 7182, -1, 7183, 7183, 7183, -1, + 7184, 7184, 7184, -1, 7185, 7185, 7185, -1, + 7186, 7186, 7186, -1, 7187, 7187, 7187, -1, + 7188, 7188, 7188, -1, 7189, 7189, 7189, -1, + 7190, 7190, 7190, -1, 7191, 7191, 7191, -1, + 7192, 7192, 7192, -1, 7193, 7193, 7193, -1, + 7194, 7194, 7194, -1, 7195, 7195, 7195, -1, + 7196, 7196, 7196, -1, 7197, 7197, 7197, -1, + 7198, 7198, 7198, -1, 7199, 7199, 7199, -1, + 7200, 7200, 7200, -1, 7201, 7201, 7201, -1, + 7202, 7202, 7202, -1, 7203, 7203, 7203, -1, + 7204, 7204, 7204, -1, 7205, 7205, 7205, -1, + 7206, 7206, 7206, -1, 7207, 7207, 7207, -1, + 7208, 7208, 7208, -1, 7209, 7209, 7209, -1, + 7210, 7210, 7210, -1, 7211, 7211, 7211, -1, + 7212, 7212, 7212, -1, 7213, 7213, 7213, -1, + 7214, 7214, 7214, -1, 7215, 7215, 7215, -1, + 7216, 7216, 7216, -1, 7217, 7217, 7217, -1, + 7218, 7218, 7218, -1, 7219, 7219, 7219, -1, + 7220, 7220, 7220, -1, 7221, 7221, 7221, -1, + 7222, 7222, 7222, -1, 7223, 7223, 7223, -1, + 7224, 7224, 7224, -1, 7225, 7225, 7225, -1, + 7226, 7226, 7226, -1, 7227, 7227, 7227, -1, + 7228, 7228, 7228, -1, 7229, 7229, 7229, -1, + 7230, 7230, 7230, -1, 7231, 7231, 7231, -1, + 7232, 7232, 7232, -1, 7233, 7233, 7233, -1, + 7234, 7234, 7234, -1, 7235, 7235, 7235, -1, + 7236, 7236, 7236, -1, 7237, 7237, 7237, -1, + 7238, 7238, 7238, -1, 7239, 7239, 7239, -1, + 7240, 7240, 7240, -1, 7241, 7241, 7241, -1, + 7242, 7242, 7242, -1, 7243, 7243, 7243, -1, + 7244, 7244, 7244, -1, 7245, 7245, 7245, -1, + 7246, 7246, 7246, -1, 7247, 7247, 7247, -1, + 7248, 7248, 7248, -1, 7249, 7249, 7249, -1, + 7250, 7250, 7250, -1, 7251, 7251, 7251, -1, + 7252, 7252, 7252, -1, 7253, 7253, 7253, -1, + 7254, 7254, 7254, -1, 7255, 7255, 7255, -1, + 7256, 7256, 7256, -1, 7257, 7257, 7257, -1, + 7258, 7258, 7258, -1, 7259, 7259, 7259, -1, + 7260, 7260, 7260, -1, 7261, 7261, 7261, -1, + 7262, 7262, 7262, -1, 7263, 7263, 7263, -1, + 7264, 7264, 7264, -1, 7265, 7265, 7265, -1, + 7266, 7266, 7266, -1, 7267, 7267, 7267, -1, + 7268, 7268, 7268, -1, 7269, 7269, 7269, -1, + 7270, 7270, 7270, -1, 7271, 7271, 7271, -1, + 7272, 7272, 7272, -1, 7273, 7273, 7273, -1, + 7274, 7274, 7274, -1, 7275, 7275, 7275, -1, + 7276, 7276, 7276, -1, 7277, 7277, 7277, -1, + 7278, 7278, 7278, -1, 7279, 7279, 7279, -1, + 7280, 7280, 7280, -1, 7281, 7281, 7281, -1, + 7282, 7282, 7282, -1, 7283, 7283, 7283, -1, + 7284, 7284, 7284, -1, 7285, 7285, 7285, -1, + 7286, 7286, 7286, -1, 7287, 7287, 7287, -1, + 7288, 7288, 7288, -1, 7289, 7289, 7289, -1, + 7290, 7290, 7290, -1, 7291, 7291, 7291, -1, + 7292, 7292, 7292, -1, 7293, 7293, 7293, -1, + 7294, 7294, 7294, -1, 7295, 7295, 7295, -1, + 7296, 7296, 7296, -1, 7297, 7297, 7297, -1, + 7298, 7298, 7298, -1, 7299, 7299, 7299, -1, + 7300, 7300, 7300, -1, 7301, 7301, 7301, -1, + 7302, 7302, 7302, -1, 7303, 7303, 7303, -1, + 7304, 7304, 7304, -1, 7305, 7305, 7305, -1, + 7306, 7306, 7306, -1, 7307, 7307, 7307, -1, + 7308, 7308, 7308, -1, 7309, 7309, 7309, -1, + 7310, 7310, 7310, -1, 7311, 7311, 7311, -1, + 7312, 7312, 7312, -1, 7313, 7313, 7313, -1, + 7314, 7314, 7314, -1, 7315, 7315, 7315, -1, + 7316, 7316, 7316, -1, 7317, 7317, 7317, -1, + 7318, 7318, 7318, -1, 7319, 7319, 7319, -1, + 7320, 7320, 7320, -1, 7321, 7321, 7321, -1, + 7322, 7322, 7322, -1, 7323, 7323, 7323, -1, + 7324, 7324, 7324, -1, 7325, 7325, 7325, -1, + 7326, 7326, 7326, -1, 7327, 7327, 7327, -1, + 7328, 7328, 7328, -1, 7329, 7329, 7329, -1, + 7330, 7330, 7330, -1, 7331, 7331, 7331, -1, + 7332, 7332, 7332, -1, 7333, 7333, 7333, -1, + 7334, 7334, 7334, -1, 7335, 7335, 7335, -1, + 7336, 7336, 7336, -1, 7337, 7337, 7337, -1, + 7338, 7338, 7338, -1, 7339, 7339, 7339, -1, + 7340, 7340, 7340, -1, 7341, 7341, 7341, -1, + 7342, 7342, 7342, -1, 7343, 7343, 7343, -1, + 7344, 7344, 7344, -1, 7345, 7345, 7345, -1, + 7346, 7346, 7346, -1, 7347, 7347, 7347, -1, + 7348, 7348, 7348, -1, 7349, 7349, 7349, -1, + 7350, 7350, 7350, -1, 7351, 7351, 7351, -1, + 7352, 7352, 7352, -1, 7353, 7353, 7353, -1, + 7354, 7354, 7354, -1, 7355, 7355, 7355, -1, + 7356, 7356, 7356, -1, 7357, 7357, 7357, -1, + 7358, 7358, 7358, -1, 7359, 7359, 7359, -1, + 7360, 7360, 7360, -1, 7361, 7361, 7361, -1, + 7362, 7362, 7362, -1, 7363, 7363, 7363, -1, + 7364, 7364, 7364, -1, 7365, 7365, 7365, -1, + 7366, 7366, 7366, -1, 7367, 7367, 7367, -1, + 7368, 7368, 7368, -1, 7369, 7369, 7369, -1, + 7370, 7370, 7370, -1, 7371, 7371, 7371, -1, + 7372, 7372, 7372, -1, 7373, 7373, 7373, -1, + 7374, 7374, 7374, -1, 7375, 7375, 7375, -1, + 7376, 7376, 7376, -1, 7377, 7377, 7377, -1, + 7378, 7378, 7378, -1, 7379, 7379, 7379, -1, + 7380, 7380, 7380, -1, 7381, 7381, 7381, -1, + 7382, 7382, 7382, -1, 7383, 7383, 7383, -1, + 7384, 7384, 7384, -1, 7385, 7385, 7385, -1, + 7386, 7386, 7386, -1, 7387, 7387, 7387, -1, + 7388, 7388, 7388, -1, 7389, 7389, 7389, -1, + 7390, 7390, 7390, -1, 7391, 7391, 7391, -1, + 7392, 7392, 7392, -1, 7393, 7393, 7393, -1, + 7394, 7394, 7394, -1, 7395, 7395, 7395, -1, + 7396, 7396, 7396, -1, 7397, 7397, 7397, -1, + 7398, 7398, 7398, -1, 7399, 7399, 7399, -1, + 7400, 7400, 7400, -1, 7401, 7401, 7401, -1, + 7402, 7402, 7402, -1, 7403, 7403, 7403, -1, + 7404, 7404, 7404, -1, 7405, 7405, 7405, -1, + 7406, 7406, 7406, -1, 7407, 7407, 7407, -1, + 7408, 7408, 7408, -1, 7409, 7409, 7409, -1, + 7410, 7410, 7410, -1, 7411, 7411, 7411, -1, + 7412, 7412, 7412, -1, 7413, 7413, 7413, -1, + 7414, 7414, 7414, -1, 7415, 7415, 7415, -1, + 7416, 7416, 7416, -1, 7417, 7417, 7417, -1, + 7418, 7418, 7418, -1, 7419, 7419, 7419, -1, + 7420, 7420, 7420, -1, 7421, 7421, 7421, -1, + 7422, 7422, 7422, -1, 7423, 7423, 7423, -1, + 7424, 7424, 7424, -1, 7425, 7425, 7425, -1, + 7426, 7426, 7426, -1, 7427, 7427, 7427, -1, + 7428, 7428, 7428, -1, 7429, 7429, 7429, -1, + 7430, 7430, 7430, -1, 7431, 7431, 7431, -1, + 7432, 7432, 7432, -1, 7433, 7433, 7433, -1, + 7434, 7434, 7434, -1, 7435, 7435, 7435, -1, + 7436, 7436, 7436, -1, 7437, 7437, 7437, -1, + 7438, 7438, 7438, -1, 7439, 7439, 7439, -1, + 7440, 7440, 7440, -1, 7441, 7441, 7441, -1, + 7442, 7442, 7442, -1, 7443, 7443, 7443, -1, + 7444, 7444, 7444, -1, 7445, 7445, 7445, -1, + 7446, 7446, 7446, -1, 7447, 7447, 7447, -1, + 7448, 7448, 7448, -1, 7449, 7449, 7449, -1, + 7450, 7450, 7450, -1, 7451, 7451, 7451, -1, + 7452, 7452, 7452, -1, 7453, 7453, 7453, -1, + 7454, 7454, 7454, -1, 7455, 7455, 7455, -1, + 7456, 7456, 7456, -1, 7457, 7457, 7457, -1, + 7458, 7458, 7458, -1, 7459, 7459, 7459, -1, + 7460, 7460, 7460, -1, 7461, 7461, 7461, -1, + 7462, 7462, 7462, -1, 7463, 7463, 7463, -1, + 7464, 7464, 7464, -1, 7465, 7465, 7465, -1, + 7466, 7466, 7466, -1, 7467, 7467, 7467, -1, + 7468, 7468, 7468, -1, 7469, 7469, 7469, -1, + 7470, 7470, 7470, -1, 7471, 7471, 7471, -1, + 7472, 7472, 7472, -1, 7473, 7473, 7473, -1, + 7474, 7474, 7474, -1, 7475, 7475, 7475, -1, + 7476, 7476, 7476, -1, 7477, 7477, 7477, -1, + 7478, 7478, 7478, -1, 7479, 7479, 7479, -1, + 7480, 7480, 7480, -1, 7481, 7481, 7481, -1, + 7482, 7482, 7482, -1, 7483, 7483, 7483, -1, + 7484, 7484, 7484, -1, 7485, 7485, 7485, -1, + 7486, 7486, 7486, -1, 7487, 7487, 7487, -1, + 7488, 7488, 7488, -1, 7489, 7489, 7489, -1, + 7490, 7490, 7490, -1, 7491, 7491, 7491, -1, + 7492, 7492, 7492, -1, 7493, 7493, 7493, -1, + 7494, 7494, 7494, -1, 7495, 7495, 7495, -1, + 7496, 7496, 7496, -1, 7497, 7497, 7497, -1, + 7498, 7498, 7498, -1, 7499, 7499, 7499, -1, + 7500, 7500, 7500, -1, 7501, 7501, 7501, -1, + 7502, 7502, 7502, -1, 7503, 7503, 7503, -1, + 7504, 7504, 7504, -1, 7505, 7505, 7505, -1, + 7506, 7506, 7506, -1, 7507, 7507, 7507, -1, + 7508, 7508, 7508, -1, 7509, 7509, 7509, -1, + 7510, 7510, 7510, -1, 7511, 7511, 7511, -1, + 7512, 7512, 7512, -1, 7513, 7513, 7513, -1, + 7514, 7514, 7514, -1, 7515, 7515, 7515, -1, + 7516, 7516, 7516, -1, 7517, 7517, 7517, -1, + 7518, 7518, 7518, -1, 7519, 7519, 7519, -1, + 7520, 7520, 7520, -1, 7521, 7521, 7521, -1, + 7522, 7522, 7522, -1, 7523, 7523, 7523, -1, + 7524, 7524, 7524, -1, 7525, 7525, 7525, -1, + 7526, 7526, 7526, -1, 7527, 7527, 7527, -1, + 7528, 7528, 7528, -1, 7529, 7529, 7529, -1, + 7530, 7530, 7530, -1, 7531, 7531, 7531, -1, + 7532, 7532, 7532, -1, 7533, 7533, 7533, -1, + 7534, 7534, 7534, -1, 7535, 7535, 7535, -1, + 7536, 7536, 7536, -1, 7537, 7537, 7537, -1, + 7538, 7538, 7538, -1, 7539, 7539, 7539, -1, + 7540, 7540, 7540, -1, 7541, 7541, 7541, -1, + 7542, 7542, 7542, -1, 7543, 7543, 7543, -1, + 7544, 7544, 7544, -1, 7545, 7545, 7545, -1, + 7546, 7546, 7546, -1, 7547, 7547, 7547, -1, + 7548, 7548, 7548, -1, 7549, 7549, 7549, -1, + 7550, 7550, 7550, -1, 7551, 7551, 7551, -1, + 7552, 7552, 7552, -1, 7553, 7553, 7553, -1, + 7554, 7554, 7554, -1, 7555, 7555, 7555, -1, + 7556, 7556, 7556, -1, 7557, 7557, 7557, -1, + 7558, 7558, 7558, -1, 7559, 7559, 7559, -1, + 7560, 7560, 7560, -1, 7561, 7561, 7561, -1, + 7562, 7562, 7562, -1, 7563, 7563, 7563, -1, + 7564, 7564, 7564, -1, 7565, 7565, 7565, -1, + 7566, 7566, 7566, -1, 7567, 7567, 7567, -1, + 7568, 7568, 7568, -1, 7569, 7569, 7569, -1, + 7570, 7570, 7570, -1, 7571, 7571, 7571, -1, + 7572, 7572, 7572, -1, 7573, 7573, 7573, -1, + 7574, 7574, 7574, -1, 7575, 7575, 7575, -1, + 7576, 7576, 7576, -1, 7577, 7577, 7577, -1, + 7578, 7578, 7578, -1, 7579, 7579, 7579, -1, + 7580, 7580, 7580, -1, 7581, 7581, 7581, -1, + 7582, 7582, 7582, -1, 7583, 7583, 7583, -1, + 7584, 7584, 7584, -1, 7585, 7585, 7585, -1, + 7586, 7586, 7586, -1, 7587, 7587, 7587, -1, + 7588, 7588, 7588, -1, 7589, 7589, 7589, -1, + 7590, 7590, 7590, -1, 7591, 7591, 7591, -1, + 7592, 7592, 7592, -1, 7593, 7593, 7593, -1, + 7594, 7594, 7594, -1, 7595, 7595, 7595, -1, + 7596, 7596, 7596, -1, 7597, 7597, 7597, -1, + 7598, 7598, 7598, -1, 7599, 7599, 7599, -1, + 7600, 7600, 7600, -1, 7601, 7601, 7601, -1, + 7602, 7602, 7602, -1, 7603, 7603, 7603, -1, + 7604, 7604, 7604, -1, 7605, 7605, 7605, -1, + 7606, 7606, 7606, -1, 7607, 7607, 7607, -1, + 7608, 7608, 7608, -1, 7609, 7609, 7609, -1, + 7610, 7610, 7610, -1, 7611, 7611, 7611, -1, + 7612, 7612, 7612, -1, 7613, 7613, 7613, -1, + 7614, 7614, 7614, -1, 7615, 7615, 7615, -1, + 7616, 7616, 7616, -1, 7617, 7617, 7617, -1, + 7618, 7618, 7618, -1, 7619, 7619, 7619, -1, + 7620, 7620, 7620, -1, 7621, 7621, 7621, -1, + 7622, 7622, 7622, -1, 7623, 7623, 7623, -1, + 7624, 7624, 7624, -1, 7625, 7625, 7625, -1, + 7626, 7626, 7626, -1, 7627, 7627, 7627, -1, + 7628, 7628, 7628, -1, 7629, 7629, 7629, -1, + 7630, 7630, 7630, -1, 7631, 7631, 7631, -1, + 7632, 7632, 7632, -1, 7633, 7633, 7633, -1, + 7634, 7634, 7634, -1, 7635, 7635, 7635, -1, + 7636, 7636, 7636, -1, 7637, 7637, 7637, -1, + 7638, 7638, 7638, -1, 7639, 7639, 7639, -1, + 7640, 7640, 7640, -1, 7641, 7641, 7641, -1, + 7642, 7642, 7642, -1, 7643, 7643, 7643, -1, + 7644, 7644, 7644, -1, 7645, 7645, 7645, -1, + 7646, 7646, 7646, -1, 7647, 7647, 7647, -1, + 7648, 7648, 7648, -1, 7649, 7649, 7649, -1, + 7650, 7650, 7650, -1, 7651, 7651, 7651, -1, + 7652, 7652, 7652, -1, 7653, 7653, 7653, -1, + 7654, 7654, 7654, -1, 7655, 7655, 7655, -1, + 7656, 7656, 7656, -1, 7657, 7657, 7657, -1, + 7658, 7658, 7658, -1, 7659, 7659, 7659, -1, + 7660, 7660, 7660, -1, 7661, 7661, 7661, -1, + 7662, 7662, 7662, -1, 7663, 7663, 7663, -1, + 7664, 7664, 7664, -1, 7665, 7665, 7665, -1, + 7666, 7666, 7666, -1, 7667, 7667, 7667, -1, + 7668, 7668, 7668, -1, 7669, 7669, 7669, -1, + 7670, 7670, 7670, -1, 7671, 7671, 7671, -1, + 7672, 7672, 7672, -1, 7673, 7673, 7673, -1, + 7674, 7674, 7674, -1, 7675, 7675, 7675, -1, + 7676, 7676, 7676, -1, 7677, 7677, 7677, -1, + 7678, 7678, 7678, -1, 7679, 7679, 7679, -1, + 7680, 7680, 7680, -1, 7681, 7681, 7681, -1, + 7682, 7682, 7682, -1, 7683, 7683, 7683, -1, + 7684, 7684, 7684, -1, 7685, 7685, 7685, -1, + 7686, 7686, 7686, -1, 7687, 7687, 7687, -1, + 7688, 7688, 7688, -1, 7689, 7689, 7689, -1, + 7690, 7690, 7690, -1, 7691, 7691, 7691, -1, + 7692, 7692, 7692, -1, 7693, 7693, 7693, -1, + 7694, 7694, 7694, -1, 7695, 7695, 7695, -1, + 7696, 7696, 7696, -1, 7697, 7697, 7697, -1, + 7698, 7698, 7698, -1, 7699, 7699, 7699, -1, + 7700, 7700, 7700, -1, 7701, 7701, 7701, -1, + 7702, 7702, 7702, -1, 7703, 7703, 7703, -1, + 7704, 7704, 7704, -1, 7705, 7705, 7705, -1, + 7706, 7706, 7706, -1, 7707, 7707, 7707, -1, + 7708, 7708, 7708, -1, 7709, 7709, 7709, -1, + 7710, 7710, 7710, -1, 7711, 7711, 7711, -1, + 7712, 7712, 7712, -1, 7713, 7713, 7713, -1, + 7714, 7714, 7714, -1, 7715, 7715, 7715, -1, + 7716, 7716, 7716, -1, 7717, 7717, 7717, -1, + 7718, 7718, 7718, -1, 7719, 7719, 7719, -1, + 7720, 7720, 7720, -1, 7721, 7721, 7721, -1, + 7722, 7722, 7722, -1, 7723, 7723, 7723, -1, + 7724, 7724, 7724, -1, 7725, 7725, 7725, -1, + 7726, 7726, 7726, -1, 7727, 7727, 7727, -1, + 7728, 7728, 7728, -1, 7729, 7729, 7729, -1, + 7730, 7730, 7730, -1, 7731, 7731, 7731, -1, + 7732, 7732, 7732, -1, 7733, 7733, 7733, -1, + 7734, 7734, 7734, -1, 7735, 7735, 7735, -1, + 7736, 7736, 7736, -1, 7737, 7737, 7737, -1, + 7738, 7738, 7738, -1, 7739, 7739, 7739, -1, + 7740, 7740, 7740, -1, 7741, 7741, 7741, -1, + 7742, 7742, 7742, -1, 7743, 7743, 7743, -1, + 7744, 7744, 7744, -1, 7745, 7745, 7745, -1, + 7746, 7746, 7746, -1, 7747, 7747, 7747, -1, + 7748, 7748, 7748, -1, 7749, 7749, 7749, -1, + 7750, 7750, 7750, -1, 7751, 7751, 7751, -1, + 7752, 7752, 7752, -1, 7753, 7753, 7753, -1, + 7754, 7754, 7754, -1, 7755, 7755, 7755, -1, + 7756, 7756, 7756, -1, 7757, 7757, 7757, -1, + 7758, 7758, 7758, -1, 7759, 7759, 7759, -1, + 7760, 7760, 7760, -1, 7761, 7761, 7761, -1, + 7762, 7762, 7762, -1, 7763, 7763, 7763, -1, + 7764, 7764, 7764, -1, 7765, 7765, 7765, -1, + 7766, 7766, 7766, -1, 7767, 7767, 7767, -1, + 7768, 7768, 7768, -1, 7769, 7769, 7769, -1, + 7770, 7770, 7770, -1, 7771, 7771, 7771, -1, + 7772, 7772, 7772, -1, 7773, 7773, 7773, -1, + 7774, 7774, 7774, -1, 7775, 7775, 7775, -1, + 7776, 7776, 7776, -1, 7777, 7777, 7777, -1, + 7778, 7778, 7778, -1, 7779, 7779, 7779, -1, + 7780, 7780, 7780, -1, 7781, 7781, 7781, -1, + 7782, 7782, 7782, -1, 7783, 7783, 7783, -1, + 7784, 7784, 7784, -1, 7785, 7785, 7785, -1, + 7786, 7786, 7786, -1, 7787, 7787, 7787, -1, + 7788, 7788, 7788, -1, 7789, 7789, 7789, -1, + 7790, 7790, 7790, -1, 7791, 7791, 7791, -1, + 7792, 7792, 7792, -1, 7793, 7793, 7793, -1, + 7794, 7794, 7794, -1, 7795, 7795, 7795, -1, + 7796, 7796, 7796, -1, 7797, 7797, 7797, -1, + 7798, 7798, 7798, -1, 7799, 7799, 7799, -1, + 7800, 7800, 7800, -1, 7801, 7801, 7801, -1, + 7802, 7802, 7802, -1, 7803, 7803, 7803, -1, + 7804, 7804, 7804, -1, 7805, 7805, 7805, -1, + 7806, 7806, 7806, -1, 7807, 7807, 7807, -1, + 7808, 7808, 7808, -1, 7809, 7809, 7809, -1, + 7810, 7810, 7810, -1, 7811, 7811, 7811, -1, + 7812, 7812, 7812, -1, 7813, 7813, 7813, -1, + 7814, 7814, 7814, -1, 7815, 7815, 7815, -1, + 7816, 7816, 7816, -1, 7817, 7817, 7817, -1, + 7818, 7818, 7818, -1, 7819, 7819, 7819, -1, + 7820, 7820, 7820, -1, 7821, 7821, 7821, -1, + 7822, 7822, 7822, -1, 7823, 7823, 7823, -1, + 7824, 7824, 7824, -1, 7825, 7825, 7825, -1, + 7826, 7826, 7826, -1, 7827, 7827, 7827, -1, + 7828, 7828, 7828, -1, 7829, 7829, 7829, -1, + 7830, 7830, 7830, -1, 7831, 7831, 7831, -1, + 7832, 7832, 7832, -1, 7833, 7833, 7833, -1, + 7834, 7834, 7834, -1, 7835, 7835, 7835, -1, + 7836, 7836, 7836, -1, 7837, 7837, 7837, -1, + 7838, 7838, 7838, -1, 7839, 7839, 7839, -1, + 7840, 7840, 7840, -1, 7841, 7841, 7841, -1, + 7842, 7842, 7842, -1, 7843, 7843, 7843, -1, + 7844, 7844, 7844, -1, 7845, 7845, 7845, -1, + 7846, 7846, 7846, -1, 7847, 7847, 7847, -1, + 7848, 7848, 7848, -1, 7849, 7849, 7849, -1, + 7850, 7850, 7850, -1, 7851, 7851, 7851, -1, + 7852, 7852, 7852, -1, 7853, 7853, 7853, -1, + 7854, 7854, 7854, -1, 7855, 7855, 7855, -1, + 7856, 7856, 7856, -1, 7857, 7857, 7857, -1, + 7858, 7858, 7858, -1, 7859, 7859, 7859, -1, + 7860, 7860, 7860, -1, 7861, 7861, 7861, -1, + 7862, 7862, 7862, -1, 7863, 7863, 7863, -1, + 7864, 7864, 7864, -1, 7865, 7865, 7865, -1, + 7866, 7866, 7866, -1, 7867, 7867, 7867, -1, + 7868, 7868, 7868, -1, 7869, 7869, 7869, -1, + 7870, 7870, 7870, -1, 7871, 7871, 7871, -1, + 7872, 7872, 7872, -1, 7873, 7873, 7873, -1, + 7874, 7874, 7874, -1, 7875, 7875, 7875, -1, + 7876, 7876, 7876, -1, 7877, 7877, 7877, -1, + 7878, 7878, 7878, -1, 7879, 7879, 7879, -1, + 7880, 7880, 7880, -1, 7881, 7881, 7881, -1, + 7882, 7882, 7882, -1, 7883, 7883, 7883, -1, + 7884, 7884, 7884, -1, 7885, 7885, 7885, -1, + 7886, 7886, 7886, -1, 7887, 7887, 7887, -1, + 7888, 7888, 7888, -1, 7889, 7889, 7889, -1, + 7890, 7890, 7890, -1, 7891, 7891, 7891, -1, + 7892, 7892, 7892, -1, 7893, 7893, 7893, -1, + 7894, 7894, 7894, -1, 7895, 7895, 7895, -1, + 7896, 7896, 7896, -1, 7897, 7897, 7897, -1, + 7898, 7898, 7898, -1, 7899, 7899, 7899, -1, + 7900, 7900, 7900, -1, 7901, 7901, 7901, -1, + 7902, 7902, 7902, -1, 7903, 7903, 7903, -1, + 7904, 7904, 7904, -1, 7905, 7905, 7905, -1, + 7906, 7906, 7906, -1, 7907, 7907, 7907, -1, + 7908, 7908, 7908, -1, 7909, 7909, 7909, -1, + 7910, 7910, 7910, -1, 7911, 7911, 7911, -1, + 7912, 7912, 7912, -1, 7913, 7913, 7913, -1, + 7914, 7914, 7914, -1, 7915, 7915, 7915, -1, + 7916, 7916, 7916, -1, 7917, 7917, 7917, -1, + 7918, 7918, 7918, -1, 7919, 7919, 7919, -1, + 7920, 7920, 7920, -1, 7921, 7921, 7921, -1, + 7922, 7922, 7922, -1, 7923, 7923, 7923, -1, + 7924, 7924, 7924, -1, 7925, 7925, 7925, -1, + 7926, 7926, 7926, -1, 7927, 7927, 7927, -1, + 7928, 7928, 7928, -1, 7929, 7929, 7929, -1, + 7930, 7930, 7930, -1, 7931, 7931, 7931, -1, + 7932, 7932, 7932, -1, 7933, 7933, 7933, -1, + 7934, 7934, 7934, -1, 7935, 7935, 7935, -1, + 7936, 7936, 7936, -1, 7937, 7937, 7937, -1, + 7938, 7938, 7938, -1, 7939, 7939, 7939, -1, + 7940, 7940, 7940, -1, 7941, 7941, 7941, -1, + 7942, 7942, 7942, -1, 7943, 7943, 7943, -1, + 7944, 7944, 7944, -1, 7945, 7945, 7945, -1, + 7946, 7946, 7946, -1, 7947, 7947, 7947, -1, + 7948, 7948, 7948, -1, 7949, 7949, 7949, -1, + 7950, 7950, 7950, -1, 7951, 7951, 7951, -1, + 7952, 7952, 7952, -1, 7953, 7953, 7953, -1, + 7954, 7954, 7954, -1, 7955, 7955, 7955, -1, + 7956, 7956, 7956, -1, 7957, 7957, 7957, -1, + 7958, 7958, 7958, -1, 7959, 7959, 7959, -1, + 7960, 7960, 7960, -1, 7961, 7961, 7961, -1, + 7962, 7962, 7962, -1, 7963, 7963, 7963, -1, + 7964, 7964, 7964, -1, 7965, 7965, 7965, -1, + 7966, 7966, 7966, -1, 7967, 7967, 7967, -1, + 7968, 7968, 7968, -1, 7969, 7969, 7969, -1, + 7970, 7970, 7970, -1, 7971, 7971, 7971, -1, + 7972, 7972, 7972, -1, 7973, 7973, 7973, -1, + 7974, 7974, 7974, -1, 7975, 7975, 7975, -1, + 7976, 7976, 7976, -1, 7977, 7977, 7977, -1, + 7978, 7978, 7978, -1, 7979, 7979, 7979, -1, + 7980, 7980, 7980, -1, 7981, 7981, 7981, -1, + 7982, 7982, 7982, -1, 7983, 7983, 7983, -1, + 7984, 7984, 7984, -1, 7985, 7985, 7985, -1, + 7986, 7986, 7986, -1, 7987, 7987, 7987, -1, + 7988, 7988, 7988, -1, 7989, 7989, 7989, -1, + 7990, 7990, 7990, -1, 7991, 7991, 7991, -1, + 7992, 7992, 7992, -1, 7993, 7993, 7993, -1, + 7994, 7994, 7994, -1, 7995, 7995, 7995, -1, + 7996, 7996, 7996, -1, 7997, 7997, 7997, -1, + 7998, 7998, 7998, -1, 7999, 7999, 7999, -1, + 8000, 8000, 8000, -1, 8001, 8001, 8001, -1, + 8002, 8002, 8002, -1, 8003, 8003, 8003, -1, + 8004, 8004, 8004, -1, 8005, 8005, 8005, -1, + 8006, 8006, 8006, -1, 8007, 8007, 8007, -1, + 8008, 8008, 8008, -1, 8009, 8009, 8009, -1, + 8010, 8010, 8010, -1, 8011, 8011, 8011, -1, + 8012, 8012, 8012, -1, 8013, 8013, 8013, -1, + 8014, 8014, 8014, -1, 8015, 8015, 8015, -1, + 8016, 8016, 8016, -1, 8017, 8017, 8017, -1, + 8018, 8018, 8018, -1, 8019, 8019, 8019, -1, + 8020, 8020, 8020, -1, 8021, 8021, 8021, -1, + 8022, 8022, 8022, -1, 8023, 8023, 8023, -1, + 8024, 8024, 8024, -1, 8025, 8025, 8025, -1, + 8026, 8026, 8026, -1, 8027, 8027, 8027, -1, + 8028, 8028, 8028, -1, 8029, 8029, 8029, -1, + 8030, 8030, 8030, -1, 8031, 8031, 8031, -1, + 8032, 8032, 8032, -1, 8033, 8033, 8033, -1, + 8034, 8034, 8034, -1, 8035, 8035, 8035, -1, + 8036, 8036, 8036, -1, 8037, 8037, 8037, -1, + 8038, 8038, 8038, -1, 8039, 8039, 8039, -1, + 8040, 8040, 8040, -1, 8041, 8041, 8041, -1, + 8042, 8042, 8042, -1, 8043, 8043, 8043, -1, + 8044, 8044, 8044, -1, 8045, 8045, 8045, -1, + 8046, 8046, 8046, -1, 8047, 8047, 8047, -1, + 8048, 8048, 8048, -1, 8049, 8049, 8049, -1, + 8050, 8050, 8050, -1, 8051, 8051, 8051, -1, + 8052, 8052, 8052, -1, 8053, 8053, 8053, -1, + 8054, 8054, 8054, -1, 8055, 8055, 8055, -1, + 8056, 8056, 8056, -1, 8057, 8057, 8057, -1, + 8058, 8058, 8058, -1, 8059, 8059, 8059, -1, + 8060, 8060, 8060, -1, 8061, 8061, 8061, -1, + 8062, 8062, 8062, -1, 8063, 8063, 8063, -1, + 8064, 8064, 8064, -1, 8065, 8065, 8065, -1, + 8066, 8066, 8066, -1, 8067, 8067, 8067, -1, + 8068, 8068, 8068, -1, 8069, 8069, 8069, -1, + 8070, 8070, 8070, -1, 8071, 8071, 8071, -1, + 8072, 8072, 8072, -1, 8073, 8073, 8073, -1, + 8074, 8074, 8074, -1, 8075, 8075, 8075, -1, + 8076, 8076, 8076, -1, 8077, 8077, 8077, -1, + 8078, 8078, 8078, -1, 8079, 8079, 8079, -1, + 8080, 8080, 8080, -1, 8081, 8081, 8081, -1, + 8082, 8082, 8082, -1, 8083, 8083, 8083, -1, + 8084, 8084, 8084, -1, 8085, 8085, 8085, -1, + 8086, 8086, 8086, -1, 8087, 8087, 8087, -1, + 8088, 8088, 8088, -1, 8089, 8089, 8089, -1, + 8090, 8090, 8090, -1, 8091, 8091, 8091, -1, + 8092, 8092, 8092, -1, 8093, 8093, 8093, -1, + 8094, 8094, 8094, -1, 8095, 8095, 8095, -1, + 8096, 8096, 8096, -1, 8097, 8097, 8097, -1, + 8098, 8098, 8098, -1, 8099, 8099, 8099, -1, + 8100, 8100, 8100, -1, 8101, 8101, 8101, -1, + 8102, 8102, 8102, -1, 8103, 8103, 8103, -1, + 8104, 8104, 8104, -1, 8105, 8105, 8105, -1, + 8106, 8106, 8106, -1, 8107, 8107, 8107, -1, + 8108, 8108, 8108, -1, 8109, 8109, 8109, -1, + 8110, 8110, 8110, -1, 8111, 8111, 8111, -1, + 8112, 8112, 8112, -1, 8113, 8113, 8113, -1, + 8114, 8114, 8114, -1, 8115, 8115, 8115, -1, + 8116, 8116, 8116, -1, 8117, 8117, 8117, -1, + 8118, 8118, 8118, -1, 8119, 8119, 8119, -1, + 8120, 8120, 8120, -1, 8121, 8121, 8121, -1, + 8122, 8122, 8122, -1, 8123, 8123, 8123, -1, + 8124, 8124, 8124, -1, 8125, 8125, 8125, -1, + 8126, 8126, 8126, -1, 8127, 8127, 8127, -1, + 8128, 8128, 8128, -1, 8129, 8129, 8129, -1, + 8130, 8130, 8130, -1, 8131, 8131, 8131, -1, + 8132, 8132, 8132, -1, 8133, 8133, 8133, -1, + 8134, 8134, 8134, -1, 8135, 8135, 8135, -1, + 8136, 8136, 8136, -1, 8137, 8137, 8137, -1, + 8138, 8138, 8138, -1, 8139, 8139, 8139, -1, + 8140, 8140, 8140, -1, 8141, 8141, 8141, -1, + 8142, 8142, 8142, -1, 8143, 8143, 8143, -1, + 8144, 8144, 8144, -1, 8145, 8145, 8145, -1, + 8146, 8146, 8146, -1, 8147, 8147, 8147, -1, + 8148, 8148, 8148, -1, 8149, 8149, 8149, -1, + 8150, 8150, 8150, -1, 8151, 8151, 8151, -1, + 8152, 8152, 8152, -1, 8153, 8153, 8153, -1, + 8154, 8154, 8154, -1, 8155, 8155, 8155, -1, + 8156, 8156, 8156, -1, 8157, 8157, 8157, -1, + 8158, 8158, 8158, -1, 8159, 8159, 8159, -1, + 8160, 8160, 8160, -1, 8161, 8161, 8161, -1, + 8162, 8162, 8162, -1, 8163, 8163, 8163, -1, + 8164, 8164, 8164, -1, 8165, 8165, 8165, -1, + 8166, 8166, 8166, -1, 8167, 8167, 8167, -1, + 8168, 8168, 8168, -1, 8169, 8169, 8169, -1, + 8170, 8170, 8170, -1, 8171, 8171, 8171, -1, + 8172, 8172, 8172, -1, 8173, 8173, 8173, -1, + 8174, 8174, 8174, -1, 8175, 8175, 8175, -1, + 8176, 8176, 8176, -1, 8177, 8177, 8177, -1, + 8178, 8178, 8178, -1, 8179, 8179, 8179, -1, + 8180, 8180, 8180, -1, 8181, 8181, 8181, -1, + 8182, 8182, 8182, -1, 8183, 8183, 8183, -1, + 8184, 8184, 8184, -1, 8185, 8185, 8185, -1, + 8186, 8186, 8186, -1, 8187, 8187, 8187, -1, + 8188, 8188, 8188, -1, 8189, 8189, 8189, -1, + 8190, 8190, 8190, -1, 8191, 8191, 8191, -1, + 8192, 8192, 8192, -1, 8193, 8193, 8193, -1, + 8194, 8194, 8194, -1, 8195, 8195, 8195, -1, + 8196, 8196, 8196, -1, 8197, 8197, 8197, -1, + 8198, 8198, 8198, -1, 8199, 8199, 8199, -1, + 8200, 8200, 8200, -1, 8201, 8201, 8201, -1, + 8202, 8202, 8202, -1, 8203, 8203, 8203, -1, + 8204, 8204, 8204, -1, 8205, 8205, 8205, -1, + 8206, 8206, 8206, -1, 8207, 8207, 8207, -1, + 8208, 8208, 8208, -1, 8209, 8209, 8209, -1, + 8210, 8210, 8210, -1, 8211, 8211, 8211, -1, + 8212, 8212, 8212, -1, 8213, 8213, 8213, -1, + 8214, 8214, 8214, -1, 8215, 8215, 8215, -1, + 8216, 8216, 8216, -1, 8217, 8217, 8217, -1, + 8218, 8218, 8218, -1, 8219, 8219, 8219, -1, + 8220, 8220, 8220, -1, 8221, 8221, 8221, -1, + 8222, 8222, 8222, -1, 8223, 8223, 8223, -1, + 8224, 8224, 8224, -1, 8225, 8225, 8225, -1, + 8226, 8226, 8226, -1, 8227, 8227, 8227, -1, + 8228, 8228, 8228, -1, 8229, 8229, 8229, -1, + 8230, 8230, 8230, -1, 8231, 8231, 8231, -1, + 8232, 8232, 8232, -1, 8233, 8233, 8233, -1, + 8234, 8234, 8234, -1, 8235, 8235, 8235, -1, + 8236, 8236, 8236, -1, 8237, 8237, 8237, -1, + 8238, 8238, 8238, -1, 8239, 8239, 8239, -1, + 8240, 8240, 8240, -1, 8241, 8241, 8241, -1, + 8242, 8242, 8242, -1, 8243, 8243, 8243, -1, + 8244, 8244, 8244, -1, 8245, 8245, 8245, -1, + 8246, 8246, 8246, -1, 8247, 8247, 8247, -1, + 8248, 8248, 8248, -1, 8249, 8249, 8249, -1, + 8250, 8250, 8250, -1, 8251, 8251, 8251, -1, + 8252, 8252, 8252, -1, 8253, 8253, 8253, -1, + 8254, 8254, 8254, -1, 8255, 8255, 8255, -1, + 8256, 8256, 8256, -1, 8257, 8257, 8257, -1, + 8258, 8258, 8258, -1, 8259, 8259, 8259, -1, + 8260, 8260, 8260, -1, 8261, 8261, 8261, -1, + 8262, 8262, 8262, -1, 8263, 8263, 8263, -1, + 8264, 8264, 8264, -1, 8265, 8265, 8265, -1, + 8266, 8266, 8266, -1, 8267, 8267, 8267, -1, + 8268, 8268, 8268, -1, 8269, 8269, 8269, -1, + 8270, 8270, 8270, -1, 8271, 8271, 8271, -1, + 8272, 8272, 8272, -1, 8273, 8273, 8273, -1, + 8274, 8274, 8274, -1, 8275, 8275, 8275, -1, + 8276, 8276, 8276, -1, 8277, 8277, 8277, -1, + 8278, 8278, 8278, -1, 8279, 8279, 8279, -1, + 8280, 8280, 8280, -1, 8281, 8281, 8281, -1, + 8282, 8282, 8282, -1, 8283, 8283, 8283, -1, + 8284, 8284, 8284, -1, 8285, 8285, 8285, -1, + 8286, 8286, 8286, -1, 8287, 8287, 8287, -1, + 8288, 8288, 8288, -1, 8289, 8289, 8289, -1, + 8290, 8290, 8290, -1, 8291, 8291, 8291, -1, + 8292, 8292, 8292, -1, 8293, 8293, 8293, -1, + 8294, 8294, 8294, -1, 8295, 8295, 8295, -1, + 8296, 8296, 8296, -1, 8297, 8297, 8297, -1, + 8298, 8298, 8298, -1, 8299, 8299, 8299, -1, + 8300, 8300, 8300, -1, 8301, 8301, 8301, -1, + 8302, 8302, 8302, -1, 8303, 8303, 8303, -1, + 8304, 8304, 8304, -1, 8305, 8305, 8305, -1, + 8306, 8306, 8306, -1, 8307, 8307, 8307, -1, + 8308, 8308, 8308, -1, 8309, 8309, 8309, -1, + 8310, 8310, 8310, -1, 8311, 8311, 8311, -1, + 8312, 8312, 8312, -1, 8313, 8313, 8313, -1, + 8314, 8314, 8314, -1, 8315, 8315, 8315, -1, + 8316, 8316, 8316, -1, 8317, 8317, 8317, -1, + 8318, 8318, 8318, -1, 8319, 8319, 8319, -1, + 8320, 8320, 8320, -1, 8321, 8321, 8321, -1, + 8322, 8322, 8322, -1, 8323, 8323, 8323, -1, + 8324, 8324, 8324, -1, 8325, 8325, 8325, -1, + 8326, 8326, 8326, -1, 8327, 8327, 8327, -1, + 8328, 8328, 8328, -1, 8329, 8329, 8329, -1, + 8330, 8330, 8330, -1, 8331, 8331, 8331, -1, + 8332, 8332, 8332, -1, 8333, 8333, 8333, -1, + 8334, 8334, 8334, -1, 8335, 8335, 8335, -1, + 8336, 8336, 8336, -1, 8337, 8337, 8337, -1, + 8338, 8338, 8338, -1, 8339, 8339, 8339, -1, + 8340, 8340, 8340, -1, 8341, 8341, 8341, -1, + 8342, 8342, 8342, -1, 8343, 8343, 8343, -1, + 8344, 8344, 8344, -1, 8345, 8345, 8345, -1, + 8346, 8346, 8346, -1, 8347, 8347, 8347, -1, + 8348, 8348, 8348, -1, 8349, 8349, 8349, -1, + 8350, 8350, 8350, -1, 8351, 8351, 8351, -1, + 8352, 8352, 8352, -1, 8353, 8353, 8353, -1, + 8354, 8354, 8354, -1, 8355, 8355, 8355, -1, + 8356, 8356, 8356, -1, 8357, 8357, 8357, -1, + 8358, 8358, 8358, -1, 8359, 8359, 8359, -1, + 8360, 8360, 8360, -1, 8361, 8361, 8361, -1, + 8362, 8362, 8362, -1, 8363, 8363, 8363, -1, + 8364, 8364, 8364, -1, 8365, 8365, 8365, -1, + 8366, 8366, 8366, -1, 8367, 8367, 8367, -1, + 8368, 8368, 8368, -1, 8369, 8369, 8369, -1, + 8370, 8370, 8370, -1, 8371, 8371, 8371, -1, + 8372, 8372, 8372, -1, 8373, 8373, 8373, -1, + 8374, 8374, 8374, -1, 8375, 8375, 8375, -1, + 8376, 8376, 8376, -1, 8377, 8377, 8377, -1, + 8378, 8378, 8378, -1, 8379, 8379, 8379, -1, + 8380, 8380, 8380, -1, 8381, 8381, 8381, -1, + 8382, 8382, 8382, -1, 8383, 8383, 8383, -1, + 8384, 8384, 8384, -1, 8385, 8385, 8385, -1, + 8386, 8386, 8386, -1, 8387, 8387, 8387, -1, + 8388, 8388, 8388, -1, 8389, 8389, 8389, -1, + 8390, 8390, 8390, -1, 8391, 8391, 8391, -1, + 8392, 8392, 8392, -1, 8393, 8393, 8393, -1, + 8394, 8394, 8394, -1, 8395, 8395, 8395, -1, + 8396, 8396, 8396, -1, 8397, 8397, 8397, -1, + 8398, 8398, 8398, -1, 8399, 8399, 8399, -1, + 8400, 8400, 8400, -1, 8401, 8401, 8401, -1, + 8402, 8402, 8402, -1, 8403, 8403, 8403, -1, + 8404, 8404, 8404, -1, 8405, 8405, 8405, -1, + 8406, 8406, 8406, -1, 8407, 8407, 8407, -1, + 8408, 8408, 8408, -1, 8409, 8409, 8409, -1, + 8410, 8410, 8410, -1, 8411, 8411, 8411, -1, + 8412, 8412, 8412, -1, 8413, 8413, 8413, -1, + 8414, 8414, 8414, -1, 8415, 8415, 8415, -1, + 8416, 8416, 8416, -1, 8417, 8417, 8417, -1, + 8418, 8418, 8418, -1, 8419, 8419, 8419, -1, + 8420, 8420, 8420, -1, 8421, 8421, 8421, -1, + 8422, 8422, 8422, -1, 8423, 8423, 8423, -1, + 8424, 8424, 8424, -1, 8425, 8425, 8425, -1, + 8426, 8426, 8426, -1, 8427, 8427, 8427, -1, + 8428, 8428, 8428, -1, 8429, 8429, 8429, -1, + 8430, 8430, 8430, -1, 8431, 8431, 8431, -1, + 8432, 8432, 8432, -1, 8433, 8433, 8433, -1, + 8434, 8434, 8434, -1, 8435, 8435, 8435, -1, + 8436, 8436, 8436, -1, 8437, 8437, 8437, -1, + 8438, 8438, 8438, -1, 8439, 8439, 8439, -1, + 8440, 8440, 8440, -1, 8441, 8441, 8441, -1, + 8442, 8442, 8442, -1, 8443, 8443, 8443, -1, + 8444, 8444, 8444, -1, 8445, 8445, 8445, -1, + 8446, 8446, 8446, -1, 8447, 8447, 8447, -1, + 8448, 8448, 8448, -1, 8449, 8449, 8449, -1, + 8450, 8450, 8450, -1, 8451, 8451, 8451, -1, + 8452, 8452, 8452, -1, 8453, 8453, 8453, -1, + 8454, 8454, 8454, -1, 8455, 8455, 8455, -1, + 8456, 8456, 8456, -1, 8457, 8457, 8457, -1, + 8458, 8458, 8458, -1, 8459, 8459, 8459, -1, + 8460, 8460, 8460, -1, 8461, 8461, 8461, -1, + 8462, 8462, 8462, -1, 8463, 8463, 8463, -1, + 8464, 8464, 8464, -1, 8465, 8465, 8465, -1, + 8466, 8466, 8466, -1, 8467, 8467, 8467, -1, + 8468, 8468, 8468, -1, 8469, 8469, 8469, -1, + 8470, 8470, 8470, -1, 8471, 8471, 8471, -1, + 8472, 8472, 8472, -1, 8473, 8473, 8473, -1, + 8474, 8474, 8474, -1, 8475, 8475, 8475, -1, + 8476, 8476, 8476, -1, 8477, 8477, 8477, -1, + 8478, 8478, 8478, -1, 8479, 8479, 8479, -1, + 8480, 8480, 8480, -1, 8481, 8481, 8481, -1, + 8482, 8482, 8482, -1, 8483, 8483, 8483, -1, + 8484, 8484, 8484, -1, 8485, 8485, 8485, -1, + 8486, 8486, 8486, -1, 8487, 8487, 8487, -1, + 8488, 8488, 8488, -1, 8489, 8489, 8489, -1, + 8490, 8490, 8490, -1, 8491, 8491, 8491, -1, + 8492, 8492, 8492, -1, 8493, 8493, 8493, -1, + 8494, 8494, 8494, -1, 8495, 8495, 8495, -1, + 8496, 8496, 8496, -1, 8497, 8497, 8497, -1, + 8498, 8498, 8498, -1, 8499, 8499, 8499, -1, + 8500, 8500, 8500, -1, 8501, 8501, 8501, -1, + 8502, 8502, 8502, -1, 8503, 8503, 8503, -1, + 8504, 8504, 8504, -1, 8505, 8505, 8505, -1, + 8506, 8506, 8506, -1, 8507, 8507, 8507, -1, + 8508, 8508, 8508, -1, 8509, 8509, 8509, -1, + 8510, 8510, 8510, -1, 8511, 8511, 8511, -1, + 8512, 8512, 8512, -1, 8513, 8513, 8513, -1, + 8514, 8514, 8514, -1, 8515, 8515, 8515, -1, + 8516, 8516, 8516, -1, 8517, 8517, 8517, -1, + 8518, 8518, 8518, -1, 8519, 8519, 8519, -1, + 8520, 8520, 8520, -1, 8521, 8521, 8521, -1, + 8522, 8522, 8522, -1, 8523, 8523, 8523, -1, + 8524, 8524, 8524, -1, 8525, 8525, 8525, -1, + 8526, 8526, 8526, -1, 8527, 8527, 8527, -1, + 8528, 8528, 8528, -1, 8529, 8529, 8529, -1, + 8530, 8530, 8530, -1, 8531, 8531, 8531, -1, + 8532, 8532, 8532, -1, 8533, 8533, 8533, -1, + 8534, 8534, 8534, -1, 8535, 8535, 8535, -1, + 8536, 8536, 8536, -1, 8537, 8537, 8537, -1, + 8538, 8538, 8538, -1, 8539, 8539, 8539, -1, + 8540, 8540, 8540, -1, 8541, 8541, 8541, -1, + 8542, 8542, 8542, -1, 8543, 8543, 8543, -1, + 8544, 8544, 8544, -1, 8545, 8545, 8545, -1, + 8546, 8546, 8546, -1, 8547, 8547, 8547, -1, + 8548, 8548, 8548, -1, 8549, 8549, 8549, -1, + 8550, 8550, 8550, -1, 8551, 8551, 8551, -1, + 8552, 8552, 8552, -1, 8553, 8553, 8553, -1, + 8554, 8554, 8554, -1, 8555, 8555, 8555, -1, + 8556, 8556, 8556, -1, 8557, 8557, 8557, -1, + 8558, 8558, 8558, -1, 8559, 8559, 8559, -1, + 8560, 8560, 8560, -1, 8561, 8561, 8561, -1, + 8562, 8562, 8562, -1, 8563, 8563, 8563, -1, + 8564, 8564, 8564, -1, 8565, 8565, 8565, -1, + 8566, 8566, 8566, -1, 8567, 8567, 8567, -1, + 8568, 8568, 8568, -1, 8569, 8569, 8569, -1, + 8570, 8570, 8570, -1, 8571, 8571, 8571, -1, + 8572, 8572, 8572, -1, 8573, 8573, 8573, -1, + 8574, 8574, 8574, -1, 8575, 8575, 8575, -1, + 8576, 8576, 8576, -1, 8577, 8577, 8577, -1, + 8578, 8578, 8578, -1, 8579, 8579, 8579, -1, + 8580, 8580, 8580, -1, 8581, 8581, 8581, -1, + 8582, 8582, 8582, -1, 8583, 8583, 8583, -1, + 8584, 8584, 8584, -1, 8585, 8585, 8585, -1, + 8586, 8586, 8586, -1, 8587, 8587, 8587, -1, + 8588, 8588, 8588, -1, 8589, 8589, 8589, -1, + 8590, 8590, 8590, -1, 8591, 8591, 8591, -1, + 8592, 8592, 8592, -1, 8593, 8593, 8593, -1, + 8594, 8594, 8594, -1, 8595, 8595, 8595, -1, + 8596, 8596, 8596, -1, 8597, 8597, 8597, -1, + 8598, 8598, 8598, -1, 8599, 8599, 8599, -1, + 8600, 8600, 8600, -1, 8601, 8601, 8601, -1, + 8602, 8602, 8602, -1, 8603, 8603, 8603, -1, + 8604, 8604, 8604, -1, 8605, 8605, 8605, -1, + 8606, 8606, 8606, -1, 8607, 8607, 8607, -1, + 8608, 8608, 8608, -1, 8609, 8609, 8609, -1, + 8610, 8610, 8610, -1, 8611, 8611, 8611, -1, + 8612, 8612, 8612, -1, 8613, 8613, 8613, -1, + 8614, 8614, 8614, -1, 8615, 8615, 8615, -1, + 8616, 8616, 8616, -1, 8617, 8617, 8617, -1, + 8618, 8618, 8618, -1, 8619, 8619, 8619, -1, + 8620, 8620, 8620, -1, 8621, 8621, 8621, -1, + 8622, 8622, 8622, -1, 8623, 8623, 8623, -1, + 8624, 8624, 8624, -1, 8625, 8625, 8625, -1, + 8626, 8626, 8626, -1, 8627, 8627, 8627, -1, + 8628, 8628, 8628, -1, 8629, 8629, 8629, -1, + 8630, 8630, 8630, -1, 8631, 8631, 8631, -1, + 8632, 8632, 8632, -1, 8633, 8633, 8633, -1, + 8634, 8634, 8634, -1, 8635, 8635, 8635, -1, + 8636, 8636, 8636, -1, 8637, 8637, 8637, -1, + 8638, 8638, 8638, -1, 8639, 8639, 8639, -1, + 8640, 8640, 8640, -1, 8641, 8641, 8641, -1, + 8642, 8642, 8642, -1, 8643, 8643, 8643, -1, + 8644, 8644, 8644, -1, 8645, 8645, 8645, -1, + 8646, 8646, 8646, -1, 8647, 8647, 8647, -1, + 8648, 8648, 8648, -1, 8649, 8649, 8649, -1, + 8650, 8650, 8650, -1, 8651, 8651, 8651, -1, + 8652, 8652, 8652, -1, 8653, 8653, 8653, -1, + 8654, 8654, 8654, -1, 8655, 8655, 8655, -1, + 8656, 8656, 8656, -1, 8657, 8657, 8657, -1, + 8658, 8658, 8658, -1, 8659, 8659, 8659, -1, + 8660, 8660, 8660, -1, 8661, 8661, 8661, -1, + 8662, 8662, 8662, -1, 8663, 8663, 8663, -1, + 8664, 8664, 8664, -1, 8665, 8665, 8665, -1, + 8666, 8666, 8666, -1, 8667, 8667, 8667, -1, + 8668, 8668, 8668, -1, 8669, 8669, 8669, -1, + 8670, 8670, 8670, -1, 8671, 8671, 8671, -1, + 8672, 8672, 8672, -1, 8673, 8673, 8673, -1, + 8674, 8674, 8674, -1, 8675, 8675, 8675, -1, + 8676, 8676, 8676, -1, 8677, 8677, 8677, -1, + 8678, 8678, 8678, -1, 8679, 8679, 8679, -1, + 8680, 8680, 8680, -1, 8681, 8681, 8681, -1, + 8682, 8682, 8682, -1, 8683, 8683, 8683, -1, + 8684, 8684, 8684, -1, 8685, 8685, 8685, -1, + 8686, 8686, 8686, -1, 8687, 8687, 8687, -1, + 8688, 8688, 8688, -1, 8689, 8689, 8689, -1, + 8690, 8690, 8690, -1, 8691, 8691, 8691, -1, + 8692, 8692, 8692, -1, 8693, 8693, 8693, -1, + 8694, 8694, 8694, -1, 8695, 8695, 8695, -1, + 8696, 8696, 8696, -1, 8697, 8697, 8697, -1, + 8698, 8698, 8698, -1, 8699, 8699, 8699, -1, + 8700, 8700, 8700, -1, 8701, 8701, 8701, -1, + 8702, 8702, 8702, -1, 8703, 8703, 8703, -1, + 8704, 8704, 8704, -1, 8705, 8705, 8705, -1, + 8706, 8706, 8706, -1, 8707, 8707, 8707, -1, + 8708, 8708, 8708, -1, 8709, 8709, 8709, -1, + 8710, 8710, 8710, -1, 8711, 8711, 8711, -1, + 8712, 8712, 8712, -1, 8713, 8713, 8713, -1, + 8714, 8714, 8714, -1, 8715, 8715, 8715, -1, + 8716, 8716, 8716, -1, 8717, 8717, 8717, -1, + 8718, 8718, 8718, -1, 8719, 8719, 8719, -1, + 8720, 8720, 8720, -1, 8721, 8721, 8721, -1, + 8722, 8722, 8722, -1, 8723, 8723, 8723, -1, + 8724, 8724, 8724, -1, 8725, 8725, 8725, -1, + 8726, 8726, 8726, -1, 8727, 8727, 8727, -1, + 8728, 8728, 8728, -1, 8729, 8729, 8729, -1, + 8730, 8730, 8730, -1, 8731, 8731, 8731, -1, + 8732, 8732, 8732, -1, 8733, 8733, 8733, -1, + 8734, 8734, 8734, -1, 8735, 8735, 8735, -1, + 8736, 8736, 8736, -1, 8737, 8737, 8737, -1, + 8738, 8738, 8738, -1, 8739, 8739, 8739, -1, + 8740, 8740, 8740, -1, 8741, 8741, 8741, -1, + 8742, 8742, 8742, -1, 8743, 8743, 8743, -1, + 8744, 8744, 8744, -1, 8745, 8745, 8745, -1, + 8746, 8746, 8746, -1, 8747, 8747, 8747, -1, + 8748, 8748, 8748, -1, 8749, 8749, 8749, -1, + 8750, 8750, 8750, -1, 8751, 8751, 8751, -1, + 8752, 8752, 8752, -1, 8753, 8753, 8753, -1, + 8754, 8754, 8754, -1, 8755, 8755, 8755, -1, + 8756, 8756, 8756, -1, 8757, 8757, 8757, -1, + 8758, 8758, 8758, -1, 8759, 8759, 8759, -1, + 8760, 8760, 8760, -1, 8761, 8761, 8761, -1, + 8762, 8762, 8762, -1, 8763, 8763, 8763, -1, + 8764, 8764, 8764, -1, 8765, 8765, 8765, -1, + 8766, 8766, 8766, -1, 8767, 8767, 8767, -1, + 8768, 8768, 8768, -1, 8769, 8769, 8769, -1, + 8770, 8770, 8770, -1, 8771, 8771, 8771, -1, + 8772, 8772, 8772, -1, 8773, 8773, 8773, -1, + 8774, 8774, 8774, -1, 8775, 8775, 8775, -1, + 8776, 8776, 8776, -1, 8777, 8777, 8777, -1, + 8778, 8778, 8778, -1, 8779, 8779, 8779, -1, + 8780, 8780, 8780, -1, 8781, 8781, 8781, -1, + 8782, 8782, 8782, -1, 8783, 8783, 8783, -1, + 8784, 8784, 8784, -1, 8785, 8785, 8785, -1, + 8786, 8786, 8786, -1, 8787, 8787, 8787, -1, + 8788, 8788, 8788, -1, 8789, 8789, 8789, -1, + 8790, 8790, 8790, -1, 8791, 8791, 8791, -1, + 8792, 8792, 8792, -1, 8793, 8793, 8793, -1, + 8794, 8794, 8794, -1, 8795, 8795, 8795, -1, + 8796, 8796, 8796, -1, 8797, 8797, 8797, -1, + 8798, 8798, 8798, -1, 8799, 8799, 8799, -1, + 8800, 8800, 8800, -1, 8801, 8801, 8801, -1, + 8802, 8802, 8802, -1, 8803, 8803, 8803, -1, + 8804, 8804, 8804, -1, 8805, 8805, 8805, -1, + 8806, 8806, 8806, -1, 8807, 8807, 8807, -1, + 8808, 8808, 8808, -1, 8809, 8809, 8809, -1, + 8810, 8810, 8810, -1, 8811, 8811, 8811, -1, + 8812, 8812, 8812, -1, 8813, 8813, 8813, -1, + 8814, 8814, 8814, -1, 8815, 8815, 8815, -1, + 8816, 8816, 8816, -1, 8817, 8817, 8817, -1, + 8818, 8818, 8818, -1, 8819, 8819, 8819, -1, + 8820, 8820, 8820, -1, 8821, 8821, 8821, -1, + 8822, 8822, 8822, -1, 8823, 8823, 8823, -1, + 8824, 8824, 8824, -1, 8825, 8825, 8825, -1, + 8826, 8826, 8826, -1, 8827, 8827, 8827, -1, + 8828, 8828, 8828, -1, 8829, 8829, 8829, -1, + 8830, 8830, 8830, -1, 8831, 8831, 8831, -1, + 8832, 8832, 8832, -1, 8833, 8833, 8833, -1, + 8834, 8834, 8834, -1, 8835, 8835, 8835, -1, + 8836, 8836, 8836, -1, 8837, 8837, 8837, -1, + 8838, 8838, 8838, -1, 8839, 8839, 8839, -1, + 8840, 8840, 8840, -1, 8841, 8841, 8841, -1, + 8842, 8842, 8842, -1, 8843, 8843, 8843, -1, + 8844, 8844, 8844, -1, 8845, 8845, 8845, -1, + 8846, 8846, 8846, -1, 8847, 8847, 8847, -1, + 8848, 8848, 8848, -1, 8849, 8849, 8849, -1, + 8850, 8850, 8850, -1, 8851, 8851, 8851, -1, + 8852, 8852, 8852, -1, 8853, 8853, 8853, -1, + 8854, 8854, 8854, -1, 8855, 8855, 8855, -1, + 8856, 8856, 8856, -1, 8857, 8857, 8857, -1, + 8858, 8858, 8858, -1, 8859, 8859, 8859, -1, + 8860, 8860, 8860, -1, 8861, 8861, 8861, -1, + 8862, 8862, 8862, -1, 8863, 8863, 8863, -1, + 8864, 8864, 8864, -1, 8865, 8865, 8865, -1, + 8866, 8866, 8866, -1, 8867, 8867, 8867, -1, + 8868, 8868, 8868, -1, 8869, 8869, 8869, -1, + 8870, 8870, 8870, -1, 8871, 8871, 8871, -1, + 8872, 8872, 8872, -1, 8873, 8873, 8873, -1, + 8874, 8874, 8874, -1, 8875, 8875, 8875, -1, + 8876, 8876, 8876, -1, 8877, 8877, 8877, -1, + 8878, 8878, 8878, -1, 8879, 8879, 8879, -1, + 8880, 8880, 8880, -1, 8881, 8881, 8881, -1, + 8882, 8882, 8882, -1, 8883, 8883, 8883, -1, + 8884, 8884, 8884, -1, 8885, 8885, 8885, -1, + 8886, 8886, 8886, -1, 8887, 8887, 8887, -1, + 8888, 8888, 8888, -1, 8889, 8889, 8889, -1, + 8890, 8890, 8890, -1, 8891, 8891, 8891, -1, + 8892, 8892, 8892, -1, 8893, 8893, 8893, -1, + 8894, 8894, 8894, -1, 8895, 8895, 8895, -1, + 8896, 8896, 8896, -1, 8897, 8897, 8897, -1, + 8898, 8898, 8898, -1, 8899, 8899, 8899, -1, + 8900, 8900, 8900, -1, 8901, 8901, 8901, -1, + 8902, 8902, 8902, -1, 8903, 8903, 8903, -1, + 8904, 8904, 8904, -1, 8905, 8905, 8905, -1, + 8906, 8906, 8906, -1, 8907, 8907, 8907, -1, + 8908, 8908, 8908, -1, 8909, 8909, 8909, -1, + 8910, 8910, 8910, -1, 8911, 8911, 8911, -1, + 8912, 8912, 8912, -1, 8913, 8913, 8913, -1, + 8914, 8914, 8914, -1, 8915, 8915, 8915, -1, + 8916, 8916, 8916, -1, 8917, 8917, 8917, -1, + 8918, 8918, 8918, -1, 8919, 8919, 8919, -1, + 8920, 8920, 8920, -1, 8921, 8921, 8921, -1, + 8922, 8922, 8922, -1, 8923, 8923, 8923, -1, + 8924, 8924, 8924, -1, 8925, 8925, 8925, -1, + 8926, 8926, 8926, -1, 8927, 8927, 8927, -1, + 8928, 8928, 8928, -1, 8929, 8929, 8929, -1, + 8930, 8930, 8930, -1, 8931, 8931, 8931, -1, + 8932, 8932, 8932, -1, 8933, 8933, 8933, -1, + 8934, 8934, 8934, -1, 8935, 8935, 8935, -1, + 8936, 8936, 8936, -1, 8937, 8937, 8937, -1, + 8938, 8938, 8938, -1, 8939, 8939, 8939, -1, + 8940, 8940, 8940, -1, 8941, 8941, 8941, -1, + 8942, 8942, 8942, -1, 8943, 8943, 8943, -1, + 8944, 8944, 8944, -1, 8945, 8945, 8945, -1, + 8946, 8946, 8946, -1, 8947, 8947, 8947, -1, + 8948, 8948, 8948, -1, 8949, 8949, 8949, -1, + 8950, 8950, 8950, -1, 8951, 8951, 8951, -1, + 8952, 8952, 8952, -1, 8953, 8953, 8953, -1, + 8954, 8954, 8954, -1, 8955, 8955, 8955, -1, + 8956, 8956, 8956, -1, 8957, 8957, 8957, -1, + 8958, 8958, 8958, -1, 8959, 8959, 8959, -1, + 8960, 8960, 8960, -1, 8961, 8961, 8961, -1, + 8962, 8962, 8962, -1, 8963, 8963, 8963, -1, + 8964, 8964, 8964, -1, 8965, 8965, 8965, -1, + 8966, 8966, 8966, -1, 8967, 8967, 8967, -1, + 8968, 8968, 8968, -1, 8969, 8969, 8969, -1, + 8970, 8970, 8970, -1, 8971, 8971, 8971, -1, + 8972, 8972, 8972, -1, 8973, 8973, 8973, -1, + 8974, 8974, 8974, -1, 8975, 8975, 8975, -1, + 8976, 8976, 8976, -1, 8977, 8977, 8977, -1, + 8978, 8978, 8978, -1, 8979, 8979, 8979, -1, + 8980, 8980, 8980, -1, 8981, 8981, 8981, -1, + 8982, 8982, 8982, -1, 8983, 8983, 8983, -1, + 8984, 8984, 8984, -1, 8985, 8985, 8985, -1, + 8986, 8986, 8986, -1, 8987, 8987, 8987, -1, + 8988, 8988, 8988, -1, 8989, 8989, 8989, -1, + 8990, 8990, 8990, -1, 8991, 8991, 8991, -1, + 8992, 8992, 8992, -1, 8993, 8993, 8993, -1, + 8994, 8994, 8994, -1, 8995, 8995, 8995, -1, + 8996, 8996, 8996, -1, 8997, 8997, 8997, -1, + 8998, 8998, 8998, -1, 8999, 8999, 8999, -1, + 9000, 9000, 9000, -1, 9001, 9001, 9001, -1, + 9002, 9002, 9002, -1, 9003, 9003, 9003, -1, + 9004, 9004, 9004, -1, 9005, 9005, 9005, -1, + 9006, 9006, 9006, -1, 9007, 9007, 9007, -1, + 9008, 9008, 9008, -1, 9009, 9009, 9009, -1, + 9010, 9010, 9010, -1, 9011, 9011, 9011, -1, + 9012, 9012, 9012, -1, 9013, 9013, 9013, -1, + 9014, 9014, 9014, -1, 9015, 9015, 9015, -1, + 9016, 9016, 9016, -1, 9017, 9017, 9017, -1, + 9018, 9018, 9018, -1, 9019, 9019, 9019, -1, + 9020, 9020, 9020, -1, 9021, 9021, 9021, -1, + 9022, 9022, 9022, -1, 9023, 9023, 9023, -1, + 9024, 9024, 9024, -1, 9025, 9025, 9025, -1, + 9026, 9026, 9026, -1, 9027, 9027, 9027, -1, + 9028, 9028, 9028, -1, 9029, 9029, 9029, -1, + 9030, 9030, 9030, -1, 9031, 9031, 9031, -1, + 9032, 9032, 9032, -1, 9033, 9033, 9033, -1, + 9034, 9034, 9034, -1, 9035, 9035, 9035, -1, + 9036, 9036, 9036, -1, 9037, 9037, 9037, -1, + 9038, 9038, 9038, -1, 9039, 9039, 9039, -1, + 9040, 9040, 9040, -1, 9041, 9041, 9041, -1, + 9042, 9042, 9042, -1, 9043, 9043, 9043, -1, + 9044, 9044, 9044, -1, 9045, 9045, 9045, -1, + 9046, 9046, 9046, -1, 9047, 9047, 9047, -1, + 9048, 9048, 9048, -1, 9049, 9049, 9049, -1, + 9050, 9050, 9050, -1, 9051, 9051, 9051, -1, + 9052, 9052, 9052, -1, 9053, 9053, 9053, -1, + 9054, 9054, 9054, -1, 9055, 9055, 9055, -1, + 9056, 9056, 9056, -1, 9057, 9057, 9057, -1, + 9058, 9058, 9058, -1, 9059, 9059, 9059, -1, + 9060, 9060, 9060, -1, 9061, 9061, 9061, -1, + 9062, 9062, 9062, -1, 9063, 9063, 9063, -1, + 9064, 9064, 9064, -1, 9065, 9065, 9065, -1, + 9066, 9066, 9066, -1, 9067, 9067, 9067, -1, + 9068, 9068, 9068, -1, 9069, 9069, 9069, -1, + 9070, 9070, 9070, -1, 9071, 9071, 9071, -1, + 9072, 9072, 9072, -1, 9073, 9073, 9073, -1, + 9074, 9074, 9074, -1, 9075, 9075, 9075, -1, + 9076, 9076, 9076, -1, 9077, 9077, 9077, -1, + 9078, 9078, 9078, -1, 9079, 9079, 9079, -1, + 9080, 9080, 9080, -1, 9081, 9081, 9081, -1, + 9082, 9082, 9082, -1, 9083, 9083, 9083, -1, + 9084, 9084, 9084, -1, 9085, 9085, 9085, -1, + 9086, 9086, 9086, -1, 9087, 9087, 9087, -1, + 9088, 9088, 9088, -1, 9089, 9089, 9089, -1, + 9090, 9090, 9090, -1, 9091, 9091, 9091, -1, + 9092, 9092, 9092, -1, 9093, 9093, 9093, -1, + 9094, 9094, 9094, -1, 9095, 9095, 9095, -1, + 9096, 9096, 9096, -1, 9097, 9097, 9097, -1, + 9098, 9098, 9098, -1, 9099, 9099, 9099, -1, + 9100, 9100, 9100, -1, 9101, 9101, 9101, -1, + 9102, 9102, 9102, -1, 9103, 9103, 9103, -1, + 9104, 9104, 9104, -1, 9105, 9105, 9105, -1, + 9106, 9106, 9106, -1, 9107, 9107, 9107, -1, + 9108, 9108, 9108, -1, 9109, 9109, 9109, -1, + 9110, 9110, 9110, -1, 9111, 9111, 9111, -1, + 9112, 9112, 9112, -1, 9113, 9113, 9113, -1, + 9114, 9114, 9114, -1, 9115, 9115, 9115, -1, + 9116, 9116, 9116, -1, 9117, 9117, 9117, -1, + 9118, 9118, 9118, -1, 9119, 9119, 9119, -1, + 9120, 9120, 9120, -1, 9121, 9121, 9121, -1, + 9122, 9122, 9122, -1, 9123, 9123, 9123, -1, + 9124, 9124, 9124, -1, 9125, 9125, 9125, -1, + 9126, 9126, 9126, -1, 9127, 9127, 9127, -1, + 9128, 9128, 9128, -1, 9129, 9129, 9129, -1, + 9130, 9130, 9130, -1, 9131, 9131, 9131, -1, + 9132, 9132, 9132, -1, 9133, 9133, 9133, -1, + 9134, 9134, 9134, -1, 9135, 9135, 9135, -1, + 9136, 9136, 9136, -1, 9137, 9137, 9137, -1, + 9138, 9138, 9138, -1, 9139, 9139, 9139, -1, + 9140, 9140, 9140, -1, 9141, 9141, 9141, -1, + 9142, 9142, 9142, -1, 9143, 9143, 9143, -1, + 9144, 9144, 9144, -1, 9145, 9145, 9145, -1, + 9146, 9146, 9146, -1, 9147, 9147, 9147, -1, + 9148, 9148, 9148, -1, 9149, 9149, 9149, -1, + 9150, 9150, 9150, -1, 9151, 9151, 9151, -1, + 9152, 9152, 9152, -1, 9153, 9153, 9153, -1, + 9154, 9154, 9154, -1, 9155, 9155, 9155, -1, + 9156, 9156, 9156, -1, 9157, 9157, 9157, -1, + 9158, 9158, 9158, -1, 9159, 9159, 9159, -1, + 9160, 9160, 9160, -1, 9161, 9161, 9161, -1, + 9162, 9162, 9162, -1, 9163, 9163, 9163, -1, + 9164, 9164, 9164, -1, 9165, 9165, 9165, -1, + 9166, 9166, 9166, -1, 9167, 9167, 9167, -1, + 9168, 9168, 9168, -1, 9169, 9169, 9169, -1, + 9170, 9170, 9170, -1, 9171, 9171, 9171, -1, + 9172, 9172, 9172, -1, 9173, 9173, 9173, -1, + 9174, 9174, 9174, -1, 9175, 9175, 9175, -1, + 9176, 9176, 9176, -1, 9177, 9177, 9177, -1, + 9178, 9178, 9178, -1, 9179, 9179, 9179, -1, + 9180, 9180, 9180, -1, 9181, 9181, 9181, -1, + 9182, 9182, 9182, -1, 9183, 9183, 9183, -1, + 9184, 9184, 9184, -1, 9185, 9185, 9185, -1, + 9186, 9186, 9186, -1, 9187, 9187, 9187, -1, + 9188, 9188, 9188, -1, 9189, 9189, 9189, -1, + 9190, 9190, 9190, -1, 9191, 9191, 9191, -1, + 9192, 9192, 9192, -1, 9193, 9193, 9193, -1, + 9194, 9194, 9194, -1, 9195, 9195, 9195, -1, + 9196, 9196, 9196, -1, 9197, 9197, 9197, -1, + 9198, 9198, 9198, -1, 9199, 9199, 9199, -1, + 9200, 9200, 9200, -1, 9201, 9201, 9201, -1, + 9202, 9202, 9202, -1, 9203, 9203, 9203, -1, + 9204, 9204, 9204, -1, 9205, 9205, 9205, -1, + 9206, 9206, 9206, -1, 9207, 9207, 9207, -1, + 9208, 9208, 9208, -1, 9209, 9209, 9209, -1, + 9210, 9210, 9210, -1, 9211, 9211, 9211, -1, + 9212, 9212, 9212, -1, 9213, 9213, 9213, -1, + 9214, 9214, 9214, -1, 9215, 9215, 9215, -1, + 9216, 9216, 9216, -1, 9217, 9217, 9217, -1, + 9218, 9218, 9218, -1, 9219, 9219, 9219, -1, + 9220, 9220, 9220, -1, 9221, 9221, 9221, -1, + 9222, 9222, 9222, -1, 9223, 9223, 9223, -1, + 9224, 9224, 9224, -1, 9225, 9225, 9225, -1, + 9226, 9226, 9226, -1, 9227, 9227, 9227, -1, + 9228, 9228, 9228, -1, 9229, 9229, 9229, -1, + 9230, 9230, 9230, -1, 9231, 9231, 9231, -1, + 9232, 9232, 9232, -1, 9233, 9233, 9233, -1, + 9234, 9234, 9234, -1, 9235, 9235, 9235, -1, + 9236, 9236, 9236, -1, 9237, 9237, 9237, -1, + 9238, 9238, 9238, -1, 9239, 9239, 9239, -1, + 9240, 9240, 9240, -1, 9241, 9241, 9241, -1, + 9242, 9242, 9242, -1, 9243, 9243, 9243, -1, + 9244, 9244, 9244, -1, 9245, 9245, 9245, -1, + 9246, 9246, 9246, -1, 9247, 9247, 9247, -1, + 9248, 9248, 9248, -1, 9249, 9249, 9249, -1, + 9250, 9250, 9250, -1, 9251, 9251, 9251, -1, + 9252, 9252, 9252, -1, 9253, 9253, 9253, -1, + 9254, 9254, 9254, -1, 9255, 9255, 9255, -1, + 9256, 9256, 9256, -1, 9257, 9257, 9257, -1, + 9258, 9258, 9258, -1, 9259, 9259, 9259, -1, + 9260, 9260, 9260, -1, 9261, 9261, 9261, -1, + 9262, 9262, 9262, -1, 9263, 9263, 9263, -1, + 9264, 9264, 9264, -1, 9265, 9265, 9265, -1, + 9266, 9266, 9266, -1, 9267, 9267, 9267, -1, + 9268, 9268, 9268, -1, 9269, 9269, 9269, -1, + 9270, 9270, 9270, -1, 9271, 9271, 9271, -1, + 9272, 9272, 9272, -1, 9273, 9273, 9273, -1, + 9274, 9274, 9274, -1, 9275, 9275, 9275, -1, + 9276, 9276, 9276, -1, 9277, 9277, 9277, -1, + 9278, 9278, 9278, -1, 9279, 9279, 9279, -1, + 9280, 9280, 9280, -1, 9281, 9281, 9281, -1, + 9282, 9282, 9282, -1, 9283, 9283, 9283, -1, + 9284, 9284, 9284, -1, 9285, 9285, 9285, -1, + 9286, 9286, 9286, -1, 9287, 9287, 9287, -1, + 9288, 9288, 9288, -1, 9289, 9289, 9289, -1, + 9290, 9290, 9290, -1, 9291, 9291, 9291, -1, + 9292, 9292, 9292, -1, 9293, 9293, 9293, -1, + 9294, 9294, 9294, -1, 9295, 9295, 9295, -1, + 9296, 9296, 9296, -1, 9297, 9297, 9297, -1, + 9298, 9298, 9298, -1, 9299, 9299, 9299, -1, + 9300, 9300, 9300, -1, 9301, 9301, 9301, -1, + 9302, 9302, 9302, -1, 9303, 9303, 9303, -1, + 9304, 9304, 9304, -1, 9305, 9305, 9305, -1, + 9306, 9306, 9306, -1, 9307, 9307, 9307, -1, + 9308, 9308, 9308, -1, 9309, 9309, 9309, -1, + 9310, 9310, 9310, -1, 9311, 9311, 9311, -1, + 9312, 9312, 9312, -1, 9313, 9313, 9313, -1, + 9314, 9314, 9314, -1, 9315, 9315, 9315, -1, + 9316, 9316, 9316, -1, 9317, 9317, 9317, -1, + 9318, 9318, 9318, -1, 9319, 9319, 9319, -1, + 9320, 9320, 9320, -1, 9321, 9321, 9321, -1, + 9322, 9322, 9322, -1, 9323, 9323, 9323, -1, + 9324, 9324, 9324, -1, 9325, 9325, 9325, -1, + 9326, 9326, 9326, -1, 9327, 9327, 9327, -1, + 9328, 9328, 9328, -1, 9329, 9329, 9329, -1, + 9330, 9330, 9330, -1, 9331, 9331, 9331, -1, + 9332, 9332, 9332, -1, 9333, 9333, 9333, -1, + 9334, 9334, 9334, -1, 9335, 9335, 9335, -1, + 9336, 9336, 9336, -1, 9337, 9337, 9337, -1, + 9338, 9338, 9338, -1, 9339, 9339, 9339, -1, + 9340, 9340, 9340, -1, 9341, 9341, 9341, -1, + 9342, 9342, 9342, -1, 9343, 9343, 9343, -1, + 9344, 9344, 9344, -1, 9345, 9345, 9345, -1, + 9346, 9346, 9346, -1, 9347, 9347, 9347, -1, + 9348, 9348, 9348, -1, 9349, 9349, 9349, -1, + 9350, 9350, 9350, -1, 9351, 9351, 9351, -1, + 9352, 9352, 9352, -1, 9353, 9353, 9353, -1, + 9354, 9354, 9354, -1, 9355, 9355, 9355, -1, + 9356, 9356, 9356, -1, 9357, 9357, 9357, -1, + 9358, 9358, 9358, -1, 9359, 9359, 9359, -1, + 9360, 9360, 9360, -1, 9361, 9361, 9361, -1, + 9362, 9362, 9362, -1, 9363, 9363, 9363, -1, + 9364, 9364, 9364, -1, 9365, 9365, 9365, -1, + 9366, 9366, 9366, -1, 9367, 9367, 9367, -1, + 9368, 9368, 9368, -1, 9369, 9369, 9369, -1, + 9370, 9370, 9370, -1, 9371, 9371, 9371, -1, + 9372, 9372, 9372, -1, 9373, 9373, 9373, -1, + 9374, 9374, 9374, -1, 9375, 9375, 9375, -1, + 9376, 9376, 9376, -1, 9377, 9377, 9377, -1, + 9378, 9378, 9378, -1, 9379, 9379, 9379, -1, + 9380, 9380, 9380, -1, 9381, 9381, 9381, -1, + 9382, 9382, 9382, -1, 9383, 9383, 9383, -1, + 9384, 9384, 9384, -1, 9385, 9385, 9385, -1, + 9386, 9386, 9386, -1, 9387, 9387, 9387, -1, + 9388, 9388, 9388, -1, 9389, 9389, 9389, -1, + 9390, 9390, 9390, -1, 9391, 9391, 9391, -1, + 9392, 9392, 9392, -1, 9393, 9393, 9393, -1, + 9394, 9394, 9394, -1, 9395, 9395, 9395, -1, + 9396, 9396, 9396, -1, 9397, 9397, 9397, -1, + 9398, 9398, 9398, -1, 9399, 9399, 9399, -1, + 9400, 9400, 9400, -1, 9401, 9401, 9401, -1, + 9402, 9402, 9402, -1, 9403, 9403, 9403, -1, + 9404, 9404, 9404, -1, 9405, 9405, 9405, -1, + 9406, 9406, 9406, -1, 9407, 9407, 9407, -1, + 9408, 9408, 9408, -1, 9409, 9409, 9409, -1, + 9410, 9410, 9410, -1, 9411, 9411, 9411, -1, + 9412, 9412, 9412, -1, 9413, 9413, 9413, -1, + 9414, 9414, 9414, -1, 9415, 9415, 9415, -1, + 9416, 9416, 9416, -1, 9417, 9417, 9417, -1, + 9418, 9418, 9418, -1, 9419, 9419, 9419, -1, + 9420, 9420, 9420, -1, 9421, 9421, 9421, -1, + 9422, 9422, 9422, -1, 9423, 9423, 9423, -1, + 9424, 9424, 9424, -1, 9425, 9425, 9425, -1, + 9426, 9426, 9426, -1, 9427, 9427, 9427, -1, + 9428, 9428, 9428, -1, 9429, 9429, 9429, -1, + 9430, 9430, 9430, -1, 9431, 9431, 9431, -1, + 9432, 9432, 9432, -1, 9433, 9433, 9433, -1, + 9434, 9434, 9434, -1, 9435, 9435, 9435, -1, + 9436, 9436, 9436, -1, 9437, 9437, 9437, -1, + 9438, 9438, 9438, -1, 9439, 9439, 9439, -1, + 9440, 9440, 9440, -1, 9441, 9441, 9441, -1, + 9442, 9442, 9442, -1, 9443, 9443, 9443, -1, + 9444, 9444, 9444, -1, 9445, 9445, 9445, -1, + 9446, 9446, 9446, -1, 9447, 9447, 9447, -1, + 9448, 9448, 9448, -1, 9449, 9449, 9449, -1, + 9450, 9450, 9450, -1, 9451, 9451, 9451, -1, + 9452, 9452, 9452, -1, 9453, 9453, 9453, -1, + 9454, 9454, 9454, -1, 9455, 9455, 9455, -1, + 9456, 9456, 9456, -1, 9457, 9457, 9457, -1, + 9458, 9458, 9458, -1, 9459, 9459, 9459, -1, + 9460, 9460, 9460, -1, 9461, 9461, 9461, -1, + 9462, 9462, 9462, -1, 9463, 9463, 9463, -1, + 9464, 9464, 9464, -1, 9465, 9465, 9465, -1, + 9466, 9466, 9466, -1, 9467, 9467, 9467, -1, + 9468, 9468, 9468, -1, 9469, 9469, 9469, -1, + 9470, 9470, 9470, -1, 9471, 9471, 9471, -1, + 9472, 9472, 9472, -1, 9473, 9473, 9473, -1, + 9474, 9474, 9474, -1, 9475, 9475, 9475, -1, + 9476, 9476, 9476, -1, 9477, 9477, 9477, -1, + 9478, 9478, 9478, -1, 9479, 9479, 9479, -1, + 9480, 9480, 9480, -1, 9481, 9481, 9481, -1, + 9482, 9482, 9482, -1, 9483, 9483, 9483, -1, + 9484, 9484, 9484, -1, 9485, 9485, 9485, -1, + 9486, 9486, 9486, -1, 9487, 9487, 9487, -1, + 9488, 9488, 9488, -1, 9489, 9489, 9489, -1, + 9490, 9490, 9490, -1, 9491, 9491, 9491, -1, + 9492, 9492, 9492, -1, 9493, 9493, 9493, -1, + 9494, 9494, 9494, -1, 9495, 9495, 9495, -1, + 9496, 9496, 9496, -1, 9497, 9497, 9497, -1, + 9498, 9498, 9498, -1, 9499, 9499, 9499, -1, + 9500, 9500, 9500, -1, 9501, 9501, 9501, -1, + 9502, 9502, 9502, -1, 9503, 9503, 9503, -1, + 9504, 9504, 9504, -1, 9505, 9505, 9505, -1, + 9506, 9506, 9506, -1, 9507, 9507, 9507, -1, + 9508, 9508, 9508, -1, 9509, 9509, 9509, -1, + 9510, 9510, 9510, -1, 9511, 9511, 9511, -1, + 9512, 9512, 9512, -1, 9513, 9513, 9513, -1, + 9514, 9514, 9514, -1, 9515, 9515, 9515, -1, + 9516, 9516, 9516, -1, 9517, 9517, 9517, -1, + 9518, 9518, 9518, -1, 9519, 9519, 9519, -1, + 9520, 9520, 9520, -1, 9521, 9521, 9521, -1, + 9522, 9522, 9522, -1, 9523, 9523, 9523, -1, + 9524, 9524, 9524, -1, 9525, 9525, 9525, -1, + 9526, 9526, 9526, -1, 9527, 9527, 9527, -1, + 9528, 9528, 9528, -1, 9529, 9529, 9529, -1, + 9530, 9530, 9530, -1, 9531, 9531, 9531, -1, + 9532, 9532, 9532, -1, 9533, 9533, 9533, -1, + 9534, 9534, 9534, -1, 9535, 9535, 9535, -1, + 9536, 9536, 9536, -1, 9537, 9537, 9537, -1, + 9538, 9538, 9538, -1, 9539, 9539, 9539, -1, + 9540, 9540, 9540, -1, 9541, 9541, 9541, -1, + 9542, 9542, 9542, -1, 9543, 9543, 9543, -1, + 9544, 9544, 9544, -1, 9545, 9545, 9545, -1, + 9546, 9546, 9546, -1, 9547, 9547, 9547, -1, + 9548, 9548, 9548, -1, 9549, 9549, 9549, -1, + 9550, 9550, 9550, -1, 9551, 9551, 9551, -1, + 9552, 9552, 9552, -1, 9553, 9553, 9553, -1, + 9554, 9554, 9554, -1, 9555, 9555, 9555, -1, + 9556, 9556, 9556, -1, 9557, 9557, 9557, -1, + 9558, 9558, 9558, -1, 9559, 9559, 9559, -1, + 9560, 9560, 9560, -1, 9561, 9561, 9561, -1, + 9562, 9562, 9562, -1, 9563, 9563, 9563, -1, + 9564, 9564, 9564, -1, 9565, 9565, 9565, -1, + 9566, 9566, 9566, -1, 9567, 9567, 9567, -1, + 9568, 9568, 9568, -1, 9569, 9569, 9569, -1, + 9570, 9570, 9570, -1, 9571, 9571, 9571, -1, + 9572, 9572, 9572, -1, 9573, 9573, 9573, -1, + 9574, 9574, 9574, -1, 9575, 9575, 9575, -1, + 9576, 9576, 9576, -1, 9577, 9577, 9577, -1, + 9578, 9578, 9578, -1, 9579, 9579, 9579, -1, + 9580, 9580, 9580, -1, 9581, 9581, 9581, -1, + 9582, 9582, 9582, -1, 9583, 9583, 9583, -1, + 9584, 9584, 9584, -1, 9585, 9585, 9585, -1, + 9586, 9586, 9586, -1, 9587, 9587, 9587, -1, + 9588, 9588, 9588, -1, 9589, 9589, 9589, -1, + 9590, 9590, 9590, -1, 9591, 9591, 9591, -1, + 9592, 9592, 9592, -1, 9593, 9593, 9593, -1, + 9594, 9594, 9594, -1, 9595, 9595, 9595, -1, + 9596, 9596, 9596, -1, 9597, 9597, 9597, -1, + 9598, 9598, 9598, -1, 9599, 9599, 9599, -1, + 9600, 9600, 9600, -1, 9601, 9601, 9601, -1, + 9602, 9602, 9602, -1, 9603, 9603, 9603, -1, + 9604, 9604, 9604, -1, 9605, 9605, 9605, -1, + 9606, 9606, 9606, -1, 9607, 9607, 9607, -1, + 9608, 9608, 9608, -1, 9609, 9609, 9609, -1, + 9610, 9610, 9610, -1, 9611, 9611, 9611, -1, + 9612, 9612, 9612, -1, 9613, 9613, 9613, -1, + 9614, 9614, 9614, -1, 9615, 9615, 9615, -1, + 9616, 9616, 9616, -1, 9617, 9617, 9617, -1, + 9618, 9618, 9618, -1, 9619, 9619, 9619, -1, + 9620, 9620, 9620, -1, 9621, 9621, 9621, -1, + 9622, 9622, 9622, -1, 9623, 9623, 9623, -1, + 9624, 9624, 9624, -1, 9625, 9625, 9625, -1, + 9626, 9626, 9626, -1, 9627, 9627, 9627, -1, + 9628, 9628, 9628, -1, 9629, 9629, 9629, -1, + 9630, 9630, 9630, -1, 9631, 9631, 9631, -1, + 9632, 9632, 9632, -1, 9633, 9633, 9633, -1, + 9634, 9634, 9634, -1, 9635, 9635, 9635, -1, + 9636, 9636, 9636, -1, 9637, 9637, 9637, -1, + 9638, 9638, 9638, -1, 9639, 9639, 9639, -1, + 9640, 9640, 9640, -1, 9641, 9641, 9641, -1, + 9642, 9642, 9642, -1, 9643, 9643, 9643, -1, + 9644, 9644, 9644, -1, 9645, 9645, 9645, -1, + 9646, 9646, 9646, -1, 9647, 9647, 9647, -1, + 9648, 9648, 9648, -1, 9649, 9649, 9649, -1, + 9650, 9650, 9650, -1, 9651, 9651, 9651, -1, + 9652, 9652, 9652, -1, 9653, 9653, 9653, -1, + 9654, 9654, 9654, -1, 9655, 9655, 9655, -1, + 9656, 9656, 9656, -1, 9657, 9657, 9657, -1, + 9658, 9658, 9658, -1, 9659, 9659, 9659, -1, + 9660, 9660, 9660, -1, 9661, 9661, 9661, -1, + 9662, 9662, 9662, -1, 9663, 9663, 9663, -1, + 9664, 9664, 9664, -1, 9665, 9665, 9665, -1, + 9666, 9666, 9666, -1, 9667, 9667, 9667, -1, + 9668, 9668, 9668, -1, 9669, 9669, 9669, -1, + 9670, 9670, 9670, -1, 9671, 9671, 9671, -1, + 9672, 9672, 9672, -1, 9673, 9673, 9673, -1, + 9674, 9674, 9674, -1, 9675, 9675, 9675, -1, + 9676, 9676, 9676, -1, 9677, 9677, 9677, -1, + 9678, 9678, 9678, -1, 9679, 9679, 9679, -1, + 9680, 9680, 9680, -1, 9681, 9681, 9681, -1, + 9682, 9682, 9682, -1, 9683, 9683, 9683, -1, + 9684, 9684, 9684, -1, 9685, 9685, 9685, -1, + 9686, 9686, 9686, -1, 9687, 9687, 9687, -1, + 9688, 9688, 9688, -1, 9689, 9689, 9689, -1, + 9690, 9690, 9690, -1, 9691, 9691, 9691, -1, + 9692, 9692, 9692, -1, 9693, 9693, 9693, -1, + 9694, 9694, 9694, -1, 9695, 9695, 9695, -1, + 9696, 9696, 9696, -1, 9697, 9697, 9697, -1, + 9698, 9698, 9698, -1, 9699, 9699, 9699, -1, + 9700, 9700, 9700, -1, 9701, 9701, 9701, -1, + 9702, 9702, 9702, -1, 9703, 9703, 9703, -1, + 9704, 9704, 9704, -1, 9705, 9705, 9705, -1, + 9706, 9706, 9706, -1, 9707, 9707, 9707, -1, + 9708, 9708, 9708, -1, 9709, 9709, 9709, -1, + 9710, 9710, 9710, -1, 9711, 9711, 9711, -1, + 9712, 9712, 9712, -1, 9713, 9713, 9713, -1, + 9714, 9714, 9714, -1, 9715, 9715, 9715, -1, + 9716, 9716, 9716, -1, 9717, 9717, 9717, -1, + 9718, 9718, 9718, -1, 9719, 9719, 9719, -1, + 9720, 9720, 9720, -1, 9721, 9721, 9721, -1, + 9722, 9722, 9722, -1, 9723, 9723, 9723, -1, + 9724, 9724, 9724, -1, 9725, 9725, 9725, -1, + 9726, 9726, 9726, -1, 9727, 9727, 9727, -1, + 9728, 9728, 9728, -1, 9729, 9729, 9729, -1, + 9730, 9730, 9730, -1, 9731, 9731, 9731, -1, + 9732, 9732, 9732, -1, 9733, 9733, 9733, -1, + 9734, 9734, 9734, -1, 9735, 9735, 9735, -1, + 9736, 9736, 9736, -1, 9737, 9737, 9737, -1, + 9738, 9738, 9738, -1, 9739, 9739, 9739, -1, + 9740, 9740, 9740, -1, 9741, 9741, 9741, -1, + 9742, 9742, 9742, -1, 9743, 9743, 9743, -1, + 9744, 9744, 9744, -1, 9745, 9745, 9745, -1, + 9746, 9746, 9746, -1, 9747, 9747, 9747, -1, + 9748, 9748, 9748, -1, 9749, 9749, 9749, -1, + 9750, 9750, 9750, -1, 9751, 9751, 9751, -1, + 9752, 9752, 9752, -1, 9753, 9753, 9753, -1, + 9754, 9754, 9754, -1, 9755, 9755, 9755, -1, + 9756, 9756, 9756, -1, 9757, 9757, 9757, -1, + 9758, 9758, 9758, -1, 9759, 9759, 9759, -1, + 9760, 9760, 9760, -1, 9761, 9761, 9761, -1, + 9762, 9762, 9762, -1, 9763, 9763, 9763, -1, + 9764, 9764, 9764, -1, 9765, 9765, 9765, -1, + 9766, 9766, 9766, -1, 9767, 9767, 9767, -1, + 9768, 9768, 9768, -1, 9769, 9769, 9769, -1, + 9770, 9770, 9770, -1, 9771, 9771, 9771, -1, + 9772, 9772, 9772, -1, 9773, 9773, 9773, -1, + 9774, 9774, 9774, -1, 9775, 9775, 9775, -1, + 9776, 9776, 9776, -1, 9777, 9777, 9777, -1, + 9778, 9778, 9778, -1, 9779, 9779, 9779, -1, + 9780, 9780, 9780, -1, 9781, 9781, 9781, -1, + 9782, 9782, 9782, -1, 9783, 9783, 9783, -1, + 9784, 9784, 9784, -1, 9785, 9785, 9785, -1, + 9786, 9786, 9786, -1, 9787, 9787, 9787, -1, + 9788, 9788, 9788, -1, 9789, 9789, 9789, -1, + 9790, 9790, 9790, -1, 9791, 9791, 9791, -1, + 9792, 9792, 9792, -1, 9793, 9793, 9793, -1, + 9794, 9794, 9794, -1, 9795, 9795, 9795, -1, + 9796, 9796, 9796, -1, 9797, 9797, 9797, -1, + 9798, 9798, 9798, -1, 9799, 9799, 9799, -1, + 9800, 9800, 9800, -1, 9801, 9801, 9801, -1, + 9802, 9802, 9802, -1, 9803, 9803, 9803, -1, + 9804, 9804, 9804, -1, 9805, 9805, 9805, -1, + 9806, 9806, 9806, -1, 9807, 9807, 9807, -1, + 9808, 9808, 9808, -1, 9809, 9809, 9809, -1, + 9810, 9810, 9810, -1, 9811, 9811, 9811, -1, + 9812, 9812, 9812, -1, 9813, 9813, 9813, -1, + 9814, 9814, 9814, -1, 9815, 9815, 9815, -1, + 9816, 9816, 9816, -1, 9817, 9817, 9817, -1, + 9818, 9818, 9818, -1, 9819, 9819, 9819, -1, + 9820, 9820, 9820, -1, 9821, 9821, 9821, -1, + 9822, 9822, 9822, -1, 9823, 9823, 9823, -1, + 9824, 9824, 9824, -1, 9825, 9825, 9825, -1, + 9826, 9826, 9826, -1, 9827, 9827, 9827, -1, + 9828, 9828, 9828, -1, 9829, 9829, 9829, -1, + 9830, 9830, 9830, -1, 9831, 9831, 9831, -1, + 9832, 9832, 9832, -1, 9833, 9833, 9833, -1, + 9834, 9834, 9834, -1, 9835, 9835, 9835, -1, + 9836, 9836, 9836, -1, 9837, 9837, 9837, -1, + 9838, 9838, 9838, -1, 9839, 9839, 9839, -1, + 9840, 9840, 9840, -1, 9841, 9841, 9841, -1, + 9842, 9842, 9842, -1, 9843, 9843, 9843, -1, + 9844, 9844, 9844, -1, 9845, 9845, 9845, -1, + 9846, 9846, 9846, -1, 9847, 9847, 9847, -1, + 9848, 9848, 9848, -1, 9849, 9849, 9849, -1, + 9850, 9850, 9850, -1, 9851, 9851, 9851, -1, + 9852, 9852, 9852, -1, 9853, 9853, 9853, -1, + 9854, 9854, 9854, -1, 9855, 9855, 9855, -1, + 9856, 9856, 9856, -1, 9857, 9857, 9857, -1, + 9858, 9858, 9858, -1, 9859, 9859, 9859, -1, + 9860, 9860, 9860, -1, 9861, 9861, 9861, -1, + 9862, 9862, 9862, -1, 9863, 9863, 9863, -1, + 9864, 9864, 9864, -1, 9865, 9865, 9865, -1, + 9866, 9866, 9866, -1, 9867, 9867, 9867, -1, + 9868, 9868, 9868, -1, 9869, 9869, 9869, -1, + 9870, 9870, 9870, -1, 9871, 9871, 9871, -1, + 9872, 9872, 9872, -1, 9873, 9873, 9873, -1, + 9874, 9874, 9874, -1, 9875, 9875, 9875, -1, + 9876, 9876, 9876, -1, 9877, 9877, 9877, -1, + 9878, 9878, 9878, -1, 9879, 9879, 9879, -1, + 9880, 9880, 9880, -1, 9881, 9881, 9881, -1, + 9882, 9882, 9882, -1, 9883, 9883, 9883, -1, + 9884, 9884, 9884, -1, 9885, 9885, 9885, -1, + 9886, 9886, 9886, -1, 9887, 9887, 9887, -1, + 9888, 9888, 9888, -1, 9889, 9889, 9889, -1, + 9890, 9890, 9890, -1, 9891, 9891, 9891, -1, + 9892, 9892, 9892, -1, 9893, 9893, 9893, -1, + 9894, 9894, 9894, -1, 9895, 9895, 9895, -1, + 9896, 9896, 9896, -1, 9897, 9897, 9897, -1, + 9898, 9898, 9898, -1, 9899, 9899, 9899, -1, + 9900, 9900, 9900, -1, 9901, 9901, 9901, -1, + 9902, 9902, 9902, -1, 9903, 9903, 9903, -1, + 9904, 9904, 9904, -1, 9905, 9905, 9905, -1, + 9906, 9906, 9906, -1, 9907, 9907, 9907, -1, + 9908, 9908, 9908, -1, 9909, 9909, 9909, -1, + 9910, 9910, 9910, -1, 9911, 9911, 9911, -1, + 9912, 9912, 9912, -1, 9913, 9913, 9913, -1, + 9914, 9914, 9914, -1, 9915, 9915, 9915, -1, + 9916, 9916, 9916, -1, 9917, 9917, 9917, -1, + 9918, 9918, 9918, -1, 9919, 9919, 9919, -1, + 9920, 9920, 9920, -1, 9921, 9921, 9921, -1, + 9922, 9922, 9922, -1, 9923, 9923, 9923, -1, + 9924, 9924, 9924, -1, 9925, 9925, 9925, -1, + 9926, 9926, 9926, -1, 9927, 9927, 9927, -1, + 9928, 9928, 9928, -1, 9929, 9929, 9929, -1, + 9930, 9930, 9930, -1, 9931, 9931, 9931, -1, + 9932, 9932, 9932, -1, 9933, 9933, 9933, -1, + 9934, 9934, 9934, -1, 9935, 9935, 9935, -1, + 9936, 9936, 9936, -1, 9937, 9937, 9937, -1, + 9938, 9938, 9938, -1, 9939, 9939, 9939, -1, + 9940, 9940, 9940, -1, 9941, 9941, 9941, -1, + 9942, 9942, 9942, -1, 9943, 9943, 9943, -1, + 9944, 9944, 9944, -1, 9945, 9945, 9945, -1, + 9946, 9946, 9946, -1, 9947, 9947, 9947, -1, + 9948, 9948, 9948, -1, 9949, 9949, 9949, -1, + 9950, 9950, 9950, -1, 9951, 9951, 9951, -1, + 9952, 9952, 9952, -1, 9953, 9953, 9953, -1, + 9954, 9954, 9954, -1, 9955, 9955, 9955, -1, + 9956, 9956, 9956, -1, 9957, 9957, 9957, -1, + 9958, 9958, 9958, -1, 9959, 9959, 9959, -1, + 9960, 9960, 9960, -1, 9961, 9961, 9961, -1, + 9962, 9962, 9962, -1, 9963, 9963, 9963, -1, + 9964, 9964, 9964, -1, 9965, 9965, 9965, -1, + 9966, 9966, 9966, -1, 9967, 9967, 9967, -1, + 9968, 9968, 9968, -1, 9969, 9969, 9969, -1, + 9970, 9970, 9970, -1, 9971, 9971, 9971, -1, + 9972, 9972, 9972, -1, 9973, 9973, 9973, -1, + 9974, 9974, 9974, -1, 9975, 9975, 9975, -1, + 9976, 9976, 9976, -1, 9977, 9977, 9977, -1, + 9978, 9978, 9978, -1, 9979, 9979, 9979, -1, + 9980, 9980, 9980, -1, 9981, 9981, 9981, -1, + 9982, 9982, 9982, -1, 9983, 9983, 9983, -1, + 9984, 9984, 9984, -1, 9985, 9985, 9985, -1, + 9986, 9986, 9986, -1, 9987, 9987, 9987, -1, + 9988, 9988, 9988, -1, 9989, 9989, 9989, -1, + 9990, 9990, 9990, -1, 9991, 9991, 9991, -1, + 9992, 9992, 9992, -1, 9993, 9993, 9993, -1, + 9994, 9994, 9994, -1, 9995, 9995, 9995, -1, + 9996, 9996, 9996, -1, 9997, 9997, 9997, -1, + 9998, 9998, 9998, -1, 9999, 9999, 9999, -1, + 10000, 10000, 10000, -1, 10001, 10001, 10001, -1, + 10002, 10002, 10002, -1, 10003, 10003, 10003, -1, + 10004, 10004, 10004, -1, 10005, 10005, 10005, -1, + 10006, 10006, 10006, -1, 10007, 10007, 10007, -1, + 10008, 10008, 10008, -1, 10009, 10009, 10009, -1, + 10010, 10010, 10010, -1, 10011, 10011, 10011, -1, + 10012, 10012, 10012, -1, 10013, 10013, 10013, -1, + 10014, 10014, 10014, -1, 10015, 10015, 10015, -1, + 10016, 10016, 10016, -1, 10017, 10017, 10017, -1, + 10018, 10018, 10018, -1, 10019, 10019, 10019, -1, + 10020, 10020, 10020, -1, 10021, 10021, 10021, -1, + 10022, 10022, 10022, -1, 10023, 10023, 10023, -1, + 10024, 10024, 10024, -1, 10025, 10025, 10025, -1, + 10026, 10026, 10026, -1, 10027, 10027, 10027, -1, + 10028, 10028, 10028, -1, 10029, 10029, 10029, -1, + 10030, 10030, 10030, -1, 10031, 10031, 10031, -1, + 10032, 10032, 10032, -1, 10033, 10033, 10033, -1, + 10034, 10034, 10034, -1, 10035, 10035, 10035, -1, + 10036, 10036, 10036, -1, 10037, 10037, 10037, -1, + 10038, 10038, 10038, -1, 10039, 10039, 10039, -1, + 10040, 10040, 10040, -1, 10041, 10041, 10041, -1, + 10042, 10042, 10042, -1, 10043, 10043, 10043, -1, + 10044, 10044, 10044, -1, 10045, 10045, 10045, -1, + 10046, 10046, 10046, -1, 10047, 10047, 10047, -1, + 10048, 10048, 10048, -1, 10049, 10049, 10049, -1, + 10050, 10050, 10050, -1, 10051, 10051, 10051, -1, + 10052, 10052, 10052, -1, 10053, 10053, 10053, -1, + 10054, 10054, 10054, -1, 10055, 10055, 10055, -1, + 10056, 10056, 10056, -1, 10057, 10057, 10057, -1, + 10058, 10058, 10058, -1, 10059, 10059, 10059, -1, + 10060, 10060, 10060, -1, 10061, 10061, 10061, -1, + 10062, 10062, 10062, -1, 10063, 10063, 10063, -1, + 10064, 10064, 10064, -1, 10065, 10065, 10065, -1, + 10066, 10066, 10066, -1, 10067, 10067, 10067, -1, + 10068, 10068, 10068, -1, 10069, 10069, 10069, -1, + 10070, 10070, 10070, -1, 10071, 10071, 10071, -1, + 10072, 10072, 10072, -1, 10073, 10073, 10073, -1, + 10074, 10074, 10074, -1, 10075, 10075, 10075, -1, + 10076, 10076, 10076, -1, 10077, 10077, 10077, -1, + 10078, 10078, 10078, -1, 10079, 10079, 10079, -1, + 10080, 10080, 10080, -1, 10081, 10081, 10081, -1, + 10082, 10082, 10082, -1, 10083, 10083, 10083, -1, + 10084, 10084, 10084, -1, 10085, 10085, 10085, -1, + 10086, 10086, 10086, -1, 10087, 10087, 10087, -1, + 10088, 10088, 10088, -1, 10089, 10089, 10089, -1, + 10090, 10090, 10090, -1, 10091, 10091, 10091, -1, + 10092, 10092, 10092, -1, 10093, 10093, 10093, -1, + 10094, 10094, 10094, -1, 10095, 10095, 10095, -1, + 10096, 10096, 10096, -1, 10097, 10097, 10097, -1, + 10098, 10098, 10098, -1, 10099, 10099, 10099, -1, + 10100, 10100, 10100, -1, 10101, 10101, 10101, -1, + 10102, 10102, 10102, -1, 10103, 10103, 10103, -1, + 10104, 10104, 10104, -1, 10105, 10105, 10105, -1, + 10106, 10106, 10106, -1, 10107, 10107, 10107, -1, + 10108, 10108, 10108, -1, 10109, 10109, 10109, -1, + 10110, 10110, 10110, -1, 10111, 10111, 10111, -1, + 10112, 10112, 10112, -1, 10113, 10113, 10113, -1, + 10114, 10114, 10114, -1, 10115, 10115, 10115, -1, + 10116, 10116, 10116, -1, 10117, 10117, 10117, -1, + 10118, 10118, 10118, -1, 10119, 10119, 10119, -1, + 10120, 10120, 10120, -1, 10121, 10121, 10121, -1, + 10122, 10122, 10122, -1, 10123, 10123, 10123, -1, + 10124, 10124, 10124, -1, 10125, 10125, 10125, -1, + 10126, 10126, 10126, -1, 10127, 10127, 10127, -1, + 10128, 10128, 10128, -1, 10129, 10129, 10129, -1, + 10130, 10130, 10130, -1, 10131, 10131, 10131, -1, + 10132, 10132, 10132, -1, 10133, 10133, 10133, -1, + 10134, 10134, 10134, -1, 10135, 10135, 10135, -1, + 10136, 10136, 10136, -1, 10137, 10137, 10137, -1, + 10138, 10138, 10138, -1, 10139, 10139, 10139, -1, + 10140, 10140, 10140, -1, 10141, 10141, 10141, -1, + 10142, 10142, 10142, -1, 10143, 10143, 10143, -1, + 10144, 10144, 10144, -1, 10145, 10145, 10145, -1, + 10146, 10146, 10146, -1, 10147, 10147, 10147, -1, + 10148, 10148, 10148, -1, 10149, 10149, 10149, -1, + 10150, 10150, 10150, -1, 10151, 10151, 10151, -1, + 10152, 10152, 10152, -1, 10153, 10153, 10153, -1, + 10154, 10154, 10154, -1, 10155, 10155, 10155, -1, + 10156, 10156, 10156, -1, 10157, 10157, 10157, -1, + 10158, 10158, 10158, -1, 10159, 10159, 10159, -1, + 10160, 10160, 10160, -1, 10161, 10161, 10161, -1, + 10162, 10162, 10162, -1, 10163, 10163, 10163, -1, + 10164, 10164, 10164, -1, 10165, 10165, 10165, -1, + 10166, 10166, 10166, -1, 10167, 10167, 10167, -1, + 10168, 10168, 10168, -1, 10169, 10169, 10169, -1, + 10170, 10170, 10170, -1, 10171, 10171, 10171, -1, + 10172, 10172, 10172, -1, 10173, 10173, 10173, -1, + 10174, 10174, 10174, -1, 10175, 10175, 10175, -1, + 10176, 10176, 10176, -1, 10177, 10177, 10177, -1, + 10178, 10178, 10178, -1, 10179, 10179, 10179, -1, + 10180, 10180, 10180, -1, 10181, 10181, 10181, -1, + 10182, 10182, 10182, -1, 10183, 10183, 10183, -1, + 10184, 10184, 10184, -1, 10185, 10185, 10185, -1, + 10186, 10186, 10186, -1, 10187, 10187, 10187, -1, + 10188, 10188, 10188, -1, 10189, 10189, 10189, -1, + 10190, 10190, 10190, -1, 10191, 10191, 10191, -1, + 10192, 10192, 10192, -1, 10193, 10193, 10193, -1, + 10194, 10194, 10194, -1, 10195, 10195, 10195, -1, + 10196, 10196, 10196, -1, 10197, 10197, 10197, -1, + 10198, 10198, 10198, -1, 10199, 10199, 10199, -1, + 10200, 10200, 10200, -1, 10201, 10201, 10201, -1, + 10202, 10202, 10202, -1, 10203, 10203, 10203, -1, + 10204, 10204, 10204, -1, 10205, 10205, 10205, -1, + 10206, 10206, 10206, -1, 10207, 10207, 10207, -1, + 10208, 10208, 10208, -1, 10209, 10209, 10209, -1, + 10210, 10210, 10210, -1, 10211, 10211, 10211, -1, + 10212, 10212, 10212, -1, 10213, 10213, 10213, -1, + 10214, 10214, 10214, -1, 10215, 10215, 10215, -1, + 10216, 10216, 10216, -1, 10217, 10217, 10217, -1, + 10218, 10218, 10218, -1, 10219, 10219, 10219, -1, + 10220, 10220, 10220, -1, 10221, 10221, 10221, -1, + 10222, 10222, 10222, -1, 10223, 10223, 10223, -1, + 10224, 10224, 10224, -1, 10225, 10225, 10225, -1, + 10226, 10226, 10226, -1, 10227, 10227, 10227, -1, + 10228, 10228, 10228, -1, 10229, 10229, 10229, -1, + 10230, 10230, 10230, -1, 10231, 10231, 10231, -1, + 10232, 10232, 10232, -1, 10233, 10233, 10233, -1, + 10234, 10234, 10234, -1, 10235, 10235, 10235, -1, + 10236, 10236, 10236, -1, 10237, 10237, 10237, -1, + 10238, 10238, 10238, -1, 10239, 10239, 10239, -1, + 10240, 10240, 10240, -1, 10241, 10241, 10241, -1, + 10242, 10242, 10242, -1, 10243, 10243, 10243, -1, + 10244, 10244, 10244, -1, 10245, 10245, 10245, -1, + 10246, 10246, 10246, -1, 10247, 10247, 10247, -1, + 10248, 10248, 10248, -1, 10249, 10249, 10249, -1, + 10250, 10250, 10250, -1, 10251, 10251, 10251, -1, + 10252, 10252, 10252, -1, 10253, 10253, 10253, -1, + 10254, 10254, 10254, -1, 10255, 10255, 10255, -1, + 10256, 10256, 10256, -1, 10257, 10257, 10257, -1, + 10258, 10258, 10258, -1, 10259, 10259, 10259, -1, + 10260, 10260, 10260, -1, 10261, 10261, 10261, -1, + 10262, 10262, 10262, -1, 10263, 10263, 10263, -1, + 10264, 10264, 10264, -1, 10265, 10265, 10265, -1, + 10266, 10266, 10266, -1, 10267, 10267, 10267, -1, + 10268, 10268, 10268, -1, 10269, 10269, 10269, -1, + 10270, 10270, 10270, -1, 10271, 10271, 10271, -1, + 10272, 10272, 10272, -1, 10273, 10273, 10273, -1, + 10274, 10274, 10274, -1, 10275, 10275, 10275, -1, + 10276, 10276, 10276, -1, 10277, 10277, 10277, -1, + 10278, 10278, 10278, -1, 10279, 10279, 10279, -1, + 10280, 10280, 10280, -1, 10281, 10281, 10281, -1, + 10282, 10282, 10282, -1, 10283, 10283, 10283, -1, + 10284, 10284, 10284, -1, 10285, 10285, 10285, -1, + 10286, 10286, 10286, -1, 10287, 10287, 10287, -1, + 10288, 10288, 10288, -1, 10289, 10289, 10289, -1, + 10290, 10290, 10290, -1, 10291, 10291, 10291, -1, + 10292, 10292, 10292, -1, 10293, 10293, 10293, -1, + 10294, 10294, 10294, -1, 10295, 10295, 10295, -1, + 10296, 10296, 10296, -1, 10297, 10297, 10297, -1, + 10298, 10298, 10298, -1, 10299, 10299, 10299, -1, + 10300, 10300, 10300, -1, 10301, 10301, 10301, -1, + 10302, 10302, 10302, -1, 10303, 10303, 10303, -1, + 10304, 10304, 10304, -1, 10305, 10305, 10305, -1, + 10306, 10306, 10306, -1, 10307, 10307, 10307, -1, + 10308, 10308, 10308, -1, 10309, 10309, 10309, -1, + 10310, 10310, 10310, -1, 10311, 10311, 10311, -1, + 10312, 10312, 10312, -1, 10313, 10313, 10313, -1, + 10314, 10314, 10314, -1, 10315, 10315, 10315, -1, + 10316, 10316, 10316, -1, 10317, 10317, 10317, -1, + 10318, 10318, 10318, -1, 10319, 10319, 10319, -1, + 10320, 10320, 10320, -1, 10321, 10321, 10321, -1, + 10322, 10322, 10322, -1, 10323, 10323, 10323, -1, + 10324, 10324, 10324, -1, 10325, 10325, 10325, -1, + 10326, 10326, 10326, -1, 10327, 10327, 10327, -1, + 10328, 10328, 10328, -1, 10329, 10329, 10329, -1, + 10330, 10330, 10330, -1, 10331, 10331, 10331, -1, + 10332, 10332, 10332, -1, 10333, 10333, 10333, -1, + 10334, 10334, 10334, -1, 10335, 10335, 10335, -1, + 10336, 10336, 10336, -1, 10337, 10337, 10337, -1, + 10338, 10338, 10338, -1, 10339, 10339, 10339, -1, + 10340, 10340, 10340, -1, 10341, 10341, 10341, -1, + 10342, 10342, 10342, -1, 10343, 10343, 10343, -1, + 10344, 10344, 10344, -1, 10345, 10345, 10345, -1, + 10346, 10346, 10346, -1, 10347, 10347, 10347, -1, + 10348, 10348, 10348, -1, 10349, 10349, 10349, -1, + 10350, 10350, 10350, -1, 10351, 10351, 10351, -1, + 10352, 10352, 10352, -1, 10353, 10353, 10353, -1, + 10354, 10354, 10354, -1, 10355, 10355, 10355, -1, + 10356, 10356, 10356, -1, 10357, 10357, 10357, -1, + 10358, 10358, 10358, -1, 10359, 10359, 10359, -1, + 10360, 10360, 10360, -1, 10361, 10361, 10361, -1, + 10362, 10362, 10362, -1, 10363, 10363, 10363, -1, + 10364, 10364, 10364, -1, 10365, 10365, 10365, -1, + 10366, 10366, 10366, -1, 10367, 10367, 10367, -1, + 10368, 10368, 10368, -1, 10369, 10369, 10369, -1, + 10370, 10370, 10370, -1, 10371, 10371, 10371, -1, + 10372, 10372, 10372, -1, 10373, 10373, 10373, -1, + 10374, 10374, 10374, -1, 10375, 10375, 10375, -1, + 10376, 10376, 10376, -1, 10377, 10377, 10377, -1, + 10378, 10378, 10378, -1, 10379, 10379, 10379, -1, + 10380, 10380, 10380, -1, 10381, 10381, 10381, -1, + 10382, 10382, 10382, -1, 10383, 10383, 10383, -1, + 10384, 10384, 10384, -1, 10385, 10385, 10385, -1, + 10386, 10386, 10386, -1, 10387, 10387, 10387, -1, + 10388, 10388, 10388, -1, 10389, 10389, 10389, -1, + 10390, 10390, 10390, -1, 10391, 10391, 10391, -1, + 10392, 10392, 10392, -1, 10393, 10393, 10393, -1, + 10394, 10394, 10394, -1, 10395, 10395, 10395, -1, + 10396, 10396, 10396, -1, 10397, 10397, 10397, -1, + 10398, 10398, 10398, -1, 10399, 10399, 10399, -1, + 10400, 10400, 10400, -1, 10401, 10401, 10401, -1, + 10402, 10402, 10402, -1, 10403, 10403, 10403, -1, + 10404, 10404, 10404, -1, 10405, 10405, 10405, -1, + 10406, 10406, 10406, -1, 10407, 10407, 10407, -1, + 10408, 10408, 10408, -1, 10409, 10409, 10409, -1, + 10410, 10410, 10410, -1, 10411, 10411, 10411, -1, + 10412, 10412, 10412, -1, 10413, 10413, 10413, -1, + 10414, 10414, 10414, -1, 10415, 10415, 10415, -1, + 10416, 10416, 10416, -1, 10417, 10417, 10417, -1, + 10418, 10418, 10418, -1, 10419, 10419, 10419, -1, + 10420, 10420, 10420, -1, 10421, 10421, 10421, -1, + 10422, 10422, 10422, -1, 10423, 10423, 10423, -1, + 10424, 10424, 10424, -1, 10425, 10425, 10425, -1, + 10426, 10426, 10426, -1, 10427, 10427, 10427, -1, + 10428, 10428, 10428, -1, 10429, 10429, 10429, -1, + 10430, 10430, 10430, -1, 10431, 10431, 10431, -1, + 10432, 10432, 10432, -1, 10433, 10433, 10433, -1, + 10434, 10434, 10434, -1, 10435, 10435, 10435, -1, + 10436, 10436, 10436, -1, 10437, 10437, 10437, -1, + 10438, 10438, 10438, -1, 10439, 10439, 10439, -1, + 10440, 10440, 10440, -1, 10441, 10441, 10441, -1, + 10442, 10442, 10442, -1, 10443, 10443, 10443, -1, + 10444, 10444, 10444, -1, 10445, 10445, 10445, -1, + 10446, 10446, 10446, -1, 10447, 10447, 10447, -1, + 10448, 10448, 10448, -1, 10449, 10449, 10449, -1, + 10450, 10450, 10450, -1, 10451, 10451, 10451, -1, + 10452, 10452, 10452, -1, 10453, 10453, 10453, -1, + 10454, 10454, 10454, -1, 10455, 10455, 10455, -1, + 10456, 10456, 10456, -1, 10457, 10457, 10457, -1, + 10458, 10458, 10458, -1, 10459, 10459, 10459, -1, + 10460, 10460, 10460, -1, 10461, 10461, 10461, -1, + 10462, 10462, 10462, -1, 10463, 10463, 10463, -1, + 10464, 10464, 10464, -1, 10465, 10465, 10465, -1, + 10466, 10466, 10466, -1, 10467, 10467, 10467, -1, + 10468, 10468, 10468, -1, 10469, 10469, 10469, -1, + 10470, 10470, 10470, -1, 10471, 10471, 10471, -1, + 10472, 10472, 10472, -1, 10473, 10473, 10473, -1, + 10474, 10474, 10474, -1, 10475, 10475, 10475, -1, + 10476, 10476, 10476, -1, 10477, 10477, 10477, -1, + 10478, 10478, 10478, -1, 10479, 10479, 10479, -1, + 10480, 10480, 10480, -1, 10481, 10481, 10481, -1, + 10482, 10482, 10482, -1, 10483, 10483, 10483, -1, + 10484, 10484, 10484, -1, 10485, 10485, 10485, -1, + 10486, 10486, 10486, -1, 10487, 10487, 10487, -1, + 10488, 10488, 10488, -1, 10489, 10489, 10489, -1, + 10490, 10490, 10490, -1, 10491, 10491, 10491, -1, + 10492, 10492, 10492, -1, 10493, 10493, 10493, -1, + 10494, 10494, 10494, -1, 10495, 10495, 10495, -1, + 10496, 10496, 10496, -1, 10497, 10497, 10497, -1, + 10498, 10498, 10498, -1, 10499, 10499, 10499, -1, + 10500, 10500, 10500, -1, 10501, 10501, 10501, -1, + 10502, 10502, 10502, -1, 10503, 10503, 10503, -1, + 10504, 10504, 10504, -1, 10505, 10505, 10505, -1, + 10506, 10506, 10506, -1, 10507, 10507, 10507, -1, + 10508, 10508, 10508, -1, 10509, 10509, 10509, -1, + 10510, 10510, 10510, -1, 10511, 10511, 10511, -1, + 10512, 10512, 10512, -1, 10513, 10513, 10513, -1, + 10514, 10514, 10514, -1, 10515, 10515, 10515, -1, + 10516, 10516, 10516, -1, 10517, 10517, 10517, -1, + 10518, 10518, 10518, -1, 10519, 10519, 10519, -1, + 10520, 10520, 10520, -1, 10521, 10521, 10521, -1, + 10522, 10522, 10522, -1, 10523, 10523, 10523, -1, + 10524, 10524, 10524, -1, 10525, 10525, 10525, -1, + 10526, 10526, 10526, -1, 10527, 10527, 10527, -1, + 10528, 10528, 10528, -1, 10529, 10529, 10529, -1, + 10530, 10530, 10530, -1, 10531, 10531, 10531, -1, + 10532, 10532, 10532, -1, 10533, 10533, 10533, -1, + 10534, 10534, 10534, -1, 10535, 10535, 10535, -1, + 10536, 10536, 10536, -1, 10537, 10537, 10537, -1, + 10538, 10538, 10538, -1, 10539, 10539, 10539, -1, + 10540, 10540, 10540, -1, 10541, 10541, 10541, -1, + 10542, 10542, 10542, -1, 10543, 10543, 10543, -1, + 10544, 10544, 10544, -1, 10545, 10545, 10545, -1, + 10546, 10546, 10546, -1, 10547, 10547, 10547, -1, + 10548, 10548, 10548, -1, 10549, 10549, 10549, -1, + 10550, 10550, 10550, -1, 10551, 10551, 10551, -1, + 10552, 10552, 10552, -1, 10553, 10553, 10553, -1, + 10554, 10554, 10554, -1, 10555, 10555, 10555, -1, + 10556, 10556, 10556, -1, 10557, 10557, 10557, -1, + 10558, 10558, 10558, -1, 10559, 10559, 10559, -1, + 10560, 10560, 10560, -1, 10561, 10561, 10561, -1, + 10562, 10562, 10562, -1, 10563, 10563, 10563, -1, + 10564, 10564, 10564, -1, 10565, 10565, 10565, -1, + 10566, 10566, 10566, -1, 10567, 10567, 10567, -1, + 10568, 10568, 10568, -1, 10569, 10569, 10569, -1, + 10570, 10570, 10570, -1, 10571, 10571, 10571, -1, + 10572, 10572, 10572, -1, 10573, 10573, 10573, -1, + 10574, 10574, 10574, -1, 10575, 10575, 10575, -1, + 10576, 10576, 10576, -1, 10577, 10577, 10577, -1, + 10578, 10578, 10578, -1, 10579, 10579, 10579, -1, + 10580, 10580, 10580, -1, 10581, 10581, 10581, -1, + 10582, 10582, 10582, -1, 10583, 10583, 10583, -1, + 10584, 10584, 10584, -1, 10585, 10585, 10585, -1, + 10586, 10586, 10586, -1, 10587, 10587, 10587, -1, + 10588, 10588, 10588, -1, 10589, 10589, 10589, -1, + 10590, 10590, 10590, -1, 10591, 10591, 10591, -1, + 10592, 10592, 10592, -1, 10593, 10593, 10593, -1, + 10594, 10594, 10594, -1, 10595, 10595, 10595, -1, + 10596, 10596, 10596, -1, 10597, 10597, 10597, -1, + 10598, 10598, 10598, -1, 10599, 10599, 10599, -1, + 10600, 10600, 10600, -1, 10601, 10601, 10601, -1, + 10602, 10602, 10602, -1, 10603, 10603, 10603, -1, + 10604, 10604, 10604, -1, 10605, 10605, 10605, -1, + 10606, 10606, 10606, -1, 10607, 10607, 10607, -1, + 10608, 10608, 10608, -1, 10609, 10609, 10609, -1, + 10610, 10610, 10610, -1, 10611, 10611, 10611, -1, + 10612, 10612, 10612, -1, 10613, 10613, 10613, -1, + 10614, 10614, 10614, -1, 10615, 10615, 10615, -1, + 10616, 10616, 10616, -1, 10617, 10617, 10617, -1, + 10618, 10618, 10618, -1, 10619, 10619, 10619, -1, + 10620, 10620, 10620, -1, 10621, 10621, 10621, -1, + 10622, 10622, 10622, -1, 10623, 10623, 10623, -1, + 10624, 10624, 10624, -1, 10625, 10625, 10625, -1, + 10626, 10626, 10626, -1, 10627, 10627, 10627, -1, + 10628, 10628, 10628, -1, 10629, 10629, 10629, -1, + 10630, 10630, 10630, -1, 10631, 10631, 10631, -1, + 10632, 10632, 10632, -1, 10633, 10633, 10633, -1, + 10634, 10634, 10634, -1, 10635, 10635, 10635, -1, + 10636, 10636, 10636, -1, 10637, 10637, 10637, -1, + 10638, 10638, 10638, -1, 10639, 10639, 10639, -1, + 10640, 10640, 10640, -1, 10641, 10641, 10641, -1, + 10642, 10642, 10642, -1, 10643, 10643, 10643, -1, + 10644, 10644, 10644, -1, 10645, 10645, 10645, -1, + 10646, 10646, 10646, -1, 10647, 10647, 10647, -1, + 10648, 10648, 10648, -1, 10649, 10649, 10649, -1, + 10650, 10650, 10650, -1, 10651, 10651, 10651, -1, + 10652, 10652, 10652, -1, 10653, 10653, 10653, -1, + 10654, 10654, 10654, -1, 10655, 10655, 10655, -1, + 10656, 10656, 10656, -1, 10657, 10657, 10657, -1, + 10658, 10658, 10658, -1, 10659, 10659, 10659, -1, + 10660, 10660, 10660, -1, 10661, 10661, 10661, -1, + 10662, 10662, 10662, -1, 10663, 10663, 10663, -1, + 10664, 10664, 10664, -1, 10665, 10665, 10665, -1, + 10666, 10666, 10666, -1, 10667, 10667, 10667, -1, + 10668, 10668, 10668, -1, 10669, 10669, 10669, -1, + 10670, 10670, 10670, -1, 10671, 10671, 10671, -1, + 10672, 10672, 10672, -1, 10673, 10673, 10673, -1, + 10674, 10674, 10674, -1, 10675, 10675, 10675, -1, + 10676, 10676, 10676, -1, 10677, 10677, 10677, -1, + 10678, 10678, 10678, -1, 10679, 10679, 10679, -1, + 10680, 10680, 10680, -1, 10681, 10681, 10681, -1, + 10682, 10682, 10682, -1, 10683, 10683, 10683, -1, + 10684, 10684, 10684, -1, 10685, 10685, 10685, -1, + 10686, 10686, 10686, -1, 10687, 10687, 10687, -1, + 10688, 10688, 10688, -1, 10689, 10689, 10689, -1, + 10690, 10690, 10690, -1, 10691, 10691, 10691, -1, + 10692, 10692, 10692, -1, 10693, 10693, 10693, -1, + 10694, 10694, 10694, -1, 10695, 10695, 10695, -1, + 10696, 10696, 10696, -1, 10697, 10697, 10697, -1, + 10698, 10698, 10698, -1, 10699, 10699, 10699, -1, + 10700, 10700, 10700, -1, 10701, 10701, 10701, -1, + 10702, 10702, 10702, -1, 10703, 10703, 10703, -1, + 10704, 10704, 10704, -1, 10705, 10705, 10705, -1, + 10706, 10706, 10706, -1, 10707, 10707, 10707, -1, + 10708, 10708, 10708, -1, 10709, 10709, 10709, -1, + 10710, 10710, 10710, -1, 10711, 10711, 10711, -1, + 10712, 10712, 10712, -1, 10713, 10713, 10713, -1, + 10714, 10714, 10714, -1, 10715, 10715, 10715, -1, + 10716, 10716, 10716, -1, 10717, 10717, 10717, -1, + 10718, 10718, 10718, -1, 10719, 10719, 10719, -1, + 10720, 10720, 10720, -1, 10721, 10721, 10721, -1, + 10722, 10722, 10722, -1, 10723, 10723, 10723, -1, + 10724, 10724, 10724, -1, 10725, 10725, 10725, -1, + 10726, 10726, 10726, -1, 10727, 10727, 10727, -1, + 10728, 10728, 10728, -1, 10729, 10729, 10729, -1, + 10730, 10730, 10730, -1, 10731, 10731, 10731, -1, + 10732, 10732, 10732, -1, 10733, 10733, 10733, -1, + 10734, 10734, 10734, -1, 10735, 10735, 10735, -1, + 10736, 10736, 10736, -1, 10737, 10737, 10737, -1, + 10738, 10738, 10738, -1, 10739, 10739, 10739, -1, + 10740, 10740, 10740, -1, 10741, 10741, 10741, -1, + 10742, 10742, 10742, -1, 10743, 10743, 10743, -1, + 10744, 10744, 10744, -1, 10745, 10745, 10745, -1, + 10746, 10746, 10746, -1, 10747, 10747, 10747, -1, + 10748, 10748, 10748, -1, 10749, 10749, 10749, -1, + 10750, 10750, 10750, -1, 10751, 10751, 10751, -1, + 10752, 10752, 10752, -1, 10753, 10753, 10753, -1, + 10754, 10754, 10754, -1, 10755, 10755, 10755, -1, + 10756, 10756, 10756, -1, 10757, 10757, 10757, -1, + 10758, 10758, 10758, -1, 10759, 10759, 10759, -1, + 10760, 10760, 10760, -1, 10761, 10761, 10761, -1, + 10762, 10762, 10762, -1, 10763, 10763, 10763, -1, + 10764, 10764, 10764, -1, 10765, 10765, 10765, -1, + 10766, 10766, 10766, -1, 10767, 10767, 10767, -1, + 10768, 10768, 10768, -1, 10769, 10769, 10769, -1, + 10770, 10770, 10770, -1, 10771, 10771, 10771, -1, + 10772, 10772, 10772, -1, 10773, 10773, 10773, -1, + 10774, 10774, 10774, -1, 10775, 10775, 10775, -1, + 10776, 10776, 10776, -1, 10777, 10777, 10777, -1, + 10778, 10778, 10778, -1, 10779, 10779, 10779, -1, + 10780, 10780, 10780, -1, 10781, 10781, 10781, -1, + 10782, 10782, 10782, -1, 10783, 10783, 10783, -1, + 10784, 10784, 10784, -1, 10785, 10785, 10785, -1, + 10786, 10786, 10786, -1, 10787, 10787, 10787, -1, + 10788, 10788, 10788, -1, 10789, 10789, 10789, -1, + 10790, 10790, 10790, -1, 10791, 10791, 10791, -1, + 10792, 10792, 10792, -1, 10793, 10793, 10793, -1, + 10794, 10794, 10794, -1, 10795, 10795, 10795, -1, + 10796, 10796, 10796, -1, 10797, 10797, 10797, -1, + 10798, 10798, 10798, -1, 10799, 10799, 10799, -1, + 10800, 10800, 10800, -1, 10801, 10801, 10801, -1, + 10802, 10802, 10802, -1, 10803, 10803, 10803, -1, + 10804, 10804, 10804, -1, 10805, 10805, 10805, -1, + 10806, 10806, 10806, -1, 10807, 10807, 10807, -1, + 10808, 10808, 10808, -1, 10809, 10809, 10809, -1, + 10810, 10810, 10810, -1, 10811, 10811, 10811, -1, + 10812, 10812, 10812, -1, 10813, 10813, 10813, -1, + 10814, 10814, 10814, -1, 10815, 10815, 10815, -1, + 10816, 10816, 10816, -1, 10817, 10817, 10817, -1, + 10818, 10818, 10818, -1, 10819, 10819, 10819, -1, + 10820, 10820, 10820, -1, 10821, 10821, 10821, -1, + 10822, 10822, 10822, -1, 10823, 10823, 10823, -1, + 10824, 10824, 10824, -1, 10825, 10825, 10825, -1, + 10826, 10826, 10826, -1, 10827, 10827, 10827, -1, + 10828, 10828, 10828, -1, 10829, 10829, 10829, -1, + 10830, 10830, 10830, -1, 10831, 10831, 10831, -1, + 10832, 10832, 10832, -1, 10833, 10833, 10833, -1, + 10834, 10834, 10834, -1, 10835, 10835, 10835, -1, + 10836, 10836, 10836, -1, 10837, 10837, 10837, -1, + 10838, 10838, 10838, -1, 10839, 10839, 10839, -1, + 10840, 10840, 10840, -1, 10841, 10841, 10841, -1, + 10842, 10842, 10842, -1, 10843, 10843, 10843, -1, + 10844, 10844, 10844, -1, 10845, 10845, 10845, -1, + 10846, 10846, 10846, -1, 10847, 10847, 10847, -1, + 10848, 10848, 10848, -1, 10849, 10849, 10849, -1, + 10850, 10850, 10850, -1, 10851, 10851, 10851, -1, + 10852, 10852, 10852, -1, 10853, 10853, 10853, -1, + 10854, 10854, 10854, -1, 10855, 10855, 10855, -1, + 10856, 10856, 10856, -1, 10857, 10857, 10857, -1, + 10858, 10858, 10858, -1, 10859, 10859, 10859, -1, + 10860, 10860, 10860, -1, 10861, 10861, 10861, -1, + 10862, 10862, 10862, -1, 10863, 10863, 10863, -1, + 10864, 10864, 10864, -1, 10865, 10865, 10865, -1, + 10866, 10866, 10866, -1, 10867, 10867, 10867, -1, + 10868, 10868, 10868, -1, 10869, 10869, 10869, -1, + 10870, 10870, 10870, -1, 10871, 10871, 10871, -1, + 10872, 10872, 10872, -1, 10873, 10873, 10873, -1, + 10874, 10874, 10874, -1, 10875, 10875, 10875, -1, + 10876, 10876, 10876, -1, 10877, 10877, 10877, -1, + 10878, 10878, 10878, -1, 10879, 10879, 10879, -1, + 10880, 10880, 10880, -1, 10881, 10881, 10881, -1, + 10882, 10882, 10882, -1, 10883, 10883, 10883, -1, + 10884, 10884, 10884, -1, 10885, 10885, 10885, -1, + 10886, 10886, 10886, -1, 10887, 10887, 10887, -1, + 10888, 10888, 10888, -1, 10889, 10889, 10889, -1, + 10890, 10890, 10890, -1, 10891, 10891, 10891, -1, + 10892, 10892, 10892, -1, 10893, 10893, 10893, -1, + 10894, 10894, 10894, -1, 10895, 10895, 10895, -1, + 10896, 10896, 10896, -1, 10897, 10897, 10897, -1, + 10898, 10898, 10898, -1, 10899, 10899, 10899, -1, + 10900, 10900, 10900, -1, 10901, 10901, 10901, -1, + 10902, 10902, 10902, -1, 10903, 10903, 10903, -1, + 10904, 10904, 10904, -1, 10905, 10905, 10905, -1, + 10906, 10906, 10906, -1, 10907, 10907, 10907, -1, + 10908, 10908, 10908, -1, 10909, 10909, 10909, -1, + 10910, 10910, 10910, -1, 10911, 10911, 10911, -1, + 10912, 10912, 10912, -1, 10913, 10913, 10913, -1, + 10914, 10914, 10914, -1, 10915, 10915, 10915, -1, + 10916, 10916, 10916, -1, 10917, 10917, 10917, -1, + 10918, 10918, 10918, -1, 10919, 10919, 10919, -1, + 10920, 10920, 10920, -1, 10921, 10921, 10921, -1, + 10922, 10922, 10922, -1, 10923, 10923, 10923, -1, + 10924, 10924, 10924, -1, 10925, 10925, 10925, -1, + 10926, 10926, 10926, -1, 10927, 10927, 10927, -1, + 10928, 10928, 10928, -1, 10929, 10929, 10929, -1, + 10930, 10930, 10930, -1, 10931, 10931, 10931, -1, + 10932, 10932, 10932, -1, 10933, 10933, 10933, -1, + 10934, 10934, 10934, -1, 10935, 10935, 10935, -1, + 10936, 10936, 10936, -1, 10937, 10937, 10937, -1, + 10938, 10938, 10938, -1, 10939, 10939, 10939, -1, + 10940, 10940, 10940, -1, 10941, 10941, 10941, -1, + 10942, 10942, 10942, -1, 10943, 10943, 10943, -1, + 10944, 10944, 10944, -1, 10945, 10945, 10945, -1, + 10946, 10946, 10946, -1, 10947, 10947, 10947, -1, + 10948, 10948, 10948, -1, 10949, 10949, 10949, -1, + 10950, 10950, 10950, -1, 10951, 10951, 10951, -1, + 10952, 10952, 10952, -1, 10953, 10953, 10953, -1, + 10954, 10954, 10954, -1, 10955, 10955, 10955, -1, + 10956, 10956, 10956, -1, 10957, 10957, 10957, -1, + 10958, 10958, 10958, -1, 10959, 10959, 10959, -1, + 10960, 10960, 10960, -1, 10961, 10961, 10961, -1, + 10962, 10962, 10962, -1, 10963, 10963, 10963, -1, + 10964, 10964, 10964, -1, 10965, 10965, 10965, -1, + 10966, 10966, 10966, -1, 10967, 10967, 10967, -1, + 10968, 10968, 10968, -1, 10969, 10969, 10969, -1, + 10970, 10970, 10970, -1, 10971, 10971, 10971, -1, + 10972, 10972, 10972, -1, 10973, 10973, 10973, -1, + 10974, 10974, 10974, -1, 10975, 10975, 10975, -1, + 10976, 10976, 10976, -1, 10977, 10977, 10977, -1, + 10978, 10978, 10978, -1, 10979, 10979, 10979, -1, + 10980, 10980, 10980, -1, 10981, 10981, 10981, -1, + 10982, 10982, 10982, -1, 10983, 10983, 10983, -1, + 10984, 10984, 10984, -1, 10985, 10985, 10985, -1, + 10986, 10986, 10986, -1, 10987, 10987, 10987, -1, + 10988, 10988, 10988, -1, 10989, 10989, 10989, -1, + 10990, 10990, 10990, -1, 10991, 10991, 10991, -1, + 10992, 10992, 10992, -1, 10993, 10993, 10993, -1, + 10994, 10994, 10994, -1, 10995, 10995, 10995, -1, + 10996, 10996, 10996, -1, 10997, 10997, 10997, -1, + 10998, 10998, 10998, -1, 10999, 10999, 10999, -1, + 11000, 11000, 11000, -1, 11001, 11001, 11001, -1, + 11002, 11002, 11002, -1, 11003, 11003, 11003, -1, + 11004, 11004, 11004, -1, 11005, 11005, 11005, -1, + 11006, 11006, 11006, -1, 11007, 11007, 11007, -1, + 11008, 11008, 11008, -1, 11009, 11009, 11009, -1, + 11010, 11010, 11010, -1, 11011, 11011, 11011, -1, + 11012, 11012, 11012, -1, 11013, 11013, 11013, -1, + 11014, 11014, 11014, -1, 11015, 11015, 11015, -1, + 11016, 11016, 11016, -1, 11017, 11017, 11017, -1, + 11018, 11018, 11018, -1, 11019, 11019, 11019, -1, + 11020, 11020, 11020, -1, 11021, 11021, 11021, -1, + 11022, 11022, 11022, -1, 11023, 11023, 11023, -1, + 11024, 11024, 11024, -1, 11025, 11025, 11025, -1, + 11026, 11026, 11026, -1, 11027, 11027, 11027, -1, + 11028, 11028, 11028, -1, 11029, 11029, 11029, -1, + 11030, 11030, 11030, -1, 11031, 11031, 11031, -1, + 11032, 11032, 11032, -1, 11033, 11033, 11033, -1, + 11034, 11034, 11034, -1, 11035, 11035, 11035, -1, + 11036, 11036, 11036, -1, 11037, 11037, 11037, -1, + 11038, 11038, 11038, -1, 11039, 11039, 11039, -1, + 11040, 11040, 11040, -1, 11041, 11041, 11041, -1, + 11042, 11042, 11042, -1, 11043, 11043, 11043, -1, + 11044, 11044, 11044, -1, 11045, 11045, 11045, -1, + 11046, 11046, 11046, -1, 11047, 11047, 11047, -1, + 11048, 11048, 11048, -1, 11049, 11049, 11049, -1, + 11050, 11050, 11050, -1, 11051, 11051, 11051, -1, + 11052, 11052, 11052, -1, 11053, 11053, 11053, -1, + 11054, 11054, 11054, -1, 11055, 11055, 11055, -1, + 11056, 11056, 11056, -1, 11057, 11057, 11057, -1, + 11058, 11058, 11058, -1, 11059, 11059, 11059, -1, + 11060, 11060, 11060, -1, 11061, 11061, 11061, -1, + 11062, 11062, 11062, -1, 11063, 11063, 11063, -1, + 11064, 11064, 11064, -1, 11065, 11065, 11065, -1, + 11066, 11066, 11066, -1, 11067, 11067, 11067, -1, + 11068, 11068, 11068, -1, 11069, 11069, 11069, -1, + 11070, 11070, 11070, -1, 11071, 11071, 11071, -1, + 11072, 11072, 11072, -1, 11073, 11073, 11073, -1, + 11074, 11074, 11074, -1, 11075, 11075, 11075, -1, + 11076, 11076, 11076, -1, 11077, 11077, 11077, -1, + 11078, 11078, 11078, -1, 11079, 11079, 11079, -1, + 11080, 11080, 11080, -1, 11081, 11081, 11081, -1, + 11082, 11082, 11082, -1, 11083, 11083, 11083, -1, + 11084, 11084, 11084, -1, 11085, 11085, 11085, -1, + 11086, 11086, 11086, -1, 11087, 11087, 11087, -1, + 11088, 11088, 11088, -1, 11089, 11089, 11089, -1, + 11090, 11090, 11090, -1, 11091, 11091, 11091, -1, + 11092, 11092, 11092, -1, 11093, 11093, 11093, -1, + 11094, 11094, 11094, -1, 11095, 11095, 11095, -1, + 11096, 11096, 11096, -1, 11097, 11097, 11097, -1, + 11098, 11098, 11098, -1, 11099, 11099, 11099, -1, + 11100, 11100, 11100, -1, 11101, 11101, 11101, -1, + 11102, 11102, 11102, -1, 11103, 11103, 11103, -1, + 11104, 11104, 11104, -1, 11105, 11105, 11105, -1, + 11106, 11106, 11106, -1, 11107, 11107, 11107, -1, + 11108, 11108, 11108, -1, 11109, 11109, 11109, -1, + 11110, 11110, 11110, -1, 11111, 11111, 11111, -1, + 11112, 11112, 11112, -1, 11113, 11113, 11113, -1, + 11114, 11114, 11114, -1, 11115, 11115, 11115, -1, + 11116, 11116, 11116, -1, 11117, 11117, 11117, -1, + 11118, 11118, 11118, -1, 11119, 11119, 11119, -1, + 11120, 11120, 11120, -1, 11121, 11121, 11121, -1, + 11122, 11122, 11122, -1, 11123, 11123, 11123, -1, + 11124, 11124, 11124, -1, 11125, 11125, 11125, -1, + 11126, 11126, 11126, -1, 11127, 11127, 11127, -1, + 11128, 11128, 11128, -1, 11129, 11129, 11129, -1, + 11130, 11130, 11130, -1, 11131, 11131, 11131, -1, + 11132, 11132, 11132, -1, 11133, 11133, 11133, -1, + 11134, 11134, 11134, -1, 11135, 11135, 11135, -1, + 11136, 11136, 11136, -1, 11137, 11137, 11137, -1, + 11138, 11138, 11138, -1, 11139, 11139, 11139, -1, + 11140, 11140, 11140, -1, 11141, 11141, 11141, -1, + 11142, 11142, 11142, -1, 11143, 11143, 11143, -1, + 11144, 11144, 11144, -1, 11145, 11145, 11145, -1, + 11146, 11146, 11146, -1, 11147, 11147, 11147, -1, + 11148, 11148, 11148, -1, 11149, 11149, 11149, -1, + 11150, 11150, 11150, -1, 11151, 11151, 11151, -1, + 11152, 11152, 11152, -1, 11153, 11153, 11153, -1, + 11154, 11154, 11154, -1, 11155, 11155, 11155, -1, + 11156, 11156, 11156, -1, 11157, 11157, 11157, -1, + 11158, 11158, 11158, -1, 11159, 11159, 11159, -1, + 11160, 11160, 11160, -1, 11161, 11161, 11161, -1, + 11162, 11162, 11162, -1, 11163, 11163, 11163, -1, + 11164, 11164, 11164, -1, 11165, 11165, 11165, -1, + 11166, 11166, 11166, -1, 11167, 11167, 11167, -1, + 11168, 11168, 11168, -1, 11169, 11169, 11169, -1, + 11170, 11170, 11170, -1, 11171, 11171, 11171, -1, + 11172, 11172, 11172, -1, 11173, 11173, 11173, -1, + 11174, 11174, 11174, -1, 11175, 11175, 11175, -1, + 11176, 11176, 11176, -1, 11177, 11177, 11177, -1, + 11178, 11178, 11178, -1, 11179, 11179, 11179, -1, + 11180, 11180, 11180, -1, 11181, 11181, 11181, -1, + 11182, 11182, 11182, -1, 11183, 11183, 11183, -1, + 11184, 11184, 11184, -1, 11185, 11185, 11185, -1, + 11186, 11186, 11186, -1, 11187, 11187, 11187, -1, + 11188, 11188, 11188, -1, 11189, 11189, 11189, -1, + 11190, 11190, 11190, -1, 11191, 11191, 11191, -1, + 11192, 11192, 11192, -1, 11193, 11193, 11193, -1, + 11194, 11194, 11194, -1, 11195, 11195, 11195, -1, + 11196, 11196, 11196, -1, 11197, 11197, 11197, -1, + 11198, 11198, 11198, -1, 11199, 11199, 11199, -1, + 11200, 11200, 11200, -1, 11201, 11201, 11201, -1, + 11202, 11202, 11202, -1, 11203, 11203, 11203, -1, + 11204, 11204, 11204, -1, 11205, 11205, 11205, -1, + 11206, 11206, 11206, -1, 11207, 11207, 11207, -1, + 11208, 11208, 11208, -1, 11209, 11209, 11209, -1, + 11210, 11210, 11210, -1, 11211, 11211, 11211, -1, + 11212, 11212, 11212, -1, 11213, 11213, 11213, -1, + 11214, 11214, 11214, -1, 11215, 11215, 11215, -1, + 11216, 11216, 11216, -1, 11217, 11217, 11217, -1, + 11218, 11218, 11218, -1, 11219, 11219, 11219, -1, + 11220, 11220, 11220, -1, 11221, 11221, 11221, -1, + 11222, 11222, 11222, -1, 11223, 11223, 11223, -1, + 11224, 11224, 11224, -1, 11225, 11225, 11225, -1, + 11226, 11226, 11226, -1, 11227, 11227, 11227, -1, + 11228, 11228, 11228, -1, 11229, 11229, 11229, -1, + 11230, 11230, 11230, -1, 11231, 11231, 11231, -1, + 11232, 11232, 11232, -1, 11233, 11233, 11233, -1, + 11234, 11234, 11234, -1, 11235, 11235, 11235, -1, + 11236, 11236, 11236, -1, 11237, 11237, 11237, -1, + 11238, 11238, 11238, -1, 11239, 11239, 11239, -1, + 11240, 11240, 11240, -1, 11241, 11241, 11241, -1, + 11242, 11242, 11242, -1, 11243, 11243, 11243, -1, + 11244, 11244, 11244, -1, 11245, 11245, 11245, -1, + 11246, 11246, 11246, -1, 11247, 11247, 11247, -1, + 11248, 11248, 11248, -1, 11249, 11249, 11249, -1, + 11250, 11250, 11250, -1, 11251, 11251, 11251, -1, + 11252, 11252, 11252, -1, 11253, 11253, 11253, -1, + 11254, 11254, 11254, -1, 11255, 11255, 11255, -1, + 11256, 11256, 11256, -1, 11257, 11257, 11257, -1, + 11258, 11258, 11258, -1, 11259, 11259, 11259, -1, + 11260, 11260, 11260, -1, 11261, 11261, 11261, -1, + 11262, 11262, 11262, -1, 11263, 11263, 11263, -1, + 11264, 11264, 11264, -1, 11265, 11265, 11265, -1, + 11266, 11266, 11266, -1, 11267, 11267, 11267, -1, + 11268, 11268, 11268, -1, 11269, 11269, 11269, -1, + 11270, 11270, 11270, -1, 11271, 11271, 11271, -1, + 11272, 11272, 11272, -1, 11273, 11273, 11273, -1, + 11274, 11274, 11274, -1, 11275, 11275, 11275, -1, + 11276, 11276, 11276, -1, 11277, 11277, 11277, -1, + 11278, 11278, 11278, -1, 11279, 11279, 11279, -1, + 11280, 11280, 11280, -1, 11281, 11281, 11281, -1, + 11282, 11282, 11282, -1, 11283, 11283, 11283, -1, + 11284, 11284, 11284, -1, 11285, 11285, 11285, -1, + 11286, 11286, 11286, -1, 11287, 11287, 11287, -1, + 11288, 11288, 11288, -1, 11289, 11289, 11289, -1, + 11290, 11290, 11290, -1, 11291, 11291, 11291, -1, + 11292, 11292, 11292, -1, 11293, 11293, 11293, -1, + 11294, 11294, 11294, -1, 11295, 11295, 11295, -1, + 11296, 11296, 11296, -1, 11297, 11297, 11297, -1, + 11298, 11298, 11298, -1, 11299, 11299, 11299, -1, + 11300, 11300, 11300, -1, 11301, 11301, 11301, -1, + 11302, 11302, 11302, -1, 11303, 11303, 11303, -1, + 11304, 11304, 11304, -1, 11305, 11305, 11305, -1, + 11306, 11306, 11306, -1, 11307, 11307, 11307, -1, + 11308, 11308, 11308, -1, 11309, 11309, 11309, -1, + 11310, 11310, 11310, -1, 11311, 11311, 11311, -1, + 11312, 11312, 11312, -1, 11313, 11313, 11313, -1, + 11314, 11314, 11314, -1, 11315, 11315, 11315, -1, + 11316, 11316, 11316, -1, 11317, 11317, 11317, -1, + 11318, 11318, 11318, -1, 11319, 11319, 11319, -1, + 11320, 11320, 11320, -1, 11321, 11321, 11321, -1, + 11322, 11322, 11322, -1, 11323, 11323, 11323, -1, + 11324, 11324, 11324, -1, 11325, 11325, 11325, -1, + 11326, 11326, 11326, -1, 11327, 11327, 11327, -1, + 11328, 11328, 11328, -1, 11329, 11329, 11329, -1, + 11330, 11330, 11330, -1, 11331, 11331, 11331, -1, + 11332, 11332, 11332, -1, 11333, 11333, 11333, -1, + 11334, 11334, 11334, -1, 11335, 11335, 11335, -1, + 11336, 11336, 11336, -1, 11337, 11337, 11337, -1, + 11338, 11338, 11338, -1, 11339, 11339, 11339, -1, + 11340, 11340, 11340, -1, 11341, 11341, 11341, -1, + 11342, 11342, 11342, -1, 11343, 11343, 11343, -1, + 11344, 11344, 11344, -1, 11345, 11345, 11345, -1, + 11346, 11346, 11346, -1, 11347, 11347, 11347, -1, + 11348, 11348, 11348, -1, 11349, 11349, 11349, -1, + 11350, 11350, 11350, -1, 11351, 11351, 11351, -1, + 11352, 11352, 11352, -1, 11353, 11353, 11353, -1, + 11354, 11354, 11354, -1, 11355, 11355, 11355, -1, + 11356, 11356, 11356, -1, 11357, 11357, 11357, -1, + 11358, 11358, 11358, -1, 11359, 11359, 11359, -1, + 11360, 11360, 11360, -1, 11361, 11361, 11361, -1, + 11362, 11362, 11362, -1, 11363, 11363, 11363, -1, + 11364, 11364, 11364, -1, 11365, 11365, 11365, -1, + 11366, 11366, 11366, -1, 11367, 11367, 11367, -1, + 11368, 11368, 11368, -1, 11369, 11369, 11369, -1, + 11370, 11370, 11370, -1, 11371, 11371, 11371, -1, + 11372, 11372, 11372, -1, 11373, 11373, 11373, -1, + 11374, 11374, 11374, -1, 11375, 11375, 11375, -1, + 11376, 11376, 11376, -1, 11377, 11377, 11377, -1, + 11378, 11378, 11378, -1, 11379, 11379, 11379, -1, + 11380, 11380, 11380, -1, 11381, 11381, 11381, -1, + 11382, 11382, 11382, -1, 11383, 11383, 11383, -1, + 11384, 11384, 11384, -1, 11385, 11385, 11385, -1, + 11386, 11386, 11386, -1, 11387, 11387, 11387, -1, + 11388, 11388, 11388, -1, 11389, 11389, 11389, -1, + 11390, 11390, 11390, -1, 11391, 11391, 11391, -1, + 11392, 11392, 11392, -1, 11393, 11393, 11393, -1, + 11394, 11394, 11394, -1, 11395, 11395, 11395, -1, + 11396, 11396, 11396, -1, 11397, 11397, 11397, -1, + 11398, 11398, 11398, -1, 11399, 11399, 11399, -1, + 11400, 11400, 11400, -1, 11401, 11401, 11401, -1, + 11402, 11402, 11402, -1, 11403, 11403, 11403, -1, + 11404, 11404, 11404, -1, 11405, 11405, 11405, -1, + 11406, 11406, 11406, -1, 11407, 11407, 11407, -1, + 11408, 11408, 11408, -1, 11409, 11409, 11409, -1, + 11410, 11410, 11410, -1, 11411, 11411, 11411, -1, + 11412, 11412, 11412, -1, 11413, 11413, 11413, -1, + 11414, 11414, 11414, -1, 11415, 11415, 11415, -1, + 11416, 11416, 11416, -1, 11417, 11417, 11417, -1, + 11418, 11418, 11418, -1, 11419, 11419, 11419, -1, + 11420, 11420, 11420, -1, 11421, 11421, 11421, -1, + 11422, 11422, 11422, -1, 11423, 11423, 11423, -1, + 11424, 11424, 11424, -1, 11425, 11425, 11425, -1, + 11426, 11426, 11426, -1, 11427, 11427, 11427, -1, + 11428, 11428, 11428, -1, 11429, 11429, 11429, -1, + 11430, 11430, 11430, -1, 11431, 11431, 11431, -1, + 11432, 11432, 11432, -1, 11433, 11433, 11433, -1, + 11434, 11434, 11434, -1, 11435, 11435, 11435, -1, + 11436, 11436, 11436, -1, 11437, 11437, 11437, -1, + 11438, 11438, 11438, -1, 11439, 11439, 11439, -1, + 11440, 11440, 11440, -1, 11441, 11441, 11441, -1, + 11442, 11442, 11442, -1, 11443, 11443, 11443, -1, + 11444, 11444, 11444, -1, 11445, 11445, 11445, -1, + 11446, 11446, 11446, -1, 11447, 11447, 11447, -1, + 11448, 11448, 11448, -1, 11449, 11449, 11449, -1, + 11450, 11450, 11450, -1, 11451, 11451, 11451, -1, + 11452, 11452, 11452, -1, 11453, 11453, 11453, -1, + 11454, 11454, 11454, -1, 11455, 11455, 11455, -1, + 11456, 11456, 11456, -1, 11457, 11457, 11457, -1, + 11458, 11458, 11458, -1, 11459, 11459, 11459, -1, + 11460, 11460, 11460, -1, 11461, 11461, 11461, -1, + 11462, 11462, 11462, -1, 11463, 11463, 11463, -1, + 11464, 11464, 11464, -1, 11465, 11465, 11465, -1, + 11466, 11466, 11466, -1, 11467, 11467, 11467, -1, + 11468, 11468, 11468, -1, 11469, 11469, 11469, -1, + 11470, 11470, 11470, -1, 11471, 11471, 11471, -1, + 11472, 11472, 11472, -1, 11473, 11473, 11473, -1, + 11474, 11474, 11474, -1, 11475, 11475, 11475, -1, + 11476, 11476, 11476, -1, 11477, 11477, 11477, -1, + 11478, 11478, 11478, -1, 11479, 11479, 11479, -1, + 11480, 11480, 11480, -1, 11481, 11481, 11481, -1, + 11482, 11482, 11482, -1, 11483, 11483, 11483, -1, + 11484, 11484, 11484, -1, 11485, 11485, 11485, -1, + 11486, 11486, 11486, -1, 11487, 11487, 11487, -1, + 11488, 11488, 11488, -1, 11489, 11489, 11489, -1, + 11490, 11490, 11490, -1, 11491, 11491, 11491, -1, + 11492, 11492, 11492, -1, 11493, 11493, 11493, -1, + 11494, 11494, 11494, -1, 11495, 11495, 11495, -1, + 11496, 11496, 11496, -1, 11497, 11497, 11497, -1, + 11498, 11498, 11498, -1, 11499, 11499, 11499, -1, + 11500, 11500, 11500, -1, 11501, 11501, 11501, -1, + 11502, 11502, 11502, -1, 11503, 11503, 11503, -1, + 11504, 11504, 11504, -1, 11505, 11505, 11505, -1, + 11506, 11506, 11506, -1, 11507, 11507, 11507, -1, + 11508, 11508, 11508, -1, 11509, 11509, 11509, -1, + 11510, 11510, 11510, -1, 11511, 11511, 11511, -1, + 11512, 11512, 11512, -1, 11513, 11513, 11513, -1, + 11514, 11514, 11514, -1, 11515, 11515, 11515, -1, + 11516, 11516, 11516, -1, 11517, 11517, 11517, -1, + 11518, 11518, 11518, -1, 11519, 11519, 11519, -1, + 11520, 11520, 11520, -1, 11521, 11521, 11521, -1, + 11522, 11522, 11522, -1, 11523, 11523, 11523, -1, + 11524, 11524, 11524, -1, 11525, 11525, 11525, -1, + 11526, 11526, 11526, -1, 11527, 11527, 11527, -1, + 11528, 11528, 11528, -1, 11529, 11529, 11529, -1, + 11530, 11530, 11530, -1, 11531, 11531, 11531, -1, + 11532, 11532, 11532, -1, 11533, 11533, 11533, -1, + 11534, 11534, 11534, -1, 11535, 11535, 11535, -1, + 11536, 11536, 11536, -1, 11537, 11537, 11537, -1, + 11538, 11538, 11538, -1, 11539, 11539, 11539, -1, + 11540, 11540, 11540, -1, 11541, 11541, 11541, -1, + 11542, 11542, 11542, -1, 11543, 11543, 11543, -1, + 11544, 11544, 11544, -1, 11545, 11545, 11545, -1, + 11546, 11546, 11546, -1, 11547, 11547, 11547, -1, + 11548, 11548, 11548, -1, 11549, 11549, 11549, -1, + 11550, 11550, 11550, -1, 11551, 11551, 11551, -1, + 11552, 11552, 11552, -1, 11553, 11553, 11553, -1, + 11554, 11554, 11554, -1, 11555, 11555, 11555, -1, + 11556, 11556, 11556, -1, 11557, 11557, 11557, -1, + 11558, 11558, 11558, -1, 11559, 11559, 11559, -1, + 11560, 11560, 11560, -1, 11561, 11561, 11561, -1, + 11562, 11562, 11562, -1, 11563, 11563, 11563, -1, + 11564, 11564, 11564, -1, 11565, 11565, 11565, -1, + 11566, 11566, 11566, -1, 11567, 11567, 11567, -1, + 11568, 11568, 11568, -1, 11569, 11569, 11569, -1, + 11570, 11570, 11570, -1, 11571, 11571, 11571, -1, + 11572, 11572, 11572, -1, 11573, 11573, 11573, -1, + 11574, 11574, 11574, -1, 11575, 11575, 11575, -1, + 11576, 11576, 11576, -1, 11577, 11577, 11577, -1, + 11578, 11578, 11578, -1, 11579, 11579, 11579, -1, + 11580, 11580, 11580, -1, 11581, 11581, 11581, -1, + 11582, 11582, 11582, -1, 11583, 11583, 11583, -1, + 11584, 11584, 11584, -1, 11585, 11585, 11585, -1, + 11586, 11586, 11586, -1, 11587, 11587, 11587, -1, + 11588, 11588, 11588, -1, 11589, 11589, 11589, -1, + 11590, 11590, 11590, -1, 11591, 11591, 11591, -1, + 11592, 11592, 11592, -1, 11593, 11593, 11593, -1, + 11594, 11594, 11594, -1, 11595, 11595, 11595, -1, + 11596, 11596, 11596, -1, 11597, 11597, 11597, -1, + 11598, 11598, 11598, -1, 11599, 11599, 11599, -1, + 11600, 11600, 11600, -1, 11601, 11601, 11601, -1, + 11602, 11602, 11602, -1, 11603, 11603, 11603, -1, + 11604, 11604, 11604, -1, 11605, 11605, 11605, -1, + 11606, 11606, 11606, -1, 11607, 11607, 11607, -1, + 11608, 11608, 11608, -1, 11609, 11609, 11609, -1, + 11610, 11610, 11610, -1, 11611, 11611, 11611, -1, + 11612, 11612, 11612, -1, 11613, 11613, 11613, -1, + 11614, 11614, 11614, -1, 11615, 11615, 11615, -1, + 11616, 11616, 11616, -1, 11617, 11617, 11617, -1, + 11618, 11618, 11618, -1, 11619, 11619, 11619, -1, + 11620, 11620, 11620, -1, 11621, 11621, 11621, -1, + 11622, 11622, 11622, -1, 11623, 11623, 11623, -1, + 11624, 11624, 11624, -1, 11625, 11625, 11625, -1, + 11626, 11626, 11626, -1, 11627, 11627, 11627, -1, + 11628, 11628, 11628, -1, 11629, 11629, 11629, -1, + 11630, 11630, 11630, -1, 11631, 11631, 11631, -1, + 11632, 11632, 11632, -1, 11633, 11633, 11633, -1, + 11634, 11634, 11634, -1, 11635, 11635, 11635, -1, + 11636, 11636, 11636, -1, 11637, 11637, 11637, -1, + 11638, 11638, 11638, -1, 11639, 11639, 11639, -1, + 11640, 11640, 11640, -1, 11641, 11641, 11641, -1, + 11642, 11642, 11642, -1, 11643, 11643, 11643, -1, + 11644, 11644, 11644, -1, 11645, 11645, 11645, -1, + 11646, 11646, 11646, -1, 11647, 11647, 11647, -1, + 11648, 11648, 11648, -1, 11649, 11649, 11649, -1, + 11650, 11650, 11650, -1, 11651, 11651, 11651, -1, + 11652, 11652, 11652, -1, 11653, 11653, 11653, -1, + 11654, 11654, 11654, -1, 11655, 11655, 11655, -1, + 11656, 11656, 11656, -1, 11657, 11657, 11657, -1, + 11658, 11658, 11658, -1, 11659, 11659, 11659, -1, + 11660, 11660, 11660, -1, 11661, 11661, 11661, -1, + 11662, 11662, 11662, -1, 11663, 11663, 11663, -1, + 11664, 11664, 11664, -1, 11665, 11665, 11665, -1, + 11666, 11666, 11666, -1, 11667, 11667, 11667, -1, + 11668, 11668, 11668, -1, 11669, 11669, 11669, -1, + 11670, 11670, 11670, -1, 11671, 11671, 11671, -1, + 11672, 11672, 11672, -1, 11673, 11673, 11673, -1, + 11674, 11674, 11674, -1, 11675, 11675, 11675, -1, + 11676, 11676, 11676, -1, 11677, 11677, 11677, -1, + 11678, 11678, 11678, -1, 11679, 11679, 11679, -1, + 11680, 11680, 11680, -1, 11681, 11681, 11681, -1, + 11682, 11682, 11682, -1, 11683, 11683, 11683, -1, + 11684, 11684, 11684, -1, 11685, 11685, 11685, -1, + 11686, 11686, 11686, -1, 11687, 11687, 11687, -1, + 11688, 11688, 11688, -1, 11689, 11689, 11689, -1, + 11690, 11690, 11690, -1, 11691, 11691, 11691, -1, + 11692, 11692, 11692, -1, 11693, 11693, 11693, -1, + 11694, 11694, 11694, -1, 11695, 11695, 11695, -1, + 11696, 11696, 11696, -1, 11697, 11697, 11697, -1, + 11698, 11698, 11698, -1, 11699, 11699, 11699, -1, + 11700, 11700, 11700, -1, 11701, 11701, 11701, -1, + 11702, 11702, 11702, -1, 11703, 11703, 11703, -1, + 11704, 11704, 11704, -1, 11705, 11705, 11705, -1, + 11706, 11706, 11706, -1, 11707, 11707, 11707, -1, + 11708, 11708, 11708, -1, 11709, 11709, 11709, -1, + 11710, 11710, 11710, -1, 11711, 11711, 11711, -1, + 11712, 11712, 11712, -1, 11713, 11713, 11713, -1, + 11714, 11714, 11714, -1, 11715, 11715, 11715, -1, + 11716, 11716, 11716, -1, 11717, 11717, 11717, -1, + 11718, 11718, 11718, -1, 11719, 11719, 11719, -1, + 11720, 11720, 11720, -1, 11721, 11721, 11721, -1, + 11722, 11722, 11722, -1, 11723, 11723, 11723, -1, + 11724, 11724, 11724, -1, 11725, 11725, 11725, -1, + 11726, 11726, 11726, -1, 11727, 11727, 11727, -1, + 11728, 11728, 11728, -1, 11729, 11729, 11729, -1, + 11730, 11730, 11730, -1, 11731, 11731, 11731, -1, + 11732, 11732, 11732, -1, 11733, 11733, 11733, -1, + 11734, 11734, 11734, -1, 11735, 11735, 11735, -1, + 11736, 11736, 11736, -1, 11737, 11737, 11737, -1, + 11738, 11738, 11738, -1, 11739, 11739, 11739, -1, + 11740, 11740, 11740, -1, 11741, 11741, 11741, -1, + 11742, 11742, 11742, -1, 11743, 11743, 11743, -1, + 11744, 11744, 11744, -1, 11745, 11745, 11745, -1, + 11746, 11746, 11746, -1, 11747, 11747, 11747, -1, + 11748, 11748, 11748, -1, 11749, 11749, 11749, -1, + 11750, 11750, 11750, -1, 11751, 11751, 11751, -1, + 11752, 11752, 11752, -1, 11753, 11753, 11753, -1, + 11754, 11754, 11754, -1, 11755, 11755, 11755, -1, + 11756, 11756, 11756, -1, 11757, 11757, 11757, -1, + 11758, 11758, 11758, -1, 11759, 11759, 11759, -1, + 11760, 11760, 11760, -1, 11761, 11761, 11761, -1, + 11762, 11762, 11762, -1, 11763, 11763, 11763, -1, + 11764, 11764, 11764, -1, 11765, 11765, 11765, -1, + 11766, 11766, 11766, -1, 11767, 11767, 11767, -1, + 11768, 11768, 11768, -1, 11769, 11769, 11769, -1, + 11770, 11770, 11770, -1, 11771, 11771, 11771, -1, + 11772, 11772, 11772, -1, 11773, 11773, 11773, -1, + 11774, 11774, 11774, -1, 11775, 11775, 11775, -1, + 11776, 11776, 11776, -1, 11777, 11777, 11777, -1, + 11778, 11778, 11778, -1, 11779, 11779, 11779, -1, + 11780, 11780, 11780, -1, 11781, 11781, 11781, -1, + 11782, 11782, 11782, -1, 11783, 11783, 11783, -1, + 11784, 11784, 11784, -1, 11785, 11785, 11785, -1, + 11786, 11786, 11786, -1, 11787, 11787, 11787, -1, + 11788, 11788, 11788, -1, 11789, 11789, 11789, -1, + 11790, 11790, 11790, -1, 11791, 11791, 11791, -1, + 11792, 11792, 11792, -1, 11793, 11793, 11793, -1, + 11794, 11794, 11794, -1, 11795, 11795, 11795, -1, + 11796, 11796, 11796, -1, 11797, 11797, 11797, -1, + 11798, 11798, 11798, -1, 11799, 11799, 11799, -1, + 11800, 11800, 11800, -1, 11801, 11801, 11801, -1, + 11802, 11802, 11802, -1, 11803, 11803, 11803, -1, + 11804, 11804, 11804, -1, 11805, 11805, 11805, -1, + 11806, 11806, 11806, -1, 11807, 11807, 11807, -1, + 11808, 11808, 11808, -1, 11809, 11809, 11809, -1, + 11810, 11810, 11810, -1, 11811, 11811, 11811, -1, + 11812, 11812, 11812, -1, 11813, 11813, 11813, -1, + 11814, 11814, 11814, -1, 11815, 11815, 11815, -1, + 11816, 11816, 11816, -1, 11817, 11817, 11817, -1, + 11818, 11818, 11818, -1, 11819, 11819, 11819, -1, + 11820, 11820, 11820, -1, 11821, 11821, 11821, -1, + 11822, 11822, 11822, -1, 11823, 11823, 11823, -1, + 11824, 11824, 11824, -1, 11825, 11825, 11825, -1, + 11826, 11826, 11826, -1, 11827, 11827, 11827, -1, + 11828, 11828, 11828, -1, 11829, 11829, 11829, -1, + 11830, 11830, 11830, -1, 11831, 11831, 11831, -1, + 11832, 11832, 11832, -1, 11833, 11833, 11833, -1, + 11834, 11834, 11834, -1, 11835, 11835, 11835, -1, + 11836, 11836, 11836, -1, 11837, 11837, 11837, -1, + 11838, 11838, 11838, -1, 11839, 11839, 11839, -1, + 11840, 11840, 11840, -1, 11841, 11841, 11841, -1, + 11842, 11842, 11842, -1, 11843, 11843, 11843, -1, + 11844, 11844, 11844, -1, 11845, 11845, 11845, -1, + 11846, 11846, 11846, -1, 11847, 11847, 11847, -1, + 11848, 11848, 11848, -1, 11849, 11849, 11849, -1, + 11850, 11850, 11850, -1, 11851, 11851, 11851, -1, + 11852, 11852, 11852, -1, 11853, 11853, 11853, -1, + 11854, 11854, 11854, -1, 11855, 11855, 11855, -1, + 11856, 11856, 11856, -1, 11857, 11857, 11857, -1, + 11858, 11858, 11858, -1, 11859, 11859, 11859, -1, + 11860, 11860, 11860, -1, 11861, 11861, 11861, -1, + 11862, 11862, 11862, -1, 11863, 11863, 11863, -1, + 11864, 11864, 11864, -1, 11865, 11865, 11865, -1, + 11866, 11866, 11866, -1, 11867, 11867, 11867, -1, + 11868, 11868, 11868, -1, 11869, 11869, 11869, -1, + 11870, 11870, 11870, -1, 11871, 11871, 11871, -1, + 11872, 11872, 11872, -1, 11873, 11873, 11873, -1, + 11874, 11874, 11874, -1, 11875, 11875, 11875, -1, + 11876, 11876, 11876, -1, 11877, 11877, 11877, -1, + 11878, 11878, 11878, -1, 11879, 11879, 11879, -1, + 11880, 11880, 11880, -1, 11881, 11881, 11881, -1, + 11882, 11882, 11882, -1, 11883, 11883, 11883, -1, + 11884, 11884, 11884, -1, 11885, 11885, 11885, -1, + 11886, 11886, 11886, -1, 11887, 11887, 11887, -1, + 11888, 11888, 11888, -1, 11889, 11889, 11889, -1, + 11890, 11890, 11890, -1, 11891, 11891, 11891, -1, + 11892, 11892, 11892, -1, 11893, 11893, 11893, -1, + 11894, 11894, 11894, -1, 11895, 11895, 11895, -1, + 11896, 11896, 11896, -1, 11897, 11897, 11897, -1, + 11898, 11898, 11898, -1, 11899, 11899, 11899, -1, + 11900, 11900, 11900, -1, 11901, 11901, 11901, -1, + 11902, 11902, 11902, -1, 11903, 11903, 11903, -1, + 11904, 11904, 11904, -1, 11905, 11905, 11905, -1, + 11906, 11906, 11906, -1, 11907, 11907, 11907, -1, + 11908, 11908, 11908, -1, 11909, 11909, 11909, -1, + 11910, 11910, 11910, -1, 11911, 11911, 11911, -1, + 11912, 11912, 11912, -1, 11913, 11913, 11913, -1, + 11914, 11914, 11914, -1, 11915, 11915, 11915, -1, + 11916, 11916, 11916, -1, 11917, 11917, 11917, -1, + 11918, 11918, 11918, -1, 11919, 11919, 11919, -1, + 11920, 11920, 11920, -1, 11921, 11921, 11921, -1, + 11922, 11922, 11922, -1, 11923, 11923, 11923, -1, + 11924, 11924, 11924, -1, 11925, 11925, 11925, -1, + 11926, 11926, 11926, -1, 11927, 11927, 11927, -1, + 11928, 11928, 11928, -1, 11929, 11929, 11929, -1, + 11930, 11930, 11930, -1, 11931, 11931, 11931, -1, + 11932, 11932, 11932, -1, 11933, 11933, 11933, -1, + 11934, 11934, 11934, -1, 11935, 11935, 11935, -1, + 11936, 11936, 11936, -1, 11937, 11937, 11937, -1, + 11938, 11938, 11938, -1, 11939, 11939, 11939, -1, + 11940, 11940, 11940, -1, 11941, 11941, 11941, -1, + 11942, 11942, 11942, -1, 11943, 11943, 11943, -1, + 11944, 11944, 11944, -1, 11945, 11945, 11945, -1, + 11946, 11946, 11946, -1, 11947, 11947, 11947, -1, + 11948, 11948, 11948, -1, 11949, 11949, 11949, -1, + 11950, 11950, 11950, -1, 11951, 11951, 11951, -1, + 11952, 11952, 11952, -1, 11953, 11953, 11953, -1, + 11954, 11954, 11954, -1, 11955, 11955, 11955, -1, + 11956, 11956, 11956, -1, 11957, 11957, 11957, -1, + 11958, 11958, 11958, -1, 11959, 11959, 11959, -1, + 11960, 11960, 11960, -1, 11961, 11961, 11961, -1, + 11962, 11962, 11962, -1, 11963, 11963, 11963, -1, + 11964, 11964, 11964, -1, 11965, 11965, 11965, -1, + 11966, 11966, 11966, -1, 11967, 11967, 11967, -1, + 11968, 11968, 11968, -1, 11969, 11969, 11969, -1, + 11970, 11970, 11970, -1, 11971, 11971, 11971, -1, + 11972, 11972, 11972, -1, 11973, 11973, 11973, -1, + 11974, 11974, 11974, -1, 11975, 11975, 11975, -1, + 11976, 11976, 11976, -1, 11977, 11977, 11977, -1, + 11978, 11978, 11978, -1, 11979, 11979, 11979, -1, + 11980, 11980, 11980, -1, 11981, 11981, 11981, -1, + 11982, 11982, 11982, -1, 11983, 11983, 11983, -1, + 11984, 11984, 11984, -1, 11985, 11985, 11985, -1, + 11986, 11986, 11986, -1, 11987, 11987, 11987, -1, + 11988, 11988, 11988, -1, 11989, 11989, 11989, -1, + 11990, 11990, 11990, -1, 11991, 11991, 11991, -1, + 11992, 11992, 11992, -1, 11993, 11993, 11993, -1, + 11994, 11994, 11994, -1, 11995, 11995, 11995, -1, + 11996, 11996, 11996, -1, 11997, 11997, 11997, -1, + 11998, 11998, 11998, -1, 11999, 11999, 11999, -1, + 12000, 12000, 12000, -1, 12001, 12001, 12001, -1, + 12002, 12002, 12002, -1, 12003, 12003, 12003, -1, + 12004, 12004, 12004, -1, 12005, 12005, 12005, -1, + 12006, 12006, 12006, -1, 12007, 12007, 12007, -1, + 12008, 12008, 12008, -1, 12009, 12009, 12009, -1, + 12010, 12010, 12010, -1, 12011, 12011, 12011, -1, + 12012, 12012, 12012, -1, 12013, 12013, 12013, -1, + 12014, 12014, 12014, -1, 12015, 12015, 12015, -1, + 12016, 12016, 12016, -1, 12017, 12017, 12017, -1, + 12018, 12018, 12018, -1, 12019, 12019, 12019, -1, + 12020, 12020, 12020, -1, 12021, 12021, 12021, -1, + 12022, 12022, 12022, -1, 12023, 12023, 12023, -1, + 12024, 12024, 12024, -1, 12025, 12025, 12025, -1, + 12026, 12026, 12026, -1, 12027, 12027, 12027, -1, + 12028, 12028, 12028, -1, 12029, 12029, 12029, -1, + 12030, 12030, 12030, -1, 12031, 12031, 12031, -1, + 12032, 12032, 12032, -1, 12033, 12033, 12033, -1, + 12034, 12034, 12034, -1, 12035, 12035, 12035, -1, + 12036, 12036, 12036, -1, 12037, 12037, 12037, -1, + 12038, 12038, 12038, -1, 12039, 12039, 12039, -1, + 12040, 12040, 12040, -1, 12041, 12041, 12041, -1, + 12042, 12042, 12042, -1, 12043, 12043, 12043, -1, + 12044, 12044, 12044, -1, 12045, 12045, 12045, -1, + 12046, 12046, 12046, -1, 12047, 12047, 12047, -1, + 12048, 12048, 12048, -1, 12049, 12049, 12049, -1, + 12050, 12050, 12050, -1, 12051, 12051, 12051, -1, + 12052, 12052, 12052, -1, 12053, 12053, 12053, -1, + 12054, 12054, 12054, -1, 12055, 12055, 12055, -1, + 12056, 12056, 12056, -1, 12057, 12057, 12057, -1, + 12058, 12058, 12058, -1, 12059, 12059, 12059, -1, + 12060, 12060, 12060, -1, 12061, 12061, 12061, -1, + 12062, 12062, 12062, -1, 12063, 12063, 12063, -1, + 12064, 12064, 12064, -1, 12065, 12065, 12065, -1, + 12066, 12066, 12066, -1, 12067, 12067, 12067, -1, + 12068, 12068, 12068, -1, 12069, 12069, 12069, -1, + 12070, 12070, 12070, -1, 12071, 12071, 12071, -1, + 12072, 12072, 12072, -1, 12073, 12073, 12073, -1, + 12074, 12074, 12074, -1, 12075, 12075, 12075, -1, + 12076, 12076, 12076, -1, 12077, 12077, 12077, -1, + 12078, 12078, 12078, -1, 12079, 12079, 12079, -1, + 12080, 12080, 12080, -1, 12081, 12081, 12081, -1, + 12082, 12082, 12082, -1, 12083, 12083, 12083, -1, + 12084, 12084, 12084, -1, 12085, 12085, 12085, -1, + 12086, 12086, 12086, -1, 12087, 12087, 12087, -1, + 12088, 12088, 12088, -1, 12089, 12089, 12089, -1, + 12090, 12090, 12090, -1, 12091, 12091, 12091, -1, + 12092, 12092, 12092, -1, 12093, 12093, 12093, -1, + 12094, 12094, 12094, -1, 12095, 12095, 12095, -1, + 12096, 12096, 12096, -1, 12097, 12097, 12097, -1, + 12098, 12098, 12098, -1, 12099, 12099, 12099, -1, + 12100, 12100, 12100, -1, 12101, 12101, 12101, -1, + 12102, 12102, 12102, -1, 12103, 12103, 12103, -1, + 12104, 12104, 12104, -1, 12105, 12105, 12105, -1, + 12106, 12106, 12106, -1, 12107, 12107, 12107, -1, + 12108, 12108, 12108, -1, 12109, 12109, 12109, -1, + 12110, 12110, 12110, -1, 12111, 12111, 12111, -1, + 12112, 12112, 12112, -1, 12113, 12113, 12113, -1, + 12114, 12114, 12114, -1, 12115, 12115, 12115, -1, + 12116, 12116, 12116, -1, 12117, 12117, 12117, -1, + 12118, 12118, 12118, -1, 12119, 12119, 12119, -1, + 12120, 12120, 12120, -1, 12121, 12121, 12121, -1, + 12122, 12122, 12122, -1, 12123, 12123, 12123, -1, + 12124, 12124, 12124, -1, 12125, 12125, 12125, -1, + 12126, 12126, 12126, -1, 12127, 12127, 12127, -1, + 12128, 12128, 12128, -1, 12129, 12129, 12129, -1, + 12130, 12130, 12130, -1, 12131, 12131, 12131, -1, + 12132, 12132, 12132, -1, 12133, 12133, 12133, -1, + 12134, 12134, 12134, -1, 12135, 12135, 12135, -1, + 12136, 12136, 12136, -1, 12137, 12137, 12137, -1, + 12138, 12138, 12138, -1, 12139, 12139, 12139, -1, + 12140, 12140, 12140, -1, 12141, 12141, 12141, -1, + 12142, 12142, 12142, -1, 12143, 12143, 12143, -1, + 12144, 12144, 12144, -1, 12145, 12145, 12145, -1, + 12146, 12146, 12146, -1, 12147, 12147, 12147, -1, + 12148, 12148, 12148, -1, 12149, 12149, 12149, -1, + 12150, 12150, 12150, -1, 12151, 12151, 12151, -1, + 12152, 12152, 12152, -1, 12153, 12153, 12153, -1, + 12154, 12154, 12154, -1, 12155, 12155, 12155, -1, + 12156, 12156, 12156, -1, 12157, 12157, 12157, -1, + 12158, 12158, 12158, -1, 12159, 12159, 12159, -1, + 12160, 12160, 12160, -1, 12161, 12161, 12161, -1, + 12162, 12162, 12162, -1, 12163, 12163, 12163, -1, + 12164, 12164, 12164, -1, 12165, 12165, 12165, -1, + 12166, 12166, 12166, -1, 12167, 12167, 12167, -1, + 12168, 12168, 12168, -1, 12169, 12169, 12169, -1, + 12170, 12170, 12170, -1, 12171, 12171, 12171, -1, + 12172, 12172, 12172, -1, 12173, 12173, 12173, -1, + 12174, 12174, 12174, -1, 12175, 12175, 12175, -1, + 12176, 12176, 12176, -1, 12177, 12177, 12177, -1, + 12178, 12178, 12178, -1, 12179, 12179, 12179, -1, + 12180, 12180, 12180, -1, 12181, 12181, 12181, -1, + 12182, 12182, 12182, -1, 12183, 12183, 12183, -1, + 12184, 12184, 12184, -1, 12185, 12185, 12185, -1, + 12186, 12186, 12186, -1, 12187, 12187, 12187, -1, + 12188, 12188, 12188, -1, 12189, 12189, 12189, -1, + 12190, 12190, 12190, -1, 12191, 12191, 12191, -1, + 12192, 12192, 12192, -1, 12193, 12193, 12193, -1, + 12194, 12194, 12194, -1, 12195, 12195, 12195, -1, + 12196, 12196, 12196, -1, 12197, 12197, 12197, -1, + 12198, 12198, 12198, -1, 12199, 12199, 12199, -1, + 12200, 12200, 12200, -1, 12201, 12201, 12201, -1, + 12202, 12202, 12202, -1, 12203, 12203, 12203, -1, + 12204, 12204, 12204, -1, 12205, 12205, 12205, -1, + 12206, 12206, 12206, -1, 12207, 12207, 12207, -1, + 12208, 12208, 12208, -1, 12209, 12209, 12209, -1, + 12210, 12210, 12210, -1, 12211, 12211, 12211, -1, + 12212, 12212, 12212, -1, 12213, 12213, 12213, -1, + 12214, 12214, 12214, -1, 12215, 12215, 12215, -1, + 12216, 12216, 12216, -1, 12217, 12217, 12217, -1, + 12218, 12218, 12218, -1, 12219, 12219, 12219, -1, + 12220, 12220, 12220, -1, 12221, 12221, 12221, -1, + 12222, 12222, 12222, -1, 12223, 12223, 12223, -1, + 12224, 12224, 12224, -1, 12225, 12225, 12225, -1, + 12226, 12226, 12226, -1, 12227, 12227, 12227, -1, + 12228, 12228, 12228, -1, 12229, 12229, 12229, -1, + 12230, 12230, 12230, -1, 12231, 12231, 12231, -1, + 12232, 12232, 12232, -1, 12233, 12233, 12233, -1, + 12234, 12234, 12234, -1, 12235, 12235, 12235, -1, + 12236, 12236, 12236, -1, 12237, 12237, 12237, -1, + 12238, 12238, 12238, -1, 12239, 12239, 12239, -1, + 12240, 12240, 12240, -1, 12241, 12241, 12241, -1, + 12242, 12242, 12242, -1, 12243, 12243, 12243, -1, + 12244, 12244, 12244, -1, 12245, 12245, 12245, -1, + 12246, 12246, 12246, -1, 12247, 12247, 12247, -1, + 12248, 12248, 12248, -1, 12249, 12249, 12249, -1, + 12250, 12250, 12250, -1, 12251, 12251, 12251, -1, + 12252, 12252, 12252, -1, 12253, 12253, 12253, -1, + 12254, 12254, 12254, -1, 12255, 12255, 12255, -1, + 12256, 12256, 12256, -1, 12257, 12257, 12257, -1, + 12258, 12258, 12258, -1, 12259, 12259, 12259, -1, + 12260, 12260, 12260, -1, 12261, 12261, 12261, -1, + 12262, 12262, 12262, -1, 12263, 12263, 12263, -1, + 12264, 12264, 12264, -1, 12265, 12265, 12265, -1, + 12266, 12266, 12266, -1, 12267, 12267, 12267, -1, + 12268, 12268, 12268, -1, 12269, 12269, 12269, -1, + 12270, 12270, 12270, -1, 12271, 12271, 12271, -1, + 12272, 12272, 12272, -1, 12273, 12273, 12273, -1, + 12274, 12274, 12274, -1, 12275, 12275, 12275, -1, + 12276, 12276, 12276, -1, 12277, 12277, 12277, -1, + 12278, 12278, 12278, -1, 12279, 12279, 12279, -1, + 12280, 12280, 12280, -1, 12281, 12281, 12281, -1, + 12282, 12282, 12282, -1, 12283, 12283, 12283, -1, + 12284, 12284, 12284, -1, 12285, 12285, 12285, -1, + 12286, 12286, 12286, -1, 12287, 12287, 12287, -1, + 12288, 12288, 12288, -1, 12289, 12289, 12289, -1, + 12290, 12290, 12290, -1, 12291, 12291, 12291, -1, + 12292, 12292, 12292, -1, 12293, 12293, 12293, -1, + 12294, 12294, 12294, -1, 12295, 12295, 12295, -1, + 12296, 12296, 12296, -1, 12297, 12297, 12297, -1, + 12298, 12298, 12298, -1, 12299, 12299, 12299, -1, + 12300, 12300, 12300, -1, 12301, 12301, 12301, -1, + 12302, 12302, 12302, -1, 12303, 12303, 12303, -1, + 12304, 12304, 12304, -1, 12305, 12305, 12305, -1, + 12306, 12306, 12306, -1, 12307, 12307, 12307, -1, + 12308, 12308, 12308, -1, 12309, 12309, 12309, -1, + 12310, 12310, 12310, -1, 12311, 12311, 12311, -1, + 12312, 12312, 12312, -1, 12313, 12313, 12313, -1, + 12314, 12314, 12314, -1, 12315, 12315, 12315, -1, + 12316, 12316, 12316, -1, 12317, 12317, 12317, -1, + 12318, 12318, 12318, -1, 12319, 12319, 12319, -1, + 12320, 12320, 12320, -1, 12321, 12321, 12321, -1, + 12322, 12322, 12322, -1, 12323, 12323, 12323, -1, + 12324, 12324, 12324, -1, 12325, 12325, 12325, -1, + 12326, 12326, 12326, -1, 12327, 12327, 12327, -1, + 12328, 12328, 12328, -1, 12329, 12329, 12329, -1, + 12330, 12330, 12330, -1, 12331, 12331, 12331, -1, + 12332, 12332, 12332, -1, 12333, 12333, 12333, -1, + 12334, 12334, 12334, -1, 12335, 12335, 12335, -1, + 12336, 12336, 12336, -1, 12337, 12337, 12337, -1, + 12338, 12338, 12338, -1, 12339, 12339, 12339, -1, + 12340, 12340, 12340, -1, 12341, 12341, 12341, -1, + 12342, 12342, 12342, -1, 12343, 12343, 12343, -1, + 12344, 12344, 12344, -1, 12345, 12345, 12345, -1, + 12346, 12346, 12346, -1, 12347, 12347, 12347, -1, + 12348, 12348, 12348, -1, 12349, 12349, 12349, -1, + 12350, 12350, 12350, -1, 12351, 12351, 12351, -1, + 12352, 12352, 12352, -1, 12353, 12353, 12353, -1, + 12354, 12354, 12354, -1, 12355, 12355, 12355, -1, + 12356, 12356, 12356, -1, 12357, 12357, 12357, -1, + 12358, 12358, 12358, -1, 12359, 12359, 12359, -1, + 12360, 12360, 12360, -1, 12361, 12361, 12361, -1, + 12362, 12362, 12362, -1, 12363, 12363, 12363, -1, + 12364, 12364, 12364, -1, 12365, 12365, 12365, -1, + 12366, 12366, 12366, -1, 12367, 12367, 12367, -1, + 12368, 12368, 12368, -1, 12369, 12369, 12369, -1, + 12370, 12370, 12370, -1, 12371, 12371, 12371, -1, + 12372, 12372, 12372, -1, 12373, 12373, 12373, -1, + 12374, 12374, 12374, -1, 12375, 12375, 12375, -1, + 12376, 12376, 12376, -1, 12377, 12377, 12377, -1, + 12378, 12378, 12378, -1, 12379, 12379, 12379, -1, + 12380, 12380, 12380, -1, 12381, 12381, 12381, -1, + 12382, 12382, 12382, -1, 12383, 12383, 12383, -1, + 12384, 12384, 12384, -1, 12385, 12385, 12385, -1, + 12386, 12386, 12386, -1, 12387, 12387, 12387, -1, + 12388, 12388, 12388, -1, 12389, 12389, 12389, -1, + 12390, 12390, 12390, -1, 12391, 12391, 12391, -1, + 12392, 12392, 12392, -1, 12393, 12393, 12393, -1, + 12394, 12394, 12394, -1, 12395, 12395, 12395, -1, + 12396, 12396, 12396, -1, 12397, 12397, 12397, -1, + 12398, 12398, 12398, -1, 12399, 12399, 12399, -1, + 12400, 12400, 12400, -1, 12401, 12401, 12401, -1, + 12402, 12402, 12402, -1, 12403, 12403, 12403, -1, + 12404, 12404, 12404, -1, 12405, 12405, 12405, -1, + 12406, 12406, 12406, -1, 12407, 12407, 12407, -1, + 12408, 12408, 12408, -1, 12409, 12409, 12409, -1, + 12410, 12410, 12410, -1, 12411, 12411, 12411, -1, + 12412, 12412, 12412, -1, 12413, 12413, 12413, -1, + 12414, 12414, 12414, -1, 12415, 12415, 12415, -1, + 12416, 12416, 12416, -1, 12417, 12417, 12417, -1, + 12418, 12418, 12418, -1, 12419, 12419, 12419, -1, + 12420, 12420, 12420, -1, 12421, 12421, 12421, -1, + 12422, 12422, 12422, -1, 12423, 12423, 12423, -1, + 12424, 12424, 12424, -1, 12425, 12425, 12425, -1, + 12426, 12426, 12426, -1, 12427, 12427, 12427, -1, + 12428, 12428, 12428, -1, 12429, 12429, 12429, -1, + 12430, 12430, 12430, -1, 12431, 12431, 12431, -1, + 12432, 12432, 12432, -1, 12433, 12433, 12433, -1, + 12434, 12434, 12434, -1, 12435, 12435, 12435, -1, + 12436, 12436, 12436, -1, 12437, 12437, 12437, -1, + 12438, 12438, 12438, -1, 12439, 12439, 12439, -1, + 12440, 12440, 12440, -1, 12441, 12441, 12441, -1, + 12442, 12442, 12442, -1, 12443, 12443, 12443, -1, + 12444, 12444, 12444, -1, 12445, 12445, 12445, -1, + 12446, 12446, 12446, -1, 12447, 12447, 12447, -1, + 12448, 12448, 12448, -1, 12449, 12449, 12449, -1, + 12450, 12450, 12450, -1, 12451, 12451, 12451, -1, + 12452, 12452, 12452, -1, 12453, 12453, 12453, -1, + 12454, 12454, 12454, -1, 12455, 12455, 12455, -1, + 12456, 12456, 12456, -1, 12457, 12457, 12457, -1, + 12458, 12458, 12458, -1, 12459, 12459, 12459, -1, + 12460, 12460, 12460, -1, 12461, 12461, 12461, -1, + 12462, 12462, 12462, -1, 12463, 12463, 12463, -1, + 12464, 12464, 12464, -1, 12465, 12465, 12465, -1, + 12466, 12466, 12466, -1, 12467, 12467, 12467, -1, + 12468, 12468, 12468, -1, 12469, 12469, 12469, -1, + 12470, 12470, 12470, -1, 12471, 12471, 12471, -1, + 12472, 12472, 12472, -1, 12473, 12473, 12473, -1, + 12474, 12474, 12474, -1, 12475, 12475, 12475, -1, + 12476, 12476, 12476, -1, 12477, 12477, 12477, -1, + 12478, 12478, 12478, -1, 12479, 12479, 12479, -1, + 12480, 12480, 12480, -1, 12481, 12481, 12481, -1, + 12482, 12482, 12482, -1, 12483, 12483, 12483, -1, + 12484, 12484, 12484, -1, 12485, 12485, 12485, -1, + 12486, 12486, 12486, -1, 12487, 12487, 12487, -1, + 12488, 12488, 12488, -1, 12489, 12489, 12489, -1, + 12490, 12490, 12490, -1, 12491, 12491, 12491, -1, + 12492, 12492, 12492, -1, 12493, 12493, 12493, -1, + 12494, 12494, 12494, -1, 12495, 12495, 12495, -1, + 12496, 12496, 12496, -1, 12497, 12497, 12497, -1, + 12498, 12498, 12498, -1, 12499, 12499, 12499, -1, + 12500, 12500, 12500, -1, 12501, 12501, 12501, -1, + 12502, 12502, 12502, -1, 12503, 12503, 12503, -1, + 12504, 12504, 12504, -1, 12505, 12505, 12505, -1, + 12506, 12506, 12506, -1, 12507, 12507, 12507, -1, + 12508, 12508, 12508, -1, 12509, 12509, 12509, -1, + 12510, 12510, 12510, -1, 12511, 12511, 12511, -1, + 12512, 12512, 12512, -1, 12513, 12513, 12513, -1, + 12514, 12514, 12514, -1, 12515, 12515, 12515, -1, + 12516, 12516, 12516, -1, 12517, 12517, 12517, -1, + 12518, 12518, 12518, -1, 12519, 12519, 12519, -1, + 12520, 12520, 12520, -1, 12521, 12521, 12521, -1, + 12522, 12522, 12522, -1, 12523, 12523, 12523, -1, + 12524, 12524, 12524, -1, 12525, 12525, 12525, -1, + 12526, 12526, 12526, -1, 12527, 12527, 12527, -1, + 12528, 12528, 12528, -1, 12529, 12529, 12529, -1, + 12530, 12530, 12530, -1, 12531, 12531, 12531, -1, + 12532, 12532, 12532, -1, 12533, 12533, 12533, -1, + 12534, 12534, 12534, -1, 12535, 12535, 12535, -1, + 12536, 12536, 12536, -1, 12537, 12537, 12537, -1, + 12538, 12538, 12538, -1, 12539, 12539, 12539, -1, + 12540, 12540, 12540, -1, 12541, 12541, 12541, -1, + 12542, 12542, 12542, -1, 12543, 12543, 12543, -1, + 12544, 12544, 12544, -1, 12545, 12545, 12545, -1, + 12546, 12546, 12546, -1, 12547, 12547, 12547, -1, + 12548, 12548, 12548, -1, 12549, 12549, 12549, -1, + 12550, 12550, 12550, -1, 12551, 12551, 12551, -1, + 12552, 12552, 12552, -1, 12553, 12553, 12553, -1, + 12554, 12554, 12554, -1, 12555, 12555, 12555, -1, + 12556, 12556, 12556, -1, 12557, 12557, 12557, -1, + 12558, 12558, 12558, -1, 12559, 12559, 12559, -1, + 12560, 12560, 12560, -1, 12561, 12561, 12561, -1, + 12562, 12562, 12562, -1, 12563, 12563, 12563, -1, + 12564, 12564, 12564, -1, 12565, 12565, 12565, -1, + 12566, 12566, 12566, -1, 12567, 12567, 12567, -1, + 12568, 12568, 12568, -1, 12569, 12569, 12569, -1, + 12570, 12570, 12570, -1, 12571, 12571, 12571, -1, + 12572, 12572, 12572, -1, 12573, 12573, 12573, -1, + 12574, 12574, 12574, -1, 12575, 12575, 12575, -1, + 12576, 12576, 12576, -1, 12577, 12577, 12577, -1, + 12578, 12578, 12578, -1, 12579, 12579, 12579, -1, + 12580, 12580, 12580, -1, 12581, 12581, 12581, -1, + 12582, 12582, 12582, -1, 12583, 12583, 12583, -1, + 12584, 12584, 12584, -1, 12585, 12585, 12585, -1, + 12586, 12586, 12586, -1, 12587, 12587, 12587, -1, + 12588, 12588, 12588, -1, 12589, 12589, 12589, -1, + 12590, 12590, 12590, -1, 12591, 12591, 12591, -1, + 12592, 12592, 12592, -1, 12593, 12593, 12593, -1, + 12594, 12594, 12594, -1, 12595, 12595, 12595, -1, + 12596, 12596, 12596, -1, 12597, 12597, 12597, -1, + 12598, 12598, 12598, -1, 12599, 12599, 12599, -1, + 12600, 12600, 12600, -1, 12601, 12601, 12601, -1, + 12602, 12602, 12602, -1, 12603, 12603, 12603, -1, + 12604, 12604, 12604, -1, 12605, 12605, 12605, -1, + 12606, 12606, 12606, -1, 12607, 12607, 12607, -1, + 12608, 12608, 12608, -1, 12609, 12609, 12609, -1, + 12610, 12610, 12610, -1, 12611, 12611, 12611, -1, + 12612, 12612, 12612, -1, 12613, 12613, 12613, -1, + 12614, 12614, 12614, -1, 12615, 12615, 12615, -1, + 12616, 12616, 12616, -1, 12617, 12617, 12617, -1, + 12618, 12618, 12618, -1, 12619, 12619, 12619, -1, + 12620, 12620, 12620, -1, 12621, 12621, 12621, -1, + 12622, 12622, 12622, -1, 12623, 12623, 12623, -1, + 12624, 12624, 12624, -1, 12625, 12625, 12625, -1, + 12626, 12626, 12626, -1, 12627, 12627, 12627, -1, + 12628, 12628, 12628, -1, 12629, 12629, 12629, -1, + 12630, 12630, 12630, -1, 12631, 12631, 12631, -1, + 12632, 12632, 12632, -1, 12633, 12633, 12633, -1, + 12634, 12634, 12634, -1, 12635, 12635, 12635, -1, + 12636, 12636, 12636, -1, 12637, 12637, 12637, -1, + 12638, 12638, 12638, -1, 12639, 12639, 12639, -1, + 12640, 12640, 12640, -1, 12641, 12641, 12641, -1, + 12642, 12642, 12642, -1, 12643, 12643, 12643, -1, + 12644, 12644, 12644, -1, 12645, 12645, 12645, -1, + 12646, 12646, 12646, -1, 12647, 12647, 12647, -1, + 12648, 12648, 12648, -1, 12649, 12649, 12649, -1, + 12650, 12650, 12650, -1, 12651, 12651, 12651, -1, + 12652, 12652, 12652, -1, 12653, 12653, 12653, -1, + 12654, 12654, 12654, -1, 12655, 12655, 12655, -1, + 12656, 12656, 12656, -1, 12657, 12657, 12657, -1, + 12658, 12658, 12658, -1, 12659, 12659, 12659, -1, + 12660, 12660, 12660, -1, 12661, 12661, 12661, -1, + 12662, 12662, 12662, -1, 12663, 12663, 12663, -1, + 12664, 12664, 12664, -1, 12665, 12665, 12665, -1, + 12666, 12666, 12666, -1, 12667, 12667, 12667, -1, + 12668, 12668, 12668, -1, 12669, 12669, 12669, -1, + 12670, 12670, 12670, -1, 12671, 12671, 12671, -1, + 12672, 12672, 12672, -1, 12673, 12673, 12673, -1, + 12674, 12674, 12674, -1, 12675, 12675, 12675, -1, + 12676, 12676, 12676, -1, 12677, 12677, 12677, -1, + 12678, 12678, 12678, -1, 12679, 12679, 12679, -1, + 12680, 12680, 12680, -1, 12681, 12681, 12681, -1, + 12682, 12682, 12682, -1, 12683, 12683, 12683, -1, + 12684, 12684, 12684, -1, 12685, 12685, 12685, -1, + 12686, 12686, 12686, -1, 12687, 12687, 12687, -1, + 12688, 12688, 12688, -1, 12689, 12689, 12689, -1, + 12690, 12690, 12690, -1, 12691, 12691, 12691, -1, + 12692, 12692, 12692, -1, 12693, 12693, 12693, -1, + 12694, 12694, 12694, -1, 12695, 12695, 12695, -1, + 12696, 12696, 12696, -1, 12697, 12697, 12697, -1, + 12698, 12698, 12698, -1, 12699, 12699, 12699, -1, + 12700, 12700, 12700, -1, 12701, 12701, 12701, -1, + 12702, 12702, 12702, -1, 12703, 12703, 12703, -1, + 12704, 12704, 12704, -1, 12705, 12705, 12705, -1, + 12706, 12706, 12706, -1, 12707, 12707, 12707, -1, + 12708, 12708, 12708, -1, 12709, 12709, 12709, -1, + 12710, 12710, 12710, -1, 12711, 12711, 12711, -1, + 12712, 12712, 12712, -1, 12713, 12713, 12713, -1, + 12714, 12714, 12714, -1, 12715, 12715, 12715, -1, + 12716, 12716, 12716, -1, 12717, 12717, 12717, -1, + 12718, 12718, 12718, -1, 12719, 12719, 12719, -1, + 12720, 12720, 12720, -1, 12721, 12721, 12721, -1, + 12722, 12722, 12722, -1, 12723, 12723, 12723, -1, + 12724, 12724, 12724, -1, 12725, 12725, 12725, -1, + 12726, 12726, 12726, -1, 12727, 12727, 12727, -1, + 12728, 12728, 12728, -1, 12729, 12729, 12729, -1, + 12730, 12730, 12730, -1, 12731, 12731, 12731, -1, + 12732, 12732, 12732, -1, 12733, 12733, 12733, -1, + 12734, 12734, 12734, -1, 12735, 12735, 12735, -1, + 12736, 12736, 12736, -1, 12737, 12737, 12737, -1, + 12738, 12738, 12738, -1, 12739, 12739, 12739, -1, + 12740, 12740, 12740, -1, 12741, 12741, 12741, -1, + 12742, 12742, 12742, -1, 12743, 12743, 12743, -1, + 12744, 12744, 12744, -1, 12745, 12745, 12745, -1, + 12746, 12746, 12746, -1, 12747, 12747, 12747, -1, + 12748, 12748, 12748, -1, 12749, 12749, 12749, -1, + 12750, 12750, 12750, -1, 12751, 12751, 12751, -1, + 12752, 12752, 12752, -1, 12753, 12753, 12753, -1, + 12754, 12754, 12754, -1, 12755, 12755, 12755, -1, + 12756, 12756, 12756, -1, 12757, 12757, 12757, -1, + 12758, 12758, 12758, -1, 12759, 12759, 12759, -1, + 12760, 12760, 12760, -1, 12761, 12761, 12761, -1, + 12762, 12762, 12762, -1, 12763, 12763, 12763, -1, + 12764, 12764, 12764, -1, 12765, 12765, 12765, -1, + 12766, 12766, 12766, -1, 12767, 12767, 12767, -1, + 12768, 12768, 12768, -1, 12769, 12769, 12769, -1, + 12770, 12770, 12770, -1, 12771, 12771, 12771, -1, + 12772, 12772, 12772, -1, 12773, 12773, 12773, -1, + 12774, 12774, 12774, -1, 12775, 12775, 12775, -1, + 12776, 12776, 12776, -1, 12777, 12777, 12777, -1, + 12778, 12778, 12778, -1, 12779, 12779, 12779, -1, + 12780, 12780, 12780, -1, 12781, 12781, 12781, -1, + 12782, 12782, 12782, -1, 12783, 12783, 12783, -1, + 12784, 12784, 12784, -1, 12785, 12785, 12785, -1, + 12786, 12786, 12786, -1, 12787, 12787, 12787, -1, + 12788, 12788, 12788, -1, 12789, 12789, 12789, -1, + 12790, 12790, 12790, -1, 12791, 12791, 12791, -1, + 12792, 12792, 12792, -1, 12793, 12793, 12793, -1, + 12794, 12794, 12794, -1, 12795, 12795, 12795, -1, + 12796, 12796, 12796, -1, 12797, 12797, 12797, -1, + 12798, 12798, 12798, -1, 12799, 12799, 12799, -1, + 12800, 12800, 12800, -1, 12801, 12801, 12801, -1, + 12802, 12802, 12802, -1, 12803, 12803, 12803, -1, + 12804, 12804, 12804, -1, 12805, 12805, 12805, -1, + 12806, 12806, 12806, -1, 12807, 12807, 12807, -1, + 12808, 12808, 12808, -1, 12809, 12809, 12809, -1, + 12810, 12810, 12810, -1, 12811, 12811, 12811, -1, + 12812, 12812, 12812, -1, 12813, 12813, 12813, -1, + 12814, 12814, 12814, -1, 12815, 12815, 12815, -1, + 12816, 12816, 12816, -1, 12817, 12817, 12817, -1, + 12818, 12818, 12818, -1, 12819, 12819, 12819, -1, + 12820, 12820, 12820, -1, 12821, 12821, 12821, -1, + 12822, 12822, 12822, -1, 12823, 12823, 12823, -1, + 12824, 12824, 12824, -1, 12825, 12825, 12825, -1, + 12826, 12826, 12826, -1, 12827, 12827, 12827, -1, + 12828, 12828, 12828, -1, 12829, 12829, 12829, -1, + 12830, 12830, 12830, -1, 12831, 12831, 12831, -1, + 12832, 12832, 12832, -1, 12833, 12833, 12833, -1, + 12834, 12834, 12834, -1, 12835, 12835, 12835, -1, + 12836, 12836, 12836, -1, 12837, 12837, 12837, -1, + 12838, 12838, 12838, -1, 12839, 12839, 12839, -1, + 12840, 12840, 12840, -1, 12841, 12841, 12841, -1, + 12842, 12842, 12842, -1, 12843, 12843, 12843, -1, + 12844, 12844, 12844, -1, 12845, 12845, 12845, -1, + 12846, 12846, 12846, -1, 12847, 12847, 12847, -1, + 12848, 12848, 12848, -1, 12849, 12849, 12849, -1, + 12850, 12850, 12850, -1, 12851, 12851, 12851, -1, + 12852, 12852, 12852, -1, 12853, 12853, 12853, -1, + 12854, 12854, 12854, -1, 12855, 12855, 12855, -1, + 12856, 12856, 12856, -1, 12857, 12857, 12857, -1, + 12858, 12858, 12858, -1, 12859, 12859, 12859, -1, + 12860, 12860, 12860, -1, 12861, 12861, 12861, -1, + 12862, 12862, 12862, -1, 12863, 12863, 12863, -1, + 12864, 12864, 12864, -1, 12865, 12865, 12865, -1, + 12866, 12866, 12866, -1, 12867, 12867, 12867, -1, + 12868, 12868, 12868, -1, 12869, 12869, 12869, -1, + 12870, 12870, 12870, -1, 12871, 12871, 12871, -1, + 12872, 12872, 12872, -1, 12873, 12873, 12873, -1, + 12874, 12874, 12874, -1, 12875, 12875, 12875, -1, + 12876, 12876, 12876, -1, 12877, 12877, 12877, -1, + 12878, 12878, 12878, -1, 12879, 12879, 12879, -1, + 12880, 12880, 12880, -1, 12881, 12881, 12881, -1, + 12882, 12882, 12882, -1, 12883, 12883, 12883, -1, + 12884, 12884, 12884, -1, 12885, 12885, 12885, -1, + 12886, 12886, 12886, -1, 12887, 12887, 12887, -1, + 12888, 12888, 12888, -1, 12889, 12889, 12889, -1, + 12890, 12890, 12890, -1, 12891, 12891, 12891, -1, + 12892, 12892, 12892, -1, 12893, 12893, 12893, -1, + 12894, 12894, 12894, -1, 12895, 12895, 12895, -1, + 12896, 12896, 12896, -1, 12897, 12897, 12897, -1, + 12898, 12898, 12898, -1, 12899, 12899, 12899, -1, + 12900, 12900, 12900, -1, 12901, 12901, 12901, -1, + 12902, 12902, 12902, -1, 12903, 12903, 12903, -1, + 12904, 12904, 12904, -1, 12905, 12905, 12905, -1, + 12906, 12906, 12906, -1, 12907, 12907, 12907, -1, + 12908, 12908, 12908, -1, 12909, 12909, 12909, -1, + 12910, 12910, 12910, -1, 12911, 12911, 12911, -1, + 12912, 12912, 12912, -1, 12913, 12913, 12913, -1, + 12914, 12914, 12914, -1, 12915, 12915, 12915, -1, + 12916, 12916, 12916, -1, 12917, 12917, 12917, -1, + 12918, 12918, 12918, -1, 12919, 12919, 12919, -1, + 12920, 12920, 12920, -1, 12921, 12921, 12921, -1, + 12922, 12922, 12922, -1, 12923, 12923, 12923, -1, + 12924, 12924, 12924, -1, 12925, 12925, 12925, -1, + 12926, 12926, 12926, -1, 12927, 12927, 12927, -1, + 12928, 12928, 12928, -1, 12929, 12929, 12929, -1, + 12930, 12930, 12930, -1, 12931, 12931, 12931, -1, + 12932, 12932, 12932, -1, 12933, 12933, 12933, -1, + 12934, 12934, 12934, -1, 12935, 12935, 12935, -1, + 12936, 12936, 12936, -1, 12937, 12937, 12937, -1, + 12938, 12938, 12938, -1, 12939, 12939, 12939, -1, + 12940, 12940, 12940, -1, 12941, 12941, 12941, -1, + 12942, 12942, 12942, -1, 12943, 12943, 12943, -1, + 12944, 12944, 12944, -1, 12945, 12945, 12945, -1, + 12946, 12946, 12946, -1, 12947, 12947, 12947, -1, + 12948, 12948, 12948, -1, 12949, 12949, 12949, -1, + 12950, 12950, 12950, -1, 12951, 12951, 12951, -1, + 12952, 12952, 12952, -1, 12953, 12953, 12953, -1, + 12954, 12954, 12954, -1, 12955, 12955, 12955, -1, + 12956, 12956, 12956, -1, 12957, 12957, 12957, -1, + 12958, 12958, 12958, -1, 12959, 12959, 12959, -1, + 12960, 12960, 12960, -1, 12961, 12961, 12961, -1, + 12962, 12962, 12962, -1, 12963, 12963, 12963, -1, + 12964, 12964, 12964, -1, 12965, 12965, 12965, -1, + 12966, 12966, 12966, -1, 12967, 12967, 12967, -1, + 12968, 12968, 12968, -1, 12969, 12969, 12969, -1, + 12970, 12970, 12970, -1, 12971, 12971, 12971, -1, + 12972, 12972, 12972, -1, 12973, 12973, 12973, -1, + 12974, 12974, 12974, -1, 12975, 12975, 12975, -1, + 12976, 12976, 12976, -1, 12977, 12977, 12977, -1, + 12978, 12978, 12978, -1, 12979, 12979, 12979, -1, + 12980, 12980, 12980, -1, 12981, 12981, 12981, -1, + 12982, 12982, 12982, -1, 12983, 12983, 12983, -1, + 12984, 12984, 12984, -1, 12985, 12985, 12985, -1, + 12986, 12986, 12986, -1, 12987, 12987, 12987, -1, + 12988, 12988, 12988, -1, 12989, 12989, 12989, -1, + 12990, 12990, 12990, -1, 12991, 12991, 12991, -1, + 12992, 12992, 12992, -1, 12993, 12993, 12993, -1, + 12994, 12994, 12994, -1, 12995, 12995, 12995, -1, + 12996, 12996, 12996, -1, 12997, 12997, 12997, -1, + 12998, 12998, 12998, -1, 12999, 12999, 12999, -1, + 13000, 13000, 13000, -1, 13001, 13001, 13001, -1, + 13002, 13002, 13002, -1, 13003, 13003, 13003, -1, + 13004, 13004, 13004, -1, 13005, 13005, 13005, -1, + 13006, 13006, 13006, -1, 13007, 13007, 13007, -1, + 13008, 13008, 13008, -1, 13009, 13009, 13009, -1, + 13010, 13010, 13010, -1, 13011, 13011, 13011, -1, + 13012, 13012, 13012, -1, 13013, 13013, 13013, -1, + 13014, 13014, 13014, -1, 13015, 13015, 13015, -1, + 13016, 13016, 13016, -1, 13017, 13017, 13017, -1, + 13018, 13018, 13018, -1, 13019, 13019, 13019, -1, + 13020, 13020, 13020, -1, 13021, 13021, 13021, -1, + 13022, 13022, 13022, -1, 13023, 13023, 13023, -1, + 13024, 13024, 13024, -1, 13025, 13025, 13025, -1, + 13026, 13026, 13026, -1, 13027, 13027, 13027, -1, + 13028, 13028, 13028, -1, 13029, 13029, 13029, -1, + 13030, 13030, 13030, -1, 13031, 13031, 13031, -1, + 13032, 13032, 13032, -1, 13033, 13033, 13033, -1, + 13034, 13034, 13034, -1, 13035, 13035, 13035, -1, + 13036, 13036, 13036, -1, 13037, 13037, 13037, -1, + 13038, 13038, 13038, -1, 13039, 13039, 13039, -1, + 13040, 13040, 13040, -1, 13041, 13041, 13041, -1, + 13042, 13042, 13042, -1, 13043, 13043, 13043, -1, + 13044, 13044, 13044, -1, 13045, 13045, 13045, -1, + 13046, 13046, 13046, -1, 13047, 13047, 13047, -1, + 13048, 13048, 13048, -1, 13049, 13049, 13049, -1, + 13050, 13050, 13050, -1, 13051, 13051, 13051, -1, + 13052, 13052, 13052, -1, 13053, 13053, 13053, -1, + 13054, 13054, 13054, -1, 13055, 13055, 13055, -1, + 13056, 13056, 13056, -1, 13057, 13057, 13057, -1, + 13058, 13058, 13058, -1, 13059, 13059, 13059, -1, + 13060, 13060, 13060, -1, 13061, 13061, 13061, -1, + 13062, 13062, 13062, -1, 13063, 13063, 13063, -1, + 13064, 13064, 13064, -1, 13065, 13065, 13065, -1, + 13066, 13066, 13066, -1, 13067, 13067, 13067, -1, + 13068, 13068, 13068, -1, 13069, 13069, 13069, -1, + 13070, 13070, 13070, -1, 13071, 13071, 13071, -1, + 13072, 13072, 13072, -1, 13073, 13073, 13073, -1, + 13074, 13074, 13074, -1, 13075, 13075, 13075, -1, + 13076, 13076, 13076, -1, 13077, 13077, 13077, -1, + 13078, 13078, 13078, -1, 13079, 13079, 13079, -1, + 13080, 13080, 13080, -1, 13081, 13081, 13081, -1, + 13082, 13082, 13082, -1, 13083, 13083, 13083, -1, + 13084, 13084, 13084, -1, 13085, 13085, 13085, -1, + 13086, 13086, 13086, -1, 13087, 13087, 13087, -1, + 13088, 13088, 13088, -1, 13089, 13089, 13089, -1, + 13090, 13090, 13090, -1, 13091, 13091, 13091, -1, + 13092, 13092, 13092, -1, 13093, 13093, 13093, -1, + 13094, 13094, 13094, -1, 13095, 13095, 13095, -1, + 13096, 13096, 13096, -1, 13097, 13097, 13097, -1, + 13098, 13098, 13098, -1, 13099, 13099, 13099, -1, + 13100, 13100, 13100, -1, 13101, 13101, 13101, -1, + 13102, 13102, 13102, -1, 13103, 13103, 13103, -1, + 13104, 13104, 13104, -1, 13105, 13105, 13105, -1, + 13106, 13106, 13106, -1, 13107, 13107, 13107, -1, + 13108, 13108, 13108, -1, 13109, 13109, 13109, -1, + 13110, 13110, 13110, -1, 13111, 13111, 13111, -1, + 13112, 13112, 13112, -1, 13113, 13113, 13113, -1, + 13114, 13114, 13114, -1, 13115, 13115, 13115, -1, + 13116, 13116, 13116, -1, 13117, 13117, 13117, -1, + 13118, 13118, 13118, -1, 13119, 13119, 13119, -1, + 13120, 13120, 13120, -1, 13121, 13121, 13121, -1, + 13122, 13122, 13122, -1, 13123, 13123, 13123, -1, + 13124, 13124, 13124, -1, 13125, 13125, 13125, -1, + 13126, 13126, 13126, -1, 13127, 13127, 13127, -1, + 13128, 13128, 13128, -1, 13129, 13129, 13129, -1, + 13130, 13130, 13130, -1, 13131, 13131, 13131, -1, + 13132, 13132, 13132, -1, 13133, 13133, 13133, -1, + 13134, 13134, 13134, -1, 13135, 13135, 13135, -1, + 13136, 13136, 13136, -1, 13137, 13137, 13137, -1, + 13138, 13138, 13138, -1, 13139, 13139, 13139, -1, + 13140, 13140, 13140, -1, 13141, 13141, 13141, -1, + 13142, 13142, 13142, -1, 13143, 13143, 13143, -1, + 13144, 13144, 13144, -1, 13145, 13145, 13145, -1, + 13146, 13146, 13146, -1, 13147, 13147, 13147, -1, + 13148, 13148, 13148, -1, 13149, 13149, 13149, -1, + 13150, 13150, 13150, -1, 13151, 13151, 13151, -1, + 13152, 13152, 13152, -1, 13153, 13153, 13153, -1, + 13154, 13154, 13154, -1, 13155, 13155, 13155, -1, + 13156, 13156, 13156, -1, 13157, 13157, 13157, -1, + 13158, 13158, 13158, -1, 13159, 13159, 13159, -1, + 13160, 13160, 13160, -1, 13161, 13161, 13161, -1, + 13162, 13162, 13162, -1, 13163, 13163, 13163, -1, + 13164, 13164, 13164, -1, 13165, 13165, 13165, -1, + 13166, 13166, 13166, -1, 13167, 13167, 13167, -1, + 13168, 13168, 13168, -1, 13169, 13169, 13169, -1, + 13170, 13170, 13170, -1, 13171, 13171, 13171, -1, + 13172, 13172, 13172, -1, 13173, 13173, 13173, -1, + 13174, 13174, 13174, -1, 13175, 13175, 13175, -1, + 13176, 13176, 13176, -1, 13177, 13177, 13177, -1, + 13178, 13178, 13178, -1, 13179, 13179, 13179, -1, + 13180, 13180, 13180, -1, 13181, 13181, 13181, -1, + 13182, 13182, 13182, -1, 13183, 13183, 13183, -1, + 13184, 13184, 13184, -1, 13185, 13185, 13185, -1, + 13186, 13186, 13186, -1, 13187, 13187, 13187, -1, + 13188, 13188, 13188, -1, 13189, 13189, 13189, -1, + 13190, 13190, 13190, -1, 13191, 13191, 13191, -1, + 13192, 13192, 13192, -1, 13193, 13193, 13193, -1, + 13194, 13194, 13194, -1, 13195, 13195, 13195, -1, + 13196, 13196, 13196, -1, 13197, 13197, 13197, -1, + 13198, 13198, 13198, -1, 13199, 13199, 13199, -1, + 13200, 13200, 13200, -1, 13201, 13201, 13201, -1, + 13202, 13202, 13202, -1, 13203, 13203, 13203, -1, + 13204, 13204, 13204, -1, 13205, 13205, 13205, -1, + 13206, 13206, 13206, -1, 13207, 13207, 13207, -1, + 13208, 13208, 13208, -1, 13209, 13209, 13209, -1, + 13210, 13210, 13210, -1, 13211, 13211, 13211, -1, + 13212, 13212, 13212, -1, 13213, 13213, 13213, -1, + 13214, 13214, 13214, -1, 13215, 13215, 13215, -1, + 13216, 13216, 13216, -1, 13217, 13217, 13217, -1, + 13218, 13218, 13218, -1, 13219, 13219, 13219, -1, + 13220, 13220, 13220, -1, 13221, 13221, 13221, -1, + 13222, 13222, 13222, -1, 13223, 13223, 13223, -1, + 13224, 13224, 13224, -1, 13225, 13225, 13225, -1, + 13226, 13226, 13226, -1, 13227, 13227, 13227, -1, + 13228, 13228, 13228, -1, 13229, 13229, 13229, -1, + 13230, 13230, 13230, -1, 13231, 13231, 13231, -1, + 13232, 13232, 13232, -1, 13233, 13233, 13233, -1, + 13234, 13234, 13234, -1, 13235, 13235, 13235, -1, + 13236, 13236, 13236, -1, 13237, 13237, 13237, -1, + 13238, 13238, 13238, -1, 13239, 13239, 13239, -1, + 13240, 13240, 13240, -1, 13241, 13241, 13241, -1, + 13242, 13242, 13242, -1, 13243, 13243, 13243, -1, + 13244, 13244, 13244, -1, 13245, 13245, 13245, -1, + 13246, 13246, 13246, -1, 13247, 13247, 13247, -1, + 13248, 13248, 13248, -1, 13249, 13249, 13249, -1, + 13250, 13250, 13250, -1, 13251, 13251, 13251, -1, + 13252, 13252, 13252, -1, 13253, 13253, 13253, -1, + 13254, 13254, 13254, -1, 13255, 13255, 13255, -1, + 13256, 13256, 13256, -1, 13257, 13257, 13257, -1, + 13258, 13258, 13258, -1, 13259, 13259, 13259, -1, + 13260, 13260, 13260, -1, 13261, 13261, 13261, -1, + 13262, 13262, 13262, -1, 13263, 13263, 13263, -1, + 13264, 13264, 13264, -1, 13265, 13265, 13265, -1, + 13266, 13266, 13266, -1, 13267, 13267, 13267, -1, + 13268, 13268, 13268, -1, 13269, 13269, 13269, -1, + 13270, 13270, 13270, -1, 13271, 13271, 13271, -1, + 13272, 13272, 13272, -1, 13273, 13273, 13273, -1, + 13274, 13274, 13274, -1, 13275, 13275, 13275, -1, + 13276, 13276, 13276, -1, 13277, 13277, 13277, -1, + 13278, 13278, 13278, -1, 13279, 13279, 13279, -1, + 13280, 13280, 13280, -1, 13281, 13281, 13281, -1, + 13282, 13282, 13282, -1, 13283, 13283, 13283, -1, + 13284, 13284, 13284, -1, 13285, 13285, 13285, -1, + 13286, 13286, 13286, -1, 13287, 13287, 13287, -1, + 13288, 13288, 13288, -1, 13289, 13289, 13289, -1, + 13290, 13290, 13290, -1, 13291, 13291, 13291, -1, + 13292, 13292, 13292, -1, 13293, 13293, 13293, -1, + 13294, 13294, 13294, -1, 13295, 13295, 13295, -1, + 13296, 13296, 13296, -1, 13297, 13297, 13297, -1, + 13298, 13298, 13298, -1, 13299, 13299, 13299, -1, + 13300, 13300, 13300, -1, 13301, 13301, 13301, -1, + 13302, 13302, 13302, -1, 13303, 13303, 13303, -1, + 13304, 13304, 13304, -1, 13305, 13305, 13305, -1, + 13306, 13306, 13306, -1, 13307, 13307, 13307, -1, + 13308, 13308, 13308, -1, 13309, 13309, 13309, -1, + 13310, 13310, 13310, -1, 13311, 13311, 13311, -1, + 13312, 13312, 13312, -1, 13313, 13313, 13313, -1, + 13314, 13314, 13314, -1, 13315, 13315, 13315, -1, + 13316, 13316, 13316, -1, 13317, 13317, 13317, -1, + 13318, 13318, 13318, -1, 13319, 13319, 13319, -1, + 13320, 13320, 13320, -1, 13321, 13321, 13321, -1, + 13322, 13322, 13322, -1, 13323, 13323, 13323, -1, + 13324, 13324, 13324, -1, 13325, 13325, 13325, -1, + 13326, 13326, 13326, -1, 13327, 13327, 13327, -1, + 13328, 13328, 13328, -1, 13329, 13329, 13329, -1, + 13330, 13330, 13330, -1, 13331, 13331, 13331, -1, + 13332, 13332, 13332, -1, 13333, 13333, 13333, -1, + 13334, 13334, 13334, -1, 13335, 13335, 13335, -1, + 13336, 13336, 13336, -1, 13337, 13337, 13337, -1, + 13338, 13338, 13338, -1, 13339, 13339, 13339, -1, + 13340, 13340, 13340, -1, 13341, 13341, 13341, -1, + 13342, 13342, 13342, -1, 13343, 13343, 13343, -1, + 13344, 13344, 13344, -1, 13345, 13345, 13345, -1, + 13346, 13346, 13346, -1, 13347, 13347, 13347, -1, + 13348, 13348, 13348, -1, 13349, 13349, 13349, -1, + 13350, 13350, 13350, -1, 13351, 13351, 13351, -1, + 13352, 13352, 13352, -1, 13353, 13353, 13353, -1, + 13354, 13354, 13354, -1, 13355, 13355, 13355, -1, + 13356, 13356, 13356, -1, 13357, 13357, 13357, -1, + 13358, 13358, 13358, -1, 13359, 13359, 13359, -1, + 13360, 13360, 13360, -1, 13361, 13361, 13361, -1, + 13362, 13362, 13362, -1, 13363, 13363, 13363, -1, + 13364, 13364, 13364, -1, 13365, 13365, 13365, -1, + 13366, 13366, 13366, -1, 13367, 13367, 13367, -1, + 13368, 13368, 13368, -1, 13369, 13369, 13369, -1, + 13370, 13370, 13370, -1, 13371, 13371, 13371, -1, + 13372, 13372, 13372, -1, 13373, 13373, 13373, -1, + 13374, 13374, 13374, -1, 13375, 13375, 13375, -1, + 13376, 13376, 13376, -1, 13377, 13377, 13377, -1, + 13378, 13378, 13378, -1, 13379, 13379, 13379, -1, + 13380, 13380, 13380, -1, 13381, 13381, 13381, -1, + 13382, 13382, 13382, -1, 13383, 13383, 13383, -1, + 13384, 13384, 13384, -1, 13385, 13385, 13385, -1, + 13386, 13386, 13386, -1, 13387, 13387, 13387, -1, + 13388, 13388, 13388, -1, 13389, 13389, 13389, -1, + 13390, 13390, 13390, -1, 13391, 13391, 13391, -1, + 13392, 13392, 13392, -1, 13393, 13393, 13393, -1, + 13394, 13394, 13394, -1, 13395, 13395, 13395, -1, + 13396, 13396, 13396, -1, 13397, 13397, 13397, -1, + 13398, 13398, 13398, -1, 13399, 13399, 13399, -1, + 13400, 13400, 13400, -1, 13401, 13401, 13401, -1, + 13402, 13402, 13402, -1, 13403, 13403, 13403, -1, + 13404, 13404, 13404, -1, 13405, 13405, 13405, -1, + 13406, 13406, 13406, -1, 13407, 13407, 13407, -1, + 13408, 13408, 13408, -1, 13409, 13409, 13409, -1, + 13410, 13410, 13410, -1, 13411, 13411, 13411, -1, + 13412, 13412, 13412, -1, 13413, 13413, 13413, -1, + 13414, 13414, 13414, -1, 13415, 13415, 13415, -1, + 13416, 13416, 13416, -1, 13417, 13417, 13417, -1, + 13418, 13418, 13418, -1, 13419, 13419, 13419, -1, + 13420, 13420, 13420, -1, 13421, 13421, 13421, -1, + 13422, 13422, 13422, -1, 13423, 13423, 13423, -1, + 13424, 13424, 13424, -1, 13425, 13425, 13425, -1, + 13426, 13426, 13426, -1, 13427, 13427, 13427, -1, + 13428, 13428, 13428, -1, 13429, 13429, 13429, -1, + 13430, 13430, 13430, -1, 13431, 13431, 13431, -1, + 13432, 13432, 13432, -1, 13433, 13433, 13433, -1, + 13434, 13434, 13434, -1, 13435, 13435, 13435, -1, + 13436, 13436, 13436, -1, 13437, 13437, 13437, -1, + 13438, 13438, 13438, -1, 13439, 13439, 13439, -1, + 13440, 13440, 13440, -1, 13441, 13441, 13441, -1, + 13442, 13442, 13442, -1, 13443, 13443, 13443, -1, + 13444, 13444, 13444, -1, 13445, 13445, 13445, -1, + 13446, 13446, 13446, -1, 13447, 13447, 13447, -1, + 13448, 13448, 13448, -1, 13449, 13449, 13449, -1, + 13450, 13450, 13450, -1, 13451, 13451, 13451, -1, + 13452, 13452, 13452, -1, 13453, 13453, 13453, -1, + 13454, 13454, 13454, -1, 13455, 13455, 13455, -1, + 13456, 13456, 13456, -1, 13457, 13457, 13457, -1, + 13458, 13458, 13458, -1, 13459, 13459, 13459, -1, + 13460, 13460, 13460, -1, 13461, 13461, 13461, -1, + 13462, 13462, 13462, -1, 13463, 13463, 13463, -1, + 13464, 13464, 13464, -1, 13465, 13465, 13465, -1, + 13466, 13466, 13466, -1, 13467, 13467, 13467, -1, + 13468, 13468, 13468, -1, 13469, 13469, 13469, -1, + 13470, 13470, 13470, -1, 13471, 13471, 13471, -1, + 13472, 13472, 13472, -1, 13473, 13473, 13473, -1, + 13474, 13474, 13474, -1, 13475, 13475, 13475, -1, + 13476, 13476, 13476, -1, 13477, 13477, 13477, -1, + 13478, 13478, 13478, -1, 13479, 13479, 13479, -1, + 13480, 13480, 13480, -1, 13481, 13481, 13481, -1, + 13482, 13482, 13482, -1, 13483, 13483, 13483, -1, + 13484, 13484, 13484, -1, 13485, 13485, 13485, -1, + 13486, 13486, 13486, -1, 13487, 13487, 13487, -1, + 13488, 13488, 13488, -1, 13489, 13489, 13489, -1, + 13490, 13490, 13490, -1, 13491, 13491, 13491, -1, + 13492, 13492, 13492, -1, 13493, 13493, 13493, -1, + 13494, 13494, 13494, -1, 13495, 13495, 13495, -1, + 13496, 13496, 13496, -1, 13497, 13497, 13497, -1, + 13498, 13498, 13498, -1, 13499, 13499, 13499, -1, + 13500, 13500, 13500, -1, 13501, 13501, 13501, -1, + 13502, 13502, 13502, -1, 13503, 13503, 13503, -1, + 13504, 13504, 13504, -1, 13505, 13505, 13505, -1, + 13506, 13506, 13506, -1, 13507, 13507, 13507, -1, + 13508, 13508, 13508, -1, 13509, 13509, 13509, -1, + 13510, 13510, 13510, -1, 13511, 13511, 13511, -1, + 13512, 13512, 13512, -1, 13513, 13513, 13513, -1, + 13514, 13514, 13514, -1, 13515, 13515, 13515, -1, + 13516, 13516, 13516, -1, 13517, 13517, 13517, -1, + 13518, 13518, 13518, -1, 13519, 13519, 13519, -1, + 13520, 13520, 13520, -1, 13521, 13521, 13521, -1, + 13522, 13522, 13522, -1, 13523, 13523, 13523, -1, + 13524, 13524, 13524, -1, 13525, 13525, 13525, -1, + 13526, 13526, 13526, -1, 13527, 13527, 13527, -1, + 13528, 13528, 13528, -1, 13529, 13529, 13529, -1, + 13530, 13530, 13530, -1, 13531, 13531, 13531, -1, + 13532, 13532, 13532, -1, 13533, 13533, 13533, -1, + 13534, 13534, 13534, -1, 13535, 13535, 13535, -1, + 13536, 13536, 13536, -1, 13537, 13537, 13537, -1, + 13538, 13538, 13538, -1, 13539, 13539, 13539, -1, + 13540, 13540, 13540, -1, 13541, 13541, 13541, -1, + 13542, 13542, 13542, -1, 13543, 13543, 13543, -1, + 13544, 13544, 13544, -1, 13545, 13545, 13545, -1, + 13546, 13546, 13546, -1, 13547, 13547, 13547, -1, + 13548, 13548, 13548, -1, 13549, 13549, 13549, -1, + 13550, 13550, 13550, -1, 13551, 13551, 13551, -1, + 13552, 13552, 13552, -1, 13553, 13553, 13553, -1, + 13554, 13554, 13554, -1, 13555, 13555, 13555, -1, + 13556, 13556, 13556, -1, 13557, 13557, 13557, -1, + 13558, 13558, 13558, -1, 13559, 13559, 13559, -1, + 13560, 13560, 13560, -1, 13561, 13561, 13561, -1, + 13562, 13562, 13562, -1, 13563, 13563, 13563, -1, + 13564, 13564, 13564, -1, 13565, 13565, 13565, -1, + 13566, 13566, 13566, -1, 13567, 13567, 13567, -1, + 13568, 13568, 13568, -1, 13569, 13569, 13569, -1, + 13570, 13570, 13570, -1, 13571, 13571, 13571, -1, + 13572, 13572, 13572, -1, 13573, 13573, 13573, -1, + 13574, 13574, 13574, -1, 13575, 13575, 13575, -1, + 13576, 13576, 13576, -1, 13577, 13577, 13577, -1, + 13578, 13578, 13578, -1, 13579, 13579, 13579, -1, + 13580, 13580, 13580, -1, 13581, 13581, 13581, -1, + 13582, 13582, 13582, -1, 13583, 13583, 13583, -1, + 13584, 13584, 13584, -1, 13585, 13585, 13585, -1, + 13586, 13586, 13586, -1, 13587, 13587, 13587, -1, + 13588, 13588, 13588, -1, 13589, 13589, 13589, -1, + 13590, 13590, 13590, -1, 13591, 13591, 13591, -1, + 13592, 13592, 13592, -1, 13593, 13593, 13593, -1, + 13594, 13594, 13594, -1, 13595, 13595, 13595, -1, + 13596, 13596, 13596, -1, 13597, 13597, 13597, -1, + 13598, 13598, 13598, -1, 13599, 13599, 13599, -1, + 13600, 13600, 13600, -1, 13601, 13601, 13601, -1, + 13602, 13602, 13602, -1, 13603, 13603, 13603, -1, + 13604, 13604, 13604, -1, 13605, 13605, 13605, -1, + 13606, 13606, 13606, -1, 13607, 13607, 13607, -1, + 13608, 13608, 13608, -1, 13609, 13609, 13609, -1, + 13610, 13610, 13610, -1, 13611, 13611, 13611, -1, + 13612, 13612, 13612, -1, 13613, 13613, 13613, -1, + 13614, 13614, 13614, -1, 13615, 13615, 13615, -1, + 13616, 13616, 13616, -1, 13617, 13617, 13617, -1, + 13618, 13618, 13618, -1, 13619, 13619, 13619, -1, + 13620, 13620, 13620, -1, 13621, 13621, 13621, -1, + 13622, 13622, 13622, -1, 13623, 13623, 13623, -1, + 13624, 13624, 13624, -1, 13625, 13625, 13625, -1, + 13626, 13626, 13626, -1, 13627, 13627, 13627, -1, + 13628, 13628, 13628, -1, 13629, 13629, 13629, -1, + 13630, 13630, 13630, -1, 13631, 13631, 13631, -1, + 13632, 13632, 13632, -1, 13633, 13633, 13633, -1, + 13634, 13634, 13634, -1, 13635, 13635, 13635, -1, + 13636, 13636, 13636, -1, 13637, 13637, 13637, -1, + 13638, 13638, 13638, -1, 13639, 13639, 13639, -1, + 13640, 13640, 13640, -1, 13641, 13641, 13641, -1, + 13642, 13642, 13642, -1, 13643, 13643, 13643, -1, + 13644, 13644, 13644, -1, 13645, 13645, 13645, -1, + 13646, 13646, 13646, -1, 13647, 13647, 13647, -1, + 13648, 13648, 13648, -1, 13649, 13649, 13649, -1, + 13650, 13650, 13650, -1, 13651, 13651, 13651, -1, + 13652, 13652, 13652, -1, 13653, 13653, 13653, -1, + 13654, 13654, 13654, -1, 13655, 13655, 13655, -1, + 13656, 13656, 13656, -1, 13657, 13657, 13657, -1, + 13658, 13658, 13658, -1, 13659, 13659, 13659, -1, + 13660, 13660, 13660, -1, 13661, 13661, 13661, -1, + 13662, 13662, 13662, -1, 13663, 13663, 13663, -1, + 13664, 13664, 13664, -1, 13665, 13665, 13665, -1, + 13666, 13666, 13666, -1, 13667, 13667, 13667, -1, + 13668, 13668, 13668, -1, 13669, 13669, 13669, -1, + 13670, 13670, 13670, -1, 13671, 13671, 13671, -1, + 13672, 13672, 13672, -1, 13673, 13673, 13673, -1, + 13674, 13674, 13674, -1, 13675, 13675, 13675, -1, + 13676, 13676, 13676, -1, 13677, 13677, 13677, -1, + 13678, 13678, 13678, -1, 13679, 13679, 13679, -1, + 13680, 13680, 13680, -1, 13681, 13681, 13681, -1, + 13682, 13682, 13682, -1, 13683, 13683, 13683, -1, + 13684, 13684, 13684, -1, 13685, 13685, 13685, -1, + 13686, 13686, 13686, -1, 13687, 13687, 13687, -1, + 13688, 13688, 13688, -1, 13689, 13689, 13689, -1, + 13690, 13690, 13690, -1, 13691, 13691, 13691, -1, + 13692, 13692, 13692, -1, 13693, 13693, 13693, -1, + 13694, 13694, 13694, -1, 13695, 13695, 13695, -1, + 13696, 13696, 13696, -1, 13697, 13697, 13697, -1, + 13698, 13698, 13698, -1, 13699, 13699, 13699, -1, + 13700, 13700, 13700, -1, 13701, 13701, 13701, -1, + 13702, 13702, 13702, -1, 13703, 13703, 13703, -1, + 13704, 13704, 13704, -1, 13705, 13705, 13705, -1, + 13706, 13706, 13706, -1, 13707, 13707, 13707, -1, + 13708, 13708, 13708, -1, 13709, 13709, 13709, -1, + 13710, 13710, 13710, -1, 13711, 13711, 13711, -1, + 13712, 13712, 13712, -1, 13713, 13713, 13713, -1, + 13714, 13714, 13714, -1, 13715, 13715, 13715, -1, + 13716, 13716, 13716, -1, 13717, 13717, 13717, -1, + 13718, 13718, 13718, -1, 13719, 13719, 13719, -1, + 13720, 13720, 13720, -1, 13721, 13721, 13721, -1, + 13722, 13722, 13722, -1, 13723, 13723, 13723, -1, + 13724, 13724, 13724, -1, 13725, 13725, 13725, -1, + 13726, 13726, 13726, -1, 13727, 13727, 13727, -1, + 13728, 13728, 13728, -1, 13729, 13729, 13729, -1, + 13730, 13730, 13730, -1, 13731, 13731, 13731, -1, + 13732, 13732, 13732, -1, 13733, 13733, 13733, -1, + 13734, 13734, 13734, -1, 13735, 13735, 13735, -1, + 13736, 13736, 13736, -1, 13737, 13737, 13737, -1, + 13738, 13738, 13738, -1, 13739, 13739, 13739, -1, + 13740, 13740, 13740, -1, 13741, 13741, 13741, -1, + 13742, 13742, 13742, -1, 13743, 13743, 13743, -1, + 13744, 13744, 13744, -1, 13745, 13745, 13745, -1, + 13746, 13746, 13746, -1, 13747, 13747, 13747, -1, + 13748, 13748, 13748, -1, 13749, 13749, 13749, -1, + 13750, 13750, 13750, -1, 13751, 13751, 13751, -1, + 13752, 13752, 13752, -1, 13753, 13753, 13753, -1, + 13754, 13754, 13754, -1, 13755, 13755, 13755, -1, + 13756, 13756, 13756, -1, 13757, 13757, 13757, -1, + 13758, 13758, 13758, -1, 13759, 13759, 13759, -1, + 13760, 13760, 13760, -1, 13761, 13761, 13761, -1, + 13762, 13762, 13762, -1, 13763, 13763, 13763, -1, + 13764, 13764, 13764, -1, 13765, 13765, 13765, -1, + 13766, 13766, 13766, -1, 13767, 13767, 13767, -1, + 13768, 13768, 13768, -1, 13769, 13769, 13769, -1, + 13770, 13770, 13770, -1, 13771, 13771, 13771, -1, + 13772, 13772, 13772, -1, 13773, 13773, 13773, -1, + 13774, 13774, 13774, -1, 13775, 13775, 13775, -1, + 13776, 13776, 13776, -1, 13777, 13777, 13777, -1, + 13778, 13778, 13778, -1, 13779, 13779, 13779, -1, + 13780, 13780, 13780, -1, 13781, 13781, 13781, -1, + 13782, 13782, 13782, -1, 13783, 13783, 13783, -1, + 13784, 13784, 13784, -1, 13785, 13785, 13785, -1, + 13786, 13786, 13786, -1, 13787, 13787, 13787, -1, + 13788, 13788, 13788, -1, 13789, 13789, 13789, -1, + 13790, 13790, 13790, -1, 13791, 13791, 13791, -1, + 13792, 13792, 13792, -1, 13793, 13793, 13793, -1, + 13794, 13794, 13794, -1, 13795, 13795, 13795, -1, + 13796, 13796, 13796, -1, 13797, 13797, 13797, -1, + 13798, 13798, 13798, -1, 13799, 13799, 13799, -1, + 13800, 13800, 13800, -1, 13801, 13801, 13801, -1, + 13802, 13802, 13802, -1, 13803, 13803, 13803, -1, + 13804, 13804, 13804, -1, 13805, 13805, 13805, -1, + 13806, 13806, 13806, -1, 13807, 13807, 13807, -1, + 13808, 13808, 13808, -1, 13809, 13809, 13809, -1, + 13810, 13810, 13810, -1, 13811, 13811, 13811, -1, + 13812, 13812, 13812, -1, 13813, 13813, 13813, -1, + 13814, 13814, 13814, -1, 13815, 13815, 13815, -1, + 13816, 13816, 13816, -1, 13817, 13817, 13817, -1, + 13818, 13818, 13818, -1, 13819, 13819, 13819, -1, + 13820, 13820, 13820, -1, 13821, 13821, 13821, -1, + 13822, 13822, 13822, -1, 13823, 13823, 13823, -1, + 13824, 13824, 13824, -1, 13825, 13825, 13825, -1, + 13826, 13826, 13826, -1, 13827, 13827, 13827, -1, + 13828, 13828, 13828, -1, 13829, 13829, 13829, -1, + 13830, 13830, 13830, -1, 13831, 13831, 13831, -1, + 13832, 13832, 13832, -1, 13833, 13833, 13833, -1, + 13834, 13834, 13834, -1, 13835, 13835, 13835, -1, + 13836, 13836, 13836, -1, 13837, 13837, 13837, -1, + 13838, 13838, 13838, -1, 13839, 13839, 13839, -1, + 13840, 13840, 13840, -1, 13841, 13841, 13841, -1, + 13842, 13842, 13842, -1, 13843, 13843, 13843, -1, + 13844, 13844, 13844, -1, 13845, 13845, 13845, -1, + 13846, 13846, 13846, -1, 13847, 13847, 13847, -1, + 13848, 13848, 13848, -1, 13849, 13849, 13849, -1, + 13850, 13850, 13850, -1, 13851, 13851, 13851, -1, + 13852, 13852, 13852, -1, 13853, 13853, 13853, -1, + 13854, 13854, 13854, -1, 13855, 13855, 13855, -1, + 13856, 13856, 13856, -1, 13857, 13857, 13857, -1, + 13858, 13858, 13858, -1, 13859, 13859, 13859, -1, + 13860, 13860, 13860, -1, 13861, 13861, 13861, -1, + 13862, 13862, 13862, -1, 13863, 13863, 13863, -1, + 13864, 13864, 13864, -1, 13865, 13865, 13865, -1, + 13866, 13866, 13866, -1, 13867, 13867, 13867, -1, + 13868, 13868, 13868, -1, 13869, 13869, 13869, -1, + 13870, 13870, 13870, -1, 13871, 13871, 13871, -1, + 13872, 13872, 13872, -1, 13873, 13873, 13873, -1, + 13874, 13874, 13874, -1, 13875, 13875, 13875, -1, + 13876, 13876, 13876, -1, 13877, 13877, 13877, -1, + 13878, 13878, 13878, -1, 13879, 13879, 13879, -1, + 13880, 13880, 13880, -1, 13881, 13881, 13881, -1, + 13882, 13882, 13882, -1, 13883, 13883, 13883, -1, + 13884, 13884, 13884, -1, 13885, 13885, 13885, -1, + 13886, 13886, 13886, -1, 13887, 13887, 13887, -1, + 13888, 13888, 13888, -1, 13889, 13889, 13889, -1, + 13890, 13890, 13890, -1, 13891, 13891, 13891, -1, + 13892, 13892, 13892, -1, 13893, 13893, 13893, -1, + 13894, 13894, 13894, -1, 13895, 13895, 13895, -1, + 13896, 13896, 13896, -1, 13897, 13897, 13897, -1, + 13898, 13898, 13898, -1, 13899, 13899, 13899, -1, + 13900, 13900, 13900, -1, 13901, 13901, 13901, -1, + 13902, 13902, 13902, -1, 13903, 13903, 13903, -1, + 13904, 13904, 13904, -1, 13905, 13905, 13905, -1, + 13906, 13906, 13906, -1, 13907, 13907, 13907, -1, + 13908, 13908, 13908, -1, 13909, 13909, 13909, -1, + 13910, 13910, 13910, -1, 13911, 13911, 13911, -1, + 13912, 13912, 13912, -1, 13913, 13913, 13913, -1, + 13914, 13914, 13914, -1, 13915, 13915, 13915, -1, + 13916, 13916, 13916, -1, 13917, 13917, 13917, -1, + 13918, 13918, 13918, -1, 13919, 13919, 13919, -1, + 13920, 13920, 13920, -1, 13921, 13921, 13921, -1, + 13922, 13922, 13922, -1, 13923, 13923, 13923, -1, + 13924, 13924, 13924, -1, 13925, 13925, 13925, -1, + 13926, 13926, 13926, -1, 13927, 13927, 13927, -1, + 13928, 13928, 13928, -1, 13929, 13929, 13929, -1, + 13930, 13930, 13930, -1, 13931, 13931, 13931, -1, + 13932, 13932, 13932, -1, 13933, 13933, 13933, -1, + 13934, 13934, 13934, -1, 13935, 13935, 13935, -1, + 13936, 13936, 13936, -1, 13937, 13937, 13937, -1, + 13938, 13938, 13938, -1, 13939, 13939, 13939, -1, + 13940, 13940, 13940, -1, 13941, 13941, 13941, -1, + 13942, 13942, 13942, -1, 13943, 13943, 13943, -1, + 13944, 13944, 13944, -1, 13945, 13945, 13945, -1, + 13946, 13946, 13946, -1, 13947, 13947, 13947, -1, + 13948, 13948, 13948, -1, 13949, 13949, 13949, -1, + 13950, 13950, 13950, -1, 13951, 13951, 13951, -1, + 13952, 13952, 13952, -1, 13953, 13953, 13953, -1, + 13954, 13954, 13954, -1, 13955, 13955, 13955, -1, + 13956, 13956, 13956, -1, 13957, 13957, 13957, -1, + 13958, 13958, 13958, -1, 13959, 13959, 13959, -1, + 13960, 13960, 13960, -1, 13961, 13961, 13961, -1, + 13962, 13962, 13962, -1, 13963, 13963, 13963, -1, + 13964, 13964, 13964, -1, 13965, 13965, 13965, -1, + 13966, 13966, 13966, -1, 13967, 13967, 13967, -1, + 13968, 13968, 13968, -1, 13969, 13969, 13969, -1, + 13970, 13970, 13970, -1, 13971, 13971, 13971, -1, + 13972, 13972, 13972, -1, 13973, 13973, 13973, -1, + 13974, 13974, 13974, -1, 13975, 13975, 13975, -1, + 13976, 13976, 13976, -1, 13977, 13977, 13977, -1, + 13978, 13978, 13978, -1, 13979, 13979, 13979, -1, + 13980, 13980, 13980, -1, 13981, 13981, 13981, -1, + 13982, 13982, 13982, -1, 13983, 13983, 13983, -1, + 13984, 13984, 13984, -1, 13985, 13985, 13985, -1, + 13986, 13986, 13986, -1, 13987, 13987, 13987, -1, + 13988, 13988, 13988, -1, 13989, 13989, 13989, -1, + 13990, 13990, 13990, -1, 13991, 13991, 13991, -1, + 13992, 13992, 13992, -1, 13993, 13993, 13993, -1, + 13994, 13994, 13994, -1, 13995, 13995, 13995, -1, + 13996, 13996, 13996, -1, 13997, 13997, 13997, -1, + 13998, 13998, 13998, -1, 13999, 13999, 13999, -1, + 14000, 14000, 14000, -1, 14001, 14001, 14001, -1, + 14002, 14002, 14002, -1, 14003, 14003, 14003, -1, + 14004, 14004, 14004, -1, 14005, 14005, 14005, -1, + 14006, 14006, 14006, -1, 14007, 14007, 14007, -1, + 14008, 14008, 14008, -1, 14009, 14009, 14009, -1, + 14010, 14010, 14010, -1, 14011, 14011, 14011, -1, + 14012, 14012, 14012, -1, 14013, 14013, 14013, -1, + 14014, 14014, 14014, -1, 14015, 14015, 14015, -1, + 14016, 14016, 14016, -1, 14017, 14017, 14017, -1, + 14018, 14018, 14018, -1, 14019, 14019, 14019, -1, + 14020, 14020, 14020, -1, 14021, 14021, 14021, -1, + 14022, 14022, 14022, -1, 14023, 14023, 14023, -1, + 14024, 14024, 14024, -1, 14025, 14025, 14025, -1, + 14026, 14026, 14026, -1, 14027, 14027, 14027, -1, + 14028, 14028, 14028, -1, 14029, 14029, 14029, -1, + 14030, 14030, 14030, -1, 14031, 14031, 14031, -1, + 14032, 14032, 14032, -1, 14033, 14033, 14033, -1, + 14034, 14034, 14034, -1, 14035, 14035, 14035, -1, + 14036, 14036, 14036, -1, 14037, 14037, 14037, -1, + 14038, 14038, 14038, -1, 14039, 14039, 14039, -1, + 14040, 14040, 14040, -1, 14041, 14041, 14041, -1, + 14042, 14042, 14042, -1, 14043, 14043, 14043, -1, + 14044, 14044, 14044, -1, 14045, 14045, 14045, -1, + 14046, 14046, 14046, -1, 14047, 14047, 14047, -1, + 14048, 14048, 14048, -1, 14049, 14049, 14049, -1, + 14050, 14050, 14050, -1, 14051, 14051, 14051, -1, + 14052, 14052, 14052, -1, 14053, 14053, 14053, -1, + 14054, 14054, 14054, -1, 14055, 14055, 14055, -1, + 14056, 14056, 14056, -1, 14057, 14057, 14057, -1, + 14058, 14058, 14058, -1, 14059, 14059, 14059, -1, + 14060, 14060, 14060, -1, 14061, 14061, 14061, -1, + 14062, 14062, 14062, -1, 14063, 14063, 14063, -1, + 14064, 14064, 14064, -1, 14065, 14065, 14065, -1, + 14066, 14066, 14066, -1, 14067, 14067, 14067, -1, + 14068, 14068, 14068, -1, 14069, 14069, 14069, -1, + 14070, 14070, 14070, -1, 14071, 14071, 14071, -1, + 14072, 14072, 14072, -1, 14073, 14073, 14073, -1, + 14074, 14074, 14074, -1, 14075, 14075, 14075, -1, + 14076, 14076, 14076, -1, 14077, 14077, 14077, -1, + 14078, 14078, 14078, -1, 14079, 14079, 14079, -1, + 14080, 14080, 14080, -1, 14081, 14081, 14081, -1, + 14082, 14082, 14082, -1, 14083, 14083, 14083, -1, + 14084, 14084, 14084, -1, 14085, 14085, 14085, -1, + 14086, 14086, 14086, -1, 14087, 14087, 14087, -1, + 14088, 14088, 14088, -1, 14089, 14089, 14089, -1, + 14090, 14090, 14090, -1, 14091, 14091, 14091, -1, + 14092, 14092, 14092, -1, 14093, 14093, 14093, -1, + 14094, 14094, 14094, -1, 14095, 14095, 14095, -1, + 14096, 14096, 14096, -1, 14097, 14097, 14097, -1, + 14098, 14098, 14098, -1, 14099, 14099, 14099, -1, + 14100, 14100, 14100, -1, 14101, 14101, 14101, -1, + 14102, 14102, 14102, -1, 14103, 14103, 14103, -1, + 14104, 14104, 14104, -1, 14105, 14105, 14105, -1, + 14106, 14106, 14106, -1, 14107, 14107, 14107, -1, + 14108, 14108, 14108, -1, 14109, 14109, 14109, -1, + 14110, 14110, 14110, -1, 14111, 14111, 14111, -1, + 14112, 14112, 14112, -1, 14113, 14113, 14113, -1, + 14114, 14114, 14114, -1, 14115, 14115, 14115, -1, + 14116, 14116, 14116, -1, 14117, 14117, 14117, -1, + 14118, 14118, 14118, -1, 14119, 14119, 14119, -1, + 14120, 14120, 14120, -1, 14121, 14121, 14121, -1, + 14122, 14122, 14122, -1, 14123, 14123, 14123, -1, + 14124, 14124, 14124, -1, 14125, 14125, 14125, -1, + 14126, 14126, 14126, -1, 14127, 14127, 14127, -1, + 14128, 14128, 14128, -1, 14129, 14129, 14129, -1, + 14130, 14130, 14130, -1, 14131, 14131, 14131, -1, + 14132, 14132, 14132, -1, 14133, 14133, 14133, -1, + 14134, 14134, 14134, -1, 14135, 14135, 14135, -1, + 14136, 14136, 14136, -1, 14137, 14137, 14137, -1, + 14138, 14138, 14138, -1, 14139, 14139, 14139, -1, + 14140, 14140, 14140, -1, 14141, 14141, 14141, -1, + 14142, 14142, 14142, -1, 14143, 14143, 14143, -1, + 14144, 14144, 14144, -1, 14145, 14145, 14145, -1, + 14146, 14146, 14146, -1, 14147, 14147, 14147, -1, + 14148, 14148, 14148, -1, 14149, 14149, 14149, -1, + 14150, 14150, 14150, -1, 14151, 14151, 14151, -1, + 14152, 14152, 14152, -1, 14153, 14153, 14153, -1, + 14154, 14154, 14154, -1, 14155, 14155, 14155, -1, + 14156, 14156, 14156, -1, 14157, 14157, 14157, -1, + 14158, 14158, 14158, -1, 14159, 14159, 14159, -1, + 14160, 14160, 14160, -1, 14161, 14161, 14161, -1, + 14162, 14162, 14162, -1, 14163, 14163, 14163, -1, + 14164, 14164, 14164, -1, 14165, 14165, 14165, -1, + 14166, 14166, 14166, -1, 14167, 14167, 14167, -1, + 14168, 14168, 14168, -1, 14169, 14169, 14169, -1, + 14170, 14170, 14170, -1, 14171, 14171, 14171, -1, + 14172, 14172, 14172, -1, 14173, 14173, 14173, -1, + 14174, 14174, 14174, -1, 14175, 14175, 14175, -1, + 14176, 14176, 14176, -1, 14177, 14177, 14177, -1, + 14178, 14178, 14178, -1, 14179, 14179, 14179, -1, + 14180, 14180, 14180, -1, 14181, 14181, 14181, -1, + 14182, 14182, 14182, -1, 14183, 14183, 14183, -1, + 14184, 14184, 14184, -1, 14185, 14185, 14185, -1, + 14186, 14186, 14186, -1, 14187, 14187, 14187, -1, + 14188, 14188, 14188, -1, 14189, 14189, 14189, -1, + 14190, 14190, 14190, -1, 14191, 14191, 14191, -1, + 14192, 14192, 14192, -1, 14193, 14193, 14193, -1, + 14194, 14194, 14194, -1, 14195, 14195, 14195, -1, + 14196, 14196, 14196, -1, 14197, 14197, 14197, -1, + 14198, 14198, 14198, -1, 14199, 14199, 14199, -1, + 14200, 14200, 14200, -1, 14201, 14201, 14201, -1, + 14202, 14202, 14202, -1, 14203, 14203, 14203, -1, + 14204, 14204, 14204, -1, 14205, 14205, 14205, -1, + 14206, 14206, 14206, -1, 14207, 14207, 14207, -1, + 14208, 14208, 14208, -1, 14209, 14209, 14209, -1, + 14210, 14210, 14210, -1, 14211, 14211, 14211, -1, + 14212, 14212, 14212, -1, 14213, 14213, 14213, -1, + 14214, 14214, 14214, -1, 14215, 14215, 14215, -1, + 14216, 14216, 14216, -1, 14217, 14217, 14217, -1, + 14218, 14218, 14218, -1, 14219, 14219, 14219, -1, + 14220, 14220, 14220, -1, 14221, 14221, 14221, -1, + 14222, 14222, 14222, -1, 14223, 14223, 14223, -1, + 14224, 14224, 14224, -1, 14225, 14225, 14225, -1, + 14226, 14226, 14226, -1, 14227, 14227, 14227, -1, + 14228, 14228, 14228, -1, 14229, 14229, 14229, -1, + 14230, 14230, 14230, -1, 14231, 14231, 14231, -1, + 14232, 14232, 14232, -1, 14233, 14233, 14233, -1, + 14234, 14234, 14234, -1, 14235, 14235, 14235, -1, + 14236, 14236, 14236, -1, 14237, 14237, 14237, -1, + 14238, 14238, 14238, -1, 14239, 14239, 14239, -1, + 14240, 14240, 14240, -1, 14241, 14241, 14241, -1, + 14242, 14242, 14242, -1, 14243, 14243, 14243, -1, + 14244, 14244, 14244, -1, 14245, 14245, 14245, -1, + 14246, 14246, 14246, -1, 14247, 14247, 14247, -1, + 14248, 14248, 14248, -1, 14249, 14249, 14249, -1, + 14250, 14250, 14250, -1, 14251, 14251, 14251, -1, + 14252, 14252, 14252, -1, 14253, 14253, 14253, -1, + 14254, 14254, 14254, -1, 14255, 14255, 14255, -1, + 14256, 14256, 14256, -1, 14257, 14257, 14257, -1, + 14258, 14258, 14258, -1, 14259, 14259, 14259, -1, + 14260, 14260, 14260, -1, 14261, 14261, 14261, -1, + 14262, 14262, 14262, -1, 14263, 14263, 14263, -1, + 14264, 14264, 14264, -1, 14265, 14265, 14265, -1, + 14266, 14266, 14266, -1, 14267, 14267, 14267, -1, + 14268, 14268, 14268, -1, 14269, 14269, 14269, -1, + 14270, 14270, 14270, -1, 14271, 14271, 14271, -1, + 14272, 14272, 14272, -1, 14273, 14273, 14273, -1, + 14274, 14274, 14274, -1, 14275, 14275, 14275, -1, + 14276, 14276, 14276, -1, 14277, 14277, 14277, -1, + 14278, 14278, 14278, -1, 14279, 14279, 14279, -1, + 14280, 14280, 14280, -1, 14281, 14281, 14281, -1, + 14282, 14282, 14282, -1, 14283, 14283, 14283, -1, + 14284, 14284, 14284, -1, 14285, 14285, 14285, -1, + 14286, 14286, 14286, -1, 14287, 14287, 14287, -1, + 14288, 14288, 14288, -1, 14289, 14289, 14289, -1, + 14290, 14290, 14290, -1, 14291, 14291, 14291, -1, + 14292, 14292, 14292, -1, 14293, 14293, 14293, -1, + 14294, 14294, 14294, -1, 14295, 14295, 14295, -1, + 14296, 14296, 14296, -1, 14297, 14297, 14297, -1, + 14298, 14298, 14298, -1, 14299, 14299, 14299, -1, + 14300, 14300, 14300, -1, 14301, 14301, 14301, -1, + 14302, 14302, 14302, -1, 14303, 14303, 14303, -1, + 14304, 14304, 14304, -1, 14305, 14305, 14305, -1, + 14306, 14306, 14306, -1, 14307, 14307, 14307, -1, + 14308, 14308, 14308, -1, 14309, 14309, 14309, -1, + 14310, 14310, 14310, -1, 14311, 14311, 14311, -1, + 14312, 14312, 14312, -1, 14313, 14313, 14313, -1, + 14314, 14314, 14314, -1, 14315, 14315, 14315, -1, + 14316, 14316, 14316, -1, 14317, 14317, 14317, -1, + 14318, 14318, 14318, -1, 14319, 14319, 14319, -1, + 14320, 14320, 14320, -1, 14321, 14321, 14321, -1, + 14322, 14322, 14322, -1, 14323, 14323, 14323, -1, + 14324, 14324, 14324, -1, 14325, 14325, 14325, -1, + 14326, 14326, 14326, -1, 14327, 14327, 14327, -1, + 14328, 14328, 14328, -1, 14329, 14329, 14329, -1, + 14330, 14330, 14330, -1, 14331, 14331, 14331, -1, + 14332, 14332, 14332, -1, 14333, 14333, 14333, -1, + 14334, 14334, 14334, -1, 14335, 14335, 14335, -1, + 14336, 14336, 14336, -1, 14337, 14337, 14337, -1, + 14338, 14338, 14338, -1, 14339, 14339, 14339, -1, + 14340, 14340, 14340, -1, 14341, 14341, 14341, -1, + 14342, 14342, 14342, -1, 14343, 14343, 14343, -1, + 14344, 14344, 14344, -1, 14345, 14345, 14345, -1, + 14346, 14346, 14346, -1, 14347, 14347, 14347, -1, + 14348, 14348, 14348, -1, 14349, 14349, 14349, -1, + 14350, 14350, 14350, -1, 14351, 14351, 14351, -1, + 14352, 14352, 14352, -1, 14353, 14353, 14353, -1, + 14354, 14354, 14354, -1, 14355, 14355, 14355, -1, + 14356, 14356, 14356, -1, 14357, 14357, 14357, -1, + 14358, 14358, 14358, -1, 14359, 14359, 14359, -1, + 14360, 14360, 14360, -1, 14361, 14361, 14361, -1, + 14362, 14362, 14362, -1, 14363, 14363, 14363, -1, + 14364, 14364, 14364, -1, 14365, 14365, 14365, -1, + 14366, 14366, 14366, -1, 14367, 14367, 14367, -1, + 14368, 14368, 14368, -1, 14369, 14369, 14369, -1, + 14370, 14370, 14370, -1, 14371, 14371, 14371, -1, + 14372, 14372, 14372, -1, 14373, 14373, 14373, -1, + 14374, 14374, 14374, -1, 14375, 14375, 14375, -1, + 14376, 14376, 14376, -1, 14377, 14377, 14377, -1, + 14378, 14378, 14378, -1, 14379, 14379, 14379, -1, + 14380, 14380, 14380, -1, 14381, 14381, 14381, -1, + 14382, 14382, 14382, -1, 14383, 14383, 14383, -1, + 14384, 14384, 14384, -1, 14385, 14385, 14385, -1, + 14386, 14386, 14386, -1, 14387, 14387, 14387, -1, + 14388, 14388, 14388, -1, 14389, 14389, 14389, -1, + 14390, 14390, 14390, -1, 14391, 14391, 14391, -1, + 14392, 14392, 14392, -1, 14393, 14393, 14393, -1, + 14394, 14394, 14394, -1, 14395, 14395, 14395, -1, + 14396, 14396, 14396, -1, 14397, 14397, 14397, -1, + 14398, 14398, 14398, -1, 14399, 14399, 14399, -1, + 14400, 14400, 14400, -1, 14401, 14401, 14401, -1, + 14402, 14402, 14402, -1, 14403, 14403, 14403, -1, + 14404, 14404, 14404, -1, 14405, 14405, 14405, -1, + 14406, 14406, 14406, -1, 14407, 14407, 14407, -1, + 14408, 14408, 14408, -1, 14409, 14409, 14409, -1, + 14410, 14410, 14410, -1, 14411, 14411, 14411, -1, + 14412, 14412, 14412, -1, 14413, 14413, 14413, -1, + 14414, 14414, 14414, -1, 14415, 14415, 14415, -1, + 14416, 14416, 14416, -1, 14417, 14417, 14417, -1, + 14418, 14418, 14418, -1, 14419, 14419, 14419, -1, + 14420, 14420, 14420, -1, 14421, 14421, 14421, -1, + 14422, 14422, 14422, -1, 14423, 14423, 14423, -1, + 14424, 14424, 14424, -1, 14425, 14425, 14425, -1, + 14426, 14426, 14426, -1, 14427, 14427, 14427, -1, + 14428, 14428, 14428, -1, 14429, 14429, 14429, -1, + 14430, 14430, 14430, -1, 14431, 14431, 14431, -1, + 14432, 14432, 14432, -1, 14433, 14433, 14433, -1, + 14434, 14434, 14434, -1, 14435, 14435, 14435, -1, + 14436, 14436, 14436, -1, 14437, 14437, 14437, -1, + 14438, 14438, 14438, -1, 14439, 14439, 14439, -1, + 14440, 14440, 14440, -1, 14441, 14441, 14441, -1, + 14442, 14442, 14442, -1, 14443, 14443, 14443, -1, + 14444, 14444, 14444, -1, 14445, 14445, 14445, -1, + 14446, 14446, 14446, -1, 14447, 14447, 14447, -1, + 14448, 14448, 14448, -1, 14449, 14449, 14449, -1, + 14450, 14450, 14450, -1, 14451, 14451, 14451, -1, + 14452, 14452, 14452, -1, 14453, 14453, 14453, -1, + 14454, 14454, 14454, -1, 14455, 14455, 14455, -1, + 14456, 14456, 14456, -1, 14457, 14457, 14457, -1, + 14458, 14458, 14458, -1, 14459, 14459, 14459, -1, + 14460, 14460, 14460, -1, 14461, 14461, 14461, -1, + 14462, 14462, 14462, -1, 14463, 14463, 14463, -1, + 14464, 14464, 14464, -1, 14465, 14465, 14465, -1, + 14466, 14466, 14466, -1, 14467, 14467, 14467, -1, + 14468, 14468, 14468, -1, 14469, 14469, 14469, -1, + 14470, 14470, 14470, -1, 14471, 14471, 14471, -1, + 14472, 14472, 14472, -1, 14473, 14473, 14473, -1, + 14474, 14474, 14474, -1, 14475, 14475, 14475, -1, + 14476, 14476, 14476, -1, 14477, 14477, 14477, -1, + 14478, 14478, 14478, -1, 14479, 14479, 14479, -1, + 14480, 14480, 14480, -1, 14481, 14481, 14481, -1, + 14482, 14482, 14482, -1, 14483, 14483, 14483, -1, + 14484, 14484, 14484, -1, 14485, 14485, 14485, -1, + 14486, 14486, 14486, -1, 14487, 14487, 14487, -1, + 14488, 14488, 14488, -1, 14489, 14489, 14489, -1, + 14490, 14490, 14490, -1, 14491, 14491, 14491, -1, + 14492, 14492, 14492, -1, 14493, 14493, 14493, -1, + 14494, 14494, 14494, -1, 14495, 14495, 14495, -1, + 14496, 14496, 14496, -1, 14497, 14497, 14497, -1, + 14498, 14498, 14498, -1, 14499, 14499, 14499, -1, + 14500, 14500, 14500, -1, 14501, 14501, 14501, -1, + 14502, 14502, 14502, -1, 14503, 14503, 14503, -1, + 14504, 14504, 14504, -1, 14505, 14505, 14505, -1, + 14506, 14506, 14506, -1, 14507, 14507, 14507, -1, + 14508, 14508, 14508, -1, 14509, 14509, 14509, -1, + 14510, 14510, 14510, -1, 14511, 14511, 14511, -1, + 14512, 14512, 14512, -1, 14513, 14513, 14513, -1, + 14514, 14514, 14514, -1, 14515, 14515, 14515, -1, + 14516, 14516, 14516, -1, 14517, 14517, 14517, -1, + 14518, 14518, 14518, -1, 14519, 14519, 14519, -1, + 14520, 14520, 14520, -1, 14521, 14521, 14521, -1, + 14522, 14522, 14522, -1, 14523, 14523, 14523, -1, + 14524, 14524, 14524, -1, 14525, 14525, 14525, -1, + 14526, 14526, 14526, -1, 14527, 14527, 14527, -1, + 14528, 14528, 14528, -1, 14529, 14529, 14529, -1, + 14530, 14530, 14530, -1, 14531, 14531, 14531, -1, + 14532, 14532, 14532, -1, 14533, 14533, 14533, -1, + 14534, 14534, 14534, -1, 14535, 14535, 14535, -1, + 14536, 14536, 14536, -1, 14537, 14537, 14537, -1, + 14538, 14538, 14538, -1, 14539, 14539, 14539, -1, + 14540, 14540, 14540, -1, 14541, 14541, 14541, -1, + 14542, 14542, 14542, -1, 14543, 14543, 14543, -1, + 14544, 14544, 14544, -1, 14545, 14545, 14545, -1, + 14546, 14546, 14546, -1, 14547, 14547, 14547, -1, + 14548, 14548, 14548, -1, 14549, 14549, 14549, -1, + 14550, 14550, 14550, -1, 14551, 14551, 14551, -1, + 14552, 14552, 14552, -1, 14553, 14553, 14553, -1, + 14554, 14554, 14554, -1, 14555, 14555, 14555, -1, + 14556, 14556, 14556, -1, 14557, 14557, 14557, -1, + 14558, 14558, 14558, -1, 14559, 14559, 14559, -1, + 14560, 14560, 14560, -1, 14561, 14561, 14561, -1, + 14562, 14562, 14562, -1, 14563, 14563, 14563, -1, + 14564, 14564, 14564, -1, 14565, 14565, 14565, -1, + 14566, 14566, 14566, -1, 14567, 14567, 14567, -1, + 14568, 14568, 14568, -1, 14569, 14569, 14569, -1, + 14570, 14570, 14570, -1, 14571, 14571, 14571, -1, + 14572, 14572, 14572, -1, 14573, 14573, 14573, -1, + 14574, 14574, 14574, -1, 14575, 14575, 14575, -1, + 14576, 14576, 14576, -1, 14577, 14577, 14577, -1, + 14578, 14578, 14578, -1, 14579, 14579, 14579, -1, + 14580, 14580, 14580, -1, 14581, 14581, 14581, -1, + 14582, 14582, 14582, -1, 14583, 14583, 14583, -1, + 14584, 14584, 14584, -1, 14585, 14585, 14585, -1, + 14586, 14586, 14586, -1, 14587, 14587, 14587, -1, + 14588, 14588, 14588, -1, 14589, 14589, 14589, -1, + 14590, 14590, 14590, -1, 14591, 14591, 14591, -1, + 14592, 14592, 14592, -1, 14593, 14593, 14593, -1, + 14594, 14594, 14594, -1, 14595, 14595, 14595, -1, + 14596, 14596, 14596, -1, 14597, 14597, 14597, -1, + 14598, 14598, 14598, -1, 14599, 14599, 14599, -1, + 14600, 14600, 14600, -1, 14601, 14601, 14601, -1, + 14602, 14602, 14602, -1, 14603, 14603, 14603, -1, + 14604, 14604, 14604, -1, 14605, 14605, 14605, -1, + 14606, 14606, 14606, -1, 14607, 14607, 14607, -1, + 14608, 14608, 14608, -1, 14609, 14609, 14609, -1, + 14610, 14610, 14610, -1, 14611, 14611, 14611, -1, + 14612, 14612, 14612, -1, 14613, 14613, 14613, -1, + 14614, 14614, 14614, -1, 14615, 14615, 14615, -1, + 14616, 14616, 14616, -1, 14617, 14617, 14617, -1, + 14618, 14618, 14618, -1, 14619, 14619, 14619, -1, + 14620, 14620, 14620, -1, 14621, 14621, 14621, -1, + 14622, 14622, 14622, -1, 14623, 14623, 14623, -1, + 14624, 14624, 14624, -1, 14625, 14625, 14625, -1, + 14626, 14626, 14626, -1, 14627, 14627, 14627, -1, + 14628, 14628, 14628, -1, 14629, 14629, 14629, -1, + 14630, 14630, 14630, -1, 14631, 14631, 14631, -1, + 14632, 14632, 14632, -1, 14633, 14633, 14633, -1, + 14634, 14634, 14634, -1, 14635, 14635, 14635, -1, + 14636, 14636, 14636, -1, 14637, 14637, 14637, -1, + 14638, 14638, 14638, -1, 14639, 14639, 14639, -1, + 14640, 14640, 14640, -1, 14641, 14641, 14641, -1, + 14642, 14642, 14642, -1, 14643, 14643, 14643, -1, + 14644, 14644, 14644, -1, 14645, 14645, 14645, -1, + 14646, 14646, 14646, -1, 14647, 14647, 14647, -1, + 14648, 14648, 14648, -1, 14649, 14649, 14649, -1, + 14650, 14650, 14650, -1, 14651, 14651, 14651, -1, + 14652, 14652, 14652, -1, 14653, 14653, 14653, -1, + 14654, 14654, 14654, -1, 14655, 14655, 14655, -1, + 14656, 14656, 14656, -1, 14657, 14657, 14657, -1, + 14658, 14658, 14658, -1, 14659, 14659, 14659, -1, + 14660, 14660, 14660, -1, 14661, 14661, 14661, -1, + 14662, 14662, 14662, -1, 14663, 14663, 14663, -1, + 14664, 14664, 14664, -1, 14665, 14665, 14665, -1, + 14666, 14666, 14666, -1, 14667, 14667, 14667, -1, + 14668, 14668, 14668, -1, 14669, 14669, 14669, -1, + 14670, 14670, 14670, -1, 14671, 14671, 14671, -1, + 14672, 14672, 14672, -1, 14673, 14673, 14673, -1, + 14674, 14674, 14674, -1, 14675, 14675, 14675, -1, + 14676, 14676, 14676, -1, 14677, 14677, 14677, -1, + 14678, 14678, 14678, -1, 14679, 14679, 14679, -1, + 14680, 14680, 14680, -1, 14681, 14681, 14681, -1, + 14682, 14682, 14682, -1, 14683, 14683, 14683, -1, + 14684, 14684, 14684, -1, 14685, 14685, 14685, -1, + 14686, 14686, 14686, -1, 14687, 14687, 14687, -1, + 14688, 14688, 14688, -1, 14689, 14689, 14689, -1, + 14690, 14690, 14690, -1, 14691, 14691, 14691, -1, + 14692, 14692, 14692, -1, 14693, 14693, 14693, -1, + 14694, 14694, 14694, -1, 14695, 14695, 14695, -1, + 14696, 14696, 14696, -1, 14697, 14697, 14697, -1, + 14698, 14698, 14698, -1, 14699, 14699, 14699, -1, + 14700, 14700, 14700, -1, 14701, 14701, 14701, -1, + 14702, 14702, 14702, -1, 14703, 14703, 14703, -1, + 14704, 14704, 14704, -1, 14705, 14705, 14705, -1, + 14706, 14706, 14706, -1, 14707, 14707, 14707, -1, + 14708, 14708, 14708, -1, 14709, 14709, 14709, -1, + 14710, 14710, 14710, -1, 14711, 14711, 14711, -1, + 14712, 14712, 14712, -1, 14713, 14713, 14713, -1, + 14714, 14714, 14714, -1, 14715, 14715, 14715, -1, + 14716, 14716, 14716, -1, 14717, 14717, 14717, -1, + 14718, 14718, 14718, -1, 14719, 14719, 14719, -1, + 14720, 14720, 14720, -1, 14721, 14721, 14721, -1, + 14722, 14722, 14722, -1, 14723, 14723, 14723, -1, + 14724, 14724, 14724, -1, 14725, 14725, 14725, -1, + 14726, 14726, 14726, -1, 14727, 14727, 14727, -1, + 14728, 14728, 14728, -1, 14729, 14729, 14729, -1, + 14730, 14730, 14730, -1, 14731, 14731, 14731, -1, + 14732, 14732, 14732, -1, 14733, 14733, 14733, -1, + 14734, 14734, 14734, -1, 14735, 14735, 14735, -1, + 14736, 14736, 14736, -1, 14737, 14737, 14737, -1, + 14738, 14738, 14738, -1, 14739, 14739, 14739, -1, + 14740, 14740, 14740, -1, 14741, 14741, 14741, -1, + 14742, 14742, 14742, -1, 14743, 14743, 14743, -1, + 14744, 14744, 14744, -1, 14745, 14745, 14745, -1, + 14746, 14746, 14746, -1, 14747, 14747, 14747, -1, + 14748, 14748, 14748, -1, 14749, 14749, 14749, -1, + 14750, 14750, 14750, -1, 14751, 14751, 14751, -1, + 14752, 14752, 14752, -1, 14753, 14753, 14753, -1, + 14754, 14754, 14754, -1, 14755, 14755, 14755, -1, + 14756, 14756, 14756, -1, 14757, 14757, 14757, -1, + 14758, 14758, 14758, -1, 14759, 14759, 14759, -1, + 14760, 14760, 14760, -1, 14761, 14761, 14761, -1, + 14762, 14762, 14762, -1, 14763, 14763, 14763, -1, + 14764, 14764, 14764, -1, 14765, 14765, 14765, -1, + 14766, 14766, 14766, -1, 14767, 14767, 14767, -1, + 14768, 14768, 14768, -1, 14769, 14769, 14769, -1, + 14770, 14770, 14770, -1, 14771, 14771, 14771, -1, + 14772, 14772, 14772, -1, 14773, 14773, 14773, -1, + 14774, 14774, 14774, -1, 14775, 14775, 14775, -1, + 14776, 14776, 14776, -1, 14777, 14777, 14777, -1, + 14778, 14778, 14778, -1, 14779, 14779, 14779, -1, + 14780, 14780, 14780, -1, 14781, 14781, 14781, -1, + 14782, 14782, 14782, -1, 14783, 14783, 14783, -1, + 14784, 14784, 14784, -1, 14785, 14785, 14785, -1, + 14786, 14786, 14786, -1, 14787, 14787, 14787, -1, + 14788, 14788, 14788, -1, 14789, 14789, 14789, -1, + 14790, 14790, 14790, -1, 14791, 14791, 14791, -1, + 14792, 14792, 14792, -1, 14793, 14793, 14793, -1, + 14794, 14794, 14794, -1, 14795, 14795, 14795, -1, + 14796, 14796, 14796, -1, 14797, 14797, 14797, -1, + 14798, 14798, 14798, -1, 14799, 14799, 14799, -1, + 14800, 14800, 14800, -1, 14801, 14801, 14801, -1, + 14802, 14802, 14802, -1, 14803, 14803, 14803, -1, + 14804, 14804, 14804, -1, 14805, 14805, 14805, -1, + 14806, 14806, 14806, -1, 14807, 14807, 14807, -1, + 14808, 14808, 14808, -1, 14809, 14809, 14809, -1, + 14810, 14810, 14810, -1, 14811, 14811, 14811, -1, + 14812, 14812, 14812, -1, 14813, 14813, 14813, -1, + 14814, 14814, 14814, -1, 14815, 14815, 14815, -1, + 14816, 14816, 14816, -1, 14817, 14817, 14817, -1, + 14818, 14818, 14818, -1, 14819, 14819, 14819, -1, + 14820, 14820, 14820, -1, 14821, 14821, 14821, -1, + 14822, 14822, 14822, -1, 14823, 14823, 14823, -1, + 14824, 14824, 14824, -1, 14825, 14825, 14825, -1, + 14826, 14826, 14826, -1, 14827, 14827, 14827, -1, + 14828, 14828, 14828, -1, 14829, 14829, 14829, -1, + 14830, 14830, 14830, -1, 14831, 14831, 14831, -1, + 14832, 14832, 14832, -1, 14833, 14833, 14833, -1, + 14834, 14834, 14834, -1, 14835, 14835, 14835, -1, + 14836, 14836, 14836, -1, 14837, 14837, 14837, -1, + 14838, 14838, 14838, -1, 14839, 14839, 14839, -1, + 14840, 14840, 14840, -1, 14841, 14841, 14841, -1, + 14842, 14842, 14842, -1, 14843, 14843, 14843, -1, + 14844, 14844, 14844, -1, 14845, 14845, 14845, -1, + 14846, 14846, 14846, -1, 14847, 14847, 14847, -1, + 14848, 14848, 14848, -1, 14849, 14849, 14849, -1, + 14850, 14850, 14850, -1, 14851, 14851, 14851, -1, + 14852, 14852, 14852, -1, 14853, 14853, 14853, -1, + 14854, 14854, 14854, -1, 14855, 14855, 14855, -1, + 14856, 14856, 14856, -1, 14857, 14857, 14857, -1, + 14858, 14858, 14858, -1, 14859, 14859, 14859, -1, + 14860, 14860, 14860, -1, 14861, 14861, 14861, -1, + 14862, 14862, 14862, -1, 14863, 14863, 14863, -1, + 14864, 14864, 14864, -1, 14865, 14865, 14865, -1, + 14866, 14866, 14866, -1, 14867, 14867, 14867, -1, + 14868, 14868, 14868, -1, 14869, 14869, 14869, -1, + 14870, 14870, 14870, -1, 14871, 14871, 14871, -1, + 14872, 14872, 14872, -1, 14873, 14873, 14873, -1, + 14874, 14874, 14874, -1, 14875, 14875, 14875, -1, + 14876, 14876, 14876, -1, 14877, 14877, 14877, -1, + 14878, 14878, 14878, -1, 14879, 14879, 14879, -1, + 14880, 14880, 14880, -1, 14881, 14881, 14881, -1, + 14882, 14882, 14882, -1, 14883, 14883, 14883, -1, + 14884, 14884, 14884, -1, 14885, 14885, 14885, -1, + 14886, 14886, 14886, -1, 14887, 14887, 14887, -1, + 14888, 14888, 14888, -1, 14889, 14889, 14889, -1, + 14890, 14890, 14890, -1, 14891, 14891, 14891, -1, + 14892, 14892, 14892, -1, 14893, 14893, 14893, -1, + 14894, 14894, 14894, -1, 14895, 14895, 14895, -1, + 14896, 14896, 14896, -1, 14897, 14897, 14897, -1, + 14898, 14898, 14898, -1, 14899, 14899, 14899, -1, + 14900, 14900, 14900, -1, 14901, 14901, 14901, -1, + 14902, 14902, 14902, -1, 14903, 14903, 14903, -1, + 14904, 14904, 14904, -1, 14905, 14905, 14905, -1, + 14906, 14906, 14906, -1, 14907, 14907, 14907, -1, + 14908, 14908, 14908, -1, 14909, 14909, 14909, -1, + 14910, 14910, 14910, -1, 14911, 14911, 14911, -1, + 14912, 14912, 14912, -1, 14913, 14913, 14913, -1, + 14914, 14914, 14914, -1, 14915, 14915, 14915, -1, + 14916, 14916, 14916, -1, 14917, 14917, 14917, -1, + 14918, 14918, 14918, -1, 14919, 14919, 14919, -1, + 14920, 14920, 14920, -1, 14921, 14921, 14921, -1, + 14922, 14922, 14922, -1, 14923, 14923, 14923, -1, + 14924, 14924, 14924, -1, 14925, 14925, 14925, -1, + 14926, 14926, 14926, -1, 14927, 14927, 14927, -1, + 14928, 14928, 14928, -1, 14929, 14929, 14929, -1, + 14930, 14930, 14930, -1, 14931, 14931, 14931, -1, + 14932, 14932, 14932, -1, 14933, 14933, 14933, -1, + 14934, 14934, 14934, -1, 14935, 14935, 14935, -1, + 14936, 14936, 14936, -1, 14937, 14937, 14937, -1, + 14938, 14938, 14938, -1, 14939, 14939, 14939, -1, + 14940, 14940, 14940, -1, 14941, 14941, 14941, -1, + 14942, 14942, 14942, -1, 14943, 14943, 14943, -1, + 14944, 14944, 14944, -1, 14945, 14945, 14945, -1, + 14946, 14946, 14946, -1, 14947, 14947, 14947, -1, + 14948, 14948, 14948, -1, 14949, 14949, 14949, -1, + 14950, 14950, 14950, -1, 14951, 14951, 14951, -1, + 14952, 14952, 14952, -1, 14953, 14953, 14953, -1, + 14954, 14954, 14954, -1, 14955, 14955, 14955, -1, + 14956, 14956, 14956, -1, 14957, 14957, 14957, -1, + 14958, 14958, 14958, -1, 14959, 14959, 14959, -1, + 14960, 14960, 14960, -1, 14961, 14961, 14961, -1, + 14962, 14962, 14962, -1, 14963, 14963, 14963, -1, + 14964, 14964, 14964, -1, 14965, 14965, 14965, -1, + 14966, 14966, 14966, -1, 14967, 14967, 14967, -1, + 14968, 14968, 14968, -1, 14969, 14969, 14969, -1, + 14970, 14970, 14970, -1, 14971, 14971, 14971, -1, + 14972, 14972, 14972, -1, 14973, 14973, 14973, -1, + 14974, 14974, 14974, -1, 14975, 14975, 14975, -1, + 14976, 14976, 14976, -1, 14977, 14977, 14977, -1, + 14978, 14978, 14978, -1, 14979, 14979, 14979, -1, + 14980, 14980, 14980, -1, 14981, 14981, 14981, -1, + 14982, 14982, 14982, -1, 14983, 14983, 14983, -1, + 14984, 14984, 14984, -1, 14985, 14985, 14985, -1, + 14986, 14986, 14986, -1, 14987, 14987, 14987, -1, + 14988, 14988, 14988, -1, 14989, 14989, 14989, -1, + 14990, 14990, 14990, -1, 14991, 14991, 14991, -1, + 14992, 14992, 14992, -1, 14993, 14993, 14993, -1, + 14994, 14994, 14994, -1, 14995, 14995, 14995, -1, + 14996, 14996, 14996, -1, 14997, 14997, 14997, -1, + 14998, 14998, 14998, -1, 14999, 14999, 14999, -1, + 15000, 15000, 15000, -1, 15001, 15001, 15001, -1, + 15002, 15002, 15002, -1, 15003, 15003, 15003, -1, + 15004, 15004, 15004, -1, 15005, 15005, 15005, -1, + 15006, 15006, 15006, -1, 15007, 15007, 15007, -1, + 15008, 15008, 15008, -1, 15009, 15009, 15009, -1, + 15010, 15010, 15010, -1, 15011, 15011, 15011, -1, + 15012, 15012, 15012, -1, 15013, 15013, 15013, -1, + 15014, 15014, 15014, -1, 15015, 15015, 15015, -1, + 15016, 15016, 15016, -1, 15017, 15017, 15017, -1, + 15018, 15018, 15018, -1, 15019, 15019, 15019, -1, + 15020, 15020, 15020, -1, 15021, 15021, 15021, -1, + 15022, 15022, 15022, -1, 15023, 15023, 15023, -1, + 15024, 15024, 15024, -1, 15025, 15025, 15025, -1, + 15026, 15026, 15026, -1, 15027, 15027, 15027, -1, + 15028, 15028, 15028, -1, 15029, 15029, 15029, -1, + 15030, 15030, 15030, -1, 15031, 15031, 15031, -1, + 15032, 15032, 15032, -1, 15033, 15033, 15033, -1, + 15034, 15034, 15034, -1, 15035, 15035, 15035, -1, + 15036, 15036, 15036, -1, 15037, 15037, 15037, -1, + 15038, 15038, 15038, -1, 15039, 15039, 15039, -1, + 15040, 15040, 15040, -1, 15041, 15041, 15041, -1, + 15042, 15042, 15042, -1, 15043, 15043, 15043, -1, + 15044, 15044, 15044, -1, 15045, 15045, 15045, -1, + 15046, 15046, 15046, -1, 15047, 15047, 15047, -1, + 15048, 15048, 15048, -1, 15049, 15049, 15049, -1, + 15050, 15050, 15050, -1, 15051, 15051, 15051, -1, + 15052, 15052, 15052, -1, 15053, 15053, 15053, -1, + 15054, 15054, 15054, -1, 15055, 15055, 15055, -1, + 15056, 15056, 15056, -1, 15057, 15057, 15057, -1, + 15058, 15058, 15058, -1, 15059, 15059, 15059, -1, + 15060, 15060, 15060, -1, 15061, 15061, 15061, -1, + 15062, 15062, 15062, -1, 15063, 15063, 15063, -1, + 15064, 15064, 15064, -1, 15065, 15065, 15065, -1, + 15066, 15066, 15066, -1, 15067, 15067, 15067, -1, + 15068, 15068, 15068, -1, 15069, 15069, 15069, -1, + 15070, 15070, 15070, -1, 15071, 15071, 15071, -1, + 15072, 15072, 15072, -1, 15073, 15073, 15073, -1, + 15074, 15074, 15074, -1, 15075, 15075, 15075, -1, + 15076, 15076, 15076, -1, 15077, 15077, 15077, -1, + 15078, 15078, 15078, -1, 15079, 15079, 15079, -1, + 15080, 15080, 15080, -1, 15081, 15081, 15081, -1, + 15082, 15082, 15082, -1, 15083, 15083, 15083, -1, + 15084, 15084, 15084, -1, 15085, 15085, 15085, -1, + 15086, 15086, 15086, -1, 15087, 15087, 15087, -1, + 15088, 15088, 15088, -1, 15089, 15089, 15089, -1, + 15090, 15090, 15090, -1, 15091, 15091, 15091, -1, + 15092, 15092, 15092, -1, 15093, 15093, 15093, -1, + 15094, 15094, 15094, -1, 15095, 15095, 15095, -1, + 15096, 15096, 15096, -1, 15097, 15097, 15097, -1, + 15098, 15098, 15098, -1, 15099, 15099, 15099, -1, + 15100, 15100, 15100, -1, 15101, 15101, 15101, -1, + 15102, 15102, 15102, -1, 15103, 15103, 15103, -1, + 15104, 15104, 15104, -1, 15105, 15105, 15105, -1, + 15106, 15106, 15106, -1, 15107, 15107, 15107, -1, + 15108, 15108, 15108, -1, 15109, 15109, 15109, -1, + 15110, 15110, 15110, -1, 15111, 15111, 15111, -1, + 15112, 15112, 15112, -1, 15113, 15113, 15113, -1, + 15114, 15114, 15114, -1, 15115, 15115, 15115, -1, + 15116, 15116, 15116, -1, 15117, 15117, 15117, -1, + 15118, 15118, 15118, -1, 15119, 15119, 15119, -1, + 15120, 15120, 15120, -1, 15121, 15121, 15121, -1, + 15122, 15122, 15122, -1, 15123, 15123, 15123, -1, + 15124, 15124, 15124, -1, 15125, 15125, 15125, -1, + 15126, 15126, 15126, -1, 15127, 15127, 15127, -1, + 15128, 15128, 15128, -1, 15129, 15129, 15129, -1, + 15130, 15130, 15130, -1, 15131, 15131, 15131, -1, + 15132, 15132, 15132, -1, 15133, 15133, 15133, -1, + 15134, 15134, 15134, -1, 15135, 15135, 15135, -1, + 15136, 15136, 15136, -1, 15137, 15137, 15137, -1, + 15138, 15138, 15138, -1, 15139, 15139, 15139, -1, + 15140, 15140, 15140, -1, 15141, 15141, 15141, -1, + 15142, 15142, 15142, -1, 15143, 15143, 15143, -1, + 15144, 15144, 15144, -1, 15145, 15145, 15145, -1, + 15146, 15146, 15146, -1, 15147, 15147, 15147, -1, + 15148, 15148, 15148, -1, 15149, 15149, 15149, -1, + 15150, 15150, 15150, -1, 15151, 15151, 15151, -1, + 15152, 15152, 15152, -1, 15153, 15153, 15153, -1, + 15154, 15154, 15154, -1, 15155, 15155, 15155, -1, + 15156, 15156, 15156, -1, 15157, 15157, 15157, -1, + 15158, 15158, 15158, -1, 15159, 15159, 15159, -1, + 15160, 15160, 15160, -1, 15161, 15161, 15161, -1, + 15162, 15162, 15162, -1, 15163, 15163, 15163, -1, + 15164, 15164, 15164, -1, 15165, 15165, 15165, -1, + 15166, 15166, 15166, -1, 15167, 15167, 15167, -1, + 15168, 15168, 15168, -1, 15169, 15169, 15169, -1, + 15170, 15170, 15170, -1, 15171, 15171, 15171, -1, + 15172, 15172, 15172, -1, 15173, 15173, 15173, -1, + 15174, 15174, 15174, -1, 15175, 15175, 15175, -1, + 15176, 15176, 15176, -1, 15177, 15177, 15177, -1, + 15178, 15178, 15178, -1, 15179, 15179, 15179, -1, + 15180, 15180, 15180, -1, 15181, 15181, 15181, -1, + 15182, 15182, 15182, -1, 15183, 15183, 15183, -1, + 15184, 15184, 15184, -1, 15185, 15185, 15185, -1, + 15186, 15186, 15186, -1, 15187, 15187, 15187, -1, + 15188, 15188, 15188, -1, 15189, 15189, 15189, -1, + 15190, 15190, 15190, -1, 15191, 15191, 15191, -1, + 15192, 15192, 15192, -1, 15193, 15193, 15193, -1, + 15194, 15194, 15194, -1, 15195, 15195, 15195, -1, + 15196, 15196, 15196, -1, 15197, 15197, 15197, -1, + 15198, 15198, 15198, -1, 15199, 15199, 15199, -1, + 15200, 15200, 15200, -1, 15201, 15201, 15201, -1, + 15202, 15202, 15202, -1, 15203, 15203, 15203, -1, + 15204, 15204, 15204, -1, 15205, 15205, 15205, -1, + 15206, 15206, 15206, -1, 15207, 15207, 15207, -1, + 15208, 15208, 15208, -1, 15209, 15209, 15209, -1, + 15210, 15210, 15210, -1, 15211, 15211, 15211, -1, + 15212, 15212, 15212, -1, 15213, 15213, 15213, -1, + 15214, 15214, 15214, -1, 15215, 15215, 15215, -1, + 15216, 15216, 15216, -1, 15217, 15217, 15217, -1, + 15218, 15218, 15218, -1, 15219, 15219, 15219, -1, + 15220, 15220, 15220, -1, 15221, 15221, 15221, -1, + 15222, 15222, 15222, -1, 15223, 15223, 15223, -1, + 15224, 15224, 15224, -1, 15225, 15225, 15225, -1, + 15226, 15226, 15226, -1, 15227, 15227, 15227, -1, + 15228, 15228, 15228, -1, 15229, 15229, 15229, -1, + 15230, 15230, 15230, -1, 15231, 15231, 15231, -1, + 15232, 15232, 15232, -1, 15233, 15233, 15233, -1, + 15234, 15234, 15234, -1, 15235, 15235, 15235, -1, + 15236, 15236, 15236, -1, 15237, 15237, 15237, -1, + 15238, 15238, 15238, -1, 15239, 15239, 15239, -1, + 15240, 15240, 15240, -1, 15241, 15241, 15241, -1, + 15242, 15242, 15242, -1, 15243, 15243, 15243, -1, + 15244, 15244, 15244, -1, 15245, 15245, 15245, -1, + 15246, 15246, 15246, -1, 15247, 15247, 15247, -1, + 15248, 15248, 15248, -1, 15249, 15249, 15249, -1, + 15250, 15250, 15250, -1, 15251, 15251, 15251, -1, + 15252, 15252, 15252, -1, 15253, 15253, 15253, -1, + 15254, 15254, 15254, -1, 15255, 15255, 15255, -1, + 15256, 15256, 15256, -1, 15257, 15257, 15257, -1, + 15258, 15258, 15258, -1, 15259, 15259, 15259, -1, + 15260, 15260, 15260, -1, 15261, 15261, 15261, -1, + 15262, 15262, 15262, -1, 15263, 15263, 15263, -1, + 15264, 15264, 15264, -1, 15265, 15265, 15265, -1, + 15266, 15266, 15266, -1, 15267, 15267, 15267, -1, + 15268, 15268, 15268, -1, 15269, 15269, 15269, -1, + 15270, 15270, 15270, -1, 15271, 15271, 15271, -1, + 15272, 15272, 15272, -1, 15273, 15273, 15273, -1, + 15274, 15274, 15274, -1, 15275, 15275, 15275, -1, + 15276, 15276, 15276, -1, 15277, 15277, 15277, -1, + 15278, 15278, 15278, -1, 15279, 15279, 15279, -1, + 15280, 15280, 15280, -1, 15281, 15281, 15281, -1, + 15282, 15282, 15282, -1, 15283, 15283, 15283, -1, + 15284, 15284, 15284, -1, 15285, 15285, 15285, -1, + 15286, 15286, 15286, -1, 15287, 15287, 15287, -1, + 15288, 15288, 15288, -1, 15289, 15289, 15289, -1, + 15290, 15290, 15290, -1, 15291, 15291, 15291, -1, + 15292, 15292, 15292, -1, 15293, 15293, 15293, -1, + 15294, 15294, 15294, -1, 15295, 15295, 15295, -1, + 15296, 15296, 15296, -1, 15297, 15297, 15297, -1, + 15298, 15298, 15298, -1, 15299, 15299, 15299, -1, + 15300, 15300, 15300, -1, 15301, 15301, 15301, -1, + 15302, 15302, 15302, -1, 15303, 15303, 15303, -1, + 15304, 15304, 15304, -1, 15305, 15305, 15305, -1, + 15306, 15306, 15306, -1, 15307, 15307, 15307, -1, + 15308, 15308, 15308, -1, 15309, 15309, 15309, -1, + 15310, 15310, 15310, -1, 15311, 15311, 15311, -1, + 15312, 15312, 15312, -1, 15313, 15313, 15313, -1, + 15314, 15314, 15314, -1, 15315, 15315, 15315, -1, + 15316, 15316, 15316, -1, 15317, 15317, 15317, -1, + 15318, 15318, 15318, -1, 15319, 15319, 15319, -1, + 15320, 15320, 15320, -1, 15321, 15321, 15321, -1, + 15322, 15322, 15322, -1, 15323, 15323, 15323, -1, + 15324, 15324, 15324, -1, 15325, 15325, 15325, -1, + 15326, 15326, 15326, -1, 15327, 15327, 15327, -1, + 15328, 15328, 15328, -1, 15329, 15329, 15329, -1, + 15330, 15330, 15330, -1, 15331, 15331, 15331, -1, + 15332, 15332, 15332, -1, 15333, 15333, 15333, -1, + 15334, 15334, 15334, -1, 15335, 15335, 15335, -1, + 15336, 15336, 15336, -1, 15337, 15337, 15337, -1, + 15338, 15338, 15338, -1, 15339, 15339, 15339, -1, + 15340, 15340, 15340, -1, 15341, 15341, 15341, -1, + 15342, 15342, 15342, -1, 15343, 15343, 15343, -1, + 15344, 15344, 15344, -1, 15345, 15345, 15345, -1, + 15346, 15346, 15346, -1, 15347, 15347, 15347, -1, + 15348, 15348, 15348, -1, 15349, 15349, 15349, -1, + 15350, 15350, 15350, -1, 15351, 15351, 15351, -1, + 15352, 15352, 15352, -1, 15353, 15353, 15353, -1, + 15354, 15354, 15354, -1, 15355, 15355, 15355, -1, + 15356, 15356, 15356, -1, 15357, 15357, 15357, -1, + 15358, 15358, 15358, -1, 15359, 15359, 15359, -1, + 15360, 15360, 15360, -1, 15361, 15361, 15361, -1, + 15362, 15362, 15362, -1, 15363, 15363, 15363, -1, + 15364, 15364, 15364, -1, 15365, 15365, 15365, -1, + 15366, 15366, 15366, -1, 15367, 15367, 15367, -1, + 15368, 15368, 15368, -1, 15369, 15369, 15369, -1, + 15370, 15370, 15370, -1, 15371, 15371, 15371, -1, + 15372, 15372, 15372, -1, 15373, 15373, 15373, -1, + 15374, 15374, 15374, -1, 15375, 15375, 15375, -1, + 15376, 15376, 15376, -1, 15377, 15377, 15377, -1, + 15378, 15378, 15378, -1, 15379, 15379, 15379, -1, + 15380, 15380, 15380, -1, 15381, 15381, 15381, -1, + 15382, 15382, 15382, -1, 15383, 15383, 15383, -1, + 15384, 15384, 15384, -1, 15385, 15385, 15385, -1, + 15386, 15386, 15386, -1, 15387, 15387, 15387, -1, + 15388, 15388, 15388, -1, 15389, 15389, 15389, -1, + 15390, 15390, 15390, -1, 15391, 15391, 15391, -1, + 15392, 15392, 15392, -1, 15393, 15393, 15393, -1, + 15394, 15394, 15394, -1, 15395, 15395, 15395, -1, + 15396, 15396, 15396, -1, 15397, 15397, 15397, -1, + 15398, 15398, 15398, -1, 15399, 15399, 15399, -1, + 15400, 15400, 15400, -1, 15401, 15401, 15401, -1, + 15402, 15402, 15402, -1, 15403, 15403, 15403, -1, + 15404, 15404, 15404, -1, 15405, 15405, 15405, -1, + 15406, 15406, 15406, -1, 15407, 15407, 15407, -1, + 15408, 15408, 15408, -1, 15409, 15409, 15409, -1, + 15410, 15410, 15410, -1, 15411, 15411, 15411, -1, + 15412, 15412, 15412, -1, 15413, 15413, 15413, -1, + 15414, 15414, 15414, -1, 15415, 15415, 15415, -1, + 15416, 15416, 15416, -1, 15417, 15417, 15417, -1, + 15418, 15418, 15418, -1, 15419, 15419, 15419, -1, + 15420, 15420, 15420, -1, 15421, 15421, 15421, -1, + 15422, 15422, 15422, -1, 15423, 15423, 15423, -1, + 15424, 15424, 15424, -1, 15425, 15425, 15425, -1, + 15426, 15426, 15426, -1, 15427, 15427, 15427, -1, + 15428, 15428, 15428, -1, 15429, 15429, 15429, -1, + 15430, 15430, 15430, -1, 15431, 15431, 15431, -1, + 15432, 15432, 15432, -1, 15433, 15433, 15433, -1, + 15434, 15434, 15434, -1, 15435, 15435, 15435, -1, + 15436, 15436, 15436, -1, 15437, 15437, 15437, -1, + 15438, 15438, 15438, -1, 15439, 15439, 15439, -1, + 15440, 15440, 15440, -1, 15441, 15441, 15441, -1, + 15442, 15442, 15442, -1, 15443, 15443, 15443, -1, + 15444, 15444, 15444, -1, 15445, 15445, 15445, -1, + 15446, 15446, 15446, -1, 15447, 15447, 15447, -1, + 15448, 15448, 15448, -1, 15449, 15449, 15449, -1, + 15450, 15450, 15450, -1, 15451, 15451, 15451, -1, + 15452, 15452, 15452, -1, 15453, 15453, 15453, -1, + 15454, 15454, 15454, -1, 15455, 15455, 15455, -1, + 15456, 15456, 15456, -1, 15457, 15457, 15457, -1, + 15458, 15458, 15458, -1, 15459, 15459, 15459, -1, + 15460, 15460, 15460, -1, 15461, 15461, 15461, -1, + 15462, 15462, 15462, -1, 15463, 15463, 15463, -1, + 15464, 15464, 15464, -1, 15465, 15465, 15465, -1, + 15466, 15466, 15466, -1, 15467, 15467, 15467, -1, + 15468, 15468, 15468, -1, 15469, 15469, 15469, -1, + 15470, 15470, 15470, -1, 15471, 15471, 15471, -1, + 15472, 15472, 15472, -1, 15473, 15473, 15473, -1, + 15474, 15474, 15474, -1, 15475, 15475, 15475, -1, + 15476, 15476, 15476, -1, 15477, 15477, 15477, -1, + 15478, 15478, 15478, -1, 15479, 15479, 15479, -1, + 15480, 15480, 15480, -1, 15481, 15481, 15481, -1, + 15482, 15482, 15482, -1, 15483, 15483, 15483, -1, + 15484, 15484, 15484, -1, 15485, 15485, 15485, -1, + 15486, 15486, 15486, -1, 15487, 15487, 15487, -1, + 15488, 15488, 15488, -1, 15489, 15489, 15489, -1, + 15490, 15490, 15490, -1, 15491, 15491, 15491, -1, + 15492, 15492, 15492, -1, 15493, 15493, 15493, -1, + 15494, 15494, 15494, -1, 15495, 15495, 15495, -1, + 15496, 15496, 15496, -1, 15497, 15497, 15497, -1, + 15498, 15498, 15498, -1, 15499, 15499, 15499, -1, + 15500, 15500, 15500, -1, 15501, 15501, 15501, -1, + 15502, 15502, 15502, -1, 15503, 15503, 15503, -1, + 15504, 15504, 15504, -1, 15505, 15505, 15505, -1, + 15506, 15506, 15506, -1, 15507, 15507, 15507, -1, + 15508, 15508, 15508, -1, 15509, 15509, 15509, -1, + 15510, 15510, 15510, -1, 15511, 15511, 15511, -1, + 15512, 15512, 15512, -1, 15513, 15513, 15513, -1, + 15514, 15514, 15514, -1, 15515, 15515, 15515, -1, + 15516, 15516, 15516, -1, 15517, 15517, 15517, -1, + 15518, 15518, 15518, -1, 15519, 15519, 15519, -1, + 15520, 15520, 15520, -1, 15521, 15521, 15521, -1, + 15522, 15522, 15522, -1, 15523, 15523, 15523, -1, + 15524, 15524, 15524, -1, 15525, 15525, 15525, -1, + 15526, 15526, 15526, -1, 15527, 15527, 15527, -1, + 15528, 15528, 15528, -1, 15529, 15529, 15529, -1, + 15530, 15530, 15530, -1, 15531, 15531, 15531, -1, + 15532, 15532, 15532, -1, 15533, 15533, 15533, -1, + 15534, 15534, 15534, -1, 15535, 15535, 15535, -1, + 15536, 15536, 15536, -1, 15537, 15537, 15537, -1, + 15538, 15538, 15538, -1, 15539, 15539, 15539, -1, + 15540, 15540, 15540, -1, 15541, 15541, 15541, -1, + 15542, 15542, 15542, -1, 15543, 15543, 15543, -1, + 15544, 15544, 15544, -1, 15545, 15545, 15545, -1, + 15546, 15546, 15546, -1, 15547, 15547, 15547, -1, + 15548, 15548, 15548, -1, 15549, 15549, 15549, -1, + 15550, 15550, 15550, -1, 15551, 15551, 15551, -1, + 15552, 15552, 15552, -1, 15553, 15553, 15553, -1, + 15554, 15554, 15554, -1, 15555, 15555, 15555, -1, + 15556, 15556, 15556, -1, 15557, 15557, 15557, -1, + 15558, 15558, 15558, -1, 15559, 15559, 15559, -1, + 15560, 15560, 15560, -1, 15561, 15561, 15561, -1, + 15562, 15562, 15562, -1, 15563, 15563, 15563, -1, + 15564, 15564, 15564, -1, 15565, 15565, 15565, -1, + 15566, 15566, 15566, -1, 15567, 15567, 15567, -1, + 15568, 15568, 15568, -1, 15569, 15569, 15569, -1, + 15570, 15570, 15570, -1, 15571, 15571, 15571, -1, + 15572, 15572, 15572, -1, 15573, 15573, 15573, -1, + 15574, 15574, 15574, -1, 15575, 15575, 15575, -1, + 15576, 15576, 15576, -1, 15577, 15577, 15577, -1, + 15578, 15578, 15578, -1, 15579, 15579, 15579, -1, + 15580, 15580, 15580, -1, 15581, 15581, 15581, -1, + 15582, 15582, 15582, -1, 15583, 15583, 15583, -1, + 15584, 15584, 15584, -1, 15585, 15585, 15585, -1, + 15586, 15586, 15586, -1, 15587, 15587, 15587, -1, + 15588, 15588, 15588, -1, 15589, 15589, 15589, -1, + 15590, 15590, 15590, -1, 15591, 15591, 15591, -1, + 15592, 15592, 15592, -1, 15593, 15593, 15593, -1, + 15594, 15594, 15594, -1, 15595, 15595, 15595, -1, + 15596, 15596, 15596, -1, 15597, 15597, 15597, -1, + 15598, 15598, 15598, -1, 15599, 15599, 15599, -1, + 15600, 15600, 15600, -1, 15601, 15601, 15601, -1, + 15602, 15602, 15602, -1, 15603, 15603, 15603, -1, + 15604, 15604, 15604, -1, 15605, 15605, 15605, -1, + 15606, 15606, 15606, -1, 15607, 15607, 15607, -1, + 15608, 15608, 15608, -1, 15609, 15609, 15609, -1, + 15610, 15610, 15610, -1, 15611, 15611, 15611, -1, + 15612, 15612, 15612, -1, 15613, 15613, 15613, -1, + 15614, 15614, 15614, -1, 15615, 15615, 15615, -1, + 15616, 15616, 15616, -1, 15617, 15617, 15617, -1, + 15618, 15618, 15618, -1, 15619, 15619, 15619, -1, + 15620, 15620, 15620, -1, 15621, 15621, 15621, -1, + 15622, 15622, 15622, -1, 15623, 15623, 15623, -1, + 15624, 15624, 15624, -1, 15625, 15625, 15625, -1, + 15626, 15626, 15626, -1, 15627, 15627, 15627, -1, + 15628, 15628, 15628, -1, 15629, 15629, 15629, -1, + 15630, 15630, 15630, -1, 15631, 15631, 15631, -1, + 15632, 15632, 15632, -1, 15633, 15633, 15633, -1, + 15634, 15634, 15634, -1, 15635, 15635, 15635, -1, + 15636, 15636, 15636, -1, 15637, 15637, 15637, -1, + 15638, 15638, 15638, -1, 15639, 15639, 15639, -1, + 15640, 15640, 15640, -1, 15641, 15641, 15641, -1, + 15642, 15642, 15642, -1, 15643, 15643, 15643, -1, + 15644, 15644, 15644, -1, 15645, 15645, 15645, -1, + 15646, 15646, 15646, -1, 15647, 15647, 15647, -1, + 15648, 15648, 15648, -1, 15649, 15649, 15649, -1, + 15650, 15650, 15650, -1, 15651, 15651, 15651, -1, + 15652, 15652, 15652, -1, 15653, 15653, 15653, -1, + 15654, 15654, 15654, -1, 15655, 15655, 15655, -1, + 15656, 15656, 15656, -1, 15657, 15657, 15657, -1, + 15658, 15658, 15658, -1, 15659, 15659, 15659, -1, + 15660, 15660, 15660, -1, 15661, 15661, 15661, -1, + 15662, 15662, 15662, -1, 15663, 15663, 15663, -1, + 15664, 15664, 15664, -1, 15665, 15665, 15665, -1, + 15666, 15666, 15666, -1, 15667, 15667, 15667, -1, + 15668, 15668, 15668, -1, 15669, 15669, 15669, -1, + 15670, 15670, 15670, -1, 15671, 15671, 15671, -1, + 15672, 15672, 15672, -1, 15673, 15673, 15673, -1, + 15674, 15674, 15674, -1, 15675, 15675, 15675, -1, + 15676, 15676, 15676, -1, 15677, 15677, 15677, -1, + 15678, 15678, 15678, -1, 15679, 15679, 15679, -1, + 15680, 15680, 15680, -1, 15681, 15681, 15681, -1, + 15682, 15682, 15682, -1, 15683, 15683, 15683, -1, + 15684, 15684, 15684, -1, 15685, 15685, 15685, -1, + 15686, 15686, 15686, -1, 15687, 15687, 15687, -1, + 15688, 15688, 15688, -1, 15689, 15689, 15689, -1, + 15690, 15690, 15690, -1, 15691, 15691, 15691, -1, + 15692, 15692, 15692, -1, 15693, 15693, 15693, -1, + 15694, 15694, 15694, -1, 15695, 15695, 15695, -1, + 15696, 15696, 15696, -1, 15697, 15697, 15697, -1, + 15698, 15698, 15698, -1, 15699, 15699, 15699, -1, + 15700, 15700, 15700, -1, 15701, 15701, 15701, -1, + 15702, 15702, 15702, -1, 15703, 15703, 15703, -1, + 15704, 15704, 15704, -1, 15705, 15705, 15705, -1, + 15706, 15706, 15706, -1, 15707, 15707, 15707, -1, + 15708, 15708, 15708, -1, 15709, 15709, 15709, -1, + 15710, 15710, 15710, -1, 15711, 15711, 15711, -1, + 15712, 15712, 15712, -1, 15713, 15713, 15713, -1, + 15714, 15714, 15714, -1, 15715, 15715, 15715, -1, + 15716, 15716, 15716, -1, 15717, 15717, 15717, -1, + 15718, 15718, 15718, -1, 15719, 15719, 15719, -1, + 15720, 15720, 15720, -1, 15721, 15721, 15721, -1, + 15722, 15722, 15722, -1, 15723, 15723, 15723, -1, + 15724, 15724, 15724, -1, 15725, 15725, 15725, -1, + 15726, 15726, 15726, -1, 15727, 15727, 15727, -1, + 15728, 15728, 15728, -1, 15729, 15729, 15729, -1, + 15730, 15730, 15730, -1, 15731, 15731, 15731, -1, + 15732, 15732, 15732, -1, 15733, 15733, 15733, -1, + 15734, 15734, 15734, -1, 15735, 15735, 15735, -1, + 15736, 15736, 15736, -1, 15737, 15737, 15737, -1, + 15738, 15738, 15738, -1, 15739, 15739, 15739, -1, + 15740, 15740, 15740, -1, 15741, 15741, 15741, -1, + 15742, 15742, 15742, -1, 15743, 15743, 15743, -1, + 15744, 15744, 15744, -1, 15745, 15745, 15745, -1, + 15746, 15746, 15746, -1, 15747, 15747, 15747, -1, + 15748, 15748, 15748, -1, 15749, 15749, 15749, -1, + 15750, 15750, 15750, -1, 15751, 15751, 15751, -1, + 15752, 15752, 15752, -1, 15753, 15753, 15753, -1, + 15754, 15754, 15754, -1, 15755, 15755, 15755, -1, + 15756, 15756, 15756, -1, 15757, 15757, 15757, -1, + 15758, 15758, 15758, -1, 15759, 15759, 15759, -1, + 15760, 15760, 15760, -1, 15761, 15761, 15761, -1, + 15762, 15762, 15762, -1, 15763, 15763, 15763, -1, + 15764, 15764, 15764, -1, 15765, 15765, 15765, -1, + 15766, 15766, 15766, -1, 15767, 15767, 15767, -1, + 15768, 15768, 15768, -1, 15769, 15769, 15769, -1, + 15770, 15770, 15770, -1, 15771, 15771, 15771, -1, + 15772, 15772, 15772, -1, 15773, 15773, 15773, -1, + 15774, 15774, 15774, -1, 15775, 15775, 15775, -1, + 15776, 15776, 15776, -1, 15777, 15777, 15777, -1, + 15778, 15778, 15778, -1, 15779, 15779, 15779, -1, + 15780, 15780, 15780, -1, 15781, 15781, 15781, -1, + 15782, 15782, 15782, -1, 15783, 15783, 15783, -1, + 15784, 15784, 15784, -1, 15785, 15785, 15785, -1, + 15786, 15786, 15786, -1, 15787, 15787, 15787, -1, + 15788, 15788, 15788, -1, 15789, 15789, 15789, -1, + 15790, 15790, 15790, -1, 15791, 15791, 15791, -1, + 15792, 15792, 15792, -1, 15793, 15793, 15793, -1, + 15794, 15794, 15794, -1, 15795, 15795, 15795, -1, + 15796, 15796, 15796, -1, 15797, 15797, 15797, -1, + 15798, 15798, 15798, -1, 15799, 15799, 15799, -1, + 15800, 15800, 15800, -1, 15801, 15801, 15801, -1, + 15802, 15802, 15802, -1, 15803, 15803, 15803, -1, + 15804, 15804, 15804, -1, 15805, 15805, 15805, -1, + 15806, 15806, 15806, -1, 15807, 15807, 15807, -1, + 15808, 15808, 15808, -1, 15809, 15809, 15809, -1, + 15810, 15810, 15810, -1, 15811, 15811, 15811, -1, + 15812, 15812, 15812, -1, 15813, 15813, 15813, -1, + 15814, 15814, 15814, -1, 15815, 15815, 15815, -1, + 15816, 15816, 15816, -1, 15817, 15817, 15817, -1, + 15818, 15818, 15818, -1, 15819, 15819, 15819, -1, + 15820, 15820, 15820, -1, 15821, 15821, 15821, -1, + 15822, 15822, 15822, -1, 15823, 15823, 15823, -1, + 15824, 15824, 15824, -1, 15825, 15825, 15825, -1, + 15826, 15826, 15826, -1, 15827, 15827, 15827, -1, + 15828, 15828, 15828, -1, 15829, 15829, 15829, -1, + 15830, 15830, 15830, -1, 15831, 15831, 15831, -1, + 15832, 15832, 15832, -1, 15833, 15833, 15833, -1, + 15834, 15834, 15834, -1, 15835, 15835, 15835, -1, + 15836, 15836, 15836, -1, 15837, 15837, 15837, -1, + 15838, 15838, 15838, -1, 15839, 15839, 15839, -1, + 15840, 15840, 15840, -1, 15841, 15841, 15841, -1, + 15842, 15842, 15842, -1, 15843, 15843, 15843, -1, + 15844, 15844, 15844, -1, 15845, 15845, 15845, -1, + 15846, 15846, 15846, -1, 15847, 15847, 15847, -1, + 15848, 15848, 15848, -1, 15849, 15849, 15849, -1, + 15850, 15850, 15850, -1, 15851, 15851, 15851, -1, + 15852, 15852, 15852, -1, 15853, 15853, 15853, -1, + 15854, 15854, 15854, -1, 15855, 15855, 15855, -1, + 15856, 15856, 15856, -1, 15857, 15857, 15857, -1, + 15858, 15858, 15858, -1, 15859, 15859, 15859, -1, + 15860, 15860, 15860, -1, 15861, 15861, 15861, -1, + 15862, 15862, 15862, -1, 15863, 15863, 15863, -1, + 15864, 15864, 15864, -1, 15865, 15865, 15865, -1, + 15866, 15866, 15866, -1, 15867, 15867, 15867, -1, + 15868, 15868, 15868, -1, 15869, 15869, 15869, -1, + 15870, 15870, 15870, -1, 15871, 15871, 15871, -1, + 15872, 15872, 15872, -1, 15873, 15873, 15873, -1, + 15874, 15874, 15874, -1, 15875, 15875, 15875, -1, + 15876, 15876, 15876, -1, 15877, 15877, 15877, -1, + 15878, 15878, 15878, -1, 15879, 15879, 15879, -1, + 15880, 15880, 15880, -1, 15881, 15881, 15881, -1, + 15882, 15882, 15882, -1, 15883, 15883, 15883, -1, + 15884, 15884, 15884, -1, 15885, 15885, 15885, -1, + 15886, 15886, 15886, -1, 15887, 15887, 15887, -1, + 15888, 15888, 15888, -1, 15889, 15889, 15889, -1, + 15890, 15890, 15890, -1, 15891, 15891, 15891, -1, + 15892, 15892, 15892, -1, 15893, 15893, 15893, -1, + 15894, 15894, 15894, -1, 15895, 15895, 15895, -1, + 15896, 15896, 15896, -1, 15897, 15897, 15897, -1, + 15898, 15898, 15898, -1, 15899, 15899, 15899, -1, + 15900, 15900, 15900, -1, 15901, 15901, 15901, -1, + 15902, 15902, 15902, -1, 15903, 15903, 15903, -1, + 15904, 15904, 15904, -1, 15905, 15905, 15905, -1, + 15906, 15906, 15906, -1, 15907, 15907, 15907, -1, + 15908, 15908, 15908, -1, 15909, 15909, 15909, -1, + 15910, 15910, 15910, -1, 15911, 15911, 15911, -1, + 15912, 15912, 15912, -1, 15913, 15913, 15913, -1, + 15914, 15914, 15914, -1, 15915, 15915, 15915, -1, + 15916, 15916, 15916, -1, 15917, 15917, 15917, -1, + 15918, 15918, 15918, -1, 15919, 15919, 15919, -1, + 15920, 15920, 15920, -1, 15921, 15921, 15921, -1, + 15922, 15922, 15922, -1, 15923, 15923, 15923, -1, + 15924, 15924, 15924, -1, 15925, 15925, 15925, -1, + 15926, 15926, 15926, -1, 15927, 15927, 15927, -1, + 15928, 15928, 15928, -1, 15929, 15929, 15929, -1, + 15930, 15930, 15930, -1, 15931, 15931, 15931, -1, + 15932, 15932, 15932, -1, 15933, 15933, 15933, -1, + 15934, 15934, 15934, -1, 15935, 15935, 15935, -1, + 15936, 15936, 15936, -1, 15937, 15937, 15937, -1, + 15938, 15938, 15938, -1, 15939, 15939, 15939, -1, + 15940, 15940, 15940, -1, 15941, 15941, 15941, -1, + 15942, 15942, 15942, -1, 15943, 15943, 15943, -1, + 15944, 15944, 15944, -1, 15945, 15945, 15945, -1, + 15946, 15946, 15946, -1, 15947, 15947, 15947, -1, + 15948, 15948, 15948, -1, 15949, 15949, 15949, -1, + 15950, 15950, 15950, -1, 15951, 15951, 15951, -1, + 15952, 15952, 15952, -1, 15953, 15953, 15953, -1, + 15954, 15954, 15954, -1, 15955, 15955, 15955, -1, + 15956, 15956, 15956, -1, 15957, 15957, 15957, -1, + 15958, 15958, 15958, -1, 15959, 15959, 15959, -1, + 15960, 15960, 15960, -1, 15961, 15961, 15961, -1, + 15962, 15962, 15962, -1, 15963, 15963, 15963, -1, + 15964, 15964, 15964, -1, 15965, 15965, 15965, -1, + 15966, 15966, 15966, -1, 15967, 15967, 15967, -1, + 15968, 15968, 15968, -1, 15969, 15969, 15969, -1, + 15970, 15970, 15970, -1, 15971, 15971, 15971, -1, + 15972, 15972, 15972, -1, 15973, 15973, 15973, -1, + 15974, 15974, 15974, -1, 15975, 15975, 15975, -1, + 15976, 15976, 15976, -1, 15977, 15977, 15977, -1, + 15978, 15978, 15978, -1, 15979, 15979, 15979, -1, + 15980, 15980, 15980, -1, 15981, 15981, 15981, -1, + 15982, 15982, 15982, -1, 15983, 15983, 15983, -1, + 15984, 15984, 15984, -1, 15985, 15985, 15985, -1, + 15986, 15986, 15986, -1, 15987, 15987, 15987, -1, + 15988, 15988, 15988, -1, 15989, 15989, 15989, -1, + 15990, 15990, 15990, -1, 15991, 15991, 15991, -1, + 15992, 15992, 15992, -1, 15993, 15993, 15993, -1, + 15994, 15994, 15994, -1, 15995, 15995, 15995, -1, + 15996, 15996, 15996, -1, 15997, 15997, 15997, -1, + 15998, 15998, 15998, -1, 15999, 15999, 15999, -1, + 16000, 16000, 16000, -1, 16001, 16001, 16001, -1, + 16002, 16002, 16002, -1, 16003, 16003, 16003, -1, + 16004, 16004, 16004, -1, 16005, 16005, 16005, -1, + 16006, 16006, 16006, -1, 16007, 16007, 16007, -1, + 16008, 16008, 16008, -1, 16009, 16009, 16009, -1, + 16010, 16010, 16010, -1, 16011, 16011, 16011, -1, + 16012, 16012, 16012, -1, 16013, 16013, 16013, -1, + 16014, 16014, 16014, -1, 16015, 16015, 16015, -1, + 16016, 16016, 16016, -1, 16017, 16017, 16017, -1, + 16018, 16018, 16018, -1, 16019, 16019, 16019, -1, + 16020, 16020, 16020, -1, 16021, 16021, 16021, -1, + 16022, 16022, 16022, -1, 16023, 16023, 16023, -1, + 16024, 16024, 16024, -1, 16025, 16025, 16025, -1, + 16026, 16026, 16026, -1, 16027, 16027, 16027, -1, + 16028, 16028, 16028, -1, 16029, 16029, 16029, -1, + 16030, 16030, 16030, -1, 16031, 16031, 16031, -1, + 16032, 16032, 16032, -1, 16033, 16033, 16033, -1, + 16034, 16034, 16034, -1, 16035, 16035, 16035, -1, + 16036, 16036, 16036, -1, 16037, 16037, 16037, -1, + 16038, 16038, 16038, -1, 16039, 16039, 16039, -1, + 16040, 16040, 16040, -1, 16041, 16041, 16041, -1, + 16042, 16042, 16042, -1, 16043, 16043, 16043, -1, + 16044, 16044, 16044, -1, 16045, 16045, 16045, -1, + 16046, 16046, 16046, -1, 16047, 16047, 16047, -1, + 16048, 16048, 16048, -1, 16049, 16049, 16049, -1, + 16050, 16050, 16050, -1, 16051, 16051, 16051, -1, + 16052, 16052, 16052, -1, 16053, 16053, 16053, -1, + 16054, 16054, 16054, -1, 16055, 16055, 16055, -1, + 16056, 16056, 16056, -1, 16057, 16057, 16057, -1, + 16058, 16058, 16058, -1, 16059, 16059, 16059, -1, + 16060, 16060, 16060, -1, 16061, 16061, 16061, -1, + 16062, 16062, 16062, -1, 16063, 16063, 16063, -1, + 16064, 16064, 16064, -1, 16065, 16065, 16065, -1, + 16066, 16066, 16066, -1, 16067, 16067, 16067, -1, + 16068, 16068, 16068, -1, 16069, 16069, 16069, -1, + 16070, 16070, 16070, -1, 16071, 16071, 16071, -1, + 16072, 16072, 16072, -1, 16073, 16073, 16073, -1, + 16074, 16074, 16074, -1, 16075, 16075, 16075, -1, + 16076, 16076, 16076, -1, 16077, 16077, 16077, -1, + 16078, 16078, 16078, -1, 16079, 16079, 16079, -1, + 16080, 16080, 16080, -1, 16081, 16081, 16081, -1, + 16082, 16082, 16082, -1, 16083, 16083, 16083, -1, + 16084, 16084, 16084, -1, 16085, 16085, 16085, -1, + 16086, 16086, 16086, -1, 16087, 16087, 16087, -1, + 16088, 16088, 16088, -1, 16089, 16089, 16089, -1, + 16090, 16090, 16090, -1, 16091, 16091, 16091, -1, + 16092, 16092, 16092, -1, 16093, 16093, 16093, -1, + 16094, 16094, 16094, -1, 16095, 16095, 16095, -1, + 16096, 16096, 16096, -1, 16097, 16097, 16097, -1, + 16098, 16098, 16098, -1, 16099, 16099, 16099, -1, + 16100, 16100, 16100, -1, 16101, 16101, 16101, -1, + 16102, 16102, 16102, -1, 16103, 16103, 16103, -1, + 16104, 16104, 16104, -1, 16105, 16105, 16105, -1, + 16106, 16106, 16106, -1, 16107, 16107, 16107, -1, + 16108, 16108, 16108, -1, 16109, 16109, 16109, -1, + 16110, 16110, 16110, -1, 16111, 16111, 16111, -1, + 16112, 16112, 16112, -1, 16113, 16113, 16113, -1, + 16114, 16114, 16114, -1, 16115, 16115, 16115, -1, + 16116, 16116, 16116, -1, 16117, 16117, 16117, -1, + 16118, 16118, 16118, -1, 16119, 16119, 16119, -1, + 16120, 16120, 16120, -1, 16121, 16121, 16121, -1, + 16122, 16122, 16122, -1, 16123, 16123, 16123, -1, + 16124, 16124, 16124, -1, 16125, 16125, 16125, -1, + 16126, 16126, 16126, -1, 16127, 16127, 16127, -1, + 16128, 16128, 16128, -1, 16129, 16129, 16129, -1, + 16130, 16130, 16130, -1, 16131, 16131, 16131, -1, + 16132, 16132, 16132, -1, 16133, 16133, 16133, -1, + 16134, 16134, 16134, -1, 16135, 16135, 16135, -1, + 16136, 16136, 16136, -1, 16137, 16137, 16137, -1, + 16138, 16138, 16138, -1, 16139, 16139, 16139, -1, + 16140, 16140, 16140, -1, 16141, 16141, 16141, -1, + 16142, 16142, 16142, -1, 16143, 16143, 16143, -1, + 16144, 16144, 16144, -1, 16145, 16145, 16145, -1, + 16146, 16146, 16146, -1, 16147, 16147, 16147, -1, + 16148, 16148, 16148, -1, 16149, 16149, 16149, -1, + 16150, 16150, 16150, -1, 16151, 16151, 16151, -1, + 16152, 16152, 16152, -1, 16153, 16153, 16153, -1, + 16154, 16154, 16154, -1, 16155, 16155, 16155, -1, + 16156, 16156, 16156, -1, 16157, 16157, 16157, -1, + 16158, 16158, 16158, -1, 16159, 16159, 16159, -1, + 16160, 16160, 16160, -1, 16161, 16161, 16161, -1, + 16162, 16162, 16162, -1, 16163, 16163, 16163, -1, + 16164, 16164, 16164, -1, 16165, 16165, 16165, -1, + 16166, 16166, 16166, -1, 16167, 16167, 16167, -1, + 16168, 16168, 16168, -1, 16169, 16169, 16169, -1, + 16170, 16170, 16170, -1, 16171, 16171, 16171, -1, + 16172, 16172, 16172, -1, 16173, 16173, 16173, -1, + 16174, 16174, 16174, -1, 16175, 16175, 16175, -1, + 16176, 16176, 16176, -1, 16177, 16177, 16177, -1, + 16178, 16178, 16178, -1, 16179, 16179, 16179, -1, + 16180, 16180, 16180, -1, 16181, 16181, 16181, -1, + 16182, 16182, 16182, -1, 16183, 16183, 16183, -1, + 16184, 16184, 16184, -1, 16185, 16185, 16185, -1, + 16186, 16186, 16186, -1, 16187, 16187, 16187, -1, + 16188, 16188, 16188, -1, 16189, 16189, 16189, -1, + 16190, 16190, 16190, -1, 16191, 16191, 16191, -1, + 16192, 16192, 16192, -1, 16193, 16193, 16193, -1, + 16194, 16194, 16194, -1, 16195, 16195, 16195, -1, + 16196, 16196, 16196, -1, 16197, 16197, 16197, -1, + 16198, 16198, 16198, -1, 16199, 16199, 16199, -1, + 16200, 16200, 16200, -1, 16201, 16201, 16201, -1, + 16202, 16202, 16202, -1, 16203, 16203, 16203, -1, + 16204, 16204, 16204, -1, 16205, 16205, 16205, -1, + 16206, 16206, 16206, -1, 16207, 16207, 16207, -1, + 16208, 16208, 16208, -1, 16209, 16209, 16209, -1, + 16210, 16210, 16210, -1, 16211, 16211, 16211, -1, + 16212, 16212, 16212, -1, 16213, 16213, 16213, -1, + 16214, 16214, 16214, -1, 16215, 16215, 16215, -1, + 16216, 16216, 16216, -1, 16217, 16217, 16217, -1, + 16218, 16218, 16218, -1, 16219, 16219, 16219, -1, + 16220, 16220, 16220, -1, 16221, 16221, 16221, -1, + 16222, 16222, 16222, -1, 16223, 16223, 16223, -1, + 16224, 16224, 16224, -1, 16225, 16225, 16225, -1, + 16226, 16226, 16226, -1, 16227, 16227, 16227, -1, + 16228, 16228, 16228, -1, 16229, 16229, 16229, -1, + 16230, 16230, 16230, -1, 16231, 16231, 16231, -1, + 16232, 16232, 16232, -1, 16233, 16233, 16233, -1, + 16234, 16234, 16234, -1, 16235, 16235, 16235, -1, + 16236, 16236, 16236, -1, 16237, 16237, 16237, -1, + 16238, 16238, 16238, -1, 16239, 16239, 16239, -1, + 16240, 16240, 16240, -1, 16241, 16241, 16241, -1, + 16242, 16242, 16242, -1, 16243, 16243, 16243, -1, + 16244, 16244, 16244, -1, 16245, 16245, 16245, -1, + 16246, 16246, 16246, -1, 16247, 16247, 16247, -1, + 16248, 16248, 16248, -1, 16249, 16249, 16249, -1, + 16250, 16250, 16250, -1, 16251, 16251, 16251, -1, + 16252, 16252, 16252, -1, 16253, 16253, 16253, -1, + 16254, 16254, 16254, -1, 16255, 16255, 16255, -1, + 16256, 16256, 16256, -1, 16257, 16257, 16257, -1, + 16258, 16258, 16258, -1, 16259, 16259, 16259, -1, + 16260, 16260, 16260, -1, 16261, 16261, 16261, -1, + 16262, 16262, 16262, -1, 16263, 16263, 16263, -1, + 16264, 16264, 16264, -1, 16265, 16265, 16265, -1, + 16266, 16266, 16266, -1, 16267, 16267, 16267, -1, + 16268, 16268, 16268, -1, 16269, 16269, 16269, -1, + 16270, 16270, 16270, -1, 16271, 16271, 16271, -1, + 16272, 16272, 16272, -1, 16273, 16273, 16273, -1, + 16274, 16274, 16274, -1, 16275, 16275, 16275, -1, + 16276, 16276, 16276, -1, 16277, 16277, 16277, -1, + 16278, 16278, 16278, -1, 16279, 16279, 16279, -1, + 16280, 16280, 16280, -1, 16281, 16281, 16281, -1, + 16282, 16282, 16282, -1, 16283, 16283, 16283, -1, + 16284, 16284, 16284, -1, 16285, 16285, 16285, -1, + 16286, 16286, 16286, -1, 16287, 16287, 16287, -1, + 16288, 16288, 16288, -1, 16289, 16289, 16289, -1, + 16290, 16290, 16290, -1, 16291, 16291, 16291, -1, + 16292, 16292, 16292, -1, 16293, 16293, 16293, -1, + 16294, 16294, 16294, -1, 16295, 16295, 16295, -1, + 16296, 16296, 16296, -1, 16297, 16297, 16297, -1, + 16298, 16298, 16298, -1, 16299, 16299, 16299, -1, + 16300, 16300, 16300, -1, 16301, 16301, 16301, -1, + 16302, 16302, 16302, -1, 16303, 16303, 16303, -1, + 16304, 16304, 16304, -1, 16305, 16305, 16305, -1, + 16306, 16306, 16306, -1, 16307, 16307, 16307, -1, + 16308, 16308, 16308, -1, 16309, 16309, 16309, -1, + 16310, 16310, 16310, -1, 16311, 16311, 16311, -1, + 16312, 16312, 16312, -1, 16313, 16313, 16313, -1, + 16314, 16314, 16314, -1, 16315, 16315, 16315, -1, + 16316, 16316, 16316, -1, 16317, 16317, 16317, -1, + 16318, 16318, 16318, -1, 16319, 16319, 16319, -1, + 16320, 16320, 16320, -1, 16321, 16321, 16321, -1, + 16322, 16322, 16322, -1, 16323, 16323, 16323, -1, + 16324, 16324, 16324, -1, 16325, 16325, 16325, -1, + 16326, 16326, 16326, -1, 16327, 16327, 16327, -1, + 16328, 16328, 16328, -1, 16329, 16329, 16329, -1, + 16330, 16330, 16330, -1, 16331, 16331, 16331, -1, + 16332, 16332, 16332, -1, 16333, 16333, 16333, -1, + 16334, 16334, 16334, -1, 16335, 16335, 16335, -1, + 16336, 16336, 16336, -1, 16337, 16337, 16337, -1, + 16338, 16338, 16338, -1, 16339, 16339, 16339, -1, + 16340, 16340, 16340, -1, 16341, 16341, 16341, -1, + 16342, 16342, 16342, -1, 16343, 16343, 16343, -1, + 16344, 16344, 16344, -1, 16345, 16345, 16345, -1, + 16346, 16346, 16346, -1, 16347, 16347, 16347, -1, + 16348, 16348, 16348, -1, 16349, 16349, 16349, -1, + 16350, 16350, 16350, -1, 16351, 16351, 16351, -1, + 16352, 16352, 16352, -1, 16353, 16353, 16353, -1, + 16354, 16354, 16354, -1, 16355, 16355, 16355, -1, + 16356, 16356, 16356, -1, 16357, 16357, 16357, -1, + 16358, 16358, 16358, -1, 16359, 16359, 16359, -1, + 16360, 16360, 16360, -1, 16361, 16361, 16361, -1, + 16362, 16362, 16362, -1, 16363, 16363, 16363, -1, + 16364, 16364, 16364, -1, 16365, 16365, 16365, -1, + 16366, 16366, 16366, -1, 16367, 16367, 16367, -1, + 16368, 16368, 16368, -1, 16369, 16369, 16369, -1, + 16370, 16370, 16370, -1, 16371, 16371, 16371, -1, + 16372, 16372, 16372, -1, 16373, 16373, 16373, -1, + 16374, 16374, 16374, -1, 16375, 16375, 16375, -1, + 16376, 16376, 16376, -1, 16377, 16377, 16377, -1, + 16378, 16378, 16378, -1, 16379, 16379, 16379, -1, + 16380, 16380, 16380, -1, 16381, 16381, 16381, -1, + 16382, 16382, 16382, -1, 16383, 16383, 16383, -1, + 16384, 16384, 16384, -1, 16385, 16385, 16385, -1, + 16386, 16386, 16386, -1, 16387, 16387, 16387, -1, + 16388, 16388, 16388, -1, 16389, 16389, 16389, -1, + 16390, 16390, 16390, -1, 16391, 16391, 16391, -1, + 16392, 16392, 16392, -1, 16393, 16393, 16393, -1, + 16394, 16394, 16394, -1, 16395, 16395, 16395, -1, + 16396, 16396, 16396, -1, 16397, 16397, 16397, -1, + 16398, 16398, 16398, -1, 16399, 16399, 16399, -1, + 16400, 16400, 16400, -1, 16401, 16401, 16401, -1, + 16402, 16402, 16402, -1, 16403, 16403, 16403, -1, + 16404, 16404, 16404, -1, 16405, 16405, 16405, -1, + 16406, 16406, 16406, -1, 16407, 16407, 16407, -1, + 16408, 16408, 16408, -1, 16409, 16409, 16409, -1, + 16410, 16410, 16410, -1, 16411, 16411, 16411, -1, + 16412, 16412, 16412, -1, 16413, 16413, 16413, -1, + 16414, 16414, 16414, -1, 16415, 16415, 16415, -1, + 16416, 16416, 16416, -1, 16417, 16417, 16417, -1, + 16418, 16418, 16418, -1, 16419, 16419, 16419, -1, + 16420, 16420, 16420, -1, 16421, 16421, 16421, -1, + 16422, 16422, 16422, -1, 16423, 16423, 16423, -1, + 16424, 16424, 16424, -1, 16425, 16425, 16425, -1, + 16426, 16426, 16426, -1, 16427, 16427, 16427, -1, + 16428, 16428, 16428, -1, 16429, 16429, 16429, -1, + 16430, 16430, 16430, -1, 16431, 16431, 16431, -1, + 16432, 16432, 16432, -1, 16433, 16433, 16433, -1, + 16434, 16434, 16434, -1, 16435, 16435, 16435, -1, + 16436, 16436, 16436, -1, 16437, 16437, 16437, -1, + 16438, 16438, 16438, -1, 16439, 16439, 16439, -1, + 16440, 16440, 16440, -1, 16441, 16441, 16441, -1, + 16442, 16442, 16442, -1, 16443, 16443, 16443, -1, + 16444, 16444, 16444, -1, 16445, 16445, 16445, -1, + 16446, 16446, 16446, -1, 16447, 16447, 16447, -1, + 16448, 16448, 16448, -1, 16449, 16449, 16449, -1, + 16450, 16450, 16450, -1, 16451, 16451, 16451, -1, + 16452, 16452, 16452, -1, 16453, 16453, 16453, -1, + 16454, 16454, 16454, -1, 16455, 16455, 16455, -1, + 16456, 16456, 16456, -1, 16457, 16457, 16457, -1, + 16458, 16458, 16458, -1, 16459, 16459, 16459, -1, + 16460, 16460, 16460, -1, 16461, 16461, 16461, -1, + 16462, 16462, 16462, -1, 16463, 16463, 16463, -1, + 16464, 16464, 16464, -1, 16465, 16465, 16465, -1, + 16466, 16466, 16466, -1, 16467, 16467, 16467, -1, + 16468, 16468, 16468, -1, 16469, 16469, 16469, -1, + 16470, 16470, 16470, -1, 16471, 16471, 16471, -1, + 16472, 16472, 16472, -1, 16473, 16473, 16473, -1, + 16474, 16474, 16474, -1, 16475, 16475, 16475, -1, + 16476, 16476, 16476, -1, 16477, 16477, 16477, -1, + 16478, 16478, 16478, -1, 16479, 16479, 16479, -1, + 16480, 16480, 16480, -1, 16481, 16481, 16481, -1, + 16482, 16482, 16482, -1, 16483, 16483, 16483, -1, + 16484, 16484, 16484, -1, 16485, 16485, 16485, -1, + 16486, 16486, 16486, -1, 16487, 16487, 16487, -1, + 16488, 16488, 16488, -1, 16489, 16489, 16489, -1, + 16490, 16490, 16490, -1, 16491, 16491, 16491, -1, + 16492, 16492, 16492, -1, 16493, 16493, 16493, -1, + 16494, 16494, 16494, -1, 16495, 16495, 16495, -1, + 16496, 16496, 16496, -1, 16497, 16497, 16497, -1, + 16498, 16498, 16498, -1, 16499, 16499, 16499, -1, + 16500, 16500, 16500, -1, 16501, 16501, 16501, -1, + 16502, 16502, 16502, -1, 16503, 16503, 16503, -1, + 16504, 16504, 16504, -1, 16505, 16505, 16505, -1, + 16506, 16506, 16506, -1, 16507, 16507, 16507, -1, + 16508, 16508, 16508, -1, 16509, 16509, 16509, -1, + 16510, 16510, 16510, -1, 16511, 16511, 16511, -1, + 16512, 16512, 16512, -1, 16513, 16513, 16513, -1, + 16514, 16514, 16514, -1, 16515, 16515, 16515, -1, + 16516, 16516, 16516, -1, 16517, 16517, 16517, -1, + 16518, 16518, 16518, -1, 16519, 16519, 16519, -1, + 16520, 16520, 16520, -1, 16521, 16521, 16521, -1, + 16522, 16522, 16522, -1, 16523, 16523, 16523, -1, + 16524, 16524, 16524, -1, 16525, 16525, 16525, -1, + 16526, 16526, 16526, -1, 16527, 16527, 16527, -1, + 16528, 16528, 16528, -1, 16529, 16529, 16529, -1, + 16530, 16530, 16530, -1, 16531, 16531, 16531, -1, + 16532, 16532, 16532, -1, 16533, 16533, 16533, -1, + 16534, 16534, 16534, -1, 16535, 16535, 16535, -1, + 16536, 16536, 16536, -1, 16537, 16537, 16537, -1, + 16538, 16538, 16538, -1, 16539, 16539, 16539, -1, + 16540, 16540, 16540, -1, 16541, 16541, 16541, -1, + 16542, 16542, 16542, -1, 16543, 16543, 16543, -1, + 16544, 16544, 16544, -1, 16545, 16545, 16545, -1, + 16546, 16546, 16546, -1, 16547, 16547, 16547, -1, + 16548, 16548, 16548, -1, 16549, 16549, 16549, -1, + 16550, 16550, 16550, -1, 16551, 16551, 16551, -1, + 16552, 16552, 16552, -1, 16553, 16553, 16553, -1, + 16554, 16554, 16554, -1, 16555, 16555, 16555, -1, + 16556, 16556, 16556, -1, 16557, 16557, 16557, -1, + 16558, 16558, 16558, -1, 16559, 16559, 16559, -1, + 16560, 16560, 16560, -1, 16561, 16561, 16561, -1, + 16562, 16562, 16562, -1, 16563, 16563, 16563, -1, + 16564, 16564, 16564, -1, 16565, 16565, 16565, -1, + 16566, 16566, 16566, -1, 16567, 16567, 16567, -1, + 16568, 16568, 16568, -1, 16569, 16569, 16569, -1, + 16570, 16570, 16570, -1, 16571, 16571, 16571, -1, + 16572, 16572, 16572, -1, 16573, 16573, 16573, -1, + 16574, 16574, 16574, -1, 16575, 16575, 16575, -1, + 16576, 16576, 16576, -1, 16577, 16577, 16577, -1, + 16578, 16578, 16578, -1, 16579, 16579, 16579, -1, + 16580, 16580, 16580, -1, 16581, 16581, 16581, -1, + 16582, 16582, 16582, -1, 16583, 16583, 16583, -1, + 16584, 16584, 16584, -1, 16585, 16585, 16585, -1, + 16586, 16586, 16586, -1, 16587, 16587, 16587, -1, + 16588, 16588, 16588, -1, 16589, 16589, 16589, -1, + 16590, 16590, 16590, -1, 16591, 16591, 16591, -1, + 16592, 16592, 16592, -1, 16593, 16593, 16593, -1, + 16594, 16594, 16594, -1, 16595, 16595, 16595, -1, + 16596, 16596, 16596, -1, 16597, 16597, 16597, -1, + 16598, 16598, 16598, -1, 16599, 16599, 16599, -1, + 16600, 16600, 16600, -1, 16601, 16601, 16601, -1, + 16602, 16602, 16602, -1, 16603, 16603, 16603, -1, + 16604, 16604, 16604, -1, 16605, 16605, 16605, -1, + 16606, 16606, 16606, -1, 16607, 16607, 16607, -1, + 16608, 16608, 16608, -1, 16609, 16609, 16609, -1, + 16610, 16610, 16610, -1, 16611, 16611, 16611, -1, + 16612, 16612, 16612, -1, 16613, 16613, 16613, -1, + 16614, 16614, 16614, -1, 16615, 16615, 16615, -1, + 16616, 16616, 16616, -1, 16617, 16617, 16617, -1, + 16618, 16618, 16618, -1, 16619, 16619, 16619, -1, + 16620, 16620, 16620, -1, 16621, 16621, 16621, -1, + 16622, 16622, 16622, -1, 16623, 16623, 16623, -1, + 16624, 16624, 16624, -1, 16625, 16625, 16625, -1, + 16626, 16626, 16626, -1, 16627, 16627, 16627, -1, + 16628, 16628, 16628, -1, 16629, 16629, 16629, -1, + 16630, 16630, 16630, -1, 16631, 16631, 16631, -1, + 16632, 16632, 16632, -1, 16633, 16633, 16633, -1, + 16634, 16634, 16634, -1, 16635, 16635, 16635, -1, + 16636, 16636, 16636, -1, 16637, 16637, 16637, -1, + 16638, 16638, 16638, -1, 16639, 16639, 16639, -1, + 16640, 16640, 16640, -1, 16641, 16641, 16641, -1, + 16642, 16642, 16642, -1, 16643, 16643, 16643, -1, + 16644, 16644, 16644, -1, 16645, 16645, 16645, -1, + 16646, 16646, 16646, -1, 16647, 16647, 16647, -1, + 16648, 16648, 16648, -1, 16649, 16649, 16649, -1, + 16650, 16650, 16650, -1, 16651, 16651, 16651, -1, + 16652, 16652, 16652, -1, 16653, 16653, 16653, -1, + 16654, 16654, 16654, -1, 16655, 16655, 16655, -1, + 16656, 16656, 16656, -1, 16657, 16657, 16657, -1, + 16658, 16658, 16658, -1, 16659, 16659, 16659, -1, + 16660, 16660, 16660, -1, 16661, 16661, 16661, -1, + 16662, 16662, 16662, -1, 16663, 16663, 16663, -1, + 16664, 16664, 16664, -1, 16665, 16665, 16665, -1, + 16666, 16666, 16666, -1, 16667, 16667, 16667, -1, + 16668, 16668, 16668, -1, 16669, 16669, 16669, -1, + 16670, 16670, 16670, -1, 16671, 16671, 16671, -1, + 16672, 16672, 16672, -1, 16673, 16673, 16673, -1, + 16674, 16674, 16674, -1, 16675, 16675, 16675, -1, + 16676, 16676, 16676, -1, 16677, 16677, 16677, -1, + 16678, 16678, 16678, -1, 16679, 16679, 16679, -1, + 16680, 16680, 16680, -1, 16681, 16681, 16681, -1, + 16682, 16682, 16682, -1, 16683, 16683, 16683, -1, + 16684, 16684, 16684, -1, 16685, 16685, 16685, -1, + 16686, 16686, 16686, -1, 16687, 16687, 16687, -1, + 16688, 16688, 16688, -1, 16689, 16689, 16689, -1, + 16690, 16690, 16690, -1, 16691, 16691, 16691, -1, + 16692, 16692, 16692, -1, 16693, 16693, 16693, -1, + 16694, 16694, 16694, -1, 16695, 16695, 16695, -1, + 16696, 16696, 16696, -1, 16697, 16697, 16697, -1, + 16698, 16698, 16698, -1, 16699, 16699, 16699, -1, + 16700, 16700, 16700, -1, 16701, 16701, 16701, -1, + 16702, 16702, 16702, -1, 16703, 16703, 16703, -1, + 16704, 16704, 16704, -1, 16705, 16705, 16705, -1, + 16706, 16706, 16706, -1, 16707, 16707, 16707, -1, + 16708, 16708, 16708, -1, 16709, 16709, 16709, -1, + 16710, 16710, 16710, -1, 16711, 16711, 16711, -1, + 16712, 16712, 16712, -1, 16713, 16713, 16713, -1, + 16714, 16714, 16714, -1, 16715, 16715, 16715, -1, + 16716, 16716, 16716, -1, 16717, 16717, 16717, -1, + 16718, 16718, 16718, -1, 16719, 16719, 16719, -1, + 16720, 16720, 16720, -1, 16721, 16721, 16721, -1, + 16722, 16722, 16722, -1, 16723, 16723, 16723, -1, + 16724, 16724, 16724, -1, 16725, 16725, 16725, -1, + 16726, 16726, 16726, -1, 16727, 16727, 16727, -1, + 16728, 16728, 16728, -1, 16729, 16729, 16729, -1, + 16730, 16730, 16730, -1, 16731, 16731, 16731, -1, + 16732, 16732, 16732, -1, 16733, 16733, 16733, -1, + 16734, 16734, 16734, -1, 16735, 16735, 16735, -1, + 16736, 16736, 16736, -1, 16737, 16737, 16737, -1, + 16738, 16738, 16738, -1, 16739, 16739, 16739, -1, + 16740, 16740, 16740, -1, 16741, 16741, 16741, -1, + 16742, 16742, 16742, -1, 16743, 16743, 16743, -1, + 16744, 16744, 16744, -1, 16745, 16745, 16745, -1, + 16746, 16746, 16746, -1, 16747, 16747, 16747, -1, + 16748, 16748, 16748, -1, 16749, 16749, 16749, -1, + 16750, 16750, 16750, -1, 16751, 16751, 16751, -1, + 16752, 16752, 16752, -1, 16753, 16753, 16753, -1, + 16754, 16754, 16754, -1, 16755, 16755, 16755, -1, + 16756, 16756, 16756, -1, 16757, 16757, 16757, -1, + 16758, 16758, 16758, -1, 16759, 16759, 16759, -1, + 16760, 16760, 16760, -1, 16761, 16761, 16761, -1, + 16762, 16762, 16762, -1, 16763, 16763, 16763, -1, + 16764, 16764, 16764, -1, 16765, 16765, 16765, -1, + 16766, 16766, 16766, -1, 16767, 16767, 16767, -1, + 16768, 16768, 16768, -1, 16769, 16769, 16769, -1, + 16770, 16770, 16770, -1, 16771, 16771, 16771, -1, + 16772, 16772, 16772, -1, 16773, 16773, 16773, -1, + 16774, 16774, 16774, -1, 16775, 16775, 16775, -1, + 16776, 16776, 16776, -1, 16777, 16777, 16777, -1, + 16778, 16778, 16778, -1, 16779, 16779, 16779, -1, + 16780, 16780, 16780, -1, 16781, 16781, 16781, -1, + 16782, 16782, 16782, -1, 16783, 16783, 16783, -1, + 16784, 16784, 16784, -1, 16785, 16785, 16785, -1, + 16786, 16786, 16786, -1, 16787, 16787, 16787, -1, + 16788, 16788, 16788, -1, 16789, 16789, 16789, -1, + 16790, 16790, 16790, -1, 16791, 16791, 16791, -1, + 16792, 16792, 16792, -1, 16793, 16793, 16793, -1, + 16794, 16794, 16794, -1, 16795, 16795, 16795, -1, + 16796, 16796, 16796, -1, 16797, 16797, 16797, -1, + 16798, 16798, 16798, -1, 16799, 16799, 16799, -1, + 16800, 16800, 16800, -1, 16801, 16801, 16801, -1, + 16802, 16802, 16802, -1, 16803, 16803, 16803, -1, + 16804, 16804, 16804, -1, 16805, 16805, 16805, -1, + 16806, 16806, 16806, -1, 16807, 16807, 16807, -1, + 16808, 16808, 16808, -1, 16809, 16809, 16809, -1, + 16810, 16810, 16810, -1, 16811, 16811, 16811, -1, + 16812, 16812, 16812, -1, 16813, 16813, 16813, -1, + 16814, 16814, 16814, -1, 16815, 16815, 16815, -1, + 16816, 16816, 16816, -1, 16817, 16817, 16817, -1, + 16818, 16818, 16818, -1, 16819, 16819, 16819, -1, + 16820, 16820, 16820, -1, 16821, 16821, 16821, -1, + 16822, 16822, 16822, -1, 16823, 16823, 16823, -1, + 16824, 16824, 16824, -1, 16825, 16825, 16825, -1, + 16826, 16826, 16826, -1, 16827, 16827, 16827, -1, + 16828, 16828, 16828, -1, 16829, 16829, 16829, -1, + 16830, 16830, 16830, -1, 16831, 16831, 16831, -1, + 16832, 16832, 16832, -1, 16833, 16833, 16833, -1, + 16834, 16834, 16834, -1, 16835, 16835, 16835, -1, + 16836, 16836, 16836, -1, 16837, 16837, 16837, -1, + 16838, 16838, 16838, -1, 16839, 16839, 16839, -1, + 16840, 16840, 16840, -1, 16841, 16841, 16841, -1, + 16842, 16842, 16842, -1, 16843, 16843, 16843, -1, + 16844, 16844, 16844, -1, 16845, 16845, 16845, -1, + 16846, 16846, 16846, -1, 16847, 16847, 16847, -1, + 16848, 16848, 16848, -1, 16849, 16849, 16849, -1, + 16850, 16850, 16850, -1, 16851, 16851, 16851, -1, + 16852, 16852, 16852, -1, 16853, 16853, 16853, -1, + 16854, 16854, 16854, -1, 16855, 16855, 16855, -1, + 16856, 16856, 16856, -1, 16857, 16857, 16857, -1, + 16858, 16858, 16858, -1, 16859, 16859, 16859, -1, + 16860, 16860, 16860, -1, 16861, 16861, 16861, -1, + 16862, 16862, 16862, -1, 16863, 16863, 16863, -1, + 16864, 16864, 16864, -1, 16865, 16865, 16865, -1, + 16866, 16866, 16866, -1, 16867, 16867, 16867, -1, + 16868, 16868, 16868, -1, 16869, 16869, 16869, -1, + 16870, 16870, 16870, -1, 16871, 16871, 16871, -1, + 16872, 16872, 16872, -1, 16873, 16873, 16873, -1, + 16874, 16874, 16874, -1, 16875, 16875, 16875, -1, + 16876, 16876, 16876, -1, 16877, 16877, 16877, -1, + 16878, 16878, 16878, -1, 16879, 16879, 16879, -1, + 16880, 16880, 16880, -1, 16881, 16881, 16881, -1, + 16882, 16882, 16882, -1, 16883, 16883, 16883, -1, + 16884, 16884, 16884, -1, 16885, 16885, 16885, -1, + 16886, 16886, 16886, -1, 16887, 16887, 16887, -1, + 16888, 16888, 16888, -1, 16889, 16889, 16889, -1, + 16890, 16890, 16890, -1, 16891, 16891, 16891, -1, + 16892, 16892, 16892, -1, 16893, 16893, 16893, -1, + 16894, 16894, 16894, -1, 16895, 16895, 16895, -1, + 16896, 16896, 16896, -1, 16897, 16897, 16897, -1, + 16898, 16898, 16898, -1, 16899, 16899, 16899, -1, + 16900, 16900, 16900, -1, 16901, 16901, 16901, -1, + 16902, 16902, 16902, -1, 16903, 16903, 16903, -1, + 16904, 16904, 16904, -1, 16905, 16905, 16905, -1, + 16906, 16906, 16906, -1, 16907, 16907, 16907, -1, + 16908, 16908, 16908, -1, 16909, 16909, 16909, -1, + 16910, 16910, 16910, -1, 16911, 16911, 16911, -1, + 16912, 16912, 16912, -1, 16913, 16913, 16913, -1, + 16914, 16914, 16914, -1, 16915, 16915, 16915, -1, + 16916, 16916, 16916, -1, 16917, 16917, 16917, -1, + 16918, 16918, 16918, -1, 16919, 16919, 16919, -1, + 16920, 16920, 16920, -1, 16921, 16921, 16921, -1, + 16922, 16922, 16922, -1, 16923, 16923, 16923, -1, + 16924, 16924, 16924, -1, 16925, 16925, 16925, -1, + 16926, 16926, 16926, -1, 16927, 16927, 16927, -1, + 16928, 16928, 16928, -1, 16929, 16929, 16929, -1, + 16930, 16930, 16930, -1, 16931, 16931, 16931, -1, + 16932, 16932, 16932, -1, 16933, 16933, 16933, -1, + 16934, 16934, 16934, -1, 16935, 16935, 16935, -1, + 16936, 16936, 16936, -1, 16937, 16937, 16937, -1, + 16938, 16938, 16938, -1, 16939, 16939, 16939, -1, + 16940, 16940, 16940, -1, 16941, 16941, 16941, -1, + 16942, 16942, 16942, -1, 16943, 16943, 16943, -1, + 16944, 16944, 16944, -1, 16945, 16945, 16945, -1, + 16946, 16946, 16946, -1, 16947, 16947, 16947, -1, + 16948, 16948, 16948, -1, 16949, 16949, 16949, -1, + 16950, 16950, 16950, -1, 16951, 16951, 16951, -1, + 16952, 16952, 16952, -1, 16953, 16953, 16953, -1, + 16954, 16954, 16954, -1, 16955, 16955, 16955, -1, + 16956, 16956, 16956, -1, 16957, 16957, 16957, -1, + 16958, 16958, 16958, -1, 16959, 16959, 16959, -1, + 16960, 16960, 16960, -1, 16961, 16961, 16961, -1, + 16962, 16962, 16962, -1, 16963, 16963, 16963, -1, + 16964, 16964, 16964, -1, 16965, 16965, 16965, -1, + 16966, 16966, 16966, -1, 16967, 16967, 16967, -1, + 16968, 16968, 16968, -1, 16969, 16969, 16969, -1, + 16970, 16970, 16970, -1, 16971, 16971, 16971, -1, + 16972, 16972, 16972, -1, 16973, 16973, 16973, -1, + 16974, 16974, 16974, -1, 16975, 16975, 16975, -1, + 16976, 16976, 16976, -1, 16977, 16977, 16977, -1, + 16978, 16978, 16978, -1, 16979, 16979, 16979, -1, + 16980, 16980, 16980, -1, 16981, 16981, 16981, -1, + 16982, 16982, 16982, -1, 16983, 16983, 16983, -1, + 16984, 16984, 16984, -1, 16985, 16985, 16985, -1, + 16986, 16986, 16986, -1, 16987, 16987, 16987, -1, + 16988, 16988, 16988, -1, 16989, 16989, 16989, -1, + 16990, 16990, 16990, -1, 16991, 16991, 16991, -1, + 16992, 16992, 16992, -1, 16993, 16993, 16993, -1, + 16994, 16994, 16994, -1, 16995, 16995, 16995, -1, + 16996, 16996, 16996, -1, 16997, 16997, 16997, -1, + 16998, 16998, 16998, -1, 16999, 16999, 16999, -1, + 17000, 17000, 17000, -1, 17001, 17001, 17001, -1, + 17002, 17002, 17002, -1, 17003, 17003, 17003, -1, + 17004, 17004, 17004, -1, 17005, 17005, 17005, -1, + 17006, 17006, 17006, -1, 17007, 17007, 17007, -1, + 17008, 17008, 17008, -1, 17009, 17009, 17009, -1, + 17010, 17010, 17010, -1, 17011, 17011, 17011, -1, + 17012, 17012, 17012, -1, 17013, 17013, 17013, -1, + 17014, 17014, 17014, -1, 17015, 17015, 17015, -1, + 17016, 17016, 17016, -1, 17017, 17017, 17017, -1, + 17018, 17018, 17018, -1, 17019, 17019, 17019, -1, + 17020, 17020, 17020, -1, 17021, 17021, 17021, -1, + 17022, 17022, 17022, -1, 17023, 17023, 17023, -1, + 17024, 17024, 17024, -1, 17025, 17025, 17025, -1, + 17026, 17026, 17026, -1, 17027, 17027, 17027, -1, + 17028, 17028, 17028, -1, 17029, 17029, 17029, -1, + 17030, 17030, 17030, -1, 17031, 17031, 17031, -1, + 17032, 17032, 17032, -1, 17033, 17033, 17033, -1, + 17034, 17034, 17034, -1, 17035, 17035, 17035, -1, + 17036, 17036, 17036, -1, 17036, 17036, 17036, -1, + 17037, 17037, 17037, -1, 17037, 17037, 17037, -1, + 17038, 17038, 17038, -1, 17038, 17038, 17038, -1, + 17039, 17039, 17039, -1, 17039, 17039, 17039, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17041, 17041, 17041, -1, 17041, 17041, 17041, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17043, 17043, 17043, -1, + 17043, 17043, 17043, -1, 17044, 17044, 17044, -1, + 17044, 17044, 17044, -1, 17045, 17045, 17045, -1, + 17045, 17045, 17045, -1, 17046, 17046, 17046, -1, + 17046, 17046, 17046, -1, 17047, 17047, 17047, -1, + 17047, 17047, 17047, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } ] + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link3.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link3.wrl new file mode 100644 index 0000000..a9060ca --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link3.wrl @@ -0,0 +1,45650 @@ +#VRML V2.0 utf8 + + +Group { + children [ + Group { + children + Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.037807401 -0.0094999997 0.04659, + -0.0328166 -0.0094999997 0.05023, + -0.035358898 0.0074999998 0.048473999, + 0.031582098 -0.0094999997 0.051015001, + 0.036660202 -0.0094999997 0.047497999, + 0.034166399 0.0074999998 0.049322002, + 0.0585596 -0.0094999997 -0.013068, + 0.056905501 -0.0094999997 -0.01902, + 0.0578092 0.0074999998 -0.016065, + -0.0054411199 -0.0094999997 -0.059753001, + -0.0023579099 0.0074999998 -0.059953999, + 0.00073155703 -0.0094999997 -0.059996001, + -0.0564248 -0.0094999997 -0.020401999, + -0.058223501 -0.0094999997 -0.014492, + -0.057400201 0.0074999998 -0.01747, + -0.0599568 -0.0094999997 -0.0022760001, + -0.059760101 0.0074999998 -0.0053599998, + -0.059404999 -0.0094999997 -0.0084290002, + -0.058892298 0.0074999998 -0.011476, + -0.0233551 -0.0094999997 -0.055268001, + -0.020478999 0.0074999998 -0.056396998, + -0.0175486 -0.0094999997 -0.057376001, + -0.028914001 -0.0094999997 -0.052574001, + -0.0261693 0.0074999998 -0.053991999, + -0.034166399 -0.0094999997 -0.049322002, + -0.031582098 0.0074999998 -0.051015001, + -0.0390567 -0.0094999997 -0.045547001, + -0.036660202 0.0074999998 -0.047497999, + -0.043532901 -0.0094999997 -0.04129, + -0.041349601 0.0074999998 -0.043476999, + -0.047547702 -0.0094999997 -0.036595002, + -0.045600802 0.0074999998 -0.038995001, + -0.051058501 -0.0094999997 -0.031512, + -0.049368501 0.0074999998 -0.034099001, + -0.054028001 -0.0094999997 -0.026095999, + -0.052613001 0.0074999998 -0.028842, + -0.055299699 0.0074999998 -0.02328, + -0.058146302 0.0074999998 -0.014473, + -0.05635 0.0074999998 -0.020375, + -0.0539563 0.0074999998 -0.026061, + -0.050990801 0.0074999998 -0.031470999, + -0.0474847 0.0074999998 -0.036547001, + -0.043475199 0.0074999998 -0.041235, + -0.0390049 0.0074999998 -0.045487002, + -0.0341211 0.0074999998 -0.049256999, + -0.028875699 0.0074999998 -0.052503999, + -0.0233241 0.0074999998 -0.055195, + -0.017525399 0.0074999998 -0.057300001, + -0.0145717 0.0074999998 -0.058203999, + -0.0115561 -0.0094999997 -0.058876999, + -0.0115408 0.0074999998 -0.058798999, + -0.0085099004 0.0074999998 -0.059393, + 0.048425902 -0.0094999997 -0.035425, + 0.044526801 -0.0094999997 -0.040215999, + 0.046537999 0.0074999998 -0.037870999, + 0.040155701 -0.0094999997 -0.044581998, + 0.042397399 0.0074999998 -0.042454999, + 0.035358898 -0.0094999997 -0.048473999, + 0.037807401 0.0074999998 -0.04659, + 0.0301874 -0.0094999997 -0.051853001, + 0.0328166 0.0074999998 -0.05023, + 0.024695801 -0.0094999997 -0.054682001, + 0.027478 0.0074999998 -0.053337999, + 0.018942401 -0.0094999997 -0.056931, + 0.021848099 0.0074999998 -0.055881001, + 0.0129883 -0.0094999997 -0.058577001, + 0.015986601 0.0074999998 -0.057831001, + 0.00689648 -0.0094999997 -0.059602, + 0.0099555897 0.0074999998 -0.059168, + 0.0038190801 0.0074999998 -0.059877999, + -0.0054339101 0.0074999998 -0.059673999, + 0.00688734 0.0074999998 -0.059523001, + 0.0129711 0.0074999998 -0.058499999, + 0.0189173 0.0074999998 -0.056855999, + 0.024662999 0.0074999998 -0.054609001, + 0.035312001 0.0074999998 -0.048409998, + 0.0401024 0.0074999998 -0.044523001, + 0.044467699 0.0074999998 -0.040162999, + 0.0483617 0.0074999998 -0.035378002, + 0.0501853 0.0074999998 -0.032885, + 0.051811699 -0.0094999997 -0.030258, + 0.051743001 0.0074999998 -0.030218, + 0.0533006 0.0074999998 -0.027550999, + 0.054648198 -0.0094999997 -0.024769999, + 0.054575801 0.0074999998 -0.024738001, + 0.055850901 0.0074999998 -0.021924, + 0.049368501 -0.0094999997 0.034099001, + 0.047547702 0.0074999998 0.036595002, + 0.045600802 -0.0094999997 0.038995001, + 0.052613001 -0.0094999997 0.028842, + 0.051058501 0.0074999998 0.031512, + 0.055299699 -0.0094999997 0.02328, + 0.054028001 0.0074999998 0.026095999, + 0.057400201 -0.0094999997 0.01747, + 0.0564248 0.0074999998 0.020401999, + 0.058892298 -0.0094999997 0.011476, + 0.058223501 0.0074999998 0.014492, + 0.059760101 -0.0094999997 0.0053599998, + 0.059404999 0.0074999998 0.0084290002, + 0.0599945 -0.0094999997 -0.00081300398, + 0.0599568 0.0074999998 0.0022760001, + 0.059592899 -0.0094999997 -0.006978, + 0.0598731 0.0074999998 -0.0039009999, + 0.0591546 0.0074999998 -0.010036, + 0.05683 0.0074999998 -0.018995, + 0.058481898 0.0074999998 -0.013051, + 0.0595139 0.0074999998 -0.00696899, + 0.059914902 0.0074999998 -0.000811996, + 0.059680901 0.0074999998 0.00535201, + 0.058814298 0.0074999998 0.011461, + 0.0573241 0.0074999998 0.017447, + 0.052543201 0.0074999998 0.028804, + 0.0493031 0.0074999998 0.034054, + 0.045540299 0.0074999998 0.038943, + 0.043532901 0.0074999998 0.04129, + 0.041349601 -0.0094999997 0.043476999, + 0.041294798 0.0074999998 0.043419, + 0.0390567 0.0074999998 0.045547001, + -0.021848099 -0.0094999997 0.055881001, + -0.015986601 -0.0094999997 0.057831001, + -0.018942401 0.0074999998 0.056931, + -0.0099555897 -0.0094999997 0.059168, + -0.0129883 0.0074999998 0.058577001, + -0.0038190801 -0.0094999997 0.059877999, + -0.00689648 0.0074999998 0.059602, + 0.0023579099 -0.0094999997 0.059953999, + -0.00073155703 0.0074999998 0.059996001, + 0.0085099004 -0.0094999997 0.059393, + 0.0054411199 0.0074999998 0.059753001, + 0.0145717 -0.0094999997 0.058203999, + 0.0115561 0.0074999998 0.058876999, + 0.020478999 -0.0094999997 0.056396998, + 0.0175486 0.0074999998 0.057376001, + 0.0261693 -0.0094999997 0.053991999, + 0.0233551 0.0074999998 0.055268001, + 0.028914001 0.0074999998 0.052574001, + 0.036611602 0.0074999998 0.047435001, + 0.026134601 0.0074999998 0.053920999, + 0.0204519 0.0074999998 0.056322001, + 0.0145524 0.0074999998 0.058125999, + 0.00235478 0.0074999998 0.059873998, + -0.00381402 0.0074999998 0.059799001, + -0.00994239 0.0074999998 0.05909, + -0.0159654 0.0074999998 0.057753999, + -0.0218191 0.0074999998 0.055806998, + -0.024695801 0.0074999998 0.054682001, + -0.027478 -0.0094999997 0.053337999, + -0.0274416 0.0074999998 0.053266998, + -0.0301874 0.0074999998 0.051853001, + -0.055850901 -0.0094999997 0.021924, + -0.0533006 -0.0094999997 0.027550999, + -0.054648198 0.0074999998 0.024769999, + -0.0501853 -0.0094999997 0.032885, + -0.051811699 0.0074999998 0.030258, + -0.046537999 -0.0094999997 0.037870999, + -0.048425902 0.0074999998 0.035425, + -0.042397399 -0.0094999997 0.042454999, + -0.044526801 0.0074999998 0.040215999, + -0.040155701 0.0074999998 0.044581998, + -0.0327731 0.0074999998 0.050163999, + -0.0377573 0.0074999998 0.046528, + -0.042341199 0.0074999998 0.042399, + -0.046476301 0.0074999998 0.037820999, + -0.0501188 0.0074999998 0.032841999, + -0.053229898 0.0074999998 0.027513999, + -0.055776902 0.0074999998 0.021895001, + -0.056905501 0.0074999998 0.01902, + -0.0578092 -0.0094999997 0.016065, + -0.0577325 0.0074999998 0.016044, + -0.0585596 0.0074999998 0.013068, + -0.0591546 -0.0094999997 0.010036, + -0.059076201 0.0074999998 0.010023, + -0.059592899 0.0074999998 0.006978, + -0.0598731 -0.0094999997 0.0039009999, + -0.0597937 0.0074999998 0.0038960001, + -0.0599945 0.0074999998 0.00081300398, + -0.059877299 0.0074999998 -0.0022729901, + 0.0315402 0.0074999998 0.050948001, + -0.061000001 -0.0067708199 -0.179205, + -0.061000001 -0.0065053399 -0.179471, + -0.057999998 -0.0067708199 -0.179205, + -0.057999998 -0.0065053399 -0.179471, + -0.057999998 -0.0069412701 -0.17887101, + -0.061000001 -0.0069412701 -0.17887101, + -0.061000001 -0.00617082 -0.17964099, + -0.057999998 -0.00617082 -0.17964099, + -0.057999998 -0.0070000002 -0.1785, + -0.061000001 -0.0070000002 -0.1785, + -0.057999998 -0.0069412701 -0.178129, + -0.061000001 -0.0069412701 -0.178129, + -0.057999998 -0.0067708199 -0.17779499, + -0.061000001 -0.0067708199 -0.17779499, + -0.057999998 -0.0065053399 -0.17752901, + -0.057999998 -0.00617082 -0.177359, + -0.057999998 -0.0057999999 -0.1797, + -0.057999998 -0.0057999999 -0.17730001, + -0.057999998 -0.003 -0.1797, + -0.057999998 -0.003 -0.17730001, + -0.061000001 -0.0065053399 -0.17752901, + -0.061000001 -0.00617082 -0.177359, + -0.061000001 -0.0057999999 -0.1797, + -0.061000001 -0.0057999999 -0.17730001, + -0.061000001 -0.003 -0.17730001, + -0.061000001 -0.003 -0.1797, + -0.061000001 -0.0098000001 -0.1785, + -0.061000001 -0.0096042296 -0.177264, + -0.057999998 -0.0098000001 -0.1785, + -0.057999998 -0.0096042296 -0.177264, + -0.057999998 -0.0096042296 -0.179736, + -0.061000001 -0.0096042296 -0.179736, + -0.057999998 -0.0153 -0.1855, + -0.061000001 -0.0153 -0.1855, + -0.057999998 0.0097000003 -0.1855, + -0.061000001 0.0097000003 -0.1855, + -0.057999998 0.0097000003 -0.1715, + -0.061000001 0.0097000003 -0.1715, + -0.057999998 -0.00050000002 -0.1797, + -0.061000001 -0.00050000002 -0.1797, + -0.057999998 0.0057000001 -0.1797, + -0.061000001 0.0057000001 -0.1797, + -0.061000001 -0.00050000002 -0.17730001, + -0.057999998 -0.00050000002 -0.17730001, + -0.061000001 0.0057000001 -0.17730001, + -0.057999998 0.0057000001 -0.17730001, + -0.057999998 0.0057000001 -0.1825, + -0.057999998 -0.0057999999 -0.1825, + -0.057999998 -0.0070360699 -0.18230399, + -0.057999998 -0.0081511401 -0.18173601, + -0.057999998 -0.0090360697 -0.180851, + -0.057999998 -0.0153 -0.1715, + -0.057999998 -0.0090360697 -0.176149, + -0.057999998 -0.0081511401 -0.175264, + -0.057999998 -0.0070360699 -0.174696, + -0.057999998 -0.0057999999 -0.1745, + -0.057999998 0.0057000001 -0.1745, + -0.061000001 0.0057000001 -0.1745, + -0.061000001 0.0057000001 -0.1825, + -0.061000001 -0.0057999999 -0.1825, + -0.061000001 -0.0070360699 -0.18230399, + -0.061000001 -0.0081511401 -0.18173601, + -0.061000001 -0.0090360697 -0.180851, + -0.061000001 -0.0153 -0.1715, + -0.061000001 -0.0090360697 -0.176149, + -0.061000001 -0.0081511401 -0.175264, + -0.061000001 -0.0070360699 -0.174696, + -0.061000001 -0.0057999999 -0.1745, + 0.061000001 -0.0098000001 -0.13249999, + 0.061000001 -0.0096042296 -0.133736, + 0.057999998 -0.0098000001 -0.13249999, + 0.057999998 -0.0096042296 -0.133736, + 0.057999998 -0.0096042296 -0.131264, + 0.061000001 -0.0096042296 -0.131264, + 0.057999998 -0.0153 -0.12549999, + 0.061000001 -0.0153 -0.12549999, + 0.057999998 0.0097000003 -0.12549999, + 0.061000001 0.0097000003 -0.12549999, + 0.057999998 0.0097000003 -0.13950001, + 0.061000001 0.0097000003 -0.13950001, + 0.057999998 -0.00050000002 -0.1313, + 0.061000001 -0.00050000002 -0.1313, + 0.057999998 0.0057000001 -0.1313, + 0.061000001 0.0057000001 -0.1313, + 0.061000001 -0.00050000002 -0.1337, + 0.057999998 -0.00050000002 -0.1337, + 0.061000001 0.0057000001 -0.1337, + 0.057999998 0.0057000001 -0.1337, + 0.057999998 0.0057000001 -0.1285, + 0.057999998 -0.0057999999 -0.1285, + 0.057999998 -0.0070360699 -0.12869599, + 0.057999998 -0.0081511401 -0.129264, + 0.057999998 -0.0090360697 -0.13014901, + 0.057999998 -0.0153 -0.13950001, + 0.057999998 -0.0090360697 -0.13485099, + 0.057999998 -0.0081511401 -0.135736, + 0.057999998 -0.0070360699 -0.13630401, + 0.057999998 -0.0057999999 -0.1365, + 0.057999998 0.0057000001 -0.1365, + 0.061000001 0.0057000001 -0.1365, + 0.061000001 0.0057000001 -0.1285, + 0.061000001 -0.0057999999 -0.1285, + 0.061000001 -0.0070360699 -0.12869599, + 0.061000001 -0.0081511401 -0.129264, + 0.061000001 -0.0090360697 -0.13014901, + 0.061000001 -0.0153 -0.13950001, + 0.061000001 -0.0090360697 -0.13485099, + 0.061000001 -0.0081511401 -0.135736, + 0.061000001 -0.0070360699 -0.13630401, + 0.061000001 -0.0057999999 -0.1365, + -0.057999998 -0.0153 -0.170167, + -0.061000001 -0.0153 -0.170167, + -0.057999998 0.0097000003 -0.170167, + -0.061000001 0.0097000003 -0.170167, + -0.061000001 -0.0153 -0.156167, + -0.057999998 -0.0153 -0.156167, + -0.061000001 -0.0033 -0.162467, + -0.057999998 -0.0033 -0.162467, + -0.061000001 -0.0098000001 -0.164967, + -0.057999998 -0.0098000001 -0.164967, + -0.057999998 -0.0033 -0.16196699, + -0.061000001 -0.0033 -0.16196699, + -0.057999998 -0.0098000001 -0.16196699, + -0.061000001 -0.0098000001 -0.16196699, + -0.061000001 -0.0098000001 -0.16796701, + -0.061000001 0.0057000001 -0.16796701, + -0.061000001 0.0057000001 -0.164967, + -0.061000001 -0.00205 -0.164986, + -0.061000001 -0.0098000001 -0.15916701, + -0.061000001 0.0097000003 -0.156167, + -0.061000001 0.0057000001 -0.15916701, + -0.061000001 0.0057000001 -0.16196699, + -0.061000001 -0.00079999998 -0.162467, + -0.061000001 -0.00079999998 -0.16196699, + -0.057999998 -0.0098000001 -0.15916701, + -0.057999998 0.0097000003 -0.156167, + -0.057999998 0.0057000001 -0.16196699, + -0.057999998 -0.00079999998 -0.16196699, + -0.057999998 -0.00079999998 -0.162467, + -0.057999998 0.0057000001 -0.164967, + -0.057999998 0.0057000001 -0.16796701, + -0.057999998 -0.0098000001 -0.16796701, + -0.057999998 -0.00205 -0.164986, + -0.057999998 0.0057000001 -0.15916701, + 0.057999998 -0.0153 -0.14083301, + 0.061000001 -0.0153 -0.14083301, + 0.057999998 0.0097000003 -0.14083301, + 0.061000001 0.0097000003 -0.14083301, + 0.061000001 -0.0153 -0.154833, + 0.057999998 -0.0153 -0.154833, + 0.061000001 -0.0033 -0.148533, + 0.057999998 -0.0033 -0.148533, + 0.061000001 -0.0098000001 -0.146033, + 0.057999998 -0.0098000001 -0.146033, + 0.057999998 -0.0033 -0.149033, + 0.061000001 -0.0033 -0.149033, + 0.057999998 -0.0098000001 -0.149033, + 0.061000001 -0.0098000001 -0.149033, + 0.061000001 -0.0098000001 -0.143033, + 0.061000001 0.0057000001 -0.143033, + 0.061000001 0.0057000001 -0.146033, + 0.061000001 -0.00205 -0.146014, + 0.061000001 -0.0098000001 -0.151833, + 0.061000001 0.0097000003 -0.154833, + 0.061000001 0.0057000001 -0.151833, + 0.061000001 0.0057000001 -0.149033, + 0.061000001 -0.00079999998 -0.148533, + 0.061000001 -0.00079999998 -0.149033, + 0.057999998 -0.0098000001 -0.151833, + 0.057999998 0.0097000003 -0.154833, + 0.057999998 0.0057000001 -0.149033, + 0.057999998 -0.00079999998 -0.149033, + 0.057999998 -0.00079999998 -0.148533, + 0.057999998 0.0057000001 -0.146033, + 0.057999998 0.0057000001 -0.143033, + 0.057999998 -0.0098000001 -0.143033, + 0.057999998 -0.00205 -0.146014, + 0.057999998 0.0057000001 -0.151833, + 0.061000001 0.0026708201 -0.163872, + 0.061000001 0.0024053401 -0.16413701, + 0.057999998 0.0026708201 -0.163872, + 0.057999998 0.0024053401 -0.16413701, + 0.057999998 0.0028412701 -0.16353799, + 0.061000001 0.0028412701 -0.16353799, + 0.057999998 0.0029 -0.163167, + 0.057999998 0.0028412701 -0.16279601, + 0.057999998 0.0026708201 -0.162461, + 0.057999998 0.0024053401 -0.162196, + 0.057999998 0.00207082 -0.162025, + 0.057999998 0.00207082 -0.164308, + 0.057999998 0.0017 -0.16196699, + 0.057999998 0.0017 -0.16436701, + 0.057999998 -0.0098000001 -0.16436701, + 0.057999998 -0.0098000001 -0.16196699, + 0.057999998 -0.0153 -0.170167, + 0.057999998 -0.0153 -0.156167, + 0.057999998 -0.0098000001 -0.15916701, + 0.057999998 0.0017 -0.15916701, + 0.057999998 0.0097000003 -0.156167, + 0.057999998 0.0029360701 -0.159362, + 0.057999998 0.00405114 -0.159931, + 0.057999998 0.0049360702 -0.160816, + 0.057999998 0.00550423 -0.16193099, + 0.057999998 0.0057000001 -0.163167, + 0.057999998 0.0097000003 -0.170167, + 0.057999998 0.00550423 -0.16440301, + 0.057999998 0.0049360702 -0.165518, + 0.057999998 0.00405114 -0.166403, + 0.057999998 0.0029360701 -0.166971, + 0.057999998 0.0017 -0.16716699, + 0.057999998 -0.0098000001 -0.16716699, + 0.061000001 0.00207082 -0.164308, + 0.061000001 0.0029 -0.163167, + 0.061000001 0.0028412701 -0.16279601, + 0.061000001 0.0026708201 -0.162461, + 0.061000001 0.0024053401 -0.162196, + 0.061000001 0.00207082 -0.162025, + 0.061000001 0.0017 -0.16436701, + 0.061000001 0.0017 -0.16196699, + 0.061000001 -0.0098000001 -0.16196699, + 0.061000001 -0.0098000001 -0.16436701, + 0.061000001 -0.0153 -0.156167, + 0.061000001 -0.0153 -0.170167, + 0.061000001 -0.0098000001 -0.16716699, + 0.061000001 0.0017 -0.16716699, + 0.061000001 0.0097000003 -0.170167, + 0.061000001 0.0029360701 -0.166971, + 0.061000001 0.00405114 -0.166403, + 0.061000001 0.0049360702 -0.165518, + 0.061000001 0.00550423 -0.16440301, + 0.061000001 0.0057000001 -0.163167, + 0.061000001 0.0097000003 -0.156167, + 0.061000001 0.00550423 -0.16193099, + 0.061000001 0.0049360702 -0.160816, + 0.061000001 0.00405114 -0.159931, + 0.061000001 0.0029360701 -0.159362, + 0.061000001 0.0017 -0.15916701, + 0.061000001 -0.0098000001 -0.15916701, + -0.061000001 0.0026708201 -0.147128, + -0.061000001 0.0024053401 -0.146863, + -0.057999998 0.0026708201 -0.147128, + -0.057999998 0.0024053401 -0.146863, + -0.057999998 0.0028412701 -0.147462, + -0.061000001 0.0028412701 -0.147462, + -0.057999998 0.0029 -0.147833, + -0.057999998 0.0028412701 -0.148204, + -0.057999998 0.0026708201 -0.14853901, + -0.057999998 0.0024053401 -0.14880399, + -0.057999998 0.00207082 -0.148975, + -0.057999998 0.00207082 -0.14669199, + -0.057999998 0.0017 -0.149033, + -0.057999998 0.0017 -0.146633, + -0.057999998 -0.0098000001 -0.146633, + -0.057999998 -0.0098000001 -0.149033, + -0.057999998 -0.0153 -0.14083301, + -0.057999998 -0.0153 -0.154833, + -0.057999998 -0.0098000001 -0.151833, + -0.057999998 0.0017 -0.151833, + -0.057999998 0.0097000003 -0.154833, + -0.057999998 0.0029360701 -0.151638, + -0.057999998 0.00405114 -0.151069, + -0.057999998 0.0049360702 -0.15018401, + -0.057999998 0.00550423 -0.149069, + -0.057999998 0.0057000001 -0.147833, + -0.057999998 0.0097000003 -0.14083301, + -0.057999998 0.00550423 -0.146597, + -0.057999998 0.0049360702 -0.145482, + -0.057999998 0.00405114 -0.14459699, + -0.057999998 0.0029360701 -0.14402901, + -0.057999998 0.0017 -0.143833, + -0.057999998 -0.0098000001 -0.143833, + -0.061000001 0.00207082 -0.14669199, + -0.061000001 0.0029 -0.147833, + -0.061000001 0.0028412701 -0.148204, + -0.061000001 0.0026708201 -0.14853901, + -0.061000001 0.0024053401 -0.14880399, + -0.061000001 0.00207082 -0.148975, + -0.061000001 0.0017 -0.146633, + -0.061000001 0.0017 -0.149033, + -0.061000001 -0.0098000001 -0.149033, + -0.061000001 -0.0098000001 -0.146633, + -0.061000001 -0.0153 -0.154833, + -0.061000001 -0.0153 -0.14083301, + -0.061000001 -0.0098000001 -0.143833, + -0.061000001 0.0017 -0.143833, + -0.061000001 0.0097000003 -0.14083301, + -0.061000001 0.0029360701 -0.14402901, + -0.061000001 0.00405114 -0.14459699, + -0.061000001 0.0049360702 -0.145482, + -0.061000001 0.00550423 -0.146597, + -0.061000001 0.0057000001 -0.147833, + -0.061000001 0.0097000003 -0.154833, + -0.061000001 0.00550423 -0.149069, + -0.061000001 0.0049360702 -0.15018401, + -0.061000001 0.00405114 -0.151069, + -0.061000001 0.0029360701 -0.151638, + -0.061000001 0.0017 -0.151833, + -0.061000001 -0.0098000001 -0.151833, + -0.057999998 -0.00079999998 -0.1318, + -0.061000001 -0.00079999998 -0.1318, + -0.057999998 0.0057000001 -0.13429999, + -0.061000001 0.0057000001 -0.13429999, + -0.061000001 -0.00079999998 -0.1313, + -0.057999998 -0.00079999998 -0.1313, + -0.061000001 0.0057000001 -0.1313, + -0.057999998 0.0057000001 -0.1313, + -0.057999998 -0.0033 -0.1313, + -0.057999998 -0.0098000001 -0.1313, + -0.057999998 -0.0033 -0.1318, + -0.057999998 -0.0098000001 -0.13429999, + -0.057999998 0.0097000003 -0.12549999, + -0.057999998 0.0057000001 -0.1373, + -0.057999998 0.0097000003 -0.13950001, + -0.057999998 -0.0098000001 -0.1373, + -0.057999998 -0.0153 -0.13950001, + -0.057999998 -0.00205 -0.13431901, + -0.057999998 -0.0153 -0.12549999, + -0.057999998 -0.0098000001 -0.1285, + -0.057999998 0.0057000001 -0.1285, + -0.061000001 0.0057000001 -0.1285, + -0.061000001 -0.0098000001 -0.1285, + -0.061000001 -0.0098000001 -0.1313, + -0.061000001 -0.0153 -0.12549999, + -0.061000001 0.0097000003 -0.12549999, + -0.061000001 -0.0153 -0.13950001, + -0.061000001 -0.0098000001 -0.13429999, + -0.061000001 -0.0033 -0.1318, + -0.061000001 -0.0098000001 -0.1373, + -0.061000001 0.0097000003 -0.13950001, + -0.061000001 0.0057000001 -0.1373, + -0.061000001 -0.00205 -0.13431901, + -0.061000001 -0.0033 -0.1313, + 0.057999998 -0.00079999998 -0.17919999, + 0.061000001 -0.00079999998 -0.17919999, + 0.057999998 0.0057000001 -0.1767, + 0.061000001 0.0057000001 -0.1767, + 0.061000001 -0.00079999998 -0.1797, + 0.057999998 -0.00079999998 -0.1797, + 0.061000001 0.0057000001 -0.1797, + 0.057999998 0.0057000001 -0.1797, + 0.057999998 -0.0033 -0.1797, + 0.057999998 -0.0098000001 -0.1797, + 0.057999998 -0.0033 -0.17919999, + 0.057999998 -0.0098000001 -0.1767, + 0.057999998 0.0097000003 -0.1855, + 0.057999998 0.0057000001 -0.1737, + 0.057999998 0.0097000003 -0.1715, + 0.057999998 -0.0098000001 -0.1737, + 0.057999998 -0.0153 -0.1715, + 0.057999998 -0.00205 -0.176681, + 0.057999998 -0.0153 -0.1855, + 0.057999998 -0.0098000001 -0.1825, + 0.057999998 0.0057000001 -0.1825, + 0.061000001 0.0057000001 -0.1825, + 0.061000001 -0.0098000001 -0.1825, + 0.061000001 -0.0098000001 -0.1797, + 0.061000001 -0.0153 -0.1855, + 0.061000001 0.0097000003 -0.1855, + 0.061000001 -0.0153 -0.1715, + 0.061000001 -0.0098000001 -0.1767, + 0.061000001 -0.0033 -0.17919999, + 0.061000001 -0.0098000001 -0.1737, + 0.061000001 0.0097000003 -0.1715, + 0.061000001 0.0057000001 -0.1737, + 0.061000001 -0.00205 -0.176681, + 0.061000001 -0.0033 -0.1797, + -0.0495787 -0.0094999997 -0.00647701, + -0.048541699 -0.0094999997 -0.011988, + -0.0495787 0.0074999998 -0.00647701, + -0.048541699 0.0074999998 -0.011988, + -0.0499922 0.0074999998 -0.00088499498, + -0.0499922 -0.0094999997 -0.00088499498, + -0.015675601 -0.0094999997 -0.047479, + -0.010261 -0.0094999997 -0.048935998, + -0.015675601 0.0074999998 -0.047479, + -0.010261 0.0074999998 -0.048935998, + -0.020893 0.0074999998 -0.045426, + -0.020893 -0.0094999997 -0.045426, + -0.025847699 0.0074999998 -0.042801, + -0.025847699 -0.0094999997 -0.042801, + -0.0304773 0.0074999998 -0.039638001, + -0.0304773 -0.0094999997 -0.039638001, + -0.046894301 0.0074999998 -0.017347001, + -0.046894301 -0.0094999997 -0.017347001, + -0.044657201 -0.0094999997 -0.022489, + -0.044657201 0.0074999998 -0.022489, + -0.041858502 -0.0094999997 -0.027347, + -0.041858502 0.0074999998 -0.027347, + -0.0385333 -0.0094999997 -0.031861998, + -0.0385333 0.0074999998 -0.031861998, + -0.034723699 -0.0094999997 -0.035976, + -0.034723699 0.0074999998 -0.035976, + -0.0047174101 -0.0094999997 -0.049777001, + -0.0047174101 0.0074999998 -0.049777001, + 0.039637499 -0.0094999997 -0.030477, + 0.042800698 -0.0094999997 -0.025847999, + 0.039637499 0.0074999998 -0.030477, + 0.042800698 0.0074999998 -0.025847999, + 0.0359759 0.0074999998 -0.034724001, + 0.0359759 -0.0094999997 -0.034724001, + 0.031861901 0.0074999998 -0.038532998, + 0.031861901 -0.0094999997 -0.038532998, + 0.0273472 0.0074999998 -0.041857999, + 0.0273472 -0.0094999997 -0.041857999, + 0.00088550098 0.0074999998 -0.049991999, + 0.00088550098 -0.0094999997 -0.049991999, + 0.0064772801 -0.0094999997 -0.049578998, + 0.0064772801 0.0074999998 -0.049578998, + 0.0119876 -0.0094999997 -0.048542, + 0.0119876 0.0074999998 -0.048542, + 0.0173472 -0.0094999997 -0.046893999, + 0.0173472 0.0074999998 -0.046893999, + 0.0224886 -0.0094999997 -0.044656999, + 0.0224886 0.0074999998 -0.044656999, + 0.030147299 0.0074999998 -0.051784001, + 0.045425601 -0.0094999997 -0.020893, + 0.045425601 0.0074999998 -0.020893, + 0.047479201 -0.0094999997 -0.015675999, + 0.047479201 0.0074999998 -0.015675999, + 0.0385333 0.0074999998 0.031861998, + 0.041858502 0.0074999998 0.027347, + 0.0385333 -0.0094999997 0.031861998, + 0.041858502 -0.0094999997 0.027347, + 0.034723699 -0.0094999997 0.035976, + 0.034723699 0.0074999998 0.035976, + 0.044657201 0.0074999998 0.022489, + 0.044657201 -0.0094999997 0.022489, + 0.046894301 0.0074999998 0.017347001, + 0.046894301 -0.0094999997 0.017347001, + 0.048541699 0.0074999998 0.011988, + 0.048541699 -0.0094999997 0.011988, + 0.048935801 0.0074999998 -0.010261, + 0.048935801 -0.0094999997 -0.010261, + 0.049777001 -0.0094999997 -0.0047169998, + 0.049777001 0.0074999998 -0.0047169998, + 0.0499922 -0.0094999997 0.00088499498, + 0.0499922 0.0074999998 0.00088499498, + 0.0495787 -0.0094999997 0.00647701, + 0.0495787 0.0074999998 0.00647701, + 0.0304773 -0.0094999997 0.039638001, + 0.0304773 0.0074999998 0.039638001, + -0.0173472 0.0074999998 0.046893999, + -0.0119876 0.0074999998 0.048542, + -0.0173472 -0.0094999997 0.046893999, + -0.0119876 -0.0094999997 0.048542, + -0.0224886 -0.0094999997 0.044656999, + -0.0224886 0.0074999998 0.044656999, + -0.0064772801 0.0074999998 0.049578998, + -0.0064772801 -0.0094999997 0.049578998, + -0.00088550098 0.0074999998 0.049991999, + -0.00088550098 -0.0094999997 0.049991999, + 0.0047174101 0.0074999998 0.049777001, + 0.0047174101 -0.0094999997 0.049777001, + 0.025847699 0.0074999998 0.042801, + 0.025847699 -0.0094999997 0.042801, + 0.020893 -0.0094999997 0.045426, + 0.020893 0.0074999998 0.045426, + 0.015675601 -0.0094999997 0.047479, + 0.015675601 0.0074999998 0.047479, + 0.010261 -0.0094999997 0.048935998, + 0.010261 0.0074999998 0.048935998, + -0.0273472 -0.0094999997 0.041857999, + -0.0273472 0.0074999998 0.041857999, + -0.031861901 0.0074999998 0.038532998, + -0.031861901 -0.0094999997 0.038532998, + -0.0359759 -0.0094999997 0.034724001, + -0.0359759 0.0074999998 0.034724001, + -0.039637499 -0.0094999997 0.030477, + -0.039637499 0.0074999998 0.030477, + -0.042800698 -0.0094999997 0.025847999, + -0.042800698 0.0074999998 0.025847999, + -0.045425601 -0.0094999997 0.020893, + -0.045425601 0.0074999998 0.020893, + -0.047479201 -0.0094999997 0.015675999, + -0.047479201 0.0074999998 0.015675999, + -0.048935801 -0.0094999997 0.010261, + -0.048935801 0.0074999998 0.010261, + -0.049777001 -0.0094999997 0.0047169998, + -0.049777001 0.0074999998 0.0047169998, + 0.061000001 -0.0067708199 -0.131795, + 0.061000001 -0.0065053399 -0.131529, + 0.057999998 -0.0067708199 -0.131795, + 0.057999998 -0.0065053399 -0.131529, + 0.057999998 -0.0069412701 -0.132129, + 0.061000001 -0.0069412701 -0.132129, + 0.061000001 -0.00617082 -0.131359, + 0.057999998 -0.00617082 -0.131359, + 0.057999998 -0.0070000002 -0.13249999, + 0.061000001 -0.0070000002 -0.13249999, + 0.057999998 -0.0069412701 -0.132871, + 0.061000001 -0.0069412701 -0.132871, + 0.057999998 -0.0067708199 -0.133205, + 0.061000001 -0.0067708199 -0.133205, + 0.057999998 -0.0065053399 -0.133471, + 0.057999998 -0.00617082 -0.133641, + 0.057999998 -0.0057999999 -0.1313, + 0.057999998 -0.0057999999 -0.1337, + 0.057999998 -0.003 -0.1313, + 0.057999998 -0.003 -0.1337, + 0.061000001 -0.0065053399 -0.133471, + 0.061000001 -0.00617082 -0.133641, + 0.061000001 -0.0057999999 -0.1313, + 0.061000001 -0.0057999999 -0.1337, + 0.061000001 -0.003 -0.1337, + 0.061000001 -0.003 -0.1313, + -0.059326202 0.0074999998 -0.0084180003, + 0.00073058699 0.0074999998 -0.059916001, + 0.0552264 0.0074999998 0.023249, + 0.0084986202 0.0074999998 0.059315 ] + + } + normal + Normal { + vector [ -0.58925998 -0.0046669901 0.80792999, + 0.56935769 -0.0046821479 0.82207656, + 0.96347547 -0.0046749925 -0.2677561, + -0.039335504 -0.0046794903 -0.99921513, + -0.95666325 -0.0046736212 -0.29115906, + -0.995992 -0.0046797101 -0.089320399, + -0.98152637 -0.004680742 -0.19127007, + -0.3412461 -0.0046917209 -0.93996227, + -0.43610814 -0.004649742 -0.89988232, + -0.52640885 -0.004647979 -0.85021883, + -0.61104894 -0.0047053196 -0.79157889, + -0.68913436 -0.0047154021 -0.72461838, + -0.76000601 -0.0047116498 -0.64989901, + -0.82280445 -0.0046865428 -0.56830537, + -0.87684131 -0.0046723117 -0.48075718, + -0.92166436 -0.0046816617 -0.38796014, + -0.97037935 0.0046764719 -0.24154109, + -0.97037113 0.0046764705 -0.24157403, + -0.94042212 0.0046778102 -0.33997703, + -0.94041234 0.0046778116 -0.34000412, + -0.90043414 0.0046929903 -0.43496707, + -0.90044624 0.0046929908 -0.4349421, + -0.85101914 0.0046554906 -0.52511406, + -0.85091615 0.0046554906 -0.52528107, + -0.79250181 0.0046589891 -0.6098519, + -0.79248619 0.004658991 -0.6098721, + -0.72538036 0.0046887323 -0.68833238, + -0.72568703 0.00468873 -0.68800902, + -0.65083116 0.0046625608 -0.7592082, + -0.65101856 0.0046625673 -0.75904751, + -0.56945884 0.0046605081 -0.8220067, + -0.56925315 0.0046605109 -0.82214916, + -0.482032 0.0046939901 -0.87614101, + -0.48178619 0.0046940017 -0.87627631, + -0.38943386 0.0046651079 -0.92104262, + -0.38916886 0.0046650982 -0.92115462, + -0.29236695 0.0046744091 -0.95629478, + -0.29265097 0.0046744095 -0.95620787, + -0.24297012 -0.0046982625 -0.9700225, + -0.19263296 0.0046757893 -0.98125976, + -0.19232407 0.0046757921 -0.98132038, + -0.14180692 -0.0046361671 -0.98988342, + 0.77559698 -0.0046876799 -0.63121098, + 0.70668596 -0.0046647796 -0.70751196, + 0.63005906 -0.0046887305 -0.77653313, + 0.54697496 -0.0046726195 -0.83713585, + 0.45795184 -0.0046669082 -0.88896471, + 0.36406696 -0.0047022495 -0.9313609, + 0.26645005 -0.0046984409 -0.96383727, + 0.16592601 -0.0046823607 -0.98612714, + 0.063778713 -0.0046566809 -0.99795324, + -0.090969875 0.0046669091 -0.99584275, + -0.09065108 0.0046669091 -0.99587178, + 0.11493599 0.0046785898 -0.99336189, + 0.11493205 0.0046785921 -0.99336237, + 0.21627605 0.0046407511 -0.97632122, + 0.21658705 0.0046407511 -0.97625226, + 0.31566808 0.004652061 -0.94885826, + 0.31566301 0.0046520601 -0.94885999, + 0.41178614 0.004708332 -0.91126829, + 0.41150308 0.0047083311 -0.91139627, + 0.58925706 0.0046669906 -0.80793214, + 0.58925998 0.0046669901 -0.80792999, + 0.66922557 0.0046772272 -0.74304456, + 0.66940343 0.0046772328 -0.7428844, + 0.74207819 0.0046698009 -0.67029721, + 0.74207675 0.0046697981 -0.67029876, + 0.80708998 0.00468022 -0.59040999, + 0.80710679 0.0046802191 -0.59038687, + 0.83641368 -0.004674118 -0.54807884, + 0.8634938 0.004675949 -0.50433791, + 0.8635096 0.0046759476 -0.50431079, + 0.88834757 -0.0046909577 -0.45914778, + 0.91077399 0.0046559102 -0.41287899, + 0.91084331 0.0046559218 -0.41272616, + 0.93083102 -0.0046777199 -0.36542001, + 0.79249388 -0.0046612998 0.60986197, + 0.85096788 -0.0046732896 0.52519697, + 0.90043998 -0.0046904599 0.434955, + 0.94041711 -0.0046804505 0.33999103, + 0.97037512 -0.0046795206 0.24155803, + 0.99007225 -0.004680091 0.14048202, + 0.99926889 -0.0046785395 0.037943695, + 0.99787414 -0.0046817507 -0.065003507, + 0.98589849 -0.0046716477 -0.16727893, + 0.94840366 0.0046782279 -0.31703088, + 0.94842637 0.0046782419 -0.31696311, + 0.97597575 0.0046786792 -0.21782896, + 0.97599089 0.0046786796 -0.21776097, + 0.99319679 0.004676979 -0.11635397, + 0.99320501 0.00467698 -0.116284, + 0.99989748 0.0046825325 -0.013531007, + 0.999897 0.0046825302 -0.0135662, + 0.99599075 0.0046822089 0.089333981, + 0.99599326 0.004682201 0.08930672, + 0.98153538 0.0046721818 0.19122407, + 0.98151726 0.0046721809 0.19131705, + 0.95665902 0.0046762801 0.29117301, + 0.95666754 0.0046762777 0.29114485, + 0.87683529 0.004674552 0.48076817, + 0.87684733 0.004674552 0.48074618, + 0.82285714 0.0046696104 0.56822908, + 0.8227514 0.0046696123 0.56838232, + 0.76007372 0.004692778 0.64981979, + 0.75993872 0.004692778 0.64997774, + 0.72553384 -0.0046482692 0.68817085, + 0.68922102 0.0046936902 0.724536, + 0.68904775 0.0046936981 0.72470075, + 0.65092492 -0.0046401494 0.75912786, + -0.31566301 -0.0046511102 0.94885999, + -0.2164319 -0.0046697278 0.97628653, + -0.11493205 -0.004677732 0.99336237, + -0.012305803 -0.004706291 0.99991322, + 0.090812892 -0.0046946397 0.99585688, + 0.19247609 -0.0047048521 0.98129046, + 0.29251096 -0.0046469397 0.95625091, + 0.38930085 -0.0046912483 0.92109865, + 0.48190689 -0.0047191591 0.87620974, + 0.61115789 0.004680519 0.79149485, + 0.61093831 0.0046805223 0.79166436, + 0.43611094 0.0046492796 0.89988089, + 0.43610615 0.004649282 0.89988327, + 0.3412461 0.004691551 0.93996227, + 0.34124491 0.0046915491 0.93996274, + 0.2428221 0.0047267117 0.97005934, + 0.24312206 0.0047267107 0.96998423, + 0.039175212 0.0047104307 0.99922127, + 0.039500777 0.004710427 0.99920839, + -0.063776225 0.0046553318 0.99795336, + -0.063786082 0.004655329 0.99795276, + -0.16576506 0.0046535917 0.98615438, + -0.16608199 0.0046535898 0.98610097, + -0.26644611 0.0046976623 0.96383846, + -0.26645496 0.0046976595 0.9638359, + -0.36392602 0.0046755206 0.93141609, + -0.36420798 0.0046755197 0.93130589, + -0.41164508 -0.0046793008 0.91133225, + -0.45808107 0.0046940404 0.88889813, + -0.45782301 0.0046940399 0.88903099, + -0.50311875 -0.0046936576 0.86420459, + -0.91080886 -0.0046711797 0.41280195, + -0.86350191 -0.0046787895 0.50432396, + -0.80709881 -0.0046828389 0.59039789, + -0.74207765 -0.0046695778 0.67029768, + -0.66931492 -0.0046989797 0.74296397, + -0.54686797 0.0046500997 0.83720589, + -0.54708207 0.0046501104 0.83706611, + -0.63005793 0.0046886597 0.7765339, + -0.63005906 0.0046886606 0.77653313, + -0.70669401 0.0046667601 0.70750397, + -0.70667899 0.0046667601 0.70751899, + -0.77554089 0.0046715294 0.63127995, + -0.77565318 0.0046715308 0.6311422, + -0.8363651 0.0046580406 0.54815304, + -0.83646214 0.0046580406 0.54800504, + -0.88835371 0.0046933382 0.45913583, + -0.88834125 0.004693341 0.45916012, + -0.93082559 0.0046748975 0.36543381, + -0.93083686 0.0046748994 0.36540496, + -0.94841498 -0.0046848198 0.31699699, + -0.96347123 0.0046777911 0.26777107, + -0.96347964 0.0046777884 0.26774091, + -0.97598326 -0.0046850308 0.21779504, + -0.98589575 0.0046746391 0.16729495, + -0.98590124 0.0046746409 0.16726305, + -0.9932009 -0.0046833795 0.11631899, + -0.99787474 0.004679739 0.064992487, + -0.99787337 0.0046797418 0.065014519, + -0.99989724 -0.0046793208 0.013548602, + -0.99926865 0.004679658 -0.037949886, + -0.99926913 0.0046796603 -0.037937503, + 0.52641082 0.0046491581 0.8502177, + 0 -0.70713478 -0.70707875, + 0 -0.89099157 -0.45401978, + 0 -0.45410311 -0.89094925, + 0 -0.98768765 -0.15643895, + 0 -0.98768765 0.15643895, + 0 -0.89099157 0.45401978, + 1 0 0, + 0 -0.70713478 0.70707875, + -1 0 0, + 0 -0.45410311 0.89094925, + 0 0 -1, + 0 -0.15635207 -0.98770148, + 0 -0.15635207 0.98770148, + 0 0 1, + 0 1 0, + 0 0.98768938 -0.15642805, + 0 0.98768938 0.15642805, + 0 -1 0, + 0 0.15645501 0.98768514, + 0 0.45395485 0.89102471, + 0 0.70713437 0.70707935, + 0 0.8909936 0.45401579, + 0 0.89099413 -0.45401505, + 0 0.70713437 -0.70707935, + 0 0.45395485 -0.89102471, + 0 0.15645501 -0.98768514, + 0 0.7071358 -0.7070778, + 0 0.8909936 -0.45401579, + 0 0.7071358 0.7070778, + 0 0.35897887 -0.93334562, + 0 -0.35897887 -0.93334562, + 0 0.35898304 0.93334413, + 0 -0.35898304 0.93334413, + 0 0.35897887 0.93334562, + 0 -0.35897887 0.93334562, + 0 0.35898218 -0.93334442, + 0 -0.35898218 -0.93334442, + 0 0.70713234 -0.70708138, + 0 0.45388988 -0.89105779, + 0 0.98768777 -0.15643795, + 0 0.98769426 0.15639704, + 0 0.89099139 0.4540202, + 0 0.70700026 0.70721322, + 0 0.45410711 0.89094722, + 0 0.15635207 -0.98770148, + 0 0.15634295 0.98770279, + 0 -0.9876895 -0.15642692, + 0 -0.45401978 0.89099157, + 0 -0.15645194 0.98768562, + 0 -0.70709437 0.70711935, + 0 -0.89101028 0.45398316, + 0 -0.8909936 -0.45401579, + 0 -0.7071358 -0.7070778, + 0 -0.45401779 -0.89099258, + 0 -0.15637806 -0.98769736, + 0 0.70713234 0.70708138, + 0 0.45388988 0.89105779, + 0 0.98768777 0.15643795, + 0 0.98769426 -0.15639704, + 0 0.89099139 -0.4540202, + 0 0.70700026 -0.70721322, + 0 0.45410711 -0.89094722, + 0 0.15635207 0.98770148, + 0 0.15634295 -0.98770279, + 0 -0.9876895 0.15642692, + 0 -0.98768753 -0.15643993, + 0 -0.45401978 -0.89099157, + 0 -0.15645501 -0.98768514, + 0 -0.70709437 -0.70711935, + 0 -0.89101028 -0.45398316, + 0 -0.8909936 0.45401579, + 0 -0.7071358 0.7070778, + 0 -0.45401779 0.89099258, + 0 -0.15637806 0.98769736, + 0.98275286 0 0.18492399, + 0.99727726 0 0.073743112, + 0.25984392 0 0.96565062, + 0.36616501 0 0.93054998, + 0.46815595 0 0.88364589, + 0.56412172 0 0.82569158, + 0.95585525 0 0.29383805, + 0.91697574 0 0.39894292, + 0.86649382 0 0.49918789, + 0.80519509 0 0.59301007, + 0.73373008 0 0.67944103, + 0.65307409 0 0.75729412, + 0.14998893 0 0.98868763, + -0.82564014 0 0.56419706, + -0.75737464 0 0.65298069, + -0.67938399 0 0.73378301, + -0.59301114 0 0.8051942, + 0.038346782 0 0.99926454, + -0.073659457 0 0.9972834, + -0.18494402 0 0.9827491, + -0.29390702 0 0.95583409, + -0.39896709 0 0.91696525, + -0.49918088 0 0.86649781, + 0.50311875 0.0046944376 -0.86420459, + -0.88366532 0 0.46811917, + -0.93050474 0 0.3662799, + -0.80519509 0 -0.59301007, + -0.73373008 0 -0.67944103, + -0.86649382 0 -0.49918789, + -0.91697574 0 -0.39894292, + -0.95585525 0 -0.29383805, + -0.96567327 0 0.25976005, + -0.98868376 0 0.15001497, + -0.99926299 0 0.0383863, + -0.99727726 0 -0.073743112, + -0.98275286 0 -0.18492399, + -0.65307409 0 -0.75729412, + 0.29390487 0 -0.95583463, + 0.39896709 0 -0.91696525, + 0.18494901 0 -0.98274809, + 0.073656768 0 -0.99728364, + -0.038343985 0 -0.99926466, + -0.56412172 0 -0.82569158, + -0.46815595 0 -0.88364589, + -0.36616501 0 -0.93054998, + -0.25984392 0 -0.96565062, + -0.14999107 0 -0.98868734, + 0.49918088 0 -0.86649781, + 0.59301114 0 -0.8051942, + 0.67938399 0 -0.73378301, + 0.75737464 0 -0.65298069, + 0.82564014 0 -0.56419706, + 0.88366532 0 -0.46811917, + 0.93050474 0 -0.3662799, + 0.96567327 0 -0.25976005, + 0.98868376 0 -0.15001497, + 0.99926299 0 -0.0383863, + 0 -0.70713735 0.70707637, + 0 -0.45409116 0.89095527, + 0 -0.70713735 -0.70707637, + 0 -0.45409116 -0.89095527, + -0.99007237 0.0046802019 -0.14048104, + 0.012300905 0.0047062817 -0.99991333, + 0.92166436 0.0046817618 0.38796014, + 0.14180104 0.0046360819 0.98988438 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 9, 10, 11, -1, + 12, 13, 14, -1, 15, 16, 17, -1, + 17, 18, 13, -1, 19, 20, 21, -1, + 22, 23, 19, -1, 24, 25, 22, -1, + 24, 26, 27, -1, 28, 29, 26, -1, + 28, 30, 31, -1, 30, 32, 33, -1, + 32, 34, 35, -1, 34, 12, 36, -1, + 37, 13, 18, -1, 37, 14, 13, -1, + 38, 12, 14, -1, 38, 36, 12, -1, + 39, 34, 36, -1, 39, 35, 34, -1, + 40, 32, 35, -1, 40, 33, 32, -1, + 41, 30, 33, -1, 41, 31, 30, -1, + 42, 28, 31, -1, 42, 29, 28, -1, + 43, 26, 29, -1, 43, 27, 26, -1, + 44, 24, 27, -1, 44, 25, 24, -1, + 45, 22, 25, -1, 45, 23, 22, -1, + 46, 19, 23, -1, 46, 20, 19, -1, + 47, 21, 20, -1, 47, 48, 21, -1, + 49, 21, 48, -1, 50, 49, 48, -1, + 50, 51, 49, -1, 49, 51, 9, -1, + 52, 53, 54, -1, 53, 55, 56, -1, + 55, 57, 58, -1, 59, 60, 57, -1, + 59, 61, 62, -1, 63, 64, 61, -1, + 65, 66, 63, -1, 67, 68, 65, -1, + 11, 69, 67, -1, 70, 9, 51, -1, + 70, 10, 9, -1, 71, 67, 69, -1, + 71, 68, 67, -1, 72, 65, 68, -1, + 72, 66, 65, -1, 73, 63, 66, -1, + 73, 64, 63, -1, 74, 61, 64, -1, + 74, 62, 61, -1, 75, 57, 60, -1, + 75, 58, 57, -1, 76, 55, 58, -1, + 76, 56, 55, -1, 77, 53, 56, -1, + 77, 54, 53, -1, 78, 52, 54, -1, + 78, 79, 52, -1, 80, 52, 79, -1, + 81, 80, 79, -1, 81, 82, 80, -1, + 83, 80, 82, -1, 84, 83, 82, -1, + 84, 85, 83, -1, 83, 85, 7, -1, + 86, 87, 88, -1, 89, 90, 86, -1, + 91, 92, 89, -1, 93, 94, 91, -1, + 95, 96, 93, -1, 95, 97, 98, -1, + 99, 100, 97, -1, 101, 102, 99, -1, + 6, 103, 101, -1, 104, 7, 85, -1, + 104, 8, 7, -1, 105, 6, 8, -1, + 105, 103, 6, -1, 106, 101, 103, -1, + 106, 102, 101, -1, 107, 99, 102, -1, + 107, 100, 99, -1, 108, 97, 100, -1, + 108, 98, 97, -1, 109, 95, 98, -1, + 109, 96, 95, -1, 110, 93, 96, -1, + 110, 94, 93, -1, 111, 89, 92, -1, + 111, 90, 89, -1, 112, 86, 90, -1, + 112, 87, 86, -1, 113, 88, 87, -1, + 113, 114, 88, -1, 115, 88, 114, -1, + 116, 115, 114, -1, 116, 117, 115, -1, + 4, 115, 117, -1, 118, 119, 120, -1, + 119, 121, 122, -1, 123, 124, 121, -1, + 125, 126, 123, -1, 127, 128, 125, -1, + 129, 130, 127, -1, 131, 132, 129, -1, + 133, 134, 131, -1, 133, 3, 135, -1, + 136, 4, 117, -1, 136, 5, 4, -1, + 137, 133, 135, -1, 137, 134, 133, -1, + 138, 131, 134, -1, 138, 132, 131, -1, + 139, 129, 132, -1, 139, 130, 129, -1, + 140, 125, 128, -1, 140, 126, 125, -1, + 141, 123, 126, -1, 141, 124, 123, -1, + 142, 121, 124, -1, 142, 122, 121, -1, + 143, 119, 122, -1, 143, 120, 119, -1, + 144, 118, 120, -1, 144, 145, 118, -1, + 146, 118, 145, -1, 147, 146, 145, -1, + 147, 148, 146, -1, 1, 146, 148, -1, + 149, 150, 151, -1, 150, 152, 153, -1, + 154, 155, 152, -1, 154, 156, 157, -1, + 0, 158, 156, -1, 159, 1, 148, -1, + 159, 2, 1, -1, 160, 0, 2, -1, + 160, 158, 0, -1, 161, 156, 158, -1, + 161, 157, 156, -1, 162, 154, 157, -1, + 162, 155, 154, -1, 163, 152, 155, -1, + 163, 153, 152, -1, 164, 150, 153, -1, + 164, 151, 150, -1, 165, 149, 151, -1, + 165, 166, 149, -1, 149, 166, 167, -1, + 168, 169, 167, -1, 168, 167, 166, -1, + 167, 169, 170, -1, 171, 172, 170, -1, + 171, 170, 169, -1, 170, 172, 173, -1, + 174, 175, 173, -1, 174, 173, 172, -1, + 173, 175, 15, -1, 176, 15, 175, -1, + 176, 16, 15, -1, 5, 177, 3, -1, + 3, 177, 135, -1, 178, 179, 180, -1, + 180, 179, 181, -1, 180, 182, 178, -1, + 178, 182, 183, -1, 179, 184, 181, -1, + 181, 184, 185, -1, 182, 186, 183, -1, + 183, 186, 187, -1, 186, 188, 187, -1, + 187, 188, 189, -1, 188, 190, 189, -1, + 189, 190, 191, -1, 190, 188, 192, -1, + 192, 188, 186, -1, 192, 186, 182, -1, + 182, 180, 192, -1, 192, 180, 181, -1, + 192, 181, 185, -1, 192, 185, 193, -1, + 193, 185, 194, -1, 193, 194, 195, -1, + 195, 194, 196, -1, 195, 196, 197, -1, + 190, 192, 191, -1, 191, 192, 198, -1, + 191, 198, 189, -1, 189, 198, 187, -1, + 187, 198, 183, -1, 183, 198, 178, -1, + 178, 198, 179, -1, 179, 198, 184, -1, + 198, 199, 184, -1, 184, 199, 200, -1, + 199, 201, 200, -1, 200, 201, 202, -1, + 200, 202, 203, -1, 192, 193, 198, -1, + 198, 193, 199, -1, 194, 200, 196, -1, + 196, 200, 203, -1, 194, 185, 200, -1, + 200, 185, 184, -1, 193, 195, 199, -1, + 199, 195, 201, -1, 201, 195, 202, -1, + 202, 195, 197, -1, 196, 203, 197, -1, + 197, 203, 202, -1, 204, 205, 206, -1, + 206, 205, 207, -1, 206, 208, 204, -1, + 204, 208, 209, -1, 210, 211, 212, -1, + 212, 211, 213, -1, 212, 213, 214, -1, + 214, 213, 215, -1, 216, 217, 218, -1, + 218, 217, 219, -1, 217, 216, 220, -1, + 220, 216, 221, -1, 220, 222, 217, -1, + 217, 222, 219, -1, 220, 221, 222, -1, + 222, 221, 223, -1, 221, 216, 223, -1, + 223, 216, 218, -1, 223, 218, 214, -1, + 214, 218, 212, -1, 218, 224, 212, -1, + 212, 224, 225, -1, 212, 225, 210, -1, + 210, 225, 226, -1, 210, 226, 227, -1, + 227, 228, 210, -1, 210, 228, 208, -1, + 210, 208, 206, -1, 210, 206, 229, -1, + 229, 206, 207, -1, 229, 207, 230, -1, + 230, 231, 229, -1, 229, 231, 232, -1, + 229, 232, 233, -1, 229, 233, 214, -1, + 214, 233, 234, -1, 214, 234, 223, -1, + 222, 223, 235, -1, 235, 223, 234, -1, + 218, 219, 224, -1, 224, 219, 236, -1, + 224, 236, 225, -1, 225, 236, 237, -1, + 237, 238, 225, -1, 225, 238, 226, -1, + 238, 239, 226, -1, 226, 239, 227, -1, + 239, 240, 227, -1, 227, 240, 228, -1, + 240, 209, 228, -1, 228, 209, 208, -1, + 211, 210, 241, -1, 241, 210, 229, -1, + 214, 215, 229, -1, 229, 215, 241, -1, + 205, 242, 207, -1, 207, 242, 230, -1, + 242, 243, 230, -1, 230, 243, 231, -1, + 243, 244, 231, -1, 231, 244, 232, -1, + 244, 245, 232, -1, 232, 245, 233, -1, + 233, 245, 234, -1, 234, 245, 235, -1, + 246, 247, 248, -1, 248, 247, 249, -1, + 248, 250, 246, -1, 246, 250, 251, -1, + 252, 253, 254, -1, 254, 253, 255, -1, + 254, 255, 256, -1, 256, 255, 257, -1, + 258, 259, 260, -1, 260, 259, 261, -1, + 259, 258, 262, -1, 262, 258, 263, -1, + 262, 264, 259, -1, 259, 264, 261, -1, + 262, 263, 264, -1, 264, 263, 265, -1, + 263, 258, 265, -1, 265, 258, 260, -1, + 265, 260, 256, -1, 256, 260, 254, -1, + 260, 266, 254, -1, 254, 266, 267, -1, + 254, 267, 252, -1, 252, 267, 268, -1, + 252, 268, 269, -1, 269, 270, 252, -1, + 252, 270, 250, -1, 252, 250, 248, -1, + 252, 248, 271, -1, 271, 248, 249, -1, + 271, 249, 272, -1, 272, 273, 271, -1, + 271, 273, 274, -1, 271, 274, 275, -1, + 271, 275, 256, -1, 256, 275, 276, -1, + 256, 276, 265, -1, 264, 265, 277, -1, + 277, 265, 276, -1, 260, 261, 266, -1, + 266, 261, 278, -1, 266, 278, 267, -1, + 267, 278, 279, -1, 279, 280, 267, -1, + 267, 280, 268, -1, 280, 281, 268, -1, + 268, 281, 269, -1, 281, 282, 269, -1, + 269, 282, 270, -1, 282, 251, 270, -1, + 270, 251, 250, -1, 253, 252, 283, -1, + 283, 252, 271, -1, 256, 257, 271, -1, + 271, 257, 283, -1, 247, 284, 249, -1, + 249, 284, 272, -1, 284, 285, 272, -1, + 272, 285, 273, -1, 285, 286, 273, -1, + 273, 286, 274, -1, 286, 287, 274, -1, + 274, 287, 275, -1, 275, 287, 276, -1, + 276, 287, 277, -1, 288, 289, 290, -1, + 290, 289, 291, -1, 289, 288, 292, -1, + 292, 288, 293, -1, 294, 295, 296, -1, + 296, 295, 297, -1, 295, 294, 298, -1, + 298, 294, 299, -1, 298, 299, 300, -1, + 300, 299, 301, -1, 299, 294, 301, -1, + 301, 294, 296, -1, 301, 296, 289, -1, + 289, 296, 302, -1, 289, 302, 291, -1, + 291, 302, 303, -1, 291, 303, 304, -1, + 302, 305, 303, -1, 289, 292, 301, -1, + 301, 292, 306, -1, 292, 307, 306, -1, + 306, 307, 308, -1, 308, 307, 309, -1, + 309, 307, 291, -1, 309, 291, 304, -1, + 304, 310, 309, -1, 309, 310, 311, -1, + 300, 301, 312, -1, 312, 301, 306, -1, + 313, 307, 293, -1, 293, 307, 292, -1, + 307, 313, 291, -1, 291, 313, 290, -1, + 314, 309, 315, -1, 315, 309, 311, -1, + 298, 300, 295, -1, 295, 300, 297, -1, + 315, 316, 314, -1, 314, 316, 317, -1, + 314, 317, 313, -1, 313, 317, 318, -1, + 313, 318, 290, -1, 290, 318, 319, -1, + 290, 319, 288, -1, 288, 319, 297, -1, + 288, 297, 300, -1, 318, 320, 319, -1, + 288, 300, 293, -1, 293, 300, 312, -1, + 293, 312, 313, -1, 313, 312, 321, -1, + 313, 321, 314, -1, 315, 311, 316, -1, + 316, 311, 310, -1, 316, 310, 317, -1, + 317, 310, 304, -1, 317, 304, 318, -1, + 318, 304, 303, -1, 318, 303, 320, -1, + 320, 303, 305, -1, 320, 305, 319, -1, + 319, 305, 302, -1, 319, 302, 297, -1, + 297, 302, 296, -1, 312, 306, 321, -1, + 321, 306, 308, -1, 321, 308, 314, -1, + 314, 308, 309, -1, 322, 323, 324, -1, + 324, 323, 325, -1, 323, 322, 326, -1, + 326, 322, 327, -1, 328, 329, 330, -1, + 330, 329, 331, -1, 329, 328, 332, -1, + 332, 328, 333, -1, 332, 333, 334, -1, + 334, 333, 335, -1, 333, 328, 335, -1, + 335, 328, 330, -1, 335, 330, 323, -1, + 323, 330, 336, -1, 323, 336, 325, -1, + 325, 336, 337, -1, 325, 337, 338, -1, + 336, 339, 337, -1, 323, 326, 335, -1, + 335, 326, 340, -1, 326, 341, 340, -1, + 340, 341, 342, -1, 342, 341, 343, -1, + 343, 341, 325, -1, 343, 325, 338, -1, + 338, 344, 343, -1, 343, 344, 345, -1, + 334, 335, 346, -1, 346, 335, 340, -1, + 347, 341, 327, -1, 327, 341, 326, -1, + 341, 347, 325, -1, 325, 347, 324, -1, + 348, 343, 349, -1, 349, 343, 345, -1, + 332, 334, 329, -1, 329, 334, 331, -1, + 349, 350, 348, -1, 348, 350, 351, -1, + 348, 351, 347, -1, 347, 351, 352, -1, + 347, 352, 324, -1, 324, 352, 353, -1, + 324, 353, 322, -1, 322, 353, 331, -1, + 322, 331, 334, -1, 352, 354, 353, -1, + 322, 334, 327, -1, 327, 334, 346, -1, + 327, 346, 347, -1, 347, 346, 355, -1, + 347, 355, 348, -1, 349, 345, 350, -1, + 350, 345, 344, -1, 350, 344, 351, -1, + 351, 344, 338, -1, 351, 338, 352, -1, + 352, 338, 337, -1, 352, 337, 354, -1, + 354, 337, 339, -1, 354, 339, 353, -1, + 353, 339, 336, -1, 353, 336, 331, -1, + 331, 336, 330, -1, 346, 340, 355, -1, + 355, 340, 342, -1, 355, 342, 348, -1, + 348, 342, 343, -1, 356, 357, 358, -1, + 358, 357, 359, -1, 358, 360, 356, -1, + 356, 360, 361, -1, 358, 359, 360, -1, + 360, 359, 362, -1, 362, 359, 363, -1, + 363, 359, 364, -1, 364, 359, 365, -1, + 365, 359, 366, -1, 359, 367, 366, -1, + 366, 367, 368, -1, 367, 369, 368, -1, + 368, 369, 370, -1, 368, 370, 371, -1, + 371, 370, 372, -1, 371, 372, 373, -1, + 371, 373, 374, -1, 374, 373, 375, -1, + 373, 376, 375, -1, 375, 376, 377, -1, + 377, 376, 378, -1, 378, 376, 379, -1, + 379, 376, 380, -1, 380, 376, 381, -1, + 376, 382, 381, -1, 381, 382, 383, -1, + 383, 382, 384, -1, 384, 382, 385, -1, + 385, 382, 386, -1, 386, 382, 387, -1, + 382, 372, 387, -1, 387, 372, 388, -1, + 388, 372, 370, -1, 357, 389, 359, -1, + 359, 389, 367, -1, 360, 362, 361, -1, + 361, 362, 390, -1, 362, 363, 390, -1, + 390, 363, 391, -1, 363, 364, 391, -1, + 391, 364, 392, -1, 364, 365, 392, -1, + 392, 365, 393, -1, 392, 393, 391, -1, + 391, 393, 390, -1, 390, 393, 361, -1, + 361, 393, 356, -1, 356, 393, 357, -1, + 357, 393, 389, -1, 393, 394, 389, -1, + 389, 394, 395, -1, 394, 396, 395, -1, + 395, 396, 397, -1, 395, 397, 398, -1, + 398, 397, 399, -1, 398, 399, 400, -1, + 398, 400, 401, -1, 401, 400, 402, -1, + 400, 403, 402, -1, 402, 403, 404, -1, + 404, 403, 405, -1, 405, 403, 406, -1, + 406, 403, 407, -1, 407, 403, 408, -1, + 403, 409, 408, -1, 408, 409, 410, -1, + 410, 409, 411, -1, 411, 409, 412, -1, + 412, 409, 413, -1, 413, 409, 414, -1, + 409, 399, 414, -1, 414, 399, 415, -1, + 415, 399, 397, -1, 365, 366, 393, -1, + 393, 366, 394, -1, 369, 395, 370, -1, + 370, 395, 398, -1, 369, 367, 395, -1, + 395, 367, 389, -1, 366, 368, 394, -1, + 394, 368, 396, -1, 396, 368, 397, -1, + 397, 368, 371, -1, 408, 410, 381, -1, + 381, 410, 380, -1, 381, 383, 408, -1, + 408, 383, 407, -1, 382, 403, 372, -1, + 372, 403, 400, -1, 404, 405, 386, -1, + 386, 405, 385, -1, 386, 387, 404, -1, + 404, 387, 402, -1, 405, 406, 385, -1, + 385, 406, 384, -1, 406, 407, 384, -1, + 384, 407, 383, -1, 403, 382, 409, -1, + 409, 382, 376, -1, 409, 376, 399, -1, + 399, 376, 373, -1, 410, 411, 380, -1, + 380, 411, 379, -1, 411, 412, 379, -1, + 379, 412, 378, -1, 412, 413, 378, -1, + 378, 413, 377, -1, 413, 414, 377, -1, + 377, 414, 375, -1, 399, 373, 400, -1, + 400, 373, 372, -1, 370, 398, 388, -1, + 388, 398, 401, -1, 388, 401, 387, -1, + 387, 401, 402, -1, 397, 371, 415, -1, + 415, 371, 374, -1, 415, 374, 414, -1, + 414, 374, 375, -1, 416, 417, 418, -1, + 418, 417, 419, -1, 418, 420, 416, -1, + 416, 420, 421, -1, 418, 419, 420, -1, + 420, 419, 422, -1, 422, 419, 423, -1, + 423, 419, 424, -1, 424, 419, 425, -1, + 425, 419, 426, -1, 419, 427, 426, -1, + 426, 427, 428, -1, 427, 429, 428, -1, + 428, 429, 430, -1, 428, 430, 431, -1, + 431, 430, 432, -1, 431, 432, 433, -1, + 431, 433, 434, -1, 434, 433, 435, -1, + 433, 436, 435, -1, 435, 436, 437, -1, + 437, 436, 438, -1, 438, 436, 439, -1, + 439, 436, 440, -1, 440, 436, 441, -1, + 436, 442, 441, -1, 441, 442, 443, -1, + 443, 442, 444, -1, 444, 442, 445, -1, + 445, 442, 446, -1, 446, 442, 447, -1, + 442, 432, 447, -1, 447, 432, 448, -1, + 448, 432, 430, -1, 417, 449, 419, -1, + 419, 449, 427, -1, 420, 422, 421, -1, + 421, 422, 450, -1, 422, 423, 450, -1, + 450, 423, 451, -1, 423, 424, 451, -1, + 451, 424, 452, -1, 424, 425, 452, -1, + 452, 425, 453, -1, 452, 453, 451, -1, + 451, 453, 450, -1, 450, 453, 421, -1, + 421, 453, 416, -1, 416, 453, 417, -1, + 417, 453, 449, -1, 453, 454, 449, -1, + 449, 454, 455, -1, 454, 456, 455, -1, + 455, 456, 457, -1, 455, 457, 458, -1, + 458, 457, 459, -1, 458, 459, 460, -1, + 458, 460, 461, -1, 461, 460, 462, -1, + 460, 463, 462, -1, 462, 463, 464, -1, + 464, 463, 465, -1, 465, 463, 466, -1, + 466, 463, 467, -1, 467, 463, 468, -1, + 463, 469, 468, -1, 468, 469, 470, -1, + 470, 469, 471, -1, 471, 469, 472, -1, + 472, 469, 473, -1, 473, 469, 474, -1, + 469, 459, 474, -1, 474, 459, 475, -1, + 475, 459, 457, -1, 425, 426, 453, -1, + 453, 426, 454, -1, 429, 455, 430, -1, + 430, 455, 458, -1, 429, 427, 455, -1, + 455, 427, 449, -1, 426, 428, 454, -1, + 454, 428, 456, -1, 456, 428, 457, -1, + 457, 428, 431, -1, 468, 470, 441, -1, + 441, 470, 440, -1, 441, 443, 468, -1, + 468, 443, 467, -1, 442, 463, 432, -1, + 432, 463, 460, -1, 464, 465, 446, -1, + 446, 465, 445, -1, 446, 447, 464, -1, + 464, 447, 462, -1, 465, 466, 445, -1, + 445, 466, 444, -1, 466, 467, 444, -1, + 444, 467, 443, -1, 463, 442, 469, -1, + 469, 442, 436, -1, 469, 436, 459, -1, + 459, 436, 433, -1, 470, 471, 440, -1, + 440, 471, 439, -1, 471, 472, 439, -1, + 439, 472, 438, -1, 472, 473, 438, -1, + 438, 473, 437, -1, 473, 474, 437, -1, + 437, 474, 435, -1, 459, 433, 460, -1, + 460, 433, 432, -1, 430, 458, 448, -1, + 448, 458, 461, -1, 448, 461, 447, -1, + 447, 461, 462, -1, 457, 431, 475, -1, + 475, 431, 434, -1, 475, 434, 474, -1, + 474, 434, 435, -1, 476, 477, 478, -1, + 478, 477, 479, -1, 477, 476, 480, -1, + 480, 476, 481, -1, 480, 481, 482, -1, + 482, 481, 483, -1, 484, 485, 486, -1, + 486, 485, 487, -1, 481, 476, 483, -1, + 483, 476, 478, -1, 483, 478, 488, -1, + 488, 478, 489, -1, 488, 489, 490, -1, + 490, 489, 491, -1, 490, 491, 492, -1, + 492, 491, 487, -1, 492, 487, 485, -1, + 489, 493, 491, -1, 492, 485, 494, -1, + 494, 485, 495, -1, 494, 495, 488, -1, + 488, 495, 496, -1, 488, 496, 483, -1, + 482, 483, 497, -1, 497, 483, 496, -1, + 497, 496, 498, -1, 498, 496, 495, -1, + 498, 495, 499, -1, 499, 495, 485, -1, + 500, 494, 501, -1, 501, 494, 488, -1, + 494, 500, 492, -1, 492, 500, 502, -1, + 487, 503, 486, -1, 486, 503, 504, -1, + 503, 487, 505, -1, 505, 487, 491, -1, + 492, 502, 490, -1, 490, 502, 506, -1, + 490, 506, 488, -1, 488, 506, 501, -1, + 507, 489, 479, -1, 479, 489, 478, -1, + 489, 507, 493, -1, 493, 507, 508, -1, + 493, 508, 491, -1, 491, 508, 505, -1, + 480, 482, 477, -1, 477, 482, 479, -1, + 508, 507, 505, -1, 505, 507, 506, -1, + 505, 506, 502, -1, 505, 502, 503, -1, + 503, 502, 499, -1, 503, 499, 504, -1, + 504, 499, 509, -1, 502, 500, 499, -1, + 499, 500, 498, -1, 500, 501, 498, -1, + 498, 501, 497, -1, 497, 501, 482, -1, + 482, 501, 506, -1, 482, 506, 479, -1, + 479, 506, 507, -1, 499, 485, 509, -1, + 509, 485, 484, -1, 509, 484, 504, -1, + 504, 484, 486, -1, 510, 511, 512, -1, + 512, 511, 513, -1, 511, 510, 514, -1, + 514, 510, 515, -1, 514, 515, 516, -1, + 516, 515, 517, -1, 518, 519, 520, -1, + 520, 519, 521, -1, 515, 510, 517, -1, + 517, 510, 512, -1, 517, 512, 522, -1, + 522, 512, 523, -1, 522, 523, 524, -1, + 524, 523, 525, -1, 524, 525, 526, -1, + 526, 525, 521, -1, 526, 521, 519, -1, + 523, 527, 525, -1, 526, 519, 528, -1, + 528, 519, 529, -1, 528, 529, 522, -1, + 522, 529, 530, -1, 522, 530, 517, -1, + 516, 517, 531, -1, 531, 517, 530, -1, + 531, 530, 532, -1, 532, 530, 529, -1, + 532, 529, 533, -1, 533, 529, 519, -1, + 534, 528, 535, -1, 535, 528, 522, -1, + 528, 534, 526, -1, 526, 534, 536, -1, + 521, 537, 520, -1, 520, 537, 538, -1, + 537, 521, 539, -1, 539, 521, 525, -1, + 526, 536, 524, -1, 524, 536, 540, -1, + 524, 540, 522, -1, 522, 540, 535, -1, + 541, 523, 513, -1, 513, 523, 512, -1, + 523, 541, 527, -1, 527, 541, 542, -1, + 527, 542, 525, -1, 525, 542, 539, -1, + 514, 516, 511, -1, 511, 516, 513, -1, + 542, 541, 539, -1, 539, 541, 540, -1, + 539, 540, 536, -1, 539, 536, 537, -1, + 537, 536, 533, -1, 537, 533, 538, -1, + 538, 533, 543, -1, 536, 534, 533, -1, + 533, 534, 532, -1, 534, 535, 532, -1, + 532, 535, 531, -1, 531, 535, 516, -1, + 516, 535, 540, -1, 516, 540, 513, -1, + 513, 540, 541, -1, 533, 519, 543, -1, + 543, 519, 518, -1, 543, 518, 538, -1, + 538, 518, 520, -1, 544, 545, 546, -1, + 546, 545, 547, -1, 546, 548, 544, -1, + 544, 548, 549, -1, 550, 551, 552, -1, + 552, 551, 553, -1, 552, 554, 550, -1, + 550, 554, 555, -1, 554, 556, 555, -1, + 555, 556, 557, -1, 556, 558, 557, -1, + 557, 558, 559, -1, 560, 547, 561, -1, + 561, 547, 545, -1, 561, 562, 560, -1, + 560, 562, 563, -1, 562, 564, 563, -1, + 563, 564, 565, -1, 564, 566, 565, -1, + 565, 566, 567, -1, 566, 568, 567, -1, + 567, 568, 569, -1, 568, 559, 569, -1, + 569, 559, 558, -1, 551, 570, 553, -1, + 553, 570, 571, -1, 572, 573, 574, -1, + 574, 573, 575, -1, 574, 576, 572, -1, + 572, 576, 577, -1, 576, 578, 577, -1, + 577, 578, 579, -1, 578, 580, 579, -1, + 579, 580, 581, -1, 582, 571, 583, -1, + 583, 571, 570, -1, 583, 584, 582, -1, + 582, 584, 585, -1, 584, 586, 585, -1, + 585, 586, 587, -1, 586, 588, 587, -1, + 587, 588, 589, -1, 588, 590, 589, -1, + 589, 590, 591, -1, 590, 581, 591, -1, + 591, 581, 580, -1, 62, 592, 59, -1, + 59, 592, 60, -1, 573, 593, 575, -1, + 575, 593, 594, -1, 593, 595, 594, -1, + 594, 595, 596, -1, 597, 598, 599, -1, + 599, 598, 600, -1, 599, 601, 597, -1, + 597, 601, 602, -1, 598, 603, 600, -1, + 600, 603, 604, -1, 603, 605, 604, -1, + 604, 605, 606, -1, 605, 607, 606, -1, + 606, 607, 608, -1, 609, 596, 610, -1, + 610, 596, 595, -1, 610, 611, 609, -1, + 609, 611, 612, -1, 611, 613, 612, -1, + 612, 613, 614, -1, 613, 615, 614, -1, + 614, 615, 616, -1, 615, 608, 616, -1, + 616, 608, 607, -1, 601, 617, 602, -1, + 602, 617, 618, -1, 619, 620, 621, -1, + 621, 620, 622, -1, 621, 623, 619, -1, + 619, 623, 624, -1, 620, 625, 622, -1, + 622, 625, 626, -1, 625, 627, 626, -1, + 626, 627, 628, -1, 627, 629, 628, -1, + 628, 629, 630, -1, 631, 618, 632, -1, + 632, 618, 617, -1, 632, 633, 631, -1, + 631, 633, 634, -1, 633, 635, 634, -1, + 634, 635, 636, -1, 635, 637, 636, -1, + 636, 637, 638, -1, 637, 630, 638, -1, + 638, 630, 629, -1, 623, 639, 624, -1, + 624, 639, 640, -1, 641, 640, 642, -1, + 642, 640, 639, -1, 642, 643, 641, -1, + 641, 643, 644, -1, 643, 645, 644, -1, + 644, 645, 646, -1, 645, 647, 646, -1, + 646, 647, 648, -1, 647, 649, 648, -1, + 648, 649, 650, -1, 649, 651, 650, -1, + 650, 651, 652, -1, 651, 653, 652, -1, + 652, 653, 654, -1, 653, 655, 654, -1, + 654, 655, 656, -1, 655, 549, 656, -1, + 656, 549, 548, -1, 657, 658, 659, -1, + 659, 658, 660, -1, 659, 661, 657, -1, + 657, 661, 662, -1, 658, 663, 660, -1, + 660, 663, 664, -1, 661, 665, 662, -1, + 662, 665, 666, -1, 665, 667, 666, -1, + 666, 667, 668, -1, 667, 669, 668, -1, + 668, 669, 670, -1, 669, 667, 671, -1, + 671, 667, 665, -1, 671, 665, 661, -1, + 661, 659, 671, -1, 671, 659, 660, -1, + 671, 660, 664, -1, 671, 664, 672, -1, + 672, 664, 673, -1, 672, 673, 674, -1, + 674, 673, 675, -1, 674, 675, 676, -1, + 669, 671, 670, -1, 670, 671, 677, -1, + 670, 677, 668, -1, 668, 677, 666, -1, + 666, 677, 662, -1, 662, 677, 657, -1, + 657, 677, 658, -1, 658, 677, 663, -1, + 677, 678, 663, -1, 663, 678, 679, -1, + 678, 680, 679, -1, 679, 680, 681, -1, + 679, 681, 682, -1, 671, 672, 677, -1, + 677, 672, 678, -1, 673, 679, 675, -1, + 675, 679, 682, -1, 673, 664, 679, -1, + 679, 664, 663, -1, 672, 674, 678, -1, + 678, 674, 680, -1, 680, 674, 681, -1, + 681, 674, 676, -1, 675, 682, 676, -1, + 676, 682, 681, -1, 16, 683, 17, -1, + 17, 683, 18, -1, 10, 684, 11, -1, + 11, 684, 69, -1, 94, 685, 91, -1, + 91, 685, 92, -1, 130, 686, 127, -1, + 127, 686, 128, -1, 261, 264, 255, -1, + 255, 264, 277, -1, 255, 277, 257, -1, + 257, 277, 287, -1, 257, 287, 283, -1, + 283, 287, 286, -1, 283, 286, 285, -1, + 285, 284, 283, -1, 283, 284, 247, -1, + 283, 247, 246, -1, 283, 246, 253, -1, + 253, 246, 251, -1, 253, 251, 282, -1, + 282, 281, 253, -1, 253, 281, 280, -1, + 253, 280, 279, -1, 253, 279, 255, -1, + 255, 279, 278, -1, 255, 278, 261, -1, + 219, 222, 213, -1, 213, 222, 235, -1, + 213, 235, 215, -1, 215, 235, 245, -1, + 215, 245, 241, -1, 241, 245, 244, -1, + 241, 244, 243, -1, 243, 242, 241, -1, + 241, 242, 205, -1, 241, 205, 204, -1, + 241, 204, 211, -1, 211, 204, 209, -1, + 211, 209, 240, -1, 240, 239, 211, -1, + 211, 239, 238, -1, 211, 238, 237, -1, + 211, 237, 213, -1, 213, 237, 236, -1, + 213, 236, 219, -1, 173, 15, 549, -1, + 549, 15, 544, -1, 15, 17, 544, -1, + 544, 17, 545, -1, 17, 13, 545, -1, + 545, 13, 12, -1, 545, 12, 561, -1, + 561, 12, 34, -1, 561, 34, 562, -1, + 562, 34, 32, -1, 562, 32, 564, -1, + 564, 32, 30, -1, 564, 30, 566, -1, + 566, 30, 28, -1, 566, 28, 568, -1, + 568, 28, 26, -1, 568, 26, 559, -1, + 559, 26, 24, -1, 559, 24, 557, -1, + 557, 24, 22, -1, 557, 22, 555, -1, + 555, 22, 19, -1, 555, 19, 550, -1, + 550, 19, 21, -1, 550, 21, 551, -1, + 551, 21, 49, -1, 551, 49, 570, -1, + 570, 49, 9, -1, 570, 9, 11, -1, + 570, 11, 583, -1, 583, 11, 67, -1, + 583, 67, 584, -1, 584, 67, 65, -1, + 584, 65, 586, -1, 586, 65, 63, -1, + 586, 63, 588, -1, 588, 63, 61, -1, + 588, 61, 590, -1, 590, 61, 59, -1, + 590, 59, 581, -1, 581, 59, 57, -1, + 581, 57, 579, -1, 579, 57, 55, -1, + 579, 55, 577, -1, 577, 55, 53, -1, + 577, 53, 572, -1, 572, 53, 52, -1, + 572, 52, 573, -1, 573, 52, 80, -1, + 573, 80, 593, -1, 593, 80, 83, -1, + 593, 83, 595, -1, 595, 83, 7, -1, + 595, 7, 6, -1, 595, 6, 610, -1, + 610, 6, 101, -1, 610, 101, 611, -1, + 611, 101, 99, -1, 611, 99, 613, -1, + 613, 99, 97, -1, 613, 97, 615, -1, + 615, 97, 95, -1, 615, 95, 608, -1, + 608, 95, 93, -1, 608, 93, 606, -1, + 606, 93, 91, -1, 606, 91, 604, -1, + 604, 91, 89, -1, 604, 89, 600, -1, + 600, 89, 86, -1, 600, 86, 599, -1, + 599, 86, 88, -1, 599, 88, 601, -1, + 601, 88, 115, -1, 601, 115, 617, -1, + 617, 115, 4, -1, 617, 4, 3, -1, + 617, 3, 632, -1, 632, 3, 133, -1, + 632, 133, 633, -1, 633, 133, 131, -1, + 633, 131, 635, -1, 635, 131, 129, -1, + 635, 129, 637, -1, 637, 129, 127, -1, + 637, 127, 630, -1, 630, 127, 125, -1, + 630, 125, 628, -1, 628, 125, 123, -1, + 628, 123, 626, -1, 626, 123, 121, -1, + 626, 121, 622, -1, 622, 121, 119, -1, + 622, 119, 621, -1, 621, 119, 118, -1, + 621, 118, 623, -1, 623, 118, 146, -1, + 623, 146, 639, -1, 639, 146, 1, -1, + 639, 1, 0, -1, 639, 0, 642, -1, + 642, 0, 156, -1, 642, 156, 643, -1, + 643, 156, 154, -1, 643, 154, 645, -1, + 645, 154, 152, -1, 645, 152, 647, -1, + 647, 152, 150, -1, 647, 150, 649, -1, + 649, 150, 149, -1, 649, 149, 651, -1, + 651, 149, 167, -1, 651, 167, 653, -1, + 653, 167, 170, -1, 653, 170, 655, -1, + 655, 170, 173, -1, 655, 173, 549, -1, + 548, 546, 16, -1, 16, 546, 683, -1, + 683, 546, 18, -1, 18, 546, 547, -1, + 18, 547, 37, -1, 37, 547, 14, -1, + 547, 560, 14, -1, 14, 560, 38, -1, + 38, 560, 36, -1, 36, 560, 563, -1, + 36, 563, 39, -1, 39, 563, 35, -1, + 35, 563, 40, -1, 40, 563, 565, -1, + 40, 565, 33, -1, 33, 565, 41, -1, + 565, 567, 41, -1, 41, 567, 31, -1, + 31, 567, 42, -1, 42, 567, 569, -1, + 42, 569, 29, -1, 29, 569, 43, -1, + 569, 558, 43, -1, 43, 558, 27, -1, + 27, 558, 44, -1, 44, 558, 556, -1, + 44, 556, 25, -1, 25, 556, 45, -1, + 556, 554, 45, -1, 45, 554, 23, -1, + 23, 554, 46, -1, 46, 554, 552, -1, + 46, 552, 20, -1, 20, 552, 47, -1, + 47, 552, 48, -1, 48, 552, 553, -1, + 48, 553, 50, -1, 50, 553, 51, -1, + 553, 571, 51, -1, 51, 571, 70, -1, + 70, 571, 10, -1, 10, 571, 582, -1, + 10, 582, 684, -1, 684, 582, 69, -1, + 582, 585, 69, -1, 69, 585, 71, -1, + 71, 585, 68, -1, 68, 585, 587, -1, + 68, 587, 72, -1, 72, 587, 66, -1, + 66, 587, 73, -1, 73, 587, 589, -1, + 73, 589, 64, -1, 64, 589, 74, -1, + 589, 591, 74, -1, 74, 591, 62, -1, + 62, 591, 592, -1, 592, 591, 580, -1, + 592, 580, 60, -1, 60, 580, 75, -1, + 580, 578, 75, -1, 75, 578, 58, -1, + 58, 578, 76, -1, 76, 578, 576, -1, + 76, 576, 56, -1, 56, 576, 77, -1, + 576, 574, 77, -1, 77, 574, 54, -1, + 54, 574, 78, -1, 78, 574, 79, -1, + 574, 575, 79, -1, 79, 575, 81, -1, + 81, 575, 82, -1, 82, 575, 594, -1, + 82, 594, 84, -1, 84, 594, 85, -1, + 594, 596, 85, -1, 85, 596, 104, -1, + 104, 596, 8, -1, 8, 596, 609, -1, + 8, 609, 105, -1, 105, 609, 103, -1, + 609, 612, 103, -1, 103, 612, 106, -1, + 106, 612, 102, -1, 102, 612, 107, -1, + 612, 614, 107, -1, 107, 614, 100, -1, + 100, 614, 108, -1, 108, 614, 616, -1, + 108, 616, 98, -1, 98, 616, 109, -1, + 616, 607, 109, -1, 109, 607, 96, -1, + 96, 607, 110, -1, 110, 607, 605, -1, + 110, 605, 94, -1, 94, 605, 685, -1, + 605, 603, 685, -1, 685, 603, 92, -1, + 92, 603, 111, -1, 111, 603, 598, -1, + 111, 598, 90, -1, 90, 598, 112, -1, + 598, 597, 112, -1, 112, 597, 87, -1, + 87, 597, 113, -1, 113, 597, 114, -1, + 597, 602, 114, -1, 114, 602, 116, -1, + 116, 602, 117, -1, 117, 602, 618, -1, + 117, 618, 136, -1, 136, 618, 5, -1, + 618, 631, 5, -1, 5, 631, 177, -1, + 177, 631, 135, -1, 135, 631, 634, -1, + 135, 634, 137, -1, 137, 634, 134, -1, + 134, 634, 138, -1, 138, 634, 636, -1, + 138, 636, 132, -1, 132, 636, 139, -1, + 636, 638, 139, -1, 139, 638, 130, -1, + 130, 638, 686, -1, 686, 638, 629, -1, + 686, 629, 128, -1, 128, 629, 140, -1, + 629, 627, 140, -1, 140, 627, 126, -1, + 126, 627, 141, -1, 141, 627, 625, -1, + 141, 625, 124, -1, 124, 625, 142, -1, + 625, 620, 142, -1, 142, 620, 122, -1, + 122, 620, 143, -1, 143, 620, 619, -1, + 143, 619, 120, -1, 120, 619, 144, -1, + 144, 619, 145, -1, 145, 619, 624, -1, + 145, 624, 147, -1, 147, 624, 148, -1, + 624, 640, 148, -1, 148, 640, 159, -1, + 159, 640, 2, -1, 2, 640, 641, -1, + 2, 641, 160, -1, 160, 641, 158, -1, + 641, 644, 158, -1, 158, 644, 161, -1, + 161, 644, 157, -1, 157, 644, 162, -1, + 644, 646, 162, -1, 162, 646, 155, -1, + 155, 646, 163, -1, 163, 646, 648, -1, + 163, 648, 153, -1, 153, 648, 164, -1, + 648, 650, 164, -1, 164, 650, 151, -1, + 151, 650, 165, -1, 165, 650, 652, -1, + 165, 652, 166, -1, 166, 652, 168, -1, + 652, 654, 168, -1, 168, 654, 169, -1, + 169, 654, 171, -1, 171, 654, 656, -1, + 171, 656, 172, -1, 172, 656, 174, -1, + 656, 548, 174, -1, 174, 548, 175, -1, + 175, 548, 176, -1, 176, 548, 16, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 171, 171, 171, -1, 172, 172, 172, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 173, 173, 173, -1, 174, 174, 174, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 177, 177, 177, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 179, 179, 179, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 181, 181, 181, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 187, 187, 187, -1, 188, 188, 188, -1, + 188, 188, 188, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 190, 190, 190, -1, 190, 190, 190, -1, + 191, 191, 191, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 192, 192, 192, -1, + 193, 193, 193, -1, 193, 193, 193, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 194, 194, 194, -1, 194, 194, 194, -1, + 195, 195, 195, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 196, 196, 196, -1, + 197, 197, 197, -1, 197, 197, 197, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 188, 188, 188, -1, 188, 188, 188, -1, + 187, 187, 187, -1, 187, 187, 187, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 197, 197, 197, -1, + 197, 197, 197, -1, 196, 196, 196, -1, + 196, 196, 196, -1, 198, 198, 198, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 200, 200, 200, -1, + 200, 200, 200, -1, 191, 191, 191, -1, + 191, 191, 191, -1, 190, 190, 190, -1, + 190, 190, 190, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 201, 201, 201, -1, + 201, 201, 201, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 203, 203, 203, -1, + 203, 203, 203, -1, 204, 204, 204, -1, + 204, 204, 204, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 205, 205, 205, -1, + 205, 205, 205, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 207, 207, 207, -1, + 207, 207, 207, -1, 208, 208, 208, -1, + 208, 208, 208, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 209, 209, 209, -1, + 209, 209, 209, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 210, 210, 210, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 211, 211, 211, -1, 212, 212, 212, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 213, 213, 213, -1, 214, 214, 214, -1, + 214, 214, 214, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 215, 215, 215, -1, + 215, 215, 215, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 216, 216, 216, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 217, 217, 217, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 218, 218, 218, -1, + 218, 218, 218, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 219, 219, 219, -1, + 219, 219, 219, -1, 220, 220, 220, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 221, 221, 221, -1, 222, 222, 222, -1, + 222, 222, 222, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 224, 224, 224, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 225, 225, 225, -1, 226, 226, 226, -1, + 226, 226, 226, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 230, 230, 230, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 231, 231, 231, -1, 232, 232, 232, -1, + 232, 232, 232, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 233, 233, 233, -1, + 233, 233, 233, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 234, 234, 234, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 235, 235, 235, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 236, 236, 236, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 237, 237, 237, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 238, 238, 238, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 239, 239, 239, -1, 240, 240, 240, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 241, 241, 241, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 242, 242, 242, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 243, 243, 243, -1, 244, 244, 244, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 245, 245, 245, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 201, 201, 201, -1, 201, 201, 201, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 203, 203, 203, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 204, 204, 204, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 182, 182, 182, -1, 182, 182, 182, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 205, 205, 205, -1, 205, 205, 205, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 185, 185, 185, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 207, 207, 207, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 208, 208, 208, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 246, 246, 246, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 247, 247, 247, -1, 248, 248, 248, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 249, 249, 249, -1, 250, 250, 250, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 251, 251, 251, -1, 252, 252, 252, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 253, 253, 253, -1, 254, 254, 254, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 255, 255, 255, -1, 256, 256, 256, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 257, 257, 257, -1, 258, 258, 258, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 259, 259, 259, -1, 260, 260, 260, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 261, 261, 261, -1, 262, 262, 262, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 263, 263, 263, -1, 264, 264, 264, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 265, 265, 265, -1, 266, 266, 266, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 267, 267, 267, -1, 268, 268, 268, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 269, 269, 269, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 271, 271, 271, -1, 272, 272, 272, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 273, 273, 273, -1, 274, 274, 274, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 275, 275, 275, -1, 276, 276, 276, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 277, 277, 277, -1, 278, 278, 278, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 279, 279, 279, -1, 280, 280, 280, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 281, 281, 281, -1, 282, 282, 282, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 283, 283, 283, -1, 284, 284, 284, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 285, 285, 285, -1, 286, 286, 286, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 287, 287, 287, -1, 288, 288, 288, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 289, 289, 289, -1, 290, 290, 290, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 291, 291, 291, -1, 292, 292, 292, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 293, 293, 293, -1, 294, 294, 294, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 295, 295, 295, -1, 296, 296, 296, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 297, 297, 297, -1, 298, 298, 298, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 299, 299, 299, -1, 300, 300, 300, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 301, 301, 301, -1, 302, 302, 302, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 303, 303, 303, -1, 242, 242, 242, -1, + 242, 242, 242, -1, 304, 304, 304, -1, + 304, 304, 304, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 305, 305, 305, -1, 305, 305, 305, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 306, 306, 306, -1, + 306, 306, 306, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 307, 307, 307, -1, + 307, 307, 307, -1, 308, 308, 308, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 309, 309, 309, -1, 310, 310, 310, -1, + 310, 310, 310, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 178, 178, 178, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 189, 189, 189, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 186, 186, 186, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + + } + + }, + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.0078125 0.1875 0.65625 + ambientIntensity 0.46584472 + specularColor 0 0.1 0.5 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.059692498 -0.0145 -0.0060669999, + -0.059744101 -0.0145 -0.0053960001, + -0.059682 -0.0094999997 -0.00616901, + -0.0546159 -0.044859398 0.017555, + -0.0546159 -0.047607999 0.01585, + -0.0532961 -0.047455098 0.01984, + -0.055787299 -0.0436932 0.014417, + -0.0546159 -0.050264601 0.013849, + -0.0532961 -0.050287802 0.017987, + -0.055787299 -0.046315301 0.012706, + -0.056809202 -0.042516001 0.01125, + -0.056809202 -0.0399721 0.01269, + -0.0576833 -0.038916901 0.0095229903, + -0.0576833 -0.036470499 0.010724, + -0.058412101 -0.035541002 0.00758, + -0.058412101 -0.0332435 0.0085709998, + -0.058998398 -0.0324402 0.0054709902, + -0.058998398 -0.03021 0.0063100001, + -0.059445001 -0.029536201 0.003274, + -0.059445001 -0.0250424 0.0050059999, + -0.059757002 -0.0246257 0.0020949999, + -0.059757002 -0.020297101 0.003939, + -0.0599402 -0.020127499 0.001158, + -0.0599402 -0.019051399 0.001634, + -0.059999999 -0.018941101 -0.001103, + -0.059999999 -0.0176931 -0.00057600398, + -0.0599402 -0.0176301 -0.0032889999, + -0.0599402 -0.016121 -0.0028359999, + -0.059757002 -0.0160916 -0.0055519999, + -0.059757002 -0.0152853 -0.0054199998, + -0.059679601 -0.0145 -0.00616901, + -0.059445001 -0.0152703 -0.0081660002, + -0.059757002 -0.019162601 0.0043930099, + -0.059445001 -0.020469001 0.0067579998, + -0.059757002 -0.017819799 0.0048719901, + -0.0599402 -0.017756199 0.002138, + -0.0599402 -0.0161794 0.0025520001, + -0.059999999 -0.016150201 -0.000141998, + -0.059999999 -0.0153147 -1.89972e-005, + -0.0599402 -0.0153 -0.0027089999, + -0.059999 -0.0145 -0.000345001, + -0.059931099 -0.0145 -0.002688, + -0.059999999 -0.0094999997 0, + -0.059918199 -0.0145 -0.0031320001, + -0.058998398 -0.025463499 0.0079490095, + -0.058412101 -0.030888099 0.0093650101, + -0.0576833 -0.034048799 0.011678, + -0.056809202 -0.0373987 0.013865, + -0.055787299 -0.041021802 0.015841, + 0.050219599 -0.041894302 0.029077001, + 0.050219599 -0.043482602 0.028599, + 0.051830001 -0.041028801 0.026148999, + 0.048467699 -0.0427357 0.031923998, + 0.048467699 -0.041099999 0.032308999, + 0.0465803 -0.041858301 0.035046998, + 0.0465803 -0.040197201 0.035335001, + 0.044564299 -0.0408746 0.037951, + 0.044564299 -0.037313901 0.038313001, + 0.0424264 -0.037860699 0.040777002, + 0.0424264 -0.030247901 0.041363001, + 0.040174201 -0.030572301 0.04363, + 0.040174201 -0.0227536 0.044155002, + 0.0378174 -0.022879699 0.046225, + 0.040174201 -0.018750601 0.044434, + 0.0424264 -0.018700801 0.042277001, + 0.0424264 -0.0166132 0.042392999, + 0.044564299 -0.0165888 0.040135998, + 0.042958502 -0.0145 0.041866001, + 0.0465803 -0.016563199 0.037774, + 0.048467699 -0.016536601 0.035317998, + 0.047033701 -0.0145 0.037225999, + 0.0465803 -0.0185932 0.037627, + 0.050219599 -0.0165092 0.032779001, + 0.0498452 -0.0145 0.033397999, + 0.048467699 -0.018535901 0.035154, + 0.0465803 -0.0223314 0.037229002, + 0.044564299 -0.022478901 0.039648, + 0.044564299 -0.0299062 0.038973998, + 0.0424264 -0.022619801 0.041960001, + 0.044564299 -0.0186482 0.040004998, + 0.046333499 -0.0145 0.038121, + 0.0465803 -0.036741599 0.035735, + 0.048467699 -0.0394927 0.032614999, + 0.050219599 -0.040315699 0.029478, + 0.059445001 -0.0170916 0.00789, + 0.059445001 -0.016241301 0.0080350004, + 0.058998398 -0.0179637 0.010481, + 0.059757002 -0.0162115 0.0052829999, + 0.059702002 -0.0145 0.0059730099, + 0.059431199 -0.0145 0.0081410101, + 0.059337199 -0.0145 0.0088930102, + 0.059285302 -0.0094999997 0.0092329998, + 0.056793701 -0.0145 0.019300001, + 0.056809202 -0.016362401 0.019222001, + 0.057391401 -0.0145 0.017499, + 0.056464098 -0.0145 0.020292999, + 0.056143001 -0.0094999997 0.021165, + 0.0576679 -0.0145 0.016505999, + 0.058021698 -0.0094999997 0.01528, + -0.059445001 -0.0168168 -0.0085199997, + -0.059757002 -0.017566601 -0.0060229902, + -0.059445001 -0.0160618 -0.0083029903, + -0.058998398 -0.016031699 -0.011084, + -0.058998398 -0.0152552 -0.010943, + -0.058412101 -0.01524 -0.013737, + -0.0587232 -0.0145 -0.012271, + -0.0546159 -0.0527828 0.011561, + -0.055787299 -0.0512431 0.0084349997, + -0.0546159 -0.0539768 0.010315, + -0.0532961 -0.0555542 0.013387, + -0.0532961 -0.056755401 0.012064, + -0.051830001 -0.058360599 0.015068, + -0.051830001 -0.059560299 0.013667, + -0.050219599 -0.0611826 0.016588001, + -0.050219599 -0.062372401 0.01511, + -0.048467699 -0.064000301 0.017933, + -0.048467699 -0.065171801 0.016379001, + -0.0465803 -0.066793904 0.019091001, + -0.0465803 -0.067938097 0.017464001, + -0.044564299 -0.069542304 0.020053999, + -0.044564299 -0.070650302 0.018355999, + -0.0424264 -0.0722242 0.020812999, + -0.0424264 -0.073288403 0.019049, + -0.040174201 -0.074819602 0.021361999, + -0.040174201 -0.075832799 0.019538, + -0.0378174 -0.077310398 0.0217, + -0.0378174 -0.078265302 0.019822, + -0.035366699 -0.079678498 0.021828, + -0.035366699 -0.080568202 0.019902, + -0.0328326 -0.081906401 0.021745, + -0.0328326 -0.0827263 0.019778, + -0.0302257 -0.083979398 0.021455999, + -0.0302257 -0.084725201 0.019452, + -0.027557701 -0.0858858 0.020964, + -0.027557701 -0.086553998 0.018931, + -0.0248404 -0.087615497 0.020276999, + -0.0248404 -0.088202201 0.018224001, + -0.0220857 -0.089158498 0.019406, + -0.0220857 -0.089658797 0.017355001, + -0.019305199 -0.0905044 0.018375, + -0.019305199 -0.090922303 0.016314, + -0.0165099 -0.091654703 0.017177001, + -0.0165099 -0.092024602 0.014997, + -0.0137106 -0.092642799 0.015707999, + -0.0137106 -0.093287699 0.011241, + -0.0109179 -0.093796402 0.011798, + -0.0109179 -0.0943041 0.007276, + -0.0081421202 -0.094700098 0.0076879999, + -0.0081421202 -0.095056199 0.00312199, + -0.0053918599 -0.095338397 0.00340199, + -0.0053918599 -0.095536999 -0.001196, + -0.00267513 -0.095705703 -0.001037, + -0.00267513 -0.095743202 -0.00565401, + 0 -0.095799401 -0.0056039998, + 0 -0.095673002 -0.01023, + 0.00267513 -0.095743902 -0.00565401, + 0.00267513 -0.0957065 -0.001036, + 0.0053918599 -0.095538601 -0.001196, + 0.0053918599 -0.0953402 0.0034030001, + 0.0081421202 -0.095058903 0.003123, + 0.0081421202 -0.094702803 0.0076909899, + 0.0109179 -0.094307803 0.00727901, + 0.0109179 -0.093799703 0.011804, + 0.0137106 -0.0932917 0.011248, + 0.0137106 -0.0926456 0.015712, + 0.0165099 -0.092027999 0.015002, + 0.0165099 -0.0916574 0.017178001, + 0.019305199 -0.090925403 0.016315, + 0.019305199 -0.090507597 0.018375, + 0.0220857 -0.0896625 0.017355001, + 0.0220857 -0.089162998 0.019406, + 0.0248404 -0.088207297 0.018224001, + 0.0248404 -0.087622002 0.020277999, + 0.027557701 -0.086561099 0.018932, + 0.027557701 -0.0858946 0.020966001, + 0.0302257 -0.084734902 0.019455001, + 0.0302257 -0.083990797 0.02146, + 0.0328326 -0.082738698 0.019783, + 0.0328326 -0.081920497 0.021752, + 0.035366699 -0.080583401 0.019909, + 0.035366699 -0.079694897 0.021836, + 0.0378174 -0.078282803 0.019831, + 0.0378174 -0.077328503 0.021710999, + 0.040174201 -0.075852104 0.019548999, + 0.040174201 -0.074838899 0.021375, + 0.0424264 -0.073308803 0.019063, + 0.0424264 -0.072244003 0.020827999, + 0.044564299 -0.070671096 0.018371999, + 0.044564299 -0.069562003 0.020071, + 0.0465803 -0.067958698 0.017481999, + 0.0465803 -0.066813201 0.019111, + 0.048467699 -0.065191902 0.016399, + 0.048467699 -0.064018801 0.017953999, + 0.050219599 -0.062391501 0.015132, + 0.050219599 -0.061199799 0.016612001, + 0.051830001 -0.059578098 0.013692, + 0.051830001 -0.058376402 0.015094, + 0.0532961 -0.056771599 0.01209, + 0.0532961 -0.055568401 0.013414, + 0.0546159 -0.053991299 0.010342, + 0.0546159 -0.052795202 0.011588, + 0.055787299 -0.0512558 0.0084629999, + 0.055787299 -0.050075099 0.0096340002, + 0.056809202 -0.047424801 0.0075690001, + 0.059748501 -0.0145 -0.0053969999, + 0.059914999 -0.0145 -0.003088, + 0.059757002 -0.0160942 -0.0055359998, + 0.0599402 -0.016123701 -0.0028200101, + 0.0599402 -0.016910899 -0.002998, + 0.059999999 -0.0169558 -0.000294998, + 0.059999999 -0.0177077 -0.00053799403, + 0.0599402 -0.017770801 0.002175, + 0.0599402 -0.019071801 0.001638, + 0.059757002 -0.019183001 0.0043970002, + 0.059757002 -0.020302201 0.0039440002, + 0.056809202 -0.039965902 0.012716, + 0.056809202 -0.042515401 0.011278, + 0.0576833 -0.038910601 0.0095490003, + 0.0576833 -0.036474802 0.010743, + 0.058412101 -0.035545301 0.0075989999, + 0.058412101 -0.033266298 0.0085760001, + 0.058998398 -0.0324632 0.0054759998, + 0.058998398 -0.030210201 0.0063090101, + 0.059445001 -0.0295364 0.003274, + 0.059445001 -0.025045799 0.0050059999, + 0.059757002 -0.0246292 0.0020939901, + 0.0599402 -0.020132599 0.001162, + 0.059999999 -0.018961599 -0.001099, + 0.0599402 -0.017644599 -0.0032510101, + 0.059757002 -0.0168657 -0.0057209898, + 0.059445001 -0.0160644 -0.0082869995, + 0.058985401 -0.0145 -0.010916, + 0.0592747 -0.0145 -0.0092319902, + 0.058998398 -0.0160343 -0.011068, + 0.059445001 -0.0168199 -0.0084809996, + 0.059757002 -0.0175811 -0.0059850002, + 0.0599402 -0.0188512 -0.0038370099, + 0.059999999 -0.0199643 -0.00159801, + 0.0599402 -0.024218099 -0.00077900698, + 0.059757002 -0.0288698 0.00027099601, + 0.059445001 -0.031665199 0.0023960001, + 0.058998398 -0.034618098 0.0044620102, + 0.058412101 -0.037853699 0.0063769999, + 0.0576833 -0.041331898 0.0080939904, + 0.056809202 -0.045015398 0.0095610004, + 0.0576833 -0.043703701 0.0063709999, + 0.058412101 -0.040146701 0.0049049999, + 0.058998398 -0.036799401 0.003213, + 0.059445001 -0.033696599 0.00134399, + 0.059757002 -0.030875601 -0.00065199297, + 0.0599402 -0.028211899 -0.00269299, + 0.059999999 -0.0238101 -0.0036299999, + 0.0599402 -0.0197959 -0.0043580001, + 0.059757002 -0.01874 -0.0065959902, + 0.059445001 -0.0175166 -0.0087559996, + 0.058998398 -0.0167736 -0.011271, + 0.058412101 -0.016003899 -0.013868, + 0.058412101 -0.015257 -0.013761, + 0.057669599 -0.0145 -0.016505999, + 0.058007602 -0.0145 -0.015276, + 0.0576833 -0.0152416 -0.016562, + -0.055787299 -0.032921601 0.018526001, + -0.0546159 -0.033590499 0.021539999, + -0.055787299 -0.027158299 0.019792, + -0.056809202 -0.026736399 0.016844001, + -0.056809202 -0.021167999 0.018217999, + -0.0576833 -0.020992899 0.015349, + -0.0576833 -0.0180807 0.016088, + -0.058412101 -0.0180149 0.013263, + -0.058412101 -0.016299101 0.013599, + -0.058998398 -0.016268799 0.0108, + -0.058998398 -0.0153745 0.010904, + -0.059445001 -0.0153593 0.0081280097, + -0.059432399 -0.0145 0.0081410101, + -0.0596756 -0.0145 0.0061679999, + -0.059351299 -0.0145 0.0087989997, + -0.058984298 -0.0145 0.010915, + -0.058848299 -0.0145 0.011699, + -0.058731299 -0.0094999997 0.012273, + -0.055772699 -0.0145 0.02208, + -0.056496199 -0.0145 0.020203, + -0.055787299 -0.015436 0.022077, + -0.057158101 -0.0094999997 0.018247001, + -0.056794401 -0.0145 0.019300001, + -0.0571438 -0.0145 0.018242, + -0.056809202 -0.0154207 0.019295, + -0.055787299 -0.0163901 0.021994, + -0.0546159 -0.0164201 0.024754999, + -0.0546159 -0.0182765 0.024497001, + -0.0532961 -0.018340399 0.027240001, + -0.0532961 -0.021684799 0.026691001, + -0.051830001 -0.021851899 0.02943, + -0.051830001 -0.028393701 0.028425001, + -0.050219599 -0.0287893 0.031189, + -0.051830001 -0.034898099 0.027431, + -0.0532961 -0.0342503 0.024512, + -0.058412101 -0.0153899 0.013698, + -0.0576833 -0.0154053 0.016499, + -0.058203701 -0.0145 0.014571, + -0.0576833 -0.0163296 0.016404999, + -0.056809202 -0.016359899 0.019207001, + -0.056809202 -0.018146399 0.01891, + -0.055787299 -0.0182117 0.021716001, + -0.055787299 -0.021342101 0.021073001, + -0.0546159 -0.0215146 0.023901001, + -0.0546159 -0.0275764 0.022714, + -0.0532961 -0.027988801 0.025595, + -0.057419099 -0.0145 0.017408, + -0.057668701 -0.0145 0.016505999, + -0.058397699 -0.0145 0.013707, + -0.058720101 -0.0145 0.012271, + -0.0546159 -0.036445301 0.020926001, + -0.0546159 -0.039236698 0.020083001, + -0.055787299 -0.038321901 0.016988, + -0.0546159 -0.042061701 0.018962, + -0.059746899 -0.0145 0.0053969999, + -0.059682 -0.0094999997 0.00616901, + -0.059927799 -0.0145 0.0029420001, + -0.0597114 -0.0145 0.0058780098, + -0.059757002 -0.0153443 0.0053810002, + -0.059934001 -0.0145 0.002688, + -0.059999999 -0.0145 0, + -0.0599402 -0.0153294 0.0026700001, + -0.059757002 -0.0162088 0.0052669998, + -0.059445001 -0.016238701 0.0080190003, + -0.059445001 -0.0178842 0.00764301, + -0.058998398 -0.0179494 0.010444, + -0.058998398 -0.0206428 0.00960699, + -0.058412101 -0.0208176 0.012474, + -0.058412101 -0.025887299 0.010911, + -0.0576833 -0.0263121 0.013879, + -0.0576833 -0.031567801 0.012427, + -0.056809202 -0.0322465 0.015485, + -0.056809202 -0.0348529 0.014781, + -0.055787299 -0.035652801 0.017867999, + -0.0532961 -0.040139001 0.023135001, + -0.054979 -0.0094999997 0.024026999, + -0.055437401 -0.0145 0.022949999, + -0.0546159 -0.0154512 0.024832999, + -0.0532961 -0.0164496 0.027478, + -0.051830001 -0.0184031 0.029933, + -0.050219599 -0.022015201 0.032106999, + -0.048467699 -0.029174 0.033877, + -0.050219599 -0.0355311 0.030282, + -0.051830001 -0.036513101 0.027183, + -0.0532961 -0.037227001 0.023941999, + -0.051830001 -0.039492302 0.026556, + -0.052201401 -0.0145 0.029544, + -0.0522171 -0.0094999997 0.029553, + -0.052922402 -0.0145 0.028271001, + -0.051819 -0.0145 0.030219, + -0.051830001 -0.0154811 0.030221, + -0.050219599 -0.016507 0.032765001, + -0.051472198 -0.0145 0.030832, + -0.0302191 -0.0145 0.051817998, + -0.0308876 -0.0094999997 0.051438998, + -0.030873001 -0.0145 0.051447999, + -0.0328326 -0.018874399 0.050119001, + -0.035366699 -0.018833 0.048349999, + -0.0328326 -0.023104601 0.049959, + -0.0302257 -0.0189125 0.051745001, + -0.0302257 -0.0232055 0.051612001, + -0.027557701 -0.0189473 0.053226002, + -0.0328326 -0.0314284 0.049628001, + -0.035366699 -0.0311624 0.047770001, + -0.035366699 -0.039327499 0.047386002, + -0.0378174 -0.038869198 0.045320999, + -0.0378174 -0.040862098 0.045209002, + -0.040174201 -0.040325899 0.042987, + -0.040174201 -0.042120699 0.042821001, + -0.0424264 -0.0415054 0.040447999, + -0.0424264 -0.043271001 0.040185999, + -0.044564299 -0.0425734 0.037670001, + -0.044564299 -0.0443285 0.037308998, + -0.0465803 -0.043545902 0.034660999, + -0.0465803 -0.045254402 0.034205999, + -0.048467699 -0.044385199 0.031438999, + -0.0465803 -0.046960399 0.033668, + -0.048467699 -0.042732101 0.031908002, + -0.0465803 -0.041843399 0.035037, + -0.044564299 -0.0408573 0.037946999, + -0.0424264 -0.039757401 0.040631, + -0.040174201 -0.038379699 0.043116, + -0.0378174 -0.030875999 0.045768999, + -0.035366699 -0.0229948 0.048160002, + -0.0378174 -0.0187885 0.046443999, + -0.040171701 -0.0145 0.044560999, + -0.040312301 -0.0145 0.044440001, + -0.040174201 -0.0166346 0.044523999, + -0.040756401 -0.0094999997 0.044032998, + -0.038084399 -0.0145 0.046363998, + -0.0378174 -0.016656499 0.046544999, + -0.035366699 -0.0166771 0.048436999, + -0.036008701 -0.0145 0.047984999, + -0.0328326 -0.0166962 0.050193001, + -0.033358999 -0.0145 0.049872, + -0.0302257 -0.016713699 0.051808, + -0.0308873 -0.0145 0.051438998, + -0.0275514 -0.0145 0.053284001, + -0.0254349 -0.0094999997 0.054342002, + -0.0283127 -0.0145 0.052900001, + -0.025684301 -0.0145 0.054225001, + -0.027557701 -0.016729699 0.053277999, + -0.0248404 -0.018978501 0.054559, + -0.027557701 -0.023297399 0.053117, + -0.0302257 -0.031672802 0.051336002, + -0.0328326 -0.039752901 0.049302001, + -0.035366699 -0.041363999 0.047288999, + -0.0378174 -0.042700998 0.045058999, + -0.040174201 -0.043933202 0.042575002, + -0.0424264 -0.0450764 0.039839, + -0.044564299 -0.046090301 0.036866002, + 0.0053966301 0.057746898 -0.1715, + 0.0058778701 0.0577114 -0.1715, + 0.00616926 0.057682 -0.19149999, + 0.0053973799 0.057725899 -0.169387, + 0.00294237 0.057927798 -0.1715, + 0 0.057999998 -0.19149999, + -0.0026879699 0.057931099 -0.1715, + -0.0031320599 0.057918198 -0.1715, + -0.00268824 0.0579076 -0.16938999, + -0.000344617 0.057999 -0.1715, + 0 0.057967901 -0.16939101, + 0 0.057870999 -0.16726799, + 0.00268824 0.057908598 -0.16938999, + 0.0026880901 0.057934001 -0.1715, + 0 0.057999998 -0.1715, + 0.00268824 0.057812002 -0.167266, + 0 0.057708502 -0.165134, + -0.00268824 0.0578105 -0.167266, + -0.0053973799 0.057723999 -0.169386, + -0.0053963801 0.057744101 -0.1715, + -0.0060668602 0.057692502 -0.1715, + -0.00616926 0.057682 -0.19149999, + 0.0109154 0.056984302 -0.1715, + 0.0122731 0.056731299 -0.19149999, + 0.0087992204 0.057351299 -0.1715, + 0.0116994 0.056848299 -0.1715, + 0.0109179 0.056968201 -0.16937099, + 0.0081428103 0.057414301 -0.16937999, + 0.0081428103 0.0573183 -0.167246, + 0.0053973799 0.0576296 -0.16725899, + 0.0053973799 0.0574673 -0.16512001, + 0.00268824 0.057649601 -0.165131, + 0.00268824 0.0574205 -0.16298699, + 0 0.0574794 -0.162992, + 0 0.057182901 -0.160844, + -0.00268824 0.0574187 -0.16298699, + -0.00268824 0.057647798 -0.16513, + -0.0053973799 0.057463702 -0.16511901, + -0.0053973799 0.057626501 -0.16725799, + -0.0081428103 0.057313599 -0.167245, + -0.0081428103 0.057411399 -0.16937999, + -0.0109179 0.056964301 -0.16937, + -0.0089870598 0.057323098 -0.1715, + -0.010915 0.056982499 -0.1715, + -0.0122731 0.056731299 -0.19149999, + -0.0118856 0.056811001 -0.1715, + -0.059027899 -0.0127568 -0.19149999, + -0.057608999 -0.0187691 -0.19149999, + -0.0583965 -0.015706999 -0.1715, + 0.0109179 -0.0114012 -0.074083999, + 0.0137106 -0.010628 -0.075351998, + 0.0109179 -0.0093633803 -0.077930003, + 0.0109179 -0.0123456 -0.072136, + 0.0109179 -0.0132337 -0.070171997, + 0.0137106 -0.0125148 -0.071484998, + 0.0137106 -0.011596 -0.073426001, + 0.0165099 -0.0118381 -0.072605997, + 0.0165099 -0.010903 -0.074524999, + 0.019305199 -0.0112328 -0.073533997, + 0.019305199 -0.0102902 -0.075434998, + 0.0220857 -0.0107228 -0.074270003, + 0.0220857 -0.00977722 -0.076155998, + 0.0248404 -0.010327 -0.074818, + 0.0248404 -0.0093831597 -0.076696001, + 0.027557701 -0.0100625 -0.075191997, + 0.027557701 -0.0091234697 -0.077068999, + 0.0302257 -0.0099431304 -0.075405002, + 0.0302257 -0.00900927 -0.077289, + 0.0328326 -0.0099784704 -0.075475, + 0.0328326 -0.0090472996 -0.077372998, + 0.035366699 -0.010173 -0.075421996, + 0.035366699 -0.0092396997 -0.077339999, + 0.0378174 -0.0105246 -0.075266004, + 0.0378174 -0.0095818704 -0.077210002, + 0.040174201 -0.0110259 -0.075029001, + 0.040174201 -0.0100651 -0.077000998, + 0.0424264 -0.0116657 -0.074730001, + 0.0424264 -0.0106771 -0.076729998, + 0.044564299 -0.0124293 -0.074383996, + 0.044564299 -0.0114048 -0.076412, + 0.0465803 -0.0133001 -0.074008003, + 0.0465803 -0.0122312 -0.076056004, + 0.048467699 -0.0142587 -0.073610999, + 0.048467699 -0.0131486 -0.075686999, + 0.050219599 -0.0152971 -0.073216997, + 0.050219599 -0.0141753 -0.075369999, + 0.051830001 -0.0164361 -0.072894, + 0.051830001 -0.0153017 -0.075098999, + 0.0532961 -0.0176646 -0.072635002, + 0.0532961 -0.0165122 -0.074883997, + 0.0546159 -0.0177912 -0.07474, + 0.0518195 -0.032219801 -0.1715, + 0.052944701 -0.030228799 -0.1715, + 0.051830001 -0.032348301 -0.16356599, + 0.052960701 -0.0301986 -0.19149999, + 0.055787299 -0.016516401 -0.079260997, + 0.055787299 -0.0178534 -0.076990001, + 0.056809202 -0.019188 -0.077078998, + 0.056809202 -0.017814601 -0.079395004, + 0.0576833 -0.020532601 -0.077283002, + 0.0576833 -0.017701199 -0.081995003, + 0.058412101 -0.0204756 -0.080041997, + 0.058412101 -0.017513501 -0.084987998, + 0.058998398 -0.020315999 -0.083194003, + 0.058998398 -0.017194901 -0.088353001, + 0.059445001 -0.0199976 -0.086713001, + 0.059445001 -0.016718199 -0.092030004, + 0.059757002 -0.019492 -0.090535998, + 0.059757002 -0.0162136 -0.096092001, + 0.0599402 -0.0189442 -0.094738998, + 0.0599402 -0.0158762 -0.100591, + 0.059999999 -0.0185808 -0.099367, + 0.059999999 -0.015741 -0.105495, + 0.0599402 -0.0184421 -0.104388, + 0.0599402 -0.0158448 -0.110772, + 0.059757002 -0.0185642 -0.109771, + 0.059757002 -0.0162229 -0.116392, + 0.059445001 -0.0189768 -0.115494, + 0.059445001 -0.0169024 -0.122333, + 0.058998398 -0.0196843 -0.12154, + 0.058998398 -0.0178813 -0.12857699, + 0.058412101 -0.0206795 -0.127894, + 0.058412101 -0.0191503 -0.13511001, + 0.0576833 -0.021954 -0.13454001, + 0.0576833 -0.020701 -0.14191601, + 0.056809202 -0.0234995 -0.14146, + 0.056809202 -0.0225251 -0.148976, + 0.055787299 -0.025307801 -0.148635, + 0.055787299 -0.024614699 -0.15627301, + 0.0546159 -0.027370701 -0.156047, + 0.0546159 -0.026961699 -0.16378701, + 0.0532961 -0.0296796 -0.16367599, + 0.054265399 -0.0275982 -0.1715, + 0.054602899 -0.0268347 -0.1715, + 0.055455498 -0.024906101 -0.1715, + 0.055579402 -0.0246037 -0.19149999, + 0.0532845 -0.0295518 -0.1715, + 0.052960001 -0.0301982 -0.1715, + 0.0532961 -0.030089401 -0.155825, + 0.0546159 -0.0280647 -0.148298, + 0.055787299 -0.026283201 -0.14100599, + 0.056809202 -0.0247536 -0.13397101, + 0.0576833 -0.0234844 -0.12721001, + 0.058412101 -0.022484001 -0.120742, + 0.058998398 -0.0217604 -0.114586, + 0.059445001 -0.021320101 -0.108758, + 0.059757002 -0.021164199 -0.103272, + 0.0599402 -0.0212855 -0.098142996, + 0.059999999 -0.021653701 -0.093396999, + 0.0599402 -0.0222292 -0.089061998, + 0.059757002 -0.022770301 -0.085089996, + 0.059445001 -0.0231009 -0.081410997, + 0.058998398 -0.023243399 -0.078093998, + 0.058412101 -0.0232547 -0.075167, + 0.0576833 -0.0218737 -0.074886002, + 0.056809202 -0.0204897 -0.074727997, + 0.055787299 -0.0191228 -0.074684002, + 0.0546159 -0.0165493 -0.077001996, + 0.0532961 -0.0152935 -0.077102996, + 0.051830001 -0.014103 -0.077275999, + 0.050219599 -0.0129929 -0.077505998, + 0.048467699 -0.0119776 -0.077776, + 0.0465803 -0.0110708 -0.078075998, + 0.044564299 -0.0102815 -0.078408003, + 0.0424264 -0.0095935501 -0.078709997, + 0.040174201 -0.0090137301 -0.078957997, + 0.0378174 -0.0085555902 -0.079143003, + 0.035366699 -0.0082299802 -0.079251997, + 0.0328326 -0.00804698 -0.079265997, + 0.0302257 -0.0080125201 -0.079167999, + 0.027557701 -0.00812688 -0.078939997, + 0.0248404 -0.00838558 -0.078566998, + 0.0220857 -0.0087801404 -0.078032002, + 0.019305199 -0.0092976 -0.077322997, + 0.0165099 -0.0099201398 -0.076430999, + 0.0081428103 -0.0112528 -0.074587002, + 0.0081428103 -0.0091743097 -0.078440003, + 0.0109179 -0.0082699796 -0.079824001, + 0.0081428103 -0.0068968702 -0.082204998, + 0.0053973799 -0.0090421997 -0.078795999, + 0.0053973799 -0.0111491 -0.074937999, + 0.00268824 -0.0110882 -0.075144, + 0.00268824 -0.013005 -0.071202002, + 0 -0.0129905 -0.071268, + 0 -0.0147033 -0.067258999, + -0.00268824 -0.013005 -0.071202002, + -0.00268824 -0.011088 -0.075144999, + -0.0053973799 -0.0111487 -0.074938998, + -0.0053973799 -0.0090422602 -0.078799002, + -0.0081428103 -0.0091744 -0.078443997, + -0.054601401 -0.026833899 -0.1715, + -0.055579402 -0.0246037 -0.19149999, + -0.054184102 -0.027769901 -0.1715, + -0.055569701 -0.0245999 -0.1715, + -0.055771701 -0.0240796 -0.1715, + -0.056448001 -0.022337601 -0.1715, + -0.056793399 -0.021299999 -0.1715, + -0.055787299 -0.0242381 -0.16389599, + -0.0109179 -0.0093635004 -0.077936001, + -0.0109179 -0.010408 -0.076021001, + -0.0137106 -0.0096116997 -0.077269003, + -0.0137106 -0.0085440101 -0.079161003, + -0.0165099 -0.0088859098 -0.078330003, + -0.0165099 -0.0078015402 -0.080202997, + -0.019305199 -0.0082511296 -0.079208001, + -0.019305199 -0.0071548 -0.081065997, + -0.0220857 -0.0077255899 -0.079907998, + -0.0220857 -0.0066206399 -0.081756003, + -0.0248404 -0.0073249401 -0.080438003, + -0.0248404 -0.0062128101 -0.082282998, + -0.027557701 -0.0070599201 -0.080812998, + -0.027557701 -0.0059400499 -0.082658999, + -0.0302257 -0.0069371201 -0.081047997, + -0.0302257 -0.0058069299 -0.082898997, + -0.0328326 -0.0069593 -0.081157997, + -0.0328326 -0.00581535 -0.083017997, + -0.035366699 -0.0071259998 -0.081156999, + -0.035366699 -0.00596323 -0.08303, + -0.0378174 -0.0074308501 -0.081064001, + -0.0378174 -0.0062429998 -0.082948998, + -0.040174201 -0.0078637702 -0.080891997, + -0.040174201 -0.00664279 -0.082787998, + -0.0424264 -0.0084111299 -0.080654003, + -0.0424264 -0.0071543702 -0.082583003, + -0.044564299 -0.0090634804 -0.080388002, + -0.044564299 -0.0077952002 -0.082362004, + -0.0465803 -0.0098385103 -0.080124997, + -0.0465803 -0.0085624401 -0.082122996, + -0.048467699 -0.0107324 -0.079861, + -0.048467699 -0.0094446698 -0.081892997, + -0.050219599 -0.0117325 -0.079621002, + -0.050219599 -0.0104301 -0.081689999, + -0.051830001 -0.0128259 -0.079424001, + -0.051830001 -0.0115056 -0.081533998, + -0.0532961 -0.0139979 -0.079288997, + -0.0532961 -0.0126557 -0.081439003, + -0.0546159 -0.0152318 -0.079228997, + -0.0546159 -0.0138629 -0.081421003, + -0.055787299 -0.0165096 -0.079259999, + -0.055787299 -0.0151067 -0.081495002, + -0.056809202 -0.0178103 -0.079393998, + -0.056809202 -0.0149226 -0.083944, + -0.0576833 -0.017692899 -0.081995003, + -0.0576833 -0.0146946 -0.086787999, + -0.058412101 -0.0175038 -0.084990002, + -0.058412101 -0.0143703 -0.090003997, + -0.058998398 -0.0171907 -0.088353001, + -0.058998398 -0.0139115 -0.093540996, + -0.059445001 -0.016715201 -0.092031002, + -0.059445001 -0.0134571 -0.097471997, + -0.059757002 -0.016224399 -0.096101999, + -0.059757002 -0.0131735 -0.101841, + -0.0599402 -0.015899301 -0.100608, + -0.0599402 -0.0130709 -0.106624, + -0.059999999 -0.015772 -0.105517, + -0.059999999 -0.0131809 -0.111787, + -0.0599402 -0.015879299 -0.110795, + -0.0599402 -0.0135393 -0.117302, + -0.059757002 -0.016256601 -0.116415, + -0.059757002 -0.0141796 -0.12314, + -0.059445001 -0.016931601 -0.122355, + -0.059445001 -0.0151247 -0.12927701, + -0.058998398 -0.017905099 -0.128598, + -0.058998398 -0.0163744 -0.13569701, + -0.058412101 -0.019171201 -0.13512801, + -0.058412101 -0.0179224 -0.14238399, + -0.0576833 -0.020724701 -0.141928, + -0.0576833 -0.019760801 -0.149323, + -0.056809202 -0.022557801 -0.148981, + -0.056809202 -0.021872301 -0.156499, + -0.055787299 -0.024653399 -0.156271, + -0.0546159 -0.0269928 -0.163783, + -0.055382699 -0.0250815 -0.1715, + -0.0532961 -0.0297099 -0.163672, + -0.0546159 -0.0274086 -0.156046, + -0.055787299 -0.025339801 -0.14864001, + -0.056809202 -0.0235228 -0.141472, + -0.0576833 -0.021974601 -0.13455699, + -0.058412101 -0.020702999 -0.12791499, + -0.058998398 -0.019713299 -0.121562, + -0.059445001 -0.0190103 -0.115517, + -0.059757002 -0.0185987 -0.109794, + -0.0599402 -0.018472999 -0.104409, + -0.059999999 -0.0186039 -0.099385001, + -0.0599402 -0.018955 -0.094749004, + -0.059757002 -0.019489 -0.090536997, + -0.059445001 -0.0199933 -0.086713001, + -0.058998398 -0.0203062 -0.083195999, + -0.058412101 -0.020467101 -0.080041997, + -0.0576833 -0.020528199 -0.077280998, + -0.056809202 -0.019181 -0.077078, + -0.055787299 -0.017843399 -0.076989003, + -0.0546159 -0.0165362 -0.077001996, + -0.0532961 -0.0152779 -0.077105001, + -0.051830001 -0.014086 -0.077283002, + -0.050219599 -0.0129762 -0.077520996, + -0.048467699 -0.0119633 -0.077799, + -0.0465803 -0.0110612 -0.078091003, + -0.044564299 -0.0102741 -0.078406997, + -0.0424264 -0.0095825205 -0.078712001, + -0.040174201 -0.0089985598 -0.078964002, + -0.0378174 -0.0085380701 -0.079152003, + -0.035366699 -0.0082130004 -0.079263002, + -0.0328326 -0.0080324104 -0.079278998, + -0.0302257 -0.0080010099 -0.079181001, + -0.027557701 -0.0081184804 -0.078952998, + -0.0248404 -0.0083799604 -0.078579001, + -0.0220857 -0.0087767597 -0.078043997, + -0.019305199 -0.00929596 -0.077333003, + -0.0165099 -0.0099203102 -0.076439001, + -0.0137106 -0.0106295 -0.075358003, + -0.0109179 -0.0114004 -0.074088, + -0.0081428103 -0.0112522 -0.074588999, + -0.0053973799 -0.0130495 -0.071001999, + -0.00268824 -0.0147123 -0.067194998, + 0 -0.0162051 -0.063201003, + 0.00268824 -0.0147124 -0.067194998, + 0.0053973799 -0.0130495 -0.071001999, + 0.0137106 -0.0085451696 -0.079154, + 0.0137106 -0.00742877 -0.081026003, + 0.0165099 -0.0078040599 -0.080195002, + 0.0165099 -0.00667034 -0.082048997, + 0.019305199 -0.0071591702 -0.081056997, + 0.019305199 -0.0060121999 -0.082897, + 0.0220857 -0.0066273701 -0.081745997, + 0.0220857 -0.0054693799 -0.083577, + 0.0248404 -0.00622227 -0.082272001, + 0.0248404 -0.0050535901 -0.084099002, + 0.027557701 -0.00595228 -0.082648002, + 0.027557701 -0.0047711399 -0.084476002, + 0.0302257 -0.0058214399 -0.082888998, + 0.0302257 -0.0046246299 -0.084721997, + 0.0328326 -0.0058305599 -0.083010003, + 0.0328326 -0.0046134102 -0.084849998, + 0.035366699 -0.0059765801 -0.083024003, + 0.035366699 -0.00473487 -0.084872998, + 0.0378174 -0.0062528299 -0.082947001, + 0.0378174 -0.0049815201 -0.084801003, + 0.040174201 -0.00664947 -0.082788996, + 0.040174201 -0.0053505599 -0.084652998, + 0.0424264 -0.0071631698 -0.082569003, + 0.0424264 -0.0058549899 -0.084480003, + 0.044564299 -0.00780831 -0.082341, + 0.044564299 -0.0064905901 -0.084285997, + 0.0465803 -0.0085779298 -0.082110003, + 0.0465803 -0.00724757 -0.084083997, + 0.048467699 -0.0094606001 -0.081886001, + 0.048467699 -0.0081154201 -0.083892003, + 0.050219599 -0.0104449 -0.081688002, + 0.050219599 -0.0090825297 -0.083728001, + 0.051830001 -0.0115181 -0.081533998, + 0.051830001 -0.0101356 -0.083609998, + 0.0532961 -0.0126653 -0.081440002, + 0.0532961 -0.0112587 -0.083554, + 0.0546159 -0.0138696 -0.081422001, + 0.0546159 -0.0124324 -0.083577998, + 0.056809202 -0.0214254 -0.164015, + 0.055787299 -0.0242064 -0.1639, + 0.056512099 -0.0221588 -0.1715, + 0.056809202 -0.0218329 -0.1565, + 0.0576833 -0.019036399 -0.156729, + 0.0576833 -0.019727699 -0.14931799, + 0.058412101 -0.016926199 -0.149661, + 0.058412101 -0.0178985 -0.142372, + 0.058998398 -0.0151026 -0.142828, + 0.058998398 -0.0163533 -0.13567901, + 0.059445001 -0.013574 -0.136245, + 0.059445001 -0.0151008 -0.129256, + 0.059757002 -0.01235 -0.12992799, + 0.059757002 -0.0141502 -0.123117, + 0.0599402 -0.0114344 -0.123891, + 0.0599402 -0.0135055 -0.117279, + 0.059999999 -0.0108091 -0.118158, + 0.059999999 -0.0131464 -0.111765, + 0.0599402 -0.010448 -0.112757, + 0.0599402 -0.01304 -0.106603, + 0.059757002 -0.010318 -0.107719, + 0.059757002 -0.0131505 -0.101824, + 0.059445001 -0.0103884 -0.103074, + 0.059445001 -0.0134464 -0.097462997, + 0.058998398 -0.0106494 -0.098848, + 0.058998398 -0.0139145 -0.093539998, + 0.058412101 -0.0110929 -0.095059998, + 0.058412101 -0.0143745 -0.090003997, + 0.0576833 -0.0115473 -0.091659002, + 0.0576833 -0.0147042 -0.086786002, + 0.056809202 -0.0118991 -0.088582002, + 0.056809202 -0.0149308 -0.083944999, + 0.055787299 -0.0121752 -0.085883997, + 0.055787299 -0.015111 -0.081496, + 0.0546159 -0.0152416 -0.079230003, + 0.0532961 -0.0140106 -0.079288997, + 0.051830001 -0.0128411 -0.079421997, + 0.050219599 -0.011749 -0.079613999, + 0.048467699 -0.0107485 -0.079846002, + 0.0465803 -0.0098522203 -0.080103002, + 0.044564299 -0.0090727201 -0.080374002, + 0.0424264 -0.00841818 -0.080655001, + 0.040174201 -0.0078742197 -0.080890998, + 0.0378174 -0.00744513 -0.081058003, + 0.035366699 -0.0071423799 -0.081148997, + 0.0328326 -0.0069750599 -0.081147, + 0.0302257 -0.0069505302 -0.081036001, + 0.027557701 -0.0070704101 -0.080801003, + 0.0248404 -0.0073325201 -0.080426, + 0.0220857 -0.0077305799 -0.079897001, + 0.019305199 -0.0082540801 -0.079198003, + 0.0165099 -0.0088873096 -0.078322001, + 0.0137106 -0.00961156 -0.077261999, + 0.0555728 -0.0246011 -0.1715, + 0.055773102 -0.0240802 -0.1715, + 0.0567948 -0.0213005 -0.1715, + 0.057432801 -0.019362999 -0.1715, + 0.057608999 -0.0187691 -0.19149999, + 0.059027899 -0.0127568 -0.19149999, + 0.058398101 -0.0157074 -0.1715, + 0.059999999 -0.00195241 -0.1715, + 0.0599989 -0.0019999701 -0.1715, + 0.059980098 -0.000455125 -0.19149999, + 0.0532961 0.023413301 -0.149105, + 0.051830001 0.025501801 -0.146797, + 0.0532961 0.022178501 -0.143521, + 0.0574052 0.0154541 -0.1715, + 0.057668298 0.0145058 -0.1715, + 0.056669399 0.0177125 -0.19149999, + 0.051830001 0.027713001 -0.16055501, + 0.050219599 0.030018199 -0.158067, + 0.051830001 0.0270382 -0.155045, + 0.0532961 0.0250446 -0.160337, + 0.0532961 0.025440799 -0.165939, + 0.0546159 0.022723701 -0.16582701, + 0.0542247 0.0236843 -0.1715, + 0.054602101 0.022834299 -0.1715, + 0.055419099 0.020994 -0.1715, + 0.054336499 0.0234324 -0.1715, + 0.054342099 0.0234349 -0.19149999, + 0.0583959 0.0117813 -0.19149999, + 0.0581921 0.0126178 -0.1715, + 0.0576833 0.0143933 -0.16548499, + 0.056809202 0.017188599 -0.1656, + 0.056809202 0.0167906 -0.159661, + 0.055787299 0.0195716 -0.159889, + 0.055787299 0.018893801 -0.154047, + 0.0546159 0.0216501 -0.154385, + 0.0546159 0.020693401 -0.148661, + 0.0137106 0.020212799 -0.108946, + 0.0137106 0.0238296 -0.111224, + 0.0109179 0.020782899 -0.109389, + 0.0165099 0.0231071 -0.110715, + 0.0165099 0.0248714 -0.111946, + 0.019305199 0.023998801 -0.11136, + 0.019305199 0.025739601 -0.112676, + 0.0220857 0.0247139 -0.112019, + 0.0220857 0.0264295 -0.11342, + 0.0248404 0.025249099 -0.112698, + 0.0248404 0.026938301 -0.114184, + 0.027557701 0.0256053 -0.113404, + 0.027557701 0.0272677 -0.114976, + 0.0302257 0.025785601 -0.114145, + 0.0302257 0.027421201 -0.115802, + 0.0328326 0.0257941 -0.114925, + 0.0328326 0.0273997 -0.116672, + 0.035366699 0.025631901 -0.115758, + 0.035366699 0.027196201 -0.117598, + 0.0378174 0.025294 -0.116655, + 0.0378174 0.0268122 -0.118589, + 0.040174201 0.024782499 -0.117627, + 0.040174201 0.0262521 -0.119656, + 0.0424264 0.0241016 -0.118683, + 0.0424264 0.025520001 -0.120806, + 0.044564299 0.023256101 -0.119829, + 0.044564299 0.024620799 -0.122046, + 0.0465803 0.022253299 -0.121075, + 0.0465803 0.023561699 -0.123384, + 0.048467699 0.0211011 -0.122426, + 0.048467699 0.022350799 -0.124827, + 0.050219599 0.019807501 -0.123891, + 0.050219599 0.020996099 -0.12638099, + 0.051830001 0.018380901 -0.12547299, + 0.051830001 0.019506101 -0.128051, + 0.0532961 0.0168304 -0.127178, + 0.0532961 0.017890399 -0.129842, + 0.0546159 0.0161599 -0.131758, + 0.058998398 0.0088011101 -0.16525599, + 0.058839001 0.0097462796 -0.1715, + 0.058412101 0.0115939 -0.16537, + 0.058412101 0.0111946 -0.15920299, + 0.0576833 0.0139947 -0.15943199, + 0.0576833 0.0133148 -0.153364, + 0.056809202 0.0161117 -0.153706, + 0.056809202 0.0151527 -0.14775801, + 0.055787299 0.0179359 -0.148212, + 0.055787299 0.0166988 -0.142406, + 0.0546159 0.0194574 -0.142967, + 0.0546159 0.0179451 -0.137325, + 0.055787299 0.0151854 -0.13665099, + 0.056809202 0.0139144 -0.141839, + 0.0576833 0.0123545 -0.147302, + 0.058412101 0.0105137 -0.15302099, + 0.058998398 0.0084011601 -0.15897501, + 0.059445001 0.0060259299 -0.165142, + 0.059344199 0.0068465099 -0.1715, + 0.058983799 0.0089153098 -0.1715, + 0.059503399 0.0057039 -0.19149999, + 0.059431799 0.0061411699 -0.1715, + 0.0594863 0.0057017799 -0.1715, + 0.059706699 0.0039254399 -0.1715, + 0.059757002 0.00328033 -0.165029, + 0.059445001 0.0056253299 -0.158747, + 0.058998398 0.0077192602 -0.152679, + 0.058412101 0.0095522804 -0.146845, + 0.0576833 0.0111151 -0.141269, + 0.056809202 0.0123997 -0.13597, + 0.055787299 0.0133988 -0.13097, + 0.0546159 0.0141052 -0.126288, + 0.0532961 0.0157042 -0.124544, + 0.051830001 0.0171912 -0.122928, + 0.050219599 0.018556699 -0.121437, + 0.048467699 0.0197914 -0.120065, + 0.0465803 0.020887099 -0.118808, + 0.044564299 0.021836 -0.117657, + 0.0424264 0.022630099 -0.116607, + 0.040174201 0.023262201 -0.115648, + 0.0378174 0.023727501 -0.114773, + 0.035366699 0.024024 -0.113972, + 0.0328326 0.0241576 -0.113232, + 0.0302257 0.0241246 -0.112537, + 0.027557701 0.0239194 -0.111884, + 0.0248404 0.0235381 -0.111267, + 0.0220857 0.022978701 -0.110676, + 0.019305199 0.0222406 -0.110106, + 0.0165099 0.019504 -0.108396, + 0.0137106 0.0183888 -0.107763, + 0.0109179 0.0171471 -0.10701, + 0.0081428103 0.017570799 -0.107373, + 0.0081428103 0.0140211 -0.104825, + 0.0053973799 0.0143083 -0.105096, + 0.0053973799 0.0108577 -0.102373, + 0.00268824 0.0110203 -0.102543, + 0.00268824 0.0076881899 -0.099646002, + 0 0.00773917 -0.099705003, + 0 0.00454272 -0.096637003, + -0.00268824 0.00768875 -0.099647, + -0.00268824 0.0110212 -0.102544, + -0.0053973799 0.0108594 -0.102375, + -0.0053973799 0.0143099 -0.105097, + -0.0081428103 0.0140235 -0.104825, + -0.0081428103 0.0175722 -0.107373, + -0.0109179 0.017148999 -0.10701, + -0.0109179 0.020783801 -0.109389, + -0.0137106 0.018390501 -0.107763, + -0.0165099 0.026619799 -0.113238, + -0.019305199 0.025742801 -0.112676, + -0.0165099 0.0248744 -0.111946, + -0.019305199 0.027461501 -0.11405, + -0.0220857 0.026432199 -0.11342, + -0.0220857 0.028123099 -0.114877, + -0.0248404 0.0269401 -0.114184, + -0.0248404 0.0286026 -0.115725, + -0.027557701 0.0272686 -0.114976, + -0.027557701 0.0289039 -0.1166, + -0.0302257 0.0274227 -0.115802, + -0.0302257 0.029023301 -0.117514, + -0.0328326 0.027398201 -0.116674, + -0.0328326 0.0289558 -0.118478, + -0.035366699 0.027189801 -0.117603, + -0.035366699 0.028702101 -0.119498, + -0.0378174 0.026801201 -0.118598, + -0.0378174 0.0282655 -0.120585, + -0.040174201 0.026236599 -0.119668, + -0.040174201 0.027650399 -0.121746, + -0.0424264 0.025500501 -0.12082, + -0.0424264 0.026861301 -0.122989, + -0.044564299 0.024597701 -0.122062, + -0.044564299 0.0259031 -0.124321, + -0.0465803 0.023535799 -0.123401, + -0.0465803 0.024783401 -0.12575001, + -0.048467699 0.022322901 -0.124845, + -0.048467699 0.0235103 -0.12728199, + -0.050219599 0.0209671 -0.12639999, + -0.050219599 0.0220921 -0.128924, + -0.051830001 0.0194769 -0.128071, + -0.051830001 0.020537701 -0.13067999, + -0.0532961 0.017862 -0.129862, + -0.0532961 0.0188573 -0.13255399, + -0.0546159 0.0161331 -0.131778, + -0.0546159 0.0170621 -0.13455001, + -0.055787299 0.0151628 -0.13666999, + 0.0109179 0.024410799 -0.111633, + 0.0137106 0.0255991 -0.112434, + 0.0109179 0.0279372 -0.114082, + 0.0081428103 0.0248536 -0.111944, + 0.0081428103 0.0212173 -0.109727, + 0.0053973799 0.021520801 -0.109963, + 0.0053973799 0.0178669 -0.107627, + 0.00268824 0.0180408 -0.107776, + 0.00268824 0.0144771 -0.105256, + 0 0.0145324 -0.105308, + 0 0.0110737 -0.102598, + -0.00268824 0.0144779 -0.105256, + -0.00268824 0.0180413 -0.107776, + -0.0053973799 0.0178679 -0.107627, + -0.0053973799 0.0215213 -0.109962, + -0.0081428103 0.021217899 -0.109726, + -0.0081428103 0.0248548 -0.111944, + -0.0109179 0.024412399 -0.111633, + -0.0109179 0.027938999 -0.114082, + -0.0137106 0.027350999 -0.113706, + -0.0137106 0.0290762 -0.115038, + -0.0165099 0.028341999 -0.114589, + -0.0165099 0.030037699 -0.115998, + -0.019305199 0.029154999 -0.115481, + -0.019305199 0.030819699 -0.116968, + -0.0220857 0.029786799 -0.116389, + -0.0220857 0.0314207 -0.117955, + -0.0248404 0.0302372 -0.117318, + -0.0248404 0.031834502 -0.118967, + -0.027557701 0.030502699 -0.118279, + -0.027557701 0.0320572 -0.120013, + -0.0302257 0.0305792 -0.119282, + -0.0302257 0.0320885 -0.121102, + -0.0328326 0.030466501 -0.120334, + -0.0328326 0.031927999 -0.122241, + -0.035366699 0.030164899 -0.121444, + -0.035366699 0.031576 -0.123438, + -0.0378174 0.0296779 -0.12262, + -0.0378174 0.0310362 -0.124699, + -0.040174201 0.029009899 -0.123869, + -0.040174201 0.030313 -0.126035, + -0.0424264 0.028165501 -0.1252, + -0.0424264 0.029410999 -0.127451, + -0.044564299 0.027149601 -0.12661999, + -0.044564299 0.0283351 -0.12895501, + -0.0465803 0.0259698 -0.128135, + -0.0465803 0.0270932 -0.13055401, + -0.048467699 0.024634499 -0.12975299, + -0.048467699 0.025693599 -0.132254, + -0.050219599 0.0231521 -0.131478, + -0.050219599 0.024145899 -0.13406099, + -0.051830001 0.0215322 -0.133316, + -0.051830001 0.022459701 -0.135978, + -0.0532961 0.0197856 -0.135271, + -0.0532961 0.0206459 -0.138008, + -0.0546159 0.0179231 -0.137344, + -0.0546159 0.0187153 -0.140156, + -0.0137106 0.0238316 -0.111224, + 0.0165099 0.026617 -0.113237, + 0.019305199 0.0274592 -0.114049, + 0.0220857 0.028121499 -0.114877, + 0.0248404 0.028601799 -0.115725, + 0.027557701 0.028902501 -0.116599, + 0.0302257 0.029024599 -0.117512, + 0.0328326 0.0289618 -0.118472, + 0.035366699 0.028712399 -0.11949, + 0.0378174 0.028279999 -0.120574, + 0.040174201 0.027668901 -0.121733, + 0.0424264 0.0268832 -0.122974, + 0.044564299 0.025927801 -0.124305, + 0.0465803 0.024810201 -0.125732, + 0.048467699 0.023538399 -0.12726299, + 0.050219599 0.0221205 -0.128904, + 0.051830001 0.020565299 -0.13066, + 0.0532961 0.0188835 -0.132534, + 0.0532961 0.0198093 -0.135251, + 0.051830001 0.0215577 -0.133297, + 0.050219599 0.023178799 -0.131459, + 0.048467699 0.0246618 -0.12973399, + 0.0465803 0.025996801 -0.128117, + 0.044564299 0.0271753 -0.12660301, + 0.0424264 0.028189 -0.125185, + 0.040174201 0.029030699 -0.123855, + 0.0378174 0.0296952 -0.122607, + 0.035366699 0.0301785 -0.121434, + 0.0328326 0.030476101 -0.120326, + 0.0302257 0.0305847 -0.119277, + 0.027557701 0.030503901 -0.118277, + 0.0248404 0.030236 -0.117317, + 0.0220857 0.029786101 -0.116389, + 0.019305199 0.0291536 -0.115481, + 0.0165099 0.028340001 -0.114588, + 0.0137106 0.027348701 -0.113705, + 0.0137106 0.029074499 -0.115037, + 0.0165099 0.0300365 -0.115998, + 0.019305199 0.030819099 -0.116968, + 0.0220857 0.031419601 -0.117955, + 0.0248404 0.031835601 -0.118965, + 0.027557701 0.032062199 -0.120009, + 0.0302257 0.032097299 -0.121095, + 0.0328326 0.031940602 -0.122232, + 0.035366699 0.031592201 -0.123426, + 0.0378174 0.0310557 -0.124686, + 0.040174201 0.0303353 -0.12602, + 0.0424264 0.0294354 -0.127435, + 0.044564299 0.0283609 -0.128938, + 0.0465803 0.0271194 -0.130536, + 0.048467699 0.0257194 -0.132236, + 0.050219599 0.024170499 -0.13404199, + 0.051830001 0.022482799 -0.135959, + 0.0532961 0.0206674 -0.13799, + 0.051830001 0.024129599 -0.14134599, + 0.0583813 0.011778 -0.1715, + 0.0583972 0.0117072 -0.1715, + 0.051818501 0.0282191 -0.1715, + 0.051830001 0.028108699 -0.16604801, + 0.0528998 0.0263127 -0.1715, + 0.0514476 0.028873 -0.1715, + -0.0484627 0.033363301 -0.1715, + -0.049977001 0.031200999 -0.1715, + -0.048467699 0.033325501 -0.168883, + -0.0479904 0.034012899 -0.19149999, + -0.048288502 0.033612002 -0.1715, + 0.050219599 0.0307154 -0.166155, + 0.049871601 0.031358998 -0.1715, + 0.048467699 0.0333426 -0.16888601, + 0.048459999 0.033361301 -0.1715, + 0.0479904 0.034012899 -0.19149999, + 0.048175599 0.033764701 -0.1715, + -0.034109399 -0.0168698 -0.052278999, + -0.0328326 -0.0168161 -0.053160999, + -0.035366699 -0.016712699 -0.053201001, + -0.0137075 -0.060398601 -0.1715, + -0.0152803 -0.060021698 -0.19149999, + -0.0116065 -0.060866699 -0.1715, + -0.0152764 -0.060007598 -0.1715, + -0.016506201 -0.059669599 -0.1715, + -0.0165099 -0.059827901 -0.16243599, + 0.0167691 -0.0094999997 0.057608999, + 0.0193005 -0.0145 0.056795001, + 0.0226037 -0.0094999997 0.055578999, + 0.033491299 -0.0145 0.049775999, + 0.035362199 -0.0145 0.048461001, + 0.033494599 -0.0094999997 0.049780998, + 0.035366699 -0.0166786 0.048447002, + 0.0328326 -0.018882399 0.050140001, + 0.0332799 -0.0145 0.049924001, + 0.0328269 -0.0145 0.050211001, + 0.0307914 -0.0145 0.051497001, + 0.0302257 -0.0232081 0.051614001, + 0.028228801 -0.0145 0.052944999, + 0.030219801 -0.0145 0.051819999, + 0.0281986 -0.0094999997 0.052960999, + -0.0144335 -0.0145 -0.058238, + -0.0137785 -0.0145 -0.058382999, + -0.0137106 -0.0150023 -0.058471002, + -0.0165099 -0.0150058 -0.057741001, + -0.019305199 -0.0150102 -0.056866001, + -0.017272299 -0.0145 -0.057459999, + -0.019305199 -0.0155342 -0.057073001, + -0.0220857 -0.0155453 -0.056049, + -0.0220857 -0.0160229 -0.056403, + -0.0248404 -0.0160423 -0.055227, + -0.023467001 -0.0164023 -0.056297, + -0.023467001 -0.016617101 -0.056821998, + -0.0248404 -0.0166359 -0.05621, + -0.0220857 -0.0163891 -0.056869, + -0.019305199 -0.0160059 -0.057429999, + -0.0165099 -0.0155248 -0.057948999, + -0.019305199 -0.016567601 -0.058432002, + -0.0220857 -0.0165994 -0.057397, + -0.019305199 -0.0163655 -0.0579, + -0.0165099 -0.0163453 -0.058781002, + -0.0165099 -0.015991401 -0.058307, + -0.0137106 -0.015979299 -0.059039, + -0.0137106 -0.0155169 -0.058679, + -0.0109179 -0.0155106 -0.059266001, + -0.0109179 -0.0149995 -0.059057999, + -0.0081428103 -0.0149974 -0.059505999, + -0.0086586103 -0.0145 -0.059372, + -0.00814154 -0.0145 -0.059434, + -0.0077019902 -0.0145 -0.059487998, + -0.0077038999 -0.0094999997 -0.059503, + -0.0109157 -0.0145 -0.058986001, + -0.01156 -0.0145 -0.058876, + -0.0220857 -0.0166585 -0.057914, + -0.0220857 -0.057933301 -0.162514, + -0.021159001 -0.058127102 -0.1715, + -0.019305199 -0.0589545 -0.16247199, + 0.00267493 -0.0619325 -0.1715, + 0.0030887299 -0.061920401 -0.19149999, + 0.0030374301 -0.061923102 -0.1715, + -0.040174201 0.042524699 -0.169073, + -0.0404175 0.042344399 -0.1715, + -0.0424264 0.040386401 -0.169029, + -0.035366699 0.046429101 -0.169153, + -0.035878699 0.0460907 -0.1715, + -0.0378174 0.044541199 -0.16911399, + -0.035366699 0.046327598 -0.166794, + -0.0328326 0.0480804 -0.166866, + -0.0328326 0.047915101 -0.16453201, + -0.0302257 0.049526699 -0.16463099, + -0.0302257 0.0492962 -0.162322, + -0.027557701 0.0507637 -0.162443, + -0.027557701 0.050466701 -0.16015901, + -0.0248404 0.051787999 -0.160294, + -0.0248404 0.051423099 -0.15803599, + -0.0220857 0.0525961 -0.15818, + -0.0220857 0.0521622 -0.155946, + -0.019305199 0.053185601 -0.156092, + -0.019305199 0.052681498 -0.15388399, + -0.0165099 0.053557102 -0.154026, + -0.0165099 0.052982099 -0.151843, + -0.0137106 0.053712402 -0.151976, + -0.0137106 0.053066999 -0.149818, + -0.0109179 0.0536546 -0.149938, + -0.0109179 0.052939601 -0.147806, + -0.0081428103 0.0533875 -0.14790601, + -0.0081428103 0.0526039 -0.14579999, + -0.0053973799 0.0529171 -0.14587601, + -0.0053973799 0.0520656 -0.14379799, + -0.00268824 0.0522498 -0.143847, + -0.00268824 0.0513312 -0.14179701, + 0 0.051391799 -0.14181399, + 0 0.050406799 -0.13979299, + 0.00268824 0.0513325 -0.14179599, + 0.00268824 0.052251 -0.14384601, + 0.0053973799 0.052067999 -0.143797, + 0.0053973799 0.052919298 -0.14587399, + 0.0081428103 0.052607201 -0.145798, + 0.0081428103 0.053390499 -0.147903, + 0.0109179 0.052943699 -0.147802, + 0.0109179 0.0536585 -0.14993399, + 0.0137106 0.053071901 -0.14981399, + 0.0137106 0.053717501 -0.15197299, + 0.0165099 0.052988201 -0.151839, + 0.0165099 0.0535639 -0.15402301, + 0.019305199 0.0526894 -0.15388, + 0.019305199 0.053195 -0.15608899, + 0.0220857 0.052172899 -0.15594301, + 0.0220857 0.052608799 -0.158178, + 0.0248404 0.0514374 -0.158034, + 0.0248404 0.0518042 -0.160294, + 0.027557701 0.050484601 -0.16015901, + 0.027557701 0.0507828 -0.162443, + 0.0302257 0.0493172 -0.162323, + 0.0302257 0.049547099 -0.16463301, + 0.0328326 0.0479373 -0.164534, + 0.0328326 0.048099101 -0.166868, + 0.035366699 0.0463477 -0.166796, + 0.035366699 0.0464416 -0.169155, + 0.0378174 0.044554599 -0.169117, + 0.035726301 0.046204001 -0.1715, + 0.037813999 0.0445759 -0.1715, + 0.034765299 0.046901699 -0.19149999, + 0.032826498 0.048209999 -0.1715, + 0.030832 0.049472202 -0.1715, + 0.0328326 0.048193101 -0.169191, + 0.027551601 0.051284 -0.1715, + 0.0256411 0.052245099 -0.1715, + 0.027557701 0.051268701 -0.169254, + -0.0295441 0.050201699 -0.1715, + -0.0302257 0.049792401 -0.169223, + -0.028437899 0.050832599 -0.1715, + -0.027557701 0.051259 -0.16925301, + -0.027550699 0.051282398 -0.1715, + -0.0258127 0.052163702 -0.1715, + -0.0240272 0.052979 -0.19149999, + -0.0248338 0.052601099 -0.1715, + 0.019305199 0.054685399 -0.167138, + 0.019305199 0.054780401 -0.16932601, + 0.0165099 0.055558801 -0.167174, + 0.0165099 0.0553969 -0.164992, + 0.0137106 0.056125 -0.16503701, + 0.0137106 0.055895802 -0.162862, + 0.0109179 0.056481201 -0.16291, + 0.0109179 0.056184299 -0.160742, + 0.0081428103 0.056630202 -0.160787, + 0.0081428103 0.056265 -0.15862601, + 0.0053973799 0.056576502 -0.158665, + 0.0053973799 0.056142099 -0.15651099, + 0.00268824 0.056324799 -0.15653799, + 0.00268824 0.055820402 -0.154392, + 0 0.055879802 -0.154402, + 0 0.055304799 -0.152266, + -0.00268824 0.055819299 -0.154393, + -0.00268824 0.056323402 -0.15653799, + -0.0053973799 0.056139499 -0.15651201, + -0.0053973799 0.056573398 -0.158665, + -0.0081428103 0.056260299 -0.158627, + -0.0081428103 0.056624901 -0.160788, + -0.0109179 0.056177199 -0.160742, + -0.0109179 0.056473698 -0.16291, + -0.0137106 0.055886298 -0.162862, + -0.0137106 0.056115702 -0.16503599, + -0.0165099 0.055385798 -0.16499101, + -0.0165099 0.055549402 -0.167173, + -0.019305199 0.054674398 -0.167137, + -0.022079499 0.053771399 -0.1715, + -0.0231252 0.0533645 -0.1715, + -0.0220857 0.0537512 -0.169304, + -0.020382199 0.054432001 -0.1715, + -0.019305199 0.054773599 -0.16932499, + -0.0165055 0.0556673 -0.1715, + -0.0175901 0.0553637 -0.1715, + -0.0165099 0.0556482 -0.16934299, + -0.018242801 0.055145901 -0.1715, + -0.0137106 0.0562791 -0.16720299, + -0.0109179 0.056703001 -0.16507199, + -0.0081428103 0.0569214 -0.162946, + -0.0053973799 0.056938101 -0.16082001, + -0.00268824 0.056757402 -0.15868799, + 0 0.056384001 -0.156546, + 0.00268824 0.056759 -0.158687, + 0.0053973799 0.056941599 -0.16081899, + 0.0081428103 0.056926999 -0.162947, + 0.0109179 0.0567104 -0.16507301, + 0.0137106 0.056286901 -0.16720399, + 0.0165099 0.055654 -0.16934399, + 0.018242201 0.0551438 -0.1715, + 0.019300301 0.054794401 -0.1715, + 0.0202034 0.054496199 -0.1715, + 0.0220857 0.053759001 -0.169305, + 0.0248404 0.052588001 -0.16928101, + 0.0229499 0.053437401 -0.1715, + 0.0220857 0.0536642 -0.167096, + 0.019305199 0.054523598 -0.164939, + 0.0165099 0.055167601 -0.162802, + 0.0137106 0.055598699 -0.16068199, + 0.0109179 0.0558189 -0.158572, + 0.0081428103 0.0558304 -0.15646701, + 0.0053973799 0.055637602 -0.15436199, + 0.00268824 0.055245399 -0.152255, + 0 0.054659698 -0.15014, + -0.00268824 0.055244401 -0.152255, + -0.0053973799 0.0556354 -0.15436301, + -0.0081428103 0.0558265 -0.156468, + -0.0109179 0.055812601 -0.158572, + -0.0137106 0.055589799 -0.16068199, + -0.0165099 0.055156201 -0.162802, + -0.019305199 0.0545105 -0.164937, + -0.0220857 0.053651702 -0.16709501, + -0.0248404 0.052579299 -0.16927999, + -0.0240207 0.052964401 -0.1715, + -0.0248404 0.052479301 -0.16704699, + -0.0220857 0.053487498 -0.164874, + -0.019305199 0.054280799 -0.16272999, + -0.0165099 0.054859601 -0.16060799, + -0.0137106 0.055225201 -0.158501, + -0.0109179 0.055378798 -0.156404, + -0.0081428103 0.055322502 -0.154313, + -0.0053973799 0.055060599 -0.15222199, + -0.00268824 0.0545993 -0.15012801, + 0 0.053945001 -0.148029, + 0.00268824 0.054600202 -0.15012801, + 0.0053973799 0.055062599 -0.15222099, + 0.0081428103 0.055325799 -0.154311, + 0.0109179 0.055384099 -0.15640201, + 0.0137106 0.055233002 -0.1585, + 0.0165099 0.054870401 -0.160607, + 0.019305199 0.054294199 -0.16273101, + 0.0220857 0.053502399 -0.164876, + 0.0248404 0.052493501 -0.16704801, + 0.024834501 0.0526025 -0.1715, + 0.024020201 0.052963201 -0.1715, + 0.0240272 0.052979 -0.19149999, + 0.029552899 0.050217099 -0.19149999, + 0.0282706 0.050922401 -0.1715, + 0.0302257 0.049803101 -0.16922399, + 0.027557701 0.051174399 -0.16699401, + 0.0248404 0.052331701 -0.164804, + 0.0220857 0.053273 -0.16264699, + 0.019305199 0.053996801 -0.16051801, + 0.0165099 0.054504499 -0.15841, + 0.0137106 0.054798 -0.15631901, + 0.0109179 0.0548793 -0.154238, + 0.0081428103 0.054750599 -0.152163, + 0.0053973799 0.054417301 -0.15008999, + 0.00268824 0.053885601 -0.14801501, + 0 0.053161599 -0.145935, + -0.00268824 0.053884599 -0.14801601, + -0.0053973799 0.054415401 -0.15009101, + -0.0081428103 0.0547476 -0.152165, + -0.0109179 0.0548748 -0.15424, + -0.0137106 0.054791398 -0.156321, + -0.0165099 0.054494999 -0.15841199, + -0.019305199 0.053984199 -0.16051801, + -0.0220857 0.053257599 -0.16264699, + -0.0248404 0.0523149 -0.164802, + -0.027557701 0.0511587 -0.16699199, + -0.030994801 0.049374301 -0.1715, + -0.0328326 0.0481815 -0.16918901, + -0.0302257 0.049691699 -0.166932, + -0.027557701 0.050994001 -0.164721, + -0.0248404 0.0520849 -0.162551, + -0.0220857 0.052960899 -0.160414, + -0.019305199 0.0536195 -0.158305, + -0.0165099 0.0540612 -0.15621699, + -0.0137106 0.0542874 -0.154145, + -0.0109179 0.054299898 -0.15208299, + -0.0081428103 0.054102302 -0.15002801, + -0.0053973799 0.0537006 -0.147975, + -0.00268824 0.053101201 -0.14592101, + 0 0.052310299 -0.14386199, + 0.00268824 0.053102199 -0.14591999, + 0.0053973799 0.0537026 -0.147973, + 0.0081428103 0.0541052 -0.15002599, + 0.0109179 0.054303899 -0.152081, + 0.0137106 0.054292999 -0.15414201, + 0.0165099 0.054069199 -0.156214, + 0.019305199 0.053630602 -0.15830299, + 0.0220857 0.052975301 -0.160413, + 0.0248404 0.0521021 -0.162551, + 0.027557701 0.051012602 -0.16472299, + 0.0302257 0.049708899 -0.166934, + 0.0302194 0.049819 -0.1715, + 0.029544 0.050201401 -0.1715, + 0.033319298 0.047898199 -0.1715, + 0.034755301 0.046887498 -0.1715, + 0.0353618 0.046460599 -0.1715, + -0.034754898 0.046886999 -0.1715, + -0.033477101 0.047792401 -0.1715, + -0.034765299 0.046901699 -0.19149999, + -0.035360001 0.0464582 -0.1715, + -0.037811901 0.044573199 -0.1715, + -0.038194101 0.044273201 -0.1715, + -0.0395981 0.043055199 -0.1715, + -0.0378174 0.044439401 -0.16671599, + -0.035366699 0.046162002 -0.164424, + -0.0328326 0.047684401 -0.162191, + -0.0302257 0.048999 -0.16001, + -0.027557701 0.050101601 -0.157874, + -0.0248404 0.050989099 -0.155779, + -0.0220857 0.051658001 -0.153717, + -0.019305199 0.052106299 -0.151683, + -0.0165099 0.052336499 -0.14967, + -0.0137106 0.052351899 -0.14767499, + -0.0109179 0.052155901 -0.14569201, + -0.0081428103 0.051752299 -0.14371599, + -0.0053973799 0.051146898 -0.141745, + -0.00268824 0.050346199 -0.13977499, + 0 0.0493562 -0.137804, + 0.00268824 0.0503476 -0.13977399, + 0.0053973799 0.051149599 -0.141743, + 0.0081428103 0.051755901 -0.143713, + 0.0109179 0.0521603 -0.145688, + 0.0137106 0.052356999 -0.14767, + 0.0165099 0.0523424 -0.149665, + 0.019305199 0.052113499 -0.151678, + 0.0220857 0.051667001 -0.153713, + 0.0248404 0.051001102 -0.15577599, + 0.027557701 0.0501175 -0.15787201, + 0.0302257 0.0490187 -0.160009, + 0.0328326 0.047707099 -0.162192, + 0.035366699 0.046185799 -0.164426, + 0.0378174 0.0444609 -0.166719, + 0.040174201 0.0425389 -0.169075, + 0.039599199 0.043056302 -0.1715, + 0.040172402 0.042562202 -0.1715, + 0.0402769 0.042472102 -0.1715, + 0.0424264 0.040401399 -0.16903099, + 0.040174201 0.042445298 -0.16663601, + 0.0378174 0.044298898 -0.16430999, + 0.035366699 0.045955501 -0.162048, + 0.0328326 0.047408301 -0.159844, + 0.0302257 0.0486512 -0.157692, + 0.027557701 0.0496809 -0.155587, + 0.0248404 0.050494902 -0.153521, + 0.0220857 0.051090799 -0.15149, + 0.019305199 0.051467501 -0.149487, + 0.0165099 0.051627401 -0.147507, + 0.0137106 0.0515735 -0.14554401, + 0.0109179 0.0513089 -0.143594, + 0.0081428103 0.050837401 -0.141654, + 0.0053973799 0.0501647 -0.139718, + 0.00268824 0.049297001 -0.137784, + 0 0.048241001 -0.13585, + -0.00268824 0.0492955 -0.137785, + -0.0053973799 0.050161801 -0.13971999, + -0.0081428103 0.0508334 -0.14165699, + -0.0109179 0.051304098 -0.14359801, + -0.0137106 0.051567901 -0.145549, + -0.0165099 0.051621199 -0.147512, + -0.019305199 0.051460601 -0.14949299, + -0.0220857 0.0510826 -0.15149599, + -0.0248404 0.050484698 -0.15352701, + -0.027557701 0.0496675 -0.155591, + -0.0302257 0.048633799 -0.157695, + -0.0328326 0.0473869 -0.15984499, + -0.035366699 0.045931 -0.162047, + -0.0378174 0.044273399 -0.164308, + -0.040174201 0.0424225 -0.166633, + -0.042543601 0.0403088 -0.1715, + -0.044022799 0.038746599 -0.1715, + -0.044564299 0.038133699 -0.168982, + -0.0424264 0.040283799 -0.166545, + -0.040174201 0.042256199 -0.164184, + -0.0378174 0.044042099 -0.161893, + -0.035366699 0.045633301 -0.159666, + -0.0328326 0.047021501 -0.157498, + -0.0302257 0.048199501 -0.15538201, + -0.027557701 0.049162999 -0.153312, + -0.0248404 0.049909201 -0.151281, + -0.0220857 0.050436702 -0.149285, + -0.019305199 0.0507451 -0.14731599, + -0.0165099 0.0508371 -0.145371, + -0.0137106 0.050715901 -0.143443, + -0.0109179 0.050384998 -0.14153001, + -0.0081428103 0.049848098 -0.139625, + -0.0053973799 0.049111001 -0.13772599, + -0.00268824 0.0481802 -0.135829, + 0 0.047063202 -0.13393199, + 0.00268824 0.048181798 -0.135828, + 0.0053973799 0.049114101 -0.137724, + 0.0081428103 0.049852502 -0.139622, + 0.0109179 0.0503904 -0.141525, + 0.0137106 0.0507221 -0.14343899, + 0.0165099 0.050843801 -0.145365, + 0.019305199 0.050752301 -0.14731, + 0.0220857 0.050444599 -0.149278, + 0.0248404 0.049918398 -0.15127499, + 0.027557701 0.049174301 -0.15330601, + 0.0302257 0.0482141 -0.155377, + 0.0328326 0.047040399 -0.15749501, + 0.035366699 0.045656402 -0.159665, + 0.0378174 0.044068299 -0.16189399, + 0.040174201 0.0422832 -0.164186, + 0.0424264 0.040307902 -0.166549, + 0.044564299 0.038149402 -0.16898499, + 0.044024602 0.038748302 -0.1715, + 0.044440001 0.038312301 -0.1715, + 0.044033099 0.0387564 -0.19149999, + 0.044561401 0.038171701 -0.1715, + 0.0463636 0.036084399 -0.1715, + 0.0465803 0.035792999 -0.168937, + 0.044564299 0.038056001 -0.166456, + 0.0424264 0.040145699 -0.164055, + 0.040174201 0.042052399 -0.16172899, + 0.0378174 0.043768801 -0.159472, + 0.035366699 0.045288 -0.15728, + 0.0328326 0.046603002 -0.155147, + 0.0302257 0.0477072 -0.15306599, + 0.027557701 0.048597399 -0.151033, + 0.0248404 0.0492719 -0.149039, + 0.0220857 0.049729198 -0.147081, + 0.019305199 0.0499685 -0.145151, + 0.0165099 0.0499922 -0.143245, + 0.0137106 0.049803399 -0.141357, + 0.0109179 0.0494054 -0.139484, + 0.0081428103 0.048801798 -0.137621, + 0.0053973799 0.047998801 -0.135764, + 0.00268824 0.047003999 -0.13391, + 0 0.045825299 -0.132055, + -0.00268824 0.047002401 -0.133911, + -0.0053973799 0.047995701 -0.135766, + -0.0081428103 0.048797201 -0.137624, + -0.0109179 0.049399599 -0.139488, + -0.0137106 0.0497967 -0.14136299, + -0.0165099 0.049984898 -0.143251, + -0.019305199 0.049960699 -0.14515799, + -0.0220857 0.049720999 -0.14708801, + -0.0248404 0.049263 -0.149047, + -0.027557701 0.048587199 -0.15104, + -0.0302257 0.047694799 -0.153073, + -0.0328326 0.046587002 -0.15515199, + -0.035366699 0.045267701 -0.15728299, + -0.0378174 0.043744199 -0.159473, + -0.040174201 0.042024601 -0.16172799, + -0.0424264 0.0401171 -0.16405199, + -0.044564299 0.038030699 -0.166453, + -0.0465803 0.0357766 -0.168934, + -0.046578299 0.035815801 -0.1715, + -0.047982302 0.034006599 -0.1715, + -0.0464839 0.035937399 -0.1715, + -0.044567399 0.0381715 -0.1715, + -0.044033099 0.0387564 -0.19149999, + -0.042423699 0.040423598 -0.1715, + -0.039609101 0.043067899 -0.19149999, + -0.040169802 0.0425593 -0.1715, + -0.032825101 0.048207901 -0.1715, + -0.029552899 0.050217099 -0.19149999, + -0.0302184 0.049817201 -0.1715, + -0.0182469 0.055158101 -0.19149999, + -0.0192999 0.054793101 -0.1715, + -0.0147556 0.056157298 -0.1715, + -0.0137106 0.056377601 -0.169358, + -0.0109179 0.056866199 -0.167227, + -0.0081428103 0.057150599 -0.16509999, + -0.0053973799 0.0572345 -0.162972, + -0.00268824 0.057122201 -0.16083799, + 0 0.056818001 -0.158695, + 0.00268824 0.057123899 -0.16083799, + 0.0053973799 0.057238299 -0.162972, + 0.0081428103 0.057156101 -0.16509999, + 0.0109179 0.056872401 -0.167228, + 0.0137106 0.056382399 -0.169359, + 0.0137073 0.056397699 -0.1715, + 0.0122706 0.0567201 -0.1715, + 0.0145714 0.056203701 -0.1715, + 0.016505901 0.0556687 -0.1715, + 0.0182469 0.055158101 -0.19149999, + 0.017408401 0.055419099 -0.1715, + 0.022080099 0.053772699 -0.1715, + 0.019300099 -0.058793701 -0.1715, + 0.019305199 -0.058943499 -0.16247299, + 0.0174994 -0.059391402 -0.1715, + 0.020292999 -0.058464099 -0.1715, + 0.021165101 -0.058143001 -0.19149999, + 0.0165057 -0.0596679 -0.1715, + 0.0152803 -0.060021698 -0.19149999, + 0.0424264 -0.044552799 -0.163065, + 0.042476799 -0.044376001 -0.1715, + 0.044564299 -0.0422998 -0.163157, + 0.044564299 -0.042713098 -0.154792, + 0.058998398 -0.0376455 -0.078562997, + 0.058998398 -0.035975799 -0.081658997, + 0.059445001 -0.036444899 -0.077086002, + 0.058412101 -0.038797401 -0.080140002, + 0.058412101 -0.035473201 -0.086552002, + 0.0576833 -0.0382948 -0.085155003, + 0.0576833 -0.035192199 -0.091852002, + 0.056809202 -0.0380047 -0.090580001, + 0.056809202 -0.035139099 -0.097544, + 0.055787299 -0.0379331 -0.096399002, + 0.055787299 -0.035316799 -0.10361, + 0.0546159 -0.038082302 -0.102593, + 0.0546159 -0.035726398 -0.110031, + 0.0532961 -0.038452301 -0.109142, + 0.0532961 -0.036366101 -0.116787, + 0.051830001 -0.039040901 -0.116025, + 0.051830001 -0.037227798 -0.123856, + 0.050219599 -0.039840098 -0.123218, + 0.050219599 -0.038302299 -0.13121501, + 0.048467699 -0.040840499 -0.13069899, + 0.048467699 -0.039580099 -0.13884, + 0.0465803 -0.042033799 -0.138441, + 0.0465803 -0.041053001 -0.146708, + 0.044564299 -0.043411899 -0.146419, + 0.0424264 -0.044966899 -0.154607, + 0.040174201 -0.0466915 -0.162977, + 0.0418665 -0.044958498 -0.1715, + 0.040347401 -0.046408199 -0.1715, + 0.040171102 -0.046560701 -0.1715, + 0.038121 -0.0483335 -0.1715, + 0.037236601 -0.049047198 -0.19149999, + 0.0378129 -0.0485745 -0.1715, + 0.058998398 -0.040776402 -0.072311997, + 0.058998398 -0.039247502 -0.075444996, + 0.059445001 -0.039443601 -0.070949003, + 0.058412101 -0.0420679 -0.073794998, + 0.058412101 -0.040468499 -0.076978996, + 0.0576833 -0.043298401 -0.075392, + 0.0576833 -0.0416256 -0.078616001, + 0.056809202 -0.044449799 -0.077095002, + 0.056809202 -0.041112401 -0.083759002, + 0.055787299 -0.043915 -0.082370996, + 0.055787299 -0.040802401 -0.089313999, + 0.0546159 -0.043574199 -0.088059999, + 0.0546159 -0.0407013 -0.095264003, + 0.0532961 -0.0434318 -0.094145, + 0.0532961 -0.040810201 -0.10159, + 0.051830001 -0.0434887 -0.100605, + 0.051830001 -0.0411289 -0.108269, + 0.050219599 -0.043744098 -0.107416, + 0.050219599 -0.041654602 -0.11528, + 0.048467699 -0.044195399 -0.114557, + 0.048467699 -0.042379498 -0.122599, + 0.0465803 -0.044835299 -0.122, + 0.0465803 -0.043295201 -0.1302, + 0.044564299 -0.045655798 -0.12972, + 0.044564299 -0.044393498 -0.13805699, + 0.0424264 -0.046648599 -0.13768899, + 0.0424264 -0.0456663 -0.146144, + 0.040174201 -0.0478062 -0.145882, + 0.040174201 -0.0471063 -0.154432, + 0.0378174 -0.049123801 -0.154267, + 0.0378174 -0.048708402 -0.162894, + 0.035366699 -0.050596699 -0.162816, + 0.037225999 -0.049033701 -0.1715, + 0.035360798 -0.0504594 -0.1715, + 0.0358027 -0.050147299 -0.1715, + 0.0322018 -0.052626502 -0.19149999, + 0.033398401 -0.0518452 -0.1715, + 0.032825802 -0.0522089 -0.1715, + 0.059757002 -0.0366886 -0.072713003, + 0.059757002 -0.038089398 -0.069711, + 0.0599402 -0.036727902 -0.068603002, + 0.059999999 -0.035354599 -0.067645997, + 0.059999999 -0.034063701 -0.070478, + 0.0599402 -0.033972301 -0.066838004, + 0.0599402 -0.033969998 -0.074453004, + 0.059757002 -0.033672199 -0.078708999, + 0.059445001 -0.033172101 -0.083168998, + 0.058998398 -0.032658301 -0.087945998, + 0.058412101 -0.0323755 -0.093125999, + 0.0576833 -0.032330301 -0.098695002, + 0.056809202 -0.032525498 -0.104636, + 0.055787299 -0.032963 -0.110932, + 0.0546159 -0.0336418 -0.117563, + 0.0532961 -0.034554299 -0.124508, + 0.051830001 -0.035691202 -0.13174599, + 0.050219599 -0.0370428 -0.139254, + 0.048467699 -0.038600001 -0.147008, + 0.0465803 -0.0403549 -0.154985, + 0.044562999 -0.042173099 -0.1715, + 0.0460645 -0.0404284 -0.1715, + 0.0465803 -0.039942302 -0.16325399, + 0.048467699 -0.037902702 -0.155185, + 0.050219599 -0.0360636 -0.147319, + 0.051830001 -0.034432799 -0.139679, + 0.0532961 -0.033018898 -0.13228901, + 0.0546159 -0.0318316 -0.125173, + 0.055787299 -0.030880099 -0.11835, + 0.056809202 -0.030173801 -0.111842, + 0.0576833 -0.029719399 -0.105668, + 0.058412101 -0.029517399 -0.099848002, + 0.058998398 -0.029565699 -0.094397001, + 0.059445001 -0.029861201 -0.089331999, + 0.059757002 -0.0303983 -0.084663004, + 0.0599402 -0.0309362 -0.080310002, + 0.059999999 -0.0312723 -0.076180004, + 0.0599402 -0.0313995 -0.072353996, + 0.059757002 -0.031338099 -0.068884999, + 0.059757002 -0.032550901 -0.066166997, + 0.059445001 -0.029913001 -0.068320997, + 0.059445001 -0.0310729 -0.065650001, + 0.058998398 -0.0284418 -0.067906998, + 0.058998398 -0.029556001 -0.065284997, + 0.058412101 -0.026946999 -0.067635998, + 0.058412101 -0.028021401 -0.065063998, + 0.0576833 -0.0254483 -0.067497998, + 0.0576833 -0.026487799 -0.064978004, + 0.056809202 -0.0239638 -0.067483999, + 0.056809202 -0.024973201 -0.065015003, + 0.055787299 -0.023495199 -0.065165997, + 0.055787299 -0.022510801 -0.067581996, + 0.0546159 -0.0220729 -0.065426998, + 0.055787299 -0.0214532 -0.069977, + 0.056809202 -0.022879001 -0.069927998, + 0.0576833 -0.024331801 -0.069991, + 0.058412101 -0.025793999 -0.070178002, + 0.058998398 -0.027246701 -0.070497997, + 0.059445001 -0.0286685 -0.07096, + 0.059757002 -0.028714599 -0.074243002, + 0.0599402 -0.028574601 -0.077907003, + 0.059999999 -0.0282213 -0.081899002, + 0.0599402 -0.027661201 -0.086136997, + 0.059757002 -0.027093999 -0.090703003, + 0.059445001 -0.0267736 -0.095660999, + 0.058998398 -0.026711199 -0.100998, + 0.058412101 -0.0269092 -0.106702, + 0.0576833 -0.027369799 -0.112756, + 0.056809202 -0.028092699 -0.119144, + 0.055787299 -0.029071299 -0.125846, + 0.0546159 -0.0302974 -0.132843, + 0.0532961 -0.031761602 -0.14011399, + 0.051830001 -0.0334545 -0.14763799, + 0.050219599 -0.035367101 -0.155393, + 0.048467699 -0.0374908 -0.16335499, + 0.048232201 -0.0376883 -0.1715, + 0.046576701 -0.039814599 -0.1715, + 0.0460728 -0.040435601 -0.19149999, + 0.046423901 -0.040010799 -0.1715, + 0.044503901 -0.042241801 -0.1715, + 0.041876599 -0.044969101 -0.19149999, + 0.0424252 -0.044425201 -0.1715, + -0.0248404 -0.056762502 -0.162562, + -0.0228623 -0.0574736 -0.1715, + -0.0248404 -0.057183798 -0.15360799, + -0.027557701 -0.055864502 -0.153716, + -0.027557701 -0.0565635 -0.144815, + -0.0302257 -0.0550972 -0.144995, + -0.0302257 -0.056077302 -0.136163, + -0.0328326 -0.0544657 -0.136426, + -0.0328326 -0.055730101 -0.127684, + -0.035366699 -0.053975999 -0.128041, + -0.035366699 -0.055522699 -0.119409, + -0.0378174 -0.053632099 -0.119871, + -0.0378174 -0.055457398 -0.111369, + -0.040174201 -0.053436998 -0.111945, + -0.040174201 -0.055537 -0.103594, + -0.0424264 -0.0533932 -0.104294, + -0.0424264 -0.055762701 -0.096116997, + -0.044564299 -0.053502601 -0.096949004, + -0.044564299 -0.056133799 -0.088965997, + -0.0465803 -0.053766299 -0.089937001, + -0.0465803 -0.056650002 -0.082167998, + -0.048467699 -0.054184701 -0.083283, + -0.048467699 -0.057310801 -0.075749002, + -0.050219599 -0.054756701 -0.077013999, + -0.050219599 -0.058114301 -0.069735996, + -0.051830001 -0.055480398 -0.071153998, + -0.051830001 -0.057161599 -0.067613997, + -0.0532961 -0.0544645 -0.069127001, + -0.0532961 -0.056048501 -0.065609999, + -0.0546159 -0.053304199 -0.067216001, + -0.0546159 -0.0547961 -0.063732997, + -0.055787299 -0.052020699 -0.065430999, + -0.055787299 -0.0534258 -0.061994001, + -0.056809202 -0.050635502 -0.063780002, + -0.056809202 -0.051959399 -0.060401, + -0.0576833 -0.049169499 -0.062272001, + -0.0576833 -0.050417501 -0.058961999, + -0.058412101 -0.047643099 -0.060913999, + -0.058412101 -0.048821699 -0.057684001, + -0.058998398 -0.046077799 -0.059712, + -0.058998398 -0.0471977 -0.056554999, + -0.059445001 -0.044499401 -0.058651999, + -0.059445001 -0.045552999 -0.055542, + -0.059757002 -0.042915199 -0.057696, + -0.059757002 -0.043899499 -0.054637, + -0.0599402 -0.041331001 -0.056839999, + -0.0599402 -0.042252399 -0.053835001, + -0.059999999 -0.039741099 -0.056097001, + -0.059999999 -0.0406055 -0.053146999, + -0.0599402 -0.038134702 -0.055484001, + -0.0599402 -0.038947999 -0.052593, + -0.059757002 -0.036502 -0.055022001, + -0.059757002 -0.037269998 -0.052191, + -0.059445001 -0.034838799 -0.054726001, + -0.059445001 -0.035568599 -0.051956002, + -0.058998398 -0.0331623 -0.054590002, + -0.058998398 -0.033863898 -0.051874999, + -0.058412101 -0.031496499 -0.054595999, + -0.058412101 -0.0321646 -0.051998001, + -0.0576833 -0.0298489 -0.054791, + -0.0576833 -0.0304197 -0.052276, + -0.056809202 -0.028172201 -0.055126999, + -0.056809202 -0.0286428 -0.052650999, + -0.055787299 -0.0264803 -0.055548001, + -0.055787299 -0.0268672 -0.053130999, + -0.0546159 -0.0248057 -0.056058001, + -0.0546159 -0.025124799 -0.053709999, + -0.0532961 -0.0231796 -0.056648999, + -0.0532961 -0.023449199 -0.054379001, + -0.051830001 -0.021633999 -0.057310998, + -0.051830001 -0.021872399 -0.055124, + -0.050219599 -0.0201985 -0.058026999, + -0.050219599 -0.0204257 -0.055920999, + -0.048467699 -0.0189014 -0.058773998, + -0.048467699 -0.019135199 -0.056745999, + -0.0465803 -0.017765701 -0.059526, + -0.0465803 -0.018022001 -0.057567999, + -0.044564299 -0.0168094 -0.060253002, + -0.044564299 -0.017100699 -0.058352999, + -0.0424264 -0.016044 -0.060922999, + -0.0424264 -0.0163799 -0.059066001, + -0.040174201 -0.0154748 -0.061501, + -0.040174201 -0.015858799 -0.059673, + -0.0378174 -0.0150976 -0.061957002, + -0.0378174 -0.0155227 -0.060143001, + -0.035366699 -0.0148961 -0.062263001, + -0.035366699 -0.0153653 -0.060449, + -0.0328326 -0.0148619 -0.062392998, + -0.0328326 -0.0153652 -0.060568999, + -0.0302257 -0.0149742 -0.06233, + -0.0302257 -0.0154815 -0.060469002, + -0.027557701 -0.0151929 -0.062047999, + -0.027557701 -0.015719799 -0.060148999, + -0.0248404 -0.0155196 -0.061549, + -0.0248404 -0.0160549 -0.059617002, + -0.0220857 -0.0159296 -0.060839999, + -0.0220857 -0.016467899 -0.058876999, + -0.019305199 -0.0164041 -0.059925999, + -0.019305199 -0.016540401 -0.059427999, + -0.0165099 -0.0164956 -0.060322002, + -0.0165099 -0.016581699 -0.059845001, + -0.0137106 -0.016552201 -0.060587, + -0.0137106 -0.016518099 -0.060056999, + -0.0109179 -0.0165001 -0.060651001, + -0.0109179 -0.016315199 -0.060107, + -0.0081428103 -0.016305 -0.060555998, + -0.0081428103 -0.0159622 -0.060075998, + -0.0053973799 -0.015957 -0.060387999, + -0.0053973799 -0.0155025 -0.060026001, + -0.00268824 -0.0155006 -0.060208999, + 0 -0.0155 -0.060268, + -0.00268824 -0.0159541 -0.060571998, + -0.0053973799 -0.016298 -0.060869999, + -0.0081428103 -0.016486499 -0.061103001, + -0.0109179 -0.0165287 -0.061184, + -0.0137106 -0.0164582 -0.061067, + -0.0165099 -0.016349399 -0.060823001, + -0.019305199 -0.0158203 -0.061905999, + -0.0220857 -0.0153419 -0.062790997, + -0.0248404 -0.0149331 -0.063469999, + -0.027557701 -0.0146182 -0.063933998, + -0.0302257 -0.0143993 -0.064181, + -0.0328326 -0.0143145 -0.064230002, + -0.035366699 -0.0143849 -0.064094998, + -0.0378174 -0.0146212 -0.063796997, + -0.040174201 -0.0150409 -0.063362002, + -0.0424264 -0.0156506 -0.062820002, + -0.044564299 -0.0164489 -0.062199999, + -0.0465803 -0.0174274 -0.061531998, + -0.048467699 -0.0185712 -0.060849, + -0.050219599 -0.019860299 -0.060176, + -0.051830001 -0.0212697 -0.059535, + -0.0532961 -0.0227722 -0.058945, + -0.0546159 -0.0243378 -0.058417, + -0.055787299 -0.0259366 -0.057962999, + -0.056809202 -0.027536601 -0.057581, + -0.0576833 -0.029123399 -0.057325002, + -0.058412101 -0.030740799 -0.057241999, + -0.058998398 -0.032381501 -0.057287998, + -0.059445001 -0.034023199 -0.057482999, + -0.059757002 -0.035644799 -0.057840001, + -0.0599402 -0.037229799 -0.058359001, + -0.059999999 -0.038782299 -0.059027001, + -0.0599402 -0.040312201 -0.059820998, + -0.059757002 -0.041829798 -0.060727, + -0.059445001 -0.043351099 -0.061728001, + -0.058998398 -0.044875398 -0.062862001, + -0.058412101 -0.046375498 -0.064145997, + -0.0576833 -0.047830399 -0.065576002, + -0.056809202 -0.0492194 -0.067143999, + -0.055787299 -0.0505221 -0.068843998, + -0.0546159 -0.051717602 -0.070667997, + -0.0532961 -0.052784801 -0.072605997, + -0.051830001 -0.052129202 -0.078316003, + -0.050219599 -0.051635399 -0.084436998, + -0.048467699 -0.0513044 -0.090947002, + -0.0465803 -0.0511375 -0.097819999, + -0.044564299 -0.051134799 -0.105032, + -0.0424264 -0.051294498 -0.112556, + -0.040174201 -0.051612701 -0.120365, + -0.0378174 -0.052086201 -0.128426, + -0.035366699 -0.0527124 -0.136712, + -0.0328326 -0.053486399 -0.145192, + -0.0302257 -0.054398902 -0.153836, + -0.027557701 -0.055443399 -0.162616, + -0.0255554 -0.056285601 -0.1715, + -0.0275521 -0.055284999 -0.1715, + -0.026817599 -0.055653099 -0.1715, + -0.026825599 -0.0556692 -0.19149999, + -0.032192402 -0.052611601 -0.1715, + -0.032827299 -0.052211199 -0.1715, + -0.0322018 -0.052626502 -0.19149999, + -0.037815198 -0.048577402 -0.1715, + -0.0372269 -0.0490348 -0.1715, + -0.0378174 -0.0487299 -0.162891, + -0.037236601 -0.049047198 -0.19149999, + -0.030220101 -0.0538201 -0.1715, + -0.035362698 -0.050462 -0.1715, + -0.041876599 -0.044969101 -0.19149999, + -0.040173799 -0.046563901 -0.1715, + -0.041868102 -0.0449601 -0.1715, + -0.042342398 -0.044510201 -0.1715, + -0.042424399 -0.0444245 -0.1715, + -0.044376299 -0.042382501 -0.1715, + -0.0424264 -0.044576999 -0.16306099, + -0.058998398 -0.0376436 -0.078562997, + -0.059445001 -0.0364406 -0.077086002, + -0.058998398 -0.035972901 -0.081660002, + -0.058412101 -0.038794398 -0.080141, + -0.058412101 -0.035483699 -0.086562, + -0.0576833 -0.038305201 -0.085164003, + -0.0576833 -0.035214402 -0.091868997, + -0.056809202 -0.038026601 -0.090595998, + -0.056809202 -0.035168499 -0.097563997, + -0.055787299 -0.0379619 -0.096418999, + -0.055787299 -0.0353489 -0.103631, + -0.0546159 -0.038113698 -0.102614, + -0.0546159 -0.035757199 -0.110052, + -0.0532961 -0.038482402 -0.109162, + -0.0532961 -0.036392201 -0.116807, + -0.051830001 -0.0390664 -0.116044, + -0.051830001 -0.037248701 -0.123874, + -0.050219599 -0.039860301 -0.123236, + -0.050219599 -0.038320199 -0.13123, + -0.048467699 -0.0408579 -0.130713, + -0.048467699 -0.0396 -0.138851, + -0.0465803 -0.042052999 -0.138451, + -0.0465803 -0.0410797 -0.14671201, + -0.044564299 -0.0434375 -0.146423, + -0.044564299 -0.0427441 -0.15479, + -0.0424264 -0.044996299 -0.154606, + -0.040174201 -0.046714399 -0.162974, + -0.0402066 -0.046535701 -0.1715, + -0.037974101 -0.048453901 -0.1715, + -0.040174201 -0.047134101 -0.154431, + -0.0424264 -0.0456906 -0.146147, + -0.044564299 -0.044411801 -0.13806599, + -0.0465803 -0.043311901 -0.13021301, + -0.048467699 -0.042399 -0.122616, + -0.050219599 -0.0416792 -0.115299, + -0.051830001 -0.041158099 -0.108289, + -0.0532961 -0.040840901 -0.10161, + -0.0546159 -0.0407295 -0.095284, + -0.055787299 -0.040823799 -0.089330003, + -0.056809202 -0.0411226 -0.083768003, + -0.0576833 -0.041622799 -0.078616999, + -0.058412101 -0.0404667 -0.076978996, + -0.058998398 -0.0392433 -0.075446002, + -0.059445001 -0.039433699 -0.070951, + -0.059757002 -0.036678601 -0.072714001, + -0.059757002 -0.039404199 -0.066712998, + -0.0599402 -0.036719199 -0.068603002, + -0.0576833 -0.0283134 -0.059898999, + -0.056809202 -0.0267538 -0.060049001, + -0.0576833 -0.027429599 -0.062451001, + -0.058412101 -0.029908501 -0.059866, + -0.058412101 -0.0289963 -0.062476002, + -0.058998398 -0.031517699 -0.059971999, + -0.058998398 -0.0305709 -0.062638998, + -0.059445001 -0.0331214 -0.060226001, + -0.059445001 -0.032134201 -0.06295, + -0.059757002 -0.0346989 -0.060639001, + -0.059757002 -0.033665098 -0.063415997, + -0.0599402 -0.0362336 -0.061213002, + -0.0599402 -0.035146501 -0.064039998, + -0.059999999 -0.037729301 -0.061930999, + -0.059999999 -0.036581598 -0.064805001, + -0.0599402 -0.039195601 -0.062774003, + -0.059757002 -0.040653601 -0.063722, + -0.059445001 -0.042125098 -0.064797997, + -0.058998398 -0.042218599 -0.069168001, + -0.058998398 -0.043588199 -0.066016003, + -0.058412101 -0.045021102 -0.067373998, + -0.058412101 -0.043582901 -0.070592001, + -0.0576833 -0.046403199 -0.068866998, + -0.0576833 -0.044890899 -0.072140001, + -0.056809202 -0.047713999 -0.070487998, + -0.056809202 -0.046122201 -0.073807001, + -0.055787299 -0.048932999 -0.072229996, + -0.055787299 -0.047256202 -0.075583003, + -0.0546159 -0.050039399 -0.074083999, + -0.0546159 -0.046701498 -0.081005, + -0.0532961 -0.049440201 -0.079648003, + -0.0532961 -0.046328802 -0.086838998, + -0.051830001 -0.049012899 -0.085624002, + -0.051830001 -0.046139698 -0.093065001, + -0.050219599 -0.0487586 -0.091991, + -0.050219599 -0.0461349 -0.099661, + -0.048467699 -0.0486781 -0.098724999, + -0.048467699 -0.0463138 -0.106606, + -0.0465803 -0.0487714 -0.105804, + -0.0465803 -0.046675399 -0.113874, + -0.044564299 -0.0490373 -0.1132, + -0.044564299 -0.047215 -0.121439, + -0.0424264 -0.049471099 -0.120888, + -0.0424264 -0.047927 -0.129274, + -0.040174201 -0.0500676 -0.128838, + -0.040174201 -0.048805799 -0.13734899, + -0.0378174 -0.050823499 -0.13702001, + -0.0378174 -0.049846102 -0.145638, + -0.035366699 -0.051734101 -0.14540701, + -0.035366699 -0.0510372 -0.154112, + -0.0328326 -0.052788801 -0.15396801, + -0.0302257 -0.053978 -0.16267601, + -0.0328326 -0.052368201 -0.162742, + -0.030750699 -0.053520799 -0.1715, + -0.035366699 -0.050616801 -0.16281401, + -0.0332404 -0.051950701 -0.1715, + -0.0378174 -0.049150001 -0.154266, + -0.040174201 -0.0478293 -0.14588501, + -0.0424264 -0.046666 -0.13769799, + -0.044564299 -0.045671701 -0.129733, + -0.0465803 -0.044854101 -0.122016, + -0.048467699 -0.044219099 -0.114575, + -0.050219599 -0.0437725 -0.107435, + -0.051830001 -0.043518599 -0.100624, + -0.0532961 -0.043459401 -0.094163999, + -0.0546159 -0.043595199 -0.088076003, + -0.055787299 -0.043924998 -0.082379997, + -0.056809202 -0.044447001 -0.077096, + -0.0576833 -0.043296501 -0.075392, + -0.058412101 -0.042063698 -0.073794998, + -0.058998398 -0.040769201 -0.072313003, + -0.035650201 -0.050260399 -0.1715, + -0.028186901 -0.0549669 -0.1715, + -0.055787299 -0.025236599 -0.060355, + -0.0546159 -0.023721701 -0.060773, + -0.0532961 -0.0222244 -0.061248001, + -0.051830001 -0.0207757 -0.061779, + -0.050219599 -0.0194037 -0.062353998, + -0.048467699 -0.0181362 -0.062959999, + -0.0465803 -0.0169976 -0.063578002, + -0.044564299 -0.016009901 -0.064185001, + -0.0424264 -0.0151904 -0.064754002, + -0.040174201 -0.0145507 -0.065256, + -0.0378174 -0.014095 -0.065663002, + -0.035366699 -0.0138221 -0.065945998, + -0.0328326 -0.0137234 -0.066079997, + -0.0302257 -0.0137799 -0.066039003, + -0.027557701 -0.0139781 -0.065807998, + -0.0248404 -0.0142978 -0.065378003, + -0.0220857 -0.0147025 -0.064732, + -0.019305199 -0.0151869 -0.063874997, + -0.0165099 -0.0157269 -0.062818997, + -0.0137106 -0.016303901 -0.061570998, + -0.0109179 -0.016428201 -0.061666001, + -0.0081428103 -0.0165108 -0.061639, + -0.0053973799 -0.016477101 -0.061418999, + -0.00268824 -0.016294099 -0.061055001, + 0 -0.015953099 -0.060631, + 0.00268824 -0.0159542 -0.060570002, + 0.00268824 -0.016294699 -0.061053, + 0.0053973799 -0.0162993 -0.060867, + 0.0053973799 -0.016479099 -0.061416999, + 0.0081428103 -0.0164895 -0.061099999, + 0.0081428103 -0.016513599 -0.061638001, + 0.0109179 -0.016532401 -0.061183002, + 0.0109179 -0.016429899 -0.061666001, + 0.0137106 -0.0164604 -0.061067, + 0.0137106 -0.0163051 -0.06157, + 0.0165099 -0.016350901 -0.060821999, + 0.0165099 -0.015727701 -0.062818997, + 0.019305199 -0.015821399 -0.061907001, + 0.019305199 -0.015188 -0.063874997, + 0.0220857 -0.0153432 -0.062790997, + 0.0220857 -0.0147024 -0.064732, + 0.0248404 -0.014933 -0.063469999, + 0.0248404 -0.0142979 -0.065378003, + 0.027557701 -0.0146183 -0.063933998, + 0.027557701 -0.0139889 -0.065806001, + 0.0302257 -0.014411 -0.064177997, + 0.0302257 -0.0137821 -0.066028997, + 0.0328326 -0.0143169 -0.064219996, + 0.0328326 -0.0137198 -0.066064999, + 0.035366699 -0.0143811 -0.064079002, + 0.035366699 -0.0138217 -0.065929003, + 0.0378174 -0.0146208 -0.063777998, + 0.0378174 -0.0140982 -0.065644003, + 0.040174201 -0.0150443 -0.063341998, + 0.040174201 -0.0145568 -0.065236002, + 0.0424264 -0.015657101 -0.062798001, + 0.0424264 -0.0152 -0.064732999, + 0.044564299 -0.016458901 -0.062176999, + 0.044564299 -0.0160235 -0.064162999, + 0.0465803 -0.017441601 -0.06151, + 0.0465803 -0.017015301 -0.063556999, + 0.048467699 -0.0185897 -0.060826998, + 0.048467699 -0.0181577 -0.062941, + 0.050219599 -0.019882601 -0.060155999, + 0.050219599 -0.019427801 -0.062337998, + 0.051830001 -0.021294599 -0.059517998, + 0.051830001 -0.0207997 -0.061765999, + 0.0532961 -0.022796899 -0.058931999, + 0.0532961 -0.022244601 -0.061239999, + 0.0546159 -0.024358399 -0.058409002, + 0.0546159 -0.023735899 -0.060771, + 0.055787299 -0.025951101 -0.057960998, + 0.055787299 -0.025245899 -0.060357001, + 0.056809202 -0.0275461 -0.057581998, + 0.056809202 -0.026765499 -0.060031001, + 0.0576833 -0.0291353 -0.057307001, + 0.0576833 -0.028330401 -0.059872001, + 0.058412101 -0.030758001 -0.057213999, + 0.058412101 -0.0299279 -0.059849001, + 0.058998398 -0.0324011 -0.057270002, + 0.058998398 -0.031537101 -0.059964001, + 0.059445001 -0.034042701 -0.057475999, + 0.059445001 -0.033138901 -0.060224, + 0.059757002 -0.035662301 -0.057836998, + 0.059757002 -0.034713302 -0.06064, + 0.0599402 -0.0372441 -0.058359999, + 0.0599402 -0.036244299 -0.061214, + 0.059999999 -0.038793001 -0.059028, + 0.059999999 -0.037736699 -0.061932001, + 0.0599402 -0.040319599 -0.059822999, + 0.0599402 -0.039200101 -0.062775999, + 0.059757002 -0.041834399 -0.060727999, + 0.059757002 -0.040657699 -0.063725002, + 0.059445001 -0.043355301 -0.061730999, + 0.059445001 -0.0421337 -0.064797997, + 0.058998398 -0.044883899 -0.062863, + 0.058998398 -0.043598998 -0.066014998, + 0.058412101 -0.046386201 -0.064144999, + 0.058412101 -0.045030799 -0.067372002, + 0.0576833 -0.047839999 -0.065573998, + 0.0576833 -0.046410199 -0.068866, + 0.056809202 -0.0492264 -0.067143001, + 0.056809202 -0.0477181 -0.070487998, + 0.055787299 -0.050526101 -0.068843998, + 0.055787299 -0.048934702 -0.072229996, + 0.0546159 -0.051719401 -0.070667997, + 0.0546159 -0.0500421 -0.074083999, + 0.0532961 -0.052787401 -0.072604999, + 0.0532961 -0.049430601 -0.079639003, + 0.051830001 -0.0521199 -0.078307003, + 0.051830001 -0.048992898 -0.085608996, + 0.050219599 -0.051616099 -0.084422998, + 0.050219599 -0.048732702 -0.091972999, + 0.048467699 -0.0512794 -0.090929002, + 0.048467699 -0.048650201 -0.098706998, + 0.0465803 -0.0511107 -0.097801998, + 0.0465803 -0.0487452 -0.105786, + 0.044564299 -0.051109601 -0.105015, + 0.044564299 -0.049015399 -0.113184, + 0.0424264 -0.0512737 -0.11254, + 0.0424264 -0.049454 -0.120873, + 0.040174201 -0.051596399 -0.120351, + 0.040174201 -0.050053202 -0.12882601, + 0.0378174 -0.0520727 -0.128415, + 0.0378174 -0.050808001 -0.137012, + 0.035366699 -0.052697901 -0.136705, + 0.035366699 -0.051713701 -0.145404, + 0.0328326 -0.053467602 -0.145189, + 0.0328326 -0.0527661 -0.153969, + 0.0302257 -0.054377899 -0.153837, + 0.0302257 -0.0539608 -0.162678, + 0.027557701 -0.055427801 -0.162618, + 0.028354499 -0.0548774 -0.1715, + 0.026825599 -0.0556692 -0.19149999, + 0.0248341 -0.056601699 -0.1715, + 0.025727101 -0.056204401 -0.1715, + 0.0275511 -0.0552832 -0.1715, + 0.030218899 -0.053817999 -0.1715, + 0.030913601 -0.0534232 -0.1715, + -0.0030887299 -0.061920401 -0.19149999, + 5.2000001e-008 -0.0619977 -0.1715, + -0.0026750399 -0.0619363 -0.1715, + -0.00267513 -0.062081099 -0.16234399, + -0.0028477299 -0.0619324 -0.1715, + -0.0053912699 -0.0617489 -0.1715, + -0.0030883299 -0.061914999 -0.1715, + -0.0053918599 -0.061898701 -0.162351, + -0.0053918599 -0.062320001 -0.15318801, + -0.0081421202 -0.062008701 -0.15321299, + -0.0081421202 -0.062711 -0.144061, + -0.0109179 -0.062264901 -0.144115, + -0.0109179 -0.063249402 -0.134992, + -0.0137106 -0.062663198 -0.135088, + -0.0137106 -0.063931398 -0.126012, + -0.0165099 -0.063201897 -0.12616099, + -0.0165099 -0.064752199 -0.117151, + -0.019305199 -0.063877001 -0.117366, + -0.019305199 -0.065706603 -0.108443, + -0.0220857 -0.064682998 -0.108735, + -0.0220857 -0.066789001 -0.099918, + -0.0248404 -0.065614797 -0.100302, + -0.0248404 -0.067993201 -0.091613002, + -0.027557701 -0.066669203 -0.092100002, + -0.027557701 -0.069313899 -0.083558001, + -0.0302257 -0.0678415 -0.084161997, + -0.0302257 -0.070745103 -0.075786002, + -0.0328326 -0.069125399 -0.076520003, + -0.0328326 -0.072280101 -0.068332002, + -0.035366699 -0.0705145 -0.069206998, + -0.035366699 -0.073911302 -0.061228, + -0.0378174 -0.0720044 -0.062254999, + -0.0378174 -0.0736944 -0.058340002, + -0.040174201 -0.071656398 -0.059482999, + -0.040174201 -0.0732245 -0.055555999, + -0.0424264 -0.071065299 -0.056820001, + -0.0424264 -0.072514303 -0.052894998, + -0.044564299 -0.070245102 -0.054283001, + -0.044564299 -0.071578696 -0.050372999, + -0.0465803 -0.069213599 -0.051887002, + -0.0465803 -0.070436202 -0.048006002, + -0.048467699 -0.067990102 -0.049647, + -0.048467699 -0.069106497 -0.045807999, + -0.050219599 -0.066594802 -0.047575999, + -0.050219599 -0.067610301 -0.043793, + -0.051830001 -0.065048903 -0.045687001, + -0.051830001 -0.065972 -0.041965, + -0.0532961 -0.063377701 -0.043981001, + -0.0532961 -0.064207301 -0.040307999, + -0.0546159 -0.061596401 -0.042440001, + -0.0546159 -0.062333699 -0.038823999, + -0.055787299 -0.059721801 -0.041065, + -0.055787299 -0.060373701 -0.037510999, + -0.056809202 -0.057776101 -0.039850999, + -0.056809202 -0.058349699 -0.036364, + -0.0576833 -0.055780299 -0.038794, + -0.0576833 -0.056282301 -0.035379, + -0.058412101 -0.053754602 -0.037889, + -0.058412101 -0.054191399 -0.034547001, + -0.058998398 -0.051718201 -0.037126001, + -0.058998398 -0.0520969 -0.033860002, + -0.059445001 -0.0496905 -0.036495, + -0.059445001 -0.050022401 -0.033296, + -0.059757002 -0.047695 -0.035971999, + -0.059757002 -0.047971301 -0.032929, + -0.0599402 -0.0457302 -0.035633001, + -0.0599402 -0.045856498 -0.032692999, + -0.059999999 -0.043694898 -0.035434999, + -0.059999999 -0.043658499 -0.032540001, + -0.0599402 -0.041567501 -0.035340998, + -0.0599402 -0.0413845 -0.032524001, + -0.059757002 -0.039356899 -0.035402, + -0.059757002 -0.039044101 -0.032680999, + -0.059445001 -0.0370785 -0.035650998, + -0.059445001 -0.036659501 -0.033045001, + -0.058998398 -0.0347712 -0.036095001, + -0.058998398 -0.034271698 -0.033620998, + -0.058412101 -0.032478198 -0.036731001, + -0.058412101 -0.031927999 -0.034396, + -0.0576833 -0.030244101 -0.037547, + -0.0576833 -0.0296728 -0.035354, + -0.056809202 -0.028110599 -0.038525999, + -0.056809202 -0.027547499 -0.03647, + -0.055787299 -0.0261168 -0.039639, + -0.055787299 -0.025588199 -0.03771, + -0.0546159 -0.0242956 -0.040854, + -0.0546159 -0.023825601 -0.039037, + -0.0532961 -0.022675101 -0.042132001, + -0.0532961 -0.02228 -0.040406998, + -0.051830001 -0.0212727 -0.043430001, + -0.051830001 -0.020952599 -0.041774001, + -0.050219599 -0.020087 -0.044702001, + -0.050219599 -0.019970899 -0.043887999, + -0.048467699 -0.019130601 -0.045906998, + -0.0390082 -0.017105799 -0.048406001, + -0.0378174 -0.0170437 -0.049424998, + -0.040174201 -0.017130399 -0.049127001, + -0.0378174 -0.017066499 -0.048969999, + -0.036603201 -0.0170171 -0.049950998, + -0.036603201 -0.0169944 -0.049516998, + -0.035366699 -0.016956599 -0.050461002, + -0.035366699 -0.016828099 -0.049977999, + -0.034109399 -0.016800201 -0.050884001, + -0.034109399 -0.0165384 -0.050386999, + -0.0328326 -0.016518399 -0.051252998, + -0.051042698 -0.017984999 -0.033980999, + -0.050219599 -0.0179039 -0.03531, + -0.051830001 -0.018664701 -0.034162998, + 0.0465803 -0.017407499 -0.039611999, + 0.0465803 -0.017525099 -0.040011, + 0.045588002 -0.017358501 -0.040824998, + 0.047540501 -0.0175878 -0.038768999, + 0.0465803 -0.0175959 -0.040424999, + 0.048467699 -0.0177495 -0.037909001, + 0.048467699 -0.0181171 -0.039528001, + 0.055787299 -0.024339801 -0.034182001, + 0.055787299 -0.023659401 -0.032612, + 0.056809202 -0.0253895 -0.031032, + 0.056809202 -0.026168499 -0.032703999, + 0.0576833 -0.027351899 -0.029519999, + 0.0576833 -0.028209399 -0.031316999, + 0.058412101 -0.029523 -0.028122, + 0.058412101 -0.0304353 -0.030063, + 0.058998398 -0.031872399 -0.02688, + 0.058998398 -0.032811198 -0.02898, + 0.059445001 -0.034362201 -0.025831999, + 0.059445001 -0.035295501 -0.028099, + 0.059757002 -0.036947198 -0.025008, + 0.059757002 -0.037839901 -0.027445, + 0.0599402 -0.039579902 -0.024428001, + 0.0599402 -0.040397801 -0.027028, + 0.059999999 -0.042227201 -0.024073999, + 0.059999999 -0.0429371 -0.026823999, + 0.0599402 -0.044861801 -0.023916001, + 0.0599402 -0.045436401 -0.026798001, + 0.059757002 -0.047463998 -0.023918999, + 0.059757002 -0.047879402 -0.026908999, + 0.059445001 -0.050014801 -0.024049001, + 0.059445001 -0.050257999 -0.027125999, + 0.058998398 -0.052489299 -0.024296001, + 0.058998398 -0.052547898 -0.027422, + 0.058412101 -0.0548581 -0.024635, + 0.058412101 -0.054754701 -0.027851, + 0.0576833 -0.0571278 -0.025123, + 0.0576833 -0.056963202 -0.028523, + 0.056809202 -0.059386998 -0.025869001, + 0.056809202 -0.0591649 -0.029364999, + 0.055787299 -0.061627001 -0.026797, + 0.055787299 -0.061335299 -0.030371999, + 0.0546159 -0.063822299 -0.027902, + 0.0546159 -0.063453503 -0.031550001, + 0.0532961 -0.065950803 -0.029188, + 0.0532961 -0.065498598 -0.032906, + 0.051830001 -0.067990899 -0.030661, + 0.051830001 -0.067448899 -0.034444999, + 0.050219599 -0.069920398 -0.032325, + 0.050219599 -0.069281802 -0.036169998, + 0.048467699 -0.071716599 -0.034182001, + 0.048467699 -0.070974797 -0.038081001, + 0.0465803 -0.073357597 -0.036228999, + 0.0465803 -0.072511598 -0.040174998, + 0.044564299 -0.074827097 -0.038463, + 0.044564299 -0.073877603 -0.042454999, + 0.0424264 -0.076109603 -0.040883999, + 0.0424264 -0.0750442 -0.044918999, + 0.040174201 -0.077177703 -0.043487001, + 0.040174201 -0.075991303 -0.047552001, + 0.0378174 -0.078014202 -0.046255998, + 0.0378174 -0.076704197 -0.050335001, + 0.035366699 -0.078605503 -0.049171999, + 0.035366699 -0.077169403 -0.053249002, + 0.0328326 -0.0789387 -0.052212998, + 0.0328326 -0.077374399 -0.056276999, + 0.0302257 -0.079002298 -0.055362999, + 0.0302257 -0.077310003 -0.059397999, + 0.027557701 -0.078791201 -0.058600999, + 0.027557701 -0.075375497 -0.066790998, + 0.0248404 -0.076706 -0.066132002, + 0.0248404 -0.073537402 -0.074510001, + 0.0220857 -0.074716501 -0.073977001, + 0.0220857 -0.071804203 -0.082523003, + 0.019305199 -0.072831601 -0.082102001, + 0.019305199 -0.0701821 -0.090793997, + 0.0165099 -0.0710603 -0.090471998, + 0.0165099 -0.068679802 -0.099290997, + 0.0137106 -0.069411702 -0.099053003, + 0.0137106 -0.067305401 -0.107978, + 0.0109179 -0.067893803 -0.107811, + 0.0109179 -0.066064298 -0.116825, + 0.0081421202 -0.066512302 -0.116716, + 0.0081421202 -0.064961798 -0.125798, + 0.0053918599 -0.065274902 -0.125735, + 0.0053918599 -0.064005598 -0.134866, + 0.00267513 -0.064189501 -0.134837, + 0.00267513 -0.063203499 -0.143999, + 0 -0.063264102 -0.14399201, + 0 -0.062561102 -0.15316799, + -0.00267513 -0.063204996 -0.14399999, + -0.00267513 -0.064190596 -0.134837, + -0.0053918599 -0.064007796 -0.134867, + -0.0053918599 -0.065276802 -0.125737, + -0.0081421202 -0.064964697 -0.1258, + -0.0081421202 -0.066515602 -0.116719, + -0.0109179 -0.066068701 -0.116829, + -0.0109179 -0.0678991 -0.107816, + -0.0137106 -0.067312203 -0.107984, + -0.0137106 -0.069419399 -0.099058002, + -0.0165099 -0.0686891 -0.099297002, + -0.0165099 -0.071069799 -0.090478003, + -0.019305199 -0.070193201 -0.090801999, + -0.019305199 -0.0728416 -0.082108997, + -0.0220857 -0.071815602 -0.082530998, + -0.0220857 -0.074725002 -0.073983997, + -0.0248404 -0.073546998 -0.074518003, + -0.0248404 -0.076710403 -0.066136003, + -0.027557701 -0.075380497 -0.066795997, + -0.027557701 -0.0787898 -0.058600999, + -0.0302257 -0.077308498 -0.059399001, + -0.0302257 -0.0790013 -0.055362999, + -0.0328326 -0.0773734 -0.056276001, + -0.0328326 -0.078936301 -0.052212998, + -0.035366699 -0.0771669 -0.053249002, + -0.035366699 -0.078601196 -0.049171999, + -0.0378174 -0.076699503 -0.050335001, + -0.0378174 -0.078007899 -0.046257999, + -0.040174201 -0.075984597 -0.047552999, + -0.040174201 -0.077170402 -0.043489002, + -0.0424264 -0.075036503 -0.044920001, + -0.0424264 -0.076103501 -0.040883999, + -0.044564299 -0.073871203 -0.042454999, + -0.044564299 -0.074823998 -0.038461, + -0.0465803 -0.072508298 -0.040171999, + -0.0465803 -0.073354103 -0.036228001, + -0.048467699 -0.070971102 -0.038079999, + -0.048467699 -0.071710601 -0.034180999, + -0.050219599 -0.0692757 -0.036169, + -0.050219599 -0.069911398 -0.032324001, + -0.051830001 -0.067439601 -0.034444001, + -0.051830001 -0.067978501 -0.030661, + -0.0532961 -0.065485902 -0.032906, + -0.0532961 -0.065935098 -0.02919, + -0.0546159 -0.063437402 -0.031552002, + -0.0546159 -0.063804299 -0.027908999, + -0.055787299 -0.0613169 -0.030378999, + -0.055787299 -0.061608501 -0.026814001, + -0.056809202 -0.059145998 -0.029381, + -0.056809202 -0.059370302 -0.025897, + -0.0576833 -0.056946199 -0.028550999, + -0.0576833 -0.057115801 -0.025141001, + -0.058412101 -0.054742601 -0.027868999, + -0.058412101 -0.054848399 -0.024633, + -0.058998398 -0.052538101 -0.027419999, + -0.058998398 -0.052474 -0.024297999, + -0.059445001 -0.050242499 -0.027129, + -0.059445001 -0.049992401 -0.024057999, + -0.059757002 -0.0478568 -0.026918, + -0.059757002 -0.047436301 -0.023933999, + -0.0599402 -0.045408599 -0.026812, + -0.0599402 -0.044833001 -0.023936, + -0.059999999 -0.0429083 -0.026843, + -0.059999999 -0.042200599 -0.024096999, + -0.0599402 -0.040371198 -0.027051, + -0.0599402 -0.039556999 -0.024455, + -0.059757002 -0.037817098 -0.027472001, + -0.059757002 -0.036929 -0.025037, + -0.059445001 -0.0352774 -0.028128, + -0.059445001 -0.0343487 -0.025862001, + -0.058998398 -0.032797899 -0.02901, + -0.058998398 -0.031863399 -0.02691, + -0.058412101 -0.030426299 -0.030092999, + -0.058412101 -0.029518001 -0.028152, + -0.0576833 -0.028204501 -0.031346001, + -0.0576833 -0.027352501 -0.029548001, + -0.056809202 -0.026169101 -0.032731999, + -0.056809202 -0.025395701 -0.031057, + -0.055787299 -0.024345901 -0.034208, + -0.055787299 -0.0236552 -0.03263, + -0.0546159 -0.022740601 -0.035725001, + -0.0546159 -0.0221569 -0.034221999, + -0.0532961 -0.0213756 -0.037238002, + -0.0532961 -0.0208677 -0.035778999, + -0.051830001 -0.0202199 -0.038697001, + -0.051830001 -0.019734399 -0.037195999, + -0.050219599 -0.0192212 -0.040004998, + -0.050219599 -0.018824499 -0.038447998, + -0.048467699 -0.018440001 -0.041134998, + -0.048467699 -0.0181146 -0.039528001, + -0.0465803 -0.017852301 -0.042086001, + -0.0465803 -0.017592 -0.040428001, + -0.045588002 -0.017456399 -0.041228, + -0.044564299 -0.017444501 -0.042847998, + -0.047540501 -0.017667999 -0.039182, + -0.0465803 -0.017517701 -0.040010002, + -0.045588002 -0.017343 -0.040828001, + -0.044564299 -0.017295299 -0.042015001, + -0.0401715 -0.0145 -0.044567, + -0.040756401 -0.0094999997 -0.044032998, + -0.037937399 -0.0145 -0.046484001, + -0.046273202 -0.0145 -0.038194001, + -0.046573199 -0.0145 -0.037811998, + -0.045067899 -0.0094999997 -0.039609, + -0.0423088 -0.0145 -0.042544, + -0.042423598 -0.0145 -0.042424001, + -0.024834299 -0.0145 0.054602001, + -0.0254324 -0.0145 0.054336999, + -0.0248404 -0.0167441 0.054600999, + -0.022994 -0.0145 0.055419002, + -0.0220857 -0.016756799 0.055775002, + -0.0220857 -0.019006399 0.055741999, + -0.0220799 -0.0145 0.055771999, + -0.0202484 -0.0145 0.056480002, + -0.0197125 -0.0094999997 0.056669001, + -0.0165099 -0.0190515 0.057657, + -0.017454101 -0.0145 0.057404999, + -0.019305199 -0.016767999 0.0568, + -0.0137813 -0.0094999997 0.058396, + -0.0109153 -0.0145 0.058984, + -0.0077038999 -0.0094999997 0.059503, + -0.0165058 -0.0145 0.057668, + -0.0146178 -0.0145 0.058192, + -0.0193002 -0.0145 0.056793999, + -0.019709 -0.0145 0.056659002, + -0.0424264 -0.048700199 0.038890999, + -0.044564299 -0.047850002 0.036339, + -0.0424264 -0.050506499 0.038286, + -0.0424264 -0.0468891 0.039407998, + -0.040174201 -0.047647402 0.041820999, + -0.040174201 -0.045786299 0.042241, + -0.0378174 -0.046455801 0.044505998, + -0.0378174 -0.044557702 0.044826999, + -0.035366699 -0.045142401 0.046936002, + -0.035366699 -0.043244299 0.047153998, + -0.0328326 -0.043748699 0.049098998, + -0.0328326 -0.041829899 0.049219999, + -0.0302257 -0.0422583 0.050995, + -0.0302257 -0.0401439 0.051064, + -0.027557701 -0.0404999 0.052666999, + -0.027557701 -0.031895399 0.052891001, + -0.0248404 -0.032095701 0.05429, + -0.0248404 -0.023380101 0.054473002, + -0.0220857 -0.023453601 0.055675, + -0.019305199 -0.0190307 0.056774002, + -0.019305199 -0.0235177 0.056724999, + -0.0220857 -0.032273602 0.055532001, + -0.0248404 -0.040820301 0.054111, + -0.027557701 -0.0426482 0.052611001, + -0.0302257 -0.0442123 0.050887, + -0.0328326 -0.045685101 0.048893001, + -0.035366699 -0.047082599 0.046627, + -0.0378174 -0.0483624 0.044096999, + -0.040174201 -0.049507201 0.041313998, + 0.035366699 -0.0529228 0.045171, + 0.0378174 -0.052166902 0.043026999, + 0.035366699 -0.050976701 0.045754001, + 0.0328326 -0.051638201 0.047738001, + 0.0328326 -0.049650699 0.048218999, + 0.0302257 -0.050221998 0.050035998, + 0.0302257 -0.048201501 0.050414, + 0.027557701 -0.048688199 0.052060999, + 0.027557701 -0.046647198 0.052336, + 0.0248404 -0.047055401 0.05381, + 0.0248404 -0.045024302 0.053980999, + 0.0220857 -0.045360599 0.055282, + 0.0220857 -0.043313898 0.055357002, + 0.019305199 -0.043585401 0.056483001, + 0.019305199 -0.041352998 0.056510001, + 0.0165099 -0.041565198 0.057466, + 0.0220857 -0.041104902 0.055392001, + 0.0248404 -0.043002699 0.054065999, + 0.027557701 -0.044645201 0.052517001, + 0.0302257 -0.046193801 0.050698999, + 0.0328326 -0.0476669 0.048606001, + 0.035366699 -0.049029201 0.046241999, + 0.0378174 -0.050264001 0.043616001, + 0.040174201 -0.051359501 0.040736001, + 0.0378174 -0.054063201 0.042342, + -0.0081421202 -0.0236832 0.059431002, + -0.0088465102 -0.0145 0.059344001, + -0.0109179 -0.019083001 0.058986001, + -0.0137072 -0.0145 0.058396999, + -0.013778 -0.0145 0.058380999, + -0.0137106 -0.0190689 0.058394, + -0.0117463 -0.0145 0.058839001, + -0.0137106 -0.0236183 0.058371, + -0.0165099 -0.0235726 0.057622001, + -0.0165099 -0.0325615 0.057542998, + -0.019305199 -0.0324287 0.056616001, + -0.019305199 -0.041352902 0.056510001, + -0.0220857 -0.041104801 0.055392001, + -0.0220857 -0.043310899 0.055357002, + -0.0248404 -0.042999301 0.054065999, + -0.0248404 -0.045014601 0.053978998, + -0.027557701 -0.044634499 0.052514002, + -0.027557701 -0.046638399 0.052331001, + -0.0302257 -0.0461841 0.050693002, + -0.0302257 -0.048199199 0.050404999, + -0.0328326 -0.0476644 0.048595, + -0.0328326 -0.049653102 0.048206002, + -0.035366699 -0.049031802 0.046227999, + -0.035366699 -0.050980501 0.045738, + -0.0378174 -0.050268099 0.043598998, + -0.0378174 -0.052169699 0.043008, + -0.040174201 -0.0513625 0.040716, + -0.0378174 -0.0540636 0.042323999, + -0.035366699 -0.0529253 0.045154002, + -0.0328326 -0.0516418 0.047722999, + -0.0302257 -0.0502243 0.050023999, + -0.027557701 -0.048686098 0.052051999, + -0.0248404 -0.047047399 0.053805001, + -0.0220857 -0.045352001 0.05528, + -0.019305199 -0.0435827 0.056483001, + -0.0165099 -0.041565102 0.057466, + -0.0137106 -0.0326721 0.058316, + -0.0109179 -0.0236551 0.058972999, + -0.0109179 -0.032761201 0.058938, + -0.0137106 -0.041742101 0.058263998, + -0.0165099 -0.0438153 0.057447001, + -0.019305199 -0.0456465 0.056414001, + -0.0220857 -0.047410499 0.055114001, + -0.0248404 -0.049124401 0.053534999, + -0.027557701 -0.050744198 0.051679, + -0.0302257 -0.052249599 0.049548998, + -0.0328326 -0.053626802 0.047146, + -0.035366699 -0.0548627 0.044473998, + -0.035366699 -0.0567885 0.043697, + -0.0328326 -0.057570498 0.045696001, + -0.0328326 -0.059517901 0.044822998, + -0.0302257 -0.060273699 0.046661001, + -0.0302257 -0.0622316 0.04569, + -0.027557701 -0.0629531 0.047363002, + -0.027557701 -0.064909801 0.046289999, + -0.0248404 -0.0655891 0.047795001, + -0.0248404 -0.067533001 0.046620999, + -0.0220857 -0.068162203 0.047954999, + -0.0220857 -0.070082001 0.04668, + -0.019305199 -0.070653401 0.047839999, + -0.019305199 -0.0725381 0.046466999, + -0.0165099 -0.073045798 0.047456, + -0.0165099 -0.074884199 0.045988001, + -0.0137106 -0.075323097 0.046810001, + -0.0137106 -0.077104598 0.045249999, + -0.0109179 -0.077469803 0.045906998, + -0.0109179 -0.079185098 0.044261001, + -0.0081421202 -0.0794724 0.044759002, + -0.0081421202 -0.081112802 0.043033998, + -0.0053918599 -0.081319898 0.04338, + -0.0053918599 -0.082877003 0.041582, + -0.00267513 -0.083002202 0.041783001, + -0.00267513 -0.084468402 0.039919, + 0 -0.084510803 0.039985001, + 0 -0.085880697 0.038063999, + 0.00267513 -0.084469698 0.039919998, + 0.00267513 -0.083003402 0.041784, + 0.0053918599 -0.082879402 0.041584, + 0.0053918599 -0.081322096 0.043382, + 0.0081421202 -0.081116199 0.043037001, + 0.0081421202 -0.0794755 0.044762999, + 0.0109179 -0.079189204 0.044266, + 0.0109179 -0.077473603 0.045912001, + 0.0137106 -0.0771093 0.045256, + 0.0137106 -0.0753273 0.046815999, + 0.0165099 -0.074889302 0.045995999, + 0.0165099 -0.073050201 0.047465, + 0.019305199 -0.072543196 0.046477001, + 0.019305199 -0.070657797 0.047850002, + 0.0220857 -0.070087001 0.046691, + 0.0220857 -0.068166301 0.047966, + 0.0248404 -0.067537703 0.046634, + 0.0248404 -0.0655929 0.047807999, + 0.027557701 -0.064914003 0.046305001, + 0.027557701 -0.0629564 0.047377001, + 0.0302257 -0.062235199 0.045705002, + 0.0302257 -0.0602763 0.046677001, + 0.0328326 -0.059520699 0.044838998, + 0.0328326 -0.057571899 0.045713, + 0.035366699 -0.056790002 0.043715, + 0.035366699 -0.054862302 0.044491999, + 0.0328326 -0.053624399 0.047162, + 0.0302257 -0.052246299 0.049563002, + 0.027557701 -0.050742202 0.051690001, + 0.0248404 -0.049126301 0.053543001, + 0.0220857 -0.0474176 0.055119, + 0.019305199 -0.045653999 0.056416001, + 0.0165099 -0.043817598 0.057447001, + 0.0137106 -0.041742198 0.058263998, + 0.0081421202 -0.032829501 0.059411, + 0.0109179 -0.032761801 0.058938, + 0.00875236 -0.0145 0.059358001, + 0.0109155 -0.0145 0.058984999, + 0.0107542 -0.0145 0.059013002, + 0.0107568 -0.0094999997 0.059028, + 0.0116529 -0.0145 0.058858, + 0.0137106 -0.032672901 0.058316, + 0.0165099 -0.032562401 0.057542998, + 0.0145255 -0.0145 0.058215, + 0.0167659 -0.0145 0.057597, + 0.017363001 -0.0145 0.057433002, + 0.019305199 -0.032429799 0.056616001, + 0.0220857 -0.023455501 0.055677, + 0.020158799 -0.0145 0.056511998, + 0.0248404 -0.023382301 0.054474, + 0.0248404 -0.032097202 0.05429, + 0.027557701 -0.031897001 0.052889999, + 0.027557701 -0.0405 0.052666999, + 0.0302257 -0.040144 0.051063001, + 0.0302257 -0.042262401 0.050995, + 0.0328326 -0.041834399 0.049221002, + 0.0328326 -0.043761399 0.049102001, + 0.035366699 -0.043258101 0.047157001, + 0.035366699 -0.0451537 0.046943001, + 0.0378174 -0.044569802 0.044835001, + 0.0378174 -0.046458699 0.044519, + 0.040174201 -0.045789301 0.042254001, + 0.040174201 -0.047644399 0.041838001, + 0.0424264 -0.046886001 0.039425001, + 0.0424264 -0.048695602 0.038910002, + 0.044564299 -0.0478452 0.036359001, + 0.0424264 -0.050503399 0.038306002, + 0.040174201 -0.049502801 0.041331999, + 0.0378174 -0.048359599 0.044112999, + 0.035366699 -0.0470853 0.046638001, + 0.0328326 -0.045695599 0.048900001, + 0.0302257 -0.044224098 0.050889, + 0.027557701 -0.042652 0.052611001, + 0.0248404 -0.040820401 0.054111, + 0.0220857 -0.032274898 0.055532001, + 0.040174201 -0.0532097 0.040047001, + 0.0378174 -0.055947602 0.041563001, + 0.035366699 -0.058698799 0.042840999, + 0.0328326 -0.061443001 0.043868002, + 0.0302257 -0.064159803 0.044633999, + 0.027557701 -0.066829301 0.045132998, + 0.0248404 -0.069432601 0.045363002, + 0.0220857 -0.071950398 0.045322001, + 0.019305199 -0.074363798 0.045012999, + 0.0165099 -0.076656297 0.044440001, + 0.0137106 -0.0788133 0.043614, + 0.0109179 -0.080821298 0.042544, + 0.0081421202 -0.082667597 0.041241001, + 0.0053918599 -0.084342398 0.039721001, + 0.00267513 -0.085838497 0.037999999, + 0 -0.0871507 0.036093999, + -0.00267513 -0.085837297 0.037999, + -0.0053918599 -0.084339902 0.039719, + -0.0081421202 -0.082663998 0.041237999, + -0.0109179 -0.080816701 0.042539001, + -0.0137106 -0.078808002 0.043607999, + -0.0165099 -0.076650597 0.044433001, + -0.019305199 -0.074357897 0.045003999, + -0.0220857 -0.071944498 0.045311, + -0.0248404 -0.069426998 0.04535, + -0.027557701 -0.066824101 0.045118999, + -0.0302257 -0.064155102 0.044619001, + -0.0328326 -0.061439101 0.043850999, + -0.035366699 -0.058695801 0.042823002, + -0.0378174 -0.055946 0.041544002, + -0.040174201 -0.053210098 0.040027, + -0.0081404904 -0.0145 0.059432, + -0.0077017802 -0.0145 0.059486002, + -0.0059254402 -0.0145 0.059707001, + -0.0053918599 -0.023702901 0.059751999, + -0.0081421202 -0.032829002 0.059411, + -0.0109179 -0.041884501 0.058905002, + -0.0137106 -0.044009302 0.058249999, + -0.0165099 -0.0458984 0.057385001, + -0.019305199 -0.047727302 0.056256, + -0.0220857 -0.0495135 0.054850999, + -0.0248404 -0.0512123 0.053169001, + -0.027557701 -0.052802999 0.051210999, + -0.0302257 -0.054271501 0.048976999, + -0.0328326 -0.055604398 0.046471, + -0.0302257 -0.058289301 0.047534, + -0.027557701 -0.060961802 0.048335999, + -0.0248404 -0.063602597 0.048870001, + -0.0220857 -0.066192098 0.049130999, + -0.019305199 -0.068711102 0.049118001, + -0.0165099 -0.071142197 0.048833001, + -0.0137106 -0.073469304 0.048280999, + -0.0109179 -0.075676203 0.04747, + -0.0081421202 -0.077748202 0.046408001, + -0.0053918599 -0.079673402 0.045108002, + -0.00267513 -0.081441604 0.043582998, + 0 -0.083043501 0.041850001, + 0.00267513 -0.081442699 0.043584, + 0.0053918599 -0.079675399 0.045109998, + 0.0081421202 -0.077751003 0.046411999, + 0.0109179 -0.0756796 0.047474999, + 0.0137106 -0.073472902 0.048287999, + 0.0165099 -0.071145996 0.048841, + 0.019305199 -0.068714701 0.049128, + 0.0220857 -0.066195503 0.049143001, + 0.0248404 -0.063605599 0.048882, + 0.027557701 -0.0609641 0.048349999, + 0.0302257 -0.058290601 0.047548998, + 0.0328326 -0.0556041 0.046487, + 0.0302257 -0.054269299 0.048990998, + 0.027557701 -0.0528 0.051222999, + 0.0248404 -0.0512104 0.053179, + 0.0220857 -0.049515199 0.054857999, + 0.019305199 -0.047733501 0.056260001, + 0.0165099 -0.0459048 0.057386, + 0.0137106 -0.044011202 0.058249999, + 0.0109179 -0.041884501 0.058905002, + 0.0081421202 -0.041992899 0.059393, + 0.0053918599 -0.042068701 0.059735, + 0.0081421202 -0.044285402 0.059388001, + 0.0109179 -0.0441668 0.058896001, + 0.0109179 -0.046282001 0.058846001, + 0.0137106 -0.046113901 0.058194999, + 0.0137106 -0.0482288 0.058049999, + 0.0165099 -0.048003599 0.057236001, + 0.0165099 -0.050144501 0.056986999, + 0.019305199 -0.049854401 0.056005999, + 0.019305199 -0.051988602 0.055654, + 0.0220857 -0.051626101 0.054501001, + 0.0220857 -0.053740699 0.054044001, + 0.0248404 -0.053298298 0.052717999, + 0.0248404 -0.055385001 0.052156001, + 0.027557701 -0.054856502 0.050657, + 0.027557701 -0.0569066 0.049989998, + 0.0302257 -0.056285899 0.048321001, + 0.027557701 -0.0589449 0.049221002, + 0.0248404 -0.057465401 0.051493, + 0.0220857 -0.055854201 0.053486999, + 0.019305199 -0.054126699 0.055202, + 0.0165099 -0.052298799 0.056639999, + 0.0137106 -0.050386399 0.057806, + 0.0109179 -0.048409902 0.058704998, + 0.0081421202 -0.046409901 0.059340999, + 0.0053918599 -0.044368099 0.059732001, + 0.00267513 -0.0421132 0.059935, + -0.00267513 -0.064080499 0.055925, + 0 -0.0641087 0.055994, + -0.00267513 -0.061909799 0.056791998, + 0 -0.0662532 0.055020001, + 0.00267513 -0.0640807 0.055927001, + 0 -0.061936598 0.056860998, + 0 -0.059745099 0.05762, + 0.00267513 -0.061909899 0.056793999, + 0.0053918599 -0.063994899 0.055718001, + 0.00267513 -0.066223897 0.054951999, + 0 -0.0683617 0.053939, + -0.00267513 -0.066223599 0.054951001, + -0.0053918599 -0.063994497 0.055714998, + 0.00267513 -0.055309601 0.058745001, + 0 -0.0553324 0.058812998, + 0.00267513 -0.0575178 0.058201998, + 0.0053918599 -0.057444401 0.057994999, + 0.0053918599 -0.059642199 0.057344001, + 0.0081421202 -0.05951 0.056990001, + 0.0081421202 -0.061689001 0.056230001, + 0.0109179 -0.061489701 0.055721, + 0.0081421202 -0.0638486 0.055362999, + 0.0053918599 -0.0618283 0.056584999, + 0.00267513 -0.0597197 0.057551999, + 0 -0.057541899 0.05827, + -0.00267513 -0.057518002 0.058201, + -0.00267513 -0.059719801 0.057551, + -0.0053918599 -0.059642199 0.057342, + -0.0053918599 -0.061827999 0.056582998, + -0.0081421202 -0.061688699 0.056226, + 0.0053918599 -0.066133901 0.054744001, + 0.00267513 -0.0683311 0.053870998, + 0 -0.070426099 0.052753001, + -0.00267513 -0.068330698 0.05387, + -0.0053918599 -0.066133298 0.054740999, + -0.0081421202 -0.063847899 0.055358998, + -0.0109179 -0.061489299 0.055716, + -0.0081421202 -0.059510101 0.056984998, + -0.0053918599 -0.0574448 0.057992, + -0.00267513 -0.055309899 0.058743998, + 0 -0.053121202 0.059250999, + 0.00267513 -0.0530999 0.059184, + 0.0053918599 -0.0552403 0.058538999, + 0.0081421202 -0.057319298 0.057641, + 0.0109179 -0.059320901 0.056481, + 0.0137106 -0.0612281 0.055052999, + 0.0109179 -0.063639201 0.054854002, + 0.0081421202 -0.065980598 0.054388002, + 0.0053918599 -0.068236999 0.053663, + 0.00267513 -0.070394203 0.052685, + 0 -0.072438903 0.051465001, + -0.00267513 -0.070393696 0.052684002, + -0.0053918599 -0.068236202 0.053661, + -0.0081421202 -0.0659796 0.054384001, + -0.0109179 -0.063638203 0.054848, + -0.0137106 -0.061227601 0.055046, + -0.0109179 -0.059321102 0.056476001, + -0.0081421202 -0.057319898 0.057636999, + -0.0053918599 -0.055240899 0.058536001, + -0.00267513 -0.053100102 0.059183002, + 0 -0.050913099 0.059587002, + 0.00267513 -0.0508934 0.059519999, + 0.0053918599 -0.053034801 0.058977999, + 0.0081421202 -0.055122402 0.058185998, + 0.0109179 -0.057140399 0.057133999, + 0.0137106 -0.059072699 0.055814002, + 0.0165099 -0.060902901 0.054223001, + 0.0137106 -0.0633642 0.054184999, + 0.0109179 -0.065761 0.053879999, + 0.0081421202 -0.0680767 0.053307999, + 0.0053918599 -0.070296101 0.052478001, + 0.00267513 -0.0724058 0.051398002, + 0 -0.074392803 0.050080001, + -0.00267513 -0.072405197 0.051397, + -0.0053918599 -0.070295103 0.052475002, + -0.0081421202 -0.068075404 0.053304002, + -0.0109179 -0.065759704 0.053874001, + -0.0137106 -0.063363001 0.054177999, + -0.0165099 -0.060902201 0.054214001, + -0.0137106 -0.059072901 0.055808, + -0.0109179 -0.0571412 0.057128999, + -0.0081421202 -0.055123299 0.058182001, + -0.0053918599 -0.0530352 0.058975998, + -0.00267513 -0.050893199 0.059519, + 0 -0.048718199 0.059822999, + 0.00267513 -0.048700102 0.059756, + 0.0053918599 -0.0508327 0.059315, + 0.0081421202 -0.052924 0.058626, + 0.0109179 -0.054953601 0.05768, + 0.0137106 -0.056905601 0.056467999, + 0.0165099 -0.0587641 0.054985002, + 0.019305199 -0.0605128 0.053226002, + 0.0165099 -0.063022301 0.053353999, + 0.0137106 -0.0654727 0.053211, + 0.0109179 -0.067847103 0.0528, + 0.0081421202 -0.070128798 0.052122999, + 0.0053918599 -0.072303697 0.051190998, + 0.00267513 -0.074358404 0.050012998, + 0 -0.076280497 0.048599999, + -0.00267513 -0.074357703 0.050011002, + -0.0053918599 -0.072302498 0.051188, + -0.0081421202 -0.070127301 0.052119002, + -0.0109179 -0.067845397 0.052793998, + -0.0137106 -0.065471098 0.053204, + -0.0165099 -0.0630209 0.053346001, + -0.019305199 -0.060511999 0.053215999, + -0.0165099 -0.058764301 0.054977, + -0.0137106 -0.0569066 0.056462001, + -0.0109179 -0.054954801 0.057675, + -0.0081421202 -0.052924599 0.058623001, + -0.0053918599 -0.050832301 0.059312999, + -0.00267513 -0.048699301 0.059755001, + 0 -0.046567898 0.059957001, + 0.00267513 -0.046551298 0.059891, + 0.0053918599 -0.048643898 0.059551999, + 0.0081421202 -0.0507291 0.058965001, + 0.0109179 -0.0527655 0.058123, + 0.0137106 -0.0547322 0.057016999, + 0.0165099 -0.056613602 0.055640999, + 0.019305199 -0.058394 0.053989999, + 0.0220857 -0.060056798 0.052060999, + 0.019305199 -0.062612198 0.052356999, + 0.0165099 -0.065114297 0.052379999, + 0.0137106 -0.0675456 0.052133001, + 0.0109179 -0.0698893 0.051615998, + 0.0081421202 -0.0721296 0.050838001, + 0.0053918599 -0.074252501 0.049805999, + 0.00267513 -0.076244898 0.048533998, + 0 -0.0780949 0.047031999, + -0.00267513 -0.076244101 0.048532002, + -0.0053918599 -0.074251004 0.049803998, + -0.0081421202 -0.072127797 0.050833002, + -0.0109179 -0.069887303 0.051610999, + -0.0137106 -0.067543499 0.052124999, + -0.0165099 -0.0651123 0.052372001, + -0.019305199 -0.062610596 0.052347001, + -0.0220857 -0.0600558 0.052049998, + -0.019305199 -0.058394201 0.05398, + -0.0165099 -0.056614801 0.055633001, + -0.0137106 -0.0547336 0.057009999, + -0.0109179 -0.052766301 0.058118001, + -0.0081421202 -0.0507285 0.058961999, + -0.0053918599 -0.048642099 0.059551001, + -0.00267513 -0.046550199 0.059891, + 0 -0.044432402 0.059999999, + 0.00267513 -0.0444167 0.059934001, + 0.0053918599 -0.0464991 0.059687998, + 0.0081421202 -0.0485477 0.059202999, + 0.0109179 -0.0505809 0.058463998, + 0.0137106 -0.052557401 0.057461999, + 0.0165099 -0.0544568 0.056191001, + 0.019305199 -0.056263499 0.054648001, + 0.0220857 -0.057961401 0.052825999, + 0.0248404 -0.059533998 0.050726, + 0.0220857 -0.062132899 0.051192001, + 0.019305199 -0.064684398 0.051383998, + 0.0165099 -0.067170799 0.051302001, + 0.0137106 -0.069574803 0.050949998, + 0.0109179 -0.071880303 0.050331999, + 0.0081421202 -0.074071698 0.049454, + 0.0053918599 -0.076135099 0.048328001, + 0.00267513 -0.078058198 0.046964999, + 0 -0.079830498 0.045379002, + -0.00267513 -0.0780572 0.046964001, + -0.0053918599 -0.076133497 0.048326001, + -0.0081421202 -0.0740695 0.049449999, + -0.0109179 -0.0718778 0.050326001, + -0.0137106 -0.0695723 0.050942998, + -0.0165099 -0.067168199 0.051293999, + -0.019305199 -0.064682104 0.051374, + -0.0220857 -0.062130999 0.051180001, + -0.0248404 -0.059532899 0.050712999, + -0.0220857 -0.057961602 0.052816, + -0.019305199 -0.0562649 0.054637998, + -0.0165099 -0.0544586 0.056184001, + -0.0137106 -0.0525585 0.057456002, + -0.0109179 -0.050580099 0.058460001, + -0.0081421202 -0.0485451 0.059202, + -0.0053918599 -0.046496999 0.059687, + -0.00267513 -0.044416301 0.059934001, + 0.0248404 -0.061583299 0.049855001, + 0.0220857 -0.064181797 0.050218001, + 0.019305199 -0.066721201 0.050306998, + 0.0165099 -0.069183797 0.050120998, + 0.0137106 -0.071552999 0.049667001, + 0.0109179 -0.073812798 0.048950002, + 0.0081421202 -0.075947799 0.047977999, + 0.0053918599 -0.077944703 0.046760999, + 0.00267513 -0.0797925 0.045313001, + 0 -0.081481799 0.043650001, + -0.00267513 -0.079791501 0.045311999, + -0.0053918599 -0.077942804 0.046758, + -0.0081421202 -0.075945303 0.047974002, + -0.0109179 -0.073809899 0.048944999, + -0.0137106 -0.0715499 0.049660001, + -0.0165099 -0.069180697 0.050113, + -0.019305199 -0.066718198 0.050297, + -0.0220857 -0.0641791 0.050207, + -0.0248404 -0.061581202 0.049842998, + -0.027557701 -0.0589437 0.049206998, + -0.0248404 -0.057465699 0.051479999, + -0.0220857 -0.055855799 0.053475998, + -0.019305199 -0.0541288 0.055193, + -0.0165099 -0.052299999 0.056632999, + -0.0137106 -0.050385401 0.057801001, + -0.0109179 -0.0484064 0.058701999, + -0.0081421202 -0.046406701 0.059340999, + -0.0053918599 -0.044367399 0.059732001, + -0.00267513 -0.0421132 0.059935, + 0 -0.042127699 0.060001001, + 0 -0.032913499 0.059999999, + 0.00267513 -0.032904498 0.059935998, + 0.0053918599 -0.032876801 0.059742, + 0.0046292599 -0.0145 0.059804, + 0.0058307201 -0.0145 0.059716001, + -0.0302257 -0.056286201 0.048305999, + -0.027557701 -0.054858498 0.050643999, + -0.0248404 -0.0533011 0.052705999, + -0.0220857 -0.051627699 0.054492, + -0.019305199 -0.0498529 0.056000002, + -0.0165099 -0.047998399 0.057232998, + -0.0137106 -0.0461086 0.058194, + -0.0109179 -0.044165298 0.058896001, + -0.0081421202 -0.041992899 0.059393, + -0.0053918599 -0.032876499 0.059742, + -0.00267513 -0.023714401 0.059939999, + -0.0029901101 -0.0145 0.059925001, + 0 -0.023718299 0.060001001, + -0.00154442 -0.0145 0.059962001, + -0.00267513 -0.032904401 0.059935998, + -0.0053918599 -0.042068701 0.059735, + -0.0081421202 -0.044284299 0.059388001, + -0.0109179 -0.046277702 0.058844998, + -0.0137106 -0.048224501 0.058047, + -0.0165099 -0.050143301 0.056981999, + -0.019305199 -0.051990099 0.055645999, + -0.0220857 -0.053743199 0.054033998, + -0.0248404 -0.0553868 0.052143998, + -0.027557701 -0.056906901 0.049977001, + 0.0026750199 -0.0145 0.059935, + -2.7e-008 -0.0145 0.059999, + -0.00154487 -0.0094999997 0.059980001, + -4.7590001e-005 -0.0145 0.059999999, + -0.0026749601 -0.0145 0.059932999, + -0.0053910702 -0.0145 0.059746999, + -0.048901699 -0.0094999997 -0.034765001, + -0.050207902 -0.0145 -0.032825001, + -0.049792401 -0.0145 -0.033477001, + -0.0522171 -0.0094999997 -0.029553, + -0.051830001 -0.0151508 -0.030262001, + -0.051374301 -0.0145 -0.030995, + -0.050219599 -0.0151367 -0.032871, + -0.0576833 -0.020132599 -0.019848, + -0.058412101 -0.0217261 -0.018169001, + -0.0576833 -0.0189256 -0.018552, + -0.056809202 -0.018750601 -0.021422001, + -0.056809202 -0.018149501 -0.020763, + -0.055787299 -0.0180356 -0.023595, + -0.055787299 -0.0171756 -0.022864999, + -0.0546159 -0.0171111 -0.025645001, + -0.0546159 -0.0165384 -0.025304001, + -0.0532961 -0.016493101 -0.028035, + -0.0532961 -0.015851101 -0.027760999, + -0.051830001 -0.0158222 -0.030433999, + 0.0465803 -0.0755568 -0.012273, + 0.0465803 -0.075537801 -0.016267, + 0.048467699 -0.0733869 -0.014536, + 0.048467699 -0.073313303 -0.010623, + 0.050219599 -0.071116097 -0.013028, + 0.050219599 -0.0709645 -0.0092139998, + 0.051830001 -0.068754598 -0.011755, + 0.051830001 -0.068659097 -0.0099170096, + 0.0532961 -0.066424198 -0.012549, + 0.0532961 -0.066312499 -0.010817, + 0.055787299 -0.061664101 -0.014598, + 0.055787299 -0.061468799 -0.012904, + 0.0546159 -0.0639119 -0.011819, + 0.0546159 -0.064064801 -0.013528, + 0.0532961 -0.066492997 -0.014355, + 0.051830001 -0.0688558 -0.015503, + 0.050219599 -0.071143098 -0.016875001, + 0.048467699 -0.073325403 -0.018464001, + 0.0465803 -0.075379699 -0.020268001, + 0.044564299 -0.077545501 -0.018219, + 0.044564299 -0.0772838 -0.022289, + 0.0424264 -0.079387501 -0.020393001, + 0.0424264 -0.079015501 -0.024522001, + 0.040174201 -0.0810422 -0.022784, + 0.040174201 -0.0805531 -0.026965, + -0.052581199 -0.0181501 -0.031272002, + -0.0532961 -0.018234 -0.029895, + -0.052581199 -0.0177566 -0.030533001, + -0.051830001 -0.0177023 -0.031884, + -0.051830001 -0.0174012 -0.031486001, + -0.0532961 -0.017485199 -0.028781001, + -0.051830001 -0.0169851 -0.03108, + -0.050219599 -0.016924201 -0.033709999, + -0.050219599 -0.0164051 -0.033337001, + -0.048467699 -0.0163629 -0.035884, + -0.048467699 -0.0168649 -0.036267001, + -0.0465803 -0.016322 -0.038346998, + -0.0465803 -0.015739899 -0.038042001, + -0.044564299 -0.015714301 -0.040403999, + -0.048467699 -0.015766401 -0.035585999, + -0.050219599 -0.015793899 -0.033047002, + -0.051830001 -0.0164486 -0.030717, + -0.0532961 -0.0170475 -0.028387001, + -0.0546159 -0.0179228 -0.0264, + -0.0576833 -0.0224343 -0.022421001, + -0.058412101 -0.024229901 -0.020631, + -0.0576833 -0.021301299 -0.021137999, + -0.056809202 -0.020877101 -0.024102001, + -0.056809202 -0.019833401 -0.022764999, + -0.055787299 -0.019535899 -0.025667001, + -0.055787299 -0.018576499 -0.024277, + -0.0546159 -0.0184041 -0.027105, + -0.0532961 -0.0178115 -0.029167, + -0.0546159 -0.0192411 -0.028542001, + -0.055787299 -0.0204552 -0.027051, + -0.056809202 -0.021884101 -0.025432, + -0.0576833 -0.023550199 -0.023693001, + -0.058412101 -0.025357099 -0.021868, + -0.058998398 -0.026160199 -0.018767999, + -0.058998398 -0.0273633 -0.020086, + -0.059445001 -0.028284701 -0.016969001, + -0.059445001 -0.0296099 -0.018409999, + -0.059757002 -0.030646401 -0.0153, + -0.059757002 -0.032057401 -0.016890001, + -0.0599402 -0.033204399 -0.013804, + -0.0599402 -0.034690101 -0.015571, + -0.059999999 -0.035951499 -0.012503, + -0.059999999 -0.037481599 -0.014466, + -0.0599402 -0.038864899 -0.011402, + -0.0599402 -0.040401898 -0.013574, + -0.059757002 -0.041916002 -0.0105, + -0.059757002 -0.043423001 -0.012885, + -0.059445001 -0.045074601 -0.0097940098, + -0.059445001 -0.046513502 -0.012391, + -0.058998398 -0.0482958 -0.0093, + -0.058998398 -0.049630299 -0.012099, + -0.058412101 -0.051530901 -0.0090300003, + -0.058412101 -0.052724998 -0.012013, + -0.0576833 -0.054729499 -0.0089849997, + -0.0576833 -0.055754099 -0.012127, + -0.056809202 -0.057846501 -0.0091570001, + -0.056809202 -0.058675401 -0.012429, + -0.055787299 -0.060838301 -0.0095319999, + -0.055787299 -0.0614543 -0.012906, + -0.0546159 -0.063669503 -0.010096, + 0.035366699 -0.084027 -0.026044, + 0.035366699 -0.083713099 -0.028181, + 0.0378174 -0.082489997 -0.025382999, + 0.0328326 -0.085416399 -0.026857, + 0.0328326 -0.0846968 -0.031165, + 0.0302257 -0.086278997 -0.029995, + 0.0302257 -0.085428298 -0.034324002, + 0.027557701 -0.086881101 -0.033302002, + 0.027557701 -0.085891202 -0.037641, + 0.0248404 -0.0872081 -0.036757998, + 0.0248404 -0.0860769 -0.041095, + 0.0220857 -0.0872522 -0.040341999, + 0.0220857 -0.085979 -0.044661, + 0.019305199 -0.087008297 -0.044031002, + 0.019305199 -0.085593201 -0.048317999, + 0.0165099 -0.086475901 -0.047800999, + 0.0165099 -0.084918998 -0.052044, + 0.0137106 -0.085655801 -0.051631, + 0.0137106 -0.083959803 -0.055817001, + 0.0109179 -0.084551997 -0.055498, + 0.0109179 -0.081124499 -0.063945003, + 0.0081421202 -0.081574902 -0.063722998, + 0.0081421202 -0.078399301 -0.072314002, + 0.0053918599 -0.078713797 -0.072172999, + 0.0053918599 -0.075797103 -0.080890998, + 0.00267513 -0.0759819 -0.080816001, + 0.00267513 -0.073329702 -0.089640997, + 0 -0.073390499 -0.089620002, + 0 -0.071008198 -0.098536, + -0.00267513 -0.073331296 -0.089642003, + -0.00267513 -0.075983196 -0.080816999, + -0.0053918599 -0.075799897 -0.080893002, + -0.0053918599 -0.078715801 -0.072173998, + -0.0081421202 -0.0784024 -0.072316997, + -0.0081421202 -0.081576303 -0.063723996, + -0.0109179 -0.081126399 -0.063947, + -0.0109179 -0.084551401 -0.055498, + -0.0137106 -0.083959103 -0.055817001, + -0.0137106 -0.085655302 -0.051631, + -0.0165099 -0.084918499 -0.052044, + -0.0165099 -0.086474702 -0.047800999, + -0.019305199 -0.085591801 -0.048317999, + -0.019305199 -0.087006003 -0.044032, + -0.0220857 -0.085976303 -0.044661, + -0.0220857 -0.087248497 -0.040343001, + -0.0248404 -0.086072698 -0.041095, + -0.0248404 -0.0872036 -0.036759, + -0.027557701 -0.085886203 -0.037641998, + -0.027557701 -0.0868771 -0.033301, + -0.0302257 -0.085423902 -0.034324002, + -0.0302257 -0.086276896 -0.029994, + -0.0328326 -0.084694602 -0.031164, + -0.0328326 -0.085413903 -0.026857, + -0.035366699 -0.083710402 -0.028179999, + -0.035366699 -0.084298901 -0.023902001, + -0.0378174 -0.082485303 -0.025381999, + -0.0378174 -0.082946599 -0.021143001, + -0.040174201 -0.081035003 -0.022783, + -0.040174201 -0.081374802 -0.018594, + -0.0424264 -0.079377301 -0.020393001, + -0.0424264 -0.0796028 -0.016263001, + -0.044564299 -0.077532403 -0.018221, + -0.044564299 -0.077650703 -0.014159, + -0.0465803 -0.075522497 -0.016272999, + -0.0465803 -0.075541303 -0.012287, + -0.048467699 -0.073370799 -0.01455, + -0.048467699 -0.073298998 -0.010646, + -0.050219599 -0.0711013 -0.013052, + -0.050219599 -0.070954002 -0.00923, + -0.051830001 -0.068743899 -0.011771, + -0.051830001 -0.068510801 -0.0081529999, + -0.0532961 -0.066303603 -0.010815, + -0.0532961 -0.0661183 -0.0090770004, + -0.0546159 -0.063900702 -0.011818, + -0.0546159 -0.064055704 -0.013527, + -0.0532961 -0.066481903 -0.014372, + -0.051830001 -0.068840504 -0.015528, + -0.050219599 -0.071126401 -0.016890001, + -0.048467699 -0.073309503 -0.01847, + -0.0465803 -0.075365998 -0.020269999, + -0.044564299 -0.077273101 -0.022288, + -0.0424264 -0.079007901 -0.024522001, + -0.040174201 -0.0805481 -0.026963999, + -0.0378174 -0.081874996 -0.029607, + -0.035366699 -0.0829731 -0.032435998, + -0.0328326 -0.083827697 -0.035447001, + -0.0302257 -0.084422797 -0.038624, + -0.027557701 -0.084748097 -0.041942999, + -0.0248404 -0.0847959 -0.045382999, + -0.0220857 -0.084559701 -0.048921999, + -0.019305199 -0.084034801 -0.052540001, + -0.0165099 -0.083222598 -0.056214001, + -0.0137106 -0.080535799 -0.064240001, + -0.0109179 -0.077953599 -0.072521001, + -0.0081421202 -0.0754871 -0.081022002, + -0.0053918599 -0.073148198 -0.089709997, + -0.00267513 -0.070949003 -0.098555997, + 0 -0.068900503 -0.107527, + 0.00267513 -0.070947498 -0.098554999, + 0.0053918599 -0.073145099 -0.089708, + 0.0081421202 -0.075482897 -0.081018999, + 0.0109179 -0.077949397 -0.072517, + 0.0137106 -0.0805334 -0.064237997, + 0.0165099 -0.083223403 -0.056212999, + 0.019305199 -0.084035501 -0.052540001, + 0.0220857 -0.084561199 -0.048921999, + 0.0248404 -0.084798999 -0.045382999, + 0.027557701 -0.084752701 -0.041942, + 0.0302257 -0.084428303 -0.038623001, + 0.0328326 -0.083832502 -0.035448, + 0.035366699 -0.082975604 -0.032437999, + 0.0378174 -0.081877902 -0.029608, + 0.0378174 -0.082740299 -0.023265, + 0.035366699 -0.0843032 -0.023902001, + 0.0328326 -0.085720502 -0.024695, + 0.0302257 -0.086982198 -0.025641, + 0.027557701 -0.0877195 -0.028929999, + 0.0248404 -0.088188797 -0.032381002, + 0.0220857 -0.088376999 -0.035974, + 0.019305199 -0.0882774 -0.039686002, + 0.0165099 -0.0878888 -0.043492999, + 0.0137106 -0.087211899 -0.047370002, + 0.0109179 -0.086248301 -0.051298, + 0.0081421202 -0.0850031 -0.055255, + 0.0053918599 -0.081889696 -0.063566998, + 0.00267513 -0.078898601 -0.07209, + 0 -0.0760426 -0.080790997, + -0.00267513 -0.0788996 -0.072090998, + -0.0053918599 -0.081890598 -0.063568003, + -0.0081421202 -0.085002698 -0.055255, + -0.0109179 -0.086248003 -0.051298, + -0.0137106 -0.087210901 -0.047371, + -0.0165099 -0.087886803 -0.043492999, + -0.019305199 -0.088274203 -0.039686002, + -0.0220857 -0.088372998 -0.035974, + -0.0248404 -0.088185199 -0.032381002, + -0.027557701 -0.087717503 -0.028929001, + -0.0302257 -0.086979903 -0.02564, + -0.0328326 -0.0859823 -0.022527, + -0.035366699 -0.084736198 -0.019608, + -0.0378174 -0.083258398 -0.016897, + -0.040174201 -0.081568003 -0.014405, + -0.0424264 -0.0796846 -0.01214, + -0.044564299 -0.077628702 -0.010111, + -0.0465803 -0.075424403 -0.0083189998, + -0.048467699 -0.073102601 -0.00675999, + -0.050219599 -0.070667498 -0.0055509899, + -0.051830001 -0.068295702 -0.0063849902, + -0.0532961 -0.065854602 -0.0073250001, + -0.0546159 -0.063363098 -0.0083760098, + -0.0546159 -0.0629813 -0.00666299, + -0.0532961 -0.065513603 -0.0055740098, + -0.051830001 -0.068000101 -0.0046029999, + -0.050219599 -0.070423201 -0.0037539999, + -0.048467699 -0.072764002 -0.003022, + -0.0302257 -0.088163503 -0.012479, + -0.027557701 -0.089533404 -0.011246, + -0.0302257 -0.088224903 -0.010283, + -0.0328326 -0.086732 -0.01166, + -0.0328326 -0.086767003 -0.0094880098, + -0.035366699 -0.085156403 -0.011011, + -0.035366699 -0.085167199 -0.00886501, + -0.0378174 -0.083435901 -0.0084149903, + -0.0378174 -0.083421297 -0.012652, + -0.040174201 -0.081615299 -0.010223, + -0.040174201 -0.0815171 -0.006056, + -0.0424264 -0.079623498 -0.0080310097, + -0.0424264 -0.079421602 -0.0039420002, + -0.044564299 -0.077468298 -0.0060809902, + -0.044564299 -0.077178396 -0.00207401, + -0.0465803 -0.0751803 -0.004371, + -0.0465803 -0.075010799 -0.0024279901, + -0.048467699 -0.072957702 -0.0048459899, + -0.035366699 -0.085021898 -0.015309, + 0.0302257 -0.087277099 -0.023453999, + 0.0302257 -0.087533399 -0.021264, + 0.027557701 -0.088407598 -0.024533, + 0.0328326 -0.085986301 -0.022528, + 0.0328326 -0.086213998 -0.020357, + 0.035366699 -0.084541798 -0.021756999, + 0.035366699 -0.084742501 -0.019609001, + 0.0378174 -0.082953297 -0.021144001, + 0.0378174 -0.083129101 -0.019021001, + 0.040174201 -0.081384398 -0.018594, + 0.040174201 -0.0815005 -0.016497999, + 0.0424264 -0.079615198 -0.016262, + 0.0378174 -0.083267502 -0.016897, + 0.035366699 -0.084905401 -0.017459, + 0.0328326 -0.086403303 -0.018184001, + 0.0302257 -0.087751001 -0.019069999, + 0.027557701 -0.088941902 -0.020114001, + 0.0248404 -0.089690797 -0.023535, + 0.0248404 -0.089016102 -0.027972, + 0.0220857 -0.090167001 -0.027121, + 0.0220857 -0.089349598 -0.031564001, + 0.019305199 -0.090362102 -0.030851001, + 0.019305199 -0.089396603 -0.035289001, + 0.0165099 -0.090268798 -0.034704, + 0.0165099 -0.0891544 -0.039124001, + 0.0137106 -0.0898856 -0.038656, + 0.0137106 -0.088622898 -0.043042999, + 0.0109179 -0.089213401 -0.042682, + 0.0109179 -0.087803803 -0.047024, + 0.0081421202 -0.088254698 -0.04676, + 0.0081421202 -0.086699799 -0.051045001, + 0.0053918599 -0.087015197 -0.050868001, + 0.0053918599 -0.085318401 -0.055085, + 0.00267513 -0.085503303 -0.054986, + 0.00267513 -0.082074501 -0.063476004, + 0 -0.082134999 -0.063446, + 0 -0.078959197 -0.072062999, + -0.00267513 -0.082075 -0.063476004, + -0.00267513 -0.085503198 -0.054986, + -0.0053918599 -0.085318103 -0.055085, + -0.0053918599 -0.087015003 -0.050868001, + -0.0081421202 -0.086699501 -0.051045001, + -0.0081421202 -0.088254198 -0.04676, + -0.0109179 -0.087802999 -0.047024, + -0.0109179 -0.089212 -0.042682, + -0.0137106 -0.088621303 -0.043044001, + -0.0137106 -0.089883298 -0.038656, + -0.0165099 -0.089151599 -0.039124999, + -0.0165099 -0.090265803 -0.034705002, + -0.019305199 -0.089393102 -0.035289999, + -0.019305199 -0.0903593 -0.030851001, + -0.0220857 -0.089346401 -0.031564001, + -0.0220857 -0.090165399 -0.02712, + -0.0248404 -0.089014404 -0.027969999, + -0.0248404 -0.089688897 -0.023535, + -0.027557701 -0.088405497 -0.024532, + -0.027557701 -0.088938497 -0.020113001, + -0.0302257 -0.087529697 -0.021263, + -0.0302257 -0.087924398 -0.016874, + -0.0328326 -0.086397402 -0.018184001, + -0.0328326 -0.0865473 -0.016008999, + -0.035366699 -0.084898002 -0.017459, + 0.044564299 -0.077665403 -0.014154, + 0.044564299 -0.077643499 -0.010097, + 0.0465803 -0.075438097 -0.0082970001, + 0.048467699 -0.0731126 -0.0067449999, + 0.050219599 -0.070842803 -0.0073439898, + 0.051830001 -0.068519503 -0.0081540104, + 0.0532961 -0.066129297 -0.0090770004, + 0.0546159 -0.063683704 -0.010094, + 0.055787299 -0.061200801 -0.01121, + 0.056809202 -0.0586969 -0.012421, + 0.044563901 -0.0145 -0.040174, + 0.046453901 -0.0145 -0.037974, + 0.044564299 -0.0151104 -0.040235002, + 0.0532961 -0.0182386 -0.029890999, + 0.0532961 -0.017829699 -0.029163999, + 0.0546159 -0.0184088 -0.027101001, + 0.0546159 -0.0192439 -0.028542001, + 0.055787299 -0.019538799 -0.025667001, + 0.055787299 -0.0204584 -0.027051, + 0.056809202 -0.021883801 -0.025433, + 0.056809202 -0.020880399 -0.024103001, + 0.0576833 -0.023550401 -0.023693999, + 0.055787299 -0.018581299 -0.024273001, + 0.0546159 -0.0179414 -0.026396001, + 0.0532961 -0.017504999 -0.028762, + 0.051830001 -0.0174204 -0.031466998, + 0.051830001 -0.016997701 -0.031047, + 0.050219599 -0.016936401 -0.033677999, + 0.050219599 -0.0164077 -0.033303998, + 0.048467699 -0.0163654 -0.035852, + 0.048467699 -0.015768601 -0.035572998, + 0.0465803 -0.0157419 -0.038029999, + 0.0465803 -0.0151235 -0.037877999, + 0.046577401 -0.0145 -0.037815001, + 0.0470348 -0.0145 -0.037227001, + 0.047047202 -0.0094999997 -0.037237, + 0.033437699 -0.0145 -0.049819, + 0.032825399 -0.0145 -0.050207999, + 0.033494599 -0.0094999997 -0.049780998, + 0.0424252 -0.0145 0.042424999, + 0.0429691 -0.0094999997 0.041877002, + 0.042376 -0.0145 0.042477001, + 0.0402418 -0.0145 0.044504002, + 0.040174201 -0.016636301 0.044535, + 0.037814599 -0.0145 0.046576999, + 0.0356883 -0.0145 0.048232, + 0.0378174 -0.0166582 0.046555001, + 0.038435601 -0.0094999997 0.046073001, + 0.038010798 -0.0145 0.046424001, + 0.0378174 -0.042715698 0.045062002, + 0.0378174 -0.038869299 0.045320999, + 0.035366699 -0.041368902 0.047290001, + 0.040174201 -0.042136401 0.042824, + 0.040174201 -0.043946002 0.042583, + 0.0424264 -0.043284498 0.040194999, + 0.0424264 -0.0450796 0.039852999, + 0.044564299 -0.0443318 0.037323002, + 0.044564299 -0.046087001 0.036883999, + 0.0465803 -0.0452509 0.034224, + 0.0465803 -0.046955299 0.033689, + 0.048467699 -0.0443816 0.031459, + 0.0465803 -0.0435494 0.034676, + 0.044564299 -0.042587601 0.037679002, + 0.0424264 -0.041521899 0.040451001, + 0.040174201 -0.0383798 0.043115001, + 0.0378174 -0.030878101 0.045768, + 0.035366699 -0.031164501 0.047770001, + 0.035366699 -0.0229978 0.048163, + 0.0328326 -0.0231074 0.049961001, + 0.035366699 -0.0188416 0.048372, + 0.0378174 -0.018797699 0.046468001, + 0.0384284 -0.0145 0.046064999, + 0.040173098 -0.0145 0.044562999, + 0.024833901 -0.0145 -0.054600999, + 0.0226037 -0.0094999997 -0.055578999, + 0.025769901 -0.0145 -0.054184001, + 0.0230815 -0.0145 -0.055383001, + 0.0248404 -0.0150286 -0.054680999, + 0.027557701 -0.0150362 -0.053360999, + 0.027557701 -0.0155734 -0.053546, + 0.0302257 -0.0155894 -0.052076001, + 0.0302257 -0.016090199 -0.052407999, + 0.0328326 -0.0161172 -0.050788, + 0.027557701 -0.0167253 -0.055836, + 0.0248404 -0.016657 -0.057186, + 0.0262044 -0.016741101 -0.056067001, + 0.027557701 -0.016626 -0.056317002, + 0.0165099 -0.059818499 -0.16243701, + 0.0137106 -0.060548201 -0.162407, + 0.015277 -0.0600099 -0.1715, + 0.0165099 -0.060237899 -0.153358, + 0.019305199 -0.059362501 -0.15343, + 0.019305199 -0.0600655 -0.144382, + 0.0220857 -0.0590421 -0.14450701, + 0.0220857 -0.060028099 -0.13551199, + 0.0248404 -0.0588549 -0.135703, + 0.0248404 -0.060122501 -0.12678, + 0.027557701 -0.058800299 -0.127048, + 0.027557701 -0.060347699 -0.118217, + 0.0302257 -0.058878198 -0.118575, + 0.0302257 -0.060703199 -0.109856, + 0.0328326 -0.059088301 -0.110316, + 0.0328326 -0.061188899 -0.10173, + 0.035366699 -0.059431002 -0.102303, + 0.035366699 -0.061804499 -0.093870997, + 0.0378174 -0.059909198 -0.094567999, + 0.0378174 -0.062549204 -0.086312003, + 0.040174201 -0.060522899 -0.087141998, + 0.040174201 -0.063421398 -0.079084001, + 0.0424264 -0.061269999 -0.080057003, + 0.0424264 -0.064418197 -0.072217003, + 0.044564299 -0.0621479 -0.073340997, + 0.044564299 -0.0655341 -0.065739997, + 0.0465803 -0.063153103 -0.067023002, + 0.0465803 -0.0648375 -0.063308999, + 0.048467699 -0.062360201 -0.064699002, + 0.048467699 -0.063938797 -0.060993001, + 0.050219599 -0.0613796 -0.062491, + 0.050219599 -0.062854402 -0.058807001, + 0.051830001 -0.060228098 -0.060412999, + 0.051830001 -0.061603401 -0.056763001, + 0.0532961 -0.058926102 -0.058476999, + 0.0532961 -0.060205601 -0.054873999, + 0.0546159 -0.057493798 -0.056692999, + 0.0546159 -0.0586817 -0.053151, + 0.055787299 -0.0559517 -0.055073, + 0.055787299 -0.057054698 -0.051601999, + 0.056809202 -0.054322802 -0.053622, + 0.056809202 -0.055357601 -0.050218999, + 0.0576833 -0.0526396 -0.052331001, + 0.0576833 -0.053599399 -0.048978001, + 0.058412101 -0.050909799 -0.051174, + 0.058412101 -0.051791701 -0.047876999, + 0.058998398 -0.049144 -0.050147999, + 0.058998398 -0.049954601 -0.046909001, + 0.059445001 -0.047362301 -0.049245, + 0.059445001 -0.048107199 -0.046066001, + 0.059757002 -0.0455839 -0.048452999, + 0.059757002 -0.046268102 -0.045334999, + 0.0599402 -0.043822099 -0.047764, + 0.0599402 -0.044450201 -0.044707, + 0.059999999 -0.042069599 -0.047189001, + 0.059999999 -0.042647101 -0.044197001, + 0.0599402 -0.040316101 -0.046749, + 0.0599402 -0.0408528 -0.043834001, + 0.059757002 -0.0385562 -0.046475001, + 0.059757002 -0.039051399 -0.043703001, + 0.059445001 -0.036780301 -0.046443, + 0.059445001 -0.0371629 -0.043738998, + 0.058998398 -0.034931399 -0.046569001, + 0.058998398 -0.035188701 -0.043905001, + 0.058412101 -0.033016302 -0.046815, + 0.058412101 -0.033162098 -0.044220001, + 0.0576833 -0.031066701 -0.047194, + 0.0576833 -0.031115999 -0.044682, + 0.056809202 -0.0291145 -0.047704998, + 0.056809202 -0.029089401 -0.045288999, + 0.055787299 -0.0271971 -0.048345, + 0.055787299 -0.027120899 -0.046032999, + 0.0546159 -0.0253515 -0.049102001, + 0.0546159 -0.025249699 -0.046898, + 0.0532961 -0.0236148 -0.049958002, + 0.0532961 -0.023511 -0.047860999, + 0.051830001 -0.022019699 -0.050887998, + 0.051830001 -0.021936201 -0.048889, + 0.050219599 -0.020594601 -0.051860999, + 0.050219599 -0.0205498 -0.049949002, + 0.048467699 -0.0193606 -0.052841999, + 0.048467699 -0.019368401 -0.051002, + 0.0465803 -0.018330799 -0.053794, + 0.0465803 -0.0184012 -0.052009001, + 0.044564299 -0.017511601 -0.054680001, + 0.044564299 -0.017652901 -0.052933, + 0.0424264 -0.016905 -0.055464, + 0.0424264 -0.017117901 -0.053739, + 0.040174201 -0.0165026 -0.056113001, + 0.040174201 -0.0167385 -0.054382998, + 0.0378174 -0.016248999 -0.056588002, + 0.0378174 -0.0165148 -0.054814, + 0.035366699 -0.0161433 -0.056846999, + 0.035366699 -0.0164543 -0.055029001, + 0.0328326 -0.0161884 -0.056887001, + 0.0328326 -0.016527001 -0.055029001, + 0.0302257 -0.0163546 -0.056710001, + 0.0302257 -0.0167179 -0.054811999, + 0.0302257 -0.0168011 -0.054336999, + 0.0288986 -0.016798699 -0.054648001, + 0.0328326 -0.016818799 -0.053158, + 0.035366699 -0.016714601 -0.053201001, + 0.0378174 -0.016740801 -0.053027999, + 0.040174201 -0.0169116 -0.052643001, + 0.0424264 -0.017257599 -0.052044, + 0.044564299 -0.017766099 -0.051238999, + 0.0465803 -0.018435501 -0.050285999, + 0.048467699 -0.019326299 -0.049231999, + 0.050219599 -0.020441299 -0.048115, + 0.051830001 -0.0217731 -0.046973001, + 0.0532961 -0.0233093 -0.045848001, + 0.0546159 -0.025029801 -0.044776998, + 0.055787299 -0.026907099 -0.043797001, + 0.056809202 -0.0289069 -0.042936001, + 0.0576833 -0.0309917 -0.042217001, + 0.058412101 -0.033120502 -0.041653998, + 0.058998398 -0.0352525 -0.041253, + 0.059445001 -0.037347302 -0.041014001, + 0.059757002 -0.0393705 -0.040938001, + 0.0599402 -0.0412925 -0.041000001, + 0.059999999 -0.043131799 -0.041214, + 0.0599402 -0.044978201 -0.041645002, + 0.059757002 -0.046849199 -0.042206001, + 0.059445001 -0.048746899 -0.042872999, + 0.058998398 -0.050657701 -0.043653, + 0.058412101 -0.0525635 -0.044558998, + 0.0576833 -0.054445699 -0.045600001, + 0.056809202 -0.056285098 -0.046783999, + 0.055787299 -0.058061201 -0.048117001, + 0.0546159 -0.059761301 -0.049601, + 0.0532961 -0.061374601 -0.051254999, + 0.051830001 -0.062868297 -0.053087998, + 0.050219599 -0.064219303 -0.055087999, + 0.048467699 -0.065407403 -0.057245001, + 0.0465803 -0.066413797 -0.059544001, + 0.044564299 -0.067219898 -0.061973002, + 0.0424264 -0.067809597 -0.064515002, + 0.040174201 -0.066573299 -0.071148999, + 0.0378174 -0.065450199 -0.078166001, + 0.035366699 -0.064446203 -0.085534997, + 0.0328326 -0.063563697 -0.093225002, + 0.0302257 -0.0628049 -0.101203, + 0.027557701 -0.062173501 -0.109438, + 0.0248404 -0.061670501 -0.117895, + 0.0220857 -0.061296199 -0.126541, + 0.019305199 -0.0610517 -0.135346, + 0.0165099 -0.060941 -0.14427499, + 0.0137106 -0.060968 -0.15329801, + 0.0109179 -0.0611353 -0.16238301, + 0.0117927 -0.060829699 -0.1715, + 0.048467699 -0.0172574 -0.036680002, + 0.050219599 -0.017337799 -0.034111001, + 0.049361002 -0.017560201 -0.035836, + 0.048467699 -0.016876699 -0.036237001, + 0.040174201 -0.0150857 -0.044627, + 0.040382501 -0.0145 -0.044376001, + 0.0424264 -0.0150978 -0.042488001, + 0.0424264 -0.0156918 -0.042649999, + 0.044564299 -0.015716299 -0.040392, + 0.044564299 -0.016285099 -0.040686, + 0.0465803 -0.016324401 -0.038316, + 0.0465803 -0.016819 -0.038711, + 0.0465803 -0.0171797 -0.039166, + 0.047540501 -0.0174575 -0.038375001, + 0.044564299 -0.016763501 -0.04109, + 0.0424264 -0.016247399 -0.042950999, + 0.040174201 -0.0156685 -0.044792999, + 0.0378174 -0.0150744 -0.046643998, + 0.038430501 -0.0145 -0.046066999, + 0.0328326 -0.0150538 -0.050283998, + 0.033493701 -0.0145 -0.049779002, + 0.035366699 -0.0150637 -0.048532002, + 0.035366699 -0.015626 -0.048705999, + 0.030218599 -0.0145 -0.051817998, + 0.0281986 -0.0094999997 -0.052960999, + 0.030954201 -0.0145 -0.051399, + 0.0283962 -0.0145 -0.052855, + 0.0302257 -0.0150446 -0.051895, + 0.0328326 -0.0156069 -0.050462, + 0.035366699 -0.0161465 -0.049026001, + 0.0378174 -0.016178001 -0.047127999, + 0.036603201 -0.016589699 -0.048526999, + 0.040174201 -0.0162117 -0.045101002, + 0.0390082 -0.0166358 -0.046556, + 0.0378174 -0.015646599 -0.046813998, + 0.035840798 -0.0145 -0.048119001, + 0.0424264 -0.016710401 -0.043364, + 0.043510102 -0.017068701 -0.042711001, + 0.0053918599 -0.061895601 -0.162352, + 0.0059725801 -0.061702002 -0.1715, + 0.0081421202 -0.061582699 -0.162365, + 0.0081421202 -0.062003098 -0.15321399, + 0.0378174 -0.017072501 -0.048969999, + 0.0378174 -0.0170465 -0.048535999, + 0.0390082 -0.017123699 -0.047954999, + 0.0378174 -0.0170469 -0.049422, + 0.040174201 -0.017173201 -0.047352001, + 0.040174201 -0.0171325 -0.049127001, + 0.051830001 -0.021267001 -0.043405998, + 0.051830001 -0.0209565 -0.041756999, + 0.0532961 -0.0226746 -0.042105, + 0.050219599 -0.0200908 -0.044686001, + 0.050219599 -0.0198787 -0.043088999, + 0.048467699 -0.019149501 -0.045901999, + 0.048467699 -0.018971801 -0.044321001, + 0.0465803 -0.018376701 -0.047001999, + 0.0465803 -0.018239699 -0.045375001, + 0.044564299 -0.0177758 -0.047913998, + 0.044564299 -0.0177132 -0.046234, + 0.0424264 -0.017371301 -0.048622001, + 0.0424264 -0.017361401 -0.046895999, + 0.0424264 -0.0173072 -0.045157, + 0.041313998 -0.017231099 -0.045830999, + 0.044564299 -0.0176025 -0.044546001, + 0.0465803 -0.018070901 -0.043735001, + 0.048467699 -0.018722201 -0.042734999, + 0.050219599 -0.0195871 -0.041549001, + 0.051830001 -0.0206287 -0.040194999, + 0.0532961 -0.0218424 -0.038759999, + 0.0546159 -0.023824999 -0.039009999, + 0.0546159 -0.024300201 -0.040826, + 0.055787299 -0.025592901 -0.037682001, + 0.055787299 -0.026125301 -0.039609998, + 0.056809202 -0.0275562 -0.03644, + 0.056809202 -0.0281235 -0.038497001, + 0.0576833 -0.029685801 -0.035324998, + 0.0576833 -0.030261699 -0.037519, + 0.058412101 -0.031945799 -0.034368001, + 0.058412101 -0.032500401 -0.036704998, + 0.058998398 -0.034294199 -0.033594001, + 0.058998398 -0.0347974 -0.036072001, + 0.059445001 -0.036685899 -0.033022001, + 0.059445001 -0.037106998 -0.035631001, + 0.059757002 -0.0390727 -0.032662001, + 0.059757002 -0.039384499 -0.035388, + 0.0599402 -0.041412301 -0.032510001, + 0.0599402 -0.041590098 -0.035332002, + 0.059999999 -0.043681201 -0.032531999, + 0.059999999 -0.0437105 -0.035432, + 0.0599402 -0.0458721 -0.03269, + 0.0599402 -0.045740101 -0.035634998, + 0.059757002 -0.047981199 -0.032931, + 0.059757002 -0.047707401 -0.035953, + 0.059445001 -0.050034799 -0.033278, + 0.059445001 -0.049708001 -0.036465999, + 0.058998398 -0.0521143 -0.033831999, + 0.058998398 -0.0517378 -0.037108999, + 0.058412101 -0.054210801 -0.034529999, + 0.058412101 -0.053773802 -0.037881002, + 0.0576833 -0.056301199 -0.035371002, + 0.0576833 -0.055797301 -0.038791999, + 0.056809202 -0.058366299 -0.036362, + 0.056809202 -0.057789698 -0.039850999, + 0.055787299 -0.060387101 -0.037510999, + 0.055787299 -0.0597318 -0.041065, + 0.0546159 -0.0623434 -0.038825002, + 0.0546159 -0.0616032 -0.042440999, + 0.0532961 -0.064213902 -0.040309001, + 0.0532961 -0.063381799 -0.043981999, + 0.051830001 -0.065976001 -0.041965999, + 0.051830001 -0.065052502 -0.045689002, + 0.050219599 -0.067613803 -0.043795999, + 0.050219599 -0.066602103 -0.047575999, + 0.048467699 -0.0691135 -0.045807999, + 0.048467699 -0.067998901 -0.049644999, + 0.0465803 -0.070444703 -0.048005, + 0.0465803 -0.069221303 -0.051886, + 0.044564299 -0.071586199 -0.050372001, + 0.044564299 -0.070250504 -0.054281998, + 0.0424264 -0.072519504 -0.052894998, + 0.0424264 -0.071068399 -0.056820001, + 0.040174201 -0.073227398 -0.055555999, + 0.040174201 -0.071657702 -0.059484001, + 0.0378174 -0.0736956 -0.058340002, + 0.0378174 -0.0720063 -0.062254999, + 0.035366699 -0.073913097 -0.061228, + 0.035366699 -0.0705081 -0.069201, + 0.0328326 -0.072274096 -0.068327002, + 0.0328326 -0.0691128 -0.076509997, + 0.0302257 -0.070733503 -0.075778, + 0.0302257 -0.067825899 -0.084151, + 0.027557701 -0.069299698 -0.083548002, + 0.027557701 -0.066653401 -0.092090003, + 0.0248404 -0.067978904 -0.091603003, + 0.0248404 -0.065600701 -0.100293, + 0.0220857 -0.066776499 -0.099909998, + 0.0220857 -0.064672098 -0.108727, + 0.019305199 -0.065697201 -0.108435, + 0.019305199 -0.063869201 -0.117359, + 0.0165099 -0.064745501 -0.117146, + 0.0165099 -0.063196003 -0.126156, + 0.0137106 -0.063926503 -0.126008, + 0.0137106 -0.062657498 -0.135085, + 0.0109179 -0.063244998 -0.13499001, + 0.0109179 -0.062258601 -0.144114, + 0.0081421202 -0.062706299 -0.14406, + 0.0053918599 -0.062316202 -0.15318801, + 0.00267513 -0.0620795 -0.16234399, + 0.00308863 -0.061919201 -0.1715, + 0 -0.0621401 -0.162342, + 9.4966999e-005 -0.061999898 -0.1715, + 0.00267513 -0.062500402 -0.153173, + 0.0053918599 -0.063019402 -0.144022, + 0.0081421202 -0.0636926 -0.13491701, + 0.0109179 -0.064514101 -0.125889, + 0.0137106 -0.065476403 -0.116968, + 0.0165099 -0.066574097 -0.108186, + 0.019305199 -0.067802303 -0.099575996, + 0.0220857 -0.069155604 -0.091170996, + 0.0248404 -0.0706264 -0.083005004, + 0.027557701 -0.072209097 -0.075111002, + 0.0302257 -0.073897503 -0.067523003, + 0.0328326 -0.075683102 -0.060274001, + 0.035366699 -0.0756035 -0.057270002, + 0.0378174 -0.075263403 -0.054365002, + 0.040174201 -0.074673198 -0.051577002, + 0.0424264 -0.073846102 -0.048925001, + 0.044564299 -0.072796598 -0.046427, + 0.0465803 -0.071542099 -0.044098999, + 0.048467699 -0.070103697 -0.041955002, + 0.050219599 -0.068510696 -0.039995998, + 0.051830001 -0.0667772 -0.038215999, + 0.0532961 -0.064919502 -0.036614999, + 0.0546159 -0.062960401 -0.035193, + 0.055787299 -0.060921699 -0.033945002, + 0.056809202 -0.058825001 -0.032864999, + 0.0576833 -0.056689698 -0.031945001, + 0.058412101 -0.054535899 -0.031181, + 0.058998398 -0.052387301 -0.030572999, + 0.059445001 -0.0502523 -0.030191001, + 0.059757002 -0.0480504 -0.029927, + 0.0599402 -0.045772199 -0.029731, + 0.059999999 -0.043424301 -0.029654, + 0.0599402 -0.041012399 -0.029732, + 0.059757002 -0.038554199 -0.030005001, + 0.059445001 -0.036076501 -0.030502999, + 0.058998398 -0.033626001 -0.031222999, + 0.058412101 -0.031250399 -0.032148998, + 0.0576833 -0.0289947 -0.033254001, + 0.056809202 -0.026897701 -0.034508001, + 0.055787299 -0.0249913 -0.035872001, + 0.0546159 -0.0227447 -0.035707001, + 0.0532961 -0.0213964 -0.037234001, + 0.051830001 -0.020220101 -0.038697999, + 0.050219599 -0.019221 -0.040004998, + 0.048467699 -0.0184428 -0.041136, + 0.0465803 -0.0178548 -0.042086001, + 0.044564299 -0.0174483 -0.042844001, + 0.043510102 -0.017344501 -0.043586001, + 0.0424264 -0.017033299 -0.043839, + 0.0424264 -0.017217699 -0.044305999, + 0.041313998 -0.0169989 -0.044938002, + 0.043510102 -0.0172635 -0.043173, + 0.044564299 -0.0174034 -0.04242, + 0.045588002 -0.0174636 -0.041228, + 0.044564299 -0.0173105 -0.042011999, + 0.040174201 -0.016659901 -0.045522001, + 0.040174201 -0.0169654 -0.046007, + 0.041313998 -0.0171731 -0.04541, + 0.0424264 -0.0172871 -0.044723, + 0.040174201 -0.0171296 -0.046482999, + 0.0390082 -0.016932899 -0.047045, + 0.0378174 -0.016612399 -0.047557998, + 0.0378174 -0.016901299 -0.048052002, + 0.0390082 -0.0170874 -0.047525998, + 0.040174201 -0.0171766 -0.046909001, + 0.036603201 -0.0168707 -0.049024999, + 0.035366699 -0.0165678 -0.049463999, + 0.034109399 -0.0165467 -0.050365001, + 0.035366699 -0.016841199 -0.049966, + 0.036603201 -0.0170069 -0.049513999, + 0.035366699 -0.0169749 -0.050900001, + 0.0328326 -0.0168844 -0.052691001, + 0.034109399 -0.0169318 -0.051368002, + 0.035366699 -0.0169286 -0.05136, + 0.0378174 -0.016916599 -0.051231001, + 0.040174201 -0.0170468 -0.050889999, + 0.0424264 -0.0173325 -0.050340001, + 0.044564299 -0.0178045 -0.04958, + 0.0465803 -0.0184443 -0.048622999, + 0.048467699 -0.0192493 -0.047533002, + 0.050219599 -0.0202829 -0.046360001, + 0.051830001 -0.021545 -0.045145001, + 0.0532961 -0.023025099 -0.043928001, + 0.0546159 -0.024707699 -0.042750001, + 0.055787299 -0.0265694 -0.041652001, + 0.056809202 -0.0285799 -0.040665999, + 0.0576833 -0.0307023 -0.039822999, + 0.058412101 -0.032896899 -0.039140999, + 0.058998398 -0.0351201 -0.038633, + 0.059445001 -0.037329599 -0.038304999, + 0.059757002 -0.039482798 -0.038153999, + 0.0599402 -0.0415489 -0.038175002, + 0.059999999 -0.043516301 -0.038316999, + 0.0599402 -0.0454107 -0.038594, + 0.059757002 -0.047327399 -0.039073002, + 0.059445001 -0.049280401 -0.039671, + 0.058998398 -0.051252399 -0.040385, + 0.058412101 -0.0532245 -0.041226, + 0.0576833 -0.055178501 -0.042203002, + 0.056809202 -0.0570958 -0.043327, + 0.055787299 -0.0589565 -0.044603001, + 0.0546159 -0.0607397 -0.046036001, + 0.0532961 -0.062431101 -0.047628, + 0.051830001 -0.0640186 -0.049394, + 0.050219599 -0.065469898 -0.051341999, + 0.048467699 -0.066762201 -0.053459998, + 0.0465803 -0.067876302 -0.055734999, + 0.044564299 -0.0687939 -0.058150999, + 0.0424264 -0.069496602 -0.060695998, + 0.040174201 -0.069969498 -0.063352004, + 0.0378174 -0.068605497 -0.070142999, + 0.035366699 -0.067349598 -0.077307999, + 0.0328326 -0.0662072 -0.084813997, + 0.0302257 -0.065181002 -0.092630997, + 0.027557701 -0.064276204 -0.100724, + 0.0248404 -0.063497201 -0.109061, + 0.0220857 -0.062844798 -0.117608, + 0.019305199 -0.062320098 -0.126334, + 0.0165099 -0.0619273 -0.135203, + 0.0137106 -0.061671201 -0.144186, + 0.0109179 -0.0615554 -0.15324999, + 0.0092321504 -0.0612779 -0.1715, + 0.031537499 -0.016862299 -0.053080998, + 0.0302257 -0.016488301 -0.052859001, + 0.0288986 -0.016470499 -0.053617001, + 0.0302257 -0.016734101 -0.053374998, + 0.031537499 -0.0167592 -0.052577, + 0.0328326 -0.0168963 -0.052243002, + 0.0328326 -0.0167854 -0.051741999, + 0.031537499 -0.016506899 -0.052064002, + 0.0328326 -0.016526399 -0.051231999, + 0.034109399 -0.016812799 -0.050872002, + 0.035366699 -0.0169686 -0.050457999, + 0.028196299 -0.0145 -0.052956, + 0.0275509 -0.0145 -0.053282999, + 0.0353604 -0.0145 -0.048459001, + 0.038435601 -0.0094999997 -0.046073001, + 0.0381575 -0.0145 -0.046303, + 0.037812401 -0.0145 -0.046574, + 0.040170401 -0.0145 -0.04456, + 0.0429691 -0.0094999997 -0.041877002, + 0.055787299 -0.0152108 -0.02214, + 0.056127101 -0.0145 -0.021159001, + 0.056809202 -0.0152262 -0.019358, + 0.056809202 -0.015943199 -0.019475, + 0.0546159 -0.0151956 -0.024896, + 0.0554736 -0.0145 -0.022862, + 0.055787299 -0.0159129 -0.022262, + 0.056809202 -0.0166336 -0.019703001, + 0.0576833 -0.0166802 -0.016892999, + 0.0576833 -0.0173201 -0.017201999, + 0.058412101 -0.0173859 -0.014376, + 0.058412101 -0.0183987 -0.015062, + 0.058998398 -0.0185134 -0.012218, + 0.058998398 -0.019280599 -0.012807, + 0.059445001 -0.019454399 -0.0099579897, + 0.059445001 -0.022574401 -0.012265, + 0.059757002 -0.022991 -0.009354, + 0.059757002 -0.026248701 -0.011538, + 0.0599402 -0.0269065 -0.0085740099, + 0.0599402 -0.0285502 -0.0096270004, + 0.059999999 -0.029323401 -0.0066430098, + 0.059999999 -0.030992899 -0.0078019998, + 0.0599402 -0.031885501 -0.0047829999, + 0.0599402 -0.033692401 -0.00611099, + 0.059757002 -0.034715202 -0.0030420099, + 0.059757002 -0.036627099 -0.0045639998, + 0.059445001 -0.037789401 -0.001437, + 0.059445001 -0.039777599 -0.003179, + 0.058998398 -0.0410797 -1.19934e-005, + 0.058998398 -0.043108899 -0.001991, + 0.058412101 -0.044546001 0.001192, + 0.058412101 -0.046575401 -0.00103799, + 0.0576833 -0.048139799 0.002138, + 0.0576833 -0.050126102 -0.000345993, + 0.056809202 -0.051807601 0.0028009899, + 0.056809202 -0.053704701 6.7001303e-005, + 0.055787299 -0.056405298 0.001703, + 0.055787299 -0.057255398 0.000195999, + 0.0546159 -0.0591297 0.0032230101, + 0.0546159 -0.059961401 0.00165199, + 0.0532961 -0.061859298 0.0046150102, + 0.0532961 -0.062665902 0.0029819901, + 0.051830001 -0.064575799 0.005868, + 0.051830001 -0.065350503 0.0041769999, + 0.050219599 -0.0672599 0.006972, + 0.050219599 -0.067996003 0.0052270102, + 0.048467699 -0.069892302 0.0079190098, + 0.048467699 -0.070583001 0.0061249998, + 0.0465803 -0.072453797 0.0087029999, + 0.0465803 -0.073094398 0.0068640001, + 0.044564299 -0.074927203 0.0093189999, + 0.044564299 -0.075513303 0.0074379998, + 0.0424264 -0.077295303 0.0097599896, + 0.0424264 -0.077822901 0.0078439899, + 0.040174201 -0.079541601 0.010025, + 0.040174201 -0.080006301 0.0080819996, + 0.0378174 -0.081651203 0.010116, + 0.0378174 -0.0820475 0.0081670098, + 0.035366699 -0.083608598 0.01005, + 0.035366699 -0.083939001 0.0080840001, + 0.0328326 -0.0854064 0.0098130004, + 0.0328326 -0.085702501 0.0077300002, + 0.0302257 -0.087067403 0.0092989998, + 0.0302257 -0.087344103 0.007158, + 0.027557701 -0.088857502 0.0063939998, + 0.051520798 -0.0145 -0.030750999, + 0.051830001 -0.0151658 -0.030283, + 0.0506116 -0.0145 -0.032191999, + 0.050626501 -0.0094999997 -0.032202002, + 0.050211199 -0.0145 -0.032827001, + 0.050219599 -0.0151513 -0.032891002, + 0.051830001 -0.0158245 -0.03042, + 0.055787299 -0.0176783 -0.023213999, + 0.055787299 -0.0171891 -0.02283, + 0.056809202 -0.0181689 -0.020759, + 0.0546159 -0.0171244 -0.025611, + 0.0546159 -0.0165412 -0.025268, + 0.0532961 -0.0164958 -0.028000001, + 0.0532961 -0.0158535 -0.027745999, + 0.0532961 -0.0151806 -0.027613999, + 0.0529669 -0.0145 -0.028186999, + 0.0546159 -0.015883001 -0.025023, + 0.055787299 -0.0165872 -0.022499001, + 0.056809202 -0.0172545 -0.020022999, + 0.0576833 -0.018283701 -0.017913001, + 0.0576833 -0.0189305 -0.018548001, + 0.058412101 -0.019105799 -0.015674001, + 0.058412101 -0.021729499 -0.018169999, + 0.058998398 -0.022153299 -0.015208, + 0.058998398 -0.0249083 -0.017577, + 0.059445001 -0.025582099 -0.014541, + 0.059445001 -0.0269813 -0.015682001, + 0.059757002 -0.027771 -0.012635, + 0.059757002 -0.0292008 -0.013865, + 0.0599402 -0.030100301 -0.010822, + 0.0599402 -0.031662699 -0.012203, + 0.059999999 -0.032677501 -0.0091570001, + 0.059999999 -0.034341902 -0.010712, + 0.0599402 -0.035480101 -0.0076499898, + 0.0599402 -0.037218101 -0.0094040101, + 0.059757002 -0.038489301 -0.0063120001, + 0.059757002 -0.040268201 -0.0082830004, + 0.059445001 -0.041680899 -0.0051540099, + 0.059445001 -0.0434638 -0.0073549999, + 0.058998398 -0.045014702 -0.0042059901, + 0.058998398 -0.046762101 -0.0066410098, + 0.058412101 -0.048442099 -0.0034969901, + 0.058412101 -0.0501118 -0.0061639999, + 0.0576833 -0.051909599 -0.0030460099, + 0.0576833 -0.0534616 -0.0059310002, + 0.056809202 -0.055363599 -0.0028589901, + 0.056809202 -0.056758299 -0.0059429901, + 0.019305199 -0.092649497 -0.012825, + 0.0220857 -0.091793798 -0.011402, + 0.019305199 -0.092820898 -0.008289, + 0.0165099 -0.093478002 -0.012114, + 0.0165099 -0.093156397 -0.016671, + 0.0137106 -0.093856603 -0.016099, + 0.0137106 -0.093381703 -0.020666, + 0.0109179 -0.093951598 -0.020222999, + 0.0109179 -0.093321599 -0.024788, + 0.0081421202 -0.093760297 -0.024463, + 0.0081421202 -0.0929735 -0.029012, + 0.0053918599 -0.093282603 -0.028795, + 0.0053918599 -0.092337497 -0.033316001, + 0.00267513 -0.092519999 -0.033193, + 0.00267513 -0.091418102 -0.037673999, + 0 -0.091477796 -0.037636001, + 0 -0.0902218 -0.042064998, + -0.00267513 -0.091417603 -0.037675001, + -0.00267513 -0.092519499 -0.033193, + -0.0053918599 -0.092336498 -0.033316001, + -0.0053918599 -0.093281902 -0.028795, + -0.0081421202 -0.092972398 -0.029012, + -0.0081421202 -0.093759798 -0.024463, + -0.0109179 -0.093320899 -0.024786999, + -0.0109179 -0.093950801 -0.020222999, + -0.0137106 -0.093380697 -0.020666, + -0.0137106 -0.093854897 -0.016099, + -0.0165099 -0.093154401 -0.016671, + -0.0165099 -0.093475103 -0.012114, + -0.019305199 -0.0926461 -0.012824, + -0.019305199 -0.092816301 -0.008289, + -0.0220857 -0.0918613 -0.009149, + -0.0220857 -0.091885902 -0.0046470002, + -0.0248404 -0.090808801 -0.0056659998, + -0.0378174 -0.083024301 3.00598e-006, + -0.035366699 -0.084661298 0.001795, + -0.0378174 -0.082609899 0.0041710101, + -0.040174201 -0.080900602 0.00220599, + -0.040174201 -0.0806631 0.0042300001, + -0.0424264 -0.0788721 0.0021200001, + -0.0424264 -0.078604497 0.0040229899, + -0.044564299 -0.076741204 0.00177499, + -0.044564299 -0.076415002 0.0036530001, + -0.0465803 -0.074491501 0.00127499, + -0.0465803 -0.0741053 0.0031410099, + -0.048467699 -0.072134398 0.00064100599, + -0.048467699 -0.071694098 0.00247701, + -0.050219599 -0.069688402 -0.000134995, + -0.050219599 -0.069198698 0.001664, + -0.051830001 -0.067170702 -0.001052, + -0.051830001 -0.066636197 0.00070500199, + -0.0532961 -0.064598702 -0.00210201, + -0.0532961 -0.064023897 -0.00038999901, + -0.0546159 -0.0619899 -0.00327699, + -0.0546159 -0.061379701 -0.0016120001, + -0.055787299 -0.058722001 -0.0029539899, + -0.0220857 -0.091010399 0.00874699, + -0.0248404 -0.0899942 0.0076339999, + -0.0220857 -0.091253497 0.0065319999, + -0.0248404 -0.089423403 0.012006, + -0.027557701 -0.088304304 0.010719, + -0.027557701 -0.087978698 0.012847, + -0.0302257 -0.086750403 0.0114, + -0.0302257 -0.086384602 0.013407, + -0.0328326 -0.0850522 0.011799, + -0.0328326 -0.0846138 0.013788, + -0.035366699 -0.0831839 0.012021, + -0.035366699 -0.082670502 0.014005, + -0.0378174 -0.081152499 0.01208, + -0.0378174 -0.080569699 0.014039, + -0.040174201 -0.078973897 0.01196, + -0.040174201 -0.078325897 0.013886, + -0.0424264 -0.0766626 0.011658, + -0.0424264 -0.075953901 0.013544, + -0.044564299 -0.0742338 0.011174, + -0.044564299 -0.073468901 0.013015, + -0.0465803 -0.071704596 0.010511, + -0.0465803 -0.070888601 0.012303, + -0.048467699 -0.069092803 0.0096749999, + -0.048467699 -0.068232499 0.011412, + -0.050219599 -0.066417702 0.0086710099, + -0.050219599 -0.065520197 0.010349, + -0.051830001 -0.063698702 0.0075059999, + -0.051830001 -0.062770799 0.0091199996, + -0.0532961 -0.060954899 0.0061880001, + -0.0532961 -0.0600035 0.007735, + -0.0546159 -0.058205198 0.0047280001, + -0.0546159 -0.057238501 0.006207, + -0.055787299 -0.055469099 0.0031390099, + -0.055787299 -0.054494798 0.0045480002, + -0.056809202 -0.0517902 0.0027729899, + -0.055787299 -0.053463101 0.00590401, + -0.0546159 -0.056209002 0.0076339999, + -0.0532961 -0.058984 0.0092339898, + -0.051830001 -0.061769299 0.010688, + -0.050219599 -0.064545102 0.011985, + -0.048467699 -0.067290999 0.013113, + -0.0465803 -0.069987603 0.014063, + -0.044564299 -0.072615601 0.01483, + -0.0424264 -0.075155102 0.015408, + -0.040174201 -0.0775868 0.015794, + -0.0378174 -0.079894498 0.015985999, + -0.035366699 -0.0820636 0.015985001, + -0.0328326 -0.084079497 0.015791999, + -0.0302257 -0.085928299 0.015413, + -0.027557701 -0.087597601 0.01487, + -0.0248404 -0.089084499 0.014149, + -0.0220857 -0.0904167 0.013148, + -0.019305199 -0.091896899 0.009718, + -0.019305199 -0.092364103 0.00525301, + -0.0165099 -0.093138598 0.00606, + 0.0165099 -0.093469597 0.00154401, + 0.019305199 -0.092545703 0.0030129999, + 0.0165099 -0.093144096 0.0060649998, + 0.0137106 -0.094127297 0.00219701, + 0.0137106 -0.094303697 -0.0023650101, + 0.0109179 -0.094842099 -0.001855, + 0.0109179 -0.094865002 -0.0064470102, + 0.0081421202 -0.095281899 -0.0060709999, + 0.0081421202 -0.095147498 -0.010681, + 0.0053918599 -0.0954431 -0.010427, + 0.0053918599 -0.095148198 -0.015044, + 0.00267513 -0.095324002 -0.0149, + 0.00267513 -0.094867103 -0.019512, + 0 -0.094925202 -0.019466, + 0 -0.094305404 -0.02406, + -0.00267513 -0.094866902 -0.019512, + -0.00267513 -0.095323697 -0.0149, + -0.0053918599 -0.095147602 -0.015044, + -0.0053918599 -0.095442198 -0.010427, + -0.0081421202 -0.095146 -0.010681, + -0.0081421202 -0.095279999 -0.0060709999, + -0.0109179 -0.094862401 -0.0064470102, + -0.0109179 -0.094838902 -0.001856, + -0.0137106 -0.094299696 -0.0023650101, + -0.0137106 -0.094122797 0.00219501, + -0.0165099 -0.093464203 0.00154201, + -0.019305199 -0.092674501 0.00075799599, + -0.0220857 -0.091624796 0.002078, + -0.0165099 -0.093629301 -0.00299899, + -0.0137106 -0.094314396 -0.0069400002, + -0.0109179 -0.094722398 -0.011044, + -0.0081421202 -0.094847597 -0.015289, + -0.0053918599 -0.094688699 -0.019649999, + -0.00267513 -0.094246499 -0.024103001, + 0 -0.093523003 -0.028625, + 0.00267513 -0.0942467 -0.024103001, + 0.0053918599 -0.094689101 -0.019649999, + 0.0081421202 -0.094848603 -0.015289, + 0.0109179 -0.094724298 -0.011044, + 0.0137106 -0.094317697 -0.0069400002, + 0.0165099 -0.093634203 -0.002998, + 0.019305199 -0.092776097 -0.00149699, + 0.035366699 -0.084461398 0.0039240001, + 0.035366699 -0.084671699 0.0018119999, + 0.0378174 -0.082617797 0.004183, + 0.0328326 -0.086190499 0.0034739999, + 0.0328326 -0.0863823 0.00133, + 0.0302257 -0.087793402 0.00283701, + 0.0302257 -0.087963 0.00066299399, + 0.027557701 -0.089260899 0.00201601, + 0.027557701 -0.089405097 -0.000184006, + 0.0248404 -0.090585001 0.0010169999, + 0.0248404 -0.090701498 -0.00120599, + 0.0220857 -0.091758698 -0.000156006, + 0.0220857 -0.091845401 -0.0023990001, + 0.019305199 -0.092831202 -0.003758, + 0.0165099 -0.093637198 -0.0075539998, + 0.0137106 -0.094168797 -0.011521, + 0.0109179 -0.094419599 -0.015639, + 0.0081421202 -0.094385803 -0.019886, + 0.0053918599 -0.094066903 -0.024236999, + 0.00267513 -0.093464002 -0.028666999, + 0 -0.092579499 -0.033153001, + -0.00267513 -0.0934636 -0.028666999, + -0.0053918599 -0.094066501 -0.024235999, + -0.0081421202 -0.094385199 -0.019886, + -0.0109179 -0.094418302 -0.015639, + -0.0137106 -0.094166301 -0.011521, + -0.0165099 -0.093633197 -0.0075539998, + -0.019305199 -0.092825502 -0.003759, + -0.0220857 -0.091751397 -0.00015899701, + -0.0248404 -0.090576701 0.00101199, + -0.0248404 -0.090420902 0.0032270099, + -0.027557701 -0.089251697 0.0020079999, + -0.027557701 -0.089069098 0.0041979998, + -0.0302257 -0.087783702 0.0028250001, + -0.0302257 -0.087577701 0.00498801, + -0.0328326 -0.086180799 0.003459, + -0.0328326 -0.085695602 0.0077189901, + -0.035366699 -0.084210202 0.0060109999, + -0.035366699 -0.083933398 0.0080819996, + -0.0378174 -0.082352199 0.0062199999, + -0.0378174 -0.082041197 0.0081679998, + -0.040174201 -0.080373198 0.0061560101, + -0.040174201 -0.079998001 0.0080819996, + -0.0424264 -0.078253202 0.0059250002, + -0.0424264 -0.0778118 0.0078429999, + -0.044564299 -0.076000497 0.0055450001, + -0.044564299 -0.075499102 0.00743401, + -0.0465803 -0.073633797 0.0050039999, + -0.0465803 -0.0730768 0.00685699, + -0.048467699 -0.071170203 0.0043040002, + -0.048467699 -0.070562303 0.00611501, + -0.050219599 -0.068627 0.00344901, + -0.050219599 -0.067972697 0.0052149999, + -0.051830001 -0.066021197 0.00244501, + -0.051830001 -0.065325603 0.004162, + -0.0532961 -0.063370697 0.00130099, + -0.0532961 -0.062640302 0.002965, + -0.0546159 -0.060694501 2.6001e-005, + -0.0546159 -0.059935901 0.001632, + -0.055787299 -0.0580112 -0.00137199, + -0.055787299 -0.0572307 0.000173996, + -0.056809202 -0.055338401 -0.0028820001, + -0.0328326 -0.086371802 0.00131599, + -0.0302257 -0.087953001 0.00065400702, + -0.027557701 -0.089395903 -0.00018899501, + -0.0248404 -0.090693302 -0.001209, + -0.0248404 -0.090770699 -0.0034350001, + -0.027557701 -0.089501299 -0.0023930101, + -0.0302257 -0.088084199 -0.001524, + -0.0328326 -0.086526401 -0.00083299301, + -0.035366699 -0.084835902 -0.000324997, + -0.035366699 -0.084974602 -0.002451, + -0.0328326 -0.086643502 -0.00299001, + -0.0302257 -0.0881771 -0.0037070001, + -0.027557701 -0.089567803 -0.0046009999, + 0.0220857 -0.091899499 -0.0068970001, + 0.0378174 -0.083193302 -0.002078, + 0.0378174 -0.083315402 -0.004183, + 0.040174201 -0.0812876 -0.00189301, + 0.035366699 -0.084986404 -0.0024409899, + 0.035366699 -0.085088097 -0.0045770002, + 0.0328326 -0.086654499 -0.0029829999, + 0.0328326 -0.086733498 -0.0051469998, + 0.0302257 -0.088187002 -0.003703, + 0.0302257 -0.0882411 -0.0058930102, + 0.027557701 -0.089576498 -0.0045989999, + 0.027557701 -0.089603499 -0.0068120002, + 0.0248404 -0.090816103 -0.0056649898, + 0.0248404 -0.090814203 -0.0078990003, + 0.0220857 -0.091866598 -0.009149, + 0.0248404 -0.090772599 -0.010135, + 0.027557701 -0.089591399 -0.0090279998, + 0.0302257 -0.088256396 -0.0080870101, + 0.0328326 -0.0867742 -0.0073150001, + 0.035366699 -0.085152097 -0.0067179999, + 0.0378174 -0.083400503 -0.0062940102, + 0.040174201 -0.0815304 -0.0060440102, + 0.0424264 -0.079434097 -0.0039220001, + 0.0424264 -0.079096802 0.000134995, + 0.044564299 -0.077187702 -0.0020590101, + 0.044564299 -0.076992303 -0.000100006, + 0.0465803 -0.075018302 -0.0024250001, + 0.0465803 -0.074799202 -0.000578003, + 0.048467699 -0.072772101 -0.003024, + 0.048467699 -0.072501399 -0.001198, + 0.050219599 -0.070433602 -0.003755, + 0.050219599 -0.070109598 -0.001942, + 0.051830001 -0.068013601 -0.0046009999, + 0.051830001 -0.067641698 -0.00281799, + 0.0532961 -0.065530598 -0.0055689998, + 0.0532961 -0.065115198 -0.00382401, + 0.0546159 -0.063001901 -0.0066550002, + 0.0546159 -0.062546998 -0.0049510002, + 0.055787299 -0.060444001 -0.0078490004, + 0.055787299 -0.0599536 -0.0061900001, + 0.055787299 -0.059388101 -0.0045509902, + 0.0546159 -0.062015198 -0.00326401, + 0.0532961 -0.064621501 -0.0020920001, + 0.051830001 -0.0671902 -0.001045, + 0.050219599 -0.069704399 -0.000130997, + 0.048467699 -0.072146997 0.00064300501, + 0.0465803 -0.074501097 0.00127499, + 0.044564299 -0.076748602 0.001774, + 0.0424264 -0.078878798 0.0021230001, + 0.040174201 -0.080908902 0.0022189899, + 0.0378174 -0.083035499 2.09961e-005, + 0.035366699 -0.084847197 -0.00031100499, + 0.0328326 -0.086537398 -0.00082400499, + 0.0302257 -0.088094302 -0.00151801, + 0.027557701 -0.089510299 -0.00238901, + 0.0248404 -0.0907785 -0.0034330001, + 0.0220857 -0.091892399 -0.004646, + 0.040174201 -0.0806695 0.0042319898, + 0.0424264 -0.078611597 0.0040210001, + 0.044564299 -0.0764241 0.0036519901, + 0.0465803 -0.0741174 0.00314301, + 0.048467699 -0.071709603 0.00248199, + 0.050219599 -0.069217697 0.00167101, + 0.051830001 -0.066658303 0.00071499601, + 0.0532961 -0.064048603 -0.000376999, + 0.0546159 -0.061405901 -0.0015970001, + 0.055787299 -0.0587487 -0.002936, + 0.055787299 -0.0580373 -0.0013520099, + 0.0546159 -0.060720701 4.2999302e-005, + 0.0532961 -0.063396297 0.00131599, + 0.051830001 -0.066045202 0.0024579901, + 0.050219599 -0.068648502 0.00345799, + 0.048467699 -0.071188502 0.004311, + 0.0465803 -0.073648602 0.0050090002, + 0.044564299 -0.076012097 0.0055470001, + 0.0424264 -0.078261897 0.0059250002, + 0.040174201 -0.080379903 0.0061550001, + 0.0378174 -0.082358196 0.0062219999, + 0.035366699 -0.084217504 0.0060229902, + 0.0328326 -0.085963398 0.0056089899, + 0.0302257 -0.087586597 0.0050030099, + 0.027557701 -0.089077897 0.0042090002, + 0.0248404 -0.090429097 0.0032339899, + 0.0220857 -0.091632202 0.00208299, + 0.019305199 -0.092680901 0.00075999502, + 0.0220857 -0.091466099 0.00431599, + 0.0248404 -0.090234198 0.00544501, + 0.053653099 -0.0145 -0.026818, + 0.054285601 -0.0145 -0.025555, + 0.053669199 -0.0094999997 -0.026826, + 0.053284999 -0.0145 -0.027551999, + 0.051820099 -0.0145 -0.03022, + 0.048462 -0.0145 -0.035363, + 0.055400901 -0.0145 0.023038, + 0.055771999 -0.0145 0.02208, + 0.054601699 -0.0145 0.024834, + 0.0546159 -0.016422501 0.024769001, + 0.054204401 -0.0145 0.025727, + 0.053669199 -0.0094999997 0.026826, + 0.0528774 -0.0145 0.028354, + 0.0532832 -0.0145 0.027550999, + 0.051817998 -0.0145 0.030219, + 0.051830001 -0.0164809 0.030166, + 0.051423199 -0.0145 0.030913999, + 0.050626501 -0.0094999997 0.032202002, + 0.048459399 -0.0145 0.035360999, + 0.047047202 -0.0094999997 0.037237, + 0.048147298 -0.0145 0.035803001, + 0.044560701 -0.0145 0.040171001, + 0.044408198 -0.0145 0.040346999, + 0.0445357 -0.0145 -0.040206999, + 0.0429601 -0.0145 -0.041868001, + 0.0425102 -0.0145 -0.042342, + 0.0424245 -0.0145 -0.042424001, + 0.051830001 -0.0177199 -0.031881001, + 0.051830001 -0.017917 -0.032249, + 0.050219599 -0.017612699 -0.034536, + 0.050219599 -0.017782399 -0.034914002, + 0.051830001 -0.018071501 -0.03263, + 0.0532961 -0.018952999 -0.031378001, + 0.0546159 -0.0200404 -0.029973, + 0.055787299 -0.0213365 -0.028427999, + 0.056809202 -0.022871699 -0.026752001, + 0.0576833 -0.0245746 -0.024970001, + 0.058412101 -0.025379799 -0.021863, + 0.058412101 -0.026440401 -0.023204001, + 0.058998398 -0.0273677 -0.020067001, + 0.058998398 -0.028555799 -0.021528, + 0.059445001 -0.029603399 -0.018383, + 0.059445001 -0.030894401 -0.019988, + 0.059757002 -0.032056801 -0.016860999, + 0.059757002 -0.033424001 -0.018633001, + 0.0599402 -0.034695201 -0.015541, + 0.0599402 -0.036107399 -0.017499, + 0.059999999 -0.037490699 -0.014435, + 0.059999999 -0.038913101 -0.016593, + 0.0599402 -0.040415499 -0.013543, + 0.0599402 -0.041811399 -0.015906001, + 0.059757002 -0.043441199 -0.012856, + 0.059757002 -0.044772901 -0.015422, + 0.059445001 -0.046536099 -0.012365, + 0.059445001 -0.047768202 -0.015125, + 0.058998398 -0.049656499 -0.012076, + 0.058998398 -0.050753701 -0.015015, + 0.058412101 -0.052753098 -0.011994, + 0.058412101 -0.053685799 -0.015088, + 0.0576833 -0.055780798 -0.012114, + 0.0576833 -0.056522701 -0.015333, + 0.056809202 -0.0592332 -0.01574, + 0.055787299 -0.0617861 -0.016277, + 0.0546159 -0.064189598 -0.017003, + 0.0532961 -0.066542499 -0.018036, + 0.051830001 -0.068834797 -0.019282, + 0.050219599 -0.071037598 -0.020736, + 0.048467699 -0.073127501 -0.022399001, + 0.0465803 -0.075082399 -0.024272, + 0.044564299 -0.076880299 -0.026354, + 0.0424264 -0.078499101 -0.028643001, + 0.040174201 -0.079917699 -0.031130999, + 0.0378174 -0.081121199 -0.033808999, + 0.035366699 -0.082096398 -0.036669999, + 0.0328326 -0.082821302 -0.039701, + 0.0302257 -0.083281703 -0.042884, + 0.027557701 -0.083469503 -0.046195999, + 0.0248404 -0.0833783 -0.049614999, + 0.0220857 -0.0830025 -0.053119, + 0.019305199 -0.082340397 -0.056689002, + 0.0165099 -0.0797984 -0.064602003, + 0.0137106 -0.077358998 -0.072783999, + 0.0109179 -0.075033396 -0.081202, + 0.0081421202 -0.072831102 -0.089823, + 0.0053918599 -0.070762999 -0.098614, + 0.00267513 -0.0688399 -0.107544, + 0 -0.067070097 -0.116582, + -0.00267513 -0.068841197 -0.107545, + -0.0053918599 -0.070766099 -0.098615997, + -0.0081421202 -0.072835803 -0.089826003, + -0.0109179 -0.075039104 -0.081206001, + -0.0137106 -0.077364303 -0.072788, + -0.0165099 -0.079801403 -0.064603999, + -0.019305199 -0.082339399 -0.056689002, + -0.0220857 -0.0830018 -0.053119, + -0.0248404 -0.083376497 -0.049614999, + -0.027557701 -0.083466098 -0.046197001, + -0.0302257 -0.083276697 -0.042885002, + -0.0328326 -0.082815297 -0.039701998, + -0.035366699 -0.082091302 -0.036669001, + -0.0378174 -0.081118599 -0.033806998, + -0.040174201 -0.0799146 -0.031129999, + -0.0424264 -0.078493901 -0.028642001, + -0.044564299 -0.076872297 -0.026353, + -0.0465803 -0.075071201 -0.024272, + -0.048467699 -0.073113203 -0.022400999, + -0.050219599 -0.071021102 -0.020742999, + -0.051830001 -0.068817496 -0.019297, + -0.0532961 -0.0665268 -0.018061001, + -0.0546159 -0.064178199 -0.017021, + -0.055787299 -0.061776798 -0.016276, + -0.056809202 -0.059218399 -0.015743, + -0.0576833 -0.056501001 -0.015341, + -0.058412101 -0.053658701 -0.015101, + -0.058998398 -0.0507254 -0.015034, + -0.059445001 -0.047741801 -0.015149, + -0.059757002 -0.044750098 -0.015449, + -0.0599402 -0.041793101 -0.015935, + -0.059999999 -0.0388995 -0.016624, + -0.0599402 -0.036098201 -0.01753, + -0.059757002 -0.033418901 -0.018664001, + -0.059445001 -0.030895 -0.020017, + -0.058998398 -0.0285623 -0.021555001, + -0.058412101 -0.026435999 -0.023223, + -0.0576833 -0.024552099 -0.024975, + -0.056809202 -0.0228715 -0.026751, + -0.055787299 -0.021336701 -0.028427999, + -0.0546159 -0.0200372 -0.029972, + -0.0532961 -0.0189503 -0.031378001, + -0.051830001 -0.018067099 -0.032634001, + -0.051042698 -0.0176486 -0.033220001, + -0.050219599 -0.017319201 -0.034129001, + -0.048467699 -0.0172395 -0.036697999, + -0.049361002 -0.0175434 -0.035838999, + -0.0465803 -0.0168077 -0.038740002, + -0.044564299 -0.016282801 -0.040715002, + -0.0424264 -0.0156899 -0.042661, + -0.040174201 -0.0150741 -0.044611, + -0.0424264 -0.0150855 -0.042470999, + -0.040746599 -0.0145 -0.044023, + -0.044564299 -0.0150975 -0.040217999, + -0.044344399 -0.0145 -0.040417001, + -0.0465803 -0.01511 -0.037859, + -0.045055199 -0.0145 -0.039597999, + -0.048467699 -0.0151232 -0.035406999, + -0.0480907 -0.0145 -0.035879001, + -0.048886999 -0.0145 -0.034754999, + -0.058998398 -0.024908001 -0.017576, + -0.059445001 -0.026958199 -0.015687, + -0.059757002 -0.0291963 -0.013885, + -0.0599402 -0.031669199 -0.01223, + -0.059999999 -0.034342501 -0.010742, + -0.0599402 -0.037213001 -0.0094349999, + -0.059757002 -0.040259 -0.0083140004, + -0.059445001 -0.0434504 -0.0073849899, + -0.058998398 -0.046744101 -0.00667, + -0.058412101 -0.050089601 -0.0061900001, + -0.0576833 -0.053436 -0.0059539899, + -0.056809202 -0.056731001 -0.00596201, + -0.055787299 -0.059927799 -0.006203, + -0.0546159 -0.0625237 -0.0049609998, + -0.0532961 -0.065095097 -0.0038320001, + -0.051830001 -0.067625202 -0.0028230001, + -0.050219599 -0.0700965 -0.001944, + -0.048467699 -0.0724914 -0.001198, + -0.0465803 -0.074791498 -0.00057699601, + -0.044564299 -0.076985203 -0.000102005, + -0.0424264 -0.079088002 0.000121994, + -0.040174201 -0.081275798 -0.001912, + -0.0378174 -0.083302803 -0.0041950098, + -0.027557701 -0.089584 -0.0090279998, + -0.0248404 -0.090766698 -0.010135, + -0.027557701 -0.0895954 -0.006813, + -0.0302257 -0.0882475 -0.0080880001, + -0.0302257 -0.088231601 -0.0058960002, + -0.0328326 -0.086763903 -0.0073179901, + -0.0328326 -0.086722702 -0.0051519899, + -0.035366699 -0.085140496 -0.00672301, + -0.035366699 -0.085076198 -0.004584, + -0.0378174 -0.0833878 -0.006302, + -0.0248404 -0.090566099 -0.014608, + -0.0220857 -0.091677003 -0.013656, + -0.0220857 -0.091332398 -0.018159, + -0.019305199 -0.0923144 -0.017356999, + -0.019305199 -0.091821797 -0.021877, + -0.0165099 -0.092671797 -0.021217, + -0.0165099 -0.092028499 -0.025742, + -0.0137106 -0.092744797 -0.025212999, + -0.0137106 -0.091948397 -0.029733, + -0.0109179 -0.092529498 -0.029324001, + -0.0109179 -0.091578797 -0.033824001, + -0.0081421202 -0.092024803 -0.033525001, + -0.0081421202 -0.090920202 -0.037992999, + -0.0053918599 -0.091233604 -0.037792001, + -0.0053918599 -0.089976698 -0.042215001, + -0.00267513 -0.090161398 -0.042102002, + -0.00267513 -0.088754497 -0.046466999, + 0 -0.088815004 -0.046432, + 0 -0.087260701 -0.050730001, + 0.00267513 -0.088754699 -0.046466999, + 0.00267513 -0.090161704 -0.042102002, + 0.0053918599 -0.089977399 -0.042215001, + 0.0053918599 -0.091234498 -0.037792001, + 0.0081421202 -0.090921499 -0.037992001, + 0.0081421202 -0.092026196 -0.033525001, + 0.0109179 -0.091580801 -0.033824001, + 0.0109179 -0.0925311 -0.029324001, + 0.0137106 -0.091950402 -0.029733, + 0.0137106 -0.092745699 -0.025214, + 0.0165099 -0.092029698 -0.025743, + 0.0165099 -0.092673101 -0.021217, + 0.019305199 -0.091823302 -0.021878, + 0.019305199 -0.092316799 -0.017356999, + 0.0220857 -0.091335103 -0.018159, + 0.0220857 -0.091681004 -0.013656, + 0.0248404 -0.090410002 -0.016844001, + 0.040174201 -0.081622504 -0.012309, + 0.040174201 -0.081579797 -0.014403, + 0.0424264 -0.0796986 -0.012134, + 0.0378174 -0.083432399 -0.01265, + 0.0378174 -0.083368599 -0.014773, + 0.035366699 -0.085117497 -0.013159, + 0.035366699 -0.085030399 -0.015309, + 0.0328326 -0.086666703 -0.013835, + 0.0328326 -0.086554199 -0.016009999, + 0.0302257 -0.0880697 -0.014677, + 0.0302257 -0.0879298 -0.016874, + 0.027557701 -0.089319602 -0.015682001, + 0.027557701 -0.089150399 -0.017898999, + 0.0248404 -0.090209797 -0.019078, + 0.0220857 -0.090829797 -0.02265, + 0.019305199 -0.0911709 -0.026378, + 0.0165099 -0.091228202 -0.030241, + 0.0137106 -0.090995997 -0.034216002, + 0.0109179 -0.0904736 -0.038279001, + 0.0081421202 -0.089663103 -0.042406999, + 0.0053918599 -0.088569798 -0.046576001, + 0.00267513 -0.087200299 -0.050763998, + 0 -0.085563697 -0.054953001, + -0.00267513 -0.087200202 -0.050763998, + -0.0053918599 -0.088569403 -0.046576001, + -0.0081421202 -0.089662097 -0.042406999, + -0.0109179 -0.090471797 -0.038279999, + -0.0137106 -0.090993501 -0.034217, + -0.0165099 -0.091225803 -0.030241, + -0.019305199 -0.091169603 -0.026377, + -0.0220857 -0.090828098 -0.022648999, + -0.0248404 -0.090206698 -0.019078, + -0.027557701 -0.089314602 -0.015682001, + -0.0302257 -0.088063397 -0.014677, + -0.0328326 -0.086658798 -0.013835, + -0.035366699 -0.085107997 -0.013159, + 0.0424264 -0.079686098 -0.010074, + 0.040174201 -0.081628501 -0.010218, + 0.0378174 -0.083458997 -0.010529, + 0.035366699 -0.085166797 -0.01101, + 0.0328326 -0.086740799 -0.01166, + 0.0302257 -0.088170797 -0.012479, + 0.027557701 -0.089449503 -0.013464, + 0.0248404 -0.090570599 -0.014609, + 0.0248404 -0.090691403 -0.012372, + 0.027557701 -0.089539997 -0.011246, + 0.0302257 -0.088233002 -0.010282, + 0.0328326 -0.086776599 -0.0094870003, + 0.035366699 -0.085178301 -0.008862, + 0.0378174 -0.083448403 -0.0084100002, + 0.040174201 -0.081597798 -0.0081289997, + 0.0424264 -0.079637602 -0.0080180103, + 0.044564299 -0.077481396 -0.00606, + 0.0465803 -0.07519 -0.0043560001, + 0.048467699 -0.072965503 -0.0048439899, + 0.050219599 -0.070675798 -0.0055529899, + 0.051830001 -0.068306401 -0.0063849902, + 0.0532961 -0.065868497 -0.0073220101, + 0.0546159 -0.063380502 -0.0083699999, + 0.055787299 -0.060859401 -0.0095239999, + 0.056809202 -0.057872798 -0.0091439998, + 0.0576833 -0.0547571 -0.0089670001, + 0.058412101 -0.0515568 -0.0090070004, + 0.058998398 -0.0483183 -0.0092740003, + 0.059445001 -0.045092799 -0.0097650001, + 0.059757002 -0.041929498 -0.010469, + 0.0599402 -0.038874101 -0.011371, + 0.059999999 -0.035956699 -0.012473, + 0.0599402 -0.033203799 -0.013775, + 0.059757002 -0.0306399 -0.015273, + 0.059445001 -0.028289201 -0.01695, + 0.058998398 -0.0261831 -0.018763, + 0.058412101 -0.024230201 -0.020632001, + 0.0576833 -0.0213046 -0.021137999, + 0.056809202 -0.018755401 -0.021418, + 0.055787299 -0.018054601 -0.023591001, + 0.0546159 -0.017591 -0.026007, + 0.0532961 -0.0170605 -0.028354, + 0.051830001 -0.0164512 -0.030683, + 0.050219599 -0.015796101 -0.033032998, + 0.048467699 -0.0151372 -0.035425998, + 0.048260398 -0.0145 -0.03565, + 0.0499507 -0.0145 -0.033240002, + -0.0576833 -0.051887602 -0.0030720099, + -0.058412101 -0.0484243 -0.0035260001, + -0.058998398 -0.045001399 -0.0042359899, + -0.059445001 -0.041671801 -0.0051850001, + -0.059757002 -0.038484201 -0.0063430001, + -0.0599402 -0.0354807 -0.00767999, + -0.059999999 -0.032684099 -0.0091840103, + -0.0599402 -0.030095801 -0.010842, + -0.059757002 -0.027747801 -0.01264, + -0.059445001 -0.025581799 -0.014541, + -0.058998398 -0.0221499 -0.015207, + -0.058412101 -0.0191008 -0.015678, + -0.0576833 -0.0182641 -0.017917, + -0.056809202 -0.017240699 -0.020059001, + -0.055787299 -0.0165843 -0.022535, + -0.0546159 -0.0158806 -0.025037, + -0.0532961 -0.0151651 -0.027593, + -0.0528326 -0.0145 -0.028438, + -0.052201699 -0.0145 -0.029544, + -0.051817201 -0.0145 -0.030218, + -0.0484582 -0.0145 -0.035360001, + -0.0445593 -0.0145 -0.040169999, + -0.037815802 -0.0145 -0.046578001, + -0.0360066 -0.0145 -0.047982, + -0.0378174 -0.0150634 -0.046627998, + -0.040174201 -0.015666701 -0.044803999, + -0.0424264 -0.0162453 -0.042978998, + -0.044564299 -0.016752601 -0.041118, + -0.0465803 -0.017162399 -0.039182, + -0.047540501 -0.017441301 -0.038378999, + -0.049361002 -0.017824 -0.036621001, + -0.048467699 -0.017745299 -0.037912, + -0.050219599 -0.0183858 -0.036883, + -0.048467699 -0.017643901 -0.037503999, + -0.047540501 -0.0175802 -0.038768999, + -0.0465803 -0.0173917 -0.039615002, + -0.051830001 -0.019220101 -0.035682999, + -0.0532961 -0.0202596 -0.034322001, + -0.0546159 -0.021527501 -0.032806002, + -0.055787299 -0.0229489 -0.031164, + -0.056809202 -0.0245784 -0.029507, + -0.0576833 -0.026450999 -0.02789, + -0.058412101 -0.0285377 -0.026358999, + -0.058998398 -0.0308285 -0.024963999, + -0.059445001 -0.033291399 -0.023747001, + -0.059757002 -0.035883099 -0.022747001, + -0.0599402 -0.038558699 -0.021988001, + -0.059999999 -0.0412836 -0.021461001, + -0.0599402 -0.044029899 -0.021143001, + -0.059757002 -0.0467727 -0.021005001, + -0.059445001 -0.049491201 -0.021017, + -0.058998398 -0.052150998 -0.021167001, + -0.058412101 -0.054719601 -0.021449, + -0.0576833 -0.0571642 -0.021840001, + -0.056809202 -0.059485599 -0.022415999, + -0.055787299 -0.061781399 -0.023257, + -0.0546159 -0.064048097 -0.02427, + -0.0532961 -0.066257901 -0.025472, + -0.051830001 -0.068387501 -0.026869999, + -0.050219599 -0.070413999 -0.028467, + -0.048467699 -0.072314098 -0.030262999, + -0.0465803 -0.074065402 -0.032258, + -0.044564299 -0.0756457 -0.034446999, + -0.0424264 -0.077036999 -0.036825001, + -0.040174201 -0.078222401 -0.039391998, + -0.0378174 -0.079182699 -0.042139001, + -0.035366699 -0.079902202 -0.045045, + -0.0328326 -0.080366299 -0.048092999, + -0.0302257 -0.0805628 -0.051261, + -0.027557701 -0.080483399 -0.054531999, + -0.0248404 -0.080123298 -0.057882998, + -0.0220857 -0.077890903 -0.065550998, + -0.019305199 -0.075752601 -0.073518001, + -0.0165099 -0.073719099 -0.081749, + -0.0137106 -0.071800597 -0.090209, + -0.0109179 -0.070006602 -0.098866001, + -0.0081421202 -0.068346098 -0.107687, + -0.0053918599 -0.0668277 -0.116642, + -0.00267513 -0.065459698 -0.125699, + 0 -0.064249903 -0.134827, + 0.00267513 -0.065458797 -0.125698, + 0.0053918599 -0.066825598 -0.11664, + 0.0081421202 -0.068342097 -0.107684, + 0.0109179 -0.070000499 -0.098861001, + 0.0137106 -0.071792699 -0.090203002, + 0.0165099 -0.073710598 -0.081743002, + 0.019305199 -0.075745203 -0.073513001, + 0.0220857 -0.077886902 -0.065548003, + 0.0248404 -0.080124497 -0.057882, + 0.027557701 -0.080484301 -0.054531999, + 0.0302257 -0.080564998 -0.051261, + 0.0328326 -0.080370396 -0.048092, + 0.035366699 -0.079907998 -0.045044001, + 0.0378174 -0.079189502 -0.042137999, + 0.040174201 -0.078228198 -0.039391998, + 0.0424264 -0.077040002 -0.036826, + 0.044564299 -0.075649098 -0.034449, + 0.0465803 -0.074071102 -0.032258999, + 0.048467699 -0.072322801 -0.030263999, + 0.050219599 -0.070426002 -0.028467, + 0.051830001 -0.0684027 -0.026868001, + 0.0532961 -0.0662755 -0.025465, + 0.0546159 -0.064066298 -0.024254, + 0.055787299 -0.061797898 -0.023229999, + 0.056809202 -0.059497401 -0.022398001, + 0.0576833 -0.0571738 -0.021841999, + 0.058412101 -0.0547348 -0.021446999, + 0.058998398 -0.052173302 -0.021158, + 0.059445001 -0.049518801 -0.021003, + 0.059757002 -0.046801399 -0.020986, + 0.0599402 -0.044056501 -0.021119, + 0.059999999 -0.041306399 -0.021434, + 0.0599402 -0.038577002 -0.021957999, + 0.059757002 -0.035896599 -0.022717001, + 0.059445001 -0.0333005 -0.023716999, + 0.058998398 -0.0308335 -0.024933999, + 0.058412101 -0.0285371 -0.026331, + 0.0576833 -0.0264447 -0.027864, + 0.056809202 -0.024582701 -0.029488999, + 0.055787299 -0.0229706 -0.031160001, + 0.0546159 -0.0221781 -0.034217, + 0.0546159 -0.0215277 -0.032807, + 0.0532961 -0.020867901 -0.035778999, + 0.0532961 -0.020259401 -0.034322999, + 0.051830001 -0.0197342 -0.037197001, + 0.051830001 -0.0192231 -0.035684001, + 0.050219599 -0.018827399 -0.038447998, + 0.050219599 -0.0183884 -0.036883, + 0.050219599 -0.017908201 -0.035307001, + 0.049361002 -0.017716501 -0.036219001, + 0.051830001 -0.0186674 -0.034162998, + 0.0532961 -0.019628 -0.032853998, + 0.0546159 -0.0207943 -0.031396002, + 0.055787299 -0.0221966 -0.029793, + 0.056809202 -0.0237705 -0.028073, + 0.0576833 -0.0255109 -0.026349001, + 0.058412101 -0.027501499 -0.024692001, + 0.058998398 -0.0297195 -0.023149, + 0.059445001 -0.032135699 -0.021767, + 0.059757002 -0.034713302 -0.020586999, + 0.0599402 -0.037410699 -0.019642999, + 0.059999999 -0.040194198 -0.018932, + 0.0599402 -0.043032899 -0.018440001, + 0.059757002 -0.045899998 -0.018142, + 0.059445001 -0.048767 -0.018015999, + 0.058998398 -0.051595699 -0.018053999, + 0.058412101 -0.054345399 -0.018248999, + 0.0576833 -0.056985699 -0.018591, + 0.056809202 -0.059486099 -0.019052001, + 0.055787299 -0.0618544 -0.019688001, + 0.0546159 -0.064186402 -0.020615, + 0.0532961 -0.066472299 -0.021745, + 0.051830001 -0.068684198 -0.023073001, + 0.050219599 -0.070798501 -0.024602, + 0.048467699 -0.072793201 -0.026334001, + 0.0465803 -0.0746461 -0.028271001, + 0.044564299 -0.076335303 -0.030409999, + 0.0424264 -0.077839002 -0.032747, + 0.040174201 -0.079140402 -0.035273001, + 0.0378174 -0.080226101 -0.037985999, + 0.035366699 -0.081073001 -0.040874001, + 0.0328326 -0.081665903 -0.043919001, + 0.0302257 -0.081992596 -0.0471, + 0.027557701 -0.082045503 -0.050395001, + 0.0248404 -0.081818402 -0.053784002, + 0.0220857 -0.081308 -0.057245001, + 0.019305199 -0.078917198 -0.065038003, + 0.0165099 -0.076625198 -0.073114999, + 0.0137106 -0.074443698 -0.081442997, + 0.0109179 -0.072382003 -0.089987002, + 0.0081421202 -0.070449203 -0.098715998, + 0.0053918599 -0.068655603 -0.107596, + 0.00267513 -0.067009598 -0.116596, + 0 -0.065519102 -0.125686, + -0.00267513 -0.067010701 -0.116597, + -0.0053918599 -0.0686583 -0.107598, + -0.0081421202 -0.0704538 -0.098719001, + -0.0109179 -0.072388299 -0.089992002, + -0.0137106 -0.074450798 -0.081448004, + -0.0165099 -0.076631501 -0.073119998, + -0.019305199 -0.078920603 -0.065040998, + -0.0220857 -0.081306897 -0.057245001, + -0.0248404 -0.081817597 -0.053784002, + -0.027557701 -0.082043499 -0.050395001, + -0.0302257 -0.081988901 -0.0471, + -0.0328326 -0.081660397 -0.043919999, + -0.035366699 -0.081066601 -0.040874999, + -0.0378174 -0.080220602 -0.037985999, + -0.040174201 -0.079137601 -0.035271998, + -0.0424264 -0.077835798 -0.032745998, + -0.044564299 -0.076329798 -0.030409001, + -0.0465803 -0.0746378 -0.028270001, + -0.048467699 -0.0727816 -0.026334001, + -0.050219599 -0.070783801 -0.024604, + -0.051830001 -0.068667099 -0.023080001, + -0.0532961 -0.066454597 -0.021761, + -0.0546159 -0.064170301 -0.020640999, + -0.055787299 -0.061842799 -0.019706, + -0.056809202 -0.059476599 -0.01905, + -0.0576833 -0.056970701 -0.018594, + -0.058412101 -0.054323401 -0.018257, + -0.058998398 -0.0515684 -0.018068001, + -0.059445001 -0.048738498 -0.018036, + -0.059757002 -0.0458735 -0.018166, + -0.0599402 -0.043010101 -0.018467, + -0.059999999 -0.0401759 -0.018960999, + -0.0599402 -0.037397102 -0.019672999, + -0.059757002 -0.0347041 -0.020617999, + -0.059445001 -0.032130599 -0.021796999, + -0.058998398 -0.0297201 -0.023178, + -0.058412101 -0.027507899 -0.024719, + -0.0576833 -0.0255065 -0.026366999, + -0.056809202 -0.0237484 -0.028077999, + -0.055787299 -0.022196401 -0.029793, + -0.0546159 -0.0207945 -0.031394999, + -0.0532961 -0.0196249 -0.032853998, + -0.049361002 -0.0177087 -0.036219001, + -0.048467699 -0.017491899 -0.03712, + -0.050219599 -0.0177745 -0.034913, + -0.050219599 -0.0175956 -0.034538999, + 0.048467699 -0.017508401 -0.037115999, + 0.048467699 -0.017651601 -0.037505001, + 0.044564299 -0.0171049 -0.041554999, + -0.00267513 -0.062502198 -0.153173, + -0.0053918599 -0.063022502 -0.144022, + -0.0081421202 -0.063695997 -0.134919, + -0.0109179 -0.064517997 -0.125892, + -0.0137106 -0.065481901 -0.116973, + -0.0165099 -0.066582203 -0.108192, + -0.019305199 -0.067813203 -0.099583, + -0.0220857 -0.069168299 -0.091179997, + -0.0248404 -0.070639201 -0.083013996, + -0.027557701 -0.0722197 -0.075119004, + -0.0302257 -0.073903002 -0.067528002, + -0.0328326 -0.075681403 -0.060275, + -0.035366699 -0.075602397 -0.057270002, + -0.0378174 -0.075260699 -0.054365002, + -0.040174201 -0.074668303 -0.051578, + -0.0424264 -0.073839098 -0.048926, + -0.044564299 -0.072788499 -0.046427999, + -0.0465803 -0.071535401 -0.044098999, + -0.048467699 -0.0701003 -0.041953001, + -0.050219599 -0.068506896 -0.039995, + -0.051830001 -0.066770799 -0.038215, + -0.0532961 -0.064910002 -0.036614001, + -0.0546159 -0.062947303 -0.035193, + -0.055787299 -0.060905401 -0.033946998, + -0.056809202 -0.0588063 -0.032871999, + -0.0576833 -0.056670502 -0.031962998, + -0.058412101 -0.0545187 -0.031207999, + -0.058998398 -0.052375 -0.030592, + -0.059445001 -0.050242402 -0.03019, + -0.059757002 -0.048034899 -0.029929001, + -0.0599402 -0.0457495 -0.02974, + -0.059999999 -0.043396499 -0.029668, + -0.0599402 -0.040983699 -0.029751001, + -0.059757002 -0.038527701 -0.030028, + -0.059445001 -0.0360539 -0.03053, + -0.058998398 -0.033608001 -0.031252, + -0.058412101 -0.0312372 -0.032179002, + -0.0576833 -0.028985901 -0.033284001, + -0.056809202 -0.0268928 -0.034536999, + -0.055787299 -0.024991799 -0.035898998, + -0.0546159 -0.0233059 -0.037328001, + -0.0532961 -0.021838401 -0.038777001, + -0.0424264 -0.017303601 -0.045159999, + -0.041313998 -0.0172245 -0.04583, + -0.040174201 -0.0171698 -0.047355, + -0.0424264 -0.0173591 -0.046895999, + -0.044564299 -0.0176001 -0.044544999, + -0.044564299 -0.0177106 -0.046232998, + -0.0465803 -0.0180682 -0.043733999, + -0.0465803 -0.0182399 -0.045373999, + -0.048467699 -0.018722299 -0.042734001, + -0.048467699 -0.0189716 -0.044321001, + -0.050219599 -0.0195869 -0.041549001, + -0.050219599 -0.0198591 -0.043094002, + -0.051830001 -0.0206086 -0.040199999, + -0.051830001 -0.0207777 -0.040975999, + -0.0532961 -0.0216034 -0.037996002, + -0.043510102 -0.0173376 -0.043584999, + -0.0424264 -0.017017599 -0.043853998, + -0.043510102 -0.017248699 -0.043175999, + -0.044564299 -0.0170884 -0.041570999, + -0.0424264 -0.0167001 -0.043391, + -0.041313998 -0.0169836 -0.044953, + -0.0424264 -0.017203299 -0.044309001, + -0.044564299 -0.017396299 -0.04242, + -0.040174201 -0.0162096 -0.045127001, + -0.0378174 -0.015644901 -0.046824001, + -0.035366699 -0.0150535 -0.048517, + -0.035363302 -0.0145 -0.048463002, + -0.033201002 -0.0145 -0.049977001, + -0.036012899 -0.0094999997 -0.047990002, + -0.035611998 -0.0145 -0.048289001, + -0.0308876 -0.0094999997 -0.051438998, + -0.032827701 -0.0145 -0.050212, + -0.0308851 -0.0145 -0.051435001, + -0.0328326 -0.0150443 -0.050271001, + -0.035366699 -0.0161446 -0.049049001, + -0.036603201 -0.0165808 -0.048549999, + -0.0378174 -0.016176101 -0.047153, + -0.035366699 -0.0156245 -0.048714999, + -0.0328326 -0.0156055 -0.050471, + -0.0302257 -0.0150358 -0.051881999, + -0.030220401 -0.0145 -0.051821001, + -0.028145101 -0.0145 -0.052988999, + -0.030710001 -0.0145 -0.051545002, + -0.040174201 -0.0166502 -0.045547999, + -0.040174201 -0.016950499 -0.046021, + -0.041313998 -0.017159 -0.045412, + -0.0424264 -0.017280299 -0.044721998, + -0.040174201 -0.0171159 -0.046486001, + -0.0390082 -0.0169184 -0.047059, + -0.0378174 -0.0166032 -0.047582, + -0.0378174 -0.0168873 -0.048064999, + -0.0390082 -0.017074101 -0.047527999, + -0.040174201 -0.017170301 -0.046907999, + -0.0390082 -0.017117601 -0.047954999, + -0.0378174 -0.017033599 -0.048539001, + -0.036603201 -0.016857199 -0.049038, + -0.035366699 -0.0165592 -0.049486, + -0.0424264 -0.0173689 -0.048622001, + -0.044564299 -0.017775999 -0.047913, + -0.0465803 -0.0183766 -0.047001999, + 0.00923343 -0.061285298 -0.19149999, + 0.0081404103 -0.0614313 -0.1715, + 0.0088933604 -0.061337199 -0.1715, + 0.0109152 -0.0609833 -0.1715, + 0.0146637 -0.0601805 -0.1715, + 0.0137071 -0.060396802 -0.1715, + 0.0220857 -0.058339398 -0.153513, + 0.0248404 -0.057869099 -0.144651, + 0.027557701 -0.0575331 -0.13591801, + 0.0302257 -0.057331599 -0.12734599, + 0.0328326 -0.057264201 -0.118968, + 0.035366699 -0.057331499 -0.110816, + 0.0378174 -0.057537101 -0.10292, + 0.040174201 -0.057884902 -0.095311999, + 0.0424264 -0.058374301 -0.088022999, + 0.044564299 -0.059003599 -0.081082001, + 0.0465803 -0.059772301 -0.074516997, + 0.048467699 -0.0606771 -0.068356, + 0.050219599 -0.059798501 -0.066136003, + 0.051830001 -0.0587468 -0.064032003, + 0.0532961 -0.057540301 -0.062057, + 0.0546159 -0.056199402 -0.060222, + 0.055787299 -0.054744601 -0.058536999, + 0.056809202 -0.053196099 -0.057011999, + 0.0576833 -0.051576301 -0.055652998, + 0.058412101 -0.049917702 -0.054446001, + 0.058998398 -0.048226599 -0.053365, + 0.059445001 -0.046513099 -0.052405, + 0.059757002 -0.044797599 -0.051555, + 0.0599402 -0.043093901 -0.050808001, + 0.059999999 -0.041394901 -0.050174002, + 0.0599402 -0.039689001 -0.049672, + 0.059757002 -0.037966799 -0.049321, + 0.059445001 -0.036228701 -0.049151, + 0.058998398 -0.034484599 -0.049213, + 0.058412101 -0.032685801 -0.049417999, + 0.0576833 -0.0308387 -0.049731001, + 0.056809202 -0.028974401 -0.050163999, + 0.055787299 -0.0271235 -0.050712999, + 0.0546159 -0.025322201 -0.051371999, + 0.0532961 -0.023606 -0.052127998, + 0.051830001 -0.022009499 -0.052962001, + 0.050219599 -0.0205626 -0.053846002, + 0.048467699 -0.019290401 -0.054749999, + 0.0465803 -0.0182105 -0.055640001, + 0.044564299 -0.017333001 -0.056479, + 0.0424264 -0.0166614 -0.057232, + 0.040174201 -0.016194999 -0.057866, + 0.0378174 -0.015922399 -0.058350999, + 0.035366699 -0.015790701 -0.058653001, + 0.0328326 -0.015798399 -0.058735002, + 0.0302257 -0.0159439 -0.058595002, + 0.027557701 -0.016197599 -0.05824, + 0.0248404 -0.016543301 -0.057672001, + 0.0220857 -0.016596399 -0.058382999, + 0.0220857 -0.016666001 -0.057913002, + 0.019305199 -0.016623599 -0.058954, + 0.020698 -0.016590601 -0.057925999, + 0 -0.0149956 -0.060063001, + 0.000142344 -0.0145 -0.059999999, + 0.00268824 -0.0149963 -0.060003001, + 0.00268824 -0.0155007 -0.060208, + 0.0220857 -0.057920702 -0.162515, + 0.023037801 -0.057400901 -0.1715, + 0.0248404 -0.056748401 -0.16256399, + 0.0248404 -0.057166599 -0.15360899, + 0.027557701 -0.055845398 -0.153717, + 0.027557701 -0.056547701 -0.144812, + 0.0302257 -0.055079799 -0.14499199, + 0.0302257 -0.0560649 -0.13615701, + 0.0328326 -0.054452199 -0.136419, + 0.0328326 -0.055718299 -0.127674, + 0.035366699 -0.0539633 -0.128031, + 0.035366699 -0.055508401 -0.119396, + 0.0378174 -0.0536169 -0.119858, + 0.0378174 -0.055438899 -0.111354, + 0.040174201 -0.053417299 -0.11193, + 0.040174201 -0.055514298 -0.103579, + 0.0424264 -0.053369299 -0.104278, + 0.0424264 -0.0557383 -0.096101001, + 0.044564299 -0.0534769 -0.096932001, + 0.044564299 -0.056110799 -0.088950001, + 0.0465803 -0.053742301 -0.089919999, + 0.0465803 -0.056632102 -0.082153998, + 0.048467699 -0.054166 -0.083269, + 0.048467699 -0.057301998 -0.075741, + 0.050219599 -0.0547476 -0.077005997, + 0.050219599 -0.058116801 -0.069734998, + 0.051830001 -0.055482998 -0.071153, + 0.051830001 -0.057163201 -0.067613997, + 0.0532961 -0.054466199 -0.069127001, + 0.0532961 -0.056052402 -0.065609001, + 0.0546159 -0.0533082 -0.067216001, + 0.0546159 -0.054802801 -0.063731998, + 0.055787299 -0.052027501 -0.06543, + 0.055787299 -0.053435098 -0.061992001, + 0.056809202 -0.050645001 -0.063777998, + 0.056809202 -0.0519697 -0.060399, + 0.0576833 -0.049180001 -0.062270999, + 0.0576833 -0.050425898 -0.058961999, + 0.058412101 -0.0476516 -0.060915001, + 0.058412101 -0.0488258 -0.057686001, + 0.058998398 -0.046081901 -0.059714999, + 0.058998398 -0.0472022 -0.056557, + 0.059445001 -0.044503901 -0.058653999, + 0.059445001 -0.0455603 -0.055543002, + 0.059757002 -0.042922501 -0.057697002, + 0.059757002 -0.043910202 -0.054637998, + 0.0599402 -0.0413417 -0.056841001, + 0.0599402 -0.042266801 -0.053835001, + 0.059999999 -0.0397554 -0.056097001, + 0.059999999 -0.040623099 -0.053144999, + 0.0599402 -0.0381523 -0.055482, + 0.0599402 -0.038967699 -0.052584998, + 0.059757002 -0.036521599 -0.055013999, + 0.059757002 -0.037289899 -0.052173, + 0.059445001 -0.034858599 -0.054708, + 0.059445001 -0.0355861 -0.051927, + 0.058998398 -0.0331797 -0.054561999, + 0.058998398 -0.033876099 -0.051856, + 0.058412101 -0.031508598 -0.054577999, + 0.058412101 -0.0321743 -0.051998999, + 0.0576833 -0.0298585 -0.054793, + 0.0576833 -0.0304347 -0.052273002, + 0.056809202 -0.028186901 -0.055125002, + 0.056809202 -0.0286643 -0.052643001, + 0.055787299 -0.0265013 -0.055539999, + 0.055787299 -0.0268931 -0.053118002, + 0.0546159 -0.024831001 -0.056045, + 0.0546159 -0.025150999 -0.053693, + 0.0532961 -0.0232052 -0.056632001, + 0.0532961 -0.023472801 -0.054358002, + 0.051830001 -0.021656999 -0.057291001, + 0.051830001 -0.021892199 -0.055100001, + 0.050219599 -0.020217599 -0.058003999, + 0.050219599 -0.020440999 -0.055897001, + 0.048467699 -0.018916201 -0.05875, + 0.048467699 -0.0191461 -0.056722, + 0.0465803 -0.017776299 -0.059503, + 0.0465803 -0.0180292 -0.057544, + 0.044564299 -0.016816201 -0.060230002, + 0.044564299 -0.017104501 -0.058329999, + 0.0424264 -0.016047601 -0.060901001, + 0.0424264 -0.0163795 -0.059044998, + 0.040174201 -0.0154743 -0.061480999, + 0.040174201 -0.0158545 -0.059655, + 0.0378174 -0.0150935 -0.061939999, + 0.0378174 -0.0155255 -0.060130998, + 0.035366699 -0.0148987 -0.062251002, + 0.035366699 -0.0153791 -0.060446002, + 0.0328326 -0.0148747 -0.062391002, + 0.0328326 -0.0153653 -0.060568999, + 0.0302257 -0.0149743 -0.062330998, + 0.0302257 -0.0154814 -0.060469002, + 0.027557701 -0.0151928 -0.062049001, + 0.027557701 -0.015721399 -0.060150001, + 0.0248404 -0.015521 -0.061549, + 0.0248404 -0.0160562 -0.059618, + 0.0220857 -0.0159308 -0.060839999, + 0.0220857 -0.016469801 -0.058874998, + 0.019305199 -0.0164057 -0.059923999, + 0.019305199 -0.0165435 -0.059427999, + 0.0165099 -0.016498201 -0.060322002, + 0.0165099 -0.0165873 -0.059843998, + 0.0137106 -0.0165569 -0.060586002, + 0.0137106 -0.0165231 -0.060052, + 0.0109179 -0.0165041 -0.060647, + 0.0109179 -0.0163178 -0.0601, + 0.0081428103 -0.016307 -0.060550999, + 0.0081428103 -0.015962601 -0.060070001, + 0.0053973799 -0.0159573 -0.060385, + 0.0053973799 -0.0155028 -0.060024001, + 0.0053973799 -0.0149977 -0.059820998, + 0.0046291598 -0.0145 -0.059803002, + 0.0081428103 -0.0155062 -0.059711002, + 0.0109179 -0.0159701 -0.05962, + 0.0137106 -0.0163319 -0.059507001, + 0.0165099 -0.0165467 -0.059312001, + 0.0211595 -0.058128498 -0.1715, + 0.022079799 -0.057771999 -0.1715, + -0.00268824 -0.0149955 -0.060001999, + -0.00154448 -0.0145 -0.059962001, + -0.0053973799 -0.0149961 -0.059819002, + -0.0028003999 -0.0145 -0.059935, + -0.0081428103 -0.0155059 -0.059712999, + -0.0109179 -0.015969601 -0.059627, + -0.0137106 -0.016328599 -0.059516001, + -0.0165099 -0.0165406 -0.059317999, + -0.019305199 -0.016617101 -0.058954999, + -0.0220857 -0.016592899 -0.058382999, + -0.0248404 -0.016541099 -0.057673998, + -0.027557701 -0.0161961 -0.05824, + -0.0302257 -0.015942199 -0.058594, + -0.0328326 -0.0157985 -0.058734, + -0.035366699 -0.0157906 -0.058651999, + -0.0378174 -0.015907601 -0.058354001, + -0.040174201 -0.016192 -0.057879001, + -0.0424264 -0.016666099 -0.057252001, + -0.044564299 -0.0173335 -0.056501001, + -0.0465803 -0.0182065 -0.055663001, + -0.048467699 -0.019283 -0.054775, + -0.050219599 -0.0205513 -0.053872, + -0.051830001 -0.0219937 -0.052987002, + -0.0532961 -0.023585699 -0.052152, + -0.0546159 -0.025297999 -0.051394001, + -0.055787299 -0.0270967 -0.050731, + -0.056809202 -0.028948 -0.050177, + -0.0576833 -0.0308169 -0.049738999, + -0.058412101 -0.032670598 -0.049419999, + -0.058998398 -0.034474801 -0.049210999, + -0.059445001 -0.036216401 -0.049169999, + -0.059757002 -0.037949201 -0.049350001, + -0.0599402 -0.0396691 -0.049688999, + -0.059999999 -0.041375201 -0.050182, + -0.0599402 -0.043076299 -0.050810002, + -0.059757002 -0.044783201 -0.051555, + -0.059445001 -0.0465024 -0.052404001, + -0.058998398 -0.048219301 -0.053364001, + -0.058412101 -0.049913201 -0.054444999, + -0.0576833 -0.0515723 -0.05565, + -0.056809202 -0.053187899 -0.057011999, + -0.055787299 -0.054734498 -0.058538999, + -0.0546159 -0.056190301 -0.060224, + -0.0532961 -0.057533801 -0.062058002, + -0.051830001 -0.058743101 -0.064032003, + -0.050219599 -0.0597969 -0.066136003, + -0.048467699 -0.060674701 -0.068356998, + -0.0465803 -0.059780698 -0.074524999, + -0.044564299 -0.059020799 -0.081093997, + -0.0424264 -0.058396202 -0.088037997, + -0.040174201 -0.057907999 -0.095326997, + -0.0378174 -0.057558499 -0.102934, + -0.035366699 -0.057348799 -0.110829, + -0.0328326 -0.0572774 -0.11898, + -0.0302257 -0.057342399 -0.12735499, + -0.027557701 -0.057544399 -0.135924, + -0.0248404 -0.0578834 -0.14465301, + -0.0220857 -0.058354702 -0.153512, + -0.019305199 -0.059375901 -0.153429, + -0.0220857 -0.059054799 -0.144509, + -0.0248404 -0.0588651 -0.135708, + -0.027557701 -0.058810201 -0.127056, + -0.0302257 -0.058890399 -0.118586, + -0.0328326 -0.059104402 -0.110328, + -0.035366699 -0.059450898 -0.102316, + -0.0378174 -0.059930999 -0.094581999, + -0.040174201 -0.060543701 -0.087157004, + -0.0424264 -0.061286401 -0.080068998, + -0.044564299 -0.062155999 -0.073348001, + -0.0465803 -0.063150696 -0.067023002, + -0.048467699 -0.062358599 -0.064699002, + -0.050219599 -0.061376002 -0.062491, + -0.051830001 -0.060221799 -0.060414001, + -0.0532961 -0.058917198 -0.058478002, + -0.0546159 -0.0574839 -0.056694999, + -0.055787299 -0.055943601 -0.055071998, + -0.056809202 -0.054318801 -0.053619999, + -0.0576833 -0.0526352 -0.052329998, + -0.058412101 -0.050902601 -0.051173002, + -0.058998398 -0.049133498 -0.050147001, + -0.059445001 -0.047348 -0.049245, + -0.059757002 -0.045566399 -0.048455, + -0.0599402 -0.043802399 -0.047772001, + -0.059999999 -0.042049699 -0.047207002, + -0.0599402 -0.040298399 -0.046778001, + -0.059757002 -0.038543802 -0.046494, + -0.059445001 -0.0367704 -0.046441, + -0.058998398 -0.034916099 -0.046572, + -0.058412101 -0.0329942 -0.046822999, + -0.0576833 -0.03104 -0.047208, + -0.056809202 -0.029087201 -0.047724001, + -0.055787299 -0.027172299 -0.048367001, + -0.0546159 -0.0253307 -0.049125999, + -0.0532961 -0.0235985 -0.049984001, + -0.051830001 -0.022008 -0.050914001, + -0.050219599 -0.0205869 -0.051887002, + -0.048467699 -0.0193564 -0.052866999, + -0.0465803 -0.0183313 -0.053817, + -0.044564299 -0.017516499 -0.054699998, + -0.0424264 -0.0169018 -0.055477001, + -0.040174201 -0.016487001 -0.056116, + -0.0378174 -0.0162489 -0.056588002, + -0.035366699 -0.0161434 -0.056846999, + -0.0328326 -0.0161865 -0.056887001, + -0.0302257 -0.016353 -0.056710001, + -0.027557701 -0.0166237 -0.056318998, + -0.0248404 -0.0166531 -0.057185002, + -0.0057364102 -0.0145 -0.059725001, + 0.0030847499 -0.0145 -0.059921, + 0.002688 -0.0145 -0.059930999, + 0.0046305298 -0.0094999997 -0.059820998, + -0.00154487 -0.0094999997 -0.059980001, + 0.0118392 -0.0145 -0.058820002, + 0.0109151 -0.0145 -0.058983002, + 0.0107568 -0.0094999997 -0.059028, + 0.0137106 -0.0150062 -0.058476999, + 0.0147097 -0.0145 -0.058169, + 0.0165099 -0.0150106 -0.057748001, + 0.0165099 -0.0155255 -0.057944, + 0.019305199 -0.0155351 -0.057068001, + 0.019305199 -0.0160069 -0.057417002, + 0.0220857 -0.016607599 -0.057388999, + 0.0220857 -0.0163945 -0.056855001, + 0.023467001 -0.016625799 -0.056814, + 0.020698 -0.016381901 -0.057390001, + 0.0220857 -0.016023999 -0.056389, + 0.0248404 -0.0160436 -0.055210002, + 0.0248404 -0.015559 -0.054869, + 0.027557701 -0.0160657 -0.053883001, + 0.019305199 -0.0150158 -0.056874, + 0.0203376 -0.0145 -0.056448001, + 0.0220857 -0.0150218 -0.055852, + 0.0220857 -0.0155462 -0.056042999, + 0.0175448 -0.0145 -0.057378002, + 0.0167653 -0.0145 -0.057595, + 0.0167691 -0.0094999997 -0.057608999, + 0.016505601 -0.0145 -0.057668, + 0.013707 -0.0145 -0.058396, + 0.0060197199 -0.0145 -0.059696998, + 0.0053964402 -0.0145 -0.059744999, + 0.0081410101 -0.0145 -0.059431002, + 0.0081428103 -0.0149998 -0.059509002, + 0.0089402199 -0.0145 -0.059330001, + -0.0053968299 -0.0145 -0.059749, + -0.0026881699 -0.0145 -0.059937, + 7.3000002e-008 -0.0145 -0.059997, + 0.0109179 -0.0155111 -0.059262998, + 0.0137106 -0.01598 -0.05903, + 0.0165099 -0.016349301 -0.058770999, + 0.019305199 -0.0165748 -0.058426, + 0.019305199 -0.0163702 -0.057886999, + 0.0165099 -0.0159922 -0.058295999, + 0.0137106 -0.0155175 -0.058674999, + 0.0109179 -0.0150026 -0.059062999, + 0.0107539 -0.0145 -0.059011001, + 0.0248404 -0.016714601 -0.05672, + 0.0248404 -0.0166451 -0.056201, + 0.023467001 -0.016408 -0.056281999, + 0.0248404 -0.0164223 -0.055672001, + 0.0262044 -0.0166656 -0.055550002, + 0.027557701 -0.016769201 -0.055376001, + 0.027557701 -0.0166873 -0.054862, + 0.0262044 -0.016437501 -0.055024002, + 0.027557701 -0.0164536 -0.054338999, + 0.0288986 -0.016710101 -0.054136999, + 0.0302257 -0.0168298 -0.053883001, + 0.0225999 -0.0145 -0.055569999, + 0.0220796 -0.0145 -0.055771999, + 0.019300001 -0.0145 -0.056793001, + 0.0328326 -0.0314303 0.049628001, + 0.035366699 -0.039327599 0.047385, + 0.0328326 -0.039753001 0.049302001, + 0.0302257 -0.031674601 0.051336002, + 0.027557701 -0.0232997 0.053119998, + 0.028198199 -0.0145 0.052960001, + 0.0275518 -0.0145 0.053284999, + 0.0255982 -0.0145 0.054265, + -0.027557701 -0.016064299 -0.053901002, + -0.0288986 -0.0164635 -0.053635001, + -0.0302257 -0.0160887 -0.052428, + -0.0220806 -0.0145 -0.055774, + -0.0200695 -0.0145 -0.056543998, + -0.0220857 -0.0150154 -0.055842999, + -0.0197125 -0.0094999997 -0.056669001, + -0.0228185 -0.0145 -0.055491999, + -0.0248404 -0.0150214 -0.054671001, + -0.0248404 -0.0155579 -0.054876, + -0.027557701 -0.0155722 -0.053553, + -0.031537499 -0.0164993 -0.052083001, + -0.0328326 -0.0161155 -0.050810002, + -0.0302257 -0.0155881 -0.052083999, + -0.027557701 -0.0150282 -0.053350002, + -0.0255125 -0.0145 -0.054306, + -0.025434 -0.0145 -0.054340001, + -0.0254349 -0.0094999997 -0.054342002, + -0.0248351 -0.0145 -0.054604001, + -0.0137813 -0.0094999997 -0.058396, + -0.016506299 -0.0145 -0.057670001, + -0.0137077 -0.0145 -0.058398999, + -0.0193008 -0.0145 -0.056795999, + -0.019710001 -0.0145 -0.056662001, + -0.0262044 -0.016431199 -0.055041, + -0.027557701 -0.0167598 -0.055378001, + -0.0262044 -0.0166559 -0.05556, + -0.0248404 -0.0167061 -0.056720998, + -0.027557701 -0.016721001 -0.055836, + -0.0288986 -0.0167889 -0.054650001, + -0.027557701 -0.0166771 -0.054871999, + -0.0248404 -0.0164163 -0.055688001, + -0.0302257 -0.016715299 -0.054814, + -0.0328326 -0.0165253 -0.055029001, + -0.035366699 -0.016452299 -0.055029001, + -0.0378174 -0.016514899 -0.054814, + -0.040174201 -0.0167384 -0.054382, + -0.0424264 -0.0171014 -0.053743001, + -0.044564299 -0.0176496 -0.052948002, + -0.0465803 -0.0184063 -0.052030001, + -0.048467699 -0.0193689 -0.051026002, + -0.050219599 -0.020545499 -0.049975, + -0.051830001 -0.021928299 -0.048916001, + -0.0532961 -0.0234989 -0.047888, + -0.0546159 -0.025233001 -0.046925001, + -0.055787299 -0.027099701 -0.046057999, + -0.056809202 -0.029064201 -0.045311, + -0.0576833 -0.0310883 -0.0447, + -0.058412101 -0.033135101 -0.044234, + -0.058998398 -0.035166401 -0.043914001, + -0.059445001 -0.037147399 -0.043740999, + -0.059757002 -0.039041501 -0.043701999, + -0.0599402 -0.040840399 -0.043853, + -0.059999999 -0.042629499 -0.044225, + -0.0599402 -0.0444302 -0.044725001, + -0.059757002 -0.046248499 -0.045343, + -0.059445001 -0.048089799 -0.046068002, + -0.058998398 -0.0499405 -0.046909001, + -0.058412101 -0.0517812 -0.047876, + -0.0576833 -0.053592298 -0.048976, + -0.056809202 -0.055353299 -0.050216999, + -0.055787299 -0.057050802 -0.051600002, + -0.0546159 -0.058673799 -0.053151, + -0.0532961 -0.0601959 -0.054875001, + -0.051830001 -0.061594699 -0.056763999, + -0.050219599 -0.0628483 -0.058807999, + -0.048467699 -0.063935302 -0.060993001, + -0.0465803 -0.064836003 -0.063308999, + -0.044564299 -0.065531902 -0.065741003, + -0.0424264 -0.064425901 -0.072223999, + -0.040174201 -0.063436903 -0.079094999, + -0.0378174 -0.062568702 -0.086326003, + -0.035366699 -0.061824799 -0.093884997, + -0.0328326 -0.061207399 -0.101742, + -0.0302257 -0.060718101 -0.109867, + -0.027557701 -0.0603588 -0.118226, + -0.0248404 -0.060131401 -0.12678701, + -0.0220857 -0.060037199 -0.135517, + -0.019305199 -0.060076602 -0.144384, + -0.0165099 -0.060249399 -0.153357, + -0.0137106 -0.060555998 -0.162406, + -0.0144795 -0.060226701 -0.1715, + -0.0109179 -0.061141498 -0.16238201, + -0.0137106 -0.0609775 -0.15329801, + -0.0165099 -0.060950499 -0.14427701, + -0.019305199 -0.061059602 -0.13535, + -0.0220857 -0.0613041 -0.12654801, + -0.0248404 -0.0616806 -0.117903, + -0.027557701 -0.062187001 -0.109448, + -0.0302257 -0.062821999 -0.101215, + -0.0328326 -0.063582599 -0.093238004, + -0.035366699 -0.064464502 -0.085547999, + -0.0378174 -0.065464802 -0.078176998, + -0.040174201 -0.066580497 -0.071156003, + -0.0424264 -0.067807399 -0.064516, + -0.044564299 -0.067218401 -0.061973002, + -0.0465803 -0.066410497 -0.059544999, + -0.048467699 -0.065401502 -0.057246, + -0.050219599 -0.064210899 -0.055089999, + -0.051830001 -0.062858798 -0.053089, + -0.0532961 -0.0613668 -0.051254999, + -0.0546159 -0.059757501 -0.049598999, + -0.055787299 -0.058056898 -0.048115999, + -0.056809202 -0.056278098 -0.046783, + -0.0576833 -0.054435398 -0.045598999, + -0.058412101 -0.0525495 -0.044558998, + -0.058998398 -0.0506404 -0.043655999, + -0.059445001 -0.048727401 -0.042881001, + -0.059757002 -0.046829399 -0.042224001, + -0.0599402 -0.044960599 -0.041673001, + -0.059999999 -0.043119401 -0.041232999, + -0.0599402 -0.041282602 -0.040998001, + -0.059757002 -0.039354902 -0.040941, + -0.059445001 -0.037324801 -0.041023001, + -0.058998398 -0.035225201 -0.041267, + -0.058412101 -0.033092398 -0.041673001, + -0.0576833 -0.0309662 -0.042240001, + -0.056809202 -0.028885299 -0.042962, + -0.055787299 -0.02689 -0.043823998, + -0.0546159 -0.025017399 -0.044805001, + -0.0532961 -0.0233011 -0.045875002, + -0.051830001 -0.0217687 -0.046999998, + -0.050219599 -0.0204418 -0.048140001, + -0.048467699 -0.019331601 -0.049254, + -0.0465803 -0.018432001 -0.050301, + -0.044564299 -0.017748799 -0.051243, + -0.0424264 -0.0172575 -0.052044, + -0.040174201 -0.016911799 -0.052641999, + -0.0378174 -0.016738599 -0.053027, + -0.0302257 -0.016796401 -0.054336999, + -0.0302257 -0.016819499 -0.053885002, + -0.0288986 -0.0166994 -0.054148, + -0.027557701 -0.0164469 -0.054357, + -0.0302257 -0.016722901 -0.053385999, + -0.031537499 -0.0168516 -0.053082999, + -0.0328326 -0.016879199 -0.052689999, + -0.0328326 -0.0168851 -0.052244999, + -0.031537499 -0.016747501 -0.052588001, + -0.0302257 -0.016481001 -0.052878, + -0.0328326 -0.0167733 -0.051754002, + -0.034109399 -0.016920101 -0.051369999, + -0.036603201 -0.0169836 -0.050409999, + -0.035366699 -0.016925599 -0.051362, + -0.0378174 -0.016914699 -0.051231001, + -0.035366699 -0.016969301 -0.050898999, + -0.034109399 -0.0169234 -0.051812999, + -0.040174201 -0.0170445 -0.050889, + -0.0424264 -0.0173326 -0.050338998, + -0.044564299 -0.0178043 -0.04958, + -0.0465803 -0.0184262 -0.048627, + -0.048467699 -0.019245701 -0.047548, + -0.050219599 -0.0202884 -0.046383001, + -0.051830001 -0.0215455 -0.045170002, + -0.0532961 -0.023020601 -0.043954998, + -0.0546159 -0.024699301 -0.042778, + -0.055787299 -0.026556799 -0.041680001, + -0.056809202 -0.0285626 -0.040693998, + -0.0576833 -0.030680399 -0.039848998, + -0.058412101 -0.0328709 -0.039163999, + -0.058998398 -0.035091799 -0.038651999, + -0.059445001 -0.037302099 -0.038318999, + -0.059757002 -0.039460301 -0.038162999, + -0.0599402 -0.041533299 -0.038176998, + -0.059999999 -0.043506399 -0.038314998, + -0.0599402 -0.045398299 -0.038612999, + -0.059757002 -0.047309801 -0.039101001, + -0.059445001 -0.049260698 -0.039687999, + -0.058998398 -0.051233001 -0.040392999, + -0.058412101 -0.053207301 -0.041228, + -0.0576833 -0.055164699 -0.042203002, + -0.056809202 -0.0570856 -0.043326002, + -0.055787299 -0.058949601 -0.044601999, + -0.0546159 -0.060735501 -0.046034999, + -0.0532961 -0.062427402 -0.047625002, + -0.051830001 -0.064011097 -0.049394, + -0.050219599 -0.065460801 -0.051344, + -0.048467699 -0.066754103 -0.053461999, + -0.0465803 -0.067870602 -0.055736002, + -0.044564299 -0.068790697 -0.058152001, + -0.0424264 -0.069495201 -0.060695998, + -0.040174201 -0.069967397 -0.063352004, + -0.0378174 -0.0686123 -0.070148997, + -0.035366699 -0.067363299 -0.077317998, + -0.0328326 -0.066224098 -0.084826, + -0.0302257 -0.065198399 -0.092642002, + -0.027557701 -0.064291798 -0.100735, + -0.0248404 -0.063509397 -0.10907, + -0.0220857 -0.062853701 -0.117616, + -0.019305199 -0.062327001 -0.126339, + -0.0165099 -0.061934099 -0.135207, + -0.0137106 -0.061679099 -0.144187, + -0.0109179 -0.061563 -0.15324999, + -0.0081421202 -0.0615873 -0.16236401, + -0.0092316195 -0.0612747 -0.1715, + -0.0081407595 -0.0614338 -0.1715, + -0.0057835602 -0.061720598 -0.1715, + -0.00923343 -0.061285298 -0.19149999, + -0.00870548 -0.061365101 -0.1715, + -0.0109156 -0.060985401 -0.1715, + -0.017317699 -0.059446499 -0.1715, + -0.021165101 -0.058143001 -0.19149999, + -0.019300601 -0.058795199 -0.1715, + -0.0201142 -0.058527999 -0.1715, + -0.022080399 -0.057773601 -0.1715, + -0.024834899 -0.056603398 -0.1715, + -0.0460728 -0.040435601 -0.19149999, + -0.04456 -0.042170402 -0.1715, + -0.0465803 -0.039968699 -0.163251, + -0.046066999 -0.040430501 -0.1715, + -0.044564299 -0.042325102 -0.16315401, + -0.0465803 -0.040387198 -0.154983, + -0.048467699 -0.037936401 -0.155184, + -0.048467699 -0.0386279 -0.147012, + -0.050219599 -0.036092501 -0.147323, + -0.050219599 -0.037063401 -0.139264, + -0.051830001 -0.0344541 -0.13969, + -0.051830001 -0.035709701 -0.131761, + -0.0532961 -0.033038002 -0.132305, + -0.0532961 -0.034575898 -0.124527, + -0.0546159 -0.031853601 -0.125192, + -0.0546159 -0.033668701 -0.117583, + -0.055787299 -0.030907501 -0.118371, + -0.055787299 -0.032994501 -0.110953, + -0.056809202 -0.0302059 -0.111863, + -0.056809202 -0.032558199 -0.104658, + -0.0576833 -0.029752599 -0.10569, + -0.0576833 -0.032360099 -0.098715998, + -0.058412101 -0.029547499 -0.099868998, + -0.058412101 -0.032398 -0.093143001, + -0.058998398 -0.029588399 -0.094414003, + -0.058998398 -0.0326689 -0.087955996, + -0.059445001 -0.0298719 -0.089341998, + -0.059445001 -0.033169098 -0.083169997, + -0.059757002 -0.030395299 -0.084664002, + -0.059757002 -0.0336679 -0.078708999, + -0.0599402 -0.030931899 -0.080311, + -0.0599402 -0.03396 -0.074455, + -0.059999999 -0.031262301 -0.076182, + -0.059999999 -0.034054998 -0.070478, + -0.0599402 -0.031390801 -0.072352998, + -0.0599402 -0.0339677 -0.066836998, + -0.059757002 -0.031333499 -0.068884, + -0.059757002 -0.032543499 -0.066165999, + -0.059445001 -0.029905699 -0.068319999, + -0.059445001 -0.031062201 -0.065649003, + -0.058998398 -0.0284313 -0.067906, + -0.058998398 -0.0295419 -0.065284997, + -0.058412101 -0.026932999 -0.067635, + -0.058412101 -0.028004199 -0.065067001, + -0.0576833 -0.0254314 -0.067500003, + -0.0576833 -0.026468899 -0.064985998, + -0.056809202 -0.0249543 -0.065031998, + 0.0532961 -0.0187498 -0.070361003, + 0.0532961 -0.019769199 -0.068075001, + 0.0546159 -0.020071199 -0.070125997, + 0.051830001 -0.0175073 -0.070675999, + 0.051830001 -0.018511901 -0.06848, + 0.050219599 -0.0163552 -0.071082003, + 0.050219599 -0.0173089 -0.068924002, + 0.048467699 -0.0152709 -0.071509004, + 0.048467699 -0.0161695 -0.069375999, + 0.0465803 -0.0142629 -0.071929, + 0.0465803 -0.0151163 -0.069833003, + 0.044564299 -0.0133519 -0.072337002, + 0.044564299 -0.0141701 -0.070280001, + 0.0424264 -0.012557 -0.072715998, + 0.0424264 -0.0133523 -0.070699997, + 0.040174201 -0.011897 -0.07305, + 0.040174201 -0.0126809 -0.071073003, + 0.0378174 -0.0113856 -0.073319003, + 0.0378174 -0.0121686 -0.071377002, + 0.035366699 -0.0110328 -0.073501997, + 0.035366699 -0.0118228 -0.071589001, + 0.0328326 -0.0108434 -0.073577002, + 0.0328326 -0.011646 -0.071682997, + 0.0302257 -0.0108171 -0.073519997, + 0.0302257 -0.0116345 -0.071636997, + 0.027557701 -0.0109464 -0.073311001, + 0.027557701 -0.0117775 -0.071431004, + 0.0248404 -0.0112188 -0.072935, + 0.0248404 -0.0120606 -0.071047999, + 0.0220857 -0.0116185 -0.072375998, + 0.0220857 -0.0124678 -0.070476003, + 0.019305199 -0.0121284 -0.071624003, + 0.019305199 -0.0129769 -0.069706, + 0.0165099 -0.012725 -0.070675999, + 0.0165099 -0.0135531 -0.068732999, + 0.0137106 -0.0133761 -0.069531001, + 0.0137106 -0.0141858 -0.067560002, + 0.0109179 -0.0140704 -0.068190999, + 0.0109179 -0.0148556 -0.066197, + 0.0109179 -0.0162683 -0.062171999, + 0.0137106 -0.0156496 -0.063579999, + 0.0081428103 -0.0162402 -0.062631004, + 0.0081428103 -0.0164067 -0.062123001, + 0.0053973799 -0.0163904 -0.062442001, + 0.0053973799 -0.0165003 -0.061956, + 0.00268824 -0.0164923 -0.062143002, + 0.00268824 -0.0164728 -0.061602999, + 0 -0.016470401 -0.061664, + 0 -0.016293 -0.061113998, + -0.00268824 -0.016471799 -0.061604001, + -0.00268824 -0.0164914 -0.062143002, + -0.0053973799 -0.0164985 -0.061956, + -0.0053973799 -0.0163895 -0.062442001, + -0.0081428103 -0.0164054 -0.062123001, + -0.0081428103 -0.0162395 -0.062631004, + -0.0109179 -0.0162673 -0.062173001, + -0.055787299 -0.0234788 -0.065191999, + -0.055787299 -0.0243968 -0.062758997, + -0.0546159 -0.022061599 -0.065444, + -0.0546159 -0.022957901 -0.063104004, + -0.0532961 -0.0207102 -0.065816, + -0.0532961 -0.0215369 -0.063545004, + -0.051830001 -0.019391799 -0.066266999, + -0.051830001 -0.0201494 -0.064026996, + -0.050219599 -0.018122001 -0.066743001, + -0.050219599 -0.0188249 -0.064548001, + -0.048467699 -0.0169285 -0.06724, + -0.048467699 -0.017589699 -0.065095, + -0.0465803 -0.015835499 -0.067745, + -0.0465803 -0.016469 -0.065652996, + -0.044564299 -0.0148657 -0.068241999, + -0.044564299 -0.0154843 -0.066202, + -0.0424264 -0.0140382 -0.068709999, + -0.0424264 -0.0146553 -0.066720001, + -0.040174201 -0.0133695 -0.069126002, + -0.040174201 -0.0139958 -0.067179002, + -0.0378174 -0.0128694 -0.069466002, + -0.0378174 -0.0135134 -0.067553997, + -0.035366699 -0.0125423 -0.069704004, + -0.035366699 -0.0132094 -0.067815997, + -0.0328326 -0.0123875 -0.069815002, + -0.0328326 -0.0130804 -0.067941003, + -0.0302257 -0.0123985 -0.069775, + -0.0302257 -0.0131153 -0.067904003, + -0.027557701 -0.0125617 -0.069564, + -0.027557701 -0.0132932 -0.067685001, + -0.0248404 -0.0128551 -0.069167003, + -0.0248404 -0.0135991 -0.067272998, + -0.0220857 -0.0132627 -0.068572998, + -0.0220857 -0.0140134 -0.066659003, + -0.019305199 -0.0137652 -0.067777, + -0.019305199 -0.0145014 -0.065833002, + -0.0165099 -0.0143293 -0.066775002, + -0.0165099 -0.0150544 -0.064801998, + -0.0137106 -0.0149438 -0.065575004, + -0.0137106 -0.0156489 -0.063579001, + -0.0109179 -0.0155863 -0.064190999, + -0.0081428103 -0.0147873 -0.066670001, + -0.0053973799 -0.0162201 -0.062951997, + -0.00268824 -0.016380301 -0.062628999, + 0 -0.0164894 -0.062204, + 0.00268824 -0.016380699 -0.062628999, + 0.0053973799 -0.016220501 -0.062950999, + 0.0081428103 -0.0147877 -0.066670001, + 0.0081428103 -0.0131253 -0.070660003, + 0.0053973799 -0.0147403 -0.067001, + 0.00268824 -0.016209001 -0.063138999, + 0 -0.016377401 -0.062689997, + -0.00268824 -0.016208701 -0.063139997, + -0.0053973799 -0.01474 -0.067001, + -0.0081428103 -0.0131253 -0.070660003, + -0.0109179 -0.0140704 -0.068190999, + -0.055787299 -0.021434899 -0.069985002, + -0.056809202 -0.0228623 -0.069930002, + -0.055787299 -0.022492301 -0.067598999, + -0.0546159 -0.020052999 -0.070142001, + -0.0546159 -0.0210902 -0.067806996, + -0.0532961 -0.0187342 -0.070386998, + -0.0532961 -0.0197582 -0.068092003, + -0.051830001 -0.0174965 -0.070692003, + -0.051830001 -0.0185032 -0.068479002, + -0.050219599 -0.016346799 -0.071079999, + -0.050219599 -0.0172958 -0.068925999, + -0.048467699 -0.0152583 -0.071511, + -0.048467699 -0.016151199 -0.069383003, + -0.0465803 -0.0142453 -0.071935996, + -0.0465803 -0.0150947 -0.069844, + -0.044564299 -0.0133313 -0.072347, + -0.044564299 -0.0141487 -0.070294, + -0.0424264 -0.0125367 -0.072729997, + -0.0424264 -0.0133335 -0.070716999, + -0.040174201 -0.0118792 -0.073066004, + -0.040174201 -0.0126656 -0.071091004, + -0.0378174 -0.0113712 -0.073335998, + -0.0378174 -0.0121571 -0.071395002, + -0.035366699 -0.011022 -0.073518999, + -0.035366699 -0.0118148 -0.071607001, + -0.0328326 -0.010836 -0.073593996, + -0.0328326 -0.011641 -0.071699999, + -0.0302257 -0.0108125 -0.073535003, + -0.0302257 -0.0116319 -0.071653001, + -0.027557701 -0.0109441 -0.073325001, + -0.027557701 -0.0117778 -0.071443997, + -0.0248404 -0.011219 -0.072947003, + -0.0248404 -0.0120633 -0.071059003, + -0.0220857 -0.0116209 -0.072385997, + -0.0220857 -0.0124662 -0.070482999, + -0.019305199 -0.012127 -0.071630001, + -0.019305199 -0.0129694 -0.069707997, + -0.0165099 -0.0127185 -0.070678003, + -0.0165099 -0.013553 -0.068732999, + -0.0137106 -0.013376 -0.069531001, + -0.0137106 -0.0141858 -0.067560002, + -0.0109179 -0.0148549 -0.066196002, + -0.0576833 -0.024318 -0.069991, + -0.058412101 -0.0257836 -0.070176996, + -0.058998398 -0.0272395 -0.070496999, + -0.059445001 -0.028664 -0.070959002, + -0.059757002 -0.028705901 -0.074243002, + -0.0599402 -0.0285646 -0.077909, + -0.059999999 -0.0282169 -0.081900001, + -0.0599402 -0.0276582 -0.086138003, + -0.059757002 -0.0271047 -0.090712003, + -0.059445001 -0.026796401 -0.095678002, + -0.058998398 -0.0267417 -0.101019, + -0.058412101 -0.026942899 -0.106724, + -0.0576833 -0.0274023 -0.112778, + -0.056809202 -0.028120499 -0.119165, + -0.055787299 -0.0290938 -0.125866, + -0.0546159 -0.0303169 -0.13285901, + -0.0532961 -0.031783499 -0.14012501, + -0.051830001 -0.033484299 -0.147642, + -0.050219599 -0.035402 -0.15539099, + -0.048467699 -0.0375183 -0.163351, + -0.048119001 -0.037840798 -0.1715, + -0.046303399 -0.040157501 -0.1715, + -0.0465739 -0.039812401 -0.1715, + 0.0165099 -0.0150553 -0.064801998, + 0.019305199 -0.0145013 -0.065833002, + 0.0220857 -0.0140134 -0.066659003, + 0.0248404 -0.0136088 -0.067271002, + 0.027557701 -0.0132952 -0.067676, + 0.0302257 -0.013112 -0.067890003, + 0.0328326 -0.01308 -0.067924999, + 0.035366699 -0.0132125 -0.067798004, + 0.0378174 -0.0135192 -0.067534, + 0.040174201 -0.0140049 -0.067158997, + 0.0424264 -0.0146682 -0.066698998, + 0.044564299 -0.0155013 -0.066182002, + 0.0465803 -0.016489601 -0.065633997, + 0.048467699 -0.017612999 -0.065079004, + 0.050219599 -0.018848101 -0.064535998, + 0.051830001 -0.020168999 -0.06402, + 0.0532961 -0.021550801 -0.063542999, + 0.0546159 -0.022967 -0.063106, + 0.055787299 -0.024408299 -0.062740996, + 0.056809202 -0.025906401 -0.062526003, + 0.0576833 -0.027448799 -0.062433999, + 0.058412101 -0.0290155 -0.062468, + 0.058998398 -0.0305882 -0.062637001, + 0.059445001 -0.032148499 -0.06295, + 0.059757002 -0.033675801 -0.063417003, + 0.0599402 -0.035153799 -0.064041004, + 0.059999999 -0.036586199 -0.064806998, + 0.0599402 -0.037995901 -0.065692998, + 0.059757002 -0.0394128 -0.066712998, + 0.059445001 -0.040829401 -0.067873001, + 0.058998398 -0.042228401 -0.069165997, + 0.058412101 -0.043590002 -0.070591003, + 0.0576833 -0.044895101 -0.072140001, + 0.056809202 -0.046124101 -0.073807001, + 0.055787299 -0.047258999 -0.075581998, + 0.0546159 -0.0466916 -0.080995999, + 0.0532961 -0.046308301 -0.086823002, + 0.051830001 -0.046112999 -0.093047, + 0.050219599 -0.046105899 -0.099642001, + 0.048467699 -0.046286501 -0.106587, + 0.0465803 -0.0466525 -0.113857, + 0.044564299 -0.047196999 -0.121424, + 0.0424264 -0.0479118 -0.129261, + 0.040174201 -0.0487893 -0.13734099, + 0.0378174 -0.049824402 -0.14563499, + 0.035366699 -0.051012699 -0.15411299, + 0.0328326 -0.0523495 -0.162744, + 0.0321921 -0.052611299 -0.1715, + 0.0532961 -0.0207191 -0.065817997, + 0.051830001 -0.0194053 -0.066264004, + 0.050219599 -0.018141 -0.066735998, + 0.048467699 -0.016951 -0.067229003, + 0.0465803 -0.0158579 -0.067730002, + 0.044564299 -0.0148855 -0.068224996, + 0.0424264 -0.0140544 -0.068691, + 0.040174201 -0.0133818 -0.069107004, + 0.0378174 -0.0128779 -0.069447003, + 0.035366699 -0.0125478 -0.069686003, + 0.0328326 -0.0123903 -0.069798999, + 0.0302257 -0.0123982 -0.069760002, + 0.027557701 -0.0125587 -0.069551997, + 0.0248404 -0.0128569 -0.069159001, + 0.0220857 -0.0132713 -0.068571001, + 0.019305199 -0.0137653 -0.067777, + 0.0165099 -0.0143292 -0.066775002, + 0.0137106 -0.0149446 -0.065575004, + 0.055787299 -0.020323301 -0.072345003, + 0.056809202 -0.0217204 -0.072343998, + 0.0576833 -0.0231399 -0.072454996, + 0.058412101 -0.0245634 -0.072690003, + 0.058998398 -0.0259702 -0.073057003, + 0.059445001 -0.025993699 -0.076158002, + 0.059757002 -0.025855999 -0.079646997, + 0.0599402 -0.025506301 -0.083488002, + 0.059999999 -0.024945199 -0.0876, + 0.0599402 -0.0243633 -0.092055, + 0.059757002 -0.024011301 -0.09691, + 0.059445001 -0.023922799 -0.102141, + 0.058998398 -0.0241058 -0.107733, + 0.058412101 -0.024561699 -0.113672, + 0.0576833 -0.025290299 -0.119942, + 0.056809202 -0.0262853 -0.126526, + 0.055787299 -0.0275384 -0.133404, + 0.0546159 -0.0290411 -0.14055701, + 0.0532961 -0.030784201 -0.147965, + 0.051830001 -0.032758798 -0.155606, + 0.050219599 -0.0349559 -0.163459, + 0.049775898 -0.035491299 -0.1715, + 0.050210599 -0.034826901 -0.1715, + 0.051496498 -0.032791398 -0.1715, + 0.0497806 -0.035494599 -0.19149999, + 0.0499245 -0.0352799 -0.1715, + 0.048461299 -0.037362199 -0.1715, + 0.039609101 0.043067899 -0.19149999, + 0.038047399 0.044393901 -0.1715, + 0.042409498 0.040443301 -0.1715, + 0.0465752 0.035813399 -0.1715, + 0.047984999 0.0340087 -0.1715, + 0.0465803 0.035699699 -0.16636001, + 0.044564299 0.037893701 -0.16391701, + 0.0424264 0.039914601 -0.16155399, + 0.040174201 0.041752499 -0.159266, + 0.0378174 0.043400001 -0.157049, + 0.035366699 0.0448501 -0.154897, + 0.0328326 0.046095598 -0.152803, + 0.0302257 0.047129899 -0.15076301, + 0.027557701 0.0479507 -0.14877, + 0.0248404 0.048556302 -0.146818, + 0.0220857 0.0489452 -0.14489999, + 0.019305199 0.049116801 -0.143012, + 0.0165099 0.049073499 -0.141149, + 0.0137106 0.048818301 -0.139304, + 0.0109179 0.0483546 -0.137474, + 0.0081428103 0.047686402 -0.135655, + 0.0053973799 0.046820901 -0.13384201, + 0.00268824 0.045766 -0.13203099, + 0 0.044529598 -0.13022, + -0.00268824 0.045764498 -0.13203201, + -0.0053973799 0.046817798 -0.133844, + -0.0081428103 0.0476817 -0.135658, + -0.0109179 0.048348501 -0.13747901, + -0.0137106 0.048811 -0.139309, + -0.0165099 0.0490654 -0.141155, + -0.019305199 0.0491082 -0.14302, + -0.0220857 0.0489363 -0.144908, + -0.0248404 0.0485471 -0.146826, + -0.027557701 0.047940802 -0.14877801, + -0.0302257 0.047118802 -0.15077101, + -0.0328326 0.046082102 -0.15281001, + -0.035366699 0.0448329 -0.154902, + -0.0378174 0.043378301 -0.157052, + -0.040174201 0.041726299 -0.15926699, + -0.0424264 0.039885201 -0.161553, + -0.044564299 0.037863702 -0.163914, + -0.0465803 0.035673201 -0.166356, + -0.051438902 0.0288876 -0.19149999, + -0.051820699 0.0282204 -0.1715, + -0.0529892 0.026145101 -0.1715, + -0.051830001 0.028079201 -0.166044, + -0.051545098 0.02871 -0.1715, + -0.050211899 0.030827699 -0.1715, + -0.051434901 0.0288851 -0.1715, + -0.050219599 0.030686799 -0.166151, + 0.048467699 0.033086699 -0.16362099, + 0.048467699 0.0332493 -0.16625901, + 0.0465803 0.035537198 -0.163772, + 0.0465803 0.0353055 -0.161176, + 0.044564299 0.037662301 -0.161369, + 0.044564299 0.0373617 -0.15881699, + 0.0424264 0.039614301 -0.15904801, + 0.0424264 0.0392446 -0.15654001, + 0.040174201 0.0413833 -0.156802, + 0.040174201 0.040944401 -0.154339, + 0.0378174 0.042961702 -0.154627, + 0.0378174 0.0424533 -0.152209, + 0.035366699 0.044342302 -0.152518, + 0.035366699 0.043764301 -0.15014599, + 0.0328326 0.045517899 -0.15046699, + 0.0328326 0.0448706 -0.148142, + 0.0302257 0.046482898 -0.148471, + 0.0302257 0.0457667 -0.146192, + 0.027557701 0.0472348 -0.146521, + 0.027557701 0.046450298 -0.14429, + 0.0248404 0.047772098 -0.144613, + 0.0248404 0.046920002 -0.14242999, + 0.0220857 0.048093401 -0.14274099, + 0.0220857 0.0471742 -0.140606, + 0.019305199 0.048197899 -0.140898, + 0.019305199 0.0472125 -0.13881201, + 0.0165099 0.0480882 -0.13908, + 0.0165099 0.047037099 -0.137043, + 0.0137106 0.047767401 -0.137282, + 0.0137106 0.046651699 -0.13529401, + 0.0109179 0.047239099 -0.135499, + 0.0109179 0.046060901 -0.13356, + 0.0081428103 0.046508402 -0.133726, + 0.0081428103 0.045270201 -0.131837, + 0.0053973799 0.045582801 -0.13195901, + 0.0053973799 0.044286899 -0.130119, + 0.00268824 0.044470198 -0.13019501, + 0.00268824 0.043118998 -0.12840401, + 0 0.043178599 -0.12843101, + 0 0.0417745 -0.126689, + -0.00268824 0.043117799 -0.128405, + -0.00268824 0.044468801 -0.13019601, + -0.0053973799 0.044284102 -0.13012099, + -0.0053973799 0.045579799 -0.131961, + -0.0081428103 0.045265701 -0.13184001, + -0.0081428103 0.0465037 -0.133729, + -0.0109179 0.046054699 -0.13356499, + -0.0109179 0.047232799 -0.13550299, + -0.0137106 0.046643801 -0.135299, + -0.0137106 0.047759701 -0.13728701, + -0.0165099 0.0470278 -0.137049, + -0.0165099 0.048079401 -0.13908701, + -0.019305199 0.0472022 -0.13881899, + -0.019305199 0.0481884 -0.14090601, + -0.0220857 0.047163401 -0.140614, + -0.0220857 0.048083499 -0.142749, + -0.0248404 0.0469089 -0.14243899, + -0.0248404 0.0477621 -0.144622, + -0.027557701 0.046439201 -0.1443, + -0.027557701 0.047224499 -0.14653, + -0.0302257 0.045755502 -0.146202, + -0.0302257 0.046472099 -0.14848, + -0.0328326 0.044858798 -0.14815199, + -0.0328326 0.0455059 -0.15047599, + -0.035366699 0.043751199 -0.15015499, + -0.035366699 0.044327799 -0.15252499, + -0.0378174 0.042437799 -0.152217, + -0.0378174 0.042943299 -0.154633, + -0.040174201 0.040924899 -0.15434501, + -0.040174201 0.041360199 -0.15680499, + -0.0424264 0.039220199 -0.156543, + -0.0424264 0.0395867 -0.159049, + -0.044564299 0.037332602 -0.15881801, + -0.044564299 0.0376314 -0.161368, + -0.0465803 0.035273202 -0.161175, + -0.0465803 0.035505801 -0.16376901, + -0.048467699 0.033054002 -0.163618, + -0.048467699 0.033221699 -0.166255, + 0.050219599 0.030320199 -0.160768, + 0.051438499 0.0288873 -0.1715, + 0.051438902 0.0288876 -0.19149999, + 0.050209399 0.030826099 -0.1715, + 0.053283598 0.025551399 -0.1715, + 0.048467699 0.032553099 -0.158326, + 0.048467699 0.0321819 -0.15567499, + 0.0465803 0.0346337 -0.155975, + 0.0465803 0.034193199 -0.153375, + 0.044564299 0.036551502 -0.153712, + 0.044564299 0.036041599 -0.151164, + 0.0424264 0.038295899 -0.151531, + 0.0424264 0.0377165 -0.149037, + 0.040174201 0.039856698 -0.14942899, + 0.040174201 0.039208099 -0.146989, + 0.0378174 0.0412267 -0.14740001, + 0.0378174 0.0405095 -0.145014, + 0.035366699 0.0423996 -0.145438, + 0.035366699 0.041614201 -0.143108, + 0.0328326 0.043368999 -0.143537, + 0.0328326 0.042516001 -0.14126299, + 0.0302257 0.044129301 -0.14169, + 0.0302257 0.043209299 -0.139474, + 0.027557701 0.044678301 -0.139893, + 0.027557701 0.043692 -0.137734, + 0.0248404 0.045014702 -0.13813899, + 0.0248404 0.043962698 -0.13603801, + 0.0220857 0.045136999 -0.13642099, + 0.0220857 0.044020399 -0.134379, + 0.019305199 0.045044899 -0.134735, + 0.019305199 0.0438659 -0.13275, + 0.0165099 0.044742499 -0.133074, + 0.0165099 0.043503299 -0.131147, + 0.0137106 0.044234499 -0.131432, + 0.0137106 0.0429377 -0.129564, + 0.0109179 0.043526001 -0.129806, + 0.0109179 0.042174 -0.127995, + 0.0081428103 0.042622399 -0.128189, + 0.0081428103 0.041217599 -0.126435, + 0.0053973799 0.041531101 -0.126577, + 0.0053973799 0.040075898 -0.12488, + 0.00268824 0.040259901 -0.124968, + 0.00268824 0.038756698 -0.123328, + 0 0.038816702 -0.123358, + 0 0.037268002 -0.121774, + -0.00268824 0.038756199 -0.123328, + -0.00268824 0.0402591 -0.124969, + -0.0053973799 0.0400743 -0.124882, + -0.0053973799 0.041529 -0.126579, + -0.0081428103 0.0412145 -0.12643699, + -0.0081428103 0.042618699 -0.12819099, + -0.0109179 0.042169001 -0.12799799, + -0.0109179 0.043520398 -0.12981001, + -0.0137106 0.0429307 -0.12956899, + -0.0137106 0.0442269 -0.131438, + -0.0165099 0.043494198 -0.131154, + -0.0165099 0.044732999 -0.13308001, + -0.019305199 0.043854799 -0.13275801, + -0.019305199 0.045033801 -0.13474201, + -0.0220857 0.044007599 -0.134387, + -0.0220857 0.045124501 -0.13643, + -0.0248404 0.043948699 -0.13604701, + -0.0248404 0.045001399 -0.13814799, + -0.027557701 0.043677401 -0.13774399, + -0.027557701 0.0446648 -0.13990299, + -0.0302257 0.043194499 -0.139485, + -0.0302257 0.0441158 -0.141701, + -0.0328326 0.042501401 -0.141275, + -0.0328326 0.0433557 -0.143548, + -0.035366699 0.0415999 -0.14312001, + -0.035366699 0.042386498 -0.145449, + -0.0378174 0.040495399 -0.145027, + -0.0378174 0.041213199 -0.147411, + -0.040174201 0.039193701 -0.147001, + -0.040174201 0.039841902 -0.14943901, + -0.0424264 0.037700899 -0.149048, + -0.0424264 0.038278501 -0.15154, + -0.044564299 0.036023401 -0.151173, + -0.044564299 0.036529899 -0.15371799, + -0.0465803 0.034170602 -0.153382, + -0.0465803 0.0346069 -0.15597899, + -0.048467699 0.032154001 -0.155679, + -0.048467699 0.032521501 -0.158327, + -0.050219599 0.0299855 -0.158068, + -0.050219599 0.030285399 -0.160767, + -0.051830001 0.0276771 -0.16055299, + -0.050219599 0.030518699 -0.163462, + -0.048467699 0.032821 -0.16097499, + -0.0465803 0.034974001 -0.15857799, + -0.044564299 0.036965799 -0.156268, + -0.0424264 0.038784601 -0.15403999, + -0.040174201 0.040419102 -0.151889, + -0.0378174 0.041861001 -0.149809, + -0.035366699 0.0431039 -0.14779501, + -0.0328326 0.044141799 -0.145841, + -0.0302257 0.044969801 -0.143941, + -0.027557701 0.045585699 -0.14208999, + -0.0248404 0.0459884 -0.14027999, + -0.0220857 0.046176799 -0.13850699, + -0.019305199 0.046150301 -0.136764, + -0.0165099 0.045911599 -0.13504601, + -0.0137106 0.045465399 -0.133349, + -0.0109179 0.044816401 -0.131666, + -0.0081428103 0.043969799 -0.12999301, + -0.0053973799 0.042932998 -0.128326, + -0.00268824 0.0417138 -0.126662, + 0 0.0403197 -0.124997, + 0.00268824 0.041714799 -0.126661, + 0.0053973799 0.042935502 -0.128324, + 0.0081428103 0.043974102 -0.12999, + 0.0109179 0.044822499 -0.131662, + 0.0137106 0.0454733 -0.133343, + 0.0165099 0.045921199 -0.13504, + 0.019305199 0.046161201 -0.136756, + 0.0220857 0.0461886 -0.13849799, + 0.0248404 0.0460006 -0.14027099, + 0.027557701 0.045598 -0.14207999, + 0.0302257 0.044982001 -0.143931, + 0.0328326 0.0441541 -0.145831, + 0.035366699 0.043116499 -0.14778499, + 0.0378174 0.0418749 -0.149799, + 0.040174201 0.040435601 -0.15188, + 0.0424264 0.038805202 -0.15403301, + 0.044564299 0.036991399 -0.15626401, + 0.0465803 0.0350044 -0.158577, + 0.048467699 0.032854699 -0.16097599, + -0.0532961 0.025410499 -0.165934, + -0.053285599 0.025552399 -0.1715, + -0.054305699 0.023512499 -0.1715, + -0.054342099 0.0234349 -0.19149999, + -0.0557741 0.0200806 -0.1715, + -0.056543902 0.0180695 -0.1715, + -0.055787299 0.019937299 -0.16571, + -0.056669399 0.0177125 -0.19149999, + -0.0554916 0.0208185 -0.1715, + -0.0546159 0.0226926 -0.165823, + -0.0546159 0.022289 -0.16011301, + -0.0532961 0.0250076 -0.160335, + -0.0532961 0.024338201 -0.15472201, + -0.051830001 0.0273767 -0.157802, + 0.00268824 0.032316301 -0.117332, + 0.00268824 0.033984501 -0.118744, + 0 0.0323768 -0.117367, + 0 0.0289432 -0.114726, + -0.00268824 0.032316498 -0.117332, + -0.00268824 0.035615999 -0.120215, + -0.0053973799 0.035431001 -0.120115, + -0.0053973799 0.037022699 -0.121648, + -0.0081428103 0.036707699 -0.121485, + -0.0081428103 0.0382566 -0.123082, + -0.0109179 0.037806202 -0.122859, + -0.0109179 0.039309502 -0.12452, + -0.0137106 0.038718801 -0.124241, + -0.0137106 0.040174302 -0.12596799, + -0.0165099 0.039440401 -0.125636, + -0.0165099 0.040845498 -0.12742899, + -0.019305199 0.039966099 -0.127051, + -0.019305199 0.041318599 -0.12890901, + -0.0220857 0.040291101 -0.128489, + -0.0220857 0.041588601 -0.13041399, + -0.0248404 0.040411498 -0.12995701, + -0.0248404 0.041651599 -0.13194899, + -0.027557701 0.040325999 -0.13146199, + -0.027557701 0.041506398 -0.13352101, + -0.0302257 0.0400346 -0.133011, + -0.0302257 0.041152898 -0.13513599, + -0.0328326 0.039536901 -0.13461, + -0.0328326 0.040591098 -0.136803, + -0.035366699 0.0388337 -0.13626599, + -0.035366699 0.039822701 -0.13852499, + -0.0378174 0.037930101 -0.137987, + -0.0378174 0.038853001 -0.140311, + -0.040174201 0.036832102 -0.139777, + -0.040174201 0.037687998 -0.142166, + -0.0424264 0.035545502 -0.141643, + -0.0424264 0.036333598 -0.144096, + -0.044564299 0.0340771 -0.143592, + -0.044564299 0.034796301 -0.146107, + -0.0465803 0.0324357 -0.14562701, + -0.0465803 0.033085201 -0.148203, + -0.048467699 0.030631 -0.147753, + -0.048467699 0.031209899 -0.150389, + -0.050219599 0.028672701 -0.149976, + -0.050219599 0.029180501 -0.15267, + -0.051830001 0.026570899 -0.152298, + -0.051830001 0.0270085 -0.155049, + -0.050219599 0.0296176 -0.155368, + -0.048467699 0.0317173 -0.153032, + -0.0465803 0.033663701 -0.15078899, + -0.044564299 0.035445299 -0.148635, + -0.0424264 0.0370523 -0.14656501, + -0.040174201 0.038475499 -0.144575, + -0.0378174 0.039708398 -0.14265899, + -0.035366699 0.040745098 -0.140811, + -0.0328326 0.0415795 -0.139025, + -0.0302257 0.0422066 -0.13729601, + -0.027557701 0.042624202 -0.135616, + -0.0248404 0.042831399 -0.13398001, + -0.0220857 0.042828199 -0.13238101, + -0.019305199 0.0426156 -0.130813, + -0.0165099 0.0421976 -0.129269, + -0.0137106 0.041579001 -0.127745, + -0.0109179 0.0407646 -0.12623399, + -0.0081428103 0.039759599 -0.124733, + -0.0053973799 0.038571399 -0.123237, + -0.00268824 0.0372076 -0.121743, + 0 0.035676401 -0.120247, + 0.050219599 0.029204801 -0.15266301, + 0.050219599 0.029646499 -0.15536401, + 0.048467699 0.0317408 -0.153025, + 0.048467699 0.0312298 -0.150379, + 0.0465803 0.033682801 -0.15077899, + 0.0465803 0.033102401 -0.148191, + 0.044564299 0.035461798 -0.148623, + 0.044564299 0.034812301 -0.146093, + 0.0424264 0.037067499 -0.14655299, + 0.0424264 0.0363493 -0.14408199, + 0.040174201 0.0384904 -0.14456201, + 0.040174201 0.0377042 -0.142152, + 0.0378174 0.039723702 -0.142646, + 0.0378174 0.038869899 -0.140297, + 0.035366699 0.0407608 -0.140798, + 0.035366699 0.039840098 -0.138512, + 0.0328326 0.041595601 -0.13901301, + 0.0328326 0.0406086 -0.13679001, + 0.0302257 0.042222701 -0.137284, + 0.0302257 0.041170001 -0.135125, + 0.027557701 0.042639799 -0.13560501, + 0.027557701 0.041522399 -0.13350999, + 0.0248404 0.042845801 -0.13397001, + 0.0248404 0.0416659 -0.13193899, + 0.0220857 0.042840999 -0.13237301, + 0.0220857 0.041600902 -0.13040601, + 0.019305199 0.042626299 -0.130805, + 0.019305199 0.041328602 -0.128903, + 0.0165099 0.042206101 -0.129263, + 0.0165099 0.040853102 -0.127424, + 0.0137106 0.0415853 -0.12774, + 0.0137106 0.040179498 -0.125964, + 0.0109179 0.040768798 -0.126231, + 0.0109179 0.039312702 -0.124518, + 0.0081428103 0.039762001 -0.124731, + 0.0081428103 0.038258001 -0.12308, + 0.0053973799 0.0385723 -0.123236, + 0.0053973799 0.0370229 -0.121647, + 0.00268824 0.0372077 -0.121743, + 0.00268824 0.035615899 -0.120215, + 0.0053973799 0.0354308 -0.120115, + 0.0081428103 0.036708102 -0.121485, + 0.0109179 0.037808102 -0.122857, + 0.0137106 0.038722798 -0.124238, + 0.0165099 0.0394467 -0.125632, + 0.019305199 0.039974999 -0.12704401, + 0.0220857 0.0403025 -0.128481, + 0.0248404 0.040425301 -0.12994801, + 0.027557701 0.040341899 -0.13145199, + 0.0302257 0.040052101 -0.132999, + 0.0328326 0.039555401 -0.134597, + 0.035366699 0.038852599 -0.136253, + 0.0378174 0.037948702 -0.137972, + 0.040174201 0.036850002 -0.139762, + 0.0424264 0.035562702 -0.141629, + 0.044564299 0.0340937 -0.14357699, + 0.0465803 0.032452401 -0.145613, + 0.048467699 0.0306489 -0.147741, + 0.050219599 0.0286933 -0.149965, + 0.051830001 0.0260839 -0.14954001, + 0.050219599 0.028111801 -0.147276, + 0.048467699 0.029998399 -0.14511301, + 0.0465803 0.031733301 -0.143048, + 0.044564299 0.033306502 -0.141077, + 0.0424264 0.034708001 -0.139195, + 0.040174201 0.035928302 -0.13739599, + 0.0378174 0.036960699 -0.135674, + 0.035366699 0.0377989 -0.13402399, + 0.0328326 0.038437001 -0.132438, + 0.0302257 0.038871098 -0.13090999, + 0.027557701 0.039100699 -0.12943199, + 0.0248404 0.039126199 -0.12799799, + 0.0220857 0.038948201 -0.126601, + 0.019305199 0.0385678 -0.12523299, + 0.0165099 0.0379893 -0.12389, + 0.0137106 0.037217502 -0.122564, + 0.0109179 0.036257502 -0.121252, + 0.0081428103 0.035115398 -0.119945, + 0.0053973799 0.033799302 -0.11864, + 0.0053973799 0.032131199 -0.117223, + 0.00268824 0.028883001 -0.114687, + 0 0.025404301 -0.112331, + -0.00268824 0.0288835 -0.114687, + -0.0053973799 0.032131601 -0.117223, + -0.0081428103 0.033484001 -0.118463, + -0.0576833 0.0143605 -0.165481, + -0.056809202 0.017156299 -0.16559599, + -0.057460099 0.0152723 -0.1715, + -0.056809202 0.0167512 -0.15966, + -0.055787299 0.0195329 -0.159887, + -0.055787299 0.0188618 -0.154052, + -0.0546159 0.0216187 -0.15438899, + -0.0546159 0.0206709 -0.148673, + -0.0532961 0.0239002 -0.151917, + -0.0532961 0.0233914 -0.14911599, + -0.051830001 0.0260626 -0.149551, + -0.051830001 0.025482699 -0.14681099, + -0.050219599 0.028093301 -0.14728899, + -0.050219599 0.0274428 -0.144611, + -0.048467699 0.029981 -0.145127, + -0.048467699 0.029260701 -0.14251401, + -0.0465803 0.031716 -0.14306401, + -0.0465803 0.030926799 -0.140517, + -0.044564299 0.033288501 -0.141093, + -0.044564299 0.032431498 -0.138614, + -0.0424264 0.034689099 -0.139211, + -0.0424264 0.033764999 -0.136801, + -0.040174201 0.035908598 -0.137411, + -0.040174201 0.034918401 -0.13507099, + -0.0378174 0.036940601 -0.13568801, + -0.0378174 0.035885099 -0.13342001, + -0.035366699 0.037779 -0.134037, + -0.035366699 0.036659401 -0.131841, + -0.0328326 0.038417999 -0.132451, + -0.0328326 0.0372364 -0.130327, + -0.0302257 0.038853701 -0.13092101, + -0.0302257 0.0376123 -0.12887, + -0.027557701 0.039085399 -0.12944201, + -0.027557701 0.037786599 -0.127464, + -0.0248404 0.039113399 -0.12800699, + -0.0248404 0.037759699 -0.126101, + -0.0220857 0.038938101 -0.126608, + -0.0220857 0.0375317 -0.124774, + -0.019305199 0.038560402 -0.125239, + -0.019305199 0.037103899 -0.123477, + -0.0165099 0.037984502 -0.123893, + -0.0165099 0.036480099 -0.122203, + -0.0137106 0.037215099 -0.122566, + -0.0137106 0.0356654 -0.120947, + -0.0109179 0.036256999 -0.121252, + -0.0109179 0.034664601 -0.119702, + -0.0081428103 0.035115801 -0.119945, + -0.056661699 0.01771 -0.1715, + -0.056795701 0.017300799 -0.1715, + -0.057670102 0.0145063 -0.1715, + -0.0582381 0.0124335 -0.1715, + -0.058383498 0.0117785 -0.1715, + -0.058412101 0.0115607 -0.16536599, + -0.0576833 0.0139547 -0.159431, + -0.056809202 0.0160791 -0.15371101, + -0.055787299 0.017913001 -0.148223, + -0.0546159 0.0194379 -0.142983, + -0.055787299 0.0166789 -0.14242201, + -0.056809202 0.0151293 -0.14777, + -0.0576833 0.0132816 -0.15336899, + -0.058412101 0.0111541 -0.159201, + -0.058998398 0.0087675601 -0.165251, + -0.0588759 0.0095599703 -0.1715, + -0.0583992 0.0117077 -0.1715, + -0.0583959 0.0117813 -0.19149999, + -0.054603901 0.0228351 -0.1715, + -0.054340299 0.023434 -0.1715, + 0.0532961 0.0243688 -0.154718, + 0.0546159 0.0223269 -0.16011401, + 0.055787299 0.0199691 -0.165714, + 0.055772301 0.0200799 -0.1715, + 0.056480099 0.0182484 -0.1715, + 0.0566587 0.017709 -0.1715, + 0.056793999 0.0173002 -0.1715, + 0.050219599 0.0274607 -0.144596, + 0.048467699 0.0292788 -0.142499, + 0.0465803 0.030945599 -0.14050101, + 0.044564299 0.032451302 -0.138598, + 0.0424264 0.033785801 -0.136785, + 0.040174201 0.034939799 -0.135056, + 0.0378174 0.035906501 -0.133406, + 0.035366699 0.036679901 -0.131827, + 0.0328326 0.037255298 -0.13031401, + 0.0302257 0.037629101 -0.128859, + 0.027557701 0.037800901 -0.127454, + 0.0248404 0.037771098 -0.126093, + 0.0220857 0.037540201 -0.124768, + 0.019305199 0.037109502 -0.123472, + 0.0165099 0.036483102 -0.1222, + 0.0137106 0.035666 -0.120946, + 0.0109179 0.034664098 -0.119702, + 0.0081428103 0.0334838 -0.118463, + 0.0081428103 0.031815998 -0.117039, + 0.0109179 0.033032201 -0.11821, + 0.0137106 0.034071799 -0.119383, + 0.0165099 0.034930602 -0.120565, + 0.019305199 0.035602301 -0.121763, + 0.0220857 0.036080901 -0.122984, + 0.0248404 0.036362201 -0.124234, + 0.027557701 0.036444899 -0.12552001, + 0.0302257 0.036328498 -0.12684999, + 0.0328326 0.036012601 -0.12823001, + 0.035366699 0.035497501 -0.129667, + 0.0378174 0.034786802 -0.13117, + 0.040174201 0.033884998 -0.132745, + 0.0424264 0.0327967 -0.1344, + 0.044564299 0.0315286 -0.136141, + 0.0465803 0.0300899 -0.137972, + 0.048467699 0.028490599 -0.139901, + 0.050219599 0.026740599 -0.14193, + 0.051830001 0.024850201 -0.14406499, + 0.050219599 0.0259519 -0.139281, + 0.048467699 0.0276343 -0.13732199, + 0.0465803 0.0291666 -0.13546699, + 0.044564299 0.0305389 -0.13371, + 0.0424264 0.031741198 -0.132045, + 0.040174201 0.032764599 -0.130467, + 0.0378174 0.033603702 -0.12897, + 0.035366699 0.034254 -0.127545, + 0.0328326 0.0347111 -0.126186, + 0.0302257 0.034971502 -0.124884, + 0.027557701 0.035034899 -0.123633, + 0.0248404 0.034901801 -0.122425, + 0.0220857 0.034572601 -0.121253, + 0.019305199 0.034048598 -0.120109, + 0.0165099 0.033335298 -0.118987, + 0.0137106 0.032439601 -0.117878, + 0.0109179 0.031364799 -0.116775, + 0.0081428103 0.0301154 -0.115674, + 0.0053973799 0.028698999 -0.11457, + 0.00268824 0.0253448 -0.11229, + 0 0.021757299 -0.110146, + -0.00268824 0.025345201 -0.11229, + -0.0053973799 0.028699899 -0.11457, + -0.0081428103 0.031816602 -0.117039, + -0.0109179 0.0330326 -0.11821, + -0.0137106 0.034072399 -0.119383, + -0.0165099 0.034929901 -0.120567, + -0.019305199 0.0355989 -0.121767, + -0.0220857 0.036074501 -0.122989, + -0.0248404 0.036352601 -0.124241, + -0.027557701 0.036432199 -0.12552901, + -0.0302257 0.0363129 -0.12685999, + -0.0328326 0.035994399 -0.128242, + -0.035366699 0.035477199 -0.12968101, + -0.0378174 0.034764901 -0.131184, + -0.040174201 0.0338623 -0.132761, + -0.0424264 0.032774098 -0.134416, + -0.044564299 0.031506699 -0.13615701, + -0.0465803 0.0300692 -0.137989, + -0.048467699 0.028471 -0.139918, + -0.050219599 0.0267219 -0.141947, + -0.051830001 0.024831699 -0.14408, + -0.0532961 0.022810999 -0.146322, + -0.0109179 0.031365599 -0.116775, + -0.0137106 0.030773699 -0.116428, + -0.0109179 0.029666601 -0.115399, + -0.0137106 0.0324401 -0.117877, + -0.0165099 0.031703301 -0.117464, + -0.0165099 0.033336099 -0.118987, + -0.019305199 0.032453001 -0.118511, + -0.019305199 0.034047801 -0.120111, + -0.0220857 0.0330166 -0.119578, + -0.0220857 0.0345686 -0.121257, + -0.0248404 0.033387698 -0.120672, + -0.0248404 0.0348945 -0.122431, + -0.027557701 0.033565201 -0.121801, + -0.027557701 0.0350243 -0.123641, + -0.0302257 0.033548702 -0.122974, + -0.0302257 0.034957599 -0.124894, + -0.0328326 0.033337899 -0.124197, + -0.0328326 0.034694102 -0.12619799, + -0.035366699 0.032933202 -0.125476, + -0.035366699 0.0342343 -0.12755799, + -0.0378174 0.032338299 -0.12682199, + -0.0378174 0.033581901 -0.128984, + -0.040174201 0.031557601 -0.12824, + -0.040174201 0.032741401 -0.130483, + -0.0424264 0.030595601 -0.129739, + -0.0424264 0.0317173 -0.132061, + -0.044564299 0.029457601 -0.13132501, + -0.044564299 0.0305152 -0.133727, + -0.0465803 0.028151499 -0.13300499, + -0.0465803 0.029143799 -0.135484, + -0.048467699 0.026686599 -0.134785, + -0.048467699 0.027612699 -0.13733999, + -0.050219599 0.025072699 -0.136669, + -0.050219599 0.0259316 -0.13929801, + -0.051830001 0.023319401 -0.138661, + -0.051830001 0.0241103 -0.14136299, + -0.0532961 0.0214375 -0.140765, + -0.0532961 0.022159399 -0.143537, + -0.0081428103 0.0283869 -0.114369, + -0.0053973799 0.0251639 -0.112162, + -0.00268824 0.021699199 -0.110101, + 0 0.018097701 -0.107825, + 0.00268824 0.021699 -0.110101, + 0.0053973799 0.025163099 -0.112162, + 0.0081428103 0.0283856 -0.114369, + 0.0109179 0.029665301 -0.115399, + 0.0137106 0.030772701 -0.116428, + 0.0165099 0.031702802 -0.117464, + 0.019305199 0.032452099 -0.118511, + 0.0220857 0.033017602 -0.119576, + 0.0248404 0.033392102 -0.120668, + 0.027557701 0.033573199 -0.121795, + 0.0302257 0.033560298 -0.122965, + 0.0328326 0.033353001 -0.124186, + 0.035366699 0.0329515 -0.12546401, + 0.0378174 0.032359298 -0.126808, + 0.040174201 0.031580701 -0.128225, + 0.0424264 0.030620201 -0.129723, + 0.044564299 0.029482801 -0.131308, + 0.0465803 0.0281763 -0.13298699, + 0.048467699 0.0267104 -0.134766, + 0.050219599 0.025095001 -0.13665, + 0.051830001 0.0233403 -0.138643, + -0.056809202 0.0138941 -0.141856, + -0.0576833 0.0123309 -0.147314, + -0.058412101 0.0104801 -0.153026, + -0.058998398 0.0083602304 -0.15897299, + -0.059445001 0.0059921299 -0.16513699, + -0.059372 0.00665861 -0.1715, + -0.059434399 0.0061415401 -0.1715, + -0.0594876 0.0057019899 -0.1715, + -0.059725199 0.0037364101 -0.1715, + -0.059503399 0.0057039 -0.19149999, + -0.058986001 0.0089157401 -0.1715, + -0.048467699 0.0107898 -0.106844, + -0.0465803 0.0132657 -0.108178, + -0.048467699 0.0124104 -0.108928, + -0.050219599 0.0098532299 -0.107606, + -0.050219599 0.0114293 -0.109799, + -0.051830001 0.0088015897 -0.108497, + -0.051830001 0.0103307 -0.110796, + -0.0532961 0.0076439301 -0.109524, + -0.0532961 0.0091235097 -0.111928, + -0.0546159 0.0063893599 -0.110691, + -0.0546159 0.00781688 -0.113199, + -0.055787299 0.0050470699 -0.112005, + -0.055787299 0.0064201001 -0.114613, + -0.056809202 0.00362611 -0.113468, + -0.056809202 0.0049423198 -0.116174, + -0.0576833 0.0033920901 -0.117884, + -0.056809202 0.0105839 -0.130197, + -0.055787299 0.0133714 -0.130991, + -0.056809202 0.0123768 -0.13598999, + -0.0576833 0.00957595 -0.135307, + -0.0576833 0.0110945 -0.141286, + -0.058412101 0.00829079 -0.140716, + -0.058412101 0.00952831 -0.14685699, + -0.058998398 0.0067324601 -0.146402, + -0.058998398 0.00768536 -0.152684, + -0.059445001 0.0049082902 -0.152344, + -0.059445001 0.00558409 -0.158746, + -0.059757002 0.00283762 -0.158521, + -0.059757002 0.00324635 -0.165024, + -0.0599402 0.00053690898 -0.164913, + -0.059934601 0.00080040097 -0.1715, + -0.059749398 0.0033968301 -0.1715, + -0.059980098 -0.000455125 -0.19149999, + -0.059999801 -0.0021423399 -0.1715, + -0.059931301 -0.0046879998 -0.1715, + -0.059999999 -0.0021515901 -0.164803, + -0.059996702 -0.0020000699 -0.1715, + -0.059962399 -0.000455517 -0.1715, + -0.059937101 0.00068816799 -0.1715, + -0.0599402 0.0001275 -0.158299, + -0.059757002 0.00216089 -0.152007, + -0.059445001 0.00395433 -0.14594901, + -0.058998398 0.0054938202 -0.140147, + -0.058412101 0.0067710201 -0.13462199, + -0.0576833 0.0077816299 -0.129398, + -0.056809202 0.0085218297 -0.124498, + -0.055787299 0.011311 -0.12540799, + 0.0165099 0.0073786299 -0.098971002, + 0.0165099 0.00577346 -0.097443998, + 0.019305199 0.0066202502 -0.098140001, + 0.019305199 0.0082448302 -0.099648997, + 0.0220857 0.0073394501 -0.098705001, + 0.0220857 0.0089813396 -0.100198, + 0.0248404 0.0079231998 -0.099146999, + 0.0248404 0.0095801596 -0.100626, + 0.027557701 0.0083667496 -0.099478997, + 0.027557701 0.0100369 -0.100949, + 0.0302257 0.0086670201 -0.099715002, + 0.0302257 0.0103491 -0.10118, + 0.0328326 0.0088221096 -0.099871002, + 0.0328326 0.0105162 -0.101336, + 0.035366699 0.0088328402 -0.099960998, + 0.035366699 0.0105425 -0.101432, + 0.0378174 0.0087071704 -0.100006, + 0.0378174 0.0104136 -0.101482, + 0.040174201 0.0084326798 -0.100017, + 0.040174201 0.0101036 -0.101564, + 0.0424264 0.0079846997 -0.100073, + 0.0424264 0.0096421205 -0.101731, + 0.044564299 0.0073941099 -0.100223, + 0.044564299 0.0090441303 -0.101989, + 0.0465803 0.0066789701 -0.100475, + 0.0465803 0.0083238501 -0.102345, + 0.048467699 0.0074971602 -0.102806, + 0.0165099 0.0106941 -0.101898, + 0.0165099 0.0090193599 -0.100457, + 0.019305199 0.0099044302 -0.101114, + 0.019305199 0.0115969 -0.102533, + 0.0220857 0.0106572 -0.101645, + 0.0220857 0.0123648 -0.103045, + 0.0248404 0.0112702 -0.10206, + 0.0248404 0.0129908 -0.103446, + 0.027557701 0.0117394 -0.102373, + 0.027557701 0.0134725 -0.103749, + 0.0302257 0.0120637 -0.102599, + 0.0302257 0.013812 -0.103973, + 0.0328326 0.012246 -0.102756, + 0.0328326 0.0139896 -0.104125, + 0.035366699 0.0122682 -0.102853, + 0.035366699 0.0139725 -0.104287, + 0.0378174 0.0121018 -0.102971, + 0.0378174 0.0137883 -0.104512, + 0.040174201 0.011776 -0.103162, + 0.040174201 0.01345 -0.104809, + 0.0424264 0.0113045 -0.103436, + 0.0424264 0.0129675 -0.105186, + 0.044564299 0.0106983 -0.103798, + 0.044564299 0.0123525 -0.105647, + 0.0465803 0.0099722603 -0.104254, + 0.0465803 0.0116203 -0.106199, + 0.048467699 0.0107873 -0.106844, + 0.055787299 0.0050727101 -0.111987, + 0.055787299 0.0036390601 -0.109421, + 0.056809202 0.00365545 -0.113448, + 0.0546159 0.0064103799 -0.110676, + 0.0546159 0.0049234899 -0.108214, + 0.0532961 0.00765948 -0.109511, + 0.0532961 0.0061218902 -0.107156, + 0.051830001 0.0088109402 -0.108489, + 0.051830001 0.0072249002 -0.106242, + 0.050219599 0.0098553896 -0.107602, + 0.050219599 0.0082269404 -0.105465, + 0.0137106 0.0096652899 -0.10113, + 0.0137106 0.0113527 -0.102552, + 0.0165099 0.0124007 -0.103293, + 0.019305199 0.0133198 -0.103905, + 0.0220857 0.0141017 -0.104399, + 0.0248404 0.0147407 -0.104785, + 0.027557701 0.0152377 -0.10508, + 0.0302257 0.015572 -0.105295, + 0.0328326 0.015709 -0.105509, + 0.035366699 0.015672199 -0.105775, + 0.0378174 0.0154733 -0.106104, + 0.040174201 0.0151215 -0.106503, + 0.0424264 0.0146272 -0.106979, + 0.044564299 0.0140027 -0.107535, + 0.0465803 0.0132634 -0.108177, + 0.048467699 0.0124125 -0.108924, + 0.050219599 0.0114384 -0.10979, + 0.051830001 0.0103458 -0.110784, + 0.0532961 0.0091440203 -0.111913, + 0.0546159 0.0078419903 -0.113181, + 0.055787299 0.0064488999 -0.114593, + 0.056809202 0.0062309201 -0.118894, + 0.0576833 0.0034253099 -0.117862, + 0.0576833 0.0057503399 -0.123562, + 0.058412101 0.0029426699 -0.122645, + 0.058412101 0.0050039301 -0.12857699, + 0.058998398 0.00220457 -0.12777901, + 0.058998398 0.0039966102 -0.133919, + 0.059445001 0.0012162999 -0.13324, + 0.059445001 0.0027358299 -0.13956399, + 0.059757002 -1.3634e-005 -0.13900401, + 0.059757002 0.00123039 -0.14548901, + 0.0599402 -0.00148164 -0.14504699, + 0.0599402 -0.00051572098 -0.15166999, + 0.059999999 -0.0032057799 -0.15134101, + 0.059999999 -0.0025200399 -0.158081, + 0.0599402 -0.0052092099 -0.15786099, + 0.0599402 -0.0048059798 -0.16469701, + 0.059757002 -0.00751543 -0.16458599, + 0.059803601 -0.0066292598 -0.1715, + 0.0590127 -0.0127542 -0.1715, + 0.059358198 -0.0107524 -0.1715, + 0.058984801 -0.0129155 -0.1715, + 0.058998398 -0.0130366 -0.164359, + 0.059445001 -0.0102612 -0.164473, + 0.059445001 -0.0106658 -0.157414, + 0.050219599 6.6410998e-005 -0.095307, + 0.050219599 -0.00152393 -0.093381003, + 0.051830001 -0.00093986798 -0.095597997, + 0.048467699 0.00098770706 -0.095147997, + 0.048467699 -0.00060462998 -0.093336001, + 0.0465803 0.0018033599 -0.095115997, + 0.0465803 0.000186212 -0.093383998, + 0.044564299 0.0024778601 -0.095164999, + 0.044564299 0.000863783 -0.093454003, + 0.0424264 0.0030278801 -0.095220998, + 0.0424264 0.0014325799 -0.093533002, + 0.040174201 0.0034596701 -0.095270999, + 0.040174201 0.0018782601 -0.093601003, + 0.0378174 0.0037619099 -0.095297001, + 0.0378174 0.00219269 -0.09364, + 0.035366699 0.0039277701 -0.095280997, + 0.035366699 0.0023703501 -0.093634002, + 0.0328326 0.0039525498 -0.095205002, + 0.0328326 0.0024071799 -0.093562998, + 0.0302257 0.00383371 -0.09505, + 0.0302257 0.0023010401 -0.09341, + 0.027557701 0.0035727201 -0.094802998, + 0.027557701 0.0020531099 -0.093166001, + 0.0248404 0.00317222 -0.094453, + 0.0248404 0.0016668499 -0.092818998, + 0.0220857 0.00263614 -0.093988001, + 0.0220857 0.00115246 -0.092339002, + 0.019305199 0.0019745 -0.093382001, + 0.019305199 0.00051473 -0.091715001, + 0.0165099 0.00119516 -0.092625998, + 0.0165099 -0.00024052399 -0.090942003, + 0.0137106 0.00030566301 -0.091716997, + 0.0137106 -0.0011049 -0.090011999, + 0.0109179 -0.00068452 -0.090645999, + 0.0109179 -0.00206823 -0.088917002, + -0.0109179 0.0068911701 -0.098729998, + -0.0109179 0.0101885 -0.101675, + -0.0137106 0.0080151102 -0.09967, + -0.0081428103 0.0072694798 -0.099165, + 0.0081428103 0.0040953602 -0.096069999, + 0.0109179 0.00529338 -0.097193003, + 0.0081428103 0.0072678002 -0.099163003, + 0.0053973799 0.0043466599 -0.096389003, + 0.0053973799 0.00131419 -0.093145996, + 0.00268824 0.0014519 -0.093341, + 0.00268824 -0.0014255 -0.089954004, + 0 -0.0013841999 -0.090020001, + 0 -0.0040896898 -0.086493999, + -0.00268824 -0.0014243 -0.089955002, + -0.00268824 0.0014531499 -0.093341999, + -0.0053973799 0.00131669 -0.093148001, + -0.0053973799 0.0043480601 -0.096389003, + -0.0081428103 0.0040974799 -0.096070997, + -0.0109179 0.00373873 -0.095615, + -0.0137106 0.0032677299 -0.095017001, + -0.0109179 0.00222327 -0.093998, + -0.056809202 0.0022513799 -0.1108, + -0.0576833 0.00081726199 -0.112317, + -0.056809202 0.00081993302 -0.108172, + -0.055787299 0.0036175901 -0.109438, + -0.055787299 0.0021335201 -0.106913, + -0.0546159 0.0049075498 -0.108227, + -0.0546159 0.00337333 -0.105809, + -0.0532961 0.0061122798 -0.107165, + -0.0532961 0.0045304499 -0.104855, + -0.051830001 0.0072226701 -0.106246, + -0.051830001 0.0055956598 -0.104047, + -0.050219599 0.0082294596 -0.105465, + -0.050219599 0.0049413699 -0.101308, + -0.048467699 0.0075006401 -0.102806, + -0.048467699 0.00586063 -0.100836, + -0.0465803 0.0083295302 -0.102346, + -0.0465803 0.0066867201 -0.100476, + -0.044564299 0.0090515502 -0.10199, + -0.044564299 0.0074022198 -0.100224, + -0.0424264 0.0096498402 -0.101732, + -0.0424264 0.0079908501 -0.100073, + -0.040174201 0.0101094 -0.101564, + -0.040174201 0.0067498302 -0.098480999, + -0.0378174 0.00871005 -0.100005, + -0.0378174 0.0070239101 -0.098479003, + -0.035366699 0.0088371802 -0.099959999, + -0.035366699 0.0071672499 -0.098444998, + -0.0328326 0.0088279899 -0.099869996, + -0.0328326 0.0071701598 -0.098360002, + -0.0302257 0.0086742602 -0.099715002, + -0.0302257 0.0070277401 -0.098205999, + -0.027557701 0.00837484 -0.099480003, + -0.027557701 0.0067402101 -0.097967997, + -0.0248404 0.00793136 -0.099151, + -0.0248404 0.0063098799 -0.097631, + -0.0220857 0.0073467898 -0.098711997, + -0.0220857 0.0057402402 -0.097180001, + -0.019305199 0.0066259298 -0.098149002, + -0.019305199 0.0050361599 -0.096597999, + -0.0165099 0.0057768798 -0.097448997, + -0.0165099 0.0042077601 -0.095880002, + -0.0137106 0.0048104902 -0.096607, + -0.0081428103 0.00108375 -0.092816003, + -0.0053973799 -0.00154833 -0.089754, + -0.00268824 -0.0041252598 -0.086427003, + 0 -0.0066106301 -0.082840003, + 0.00268824 -0.0041260701 -0.086425997, + 0.0053973799 -0.00155073 -0.089752004, + 0.0081428103 0.0010799801 -0.092814997, + 0.0109179 0.0022191501 -0.093997002, + 0.055787299 0.0021497901 -0.1069, + 0.055787299 0.00060673198 -0.104424, + 0.056809202 0.00084179401 -0.108156, + 0.0546159 0.0033831799 -0.1058, + 0.0546159 0.00179085 -0.103433, + 0.0532961 0.00453274 -0.10485, + 0.0532961 0.00289744 -0.102594, + 0.051830001 0.0055930601 -0.104046, + 0.051830001 0.00230491 -0.099766999, + 0.050219599 0.0049377601 -0.101308, + 0.050219599 0.00167631 -0.097272001, + 0.048467699 0.0042195199 -0.098899998, + 0.048467699 0.0025957599 -0.097003996, + 0.0465803 0.00504182 -0.098645002, + 0.0465803 0.00341663 -0.096858002, + 0.044564299 0.0057524401 -0.098502003, + 0.044564299 0.0041190302 -0.096827999, + 0.0424264 0.0063320398 -0.098463997, + 0.0424264 0.0046679201 -0.096867003, + 0.040174201 0.0067467601 -0.098481998, + 0.040174201 0.0050820899 -0.096897997, + 0.0378174 0.0070192702 -0.098480001, + 0.0378174 0.0053712698 -0.096910998, + 0.035366699 0.0071609099 -0.098445997, + 0.035366699 0.0055253799 -0.096886002, + 0.0328326 0.0071622902 -0.098360002, + 0.0328326 0.00553835 -0.096804, + 0.0302257 0.0070188702 -0.098204002, + 0.0302257 0.005407 -0.096648999, + 0.027557701 0.0067311502 -0.097964004, + 0.027557701 0.0051324498 -0.096404001, + 0.0248404 0.00630162 -0.097622998, + 0.0248404 0.00471754 -0.096056998, + 0.0220857 0.0057337401 -0.097168997, + 0.0220857 0.00416558 -0.095595002, + 0.019305199 0.0050321599 -0.096592002, + 0.019305199 0.0034817001 -0.095008001, + 0.0165099 0.0042050201 -0.095880002, + 0.0165099 0.00267771 -0.094273001, + 0.0137106 0.0032641599 -0.095017001, + 0.0137106 0.00176264 -0.093386002, + 0.0109179 0.00074506801 -0.09234, + 0.0532961 -0.00038965201 -0.098188996, + 0.0546159 0.000152049 -0.101116, + 0.055787299 -0.000988791 -0.101996, + 0.056809202 -0.0021956901 -0.103036, + 0.0576833 -0.0019704199 -0.106883, + 0.0576833 0.00084704999 -0.112296, + 0.058412101 -0.0019654799 -0.111143, + 0.058412101 0.000615564 -0.116828, + 0.058998398 -0.00218753 -0.115796, + 0.058998398 0.000141653 -0.121731, + 0.059445001 -0.0026417 -0.120823, + 0.059445001 -0.000577125 -0.126986, + 0.059757002 -0.0033291699 -0.126201, + 0.059757002 -0.00153437 -0.132568, + 0.0599402 -0.0042487001 -0.131905, + 0.0599402 -0.00272678 -0.13845199, + 0.059999999 -0.0054190098 -0.137904, + 0.059999999 -0.0041727698 -0.144609, + 0.0599402 -0.00686392 -0.14417, + 0.0599402 -0.0058958698 -0.151012, + 0.059757002 -0.00860692 -0.15068001, + 0.059757002 -0.0079193301 -0.157639, + 0.059716001 -0.0078307204 -0.1715, + 0.0137106 0.0048082098 -0.096607998, + 0.0109179 0.0037358899 -0.095615, + 0.0137106 0.0063916501 -0.098154999, + 0.0109179 0.0068889 -0.098727003, + 0.0109179 0.0101849 -0.101672, + 0.0109179 0.0136102 -0.104437, + 0.0081428103 0.0105808 -0.102085, + 0.0053973799 0.0075326501 -0.099467002, + 0.00268824 0.0044942801 -0.096575998, + 0 0.00149729 -0.093405001, + -0.00268824 0.00449498 -0.096575998, + -0.0053973799 0.0075337598 -0.099468999, + -0.0081428103 0.0105835 -0.102087, + -0.0109179 0.0136134 -0.104437, + -0.0137106 0.0113572 -0.102554, + -0.0137106 0.013075 -0.103928, + -0.0165099 0.0124055 -0.103294, + -0.0165099 0.0141406 -0.104641, + -0.019305199 0.0133244 -0.103905, + -0.019305199 0.0150743 -0.105229, + -0.0220857 0.0141057 -0.104398, + -0.0220857 0.0158691 -0.105703, + -0.0248404 0.0147437 -0.104784, + -0.0248404 0.016522899 -0.106077, + -0.027557701 0.0152398 -0.10508, + -0.027557701 0.0187623 -0.107655, + -0.0302257 0.0173095 -0.106632, + -0.0302257 0.0190339 -0.108028, + -0.0328326 0.017426901 -0.106949, + -0.0328326 0.019131299 -0.108443, + -0.035366699 0.0173734 -0.107318, + -0.035366699 0.019058701 -0.10891, + -0.0378174 0.0171574 -0.107746, + -0.0378174 0.018825199 -0.109434, + -0.040174201 0.0167892 -0.108243, + -0.040174201 0.018441901 -0.110025, + -0.0424264 0.0162808 -0.108812, + -0.0424264 0.0179222 -0.110686, + -0.044564299 0.0156468 -0.10946, + -0.044564299 0.0172615 -0.111435, + -0.0465803 0.0148834 -0.110206, + -0.0465803 0.016454 -0.112287, + -0.048467699 0.0139837 -0.111063, + -0.048467699 0.015508 -0.113249, + -0.050219599 0.012956 -0.11204, + -0.050219599 0.0144313 -0.114329, + -0.051830001 0.0118081 -0.113143, + -0.051830001 0.0132318 -0.115533, + -0.0532961 0.0105491 -0.114377, + -0.0532961 0.0119188 -0.116867, + -0.0546159 0.0091882404 -0.115748, + -0.0546159 0.0105015 -0.118335, + -0.055787299 0.00773485 -0.11726, + -0.055787299 0.0089894803 -0.119942, + -0.056809202 0.0061982102 -0.118916, + -0.0576833 0.0057178098 -0.123584, + -0.058412101 0.0049752598 -0.128599, + -0.058998398 0.0039728102 -0.133939, + -0.059445001 0.0027145599 -0.13958099, + -0.059757002 0.0012058601 -0.145501, + -0.0599402 -0.00055016001 -0.151675, + -0.059999999 -0.00256167 -0.158079, + -0.0599402 -0.0048400601 -0.164692, + -0.059920698 -0.0050847498 -0.1715, + -0.059803098 -0.0066291601 -0.1715, + -0.059757002 -0.0075494 -0.164581, + -0.0599402 -0.0052507902 -0.157859, + -0.059999999 -0.0032402501 -0.151346, + -0.0599402 -0.00150624 -0.14506, + -0.059757002 -3.5023e-005 -0.13902199, + -0.059445001 0.00119231 -0.13326, + -0.058998398 0.00217561 -0.127801, + -0.058412101 0.00290973 -0.122668, + -0.044564299 0.0140041 -0.107535, + -0.0424264 0.0146302 -0.106979, + -0.040174201 0.0151264 -0.106504, + -0.0378174 0.0154796 -0.106105, + -0.035366699 0.0156787 -0.105776, + -0.0328326 0.015713699 -0.105509, + -0.0302257 0.0138143 -0.103972, + -0.027557701 0.0134758 -0.103749, + -0.0248404 0.0129953 -0.103446, + -0.0220857 0.0123701 -0.103045, + -0.019305199 0.0116025 -0.102534, + -0.0165099 0.0106995 -0.101901, + -0.0137106 0.0096698496 -0.101134, + -0.0165099 0.0090248501 -0.100462, + -0.019305199 0.00991078 -0.101117, + -0.0220857 0.0106637 -0.101646, + -0.0248404 0.0112761 -0.10206, + -0.027557701 0.0117443 -0.102372, + -0.0302257 0.0120674 -0.102598, + -0.0328326 0.0122486 -0.102755, + -0.035366699 0.0139776 -0.104287, + -0.0378174 0.0137952 -0.104513, + -0.040174201 0.0134567 -0.10481, + -0.0424264 0.0129727 -0.105187, + -0.044564299 0.0123557 -0.105648, + -0.0465803 0.0116218 -0.106199, + -0.0465803 0.0099756103 -0.104255, + -0.044564299 0.0107037 -0.103799, + -0.0424264 0.0113115 -0.103437, + -0.040174201 0.0117833 -0.103163, + -0.0378174 0.0121073 -0.10297, + -0.035366699 0.0105452 -0.101431, + -0.0328326 0.0105203 -0.101335, + -0.0302257 0.0103546 -0.10118, + -0.027557701 0.0100435 -0.100949, + -0.0248404 0.00958745 -0.100627, + -0.0220857 0.00898859 -0.100201, + -0.019305199 0.0082512498 -0.099655002, + -0.0165099 0.00738349 -0.098978996, + -0.0137106 0.0063944999 -0.098159, + -0.058412101 0.00058192702 -0.11685, + -0.058998398 0.000108377 -0.121754, + -0.059445001 -0.00060630799 -0.12700801, + -0.059757002 -0.00155848 -0.132589, + -0.0599402 -0.00274823 -0.13846999, + -0.059999999 -0.0041974001 -0.144621, + -0.0599402 -0.0059303101 -0.151017, + -0.059757002 -0.0079607796 -0.157637, + -0.059445001 -0.010295 -0.16446801, + -0.0596973 -0.0080197202 -0.1715, + -0.059011199 -0.0127539 -0.1715, + -0.058998398 -0.0130702 -0.16435499, + -0.059330199 -0.0109402 -0.1715, + -0.059430599 -0.010141 -0.1715, + -0.059821099 -0.0066305301 -0.19149999, + -0.059744701 -0.00739644 -0.1715, + -0.0546159 0.015137 -0.12903, + -0.0532961 0.016800299 -0.127198, + -0.051830001 0.018350899 -0.125493, + -0.050219599 0.0197786 -0.12391, + -0.048467699 0.0210742 -0.122445, + -0.0465803 0.022229301 -0.121091, + -0.044564299 0.0232356 -0.119844, + -0.0424264 0.0240853 -0.118695, + -0.040174201 0.0247708 -0.117637, + -0.0378174 0.0252872 -0.116661, + -0.035366699 0.0256304 -0.115761, + -0.0328326 0.0257957 -0.114926, + -0.0302257 0.025786599 -0.114145, + -0.027557701 0.025607301 -0.113404, + -0.0248404 0.025252201 -0.112698, + -0.0220857 0.024717599 -0.11202, + -0.019305199 0.024002301 -0.111361, + -0.0165099 0.023109401 -0.110715, + -0.0137106 0.0202139 -0.108946, + -0.0165099 0.019505201 -0.108395, + -0.019305199 0.022243399 -0.110105, + -0.0220857 0.0229827 -0.110677, + -0.0248404 0.0235423 -0.111267, + -0.027557701 0.0239227 -0.111885, + -0.0302257 0.0241268 -0.112538, + -0.0328326 0.024158699 -0.113232, + -0.035366699 0.0240258 -0.113973, + -0.0378174 0.0237258 -0.114776, + -0.040174201 0.023255 -0.115655, + -0.0424264 0.0226177 -0.116617, + -0.044564299 0.0218188 -0.11767, + -0.0465803 0.020865699 -0.118823, + -0.048467699 0.0197664 -0.120082, + -0.050219599 0.0185288 -0.121455, + -0.051830001 0.017161399 -0.122947, + -0.0532961 0.015673401 -0.124564, + -0.0546159 0.0140744 -0.12630901, + -0.055787299 0.0123744 -0.128186, + -0.0546159 0.0129465 -0.123618, + -0.0532961 0.0144829 -0.121963, + -0.051830001 0.0159104 -0.120438, + -0.050219599 0.0172197 -0.119039, + -0.048467699 0.018401399 -0.117761, + -0.0465803 0.019447301 -0.116598, + -0.044564299 0.020349501 -0.115542, + -0.0424264 0.021099901 -0.114588, + -0.040174201 0.021691499 -0.113725, + -0.0378174 0.022119001 -0.112946, + -0.035366699 0.022387801 -0.112238, + -0.0328326 0.0225005 -0.111586, + -0.0302257 0.0224458 -0.110981, + -0.027557701 0.022218101 -0.11042, + -0.0248404 0.021813801 -0.109893, + -0.0220857 0.0212308 -0.109393, + -0.019305199 0.018655401 -0.107735, + -0.0165099 0.0176904 -0.107191, + -0.0137106 0.016593499 -0.106533, + -0.0137106 0.0148212 -0.105254, + -0.0165099 0.0159027 -0.10594, + -0.019305199 0.016850701 -0.106505, + -0.0220857 0.017661899 -0.106962, + -0.0248404 0.0200701 -0.108576, + -0.027557701 0.020496899 -0.109009, + -0.0302257 0.020747099 -0.109478, + -0.0328326 0.0208236 -0.109989, + -0.035366699 0.0207313 -0.11055, + -0.0378174 0.020479901 -0.111168, + -0.040174201 0.020082099 -0.111849, + -0.0424264 0.0195342 -0.11261, + -0.044564299 0.018829601 -0.113463, + -0.0465803 0.0179761 -0.114418, + -0.048467699 0.0169813 -0.115482, + -0.050219599 0.0158532 -0.116663, + -0.051830001 0.0145999 -0.117965, + -0.0532961 0.0132307 -0.119396, + -0.0546159 0.0117549 -0.120959, + -0.055787299 0.0101822 -0.122659, + 0.0137106 0.0148179 -0.105254, + 0.0248404 0.018309399 -0.107318, + 0.0248404 0.0200665 -0.108576, + 0.0220857 0.017660201 -0.106963, + 0.027557701 0.018758301 -0.107655, + 0.027557701 0.020491799 -0.109008, + 0.0302257 0.019028399 -0.108027, + 0.0302257 0.0207421 -0.109477, + 0.0328326 0.019125801 -0.108442, + 0.0328326 0.020819601 -0.109989, + 0.035366699 0.0190544 -0.108909, + 0.035366699 0.0207287 -0.11055, + 0.0378174 0.0188225 -0.109434, + 0.0378174 0.020478699 -0.111168, + 0.040174201 0.0184406 -0.110025, + 0.040174201 0.020080101 -0.111848, + 0.0424264 0.017920099 -0.110685, + 0.0424264 0.019536 -0.112606, + 0.044564299 0.017263399 -0.111432, + 0.044564299 0.0188377 -0.113456, + 0.0465803 0.016462401 -0.112279, + 0.0465803 0.0179896 -0.114407, + 0.048467699 0.0155222 -0.113238, + 0.048467699 0.0169999 -0.115468, + 0.050219599 0.0144506 -0.114314, + 0.050219599 0.0158762 -0.116646, + 0.051830001 0.0132557 -0.115516, + 0.051830001 0.0146267 -0.117947, + 0.0532961 0.0119463 -0.116848, + 0.0532961 0.0132603 -0.119376, + 0.0546159 0.0105319 -0.118315, + 0.0546159 0.0117864 -0.120938, + 0.0546159 0.0129781 -0.123597, + 0.055787299 0.0113425 -0.125386, + 0.0532961 0.0145136 -0.121942, + 0.051830001 0.0159392 -0.120418, + 0.050219599 0.0172456 -0.119021, + 0.048467699 0.018423701 -0.117745, + 0.0465803 0.019465201 -0.116584, + 0.044564299 0.0203625 -0.115532, + 0.0424264 0.021107599 -0.114581, + 0.040174201 0.0216932 -0.113722, + 0.0378174 0.022117101 -0.112945, + 0.035366699 0.022386599 -0.112238, + 0.0328326 0.022498099 -0.111586, + 0.0302257 0.022442199 -0.110981, + 0.027557701 0.0222135 -0.110419, + 0.0248404 0.0218093 -0.109892, + 0.0220857 0.0212276 -0.109393, + 0.019305199 0.018653899 -0.107735, + 0.019305199 0.0168483 -0.106506, + 0.0165099 0.0176883 -0.107192, + 0.0165099 0.0158998 -0.105941, + 0.0137106 0.0165911 -0.106533, + 0.056809202 0.0106118 -0.13017599, + 0.0576833 0.00959922 -0.135287, + 0.058412101 0.0083116898 -0.140698, + 0.058998398 0.0067566801 -0.14639001, + 0.059445001 0.00494244 -0.152339, + 0.059757002 0.0028790699 -0.15852299, + 0.0599402 0.00057098898 -0.16491801, + 0.0599254 0.00099011394 -0.1715, + 0.059999999 -0.0021174799 -0.16480701, + 0.059962101 -0.00045558199 -0.1715, + 0.0599402 0.00016908 -0.158301, + 0.059757002 0.00219522 -0.15200201, + 0.059445001 0.0039787302 -0.145937, + 0.058998398 0.00551493 -0.140129, + 0.058412101 0.00679459 -0.134602, + 0.0576833 0.0078099398 -0.12937699, + 0.056809202 0.00855387 -0.124476, + 0.055787299 0.0090215998 -0.119921, + 0.0546159 0.0092164399 -0.115728, + 0.0532961 0.0105736 -0.114359, + 0.051830001 0.0118281 -0.113127, + 0.050219599 0.0129706 -0.112028, + 0.048467699 0.0139925 -0.111055, + 0.0465803 0.0148854 -0.110202, + 0.044564299 0.0156445 -0.109459, + 0.0424264 0.0162795 -0.108813, + 0.040174201 0.0167863 -0.108242, + 0.0378174 0.017152799 -0.107746, + 0.035366699 0.017367501 -0.107317, + 0.0328326 0.017420899 -0.106948, + 0.0302257 0.0173051 -0.106632, + 0.027557701 0.0170126 -0.10636, + 0.0248404 0.016520999 -0.106078, + 0.0220857 0.0158663 -0.105704, + 0.019305199 0.0150708 -0.10523, + 0.0165099 0.0141367 -0.104641, + 0.0137106 0.013071 -0.103927, + 0.059935 -0.0046881102 -0.1715, + 0.0599331 0.00068805699 -0.1715, + 0.059746101 0.00339656 -0.1715, + 0.059821099 -0.0066305301 -0.19149999, + 0.059930101 -0.0048950501 -0.1715, + 0.0597477 -0.0073966901 -0.1715, + 0.059432998 -0.0101413 -0.1715, + -0.0109179 -0.0132337 -0.070171997, + -0.0137106 -0.0125094 -0.071487002, + -0.0165099 -0.0118369 -0.072612002, + -0.019305199 -0.0112349 -0.073542997, + -0.0220857 -0.0107231 -0.074281, + -0.0248404 -0.0103249 -0.074831001, + -0.027557701 -0.0100583 -0.075205997, + -0.0302257 -0.0099362899 -0.07542, + -0.0328326 -0.0099684503 -0.075491004, + -0.035366699 -0.0101595 -0.075437002, + -0.0378174 -0.0105078 -0.075281002, + -0.040174201 -0.0110066 -0.075042002, + -0.0424264 -0.011646 -0.07474, + -0.044564299 -0.0124125 -0.074391, + -0.0465803 -0.013288 -0.07401, + -0.048467699 -0.0142506 -0.073609002, + -0.050219599 -0.0152867 -0.073233001, + -0.051830001 -0.0164208 -0.072919004, + -0.0532961 -0.017646899 -0.072650999, + -0.0546159 -0.018947801 -0.072454996, + -0.055787299 -0.0203069 -0.072347999, + -0.056809202 -0.021706801 -0.072343998, + -0.0576833 -0.023129599 -0.072453998, + -0.058412101 -0.0245563 -0.072687998, + -0.058998398 -0.0259657 -0.073055997, + -0.059445001 -0.025985099 -0.076158002, + -0.059757002 -0.025846001 -0.079649001, + -0.0599402 -0.025502 -0.083489001, + -0.059999999 -0.024942201 -0.087600999, + -0.0599402 -0.024374099 -0.092064999, + -0.059757002 -0.024034301 -0.096927002, + -0.059445001 -0.023953499 -0.102162, + -0.058998398 -0.024139799 -0.107756, + -0.058412101 -0.0245947 -0.113695, + -0.0576833 -0.025318701 -0.119964, + -0.056809202 -0.026308199 -0.126546, + -0.055787299 -0.027558301 -0.133421, + -0.0546159 -0.0290635 -0.140568, + -0.0532961 -0.030814899 -0.14796899, + -0.051830001 -0.032794699 -0.155605, + -0.050219599 -0.034984399 -0.16345499, + -0.0497793 -0.035493702 -0.1715, + -0.050208401 -0.0348254 -0.1715, + -0.0497806 -0.035494599 -0.19149999, + -0.049818899 -0.035437699 -0.1715, + -0.051398799 -0.032954201 -0.1715, + -0.0484588 -0.0373604 -0.1715, + -0.052960701 -0.0301986 -0.19149999, + -0.0518176 -0.032218602 -0.1715, + -0.052855 -0.030396201 -0.1715, + -0.051830001 -0.032377802 -0.163562, + -0.0532961 -0.0301263 -0.15582301, + -0.0546159 -0.0280961 -0.148302, + -0.055787299 -0.0263061 -0.141018, + -0.056809202 -0.024773899 -0.13398799, + -0.0576833 -0.023507699 -0.12723, + -0.058412101 -0.0225127 -0.120764, + -0.058998398 -0.021793701 -0.114608, + -0.059445001 -0.0213544 -0.108781, + -0.059757002 -0.021195101 -0.103293, + -0.0599402 -0.021308601 -0.098160997, + -0.059999999 -0.021664601 -0.093406998, + -0.0599402 -0.022226101 -0.089063004, + -0.059757002 -0.022766 -0.085089996, + -0.059445001 -0.023091 -0.081413001, + -0.058998398 -0.0232348 -0.078093998, + -0.058412101 -0.0232502 -0.075166002, + -0.0576833 -0.0218667 -0.074885003, + -0.056809202 -0.0204795 -0.074726999, + -0.055787299 -0.0191094 -0.074684002, + -0.0546159 -0.0177752 -0.074741997, + -0.0532961 -0.0164946 -0.074891001, + -0.051830001 -0.0152845 -0.075113997, + -0.050219599 -0.0141605 -0.075393997, + -0.048467699 -0.0131385 -0.075703003, + -0.0465803 -0.0122235 -0.076054998, + -0.044564299 -0.0113932 -0.076413997, + -0.0424264 -0.010661 -0.076737002, + -0.040174201 -0.0100465 -0.077010997, + -0.0378174 -0.0095637199 -0.077221997, + -0.035366699 -0.0092240097 -0.077353999, + -0.0328326 -0.0090348003 -0.077388003, + -0.0302257 -0.0090000499 -0.077303, + -0.027557701 -0.0091172401 -0.077082999, + -0.0248404 -0.0093793599 -0.076709002, + -0.0220857 -0.0097753396 -0.076167002, + -0.019305199 -0.0102904 -0.075443998, + -0.0165099 -0.0109048 -0.074533001, + -0.0137106 -0.011595 -0.073430002, + -0.052956201 -0.0301963 -0.1715, + -0.053282801 -0.029550901 -0.1715, + -0.057377499 -0.019544801 -0.1715, + -0.056809202 -0.0214577 -0.16401, + -0.0576833 -0.0190764 -0.156728, + -0.058412101 -0.016959701 -0.149666, + -0.058998398 -0.0151268 -0.14284, + -0.059445001 -0.0135953 -0.136263, + -0.059757002 -0.0123741 -0.12994801, + -0.0599402 -0.0114639 -0.123914, + -0.059999999 -0.0108429 -0.118181, + -0.0599402 -0.0104825 -0.11278, + -0.059757002 -0.0103488 -0.10774, + -0.059445001 -0.0104112 -0.103091, + -0.058998398 -0.01066 -0.098857999, + -0.058412101 -0.01109 -0.095060997, + -0.0576833 -0.0115431 -0.091659002, + -0.056809202 -0.0118896 -0.088583998, + -0.055787299 -0.0121671 -0.085883997, + -0.0546159 -0.0124282 -0.083576001, + -0.0532961 -0.0112522 -0.083553001, + -0.051830001 -0.0101264 -0.083609, + -0.050219599 -0.0090704896 -0.083728001, + -0.048467699 -0.0081011904 -0.083893999, + -0.0465803 -0.00723226 -0.084090002, + -0.044564299 -0.0064757699 -0.084298998, + -0.0424264 -0.0058425101 -0.0845, + -0.040174201 -0.00534224 -0.084665999, + -0.0378174 -0.0049752402 -0.084799998, + -0.035366699 -0.0047256802 -0.084873997, + -0.0328326 -0.0046010101 -0.084854998, + -0.0302257 -0.0046106302 -0.084729001, + -0.027557701 -0.00475791 -0.084485002, + -0.0248404 -0.0050425702 -0.084109001, + -0.0220857 -0.0054609701 -0.083586998, + -0.019305199 -0.0060063102 -0.082906, + -0.0165099 -0.0066665998 -0.082056999, + -0.0137106 -0.0074266801 -0.081033997, + -0.0109179 -0.0082690502 -0.079829998, + -0.0081428103 -0.0068956199 -0.082208999, + -0.0081428103 -0.0044223499 -0.085871004, + -0.0081428103 -0.00176009 -0.089411996, + -0.0109179 -0.00340076 -0.087160997, + -0.0053973799 -0.0042350199 -0.086221002, + 0.0081428103 -0.00442483 -0.085867003, + 0.0109179 -0.00340492 -0.087155998, + 0.0081428103 -0.0017637101 -0.089409001, + 0.0053973799 -0.0042366702 -0.086218998, + 0.0053973799 -0.0067360601 -0.082562, + 0.00268824 -0.0066416101 -0.082771003, + 0.00268824 -0.0089646699 -0.079005003, + 0 -0.0089393603 -0.079074003, + 0 -0.0110682 -0.075211003, + -0.00268824 -0.0089646997 -0.079007, + -0.00268824 -0.0066411998 -0.082772002, + -0.0053973799 -0.0067352401 -0.082563996, + -0.0109179 -0.0059322598 -0.083548002, + 0.0109179 -0.0059347302 -0.083543003, + 0.051830001 -0.0056560901 -0.089602001, + 0.051830001 -0.0071958601 -0.087646998, + 0.0532961 -0.0067519099 -0.089700997, + 0.050219599 -0.0046609701 -0.089616999, + 0.050219599 -0.0061904001 -0.087692998, + 0.048467699 -0.00375545 -0.089681998, + 0.048467699 -0.0052611502 -0.087791003, + 0.0465803 -0.0029374999 -0.089783996, + 0.0465803 -0.0044253101 -0.087922998, + 0.044564299 -0.00222344 -0.089906, + 0.044564299 -0.0036962801 -0.088071004, + 0.0424264 -0.0016259101 -0.090029001, + 0.0424264 -0.0030854801 -0.088216998, + 0.040174201 -0.00115484 -0.090134002, + 0.040174201 -0.00260217 -0.088339999, + 0.0378174 -0.00081645802 -0.090202004, + 0.0378174 -0.0022523 -0.088425003, + 0.035366699 -0.00061530498 -0.090217002, + 0.035366699 -0.0020409401 -0.088459, + 0.0328326 -0.00055550301 -0.090167001, + 0.0328326 -0.00197054 -0.088431999, + 0.0302257 -0.00063814298 -0.090039, + 0.0302257 -0.0020306101 -0.088302001, + 0.027557701 -0.00085139897 -0.089798003, + 0.027557701 -0.0022194199 -0.088055, + 0.0248404 -0.0011923501 -0.089429997, + 0.0248404 -0.0025382901 -0.087682001, + 0.0220857 -0.0016608801 -0.088927001, + 0.0220857 -0.0029862099 -0.087171003, + 0.019305199 -0.0022539201 -0.088276997, + 0.019305199 -0.0035598299 -0.086510003, + 0.0165099 -0.00296439 -0.087471001, + 0.0165099 -0.0042506098 -0.085689999, + 0.0137106 -0.0037819501 -0.086502001, + 0.0137106 -0.0050470098 -0.084702998, + 0.0109179 -0.00469393 -0.085363001, + 0.0137106 -0.0024677699 -0.088273004, + 0.0165099 -0.00162742 -0.089222997, + 0.019305199 -0.00089540199 -0.090012997, + 0.0220857 -0.000280643 -0.090650998, + 0.0248404 0.00021015901 -0.091144003, + 0.027557701 0.00057487399 -0.091502003, + 0.0302257 0.00080997503 -0.091737002, + 0.0328326 0.00090421602 -0.091881, + 0.035366699 0.00085534202 -0.091945, + 0.0378174 0.00066582602 -0.091941997, + 0.040174201 0.000339366 -0.091888003, + 0.0424264 -0.000119174 -0.091802001, + 0.044564299 -0.000702939 -0.091701001, + 0.0465803 -0.0014006899 -0.091604002, + 0.048467699 -0.0021968 -0.091531999, + 0.050219599 -0.0030946301 -0.091495, + 0.051830001 -0.0041076401 -0.091562003, + 0.0532961 -0.00361737 -0.093883999, + 0.0546159 -0.00634429 -0.092138, + 0.0546159 -0.0031339701 -0.096583001, + 0.055787299 -0.0059160702 -0.094954997, + 0.055787299 -0.00263115 -0.099616997, + 0.056809202 -0.0054403702 -0.098104, + 0.056809202 -0.0037944301 -0.100546, + 0.0576833 -0.0050130701 -0.10164, + 0.058412101 -0.0158298 -0.164244, + 0.0576833 -0.018629599 -0.164129, + 0.058215201 -0.0165255 -0.1715, + 0.058412101 -0.0162358 -0.156958, + 0.058998398 -0.0134419 -0.157187, + 0.058998398 -0.0141314 -0.150003, + 0.059445001 -0.0113543 -0.150343, + 0.059445001 -0.0123245 -0.14328, + 0.059757002 -0.0095760301 -0.143728, + 0.059757002 -0.0108245 -0.136804, + 0.0599402 -0.0081112599 -0.137356, + 0.0599402 -0.0096355602 -0.13059001, + 0.059999999 -0.0069421199 -0.131248, + 0.059999999 -0.0087396298 -0.124659, + 0.0599402 -0.00604486 -0.12542699, + 0.0599402 -0.0081126997 -0.119038, + 0.059757002 -0.0053953798 -0.119925, + 0.059757002 -0.0077286698 -0.113758, + 0.059445001 -0.0049729398 -0.114772, + 0.059445001 -0.0075595202 -0.108849, + 0.058998398 -0.00477135 -0.109993, + 0.058998398 -0.0075964299 -0.104337, + 0.058412101 -0.0047867699 -0.105609, + 0.058412101 -0.0078345798 -0.100243, + 0.0576833 -0.0082645696 -0.096583001, + 0.056809202 -0.0087241903 -0.093310997, + 0.055787299 -0.0091087604 -0.090368003, + 0.0546159 -0.0094450004 -0.087806001, + 0.0532961 -0.00979017 -0.085630998, + 0.051830001 -0.0086952196 -0.085648, + 0.050219599 -0.0076639201 -0.085730001, + 0.048467699 -0.0067149401 -0.085859999, + 0.0465803 -0.0058626798 -0.086021997, + 0.044564299 -0.0051193601 -0.086197004, + 0.0424264 -0.0044957502 -0.086365998, + 0.040174201 -0.0040008398 -0.086510003, + 0.0378174 -0.00364122 -0.086618997, + 0.035366699 -0.00342 -0.086684003, + 0.0328326 -0.00332585 -0.086659998, + 0.0302257 -0.0033602901 -0.086528003, + 0.027557701 -0.00352671 -0.086280003, + 0.0248404 -0.00382558 -0.085904002, + 0.0220857 -0.0042558201 -0.085386999, + 0.019305199 -0.00481254 -0.084716, + 0.0165099 -0.0054859198 -0.083881997, + 0.0137106 -0.0062626698 -0.082877003, + 0.0109179 -0.0071268999 -0.081694998, + 0.057597399 -0.0187659 -0.1715, + 0.057669099 -0.018506 -0.1715, + 0.058857501 -0.0136529 -0.1715, + -0.0109179 -0.00067927898 -0.09065, + -0.050219599 0.0033076301 -0.099274002, + -0.051830001 0.0023086399 -0.099766999, + -0.050219599 0.00168467 -0.097273998, + -0.048467699 0.00422758 -0.098902002, + -0.048467699 0.00260458 -0.097005002, + -0.0465803 0.0050503002 -0.098646, + -0.0465803 0.00342338 -0.096858002, + -0.044564299 0.00575889 -0.098502003, + -0.044564299 0.0024812601 -0.095164001, + -0.0424264 0.0046711601 -0.096865997, + -0.0424264 0.0030330899 -0.09522, + -0.040174201 0.0050870301 -0.096896999, + -0.040174201 0.0034668699 -0.095270999, + -0.0378174 0.0053780498 -0.09691, + -0.0378174 0.00377097 -0.095297001, + -0.035366699 0.0055338601 -0.096886002, + -0.035366699 0.0039381599 -0.095283002, + -0.0328326 0.0055479901 -0.096805997, + -0.0328326 0.0039633401 -0.095209002, + -0.0302257 0.0054169302 -0.096653, + -0.0302257 0.0038437599 -0.095059, + -0.027557701 0.0051416098 -0.096413001, + -0.027557701 0.0035808301 -0.094815999, + -0.0248404 0.0047248499 -0.096068002, + -0.0248404 0.0031773599 -0.094461001, + -0.0220857 0.0041701598 -0.095601998, + -0.0220857 0.0026398101 -0.093988001, + -0.019305199 0.0034849099 -0.095007002, + -0.019305199 0.0019795101 -0.093382001, + -0.0165099 0.0026820099 -0.094273999, + -0.0165099 0.0012014 -0.092629001, + -0.0137106 0.00176782 -0.093387999, + -0.0137106 0.000312016 -0.09172, + -0.0109179 0.00075012702 -0.092341997, + -0.0532961 0.0029001201 -0.102595, + -0.0546159 0.00178851 -0.103438, + -0.055787299 0.00059667201 -0.104433, + -0.056809202 -0.00066643901 -0.105586, + -0.0576833 -0.0019926201 -0.1069, + -0.058412101 -0.0019956499 -0.111164, + -0.058998398 -0.00222151 -0.115819, + -0.059445001 -0.0026752199 -0.120846, + -0.059757002 -0.0033585001 -0.126224, + -0.0599402 -0.0042728898 -0.131926, + -0.059999999 -0.0054404899 -0.137922, + -0.0599402 -0.00688852 -0.14418299, + -0.059757002 -0.0086412504 -0.150685, + -0.059445001 -0.010707 -0.15741199, + -0.0532961 -0.0036084999 -0.093884997, + -0.051830001 -0.000931243 -0.095599003, + -0.0532961 -0.00038581801 -0.098190002, + -0.0546159 -0.0031300399 -0.096583001, + -0.0546159 0.00015479 -0.101117, + -0.055787299 -0.0026283499 -0.099618003, + -0.055787299 -0.00099118904 -0.102001, + -0.056809202 -0.0037968699 -0.100551, + -0.056809202 -0.00220594 -0.103045, + -0.0576833 -0.0050234799 -0.10165, + -0.0576833 -0.0034813001 -0.104253, + -0.058412101 -0.0048092399 -0.105625, + -0.058412101 -0.0078451196 -0.100252, + -0.058998398 -0.0076191402 -0.104354, + -0.058998398 -0.00480182 -0.110013, + -0.059445001 -0.0075902101 -0.10887, + -0.059445001 -0.0050071701 -0.114794, + -0.059757002 -0.0077630798 -0.113781, + -0.059757002 -0.0054290802 -0.119948, + -0.0599402 -0.0081465002 -0.119061, + -0.0599402 -0.0060742898 -0.12545, + -0.059999999 -0.0087690903 -0.124682, + -0.059999999 -0.0069663301 -0.13126899, + -0.0599402 -0.0096597401 -0.130611, + -0.0599402 -0.0081327204 -0.137374, + -0.059757002 -0.0108459 -0.136822, + -0.059757002 -0.0096005602 -0.143741, + -0.059445001 -0.0123489 -0.14329299, + -0.059445001 -0.0113885 -0.15034799, + -0.058998398 -0.0141653 -0.15000799, + -0.058998398 -0.0134829 -0.157185, + -0.058412101 -0.0162763 -0.156957, + -0.058412101 -0.015862999 -0.16424, + -0.058168899 -0.0167097 -0.1715, + -0.0576833 -0.018662401 -0.164125, + -0.0588204 -0.0138392 -0.1715, + -0.050219599 7.555e-005 -0.095307998, + -0.048467699 0.00099472795 -0.095147997, + -0.0465803 0.00018976899 -0.093382999, + -0.044564299 0.00086925499 -0.093452998, + -0.0424264 0.00144018 -0.093532003, + -0.040174201 0.00188789 -0.093601003, + -0.0378174 0.00220379 -0.093641996, + -0.035366699 0.0023819699 -0.093639001, + -0.0328326 0.0024180899 -0.093572997, + -0.0302257 0.00230993 -0.093424998, + -0.027557701 0.0020588201 -0.093175001, + -0.0248404 0.00167098 -0.092818998, + -0.0220857 0.0011582 -0.09234, + -0.019305199 0.00052201998 -0.091718003, + -0.0165099 -0.00023287399 -0.090945996, + -0.0137106 -0.00109832 -0.090016, + -0.0109179 -0.0020633901 -0.088922001, + -0.0137106 -0.00246168 -0.088278003, + -0.0165099 -0.0016195 -0.089227997, + -0.019305199 -0.00088645698 -0.090016998, + -0.0220857 -0.000272303 -0.090654001, + -0.0248404 0.000216616 -0.091145001, + -0.027557701 0.000579454 -0.091502003, + -0.0302257 0.000816238 -0.091746002, + -0.0328326 0.00091387599 -0.091897003, + -0.035366699 0.000867102 -0.091955997, + -0.0378174 0.00067825301 -0.091946997, + -0.040174201 0.00035116001 -0.091889001, + -0.0424264 -0.000109006 -0.091801003, + -0.044564299 -0.00069495698 -0.091700003, + -0.0465803 -0.00139497 -0.091604002, + -0.048467699 -0.0021931001 -0.091531001, + -0.050219599 -0.00151666 -0.093379997, + -0.051830001 -0.00252609 -0.093562998, + -0.051830001 -0.0041001299 -0.091562003, + -0.050219599 -0.00465714 -0.089616001, + -0.048467699 -0.0037495 -0.089681, + -0.0465803 -0.0029291599 -0.089782998, + -0.044564299 -0.00221276 -0.089906, + -0.0424264 -0.00161345 -0.090030998, + -0.040174201 -0.00114164 -0.090139002, + -0.0378174 -0.00080388301 -0.090213001, + -0.035366699 -0.00060489902 -0.090233997, + -0.0328326 -0.00054869999 -0.090177, + -0.0302257 -0.00063311902 -0.090038002, + -0.027557701 -0.000844236 -0.089799002, + -0.0248404 -0.00118297 -0.089433998, + -0.0220857 -0.00165064 -0.088932, + -0.019305199 -0.0022446499 -0.088283002, + -0.0165099 -0.00295706 -0.087477997, + -0.0137106 -0.00377673 -0.086507998, + -0.0109179 -0.0046906001 -0.085368998, + -0.0137106 -0.00504283 -0.084709004, + -0.0165099 -0.0042443299 -0.085697003, + -0.019305199 -0.0035512601 -0.086517997, + -0.0220857 -0.0029756101 -0.087177999, + -0.0248404 -0.0025267799 -0.087687999, + -0.027557701 -0.0022090101 -0.088059001, + -0.0302257 -0.00202275 -0.088303998, + -0.0328326 -0.0019650799 -0.088431001, + -0.035366699 -0.0020336099 -0.088469997, + -0.0378174 -0.00224117 -0.088443004, + -0.040174201 -0.0025888099 -0.088352002, + -0.0424264 -0.00307153 -0.088221997, + -0.044564299 -0.0036832001 -0.088073, + -0.0465803 -0.0044141398 -0.087922998, + -0.048467699 -0.0052524698 -0.087789997, + -0.050219599 -0.0061842301 -0.087692, + -0.051830001 -0.0071919099 -0.087646, + -0.0532961 -0.0067441901 -0.089700997, + -0.0546159 -0.0063351998 -0.092139997, + -0.055787299 -0.0059120599 -0.094954997, + -0.056809202 -0.0054375199 -0.098104998, + -0.0576833 -0.00661752 -0.099092998, + -0.0576833 -0.0082616704 -0.096584, + -0.056809202 -0.0087200999 -0.093310997, + -0.055787299 -0.0090994705 -0.090369999, + -0.0546159 -0.0094370898 -0.087806001, + -0.0532961 -0.0097861001 -0.08563, + -0.051830001 -0.0086888503 -0.085647002, + -0.050219599 -0.00765493 -0.085729003, + -0.048467699 -0.00670332 -0.085859999, + -0.0465803 -0.0058490001 -0.086024001, + -0.044564299 -0.0051047201 -0.086203001, + -0.0424264 -0.0044816402 -0.086378001, + -0.040174201 -0.0039890199 -0.086529002, + -0.0378174 -0.0036333899 -0.086631, + -0.035366699 -0.0034141201 -0.086682998, + -0.0328326 -0.00331732 -0.086661004, + -0.0302257 -0.00334888 -0.086531997, + -0.027557701 -0.0035139399 -0.086286001, + -0.0248404 -0.00381366 -0.085911997, + -0.0220857 -0.0042460202 -0.085395001, + -0.019305199 -0.00480519 -0.084724002, + -0.0165099 -0.0054808902 -0.083889998, + -0.0137106 -0.0062595699 -0.082883999, + -0.0109179 -0.00712523 -0.081701003, + -0.0575951 -0.018765301 -0.1715, + -0.057667602 -0.018505599 -0.1715, + -0.058982901 -0.0129151 -0.1715, + -0.0137069 0.056396201 -0.1715, + -0.0122713 0.0567232 -0.1715, + 0.0081412597 0.057432398 -0.1715, + 0.0061684698 0.0576756 -0.1715, + -0.0061689499 0.057679601 -0.1715, + -0.00814093 0.0574301 -0.1715, + -0.0275524 -0.0145 -0.053286001, + 0.0046305298 -0.0094999997 0.059820998, + 0.00289505 -0.0145 0.05993, + 0.0053912001 -0.0145 0.059748001, + 0.0081406701 -0.0145 0.059432998, + 0.0137074 -0.0145 0.058398001, + 0.016505999 -0.0145 0.057668999, + 0.0220802 -0.0145 0.055773001, + 0.0226011 -0.0145 0.055573002, + 0.0229061 -0.0145 0.055456001, + 0.0248347 -0.0145 0.054602999, + 0.044564299 -0.049601499 0.035746999, + 0.0424264 -0.052304499 0.037611999, + 0.040174201 -0.055047799 0.039262999, + 0.0378174 -0.057813201 0.040686999, + 0.035366699 -0.0605812 0.041870002, + 0.0328326 -0.063331299 0.042799, + 0.0302257 -0.066042401 0.043466002, + 0.027557701 -0.068695299 0.043866001, + 0.0248404 -0.071270801 0.043999001, + 0.0220857 -0.073749498 0.043862998, + 0.019305199 -0.076112904 0.043462001, + 0.0165099 -0.078345701 0.042803001, + 0.0137106 -0.080433898 0.041896001, + 0.0109179 -0.082364298 0.040750999, + 0.0081421202 -0.084124997 0.039381001, + 0.0053918599 -0.085708097 0.037802, + 0.00267513 -0.087107502 0.036031, + 0 -0.088318102 0.034084, + -0.00267513 -0.087106198 0.036029998, + -0.0053918599 -0.085705496 0.037799999, + -0.0081421202 -0.084121197 0.039377999, + -0.0109179 -0.0823595 0.040747002, + -0.0137106 -0.080428198 0.041889999, + -0.0165099 -0.078339398 0.042794999, + -0.019305199 -0.076106198 0.043453, + -0.0220857 -0.073742799 0.043853, + -0.0248404 -0.0712642 0.043986, + -0.027557701 -0.0686891 0.043852001, + -0.0302257 -0.066036798 0.043451, + -0.0328326 -0.063326202 0.042782001, + -0.035366699 -0.060577001 0.041852001, + -0.0378174 -0.057810001 0.040668, + -0.040174201 -0.0550461 0.039243001, + -0.0424264 -0.052305002 0.037590999, + -0.044564299 -0.049604699 0.035726, + -0.0328261 -0.0145 0.050209001, + -0.036012899 -0.0094999997 0.047990002, + -0.035361301 -0.0145 0.048459999, + -0.035764702 -0.0145 0.048176002, + -0.037813399 -0.0145 0.046574999, + -0.045067899 -0.0094999997 0.039609, + -0.042443302 -0.0145 0.042408999, + -0.045056298 -0.0145 0.039599001, + -0.044562198 -0.0145 0.040171999, + -0.046393901 -0.0145 0.038047001, + -0.0465803 -0.016561201 0.037762001, + -0.048467699 -0.0165345 0.035305001, + -0.048204001 -0.0145 0.035726, + -0.0465803 -0.018581901 0.037597001, + -0.044564299 -0.0186374 0.039976001, + -0.044564299 -0.022475099 0.039645001, + -0.0424264 -0.0226162 0.041956998, + -0.044564299 -0.0299036 0.038975, + -0.0465803 -0.022327499 0.037225001, + -0.048467699 -0.018524099 0.035123002, + -0.048887499 -0.0145 0.034754999, + -0.0498982 -0.0145 0.033319, + -0.048901699 -0.0094999997 0.034765001, + -0.048460599 -0.0145 0.035362002, + -0.0465759 -0.0145 0.037813999, + -0.050209999 -0.0145 0.032825999, + -0.0532961 -0.0154663 0.027550999, + -0.051830001 -0.0164786 0.030152, + -0.050219599 -0.0184645 0.032565001, + -0.048467699 -0.022174001 0.034708999, + -0.0465803 -0.029545899 0.036476001, + -0.0465803 -0.036741499 0.035735, + -0.048467699 -0.036146399 0.033054002, + -0.048467699 -0.0378801 0.032850001, + -0.050219599 -0.0372063 0.030057, + -0.050219599 -0.038744699 0.029797999, + -0.051830001 -0.037994601 0.026904, + -0.054245099 -0.0145 0.025641, + -0.0546025 -0.0145 0.024834, + -0.054963201 -0.0145 0.024019999, + -0.053284001 -0.0145 0.027551999, + -0.053282399 -0.0145 -0.027550999, + -0.054979 -0.0094999997 -0.024026999, + -0.054163702 -0.0145 -0.025813, + -0.054601099 -0.0145 -0.024834, + -0.054964401 -0.0145 -0.024021, + -0.0546159 -0.0151798 -0.024874, + -0.055364501 -0.0145 -0.023125, + -0.055787299 -0.015910501 -0.022276999, + -0.056809202 -0.0166307 -0.019741001, + -0.0576833 -0.017306101 -0.017238, + -0.058412101 -0.0183788 -0.015066, + -0.058998398 -0.0192756 -0.012811, + -0.059445001 -0.022570999 -0.012264, + -0.059757002 -0.0262485 -0.011537, + -0.0599402 -0.0285269 -0.0096319998, + -0.059999999 -0.030988401 -0.0078220097, + -0.0599402 -0.033698998 -0.0061380002, + -0.059757002 -0.036627699 -0.0045939898, + -0.059445001 -0.039772499 -0.003209, + -0.058998398 -0.043099899 -0.002021, + -0.058412101 -0.046562199 -0.00106799, + -0.0576833 -0.0501085 -0.00037399301, + -0.056809202 -0.053683098 4.2007399e-005, + -0.055787299 -0.056382202 0.001679, + -0.0546159 -0.059105501 0.0032009999, + -0.0532961 -0.061834499 0.0045959898, + -0.051830001 -0.064550899 0.0058510001, + -0.050219599 -0.067235798 0.0069579901, + -0.048467699 -0.069869898 0.0079070004, + -0.0465803 -0.072433896 0.0086939996, + -0.044564299 -0.074910298 0.0093120001, + -0.0424264 -0.077281699 0.0097559998, + -0.040174201 -0.0795312 0.010023, + -0.0378174 -0.081643403 0.010117, + -0.035366699 -0.083602697 0.010051, + -0.0328326 -0.0854012 0.009811, + -0.0302257 -0.0870611 0.0092890002, + -0.027557701 -0.088849299 0.0063809999, + -0.0248404 -0.0902263 0.0054350002, + -0.0220857 -0.091458701 0.0043090102, + -0.0576833 -0.048126802 0.00210899, + -0.058412101 -0.044537 0.001162, + -0.058998398 -0.041074701 -4.2007399e-005, + -0.059445001 -0.03779 -0.001466, + -0.059757002 -0.034721699 -0.0030690001, + -0.0599402 -0.031881001 -0.0048019998, + -0.059999999 -0.029300001 -0.0066479901, + -0.0599402 -0.0269063 -0.0085740099, + -0.059757002 -0.0229876 -0.0093529997, + -0.059445001 -0.0194494 -0.0099620102, + -0.058998398 -0.0184933 -0.012222, + -0.058412101 -0.017371699 -0.014413, + -0.0576833 -0.0166773 -0.016930999, + -0.056809202 -0.0159407 -0.01949, + -0.055787299 -0.0151947 -0.022117, + -0.055771399 -0.0145 -0.02208, + -0.056432001 -0.0145 -0.020382, + -0.056809202 -0.0152097 -0.019335, + -0.0576833 -0.015970999 -0.016689001, + -0.058412101 -0.016724 -0.014117, + -0.058998398 -0.017437199 -0.011595, + -0.059445001 -0.0186071 -0.0093959998, + -0.059757002 -0.019621201 -0.0071430099, + -0.0599402 -0.023398699 -0.00648, + -0.059999999 -0.027558999 -0.0056329998, + -0.0599402 -0.030073199 -0.003664, + -0.059757002 -0.032780599 -0.001759, + -0.059445001 -0.035758201 4.2007399e-005, + -0.058998398 -0.038964901 0.00169501, + -0.058412101 -0.042385198 0.003146, + -0.0576833 -0.0459776 0.0043529999, + -0.056809202 -0.049689099 0.0052800002, + -0.055787299 -0.0523776 0.0071999999, + -0.0546159 -0.055120502 0.0090049999, + -0.0532961 -0.0579 0.010679, + -0.051830001 -0.060697801 0.012206, + -0.050219599 -0.0634946 0.013574, + -0.048467699 -0.066270001 0.01477, + -0.0465803 -0.069003403 0.015786, + -0.044564299 -0.071675397 0.016612999, + -0.0424264 -0.074266098 0.017246, + -0.040174201 -0.076755799 0.017680001, + -0.0378174 -0.079126596 0.017916, + -0.035366699 -0.081363097 0.017952001, + -0.0328326 -0.083450399 0.017792, + -0.0302257 -0.085374802 0.017434999, + -0.027557701 -0.087125003 0.016892999, + -0.0248404 -0.088689499 0.016186999, + -0.0220857 -0.090066001 0.015306, + -0.019305199 -0.091283299 0.014144, + -0.0165099 -0.092655301 0.010549, + -0.0137106 -0.0937846 0.0067339898, + -0.0109179 -0.094652496 0.00272099, + -0.0081421202 -0.095249802 -0.001467, + -0.0053918599 -0.095571801 -0.005808, + -0.00267513 -0.095616102 -0.010278, + 0 -0.095381297 -0.014853, + 0.00267513 -0.095616497 -0.010278, + 0.0053918599 -0.095573097 -0.005808, + 0.0081421202 -0.095252201 -0.001467, + 0.0109179 -0.094656102 0.00272301, + 0.0137106 -0.093789101 0.0067380099, + 0.0165099 -0.092660099 0.010556, + 0.055787299 -0.052392401 0.0072280001, + 0.055787299 -0.0534801 0.0059310002, + 0.056809202 -0.049701899 0.0053090099, + 0.0546159 -0.055137102 0.0090319999, + 0.0546159 -0.0562278 0.0076600001, + 0.0532961 -0.057918299 0.010703, + 0.0532961 -0.059004299 0.0092580002, + 0.051830001 -0.060717501 0.012229, + 0.051830001 -0.061790802 0.01071, + 0.050219599 -0.063515402 0.013595, + 0.050219599 -0.064567402 0.012005, + 0.048467699 -0.066291504 0.014789, + 0.048467699 -0.067313597 0.01313, + 0.0465803 -0.069025204 0.015802, + 0.0465803 -0.070009902 0.014078, + 0.044564299 -0.071696803 0.016627001, + 0.044564299 -0.072636999 0.014843, + 0.0424264 -0.074286498 0.017258, + 0.0424264 -0.075174801 0.015419, + 0.040174201 -0.076774403 0.017689999, + 0.040174201 -0.077604003 0.015802, + 0.0378174 -0.079142801 0.017922999, + 0.0378174 -0.079908803 0.015992001, + 0.035366699 -0.081376404 0.017958, + 0.035366699 -0.082074903 0.015989, + 0.0328326 -0.083460897 0.017795, + 0.0328326 -0.084088102 0.015794, + 0.0302257 -0.085382603 0.017436, + 0.0302257 -0.085934497 0.015413, + 0.027557701 -0.087130599 0.016891999, + 0.027557701 -0.087602101 0.014869, + 0.0248404 -0.088693701 0.016186001, + 0.0248404 -0.0890885 0.014151, + 0.0220857 -0.090069599 0.015307, + 0.0220857 -0.090421297 0.013155, + 0.019305199 -0.0912873 0.01415, + 0.019305199 -0.091902599 0.0097270096, + 0.019305199 -0.092370503 0.0052590002, + 0.0220857 -0.0912605 0.0065410002, + 0.0248404 -0.090001501 0.007646, + 0.027557701 -0.088310003 0.010728, + 0.0302257 -0.086755201 0.011402, + 0.0328326 -0.085057601 0.011799, + 0.035366699 -0.083191201 0.01202, + 0.0378174 -0.081162401 0.012081, + 0.040174201 -0.078986697 0.011964, + 0.0424264 -0.076678596 0.011665, + 0.044564299 -0.074252903 0.011183, + 0.0465803 -0.071726099 0.010522, + 0.048467699 -0.069115996 0.0096890004, + 0.050219599 -0.066441797 0.0086869998, + 0.051830001 -0.063722901 0.007524, + 0.0532961 -0.060978498 0.006209, + 0.0546159 -0.0582279 0.0047510099, + 0.055787299 -0.0554903 0.0031640001, + 0.055787299 -0.054513998 0.0045750001, + 0.0546159 -0.057259299 0.0062319902, + 0.0532961 -0.060025599 0.0077579999, + 0.051830001 -0.062793799 0.0091399997, + 0.050219599 -0.065543599 0.010367, + 0.048467699 -0.068255797 0.011428, + 0.0465803 -0.070910998 0.012316, + 0.044564299 -0.073489599 0.013026, + 0.0424264 -0.075972103 0.013552, + 0.040174201 -0.078341097 0.013892, + 0.0378174 -0.080581702 0.014043, + 0.035366699 -0.082679696 0.014007, + 0.0328326 -0.084620602 0.013788, + 0.0302257 -0.086389601 0.013406, + 0.027557701 -0.087983102 0.012849, + 0.0248404 -0.089428499 0.012014, + 0.0220857 -0.091016904 0.0087580001, + 0.0576833 -0.045986399 0.0043830001, + 0.058412101 -0.042390201 0.00317599, + 0.058998398 -0.038964301 0.001724, + 0.059445001 -0.0357517 6.9000198e-005, + 0.059757002 -0.032785099 -0.00174001, + 0.0599402 -0.030096499 -0.0036589999, + 0.059999999 -0.0275592 -0.0056340001, + 0.0599402 -0.023402199 -0.0064810002, + 0.059757002 -0.019626301 -0.0071390099, + 0.059445001 -0.018627301 -0.0093919998, + 0.058998398 -0.017451501 -0.011557, + 0.058412101 -0.016727 -0.014079, + 0.0576833 -0.015973501 -0.016673001, + -0.056809202 -0.047416098 0.0075389999, + -0.0576833 -0.043698799 0.0063410001, + -0.058412101 -0.040147301 0.0048760101, + -0.058998398 -0.036805801 0.0031870001, + -0.059445001 -0.0336922 0.001325, + -0.059757002 -0.0308524 -0.00065699802, + -0.0599402 -0.0282117 -0.00269299, + -0.059999999 -0.0238067 -0.0036289999, + -0.0599402 -0.0197908 -0.0043620002, + -0.059757002 -0.018719699 -0.0066000102, + -0.059445001 -0.0175022 -0.0087940097, + -0.058998398 -0.016770501 -0.01131, + -0.058412101 -0.0160014 -0.013883, + -0.0576833 -0.0152249 -0.016538, + -0.057145901 -0.0145 -0.018243, + -0.058396202 -0.0145 -0.013707, + -0.058731299 -0.0094999997 -0.012273, + -0.058157299 -0.0145 -0.014756, + -0.057158101 -0.0094999997 -0.018247001, + -0.0573637 -0.0145 -0.017589999, + -0.0576673 -0.0145 -0.016504999, + -0.056793101 -0.0145 -0.019300001, + -0.0594301 -0.0145 -0.0081410101, + -0.059323099 -0.0145 -0.0089870002, + -0.058982499 -0.0145 -0.010915, + -0.058811001 -0.0145 -0.011886, + -0.0599402 -0.0188308 -0.0038409999, + -0.059999999 -0.0199592 -0.00160201, + -0.0599402 -0.024214599 -0.00077799999, + -0.059757002 -0.0288695 0.00027099601, + -0.059445001 -0.031642001 0.0023910101, + -0.058998398 -0.034613598 0.0044429898, + -0.058412101 -0.037860099 0.0063510002, + -0.0576833 -0.041332498 0.0080650002, + -0.056809202 -0.0450105 0.0095319999, + -0.055787299 -0.048847001 0.010709, + -0.0546159 -0.051543701 0.01274, + -0.0532961 -0.054301601 0.014644, + -0.051830001 -0.057103101 0.016403999, + -0.050219599 -0.0599292 0.018004, + -0.048467699 -0.062759601 0.019427, + -0.0465803 -0.065574698 0.020662, + -0.044564299 -0.068353698 0.0217, + -0.0424264 -0.071075402 0.022529, + -0.040174201 -0.073718198 0.023145, + -0.0378174 -0.076263599 0.023543, + -0.035366699 -0.078693703 0.023724001, + -0.0328326 -0.0809903 0.023689, + -0.0302257 -0.083136603 0.02344, + -0.027557701 -0.085120298 0.022983, + -0.0248404 -0.0869307 0.022324, + -0.0220857 -0.088557802 0.021472, + -0.019305199 -0.089992702 0.020437, + -0.0165099 -0.091227703 0.019246999, + -0.0137106 -0.092265502 0.017896, + -0.0109179 -0.093140103 0.016279001, + -0.0081421202 -0.094184101 0.012223, + -0.0053918599 -0.094976902 0.0079770098, + -0.00267513 -0.095504299 0.0035659899, + 0 -0.095761098 -0.00098500098, + 0.00267513 -0.095505103 0.0035669999, + 0.0053918599 -0.094978698 0.0079779997, + 0.0081421202 -0.0941865 0.012227, + 0.0109179 -0.093142301 0.016283, + 0.0137106 -0.0922677 0.017897001, + 0.0165099 -0.091230497 0.019246999, + 0.019305199 -0.089996599 0.020437, + 0.0220857 -0.088563599 0.021473, + 0.0248404 -0.086938597 0.022327, + 0.027557701 -0.085130699 0.022987001, + 0.0302257 -0.0831495 0.023445999, + 0.0328326 -0.081005499 0.023697, + 0.035366699 -0.078710601 0.023734, + 0.0378174 -0.076281801 0.023554999, + 0.040174201 -0.073736899 0.023158999, + 0.0424264 -0.0710942 0.022546001, + 0.044564299 -0.068372197 0.021718999, + 0.0465803 -0.065592401 0.020683, + 0.048467699 -0.062776297 0.01945, + 0.050219599 -0.059944499 0.018028, + 0.051830001 -0.057116799 0.01643, + 0.0532961 -0.0543136 0.014671, + 0.0546159 -0.051553998 0.012768, + 0.055787299 -0.048855498 0.010738, + 0.055787299 -0.046319999 0.012734, + 0.055787299 -0.0436926 0.014445, + 0.0546159 -0.046244599 0.016767999, + 0.055787299 -0.0410157 0.015866, + 0.0546159 -0.043460999 0.018322, + 0.056809202 -0.037402902 0.013883, + 0.0576833 -0.0340712 0.011683, + 0.058412101 -0.0308883 0.0093639996, + 0.058998398 -0.0254669 0.007948, + 0.059445001 -0.0204741 0.006763, + 0.059757002 -0.0178343 0.0049100001, + 0.0599402 -0.017000601 0.0024069999, + 0.059999999 -0.0161529 -0.000126007, + 0.059935998 -0.0145 -0.002688, + 0.0599324 -0.0145 -0.00284801, + 0.0599204 -0.0094999997 -0.003089, + 0.059720598 -0.0145 -0.0057839998, + 0.059285302 -0.0094999997 -0.0092329998, + 0.059433699 -0.0145 -0.0081410101, + 0.059365101 -0.0145 -0.0087059904, + 0.058866698 -0.0145 -0.011606, + 0.058021698 -0.0094999997 -0.01528, + 0.058398601 -0.0145 -0.013708, + 0.058226701 -0.0145 -0.014479, + 0.057446498 -0.0145 -0.017317999, + 0.056143001 -0.0094999997 -0.021165, + 0.056795198 -0.0145 -0.019300999, + 0.056527998 -0.0145 -0.020114001, + 0.055773601 -0.0145 -0.02208, + 0.054603402 -0.0145 -0.024835, + 0.0599204 -0.0094999997 0.003089, + 0.059745401 -0.0145 0.0053960001, + 0.059919201 -0.0145 0.003089, + 0.059923101 -0.0145 0.0030370001, + 0.0599402 -0.016182 0.00256799, + 0.059757002 -0.0170458 0.0051299999, + 0.059445001 -0.017898601 0.00767999, + 0.058998398 -0.0206478 0.0096119996, + 0.058412101 -0.0208226 0.012479, + 0.058412101 -0.025890701 0.01091, + 0.0576833 -0.026315499 0.013879, + 0.0576833 -0.031567998 0.012427, + 0.056809202 -0.032246701 0.015484, + 0.056809202 -0.034875002 0.014786, + 0.055787299 -0.035674501 0.017873, + 0.055787299 -0.0383261 0.017006001, + 0.0546159 -0.039240699 0.020099999, + 0.0532961 -0.0416114 0.022646001, + 0.0546159 -0.0420557 0.018987, + 0.0546159 -0.036466502 0.020931, + 0.0532961 -0.038683198 0.023585999, + 0.0546159 -0.0335907 0.021539001, + 0.0532961 -0.034250502 0.024512, + 0.0546159 -0.027579499 0.022713, + 0.055787299 -0.027161499 0.019792, + 0.055787299 -0.021346901 0.021077, + 0.056809202 -0.021172799 0.018223001, + 0.056809202 -0.0181602 0.018945999, + 0.0576833 -0.0180947 0.016124999, + 0.0576833 -0.016332099 0.016419999, + 0.058412101 -0.016301701 0.013615, + 0.0580099 -0.0145 0.015277, + 0.058998398 -0.016271399 0.010816, + 0.058829699 -0.0145 0.011793, + 0.058412101 -0.018029099 0.0133, + 0.0576833 -0.0209978 0.015353, + 0.056809202 -0.026739599 0.016843, + 0.055787299 -0.032921799 0.018526001, + 0.0592779 -0.0145 0.0092319902, + 0.0589833 -0.0145 0.010915, + 0.0581805 -0.0145 0.014664, + 0.058396801 -0.0145 0.013707, + 0.055787299 -0.018225299 0.021752, + 0.0546159 -0.0215193 0.023905, + 0.0532961 -0.0279919 0.025595, + 0.051830001 -0.0283967 0.028424, + 0.0532961 -0.0216894 0.026695, + 0.0546159 -0.0182897 0.024532, + 0.055787299 -0.0163926 0.022008, + 0.056128498 -0.0145 0.021159001, + 0.0532961 -0.0183533 0.027274, + 0.051830001 -0.021856301 0.029433999, + 0.050219599 -0.028792201 0.031189, + 0.051830001 -0.0348983 0.02743, + 0.0532961 -0.037247799 0.023947001, + 0.051830001 -0.038014799 0.026908001, + 0.050219599 -0.035531301 0.030282, + 0.048467699 -0.0291768 0.033876002, + 0.050219599 -0.0220195 0.032111, + 0.051830001 -0.018415701 0.029966, + 0.0532961 -0.016452 0.027492, + 0.053653602 -0.0145 0.026818, + 0.050219599 -0.0184767 0.032597002, + 0.048467699 -0.0221781 0.034713, + 0.0465803 -0.0295486 0.036474999, + 0.048467699 -0.0361466 0.033054002, + 0.050219599 -0.038764201 0.029802, + 0.051830001 -0.039508902 0.026566001, + 0.050611299 -0.0145 0.032191999, + 0.0502089 -0.0145 0.032825999, + 0.046574499 -0.0145 0.037813, + 0.048467699 -0.04603 0.030913001, + 0.0465803 -0.0486577 0.033069, + 0.044564299 -0.051351 0.035046998, + 0.0424264 -0.0540937 0.036825001, + 0.040174201 -0.056867301 0.038387001, + 0.0378174 -0.059652701 0.039717, + 0.035366699 -0.062429901 0.040803, + 0.0328326 -0.065178096 0.041634999, + 0.0302257 -0.067876302 0.042204, + 0.027557701 -0.070505098 0.042507, + 0.0248404 -0.073045202 0.042544998, + 0.0220857 -0.075477503 0.042318001, + 0.019305199 -0.077784799 0.04183, + 0.0165099 -0.079952203 0.041088998, + 0.0137106 -0.081965998 0.040107001, + 0.0109179 -0.0838136 0.038895, + 0.0081421202 -0.085485302 0.037464999, + 0.0053918599 -0.086974002 0.035835002, + 0.00267513 -0.088274002 0.034021001, + 0 -0.089381203 0.03204, + -0.00267513 -0.088272803 0.034019999, + -0.0053918599 -0.086971402 0.035833001, + -0.0081421202 -0.085481398 0.037462, + -0.0109179 -0.083808601 0.038890999, + -0.0137106 -0.08196 0.040102001, + -0.0165099 -0.0799454 0.041083001, + -0.019305199 -0.077777401 0.041820999, + -0.0220857 -0.075469904 0.042307999, + -0.0248404 -0.073037602 0.042532999, + -0.027557701 -0.070497803 0.042493001, + -0.0302257 -0.067869499 0.042188, + -0.0328326 -0.065171897 0.041618001, + -0.035366699 -0.0624245 0.040785, + -0.0378174 -0.059648201 0.039696999, + -0.040174201 -0.0568639 0.038366001, + -0.0424264 -0.0540918 0.036804002, + -0.044564299 -0.051351398 0.035025001, + -0.0465803 -0.048661102 0.033047002, + -0.048467699 -0.046035301 0.030890999, + -0.050219599 -0.043486301 0.028579, + -0.044564299 -0.016586799 0.040123999, + -0.0424264 -0.0166113 0.042381998, + -0.044472098 -0.0145 0.040277001, + -0.0424264 -0.0186905 0.04225, + -0.040174201 -0.0187409 0.044408999, + -0.040174201 -0.022750201 0.044151999, + -0.0378174 -0.022876499 0.046222001, + -0.040174201 -0.0305699 0.043630999, + -0.0424264 -0.0302455 0.041363001, + -0.0424264 -0.037860598 0.040777002, + -0.044564299 -0.0373137 0.038313001, + -0.044564299 -0.039158501 0.038148001, + -0.0465803 -0.038531799 0.035551, + -0.0465803 -0.0401791 0.035331, + -0.048467699 -0.039473899 0.032611001, + -0.048467699 -0.041084498 0.032299001, + -0.050219599 -0.040299602 0.029468, + -0.050219599 -0.041890599 0.029061001, + -0.051830001 -0.041024901 0.026133001, + -0.040748298 -0.0145 0.044025, + -0.051830001 -0.042561699 0.025636001, + -0.050219599 -0.045078699 0.028019, + -0.048467699 -0.047679801 0.030261001, + -0.0465803 -0.050353602 0.032340001, + -0.044564299 -0.053086501 0.034233999, + -0.0424264 -0.055860601 0.035925001, + -0.040174201 -0.0586561 0.037395999, + -0.0378174 -0.0614531 0.038633, + -0.035366699 -0.064231001 0.039624002, + -0.0328326 -0.066969097 0.04036, + -0.0302257 -0.069646403 0.040835001, + -0.027557701 -0.072243303 0.041046999, + -0.0248404 -0.074740604 0.040995002, + -0.0220857 -0.077120602 0.040681999, + -0.019305199 -0.079366401 0.040114999, + -0.0165099 -0.0814633 0.039299998, + -0.0137106 -0.083398402 0.038251001, + -0.0109179 -0.085161 0.036979001, + -0.0081421202 -0.086742103 0.035498001, + -0.0053918599 -0.088134997 0.033824999, + -0.00267513 -0.089334898 0.031977002, + 0 -0.090340003 0.029968999, + 0.00267513 -0.089336097 0.031977002, + 0.0053918599 -0.088137597 0.033826001, + 0.0081421202 -0.086746 0.035500001, + 0.0109179 -0.085166201 0.036982, + 0.0137106 -0.083404802 0.038256001, + 0.0165099 -0.081470698 0.039306998, + 0.019305199 -0.079374403 0.040123001, + 0.0220857 -0.077128999 0.040692002, + 0.0248404 -0.074749097 0.041005999, + 0.027557701 -0.0722517 0.041060001, + 0.0302257 -0.069654398 0.040849999, + 0.0328326 -0.066976599 0.040376998, + 0.035366699 -0.064237699 0.039641999, + 0.0378174 -0.061458901 0.038653001, + 0.040174201 -0.058660898 0.037416998, + 0.0424264 -0.0558642 0.035946999, + 0.044564299 -0.053088501 0.034256998, + 0.0465803 -0.050353199 0.032363001, + 0.048467699 -0.047676299 0.030284001, + 0.050219599 -0.0450732 0.028042, + 0.051830001 -0.042557798 0.025657, + 0.0532961 -0.040142901 0.023153, + 0.051830001 -0.044089001 0.025088999, + 0.050219599 -0.0466615 0.027403999, + 0.048467699 -0.049315602 0.029572001, + 0.0465803 -0.052036598 0.031569, + 0.044564299 -0.054807499 0.033376999, + 0.0424264 -0.0576092 0.034977999, + 0.040174201 -0.060421601 0.036355, + 0.0378174 -0.063224599 0.037496001, + 0.035366699 -0.065997697 0.038389999, + 0.0328326 -0.068719998 0.039030001, + 0.0302257 -0.071370102 0.039409999, + 0.027557701 -0.073928401 0.039528999, + 0.0248404 -0.076377198 0.039388001, + 0.0220857 -0.078698799 0.038991999, + 0.019305199 -0.080876499 0.038346998, + 0.0165099 -0.082896203 0.037462, + 0.0137106 -0.084747203 0.036348999, + 0.0109179 -0.0864195 0.035022002, + 0.0081421202 -0.087904602 0.033495001, + 0.0053918599 -0.089196801 0.031785, + 0.00267513 -0.090294003 0.029906999, + 0 -0.091195397 0.027876999, + -0.00267513 -0.090292998 0.029905999, + -0.0053918599 -0.089194499 0.031784002, + -0.0081421202 -0.087900802 0.033493001, + -0.0109179 -0.086414203 0.035018999, + -0.0137106 -0.084740601 0.036343999, + -0.0165099 -0.082888499 0.037455998, + -0.019305199 -0.080867901 0.038339, + -0.0220857 -0.078689598 0.038982999, + -0.0248404 -0.076367699 0.039377, + -0.027557701 -0.073918998 0.039515998, + -0.0302257 -0.071360901 0.039395999, + -0.0328326 -0.068711303 0.039014, + -0.035366699 -0.0659898 0.038371999, + -0.0378174 -0.063217498 0.037475999, + -0.040174201 -0.060415499 0.036334001, + -0.0424264 -0.057604101 0.034956001, + -0.044564299 -0.054803699 0.033353999, + -0.0465803 -0.052034602 0.031544998, + -0.048467699 -0.049316101 0.029548001, + -0.050219599 -0.046665099 0.027380001, + -0.051830001 -0.0440946 0.025064999, + -0.0532961 -0.0416153 0.022624999, + -0.0532961 -0.0430874 0.022042001, + -0.051830001 -0.045621298 0.024417, + -0.050219599 -0.048243199 0.026660999, + -0.048467699 -0.0509407 0.028749, + -0.0465803 -0.053697702 0.030664001, + -0.044564299 -0.056495801 0.032386001, + -0.0424264 -0.059315201 0.033897001, + -0.040174201 -0.062134799 0.035181999, + -0.0378174 -0.064934701 0.036230002, + -0.035366699 -0.067694098 0.037032999, + -0.0328326 -0.0703917 0.037581999, + -0.0302257 -0.073006302 0.037873, + -0.027557701 -0.075519599 0.037907001, + -0.0248404 -0.077913903 0.037686002, + -0.0220857 -0.080171898 0.037216, + -0.019305199 -0.082277201 0.036502, + -0.0165099 -0.0842181 0.035556, + -0.0137106 -0.085984103 0.034389999, + -0.0109179 -0.087565899 0.033018, + -0.0081421202 -0.088955604 0.031454999, + -0.0053918599 -0.090149999 0.029715, + -0.00267513 -0.091147602 0.027814999, + 0 -0.091948099 0.025769001, + 0.00267513 -0.091148503 0.027814999, + 0.0053918599 -0.090152003 0.029716, + 0.0081421202 -0.088959098 0.031456999, + 0.0109179 -0.087571003 0.033020999, + 0.0137106 -0.085990697 0.034394, + 0.0165099 -0.084225997 0.035560999, + 0.019305199 -0.082286298 0.036509, + 0.0220857 -0.080181703 0.037225001, + 0.0248404 -0.077924199 0.037696999, + 0.027557701 -0.075530097 0.037919, + 0.0302257 -0.073016703 0.037887, + 0.0328326 -0.070401698 0.037597999, + 0.035366699 -0.067703404 0.037050001, + 0.0378174 -0.064943202 0.036249001, + 0.040174201 -0.062142398 0.035202999, + 0.0424264 -0.059321702 0.033918999, + 0.044564299 -0.056501199 0.032409001, + 0.0465803 -0.053701699 0.030688001, + 0.048467699 -0.050942801 0.028774001, + 0.050219599 -0.048242599 0.026684999, + 0.051830001 -0.045617498 0.024442, + 0.0532961 -0.0430816 0.022066001, + 0.0532961 -0.0445491 0.02141, + 0.051830001 -0.0471389 0.023716001, + 0.050219599 -0.049811698 0.025883, + 0.048467699 -0.052551799 0.027891001, + 0.0465803 -0.055341799 0.029720001, + 0.044564299 -0.058162801 0.031351998, + 0.0424264 -0.0609948 0.032770999, + 0.040174201 -0.063816801 0.033962999, + 0.0378174 -0.066608198 0.034917001, + 0.035366699 -0.069348097 0.035626002, + 0.0328326 -0.072015204 0.036084, + 0.0302257 -0.074588999 0.036286999, + 0.027557701 -0.077051498 0.036237001, + 0.0248404 -0.079385199 0.035937998, + 0.0220857 -0.081573002 0.035395, + 0.019305199 -0.083600797 0.034616001, + 0.0165099 -0.085457399 0.033613, + 0.0137106 -0.087132901 0.032398, + 0.0109179 -0.088618703 0.030987, + 0.0081421202 -0.089909799 0.029391, + 0.0053918599 -0.091003999 0.027626, + 0.00267513 -0.091900401 0.025708999, + 0 -0.092598498 0.023655999, + -0.00267513 -0.0918997 0.025707999, + -0.0053918599 -0.0910023 0.027626, + -0.0081421202 -0.0899067 0.02939, + -0.0109179 -0.088614002 0.030985, + -0.0137106 -0.087126501 0.032395002, + -0.0165099 -0.085449502 0.033608001, + -0.019305199 -0.083591603 0.03461, + -0.0220857 -0.081562698 0.035386998, + -0.0248404 -0.079374097 0.035928, + -0.027557701 -0.077040099 0.036224999, + -0.0302257 -0.074577503 0.036272999, + -0.0328326 -0.072003901 0.036068, + -0.035366699 -0.069337398 0.035608999, + -0.0378174 -0.066598199 0.034898002, + -0.040174201 -0.063807704 0.033941999, + -0.0424264 -0.060986798 0.032749001, + -0.044564299 -0.058155999 0.031328999, + -0.0465803 -0.0553362 0.029696001, + -0.048467699 -0.0525476 0.027866, + -0.050219599 -0.049809501 0.025858, + -0.051830001 -0.047139499 0.023691, + -0.0532961 -0.044553 0.021384001, + -0.0532961 -0.053002801 0.015830999, + -0.051830001 -0.055792902 0.017671, + -0.050219599 -0.0586165 0.019352, + -0.048467699 -0.061454002 0.020857001, + -0.0465803 -0.064284801 0.022173, + -0.044564299 -0.067088701 0.023288, + -0.0424264 -0.069844499 0.024193, + -0.040174201 -0.072530702 0.024878999, + -0.0378174 -0.075127102 0.025343999, + -0.035366699 -0.077615499 0.025584999, + -0.0328326 -0.079977699 0.025603, + -0.0302257 -0.082196198 0.0254, + -0.027557701 -0.084256597 0.024983, + -0.0248404 -0.086147301 0.024358001, + -0.0220857 -0.087858103 0.023531999, + -0.019305199 -0.089379899 0.022514001, + -0.0165099 -0.090706304 0.021319, + -0.0137106 -0.091830902 0.019974999, + -0.0109179 -0.0927568 0.018475, + -0.0081421202 -0.093519002 0.016714999, + -0.0053918599 -0.094455101 0.01252, + -0.00267513 -0.0951396 0.0081460001, + 0 -0.095558703 0.0036200001, + 0.00267513 -0.095140398 0.0081470003, + 0.0053918599 -0.094456702 0.012523, + 0.0081421202 -0.093520597 0.016718, + 0.0109179 -0.092758603 0.018475, + 0.0137106 -0.091833197 0.019974001, + 0.0165099 -0.090709701 0.021319, + 0.019305199 -0.089384899 0.022515001, + 0.0220857 -0.087865204 0.023534, + 0.0248404 -0.086156704 0.024362, + 0.027557701 -0.084268399 0.024987999, + 0.0302257 -0.082210198 0.025408, + 0.0328326 -0.079993501 0.025612, + 0.035366699 -0.077632502 0.025596, + 0.0378174 -0.075144798 0.025357001, + 0.040174201 -0.072548501 0.024894999, + 0.0424264 -0.069862098 0.024211001, + 0.044564299 -0.067105599 0.023308, + 0.0465803 -0.064300798 0.022195, + 0.048467699 -0.061468702 0.020880001, + 0.050219599 -0.0586298 0.019377001, + 0.051830001 -0.055804599 0.017697999, + 0.0532961 -0.053012799 0.015859, + 0.0546159 -0.050273001 0.013877, + 0.0546159 -0.048957299 0.014914, + 0.0532961 -0.0516712 0.016974, + 0.051830001 -0.054445099 0.018894, + 0.050219599 -0.057261299 0.020655001, + 0.048467699 -0.0601006 0.022242, + 0.0465803 -0.062942803 0.023638999, + 0.044564299 -0.065766796 0.024834, + 0.0424264 -0.068551801 0.025815999, + 0.040174201 -0.071276203 0.026575999, + 0.0378174 -0.0739199 0.027109999, + 0.035366699 -0.076462701 0.027415, + 0.0328326 -0.078886203 0.027491, + 0.0302257 -0.0811726 0.027339, + 0.027557701 -0.083306901 0.026965, + 0.0248404 -0.085275501 0.026377, + 0.0220857 -0.087067403 0.025582001, + 0.019305199 -0.088673398 0.024588, + 0.0165099 -0.090087399 0.023406999, + 0.0137106 -0.091304198 0.022054, + 0.0109179 -0.092317902 0.020559, + 0.0081421202 -0.093132503 0.018916, + 0.0053918599 -0.093784899 0.017021, + 0.00267513 -0.094615102 0.012696, + 0 -0.095192999 0.0082019996, + -0.00267513 -0.094614401 0.012695, + -0.0053918599 -0.093783803 0.01702, + -0.0081421202 -0.093131199 0.018914999, + -0.0109179 -0.092316099 0.02056, + -0.0137106 -0.091301396 0.022054, + -0.0165099 -0.0900831 0.023406001, + -0.019305199 -0.088667199 0.024586, + -0.0220857 -0.087058999 0.025579, + -0.0248404 -0.085264802 0.026372001, + -0.027557701 -0.083294101 0.026958, + -0.0302257 -0.081158102 0.02733, + -0.0328326 -0.078870401 0.027480001, + -0.035366699 -0.076446198 0.027402001, + -0.0378174 -0.073903099 0.027094999, + -0.040174201 -0.071259603 0.026559001, + -0.0424264 -0.068535604 0.025797, + -0.044564299 -0.0657515 0.024813, + -0.0465803 -0.062928602 0.023615999, + -0.048467699 -0.060087699 0.022217, + -0.050219599 -0.057250001 0.020629, + -0.051830001 -0.054435398 0.018866999, + -0.0532961 -0.051663 0.016946999, + -0.051830001 -0.053036101 0.019988, + -0.050219599 -0.055835199 0.021833001, + -0.048467699 -0.058666501 0.023505, + -0.0465803 -0.0615105 0.024989, + -0.044564299 -0.064346597 0.02627, + -0.0424264 -0.067153201 0.027336, + -0.040174201 -0.069909103 0.028178001, + -0.0378174 -0.072594099 0.028790999, + -0.035366699 -0.075188003 0.029170001, + -0.0328326 -0.077670701 0.029313, + -0.0302257 -0.080023997 0.029222, + -0.027557701 -0.082232803 0.028902, + -0.0248404 -0.084282599 0.028361, + -0.0220857 -0.0861599 0.027605001, + -0.019305199 -0.0878544 0.026643001, + -0.0165099 -0.089359403 0.025487, + -0.0137106 -0.090669498 0.024149001, + -0.0109179 -0.091779999 0.022646001, + -0.0081421202 -0.092685699 0.021005001, + -0.0053918599 -0.093392797 0.019223001, + -0.00267513 -0.093939297 0.017199, + 0 -0.0946666 0.012752, + 0.00267513 -0.0939399 0.017200001, + 0.0053918599 -0.093393698 0.019223999, + 0.0081421202 -0.0926871 0.021005001, + 0.0109179 -0.091782302 0.022646001, + 0.0137106 -0.090673096 0.024150001, + 0.0165099 -0.0893647 0.025489001, + 0.019305199 -0.087861702 0.026645999, + 0.0220857 -0.086169302 0.027609, + 0.0248404 -0.084294103 0.028367, + 0.027557701 -0.082245998 0.02891, + 0.0302257 -0.0800386 0.029231999, + 0.0328326 -0.077685997 0.029324999, + 0.035366699 -0.075203702 0.029184001, + 0.0378174 -0.072609797 0.028806999, + 0.040174201 -0.069924399 0.028196, + 0.0424264 -0.067167804 0.027356001, + 0.044564299 -0.064360201 0.026292, + 0.0465803 -0.061522901 0.025012, + 0.048467699 -0.058677401 0.023530001, + 0.050219599 -0.055844601 0.021859, + 0.051830001 -0.053043999 0.020014999, + 0.0532961 -0.050294202 0.018014999, + 0.0546159 -0.0476126 0.015877999, + 0.0532961 -0.048887599 0.018979, + 0.051830001 -0.0516068 0.021059001, + 0.050219599 -0.054385401 0.022986, + 0.048467699 -0.057204999 0.024741, + 0.0465803 -0.060046799 0.026310001, + 0.044564299 -0.062890597 0.027675999, + 0.0424264 -0.065714799 0.028827, + 0.040174201 -0.068497598 0.029751001, + 0.0378174 -0.071218804 0.030440999, + 0.035366699 -0.073858202 0.030895, + 0.0328326 -0.076395303 0.031107999, + 0.0302257 -0.078810401 0.031081, + 0.027557701 -0.081087597 0.030817, + 0.0248404 -0.083212197 0.030324999, + 0.0220857 -0.085170202 0.029611001, + 0.019305199 -0.086948998 0.028684, + 0.0165099 -0.088541098 0.027557001, + 0.0137106 -0.089941002 0.026240001, + 0.0109179 -0.0911441 0.024747999, + 0.0081421202 -0.092146397 0.023096001, + 0.0053918599 -0.092945002 0.021317, + 0.00267513 -0.093546897 0.019404, + 0 -0.093990304 0.017256999, + -0.00267513 -0.093546398 0.019404, + -0.0053918599 -0.0929441 0.021317, + -0.0081421202 -0.092144802 0.023096001, + -0.0109179 -0.091141298 0.024746999, + -0.0137106 -0.089936599 0.026239, + -0.0165099 -0.088534802 0.027554, + -0.019305199 -0.086940698 0.02868, + -0.0220857 -0.085160002 0.029606, + -0.0248404 -0.083200298 0.030317999, + -0.027557701 -0.081074297 0.030809, + -0.0302257 -0.078796297 0.03107, + -0.0328326 -0.0763807 0.031095, + -0.035366699 -0.073843502 0.03088, + -0.0378174 -0.071204402 0.030424001, + -0.040174201 -0.0684838 0.029732, + -0.0424264 -0.065701902 0.028805999, + -0.044564299 -0.062878802 0.027654, + -0.0465803 -0.060036302 0.026286, + -0.048467699 -0.057195898 0.024715999, + -0.050219599 -0.054377701 0.02296, + -0.051830001 -0.051600602 0.021032, + -0.0532961 -0.048883099 0.018952001, + -0.051830001 -0.050135098 0.021996999, + -0.050219599 -0.052883301 0.024007, + -0.048467699 -0.055681899 0.025849, + -0.0465803 -0.058511902 0.027504999, + -0.044564299 -0.061353602 0.028960001, + -0.0424264 -0.064186402 0.030200999, + -0.040174201 -0.066988401 0.031213, + -0.0378174 -0.069738597 0.031991001, + -0.035366699 -0.072416998 0.032527, + -0.0328326 -0.075003304 0.032818999, + -0.0302257 -0.077477202 0.032866001, + -0.027557701 -0.079821102 0.032669, + -0.0248404 -0.082019903 0.032237001, + -0.0220857 -0.084059201 0.031574, + -0.019305199 -0.085925497 0.030692, + -0.0165099 -0.087608702 0.029601, + -0.0137106 -0.089102298 0.028314, + -0.0109179 -0.090401001 0.026843, + -0.0081421202 -0.0915007 0.025203001, + -0.0053918599 -0.092399701 0.023411, + -0.00267513 -0.093095899 0.021499, + 0 -0.093596801 0.019463001, + 0.00267513 -0.093096301 0.021499, + 0.0053918599 -0.092400797 0.023411, + 0.0081421202 -0.091502897 0.025203001, + 0.0109179 -0.090404503 0.026845001, + 0.0137106 -0.089107499 0.028316, + 0.0165099 -0.087615803 0.029603999, + 0.019305199 -0.085934401 0.030696001, + 0.0220857 -0.084069803 0.031580999, + 0.0248404 -0.082031801 0.032244999, + 0.027557701 -0.079833999 0.032678999, + 0.0302257 -0.077490598 0.032876998, + 0.0328326 -0.075016901 0.032832999, + 0.035366699 -0.072430499 0.032543, + 0.0378174 -0.069751598 0.032008, + 0.040174201 -0.067000598 0.031233, + 0.0424264 -0.0641976 0.030222001, + 0.044564299 -0.061363701 0.028983001, + 0.0465803 -0.0585206 0.027528999, + 0.048467699 -0.055689301 0.025874, + 0.050219599 -0.052889299 0.024033001, + 0.051830001 -0.050139502 0.022024, + 0.0532961 -0.047457401 0.019866999, + 0.0546159 -0.044858899 0.017581999, + 0.0532961 -0.046009298 0.020677, + 0.051830001 -0.048648201 0.022910001, + 0.050219599 -0.051362701 0.024999, + 0.048467699 -0.054136101 0.026923999, + 0.0465803 -0.056950301 0.028666999, + 0.044564299 -0.059785798 0.03021, + 0.0424264 -0.062622197 0.031537998, + 0.040174201 -0.0654383 0.032637998, + 0.0378174 -0.068213098 0.033502001, + 0.035366699 -0.070925497 0.034122001, + 0.0328326 -0.073555201 0.034494001, + 0.0302257 -0.076081902 0.034614999, + 0.027557701 -0.078487702 0.034488, + 0.0248404 -0.080755301 0.034118, + 0.0220857 -0.082869902 0.033511002, + 0.019305199 -0.0848177 0.032676, + 0.0165099 -0.086588003 0.031624001, + 0.0137106 -0.088171698 0.030370001, + 0.0109179 -0.0895629 0.028926, + 0.0081421202 -0.0907574 0.027305, + 0.0053918599 -0.091753401 0.025521999, + 0.00267513 -0.092550002 0.023596, + 0 -0.093145601 0.021559, + -0.00267513 -0.092549503 0.023596, + -0.0053918599 -0.091752 0.025521999, + -0.0081421202 -0.0907548 0.027303999, + -0.0109179 -0.089558803 0.028925, + -0.0137106 -0.088165902 0.030368, + -0.0165099 -0.086580299 0.031621002, + -0.019305199 -0.084808402 0.032669999, + -0.0220857 -0.0828593 0.033504002, + -0.0248404 -0.0807437 0.034109, + -0.027557701 -0.078475401 0.034476999, + -0.0302257 -0.0760694 0.034602001, + -0.0328326 -0.073542699 0.034479, + -0.035366699 -0.070913397 0.034104999, + -0.0378174 -0.068201602 0.033484001, + -0.040174201 -0.065427601 0.032618001, + -0.0424264 -0.062612601 0.031516001, + -0.044564299 -0.059777401 0.030187, + -0.0465803 -0.0569431 0.028643001, + -0.048467699 -0.054130301 0.026899001, + -0.050219599 -0.051358402 0.024972999, + -0.051830001 -0.048645899 0.022884, + -0.0532961 -0.046009898 0.020651, + 0.059999902 -0.0145 9.5001204e-005, + 0.059932198 -0.0145 0.002688, + 0.0599977 -0.0145 0, + 0.0268177 -0.055653598 -0.1715, + -0.0487464 -0.013126 -0.2085, + -0.047194201 -0.018514 -0.2085, + -0.0487464 -0.013126 -0.19149999, + -0.047194201 -0.018514 -0.19149999, + -0.049685601 -0.0075982199 -0.19149999, + -0.049685601 -0.0075982199 -0.2085, + -0.045048401 -0.0236942 -0.2085, + -0.045048401 -0.0236942 -0.19149999, + 0.049685601 -0.0075982199 -0.2085, + 0.050000001 -0.0020000001 -0.2085, + 0.049685601 -0.0075982199 -0.19149999, + 0.050000001 -0.0020000001 -0.19149999, + 0.0487464 -0.013126 -0.19149999, + 0.0487464 -0.013126 -0.2085, + 0.047194201 -0.018514 -0.19149999, + 0.045048401 -0.0236942 -0.19149999, + 0.047194201 -0.018514 -0.2085, + 0.045048401 -0.0236942 -0.2085, + 0.042336199 -0.0286016 -0.2085, + 0.049685601 0.0035982199 -0.2085, + 0.0487464 0.0091260504 -0.2085, + 0.047194201 0.014514 -0.2085, + 0.045048401 0.0196942 -0.2085, + 0.042336199 0.024601599 -0.2085, + 0.039091598 0.029174499 -0.2085, + 0.0353553 0.033355299 -0.2085, + 0.0311745 0.037091602 -0.2085, + 0.0266016 0.040336199 -0.2085, + 0.039091598 -0.0331745 -0.2085, + 0.0353553 -0.0373553 -0.2085, + 0.0311745 -0.041091599 -0.2085, + 0.0266016 -0.0443362 -0.2085, + 0.0216942 -0.047048401 -0.2085, + 0.016514 -0.049194202 -0.2085, + 0.011126 -0.0507464 -0.2085, + 0.00559822 -0.051685601 -0.2085, + 0 -0.052000001 -0.2085, + 0.0216942 0.0430484 -0.2085, + 0.016514 0.045194201 -0.2085, + 0.011126 0.046746399 -0.2085, + 0.00559822 0.047685601 -0.2085, + 0 0.048 -0.2085, + -0.00559822 0.047685601 -0.2085, + -0.011126 0.046746399 -0.2085, + -0.00559822 -0.051685601 -0.2085, + -0.011126 -0.0507464 -0.2085, + -0.016514 -0.049194202 -0.2085, + -0.0216942 -0.047048401 -0.2085, + -0.0266016 -0.0443362 -0.2085, + -0.0311745 -0.041091599 -0.2085, + -0.0353553 -0.0373553 -0.2085, + -0.039091598 -0.0331745 -0.2085, + -0.042336199 -0.0286016 -0.2085, + -0.016514 0.045194201 -0.2085, + -0.0216942 0.0430484 -0.2085, + -0.0266016 0.040336199 -0.2085, + -0.0311745 0.037091602 -0.2085, + -0.0353553 0.033355299 -0.2085, + -0.039091598 0.029174499 -0.2085, + -0.042336199 0.024601599 -0.2085, + -0.045048401 0.0196942 -0.2085, + -0.047194201 0.014514 -0.2085, + -0.0487464 0.0091260504 -0.2085, + -0.049685601 0.0035982199 -0.2085, + -0.050000001 -0.0020000001 -0.2085, + 0.042336199 -0.0286016 -0.19149999, + 0.047194201 0.014514 -0.19149999, + 0.0487464 0.0091260504 -0.19149999, + 0.045048401 0.0196942 -0.19149999, + -0.047194201 0.014514 -0.19149999, + -0.045048401 0.0196942 -0.19149999, + -0.0487464 0.0091260504 -0.19149999, + -0.0311745 0.037091602 -0.19149999, + -0.0353553 0.033355299 -0.19149999, + -0.0266016 0.040336199 -0.19149999, + 0.016514 0.045194201 -0.19149999, + 0.011126 0.046746399 -0.19149999, + 0.0216942 0.0430484 -0.19149999, + -0.039091598 0.029174499 -0.19149999, + -0.042336199 0.024601599 -0.19149999, + -0.0216942 0.0430484 -0.19149999, + -0.016514 0.045194201 -0.19149999, + -0.011126 0.046746399 -0.19149999, + 0.00559822 0.047685601 -0.19149999, + 0.0266016 0.040336199 -0.19149999, + 0.0311745 0.037091602 -0.19149999, + 0 -0.052000001 -0.19149999, + -0.00559822 -0.051685601 -0.19149999, + 0.00559822 -0.051685601 -0.19149999, + 0.0353553 -0.0373553 -0.19149999, + 0.039091598 -0.0331745 -0.19149999, + 0.0311745 -0.041091599 -0.19149999, + -0.0266016 -0.0443362 -0.19149999, + -0.0216942 -0.047048401 -0.19149999, + -0.0311745 -0.041091599 -0.19149999, + 0.0266016 -0.0443362 -0.19149999, + 0.0216942 -0.047048401 -0.19149999, + 0.016514 -0.049194202 -0.19149999, + 0.011126 -0.0507464 -0.19149999, + -0.011126 -0.0507464 -0.19149999, + -0.016514 -0.049194202 -0.19149999, + -0.0353553 -0.0373553 -0.19149999, + 0.0353553 0.033355299 -0.19149999, + 0.039091598 0.029174499 -0.19149999, + 0.042336199 0.024601599 -0.19149999, + -0.049685601 0.0035982199 -0.19149999, + -0.050000001 -0.0020000001 -0.19149999, + 0.049685601 0.0035982199 -0.19149999, + -0.039091598 -0.0331745 -0.19149999, + -0.042336199 -0.0286016 -0.19149999, + -0.00559822 0.047685601 -0.19149999, + 0 0.048 -0.19149999, + 0.0053910101 -0.0617458 -0.1715 ] + + } + normal + Normal { + vector [ -0.99705648 0.00053005322 -0.076669641, + -0.92888403 -0.195234 0.314735, + -0.94178826 -0.17722504 0.28570306, + -0.92923725 -0.22229806 0.29513007, + -0.942038 -0.201856 0.26798999, + -0.94362974 -0.18088596 0.27720594, + -0.95513576 -0.16184996 0.24803294, + -0.95614535 -0.14428304 0.2548891, + -0.96619612 -0.12700002 0.22435702, + -0.96681535 -0.11258504 0.22933109, + -0.9755041 -0.096942715 0.19746903, + -0.97583914 -0.086536109 0.20062304, + -0.98326802 -0.072149001 0.16726799, + -0.98346913 -0.063758709 0.16948001, + -0.98964274 -0.050546188 0.13435897, + -0.98961854 -0.051685773 0.13410294, + -0.99412709 -0.038919304 0.10097902, + -0.99402553 -0.042777482 0.10041595, + -0.99757349 -0.027286412 0.064052232, + -0.99754924 -0.028304407 0.063988514, + -0.99972463 -0.0094924662 0.021459892, + -0.99972826 -0.0090691121 0.021477006, + -0.99971938 0.0092145847 -0.021821586, + -0.99973899 0.0065689902 -0.0218834, + -0.99754524 0.020132806 -0.067068815, + -0.99355346 -0.0097954944 -0.11294105, + -0.99344897 0.018463001 -0.112775, + -0.99768043 0.010997893 -0.067176864, + -0.99322379 -0.039045993 0.10946197, + -0.99752003 -0.023646999 0.066292197, + -0.99763763 -0.017445493 0.066444375, + -0.99973834 -0.0058099818 0.022128407, + -0.99974924 -0.0032618106 0.022156306, + -0.99974811 0.0032692405 -0.022206701, + -0.99972254 -0.007683346 -0.022265989, + -0.99957663 0.0018354394 -0.029036088, + -0.99957865 0.0017990193 -0.028968388, + -0.99950677 0.012131897 -0.028966293, + -0.99950475 0.012133697 -0.029033992, + -0.99768764 -0.0082370071 -0.067465276, + -0.99767411 0.010420301 -0.06736321, + -0.99974865 0.0034270289 -0.022154493, + -0.99973589 0.0062232693 -0.022123897, + -0.99974149 -0.0061560073 0.021884689, + -0.99972564 -0.0084946668 0.021829993, + -0.99754852 -0.02537719 0.065215468, + -0.99753213 -0.026086403 0.065185808, + -0.99329686 -0.042946596 0.10731699, + -0.9933601 -0.041156005 0.10743301, + -0.98834014 -0.054469209 0.14218602, + -0.98849964 -0.049358781 0.14294095, + -0.98267937 -0.060485922 0.17516506, + -0.98270702 -0.059149802 0.175466, + -0.97505379 -0.070905186 0.21033895, + -0.97481948 -0.081732839 0.20747711, + -0.96593463 -0.094850764 0.24077691, + -0.96553767 -0.10809996 0.23675191, + -0.95530653 -0.12278394 0.26891187, + -0.95459163 -0.14013895 0.26289892, + -0.94295079 -0.15660995 0.29379794, + 0.88450527 -0.13444504 0.44673815, + 0.86122233 -0.14646205 0.48666719, + 0.86087328 -0.11658005 0.49528417, + 0.832753 -0.12684999 0.53891701, + 0.83170485 -0.094851382 0.54705596, + 0.80056316 -0.10237302 0.59043914, + 0.7981782 -0.060931314 0.59933209, + 0.76085365 -0.065634668 0.64559573, + 0.75983191 -0.049896892 0.64820194, + 0.71223181 -0.053874489 0.69987381, + 0.71199 -0.047043201 0.70061201, + 0.66059595 -0.050295994 0.74905497, + 0.66058892 -0.052200094 0.74893093, + 0.69138604 -0.050235007 0.72073704, + 0.69158673 -0.040077586 0.72118074, + 0.72601718 -0.011334803 0.68758321, + 0.72567976 -0.038176585 0.68697274, + 0.79291433 -0.012436706 0.60920632, + 0.79237115 -0.044060912 0.60844612, + 0.82299829 -0.021515407 0.56763619, + 0.82242399 -0.046503998 0.566971, + 0.79450732 -0.049641419 0.60522223, + 0.79400355 -0.064358965 0.60449666, + 0.76845717 -0.067745514 0.63630515, + 0.76863998 -0.057810798 0.63706398, + 0.73468995 -0.061310291 0.67562693, + 0.73466492 -0.062954791 0.67550296, + 0.7620855 -0.060082462 0.64468265, + 0.76247817 -0.046731412 0.64532417, + 0.76059049 -0.018166889 0.64897764, + 0.7601921 -0.041243404 0.64838809, + 0.72808319 -0.043515511 0.68410617, + 0.72779518 -0.055289514 0.68356216, + 0.69854593 -0.057689693 0.71323591, + 0.69856304 -0.055830408 0.71336704, + 0.74785417 -0.05179771 0.66183919, + 0.74806416 -0.058981616 0.66100019, + 0.79238373 -0.05421738 0.60760874, + 0.79328728 -0.070008121 0.60480922, + 0.82761955 -0.064539559 0.55756664, + 0.82955348 -0.10443806 0.54857427, + 0.8581059 -0.096030787 0.50441295, + 0.85881591 -0.12612699 0.49651495, + 0.88436359 -0.11492795 0.4524298, + 0.98660201 -0.0274259 0.160824, + 0.99347526 -0.019172203 0.11242503, + 0.99356139 -0.013425005 0.11249704, + 0.99228913 0.00031964504 0.12394501, + 0.99227822 0.00031426709 0.12403203, + 0.99227649 0.001865531 0.12403206, + 0.99228734 0.0018848306 0.12394504, + 0.94908625 -0.0052935514 0.3149721, + 0.94906998 -0.00529576 0.31502101, + 0.94906598 0.0060096402 0.31501999, + 0.94908249 0.0060301726 0.31497014, + 0.96334773 -0.0023932396 0.26824495, + 0.95252979 0.014874596 0.30408195, + -0.9929145 0.032826684 -0.11420695, + -0.98640901 0.045389701 -0.157915, + -0.98699087 0.028725896 -0.15818898, + -0.97804666 0.037232384 -0.20503293, + -0.97866952 -0.0045414176 -0.2053909, + -0.94156533 -0.24319609 0.23304608, + -0.92709363 -0.27063191 0.25933692, + -0.92582136 -0.27982908 0.25406808, + -0.90950614 -0.30776203 0.27943003, + -0.90778869 -0.31858188 0.27280992, + -0.88933599 -0.347314 0.29741299, + -0.88712221 -0.35951808 0.28941506, + -0.86630386 -0.38910493 0.31323296, + -0.86348712 -0.40274906 0.30361703, + -0.84049511 -0.43265206 0.32616004, + -0.83699656 -0.44760379 0.31478184, + -0.81174117 -0.47771311 0.3359561, + -0.80740303 -0.494109 0.32242301, + -0.7795428 -0.5245499 0.34228691, + -0.77441502 -0.54172999 0.32681799, + -0.74375325 -0.5723632 0.34529912, + -0.73780864 -0.59008372 0.32777986, + -0.70480824 -0.62014526 0.34447813, + -0.69796693 -0.63834995 0.32457897, + -0.66274208 -0.66751409 0.33940804, + -0.65496993 -0.68599892 0.31689098, + -0.61717838 -0.71429443 0.32996121, + -0.6087209 -0.7323128 0.30524895, + -0.56866801 -0.75924897 0.316477, + -0.55947506 -0.77679813 0.28908902, + -0.51785988 -0.80174482 0.29837295, + -0.50828606 -0.81813115 0.26889902, + -0.46537581 -0.84085971 0.2763699, + -0.45553884 -0.8559497 0.24461091, + -0.4116469 -0.87626374 0.25041693, + -0.40193093 -0.88958687 0.21699497, + -0.35716796 -0.90743387 0.22134797, + -0.34779492 -0.91887176 0.18631496, + -0.30316493 -0.93393278 0.18936895, + -0.29606897 -0.9417069 0.15978499, + -0.25183192 -0.95413363 0.16189393, + -0.24697299 -0.95907903 0.13846201, + -0.20437789 -0.96884751 0.13987194, + -0.19919696 -0.97384089 0.10933599, + -0.15638506 -0.98152936 0.11019903, + -0.15198593 -0.98539054 0.076848663, + -0.10955202 -0.9909721 0.077284008, + -0.10630196 -0.99340767 0.042908184, + -0.064430676 -0.99699265 0.043062985, + -0.062448323 -0.99801534 0.0081057027, + -0.021154007 -0.99974334 0.0081197331, + -0.020484902 -0.99941713 -0.027308803, + 0.020225709 -0.99942249 -0.027308913, + 0.020894198 -0.99974889 0.0080965394, + 0.062156778 -0.99803364 0.0080826469, + 0.064150803 -0.99701297 0.043009799, + 0.10597499 -0.99344486 0.042855896, + 0.109228 -0.99101001 0.0772551, + 0.15163203 -0.98544723 0.076821417, + 0.15603901 -0.98158211 0.11022002, + 0.19892408 -0.97389436 0.10935704, + 0.20415197 -0.96884388 0.14022699, + 0.24680494 -0.95907176 0.13881198, + 0.25170499 -0.95406598 0.162489, + 0.29608595 -0.94160277 0.16036595, + 0.30305493 -0.93395776 0.18942195, + 0.34766111 -0.91891134 0.18637006, + 0.35693917 -0.9076004 0.22103411, + 0.40167499 -0.88977599 0.216693, + 0.41130692 -0.87660176 0.24979194, + 0.45519212 -0.8563062 0.24400806, + 0.46501395 -0.84128886 0.27567196, + 0.50777203 -0.81866097 0.26825699, + 0.51736283 -0.8022967 0.29775089, + 0.55896902 -0.77737999 0.28850299, + 0.56813914 -0.75993317 0.3157841, + 0.60826379 -0.73297077 0.30457988, + 0.61683404 -0.71477407 0.32956603, + 0.65456659 -0.68654156 0.31654882, + 0.66236216 -0.66804618 0.3391031, + 0.69766617 -0.63883317 0.32427508, + 0.70456696 -0.62051493 0.34430596, + 0.73752856 -0.59050363 0.3276538, + 0.74355882 -0.57254887 0.3454099, + 0.77425301 -0.54189998 0.32692, + 0.77941018 -0.52462614 0.34247208, + 0.80729467 -0.49417475 0.32259384, + 0.81160682 -0.4778809 0.3360419, + 0.83693409 -0.44769606 0.31481704, + 0.84047586 -0.43256193 0.32632896, + 0.86344081 -0.40270591 0.30380595, + 0.86623615 -0.38915908 0.31335309, + 0.88706499 -0.35956901 0.289527, + 0.88930327 -0.3472231 0.29761705, + 0.90780258 -0.31843185 0.27293888, + 0.90951675 -0.30761993 0.27955195, + 0.92583477 -0.27969095 0.25417095, + 0.92712474 -0.27034894 0.25952095, + 0.94156963 -0.24298291 0.23325092, + 0.94247866 -0.23538591 0.23733391, + 0.9560591 -0.20644903 0.20815803, + 0.99734336 0.011587304 -0.071917422, + 0.99772638 0.0043849214 -0.06725172, + 0.99762887 0.015178299 -0.067127995, + 0.99974477 0.0049822885 -0.022034794, + 0.99973273 0.0071096183 -0.021999195, + 0.99973577 -0.0070683383 0.021871494, + 0.99972123 -0.0090089515 0.021826105, + 0.99751288 -0.026892297 0.065152094, + 0.99752522 -0.026379406 0.065173618, + 0.96621627 -0.12661803 0.22448605, + 0.96682137 -0.11243804 0.22937809, + 0.97550899 -0.096815802 0.19750699, + 0.97585154 -0.086067453 0.20076391, + 0.98327833 -0.071754426 0.16737705, + 0.98348725 -0.062760815 0.16974704, + 0.98965263 -0.049758483 0.13457996, + 0.98961174 -0.051734887 0.13413496, + 0.99413002 -0.0389334 0.100944, + 0.99402511 -0.042910505 0.10036401, + 0.9975729 -0.027373297 0.064023696, + 0.99754113 -0.028691404 0.063941211, + 0.99972349 -0.0096271047 0.021454809, + 0.99972373 -0.0095995478 0.021455895, + 0.99971461 0.0097572459 -0.021808393, + 0.99973261 0.0075382474 -0.021860393, + 0.99750578 0.023010693 -0.066729486, + 0.99763399 0.0160309 -0.066854, + 0.99330199 0.026943101 -0.112362, + 0.98525155 0.025115589 -0.16925892, + 0.98730111 0.011780002 -0.15842302, + 0.98660547 0.040571719 -0.15799907, + 0.99331462 0.028711189 -0.11181096, + 0.99290478 0.04116869 -0.11155797, + 0.99750179 0.024457095 -0.066273086, + 0.99729788 0.032093495 -0.06608209, + 0.99971652 0.010400395 -0.021414891, + 0.99971414 0.010652301 -0.021404702, + 0.99972433 -0.010462103 0.021022407, + 0.99972838 -0.010001103 0.021050608, + 0.99782234 -0.028305009 0.059577323, + 0.99786913 -0.025769103 0.059943207, + 0.99471325 -0.040557612 0.094343819, + 0.9947415 -0.039050519 0.094681345, + 0.99010855 -0.053495675 0.12970494, + 0.98995239 -0.060204264 0.12794392, + 0.98395324 -0.075968511 0.16144605, + 0.98368913 -0.084157206 0.15897602, + 0.97644126 -0.10095602 0.19071004, + 0.97595626 -0.11226903 0.18682905, + 0.96739602 -0.13045201 0.217088, + 0.96656066 -0.14517896 0.21138492, + 0.96655524 -0.16341305 0.19765404, + 0.96763742 -0.14831191 0.20415989, + 0.97614563 -0.12760696 0.17565894, + 0.97679549 -0.11570105 0.18023309, + 0.98394275 -0.096420579 0.15019897, + 0.98430037 -0.087704532 0.15316907, + 0.99018312 -0.069455408 0.12129901, + 0.99035686 -0.063709289 0.12302198, + 0.99487448 -0.046500523 0.089791842, + 0.99497014 -0.041874506 0.091000006, + 0.99809986 -0.025757097 0.055974294, + 0.99808663 -0.026721992 0.055759281, + 0.99976325 -0.0094045922 0.019624006, + 0.99975687 -0.010300899 0.019495599, + 0.99971837 0.011087203 -0.020983808, + 0.99971366 0.011556596 -0.020955093, + 0.99725986 0.035725497 -0.064779595, + 0.99730951 0.034187384 -0.064844869, + 0.99218702 0.0581843 -0.110361, + 0.99288315 0.043724302 -0.11077601, + 0.98569751 0.061872769 -0.15675493, + 0.98662078 0.043168887 -0.15721296, + 0.97735733 0.056027818 -0.20404308, + 0.97841638 0.029302811 -0.20455508, + 0.9635669 0.037793096 -0.26478398, + 0.96770865 0.013325496 -0.25171891, + 0.96719688 0.036022097 -0.25146097, + -0.93496233 -0.076111533 0.34648612, + -0.94558823 -0.069807716 0.31778908, + -0.94536376 -0.078102484 0.31652391, + -0.9553861 -0.070758104 0.28675902, + -0.95528334 -0.072729424 0.2866081, + -0.96673155 -0.062915869 0.24793488, + -0.96742314 -0.048652206 0.24844603, + -0.97806036 -0.040034514 0.20443907, + -0.97853249 -0.023807412 0.20471311, + -0.98715276 -0.018457396 0.15870996, + -0.99240863 0.012700995 0.12232696, + -0.99240953 0.012701194 0.12231894, + -0.98718786 -0.016297998 0.15872799, + -0.98519325 0.013741104 0.17089604, + -0.98519713 0.013741402 0.17087401, + -0.98528433 0.0034416511 0.17088906, + -0.98528051 0.0034354883 0.17091092, + -0.93299925 0.013397103 0.35962909, + -0.93294501 0.017176401 0.35960901, + -0.94947189 0.013559098 0.31355897, + -0.94955498 -0.0030289099 0.313586, + -0.94955897 -0.0030318401 0.31357399, + -0.94947588 0.013559198 0.31354696, + -0.93850964 -0.020818392 0.34462488, + -0.93830788 -0.029966395 0.34449998, + -0.92017615 -0.033927005 0.39003205, + -0.91943502 -0.054134101 0.389498, + -0.9000411 -0.059993509 0.43165606, + -0.89950198 -0.070776202 0.431146, + -0.88098824 -0.076643817 0.46688911, + -0.88118476 -0.071787886 0.46728989, + -0.86623579 -0.075866789 0.49384189, + -0.86623782 -0.075477585 0.49389789, + -0.89748478 -0.066627085 0.4359839, + -0.96760511 -0.020276602 0.25165302, + -0.96749437 -0.025585309 0.25159508, + -0.95428425 -0.030240007 0.29736707, + -0.95361549 -0.049366821 0.29695216, + -0.93854421 -0.056604113 0.34048608, + -0.93785626 -0.069823414 0.33992708, + -0.92276078 -0.077539384 0.37749192, + -0.92293513 -0.073975608 0.37778106, + -0.91052699 -0.079451002 0.40574399, + -0.91066498 -0.070413299 0.40710101, + -0.88973391 -0.077798896 0.44980094, + -0.88972932 -0.078190729 0.44974214, + -0.90324122 -0.073505118 0.42279109, + -0.90304929 -0.07775303 0.42244115, + -0.91984522 -0.071009018 0.38580108, + -0.92046833 -0.058961123 0.38634413, + -0.93777055 -0.052389175 0.34328085, + -0.93850213 -0.032209005 0.34376803, + -0.95411748 -0.027932713 0.29812714, + -0.95443988 -0.0056405594 0.29834998, + -0.94892925 -0.037594609 0.31324109, + -0.94959623 -0.0030289006 0.3134611, + -0.96376663 0.005559078 0.26668891, + -0.96369398 0.0134774 0.26666901, + -0.96375066 0.013479895 0.26646391, + -0.9638229 0.0056363493 0.26648396, + -0.96692222 0.014998903 0.25463006, + -0.97570378 -0.0022657195 0.21908194, + -0.97561634 0.013571405 0.21906307, + -0.975622 0.0135717 0.21903799, + -0.97570926 -0.0022731505 0.21905807, + -0.97578865 -0.0022731894 0.21870393, + -0.97531253 -0.031319886 0.21859689, + -0.97865075 -0.0094888378 0.20531096, + -0.97846478 -0.022343494 0.20520096, + -0.96759677 -0.027332094 0.25101694, + -0.96700901 -0.045378301 0.25066799, + -0.95421964 -0.053281281 0.29432288, + -0.95350355 -0.067279972 0.29377586, + -0.94024348 -0.076013438 0.33191016, + -0.94039023 -0.073151618 0.33213708, + -0.9291296 -0.079530463 0.36109981, + -0.92932063 -0.070750378 0.36243287, + -0.91744459 -0.07622806 0.39049283, + -0.91748935 -0.083636127 0.38886815, + -0.93496013 -0.074593008 0.34682202, + -0.93954855 -0.12629394 0.31827384, + -0.9972949 0.0015983097 0.073487192, + -0.99728638 0.0015803205 0.073603027, + -0.99723226 0.010535703 0.073599018, + -0.99724078 0.010537997 0.073483184, + -0.99967462 0.0069432277 0.02454629, + -0.99967825 0.006946492 0.024397405, + -0.99770147 -0.0071799732 0.067382127, + -0.99768835 -0.0088840928 0.06737192, + -0.99354339 -0.014832205 0.11247904, + -0.99333841 -0.025668886 0.11233793, + -0.98702353 -0.035769183 0.15654093, + -0.98653775 -0.04853059 0.15616697, + -0.97862113 -0.061035406 0.19640604, + -0.97864389 -0.060562793 0.19643897, + -0.97102726 -0.070404612 0.22836205, + -0.97126067 -0.06338308 0.22942391, + -0.96311003 -0.071662098 0.25939101, + -0.96312946 -0.070153929 0.25973111, + -0.95229477 -0.079577975 0.29462194, + -0.9521119 -0.095735282 0.29037496, + -0.93994439 -0.10687504 0.32416412, + -0.92372066 -0.11074597 0.36670887, + -0.93752462 -0.10058496 0.33306187, + -0.93759722 -0.08144372 0.33805108, + -0.95016253 -0.073019162 0.30308285, + -0.95015234 -0.074660733 0.30271512, + -0.95958054 -0.067392573 0.27324587, + -0.95933855 -0.075185761 0.27205989, + -0.96814251 -0.06669987 0.24135289, + -0.9680801 -0.06791921 0.24126303, + -0.977727 -0.056873798 0.20202801, + -0.97834647 -0.042891819 0.20248109, + -0.98685253 -0.033493586 0.15811493, + -0.98719275 -0.019624995 0.15831995, + -0.99352324 -0.013978303 0.11276603, + -0.99357414 -0.0093485713 0.11279701, + -0.99229538 -0.018519107 0.12250304, + -0.99246466 -0.0012952395 0.12252396, + -0.99248779 -0.0012952397 0.12233697, + -0.99248874 -0.0012983097 0.12232897, + -0.98796713 0.015594502 0.15387602, + -0.93565214 0.011166401 0.35274702, + -0.9330681 0.0080843214 0.35960904, + -0.93301463 0.013397495 0.35958889, + -0.92016274 -0.020694494 0.39098892, + -0.91992563 -0.031458188 0.39082885, + -0.89946699 -0.035060201 0.43557999, + -0.89875388 -0.054755192 0.43502095, + -0.87728626 -0.059939615 0.47621012, + -0.87684101 -0.069387503 0.47574699, + -0.8565191 -0.074487105 0.51071209, + -0.85670185 -0.069267586 0.51113987, + -0.84028518 -0.072803818 0.53723413, + -0.84028316 -0.072285816 0.53730714, + -0.87495172 -0.064560778 0.47988683, + -0.87524056 -0.07341516 0.47808376, + -0.897493 -0.066940203 0.43591899, + -0.90122002 -0.081501298 0.42562899, + -0.92050266 -0.073484771 0.38376385, + -0.92077422 -0.10418102 0.37592709, + -0.90526903 -0.11346 0.409408, + -0.87012541 -0.0036175917 0.49281725, + -0.87006783 -0.0036175891 0.49291888, + -0.84840029 -0.020026708 0.5289762, + -0.49246082 0.00012900896 0.87033468, + -0.57246596 -0.030984996 0.81934285, + -0.52928996 -0.032062497 0.84783489, + -0.48543283 -0.02707169 0.8738547, + -0.53604108 -0.026140204 0.84378713, + -0.53612679 -0.03354349 0.84347069, + -0.59317309 -0.031991303 0.80443913, + -0.59344906 -0.037809603 0.80398309, + -0.64785701 -0.035784502 0.760921, + -0.64843595 -0.042715397 0.76006991, + -0.69030178 -0.040597387 0.72238177, + -0.6924386 -0.066445462 0.71841061, + -0.73197156 -0.062748566 0.67843956, + -0.73448879 -0.099608466 0.67127079, + -0.77134371 -0.093413971 0.62952578, + -0.7730009 -0.12780999 0.62139696, + -0.80664015 -0.11907402 0.57892406, + -0.80754262 -0.15178593 0.56994373, + -0.83815271 -0.16404194 0.52018285, + -0.83791012 -0.14046201 0.52742505, + -0.8355692 -0.14995103 0.52852511, + -0.8349641 -0.11867802 0.53735507, + -0.80427402 -0.128157 0.580275, + -0.80293649 -0.094985537 0.58844763, + -0.76905727 -0.10185604 0.63101226, + -0.76691532 -0.066819623 0.63826025, + -0.72954321 -0.07121212 0.68021727, + -0.72755277 -0.045373186 0.68454975, + -0.68771106 -0.048014209 0.72439504, + -0.68712485 -0.04065679 0.72540081, + -0.63489103 -0.043234404 0.77139109, + -0.63460726 -0.036862016 0.77195531, + -0.57956111 -0.038869709 0.8140012, + -0.57954991 -0.037166294 0.81408882, + -0.6139307 -0.035999883 0.78853863, + -0.65225101 -0.0123745 0.75790203, + -0.65229601 0.0037603099 0.75795501, + -0.65368384 0.003471859 0.75675982, + -0.65363777 -0.012352095 0.75670671, + -0.65095299 -0.016896499 0.75893003, + -0.65072769 -0.035930082 0.75846064, + -0.61391497 -0.037352495 0.78848785, + -0.61110789 -0.015894696 0.7913878, + -0.61095804 -0.031923104 0.79101914, + -0.57245106 -0.033063304 0.8192721, + -0.56956881 -0.016411895 0.82177973, + -0.56948191 -0.027911793 0.82152981, + -0.52930892 -0.028809097 0.84793991, + -0.52665496 -0.015717298 0.84993386, + -0.52660584 -0.02435459 0.84976071, + -0.48543888 -0.025046794 0.8739118, + -0.45035499 0.00170622 0.89284801, + -0.4500652 0.0015523107 0.8929944, + -0.45006505 -0.0011239201 0.89299512, + -0.45035616 -0.0011227103 0.89284831, + -0.48258877 -0.014941293 0.87571961, + -0.48256719 -0.020533007 0.87561828, + -0.440512 -0.0210461 0.89749998, + -0.440512 -0.022489499 0.89746499, + -0.49176875 -0.021812588 0.87045258, + -0.49185887 -0.028365493 0.87021279, + -0.54961598 -0.0272169 0.83497399, + -0.5498842 -0.032683112 0.83460128, + -0.60612971 -0.031122785 0.79475665, + -0.60670322 -0.037820216 0.79402828, + -0.65095592 -0.036116295 0.7582559, + -0.65316021 -0.061559822 0.7547133, + -0.69494897 -0.058457401 0.71667898, + -0.6977638 -0.096340477 0.70981979, + -0.73707217 -0.090891719 0.66967416, + -0.73907608 -0.12714401 0.66151404, + -0.77545911 -0.11917402 0.62004906, + -0.77666914 -0.15361002 0.61089206, + -0.80989683 -0.14304197 0.56886387, + -0.81036729 -0.17621806 0.55879515, + 0.073566914 0.99729025 -0.0003941771, + 0.073563367 0.99724162 0.009883496, + 0.073505782 0.99724579 0.0098835574, + 0.07350944 0.99729449 -0.00039641417, + 0.051477317 0.99866635 -0.0039680316, + -0.029028488 0.99951667 0.011128697, + -0.029030314 0.99957848 -0.00045802322, + -0.028964112 0.99958038 -0.00044912516, + -0.028962286 0.99951851 0.011128695, + -0.022412308 0.99957937 0.018407308, + -0.022379695 0.99870974 0.045584589, + 0.022010298 0.9987179 0.045584895, + 0.02204649 0.99968451 0.012033395, + 0.024543196 0.99958289 0.015218098, + -0.0028998298 0.9998799 0.015222598, + -0.0029001692 0.99999577 0, + 0.024546094 0.99969876 0, + 0.024371 0.99970299 2.3548801e-005, + 0.024369191 0.99963063 0.012032595, + 0.067253307 0.9975881 0.017179802, + 0.067156814 0.99671227 0.045328412, + 0.021880008 0.99872833 0.045420114, + 0.021813298 0.9968769 0.075898893, + -0.022360398 0.99686486 0.075897992, + -0.022431092 0.99870563 0.045649584, + -0.067482091 0.9966799 0.045556996, + -0.067576595 0.99752885 0.019227799, + -0.07665997 0.99701262 0.0094449865, + -0.076725937 0.99700749 0.0094449148, + -0.07672929 0.99705189 -0.00013069199, + -0.076663397 0.99705702 -0.000133255, + -0.051477309 0.99866623 -0.0039770207, + 0.17087506 0.98529238 -0.00086399232, + 0.17091393 0.98528564 -0.0008612817, + 0.17091 0.98526001 0.0072498, + 0.17087096 0.98526675 0.0072498983, + 0.15861894 0.98714167 0.019780893, + 0.15841506 0.98637533 0.044367116, + 0.11235099 0.99266487 0.044649996, + 0.112005 0.99085999 0.075176001, + 0.066636898 0.99491799 0.075483903, + 0.066324294 0.99214888 0.10602698, + 0.021587189 0.99410653 0.10623595, + 0.021449793 0.99037564 0.13673295, + -0.022107789 0.99036151 0.13673094, + -0.022248693 0.99409163 0.10623996, + -0.066972822 0.99210536 0.10602704, + -0.067287408 0.99485713 0.07570821, + -0.11256397 0.99077976 0.075397886, + -0.11290898 0.9925639 0.045480695, + -0.15875095 0.98628378 0.04519289, + -0.15895006 0.98703736 0.022186108, + -0.17397305 0.98475033 -0.00055474817, + -0.17396691 0.98471755 0.0081790267, + -0.17399104 0.98471326 0.0081789615, + -0.17399701 0.9847461 -0.00055304903, + -0.97325897 -0.229689 -0.00315552, + -0.032048304 0.88317209 0.46795306, + -0.040806796 0.91041487 0.41167894, + -0.044929076 0.90293658 0.4274188, + -0.047106594 0.90284586 0.42737594, + -0.050504919 0.89780432 0.43748915, + -0.049176801 0.89786398 0.437518, + -0.051718082 0.89471269 0.44363785, + -0.046687387 0.89493471 0.44374785, + -0.048646808 0.89287913 0.44766107, + -0.039254185 0.89324868 0.44784585, + -0.039758205 0.89279813 0.44869906, + -0.025157494 0.89322174 0.44891188, + -0.02404649 0.8940677 0.44728586, + -0.0042944588 0.89431769 0.44741186, + -0.0017297103 0.89596909 0.44411305, + 0.024065699 0.895711 0.44398499, + 0.027279291 0.89744073 0.44029084, + 0.059598092 0.8961789 0.43967193, + 0.062449861 0.89743948 0.43669474, + 0.10064204 0.8946293 0.43532714, + 0.10195003 0.89509231 0.43406916, + 0.14592905 0.89014828 0.43167216, + 0.14396602 0.88961011 0.43343705, + 0.19350107 0.88198429 0.42972216, + 0.186924 0.88066101 0.43531099, + 0.24114509 0.87000632 0.43004414, + 0.230378 0.86856198 0.43877801, + 0.288614 0.85458797 0.43171901, + 0.27114305 0.8533082 0.44536111, + 0.33281308 0.83598018 0.43631709, + 0.31887689 0.83580571 0.44692984, + 0.38459605 0.81401414 0.43527806, + 0.39975694 0.81289488 0.42355195, + 0.47143087 0.7821058 0.40750891, + 0.47853494 0.7807979 0.40169495, + 0.55333209 0.74068719 0.38105908, + 0.55543166 0.74006361 0.37921175, + 0.63068771 0.69064766 0.35389081, + 0.8705548 -0.49198687 -0.0091207186, + 0.87059081 -0.49200788 -4.6320391e-005, + 0.76006973 0.55999982 0.32968789, + 0.75729412 0.56173307 0.33310902, + 0.8217715 0.49012071 0.29064283, + 0.8177641 0.49333906 0.29644302, + 0.88316178 0.40206492 0.24159694, + 0.88380575 0.40137792 0.24038094, + 0.92992359 0.31549984 0.18894991, + 0.92877865 0.31711787 0.19184993, + 0.96086633 0.23701409 0.14338905, + 0.95967078 0.23927493 0.14757897, + 0.98097551 0.16523093 0.10191095, + 0.98216265 0.16194294 0.095556565, + 0.99399489 0.094243288 0.055609692, + 0.99480438 0.090165727 0.047270719, + 0.99946475 0.028972492 0.015189297, + 0.99952489 0.027964497 0.012959098, + 0.99954665 -0.027316891 -0.012658996, + 0.99958891 -0.026558096 -0.010805199, + 0.99636209 -0.078937709 -0.032115903, + 0.99664325 -0.077182911 -0.027294505, + 0.99089938 -0.12690292 -0.044877175, + 0.99147826 -0.12466403 -0.037813008, + 0.98355424 -0.17283705 -0.052424911, + 0.98439276 -0.17047895 -0.043677088, + 0.97440052 -0.2177849 -0.055796973, + 0.97542876 -0.21552895 -0.045673888, + 0.96354097 -0.26174799 -0.0554685, + 0.96467125 -0.25973505 -0.044125512, + 0.95079935 -0.30543113 -0.051888719, + 0.95193797 -0.303749 -0.039378501, + 0.93593502 -0.34924999 -0.045277402, + 0.936979 -0.347956 -0.031576902, + 0.91867697 -0.39339301 -0.035700198, + 0.91950876 -0.39252192 -0.020741595, + 0.89893728 -0.43746716 -0.023116507, + 0.89946222 -0.43697208 -0.004813781, + 0.91459322 -0.40429208 -0.0081983218, + 0.91458088 -0.40431994 -0.0081987688, + 0.91461128 -0.40433416 -0.00044759116, + 0.91462409 -0.40430507 -0.00044379907, + 0.90569514 -0.42391106 -0.0039659906, + 0.89367586 -0.44871294 4.2840496e-005, + 0.89364213 -0.44869706 -0.0086538205, + 0.89367324 -0.44863513 -0.0086528622, + 0.89370668 -0.44865185 4.0349987e-005, + 0.89441597 -0.447236 4.03466e-005, + 0.89438158 -0.44721881 -0.0087771667, + 0.87634009 -0.48166105 -0.0055493205, + 0.87573528 -0.48213518 -0.025165809, + 0.89862901 -0.438113 -0.022867899, + 0.8976379 -0.43897694 -0.039312698, + 0.9182266 -0.39447683 -0.035327382, + 0.91694134 -0.39580014 -0.05060542, + 0.93541491 -0.35069698 -0.044838697, + 0.93395877 -0.3524729 -0.059023887, + 0.95026726 -0.30715907 -0.051435713, + 0.94874924 -0.30936006 -0.064586416, + 0.96304274 -0.26366395 -0.055046383, + 0.96156335 -0.26624009 -0.06717322, + 0.97397566 -0.21976593 -0.055447582, + 0.97263622 -0.22262406 -0.066462912, + 0.98322678 -0.17476496 -0.052174989, + 0.98213333 -0.17773905 -0.061831523, + 0.99068475 -0.12861498 -0.044742089, + 0.98993367 -0.13140796 -0.05256718, + 0.99626201 -0.080203399 -0.032083798, + 0.99589223 -0.082407519 -0.037520807, + 0.99953222 -0.027834207 -0.012673103, + 0.999475 -0.028808201 -0.0148283, + 0.9994455 0.029605584 0.015238693, + 0.99936187 0.030916996 0.017890098, + 0.99374998 0.096619003 0.055908602, + 0.99338549 0.098377652 0.05921977, + 0.98004979 0.17028095 0.10250298, + 0.98089349 0.16790007 0.098273344, + 0.95856786 0.24584797 0.14389698, + 0.95982689 0.24335296 0.13968399, + 0.92531759 0.32886684 0.18876991, + 0.92615426 0.32764509 0.18678105, + 0.87494481 0.4206689 0.23981094, + 0.87883401 0.41638699 0.23296501, + 0.82437855 0.49397969 0.27637681, + 0.82731044 0.49144423 0.27210313, + 0.76417202 0.564291 0.312437, + 0.76625699 0.56288499 0.309856, + 0.69728804 0.62793708 0.34566504, + 0.69660819 0.62890017 0.34528509, + 0.6233781 0.68541217 0.37631109, + 0.62321192 0.68547493 0.37647194, + 0.54788709 0.73324406 0.40270707, + 0.54648024 0.73361439 0.40394217, + 0.47170287 0.77240783 0.42530292, + 0.46860507 0.77289212 0.42784005, + 0.39688516 0.80304128 0.44453016, + 0.38937101 0.80345899 0.45038199, + 0.32306796 0.82552385 0.46274993, + 0.30829999 0.82487297 0.47385201, + 0.24932785 0.83972651 0.48238471, + 0.26123112 0.84121239 0.47341323, + 0.20659393 0.8526727 0.47986281, + 0.22154292 0.85543573 0.46813282, + 0.17045006 0.86439729 0.47303718, + 0.17946595 0.8666178 0.46558088, + 0.13290095 0.8731057 0.46906683, + 0.13817202 0.87476212 0.46443507, + 0.096047983 0.87915087 0.46676394, + 0.098216079 0.87999374 0.46471989, + 0.061161723 0.8826133 0.46610418, + 0.060929816 0.88250422 0.46634111, + 0.029239686 0.88376856 0.46700978, + 0.027976288 0.88305557 0.4684338, + 0.0021804704 0.88339925 0.46861613, + 0.00098687655 0.88260257 0.47011876, + -0.019491702 0.88243514 0.47003007, + -0.019744406 0.88223726 0.47039112, + -0.034992702 0.88186914 0.47019407, + -0.034296986 0.88250661 0.46904776, + -0.044616699 0.88214701 0.46885601, + -0.04259152 0.88432443 0.46492621, + -0.048573393 0.88408285 0.46479893, + -0.045593187 0.88786477 0.45783988, + -0.048033893 0.8877629 0.45778793, + -0.044848584 0.8925997 0.44861385, + -0.043441903 0.89265513 0.44864205, + -0.039987687 0.89910978 0.43589291, + -0.030938193 0.89939874 0.43603292, + -0.03758442 0.88300145 0.4678632, + -0.020699605 0.85545516 0.51746315, + -0.025932394 0.85535079 0.51739991, + -0.019914394 0.87747878 0.47920188, + -0.016712304 0.87753022 0.47923011, + -0.013032802 0.89924222 0.43725708, + -0.0058869286 0.89930278 0.43728691, + -0.0046871509 0.91957825 0.3928791, + 0.0046871509 0.91957825 0.3928791, + 0.00588548 0.89932901 0.437233, + 0.013097406 0.89926744 0.4372032, + 0.016756207 0.87767839 0.47895724, + 0.019686706 0.87763125 0.47893211, + -0.91334057 -0.40719578 -0.00074399065, + -0.93220741 -0.36192417 0.00052094721, + -0.948798 -0.315837 -0.00542052, + -0.93221134 -0.36191413 0.0005206542, + -0.93216974 -0.36189792 -0.0094558578, + -0.93216586 -0.36190796 -0.0094560487, + 0.027820613 0.87756544 0.47864923, + 0.036317095 0.87732589 0.47851893, + 0.039948381 0.8702026 0.49107176, + 0.039494604 0.8702181 0.49108106, + 0.042995699 0.86462599 0.50057298, + 0.039124914 0.86476332 0.50065321, + 0.042333305 0.86047614 0.50772905, + 0.034823187 0.86072558 0.50787675, + 0.037508491 0.85767585 0.5128209, + 0.026086085 0.85798746 0.5130077, + 0.02802079 0.85610372 0.51604384, + 0.012283803 0.85637516 0.51620811, + 0.014050595 0.8548907 0.51861781, + -0.0063315486 0.85495782 0.51865888, + -0.0042938804 0.85347509 0.52111608, + -0.029238304 0.85311812 0.52089804, + -0.026654797 0.85149187 0.52368993, + -0.055739898 0.85047001 0.52306199, + -0.05200642 0.84844631 0.52672017, + -0.085357033 0.84649527 0.52550918, + -0.078715689 0.84340489 0.53148097, + -0.11571497 0.84034681 0.52955389, + -0.10504898 0.83609885 0.53842688, + -0.14554907 0.83179742 0.53565723, + -0.13926105 0.8297013 0.54055721, + -0.18452105 0.82347816 0.53650314, + -0.19262908 0.8255614 0.53041726, + -0.24519794 0.81563485 0.52403986, + -0.24884801 0.81626701 0.52132797, + -0.30810204 0.8017801 0.51207608, + -0.3130289 0.80221981 0.5083859, + -0.37845382 0.78184366 0.49547276, + -0.38275501 0.78184402 0.49215701, + -0.45392087 0.75407881 0.47467989, + -0.45768073 0.75372052 0.47162873, + -0.53232491 0.71762782 0.44904387, + -0.53371984 0.71735173 0.44782785, + -0.60959089 0.67243981 0.41978991, + -0.6093961 0.67250019 0.41997609, + -0.68461704 0.61824703 0.38609606, + -0.68215108 0.61931509 0.38874006, + -0.75397199 0.55638099 0.34923699, + -0.74947083 0.55896688 0.3547529, + -0.82878172 0.47245383 0.29984689, + -0.83279771 0.46931481 0.29358387, + -0.8907097 0.38537985 0.24107791, + -0.89087939 0.38520318 0.24073312, + -0.93274122 0.30575007 0.19107805, + -0.93154263 0.30737787 0.19428593, + -0.96152836 0.23220909 0.14677306, + -0.96444112 0.22675303 0.13578102, + -0.98299903 0.157528 0.094328403, + -0.98531437 0.15077005 0.080150232, + -0.99501598 0.088047802 0.046806902, + -0.99558061 0.08498697 0.039956287, + -0.99954122 0.027410107 0.012886803, + -0.9995845 0.026641414 0.011008806, + -0.99960041 -0.026123285 -0.010794694, + -0.99963188 -0.025530396 -0.0091812192, + -0.99672174 -0.076132186 -0.027378492, + -0.99693525 -0.074746512 -0.023087306, + -0.99164122 -0.12327903 -0.038077809, + -0.99208236 -0.12151705 -0.031721011, + -0.98464215 -0.16892402 -0.044096105, + -0.98528922 -0.16705604 -0.036021009, + -0.97575724 -0.21393904 -0.046129912, + -0.97655535 -0.21214807 -0.036508914, + -0.96506137 -0.25822809 -0.044439014, + -0.96592212 -0.25666204 -0.033452805, + -0.95235014 -0.30244902 -0.039420605, + -0.95315367 -0.30123687 -0.027467091, + -0.93732911 -0.34700602 -0.031640403, + -0.93797278 -0.34619591 -0.018855495, + -0.91972691 -0.39197794 -0.021349099, + -0.92015636 -0.39151216 -0.0055356617, + -0.93215388 -0.36193898 -0.009454269, + -0.93219548 -0.36195478 0.00052094669, + -0.91333514 -0.40720806 -0.0007456431, + -0.91328901 -0.40718701 -0.0101005, + -0.91329432 -0.40717515 -0.010100204, + -0.89938015 -0.43712205 -0.006306001, + -0.8988716 -0.43758079 -0.023514489, + -0.91944975 -0.39264092 -0.021099593, + -0.9186551 -0.39347205 -0.035391904, + -0.93696964 -0.34800589 -0.031302389, + -0.93593812 -0.34929204 -0.044888303, + -0.95195377 -0.30374393 -0.039034892, + -0.95079386 -0.30546296 -0.051801492, + -0.96467078 -0.25974995 -0.04404939, + -0.96351922 -0.26180106 -0.055597015, + -0.97541291 -0.21557797 -0.045780998, + -0.97437447 -0.2178531 -0.055987626, + -0.98437679 -0.17053296 -0.043826289, + -0.98353875 -0.17288595 -0.05255359, + -0.99146974 -0.12470297 -0.037907094, + -0.99089652 -0.12691894 -0.044897277, + -0.99664265 -0.077187873 -0.027305091, + -0.99636579 -0.07891608 -0.032053094, + -0.99958915 -0.026555104 -0.010785801, + -0.99954766 -0.027301991 -0.012608696, + -0.9995265 0.027932987 0.012900094, + -0.99946803 0.0289184 0.0150821, + -0.99483454 0.090004057 0.046940677, + -0.99404114 0.094021417 0.055155907, + -0.98230821 0.16152905 0.094757825, + -0.98099226 0.16518605 0.10182302, + -0.95970351 0.23921788 0.14745793, + -0.96094674 0.23686394 0.14309697, + -0.92893261 0.31690684 0.19145291, + -0.92991626 0.31551608 0.18895905, + -0.88378191 0.40141693 0.24040397, + -0.88295245 0.40230078 0.24196886, + -0.81733871 0.49373183 0.29696187, + -0.82222861 0.48980275 0.28988487, + -0.758008 0.561306 0.33220401, + -0.7609331 0.55947304 0.32858902, + -0.69026834 0.6239053 0.36643118, + -0.69151777 0.62331074 0.36508489, + -0.61686337 0.67914844 0.39779025, + -0.61654079 0.67925978 0.39809984, + -0.54091507 0.72563607 0.42528006, + -0.53848189 0.7261948 0.4274089, + -0.46350405 0.76364714 0.44945207, + -0.45970994 0.7641179 0.45253795, + -0.38831505 0.79290509 0.46958807, + -0.38338986 0.79303569 0.47339883, + -0.31762108 0.8141852 0.48602411, + -0.31332004 0.81391114 0.48926407, + -0.25369716 0.82902646 0.49835029, + -0.24382208 0.8275283 0.50571519, + -0.19185607 0.83742929 0.51176518, + -0.19923297 0.8391189 0.50614792, + -0.15174706 0.84636933 0.51052117, + -0.16442701 0.85007215 0.50034106, + -0.120402 0.855533 0.50355399, + -0.12804903 0.8582502 0.49700111, + -0.088284492 0.86199486 0.49916995, + -0.092102997 0.86362499 0.49564999, + -0.056766108 0.86591309 0.49696305, + -0.058649521 0.8668673 0.49507719, + -0.028303107 0.86801416 0.49573213, + -0.029066101 0.86847001 0.49488899, + -0.0036175014 0.86883128 0.49509519, + -0.0040025907 0.86910009 0.49462005, + 0.016501995 0.86898869 0.49455681, + 0.015752798 0.8695969 0.49351093, + 0.031513795 0.86927289 0.49332693, + 0.030058004 0.87064815 0.49098706, + 0.040934898 0.87031186 0.49079695, + 0.038611114 0.87287933 0.48640618, + 0.045429803 0.87262911 0.48626605, + 0.04243391 0.87653124 0.47947112, + 0.045525186 0.87641168 0.47940582, + 0.04203992 0.88184041 0.46967024, + 0.041559398 0.88185799 0.46968001, + 0.037842009 0.88897121 0.45639712, + 0.034926079 0.88906544 0.45644572, + 0.022951005 0.88004524 0.47433513, + 0.027288787 0.87994957 0.47428277, + 0.02147229 0.90032756 0.43468279, + 0.017302193 0.90040058 0.4347178, + 0.013824496 0.91988474 0.39194492, + 0.0062513575 0.91995466 0.39197484, + 0.0051226206 0.93782413 0.34707302, + -0.0050876918 0.93782437 0.34707311, + -0.0062175784 0.91994679 0.39199391, + -0.013826095 0.91987664 0.39196384, + -0.017303394 0.90039372 0.43473184, + -0.0215685 0.90031898 0.43469599, + -0.027445197 0.8797769 0.47459394, + -0.027281197 0.87978089 0.47459593, + -0.032861099 0.86557901 0.49969301, + -0.034586389 0.8655287 0.49966383, + -0.038222898 0.85823786 0.51182693, + -0.036881398 0.85828102 0.51185298, + -0.040459212 0.85243517 0.52126509, + -0.03592401 0.85258329 0.52135515, + -0.039296102 0.84797102 0.528584, + -0.0312101 0.84821302 0.52873498, + -0.034255594 0.84466583 0.53419685, + -0.02221911 0.84495342 0.53437823, + -0.025032394 0.84213281 0.5386889, + -0.0091366805 0.84236109 0.53883606, + -0.012009595 0.83986157 0.54266775, + 0.0078316974 0.83989668 0.5426898, + 0.0044284393 0.8373149 0.54670292, + 0.02829409 0.83698767 0.54648983, + 0.0234928 0.83380502 0.55155897, + 0.051040206 0.83294815 0.55099207, + 0.044805896 0.82933789 0.55694795, + 0.075842701 0.82778001 0.55590302, + 0.066244386 0.82291883 0.56428391, + 0.100377 0.82056499 0.56266999, + 0.092173092 0.81695485 0.56928796, + 0.13017003 0.8134672 0.5668571, + 0.14003292 0.81704551 0.55930966, + 0.18549095 0.81085581 0.5550729, + 0.19161803 0.81255013 0.55049509, + 0.2441631 0.80283427 0.54391319, + 0.24743406 0.80346918 0.5414921, + 0.30605799 0.78946197 0.53205103, + 0.30929095 0.78982383 0.52963889, + 0.37434298 0.77015889 0.51645195, + 0.37703985 0.77022868 0.51438183, + 0.44798884 0.74348575 0.49652281, + 0.44982794 0.74336493 0.49503893, + 0.52432209 0.70874417 0.4719831, + 0.52485412 0.70865721 0.47152212, + 0.60108978 0.66535574 0.44271085, + 0.60002691 0.6656428 0.44371989, + 0.93858463 -0.34503189 -0.0034476588, + 0.93822211 -0.34552604 -0.018737901, + 0.95395613 -0.29950604 -0.016242202, + 0.95343179 -0.30030495 -0.028012892, + 0.96680337 -0.25441709 -0.023732409, + 0.96620065 -0.25552791 -0.03408549, + 0.97740591 -0.20951498 -0.027947797, + 0.97682214 -0.21085003 -0.036891203, + 0.9859941 -0.16428502 -0.028744103, + 0.98550725 -0.16572504 -0.036204908, + 0.9925639 -0.11891998 -0.025979696, + 0.99222785 -0.12030298 -0.031799298, + 0.99716502 -0.072747096 -0.019229, + 0.99700123 -0.073847912 -0.023129907, + 0.99966514 -0.024693303 -0.0077341809, + 0.99964076 -0.025171494 -0.0092016179, + 0.99962866 0.025594791 0.0093563665, + 0.99959546 0.026213612 0.011040306, + 0.99612665 0.081036068 0.034129888, + 0.99570447 0.083455235 0.040099617, + 0.98741853 0.14252892 0.068484068, + 0.98573154 0.14779992 0.080550864, + 0.97035754 0.21220489 0.11565195, + 0.96553349 0.22169389 0.13636994, + 0.93942434 0.29194513 0.17958306, + 0.93450385 0.29857597 0.19379097, + 0.89598686 0.37249798 0.24176997, + 0.89628702 0.37219599 0.24112201, + 0.84439451 0.44961673 0.29127783, + 0.8421331 0.45136106 0.29510203, + 0.77304381 0.53094387 0.3471339, + 0.76452911 0.53574008 0.35843801, + 0.67392308 0.61404306 0.41082707, + 0.67579299 0.61331499 0.408838, + 0.68172705 0.62014705 0.38815707, + 0.60821474 0.67284179 0.42113984, + 0.60864007 0.67271107 0.42073405, + 0.53268701 0.71753299 0.44876599, + 0.53173715 0.7177192 0.44959411, + 0.45714179 0.75372267 0.47214776, + 0.454772 0.75394899 0.474071, + 0.38367683 0.78176665 0.49156177, + 0.38110685 0.78177172 0.49354881, + 0.31516892 0.8024928 0.50662988, + 0.31158507 0.80218619 0.50932515, + 0.25241786 0.81687552 0.51865172, + 0.24487901 0.81558597 0.52426499, + 0.19250707 0.82546329 0.5306142, + 0.18091999 0.82245886 0.53928596, + 0.13590503 0.82850015 0.5432471, + 0.14459002 0.83142012 0.53650206, + 0.10448694 0.8356505 0.53923172, + 0.115365 0.83999503 0.53018802, + 0.078310698 0.84304398 0.53211302, + 0.084994681 0.84615982 0.52610791, + 0.051782001 0.84809297 0.52731103, + 0.056581426 0.8506934 0.52260822, + 0.027267091 0.85174173 0.52325183, + 0.030177511 0.85356832 0.5201062, + 0.0051235114 0.85394615 0.52033609, + 0.0071769417 0.85543519 0.51786011, + -0.013337305 0.85538131 0.51782715, + -0.011531698 0.85689384 0.51536387, + -0.027597109 0.85662431 0.51520216, + -0.025690205 0.85847521 0.51221114, + -0.037253916 0.85816228 0.51202518, + -0.034625698 0.86113787 0.50719094, + -0.042253103 0.86088514 0.50704205, + -0.039175589 0.86498582 0.50026488, + -0.042959105 0.86485112 0.50018704, + -0.039429512 0.87047815 0.49062511, + -0.039997086 0.87045872 0.49061382, + -0.033901606 0.88227123 0.46951911, + -0.042110197 0.88199586 0.46937194, + -0.045504298 0.87671888 0.47884595, + -0.042456511 0.87683624 0.47891113, + -0.045498285 0.8728857 0.48579884, + -0.038584083 0.87313968 0.48594081, + -0.040750302 0.87075311 0.49002907, + -0.029559907 0.87109619 0.49022213, + -0.031066507 0.86967617 0.49264413, + -0.015178402 0.86999613 0.49282506, + -0.015751095 0.86953282 0.49362388, + 0.0049125287 0.8696298 0.49367988, + 0.0044710306 0.86932313 0.49422407, + 0.030058593 0.8689388 0.49400589, + 0.029244596 0.86845487 0.49490494, + 0.059897922 0.8672663 0.49422818, + 0.057577707 0.86609411 0.49655405, + 0.092741579 0.8637948 0.49523488, + 0.087898895 0.86172891 0.49969694, + 0.127729 0.85799199 0.497529, + 0.11998396 0.85523373 0.50416183, + 0.16362694 0.84984672 0.5009858, + 0.15077206 0.84607929 0.51129019, + 0.19832605 0.83886218 0.5069291, + 0.18851995 0.8365888 0.51437289, + 0.24003597 0.82695788 0.50845194, + 0.25355795 0.82903981 0.49839887, + 0.31326702 0.8139081 0.48930305, + 0.32088313 0.81437731 0.48355317, + 0.38694295 0.7928679 0.47078195, + 0.39078894 0.79275191 0.46779093, + 0.462118 0.76376098 0.45068401, + 0.46424001 0.763493 0.44895399, + 0.53914797 0.72599697 0.42690501, + 0.54028112 0.72573715 0.4259131, + 0.61595899 0.67941803 0.39873001, + 0.615897 0.67943901 0.39879, + 0.69062376 0.62371576 0.36608389, + 0.68922204 0.62438005 0.36759004, + 0.68310779 0.6182459 0.38876191, + 0.75325471 0.55679685 0.35012087, + 0.75002986 0.55864793 0.35407296, + 0.82907391 0.47227094 0.29932696, + 0.83271599 0.469421 0.29364601, + 0.89072371 0.38535884 0.24105991, + 0.89065403 0.38543099 0.241202, + 0.93260002 0.30594301 0.191458, + 0.93148273 0.30745894 0.19444495, + 0.96149576 0.23226795 0.14689296, + 0.96415633 0.22730108 0.13688305, + 0.98285735 0.15794006 0.095112734, + 0.98521835 0.15108407 0.080737032, + 0.99498755 0.088195354 0.047130376, + 0.99556655 0.085068263 0.04013158, + 0.99953961 0.027439591 0.012944795, + 0.99958378 0.026655594 0.011031097, + 0.99960011 -0.026130404 -0.010813701, + 0.99963188 -0.025529396 -0.0091782194, + 0.99672264 -0.07612507 -0.02736819, + 0.99693823 -0.074724816 -0.023031106, + 0.99164945 -0.12324206 -0.037984718, + 0.99209088 -0.12147599 -0.031610698, + 0.98465645 -0.16888008 -0.043946523, + 0.98529702 -0.16702799 -0.035936199, + 0.97577065 -0.21390092 -0.046020884, + 0.97655445 -0.21214211 -0.03656932, + 0.96506023 -0.25822005 -0.044512313, + 0.96590549 -0.25668612 -0.033749416, + 0.95233762 -0.30244288 -0.039765485, + 0.95315135 -0.30122212 -0.027710309, + 0.93734157 -0.34694684 -0.031916685, + 0.93801546 -0.34609818 -0.01852591, + 0.91976988 -0.39189693 -0.020977499, + 0.92021388 -0.39139393 -0.0041406397, + 0.9333269 -0.35894498 -0.0077008391, + 0.93335485 -0.35895497 0.00035463896, + 0.93337214 -0.35891002 0.00035463902, + 0.93334466 -0.35889888 -0.0077036773, + 0.93331814 -0.35896802 -0.0077047711, + 0.93334597 -0.358978 0.000356687, + 0.94978851 -0.31283385 -0.0060510873, + 0.94978237 -0.31283212 -0.0070470022, + 0.94980538 -0.31276211 -0.0070458925, + 0.94982851 -0.31276986 -0.00091967254, + 0.94448346 -0.32854414 -0.0031339014, + 0.97325873 -0.22968894 -0.0032380894, + 0.99972963 -0.023093693 -0.002723689, + 0.86586201 0.48848099 0.108025, + 0.96358764 0.2673409 -0.0052622883, + 0.84927511 0.52403605 0.06417191, + 0.8728267 0.48441184 0.059319578, + 0.87473071 0.48340183 0.03418969, + 0.89856887 0.43773896 0.030960096, + 0.89924055 0.43728879 0.012035795, + 0.91396421 0.4057551 0.0056875716, + 0.91392159 0.40585083 0.0056895474, + 0.91400969 0.40565285 0.0056605083, + 0.91402441 0.40565917 0.00030664416, + 0.91393667 0.40585685 0.00030664389, + 0.91397923 0.40576109 0.00030320705, + 0.92631412 0.37673205 -0.0039039005, + 0.96014434 0.2794871 -0.0031430111, + 0.96360189 0.26733798 -0.0013623099, + 0.96359938 0.2673381 0.002597241, + 0.96359766 0.26734391 0.002597359, + 0.9542895 0.29876116 0.0085685542, + 0.95399803 0.299142 0.020047599, + 0.93776625 0.34649009 0.023220705, + 0.93679959 0.34753484 0.040324282, + 0.91732979 0.39547491 0.045886889, + 0.91535175 0.39714491 0.066386282, + 0.89236569 0.44513685 0.074408568, + 0.88883322 0.44742113 0.098944426, + -0.025416596 0.53268492 0.84593189, + -0.016182594 0.53278685 0.84609473, + -0.0013469007 0.57205331 0.8202154, + 0.0068322015 0.57204014 0.82019717, + 0.021092398 0.60264993 0.79772687, + 0.033948995 0.60243595 0.79744488, + 0.050326418 0.63160622 0.77365428, + 0.067830294 0.63095093 0.77285188, + 0.086029649 0.65818059 0.74792856, + 0.10792401 0.65677106 0.74632704, + 0.12744506 0.68151927 0.72061735, + 0.15345794 0.67898375 0.71793574, + 0.17368196 0.70078784 0.69190383, + 0.203646 0.69669098 0.687859, + 0.22595793 0.71708274 0.65934473, + 0.26016799 0.71077102 0.65354198, + 0.28546807 0.7301262 0.62082511, + 0.32376111 0.72079426 0.61289024, + 0.34959999 0.73701298 0.578439, + 0.39143991 0.72387981 0.56813091, + 0.4163931 0.7363432 0.53330612, + 0.46119881 0.71861678 0.5204668, + 0.48452395 0.72740597 0.48591894, + 0.53107607 0.70457709 0.47066906, + 0.55214179 0.70998764 0.4371008, + 0.59871793 0.68206495 0.41990995, + 0.61710626 0.68460727 0.38793415, + 0.66238749 0.65179145 0.36933827, + 0.6778937 0.65207469 0.33949786, + 0.72112781 0.61450386 0.3199369, + 0.73374075 0.61315876 0.29267889, + 0.77406913 0.57134908 0.27272204, + 0.78397 0.568973 0.248316, + 0.82033128 0.5241462 0.22875208, + 0.82781416 0.52126813 0.20737204, + 0.86882818 0.46004611 0.18301705, + 0.97859722 0.20569305 0.0061535514, + 0.97846937 0.20596108 0.013335304, + 0.96729952 0.25310689 0.016387893, + 0.96679503 0.25396401 0.028453499, + 0.95274001 0.301898 0.0338239, + 0.95160925 0.30339307 0.04891371, + 0.93417901 0.352256 0.056791499, + 0.93199676 0.35450891 0.075533688, + 0.9106046 0.40420583 0.086122252, + 0.90676326 0.40726408 0.10916203, + 0.90024221 0.41459608 0.13294403, + 0.90536177 0.4106769 0.10800198, + 0.9281714 0.35991517 0.094652347, + 0.93113935 0.35693711 0.074668929, + 0.94951349 0.30707914 0.064239033, + 0.9511295 0.30498916 0.048315823, + 0.96575886 0.25624597 0.040593997, + 0.96655446 0.25492013 0.028076213, + 0.97804463 0.20714292 0.022814192, + 0.97837502 0.206421 0.0131439, + 0.98718154 0.15927893 0.010142095, + 0.9872545 0.15907508 0.0048784926, + 0.98516238 0.17162307 0.00083487527, + 0.98515511 0.17166501 0.00083566713, + 0.9851535 0.17166507 -0.0019700709, + 0.98516077 0.17162296 -0.0019630694, + 0.99237537 0.12324905 0.00085794128, + 0.99237567 0.12324996 0.00017379894, + 0.99239498 0.123094 0.00017093201, + 0.99239463 0.12309396 0.00086141971, + 0.99239022 0.12313003 0.00086142024, + 0.99239051 0.12312994 0.00016904192, + 0.99358267 0.11305296 0.0035471288, + 0.9935475 0.11319495 0.0070915869, + 0.98712546 0.15963508 0.010001104, + 0.98693126 0.16020505 0.017351603, + 0.97788513 0.20792703 0.022520302, + 0.97736412 0.20904604 0.032544803, + 0.96541333 0.25762108 0.040107217, + 0.96427703 0.25947699 0.053306099, + 0.94886714 0.30921802 0.063524805, + 0.94666564 0.31199187 0.080531269, + 0.92707962 0.36296788 0.09368927, + 0.92311567 0.36680788 0.11536595, + 0.89850289 0.41874495 0.13170098, + 0.89171076 0.42369491 0.15916796, + 0.86140573 0.47547382 0.17861894, + 0.85289788 0.48004293 0.20524096, + 0.81942087 0.52704191 0.22533597, + 0.81086516 0.53016609 0.24783406, + 0.773022 0.57468802 0.268646, + 0.76179087 0.57717395 0.29418498, + 0.71996063 0.61832869 0.31516084, + 0.70570123 0.61959225 0.34364411, + 0.66113019 0.65611321 0.36389908, + 0.64369673 0.6554867 0.39495781, + 0.59739405 0.68689305 0.41388205, + 0.57685286 0.68369383 0.44699389, + 0.52969283 0.70992678 0.46414381, + 0.50633281 0.70351875 0.49868682, + 0.459739 0.72449797 0.51355898, + 0.43407816 0.71437824 0.54885316, + 0.38988909 0.73022717 0.56103009, + 0.36277303 0.71620005 0.59619904, + 0.32206589 0.72760475 0.60569376, + 0.29491511 0.71008223 0.63938123, + 0.25829211 0.71791738 0.64643627, + 0.234212 0.69912398 0.67555201, + 0.20145808 0.70438224 0.68063223, + 0.17960891 0.68412971 0.70689964, + 0.15078197 0.68748784 0.71036983, + 0.129207 0.66393298 0.73654503, + 0.10474498 0.6658628 0.73868483, + 0.084108077 0.63935483 0.76429784, + 0.064185075 0.64030576 0.76543373, + 0.045115799 0.61138397 0.79004699, + 0.02991269 0.61173278 0.79049867, + 0.012846905 0.5808962 0.81387627, + 0.0025484799 0.58094198 0.813941, + -0.015622804 0.54119015 0.84075516, + -0.028237293 0.54103988 0.84052283, + -0.027102713 0.54404324 0.83861941, + -0.021940794 0.54411191 0.83872581, + -0.017838499 0.54747492 0.83663189, + -0.025843604 0.54738003 0.83648515, + -0.017229103 0.58304507 0.81225711, + -0.019185508 0.5830242 0.81222832, + -0.012683898 0.61943191 0.78494787, + -0.012077794 0.61943668 0.78495365, + -0.0079752896 0.65609401 0.754637, + -0.0041196602 0.65611005 0.75465411, + -0.0027016208 0.69246018 0.72145116, + 0.0025775894 0.69245982 0.72145182, + 0.0039771497 0.65607196 0.75468791, + 0.0078947898 0.656057 0.75467002, + 0.011985107 0.61930835 0.78505647, + 0.013173698 0.61929888 0.78504485, + 0.0196319 0.58312798 0.81214303, + 0.0173073 0.58315301 0.81217802, + 0.017834902 0.54753304 0.8365941, + 0.025928397 0.54743594 0.83644587, + -0.02512219 0.59459776 0.80363071, + -0.038941085 0.62387079 0.78055668, + -0.05410919 0.62342989 0.7800048, + -0.069853619 0.65112126 0.75575233, + -0.089494973 0.65009677 0.75456268, + -0.10684605 0.67574227 0.72935337, + -0.13049099 0.67382193 0.72727996, + -0.14876696 0.69672281 0.70174479, + -0.17618006 0.69354224 0.69854122, + -0.197402 0.71611899 0.66948199, + -0.22909392 0.71106476 0.66475779, + -0.2527051 0.73223525 0.63243324, + -0.28896308 0.72451323 0.62576425, + -0.31293291 0.7423858 0.59239888, + -0.35290903 0.73135108 0.58359307, + -0.37657791 0.7457568 0.54957789, + -0.41947216 0.73077023 0.53853315, + -0.44208714 0.74164921 0.5044952, + -0.48722601 0.72205597 0.49116799, + -0.50818872 0.72957957 0.45766574, + -0.55456805 0.70492208 0.44219807, + -0.57333803 0.70941603 0.40989307, + -0.61915487 0.67993385 0.39285791, + -0.63544494 0.68190593 0.36223498, + -0.67961198 0.64784002 0.344138, + -0.69326419 0.64785719 0.3156991, + -0.73514992 0.60940093 0.29695997, + -0.74620682 0.60803288 0.27105594, + -0.78510898 0.56569302 0.25218099, + -0.79372227 0.56347817 0.22912307, + -0.82870591 0.51846093 0.21081898, + -0.83516312 0.51586807 0.19074303, + -0.86602712 0.46896607 0.17340101, + -0.87069017 0.46634513 0.15627204, + -0.90383714 0.40570405 0.13595101, + -0.0071206801 0.57047802 0.82128203, + -0.0011908594 0.57049167 0.82130253, + -0.012784594 0.52062374 0.85369056, + -0.015799198 0.52060091 0.85365391, + -0.012861303 0.53851914 0.84251517, + -0.0117706 0.53852701 0.84252602, + -0.0078451894 0.57734597 0.81646186, + -0.00391735 0.57735902 0.81648099, + -0.0025395206 0.61675614 0.7871502, + 0.0027228794 0.6167559 0.78714985, + 0.0040878919 0.57739133 0.81645739, + 0.0079487618 0.57737809 0.8164382, + 0.011868294 0.53854579 0.84251261, + 0.012877403 0.53853911 0.84250218, + 0.015825506 0.5205552 0.85368133, + 0.012839302 0.52057713 0.85371816, + 0.0012338505 0.5705322 0.82127428, + -0.009375832 0.57050711 0.82123917, + -0.021910794 0.61092287 0.79138684, + -0.033231091 0.6107319 0.79113984, + -0.044167504 0.63849205 0.76836014, + -0.059576299 0.637981 0.767744, + -0.072395377 0.66453075 0.74374574, + -0.091732025 0.66347015 0.74255818, + -0.106043 0.68811399 0.717812, + -0.12918505 0.68621725 0.71583325, + -0.14606398 0.71063596 0.68823093, + -0.17319289 0.7074846 0.68517858, + -0.19225992 0.73077875 0.65497977, + -0.22367094 0.72580481 0.65052181, + -0.24385697 0.74661392 0.61895192, + -0.27939093 0.73919785 0.61280286, + -0.30013388 0.75712168 0.58024681, + -0.33945903 0.74658406 0.57217103, + -0.36022198 0.76141489 0.53896892, + -0.40225294 0.74726397 0.52895093, + -0.42236501 0.758892 0.49567199, + -0.46639019 0.74060124 0.48372519, + -0.48532388 0.74914581 0.45082289, + -0.53058302 0.72626698 0.43705601, + -0.54785997 0.73195994 0.40507293, + -0.59340727 0.70425236 0.38973919, + -0.60869986 0.70746285 0.35913891, + -0.65291804 0.67538708 0.34285602, + -0.66598195 0.67657793 0.31418198, + -0.70803803 0.64048606 0.29742202, + -0.71884501 0.64016998 0.27100599, + -0.7583012 0.60032713 0.25413907, + -0.76685739 0.5990023 0.2304911, + -0.80328184 0.5558669 0.21389295, + -0.80984038 0.55397326 0.19306009, + -0.84244961 0.50876474 0.17730491, + -0.8473261 0.50665003 0.15919901, + -0.87611032 0.45993918 0.14452204, + -0.8796227 0.45784986 0.12898596, + -0.90382242 0.41187522 0.11603405, + -0.90145558 0.41366878 0.12749894, + -0.87544513 0.46187705 0.14235702, + -0.87139469 0.46422184 0.15864894, + -0.84162486 0.51104295 0.17464998, + -0.836025 0.513385 0.193644, + -0.80228472 0.55853081 0.21067193, + -0.79474866 0.56059176 0.2326189, + -0.7571497 0.60335875 0.2503649, + -0.74738783 0.6047219 0.27517793, + -0.70672464 0.64395171 0.29302984, + -0.69457585 0.64412582 0.32041591, + -0.65146792 0.67927396 0.33789998, + -0.63687384 0.67772985 0.36752391, + -0.59182477 0.70858377 0.38425586, + -0.57487494 0.70478296 0.41569194, + -0.52888113 0.73101521 0.4311631, + -0.50984097 0.72446895 0.46390393, + -0.46456587 0.74574983 0.47753087, + -0.44385505 0.73610407 0.51102203, + -0.40029615 0.75276929 0.52259117, + -0.37847674 0.73983145 0.55624157, + -0.33733085 0.75244063 0.56572169, + -0.31499115 0.73614436 0.59905928, + -0.27709699 0.74525601 0.60647398, + -0.25494707 0.72576916 0.63895315, + -0.22120097 0.73197895 0.64441997, + -0.19982204 0.7095862 0.67569119, + -0.170587 0.71357697 0.67949098, + -0.15148793 0.68992466 0.70785266, + -0.12633698 0.69238782 0.71037883, + -0.11000606 0.66850442 0.7355274, + -0.08848273 0.66994822 0.73711622, + -0.073396757 0.64371365 0.76173854, + -0.056054581 0.64443976 0.76259768, + -0.042749975 0.61659163 0.78612155, + -0.029588796 0.61688495 0.78649688, + -0.020903392 0.59465575 0.80370867, + 0.0037400096 0.57637197 0.81717891, + -0.00019081993 0.57637584 0.81718469, + 0.015185507 0.52585721 0.8504374, + 0.021168094 0.52579987 0.85034484, + 0.017338298 0.54226291 0.8400299, + 0.019310897 0.54224294 0.83999985, + 0.012981007 0.5794543 0.81490141, + 0.011892704 0.57946217 0.81491232, + 0.0078961384 0.61724186 0.78673381, + 0.0037494691 0.61725688 0.78675282, + 0.0023750409 0.65532625 0.7553423, + -0.0024364004 0.65532619 0.75534219, + -0.0038306001 0.61738598 0.78665102, + -0.0079897838 0.61737132 0.78663135, + -0.012012898 0.57954895 0.8148489, + -0.012881706 0.57954228 0.81484044, + -0.019240804 0.5421921 0.84003419, + -0.017261593 0.54221177 0.84006459, + -0.021075405 0.52582413 0.8503322, + -0.015042602 0.52588105 0.85042512, + -0.0033600722 0.56445438 0.82545745, + 0.0028331401 0.56445497 0.825459, + 0.0144594 0.59467798 0.80383402, + 0.025157591 0.59455174 0.80366373, + 0.038935382 0.62372869 0.78067064, + 0.054120209 0.62328708 0.78011811, + 0.069852784 0.65095484 0.75589579, + 0.089435399 0.64993399 0.75471002, + 0.10676595 0.67555273 0.72954065, + 0.13039897 0.67363483 0.7274698, + 0.14880101 0.69669807 0.70176208, + 0.17616102 0.69352305 0.69856507, + 0.19658409 0.71526533 0.67063427, + 0.22810492 0.71026778 0.66594875, + 0.25134012 0.73114735 0.6342333, + 0.28742 0.72352201 0.62761903, + 0.31159487 0.74160177 0.59408379, + 0.3513999 0.7306838 0.58533686, + 0.37528986 0.74527174 0.5511148, + 0.41806686 0.73040378 0.54012084, + 0.4409422 0.74144733 0.50579226, + 0.48609111 0.72192919 0.49247712, + 0.50727117 0.72956026 0.45871317, + 0.55361974 0.70499563 0.44326779, + 0.57263619 0.70956826 0.41061014, + 0.61849231 0.68012428 0.39357117, + 0.63495404 0.68212807 0.36267704, + 0.67918909 0.64805806 0.34456202, + 0.69297582 0.64807981 0.3158749, + 0.73492366 0.60959673 0.29711786, + 0.74608165 0.60821468 0.27099288, + 0.78501898 0.56584698 0.25211599, + 0.7937243 0.56360215 0.22881107, + 0.82870698 0.51857603 0.21053199, + 0.83520013 0.51595908 0.19033404, + 0.86607689 0.46901593 0.17301698, + 0.87247181 0.46532688 0.14921097, + 0.87903887 0.45126995 0.15377298, + 0.84168488 0.51110995 0.17416398, + 0.83606511 0.51347005 0.19324502, + 0.80230719 0.55865711 0.21025105, + 0.79474521 0.56073409 0.23228706, + 0.75710988 0.60354996 0.25002396, + 0.747253 0.60493398 0.275078, + 0.70657325 0.64416826 0.29291913, + 0.69428897 0.64434695 0.32059297, + 0.65114427 0.67949426 0.33808112, + 0.63639021 0.67793024 0.36799213, + 0.59129786 0.7087658 0.38473091, + 0.57417881 0.70491475 0.41642985, + 0.52816433 0.73109943 0.43189827, + 0.50891691 0.72446293 0.46492693, + 0.46359879 0.74569666 0.47855276, + 0.44269699 0.73593402 0.51226997, + 0.39921793 0.75250089 0.52380097, + 0.37717009 0.73939317 0.55771011, + 0.336164 0.75189501 0.56713998, + 0.31363004 0.73541504 0.60066706, + 0.275868 0.74443799 0.60803699, + 0.25355312 0.72475636 0.64065528, + 0.22002006 0.7308802 0.64606917, + 0.19897699 0.708799 0.67676598, + 0.16993207 0.71274233 0.68053031, + 0.151512 0.68991899 0.70785302, + 0.12636004 0.69238222 0.71038026, + 0.10991797 0.66833681 0.7356928, + 0.088460304 0.66977507 0.73727608, + 0.073389545 0.64356434 0.7618655, + 0.05602558 0.64429075 0.76272571, + 0.042732984 0.61647278 0.78621572, + 0.029624192 0.6167649 0.7865898, + 0.018356608 0.58784926 0.80876231, + 0.014813894 0.58788377 0.8088097, + 0.021986205 0.61082011 0.79146415, + 0.033256486 0.61062968 0.79121763, + 0.044196427 0.63839334 0.76844049, + 0.059519514 0.63788515 0.76782817, + 0.072339721 0.66443223 0.74383926, + 0.091673106 0.66337204 0.74265307, + 0.10605295 0.68813264 0.71779263, + 0.12919495 0.68623573 0.71581364, + 0.14549203 0.70982516 0.68918818, + 0.17251399 0.70670295 0.68615592, + 0.19131307 0.72970623 0.65645123, + 0.22244492 0.72481173 0.65204775, + 0.24278405 0.74582016 0.62032914, + 0.2781159 0.73849076 0.61423373, + 0.29901797 0.75658786 0.58151793, + 0.33825609 0.74612719 0.5734781, + 0.35915899 0.76108998 0.54013598, + 0.40116906 0.74700403 0.53014004, + 0.42145175 0.75875854 0.49665269, + 0.46542013 0.74055117 0.48473513, + 0.48456705 0.74921107 0.45152807, + 0.52985913 0.72637016 0.43776211, + 0.54731607 0.73213208 0.40549707, + 0.59286994 0.70446396 0.39017394, + 0.60831308 0.70770907 0.35930902, + 0.65258944 0.6756224 0.3430182, + 0.66579121 0.67682326 0.31405813, + 0.707883 0.64071298 0.29730201, + 0.71877098 0.64038599 0.27069199, + 0.75827187 0.60049492 0.25382996, + 0.76687735 0.59915233 0.2300341, + 0.80330312 0.55600005 0.21346703, + 0.80987781 0.55409086 0.19256495, + 0.84251416 0.50882214 0.17683305, + 0.84737319 0.50670612 0.15876904, + 0.87616128 0.45996717 0.14412405, + 0.880979 0.45702299 0.122499, + 0.85859287 0.49453494 0.13510498, + 0.88269287 0.45333695 0.12384999, + 0.88748533 0.45034915 0.097752534, + 0.9117009 0.40150493 0.087150492, + 0.91452771 0.39918086 0.06552688, + 0.93482578 0.3504169 0.057522185, + 0.93635166 0.34880388 0.039767385, + 0.9530791 0.30077302 0.034291405, + 0.95379555 0.29980686 0.01974339, + 0.96744138 0.2525481 0.016631305, + 0.96764112 0.25222203 0.0074011208, + 0.97554713 0.21978404 0.0016991802, + 0.97554803 0.219785 0.000748355, + 0.97569877 0.21911494 0.00074835483, + 0.97569788 0.21911398 0.0016782997, + 0.97554535 0.21979207 0.0016912005, + 0.97547615 0.21977703 -0.012015802, + 0.98379791 0.17927998 0.00060023996, + 0.86979669 0.49334282 0.0081551475, + 0.8697899 0.49335495 0.0081554092, + -0.81909031 0.57362521 0.0067214225, + -0.81910872 0.57363784 -0.00071152375, + -0.81906313 0.57370305 -0.00070836005, + -0.81904489 0.57368994 0.0067224391, + 0.82496589 0.56500095 0.014321098, + 0.81731129 0.57619619 -0.00041803814, + 0.81731039 0.5761953 0.0017139108, + 0.81730282 0.57620591 0.0017140096, + 0.81730384 0.57620686 -0.00041751491, + 0.038657602 0.99245113 0.11638901, + -0.21746504 -0.97606725 -0.0012925003, + -0.26501197 -0.9642449 0.00073161797, + -0.26497391 -0.96410662 -0.016945994, + 0.32857704 0.012605802 0.9443931, + 0.57503682 -0.0011984195 0.81812668, + 0.57503307 -0.0040731006 0.81812012, + 0.56530893 -0.016466098 0.8247149, + 0.57344782 -0.018160794 0.81904072, + 0.57354212 -0.0011984803 0.81917518, + 0.53412092 0.0013775099 0.84540689, + 0.53516865 0.0011805892 0.84474438, + 0.53512388 -0.012985697 0.84467381, + 0.53407621 -0.012997806 0.84533644, + 0.51984906 -0.022296602 0.85396713, + 0.49194199 0.000186755 0.870628, + 0.49184117 -0.020257607 0.8704493, + 0.49186417 -0.020257307 0.87043631, + 0.491965 0.000198974 0.87061501, + 0.51471525 0.015920708 0.85721344, + -0.21398392 0.14042796 -0.96669066, + -0.25152111 0.085200436 -0.96409446, + -0.29790115 0.079441935 -0.95128548, + -0.28003898 0.35270998 -0.89284587, + -0.32528192 0.34742892 -0.87947977, + -0.28580397 0.57063496 -0.76986486, + -0.32795784 0.56253868 -0.75894266, + -0.25600407 0.76804018 -0.58700609, + -0.17849407 0.91066933 -0.37258711, + -0.16342704 0.91308922 -0.37357709, + -0.25469595 0.76034385 -0.59750086, + -0.22694393 0.76575869 -0.60175574, + -0.28577104 0.57831204 -0.76412714, + -0.24428397 0.58519495 -0.77322191, + -0.28042191 0.35709289 -0.89098167, + -0.23569287 0.36153883 -0.90207458, + -0.14144295 0.92542267 -0.35154888, + -0.11785306 0.9283064 -0.35264418, + -0.19078088 0.78657752 -0.58728063, + -0.15790001 0.79124302 -0.59076399, + -0.20456795 0.6013279 -0.77237082, + -0.16494896 0.60590488 -0.77824885, + -0.19190304 0.36995208 -0.90901524, + -0.14815801 0.37279803 -0.91600811, + -0.15864508 0.10010905 -0.98224747, + -0.11786001 0.14253801 -0.98274714, + -0.12069401 0.14249702 -0.98240912, + -0.12193801 -0.0030240505 -0.99253315, + -0.11907499 -0.0032793996 -0.99287987, + -0.16856696 0.0063595688 -0.98566973, + -0.166876 0.14140099 -0.97578597, + -0.16657995 0.14140695 -0.97583562, + -0.20492108 0.091626726 -0.97448033, + -0.19163205 0.3678101 -0.90994126, + -0.23597312 0.36417219 -0.90094143, + -0.20421797 0.59589791 -0.77665991, + -0.24443103 0.59026206 -0.76931411, + -0.191175 0.77955699 -0.59644198, + -0.22604696 0.7736479 -0.59192193, + -0.14358497 0.91939479 -0.36619192, + -0.16369794 0.91648972 -0.36503389, + -0.059902117 0.99174523 -0.11337203, + -0.053562809 0.9921031 -0.11341301, + -0.34451181 -0.93865752 -0.015283893, + 0.0259207 -0.99966401 -6.8508198e-005, + -0.68829674 0.72527176 0.015119194, + -0.60997194 0.7921989 0.018845499, + -0.60957438 0.79199648 0.034068819, + -0.56782788 0.8223868 0.035376094, + -0.56678092 0.82180989 0.058204692, + -0.52322584 0.85006469 0.060205776, + -0.52161014 0.84896219 0.084770821, + -0.47708201 0.87450999 0.087321803, + -0.47489977 0.87268758 0.11351895, + -0.42963687 0.89545768 0.11648095, + -0.42692193 0.8927089 0.14425099, + -0.3809841 0.91274226 0.14748803, + -0.37782386 0.9088797 0.17659794, + -0.33144698 0.92615288 0.17995499, + -0.3279621 0.92099923 0.21024105, + -0.2821109 0.93532163 0.21351093, + -0.27847502 0.92877114 0.24461403, + -0.23351502 0.94028813 0.24764703, + -0.22996603 0.9323861 0.27887604, + -0.18605402 0.94133514 0.28155303, + -0.18279009 0.9321214 0.31263015, + -0.14019997 0.93873078 0.3148469, + -0.13741101 0.92828715 0.34554502, + -0.096823975 0.93277377 0.34721491, + -0.094661713 0.92115313 0.37751305, + -0.05609192 0.92385137 0.37861913, + -0.054700781 0.91116673 0.40839085, + -0.018042196 0.91238475 0.4089359, + -0.017554196 0.89873677 0.43813688, + 0.016940402 0.89874613 0.43814206, + 0.017434699 0.91241801 0.40888801, + 0.054151393 0.91121787 0.40834993, + 0.055549376 0.92391658 0.37853983, + 0.094167434 0.92123336 0.37744114, + 0.096339621 0.93287224 0.34708509, + 0.13695396 0.92840075 0.3454209, + 0.13974501 0.93883109 0.31475002, + 0.18240601 0.93222815 0.31253603, + 0.18566006 0.94140035 0.28159508, + 0.22957291 0.93246865 0.2789239, + 0.23310994 0.94033277 0.24785894, + 0.2780669 0.92883664 0.24482891, + 0.28167215 0.93533039 0.2140511, + 0.32749501 0.92104203 0.21078099, + 0.33096802 0.92618513 0.18066901, + 0.37727708 0.90896821 0.17731005, + 0.3804481 0.91285324 0.14818303, + 0.42640191 0.89284676 0.14493497, + 0.42914805 0.89563709 0.11690301, + 0.47438699 0.87291199 0.113937, + 0.47662389 0.87478381 0.08708068, + 0.52120394 0.84923488 0.084537394, + 0.52287692 0.8503679 0.058941394, + 0.56653994 0.8220619 0.056979392, + 0.56762367 0.8226366 0.032747284, + 0.60946923 0.79218233 0.031535011, + 0.60990101 0.79236698 0.0132435, + 0.61494774 0.7885437 0.0061695478, + 0.61495811 0.78855717 -0.0020398605, + 0.53474873 0.84499758 0.0047723376, + 0.44939494 0.8933199 0.0048660897, + -0.49540606 0.86862612 0.0078414408, + -0.48140281 0.8762157 0.022300493, + -0.45217714 0.89189333 0.007878473, + -0.452243 0.89186001 0.0078779198, + -0.45225286 0.89188069 -0.0040174085, + -0.4079549 0.91300178 0.00079832383, + 0.29749498 0.95382488 0.041410495, + 0.29666406 0.95236325 0.070672914, + 0.25000608 0.96558934 0.071654424, + 0.24890706 0.96319425 0.10150002, + 0.20238893 0.97391266 0.10262996, + 0.20115498 0.9705019 0.13290098, + 0.15506606 0.97876936 0.13403404, + 0.15384099 0.97428089 0.16464998, + 0.108899 0.98015499 0.16564199, + 0.10783003 0.97453827 0.19659105, + 0.064046904 0.97824115 0.19733803, + 0.063289911 0.97150612 0.22840802, + 0.020644907 0.97325033 0.22881807, + 0.020355895 0.96544278 0.25981894, + -0.020808093 0.96543366 0.25981691, + -0.0210944 0.97326702 0.228706, + -0.063755497 0.97150302 0.228292, + -0.064512469 0.9782505 0.1971399, + -0.10841198 0.97451478 0.19638695, + -0.109482 0.98013002 0.16540501, + -0.15446793 0.97422254 0.16440792, + -0.15569103 0.97869223 0.13387303, + -0.20182504 0.97038525 0.13273703, + -0.203051 0.97376502 0.102723, + -0.249477 0.96303701 0.101592, + -0.2505579 0.96539062 0.072399177, + -0.29713097 0.95216286 0.071407191, + -0.36262313 0.93190533 0.0075487429, + -0.36263201 0.93193102 -0.00160814, + -0.36270192 0.93190378 -0.0016002797, + -0.36269182 0.93187857 0.0075482964, + -0.34486198 0.93836188 0.023391398, + -0.34451583 0.93781751 0.042509783, + -0.29794496 0.95360386 0.043225296, + -0.26955009 0.96295333 0.0079787727, + -0.31635591 0.94805276 0.033389192, + -0.29845685 0.95426154 0.017560693, + -0.29806995 0.95355678 0.043403689, + -0.25155684 0.9668414 0.044008374, + -0.25084287 0.96528655 0.072799161, + -0.20432693 0.97613066 0.073616967, + -0.20341896 0.97363478 0.10322798, + -0.15706305 0.98208421 0.10412402, + -0.15609403 0.97855425 0.13441104, + -0.11075205 0.98460346 0.13524106, + -0.10987103 0.98000222 0.16590405, + -0.065451518 0.98385721 0.16655704, + -0.064809583 0.97815675 0.19750695, + -0.021481005 0.97999126 0.19787805, + -0.021232799 0.97322488 0.22887197, + 0.020692103 0.97323614 0.22887403, + 0.020940792 0.97998863 0.19794893, + 0.064245775 0.97817862 0.19758293, + 0.064886525 0.98386735 0.16671807, + 0.10923205 0.9800455 0.16607007, + 0.11011194 0.98465955 0.13535494, + 0.15543696 0.97864276 0.13452797, + 0.15640901 0.98219413 0.10407201, + 0.20279005 0.97377121 0.10317902, + 0.20371193 0.97630966 0.072944768, + 0.25034797 0.96546489 0.072134495, + 0.25107399 0.96703798 0.042418901, + 0.297791 0.95371401 0.041834399, + 0.29818812 0.95440835 0.013736605, + 0.3135561 0.94955438 0.0054091318, + 0.31353989 0.94955963 0.0054091983, + 0.34461817 0.93853647 0.01969301, + 0.34425992 0.93799078 0.040723089, + 0.39099792 0.92019278 0.019124396, + 0.39061406 0.91970813 0.039467406, + 0.34394217 0.93812746 0.04025792, + 0.34302297 0.93679589 0.068911396, + 0.29624507 0.95253825 0.070069417, + 0.29498398 0.95030689 0.099505387, + 0.24846198 0.96337485 0.10087398, + 0.24698392 0.96014565 0.13084096, + 0.20069891 0.97068155 0.13227694, + 0.19914199 0.96636999 0.162701, + 0.15339802 0.97445011 0.16406101, + 0.15190592 0.9689725 0.19497891, + 0.10746601 0.97467214 0.19612603, + 0.106205 0.96802902 0.227245, + 0.063025087 0.97159976 0.22808294, + 0.062153623 0.96381235 0.25923508, + 0.020241491 0.96548152 0.25968388, + 0.019919006 0.95671624 0.29034007, + -0.020349894 0.95670778 0.29033795, + -0.020668007 0.96548134 0.25965109, + -0.06259279 0.96379387 0.25919798, + -0.063464582 0.97160578 0.22793494, + -0.10669599 0.9680109 0.22709197, + -0.10796095 0.97468054 0.19581191, + -0.15248792 0.9689455 0.19465891, + -0.15397798 0.97440976 0.16375695, + -0.199761 0.96629399 0.162393, + -0.20131491 0.97058654 0.13203794, + -0.24760206 0.96001923 0.13060004, + -0.24906403 0.9632051 0.10101002, + -0.29558694 0.95010579 0.099636078, + -0.29682395 0.95229179 0.070964485, + -0.34342891 0.93658179 0.069793783, + -0.34433091 0.93789774 0.042237289, + -0.39082295 0.91953391 0.041410297, + -0.39119014 0.92001837 0.023165908, + -0.40791091 0.91298878 0.007760718, + -0.40792301 0.91301602 0.00079902902, + -0.40794101 0.91300797 0.00079902902, + -0.40792891 0.91298074 0.0077527082, + -0.40794322 0.91297442 0.0077526039, + -0.43672985 0.89930069 0.022920093, + -0.43634978 0.89887661 0.040244583, + -0.39066491 0.91961175 0.041172989, + -0.38969609 0.91843522 0.067924917, + -0.34308115 0.93674743 0.069279328, + -0.34171498 0.93475491 0.097283788, + -0.29508293 0.95033878 0.098905675, + -0.29340684 0.94737154 0.12806094, + -0.24703901 0.96027201 0.129805, + -0.2451809 0.95621163 0.15982994, + -0.19915208 0.96655947 0.16155908, + -0.197257 0.96130198 0.192323, + -0.15191397 0.96918774 0.19389996, + -0.150149 0.96268803 0.22513799, + -0.10617605 0.9682225 0.2264331, + -0.10471805 0.96050149 0.25782013, + -0.062217623 0.96394038 0.25874308, + -0.061241124 0.95515537 0.2897031, + -0.020222293 0.95675564 0.29018891, + -0.019870399 0.94702387 0.32054797, + 0.019457908 0.94703138 0.32055113, + 0.019815201 0.9567551 0.29021904, + 0.060824901 0.95517099 0.28973901, + 0.061804131 0.96394849 0.25881213, + 0.10427795 0.96052951 0.25789389, + 0.10573395 0.96822053 0.2266479, + 0.14962102 0.96271825 0.22536007, + 0.15138102 0.96919411 0.19428504, + 0.19672297 0.96133387 0.19270997, + 0.19861896 0.96659786 0.16198498, + 0.24453409 0.95630538 0.16026007, + 0.24640597 0.96040487 0.13002498, + 0.29277405 0.94753724 0.12828302, + 0.29446998 0.95054388 0.098761387, + 0.34119189 0.93496066 0.097142264, + 0.34259292 0.93699974 0.068275988, + 0.38926095 0.91869187 0.066941895, + 0.39025599 0.91988301 0.038929898, + 0.43614006 0.89907414 0.038049202, + 0.43653807 0.89949512 0.018523501, + 0.40510505 0.91425711 0.0048975702, + 0.40499693 0.91430485 0.0048981695, + 0.40507194 0.91427189 0.0048649595, + 0.40507707 0.91428214 0.00086408114, + 0.40500176 0.91431546 0.0008640805, + 0.40510982 0.9142676 0.00085881958, + 0.44939715 0.89332527 -0.0034834212, + 0.44708878 0.89448458 -0.0029784087, + 0.44929716 0.89337832 -0.002698411, + 0.44929388 0.89337075 0.004866709, + 0.4812367 0.87641346 0.017622588, + 0.48082593 0.87605387 0.036552098, + 0.43579605 0.89926314 0.037520505, + 0.43474805 0.89822114 0.064753406, + 0.38880306 0.91893613 0.066246808, + 0.3872931 0.91711122 0.094398521, + 0.34060296 0.9352659 0.096267186, + 0.338716 0.93250501 0.125323, + 0.29215601 0.94784898 0.127386, + 0.290007 0.944022 0.157221, + 0.24386895 0.95663178 0.15932195, + 0.24159488 0.95163351 0.18980391, + 0.19605903 0.96165115 0.19180202, + 0.19381592 0.95540154 0.2228079, + 0.14902702 0.96299314 0.22457802, + 0.14699198 0.95547289 0.25586098, + 0.10378502 0.96074909 0.25727403, + 0.10214701 0.95206809 0.28832704, + 0.060469978 0.95532262 0.2893129, + 0.059389908 0.94561213 0.31982902, + 0.019271107 0.94710833 0.32033512, + 0.018879903 0.93642825 0.3503511, + -0.019344697 0.93641979 0.35034791, + -0.019729201 0.94708198 0.32038501, + -0.059829313 0.94556922 0.31987408, + -0.060906116 0.95529824 0.28930205, + -0.10256302 0.95202821 0.28831106, + -0.10420098 0.96073186 0.25716996, + -0.14744608 0.95543247 0.25575113, + -0.14948994 0.96299267 0.22427192, + -0.19429508 0.95537639 0.22249807, + -0.19654408 0.96164238 0.19134907, + -0.24218588 0.9515745 0.18934591, + -0.24446094 0.95656574 0.15881096, + -0.29059616 0.9439255 0.15671207, + -0.29273015 0.94771349 0.12707606, + -0.3393251 0.93232524 0.12501302, + -0.34117991 0.93503278 0.096487381, + -0.38780984 0.91687065 0.094613165, + -0.38928482 0.91865557 0.067300268, + -0.4350999 0.89797574 0.065785289, + -0.43611807 0.89900512 0.039887704, + -0.48101488 0.87585074 0.038860291, + -0.52535719 0.85061628 0.021255607, + -0.52495986 0.8503058 0.037379894, + -0.48079181 0.87598872 0.038508885, + -0.47974494 0.87510985 0.063462794, + -0.4346849 0.89822376 0.065138988, + -0.43313479 0.89666361 0.091589652, + -0.38720709 0.91722023 0.093689419, + -0.38520214 0.91479027 0.12156504, + -0.33861485 0.93272561 0.12394794, + -0.33624092 0.92924976 0.15309097, + -0.28981894 0.94435173 0.15557897, + -0.2872051 0.93969035 0.18572906, + -0.2413521 0.95202035 0.18816608, + -0.23864703 0.94605911 0.21913403, + -0.19348291 0.95579851 0.22138989, + -0.19087192 0.94849163 0.2528469, + -0.14671506 0.95580035 0.2547951, + -0.14441893 0.94726354 0.28606784, + -0.101985 0.952308 0.28759101, + -0.10017604 0.94265634 0.31837711, + -0.059447184 0.94574678 0.31941992, + -0.058269113 0.93506926 0.34964308, + -0.019191109 0.93648839 0.35017318, + -0.018773204 0.92486125 0.37984109, + 0.01830229 0.9248696 0.37984383, + 0.018725796 0.93649673 0.35017592, + 0.057809483 0.93509477 0.34965092, + 0.058996271 0.94579452 0.31936187, + 0.099747062 0.94271964 0.31832388, + 0.10155896 0.95235264 0.2875939, + 0.14400405 0.94732434 0.2860761, + 0.14629506 0.95582336 0.25495008, + 0.19043905 0.94853622 0.25300607, + 0.19303897 0.95580488 0.22174998, + 0.238141 0.94610202 0.21949901, + 0.24083294 0.95204073 0.18872696, + 0.28665206 0.93974823 0.18629004, + 0.28927007 0.94442624 0.15614703, + 0.33565596 0.9293679 0.15365699, + 0.33804888 0.93288064 0.12432496, + 0.38466907 0.91496509 0.12193701, + 0.38671294 0.91744685 0.09351179, + 0.43267301 0.89690399 0.091417998, + 0.43426791 0.89850676 0.064006783, + 0.47942287 0.87536573 0.062358286, + 0.48050305 0.87625211 0.036043406, + 0.52481693 0.85049587 0.034983996, + 0.52524096 0.8507989 0.016224798, + 0.49264288 0.87021881 0.0047161491, + 0.49268889 0.87019283 0.0047158389, + 0.49270025 0.87018639 0.0047114422, + 0.49270499 0.87019598 0.00090223999, + 0.49269405 0.87020212 0.00090224011, + 0.49264812 0.87022817 0.00090428925, + 0.53475302 0.84500402 -0.00272795, + 0.53669024 0.84377342 -0.0031686414, + 0.53467 0.84505397 -0.00344828, + 0.53466719 0.84504932 0.0047729318, + 0.575481 0.81764102 0.0168781, + 0.57556301 0.81775701 0.000868381, + 0.57558411 0.81774217 0.00086838123, + 0.57564992 0.81769586 0.00086539291, + 0.57564193 0.81768388 0.0054238397, + 0.57557613 0.81773019 0.0054243612, + 0.56848007 0.8226561 0.0082113212, + 0.56794357 0.82239443 0.033277277, + 0.52446985 0.8507328 0.034423992, + 0.523377 0.850003 0.059762198, + 0.47892776 0.87569261 0.061568372, + 0.47727683 0.8743217 0.088138469, + 0.43206006 0.89729714 0.090454504, + 0.42990309 0.89511722 0.11810403, + 0.38392305 0.91543114 0.12078501, + 0.38132516 0.91226429 0.14954907, + 0.33484408 0.92986226 0.15243302, + 0.33192489 0.92555863 0.18211794, + 0.28577793 0.94026679 0.18501195, + 0.28267005 0.93469322 0.21551405, + 0.23726504 0.94660813 0.21826203, + 0.23414192 0.93969065 0.24931692, + 0.18954791 0.94903654 0.25179589, + 0.18662108 0.94082046 0.28289515, + 0.14316604 0.94777924 0.28498805, + 0.14062402 0.93831915 0.31588304, + 0.099067159 0.94307452 0.31748384, + 0.097078323 0.93245924 0.3479881, + 0.057309825 0.9353444 0.34906518, + 0.05601928 0.92366463 0.37908486, + 0.018101297 0.92496586 0.37961894, + 0.017643198 0.9123109 0.40911794, + -0.018202797 0.91230178 0.40911391, + -0.018654097 0.92491877 0.37970692, + -0.056563482 0.92359865 0.37916484, + -0.057848193 0.93527991 0.34914896, + -0.097521245 0.93238342 0.34806716, + -0.099505283 0.94300687 0.31754798, + -0.14104892 0.93823552 0.31594184, + -0.14358905 0.94771433 0.28499109, + -0.18704399 0.94073701 0.282893, + -0.18998107 0.94899237 0.25163609, + -0.23458005 0.93962526 0.24915206, + -0.23772509 0.94659233 0.21783008, + -0.28317907 0.93463933 0.21507907, + -0.28629705 0.94022924 0.18439904, + -0.33247003 0.92548311 0.18150702, + -0.33538496 0.92977089 0.15179898, + -0.38190082 0.9121266 0.14891893, + -0.38446805 0.91524911 0.12043002, + -0.43043607 0.89490724 0.11775403, + -0.43255016 0.89703929 0.090668932, + -0.47771394 0.87406188 0.088346392, + -0.47931311 0.87539625 0.062773317, + -0.52366894 0.84973991 0.060933493, + -0.52472579 0.85046673 0.037002586, + -0.56806719 0.82220429 0.035773013, + -0.56861532 0.82251239 0.012252105, + -0.57797605 0.81570512 0.023853503, + -0.57814008 0.8159371 0.00090023311, + -0.57818872 0.81590259 0.00090023258, + -0.57816792 0.81587386 0.0084662689, + -0.57808888 0.81592983 0.0084671881, + -0.57810909 0.8159591 0.0009038311, + -0.61745578 0.78660172 -0.0024770291, + -0.61743212 0.7865712 0.0091277221, + -0.61741489 0.78658479 0.0091279382, + -0.65518671 0.75523764 0.018613791, + -0.64995384 0.75988179 0.011815697, + -0.64945394 0.75971687 0.032247197, + -0.60931498 0.79221499 0.033626601, + -0.60829395 0.79178089 0.055331394, + -0.56633615 0.8221693 0.057455022, + -0.56473297 0.82129586 0.080930389, + -0.52097106 0.84946012 0.083705708, + -0.51875895 0.84794891 0.10895798, + -0.47410589 0.8732878 0.11221397, + -0.47129518 0.87092727 0.13916405, + -0.42599306 0.8933931 0.14275402, + -0.422647 0.88998699 0.171151, + -0.37676305 0.9096421 0.17493102, + -0.37297001 0.90497798 0.204715, + -0.32683203 0.92179209 0.20851903, + -0.32275504 0.91572613 0.23932204, + -0.27733392 0.92955261 0.24293591, + -0.27322087 0.9221006 0.27400887, + -0.2288401 0.9331364 0.27728811, + -0.22489293 0.92430764 0.30834788, + -0.18171801 0.932814 0.31118599, + -0.17813495 0.92265576 0.34201491, + -0.13645598 0.92888188 0.34432298, + -0.13341096 0.91743165 0.37486088, + -0.093884274 0.92161775 0.37657192, + -0.091537498 0.908966 0.40669599, + -0.054193508 0.91145712 0.40781006, + -0.052692987 0.89772874 0.43738592, + -0.017362699 0.89884186 0.43792894, + -0.016838405 0.88411331 0.46696919, + 0.016204607 0.88412243 0.4669742, + 0.016732296 0.89886075 0.43791488, + 0.052086309 0.89776611 0.43738207, + 0.05359422 0.91153628 0.40771216, + 0.091019623 0.90905923 0.40660408, + 0.093370706 0.92170912 0.37647605, + 0.132945 0.91753602 0.374771, + 0.13599901 0.92899513 0.34419802, + 0.17772505 0.92277926 0.3418951, + 0.18131301 0.93293309 0.31106502, + 0.22450392 0.92444062 0.30823287, + 0.22843793 0.93322462 0.27732292, + 0.27282104 0.92220712 0.27404904, + 0.27691898 0.92962289 0.24313997, + 0.32236099 0.915811 0.239528, + 0.32639509 0.92181426 0.20910504, + 0.37250412 0.90503728 0.20530008, + 0.37627894 0.90968591 0.17574298, + 0.42211109 0.89008623 0.17195605, + 0.42548007 0.89352614 0.14345002, + 0.47076106 0.87110615 0.13985102, + 0.47360611 0.87350219 0.11265503, + 0.51832008 0.84816211 0.10938702, + 0.52058691 0.84971482 0.083510078, + 0.56440085 0.8215428 0.080741376, + 0.56606567 0.82244354 0.056180466, + 0.60807776 0.79203171 0.05410308, + 0.60913765 0.79245955 0.030970082, + 0.64938325 0.75988132 0.029696912, + 0.64986819 0.76000416 0.0080649117, + 0.65289772 0.75741565 0.0067943069, + 0.65297985 0.75734484 0.0067935684, + 0.68827194 0.72539496 0.009168529, + 0.68784177 0.72532678 0.02783579, + 0.64908415 0.76015717 0.029172508, + 0.64806622 0.75986731 0.051107418, + 0.60761404 0.79244214 0.053298406, + 0.60598898 0.79176903 0.076675497, + 0.5637427 0.82210457 0.079613164, + 0.56147993 0.82086688 0.10448799, + 0.51752692 0.84881788 0.10804599, + 0.51463193 0.84682089 0.13434398, + 0.46983701 0.87185001 0.13831399, + 0.46634388 0.8688888 0.16599895, + 0.42103791 0.89092976 0.17020896, + 0.41702616 0.88680828 0.19914907, + 0.371333 0.90593702 0.203445, + 0.36692801 0.90048403 0.233436, + 0.3211329 0.91673177 0.23764794, + 0.31653813 0.9098593 0.26825309, + 0.27154407 0.92314023 0.27216905, + 0.26697806 0.91484022 0.30296907, + 0.22323506 0.92534125 0.30644706, + 0.21888289 0.9155826 0.33734086, + 0.17653091 0.9235996 0.34029484, + 0.17259505 0.91241729 0.37108713, + 0.13190401 0.91822499 0.373449, + 0.12858702 0.90572923 0.4038811, + 0.090183958 0.90958959 0.40560281, + 0.087640606 0.89585012 0.43562806, + 0.051508989 0.89811677 0.43672991, + 0.04988908 0.88325369 0.46623382, + 0.016000705 0.88424128 0.46675617, + 0.015439092 0.8684566 0.49552476, + -0.016107501 0.86844712 0.49552006, + -0.016666496 0.88421375 0.46678489, + -0.050547607 0.88320613 0.46625307, + -0.052162692 0.8980509 0.43678793, + -0.08822722 0.89576823 0.43567809, + -0.090756558 0.90946257 0.40575981, + -0.12910798 0.90558785 0.40403193, + -0.13241903 0.91808826 0.37360308, + -0.17308001 0.91226614 0.37123302, + -0.17700395 0.92343378 0.34049892, + -0.21930607 0.91540825 0.33753908, + -0.22365786 0.92518544 0.30660883, + -0.26734212 0.91468143 0.30312714, + -0.27193287 0.9230426 0.27211189, + -0.31689811 0.9097513 0.26819408, + -0.32151192 0.91665876 0.23741694, + -0.36734211 0.90037632 0.23320009, + -0.37179092 0.90588379 0.20284496, + -0.4175089 0.88671476 0.19855295, + -0.421545 0.89085299 0.16935401, + -0.46684694 0.86877888 0.16515799, + -0.47031882 0.87171268 0.13753995, + -0.51512587 0.84664083 0.13358396, + -0.51797479 0.84859771 0.10762896, + -0.56191564 0.82062054 0.10408094, + -0.56411684 0.8218227 0.079872169, + -0.60631174 0.79149771 0.076924868, + -0.60787499 0.792153 0.054604199, + -0.64823818 0.75963515 0.05236261, + -0.64921796 0.75993586 0.031833895, + -0.68790078 0.72516876 0.030377489, + -0.72607285 0.68749779 0.012846397, + -0.72517818 0.68846315 0.011628103, + -0.72476107 0.68841308 0.028440204, + -0.687675 0.72539997 0.0299682, + -0.68675268 0.72522163 0.049238779, + -0.64781392 0.76004887 0.051603392, + -0.64631426 0.75959629 0.072742522, + -0.60570592 0.79206491 0.075851895, + -0.60355514 0.79116219 0.098911621, + -0.56111681 0.82134271 0.10268496, + -0.55827487 0.81978184 0.12761997, + -0.51416594 0.84748286 0.13193199, + -0.5106312 0.84503531 0.15865406, + -0.46573982 0.8697257 0.16328993, + -0.46154588 0.86615282 0.19171496, + -0.41626093 0.88775885 0.19649696, + -0.41152105 0.88286114 0.22628903, + -0.36600202 0.9014731 0.23106003, + -0.36094704 0.89517111 0.26150703, + -0.31552801 0.91084599 0.26608601, + -0.31035784 0.90306157 0.29691386, + -0.26595911 0.91575742 0.30108815, + -0.26089504 0.90649313 0.33197004, + -0.21793504 0.91644323 0.3356131, + -0.21315607 0.90565932 0.36653212, + -0.17183501 0.91317499 0.369573, + -0.16755992 0.90095758 0.40024883, + -0.12800997 0.90635973 0.40264791, + -0.12443103 0.89279723 0.43293208, + -0.087363467 0.89634973 0.43465486, + -0.084635369 0.88152069 0.46449783, + -0.049949691 0.88359088 0.46558794, + -0.048224088 0.86767185 0.49479288, + -0.0159047 0.86857301 0.49530599, + -0.015316902 0.8519581 0.52338606, + 0.0145954 0.85196698 0.52339202, + 0.015185894 0.86861271 0.49525881, + 0.0475333 0.86773098 0.49475601, + 0.049261 0.88365698 0.465536, + 0.083978109 0.8816061 0.46445507, + 0.086716905 0.89647114 0.43453407, + 0.12384898 0.89293289 0.43281895, + 0.12744203 0.90653223 0.4024401, + 0.16701598 0.90114689 0.40004995, + 0.17129607 0.91336441 0.36935517, + 0.21274504 0.90584421 0.36631408, + 0.21752195 0.91660875 0.33542892, + 0.26052907 0.90666425 0.33179009, + 0.26559392 0.91591573 0.30092889, + 0.31001914 0.9032284 0.29676014, + 0.31516087 0.91095871 0.26613492, + 0.36060402 0.89529413 0.26155904, + 0.36562589 0.9015497 0.2313569, + 0.41113886 0.8829627 0.22658692, + 0.4158282 0.88781041 0.19717909, + 0.46111879 0.86623156 0.19238591, + 0.46528894 0.86979187 0.16421999, + 0.51014411 0.84515721 0.15956904, + 0.5137049 0.84763479 0.13274997, + 0.55780387 0.81997782 0.12841797, + 0.56069577 0.82157558 0.10311995, + 0.60317004 0.79140311 0.099333115, + 0.60538387 0.79233479 0.075604886, + 0.64605695 0.75983787 0.072503991, + 0.64761996 0.76030087 0.050308693, + 0.68660098 0.72544801 0.0480025, + 0.68756157 0.72561157 0.027328683, + 0.72473085 0.6885438 0.025932595, + 0.72513008 0.68856108 0.0083606811, + 0.72400337 0.68979633 0.00058712129, + 0.72397494 0.68976897 0.0088961991, + 0.7568838 0.65353084 0.0049224086, + 0.75689316 0.65353817 -0.00088712922, + 0.75690609 0.65352309 -0.00088794914, + 0.75689769 0.65351474 0.0049222582, + 0.75972337 0.65017432 0.0096867746, + 0.75939471 0.65018678 0.024014091, + 0.72446883 0.68883783 0.025441594, + 0.72357798 0.68878698 0.044805199, + 0.68617672 0.72590065 0.047219478, + 0.68470085 0.72563183 0.068140686, + 0.64545703 0.76045102 0.071410403, + 0.64332426 0.75980431 0.093975239, + 0.60241675 0.79214573 0.097975262, + 0.59957832 0.79093534 0.12217706, + 0.55689281 0.8208487 0.12679796, + 0.55334079 0.81886768 0.15254395, + 0.509036 0.84618801 0.15763301, + 0.50477624 0.8432014 0.18496609, + 0.45987794 0.86735886 0.19026497, + 0.45497885 0.8631447 0.21903293, + 0.40980214 0.88415128 0.22436307, + 0.40444085 0.87857169 0.2540459, + 0.35916513 0.89654529 0.2592431, + 0.35352808 0.88948321 0.28954706, + 0.30851504 0.90450311 0.29443604, + 0.30279705 0.89586127 0.32518709, + 0.25901899 0.90790898 0.329561, + 0.25343806 0.89766622 0.36050609, + 0.2112799 0.90701461 0.36425981, + 0.20605704 0.89519322 0.39518309, + 0.16567302 0.90218312 0.39826906, + 0.16102694 0.8888607 0.42894885, + 0.12266403 0.89381224 0.43133909, + 0.11878798 0.8790679 0.46165895, + 0.08302968 0.88227975 0.46334487, + 0.080101028 0.86630332 0.49305418, + 0.046933591 0.8681379 0.49409893, + 0.045121379 0.8513366 0.52267575, + 0.014365993 0.85211658 0.52315474, + 0.013754196 0.83475882 0.55044389, + -0.01445619 0.83475041 0.55043858, + -0.015068596 0.8521198 0.52312988, + -0.045783985 0.85132271 0.52264082, + -0.047592491 0.86810088 0.49410093, + -0.08078292 0.86624515 0.49304512, + -0.083700627 0.88218528 0.46340418, + -0.11937697 0.87896079 0.46171087, + -0.12324195 0.89367968 0.43144885, + -0.16155596 0.88871479 0.42905191, + -0.16618904 0.90201622 0.39843208, + -0.20649503 0.89502209 0.39534205, + -0.21170105 0.90682322 0.36449209, + -0.25385109 0.89746028 0.36072811, + -0.25942397 0.90770686 0.32979897, + -0.30311999 0.895666 0.32542399, + -0.30885088 0.90433973 0.29458588, + -0.35384911 0.88930929 0.28968909, + -0.35951498 0.8964169 0.25920197, + -0.4047671 0.87843424 0.25400206, + -0.41017106 0.88406211 0.22404003, + -0.45534316 0.86303431 0.21871108, + -0.46029401 0.86729002 0.18957201, + -0.50524014 0.8430742 0.18427804, + -0.50952113 0.84606719 0.15671204, + -0.55379015 0.81873029 0.15164806, + -0.55732417 0.82069027 0.12592605, + -0.59999233 0.79075146 0.12133207, + -0.60277623 0.79193032 0.097505137, + -0.64366704 0.75957012 0.09352091, + -0.64573067 0.76019365 0.07167656, + -0.68495101 0.72537202 0.068393402, + -0.68636394 0.72563791 0.048520893, + -0.72369421 0.6885832 0.04604321, + -0.7245478 0.68865383 0.028040692, + -0.75941765 0.65006471 0.026469488, + -0.78998929 0.61305821 0.0087497225, + -0.78987688 0.61320293 0.0087520191, + -0.75977254 0.6500746 0.012193393, + -0.75899518 0.65109515 -0.0012353504, + -0.75895232 0.65105826 0.010710103, + -0.72605217 0.68754816 0.011217403, + -0.72609794 0.68759096 0.00071084691, + -0.72613198 0.68755502 0.00071084697, + -0.69793826 0.71614921 -0.0035350011, + -0.69157004 0.72229505 -0.0045597306, + -0.69154221 0.72226518 0.010117003, + -0.691531 0.72227597 0.0101172, + -0.69156498 0.72231197 -0.00182327, + -0.65532696 0.75534487 0.00083642389, + -0.65529728 0.75531036 0.0095797544, + -0.65522128 0.75537634 0.0095808245, + -0.65525085 0.75541085 0.00084023684, + -0.6553002 0.75536817 0.00084023719, + -0.61743623 0.78661227 -0.0037215315, + -0.62061208 0.78411114 -0.0032478406, + -0.53669071 0.84377354 -0.0030425582, + -0.53741723 0.84331143 -0.0029418613, + -0.53741723 0.84331042 -0.0032080116, + -0.49550095 0.86860687 0.00087998086, + -0.49548611 0.86858016 0.0078697316, + -0.49533206 0.86866814 0.0078711808, + -0.49534687 0.86869484 0.00088685675, + -0.49542081 0.8686527 0.00088685669, + -0.45218995 0.8919189 -0.0022392597, + -0.44708893 0.89448488 -0.0028866297, + -0.35275099 0.93571001 -0.00369044, + -0.31648988 0.94859564 0.00064875977, + -0.31648111 0.94856733 0.0077328426, + -0.31656989 0.94853765 0.0077323574, + -0.31657898 0.9485659 0.00064350793, + -0.31653312 0.94858134 0.00064350822, + -0.26955789 0.96298355 -0.0010472095, + -0.26964295 0.96295977 -0.0010392098, + -0.26963395 0.96292979 0.0079783881, + -0.25196004 0.96745414 0.023424102, + -0.25167802 0.96680212 0.044179402, + -0.20515388 0.97770941 0.044677775, + -0.20455295 0.97605973 0.073928282, + -0.15806802 0.98460811 0.074575707, + -0.15734993 0.98199755 0.10450695, + -0.11171403 0.98816025 0.10516302, + -0.11101596 0.98452663 0.13558295, + -0.066237673 0.98847455 0.13612694, + -0.065707996 0.98378599 0.166876, + -0.021765901 0.98568302 0.167198, + -0.021553598 0.97997189 0.19796596, + 0.020956609 0.97998446 0.1979681, + 0.021167509 0.98569047 0.16723107, + 0.065044232 0.98382348 0.16691507, + 0.065571912 0.98850322 0.13624203, + 0.11037997 0.98458177 0.13570197, + 0.11107899 0.9882369 0.10511498, + 0.15670295 0.98210573 0.10446298, + 0.15742791 0.9847514 0.074034058, + 0.20403707 0.97620833 0.073391832, + 0.20464399 0.97787702 0.0433295, + 0.25137806 0.96694022 0.04284491, + 0.21895297 0.9757129 0.006636139, + 0.21905406 0.97569025 0.0066358312, + 0.25166804 0.96759814 0.020425502, + 0.26654693 0.96380275 0.0060785688, + 0.26655096 0.96381986 -0.0014030599, + 0.26655796 0.96381789 -0.0014024499, + 0.26655304 0.96380115 0.0060785408, + 0.31341404 0.94922709 0.027198303, + 0.31353 0.94957799 0.00075268501, + 0.3135609 0.94956774 0.00075268483, + 0.31354412 0.94957334 0.00075365527, + 0.35970801 0.93305498 -0.0043090298, + 0.35970712 0.93305236 0.004908042, + 0.35968703 0.93306011 0.0049081403, + 0.35968992 0.93306977 -0.0020112596, + 0.35275191 0.93571275 -0.0027916294, + 0.31498501 -0.94896299 -0.015926201, + 0.3150129 -0.94895375 -0.015925996, + 0.31505296 -0.9490729 -0.0014993898, + 0.31502384 -0.94908249 -0.0015023493, + 0.26806888 -0.96339953 0.0006180167, + 0.30412197 -0.95262587 -0.0037217496, + 0.72514898 -0.68851799 -0.0100985, + 0.72427517 -0.68867117 -0.034023609, + 0.96920878 -0.21673095 -0.11688497, + 0.94887286 -0.27782997 -0.14983599, + 0.95112699 -0.27414799 -0.14212801, + 0.93120956 -0.32358384 -0.16775693, + 0.93804562 -0.31440988 -0.14565995, + 0.91756213 -0.36075804 -0.16713302, + 0.92430198 -0.35294899 -0.145234, + 0.90302414 -0.39727107 -0.16347201, + 0.90951276 -0.3907519 -0.14177297, + 0.8872267 -0.43367186 -0.15734494, + 0.8933894 -0.42831022 -0.13566805, + 0.87012947 -0.46981773 -0.14881492, + 0.87588429 -0.46550018 -0.12702905, + 0.85140544 -0.5060057 -0.13808291, + 0.85660613 -0.50267404 -0.11638202, + 0.83051503 -0.542642 -0.125636, + 0.83511919 -0.54017115 -0.10388003, + 0.80712229 -0.57976121 -0.11149304, + 0.81109589 -0.57802796 -0.089482091, + 0.7814402 -0.61663514 -0.09545882, + 0.78473413 -0.61551607 -0.073023006, + 0.7532078 -0.65320182 -0.077494085, + 0.75576669 -0.65257174 -0.054467283, + 0.72195566 -0.68954164 -0.057552975, + 0.72372103 -0.68926698 -0.0337479, + 0.68743497 -0.72537702 -0.035515901, + 0.68833679 -0.72531074 -0.010804696, + 0.69035375 -0.72340274 -0.010016397, + 0.65416616 -0.75625819 -0.011843903, + 0.65405083 -0.75635785 -0.011845397, + 0.65409607 -0.75640911 -0.0019316502, + 0.61611992 -0.7876519 0.0008625589, + 0.97043288 -0.21691997 -0.10585698, + 0.95138776 -0.27679595 -0.13507497, + 0.94978487 -0.27960896 -0.14045498, + 0.92808264 -0.33275187 -0.16714895, + 0.92550886 -0.33616897 -0.17442398, + 0.9001469 -0.38663995 -0.20061196, + 0.90363085 -0.38296995 -0.19179498, + 0.87905771 -0.42624885 -0.21346992, + 0.88952512 -0.41690806 -0.18690301, + 0.86466527 -0.45839217 -0.20550108, + 0.8743127 -0.45083585 -0.17978995, + 0.8491295 -0.49061128 -0.19565211, + 0.85792118 -0.48461413 -0.17064704, + 0.83206683 -0.52318686 -0.18422896, + 0.84003448 -0.51851028 -0.15965308, + 0.8129788 -0.55650985 -0.17135395, + 0.820153 -0.55295902 -0.14692, + 0.79162401 -0.59052002 -0.1569, + 0.79790819 -0.58797711 -0.13276103, + 0.76803488 -0.62468195 -0.14104898, + 0.7734431 -0.62297308 -0.11700601, + 0.74202025 -0.65885723 -0.12374604, + 0.74655795 -0.65782297 -0.099600486, + 0.713117 -0.69314498 -0.104949, + 0.71678323 -0.69263625 -0.080478832, + 0.6811558 -0.72724581 -0.084500179, + 0.68393403 -0.72711205 -0.059517507, + 0.64652705 -0.76034814 -0.062238008, + 0.64838904 -0.76042813 -0.036616106, + 0.60914612 -0.79214019 -0.038143106, + 0.61006665 -0.79225951 -0.011976892, + 0.57689065 -0.81681353 -0.003568738, + 0.57941288 -0.81502783 -0.0032060493, + 0.53616232 -0.84411448 0.00089678151, + 0.57684064 -0.81685251 -0.0026019984, + 0.57679188 -0.81678283 -0.013306097, + 0.57684338 -0.81674647 -0.013305509, + 0.61618006 -0.78754413 -0.0098191611, + 0.61620969 -0.78758162 0.00085813162, + 0.61621308 -0.78757912 0.00085813215, + 0.61616486 -0.78751683 -0.012575197, + 0.61607111 -0.78759021 -0.012576303, + 0.64995426 -0.75990528 -0.010174904, + 0.64900196 -0.75989187 -0.036888596, + 0.6868487 -0.72594565 -0.03524068, + 0.68502182 -0.72604781 -0.059997983, + 0.72092897 -0.69065493 -0.057073291, + 0.71824205 -0.69104904 -0.081114404, + 0.75184232 -0.65484726 -0.076865129, + 0.74833983 -0.65567982 -0.10035698, + 0.77979064 -0.61883372 -0.094717756, + 0.77550668 -0.62024277 -0.11784796, + 0.80523884 -0.58252889 -0.11068197, + 0.80020016 -0.58465409 -0.13363902, + 0.82844609 -0.54598707 -0.12480102, + 0.8226673 -0.54897618 -0.14779606, + 0.84920168 -0.50991285 -0.13727896, + 0.8427031 -0.51391107 -0.16045901, + 0.8678118 -0.47431087 -0.14809397, + 0.86070585 -0.47941193 -0.17131698, + 0.88484573 -0.43871388 -0.15677395, + 0.87715787 -0.44508794 -0.18025199, + 0.90064102 -0.402787 -0.163121, + 0.8924067 -0.41062185 -0.18708295, + 0.915214 -0.36670199 -0.167072, + 0.90652514 -0.37616307 -0.19160803, + 0.92892259 -0.32993686 -0.16806093, + 0.92602998 -0.333689 -0.17640901, + 0.94849354 -0.28006789 -0.14806093, + 0.95017052 -0.27727389 -0.14246093, + 0.96870351 -0.22078389 -0.11343694, + 0.97049886 -0.21662797 -0.10584999, + 0.98358887 -0.16210699 -0.079209991, + 0.98448765 -0.15899594 -0.074190967, + 0.99425888 -0.096964188 -0.045245696, + 0.99929613 0.034135103 0.015559702, + 0.99934113 -0.033025105 -0.015053702, + 0.99931121 -0.033567008 -0.015824703, + 0.99435622 -0.095963322 -0.04524051, + 0.99386775 -0.098780274 -0.04969329, + 0.98443353 -0.15700893 -0.078986064, + 0.98304635 -0.16147006 -0.086874932, + 0.96906662 -0.21733892 -0.11693396, + 0.96977377 -0.21580395 -0.11387497, + 0.95275146 -0.26864412 -0.14175707, + 0.95773876 -0.26019993 -0.12260697, + 0.939834 -0.30904099 -0.145622, + 0.94506311 -0.30157602 -0.12612602, + 0.92619574 -0.34784693 -0.14547797, + 0.93144763 -0.34142789 -0.12582596, + 0.91147572 -0.38597786 -0.14224295, + 0.91663313 -0.38054907 -0.12233602, + 0.89535159 -0.4239898 -0.13630193, + 0.90030074 -0.41949892 -0.11609997, + 0.87780714 -0.46166006 -0.12776801, + 0.8823787 -0.45809785 -0.10749096, + 0.85844469 -0.49934381 -0.11716896, + 0.86256689 -0.49661294 -0.096715488, + 0.83681411 -0.53739107 -0.10465702, + 0.84042668 -0.53539383 -0.083884068, + 0.81261939 -0.57577056 -0.090210035, + 0.81566328 -0.57440621 -0.068927221, + 0.78602165 -0.6137957 -0.073653765, + 0.78842288 -0.61295694 -0.051701292, + 0.75672972 -0.65141475 -0.054945081, + 0.75840813 -0.65098608 -0.032161705, + 0.75792032 -0.65227026 -0.010024304, + 0.75978845 -0.65010542 -0.0092027253, + 0.75894821 -0.65034217 -0.032448009, + 0.79087687 -0.61121494 -0.030495796, + 0.78930587 -0.61177993 -0.052169394, + 0.81903082 -0.57167488 -0.048749387, + 0.81681788 -0.57268995 -0.069532491, + 0.84453332 -0.53159916 -0.064543523, + 0.84177583 -0.53316087 -0.084575579, + 0.86727816 -0.49167612 -0.077994816, + 0.86405969 -0.49386683 -0.097449265, + 0.88755125 -0.45199412 -0.089187026, + 0.88394886 -0.45488995 -0.10821099, + 0.90582657 -0.41214779 -0.098043054, + 0.90191901 -0.41582301 -0.116762, + 0.9223401 -0.37199202 -0.10445502, + 0.91823298 -0.37649599 -0.122878, + 0.93713844 -0.3317368 -0.10826893, + 0.9329946 -0.33703884 -0.12619793, + 0.95052451 -0.29092485 -0.10893095, + 0.94649422 -0.29699007 -0.12627603, + 0.96278012 -0.24873602 -0.10575902, + 0.95901185 -0.25552097 -0.12249599, + 0.97407848 -0.2039821 -0.097788244, + 0.97082454 -0.21123789 -0.11348195, + 0.9842391 -0.15578601 -0.083691508, + 0.98377287 -0.15721798 -0.086448893, + 0.99371302 -0.098104402 -0.0539442, + 0.99419665 -0.095524162 -0.049479581, + 0.99930334 -0.03314051 -0.017166106, + 0.99935454 -0.032263685 -0.015794592, + 0.99927354 0.034228183 0.016756292, + 0.99932063 0.033399887 0.015578494, + 0.99283361 0.10830297 0.050515283, + 0.99327302 0.105746 0.047185201, + 0.97986639 0.18232706 0.081356429, + 0.98061991 0.17970699 0.078038789, + 0.95915973 0.25945693 0.11267097, + 0.96037275 0.25651893 0.10900598, + 0.92985278 0.33862591 0.14389697, + 0.93148023 0.33568108 0.14022402, + 0.89173913 0.41758105 0.17443502, + 0.89355189 0.41503593 0.17120199, + 0.84438211 0.49526006 0.20429502, + 0.84617817 0.49326912 0.20166305, + 0.72095174 0.64175874 0.26148492, + 0.78887498 0.569125 0.23188999, + 0.78798419 0.56990713 0.23299506, + 0.78375602 0.56814098 0.25088301, + 0.78227884 0.56936187 0.25271896, + 0.8416872 0.4935331 0.21906106, + 0.83971184 0.49559987 0.22195694, + 0.8902123 0.41575515 0.18619806, + 0.8881973 0.41843116 0.18979208, + 0.92912787 0.33673796 0.15273799, + 0.92736524 0.33975708 0.15671304, + 0.95890415 0.25764403 0.11883801, + 0.95752615 0.26080203 0.12298802, + 0.97982264 0.18077594 0.085250169, + 0.97863674 0.18464996 0.090412378, + 0.99335039 0.10340104 0.050629418, + 0.99296713 0.10552102 0.053680506, + 0.99932063 0.032849789 0.016711194, + 0.99927288 0.033639196 0.017945997, + 0.99934191 -0.032005195 -0.017074298, + 0.9992919 -0.032800697 -0.018435199, + 0.99399298 -0.095407598 -0.0536227, + 0.99420166 -0.094337061 -0.051608883, + 0.98481148 -0.15232307 -0.083331436, + 0.98658979 -0.14669397 -0.071564488, + 0.97489148 -0.20013508 -0.097635545, + 0.97731948 -0.19437508 -0.084054239, + 0.96379626 -0.24473706 -0.10583302, + 0.96667111 -0.23928203 -0.091055609, + 0.95168579 -0.28699595 -0.10921298, + 0.95484054 -0.28202784 -0.093486652, + 0.93840212 -0.32799503 -0.10872401, + 0.94167554 -0.32363585 -0.092232555, + 0.92365313 -0.36855504 -0.10503402, + 0.92687637 -0.36489511 -0.088044032, + 0.90715259 -0.4090628 -0.098700956, + 0.91021329 -0.40609616 -0.081225626, + 0.88883799 -0.44932199 -0.089871399, + 0.89163989 -0.44701093 -0.071829192, + 0.86846483 -0.48947188 -0.078652076, + 0.87091172 -0.48776883 -0.059953876, + 0.84556991 -0.52987695 -0.06512969, + 0.84756887 -0.52872193 -0.045609295, + 0.81984085 -0.5704729 -0.049210887, + 0.82128519 -0.56979412 -0.028728608, + 0.79138219 -0.61054611 -0.030783208, + 0.79218203 -0.61023098 -0.0081075002, + 0.7890057 -0.61430675 -0.009857906, + 0.78904414 -0.61433607 -0.00080481113, + 0.78896266 -0.61444068 -0.00079953461, + 0.78892469 -0.61441076 -0.0098594865, + 0.7579155 -0.65229142 -0.0089566754, + 0.75794554 -0.65231758 0.00054948067, + 0.75795811 -0.65230304 0.00054948108, + 0.73387504 -0.67927408 -0.0037762704, + 0.75807601 -0.65216601 0.000570192, + 0.75803769 -0.65213376 -0.010022196, + 0.72502905 -0.68864506 -0.010037101, + 0.72506505 -0.68867904 -0.0013364002, + 0.69010597 -0.72370797 0.00075148401, + 0.69006461 -0.72366357 -0.011044693, + 0.69042897 -0.72331601 -0.0110395, + 0.69047081 -0.72335982 0.00073201983, + 0.69038802 -0.72343898 0.00073202001, + 0.6542058 -0.75630385 -0.0043993089, + 0.6601584 -0.75111848 -0.0034790121, + -0.39092395 -0.92032689 -0.013296098, + -0.39014986 -0.91973364 -0.043278184, + -0.43500894 -0.89943087 -0.042322896, + -0.43340319 -0.8984344 -0.070549935, + -0.47693706 -0.87624013 -0.06880711, + -0.47433412 -0.87497318 -0.097103924, + -0.51657581 -0.8510167 -0.094445266, + -0.51285285 -0.84963572 -0.12288696, + -0.55367321 -0.82415831 -0.11920205, + -0.54879105 -0.82285613 -0.14743201, + -0.5875541 -0.79650116 -0.14271003, + -0.58145505 -0.79545414 -0.17077102, + -0.61836475 -0.76838368 -0.16495894, + -0.61095792 -0.76776087 -0.19306397, + -0.64646584 -0.7399078 -0.18605995, + -0.63764334 -0.73989344 -0.21440314, + -0.67185277 -0.71141773 -0.20615193, + -0.66155827 -0.71220535 -0.23474312, + -0.69423926 -0.68357122 -0.22530508, + -0.68232727 -0.68535727 -0.25439113, + -0.71372199 -0.65665299 -0.243737, + -0.69994497 -0.65966398 -0.273716, + -0.7305522 -0.63071716 -0.26170507, + -0.71453059 -0.63526165 -0.29306781, + -0.74483293 -0.60588396 -0.27951497, + -0.739838 -0.607732 -0.28862, + -0.77314889 -0.57289994 -0.27207798, + -0.78173786 -0.56859893 -0.25608796, + -0.81298715 -0.53091908 -0.23911703, + -0.81992388 -0.52622992 -0.22540396, + -0.84906119 -0.48562011 -0.20801005, + -0.85444009 -0.48091406 -0.19660603, + -0.88141876 -0.43721092 -0.17873895, + -0.88539755 -0.4328008 -0.16957192, + -0.90972072 -0.38660586 -0.15147294, + -0.91254956 -0.38266981 -0.14428192, + -0.93413001 -0.33398199 -0.125925, + -0.93595475 -0.33078691 -0.12070097, + -0.95476514 -0.27934504 -0.10193101, + -0.95588863 -0.2768279 -0.09820006, + -0.97184277 -0.22207195 -0.078776576, + -0.97300154 -0.21859489 -0.07405556, + -0.98542202 -0.16113199 -0.054588299, + -0.98609334 -0.15820406 -0.05090582, + -0.99468774 -0.097990975 -0.031530794, + -0.99491578 -0.096285477 -0.029523293, + -0.99940854 -0.032878485 -0.010081295, + -0.99943227 -0.032331806 -0.0094737718, + -0.99939197 0.033461399 0.0098047704, + -0.99941379 0.032957893 0.0092717884, + -0.99422187 0.10333298 0.029069996, + -0.99440587 0.10194199 0.027654996, + -0.98324102 0.175951 0.047732402, + -0.98366851 0.17404991 0.045856178, + -0.96549863 0.2518149 0.066344477, + -0.96608126 0.25002506 0.064610414, + -0.93972498 0.331056 0.085550301, + -0.93998301 0.33046901 0.084983401, + -0.90465027 0.41272616 0.10613704, + -0.91383833 0.39600715 0.089877233, + -0.87248689 0.47651893 0.10814998, + -0.88661557 0.45437279 0.086360253, + -0.8402319 0.53269094 0.10124598, + -0.8540023 0.51372916 0.082234733, + -0.80202717 0.58977914 0.094408222, + -0.81516701 0.57394999 0.078001603, + -0.7575649 0.64681393 0.087903991, + -0.76846951 0.63542062 0.075466454, + -0.70483834 0.70441735 0.083661035, + -0.71204203 0.69800204 0.07608711, + -0.642277 0.76195902 0.083058797, + -0.64322829 0.76125735 0.082126535, + -0.568142 0.818183 0.088267803, + -0.56109124 0.82230741 0.094800942, + -0.48335382 0.86966473 0.10026097, + -0.467114 0.87671798 0.114761, + -0.38999999 0.91302598 0.119514, + -0.36553097 0.92004889 0.14105698, + -0.29294604 0.94508612 0.14489602, + -0.26283097 0.94943488 0.17173599, + -0.19895607 0.96435934 0.17443506, + -0.16857699 0.9646349 0.20263597, + -0.11606397 0.97202677 0.20418896, + -0.092941754 0.96940851 0.22717589, + -0.051495198 0.97233099 0.227861, + -0.030898215 0.96767646 0.25029513, + -0.00021899493 0.96813864 0.25041491, + 0.012556194 0.96389955 0.26596987, + 0.035076015 0.96338248 0.26582712, + 0.032934703 0.9642731 0.26285502, + 0.05122041 0.96353024 0.26265207, + 0.053921383 0.96219462 0.26697192, + 0.066606179 0.96145666 0.26676691, + 0.066420317 0.96156526 0.26642206, + 0.074502103 0.96101499 0.26627001, + 0.073346697 0.96179903 0.26374799, + 0.077411383 0.96150279 0.26366594, + 0.077230334 0.9616465 0.26319513, + 0.068807311 0.96224123 0.26335806, + 0.041004386 0.98326963 0.17748094, + 0.036688898 0.98343486 0.17750998, + -0.027524786 0.99755853 -0.064181872, + -0.020084908 0.99773538 -0.064193323, + -0.074342765 0.94418651 -0.32091284, + -0.055462014 0.94534922 -0.32130808, + -0.096571334 0.8099733 -0.57846117, + -0.067433909 0.8119241 -0.57985508, + -0.089708991 0.62050194 -0.77905691, + -0.053198691 0.62213194 -0.7811029, + -0.017272795 0.62481874 -0.78057867, + -0.053616811 0.62401313 -0.77957219, + -0.040069316 0.81569833 -0.57708818, + -0.067978628 0.8144654 -0.57621628, + -0.038409792 0.94841576 -0.3146939, + -0.055857915 0.94763422 -0.31443509, + -0.013619497 0.99847078 -0.053577289, + -0.019853292 0.99836665 -0.053571682, + 0.032807786 0.98083055 0.19208091, + 0.038008492 0.98064977 0.19204496, + 0.061612114 0.95813626 0.27960506, + 0.070930615 0.95754224 0.27943105, + 0.07179708 0.95670062 0.28207991, + 0.070545204 0.9567861 0.28210604, + 0.072747566 0.95496452 0.28766385, + 0.068117581 0.95527762 0.2877579, + 0.069787376 0.95408565 0.29129091, + 0.061250877 0.95462161 0.29145491, + 0.060966879 0.95479566 0.29094392, + 0.047548912 0.95549321 0.29115605, + 0.050829325 0.95376348 0.29622915, + 0.033951286 0.95444751 0.29644084, + 0.025798414 0.95803648 0.28548315, + 0.0017169998 0.95835388 0.28557798, + -0.012440205 0.96312934 0.26875108, + -0.045589078 0.96220255 0.26849189, + -0.062740587 0.96617079 0.25015494, + -0.105845 0.96263999 0.24924099, + -0.13039695 0.96556455 0.22512589, + -0.18462606 0.95713735 0.22316207, + -0.21132404 0.95705312 0.19847304, + -0.27579197 0.94119185 0.19518398, + -0.29989395 0.93802875 0.17368296, + -0.372008 0.91271597 0.16899601, + -0.38997617 0.90800339 0.15312907, + -0.46628293 0.87231791 0.14711098, + -0.47624907 0.86838412 0.13818802, + -0.55326813 0.82265216 0.13091102, + -0.554986 0.82174599 0.12932201, + -0.63009501 0.76707703 0.120719, + -0.62437695 0.77084988 0.12626898, + -0.69528317 0.70928317 0.11618403, + -0.68442971 0.71786565 0.12737694, + -0.75029087 0.65093994 0.11550198, + -0.73555285 0.66452181 0.13180597, + -0.79655135 0.59301829 0.11762306, + -0.77999002 0.610511 0.137448, + -0.83619869 0.53503484 0.12045495, + -0.81798089 0.55686992 0.14423299, + -0.86952287 0.47811595 0.12383498, + -0.85721409 0.49506906 0.14174202, + -0.90283871 0.41337085 0.11835095, + -0.90307188 0.41297695 0.11794598, + -0.93895334 0.33081713 0.09448114, + -0.93816149 0.33255213 0.096240543, + -0.96519625 0.25121805 0.072702512, + -0.96443754 0.25345287 0.074978463, + -0.98316622 0.17520805 0.051831312, + -0.98269635 0.17720705 0.05390422, + -0.99421978 0.10271697 0.031245392, + -0.99402034 0.10415804 0.032783512, + -0.99939364 0.033213791 0.010453996, + -0.9993695 0.033742685 0.011041895, + -0.99941146 -0.032603815 -0.010669204, + -0.99938512 -0.033178102 -0.011339101, + -0.99472123 -0.09710072 -0.033185609, + -0.99446636 -0.098905034 -0.03541781, + -0.98552525 -0.15960404 -0.057154115, + -0.9849059 -0.16215998 -0.060535993, + -0.9720605 -0.2199069 -0.08209306, + -0.97144365 -0.22166993 -0.084614769, + -0.95514613 -0.27666402 -0.10560702, + -0.953987 -0.27914599 -0.109482, + -0.93471903 -0.33085099 -0.129761, + -0.93274599 -0.33413401 -0.135423, + -0.91053373 -0.38316086 -0.15529394, + -0.90750891 -0.38712993 -0.16296598, + -0.88247412 -0.43351606 -0.18249202, + -0.87819213 -0.43795004 -0.19229802, + -0.85033703 -0.48183599 -0.211568, + -0.84461218 -0.48645711 -0.22358406, + -0.81442028 -0.52725118 -0.24233408, + -0.80702162 -0.53178477 -0.25675088, + -0.77469486 -0.56943893 -0.27493098, + -0.7797907 -0.56703579 -0.26532391, + -0.7503649 -0.59872192 -0.28015098, + -0.76574862 -0.59285969 -0.24929188, + -0.73565596 -0.62439996 -0.26255497, + -0.74898922 -0.62022722 -0.23309509, + -0.71840507 -0.65115803 -0.24471903, + -0.72999793 -0.64834893 -0.21620996, + -0.69855398 -0.67880797 -0.226367, + -0.70865625 -0.67710024 -0.19834708, + -0.67574573 -0.70740765 -0.20722489, + -0.68447071 -0.70660162 -0.17948291, + -0.64994067 -0.7365936 -0.1871019, + -0.65732992 -0.73651195 -0.15958598, + -0.62137663 -0.76574254 -0.1659199, + -0.62751728 -0.76619536 -0.13844407, + -0.59008372 -0.79447663 -0.14355493, + -0.59505296 -0.79528588 -0.11589798, + -0.55567998 -0.82270598 -0.119894, + -0.55951309 -0.82369715 -0.09202192, + -0.51805812 -0.85005718 -0.094966725, + -0.52077079 -0.85104656 -0.067212373, + -0.47791988 -0.87567675 -0.069157586, + -0.47961593 -0.87649786 -0.041473597, + -0.43562716 -0.89912128 -0.042544115, + -0.43645978 -0.89962858 -0.013085893, + -0.4479818 -0.89389557 -0.016220093, + -0.44794786 -0.89391267 -0.016216895, + -0.44800684 -0.89402968 0.00089896563, + -0.44804084 -0.89401269 0.00089896563, + -0.53342992 -0.84584385 0.00088085886, + -0.61373925 -0.78938228 -0.014140205, + -0.61380005 -0.78946114 0.00078709511, + -0.49254277 -0.87028259 -0.0031348085, + -0.57941306 -0.81502712 -0.0033671104, + -0.6601578 -0.75111783 -0.0036883592, + -0.68819636 -0.72552437 0.00061903731, + -0.72253293 -0.69133592 -0.00096510287, + -0.72287405 -0.69097906 -0.00098419411, + -0.72281682 -0.69092381 -0.012657598, + -0.72247505 -0.69128108 -0.012663902, + -0.68814182 -0.72546685 -0.012592797, + -0.96928209 -0.21646303 -0.11677302, + -0.94885153 -0.27786887 -0.14989893, + -0.95141751 -0.27366787 -0.14110492, + -0.93154836 -0.32318711 -0.16663706, + -0.93828279 -0.31410292 -0.14479198, + -0.91783136 -0.36051112 -0.16618507, + -0.92442012 -0.35284704 -0.14472902, + -0.90316522 -0.39718008 -0.16291304, + -0.9095369 -0.39076594 -0.14157899, + -0.88724297 -0.43371299 -0.15714, + -0.89332712 -0.42841807 -0.13573802, + -0.87004346 -0.46995074 -0.14889792, + -0.87574869 -0.46567383 -0.12732695, + -0.85126168 -0.50616181 -0.13839695, + -0.85646313 -0.50283605 -0.11673401, + -0.8303501 -0.54280704 -0.12601301, + -0.83499718 -0.54031813 -0.10409603, + -0.80701184 -0.57987189 -0.11171597, + -0.81105113 -0.57810909 -0.089364409, + -0.78136772 -0.61674577 -0.095336966, + -0.78471279 -0.6156019 -0.072526783, + -0.75311589 -0.65336895 -0.076976292, + -0.75565284 -0.65273482 -0.054093689, + -0.72174525 -0.68979424 -0.057164919, + -0.72344834 -0.68953139 -0.034193214, + -0.68719578 -0.72558075 -0.035980888, + -0.68806601 -0.72553903 -0.0125845, + -0.68804693 -0.72555697 -0.012592098, + -0.68810183 -0.72561383 0.00061903783, + -0.65191603 -0.75827497 -0.0049608299, + -0.65186524 -0.75821632 -0.013414104, + -0.65163499 -0.75841397 -0.0134176, + -0.65169269 -0.75848162 -0.0015307793, + -0.61367404 -0.78955913 0.0007930611, + -0.61361313 -0.78948015 -0.014141904, + -0.6496278 -0.76014882 -0.012545997, + -0.64872295 -0.76010787 -0.037343495, + -0.68654883 -0.72620779 -0.035677992, + -0.68478173 -0.72630566 -0.05961547, + -0.72076362 -0.69085765 -0.056705873, + -0.71810108 -0.69125706 -0.080588311, + -0.75177997 -0.65497798 -0.076358803, + -0.74822325 -0.65583223 -0.10023004, + -0.77971417 -0.61894912 -0.094593525, + -0.77536166 -0.62038171 -0.11807094, + -0.8051039 -0.58267492 -0.11089499, + -0.80001783 -0.58481586 -0.13402197, + -0.82825583 -0.54619086 -0.12517098, + -0.82247633 -0.54917419 -0.14812306, + -0.8490321 -0.51011205 -0.13758701, + -0.8425892 -0.51407212 -0.16054104, + -0.86771232 -0.47446817 -0.14817306, + -0.86068648 -0.47951671 -0.1711209, + -0.88487124 -0.43873611 -0.15656805, + -0.87732112 -0.44500807 -0.17965402, + -0.90079856 -0.40266183 -0.16255893, + -0.89274031 -0.41035816 -0.18606706, + -0.91552889 -0.36635098 -0.16611399, + -0.90696311 -0.37572405 -0.19039303, + -0.9293189 -0.32939997 -0.16691898, + -0.92601013 -0.33370304 -0.17648701, + -0.94847399 -0.28009501 -0.14813501, + -0.95023865 -0.27715391 -0.14223996, + -0.96876436 -0.22062407 -0.11322804, + -0.97056675 -0.21644695 -0.10559798, + -0.98363054 -0.16195093 -0.079011261, + -0.98497391 -0.15724398 -0.071418889, + -0.99398738 -0.09969414 -0.045280114, + -0.8523528 0.49417189 0.17113996, + -0.89904875 0.41373992 0.14328498, + -0.89797503 0.41540599 0.14518499, + -0.93562967 0.33321789 0.11645996, + -0.93443888 0.33560297 0.11914098, + -0.96301967 0.25390592 0.090137668, + -0.96210355 0.25636789 0.092909552, + -0.98203725 0.17739704 0.064290017, + -0.98145187 0.17966299 0.066883489, + -0.99380749 0.10413405 0.038766317, + -0.99356174 0.10574298 0.040662788, + -0.99934685 0.033728395 0.012969998, + -0.99931645 0.034332115 0.013710206, + -0.99936289 -0.033146396 -0.013236698, + -0.99931246 -0.034125116 -0.014497707, + -0.99445379 -0.096801177 -0.041125089, + -0.99431491 -0.098252185 -0.041041795, + -0.98485965 -0.15995894 -0.066817977, + -0.98404121 -0.16302705 -0.071309917, + -0.97169524 -0.21643804 -0.094672821, + -0.97140813 -0.21774803 -0.094615512, + -0.95352525 -0.27635205 -0.12008003, + -0.95215279 -0.27902395 -0.12470197, + -0.93180442 -0.33137214 -0.14809808, + -0.92949736 -0.33481613 -0.15470307, + -0.9059031 -0.38443205 -0.17762801, + -0.90244913 -0.38843307 -0.18629402, + -0.87560397 -0.43553001 -0.20888101, + -0.87063581 -0.43997788 -0.22002894, + -0.84072286 -0.48428395 -0.24218597, + -0.84561759 -0.48079377 -0.23187989, + -0.81806773 -0.51802284 -0.24983491, + -0.83139479 -0.50999087 -0.22066294, + -0.80379981 -0.54598391 -0.23623595, + -0.81555986 -0.53982693 -0.20844397, + -0.78728515 -0.57519811 -0.22210206, + -0.79771829 -0.57057118 -0.19517708, + -0.7683838 -0.60554087 -0.20713896, + -0.77765316 -0.60217911 -0.18065405, + -0.74743617 -0.63631618 -0.19089505, + -0.755584 -0.63401598 -0.164671, + -0.72412062 -0.66752571 -0.17337491, + -0.73116034 -0.66610628 -0.14733307, + -0.69798702 -0.699211 -0.15465499, + -0.70395398 -0.69850302 -0.128617, + -0.66883278 -0.73112178 -0.13462396, + -0.6737628 -0.73095983 -0.10835798, + -0.63701975 -0.76251471 -0.11303596, + -0.64090729 -0.76272833 -0.086507142, + -0.6024729 -0.79305482 -0.089946575, + -0.60528612 -0.79346919 -0.063523814, + -0.5648421 -0.82256716 -0.065853417, + -0.52513313 -0.85092318 -0.012845003, + -0.5242269 -0.85060179 -0.04077689, + -0.5666461 -0.82301617 -0.039454412, + -0.56826597 -0.82274598 -0.0127606, + -0.56734502 -0.82252097 -0.039736301, + -0.60816097 -0.792889 -0.038304798, + -0.60634291 -0.79262787 -0.063947693, + -0.64522135 -0.76152146 -0.061438136, + -0.64241701 -0.76138902 -0.087104499, + -0.67956519 -0.72886115 -0.083383225, + -0.67573321 -0.72902524 -0.10911804, + -0.71113402 -0.69531101 -0.104072, + -0.70633036 -0.69593638 -0.12949906, + -0.73962915 -0.66165715 -0.12312003, + -0.73388016 -0.66289616 -0.14828603, + -0.76531088 -0.62813693 -0.14051099, + -0.7585997 -0.63014877 -0.16564694, + -0.7886377 -0.59465575 -0.15631694, + -0.78095186 -0.59760696 -0.18160398, + -0.809865 -0.56127298 -0.170562, + -0.80123073 -0.56533283 -0.19603093, + -0.82888812 -0.52854109 -0.18327302, + -0.81928003 -0.53389198 -0.20914, + -0.84599769 -0.49645483 -0.19447492, + -0.83530784 -0.50335389 -0.22112393, + -0.86166871 -0.46461582 -0.20410593, + -0.84973985 -0.47340387 -0.23201494, + -0.87607175 -0.4329769 -0.21220095, + -0.87155384 -0.43689391 -0.22252594, + -0.89940625 -0.38950109 -0.19838704, + -0.90320659 -0.38537982 -0.18894491, + -0.92762214 -0.33538002 -0.16443102, + -0.93007988 -0.33191496 -0.15742898, + -0.95106989 -0.27916598 -0.13240999, + -0.95256275 -0.27640194 -0.12738197, + -0.97003245 -0.22066911 -0.10169705, + -0.97047991 -0.21683197 -0.10560598, + -0.95147073 -0.27666995 -0.13474897, + -0.94984788 -0.27952296 -0.14019999, + -0.92819089 -0.33261096 -0.16682799, + -0.92548335 -0.33620811 -0.17448406, + -0.90012324 -0.38666508 -0.20067005, + -0.90410972 -0.38245484 -0.19056192, + -0.87957656 -0.4258258 -0.2121729, + -0.8898989 -0.41656795 -0.18587899, + -0.86505485 -0.45813689 -0.20442796, + -0.87450081 -0.45070988 -0.17918995, + -0.8492673 -0.49061117 -0.19505307, + -0.85791284 -0.48469788 -0.17045096, + -0.83202714 -0.52331907 -0.18403302, + -0.83991009 -0.51868707 -0.15973401, + -0.81283927 -0.55668819 -0.17143705, + -0.81995344 -0.55316824 -0.14724608, + -0.79140687 -0.59071994 -0.15724199, + -0.79769486 -0.58818191 -0.13313499, + -0.7678358 -0.6248399 -0.14143297, + -0.77329111 -0.62312007 -0.11722802, + -0.74184525 -0.65901023 -0.12398005, + -0.74645418 -0.65795916 -0.099478222, + -0.71298796 -0.69329697 -0.10482098, + -0.71670699 -0.69277298 -0.079979397, + -0.68100917 -0.72744316 -0.083982021, + -0.68376279 -0.72730178 -0.059165079, + -0.64625877 -0.76060569 -0.061874278, + -0.64806408 -0.76068413 -0.037050903, + -0.60884494 -0.79234987 -0.038593296, + -0.60973388 -0.79248685 -0.013755596, + -0.61366773 -0.78946763 -0.012363194, + -0.61371464 -0.78952754 0.00078709354, + -0.57413399 -0.81875098 -0.0041251499, + -0.57407498 -0.81866801 -0.0148535, + -0.57419717 -0.8185823 -0.014852006, + -0.57425892 -0.81867087 -0.0021583198, + -0.53340483 -0.84585971 0.00088199071, + -0.53334081 -0.84575868 -0.015483694, + -0.53336596 -0.84574288 -0.015483499, + -0.53336406 -0.84574413 -0.015483302, + -0.53342801 -0.84584498 0.00088085898, + -0.49130005 -0.87098414 -0.0032999006, + -0.49124011 -0.87087917 -0.015895404, + -0.49121588 -0.87089282 -0.015895596, + -0.49127612 -0.87099916 -0.0028535007, + -0.44800207 -0.89403212 0.00090074411, + -0.447943 -0.893915 -0.016220501, + -0.48114994 -0.87654287 -0.012936899, + -0.48027393 -0.87612587 -0.041717798, + -0.52356714 -0.85102016 -0.040522311, + -0.52180481 -0.85038269 -0.067594275, + -0.56377596 -0.82333088 -0.065443993, + -0.56099278 -0.82262957 -0.092561558, + -0.60095423 -0.79427129 -0.089370728, + -0.59706634 -0.79367048 -0.11661506, + -0.63502425 -0.76428628 -0.11229803, + -0.63003808 -0.76396614 -0.13931201, + -0.66639984 -0.73349881 -0.13375597, + -0.66030198 -0.73363602 -0.16056, + -0.69514102 -0.70225197 -0.15369201, + -0.68787295 -0.70302296 -0.18052599, + -0.72091305 -0.67124808 -0.17236702, + -0.71241796 -0.67283094 -0.19939697, + -0.74389124 -0.64075524 -0.18989107, + -0.73413199 -0.643323 -0.217223, + -0.76455164 -0.61068869 -0.20620389, + -0.7534532 -0.61445212 -0.23400205, + -0.78317463 -0.58108968 -0.22129689, + -0.77052712 -0.58632505 -0.25002202, + -0.79944313 -0.55259806 -0.23564003, + -0.78495491 -0.55963892 -0.26580098, + -0.81345069 -0.52538681 -0.24953291, + -0.80837685 -0.52834886 -0.25956595, + -0.83959615 -0.48755211 -0.23952305, + -0.84580803 -0.48294601 -0.22665399, + -0.87462473 -0.43887186 -0.20596893, + -0.87920141 -0.4344562 -0.19558309, + -0.90510315 -0.38771605 -0.17454101, + -0.90832025 -0.38374409 -0.16641805, + -0.93121123 -0.3343901 -0.14501403, + -0.93334436 -0.33102512 -0.13889104, + -0.95311826 -0.27903205 -0.11707603, + -0.95438474 -0.27644393 -0.11282097, + -0.9710319 -0.22123498 -0.090289392, + -0.97167188 -0.21947996 -0.087648794, + -0.98474348 -0.16160308 -0.064536028, + -0.98501521 -0.16053204 -0.063044615, + -0.99426776 -0.099519581 -0.039083488, + -0.99450254 -0.097943954 -0.03703488, + -0.99935925 -0.033478409 -0.012659003, + -0.99938834 -0.032876212 -0.011921004, + -0.99934465 0.034030888 0.012339695, + -0.99937153 0.033467386 0.011681895, + -0.9938044 0.10493394 0.036627479, + -0.99402052 0.10344595 0.034958586, + -0.98209876 0.17845196 0.060306184, + -0.98262846 0.17630009 0.057961527, + -0.96330464 0.2549839 0.083829872, + -0.96414322 0.25262207 0.081302024, + -0.93639076 0.33408391 0.10751898, + -0.93737614 0.33201703 0.10531201, + -0.90064287 0.41422194 0.13138698, + -0.90147471 0.41287184 0.12992395, + -0.85526019 0.49430212 0.15554903, + -0.85405731 0.49583519 0.15726906, + -0.79811716 0.57430613 0.18215804, + -0.81328082 0.55844986 0.16342595, + -0.75203419 0.63259315 0.18512304, + -0.77400303 0.61258298 0.160192, + -0.70940399 0.68187302 0.178312, + -0.72786683 0.66710579 0.15868096, + -0.6595673 0.73124337 0.17393708, + -0.674793 0.72074902 0.158667, + -0.60269004 0.77931511 0.17156002, + -0.61252022 0.77363729 0.16218606, + -0.53733706 0.82542413 0.17304301, + -0.54093623 0.8237564 0.16974507, + -0.46467105 0.86726213 0.17871001, + -0.46043 0.86873502 0.182493, + -0.38532394 0.90307087 0.18970597, + -0.373281 0.90583003 0.200333, + -0.30200994 0.93081278 0.20585796, + -0.28393915 0.93279743 0.22196311, + -0.21925303 0.94916612 0.22585803, + -0.19779296 0.94897479 0.24561094, + -0.14245002 0.95822811 0.24800603, + -0.12042003 0.95546025 0.26943406, + -0.07561706 0.95970851 0.27063188, + -0.05678568 0.95520866 0.29043391, + -0.021875994 0.95652378 0.29083294, + -0.0102493 0.95250899 0.30433801, + 0.015856102 0.95243913 0.30431604, + 0.024907697 0.94837886 0.31615996, + 0.043052476 0.94779354 0.31596485, + 0.047664218 0.94524336 0.32286713, + 0.060079724 0.94460934 0.32265112, + 0.055919327 0.94730347 0.31541914, + 0.065164424 0.94677138 0.31524211, + 0.063699499 0.947864 0.312244, + 0.068868175 0.94753766 0.31213689, + 0.066174611 0.94987023 0.30556107, + 0.068054691 0.94974989 0.30552197, + 0.065206774 0.95261854 0.29709587, + 0.063908584 0.95269877 0.29712093, + 0.062558785 0.95431876 0.29216793, + 0.052445181 0.95487565 0.29233888, + 0.033246201 0.978405 0.204006, + 0.027142609 0.97858536 0.20404407, + -0.013867798 0.99887788 -0.045283295, + -0.0086326078 0.99893677 -0.045285989, + -0.038923319 0.9499715 -0.30990216, + -0.022541203 0.95045012 -0.31005904, + -0.040451895 0.81704086 -0.57515895, + -0.012934498 0.81764179 -0.57558191, + -0.017355688 0.62513763 -0.78032154, + 0.017959002 0.62513107 -0.78031313, + 0.013405595 0.81723768 -0.57614481, + 0.0409104 0.81662703 -0.57571399, + 0.022939488 0.95024955 -0.31064385, + 0.039448101 0.94976002 -0.31048301, + 0.0089513017 0.99895823 -0.044748113, + 0.014103798 0.99889886 -0.044745497, + -0.027399303 0.97784811 0.20751503, + -0.033823214 0.97765547 0.20747511, + -0.0527656 0.95416498 0.29459301, + -0.06306868 0.95359367 0.29441687, + -0.063852608 0.95264912 0.29729202, + -0.065057188 0.95257479 0.29726893, + -0.067892373 0.9497155 0.30566484, + -0.0661631 0.949826 0.30570099, + -0.06905067 0.94732255 0.31274885, + -0.063997723 0.94764239 0.31285512, + -0.065121189 0.94680375 0.3151539, + -0.055868287 0.94733578 0.31533092, + -0.057495676 0.94629163 0.31816089, + -0.044459514 0.94692236 0.31837311, + -0.046451297 0.94581985 0.32135198, + -0.028981708 0.94644421 0.32156408, + -0.018482296 0.95125377 0.30785495, + 0.0069700992 0.95139289 0.30790097, + 0.022950789 0.95694554 0.28935885, + 0.057976376 0.95558763 0.28894791, + 0.077051304 0.96008509 0.26888603, + 0.12221996 0.95572865 0.26766592, + 0.14378199 0.95837188 0.24667796, + 0.19921793 0.94902265 0.24427091, + 0.22099108 0.94915235 0.22421607, + 0.28577897 0.9326269 0.22031197, + 0.30404797 0.93055588 0.20401096, + 0.37561306 0.90527612 0.19846903, + 0.38750482 0.90250456 0.18795091, + 0.46256718 0.8679623 0.18075706, + 0.46668687 0.8665148 0.17707495, + 0.54284501 0.82282799 0.168147, + 0.53875369 0.8247385 0.17190389, + 0.61381012 0.7728442 0.16108705, + 0.60286123 0.77918732 0.17153905, + 0.67497295 0.72058696 0.15863799, + 0.65849692 0.73191893 0.17514698, + 0.72688407 0.66790307 0.15982802, + 0.70783883 0.68305081 0.18001595, + 0.77270114 0.61381108 0.16176802, + 0.75084299 0.63360697 0.18648601, + 0.81227219 0.55954611 0.16468805, + 0.79707587 0.57535893 0.18339099, + 0.85332841 0.49675024 0.15833507, + 0.85571218 0.49371412 0.15492903, + 0.90175372 0.41242084 0.12941895, + 0.90134889 0.41308093 0.13013199, + 0.93781954 0.33108285 0.10430095, + 0.9366219 0.33360496 0.10699099, + 0.96429265 0.25218692 0.080879569, + 0.96330649 0.25496811 0.083857536, + 0.98261487 0.17636198 0.058004491, + 0.98205489 0.17863499 0.060479794, + 0.99400812 0.10353401 0.035053305, + 0.99377853 0.10511095 0.036821883, + 0.99936914 0.033519104 0.011742202, + 0.99934226 0.034079108 0.012395903, + 0.99938655 -0.032912984 -0.011971794, + 0.99935764 -0.033510089 -0.012703896, + 0.99448562 -0.098063059 -0.037176285, + 0.99426752 -0.099524856 -0.039075881, + 0.98502052 -0.16050893 -0.063019671, + 0.98478836 -0.16142505 -0.064296424, + 0.97175503 -0.21924099 -0.087324701, + 0.97107548 -0.22110711 -0.090133846, + 0.95443135 -0.27635109 -0.11265404, + 0.9530645 -0.27914387 -0.11724594, + 0.93327338 -0.33114311 -0.13908705, + 0.93110287 -0.33456296 -0.14530998, + 0.90819502 -0.383901 -0.166739, + 0.90495741 -0.38789219 -0.17490509, + 0.87902075 -0.43464091 -0.19598396, + 0.87444812 -0.43904507 -0.20634903, + 0.84563172 -0.48307282 -0.22704093, + 0.83968484 -0.4874799 -0.23935895, + 0.8083778 -0.52840286 -0.25945294, + 0.812675 -0.52590102 -0.25097299, + 0.78428888 -0.55990595 -0.26720098, + 0.7989648 -0.55281991 -0.23673894, + 0.77016997 -0.58633697 -0.25109199, + 0.78303897 -0.58104098 -0.22190399, + 0.75330234 -0.61439329 -0.23464112, + 0.76458889 -0.61057794 -0.20639397, + 0.73421317 -0.6431672 -0.21741004, + 0.744075 -0.64057201 -0.189789, + 0.71264744 -0.67262143 -0.19928412, + 0.72119892 -0.67102695 -0.17203198, + 0.68818563 -0.70280564 -0.18017991, + 0.69544774 -0.70203078 -0.15331393, + 0.66056329 -0.73348337 -0.16018207, + 0.66661471 -0.73334461 -0.13353094, + 0.63027519 -0.7638132 -0.13907804, + 0.63519174 -0.76413071 -0.11240796, + 0.59727025 -0.7935003 -0.11672904, + 0.60110825 -0.7941013 -0.089845233, + 0.56129801 -0.82236701 -0.093043201, + 0.56410283 -0.82308167 -0.06576208, + 0.52218199 -0.85012501 -0.067922801, + 0.52399081 -0.85077769 -0.040138286, + 0.48068893 -0.8759169 -0.041324295, + 0.48159483 -0.8763237 -0.011100196, + 0.400455 -0.91631198 -0.00284775, + 0.40648991 -0.91365278 -0.0021228495, + 0.45080405 -0.89249915 -0.014864801, + 0.45085412 -0.89259726 0.00087247923, + 0.49403483 -0.86943573 -0.0033454788, + 0.49398589 -0.86934984 -0.014452997, + 0.49403882 -0.86931968 -0.014452594, + 0.49408889 -0.86940682 -0.0028085292, + 0.49254295 -0.87028289 -0.0030139696, + 0 -0.99999255 -0.003865018, + -0.022946892 -0.99973667 -0.00032012688, + -0.022944095 -0.99961174 -0.015808897, + -0.022567308 -0.99962038 -0.015809005, + -0.022570105 -0.99974525 -0.0003279291, + -0.071928501 -0.99727601 -0.0163341, + -0.071938105 -0.99740911 0.00027063003, + -0.072125964 -0.99739552 0.00027062988, + -0.072117984 -0.99728578 -0.014837096, + -0.066939607 -0.99764311 -0.015077202, + -0.066792309 -0.99671412 -0.045824204, + -0.11193599 -0.9926669 -0.045638096, + -0.11144895 -0.99085754 -0.076028764, + -0.15676393 -0.98474151 -0.07555946, + -0.15573803 -0.98209727 -0.10597502, + -0.20083195 -0.97397178 -0.10509798, + -0.19906695 -0.97055674 -0.13561697, + -0.24320009 -0.96064335 -0.13423204, + -0.24052498 -0.95658386 -0.16460599, + -0.28343898 -0.94509989 -0.16262999, + -0.27968898 -0.9405219 -0.19285397, + -0.32150286 -0.92760861 -0.19020592, + -0.31650412 -0.92263734 -0.22037607, + -0.35701808 -0.90854025 -0.21700904, + -0.35057011 -0.90330732 -0.24725808, + -0.389303 -0.88842797 -0.243185, + -0.38128799 -0.88309801 -0.27341801, + -0.41807708 -0.86777121 -0.26867205, + -0.40830085 -0.86249369 -0.29898989, + -0.44349593 -0.84683686 -0.29356197, + -0.43166301 -0.84172201 -0.324301, + -0.46553394 -0.82585388 -0.31818798, + -0.45135716 -0.82103932 -0.34953013, + -0.48311388 -0.8055948 -0.3429549, + -0.48077404 -0.80504113 -0.34751302, + -0.51557297 -0.78667986 -0.33958697, + -0.5289129 -0.78816283 -0.31472293, + -0.56356388 -0.76717085 -0.30634093, + -0.5762068 -0.76672471 -0.28305292, + -0.61053127 -0.74297935 -0.2742871, + -0.62230867 -0.74086457 -0.25268885, + -0.65547425 -0.71478522 -0.24379408, + -0.66620308 -0.71131009 -0.22407903, + -0.69805992 -0.68295294 -0.21514598, + -0.70770025 -0.67840922 -0.19728507, + -0.73837095 -0.64756894 -0.18831597, + -0.74683279 -0.64227378 -0.17240994, + -0.77623165 -0.60889173 -0.16344793, + -0.78344631 -0.60318524 -0.14959806, + -0.81105328 -0.5677712 -0.14081405, + -0.81819582 -0.56081289 -0.12666696, + -0.84402072 -0.5231328 -0.11815695, + -0.85030168 -0.51568484 -0.10514797, + -0.87444913 -0.47533706 -0.096920513, + -0.87948877 -0.46810988 -0.08586368, + -0.90182686 -0.42500693 -0.077957496, + -0.90570414 -0.41828907 -0.068807304, + -0.92580777 -0.37298191 -0.061354384, + -0.92867702 -0.36694601 -0.0539403, + -0.94641614 -0.31951603 -0.046968207, + -0.94845212 -0.31424803 -0.041072004, + -0.96375978 -0.26452193 -0.034572791, + -0.96507013 -0.26024804 -0.030176304, + -0.97785926 -0.20787105 -0.024103105, + -0.97855538 -0.20488387 -0.021257088, + -0.98849267 -0.15046094 -0.015610694, + -0.98889321 -0.14801903 -0.013439903, + -0.99577826 -0.091415823 -0.0083003817, + -0.99629736 -0.085895531 -0.0036899114, + -0.9995715 -0.029246187 -0.0012563594, + -0.9996295 -0.027220013 0.00034224518, + -0.99960464 0.028113591 -0.00035348089, + -0.99965262 0.026299791 -0.0017085294, + -0.99658149 0.082442738 -0.0053557721, + -0.99695712 0.077442311 -0.0089025414, + -0.99086124 0.13400303 -0.015404603, + -0.9917385 0.12665007 -0.020363109, + -0.98239535 0.18444505 -0.029655412, + -0.98384774 0.17546695 -0.035426393, + -0.97082013 0.23506603 -0.047459606, + -0.97273213 0.22574903 -0.053193409, + -0.95553678 0.28701195 -0.067628786, + -0.95764786 0.27864197 -0.072589591, + -0.93535078 0.3422969 -0.089172281, + -0.93700099 0.33691901 -0.092275597, + -0.90816587 0.40374193 -0.11057699, + -0.90819198 0.40367201 -0.110618, + -0.87107718 0.47368312 -0.12980303, + -0.86706811 0.48231506 -0.12476002, + -0.81972915 0.55450112 -0.14343204, + -0.80838573 0.57379484 -0.13142295, + -0.74888998 0.64596701 -0.147954, + -0.72929096 0.67176896 -0.12985098, + -0.65756524 0.73970526 -0.14298305, + -0.61934209 0.77725512 -0.11086001, + -0.53760183 0.83475071 -0.11906096, + -0.034096196 0.99919689 0.021049798, + -0.0092580002 0.99870402 0.050045699, + -0.00019874895 0.99874675 0.050047889, + -0.082546398 0.99522698 -0.0520523, + -0.070229724 0.99616933 -0.05210162, + -0.22027807 0.94264734 -0.2507861, + -0.20243198 0.94637686 -0.25177798, + -0.31334597 0.84020287 -0.44257593, + -0.33493403 0.8336581 -0.43912807, + -0.57842684 0.7536037 -0.31225589, + 0.36573482 0.89274961 -0.26312789, + 0.39372405 0.88172811 -0.25987902, + 0.27176893 0.94859177 -0.16221996, + 0.35304412 0.91192627 -0.20916608, + 0.35073191 0.91323179 -0.20735195, + 0.90807378 0.38427591 -0.16653496, + 0.91265613 0.37049004 -0.17261502, + 0.94040889 0.30823296 -0.14360899, + 0.94138265 0.30445388 -0.14528096, + 0.96182698 0.24698 -0.117855, + 0.9614411 0.24889003 -0.11698201, + 0.97646689 0.19518296 -0.09173879, + 0.97570425 0.20001504 -0.08941672, + 0.98660177 0.14894097 -0.066583984, + 0.98591441 0.15465692 -0.063670561, + 0.9934091 0.10599201 -0.043635603, + 0.99295264 0.11128096 -0.040763184, + 0.99765712 0.064239509 -0.023531504, + 0.99745935 0.067954622 -0.021376908, + 0.99974185 0.021671299 -0.0068172989, + 0.99971622 0.023064505 -0.0059539913, + 0.99973363 -0.022345593 0.0057684183, + 0.99970376 -0.023869794 0.0047590393, + 0.99743199 -0.070237704 0.0140037, + 0.99711001 -0.075248502 0.0104542, + 0.99235463 -0.12224495 0.016983394, + 0.99133134 -0.13097705 0.010352104, + 0.98375463 -0.17895994 0.014144495, + 0.9814139 -0.19186898 0.0035968795, + 0.97054785 -0.24086598 0.0045153894, + 0.96683449 -0.25527212 -0.0082075335, + 0.95268351 -0.30380684 -0.009768025, + 0.9508695 -0.30922985 -0.014970393, + 0.93439037 -0.35583413 -0.017226605, + 0.93216634 -0.36130211 -0.022953307, + 0.91348624 -0.4060511 -0.025796205, + 0.91015267 -0.41290087 -0.033690188, + 0.88930124 -0.45580712 -0.037191108, + 0.88494223 -0.46333912 -0.046841912, + 0.86226982 -0.50388086 -0.050940689, + 0.85689199 -0.51172501 -0.0622386, + 0.8325001 -0.54997206 -0.066890307, + 0.8260479 -0.55790591 -0.079911195, + 0.79983115 -0.59416109 -0.085104123, + 0.79223502 -0.60197002 -0.099979199, + 0.76426888 -0.63618296 -0.10566098, + 0.7555151 -0.64358705 -0.12244502, + 0.72636783 -0.6751948 -0.12845898, + 0.71704715 -0.68153715 -0.14611803, + 0.68684596 -0.71065396 -0.15235999, + 0.67741108 -0.71564007 -0.17021601, + 0.64571375 -0.74285579 -0.17668894, + 0.63492125 -0.74697721 -0.19723107, + 0.60183132 -0.77216035 -0.2038811, + 0.59025371 -0.77488965 -0.22615589, + 0.55655003 -0.79754102 -0.232767, + 0.5444392 -0.79862529 -0.25648308, + 0.51041198 -0.81874299 -0.26294401, + 0.49787307 -0.81798714 -0.28813103, + 0.46324199 -0.83589101 -0.29443699, + 0.45059013 -0.83314216 -0.32069108, + 0.41552508 -0.84886819 -0.32674408, + 0.40293795 -0.84400189 -0.35397997, + 0.36852902 -0.85727113 -0.35954502, + 0.36931482 -0.85770059 -0.35770983, + 0.33752087 -0.86878872 -0.36233389, + 0.34881184 -0.87659359 -0.33153287, + 0.31501189 -0.88771969 -0.33573988, + 0.32422686 -0.89541459 -0.30513886, + 0.28814697 -0.90640086 -0.30888298, + 0.29548603 -0.91383511 -0.27855602, + 0.25790298 -0.92418885 -0.28171098, + 0.26362804 -0.93129313 -0.25138304, + 0.22439402 -0.94082612 -0.25395602, + 0.22871096 -0.94746691 -0.22360197, + 0.18791603 -0.95592511 -0.22559904, + 0.19100598 -0.96197486 -0.19524597, + 0.14870206 -0.96912235 -0.19669707, + 0.15075497 -0.97447175 -0.16636595, + 0.10772395 -0.98000151 -0.16730992, + 0.10894505 -0.98458147 -0.13685906, + 0.065406106 -0.98835611 -0.13738401, + 0.065992773 -0.99209255 -0.10675795, + 0.022226008 -0.99401438 -0.10696504, + 0.022373108 -0.99682838 -0.076371528, + -0.021810295 -0.99684078 -0.076372482, + -0.021663692 -0.99403065 -0.10692896, + -0.065574601 -0.99212402 -0.106724, + -0.064983569 -0.98838651 -0.13736494, + -0.10855805 -0.98462647 -0.13684306, + -0.10732701 -0.98003513 -0.16736801, + -0.15032202 -0.97452813 -0.16642801, + -0.14825694 -0.96916366 -0.19682893, + -0.19042803 -0.96206111 -0.19538604, + -0.18733506 -0.95601737 -0.22569108, + -0.22811407 -0.94758737 -0.22370107, + -0.22379592 -0.94095367 -0.25401092, + -0.26295996 -0.9314639 -0.25144997, + -0.25724593 -0.92439777 -0.28162593, + -0.29500914 -0.91401744 -0.27846313, + -0.28770706 -0.90663123 -0.30861706, + -0.3238979 -0.89562476 -0.30487093, + -0.31477991 -0.88802677 -0.33514491, + -0.34876683 -0.8768416 -0.33092386, + -0.33753592 -0.86910284 -0.36156592, + -0.36957297 -0.85792089 -0.35691398, + -0.36843288 -0.8573007 -0.35957289, + -0.40304375 -0.84395355 -0.35397479, + -0.41571808 -0.84885716 -0.32652709, + -0.45071584 -0.83315271 -0.32048687, + -0.46343911 -0.83590919 -0.29407507, + -0.49815288 -0.81794882 -0.28775594, + -0.51060385 -0.81869072 -0.26273391, + -0.54471207 -0.79851115 -0.25625902, + -0.55674267 -0.79743254 -0.23267786, + -0.59044111 -0.77477318 -0.22606605, + -0.60184222 -0.7720893 -0.20411807, + -0.63484526 -0.74697626 -0.19747907, + -0.64549083 -0.74292082 -0.17722896, + -0.67720282 -0.71571285 -0.17073795, + -0.68689924 -0.71059626 -0.15238906, + -0.71705961 -0.68151659 -0.14615291, + -0.72662395 -0.67500192 -0.12802398, + -0.75574964 -0.64339072 -0.12202794, + -0.7645489 -0.63593292 -0.10513899, + -0.79253501 -0.601659 -0.099472597, + -0.80012214 -0.59384209 -0.084594809, + -0.82632411 -0.55756605 -0.079427205, + -0.83274871 -0.54964983 -0.066442378, + -0.85713327 -0.51137221 -0.061815321, + -0.86240572 -0.5036698 -0.050726082, + -0.88506532 -0.46312419 -0.046642516, + -0.88929021 -0.45582113 -0.037284307, + -0.91014773 -0.41290486 -0.033773988, + -0.91336524 -0.4063001 -0.026157705, + -0.93205315 -0.36157304 -0.023278102, + -0.93421662 -0.35626587 -0.017719094, + -0.95072037 -0.30966711 -0.015401506, + -0.95262879 -0.30397293 -0.0099383472, + -0.96679312 -0.25542402 -0.0083510308, + -0.97066653 -0.24037889 0.0049355575, + -0.98149562 -0.19144392 0.0039307987, + -0.98383963 -0.17846094 0.014533695, + -0.99137902 -0.130593 0.0106353, + -0.99238563 -0.12196495 0.017187195, + -0.99712187 -0.075073496 0.010579299, + -0.99743533 -0.070181325 0.014046105, + -0.99970412 -0.023850504 0.0047734305, + -0.99973339 -0.022358088 0.0057621268, + -0.9997161 0.023075702 -0.0059470609, + -0.99974149 0.021693088 -0.0068037766, + -0.99745524 0.068028614 -0.021336306, + -0.99765146 0.06434983 -0.023469811, + -0.99293464 0.11147896 -0.040658984, + -0.99339163 0.10620096 -0.043525387, + -0.985874 0.15497801 -0.063516296, + -0.98656267 0.14927094 -0.066425778, + -0.97563291 0.20045698 -0.089204095, + -0.97640097 0.195608 -0.091535099, + -0.96131355 0.24949089 -0.11674995, + -0.96163476 0.24790794 -0.11747397, + -0.94110024 0.30555806 -0.14479204, + -0.94003779 0.30965495 -0.14297797, + -0.91213256 0.37214082 -0.17182992, + -0.90875179 0.38231692 -0.16734396, + -0.87121218 0.44971311 -0.19684404, + -0.85986698 0.47589099 -0.184815, + -0.80956918 0.54720813 -0.21251105, + -0.79495728 0.5729422 -0.19945008, + -0.731121 0.64432299 -0.224299, + -0.71846706 0.66180307 -0.21406002, + -0.64320076 0.72853577 -0.23564491, + -0.59456897 0.77915287 -0.19851597, + -0.50901818 0.83410829 -0.21251808, + -0.46100616 0.86974531 -0.17611507, + -0.37552986 0.90837473 -0.18393694, + -0.25444698 0.9547829 -0.15377398, + -0.25023508 0.95646936 -0.15016305, + -0.32824212 0.93316334 -0.14650406, + -0.35592782 0.90852058 -0.21887389, + -0.29175103 0.94173312 -0.16739202, + -0.26572502 0.94917113 -0.16871402, + -0.33962786 0.90489757 -0.25654089, + -0.36675599 0.89504302 -0.253748, + -0.65118468 0.0048747975 -0.75890362, + -0.7863791 0.014793701 -0.61756706, + -0.72249722 0.018503608 -0.69112623, + -0.71608293 0.014194098 -0.69787097, + -0.4050681 0.0007034922 0.91428626, + -0.40576708 0.00070553017 0.91397625, + -0.39207184 -0.013488995 0.91983563, + -0.39207277 -0.012701993 0.91984648, + -0.36056811 0.0021624607 0.93273038, + -0.36024091 0.0021617794 0.93285674, + -0.36024004 0.0032117004 0.93285412, + -0.36056709 0.0033893208 0.93272722, + -0.30016693 -0.0094554182 0.95383978, + -0.17918591 0.012979894 0.98372954, + -0.27953911 0.012537706 0.96005249, + -0.267423 0.00542454 0.96356398, + -0.26742604 -0.0020850303 0.96357614, + -0.26725093 -0.0020853092 0.96362466, + -0.26719192 0.021127593 0.96341163, + -0.31420189 -0.0021752494 0.94935364, + -0.31420103 0.0031965806 0.94935113, + -0.3135969 0.0031957694 0.94955075, + -0.31359816 -0.0021204809 0.94955349, + -0.31493708 -0.0021205305 0.94911021, + -0.31493613 0.0029298612 0.94910836, + -0.34590092 -0.011486597 0.93820077, + -0.34589982 -0.013757894 0.93817055, + -0.78285486 -0.19761397 0.58998895, + -0.78256762 -0.17089193 0.59865171, + -0.74672216 -0.18257704 0.63958716, + -0.74571025 -0.14667006 0.64992625, + -0.70710981 -0.15565898 0.68975782, + -0.70531917 -0.11820603 0.69896519, + -0.66412097 -0.124665 0.737158, + -0.66154701 -0.0855662 0.74500602, + -0.61758411 -0.089742519 0.7813682, + -0.61431199 -0.049660798 0.78749901, + -0.56785607 -0.051804706 0.82149613, + -0.56562191 -0.026897397 0.8242259, + -0.51754725 -0.027908213 0.8551994, + -0.51706892 -0.022274999 0.85565388, + -0.45897311 -0.023121005 0.88814926, + -0.45875579 -0.018651191 0.88836658, + -0.40028614 -0.019235307 0.9161883, + -0.40019992 -0.013808397 0.91632378, + -0.34803089 -0.014125695 0.93737662, + -0.34802008 -0.010772103 0.93742526, + -0.30127993 -0.010956497 0.95347273, + -0.30127785 -0.010408295 0.95347953, + -0.35347301 -0.0102108 0.93538898, + -0.3535499 -0.015161396 0.93529278, + -0.41177005 -0.014770302 0.9111681, + -0.41195315 -0.018692708 0.91101331, + -0.47085181 -0.018097894 0.88202667, + -0.47125405 -0.022983203 0.88169813, + -0.52032208 -0.022252902 0.85368013, + -0.52252173 -0.047054678 0.85132658, + -0.57050407 -0.045325603 0.82004315, + -0.57392102 -0.086626701 0.81431597, + -0.62018293 -0.082982093 0.78005588, + -0.62294686 -0.12303697 0.77252781, + -0.66687179 -0.11720295 0.73589778, + -0.6689077 -0.15591292 0.72681063, + -0.70987242 -0.14772908 0.68866342, + -0.71114123 -0.18491206 0.67829627, + -0.74950784 -0.17411396 0.63868785, + -0.75001121 -0.21007004 0.62717921, + 0.67966318 -0.21049905 0.70267218, + 0.63633895 -0.22137097 0.73896396, + 0.63516831 -0.18167509 0.75070333, + 0.58908099 -0.190072 0.785402, + 0.58718812 -0.14884803 0.7956472, + 0.53925413 -0.15486003 0.82778215, + 0.53674608 -0.11266401 0.83618814, + 0.487041 -0.116621 0.86555803, + 0.48402682 -0.073407367 0.87196869, + 0.43336815 -0.07560233 0.89804029, + 0.430121 -0.0330512 0.90216601, + 0.37798086 -0.033894788 0.92519265, + 0.3243551 -0.011443303 0.94586623, + 0.37627181 -0.011208294 0.92644161, + 0.37414992 -0.014693196 0.92725176, + 0.42564207 -0.014337102 0.90477812, + 0.42756709 -0.037985109 0.90318525, + 0.47797093 -0.036908995 0.8775999, + 0.48133975 -0.078924961 0.87297356, + 0.53083676 -0.076308362 0.84403157, + 0.5338611 -0.11884203 0.83717918, + 0.58188486 -0.11430197 0.80519885, + 0.58429497 -0.155384 0.79652703, + 0.63067627 -0.14858808 0.76168835, + 0.63239682 -0.18828996 0.75141281, + 0.67582893 -0.17915398 0.71495396, + 0.67681092 -0.21767397 0.70323896, + 0.71744883 -0.20597996 0.66546184, + 0.71769863 -0.23658088 0.65493369, + 0.68007201 -0.24908 0.68953699, + -0.16344796 -0.0031901794 0.98654675, + -0.22031492 -0.00047455583 0.97542864, + -0.21988305 -0.00047494113 0.97552621, + -0.20739198 -0.006109389 0.97823888, + -0.20738807 -0.0049478416 0.97824633, + -0.25854403 -0.0048858305 0.96598715, + -0.2585921 -0.008490433 0.96594936, + -0.31511709 -0.0083415918 0.94901621, + -0.31523311 -0.011270104 0.94894737, + -0.37388489 -0.011014297 0.92740965, + -0.37415102 -0.014712502 0.9272511, + -0.42564514 -0.014355905 0.90477628, + -0.42764807 -0.038989305 0.90310413, + -0.47832018 -0.037878215 0.87736827, + -0.48166588 -0.07970468 0.8727228, + -0.53114706 -0.077060305 0.84376812, + -0.53416175 -0.11960494 0.8368786, + -0.5823493 -0.11501505 0.80476135, + -0.58472109 -0.15573302 0.79614609, + -0.63087368 -0.14894693 0.76145464, + -0.63258523 -0.18886307 0.75111032, + -0.67599893 -0.17969699 0.71465695, + -0.67696172 -0.21844189 0.70285565, + -0.71759158 -0.20670289 0.66508359, + -0.71782267 -0.23649488 0.65482873, + -0.68035829 -0.24894512 0.68930334, + -0.67996895 -0.21087997 0.70226192, + -0.63650596 -0.22181797 0.73868597, + -0.63535792 -0.18225199 0.75040287, + -0.58929002 -0.190679 0.78509802, + -0.58742696 -0.14963599 0.7953229, + -0.53930277 -0.15570693 0.8275916, + -0.53683919 -0.11389704 0.83596128, + -0.48714283 -0.11789796 0.86532772, + -0.48414207 -0.074627608 0.87180114, + -0.43346891 -0.076860383 0.89788479, + -0.43020809 -0.034029208 0.90208822, + -0.37805507 -0.034898203 0.92512512, + -0.37627381 -0.011221395 0.9264406, + -0.3243559 -0.011456598 0.94586575, + -0.32413808 -0.0080896718 0.94597524, + -0.2664749 -0.0082421573 0.96380663, + -0.26639199 -0.0058543999 0.96384698, + -0.21078889 -0.0059374073 0.97751355, + -0.21075307 -0.0027795609 0.97753537, + -0.16282694 -0.0028054791 0.98665065, + -0.16283599 -0.0037926496 0.98664588, + -0.21750192 -0.0037519287 0.97605264, + -0.21755596 -0.0055959788 0.97603178, + -0.27446905 -0.0055131316 0.96158022, + -0.27461708 -0.0081241028 0.96151936, + -0.3266021 -0.0079856114 0.94512826, + -0.32820204 -0.031564005 0.94408011, + -0.38026592 -0.030904692 0.92436075, + -0.383331 -0.074233599 0.920623, + -0.43583894 -0.072337896 0.89711291, + -0.43872586 -0.11583696 0.89112371, + -0.48993176 -0.11237495 0.86448759, + -0.49242911 -0.15521704 0.85640019, + -0.54210389 -0.14985897 0.82684082, + -0.54405677 -0.19157691 0.81688458, + -0.59233505 -0.18396102 0.78440911, + -0.59364378 -0.22461993 0.7727437, + -0.63962471 -0.2145599 0.73813564, + -0.64021105 -0.25441402 0.72484708, + -0.68327117 -0.24181806 0.68895918, + -0.68319285 -0.27322495 0.6771968, + -0.64631933 -0.28550819 0.70764142, + -0.64589703 -0.31229204 0.69662803, + -0.60607129 -0.32537615 0.72581536, + -0.60531211 -0.35365608 0.7131092, + -0.56339502 -0.36707401 0.74016398, + -0.56222296 -0.39763695 0.72511393, + -0.51816517 -0.41124216 0.74992323, + -0.51660311 -0.44265011 0.7329272, + -0.47008917 -0.45629516 0.75552028, + -0.46813017 -0.48887217 0.73611021, + -0.41882178 -0.50237578 0.75644362, + -0.41655901 -0.53530002 0.73480099, + -0.36569908 -0.54803312 0.75227916, + -0.36319098 -0.58137697 0.72807497, + -0.31105888 -0.59303075 0.74266875, + -0.30840185 -0.62667572 0.71565765, + -0.25447702 -0.63710004 0.72756106, + -0.25189498 -0.67005593 0.69826496, + -0.19716507 -0.67879021 0.70736825, + -0.19483 -0.71076697 0.67590803, + -0.1398759 -0.71752959 0.6823386, + -0.13795203 -0.74870521 0.64839017, + -0.08298517 -0.7533257 0.65239078, + -0.081689976 -0.78335685 0.6161809, + -0.027700104 -0.78568214 0.61801004, + -0.027219096 -0.81388289 0.58039093, + 0.0266074 -0.813896 0.580401, + 0.027088504 -0.78567511 0.61804605, + 0.08112102 -0.78337318 0.61623514, + 0.082416952 -0.75331849 0.65247142, + 0.13740002 -0.74872106 0.64848906, + 0.13931501 -0.71772105 0.68225205, + 0.19433704 -0.71097118 0.67583519, + 0.19668791 -0.67879373 0.70749766, + 0.2514649 -0.67007077 0.69840574, + 0.25404996 -0.63707292 0.72773397, + 0.30776793 -0.62671185 0.71589881, + 0.31040102 -0.59327608 0.74274808, + 0.36282796 -0.58157492 0.72809792, + 0.36535481 -0.54798073 0.7524845, + 0.41625795 -0.53525293 0.73500592, + 0.41851994 -0.50229394 0.75666487, + 0.46764395 -0.48885894 0.73642796, + 0.46959504 -0.45627606 0.75583911, + 0.51616901 -0.442635 0.73324198, + 0.51773363 -0.41092572 0.75039446, + 0.56202686 -0.3972739 0.72546482, + 0.56317294 -0.36729598 0.74022293, + 0.60528868 -0.35381383 0.71305066, + 0.60605323 -0.32549512 0.72577721, + 0.64572799 -0.31245899 0.69670999, + 0.64615279 -0.28532395 0.7078678, + 0.68319905 -0.27299604 0.67728305, + 0.68326771 -0.24126688 0.68915564, + 0.64004904 -0.25387803 0.72517806, + 0.63944596 -0.21414196 0.73841196, + 0.59345168 -0.2241779 0.77301967, + 0.59211773 -0.18336491 0.78471261, + 0.54383183 -0.19095193 0.81718069, + 0.54186618 -0.14939106 0.82708132, + 0.49215487 -0.15473098 0.85664582, + 0.48962006 -0.11149502 0.8647781, + 0.43863505 -0.11491302 0.8912881, + 0.43571791 -0.071111985 0.89726979, + 0.38321915 -0.072974533 0.92077035, + 0.38017109 -0.029948907 0.92443126, + 0.32813603 -0.030587204 0.94413513, + 0.32659999 -0.0079778098 0.94512898, + 0.27461594 -0.008116168 0.96151978, + 0.16805305 -0.0027441008 0.98577422, + 0.17112096 -0.0025130594 0.98524678, + 0.16983795 -0.0025254793 0.98546875, + 0.16983804 -0.0030476006 0.98546726, + 0.17112106 -0.0030476011 0.98524535, + 0.16970599 -0.0030946196 0.9854899, + 0.16970593 -0.0025138687 0.98549151, + 0.21752296 -0.0044797896 0.97604489, + 0.21755596 -0.0055964184 0.97603178, + 0.27446905 -0.0055135512 0.96158022, + 0.26641804 -0.0065891407 0.96383512, + 0.2664749 -0.0082428874 0.96380663, + 0.32413808 -0.0080903918 0.94597524, + 0.26480201 -0.0066351499 0.96428001, + 0.3151471 -0.0091060223 0.94899923, + 0.31523311 -0.011271404 0.94894737, + 0.37388489 -0.011015496 0.92740965, + 0.35265812 -0.011361804 0.93568337, + 0.40056714 -0.019340107 0.91606331, + 0.45901206 -0.018752502 0.88823211, + 0.45922011 -0.023021005 0.88802421, + 0.51729727 -0.022178311 0.8555184, + 0.51774484 -0.027445491 0.85509473, + 0.56535989 -0.026460994 0.8244198, + 0.56754816 -0.050755817 0.8217743, + 0.61420304 -0.048648007 0.78764713, + 0.61745608 -0.08824341 0.78164011, + 0.66124272 -0.084156163 0.74543667, + 0.66385823 -0.12340105 0.73760724, + 0.70524085 -0.11698297 0.6992498, + 0.70707518 -0.15473104 0.6900022, + 0.74567509 -0.14579701 0.65016305, + 0.74671882 -0.18206495 0.63973683, + 0.7824558 -0.17044996 0.59892386, + 0.78275615 -0.19721004 0.59025514, + 0.74989867 -0.20963989 0.62745768, + 0.74938583 -0.17394996 0.63887584, + 0.71100402 -0.184736 0.67848802, + 0.70970523 -0.14714706 0.68896025, + 0.66854727 -0.15532808 0.72726738, + 0.6664682 -0.11627703 0.7364102, + 0.62286496 -0.12201498 0.77275586, + 0.62004411 -0.081492126 0.78032321, + 0.57358509 -0.08508382 0.81471521, + 0.57018971 -0.044320479 0.82031655, + 0.5224309 -0.046001989 0.85143983, + 0.52031714 -0.022214705 0.85368419, + 0.47125012 -0.022943806 0.88170123, + 0.47085223 -0.018100809 0.88202643, + 0.4119519 -0.018695697 0.91101378, + 0.41177884 -0.014979295 0.91116071, + 0.36392391 -0.015310396 0.93130279, + 0.36389998 -0.014767698 0.93132091, + 0.42283899 -0.0143676 0.90609097, + 0.42317399 -0.018672099 0.90585601, + 0.47379187 -0.018148396 0.88044977, + 0.47579613 -0.04143161 0.87857926, + 0.5250628 -0.040089384 0.8501187, + 0.52848816 -0.081512533 0.84501833, + 0.57634193 -0.078465693 0.81343287, + 0.57932192 -0.12023699 0.80618191, + 0.62562764 -0.11507693 0.77158755, + 0.62791002 -0.15535501 0.76262301, + 0.67133093 -0.14794399 0.72624195, + 0.67286742 -0.1868061 0.71578842, + 0.71381974 -0.17684793 0.67763275, + 0.71457005 -0.21381703 0.66608703, + 0.75275731 -0.20120408 0.62679625, + 0.7528348 -0.22969994 0.61682886, + 0.72047925 -0.24200809 0.64987826, + 0.72025526 -0.2650201 0.64109021, + 0.68600094 -0.27796796 0.67241096, + 0.68549007 -0.30310902 0.66198808, + 0.64848667 -0.31690684 0.69212365, + 0.64764506 -0.34353802 0.68010104, + 0.60809511 -0.35793108 0.7085942, + 0.60685432 -0.38648519 0.69451934, + 0.56497908 -0.40121505 0.72098905, + 0.56331104 -0.43125707 0.70476806, + 0.51904297 -0.44613394 0.72908092, + 0.51699305 -0.47682205 0.71088606, + 0.47014523 -0.49163923 0.73297638, + 0.46770895 -0.52331495 0.71231294, + 0.41864607 -0.53768307 0.73186904, + 0.41588995 -0.56989092 0.70870292, + 0.36484483 -0.58345968 0.72557765, + 0.36185712 -0.61609024 0.69963723, + 0.30970094 -0.6283828 0.71359682, + 0.30666798 -0.66045094 0.68538994, + 0.25300691 -0.67130876 0.69665778, + 0.25008997 -0.70273596 0.66604596, + 0.19544391 -0.71180266 0.6746397, + 0.19281307 -0.74255925 0.64142722, + 0.13845798 -0.74947095 0.64739692, + 0.13631 -0.77914 0.61185002, + 0.081819981 -0.78384382 0.6155439, + 0.080416992 -0.81162387 0.57861894, + 0.026721699 -0.81397003 0.58029199, + 0.026211008 -0.8401953 0.54165018, + -0.026790706 -0.84018219 0.54164213, + -0.027304497 -0.8139379 0.58030993, + -0.080986604 -0.81156713 0.57861906, + -0.082389027 -0.7838273 0.61548924, + -0.13685803 -0.77910119 0.61177713, + -0.13900499 -0.74945092 0.64730293, + -0.19356096 -0.74248582 0.64128685, + -0.19619703 -0.71179408 0.67443007, + -0.25058398 -0.70274293 0.66585296, + -0.25349692 -0.67134279 0.69644678, + -0.30709288 -0.66047674 0.68517476, + -0.31014588 -0.62818378 0.71357876, + -0.36223987 -0.61589074 0.69961476, + -0.3652232 -0.58327937 0.72553241, + -0.41624299 -0.569704 0.708646, + -0.4189758 -0.53776175 0.73162264, + -0.46818694 -0.52332991 0.71198791, + -0.47063223 -0.49165624 0.73265237, + -0.51723486 -0.47689688 0.7106598, + -0.51930416 -0.44594216 0.72901225, + -0.56337297 -0.43112895 0.70479697, + -0.56502163 -0.40137675 0.72086561, + -0.60720992 -0.38652194 0.69418794, + -0.60844922 -0.35826311 0.70812225, + -0.64795297 -0.34385601 0.67964703, + -0.64881265 -0.31700182 0.69177461, + -0.68563503 -0.30325302 0.66177207, + -0.68614721 -0.27847409 0.67205226, + -0.72050798 -0.26545301 0.64062703, + -0.72074616 -0.24221505 0.6495052, + -0.75282919 -0.22999106 0.61672711, + -0.75276601 -0.20194601 0.62654698, + -0.71470064 -0.2145669 0.66570568, + -0.71395779 -0.17702994 0.67743975, + -0.6731838 -0.18696296 0.71544981, + -0.67168492 -0.14856899 0.72578692, + -0.62795097 -0.15607199 0.76244289, + -0.62570995 -0.11613698 0.77136189, + -0.57961184 -0.12132295 0.80581069, + -0.5766902 -0.079992533 0.81303728, + -0.52840424 -0.08312884 0.84491342, + -0.52498114 -0.04150781 0.85010117, + -0.47591689 -0.042891689 0.87844378, + -0.47379681 -0.018175794 0.88044667, + -0.4231762 -0.018700309 0.9058544, + -0.42283899 -0.0143657 0.90609097, + -0.36390087 -0.014765695 0.93132067, + -0.36375412 -0.011394204 0.93142533, + -0.30573693 -0.011646397 0.95204479, + -0.305673 -0.0073715001 0.95210803, + -0.25464001 -0.00748685 0.96700698, + -0.25464106 -0.0078028119 0.96700424, + -0.21959098 -0.00046339995 0.9755919, + -0.2195901 -0.0030685815 0.97558749, + -0.22031406 -0.0030685707 0.97542423, + -0.21988192 -0.0030621488 0.97552162, + -0.17188808 0.017308008 0.98496449, + -0.17191395 0.0005239009 0.98511177, + -0.17143199 0.00052366394 0.98519588, + -0.17142595 0.0078470977 0.98516577, + -0.123702 -0.0032862399 0.99231398, + -0.12370305 -8.6855631e-005 0.99231935, + -0.12213396 -8.7155473e-005 0.99251366, + -0.12213299 -0.0034259695 0.99250787, + -0.123465 -0.00342598 0.99234301, + -0.12346597 -2.2312595e-005 0.99234879, + -0.11594696 -0.0018643494 0.99325365, + -0.11594897 -0.0021708496 0.99325275, + -0.16803999 -0.0021545098 0.98577785, + -0.16807204 -0.0035645009 0.98576826, + -0.22387607 -0.0035241612 0.97461134, + -0.22399493 -0.0060212477 0.97457165, + -0.27611506 -0.0059380615 0.96110624, + -0.27745607 -0.028573509 0.96031338, + -0.3302649 -0.028072292 0.94347078, + -0.33303508 -0.071387514 0.94020826, + -0.38579193 -0.069848396 0.91993791, + -0.388549 -0.114343 0.91430598, + -0.44114912 -0.11136503 0.89049727, + -0.4435862 -0.15474507 0.88277143, + -0.49510783 -0.15001394 0.85578269, + -0.49709505 -0.19233003 0.84611213, + -0.54699618 -0.18555605 0.8163113, + -0.54843593 -0.22763497 0.80461186, + -0.59648108 -0.21849804 0.77231413, + -0.59722304 -0.25909102 0.75907612, + -0.6433478 -0.24729994 0.72453183, + -0.64340806 -0.28073102 0.71219105, + -0.60358965 -0.29238182 0.74174958, + -0.60325813 -0.32116109 0.73002416, + -0.56146979 -0.33322188 0.75743967, + -0.56078118 -0.3634901 0.74390823, + -0.51652402 -0.375918 0.76934302, + -0.51544809 -0.4078311 0.75364918, + -0.46878976 -0.42039078 0.77685761, + -0.46735117 -0.45314014 0.75910932, + -0.41816086 -0.46559581 0.77997571, + -0.41635391 -0.49976388 0.75952983, + -0.36567202 -0.51160407 0.77752513, + -0.36360404 -0.54598606 0.7547791, + -0.31120303 -0.55699909 0.77000314, + -0.30900589 -0.59116977 0.74500579, + -0.25500304 -0.60104108 0.7574451, + -0.25275707 -0.63564819 0.72942817, + -0.19796903 -0.64397705 0.73898709, + -0.19589108 -0.67778128 0.70868838, + -0.14080505 -0.68428624 0.71549022, + -0.139084 -0.71693599 0.68312401, + -0.083678395 -0.72143394 0.68740892, + -0.082509123 -0.75298619 0.65284318, + -0.028062291 -0.7552647 0.65481877, + -0.02761119 -0.7856217 0.61809075, + 0.027028397 -0.78563386 0.61810094, + 0.027479904 -0.7552591 0.65485007, + 0.081972674 -0.75300169 0.65289277, + 0.083142824 -0.72142518 0.68748319, + 0.13831602 -0.71697307 0.68324107, + 0.14002804 -0.68429923 0.71563023, + 0.19541296 -0.67778492 0.70881695, + 0.19749303 -0.64395905 0.73913008, + 0.25234997 -0.63563794 0.72957796, + 0.25458303 -0.60123807 0.75743014, + 0.30835804 -0.59142709 0.74507004, + 0.31057999 -0.55673701 0.77044398, + 0.36305708 -0.54573715 0.7552222, + 0.3651 -0.511572 0.77781498, + 0.41605586 -0.49968681 0.75974369, + 0.41784507 -0.46583506 0.78000212, + 0.46707389 -0.45337489 0.75913984, + 0.46853513 -0.42001909 0.7772122, + 0.51502603 -0.40752906 0.7541011, + 0.51608115 -0.37588716 0.76965529, + 0.56037587 -0.36346692 0.74422485, + 0.56106186 -0.3328329 0.75791281, + 0.602907 -0.320786 0.730479, + 0.60322392 -0.29193997 0.74222094, + 0.64309019 -0.28030705 0.71264517, + 0.64301521 -0.24715605 0.72487617, + 0.59685993 -0.25893196 0.75941586, + 0.59610677 -0.21845293 0.77261573, + 0.54803288 -0.22758093 0.80490184, + 0.54657185 -0.18533494 0.81664568, + 0.49684581 -0.19206892 0.84631771, + 0.49483481 -0.14951594 0.85602772, + 0.44329295 -0.15422899 0.8830089, + 0.44084388 -0.11082397 0.89071578, + 0.38821393 -0.11378498 0.91451788, + 0.38543886 -0.069016777 0.92014867, + 0.33266008 -0.070536114 0.94040525, + 0.32991701 -0.027579701 0.94360697, + 0.27742389 -0.028068688 0.96033752, + 0.2761139 -0.0059333476 0.96110666, + 0.223994 -0.00601647 0.974572, + 0.22387607 -0.0035243912 0.97461134, + 0.16807204 -0.003564731 0.98576826, + 0.12345301 -0.0021664503 0.99234813, + 0.17461702 -0.0021496103 0.9846341, + 0.17544509 -0.023259612 0.98421448, + 0.22827497 -0.023002299 0.97332489, + 0.230317 -0.066570498 0.97083598, + 0.28348106 -0.065603413 0.95673126, + 0.28570509 -0.11070903 0.95190138, + 0.33920297 -0.10867499 0.93441486, + 0.34134212 -0.15296906 0.92740834, + 0.3953051 -0.14948803 0.90630424, + 0.39723507 -0.19385803 0.89700812, + 0.4503738 -0.18860291 0.87269258, + 0.45189485 -0.23198292 0.86137968, + 0.50381589 -0.22463395 0.83409184, + 0.50478721 -0.26708409 0.82088733, + 0.55479926 -0.25741312 0.79116136, + 0.55512589 -0.29359794 0.77822584, + 0.5082221 -0.30399707 0.80578917, + 0.50780207 -0.26157704 0.82080114, + 0.45579311 -0.27026507 0.84806216, + 0.45476785 -0.22696793 0.86120373, + 0.40127686 -0.23342691 0.8857137, + 0.39979985 -0.18958093 0.8967827, + 0.34541413 -0.19409907 0.91815835, + 0.34362102 -0.14933401 0.92715913, + 0.28962302 -0.15220101 0.94496214, + 0.2877261 -0.10761504 0.95164734, + 0.23368606 -0.10925602 0.96615422, + 0.23182203 -0.064326309 0.9706291, + 0.17809007 -0.065070622 0.98186034, + 0.17648704 -0.021768905 0.98406225, + 0.12473001 -0.021943402 0.99194813, + 0.12414798 -0.0012905899 0.9922629, + 0.073444836 -0.0012971406 0.99729848, + -0.027853305 -0.37077704 0.92830414, + -0.027833892 -0.41337192 0.91013676, + 0.027117295 -0.41337991 0.91015476, + 0.027126286 -0.37057683 0.92840558, + -0.027658496 -0.37057197 0.92839187, + -0.027640697 -0.32714197 0.9445709, + 0.026917892 -0.32714787 0.94458961, + 0.026946194 -0.37076992 0.92833376, + 0.082876801 -0.369629 0.92547601, + 0.082823001 -0.412671 0.907107, + 0.027659604 -0.41393507 0.90988612, + 0.027603405 -0.45604604 0.8895281, + -0.02798859 -0.45604086 0.88951868, + -0.028048091 -0.41359085 0.91003072, + -0.083177306 -0.41232005 0.90723413, + -0.083233498 -0.369634 0.92544198, + 0.02670721 -0.23870309 0.97072536, + 0.080183007 -0.23801903 0.9679451, + 0.080468625 -0.28308806 0.95571226, + 0.13579796 -0.28137791 0.94993967, + 0.13608904 -0.32625511 0.93543434, + 0.19308604 -0.32312208 0.92645025, + 0.19321093 -0.36554289 0.91052067, + 0.13733594 -0.36903283 0.91921359, + 0.137233 -0.32488501 0.93574399, + 0.081415266 -0.32689986 0.94154555, + 0.081239775 -0.28218293 0.95591474, + 0.02691781 -0.28301609 0.95873737, + 0.026822796 -0.23856997 0.97075486, + -0.027169997 -0.23856696 0.97074586, + -0.027257096 -0.28302598 0.95872486, + -0.081591465 -0.28218687 0.9558835, + -0.081763372 -0.32693088 0.94150466, + -0.13790596 -0.32489488 0.93564165, + -0.13799699 -0.36835396 0.91938686, + -0.082325093 -0.37064996 0.9251169, + -0.082264006 -0.32635704 0.94166011, + -0.027457591 -0.32734287 0.94450665, + -0.0274048 -0.282859 0.95876998, + 0.0270546 -0.28286201 0.95877898, + 0.027114097 -0.32693198 0.94465888, + 0.082249038 -0.32594416 0.94180447, + 0.082308263 -0.37026483 0.92527258, + 0.13825598 -0.36795697 0.91950691, + 0.13817304 -0.41043615 0.90136027, + 0.083120927 -0.41297716 0.90694028, + 0.082957871 -0.45486984 0.88668573, + 0.027825208 -0.45626611 0.88940823, + 0.027726499 -0.49795601 0.866759, + -0.028126312 -0.49795023 0.86674941, + -0.028227413 -0.4562782 0.8893894, + -0.083651364 -0.45485979 0.88662559, + -0.083824508 -0.41298506 0.90687209, + -0.13854 -0.410447 0.901299, + -0.13862704 -0.36902413 0.91902333, + -0.19354098 -0.36557698 0.91043687, + -0.19341807 -0.32277113 0.92650336, + -0.13708395 -0.32587785 0.93542057, + -0.13680899 -0.28098497 0.94991088, + -0.081139833 -0.28271708 0.95576537, + -0.080867976 -0.23801593 0.96788877, + -0.027045906 -0.23871006 0.97071421, + -0.026926413 -0.19424509 0.98058349, + 0.026579088 -0.19424692 0.98059255, + 0.02611419 -0.19479293 0.98049664, + 0.079092763 -0.19424891 0.97775853, + 0.079475462 -0.23886688 0.96779454, + 0.13462898 -0.23744297 0.96202689, + 0.13509095 -0.28224385 0.9497835, + 0.19156691 -0.27957889 0.94081753, + 0.19194695 -0.32454991 0.92618775, + 0.24865203 -0.32031304 0.91409612, + 0.2487931 -0.36230713 0.89824027, + 0.19449303 -0.36692604 0.9096911, + 0.19435796 -0.40796191 0.89207178, + 0.13951704 -0.41182515 0.90051931, + 0.13923396 -0.45269486 0.88072771, + 0.083637074 -0.45554584 0.8862747, + 0.083350711 -0.49664906 0.86394012, + 0.027967095 -0.49818793 0.86661786, + 0.027825 -0.53878599 0.84198302, + -0.0282431 -0.53877997 0.84197301, + -0.028386693 -0.49820089 0.86659682, + -0.083732329 -0.49665219 0.86390132, + -0.084022209 -0.45522907 0.88640112, + -0.139617 -0.45236999 0.88083398, + -0.13989903 -0.41185108 0.90044826, + -0.19502297 -0.40795493 0.89192986, + -0.19516693 -0.3673299 0.90938371, + -0.24941097 -0.36269596 0.89791191, + -0.24928197 -0.32034898 0.91391188, + -0.19192693 -0.32464188 0.92615962, + -0.19155295 -0.28003493 0.94068474, + -0.13541605 -0.28269109 0.94960433, + -0.13495804 -0.23745309 0.96197838, + -0.080151401 -0.238874 0.96773702, + -0.07978078 -0.19424295 0.97770375, + -0.026457196 -0.19479597 0.98048687, + -0.026304897 -0.15038298 0.98827785, + 0.025955796 -0.15038398 0.98828685, + 0.025866296 -0.15049098 0.98827291, + 0.078325935 -0.15007907 0.9855665, + 0.078797176 -0.19460896 0.97771078, + 0.13305597 -0.19348095 0.97203976, + 0.13368498 -0.23862197 0.96186686, + 0.18930598 -0.23642997 0.95302886, + 0.18993795 -0.28166795 0.94052476, + 0.24644797 -0.27804196 0.92841589, + 0.24690895 -0.32261291 0.91375977, + 0.30328006 -0.31724009 0.89854324, + 0.30341798 -0.35871196 0.88275886, + 0.25072888 -0.36443383 0.89684057, + 0.2505399 -0.40388185 0.87983471, + 0.19548196 -0.40913892 0.89128679, + 0.19509792 -0.44921485 0.8718617, + 0.14004 -0.45350301 0.88018399, + 0.13956201 -0.49391106 0.85823911, + 0.083756693 -0.49703994 0.86367589, + 0.083353475 -0.53704888 0.83942282, + 0.02775109 -0.53871679 0.84202969, + 0.027574297 -0.57807595 0.81551689, + -0.028011199 -0.57806897 0.81550699, + -0.02818911 -0.53872919 0.84200728, + -0.084059179 -0.53703588 0.83936083, + -0.084470131 -0.49736318 0.86342031, + -0.14027004 -0.49421218 0.85795027, + -0.14076097 -0.45351687 0.88006175, + -0.19575295 -0.44921488 0.87171483, + -0.19614697 -0.40913194 0.89114386, + -0.25085488 -0.40389583 0.87973857, + -0.25104788 -0.36449483 0.89672661, + -0.30400896 -0.35873097 0.88254786, + -0.30388388 -0.31765187 0.89819372, + -0.24722002 -0.32307002 0.91351414, + -0.24676389 -0.27807689 0.9283216, + -0.19024791 -0.28170985 0.94044954, + -0.18962395 -0.23644593 0.95296174, + -0.13400599 -0.23864301 0.96181703, + -0.13339198 -0.19388196 0.97191375, + -0.079147138 -0.19501609 0.97760147, + -0.078678019 -0.15004803 0.98554325, + -0.026237912 -0.15046307 0.98826748, + -0.026057595 -0.10686599 0.99393189, + 0.025686985 -0.10686693 0.99394143, + 0.02561209 -0.10695796 0.99393362, + 0.077179909 -0.10667402 0.99129415, + 0.077729084 -0.15081897 0.98550075, + 0.13145506 -0.14996408 0.97991347, + 0.13223097 -0.19453095 0.97194278, + 0.18731 -0.192781 0.96319801, + 0.18817404 -0.23791206 0.95288426, + 0.24413097 -0.23490997 0.94085985, + 0.24491212 -0.28011411 0.92819941, + 0.30076814 -0.27553511 0.91302741, + 0.30128893 -0.3200129 0.89822978, + 0.35751188 -0.31342688 0.8797437, + 0.3576189 -0.35427791 0.86405784, + 0.30564094 -0.3612119 0.88097078, + 0.30539212 -0.39932415 0.86445129, + 0.25232697 -0.40578794 0.87844586, + 0.25181305 -0.44494411 0.85942715, + 0.19664395 -0.45078188 0.87070483, + 0.19598104 -0.49038011 0.8491872, + 0.14078605 -0.49509719 0.8573553, + 0.14010401 -0.53436106 0.8335641, + 0.084128305 -0.53777105 0.8388831, + 0.083596706 -0.57652605 0.81279111, + 0.027853087 -0.5783267 0.81532961, + 0.027629592 -0.61675674 0.78666872, + -0.028383195 -0.61674392 0.78665191, + -0.028616603 -0.57861304 0.81510013, + -0.08431711 -0.57678908 0.8125301, + -0.0848637 -0.53778499 0.83880001, + -0.14049803 -0.53437912 0.8334862, + -0.14118204 -0.49509713 0.85729021, + -0.19662292 -0.49034381 0.8490597, + -0.19729491 -0.4507798 0.87055856, + -0.2521379 -0.44496185 0.85932273, + -0.25265494 -0.4058159 0.87833875, + -0.30569816 -0.39934519 0.86433339, + -0.30595088 -0.36091787 0.88098371, + -0.35790187 -0.35398489 0.8640607, + -0.35780317 -0.31387514 0.8794654, + -0.30187786 -0.32044587 0.89787757, + -0.30136704 -0.27557403 0.91281813, + -0.24519908 -0.28018808 0.92810136, + -0.24442503 -0.23493204 0.94077814, + -0.18848293 -0.23793791 0.95281667, + -0.18763593 -0.19315493 0.96305966, + -0.13258196 -0.19491096 0.97181875, + -0.13180594 -0.14989093 0.97987753, + -0.078113712 -0.15074803 0.98548126, + -0.077563509 -0.10662802 0.99126911, + -0.026017895 -0.10691398 0.99392778, + -0.025798392 -0.062176779 0.99773163, + 0.025404494 -0.062177386 0.99774176, + 0.025007995 -0.062672883 0.99772078, + 0.076022469 -0.062511079 0.99514467, + 0.076658159 -0.10733195 0.99126351, + 0.12947901 -0.106743 0.98582, + 0.13039795 -0.15133092 0.97984451, + 0.18458298 -0.15001199 0.9713009, + 0.18565999 -0.19497997 0.96307486, + 0.2410861 -0.19257708 0.95120537, + 0.24216007 -0.23762205 0.94068825, + 0.29782197 -0.23379797 0.92554885, + 0.29871807 -0.27845305 0.91281521, + 0.354478 -0.27282801 0.89437699, + 0.35502201 -0.317099 0.87943602, + 0.41019785 -0.30934489 0.85792971, + 0.41025907 -0.34879604 0.84263211, + 0.35983402 -0.35684603 0.86207914, + 0.35951009 -0.39385808 0.84594816, + 0.30750096 -0.40162694 0.8626349, + 0.30688486 -0.43912178 0.84438956, + 0.25317794 -0.44635287 0.85829484, + 0.25233099 -0.48533401 0.83712602, + 0.19733012 -0.49170229 0.84810948, + 0.19640703 -0.52985805 0.82503015, + 0.14078803 -0.5350011 0.83303815, + 0.13990298 -0.57360291 0.80709785, + 0.084386095 -0.57723397 0.81220686, + 0.083718091 -0.61481696 0.7842139, + 0.027618701 -0.61674798 0.78667599, + 0.027360504 -0.65362006 0.75632811, + -0.028116493 -0.65360683 0.75631183, + -0.028386008 -0.61674613 0.78665018, + -0.083897926 -0.61482012 0.7841922, + -0.084558293 -0.57700592 0.81235087, + -0.14060095 -0.57332683 0.80717272, + -0.14148393 -0.53530079 0.83272761, + -0.19677505 -0.53016812 0.82474315, + -0.19771509 -0.49141324 0.84818745, + -0.25296801 -0.48500401 0.837125, + -0.25381005 -0.44668913 0.85793316, + -0.30720803 -0.43947905 0.84408611, + -0.30783293 -0.40167791 0.8624928, + -0.36006391 -0.39386192 0.84571081, + -0.3603971 -0.35687909 0.86183017, + -0.41053295 -0.34886298 0.84247088, + -0.41047707 -0.30944204 0.85776114, + -0.35556799 -0.31717199 0.87918901, + -0.35503608 -0.27288207 0.89413923, + -0.29929987 -0.2785179 0.91260469, + -0.29840404 -0.23339103 0.92546409, + -0.24276611 -0.23721611 0.94063449, + -0.24170803 -0.19252503 0.95105809, + -0.18630005 -0.19493507 0.96296036, + -0.18523099 -0.14992599 0.97119087, + -0.13075002 -0.15125701 0.97980911, + -0.12983997 -0.10711898 0.98573178, + -0.076702259 -0.10771495 0.99121851, + -0.076052673 -0.062966779 0.99511367, + -0.025036005 -0.063129917 0.99769121, + -0.024795797 -0.020125197 0.9994899, + 0.024787603 -0.020125201 0.99949014, + 0.024780804 -0.020133702 0.99949014, + 0.074884199 -0.020083301 0.99699003, + 0.07557261 -0.063094705 0.9951421, + 0.12779894 -0.062756769 0.98981255, + 0.12885894 -0.10755895 0.98581254, + 0.18212104 -0.10665002 0.97747523, + 0.18340304 -0.15161103 0.97127622, + 0.23827595 -0.14978397 0.95957774, + 0.23962393 -0.19462596 0.95115775, + 0.29505485 -0.19154191 0.93608457, + 0.29629898 -0.23601097 0.9254759, + 0.35125887 -0.23136091 0.90724272, + 0.35224912 -0.27618808 0.89422631, + 0.40724909 -0.26952207 0.87264317, + 0.40778092 -0.3131299 0.85770881, + 0.46157521 -0.30422115 0.83330542, + 0.46157581 -0.34252784 0.8183046, + 0.41268006 -0.35170802 0.84023613, + 0.4122811 -0.3872211 0.82467216, + 0.36164102 -0.39625707 0.84391713, + 0.3609041 -0.43298408 0.82599819, + 0.30916113 -0.44152915 0.84230131, + 0.30813313 -0.47913817 0.82187629, + 0.25411308 -0.48711118 0.83555329, + 0.25294399 -0.52434701 0.81306797, + 0.19788392 -0.53125381 0.82377869, + 0.19666091 -0.5690127 0.79846662, + 0.14095698 -0.57455194 0.80623889, + 0.139874 -0.611444 0.77882701, + 0.084297173 -0.61531675 0.78375971, + 0.083492406 -0.65204507 0.75356913, + 0.027907092 -0.65407485 0.75591481, + 0.02758879 -0.68940377 0.72385174, + -0.028114296 -0.68939394 0.72384095, + -0.028432891 -0.65386975 0.7560727, + -0.083696574 -0.65183884 0.75372481, + -0.084485665 -0.6153267 0.78373164, + -0.14057501 -0.61140299 0.77873302, + -0.14167397 -0.5742929 0.80629784, + -0.19708496 -0.56876594 0.79853791, + -0.19828989 -0.53159869 0.82345855, + -0.25356492 -0.52464283 0.8126837, + -0.25476304 -0.48679605 0.8355391, + -0.30821884 -0.47889876 0.82198358, + -0.30922997 -0.44161895 0.84222889, + -0.36145887 -0.43298185 0.82575673, + -0.3622039 -0.39627391 0.84366781, + -0.41280091 -0.38722792 0.82440883, + -0.41320714 -0.35208213 0.83982033, + -0.46204379 -0.34288785 0.81788957, + -0.46206081 -0.30465189 0.83287871, + -0.4077822 -0.31366315 0.85751343, + -0.407251 -0.269649 0.872603, + -0.3527981 -0.27625805 0.89398825, + -0.35183087 -0.23175392 0.90692073, + -0.29628712 -0.23646709 0.92536336, + -0.29505202 -0.19192003 0.9360081, + -0.23994701 -0.194994 0.95100099, + -0.23860788 -0.15008293 0.95944852, + -0.18376099 -0.15191598 0.97116089, + -0.18249705 -0.10742304 0.97732037, + -0.12890603 -0.10834602 0.98572022, + -0.127817 -0.062762 0.98980999, + -0.075951405 -0.063098304 0.99511313, + -0.075248055 -0.020089388 0.99696243, + -0.024783896 -0.020140298 0.9994899, + 0.074155569 -0.00043599185 0.99724662, + 0.074498467 -0.020588793 0.99700862, + 0.12580003 -0.020482106 0.99184424, + 0.12695602 -0.063897304 0.98984814, + 0.17928709 -0.063374832 0.98175347, + 0.18076904 -0.10851202 0.97752124, + 0.23507792 -0.10723796 0.96604264, + 0.23668496 -0.15205099 0.95961487, + 0.29127806 -0.14971103 0.94485122, + 0.29287195 -0.19477096 0.93610376, + 0.34738001 -0.191017 0.91806298, + 0.34876099 -0.23520499 0.90721798, + 0.40360808 -0.22961406 0.88565123, + 0.40463206 -0.27371302 0.87255609, + 0.45827201 -0.266031 0.84806502, + 0.45876583 -0.30890989 0.83313173, + 0.51113087 -0.29880893 0.80588984, + 0.51103598 -0.336225 0.79107201, + 0.46463495 -0.34637296 0.8149479, + 0.46413478 -0.38028881 0.79997462, + 0.41515893 -0.39058593 0.8216359, + 0.414307 -0.42543799 0.804582, + 0.36322802 -0.43551806 0.8236441, + 0.3620548 -0.47169673 0.80400151, + 0.31004393 -0.48109087 0.82001483, + 0.30863115 -0.51758522 0.79803038, + 0.25485402 -0.52618206 0.81128412, + 0.25332391 -0.56271982 0.78687572, + 0.19795008 -0.57018316 0.79731232, + 0.19646697 -0.60627192 0.77060688, + 0.14071502 -0.61217105 0.77810413, + 0.13941205 -0.64822322 0.74857926, + 0.083815411 -0.65231204 0.7533021, + 0.082897492 -0.68734092 0.72158897, + 0.02764811 -0.68945122 0.72380424, + 0.027299404 -0.72290105 0.69041204, + -0.027831009 -0.72289026 0.69040221, + -0.028179597 -0.68944591 0.72378892, + -0.083654732 -0.68730223 0.72153825, + -0.084577501 -0.65256703 0.75299603, + -0.14013804 -0.64845121 0.74824625, + -0.14145893 -0.6121667 0.77797264, + -0.19688091 -0.6062817 0.77049363, + -0.19837396 -0.56993586 0.79738384, + -0.25370494 -0.56246686 0.78693384, + -0.25522193 -0.52623385 0.81113482, + -0.30897897 -0.51762795 0.79786789, + -0.31039402 -0.48112205 0.81986409, + -0.36261296 -0.47167295 0.80376387, + -0.36379379 -0.43553072 0.8233875, + -0.41458791 -0.4254919 0.80440885, + -0.41544715 -0.39032516 0.82161433, + -0.46416822 -0.38008219 0.80005336, + -0.46466321 -0.34618118 0.81501341, + -0.51126504 -0.33599204 0.79102314, + -0.51136202 -0.29893899 0.805695, + -0.45947912 -0.30896506 0.83271819, + -0.45899394 -0.26571098 0.84777486, + -0.40486899 -0.27346799 0.87252301, + -0.403869 -0.230046 0.88542002, + -0.34931481 -0.23562588 0.90689558, + -0.34793288 -0.19092493 0.91787267, + -0.29317188 -0.19469993 0.93602467, + -0.29159603 -0.14998202 0.94471014, + -0.23703088 -0.15232792 0.95948553, + -0.23542798 -0.10753898 0.96592391, + -0.18148795 -0.10881196 0.97735465, + -0.18000305 -0.063808918 0.98159426, + -0.12664597 -0.064346083 0.98985875, + -0.12547494 -0.02095109 0.99187553, + -0.074508399 -0.021059301 0.99699801, + -0.074155673 -0.00043606685 0.99724662, + -0.02466719 0.00010926296 0.99969566, + 0.02466719 0.00010926296 0.99969566, + 0.073425487 -0.00010906697 0.99730074, + 0.071232177 -0.00040823486 0.99745965, + 0.071235813 -0.00076167216 0.99745923, + 0.12341499 -0.00075777387 0.99235487, + 0.11951195 -0.0014493496 0.99283165, + 0.11952097 -0.0019508295 0.99282974, + 0.17322604 -0.0019352104 0.98488021, + 0.17329891 -0.0038848482 0.98486155, + 0.22556703 -0.0038428705 0.9742201, + 0.22663897 -0.025464097 0.97364587, + 0.27928805 -0.025104105 0.95987922, + 0.28170684 -0.068397671 0.9570595, + 0.3346709 -0.067173988 0.93993777, + 0.33718884 -0.11194595 0.93475759, + 0.39071608 -0.10945803 0.91398025, + 0.39304087 -0.15333194 0.90664673, + 0.44603795 -0.14924498 0.88248289, + 0.44804499 -0.19275101 0.87298501, + 0.49962613 -0.18676405 0.84586817, + 0.50114512 -0.22962306 0.83434218, + 0.55110896 -0.22141597 0.80452091, + 0.55199498 -0.26290199 0.791318, + 0.60005111 -0.25221905 0.75916016, + 0.600263 -0.28742501 0.74637198, + 0.55830508 -0.29814604 0.77421212, + 0.55808514 -0.3286621 0.76192015, + 0.51375103 -0.33981404 0.78777313, + 0.51316619 -0.37212911 0.77342129, + 0.46672112 -0.38345209 0.79695415, + 0.46576795 -0.41673094 0.78063786, + 0.41666016 -0.42810616 0.8019473, + 0.41533208 -0.46307811 0.7829802, + 0.36431298 -0.47407693 0.80157787, + 0.36271691 -0.50915086 0.78051382, + 0.31043789 -0.51936382 0.79617172, + 0.30863389 -0.55489683 0.7725507, + 0.25483608 -0.56411618 0.78538632, + 0.25295198 -0.59979594 0.7591179, + 0.19807796 -0.60767388 0.7690888, + 0.19627507 -0.64294624 0.74033523, + 0.140581 -0.649189 0.74752301, + 0.13906905 -0.68354326 0.71653926, + 0.083527565 -0.68783861 0.72104162, + 0.082490869 -0.72093475 0.68807578, + 0.027593497 -0.72312492 0.69016594, + 0.027194994 -0.7550528 0.65509981, + -0.027753396 -0.7550419 0.65508896, + -0.028151697 -0.72313392 0.69013393, + -0.08300098 -0.72092479 0.68802482, + -0.08404389 -0.68760991 0.72119993, + -0.13955095 -0.68329877 0.71667874, + -0.14105096 -0.6492058 0.74741983, + -0.19673093 -0.64294678 0.74021375, + -0.19853091 -0.60771871 0.76893663, + -0.25359097 -0.59979194 0.75890785, + -0.25548601 -0.56411201 0.78517801, + -0.30900595 -0.55492085 0.77238482, + -0.31080896 -0.51942992 0.79598391, + -0.3632701 -0.50916213 0.78024918, + -0.36487702 -0.47406206 0.80133009, + -0.41584507 -0.46305406 0.78272212, + -0.41717094 -0.42842394 0.80151188, + -0.46601087 -0.4170869 0.78030282, + -0.46697801 -0.383522 0.79676998, + -0.5135982 -0.37214211 0.77312827, + -0.51419091 -0.33986497 0.7874639, + -0.55828893 -0.32875898 0.76172888, + -0.55851394 -0.29830298 0.77400088, + -0.60044289 -0.28757694 0.74616879, + -0.60024595 -0.25272796 0.75883687, + -0.55219406 -0.26344004 0.79100013, + -0.55132484 -0.22184493 0.80425471, + -0.50114304 -0.23010702 0.8342101, + -0.49964795 -0.18746199 0.84570086, + -0.44830212 -0.19344604 0.8726992, + -0.44630885 -0.14981294 0.88224971, + -0.3933461 -0.15391703 0.90641522, + -0.3910329 -0.11005697 0.91377276, + -0.33755285 -0.11255895 0.93455261, + -0.33504811 -0.068023026 0.93974239, + -0.28176609 -0.069270723 0.95697933, + -0.27931896 -0.025604596 0.95985687, + -0.22666606 -0.025971906 0.97362626, + -0.22556703 -0.0038454004 0.9742201, + -0.17329891 -0.0038874082 0.98486155, + -0.17322604 -0.0019351104 0.98488021, + -0.11952097 -0.0019507295 0.99282974, + -0.11950599 -0.0010833299 0.9928329, + -0.069034502 -0.00073425 0.99761403, + -0.06903597 -0.0010885495 0.99761355, + -0.022797801 0.000410259 0.99974, + -0.022799101 -0.00043490401 0.99974, + -0.071232475 -0.00043391186 0.99745965, + -0.071235918 -0.00076164718 0.99745923, + -0.12341499 -0.0007577489 0.99235487, + -0.12345301 -0.0021674903 0.99234813, + -0.17461799 -0.0021506397 0.98463386, + -0.17546694 -0.023759291 0.98419863, + -0.22830811 -0.023496311 0.97330546, + -0.23037592 -0.067444175 0.97076166, + -0.28354895 -0.066463888 0.95665175, + -0.28576696 -0.11138499 0.95180386, + -0.33954903 -0.10932702 0.9342131, + -0.3416771 -0.15357803 0.92718422, + -0.39560881 -0.15008092 0.90607357, + -0.3975139 -0.19416195 0.89681876, + -0.45087215 -0.18887107 0.87237728, + -0.45237011 -0.23202406 0.86111915, + -0.50403708 -0.22470103 0.83394015, + -0.50500089 -0.26724693 0.82070285, + -0.55521607 -0.25752002 0.79083413, + -0.55553025 -0.29402915 0.77777433, + -0.50822097 -0.30454201 0.80558401, + -0.50781417 -0.26210809 0.82062429, + -0.45603007 -0.27077803 0.84777111, + -0.45502013 -0.22739705 0.86095721, + -0.40152919 -0.2338741 0.88548142, + -0.40006492 -0.18990995 0.89659476, + -0.34568891 -0.19443996 0.91798276, + -0.34392503 -0.14999801 0.92693913, + -0.2896581 -0.15289506 0.94483936, + -0.28776798 -0.10832699 0.95155388, + -0.23374191 -0.10997897 0.96605867, + -0.23188089 -0.06520167 0.9705565, + -0.17848998 -0.065952189 0.98172885, + -0.17684299 -0.021788998 0.98399788, + -0.12473303 -0.021965105 0.99194723, + -0.12414798 -0.0012909799 0.9922629, + -0.073444836 -0.0012975306 0.99729848, + -0.073425487 -0.00010906497 0.99730074, + 0.024479909 5.4849017e-005 0.99970037, + 0.02116769 0.010335496 0.99972254, + 0.023914712 0.011184006 0.99965149, + 0.023916196 0.00021850297 0.9997139, + 0.021168899 0.00021850897 0.99977589, + -0.0253751 -2.17875e-005 0.99967802, + -0.025374889 -0.0036021783 0.99967152, + -0.025635496 -0.0036021795 0.9996649, + -0.025635704 0.00075865909 0.9996711, + -0.025459386 0.00075865863 0.99967551, + -0.025459206 -0.003642071 0.99966925, + -0.073921196 0.010392899 0.99720991, + -0.073925167 0.00054869585 0.99726367, + -0.074661486 0.00054872991 0.99720877, + -0.074654132 0.014130205 0.99710935, + -0.077212773 0.012937895 0.99693066, + -0.78406054 0.013024593 -0.62054765, + -0.8432591 0.011790502 -0.53737807, + -0.84369683 0.012174597 -0.53668189, + -0.85095316 0.004290171 -0.52522409, + -0.95367712 0.22014503 -0.20502703, + -0.92217201 0.283041 -0.263603, + -0.92078763 0.28818592 -0.26286691, + -0.88981313 0.33714002 -0.30752102, + -0.90928876 0.26931393 -0.31727591, + -0.87915921 0.30837607 -0.36329508, + -0.90021074 0.22278194 -0.3741509, + -0.87364119 0.24893306 -0.41807109, + -0.88658273 0.18157695 -0.42544192, + -0.85990769 0.20037092 -0.46947882, + -0.87078041 0.12202506 -0.47628924, + -0.84368527 0.13323404 -0.52004218, + 0.75289088 -0.65813792 -0.0031303796, + 0.76072663 -0.64895773 0.012206495, + 0.78797299 -0.615601 0.011579, + 0.79436314 -0.60696405 0.024125203, + 0.82022411 -0.57159108 0.022719203, + 0.82363111 -0.56636208 0.029426605, + 0.85027981 -0.52562189 0.027309895, + 0.85333884 -0.52027589 0.033554293, + 0.90878689 -0.41451493 0.047789391, + 0.90463823 -0.42448509 0.037976906, + 0.88280332 -0.46787417 0.041858714, + 0.87772024 -0.47818011 0.030839408, + 0.87581891 -0.48228994 0.018371398, + 0.84932798 -0.52748299 0.020092901, + 0.84648484 -0.53221887 0.014369897, + 0.8222087 -0.56897885 0.015362495, + 0.81651628 -0.57730818 0.0040518814, + 0.79036897 -0.612616 0.00429969, + 0.78322285 -0.62166494 -0.0097333593, + 0.75568414 -0.65485609 -0.010253001, + 0.74750274 -0.66374075 -0.026228391, + 0.71860361 -0.69487756 -0.027458783, + 0.70952499 -0.703228 -0.045217901, + 0.67906827 -0.73256224 -0.04710412, + 0.66915196 -0.74012792 -0.066680394, + 0.63729906 -0.76750809 -0.06914711, + 0.62664932 -0.77402335 -0.090546042, + -0.71022356 0.62137562 -0.33086979, + -0.67266899 0.65312302 -0.347774, + -0.75252903 0.52520102 -0.39732099, + -0.74767399 0.53855401 -0.38851401, + -0.80577254 0.41358575 -0.42388377, + -0.76699013 0.44810805 -0.45926607, + -0.80320317 0.34761208 -0.48376712, + -0.76682889 0.37453997 -0.52124196, + -0.76314628 0.39197716 -0.51377219, + -0.72434777 0.41818586 -0.54812485, + -0.7220608 0.32108191 -0.61280888, + -0.75906485 0.30213997 -0.57665592, + -0.76027 0.29032201 -0.58112198, + -0.79517353 0.27100384 -0.54245371, + -0.79622966 0.25934988 -0.54658574, + -0.82884115 0.23984006 -0.50546914, + -0.80619091 0.33156097 -0.49002394, + -0.83952618 0.30447307 -0.44999111, + -0.8124851 0.39003906 -0.43328705, + -0.84229702 0.360623 -0.400608, + -0.96094799 0.207427 -0.183175, + -0.93372875 0.26833093 -0.23695794, + -0.92686862 0.29590288 -0.2309889, + -0.8923347 0.35580188 -0.2777479, + -0.8799997 0.39090386 -0.26980492, + -0.83076221 0.45810413 -0.3161881, + -0.82907069 0.46179181 -0.31526187, + -0.78129315 0.51549113 -0.35192308, + -0.81720102 0.44015801 -0.37208, + -0.79084212 0.46739706 -0.39510605, + -0.71595919 0.6038211 -0.3504321, + -0.76087862 0.56122679 -0.32571185, + -0.76163316 0.5599491 -0.32614708, + -0.8237139 0.48995394 -0.28537798, + -0.84306902 0.44798201 -0.29756799, + -0.88892031 0.38155714 -0.2534461, + -0.900527 0.34664801 -0.26246199, + -0.93246657 0.28801486 -0.2180679, + -0.93958825 0.25732005 -0.22574405, + -0.96093303 0.20806301 -0.182531, + -0.96191853 0.20203692 -0.18410291, + -0.97692251 0.15787792 -0.14386393, + -0.97694778 0.15766795 -0.14392297, + -0.98735821 0.11706603 -0.10686103, + -0.98741335 0.11641704 -0.10706104, + -0.99413526 0.079601124 -0.073203817, + -0.99401754 0.081691764 -0.072495162, + -0.9980191 0.047055408 -0.041758105, + -0.99796033 0.04886172 -0.041083217, + -0.99979323 0.015565503 -0.013087602, + -0.99978465 0.016367195 -0.012757795, + -0.999798 -0.0158519 0.0123561, + -0.99978733 -0.016834106 0.011912504, + -0.99815488 -0.049564492 0.035073895, + -0.99804038 -0.052898519 0.03342491, + -0.99479949 -0.086103752 0.054406174, + -0.99442637 -0.092224427 0.051098119, + -0.98949689 -0.12644298 0.070057392, + -0.98865145 -0.13560405 0.064653032, + -0.98186338 -0.17113405 0.081593029, + -0.98023552 -0.18366492 0.073521465, + -0.97148663 -0.22011392 0.088111773, + -0.96870977 -0.23596694 0.076948583, + -0.9577291 -0.27349702 0.089187011, + -0.95325923 -0.29290107 0.074201018, + -0.93971026 -0.33150008 0.083979324, + -0.9329409 -0.35417497 0.064662591, + -0.91650701 -0.39351401 0.071844898, + 0.55067295 -0.82585889 -0.12131099, + 0.50756299 -0.852467 -0.125219, + 0.49969912 -0.85436219 -0.14271003, + 0.46461895 -0.87340987 -0.14589198, + 0.4536162 -0.87447244 -0.17184408, + 0.4182409 -0.89128977 -0.17514895, + 0.40708515 -0.89050931 -0.20316207, + 0.37156412 -0.90515029 -0.20650208, + 0.36086199 -0.90242797 -0.235377, + 0.3251659 -0.91504377 -0.23866694, + 0.31504396 -0.91034585 -0.26836097, + 0.27942207 -0.92098439 -0.27149808, + 0.27008504 -0.91431212 -0.30180702, + 0.23511 -0.922984 -0.30467001, + 0.2266819 -0.9143576 -0.33550784, + 0.19260095 -0.92121875 -0.33802491, + 0.18528005 -0.91077131 -0.36900812, + 0.15185992 -0.91606957 -0.37115383, + 0.15176706 -0.91588932 -0.37163612, + 0.11942296 -0.91999167 -0.37330088, + 0.12351397 -0.93078876 -0.3440589, + 0.089128889 -0.9342379 -0.34533396, + 0.091789998 -0.94432998 -0.315936, + 0.055665791 -0.94686288 -0.31678396, + 0.057108283 -0.95612264 -0.2873469, + 0.019505704 -0.95750326 -0.28776205, + 0.019929903 -0.9659161 -0.25808704, + -0.0192552 -0.96592897 -0.25808999, + -0.018825401 -0.95752501 -0.28773499, + -0.056477107 -0.95616615 -0.28732702, + -0.055033017 -0.94693333 -0.31668413, + -0.091196358 -0.94441855 -0.31584284, + -0.088529497 -0.93437397 -0.34512001, + -0.12325694 -0.93090457 -0.34383783, + -0.11916996 -0.92014563 -0.37300187, + -0.15185894 -0.91600168 -0.37132189, + -0.15188399 -0.91605085 -0.37118998, + -0.1852679 -0.91075844 -0.36904579, + -0.19262992 -0.92126262 -0.33788887, + -0.22678408 -0.91438431 -0.33536613, + -0.23520409 -0.92299938 -0.30455112, + -0.27033892 -0.91428071 -0.30167487, + -0.2796731 -0.92095536 -0.27133808, + -0.31532884 -0.91029561 -0.26819688, + -0.32539403 -0.9149701 -0.23863903, + -0.36100996 -0.90237486 -0.23535398, + -0.37166783 -0.90508556 -0.20659889, + -0.40708816 -0.89048427 -0.20326607, + -0.418127 -0.89125901 -0.175577, + -0.45345786 -0.87447071 -0.17226994, + -0.464656 -0.87339503 -0.145863, + -0.49980381 -0.8543067 -0.14267495, + -0.51121211 -0.8514362 -0.11712603, + -0.54547608 -0.83030713 -0.11421902, + -0.5568189 -0.82575881 -0.089862175, + -0.59016889 -0.80254179 -0.087335579, + -0.60111624 -0.79654533 -0.064613022, + -0.63381469 -0.77095264 -0.06253697, + -0.64410794 -0.76379687 -0.041703995, + -0.67587924 -0.73591626 -0.040181715, + -0.68543303 -0.72782707 -0.021197202, + -0.71567422 -0.69813824 -0.020332608, + -0.72436792 -0.68940592 -0.0032513896, + -0.75299591 -0.65801793 -0.0031033596, + -0.76067871 -0.64901876 0.011935095, + -0.78790927 -0.61568725 0.011322204, + -0.79407412 -0.60737008 0.023408102, + -0.81990373 -0.5720768 0.022047892, + -0.8269999 -0.56103891 0.036145497, + -0.8508082 -0.52438915 0.033784308, + -0.86055619 -0.5064851 0.05399821, + -0.88399976 -0.46485287 0.049559589, + -0.88902289 -0.45379093 0.060927391, + -0.90990168 -0.41113484 0.055200282, + -0.90774798 -0.41780099 0.037893701, + -0.88306475 -0.46733287 0.042386089, + -0.87460899 -0.48422101 0.024273301, + -0.8523401 -0.52233207 0.026183704, + -0.84619087 -0.53270394 0.013697398, + -0.82191288 -0.56942493 0.014641598, + -0.81643629 -0.57742316 0.0037763815, + -0.79030085 -0.61270589 0.004007129, + -0.78330791 -0.62155795 -0.0097189089, + -0.75577939 -0.65474629 -0.010237904, + -0.74772274 -0.66350275 -0.02597929, + -0.71883225 -0.69465125 -0.027198909, + -0.7098338 -0.70294183 -0.044817489, + -0.67937469 -0.73230463 -0.046689577, + -0.66951215 -0.73984617 -0.066190213, + -0.63760662 -0.76729751 -0.068646066, + -0.62692493 -0.7738499 -0.090119094, + -0.59421796 -0.7989049 -0.09303689, + -0.58299381 -0.80413067 -0.11615595, + -0.54967213 -0.82679915 -0.11943103, + -0.53818321 -0.8304584 -0.14386708, + -0.50409698 -0.850972 -0.147421, + -0.49274093 -0.8528809 -0.17262799, + -0.45761713 -0.87147719 -0.17639205, + -0.44626114 -0.8715933 -0.20291908, + -0.41093805 -0.8879171 -0.20672002, + -0.39973915 -0.88613027 -0.23448209, + -0.36449191 -0.90022278 -0.23821095, + -0.35369599 -0.89646298 -0.26693299, + -0.318407 -0.90853298 -0.27052701, + -0.30817088 -0.9027487 -0.30012587, + -0.27293307 -0.91290426 -0.30350205, + -0.26345405 -0.90508723 -0.33378008, + -0.22897008 -0.91330731 -0.33681211, + -0.22044307 -0.90353632 -0.36746013, + -0.18693306 -0.90999532 -0.37008712, + -0.18698391 -0.91007161 -0.36987382, + -0.15453798 -0.91528177 -0.37199092, + -0.15984495 -0.92578775 -0.34258792, + -0.12513794 -0.93047458 -0.34432182, + -0.12889205 -0.94032735 -0.31491512, + -0.09255179 -0.9441669 -0.31620097, + -0.09497422 -0.95330024 -0.28670305, + -0.057237893 -0.95605886 -0.28753296, + -0.058548026 -0.96443647 -0.25774911, + -0.0194472 -0.96591097 -0.25814301, + -0.019837206 -0.97341424 -0.22819106, + 0.020466294 -0.97340178 -0.22818895, + 0.020083494 -0.96590173 -0.25812894, + 0.059171878 -0.96440363 -0.2577289, + 0.057866521 -0.95601535 -0.28755209, + 0.095555387 -0.95323789 -0.28671697, + 0.093132667 -0.94407964 -0.31629089, + 0.12935606 -0.94023448 -0.31500214, + 0.12558395 -0.9303146 -0.34459183, + 0.15995102 -0.92566514 -0.34287003, + 0.15462592 -0.9151206 -0.37235081, + 0.18699598 -0.90992188 -0.37023598, + 0.18702805 -0.90997022 -0.37010109, + 0.22037406 -0.90354222 -0.3674871, + 0.22886908 -0.91328031 -0.33695412, + 0.26338002 -0.90505713 -0.33392003, + 0.27282989 -0.91285557 -0.30374086, + 0.30796513 -0.90273631 -0.30037412, + 0.31821096 -0.90853286 -0.27075797, + 0.3535811 -0.89644223 -0.26715505, + 0.36442199 -0.90022898 -0.238295, + 0.39956605 -0.88618314 -0.23457703, + 0.41086814 -0.88798732 -0.20655708, + 0.44617012 -0.87167621 -0.20276305, + 0.45768288 -0.8715468 -0.17587696, + 0.49285194 -0.85291988 -0.17211798, + 0.50397515 -0.85104132 -0.14743707, + 0.53813201 -0.83048999 -0.143876, + 0.54945713 -0.82688916 -0.11979603, + 0.58275193 -0.80425388 -0.11651599, + 0.59394723 -0.79905528 -0.093474329, + 0.59457701 -0.798482 -0.0943648, + 0.55306399 -0.82738101 -0.097779997, + 0.54881006 -0.82908314 -0.10690501, + 0.51115394 -0.85243189 -0.10991599, + 0.50662702 -0.85376102 -0.120088, + 0.4681648 -0.8750276 -0.12307894, + 0.46036193 -0.8763749 -0.14154099, + 0.42488986 -0.89366472 -0.14433296, + 0.41420391 -0.89389676 -0.17141695, + 0.37840384 -0.90907669 -0.17432794, + 0.36777997 -0.90741485 -0.20331296, + 0.33189508 -0.92049426 -0.20624304, + 0.32186112 -0.91687536 -0.23610409, + 0.28579006 -0.92801726 -0.23897307, + 0.27655292 -0.92245567 -0.2694329, + 0.24107194 -0.93158275 -0.27209893, + 0.23275305 -0.92410421 -0.30308005, + 0.19785704 -0.93141609 -0.30547804, + 0.19059409 -0.9221034 -0.33674815, + 0.15643394 -0.92775762 -0.33881289, + 0.15034004 -0.91669226 -0.3702341, + 0.11709096 -0.92085266 -0.37191388, + 0.11697596 -0.92055762 -0.37267989, + 0.084509104 -0.92360514 -0.37391403, + 0.087410174 -0.93456578 -0.34488592, + 0.053162392 -0.93682986 -0.34572196, + 0.054745808 -0.94699913 -0.31653702, + 0.018554002 -0.9482581 -0.31695804, + 0.019038903 -0.95755112 -0.28763402, + -0.01846741 -0.95756149 -0.28763714, + -0.017976491 -0.94827753 -0.31693286, + -0.054401811 -0.94702625 -0.31651509, + -0.05282652 -0.93688536 -0.34562311, + -0.087250657 -0.93461758 -0.34478581, + -0.084362328 -0.92370033 -0.37371212, + -0.11707401 -0.9206301 -0.37247002, + -0.11715 -0.92082298 -0.37196901, + -0.15039393 -0.91666168 -0.3702879, + -0.15650505 -0.92775625 -0.3387841, + -0.19078009 -0.92207843 -0.33671114, + -0.19806197 -0.9314279 -0.30530897, + -0.2327899 -0.92414665 -0.30292189, + -0.24113905 -0.93163526 -0.27186006, + -0.27669102 -0.92248511 -0.26919004, + -0.2858991 -0.92801434 -0.2388541, + -0.32197201 -0.91686702 -0.235985, + -0.33193108 -0.92045122 -0.20637704, + -0.36791191 -0.90733379 -0.20343596, + -0.37842906 -0.90898913 -0.17472902, + -0.41406614 -0.89388227 -0.17182507, + -0.424934 -0.89365101 -0.144288, + -0.46038812 -0.87636822 -0.14149803, + -0.47162282 -0.87429971 -0.11476895, + -0.50688785 -0.85467982 -0.11219297, + -0.51820594 -0.85085487 -0.086651392, + -0.55259514 -0.82916117 -0.084442124, + -0.56366819 -0.82378328 -0.060493223, + -0.59709072 -0.80001962 -0.05874807, + -0.60769689 -0.79332584 -0.036588691, + -0.64032084 -0.76729184 -0.035387993, + -0.65030491 -0.75952387 -0.015069298, + -0.68196601 -0.73123997 -0.0145082, + -0.69120401 -0.72264898 0.0039280001, + -0.72125566 -0.69265866 0.0037649882, + -0.72956496 -0.68361497 0.020139297, + -0.75794202 -0.65203899 0.0192091, + -0.76474899 -0.643507 0.032523599, + -0.79172415 -0.61010003 0.030835204, + -0.79975528 -0.59851426 0.046608813, + -0.82514417 -0.5632171 0.043860011, + -0.83617312 -0.54445106 0.066240206, + -0.86141872 -0.50417781 0.061340477, + -0.86725086 -0.49232593 0.074102595, + -0.88978785 -0.45129094 0.067926191, + -0.89426523 -0.44060111 0.07848902, + -0.91675442 -0.39326018 0.070055932, + -0.91822624 -0.38657108 0.086159222, + -0.89895815 -0.42754406 0.095291413, + -0.89489114 -0.43805507 0.085308805, + -0.8731581 -0.47844905 0.093175307, + -0.8679387 -0.48997581 0.081278168, + -0.84354091 -0.52982491 0.08788839, + -0.83692569 -0.54232782 0.073729172, + -0.80980146 -0.58135635 0.079035148, + -0.44745705 -0.89395612 -0.024995504, + -0.48706281 -0.87302572 -0.024410291, + -0.49131107 -0.87087113 -0.014031802, + -0.53048897 -0.84758186 -0.013656599, + -0.53457212 -0.8451122 -0.0042514009, + -0.57749087 -0.81638682 -0.004106889, + -0.57657814 -0.81703717 -0.0028144207, + -0.61001396 -0.79238588 -0.0027294997, + -0.62006593 -0.78433186 0.018484699, + -0.65256417 -0.75752318 0.017852904, + -0.66189474 -0.74868476 0.036966685, + -0.69323742 -0.71983242 0.035542123, + -0.7011888 -0.71111685 0.051448587, + -0.73084164 -0.68076771 0.049252879, + -0.73575437 -0.67468631 0.058855031, + -0.76690716 -0.63933021 0.055770714, + -0.77262628 -0.63131124 0.067043521, + -0.80195719 -0.59404111 0.063085616, + -0.80012536 -0.59812129 0.045280121, + -0.76643687 -0.64048696 0.048487391, + -0.76203901 -0.64629698 0.039960202, + -0.73389083 -0.67797279 0.041918688, + -0.72648293 -0.68664092 0.027329396, + -0.69663405 -0.71685904 0.028532105, + -0.68776721 -0.72585118 0.010794003, + -0.65628481 -0.75442982 0.011218897, + -0.64657104 -0.7628051 -0.0086280406, + -0.61400199 -0.78925401 -0.0089272102, + -0.6037001 -0.7966252 -0.030570608, + -0.57026595 -0.82085586 -0.031500395, + 0.42377594 -0.89962685 -0.10528699, + 0.47041512 -0.87646323 -0.10257602, + 0.47491181 -0.8752327 -0.09179607, + 0.51364392 -0.85332286 -0.089498192, + 0.51802617 -0.8516553 -0.079574227, + 0.55583596 -0.82768691 -0.077334791, + 0.55998385 -0.82567769 -0.068370774, + 0.60138512 -0.79623419 -0.065932713, + 0.64391392 -0.76392686 -0.042316496, + 0.60405314 -0.79572415 -0.04407781, + 0.60025501 -0.79811603 -0.052007299, + 0.56334692 -0.82447189 -0.053724691, + 0.55923897 -0.82663703 -0.0626335, + 0.52139407 -0.85087711 -0.064470105, + 0.51707673 -0.85270947 -0.074283957, + 0.47821975 -0.87492657 -0.076219462, + 0.47377595 -0.87634587 -0.086914793, + 0.43478286 -0.89613873 -0.088877767, + 0.42711285 -0.89766067 -0.10853596, + 0.39093307 -0.91376412 -0.11048301, + 0.38066199 -0.91420501 -0.139017, + 0.34420297 -0.92822486 -0.14114898, + 0.33454689 -0.92682463 -0.17051195, + 0.29760912 -0.93893033 -0.17273906, + 0.28849614 -0.93559641 -0.2035421, + 0.25199893 -0.94560874 -0.20571996, + 0.24380513 -0.94039547 -0.23709811, + 0.20777297 -0.94849485 -0.23913997, + 0.20061097 -0.94144988 -0.27097496, + 0.16514206 -0.94779134 -0.27280009, + 0.15914398 -0.93901187 -0.30484396, + 0.12416506 -0.94377345 -0.30639014, + 0.11939406 -0.93330044 -0.33866715, + 0.085534066 -0.93657959 -0.33985686, + 0.082088336 -0.9245854 -0.37202618, + 0.049476724 -0.92658043 -0.37282819, + 0.0494009 -0.92610401 -0.37402001, + 0.0167688 -0.92710602 -0.37442401, + 0.017340306 -0.93816239 -0.34576112, + -0.017166404 -0.93816525 -0.3457621, + -0.016598104 -0.92713124 -0.37436908, + -0.049469389 -0.92612374 -0.3739619, + -0.049540389 -0.92656976 -0.37284592, + -0.082119346 -0.92457545 -0.37204379, + -0.085571721 -0.93659025 -0.33981809, + -0.119501 -0.93330199 -0.33862501, + -0.12428494 -0.94379753 -0.30626684, + -0.15912405 -0.93905324 -0.30472705, + -0.16514799 -0.94784689 -0.27260298, + -0.20072493 -0.94148362 -0.2707729, + -0.20786311 -0.94848645 -0.23909512, + -0.24397688 -0.94036353 -0.23704788, + -0.25213397 -0.94555289 -0.20581096, + -0.28859109 -0.93554735 -0.20363307, + -0.29764798 -0.93886489 -0.17302698, + -0.33453384 -0.92677659 -0.17079893, + -0.34427091 -0.92819679 -0.14116697, + -0.38075492 -0.91416377 -0.13903297, + -0.39112014 -0.91371727 -0.11020803, + -0.4273009 -0.89760375 -0.10826498, + -0.43806189 -0.89533174 -0.080516279, + -0.47405118 -0.87695831 -0.078864031, + -0.48179507 -0.87421012 -0.060251009, + -0.52073383 -0.8516987 -0.058699477, + -0.5249998 -0.8496927 -0.048963681, + -0.56294185 -0.82512772 -0.047548082, + -0.56477004 -0.82291913 -0.061959807, + -0.52169079 -0.8507266 -0.064053468, + -0.51392788 -0.8539418 -0.081619181, + -0.47837806 -0.87417012 -0.083552711, + -0.46727282 -0.87721968 -0.11018996, + -0.43156508 -0.89504826 -0.11242903, + -0.420683 -0.89630198 -0.14024501, + -0.38486105 -0.91187912 -0.14268301, + -0.3744719 -0.91127676 -0.17130496, + -0.33828789 -0.92484367 -0.17385495, + -0.32841408 -0.92233324 -0.20358205, + -0.29193401 -0.93395799 -0.206148, + -0.28282198 -0.92953587 -0.23658997, + -0.246804 -0.93912297 -0.239031, + -0.23858409 -0.93280333 -0.2701031, + -0.20309907 -0.94052237 -0.27233908, + -0.19589092 -0.93234664 -0.30390188, + -0.160947 -0.93837202 -0.305866, + -0.15486699 -0.92839801 -0.33777699, + -0.12079999 -0.93285388 -0.33939797, + -0.11600297 -0.92123973 -0.3712959, + -0.082972109 -0.92430311 -0.37253103, + -0.082886368 -0.92398763 -0.37333187, + -0.050182194 -0.92600989 -0.37414896, + -0.051904213 -0.93702722 -0.3453781, + -0.017282294 -0.93815166 -0.34579289, + -0.017810896 -0.94829577 -0.31688792, + 0.018284297 -0.94828779 -0.31688491, + 0.017761298 -0.93811285 -0.34587398, + 0.052164182 -0.93698364 -0.34545687, + 0.050446793 -0.92593688 -0.37429398, + 0.082837299 -0.923931 -0.373483, + 0.082941025 -0.92431325 -0.37251309, + 0.116006 -0.92124701 -0.371277, + 0.12078501 -0.93282014 -0.33949602, + 0.15490292 -0.9283576 -0.33787185, + 0.16096708 -0.93833047 -0.30598316, + 0.19563097 -0.93235791 -0.30403498, + 0.20285396 -0.94054186 -0.27245396, + 0.23833995 -0.93283176 -0.27021995, + 0.246595 -0.93917203 -0.23905399, + 0.2825889 -0.92959964 -0.23661791, + 0.29176188 -0.93404466 -0.20599893, + 0.32835212 -0.92238933 -0.20342807, + 0.33827496 -0.9249059 -0.17354898, + 0.37455609 -0.91130024 -0.17099604, + 0.38481295 -0.91189587 -0.14270599, + 0.42061701 -0.89632899 -0.14026999, + 0.4282971 -0.89553326 -0.12075503, + 0.46700817 -0.87632227 -0.11816405, + 0.47153282 -0.87528872 -0.10736096, + 0.51020706 -0.85365415 -0.10470702, + 0.51460016 -0.85217428 -0.094793141, + 0.55232787 -0.82851684 -0.092161477, + 0.55657715 -0.82663816 -0.083013423, + 0.59343833 -0.80085135 -0.080423936, + 0.60079575 -0.79674971 -0.065071277, + 0.63346976 -0.7711997 -0.062984578, + 0.64379299 -0.76403999 -0.042113502, + 0.67555767 -0.73618966 -0.04057838, + 0.68517596 -0.72806096 -0.021473998, + 0.71543974 -0.69837075 -0.020598292, + 0.72425526 -0.68952423 -0.0032796711, + 0.72112596 -0.69279397 0.0037391295, + 0.72958577 -0.68358475 0.020407492, + 0.75798112 -0.65198606 0.019464202, + 0.76503682 -0.64312583 0.033283692, + 0.79202402 -0.60967398 0.031552501, + 0.79600817 -0.60400814 0.039310113, + 0.82446867 -0.56471282 0.036752686, + 0.82821691 -0.55865896 0.044237196, + 0.85436487 -0.51805192 0.041021798, + 0.86026073 -0.50705183 0.053385083, + 0.88373888 -0.46540794 0.049000591, + 0.88867509 -0.45457706 0.060135409, + 0.90958786 -0.41192293 0.054492794, + 0.9133023 -0.40227914 0.063642219, + 0.93359077 -0.35393891 0.055994485, + 0.75689751 0.065483361 -0.65024459, + 0.75424314 0.57228607 -0.32187903, + 0.76059544 0.56171656 -0.32552877, + 0.8229267 0.49156681 -0.28487492, + 0.84312457 0.4478648 -0.29758686, + 0.93858922 0.27544206 -0.20780304, + 0.90019375 0.3476499 -0.26227993, + 0.88890791 0.38153893 -0.25351697, + 0.88969278 0.37633592 -0.25849193, + 0.83002728 0.45972317 -0.31576812, + 0.8244428 0.47169688 -0.3127239, + 0.77578032 0.52592015 -0.34867311, + 0.81048602 0.45568401 -0.36805499, + 0.76931947 0.4969973 -0.40142423, + 0.80344868 0.41964084 -0.42234084, + 0.76444685 0.45439795 -0.45732194, + 0.80476767 0.34279886 -0.48460075, + 0.76856762 0.36946681 -0.52230078, + 0.79879469 0.25478491 -0.5449878, + 0.76431501 0.27309701 -0.584158, + 0.7850911 0.14783402 -0.60147905, + 0.75086999 0.157636 -0.64136201, + 0.7589789 0.053965494 -0.64887494, + 0.78804821 0.065517716 -0.61211711, + 0.78760785 0.065572187 -0.61267787, + 0.78930283 -0.0031844394 -0.61399591, + 0.7897408 -0.0032907594 -0.61343187, + 0.75851202 0.0060454002 -0.651631, + 0.53623605 0.00031159603 -0.84406811, + 0.72638702 -0.0036903501 0.68727601, + 0.68865067 0.0053217676 0.72507364, + 0.68861681 -0.011267297 0.72503781, + 0.61420399 -0.0072482899 0.789114, + 0.61421674 0.0032584588 0.78913069, + 0.61494327 0.0031112412 0.78856528, + 0.61493021 -0.007241583 0.78854829, + 0.65642977 -0.050682981 0.75268269, + 0.69401395 -0.048370093 0.71833491, + 0.69763321 -0.094586223 0.71018416, + 0.73680717 -0.089259021 0.67018521, + 0.73887962 -0.12611394 0.66193068, + 0.77540737 -0.11818306 0.62030327, + 0.77665013 -0.15284501 0.61110806, + 0.80988067 -0.14232896 0.56906581, + 0.81037301 -0.175474 0.559021, + 0.83799112 -0.16342601 0.52063704, + 0.83773881 -0.14019898 0.52776688, + 0.80743349 -0.15146708 0.57018334, + 0.80649817 -0.11823803 0.57929313, + 0.77295184 -0.12688297 0.62164789, + 0.77121091 -0.091495693 0.62996995, + 0.7343598 -0.097558379 0.67171282, + 0.73109782 -0.052693591 0.68023485, + 0.6884672 -0.056014214 0.7231012, + 0.68727893 -0.040569097 0.72525996, + 0.63507378 -0.043141384 0.77124572, + 0.63480681 -0.037140194 0.77177781, + 0.57934582 -0.039178785 0.81413972, + 0.57935596 -0.040938295 0.81404591, + 0.61347973 -0.039664283 0.78871369, + 0.61356229 -0.032079916 0.78899437, + 0.65062404 -0.030851103 0.75877315, + 0.65078616 -0.011881803 0.75916821, + 0.65184182 -0.012387997 0.75825381, + 0.65189022 -0.0021516306 0.75831032, + 0.65242624 -0.0021516706 0.75784928, + 0.65239793 -0.0095969792 0.7578159, + 0.65153104 -0.0096071912 0.75856113, + 0.65155917 -0.0026777808 0.7585932, + 0.67918408 0.015077402 0.73381305, + 0.40694594 0.0028441697 -0.91344786, + 0.40750808 0.0031441906 -0.91319627, + 0.40339383 0.14177392 -0.90397656, + 0.40283495 0.14180498 -0.90422088, + 0.43583593 0.076748393 -0.89674789, + 0.41806599 0.295809 -0.85890502, + 0.46337295 0.28856197 -0.83786488, + 0.419808 0.50150001 -0.75647801, + 0.46391287 0.48949188 -0.73836482, + -0.030732885 0.99322051 0.11210895, + -0.075614139 0.9765445 0.20160209, + 0.25207913 -0.9676075 -0.013857907, + 0.25154305 -0.96681523 -0.04465951, + 0.29753804 -0.95369309 -0.044053305, + 0.29631105 -0.95222121 -0.073990911, + 0.3416059 -0.93701875 -0.072809584, + 0.33952704 -0.93499613 -0.10248802, + 0.383939 -0.91786098 -0.100609, + 0.38086793 -0.91543889 -0.13004299, + 0.42376384 -0.8967697 -0.12739095, + 0.41957209 -0.89410126 -0.15666005, + 0.46089894 -0.87413585 -0.15316199, + 0.45545387 -0.8713758 -0.18238996, + 0.49534306 -0.85027111 -0.17797302, + 0.48848793 -0.8475709 -0.20737197, + 0.52699196 -0.82552087 -0.20197697, + 0.51856399 -0.823053 -0.23167901, + 0.55510974 -0.80066162 -0.22537589, + 0.54499 -0.79860699 -0.25536799, + 0.57981873 -0.77603567 -0.24815089, + 0.5678249 -0.77456385 -0.27861395, + 0.60134494 -0.75182986 -0.27043697, + 0.58720994 -0.75113785 -0.30162296, + 0.61967301 -0.728333 -0.29246601, + 0.60309625 -0.72863424 -0.32460311, + 0.63401616 -0.70639318 -0.31469408, + 0.63070804 -0.70673305 -0.32052404, + 0.66531491 -0.67990595 -0.30835697, + 0.67663831 -0.67742032 -0.28855214, + 0.71022475 -0.64766675 -0.27587792, + 0.72029597 -0.64398092 -0.25780296, + 0.75272882 -0.61117589 -0.24466994, + 0.76139432 -0.60665321 -0.22858408, + 0.79186034 -0.57148027 -0.21533111, + 0.79919618 -0.56641513 -0.20114504, + 0.82771218 -0.52879912 -0.18778704, + 0.83371681 -0.52353388 -0.17558095, + 0.86034083 -0.48326489 -0.16207595, + 0.8650372 -0.47814611 -0.15194403, + 0.88973725 -0.43503609 -0.13824403, + 0.89285713 -0.43086007 -0.13101801, + 0.91526985 -0.38541594 -0.11719899, + 0.91860163 -0.37992585 -0.10875396, + 0.93852609 -0.33187902 -0.095000915, + 0.94122487 -0.32630897 -0.087282591, + 0.95849079 -0.27543995 -0.073675983, + 0.96025962 -0.27075791 -0.067760475, + 0.97470313 -0.21681704 -0.054261208, + 0.97575402 -0.213098 -0.0499328, + 0.98694879 -0.15678796 -0.036738392, + 0.98747885 -0.15408498 -0.033811796, + 0.99522787 -0.095309786 -0.020914398, + 0.99541765 -0.093665972 -0.019244792, + 0.99946791 -0.031950098 -0.0065645291, + 0.99948752 -0.031431686 -0.0060667973, + 0.99945176 0.032509591 0.0062748385, + 0.99946678 0.032113392 0.0059125884, + 0.99474776 0.10066498 0.018533995, + 0.99483979 0.099876881 0.017842397, + 0.98454267 0.17241494 0.030800888, + 0.98629135 0.16338606 0.023118207, + 0.97097534 0.23682109 0.033508711, + 0.97473979 0.22230893 0.021471594, + 0.95476913 0.29597104 0.028586203, + 0.95983362 0.28012791 0.015739195, + 0.93523467 0.35347089 0.019859992, + 0.94153267 0.33685687 0.0066110077, + 0.91187042 0.4103992 0.0080543142, + 0.91866988 0.39500493 -0.0041038496, + 0.8831529 0.46905994 -0.0048732297, + 0.88974613 0.45620805 -0.015036002, + 0.8473981 0.53067005 -0.017490203, + 0.85234261 0.52242678 -0.024129888, + 0.80237317 0.59618711 -0.027536808, + 0.803949 0.59397101 -0.029401099, + 0.74535197 0.66585594 -0.032959297, + 0.74069077 0.67126077 -0.028039191, + 0.67278892 0.73918992 -0.030876696, + 0.65896672 0.75196564 -0.017619291, + 0.58285987 0.8123498 -0.019034196, + 0.55764616 0.83007127 0.0035192613, + 0.47751093 0.87861788 0.0037250896, + 0.44075784 0.89692873 0.03537469, + 0.36230397 0.93133587 0.036731698, + 0.31596187 0.94568366 0.076488674, + 0.24549794 0.96624178 0.078151479, + 0.19817208 0.97278637 0.12006105, + 0.14061595 0.98260862 0.12127396, + 0.12723698 0.98277777 0.13400997, + 0.079138033 0.98772335 0.13468404, + 0.06662368 0.98676366 0.14784694, + 0.026985096 0.98860091 0.14812198, + 0.0095388452 0.98563653 0.16861093, + -0.020199908 0.98548037 0.16858406, + -0.028212804 0.98340511 0.17921601, + -0.050484512 0.98254222 0.17905904, + -0.056184016 0.98061824 0.18770005, + -0.07202962 0.97961837 0.18750907, + -0.080057576 0.97620475 0.20153196, + -0.017167805 0.99657035 0.08095023, + -0.068789497 0.98267001 0.17212699, + -0.07116241 0.9825061 0.17209801, + -0.059420802 0.98631001 0.153824, + -0.037985992 0.98734277 0.15398496, + -0.028390907 0.98961425 0.14091703, + 0.00063270307 0.99001312 0.14097401, + 0.013475707 0.99199849 0.12552907, + 0.051322311 0.99078125 0.12537403, + 0.07612624 0.99220049 0.098707147, + 0.12554301 0.9872151 0.098211117, + 0.14291899 0.98638988 0.081297494, + 0.201873 0.97610199 0.080449603, + 0.21909603 0.97353214 0.065054908, + 0.28716004 0.95575112 0.063866809, + 0.34037101 0.94010502 0.018714599, + 0.41847801 0.90804702 0.0180765, + 0.46482906 0.88515013 -0.021054002, + 0.54583186 0.83765781 -0.019924294, + 0.57820231 0.8144694 -0.048184924, + 0.65526217 0.75408316 -0.044612411, + 0.67450494 0.73560995 -0.062618695, + 0.74269825 0.66721326 -0.056796517, + 0.75138611 0.65657508 -0.065788507, + 0.80934966 0.58440071 -0.058556672, + 0.81088102 0.58209097 -0.060349699, + 0.85933816 0.50868112 -0.052738812, + 0.85664016 0.5135721 -0.049105812, + 0.89691174 0.44020188 -0.04209039, + 0.89232701 0.45003799 -0.034905002, + 0.92538935 0.37788314 -0.02930871, + 0.92018634 0.39098415 -0.019715607, + 0.9472689 0.32003298 -0.016137898, + 0.94239825 0.33444908 -0.0054225014, + 0.9644025 0.26440412 -0.0042868517, + 0.96030778 0.27886194 0.0067083687, + 0.97789115 0.20905402 0.0050290506, + 0.97497255 0.2218179 0.015010593, + 0.98820603 0.15278099 0.0103388, + 0.98639274 0.16332196 0.018848397, + 0.99546188 0.094533287 0.010909799, + 0.99486154 0.10004795 0.015522593, + 0.99947822 0.031918708 0.0049522612, + 0.99946612 0.032249402 0.0052401503, + 0.99950075 -0.031187892 -0.0050676586, + 0.99948555 -0.031606086 -0.0054500373, + 0.99556679 -0.092689477 -0.015983095, + 0.99539334 -0.094264239 -0.017506106, + 0.98790252 -0.15246892 -0.028315486, + 0.98740077 -0.15515597 -0.031084593, + 0.97657335 -0.21099207 -0.042271115, + 0.975582 -0.214687 -0.046359301, + 0.96159637 -0.26828408 -0.057933223, + 0.95994252 -0.27291089 -0.063481972, + 0.94320089 -0.32358396 -0.075269192, + 0.94070727 -0.32905009 -0.08243832, + 0.92136747 -0.37703976 -0.09446124, + 0.91782534 -0.38325915 -0.10348504, + 0.89601856 -0.4286648 -0.11574595, + 0.89179111 -0.43468207 -0.12554002, + 0.86773628 -0.47750917 -0.13790904, + 0.8636899 -0.48221794 -0.14664799, + 0.83774114 -0.52244306 -0.15888101, + 0.83205539 -0.52783823 -0.17050107, + 0.80435783 -0.56538087 -0.18262796, + 0.79727709 -0.57075208 -0.19644703, + 0.76754713 -0.60609609 -0.20861202, + 0.75922889 -0.61097592 -0.22423197, + 0.72767162 -0.64392871 -0.23632587, + 0.71800107 -0.64806706 -0.25393602, + 0.68524206 -0.67811608 -0.26571003, + 0.67429507 -0.68117106 -0.28518802, + 0.64054871 -0.70834166 -0.29656285, + 0.62846398 -0.70998597 -0.31773099, + 0.59351993 -0.73461294 -0.32875198, + 0.59649938 -0.73455542 -0.32344517, + 0.56493109 -0.75517017 -0.33252209, + 0.58121604 -0.75627112 -0.30040303, + 0.54864806 -0.77700013 -0.30863604, + 0.56245989 -0.77890581 -0.27738893, + 0.52867794 -0.79962885 -0.28476897, + 0.54031718 -0.80214632 -0.2542021, + 0.50479293 -0.82290787 -0.26078096, + 0.51454401 -0.82587302 -0.23060399, + 0.47697723 -0.84653443 -0.23637313, + 0.48504913 -0.8497802 -0.20640005, + 0.44614115 -0.86967731 -0.21123308, + 0.45263514 -0.8730163 -0.18156005, + 0.41222805 -0.89199513 -0.18550701, + 0.41732514 -0.8952713 -0.15597805, + 0.375303 -0.91314697 -0.15909199, + 0.37917015 -0.91621828 -0.12951505, + 0.33549908 -0.93276721 -0.13185503, + 0.33828086 -0.93549061 -0.10209495, + 0.29365897 -0.95026785 -0.10370798, + 0.29550302 -0.95249212 -0.073734306, + 0.25017396 -0.9653129 -0.07472679, + 0.25123191 -0.96690065 -0.044560384, + 0.205604 -0.97854799 -0.0130726, + 0.2051471 -0.9776935 -0.045057721, + 0.60423708 0.69466108 -0.39031205, + 0.70374793 0.53881693 -0.46304995, + 0.68735319 0.065530315 -0.72336119, + 0.67613316 0.19384505 -0.71082217, + 0.71475118 0.18400505 -0.67473918, + 0.68626428 0.33398214 -0.64614028, + 0.72521484 0.3161529 -0.61164588, + 0.68131357 0.45679474 -0.57197064, + 0.72193605 0.43181306 -0.54069006, + 0.65957808 0.57005304 -0.48989406, + 0.53219694 0.75634289 -0.38040993, + 0.64787316 0.59693211 -0.47321513, + 0.60237408 0.62550807 -0.49586806, + 0.67679858 0.47496873 -0.56244862, + 0.63445896 0.49870393 -0.59055597, + 0.68488067 0.34709981 -0.64067173, + 0.64388704 0.36447003 -0.67273408, + 0.67623919 0.20180504 -0.70850217, + 0.64886898 0.068637997 -0.75779802, + 0.63610673 0.2113699 -0.74208564, + 0.56745297 0.070665896 -0.82036787, + 0.55178696 0.24653196 -0.79671389, + 0.49493381 0.0013147396 -0.86892968, + 0.49456689 0.0011190098 -0.86913884, + 0.49048099 0.12828401 -0.86195803, + 0.49084589 0.12825997 -0.86175382, + 0.5245508 0.071022078 -0.84841168, + 0.50773001 0.263937 -0.82009, + 0.55196905 0.25546503 -0.79376811, + 0.51086205 0.45024106 -0.73232704, + 0.47333989 0.64449084 -0.60048389, + 0.55459589 0.4358159 -0.70886379, + 0.52112788 0.61114991 -0.59575289, + 0.59883577 0.40742886 -0.68949074, + 0.5560019 0.4228479 -0.71558481, + 0.59484589 0.23762093 -0.76791584, + 0.60911179 0.066698074 -0.79027468, + 0.59470373 0.22895792 -0.77065271, + 0.63622379 0.21971893 -0.73955584, + 0.60027307 0.39448807 -0.69573808, + 0.64239895 0.37800193 -0.66666192, + 0.58587366 0.53945172 -0.60476762, + 0.62956131 0.51718426 -0.5798043, + 0.51986814 0.7119202 -0.47213012, + 0.11296701 -0.99350214 -0.013853902, + 0.11271199 -0.99258089 -0.045599297, + 0.093480721 0.99383926 -0.059540216, + -0.0052729999 0.99838603 0.056547198, + 0.026486509 0.99917436 0.03080851, + 0.03342279 0.99917865 0.022911293, + 0.74227834 0.65851933 -0.12399706, + 0.65414274 0.74330878 -0.13996196, + 0.61125714 0.78454316 -0.10419602, + 0.52939308 0.84099209 -0.11169302, + 0.51004595 0.85476488 -0.096073583, + 0.42683208 0.89867222 -0.10100902, + 0.39764082 0.91430557 -0.076987766, + 0.31762612 0.94487238 -0.079561628, + 0.26680994 0.96308076 -0.035886694, + 0.19744003 0.97963512 -0.036503505, + 0.16407301 0.98643202 -0.0056575001, + 0.10670099 0.99427485 -0.0057024797, + 0.078654796 0.99663991 0.022853099, + 0.082748041 0.99627948 -0.024084112, + 0.089469522 0.99550623 -0.031028008, + 0.14540096 0.98889261 -0.030821789, + 0.18140395 0.98130077 -0.064353988, + 0.24997191 0.96617764 -0.063362181, + 0.29034385 0.95189351 -0.097975552, + 0.36939618 0.92438841 -0.095144644, + 0.42535293 0.8940239 -0.14069898, + 0.51002085 0.84970385 -0.13372397, + 0.53873187 0.8277688 -0.15673795, + 0.62082803 0.7702601 -0.14584902, + 0.63632971 0.75497162 -0.15843692, + 0.71104217 0.68815917 -0.14441603, + 0.73373401 0.659338 -0.16403601, + 0.8160761 0.56084806 -0.13953301, + 0.82079399 0.55261803 -0.144605, + 0.86788172 0.48058981 -0.12575695, + 0.87161958 0.47249877 -0.13047694, + 0.90860075 0.4025979 -0.11117397, + 0.90853876 0.4027639 -0.11107897, + 0.9372341 0.33615103 -0.092707507, + 0.93560565 0.34147888 -0.089634269, + 0.95781255 0.27797687 -0.072965562, + 0.95569354 0.28640884 -0.067968369, + 0.97283155 0.22525789 -0.053456374, + 0.97090238 0.23468609 -0.047656819, + 0.98388785 0.17521098 -0.035579395, + 0.98242211 0.18428801 -0.029744403, + 0.99174863 0.12655996 -0.020426992, + 0.99084878 0.13410197 -0.015338496, + 0.99695379 0.077489987 -0.0088632582, + 0.99656552 0.082644165 -0.0052069575, + 0.99965113 0.026363004 -0.0016609902, + 0.99960214 0.028204104 -0.00028496402, + 0.99962711 -0.027304003 0.00027587102, + 0.99956924 -0.029319407 -0.0013141504, + 0.99627924 -0.086097926 -0.0038590708, + 0.99578065 -0.091391571 -0.008280267, + 0.98889989 -0.14797698 -0.013406998, + 0.98853314 -0.15021701 -0.015398702, + 0.97862411 -0.20458503 -0.020971902, + 0.97792143 -0.20760688 -0.023852285, + 0.96515524 -0.25996807 -0.029868107, + 0.96378011 -0.26445904 -0.034487903, + 0.94847423 -0.31419408 -0.040973712, + 0.9463641 -0.31965303 -0.047083806, + 0.92860639 -0.36710519 -0.054073326, + 0.92565358 -0.37330881 -0.061693769, + 0.90553731 -0.41858914 -0.069176823, + 0.90160877 -0.4253819 -0.078433581, + 0.87924999 -0.46846399 -0.086377203, + 0.87423569 -0.47563881 -0.097363859, + 0.85005814 -0.51598907 -0.10562401, + 0.84379721 -0.52339911 -0.11857303, + 0.8179695 -0.56104463 -0.12710193, + 0.81102699 -0.567801 -0.140845, + 0.78345412 -0.60317004 -0.14961801, + 0.77654266 -0.60864168 -0.16290092, + 0.74707693 -0.64213592 -0.17186499, + 0.73844504 -0.64754605 -0.18810403, + 0.70782197 -0.67834991 -0.19705197, + 0.69797838 -0.68298829 -0.2152981, + 0.66607994 -0.71137291 -0.22424597, + 0.65520728 -0.71488738 -0.24421212, + 0.62211895 -0.74088591 -0.25309297, + 0.61034012 -0.74298817 -0.27468807, + 0.57594013 -0.7667672 -0.28348005, + 0.5633868 -0.76720172 -0.30658889, + 0.52867073 -0.78821951 -0.31498781, + 0.51551992 -0.78675985 -0.33948198, + 0.48081869 -0.80507052 -0.34738278, + 0.48255989 -0.80548382 -0.3439939, + 0.45109114 -0.82076329 -0.35052013, + 0.46537417 -0.8256433 -0.31896713, + 0.43180406 -0.84136415 -0.32504103, + 0.44375494 -0.84655786 -0.29397497, + 0.40861008 -0.86220217 -0.29940805, + 0.41848707 -0.86754513 -0.26876402, + 0.38165992 -0.88290477 -0.27352294, + 0.38973007 -0.88826615 -0.24309203, + 0.35111883 -0.90312159 -0.24715789, + 0.35757697 -0.90836787 -0.21680997, + 0.31700012 -0.92251235 -0.22018607, + 0.32200083 -0.92748046 -0.18998788, + 0.28011701 -0.94043797 -0.192642, + 0.28384596 -0.94499791 -0.16251299, + 0.24090002 -0.95650911 -0.16449201, + 0.24355312 -0.96054649 -0.13428506, + 0.19952409 -0.97045547 -0.13567007, + 0.20127793 -0.97386062 -0.10527396, + 0.15629898 -0.98198891 -0.10615298, + 0.15732592 -0.98464555 -0.075641565, + 0.11208197 -0.99077976 -0.076112784, + 0.11257503 -0.99259824 -0.045558412, + 0.067489587 -0.99761575 -0.014417796, + 0.06733869 -0.99668086 -0.045745797, + 0.022630708 -0.99963033 -0.015067806, + 0.022580698 -0.99869388 -0.045833997, + 0.067324705 -0.99668211 -0.045741603, + 0.067030087 -0.99482775 -0.076319985, + 0.11174395 -0.99082553 -0.076012865, + 0.11100799 -0.98808688 -0.10658999, + 0.15559906 -0.98212236 -0.10594704, + 0.15422697 -0.97856677 -0.13645896, + 0.19847603 -0.97071314 -0.13536401, + 0.19628496 -0.96644491 -0.16569999, + 0.23943993 -0.95694774 -0.16407196, + 0.23624501 -0.95206702 -0.19431099, + 0.27813098 -0.9411419 -0.19208097, + 0.2737419 -0.93574762 -0.22235492, + 0.31437197 -0.92358285 -0.21946497, + 0.30858493 -0.91779375 -0.24985994, + 0.34780696 -0.90464187 -0.24627897, + 0.34046304 -0.89862114 -0.27670404, + 0.37762195 -0.88495588 -0.27249697, + 0.36852491 -0.87883276 -0.30305493, + 0.40377977 -0.86487746 -0.29824281, + 0.39266983 -0.85876161 -0.32914886, + 0.42617905 -0.84471714 -0.32376602, + 0.4128148 -0.83875757 -0.35506281, + 0.44467294 -0.8248319 -0.34916797, + 0.44325113 -0.82436216 -0.3520731, + 0.47818282 -0.80768269 -0.34494889, + 0.49126771 -0.8102625 -0.31957883, + 0.52584493 -0.79125887 -0.31208396, + 0.53867286 -0.79186082 -0.28772894, + 0.57286584 -0.77036971 -0.27991992, + 0.58510488 -0.76915181 -0.25701693, + 0.618963 -0.74493098 -0.248923, + 0.63037729 -0.74214238 -0.22770411, + 0.6630308 -0.71566385 -0.21957994, + 0.67361379 -0.71153474 -0.19990693, + 0.70492804 -0.68284106 -0.19184503, + 0.71437001 -0.67774498 -0.17417599, + 0.74444318 -0.64667219 -0.16619104, + 0.75228983 -0.64121383 -0.15134297, + 0.7810775 -0.60773563 -0.14344092, + 0.78886735 -0.6009993 -0.12840606, + 0.8159759 -0.56532693 -0.12078398, + 0.82311869 -0.5577848 -0.10654496, + 0.84845281 -0.51987189 -0.099302679, + 0.85434228 -0.51237017 -0.087040827, + 0.87800491 -0.47189093 -0.080164395, + 0.88278031 -0.46459419 -0.069650121, + 0.90461314 -0.42152306 -0.063193105, + 0.90833509 -0.41469106 -0.054395106, + 0.92795777 -0.36951992 -0.04846999, + 0.93077278 -0.36326993 -0.041193988, + 0.94804615 -0.31610703 -0.035845906, + 0.95000887 -0.31076196 -0.030166896, + 0.96489912 -0.26139203 -0.025374305, + 0.96603674 -0.25750294 -0.021570394, + 0.97849387 -0.20555598 -0.017218998, + 0.97922337 -0.20228307 -0.014252105, + 0.98886174 -0.14846897 -0.010460497, + 0.99015826 -0.13991503 -0.0032230108, + 0.99626637 -0.086310633 -0.0019882107, + 0.99676001 -0.080387697 0.0027139799, + 0.9996255 -0.027350686 0.00092339056, + 0.99967134 -0.02553561 0.002279371, + 0.99964952 0.026369587 -0.0023538189, + 0.99968934 0.02467091 -0.0035514212, + 0.99694252 0.077341564 -0.011133495, + 0.99724954 0.072744764 -0.014195793, + 0.99173439 0.12593192 -0.024575084, + 0.99245423 0.11917803 -0.028831907, + 0.98390633 0.17367506 -0.042015813, + 0.98505265 0.16579494 -0.046724986, + 0.97297174 0.22226594 -0.062639982, + 0.9744525 0.21431589 -0.067163371, + 0.95826012 0.27281502 -0.08549621, + 0.95971966 0.26651192 -0.088936068, + 0.93836588 0.32786998 -0.10941099, + 0.93913347 0.32518315 -0.11083505, + 0.91111302 0.39011899 -0.132967, + 0.90974778 0.39396992 -0.13094497, + 0.87297541 0.4628672 -0.15384407, + 0.87172711 0.46571505 -0.15232001, + 0.80748731 0.56065917 -0.18337306, + 0.79378611 0.58377504 -0.17061801, + 0.73034078 0.65565377 -0.19162592, + 0.71981716 0.66966718 -0.18278204, + 0.64558792 0.73673594 -0.20108797, + 0.62034106 0.76317209 -0.18095702, + 0.53699481 0.82082671 -0.19462793, + 0.48104113 0.86361319 -0.15090303, + 0.39589915 0.90458828 -0.15806305, + 0.35055003 0.92860413 -0.12169302, + 0.27198809 0.95414233 -0.12504004, + 0.22852805 0.96956623 -0.087842323, + 0.16121395 0.98289376 -0.089049779, + 0.15637502 0.98407614 -0.084505111, + 0.36464289 0.86607468 -0.34197989, + 0.38980085 0.85654271 -0.33821589, + 0.23584192 0.95362365 -0.18703094, + 0.25859395 0.94792676 -0.18591395, + 0.16954498 0.98004287 -0.10378098, + 0.17819904 0.97852325 -0.10362102, + 0.30118594 0.92976779 -0.21170495, + 0.27673206 0.93696523 -0.21334404, + 0.42458978 0.83426058 -0.35175681, + 0.39850691 0.84511483 -0.3563329, + 0.52211702 0.70533502 -0.47947499, + 0.50235826 0.71508235 -0.48610023, + 0.46283817 0.75445127 -0.46538618, + 0.580944 0.55726498 -0.59326202, + 0.55113888 0.57127988 -0.60818189, + 0.44010806 0.7597791 -0.47858205, + 0.46465099 0.74924397 -0.471946, + 0.33228612 0.8848393 -0.32656613, + 0.35623002 0.87660211 -0.32352602, + 0.198451 0.96681303 -0.16090301, + 0.21903902 0.9624781 -0.16018102, + 0.10093102 0.99382812 -0.046027705, + 0.095923483 0.9943229 -0.046050597, + 0.18268509 0.97397149 -0.13418606, + 0.16403708 0.97722346 -0.13463406, + 0.32450196 0.89417785 -0.30845496, + 0.30187997 0.90123087 -0.31088796, + 0.4371579 0.76863784 -0.46699989, + 0.41317308 0.7782672 -0.47285113, + 0.52190596 0.60008097 -0.60623193, + 0.50193077 0.60845572 -0.61469269, + 0.38645914 0.79615527 -0.46560317, + 0.4102228 0.78724563 -0.4603928, + 0.27308902 0.91590011 -0.29419303, + 0.29436806 0.90990525 -0.29226705, + 0.13287896 0.98515463 -0.10868996, + 0.149543 0.98279202 -0.108429, + 0.040525004 0.99914914 0.0076657808, + 0.038456798 0.99923086 0.0076663992, + 0.11996997 0.98924273 -0.08370208, + 0.10514896 0.99091566 -0.083843671, + 0.2666069 0.92315763 -0.2769489, + 0.24654993 0.92825776 -0.27847895, + 0.38389099 0.80418998 -0.453769, + 0.36158201 0.81199503 -0.45817301, + 0.47384682 0.63466674 -0.61046475, + 0.45353189 0.64232981 -0.61783588, + 0.33662498 0.82694989 -0.45037493, + 0.35924503 0.8195771 -0.44635907, + 0.22152807 0.93939835 -0.26164109, + 0.24028006 0.93511122 -0.26044706, + 0.080461778 0.99497378 -0.059608184, + 0.072513297 0.99649602 -0.041683901, + -0.0047710277 0.99838853 0.056547374, + 0.032665107 0.99945724 0.0042848508, + -0.035221592 0.99435574 0.10007998, + -0.031148111 0.99449039 0.10009404, + -0.0086655859 0.99737853 0.071839966, + 0.02722401 0.99704635 0.07181602, + 0.048099078 0.99766451 0.048496276, + 0.094591811 0.99434215 0.048334807, + 0.12042505 0.99246937 0.022413908, + 0.17875305 0.98364323 0.022214606, + 0.22124493 0.97507364 -0.016797394, + 0.29244304 0.95614111 -0.016471302, + 0.31923786 0.94685155 -0.039486282, + 0.39764401 0.91674298 -0.038230699, + 0.41864607 0.90645415 -0.055465106, + 0.50086987 0.8639068 -0.052861691, + 0.55227894 0.82822388 -0.095043384, + 0.6323328 0.76964581 -0.088321179, + 0.66607118 0.7365362 -0.11774403, + 0.73629922 0.66817224 -0.10681504, + 0.75407428 0.64497626 -0.12400705, + 0.81225669 0.5728088 -0.11013196, + 0.81990802 0.56007099 -0.118623, + 0.86693072 0.48761183 -0.10327596, + 0.86851019 0.48434913 -0.10533802, + 0.90613157 0.4133338 -0.089893453, + 0.90473586 0.41684493 -0.08771199, + 0.93444866 0.34846687 -0.073323973, + 0.93174678 0.35664591 -0.068202183, + 0.955185 0.290741 -0.055599201, + 0.95235246 0.30103815 -0.048998922, + 0.97071022 0.23713306 -0.038597308, + 0.96820676 0.24818894 -0.031272892, + 0.98236746 0.1854941 -0.023373112, + 0.98051476 0.19576795 -0.016297197, + 0.99084449 0.13454306 -0.011200406, + 0.98970211 0.14305201 -0.0050839204, + 0.99656999 0.0827021 -0.00293915, + 0.99609226 0.088310324 0.0012797303, + 0.99960309 0.028171403 0.00040824007, + 0.99954075 0.030234193 0.0020351596, + 0.99957013 -0.029253904 -0.0019691803, + 0.99951202 -0.0310455 -0.00345602, + 0.9957909 -0.091091789 -0.010140399, + 0.99566251 -0.092355758 -0.011248494, + 0.98859334 -0.14950506 -0.018209105, + 0.9882229 -0.15167698 -0.020236198, + 0.97806537 -0.20646907 -0.02754641, + 0.97719777 -0.21003796 -0.031120993, + 0.96405125 -0.26284707 -0.038945809, + 0.96257287 -0.26744097 -0.043917995, + 0.94681138 -0.31753612 -0.052144419, + 0.94458002 -0.32300901 -0.0585979, + 0.92633241 -0.37065718 -0.067241929, + 0.92323261 -0.37680686 -0.075220473, + 0.90256357 -0.4222258 -0.08428736, + 0.8984223 -0.42895415 -0.093998939, + 0.87551975 -0.47198287 -0.10342798, + 0.8701638 -0.47913489 -0.11508597, + 0.8454473 -0.5192892 -0.12473004, + 0.83940917 -0.52591515 -0.13713303, + 0.81303602 -0.56337601 -0.146901, + 0.80704248 -0.56876338 -0.15871608, + 0.77885419 -0.60412413 -0.16858305, + 0.7711637 -0.60968077 -0.18329194, + 0.741023 -0.64304799 -0.193324, + 0.7320348 -0.64806682 -0.21008195, + 0.70074338 -0.67864633 -0.21999511, + 0.69059581 -0.68275583 -0.23858294, + 0.65807879 -0.71080077 -0.24838391, + 0.64685935 -0.71370542 -0.26869616, + 0.61321968 -0.73925763 -0.27831587, + 0.60099721 -0.74066722 -0.30035713, + 0.56623995 -0.76382488 -0.30974796, + 0.55326217 -0.76345932 -0.33321312, + 0.51818889 -0.78385985 -0.34211692, + 0.52034205 -0.78418112 -0.33808902, + 0.48909205 -0.80096209 -0.34532404, + 0.50420272 -0.80467153 -0.31350183, + 0.47104895 -0.82192987 -0.32022497, + 0.48376018 -0.82609028 -0.2890521, + 0.44870687 -0.84353173 -0.29515487, + 0.45928112 -0.84800118 -0.26449007, + 0.42273614 -0.86514831 -0.26983809, + 0.43144506 -0.8697741 -0.23947503, + 0.39335209 -0.88640422 -0.24405307, + 0.4004201 -0.89104825 -0.21376805, + 0.36045811 -0.90703827 -0.21760407, + 0.36601591 -0.91151679 -0.18753496, + 0.32426184 -0.92656058 -0.19062991, + 0.32849208 -0.93074322 -0.16065505, + 0.28556103 -0.94439512 -0.16301201, + 0.28865099 -0.94815803 -0.132955, + 0.24476203 -0.9601891 -0.13464202, + 0.24688298 -0.96340489 -0.10440198, + 0.20208202 -0.9736681 -0.10551502, + 0.2033979 -0.97620851 -0.075141162, + 0.15780094 -0.98455864 -0.075783871, + 0.15848599 -0.98632097 -0.045311701, + 0.15901995 -0.98717666 -0.013962596, + 0.15866899 -0.98628902 -0.045367502, + 0.20488103 -0.9777531 -0.044974804, + 0.20400396 -0.97606778 -0.075326182, + 0.24948192 -0.96550864 -0.074511267, + 0.24789491 -0.96311164 -0.10470996, + 0.29251802 -0.95065814 -0.10335601, + 0.29005298 -0.94767088 -0.13337599, + 0.3339031 -0.93340826 -0.13136902, + 0.33040604 -0.92996812 -0.16121802, + 0.37321603 -0.91411012 -0.15846902, + 0.36852282 -0.91035759 -0.18825491, + 0.4095901 -0.89336824 -0.18474105, + 0.4035309 -0.88943577 -0.21463196, + 0.442875 -0.871566 -0.21032, + 0.4352639 -0.86758882 -0.24048895, + 0.47308993 -0.84900087 -0.23533697, + 0.4638128 -0.8451736 -0.26562989, + 0.50019008 -0.8260771 -0.25962803, + 0.48901805 -0.8225531 -0.29028904, + 0.5234592 -0.80348331 -0.2835581, + 0.51014489 -0.80041283 -0.31478792, + 0.54275376 -0.78161764 -0.30739585, + 0.5269857 -0.77916753 -0.3393878, + 0.55834264 -0.76058954 -0.33129579, + 0.55580384 -0.76042569 -0.33590889, + 0.59105992 -0.73784494 -0.32593396, + 0.6036827 -0.73716062 -0.30358085, + 0.63800085 -0.7120198 -0.29322794, + 0.64962327 -0.70973837 -0.27250913, + 0.6827358 -0.68211383 -0.26190194, + 0.69326639 -0.67852443 -0.24287115, + 0.72526217 -0.64820015 -0.23201606, + 0.73455524 -0.64362824 -0.21487507, + 0.76531881 -0.61052686 -0.20382395, + 0.77341616 -0.60523313 -0.18846804, + 0.80238712 -0.56981605 -0.17743902, + 0.80903471 -0.56430781 -0.16437595, + 0.8360942 -0.52669615 -0.15342003, + 0.8411079 -0.52158093 -0.14314598, + 0.86637712 -0.48158306 -0.13216901, + 0.8715052 -0.47520512 -0.12107303, + 0.89498776 -0.4322809 -0.11013697, + 0.89942431 -0.42553216 -0.099791341, + 0.92063338 -0.38011613 -0.089140728, + 0.92393959 -0.37393683 -0.080665365, + 0.94270891 -0.32611498 -0.070349291, + 0.94504875 -0.3206839 -0.063597783, + 0.96129614 -0.27025402 -0.053596508, + 0.96285933 -0.26564109 -0.048340417, + 0.97641134 -0.21243007 -0.038657214, + 0.97735077 -0.20874795 -0.034780491, + 0.98782974 -0.15342396 -0.025562795, + 0.98829103 -0.15083399 -0.0230223, + 0.99554443 -0.093213551 -0.014227492, + 0.99568188 -0.09191259 -0.013029298, + 0.99949914 -0.031333905 -0.0044418103, + 0.99951249 -0.030950315 -0.004107812, + 0.99947888 0.032000795 0.0042472393, + 0.99954063 0.030183388 0.0027394891, + 0.99547738 0.094609737 0.0085869227, + 0.99608874 0.08828678 0.0035613191, + 0.98826379 0.15263297 0.0061569088, + 0.98967326 0.14333902 -0.00093654922, + 0.97805142 0.20835888 -0.0013613792, + 0.98041499 0.196692 -0.0099396901, + 0.96475625 0.26281005 -0.013280903, + 0.96794367 0.2501789 -0.022260092, + 0.94797838 0.31708211 -0.028212909, + 0.95176023 0.30462506 -0.036824808, + 0.92673385 0.37300298 -0.045090795, + 0.93052334 0.36249113 -0.052217718, + 0.89936256 0.43273678 -0.062336769, + 0.9023447 0.42577085 -0.06703148, + 0.8636421 0.49797207 -0.078398407, + 0.86408716 0.49710512 -0.078992523, + 0.81661117 0.57003611 -0.090581723, + 0.8121227 0.57719785 -0.085436366, + 0.75428832 0.64946723 -0.096133634, + 0.74132478 0.66598177 -0.083101772, + 0.67240894 0.73448396 -0.091649592, + 0.64692426 0.7594673 -0.068546422, + 0.56858695 0.8192929 -0.073945992, + 0.52675408 0.84914613 -0.038484003, + 0.44489914 0.89466232 -0.040546916, + 0.38993192 0.92083079 0.0048729992, + 0.31298104 0.94974613 0.0050260206, + 0.29286188 0.95589864 0.022126092, + 0.22328906 0.97449124 0.022556506, + 0.20078009 0.97869146 0.043018322, + 0.14039604 0.98914033 0.043477613, + 0.10707995 0.99130654 0.076454461, + 0.059588823 0.99526733 0.076759927, + 0.040860884 0.99441767 0.097282864, + 0.0037671991 0.99524176 0.097363479, + -0.010941302 0.99325222 0.11545703, + -0.038855683 0.99256152 0.11537695, + -0.055701084 0.98874074 0.13888498, + -0.056097884 0.98871875 0.13888197, + 0.0034829308 0.99897921 0.04503911, + 0.36176601 0.69892102 -0.616956, + 0.24958791 0.87423271 -0.41644084, + 0.26863405 0.86961919 -0.41424409, + 0.13929297 0.97015977 -0.19846295, + 0.15355603 0.96809125 -0.19804004, + 0.0090607423 0.99960637 0.026552008, + 0.0095977336 0.99960136 0.02655191, + 0.17262998 0.96170688 -0.21288197, + 0.15712102 0.96423811 -0.21344303, + 0.28970894 0.85886484 -0.42239791, + 0.26979199 0.86407298 -0.424959, + 0.38069293 0.69324791 -0.61194795, + 0.38082001 0.70260501 -0.60110098, + 0.4076609 0.67146182 -0.61883086, + 0.29112697 0.85299486 -0.43317994, + 0.31137607 0.84729016 -0.43028408, + 0.17699794 0.95705163 -0.22961691, + 0.19358504 0.95401025 -0.22888707, + 0.039549105 0.99911612 -0.014240702, + 0.041816298 0.99902385 -0.014239398, + 0.21613197 0.94518888 -0.24475497, + 0.19847505 0.94881123 -0.24569306, + 0.33444899 0.83445799 -0.43797699, + 0.3130779 0.8409338 -0.44137588, + 0.42674705 0.66501808 -0.61289304, + 0.42651591 0.67486882 -0.60219288, + 0.50954014 0.46321812 -0.72511917, + 0.46508813 0.47657913 -0.74603319, + 0.50793469 0.27158585 -0.81746155, + 0.46305287 0.27944794 -0.84112483, + 0.48044094 0.07341589 -0.87394887, + 0.44677514 0.13580805 -0.8842783, + 0.45095301 -0.00110088 -0.89254701, + 0.45197293 -0.0011008299 -0.89203089, + 0.44788188 0.13424698 -0.88395679, + 0.4473289 0.13427997 -0.88423175, + 0.45141721 -0.0010106905 -0.89231241, + 0.42376885 0.015677594 -0.9056347, + 0.51471591 0.015877197 -0.8572138, + 0.53695422 0.00017651709 -0.84361142, + 0.53295386 0.12184297 -0.83732581, + 0.53223777 0.12189494 -0.83777356, + 0.58049893 0.048220493 -0.81283188, + 0.58117533 -0.00042997522 -0.8137784, + 0.57736504 -0.00043037205 -0.81648612, + 0.57376492 0.11148498 -0.8113969, + 0.57409316 0.11145904 -0.81116831, + 0.57769305 -0.00024664204 -0.81625414, + 0.60015893 0.015789898 -0.79972488, + 0.61762476 0.0018248193 -0.78647071, + 0.61680412 0.0019916105 -0.7871142, + 0.61366564 0.10076694 -0.78310955, + 0.61448598 0.100697 -0.78247499, + 0.65272003 0.061791908 -0.7550751, + 0.65396941 -0.0015744109 -0.7565195, + 0.65470439 -0.0015743909 -0.75588346, + 0.65202796 0.090345696 -0.75279289, + 0.65259916 0.090293519 -0.7523042, + 0.65527523 -0.0012269205 -0.75538927, + 0.67918003 0.0154055 -0.73381001, + 0.93838412 0.026918903 -0.34454402, + 0.93729657 0.056133173 -0.34398282, + 0.92029977 0.0088857077 -0.39111292, + 0.91833812 0.067756906 -0.38995406, + 0.93741536 0.059610922 -0.34307313, + 0.93329924 0.11260703 -0.34098709, + 0.95080835 0.09714134 -0.29415512, + 0.94599426 0.14096503 -0.29193106, + 0.96216035 0.11848505 -0.2453751, + 0.95605999 0.164408 -0.242733, + 0.97186202 0.13209499 -0.195026, + 0.96966237 0.14886005 -0.19389607, + 0.98264313 0.11296701 -0.14714302, + 0.9830429 0.10902499 -0.14744599, + 0.99281311 0.071152508 -0.096226811, + 0.99313986 0.065114096 -0.097125985, + 0.99790865 0.035994988 -0.053691182, + 0.99794126 0.034596108 -0.054003712, + 0.99979174 0.011008097 -0.017183397, + 0.99978638 0.011788605 -0.016981106, + 0.99979991 -0.011406799 0.016431099, + 0.99979621 -0.011956602 0.016268503, + 0.99823421 -0.035178509 0.047865011, + 0.99818677 -0.037488293 0.047092389, + 0.99519253 -0.06099727 0.076624066, + 0.99503052 -0.06561707 0.074890666, + 0.99063426 -0.089982219 0.10269902, + 0.99026024 -0.097209521 0.099675119, + 0.98441666 -0.12277895 0.12589295, + 0.98367852 -0.13307793 0.12110694, + 0.97639638 -0.15974106 0.14537205, + 0.97511137 -0.17316106 0.13846704, + 0.96624964 -0.20119293 0.16088194, + 0.96414179 -0.21803795 0.15129498, + 0.95136923 -0.26830807 0.15135203, + 0.93617988 -0.30616796 0.17270899, + 0.93440437 -0.31481913 0.16666606, + 0.91840667 -0.34966087 0.18511194, + 0.91601843 -0.35965517 0.17764708, + 0.8979001 -0.39467907 0.19494604, + 0.89480388 -0.40589094 0.18595299, + 0.87425017 -0.44136211 0.20220305, + 0.87029868 -0.45380086 0.19142893, + 0.84718502 -0.489526 0.206499, + 0.84223109 -0.50311708 0.19370103, + 0.81679648 -0.53840131 0.20728612, + 0.81082797 -0.55271101 0.192532, + 0.783077 -0.58731198 0.204585, + 0.77597928 -0.60220224 0.18764007, + 0.74560982 -0.63621384 0.19823696, + 0.73747891 -0.65113497 0.17929898, + 0.70455724 -0.68418223 0.18839808, + 0.69531077 -0.69899577 0.16717593, + 0.66043407 -0.73028809 0.17466001, + 0.65025079 -0.74448484 0.15138097, + 0.61371791 -0.77369291 0.15731998, + 0.60282171 -0.78684163 0.13223594, + 0.5646407 -0.81392258 0.13678794, + 0.55622613 -0.82276016 0.11695403, + 0.5164237 -0.84781051 0.12051492, + 0.51221889 -0.85177082 0.11008297, + 0.46542889 -0.87778479 0.11344497, + 0.84559518 0.017668704 -0.53353214, + 0.84572184 -0.003586919 -0.53361189, + 0.84587461 -0.0035868983 -0.53336978, + 0.84418881 0.063203484 -0.53230691, + 0.84986299 0.051401 -0.52449101, + 0.84610343 0.10853205 -0.52185225, + 0.90937877 0.25684193 -0.3272039, + 0.88507611 0.28739202 -0.36612302, + 0.90079576 0.22013594 -0.37430891, + 0.8743571 0.24601103 -0.41830406, + 0.88863122 0.16865404 -0.42648607, + 0.86237061 0.18617891 -0.47080177, + 0.8729701 0.099319711 -0.47755507, + 0.87636375 0.018693596 -0.48128688, + 0.87281615 0.093950711 -0.47892106, + 0.89696932 0.085104033 -0.43382415, + 0.88899428 0.15974806 -0.42915013, + 0.91239089 0.14279398 -0.38360494, + 0.90207839 0.20796511 -0.37816018, + 0.92518163 0.18288495 -0.33255389, + 0.90892774 0.26143995 -0.3248069, + 0.93420374 0.22368394 -0.27790093, + 0.92394465 0.26798791 -0.2729629, + 0.94812536 0.22271007 -0.22684507, + 0.94940013 0.21647403 -0.22754903, + 0.97228324 0.16115205 -0.16939704, + 0.97402966 0.14762394 -0.17167795, + 0.98698765 0.10483796 -0.12191995, + 0.98732913 0.10028601 -0.12298001, + 0.99410415 0.068525508 -0.08403191, + 0.99395603 0.071593001 -0.083221696, + 0.99800164 0.041208986 -0.04790248, + 0.9979769 0.042105198 -0.047636092, + 0.99979526 0.013402402 -0.015162904, + 0.99979013 0.013984902 -0.014968702, + 0.99980336 -0.013540004 0.014492505, + 0.99979651 -0.014329594 0.014198793, + 0.99823487 -0.042186398 0.041801296, + 0.99815947 -0.045019921 0.040632017, + 0.99511576 -0.073282182 0.066139586, + 0.99486637 -0.078635126 0.063697919, + 0.99032533 -0.10782704 0.087344632, + 0.98975551 -0.11599595 0.08324036, + 0.98360634 -0.14650907 0.10513704, + 0.9824965 -0.15789093 0.098848559, + 0.97470355 -0.18943891 0.11859994, + 0.97279686 -0.20401298 0.10974999, + 0.96315622 -0.23684606 0.12741303, + 0.96004897 -0.254971 0.115307, + 0.3106811 -0.94983637 -0.035891511, + 0.27548495 -0.96061975 -0.036298994, + 0.26761791 -0.96113467 -0.067828581, + 0.2288851 -0.97103846 -0.068527527, + 0.22197694 -0.96982276 -0.10084698, + 0.18340296 -0.97776574 -0.10167298, + 0.17759694 -0.97486365 -0.13453695, + 0.13918595 -0.98096865 -0.13537996, + 0.13454394 -0.97641051 -0.16887993, + 0.096839853 -0.98073852 -0.16962892, + 0.093454793 -0.97455686 -0.20372798, + 0.056398883 -0.97728276 -0.20429796, + 0.054339509 -0.96963626 -0.23843805, + 0.018276498 -0.97090888 -0.23875096, + 0.01759241 -0.96191448 -0.27278411, + -0.017668001 -0.96191311 -0.27278402, + -0.018367592 -0.97091967 -0.23869991, + -0.054521807 -0.96963912 -0.23838504, + -0.056575816 -0.97726023 -0.20435704, + -0.093590558 -0.97453153 -0.20378689, + -0.096970282 -0.98070389 -0.16975498, + -0.13465606 -0.97637349 -0.16900508, + -0.13930401 -0.98095113 -0.13538602, + -0.17766294 -0.97485065 -0.13454396, + -0.183496 -0.97776401 -0.101522, + -0.22210692 -0.96980864 -0.10069596, + -0.22902289 -0.97101951 -0.068334267, + -0.26784688 -0.96108454 -0.067635171, + -0.27571505 -0.96056324 -0.036049508, + -0.31476587 -0.94850165 -0.035596788, + -0.32340309 -0.94624722 -0.0051715313, + -0.36251798 -0.93196291 -0.0050934595, + -0.59330177 -0.8010307 0.079641469, + -0.62668693 -0.77544791 0.077097893, + -0.63291705 -0.76894414 0.090227507, + -0.66854781 -0.7386018 0.08666718, + -0.67623121 -0.72951216 0.10258402, + -0.71043605 -0.69690508 0.097999215, + -0.72038084 -0.68334681 0.11869497, + -0.75230509 -0.64909607 0.11274502, + -0.76109791 -0.63517594 0.13145898, + -0.7905758 -0.59965587 0.12410797, + -0.79804516 -0.5859831 0.14052702, + -0.82520986 -0.54925293 0.13171898, + -0.83141279 -0.53614688 0.14594297, + -0.85631555 -0.49832076 0.13564694, + -0.86136568 -0.48599482 0.14784494, + -0.88357478 -0.4480179 0.13629197, + -0.88758725 -0.4366841 0.14661503, + -0.90726179 -0.3986949 0.13385998, + -0.91034871 -0.38856885 0.14240596, + -0.92971522 -0.34578907 0.12672703, + -0.37996519 -0.91947943 0.10091604, + -0.38573983 -0.91484356 0.11944094, + -0.42513499 -0.89751297 0.117178, + -0.4318082 -0.8915894 0.13641906, + -0.47318083 -0.87083071 0.13324295, + -0.48203313 -0.8619532 0.15710105, + -0.52288407 -0.83858913 0.15284202, + -0.5341832 -0.8255533 0.18196206, + -0.57408088 -0.79960585 0.17624296, + -0.58481407 -0.78530115 0.20321102, + -0.62299699 -0.75728101 0.19596, + -0.63300478 -0.74200875 0.22074392, + -0.66918218 -0.71224821 0.21189104, + -0.67827129 -0.69644934 0.2343211, + -0.71249801 -0.66504198 0.223754, + -0.72059906 -0.64904207 0.24388804, + -0.75264531 -0.61634827 0.23160309, + -0.75971514 -0.60048908 0.24949104, + -0.78912389 -0.56722397 0.23566997, + -0.79514098 -0.55190003 0.251311, + -0.82191569 -0.51839483 0.23605391, + -0.82692909 -0.50389004 0.24956603, + -0.85132486 -0.47013593 0.23284797, + -0.85538816 -0.45675713 0.24430306, + -0.87753022 -0.42283809 0.22616106, + -0.88082576 -0.41044492 0.23596793, + -0.90047872 -0.37703285 0.21675892, + -0.90307343 -0.36583918 0.2249891, + -0.92040533 -0.33302712 0.20481007, + -0.92233658 -0.32342884 0.2113979, + -0.93763578 -0.29097694 0.19018796, + -0.93906885 -0.28271997 0.19549698, + -0.95353127 -0.24781705 0.17136204, + -0.95334655 -0.24024688 0.18278891, + -0.94018245 -0.27112013 0.2062791, + -0.93891078 -0.27910694 0.20135996, + -0.92389256 -0.31032285 0.22387989, + -0.92212546 -0.31991181 0.21757987, + -0.90509975 -0.35158792 0.23912394, + -0.90280044 -0.3624388 0.23149386, + -0.88350928 -0.39476216 0.25213909, + -0.88048488 -0.40722695 0.24271896, + -0.8587603 -0.44012916 0.26233009, + -0.85497415 -0.45379612 0.25117406, + -0.83098418 -0.48671511 0.26939505, + -0.82642901 -0.501185 0.25657099, + -0.80008572 -0.5339818 0.27336091, + -0.79455084 -0.54949886 0.25834095, + -0.76557785 -0.58220994 0.27371898, + -0.75903165 -0.59841871 0.25644889, + -0.72736806 -0.63076705 0.27031204, + -0.719809 -0.647304 0.25074399, + -0.68586868 -0.67859173 0.26286387, + -0.67736506 -0.69503903 0.24103403, + -0.64143723 -0.72482723 0.25136408, + -0.63200217 -0.74094117 0.22711106, + -0.5939399 -0.76918679 0.23576894, + -0.58372414 -0.7845462 0.20917304, + -0.54369181 -0.81095672 0.21621393, + -0.53299999 -0.82503998 0.18767001, + -0.49188095 -0.8489759 0.19311397, + -0.48077682 -0.86168671 0.16232593, + -0.43901515 -0.88294929 0.16633207, + -0.43038085 -0.89156771 0.14099395, + -0.38794801 -0.91036803 0.143967, + -0.38154399 -0.916053 0.123576, + -0.34092608 -0.93165123 0.12568003, + -0.334564 -0.93674803 0.102811, + -0.32983312 -0.93891335 0.098244436, + -0.29226911 -0.95114338 0.099524237, + 0.28022897 -0.95745486 0.068934396, + 0.2435369 -0.96738762 0.06964948, + 0.236853 -0.97082001 0.037540302, + 0.19583395 -0.97990477 0.037891593, + 0.19016191 -0.98174053 0.0048949677, + 0.14917801 -0.98879814 0.0049301605, + 0.14464393 -0.9890635 -0.028834987, + 0.10417398 -0.99413675 -0.028982893, + 0.10085896 -0.99287754 -0.063417368, + 0.061083991 -0.99610287 -0.063623391, + 0.059064467 -0.99339139 -0.098411642, + 0.019913189 -0.9949314 -0.09856414, + 0.019220604 -0.99083823 -0.13368003, + -0.019296892 -0.99083662 -0.13367996, + -0.019990198 -0.99493188 -0.098544486, + -0.059176784 -0.99338675 -0.098391481, + -0.061199091 -0.99609989 -0.063559093, + -0.10107804 -0.99285936 -0.063352324, + -0.10439502 -0.99411613 -0.028895104, + -0.14489995 -0.98902863 -0.028747289, + -0.14943901 -0.98875803 0.0050608502, + -0.19045405 -0.98168325 0.0050246413, + -0.19611095 -0.97984475 0.038010791, + -0.2371731 -0.97073734 0.037657514, + -0.243843 -0.96730602 0.069711201, + -0.28480402 -0.95610613 0.068904005, + -0.32522291 -0.94339079 0.065145582, + -0.28836793 -0.95524478 0.065964185, + -0.28075007 -0.95914721 0.034872308, + -0.24030299 -0.97005701 0.035269, + -0.23356906 -0.97233522 0.0031246208, + -0.19308807 -0.98117638 0.0031530312, + -0.18738101 -0.98183215 -0.029901205, + -0.14694408 -0.9886865 -0.030110015, + -0.14237303 -0.98774421 -0.063963518, + -0.10255095 -0.99264854 -0.064281069, + -0.099217959 -0.99016351 -0.098651253, + -0.060125414 -0.99327326 -0.098961122, + -0.058101773 -0.98931855 -0.13368994, + -0.0196626 -0.99080098 -0.133891, + -0.018982101 -0.9854511 -0.16889602, + 0.01890911 -0.98545247 -0.16889608, + 0.019589107 -0.99080235 -0.13389204, + 0.058029722 -0.98932236 -0.13369304, + 0.06005073 -0.9932735 -0.099003948, + 0.099072374 -0.99017376 -0.098694876, + 0.10239904 -0.99265736 -0.064388521, + 0.14221697 -0.98775977 -0.064070784, + 0.14678296 -0.98870575 -0.030261492, + 0.18711698 -0.98187786 -0.030052496, + 0.19282492 -0.98122853 0.0030026587, + 0.23324297 -0.9724139 0.0029756795, + 0.23997694 -0.97014177 0.035158291, + 0.27615699 -0.960482 0.0348083, + 0.5938561 -0.80061215 0.079718821, + 0.55164301 -0.82997602 0.0826426, + 0.54815984 -0.83304667 0.074524768, + 0.50856489 -0.85759884 0.076721184, + 0.50469613 -0.86068219 0.067141518, + 0.46444401 -0.88292003 0.068876296, + 0.46037179 -0.88582557 0.058059674, + 0.41954991 -0.90578878 0.059368186, + 0.4154681 -0.90836126 0.04760471, + 0.37394908 -0.92617822 0.048538413, + 0.36996099 -0.92835402 0.0358845, + 0.32782903 -0.94403213 0.036490504, + 0.32404584 -0.94576055 0.023047689, + 0.28189209 -0.95916134 0.023374308, + 0.27625993 -0.96108276 0.00063249882, + 0.23635088 -0.97166753 0.00063946471, + 0.22954603 -0.9727841 -0.031619903, + 0.18974598 -0.9813149 -0.031897195, + 0.1839781 -0.98077649 -0.065035433, + 0.14434193 -0.98735952 -0.065471873, + 0.13975796 -0.98520565 -0.099184662, + 0.10061704 -0.98992133 -0.099659637, + 0.097281434 -0.98622537 -0.13377604, + 0.058847807 -0.9892081 -0.13418001, + 0.056799125 -0.98402047 -0.16875307, + 0.019082099 -0.98543203 -0.16899601, + 0.018386992 -0.97880763 -0.20395492, + -0.018532097 -0.97880489 -0.20395496, + -0.019227402 -0.98542213 -0.16903701, + -0.05693328 -0.98400563 -0.16879395, + -0.058970399 -0.98919702 -0.13420799, + -0.097348884 -0.98621488 -0.13380398, + -0.100695 -0.98992199 -0.099574097, + -0.13987593 -0.98519754 -0.099098854, + -0.14446598 -0.98734987 -0.065343395, + -0.18420509 -0.98074245 -0.064906128, + -0.18997909 -0.9812755 -0.031724315, + -0.22981103 -0.97272712 -0.031447902, + -0.23661809 -0.97160238 0.0008315923, + -0.27656311 -0.9609955 0.00082251441, + -0.28424907 -0.95821524 0.032032706, + -0.32429498 -0.94542789 0.031605195, + -0.33042896 -0.94232291 0.053330392, + -0.37277892 -0.92643774 0.05243139, + -0.37672883 -0.92404056 0.064995266, + -0.41842699 -0.906012 0.0637272, + -0.42243901 -0.90325701 0.075313397, + -0.46335912 -0.88310623 0.073633216, + -0.46719205 -0.88017315 0.083826207, + -0.50753492 -0.85774988 0.081690595, + -0.5137248 -0.8524437 0.09709046, + -0.55007112 -0.82975316 0.094506122, + -0.55678183 -0.82333767 0.11004096, + -0.59493011 -0.79669321 0.10648002, + -0.60352468 -0.78737265 0.12570694, + -0.64025098 -0.75855899 0.121107, + -0.65113121 -0.74496126 0.14512405, + -0.68627793 -0.71391892 0.13907698, + -0.69617206 -0.69958806 0.16100001, + -0.72955322 -0.66650224 0.15338506, + -0.7383008 -0.65189785 0.17303495, + -0.76914185 -0.61768895 0.16395499, + -0.77669001 -0.60321999 0.18132401, + -0.80498409 -0.56818205 0.17079201, + -0.81137663 -0.55413878 0.18600591, + -0.83731484 -0.51830089 0.17397696, + -0.84259552 -0.50500071 0.1871019, + -0.86625731 -0.46847817 0.17357007, + -0.87053484 -0.45609888 0.18477796, + -0.89156228 -0.41975915 0.17005606, + -0.89489931 -0.40863514 0.17936707, + -0.91347712 -0.37257802 0.16354002, + -0.91605842 -0.36262617 0.17128707, + -0.9324559 -0.32667398 0.15430498, + -0.93437433 -0.31805813 0.16057307, + -0.94870812 -0.28222603 0.14248301, + -0.94840914 -0.28919902 0.12993902, + -0.93234378 -0.3298119 0.14818597, + -0.93024659 -0.33851084 0.14160393, + -0.91337222 -0.37558809 0.15711404, + -0.91054577 -0.3856369 0.14896497, + -0.89147091 -0.42264193 0.16325898, + -0.88778156 -0.4339568 0.15337993, + -0.86619061 -0.47115076 0.16652593, + -0.8615464 -0.48348624 0.15485108, + -0.8372888 -0.52070588 0.16677195, + -0.8315599 -0.53391695 0.15310399, + -0.80501586 -0.57026994 0.16352898, + -0.79814368 -0.58405179 0.14781794, + -0.76924711 -0.61942106 0.15676902, + -0.76112831 -0.63357526 0.13880305, + -0.72974676 -0.66787773 0.14631794, + -0.72034407 -0.68208003 0.12598102, + -0.68655884 -0.71498084 0.13205796, + -0.67607409 -0.72862607 0.10967202, + -0.64066267 -0.75926954 0.11428493, + -0.63243717 -0.76855719 0.096659921, + -0.59566307 -0.79695612 0.10023201, + -0.58917189 -0.8034218 0.085964374, + -0.554362 -0.82755202 0.088546298, + -0.54824603 -0.83301502 0.074244998, + -0.50869089 -0.85754985 0.076431684, + -0.5049209 -0.86055285 0.067109883, + -0.46466112 -0.88280827 0.068845518, + -0.46062589 -0.88568878 0.058130585, + -0.41982478 -0.90565658 0.059441172, + -0.4157452 -0.90823042 0.047681224, + -0.37423813 -0.92605734 0.048617117, + -0.36908391 -0.92883474 0.032296494, + -0.41305014 -0.91015828 0.031647112, + -0.417144 -0.907803 0.043412901, + -0.45783713 -0.88802129 0.042466916, + -0.46193779 -0.88530761 0.053327575, + -0.50207323 -0.86326039 0.051999625, + -0.50607473 -0.86026645 0.061886061, + -0.5455761 -0.8359012 0.060133316, + -0.5492121 -0.83286315 0.068593018, + -0.58735824 -0.80659628 0.066429719, + -0.58905011 -0.80638218 0.052609012, + -0.54653788 -0.83565784 0.05451899, + -0.54267073 -0.83871055 0.045533273, + -0.50321794 -0.86288887 0.046845995, + -0.49916011 -0.86572617 0.036843207, + -0.45912513 -0.88756824 0.037772708, + -0.45498201 -0.89009702 0.02681, + -0.41444695 -0.90966088 0.027399296, + -0.41032192 -0.91180778 0.015571896, + -0.36919808 -0.92921525 0.015869204, + -0.36453703 -0.93077111 0.027893804, + -0.32810989 -0.94421566 0.02829669, + -0.31958699 -0.94755501 -0.00192461, + -0.28003496 -0.95998788 -0.0019498698, + -0.27226487 -0.96164453 -0.033342086, + -0.23284897 -0.97192889 -0.033698697, + -0.22597294 -0.97188777 -0.066108987, + -0.186753 -0.980142 -0.0666705, + -0.18095101 -0.9784171 -0.099783815, + -0.141921 -0.98477 -0.100432, + -0.13730705 -0.98140937 -0.13409905, + -0.098827437 -0.98594338 -0.13471805, + -0.095461838 -0.98101133 -0.16883107, + -0.057826094 -0.98386288 -0.16932198, + -0.055765994 -0.97740591 -0.20388196, + -0.018899204 -0.97875422 -0.20416404, + -0.018208995 -0.97094476 -0.23860994, + 0.018029097 -0.97094786 -0.23861097, + 0.018718198 -0.97876185 -0.20414397, + 0.055657808 -0.9774161 -0.20386302, + 0.057717472 -0.98387355 -0.16929692, + 0.095493287 -0.98101288 -0.16880399, + 0.098841578 -0.98593879 -0.13474096, + 0.13723502 -0.98141611 -0.13412301, + 0.141837 -0.98477101 -0.10054, + 0.18079706 -0.97843438 -0.099893138, + 0.18658909 -0.98016149 -0.066843331, + 0.22580597 -0.97191489 -0.066280894, + 0.23266989 -0.97196352 -0.033933986, + 0.27201504 -0.96170712 -0.033576004, + 0.27978808 -0.96005934 -0.0021823607, + 0.31553096 -0.94891286 -0.0021570297, + 0.62597585 -0.77853382 0.04515909, + 0.58529896 -0.80945688 0.046952792, + 0.58155704 -0.81258512 0.038689002, + 0.54342192 -0.83850986 0.039923295, + 0.53945196 -0.84145588 0.030716496, + 0.50002795 -0.86543286 0.031591795, + 0.49590304 -0.8681131 0.021445202, + 0.45598578 -0.88971561 0.021978788, + 0.45177922 -0.89206344 0.010883906, + 0.41140205 -0.91138613 0.011119701, + 0.4072428 -0.91331959 -0.00077665265, + 0.36630812 -0.93049335 -0.0007912583, + 0.36223218 -0.93198842 -0.013614806, + 0.32076314 -0.9470585 -0.013834907, + 0.31598088 -0.94827062 -0.03064099, + 0.35959491 -0.93262178 -0.030135293, + 0.36367902 -0.93136311 -0.017329002, + 0.40442291 -0.91441375 -0.017013697, + 0.40864208 -0.91268122 -0.0049835914, + 0.44885188 -0.89359277 -0.0048793592, + 0.45307413 -0.89145124 0.0062184515, + 0.49289483 -0.87006772 0.0060692779, + 0.49706012 -0.86756319 0.016287904, + 0.53640121 -0.84381443 0.015842108, + 0.54042178 -0.84101856 0.025141289, + 0.57851303 -0.81530899 0.024372799, + 0.58231115 -0.81230628 0.03274541, + 0.61920899 -0.78458899 0.031628098, + 0.62574095 -0.77869987 0.045548696, + 0.65815276 -0.75159973 0.043963484, + 0.66681504 -0.74266106 0.061744306, + 0.69807696 -0.71356094 0.059324991, + 0.70369709 -0.70699203 0.07051751, + 0.73650074 -0.67309678 0.067136675, + 0.74242204 -0.66526806 0.078917608, + 0.77318865 -0.62976068 0.074705459, + 0.78146487 -0.61720395 0.091498293, + 0.81007189 -0.57999194 0.085981689, + 0.81735414 -0.56715006 0.10135601, + 0.84370542 -0.52843422 0.094437547, + 0.84966117 -0.51621914 0.10767402, + 0.87332273 -0.47687882 0.099468261, + 0.87811613 -0.46544105 0.11080101, + 0.89914268 -0.42575786 0.10135397, + 0.90288502 -0.415337 0.110878, + 0.9214974 -0.37524319 0.10017505, + 0.92436665 -0.36585587 0.10814697, + 0.9445675 -0.31036285 0.10708395, + 0.92735773 -0.3537139 0.12204097, + 0.92472923 -0.3630161 0.11443503, + 0.90675056 -0.40215883 0.12677394, + 0.9032917 -0.41259286 0.11760695, + 0.88294643 -0.45149022 0.12869406, + 0.87855059 -0.4628768 0.11787294, + 0.85561514 -0.50160408 0.12773502, + 0.85010201 -0.51391202 0.114983, + 0.82450283 -0.55220491 0.12355097, + 0.81778312 -0.56515008 0.10879402, + 0.7898981 -0.60218203 0.11592201, + 0.78187984 -0.61551487 0.099021778, + 0.75175691 -0.65106893 0.10474198, + 0.74276322 -0.66396326 0.086345233, + 0.71031326 -0.69800824 0.090772629, + 0.70372093 -0.70624292 0.077445693, + 0.66923505 -0.73862308 0.080996506, + 0.6631788 -0.74530685 0.068640083, + 0.63082409 -0.77265614 0.071158804, + 0.62490386 -0.77850485 0.058526486, + 0.58803815 -0.80655718 0.060635414, + 0.58454514 -0.80963415 0.052910913, + 0.54637796 -0.83575588 0.054617994, + 0.54245424 -0.83885241 0.04549922, + 0.5029639 -0.86303884 0.046811089, + 0.49887887 -0.86589283 0.036734991, + 0.45884687 -0.88771677 0.037660792, + 0.4546898 -0.89025056 0.026667386, + 0.41414693 -0.9098019 0.027253097, + 0.409998 -0.91195703 0.0153618, + 0.36889681 -0.92933857 0.015654592, + 0.36486289 -0.93105662 0.0029347588, + 0.32074887 -0.94715953 0.0029855187, + 0.32549587 -0.94533664 0.019775392, + 0.36743113 -0.92984736 0.019451408, + 0.37142187 -0.92790961 0.032084487, + 0.41275585 -0.91029769 0.031475488, + 0.416875 -0.90793103 0.043317799, + 0.45754984 -0.8881737 0.042375185, + 0.46167579 -0.88544559 0.053306073, + 0.50181222 -0.86341339 0.051979724, + 0.50584996 -0.86039388 0.061952192, + 0.54541308 -0.83600312 0.060195908, + 0.54913491 -0.83289284 0.068851486, + 0.58727676 -0.80663472 0.066680878, + 0.59343088 -0.80086184 0.080375075, + 0.62691915 -0.77519017 0.077798717, + 0.63335365 -0.76844752 0.091387048, + 0.66900975 -0.73805279 0.087772571, + 0.67620492 -0.72951996 0.10270099, + 0.71041602 -0.69691002 0.098109797, + 0.72004795 -0.68379194 0.11815099, + 0.75195867 -0.64958471 0.11223995, + 0.76061064 -0.63593173 0.13062294, + 0.79014117 -0.60039014 0.12332303, + 0.79756218 -0.58686513 0.13958503, + 0.82478648 -0.55009836 0.13084008, + 0.83100516 -0.53702211 0.14504403, + 0.85592014 -0.49922007 0.13483402, + 0.86102682 -0.48681387 0.14712296, + 0.88325912 -0.44883606 0.13564502, + 0.8873384 -0.43736121 0.14610207, + 0.90704972 -0.39933184 0.13339795, + 0.91022474 -0.3889479 0.14216296, + 0.92762798 -0.35080701 0.128222, + 0.92998457 -0.34178585 0.13531893, + 0.94517052 -0.30364487 0.12021794, + 0.94827634 -0.2892431 0.13080704, + 0.94839466 -0.2892589 0.12991096, + 0.93229675 -0.32994592 0.14818397, + 0.93017435 -0.33874112 0.14152804, + 0.91330177 -0.37580192 0.15701196, + 0.91042376 -0.38601592 0.14872897, + 0.89132339 -0.42305321 0.16299908, + 0.88753575 -0.43463391 0.15288398, + 0.86589545 -0.47188273 0.1659869, + 0.86121428 -0.48426917 0.15425105, + 0.83694184 -0.52147686 0.16610296, + 0.83116072 -0.53475183 0.15235594, + 0.80458283 -0.57111287 0.16271596, + 0.79766518 -0.58492315 0.14695303, + 0.76876134 -0.6202603 0.15583107, + 0.76064301 -0.63435102 0.137917, + 0.72928584 -0.66858983 0.14536098, + 0.72001392 -0.68254292 0.12535998, + 0.68621707 -0.71543008 0.13140002, + 0.67605484 -0.72863483 0.10973197, + 0.64061171 -0.75930262 0.11435094, + 0.63288724 -0.76804429 0.097784437, + 0.59606075 -0.79650968 0.10140897, + 0.59226269 -0.80035967 0.093001954, + 0.55402911 -0.82693321 0.096089825, + 0.55067998 -0.83003402 0.088289604, + 0.5110628 -0.85472172 0.090915568, + 0.50742191 -0.85779691 0.081899494, + 0.4670108 -0.88024861 0.08404316, + 0.46312511 -0.88322324 0.073702313, + 0.42216307 -0.9033801 0.075384304, + 0.41812614 -0.90615129 0.063720524, + 0.3764641 -0.92414922 0.064986117, + 0.37248904 -0.92655909 0.052347209, + 0.33011708 -0.94243723 0.053244311, + 0.3263531 -0.94440824 0.03983511, + 0.28181508 -0.95861638 0.040434416, + 0.28597996 -0.95651489 0.057399392, + 0.32865298 -0.94275486 0.056573693, + 0.33240303 -0.94053912 0.069961004, + 0.37502193 -0.9244619 0.068765193, + 0.37894484 -0.92184466 0.081260473, + 0.42077091 -0.90366274 0.079657681, + 0.42464486 -0.90078872 0.090864569, + 0.46571288 -0.88046777 0.08881478, + 0.46943781 -0.8774277 0.09873616, + 0.50990593 -0.85483485 0.096193887, + 0.51336908 -0.85174811 0.10477301, + 0.55308288 -0.82689381 0.10171498, + 0.55714995 -0.8229329 0.11119998, + 0.59534776 -0.79623169 0.10759196, + 0.60347211 -0.7874012 0.12578103, + 0.64020479 -0.7585867 0.12117796, + 0.65078276 -0.74538475 0.14451095, + 0.68593615 -0.71436018 0.13849603, + 0.69574201 -0.700203 0.160184, + 0.72908998 -0.66718203 0.15263, + 0.73780376 -0.65269077 0.17216393, + 0.76865691 -0.61850595 0.16314699, + 0.7762081 -0.60409307 0.18047902, + 0.80455583 -0.56902486 0.17000195, + 0.81098187 -0.55497092 0.18524499, + 0.83697212 -0.51909107 0.17326902, + 0.84232211 -0.50567305 0.18651602, + 0.86596411 -0.46920606 0.17306602, + 0.87034285 -0.45657289 0.18451196, + 0.89141613 -0.42017207 0.16980201, + 0.89481127 -0.40887615 0.17925707, + 0.91340613 -0.37279603 0.16343902, + 0.91599923 -0.36281008 0.17121404, + 0.93240666 -0.32684487 0.15424094, + 0.93436724 -0.31804308 0.16064404, + 0.94869167 -0.28224191 0.14256096, + 0.9512679 -0.26825196 0.15208599, + 0.96240014 -0.23630004 0.13397102, + 0.96494174 -0.21899894 0.14466096, + 0.97413498 -0.188546 0.124545, + 0.97571689 -0.17446099 0.13243799, + 0.98320538 -0.14536305 0.11034904, + 0.98410785 -0.13460499 0.11581598, + 0.99007034 -0.10655904 0.09168423, + 0.99053645 -0.098828241 0.095240146, + 0.99497879 -0.072067387 0.069450885, + 0.99517936 -0.067120224 0.071505219, + 0.99818325 -0.041236512 0.043930512, + 0.99824375 -0.038649894 0.044895489, + 0.9997974 -0.013130993 0.015252891, + 0.99980265 -0.012450895 0.015479594, + 0.99978936 0.012865005 -0.015994405, + 0.99979275 0.012429697 -0.016123196, + 0.99795187 0.039056897 -0.050662491, + 0.99800497 0.036911201 -0.051221501, + 0.99396086 0.06415499 -0.089027591, + 0.99383551 0.066898674 -0.088405453, + 0.98557621 0.10211902 -0.13494903, + 0.98475367 0.11155696 -0.13347396, + 0.96931612 0.15764202 -0.18861403, + 0.96854913 0.16283701 -0.18814003, + 0.95056474 0.20321795 -0.23479594, + 0.9555611 0.17502701 -0.23721004, + 0.93522501 0.21021201 -0.284895, + 0.94548148 0.14919508 -0.28949216, + 0.92600274 0.17294395 -0.3355729, + 0.93317562 0.11917996 -0.33908588, + 0.91260171 0.13556996 -0.38571885, + 0.9184739 0.071850196 -0.38889995, + 0.89682114 0.080373108 -0.43503106, + 0.89896524 0.038745008 -0.43630308, + 0.89414376 0.00035940891 -0.44777989, + 0.8941381 -0.0035968705 -0.44777706, + 0.8938874 -0.0035968616 -0.44827721, + 0.89252412 0.055329006 -0.44759306, + 0.89271969 0.05529698 -0.44720685, + 0.89408171 -0.0036680587 -0.44788885, + 0.87092602 0.0113958 -0.49128199, + 0.86944783 0.059342187 -0.49044788, + 0.86961627 0.059316821 -0.49015218, + 0.87107301 0.0133211 -0.490973, + 0.87021083 0.012501597 -0.49252087, + 0.81496912 0.013465302 -0.57934809, + 0.93247789 -0.0030874996 0.36121398, + 0.91349971 0.016692294 0.40649685, + 0.91360456 -0.0069985366 0.40654379, + 0.91363376 -0.0069961082 0.4064779, + 0.91362321 0.0084510716 0.40647408, + 0.91627002 0.0113644 0.40040001, + 0.89250398 -0.0035036399 0.45102599, + 0.86943132 0.013245204 0.49387619, + 0.86948013 -0.0079454705 0.49390405, + 0.8694768 -0.0079456484 0.4939099, + 0.86944842 0.011311206 0.49389425, + 0.87021571 0.012037395 0.49252382, + 0.81679857 0.014300893 0.57674569, + 0.8149761 0.012808002 0.57935303, + 0.7556392 0.017130204 0.65476418, + 0.75105089 0.013849298 0.66009897, + 0.75104117 0.014724704 -0.66009116, + 0.76012599 0.0212541 -0.64942801, + 0.75867617 0.065279216 -0.64818919, + 0.72395605 0.06542071 -0.68673706, + 0.72550803 -0.0025454503 -0.68820906, + 0.72530401 -0.0025454699 -0.68842399, + 0.69133174 0.0037440686 -0.72252774, + 0.69099474 0.0038160086 -0.72284979, + 0.68882108 0.079346009 -0.72057605, + 0.68915874 0.079312868 -0.72025675, + 0.72370881 0.066324882 -0.68691081, + 0.72400618 0.065788314 -0.6866492, + 0.71463108 0.17545702 -0.67713904, + 0.75099987 0.16562499 -0.63919294, + 0.72651893 0.30284196 -0.61681193, + 0.76328433 0.2847361 -0.57993317, + 0.72608763 0.41360578 -0.54929674, + 0.7648831 0.38748005 -0.51460004, + 0.71339804 0.51390809 -0.47640505, + 0.75567472 0.48031181 -0.44525984, + 0.70847565 0.57179773 -0.41365379, + 0.7537291 0.53246206 -0.38519707, + 0.69764698 0.624448 -0.351217, + 0.68979084 0.63822883 -0.3418369, + 0.64188093 0.67595392 -0.36204296, + 0.68924302 0.60835999 -0.3935, + 0.65793383 0.63232881 -0.4090029, + 0.55998003 0.75583315 -0.33932102, + 0.60204995 0.72842091 -0.32701498, + 0.57309198 0.75942898 -0.30794999, + 0.62832475 0.72093374 -0.29233989, + 0.67375219 0.66607517 -0.32000309, + 0.74863964 0.59758872 -0.28709984, + 0.77783054 0.54914069 -0.30565381, + 0.83623683 0.47914687 -0.26669493, + 0.85408771 0.43854886 -0.27965891, + 0.89683688 0.37297896 -0.23784497, + 0.90933925 0.33300808 -0.24941505, + 0.93852538 0.2763041 -0.20694508, + 0.94156748 0.26267412 -0.21083911, + 0.96214211 0.21254803 -0.17060502, + 0.96175414 0.21484102 -0.16991901, + 0.97678435 0.16802406 -0.13289204, + 0.97720367 0.16471495 -0.13394795, + 0.98749167 0.12232795 -0.099478565, + 0.98740739 0.12327004 -0.099153034, + 0.99412525 0.084338821 -0.067838512, + 0.99397975 0.086745776 -0.066929184, + 0.99800402 0.049998 -0.038576301, + 0.99792552 0.052215174 -0.037660081, + 0.99978954 0.016638793 -0.012000695, + 0.99977863 0.017569294 -0.011580396, + 0.99979222 -0.017020004 0.011218303, + 0.99977922 -0.018094303 0.010688903, + 0.99808311 -0.053285208 0.031477205, + 0.99794263 -0.056906782 0.029533489, + 0.99453902 -0.092633702 0.048075002, + 0.99408662 -0.09915816 0.044265587, + 0.98886186 -0.13590899 0.060671594, + 0.987822 -0.145762 0.054416601, + 0.98055762 -0.18383794 0.06863118, + 0.97856945 -0.19715409 0.059432831, + 0.96911901 -0.236099 0.071172997, + 0.96567434 -0.25312009 0.058338221, + 0.95372826 -0.29298905 0.067527018, + 0.94826734 -0.31340811 0.050642017, + 0.93345487 -0.35410196 0.057217494, + 0.92802078 -0.37007692 0.042666089, + 0.92603838 -0.37643716 0.027352609, + 0.90366888 -0.42710593 0.031034196, + 0.89691168 -0.44192484 0.015871294, + 0.87598872 -0.48202083 0.017311294, + 0.87090284 -0.49141088 0.0066091688, + 0.84813941 -0.52972525 0.0071244733, + 0.84316599 -0.53764498 -0.0029871601, + 0.81856418 -0.57440615 -0.0031914008, + 0.81215501 -0.583224 -0.0159362, + 0.78567088 -0.61841393 -0.016897798, + 0.7781927 -0.62723279 -0.03154479, + 0.75033802 -0.66022003 -0.033203799, + 0.74187803 -0.66869408 -0.049651407, + 0.71274179 -0.6995008 -0.051938888, + 0.70335323 -0.70736426 -0.070213623, + 0.67272103 -0.736278 -0.073083602, + 0.66250008 -0.74324906 -0.093136609, + 0.63049066 -0.77017355 -0.096510343, + 0.61952889 -0.77599984 -0.11835597, + 0.58685005 -0.80043912 -0.12208302, + 0.57565212 -0.80474418 -0.14495303, + 0.54234296 -0.82685089 -0.14893499, + 0.53125882 -0.82949769 -0.17232995, + 0.49695995 -0.84963191 -0.17651199, + 0.48525193 -0.85066086 -0.20225397, + 0.45012012 -0.86875015 -0.20655504, + 0.43843094 -0.86789191 -0.23354197, + 0.40324807 -0.8836571 -0.23778403, + 0.39183509 -0.88083422 -0.26570007, + 0.35686791 -0.89435178 -0.26977795, + 0.34586802 -0.88949913 -0.29860803, + 0.31082395 -0.90104973 -0.30248594, + 0.30041304 -0.8941381 -0.33206803, + 0.26584995 -0.90370476 -0.33562091, + 0.25630397 -0.89479786 -0.36557496, + 0.22231293 -0.90255469 -0.36874387, + 0.22237507 -0.90263122 -0.3685191, + 0.19039004 -0.90887815 -0.37106904, + 0.19692405 -0.91906321 -0.3413851, + 0.162691 -0.92492998 -0.343564, + 0.16758005 -0.93458736 -0.31378913, + 0.131382 -0.939776 -0.31553099, + 0.13480002 -0.94876909 -0.28577304, + 0.096804738 -0.95301133 -0.28705108, + 0.099002026 -0.96129525 -0.25711906, + 0.059887908 -0.96430713 -0.25792503, + 0.061048586 -0.97178078 -0.22784895, + 0.020600205 -0.97339022 -0.22822607, + 0.020940498 -0.97995889 -0.19809598, + -0.020388806 -0.97997022 -0.19809805, + -0.020040194 -0.97339678 -0.22824794, + -0.060393315 -0.97181523 -0.22787707, + -0.059226613 -0.96434522 -0.25793505, + -0.098354913 -0.96135712 -0.25713602, + -0.096155077 -0.95308673 -0.28701895, + -0.13420098 -0.94886178 -0.28574693, + -0.13078794 -0.9398995 -0.31540984, + -0.16724306 -0.93469036 -0.31366211, + -0.16239299 -0.92510486 -0.34323397, + -0.19680899 -0.919213 -0.341048, + -0.19028997 -0.90905488 -0.37068698, + -0.222674 -0.90272599 -0.36810601, + -0.22248593 -0.90249568 -0.36878389, + -0.25628501 -0.89477998 -0.365632, + -0.26589909 -0.90374827 -0.33546513, + -0.30055699 -0.89415097 -0.33190301, + -0.311001 -0.901079 -0.30221701, + -0.34595397 -0.88955188 -0.29835096, + -0.35695511 -0.89439029 -0.26953509, + -0.3920469 -0.88081676 -0.26544493, + -0.40339893 -0.88361889 -0.23766997, + -0.43860888 -0.86783379 -0.23342393, + -0.45018905 -0.8686831 -0.20668703, + -0.48526117 -0.85062331 -0.20239007, + -0.49681911 -0.84961516 -0.17698805, + -0.53105223 -0.82953143 -0.17280409, + -0.54237795 -0.82683289 -0.14890799, + -0.57571006 -0.80470812 -0.14492401, + -0.58707565 -0.80033153 -0.12170292, + -0.61975998 -0.77587199 -0.117984, + -0.63074994 -0.77001691 -0.096065283, + -0.66282469 -0.74301463 -0.092696555, + -0.67306727 -0.73601234 -0.072569638, + -0.70368063 -0.70708764 -0.069717668, + -0.71302903 -0.69924003 -0.051508199, + -0.74218839 -0.66838044 -0.049235031, + -0.7505511 -0.65999007 -0.032958303, + -0.77838898 -0.62700099 -0.031310901, + -0.78574616 -0.61831814 -0.016898403, + -0.8122285 -0.58312166 -0.01593649, + -0.81848019 -0.5745241 -0.0035063808, + -0.84306097 -0.537808 -0.0032823, + -0.84785569 -0.53018785 0.0064529176, + -0.87063003 -0.49190199 0.0059869401, + -0.87583131 -0.48232117 0.016909905, + -0.89675885 -0.44224793 0.015504899, + -0.90747899 -0.41818699 0.0400193, + -0.92544127 -0.37716809 0.036093809, + -0.93371814 -0.35329804 0.057888009, + -0.94847786 -0.31267396 0.051231693, + -0.95386666 -0.29243788 0.067959279, + -0.96578938 -0.25259709 0.058700822, + -0.96916538 -0.23586509 0.071317226, + -0.9786011 -0.19696003 0.059553806, + -0.980555 -0.183863 0.068602502, + -0.98782313 -0.14576502 0.054387607, + -0.98885322 -0.13601503 0.060575515, + -0.99408162 -0.099239364 0.044197187, + -0.99453366 -0.092730969 0.047996383, + -0.99793965 -0.056980181 0.029492188, + -0.99808067 -0.05335398 0.031438489, + -0.99977887 -0.018119298 0.010676599, + -0.99979186 -0.017050799 0.011203199, + -0.99977821 0.017601803 -0.011565203, + -0.99978924 0.016673403 -0.011984603, + -0.99792224 0.05231801 -0.037605409, + -0.99799901 0.0501603 -0.038496699, + -0.9939605 0.087055348 -0.066812627, + -0.99410534 0.08467333 -0.067712523, + -0.98736191 0.12377199 -0.098979682, + -0.9875195 0.12201394 -0.099587955, + -0.97725791 0.16427998 -0.13408598, + -0.97688723 0.16722204 -0.13314703, + -0.96192753 0.2138079 -0.17023993, + -0.96142924 0.21672104 -0.16936904, + -0.94042873 0.26788795 -0.20935595, + -0.93850255 0.27640387 -0.2069149, + -0.90935087 0.33304796 -0.24931897, + -0.897219 0.37190801 -0.23808099, + -0.85449302 0.43749699 -0.28006801, + -0.8361963 0.47917819 -0.2667661, + -0.77785212 0.54909104 -0.30568802, + -0.74973857 0.59586763 -0.28780884, + -0.68622708 0.65498608 -0.31636304, + -0.68004876 0.65198076 -0.33534288, + -0.66583383 0.67094183 -0.3263469, + -0.62639701 0.70098102 -0.340958, + -0.73319209 0.54231703 -0.41027007, + -0.68401748 0.61144942 -0.39780629, + -0.7582069 0.47442594 -0.44726095, + -0.71606678 0.50790983 -0.47882783, + -0.6143471 0.68141615 -0.39780608, + -0.70579344 0.53468829 -0.46471927, + -0.66164482 0.5659349 -0.49187788, + -0.72004884 0.43649492 -0.53944588, + -0.67918009 0.46168604 -0.57057905, + -0.72077483 0.33266592 -0.60812587, + -0.68166298 0.35114101 -0.6419, + -0.68791062 0.055324875 -0.72368366, + -0.67221606 0.22202903 -0.70627809, + -0.71080178 0.21094392 -0.67101675, + -0.72497475 0.037756786 -0.68773979, + -0.71081579 0.20307992 -0.67342377, + -0.74752599 0.191778 -0.63594502, + -0.75941968 0.04923078 -0.64873576, + -0.74752802 0.185325 -0.63785303, + -0.78172171 0.17399594 -0.59886277, + -0.79235286 0.017470598 -0.60981292, + -0.781708 0.16720501 -0.60081202, + -0.81381851 0.15580291 -0.55984366, + -0.82218319 0.04080971 -0.56775814, + -0.81379086 0.15033399 -0.56137693, + -0.84373313 0.13885002 -0.51849306, + -0.82962215 0.22986606 -0.50881112, + -0.85923982 0.21061796 -0.46620488, + -0.84197873 0.2891759 -0.45546585, + -0.87180972 0.26255491 -0.41353685, + -0.84094417 0.36853909 -0.39622208, + -0.87630028 0.32811311 -0.35276011, + -0.84241718 0.42216608 -0.3348271, + -0.88178402 0.369537 -0.29308599, + -0.88351101 0.36465201 -0.294002, + -0.92081457 0.30361086 -0.24478789, + -0.92818123 0.27578005 -0.24985006, + -0.95359564 0.22313492 -0.20215392, + -0.95735025 0.20257704 -0.20601705, + -0.97645301 0.151255 -0.153823, + -0.97690088 0.14733799 -0.15477799, + -0.98735678 0.10929198 -0.11481197, + -0.98725122 0.11061403 -0.11445403, + -0.99406564 0.07559707 -0.078221269, + -0.9940359 0.07616239 -0.078051195, + -0.99802625 0.043857511 -0.04494511, + -0.99797702 0.045512799 -0.044390701, + -0.99979502 0.0144952 -0.0141378, + -0.99978834 0.015190406 -0.013879305, + -0.99980152 -0.014708892 0.013439293, + -0.99979311 -0.015577402 0.013082102, + -0.99820501 -0.045862202 0.0385154, + -0.99811113 -0.048959509 0.037111502, + -0.99498791 -0.07968919 0.060404792, + -0.9946835 -0.085385464 0.057568375, + -0.98997778 -0.11709497 0.078947477, + -0.98927921 -0.12577704 0.074208014, + -0.98285455 -0.15880293 0.093693458, + -0.98151761 -0.17065294 0.086606473, + -0.97330976 -0.20464896 0.10385998, + -0.97099251 -0.21992089 0.093852252, + -0.96075565 -0.25513491 0.10887996, + -0.95706815 -0.27366304 0.095546812, + -0.94452226 -0.31009105 0.10826502, + -0.93887126 -0.33207208 0.090823621, + -0.92368579 -0.3695769 0.10108098, + -0.92394322 -0.36941108 0.09931992, + -0.90314728 -0.41460714 0.11147204, + -0.89946997 -0.42489299 0.102077, + -0.8784889 -0.46454495 0.11160298, + -0.87370783 -0.47600788 0.10025598, + -0.8500827 -0.51534283 0.10854096, + -0.84411681 -0.52763289 0.095238179, + -0.81778389 -0.56637293 0.10223099, + -0.8104012 -0.57944012 0.086597621, + -0.78181809 -0.61665803 0.092159808, + -0.77318388 -0.62977695 0.074616194, + -0.74245405 -0.66524404 0.078818411, + -0.73600465 -0.6737507 0.066008069, + -0.70322484 -0.70757979 0.069322385, + -0.69782609 -0.71386606 0.058599409, + -0.66659993 -0.74291694 0.060984194, + -0.65820009 -0.75157011 0.043762103, + -0.62578982 -0.77867281 0.045340188, + -0.40069515 -0.91619933 -0.0047147418, + -0.44917378 -0.89343256 -0.0045975777, + -0.45337993 -0.89129388 0.0064649889, + -0.49319687 -0.8698948 0.0063097687, + -0.49734694 -0.86739486 0.016498398, + -0.53668082 -0.8436327 0.016046394, + -0.54066998 -0.840855 0.025276899, + -0.57875806 -0.81513113 0.024503604, + -0.58250594 -0.81216586 0.032763895, + -0.61936504 -0.78446513 0.031646404, + -0.62046289 -0.78403282 0.017846096, + -0.57951188 -0.81475282 0.018545296, + -0.57571387 -0.81758779 0.010189397, + -0.53764492 -0.84310585 0.010507399, + -0.5336172 -0.8457253 0.0012072105, + -0.49433795 -0.86926889 0.0012408199, + -0.49016669 -0.87158245 -0.0089731943, + -0.45045215 -0.8927533 -0.0091911741, + -0.44617301 -0.894714 -0.020410599, + -0.40612495 -0.91357988 -0.020840999, + -0.39896807 -0.91604412 -0.041081604, + -0.36122897 -0.93154091 -0.041776497, + -0.3517209 -0.93337578 -0.071429282, + -0.31349391 -0.94682175 -0.072458282, + -0.30464306 -0.94686025 -0.10319103, + -0.26668891 -0.95810962 -0.10441697, + -0.25870395 -0.95634079 -0.13595797, + -0.22112507 -0.96553725 -0.13726503, + -0.21412508 -0.96198833 -0.16949606, + -0.17668507 -0.96933633 -0.17079106, + -0.17076601 -0.96403211 -0.20366903, + -0.13372901 -0.9696151 -0.20484903, + -0.12904105 -0.96265638 -0.23799409, + -0.092682645 -0.96659446 -0.23896712, + -0.089278623 -0.95807326 -0.27225906, + -0.053949274 -0.96051353 -0.27295288, + -0.051879101 -0.95050102 -0.30636001, + -0.017510597 -0.95163679 -0.30672595, + -0.016817803 -0.94026309 -0.34003302, + 0.016748106 -0.94026434 -0.34003311, + 0.017439695 -0.95163167 -0.30674589, + 0.05173678 -0.95050162 -0.30638188, + 0.053804282 -0.96050966 -0.27299491, + 0.089232102 -0.95806599 -0.2723, + 0.092620209 -0.96658313 -0.23903704, + 0.128823 -0.96266699 -0.238069, + 0.13353203 -0.96965921 -0.20476905, + 0.17064701 -0.96407014 -0.20358904, + 0.17658302 -0.96938813 -0.17060201, + 0.2140709 -0.96203351 -0.16930793, + 0.22102894 -0.96555978 -0.13726097, + 0.25859702 -0.95637012 -0.13595502, + 0.26654902 -0.95813012 -0.10458702, + 0.30450296 -0.9468869 -0.10335898, + 0.31332514 -0.9468565 -0.072733738, + 0.34816197 -0.93468088 -0.071798392, + 0.65013117 -0.75966418 -0.015488704, + 0.61046201 -0.79188102 -0.016145499, + 0.60677892 -0.79451185 -0.023878196, + 0.5698871 -0.82135218 -0.024684906, + 0.56590718 -0.82379329 -0.033372011, + 0.5279448 -0.84858268 -0.034376189, + 0.52373809 -0.8507421 -0.044005305, + 0.48470494 -0.87350988 -0.045182995, + 0.48035076 -0.87530357 -0.055737674, + 0.44107911 -0.89565426 -0.057033613, + 0.43667886 -0.89700872 -0.06846118, + 0.39708686 -0.91511971 -0.069843374, + 0.39273292 -0.91598177 -0.082086578, + 0.35283908 -0.93194926 -0.083517626, + 0.34588498 -0.93239391 -0.10490599, + 0.30824897 -0.94534087 -0.10636298, + 0.29938513 -0.94426036 -0.13689804, + 0.26197696 -0.95508885 -0.13846798, + 0.25400198 -0.95220488 -0.16967298, + 0.21686999 -0.96106201 -0.171252, + 0.20977597 -0.9563179 -0.20359297, + 0.17294005 -0.96334326 -0.20508905, + 0.16698796 -0.95685077 -0.23780595, + 0.13053101 -0.96217412 -0.23912904, + 0.12582903 -0.95405424 -0.27193305, + 0.090395175 -0.95776075 -0.27298895, + 0.086980842 -0.94804949 -0.30600116, + 0.052371908 -0.95035011 -0.30674404, + 0.050287608 -0.93917513 -0.33973703, + 0.016902598 -0.94023091 -0.34011796, + 0.0162053 -0.92776299 -0.37281799, + -0.016239706 -0.92776233 -0.37281811, + -0.016937802 -0.9402371 -0.34009904, + -0.050359793 -0.93917888 -0.33971596, + -0.05244742 -0.95036536 -0.30668411, + -0.087088719 -0.94805926 -0.30594006, + -0.0904985 -0.957753 -0.272982, + -0.12599798 -0.95403475 -0.27192295, + -0.13071297 -0.96217376 -0.23903094, + -0.16708802 -0.95685714 -0.23771003, + -0.173024 -0.96331602 -0.205146, + -0.20989503 -0.95628011 -0.20364803, + -0.21695608 -0.96100533 -0.17146106, + -0.25397906 -0.95217323 -0.16988504, + -0.26201987 -0.95508355 -0.13842294, + -0.29945797 -0.94424391 -0.13685198, + -0.30836213 -0.94532537 -0.10617404, + -0.34606388 -0.93234867 -0.10471696, + -0.35570204 -0.93159312 -0.07490211, + -0.39301714 -0.91657329 -0.073694527, + -0.40315109 -0.91402227 -0.045083612, + -0.44006285 -0.89687669 -0.044237886, + -0.43683192 -0.89861178 -0.040923089, + -0.48389113 -0.87422216 -0.039812412, + -0.48818782 -0.87224472 -0.029357089, + -0.52730697 -0.84919399 -0.028581301, + -0.53144187 -0.84687984 -0.019082796, + -0.56944788 -0.82181883 -0.018518096, + -0.57124507 -0.82012212 -0.032844905, + -0.52826172 -0.84840155 -0.033977482, + -0.52405101 -0.85056901 -0.043622401, + -0.48502913 -0.8733502 -0.044790812, + -0.48067188 -0.87515074 -0.055369284, + -0.44132689 -0.89555573 -0.056660283, + -0.4337641 -0.89779824 -0.076204218, + -0.39721686 -0.9144367 -0.077616371, + -0.38695091 -0.91593975 -0.10641098, + -0.35002887 -0.93048066 -0.10809996, + -0.34031686 -0.9301486 -0.13786994, + -0.30311298 -0.94265586 -0.13972299, + -0.29414186 -0.94046152 -0.17033093, + -0.25717992 -0.95089364 -0.17221995, + -0.249071 -0.94683802 -0.203621, + -0.21252607 -0.95531434 -0.20544407, + -0.20541592 -0.94943166 -0.23745291, + -0.16928498 -0.95611787 -0.23912597, + -0.16332693 -0.94849366 -0.2714479, + -0.12758493 -0.95354652 -0.27289388, + -0.12285796 -0.94426364 -0.30540487, + -0.088111907 -0.94777113 -0.30653903, + -0.084670231 -0.93686134 -0.33929613, + -0.050996911 -0.93901426 -0.34007609, + -0.04891922 -0.92674237 -0.37249911, + -0.016383093 -0.92772859 -0.37289581, + -0.016352903 -0.92716223 -0.3743031, + 0.016315892 -0.92716259 -0.37430382, + 0.016346093 -0.92772961 -0.37289482, + 0.048885509 -0.92674422 -0.37249908, + 0.050960191 -0.93900174 -0.3401159, + 0.084634967 -0.93684965 -0.33933687, + 0.088070333 -0.94774234 -0.30664012, + 0.12270802 -0.94424909 -0.30551004, + 0.12744503 -0.95355725 -0.27292207, + 0.16306502 -0.94852912 -0.27148202, + 0.16903998 -0.9561609 -0.23912697, + 0.20525795 -0.94946575 -0.23745294, + 0.21238193 -0.95536166 -0.20537293, + 0.24896502 -0.94688112 -0.20355003, + 0.25712389 -0.95095754 -0.17195091, + 0.29412907 -0.94051427 -0.17006205, + 0.30301306 -0.94268423 -0.13974804, + 0.34029484 -0.93015361 -0.13788994, + 0.34992397 -0.93049085 -0.10835098, + 0.38674101 -0.915999 -0.106664, + 0.39411184 -0.91501772 -0.086129971, + 0.433516 -0.89718002 -0.084450997, + 0.43795812 -0.89603025 -0.072956018, + 0.47708789 -0.87595677 -0.071321584, + 0.4814887 -0.87434846 -0.060689963, + 0.5204398 -0.85184872 -0.059128176, + 0.52469885 -0.8498528 -0.04941019, + 0.56260568 -0.82533157 -0.047984477, + 0.56665468 -0.82302356 -0.039173681, + 0.60353893 -0.7964319 -0.037907995, + 0.60729164 -0.7939105 -0.030051081, + 0.64339864 -0.76498353 -0.028956084, + 0.6500513 -0.75973535 -0.015350208, + 0.68169773 -0.73148465 -0.014779393, + 0.69106817 -0.72277915 0.003900961, + 0.69082481 -0.72300881 0.004388799, + 0.65292859 -0.75740552 0.0045975973, + 0.64960974 -0.76026469 -0.0021831093, + 0.61358976 -0.78962171 -0.0022674093, + 0.60994697 -0.79237986 -0.0099360291, + 0.57305998 -0.81944901 -0.0102755, + 0.569139 -0.822025 -0.018858399, + 0.53112364 -0.84707141 -0.019432986, + 0.52698308 -0.84938312 -0.028936304, + 0.48788807 -0.8724001 -0.029720403, + 0.48357013 -0.87438118 -0.04021721, + 0.44415089 -0.89500576 -0.041165888, + 0.43979821 -0.89656043 -0.052507427, + 0.40005684 -0.91492271 -0.05358278, + 0.39572304 -0.91600811 -0.06582091, + 0.35297698 -0.93322587 -0.067058094, + 0.35835803 -0.93222612 -0.050339509, + 0.39866191 -0.91576374 -0.049450491, + 0.40294594 -0.91446286 -0.037312295, + 0.44285214 -0.89584929 -0.036552817, + 0.44714913 -0.89410126 -0.025314106, + 0.48675093 -0.87319088 -0.024722096, + 0.49100211 -0.87104017 -0.014352203, + 0.53016287 -0.84778082 -0.013968896, + 0.5342657 -0.84530455 -0.0045246272, + 0.57230687 -0.82002783 -0.0043893289, + 0.57617283 -0.81731772 0.0040874388, + 0.61307496 -0.79001486 0.0039508995, + 0.61668611 -0.78712416 0.011567803, + 0.65265524 -0.75757331 0.011133504, + 0.65591121 -0.75462818 0.017798504, + 0.69080198 -0.72284299 0.0170488, + 0.69662893 -0.71685392 0.028784595, + 0.72650105 -0.68661207 0.027570203, + 0.73415375 -0.67764175 0.042660084, + 0.76235938 -0.64587528 0.040660318, + 0.7669149 -0.63983595 0.049511492, + 0.79668301 -0.60259598 0.046629801, + 0.80120009 -0.59581208 0.055555809, + 0.82914019 -0.55662614 0.051902011, + 0.83583784 -0.5450359 0.065657787, + 0.86113632 -0.50472516 0.060801722, + 0.86685669 -0.49314183 0.073284172, + 0.88945103 -0.452066 0.06718, + 0.89390498 -0.44148099 0.077643298, + 0.91398412 -0.39961705 0.070280708, + 0.91738063 -0.39009386 0.07899037, + 0.9350121 -0.34756202 0.07037811, + 0.93953955 -0.33209985 0.08351656, + 0.95311654 -0.29346585 0.073800661, + 0.95767564 -0.2737309 0.089043073, + 0.96865851 -0.23621288 0.076838464, + 0.97147787 -0.22013196 0.088163294, + 0.98023677 -0.18364696 0.073551089, + 0.98187524 -0.17102504 0.08167962, + 0.98866087 -0.13550499 0.064715691, + 0.98950624 -0.12633103 0.070127815, + 0.99443209 -0.092135705 0.051145807, + 0.99480551 -0.085998155 0.054462872, + 0.99804264 -0.052832682 0.03345909, + 0.9981575 -0.049482279 0.035116084, + 0.99978763 -0.016804194 0.011925495, + 0.99979836 -0.015820805 0.012369704, + 0.99978501 0.016333999 -0.0127709, + 0.99979365 0.015519194 -0.013106096, + 0.99796522 0.048713312 -0.041138712, + 0.99802476 0.04687579 -0.04182519, + 0.9940359 0.081371091 -0.072603896, + 0.99412638 0.079761833 -0.073149428, + 0.98739362 0.11665495 -0.10698396, + 0.98732275 0.11748597 -0.10672798, + 0.97688043 0.15824091 -0.14375091, + 0.97727352 0.15492892 -0.14468393, + 0.9625265 0.19819991 -0.18509291, + 0.96097636 0.20781107 -0.18259005, + 0.93350714 0.26935703 -0.23666704, + 0.92773455 0.29267085 -0.23162989, + 0.88155788 0.37017098 -0.29296598, + 0.87889773 0.37752986 -0.29156491, + 0.83871198 0.43100399 -0.332863, + 0.85854787 0.38096195 -0.34316698, + 0.82238889 0.42271295 -0.38077593, + 0.84527183 0.3613199 -0.3936539, + 0.81019264 0.39636582 -0.4318358, + 0.84069788 0.30018198 -0.45068595, + 0.8076241 0.32689703 -0.49079707, + 0.8318724 0.22482111 -0.50738925, + 0.79969281 0.24322994 -0.54893589, + 0.81677181 0.13082998 -0.56193191, + 0.78495061 0.14048894 -0.60341972, + 0.79121882 0.058788285 -0.60870087, + 0.78891867 0.041127186 -0.61311978, + 0.78958273 -0.0031844089 -0.61363578, + 0.81817132 0.016095005 -0.57474917, + 0.81659913 0.064009406 -0.57364506, + 0.81708568 0.063945979 -0.57295883, + 0.81873149 0.0085272444 -0.57411337, + 0.84580386 -0.0035668795 -0.53348196, + 0.84411716 0.063213617 -0.53241915, + 0.82224619 0.035091206 -0.56804913, + 0.81662184 0.12413097 -0.56366688, + 0.84625846 0.11458207 -0.52030528, + 0.8325609 0.21435297 -0.51077896, + 0.86183381 0.19626495 -0.46767789, + 0.84292716 0.28577307 -0.45585912, + 0.87261683 0.25941694 -0.4138149, + 0.85034257 0.34051284 -0.40120882, + 0.88141888 0.30563897 -0.36011896, + 0.86666083 0.35310191 -0.3524459, + 0.89766026 0.31190306 -0.31132406, + 0.88750172 0.34422088 -0.30635387, + 0.91909391 0.29434696 -0.26196596, + 0.92112398 0.286955 -0.263035, + 0.95398736 0.22103608 -0.20261107, + 0.95729262 0.20283893 -0.20602693, + 0.97643554 0.15140593 -0.15378493, + 0.97720289 0.14461298 -0.15543999, + 0.98751265 0.10730796 -0.11534195, + 0.98723012 0.11088402 -0.11437401, + 0.99405891 0.075762093 -0.078146696, + 0.99403054 0.076299161 -0.077985063, + 0.99802375 0.043944988 -0.044915989, + 0.99798226 0.045339812 -0.044448812, + 0.99979562 0.014438194 -0.014154395, + 0.99978876 0.015148097 -0.013890496, + 0.99980187 -0.014669598 0.013451698, + 0.99979347 -0.015548607 0.013090206, + 0.99820709 -0.045788404 0.038548905, + 0.99811363 -0.04887988 0.037147585, + 0.9949919 -0.07958179 0.060480293, + 0.99468833 -0.085278928 0.057642922, + 0.98998898 -0.116937 0.079041399, + 0.98928785 -0.12566899 0.074275091, + 0.98286635 -0.15867706 0.093783841, + 0.98152864 -0.17054994 0.086684473, + 0.97332436 -0.20453107 0.10395604, + 0.97098589 -0.21994898 0.093854882, + 0.96075678 -0.25513494 0.10886898, + 0.95701665 -0.2739059 0.095366165, + 0.94444287 -0.31039998 0.10807198, + 0.94066685 -0.32541198 0.096191585, + 0.93967986 -0.33199796 0.082335696, + 0.92103422 -0.37803009 0.09375152, + 0.91794926 -0.38737109 0.085515819, + 0.89862591 -0.42840093 0.094573386, + 0.894548 -0.43889299 0.084598199, + 0.87276816 -0.47931212 0.092389122, + 0.86755699 -0.49077201 0.080546498, + 0.8431254 -0.53061825 0.087086245, + 0.83659202 -0.54292297 0.073133498, + 0.80946529 -0.58191216 0.078385532, + 0.801952 -0.59404403 0.063124798, + 0.77261972 -0.63131475 0.067085281, + 0.76739913 -0.63865006 0.056787107, + 0.73623621 -0.67406523 0.059936222, + 0.73113406 -0.68040305 0.049946409, + 0.70142984 -0.7108258 0.05217969, + 0.69323337 -0.71982539 0.035763919, + 0.66184402 -0.74871802 0.0371994, + 0.65563494 -0.75468385 0.024395397, + 0.61972904 -0.78440613 0.025356203, + 0.61616689 -0.78741384 0.017826596, + 0.57926589 -0.81492984 0.018449496, + 0.57542115 -0.81779629 0.0099933539, + 0.53736681 -0.84328568 0.010304797, + 0.53330785 -0.84592068 0.00093598966, + 0.49404806 -0.86943412 0.00096200709, + 0.48985711 -0.87175316 -0.0092931818, + 0.45014411 -0.89290524 -0.0095186718, + 0.4458662 -0.89485943 -0.020737208, + 0.40581208 -0.91371125 -0.021174006, + 0.40157309 -0.91522425 -0.033221208, + 0.36103901 -0.93193698 -0.033827901, + 0.35692188 -0.93296665 -0.046689685, + 0.315896 -0.94760799 -0.047422402, + 0.30951789 -0.94834167 -0.069617979, + 0.27104697 -0.95998287 -0.070472591, + 0.26312301 -0.95935601 -0.101992, + 0.22498597 -0.96890187 -0.10300699, + 0.21805704 -0.9665311 -0.13516201, + 0.18011005 -0.97416735 -0.13622904, + 0.17425896 -0.97007877 -0.16905895, + 0.13642795 -0.97594064 -0.17007995, + 0.13173205 -0.97014338 -0.20363808, + 0.094736934 -0.97427034 -0.20450507, + 0.09133631 -0.9668951 -0.23826803, + 0.055141218 -0.96947634 -0.23890409, + 0.053083092 -0.96066791 -0.27257898, + 0.017836101 -0.96187115 -0.27292103, + 0.017141793 -0.9516905 -0.30657986, + -0.017247595 -0.95168865 -0.30657989, + -0.017942706 -0.96186435 -0.2729381, + -0.053325281 -0.96065062 -0.2725929, + -0.055374581 -0.96946865 -0.23888092, + -0.091476671 -0.96688765 -0.23824391, + -0.094870239 -0.97424537 -0.20456207, + -0.13189101 -0.97011012 -0.20369403, + -0.13657604 -0.97589433 -0.17022707, + -0.17429896 -0.97004575 -0.16920696, + -0.18017602 -0.97415411 -0.13623701, + -0.21815507 -0.96650833 -0.13516705, + -0.22511707 -0.96888733 -0.10285804, + -0.26328999 -0.95932603 -0.101843, + -0.27123091 -0.95994765 -0.070244476, + -0.30974597 -0.94828385 -0.06939099, + -0.31851813 -0.94712538 -0.038728915, + -0.3571761 -0.93325722 -0.038161807, + -0.36654589 -0.93035865 -0.0087642074, + -0.40469217 -0.91441244 -0.0086139934, + -0.41171205 -0.91124314 0.011368101, + -0.45208922 -0.8919034 0.011126806, + -0.45626789 -0.88956678 0.022146495, + -0.49620283 -0.86793768 0.021607993, + -0.50030613 -0.86526817 0.031697609, + -0.53970802 -0.84128797 0.0308192, + -0.54363692 -0.83836991 0.039933898, + -0.58176136 -0.81243849 0.038698822, + -0.5884409 -0.80676681 0.053522289, + -0.62185264 -0.78141654 0.051840469, + -0.63062292 -0.77288789 0.07042069, + -0.66292572 -0.74559665 0.067934074, + -0.66878504 -0.73915309 0.079870209, + -0.70323694 -0.70684093 0.076378591, + -0.71034104 -0.69798505 0.090732805, + -0.74279302 -0.66393501 0.086306497, + -0.75210989 -0.65055794 0.10538098, + -0.78222585 -0.61497891 0.099617675, + -0.79033798 -0.60144299 0.116757, + -0.81820172 -0.56439483 0.10956496, + -0.82493043 -0.55137825 0.12438606, + -0.85051221 -0.51306212 0.11574203, + -0.85601246 -0.50072873 0.12850392, + -0.87891209 -0.46201205 0.11856802, + -0.8832649 -0.45068794 0.12931898, + -0.90354812 -0.41186705 0.11818001, + -0.90696687 -0.40151295 0.12727298, + -0.924914 -0.362405 0.114877, + -0.92946488 -0.34585997 0.12835899, + -0.94362777 -0.31032595 0.11517097, + -0.94830197 -0.289184 0.130752, + -0.9600541 -0.25496402 0.11528002, + -0.96314234 -0.23695809 0.12731004, + -0.97278237 -0.20412508 0.10967004, + -0.97468865 -0.18957493 0.11850496, + -0.98248512 -0.15800901 0.098773412, + -0.98359078 -0.14669096 0.10502798, + -0.98974437 -0.11614905 0.083160132, + -0.99031734 -0.10795504 0.087277032, + -0.99486166 -0.078731768 0.063651279, + -0.99511111 -0.07339251 0.066087008, + -0.99815738 -0.045091115 0.040602714, + -0.99823201 -0.042301401 0.0417541, + -0.99979621 -0.014369803 0.014183904, + -0.99980289 -0.013595698 0.014471798, + -0.99978966 0.014043695 -0.014948694, + -0.99979538 0.013381905 -0.015169306, + -0.99797875 0.04203999 -0.047655489, + -0.99800235 0.041179914 -0.047911119, + -0.99395835 0.071543321 -0.083237633, + -0.994048 0.069707602 -0.083722398, + -0.98719233 0.10207903 -0.12260205, + -0.98698825 0.10476802 -0.12197503, + -0.97404748 0.14747907 -0.17170207, + -0.97233254 0.16078992 -0.16945793, + -0.94949991 0.21596897 -0.22761197, + -0.94904011 0.21824703 -0.22735703, + -0.925286 0.262647 -0.27361, + -0.93578875 0.21590695 -0.27871794, + -0.91105425 0.25248206 -0.32593408, + -0.92468941 0.18554009 -0.33245215, + -0.90151429 0.21089408 -0.37788314, + -0.91072112 0.15533601 -0.38269806, + -0.88699526 0.17367305 -0.4278751, + -0.89531887 0.10595199 -0.43264094, + -0.87071884 0.11697897 -0.47766587, + -0.87646925 -0.00088254624 -0.48145711, + -0.86750782 0.050476991 -0.49485588, + -0.86860985 -0.0035659291 -0.49548388, + -0.86859381 -0.0035659291 -0.49551189, + -0.86749071 0.050516482 -0.49488181, + -0.86766142 0.050499722 -0.49458423, + -0.8687641 -0.0036193104 -0.49521306, + -0.84320509 0.012866502 -0.53743804, + -0.84203291 0.054251794 -0.53669095, + -0.84207588 0.054247793 -0.53662395, + -0.8159765 -0.0027201583 -0.57807863, + -0.8159743 -0.0035541612 -0.5780772, + -0.81585139 -0.0035541474 -0.57825059, + -0.81457818 0.055959716 -0.57734811, + -0.81483787 0.055936191 -0.57698393, + -0.81611013 -0.0036205905 -0.57788503, + -0.78653318 0.009995603 -0.61746711, + -0.78530979 0.056637786 -0.61650687, + -0.78520215 0.056647107 -0.61664307, + -0.75521314 0.020395502 -0.65516204, + -0.75536633 -0.003358931 -0.65529424, + -0.75557113 -0.0033589303 -0.65505809, + -0.75426614 0.058850706 -0.65392607, + -0.7531271 0.058945909 -0.65522903, + -0.7544353 -0.0030964313 -0.65636724, + -0.72243077 0.0071969973 -0.69140577, + -0.72119677 0.058852177 -0.69022578, + -0.72136897 0.058838591 -0.69004697, + -0.68672717 0.047476713 -0.72536319, + -0.6875 -0.00280127 -0.726179, + -0.68719226 -0.0028012509 -0.72647023, + -0.68600631 0.058793329 -0.72521633, + -0.64997584 0.061097383 -0.75749481, + -0.61150306 0.071674809 -0.78798914, + -0.61005276 0.07176958 -0.78910369, + -0.64935666 0.055563267 -0.75845152, + -0.63183403 0.24003802 -0.73699903, + -0.67220181 0.22928093 -0.70397085, + -0.63906002 0.382186 -0.667485, + -0.68011516 0.36427209 -0.63619918, + -0.6318512 0.5046491 -0.58829713, + -0.67428708 0.48080605 -0.56050205, + -0.60486931 0.62107128 -0.49840122, + -0.65010518 0.59261912 -0.47556913, + -0.54122114 0.74597317 -0.38807708, + -0.46735406 0.84115314 -0.27210602, + -0.39817485 0.89022869 -0.22124593, + -0.3679691 0.90238726 -0.22426806, + -0.463072 0.83494598 -0.297371, + -0.43312979 0.84908658 -0.30240786, + -0.54384881 0.74161273 -0.39273286, + -0.52414006 0.75261414 -0.39855906, + -0.385865 0.87892002 -0.28037101, + -0.41398907 0.86722714 -0.27664104, + -0.31544113 0.92820334 -0.19732107, + -0.34400383 0.91844457 -0.19524591, + -0.36044997 0.90933585 -0.20780797, + -0.43803513 0.87636524 -0.20027305, + -0.48632187 0.84134883 -0.23584594, + -0.57344568 0.78883666 -0.2211259, + -0.61755323 0.74468225 -0.25313309, + -0.69628102 0.67958099 -0.231003, + -0.73551857 0.62523365 -0.26095086, + -0.7990579 0.55486596 -0.23158197, + -0.80808085 0.53829092 -0.23926596, + -0.85904711 0.46776906 -0.20791903, + -0.86728388 0.44847795 -0.21606997, + -0.90599209 0.38134405 -0.18372601, + -0.91208178 0.3626779 -0.19123696, + -0.94010562 0.30153289 -0.15899494, + -0.94141233 0.29629213 -0.16110206, + -0.96191263 0.24015291 -0.13057795, + -0.96205747 0.23940212 -0.13089006, + -0.97688287 0.18757097 -0.10255198, + -0.97645622 0.19045804 -0.10128702, + -0.9870311 0.14173302 -0.075374804, + -0.98651278 0.14640898 -0.073190488, + -0.99369538 0.10028204 -0.050131619, + -0.99334002 0.104806 -0.0478676, + -0.99778688 0.060483191 -0.027624195, + -0.99762678 0.063825786 -0.025827894, + -0.99975914 0.020347701 -0.0082339412, + -0.99973851 0.021596989 -0.0075130663, + -0.99975455 -0.020926191 0.0072797067, + -0.99973035 -0.022318007 0.0064173322, + -0.99766153 -0.06568677 0.018887591, + -0.99740773 -0.070177987 0.015899597, + -0.99313354 -0.11409495 0.025849488, + -0.99231386 -0.12209898 0.020123698, + -0.98556638 -0.16703606 0.02752991, + -0.98370963 -0.17881595 0.018446892, + -0.97410703 -0.224894 0.0232003, + -0.97047365 -0.24100991 0.0097493865, + -0.95774335 -0.2873891 0.011625504, + -0.9523111 -0.30509603 -0.0044734506, + -0.93626302 -0.351262 -0.0051503698, + -0.93364286 -0.35800898 -0.011858098, + -0.9153074 -0.40253517 -0.013332906, + -0.91254014 -0.40850505 -0.019856501, + -0.89213312 -0.45124006 -0.021933801, + -0.88816589 -0.45849493 -0.030718196, + -0.86595398 -0.49900499 -0.033432301, + -0.86093771 -0.50680381 -0.044001084, + -0.83700013 -0.54515207 -0.047330506, + -0.83090985 -0.55319691 -0.059682284, + -0.80512983 -0.58967686 -0.063617982, + -0.79789031 -0.59774923 -0.077891827, + -0.77030033 -0.63233531 -0.082398735, + -0.76191986 -0.64012194 -0.098599687, + -0.73312879 -0.67216277 -0.10353496, + -0.72361177 -0.67938876 -0.12172496, + -0.69368798 -0.70898598 -0.127027, + -0.68352896 -0.71509391 -0.14638598, + -0.65231395 -0.74254996 -0.15200698, + -0.64196903 -0.74722397 -0.171849, + -0.60929513 -0.77277017 -0.17772405, + -0.59820008 -0.77616811 -0.19929802, + -0.56486964 -0.79925251 -0.20522588, + -0.55314708 -0.80113512 -0.22849703, + -0.51924109 -0.82185316 -0.23440605, + -0.50711787 -0.82199985 -0.25912893, + -0.47262093 -0.84049189 -0.26495796, + -0.46024612 -0.83870816 -0.29110506, + -0.42512521 -0.85509241 -0.29679215, + -0.41277292 -0.85124379 -0.32404092, + -0.37804994 -0.86521685 -0.32935998, + -0.36590683 -0.85919958 -0.35761482, + -0.33163598 -0.87097585 -0.36251697, + -0.3324669 -0.87153381 -0.3604089, + -0.30032298 -0.8814429 -0.36450598, + -0.310426 -0.88994998 -0.33410299, + -0.27594689 -0.89985061 -0.33781984, + -0.28404209 -0.90809631 -0.30770311, + -0.24798906 -0.91752124 -0.31089607, + -0.25433895 -0.92543077 -0.28087294, + -0.21663393 -0.93417466 -0.2835269, + -0.22148506 -0.94166625 -0.25339505, + -0.18207794 -0.94950765 -0.25550491, + -0.18562201 -0.95646203 -0.22522201, + -0.14456092 -0.96315354 -0.22679789, + -0.14698091 -0.96943039 -0.19647188, + -0.10508502 -0.97464824 -0.19753005, + -0.106559 -0.980156 -0.167151, + -0.063895226 -0.98375434 -0.16776405, + -0.064634025 -0.98842335 -0.13726504, + -0.021438397 -0.99026686 -0.13752098, + -0.021636302 -0.99403214 -0.10692102, + 0.022068392 -0.99402267 -0.10691996, + 0.021875799 -0.99025488 -0.13753799, + 0.065040879 -0.98839462 -0.13727996, + 0.064311616 -0.98373222 -0.16773504, + 0.10704497 -0.98010862 -0.16711794, + 0.10558295 -0.97461152 -0.19744492, + 0.14757201 -0.9693591 -0.19638103, + 0.14517191 -0.96308541 -0.22669686, + 0.18616399 -0.9563809 -0.22511896, + 0.18261304 -0.94942427 -0.25543305, + 0.22200505 -0.94156426 -0.25331905, + 0.21712703 -0.93404013 -0.28359303, + 0.2548781 -0.92526537 -0.28092909, + 0.24848697 -0.91729391 -0.31116897, + 0.28449005 -0.90786523 -0.30797106, + 0.27633899 -0.89953399 -0.33834201, + 0.31046689 -0.88972872 -0.33465388, + 0.30034107 -0.88117921 -0.3651281, + 0.33203709 -0.87141818 -0.3610841, + 0.33149987 -0.87105769 -0.36244488, + 0.36592108 -0.85923117 -0.3575241, + 0.37792286 -0.86518073 -0.32960087, + 0.41261193 -0.85122889 -0.32428497, + 0.42495495 -0.8550809 -0.29706898, + 0.45997119 -0.83875728 -0.29139808, + 0.47237599 -0.84054798 -0.26521701, + 0.50695413 -0.82202417 -0.25937206, + 0.51911294 -0.8218869 -0.23457097, + 0.55301708 -0.8011781 -0.22866103, + 0.56490988 -0.79927182 -0.20503995, + 0.59823632 -0.77618635 -0.19911809, + 0.60951871 -0.77272165 -0.17716691, + 0.64219594 -0.74715394 -0.17130499, + 0.65222293 -0.74261594 -0.15207498, + 0.68351984 -0.71509182 -0.14643897, + 0.69348902 -0.70910603 -0.127443, + 0.72334421 -0.67959917 -0.12214003, + 0.73282605 -0.67241508 -0.10403802, + 0.76162273 -0.64040077 -0.099084161, + 0.77000111 -0.63263303 -0.082908109, + 0.79758912 -0.59808707 -0.078380704, + 0.80486417 -0.58999211 -0.064055115, + 0.83064801 -0.553545 -0.060098201, + 0.83683419 -0.54538614 -0.047565412, + 0.8607946 -0.50702775 -0.044219978, + 0.86594331 -0.49902719 -0.033377912, + 0.88817132 -0.45848817 -0.030666411, + 0.89225829 -0.45100814 -0.021608707, + 0.91265786 -0.40825593 -0.019560399, + 0.9155249 -0.40205795 -0.012787698, + 0.93382561 -0.35754782 -0.011371994, + 0.93634075 -0.35105792 -0.0049220286, + 0.95237797 -0.30489001 -0.0042747199, + 0.95758367 -0.28793991 0.011136697, + 0.9703539 -0.24150798 0.009340859, + 0.97397947 -0.2254961 0.022707511, + 0.98362374 -0.17932695 0.018058296, + 0.98551285 -0.16739598 0.027258396, + 0.99228251 -0.12238594 0.019929091, + 0.99312425 -0.11418803 0.025796305, + 0.9974041 -0.070237905 0.015867501, + 0.99766225 -0.065670013 0.018907504, + 0.99973053 -0.02230629 0.0064223567, + 0.99975491 -0.020903898 0.0072910292, + 0.99973887 0.021576498 -0.0075256289, + 0.9997595 0.02032011 -0.0082506035, + 0.99763227 0.063721918 -0.025873106, + 0.9977929 0.060359493 -0.027679496, + 0.99335647 0.10460405 -0.047969021, + 0.99371099 0.100074 -0.0502358, + 0.98654938 0.14609006 -0.07333523, + 0.98706335 0.14143704 -0.075508527, + 0.97651637 0.19005507 -0.10146404, + 0.97698611 0.18686202 -0.10286301, + 0.96223497 0.23847599 -0.131275, + 0.96210939 0.23913209 -0.13100204, + 0.94174314 0.29497102 -0.16159202, + 0.93975848 0.30292815 -0.15839407, + 0.91154027 0.36440313 -0.19053808, + 0.90490776 0.38453391 -0.18241596, + 0.86573887 0.45219493 -0.21451297, + 0.86289859 0.4589068 -0.2116849, + 0.8131789 0.52849692 -0.24378496, + 0.79918885 0.55459493 -0.23177896, + 0.73576725 0.62486023 -0.2611441, + 0.69505697 0.68114102 -0.230093, + 0.61605203 0.74627608 -0.25209504, + 0.57354093 0.78873289 -0.22124897, + 0.48652688 0.84119684 -0.23596494, + 0.43660995 0.87732089 -0.19919796, + 0.46891505 0.84276712 -0.26431504, + 0.46104005 0.84885013 -0.25864202, + 0.54969096 0.79909688 -0.24348298, + 0.59605575 0.75418472 -0.27554092, + 0.67777699 0.69061899 -0.25231701, + 0.71268797 0.64447194 -0.27700496, + 0.78040886 0.57445395 -0.24690998, + 0.81023961 0.52004576 -0.27030388, + 0.86105901 0.451197 -0.23451801, + 0.8700133 0.42903116 -0.24291809, + 0.9081707 0.36426389 -0.20624693, + 0.90907913 0.36139402 -0.20729104, + 0.93810153 0.30044484 -0.17233191, + 0.94131553 0.28733185 -0.17710291, + 0.96189666 0.23275191 -0.14346196, + 0.9625541 0.22917503 -0.14480501, + 0.97721386 0.17943898 -0.11337899, + 0.97702497 0.180804 -0.112837, + 0.98735386 0.13448998 -0.083933495, + 0.98699462 0.13800696 -0.082436368, + 0.99392664 0.094473764 -0.056432381, + 0.99364865 0.098367266 -0.054647181, + 0.99789113 0.056742307 -0.031522803, + 0.99776453 0.05968127 -0.030067585, + 0.99977291 0.019029697 -0.0095872292, + 0.9997561 0.020181602 -0.0089712506, + 0.999771 -0.0195543 0.0086923698, + 0.99975145 -0.020827509 0.007957804, + 0.99784279 -0.061324384 0.023430895, + 0.99763101 -0.065577 0.020784499, + 0.99372125 -0.10665602 0.033804409, + 0.99304223 -0.11419703 0.028742308, + 0.98691851 -0.15634392 0.039350383, + 0.98536164 -0.16759995 0.03118749, + 0.97668886 -0.21103697 0.039270498, + 0.97374237 -0.22598408 0.027516309, + 0.96233052 -0.26988888 0.032862283, + 0.95726001 -0.288746 0.016706901, + 0.94269311 -0.33310404 0.019273402, + 0.93586987 -0.35234398 0.0011898399, + 0.91804022 -0.39648509 0.0013389003, + 0.91473532 -0.40400216 -0.0064443625, + 0.89470786 -0.44659495 -0.007123779, + 0.89116114 -0.45344007 -0.014965402, + 0.86937284 -0.49388787 -0.016300397, + 0.86451101 -0.501912 -0.0265528, + 0.84100252 -0.54027569 -0.028582383, + 0.83504117 -0.54868013 -0.040698312, + 0.80965716 -0.58529514 -0.04341431, + 0.80268013 -0.59365904 -0.057215307, + 0.77546436 -0.6284793 -0.060571231, + 0.76741719 -0.63660419 -0.076197714, + 0.7389434 -0.6689924 -0.080074348, + 0.72985518 -0.67660517 -0.09755522, + 0.70019567 -0.70664364 -0.10188594, + 0.69012958 -0.71346259 -0.12121192, + 0.65914625 -0.74139124 -0.12595704, + 0.64861196 -0.74692494 -0.14630699, + 0.61633205 -0.77280015 -0.15137601, + 0.60581023 -0.77678829 -0.17202906, + 0.57273018 -0.80035228 -0.17724706, + 0.56115699 -0.80306 -0.20049299, + 0.52738893 -0.82432187 -0.20580196, + 0.51539588 -0.82534784 -0.23058194, + 0.48101825 -0.8443774 -0.23589912, + 0.46890181 -0.84353572 -0.26187491, + 0.43380699 -0.860493 -0.26713899, + 0.42172185 -0.85765171 -0.29425189, + 0.38687286 -0.8722257 -0.29925188, + 0.37503907 -0.86730611 -0.32730103, + 0.3405121 -0.87968522 -0.33197209, + 0.32915291 -0.87266481 -0.3607139, + 0.29497606 -0.88304126 -0.36500308, + 0.29534706 -0.88334525 -0.36396608, + 0.26311496 -0.89201289 -0.36753696, + 0.27207205 -0.90122223 -0.33730608, + 0.2378981 -0.90966332 -0.34046611, + 0.24498799 -0.91853303 -0.310287, + 0.20908904 -0.92646325 -0.31296608, + 0.21450704 -0.93485224 -0.28291005, + 0.17673907 -0.94206434 -0.2850931, + 0.18073004 -0.94992024 -0.25492805, + 0.14115702 -0.95615411 -0.25660104, + 0.14390199 -0.96335787 -0.22634897, + 0.10309599 -0.96830291 -0.22750998, + 0.10479904 -0.97474039 -0.19722708, + 0.063016169 -0.97818953 -0.19792491, + 0.063890092 -0.98377991 -0.16761598, + 0.021472892 -0.98556662 -0.16792095, + 0.021713099 -0.99026489 -0.13749199, + -0.021338798 -0.99027288 -0.13749298, + -0.02109099 -0.98557055 -0.16794592, + -0.063473694 -0.9838019 -0.16764499, + -0.06259048 -0.97820264 -0.19799493, + -0.10426998 -0.97478187 -0.19730197, + -0.10255895 -0.96834254 -0.2275839, + -0.14322601 -0.96343911 -0.22643203, + -0.14046595 -0.95624352 -0.25664687, + -0.18011202 -0.95002413 -0.25497803, + -0.17613205 -0.94220138 -0.28501609, + -0.21398197 -0.93499488 -0.28283596, + -0.20858303 -0.92664814 -0.31275603, + -0.24470305 -0.91868323 -0.31006706, + -0.23766898 -0.9098829 -0.34003899, + -0.2720269 -0.90139973 -0.33686787, + -0.26312095 -0.89225078 -0.36695492, + -0.29547095 -0.88354677 -0.3633759, + -0.29488602 -0.88306814 -0.36501104, + -0.32918209 -0.87265617 -0.36070809, + -0.34062287 -0.87972468 -0.33175388, + -0.3751891 -0.86732519 -0.3270781, + -0.38705316 -0.87225032 -0.29894713, + -0.42187086 -0.85768068 -0.2939539, + -0.43395293 -0.86050791 -0.26685396, + -0.46911311 -0.8435092 -0.26158205, + -0.48115006 -0.84433913 -0.23576704, + -0.51555389 -0.82528681 -0.23044693, + -0.52738589 -0.82427484 -0.20599796, + -0.56112295 -0.8030349 -0.20068897, + -0.57252783 -0.8003757 -0.17779393, + -0.6055699 -0.77685583 -0.17256896, + -0.61639428 -0.77275938 -0.15133107, + -0.64871418 -0.7468462 -0.14625603, + -0.65940821 -0.74122322 -0.12557505, + -0.69035894 -0.71330297 -0.12084498, + -0.70048022 -0.70643222 -0.10139504, + -0.73017067 -0.67633373 -0.097075254, + -0.73926193 -0.66870093 -0.079566494, + -0.76772863 -0.63628668 -0.075709559, + -0.77573913 -0.62818205 -0.060134709, + -0.80295682 -0.5933249 -0.056797884, + -0.80984211 -0.58505803 -0.043161903, + -0.83521456 -0.54843378 -0.040459983, + -0.84102929 -0.54023117 -0.02863491, + -0.86453283 -0.50187188 -0.026601695, + -0.86926013 -0.49407506 -0.016637102, + -0.891047 -0.45365399 -0.015276, + -0.8944667 -0.44706786 -0.0077303573, + -0.91451031 -0.40450215 -0.0069943522, + -0.91793603 -0.396727 0.00106063, + -0.93577713 -0.35259104 0.00094264012, + -0.94289351 -0.33250386 0.019821191, + -0.9574219 -0.28818098 0.017178997, + -0.96249622 -0.26922905 0.033417609, + -0.97387302 -0.225364 0.027973, + -0.97677338 -0.21058607 0.039589215, + -0.98541635 -0.16723105 0.031438611, + -0.98693788 -0.15619898 0.039439995, + -0.99305153 -0.11409895 0.028809886, + -0.99371874 -0.10668298 0.033789892, + -0.99763048 -0.06558983 0.020774309, + -0.99784011 -0.061383009 0.023392402, + -0.99975109 -0.020849101 0.0079453513, + -0.99977064 -0.019581992 0.0086763874, + -0.99975574 0.020208394 -0.008953928, + -0.99977255 0.01906389 -0.0095657054, + -0.99775887 0.059804991 -0.030008396, + -0.99788702 0.0568395 -0.031476598, + -0.99363333 0.098558635 -0.05457982, + -0.99391139 0.094677337 -0.056359917, + -0.98696476 0.13828897 -0.082320876, + -0.98730814 0.13494201 -0.083745204, + -0.97692978 0.18145695 -0.11261197, + -0.97711039 0.18016006 -0.11312704, + -0.96237862 0.2301079 -0.14449096, + -0.96204865 0.23190291 -0.14381695, + -0.94157445 0.28623116 -0.17750908, + -0.93867576 0.29815695 -0.17317696, + -0.90988714 0.35873502 -0.20836203, + -0.90588158 0.37128183 -0.2037849, + -0.86678869 0.43715584 -0.23994191, + -0.86094844 0.4514142 -0.23450612, + -0.81016117 0.52020115 -0.27024007, + -0.78138769 0.57280082 -0.24765392, + -0.71379894 0.64283997 -0.27793497, + -0.67768532 0.69068837 -0.25237313, + -0.59605712 0.75417316 -0.27557006, + -0.55103827 0.79787737 -0.24443512, + -0.47258005 0.84263211 -0.25814602, + -0.45461711 0.85616916 -0.24555606, + -0.42262107 0.8711831 -0.24986303, + -0.51252484 0.79839969 -0.31603187, + -0.48225293 0.81454086 -0.32242098, + -0.59682268 0.68860364 -0.4118588, + -0.61774194 0.67487895 -0.40364993, + -0.52993381 0.77764571 -0.33828589, + -0.56063193 0.75932986 -0.33031797, + -0.47802994 0.83510286 -0.27219597, + -0.51072574 0.81741858 -0.26643187, + -0.58393806 0.73232508 -0.35030904, + -0.57794988 0.73618084 -0.35215291, + -0.66763318 0.61731613 -0.4161571, + -0.68842393 0.60141093 -0.40543494, + -0.57717693 0.74689794 -0.33016697, + -0.61850125 0.71869522 -0.31770012, + -0.58427578 0.75587273 -0.29542887, + -0.65762597 0.70165598 -0.274239, + -0.69507593 0.65387791 -0.29885298, + -0.76607066 0.58459169 -0.26718587, + -0.79299998 0.53780502 -0.28621101, + -0.847781 0.46817601 -0.249156, + -0.86719811 0.42135805 -0.26537704, + -0.90637589 0.35747996 -0.22514597, + -0.9098199 0.34623596 -0.22879797, + -0.93875253 0.28749186 -0.18997891, + -0.94041777 0.28043595 -0.19227596, + -0.96134365 0.22709893 -0.15570594, + -0.9625271 0.22044003 -0.15794902, + -0.97722465 0.17249794 -0.12359796, + -0.97715789 0.17300498 -0.12341698, + -0.98744911 0.12857501 -0.091721304, + -0.98723 0.130863 -0.090839699, + -0.99403977 0.089555979 -0.062165987, + -0.99384034 0.092589326 -0.060898822, + -0.99795711 0.053377409 -0.035107903, + -0.99785548 0.055977125 -0.033928216, + -0.99978226 0.017844304 -0.010815603, + -0.99976873 0.018873597 -0.010308097, + -0.99978298 -0.018283799 0.0099860197, + -0.99976677 -0.019463597 0.0093551679, + -0.9979769 -0.057302892 0.027542597, + -0.99780613 -0.061180707 0.025296504, + -0.99418038 -0.09955404 0.041162815, + -0.99362814 -0.10653801 0.036780905, + -0.9880085 -0.14594707 0.050386522, + -0.98676854 -0.15621692 0.043405078, + -0.97889423 -0.19690804 0.054711416, + -0.97650689 -0.21085997 0.044410195, + -0.96620691 -0.25223398 0.053123992, + -0.96211922 -0.26983106 0.038960908, + -0.94903463 -0.31193689 0.045040585, + -0.94240326 -0.33346409 0.026035905, + -0.92613697 -0.37604299 0.029360401, + -0.91724187 -0.39825693 0.0076634991, + -0.8976993 -0.44052714 0.0084768729, + -0.89340711 -0.44924706 -0.0009799531, + -0.87198186 -0.48953694 -0.0010678399, + -0.86787844 -0.49668223 -0.0096926447, + -0.84476483 -0.53503591 -0.010441097, + -0.83928156 -0.54326779 -0.021598289, + -0.81431085 -0.5799709 -0.023057494, + -0.80770898 -0.588471 -0.036168501, + -0.7808677 -0.62351978 -0.038322683, + -0.77321237 -0.63190532 -0.053276826, + -0.74505591 -0.66464394 -0.056036994, + -0.7363438 -0.67266685 -0.072919086, + -0.70691103 -0.703183 -0.076227099, + -0.69719499 -0.710554 -0.095037699, + -0.6663838 -0.7390278 -0.098845981, + -0.65577197 -0.74543601 -0.119534, + -0.62362558 -0.77186245 -0.12377191, + -0.61251813 -0.77690518 -0.14573903, + -0.57974994 -0.80082589 -0.15022598, + -0.56858999 -0.80426198 -0.172824, + -0.53509122 -0.82594043 -0.17748208, + -0.52351207 -0.8278051 -0.20167802, + -0.48919401 -0.84738898 -0.206449, + -0.47741294 -0.8474859 -0.23204397, + -0.44229287 -0.86503184 -0.23684794, + -0.43048716 -0.86320633 -0.2637341, + -0.39550585 -0.87838072 -0.26836991, + -0.38389891 -0.87452585 -0.29635495, + -0.34905303 -0.88752711 -0.30076203, + -0.33784491 -0.88158476 -0.32964993, + -0.30313697 -0.89258587 -0.33376396, + -0.29253298 -0.88453287 -0.36335397, + -0.25841692 -0.89357769 -0.36706889, + -0.25878111 -0.8939414 -0.36592519, + -0.22635897 -0.90144485 -0.36899698, + -0.23407994 -0.91114277 -0.33915392, + -0.19984809 -0.9182744 -0.34180814, + -0.20579593 -0.92751062 -0.31204489, + -0.16953894 -0.93407762 -0.31425387, + -0.1739549 -0.94277853 -0.28444386, + -0.135801 -0.948506 -0.286172, + -0.13889496 -0.95658666 -0.2562229, + -0.099500485 -0.96115589 -0.25744697, + -0.10146702 -0.96852821 -0.22728306, + -0.060972128 -0.9717415 -0.2280371, + -0.062001169 -0.97827351 -0.19782992, + -0.020641809 -0.97995049 -0.19816908, + -0.020937605 -0.98558122 -0.16790305, + 0.02140489 -0.9855715 -0.16790092, + 0.021118306 -0.97994524 -0.19814505, + 0.062575191 -0.97824287 -0.19780096, + 0.061554607 -0.97171611 -0.22798903, + 0.10207302 -0.96847725 -0.22722906, + 0.10011098 -0.96109974 -0.25741994, + 0.13961594 -0.95649153 -0.25618589, + 0.13652897 -0.94838375 -0.28623095, + 0.17449802 -0.94266009 -0.28450403, + 0.17006993 -0.93392158 -0.31443086, + 0.20617789 -0.9273656 -0.31222385, + 0.20019197 -0.91805285 -0.34220198, + 0.23421302 -0.91095811 -0.33955804, + 0.22646803 -0.9012081 -0.36950803, + 0.25858203 -0.8937791 -0.36646202, + 0.25841203 -0.89360911 -0.36699602, + 0.29253113 -0.88456333 -0.36328113, + 0.30303994 -0.89254475 -0.3339619, + 0.33771086 -0.88156056 -0.32985187, + 0.3489159 -0.88750774 -0.30097795, + 0.38362992 -0.87456483 -0.29658794, + 0.39525416 -0.87842643 -0.26859111, + 0.43026292 -0.86325181 -0.26395094, + 0.44211593 -0.86508989 -0.23696597, + 0.47726312 -0.84753919 -0.23215806, + 0.48916683 -0.84744167 -0.20629692, + 0.52355212 -0.82781816 -0.20152004, + 0.5352779 -0.82592481 -0.17699096, + 0.56884092 -0.80418986 -0.17233299, + 0.57971781 -0.8008377 -0.15028694, + 0.61246806 -0.77693313 -0.14580101, + 0.62341112 -0.77197218 -0.12416703, + 0.655514 -0.74559999 -0.119925, + 0.66608775 -0.73922974 -0.099330463, + 0.69689715 -0.71078318 -0.095508225, + 0.706599 -0.70344001 -0.076746099, + 0.73601878 -0.67296773 -0.073421471, + 0.74476665 -0.66492969 -0.056490272, + 0.77293169 -0.63221174 -0.05371068, + 0.78068763 -0.62372971 -0.03857518, + 0.80751216 -0.5887261 -0.036410406, + 0.81424654 -0.58006161 -0.023043986, + 0.8392508 -0.54331589 -0.021584194, + 0.84487885 -0.53486192 -0.010124099, + 0.8679859 -0.49649993 -0.0093979789, + 0.87224388 -0.48907095 -0.00043284096, + 0.89366078 -0.44874287 -0.00039714892, + 0.8978349 -0.44024393 0.0088154487, + 0.91736257 -0.39797282 0.0079690265, + 0.92589766 -0.37667784 0.028762588, + 0.94219911 -0.33408102 0.025509903, + 0.94882667 -0.31265587 0.044431686, + 0.96195024 -0.27050707 0.038441908, + 0.96609449 -0.25274512 0.052740127, + 0.97642112 -0.21132302 0.044096604, + 0.978863 -0.197092 0.054607201, + 0.98674774 -0.15637095 0.04332469, + 0.98800826 -0.14593703 0.050419211, + 0.99362999 -0.106514 0.036799099, + 0.99418646 -0.099470846 0.041218217, + 0.99780875 -0.061124984 0.025328694, + 0.99798 -0.057227399 0.027586199, + 0.99976724 -0.019436903 0.0093694422, + 0.99978334 -0.018257707 0.0099999439, + 0.99976921 0.018842403 -0.010320202, + 0.99978274 0.017812395 -0.010827797, + 0.99785924 0.055883616 -0.033970509, + 0.99796087 0.053276893 -0.035153296, + 0.99385488 0.092391491 -0.060961992, + 0.99406064 0.089249268 -0.062274177, + 0.98727202 0.130429 -0.091007203, + 0.98749864 0.12804796 -0.091924071, + 0.97725224 0.17228304 -0.12368003, + 0.97715074 0.17305395 -0.12340497, + 0.96241778 0.22111194 -0.15767495, + 0.96108878 0.22853895 -0.15517198, + 0.9399991 0.28226304 -0.19164903, + 0.9400925 0.28186384 -0.19177791, + 0.91178113 0.33953702 -0.23101903, + 0.90637159 0.35744083 -0.2252259, + 0.86730289 0.42114794 -0.26536798, + 0.84727889 0.46934694 -0.24865997, + 0.7921828 0.53927487 -0.28570795, + 0.76611489 0.58448392 -0.26729497, + 0.69521308 0.65369004 -0.29894504, + 0.65628082 0.70325381 -0.27336693, + 0.5716911 0.76472521 -0.29726207, + 0.51660293 0.81546688 -0.26102698, + 0.47272924 0.8392604 -0.26864311, + 0.54224074 0.77793664 -0.31747386, + 0.51139486 0.79564184 -0.32469893, + 0.60766971 0.68828565 -0.39623281, + 0.58698303 0.70164001 -0.40392101, + 0.46176574 0.83239454 -0.30641782, + 0.49224377 0.8168686 -0.30070186, + 0.37908491 0.89933175 -0.21793796, + 0.36167592 0.90607876 -0.21957193, + 0.44244778 0.85144156 -0.28157985, + 0.41334409 0.8645252 -0.28590706, + 0.53446579 0.75269365 -0.38444582, + 0.5144999 0.76364779 -0.3900409, + 0.45914882 0.81122971 -0.36206189, + 0.59025496 0.65067494 -0.47772494, + 0.56041121 0.66760027 -0.49015224, + 0.43362173 0.8217625 -0.36970079, + 0.46029422 0.80960739 -0.36423218, + 0.32018787 0.91669261 -0.23906991, + 0.34657201 0.907664 -0.236715, + 0.25870693 0.95213377 -0.16282496, + 0.24694903 0.95775712 -0.14736901, + 0.24903609 0.95693934 -0.14915806, + 0.32701987 0.93374264 -0.14554295, + 0.37559009 0.90834022 -0.18398404, + 0.46118379 0.86964458 -0.17614691, + 0.50743085 0.8354128 -0.21118596, + 0.59291679 0.78070468 -0.19735692, + 0.64328599 0.72841001 -0.235801, + 0.71868163 0.66153967 -0.2141539, + 0.73842663 0.63381672 -0.2302229, + 0.80082083 0.5629189 -0.20447096, + 0.80691785 0.55209386 -0.20994295, + 0.85780698 0.48041001 -0.182684, + 0.87030715 0.45189807 -0.19584103, + 0.8668704 0.4651652 -0.17932409, + 0.90965289 0.38756695 -0.14940998, + 0.91244286 0.37938294 -0.15335098, + 0.9401651 0.31588903 -0.12768601, + 0.94028085 0.31545997 -0.12789398, + 0.96104062 0.25615591 -0.10385096, + 0.96013278 0.26037294 -0.10173998, + 0.97563386 0.20435797 -0.079852395, + 0.97455275 0.21068795 -0.076534785, + 0.98594779 0.15701495 -0.057037484, + 0.98504275 0.16387896 -0.053239889, + 0.99299455 0.11237895 -0.036509082, + 0.99242491 0.11833298 -0.033017695, + 0.99748045 0.068332829 -0.01906641, + 0.99723309 0.072490208 -0.016476601, + 0.9997189 0.023120698 -0.0052551897, + 0.99968725 0.024648406 -0.0042433809, + 0.99970651 -0.023876589 0.0041104881, + 0.99966913 -0.025556805 0.0029260002, + 0.99713385 -0.075166292 0.008605809, + 0.99674052 -0.080545262 0.0045637279, + 0.99139225 -0.13071603 0.007406442, + 0.99011409 -0.14026402 -0.00026081203, + 0.98151636 -0.19137807 -0.0003558571, + 0.97913176 -0.20296295 -0.010344797, + 0.96701354 -0.25439489 -0.012966193, + 0.96579951 -0.25873187 -0.017000092, + 0.95124978 -0.30775794 -0.020221394, + 0.94960034 -0.31246713 -0.024973409, + 0.93276662 -0.35933489 -0.028719289, + 0.93014622 -0.36547008 -0.035492409, + 0.91101426 -0.41044408 -0.039860111, + 0.9074434 -0.41738722 -0.048315521, + 0.88611197 -0.46039701 -0.0532941, + 0.88157469 -0.46777883 -0.063316479, + 0.85840088 -0.50834394 -0.068807192, + 0.852781 -0.51601702 -0.080566898, + 0.82793421 -0.55411214 -0.086514719, + 0.82117814 -0.56182903 -0.10007402, + 0.79450917 -0.5978421 -0.10648903, + 0.7865231 -0.60538805 -0.12201101, + 0.75819999 -0.63916999 -0.12882, + 0.74958581 -0.64578283 -0.14520897, + 0.72009903 -0.67696804 -0.15222201, + 0.71142417 -0.68224818 -0.16856204, + 0.68064672 -0.71122563 -0.17572191, + 0.67047131 -0.71589637 -0.1948351, + 0.63829672 -0.74277365 -0.20214991, + 0.62712222 -0.74626023 -0.22318907, + 0.59373671 -0.77091962 -0.23056389, + 0.5818727 -0.77289164 -0.25310588, + 0.54790282 -0.79499871 -0.26034492, + 0.53548509 -0.79524809 -0.28431702, + 0.5010938 -0.81487972 -0.2913349, + 0.48825213 -0.81321418 -0.31669009, + 0.45361206 -0.83045012 -0.32340202, + 0.44065073 -0.8267135 -0.3498168, + 0.40563914 -0.8417753 -0.35619012, + 0.40676206 -0.84226215 -0.35375002, + 0.37499502 -0.85470212 -0.35897502, + 0.38735795 -0.8616389 -0.32792097, + 0.3537409 -0.87417585 -0.33269191, + 0.36394098 -0.88112485 -0.30193698, + 0.32845604 -0.89351511 -0.30618203, + 0.33669785 -0.90033358 -0.27574289, + 0.29895994 -0.91243178 -0.27944794, + 0.30552098 -0.91903889 -0.24904697, + 0.26634508 -0.93032438 -0.25210509, + 0.27140608 -0.93657935 -0.22171608, + 0.23070505 -0.94685423 -0.22414806, + 0.23446307 -0.95260924 -0.19381104, + 0.19242108 -0.96161234 -0.19564207, + 0.19505292 -0.96675462 -0.16534793, + 0.15170003 -0.97427922 -0.16663505, + 0.15341099 -0.97872788 -0.13622299, + 0.10952204 -0.98449433 -0.13702504, + 0.11050196 -0.98815966 -0.10644196, + 0.066352822 -0.99205738 -0.10686204, + 0.066792108 -0.99484915 -0.076250508, + 0.022478193 -0.99682367 -0.07640177, + 0.022576701 -0.998694 -0.045832802, + -0.021904798 -0.9987089 -0.045833495, + -0.021807699 -0.99684089 -0.076371692, + -0.066200085 -0.99489075 -0.076222286, + -0.065758906 -0.99210614 -0.10677701, + -0.11005495 -0.98821855 -0.10635795, + -0.10906798 -0.98454976 -0.13698897, + -0.15303107 -0.97879237 -0.13618805, + -0.15130697 -0.97432774 -0.16670795, + -0.19462493 -0.96682763 -0.16542494, + -0.19197395 -0.96166575 -0.19581896, + -0.2340261 -0.95268047 -0.19398908, + -0.23027401 -0.94692498 -0.224292, + -0.27081507 -0.93671322 -0.22187306, + -0.26575595 -0.93046874 -0.25219393, + -0.30495194 -0.91920274 -0.24913993, + -0.29842687 -0.91263872 -0.27934191, + -0.33624503 -0.90053511 -0.27563703, + -0.32804808 -0.89376324 -0.30589506, + -0.36376813 -0.88130128 -0.30163011, + -0.35367787 -0.8744337 -0.33208087, + -0.38747093 -0.8618269 -0.32729298, + -0.3751941 -0.85495317 -0.3581681, + -0.40720078 -0.84240258 -0.35290983, + -0.4057079 -0.84175783 -0.35615292, + -0.44057989 -0.82675582 -0.34980592, + -0.45367095 -0.83051986 -0.32313997, + -0.48844489 -0.81320983 -0.31640393, + -0.50134015 -0.81487328 -0.29092908, + -0.53565609 -0.79527116 -0.28393006, + -0.54805589 -0.79500884 -0.25999194, + -0.58212966 -0.77281952 -0.25273484, + -0.59387314 -0.7708602 -0.23041105, + -0.62728196 -0.74617296 -0.22303197, + -0.63823283 -0.74275684 -0.20241295, + -0.67037976 -0.71591073 -0.19509692, + -0.68043458 -0.71130461 -0.17622289, + -0.71112609 -0.68243307 -0.16907002, + -0.72008467 -0.67698568 -0.15221192, + -0.74960995 -0.64575893 -0.14519098, + -0.75843072 -0.63898075 -0.12839895, + -0.78677785 -0.60513991 -0.12159899, + -0.79480499 -0.59754002 -0.105976, + -0.82144582 -0.56152385 -0.099588275, + -0.82820088 -0.55379194 -0.086010695, + -0.85305268 -0.51564282 -0.080085672, + -0.85863799 -0.50800103 -0.068380304, + -0.88177198 -0.46746001 -0.0629232, + -0.88622421 -0.46020612 -0.053075612, + -0.90754932 -0.41718015 -0.048113517, + -0.91099888 -0.41046995 -0.039941598, + -0.93012178 -0.36552492 -0.035568193, + -0.93264401 -0.359626 -0.029058799, + -0.94950724 -0.31272608 -0.025269106, + -0.95110822 -0.30816606 -0.020664506, + -0.96568835 -0.2591221 -0.017375706, + -0.96698189 -0.25450897 -0.013086598, + -0.97910821 -0.20307204 -0.010441802, + -0.98159713 -0.19096403 -6.1875908e-006, + -0.99015933 -0.13994505 -4.5344818e-006, + -0.9914391 -0.13034202 0.0077097011, + -0.99675989 -0.080294393 0.0047494094, + -0.99714565 -0.074995272 0.0087314975, + -0.99967051 -0.025496487 0.0029684885, + -0.99970686 -0.023858696 0.0041231294, + -0.99968755 0.02462999 -0.004256418, + -0.99971867 0.023133092 -0.005247748, + -0.99723047 0.07253094 -0.016453708, + -0.99747586 0.068411991 -0.019019399, + -0.99240988 0.11848099 -0.032938994, + -0.99297535 0.11258504 -0.036395811, + -0.98500079 0.16418396 -0.05307639, + -0.98590434 0.15735306 -0.056856118, + -0.97447062 0.21115392 -0.076296173, + -0.97555691 0.20481597 -0.079618894, + -0.95999837 0.2609801 -0.10145204, + -0.9609009 0.25680396 -0.10354298, + -0.94006789 0.31624898 -0.12751098, + -0.93984926 0.31705508 -0.12712003, + -0.91195029 0.38083115 -0.15269005, + -0.90908241 0.38919216 -0.14865607, + -0.87180912 0.45760107 -0.17478602, + -0.86490029 0.47337118 -0.16693506, + -0.81640756 0.54460377 -0.19205591, + -0.089626223 0.99548423 -0.031280208, + -0.090151958 0.9954195 -0.031823784, + -0.14621998 0.98874688 -0.031610396, + -0.18126595 0.98133373 -0.064240187, + -0.24979612 0.96623045 -0.063251533, + -0.292162 0.95117003 -0.0995837, + -0.37126812 0.92347836 -0.096684538, + -0.425033 0.89421201 -0.14047, + -0.50975084 0.84989971 -0.13350895, + -0.52720481 0.83684969 -0.14743695, + -0.61017311 0.7802512 -0.13746603, + -0.6420058 0.74911982 -0.16324195, + -0.70103824 0.69677222 -0.15183505, + -0.74740398 0.63619298 -0.191431, + -0.79729229 0.57799417 -0.17391907, + -0.79718685 0.57818693 -0.17376098, + -0.73454058 0.64985263 -0.19529888, + -0.71143019 0.68037218 -0.17595704, + -0.63590872 0.74718165 -0.19323491, + -0.62021631 0.76331234 -0.18079309, + -0.53673583 0.82103473 -0.19446492, + -0.48276889 0.86241084 -0.15225597, + -0.39765808 0.90356022 -0.15952104, + -0.3504611 0.92864221 -0.12165803, + -0.27184305 0.95418823 -0.12500504, + -0.229644 0.96920902 -0.088868201, + -0.16219805 0.98263621 -0.090099424, + -0.16337596 0.98233879 -0.091207281, + -0.39774299 0.84970999 -0.34611201, + -0.53379005 0.69739407 -0.47823605, + -0.50426215 0.71218425 -0.48837817, + -0.37268496 0.85915691 -0.35064998, + -0.39800882 0.84936458 -0.34665382, + -0.25434908 0.94504637 -0.20541207, + -0.27775598 0.93873286 -0.20403998, + -0.17620195 0.97817075 -0.11015797, + -0.18537699 0.97649491 -0.10996898, + -0.3208141 0.91899621 -0.22918206, + -0.29555488 0.92693663 -0.23116191, + -0.45095116 0.80902231 -0.37699616, + -0.46966717 0.80022532 -0.37289712, + -0.46830487 0.80220884 -0.3703399, + -0.59232622 0.64725924 -0.47979718, + -0.54667515 0.67268217 -0.49864313, + -0.62680209 0.52312207 -0.57746208, + -0.58294928 0.54549927 -0.60216331, + -0.63763982 0.39387292 -0.66202682, + -0.59552824 0.41074514 -0.69038725, + -0.63183177 0.24757092 -0.73450476, + -0.59051198 0.25776699 -0.76475602, + -0.60956275 0.059380177 -0.79051071, + -0.57157713 0.083152525 -0.81632417, + -0.57356071 0.0029738387 -0.8191576, + -0.57325292 0.0030341996 -0.81937289, + -0.57127011 0.08317142 -0.8165372, + -0.61320031 0.052897025 -0.78815436, + -0.61405873 -0.0020384693 -0.78925771, + -0.61307788 -0.0020384595 -0.79001981, + -0.61162812 -0.0028778408 -0.7911402, + -0.64049977 0.015263194 -0.76780671, + -0.55822593 0.015723998 -0.8295399, + -0.5303092 0.09606424 -0.84234428, + -0.47021666 0.65000153 -0.59698761, + -0.54963487 0.45141688 -0.70293981, + -0.50630689 0.46597889 -0.72561485, + -0.54807323 0.28078413 -0.78789335, + -0.50379294 0.28997996 -0.81369787, + -0.52482092 0.062352594 -0.84892589, + -0.48783094 0.10351498 -0.86677891, + -0.49046582 0.0011323796 -0.87145972, + -0.49107412 0.0010251602 -0.87111717, + -0.48843718 0.10348204 -0.86644131, + -0.53124309 0.051707506 -0.84564012, + -0.53195506 -0.00094308011 -0.84677213, + -0.5327729 -0.00094307779 -0.84625781, + -0.53274888 -0.00095601875 -0.84627283, + -0.53028589 0.096065581 -0.84235883, + -0.56829095 0.058662191 -0.8207339, + -0.54801184 0.27404392 -0.79030567, + -0.59053427 0.26439312 -0.76247334, + -0.55105811 0.43937713 -0.7094242, + -0.59396493 0.42359394 -0.68393993, + -0.53385019 0.58416623 -0.61135423, + -0.57769769 0.5639047 -0.5901497, + -0.46398589 0.75271481 -0.46705189, + -0.46604174 0.74693656 -0.47422674, + -0.34004998 0.8784529 -0.33568797, + -0.36426902 0.8699401 -0.33243403, + -0.21568495 0.95992178 -0.17896995, + -0.23729888 0.95498055 -0.17804891, + -0.10790002 0.9927581 -0.052811109, + -0.10245996 0.99333262 -0.052841581, + -0.19965293 0.96805364 -0.15169294, + -0.18022905 0.97176635 -0.15227506, + -0.33153385 0.88888556 -0.31617686, + -0.30846995 0.89622575 -0.3187879, + -0.44750094 0.75497389 -0.47932994, + -0.4094941 0.7900452 -0.45622712, + -0.52879888 0.60148489 -0.59882188, + -0.49882987 0.61420786 -0.61148787, + -0.38730693 0.79467487 -0.46742395, + -0.4109892 0.78578734 -0.46219721, + -0.27938098 0.9112739 -0.30253297, + -0.30096394 0.90506274 -0.30046993, + -0.14815398 0.98084879 -0.12643597, + -0.16575295 0.97807467 -0.12607895, + -0.046445612 0.99892026 0.0011167702, + -0.044150416 0.99902433 0.0011168903, + -0.13472797 0.98578078 -0.10042198, + -0.11902796 0.98777866 -0.10062596, + -0.27220702 0.91944009 -0.28378403, + -0.25165194 0.92477077 -0.28542995, + -0.38448793 0.80323291 -0.45495695, + -0.36194018 0.81112635 -0.45942721, + -0.47082087 0.64001483 -0.60721385, + -0.45094407 0.64750403 -0.61431909, + -0.33721596 0.82609791 -0.45149493, + -0.35948592 0.81883484 -0.44752589, + -0.22595392 0.93648064 -0.26823291, + -0.245112 0.93201703 -0.266954, + -0.093090557 0.99276954 -0.075781859, + -0.10704502 0.99137014 -0.075675108, + -0.020601697 0.99944586 0.026146796, + -0.031280592 0.99916875 0.026139595, + -0.034816194 0.99914676 0.022215795, + -0.079250239 0.9966085 0.022159411, + -0.10655794 0.99429041 -0.0056454269, + -0.16392401 0.98645711 -0.0056009605, + -0.19910797 0.97923589 -0.038119897, + -0.26867005 0.96250325 -0.037468608, + -0.31738001 0.94497299 -0.079347096, + -0.39734799 0.91444999 -0.076784097, + -0.41442591 0.90554374 -0.090783074, + -0.49777517 0.86298031 -0.08651603, + -0.536448 0.83569002 -0.117668, + -0.59908813 0.79286218 -0.11163803, + -0.65914583 0.73457885 -0.16099896, + -0.71674198 0.68116999 -0.14929301, + -0.74526083 0.64357281 -0.17435695, + -0.80571687 0.57169193 -0.15488298, + -0.81806982 0.55023986 -0.16732596, + -0.86600357 0.47840676 -0.14548093, + -0.87225097 0.46451801 -0.15297499, + -0.90920877 0.39544892 -0.13022897, + -0.91073686 0.39115995 -0.13248499, + -0.93890113 0.32599604 -0.11041401, + -0.93815678 0.32859191 -0.10903798, + -0.95957488 0.26712996 -0.088642895, + -0.95810974 0.27343494 -0.08520028, + -0.97436422 0.21479104 -0.066927418, + -0.97287863 0.22273992 -0.062402878, + -0.98500764 0.16611494 -0.046538886, + -0.98387003 0.173914 -0.041877698, + -0.9924379 0.11933699 -0.028735695, + -0.99172539 0.12601304 -0.024528209, + -0.99724662 0.072789781 -0.014168396, + -0.9969461 0.077289306 -0.011171101, + -0.99968964 0.024653891 -0.0035633789, + -0.99965113 0.026304604 -0.0023996702, + -0.99967277 -0.025476795 0.0023241495, + -0.99962777 -0.027264895 0.00098791381, + -0.99677914 -0.08014331 0.0029039101, + -0.99628466 -0.086102374 -0.0018254393, + -0.99020326 -0.13960204 -0.0029596707, + -0.98885125 -0.14853503 -0.010520902, + -0.9792065 -0.20235892 -0.014333294, + -0.97842211 -0.20587203 -0.017519202, + -0.96592909 -0.25787503 -0.021944502, + -0.96481848 -0.26166311 -0.025649114, + -0.94991064 -0.31103089 -0.030488389, + -0.94802934 -0.31614813 -0.03592781, + -0.93074036 -0.36334211 -0.041291114, + -0.92802978 -0.36936191 -0.048296187, + -0.90843588 -0.41449594 -0.054197792, + -0.90478468 -0.42120785 -0.06283848, + -0.88297528 -0.46428117 -0.069264524, + -0.87825191 -0.47151294 -0.079680592, + -0.85460269 -0.51202279 -0.086526267, + -0.84870028 -0.51955718 -0.098834835, + -0.82338214 -0.55749005 -0.10605101, + -0.81620979 -0.5650779 -0.12036897, + -0.78911185 -0.60077095 -0.12797199, + -0.78109014 -0.60771406 -0.14346401, + -0.75232786 -0.64116496 -0.15136099, + -0.74419594 -0.64681393 -0.16674599, + -0.71411425 -0.67786622 -0.17475206, + -0.70482618 -0.6828692 -0.19211905, + -0.67353427 -0.71153235 -0.20018309, + -0.66317421 -0.71557325 -0.21944207, + -0.63054401 -0.74204499 -0.22756, + -0.61922705 -0.74481606 -0.24861003, + -0.58539873 -0.7690357 -0.25669491, + -0.57319403 -0.77025598 -0.27956101, + -0.5388878 -0.79183668 -0.28739291, + -0.52605093 -0.79124188 -0.31177998, + -0.49144319 -0.8102743 -0.3192791, + -0.47813812 -0.80765319 -0.34508008, + -0.44332087 -0.82427782 -0.35218292, + -0.44524786 -0.82491368 -0.34824088, + -0.4130761 -0.83899915 -0.3541871, + -0.4263368 -0.8448956 -0.32309186, + -0.39265686 -0.85901868 -0.32849288, + -0.40365493 -0.86506486 -0.29786798, + -0.3681621 -0.87910622 -0.30270305, + -0.37719294 -0.88517588 -0.27237698, + -0.33995411 -0.89885032 -0.2765851, + -0.34725204 -0.90482813 -0.24637803, + -0.30801696 -0.91795886 -0.24995397, + -0.31379804 -0.92373812 -0.21963303, + -0.2731739 -0.93587464 -0.22251892, + -0.27758005 -0.94126827 -0.19225904, + -0.23577894 -0.95214778 -0.19448096, + -0.23899198 -0.95704389 -0.16416399, + -0.19589403 -0.9665091 -0.16578801, + -0.19810092 -0.97079366 -0.13533495, + -0.15385497 -0.97862977 -0.13642697, + -0.15523499 -0.98219287 -0.10582699, + -0.11043897 -0.98816365 -0.10646997, + -0.11117298 -0.99089485 -0.075947292, + -0.06630487 -0.99488151 -0.076252863, + -0.066596091 -0.99672991 -0.045766395, + -0.021986302 -0.9987061 -0.045857105, + -0.022032911 -0.99963647 -0.015542908, + -0.023180988 -0.99961042 -0.01554249, + -0.023183189 -0.99970353 -0.0074441661, + 0.026116196 -0.99965888 -6.4459993e-005, + 0.026112905 -0.99953026 -0.016048204, + 0.025917405 -0.99953526 -0.016048303, + 0.07591784 -0.99701548 -0.014026706, + 0.075925261 -0.99711353 6.0097969e-005, + 0.10280804 -0.99469334 -0.0039622113, + 0.12401196 -0.99228066 -0.00046628484, + 0.12390795 -0.99229366 -0.00047202283, + 0.12389202 -0.99215913 -0.016466102, + 0.12399503 -0.99214625 -0.016465904, + 0.17239891 -0.98495054 -0.012291995, + 0.17241198 -0.98502487 0.00037551695, + 0.17241894 -0.98502362 0.00037551686, + 0.17239505 -0.98489022 -0.016471503, + 0.17239699 -0.98488986 -0.016471498, + 0.17242008 -0.9850235 0.00037541517, + 0.20454797 -0.97884887 -0.0038764095, + 0.22054604 -0.97537613 -0.00094495114, + 0.22055903 -0.97537315 -0.00094389613, + 0.22052993 -0.97524363 -0.016323095, + 0.22051689 -0.97524655 -0.016323192, + 0.26797795 -0.96336377 -0.010867897, + 0.26799291 -0.96342063 0.00061276177, + 0.26814905 -0.96337724 0.00061276217, + 0.26811403 -0.96325213 -0.016131202, + 0.26803502 -0.96327412 -0.016131502, + 0.29856411 -0.95430934 -0.012375805, + 0.2979221 -0.95356739 -0.044178713, + 0.3438409 -0.93802178 -0.043458488, + 0.34245804 -0.9366861 -0.073087007, + 0.3876071 -0.91903126 -0.071709514, + 0.38531515 -0.91723537 -0.10105304, + 0.42894292 -0.89789873 -0.098922774, + 0.42562407 -0.89580411 -0.12798102, + 0.46770099 -0.87500203 -0.125009, + 0.4632428 -0.87276858 -0.15388693, + 0.50398982 -0.85058868 -0.14997694, + 0.49826512 -0.84837818 -0.17884704, + 0.53764421 -0.82503831 -0.17392705, + 0.53050971 -0.82301754 -0.20298187, + 0.56794095 -0.79912388 -0.19708897, + 0.55925208 -0.79745811 -0.22649004, + 0.59484023 -0.77326131 -0.21961807, + 0.58450174 -0.77213973 -0.2493149, + 0.61876297 -0.74757391 -0.24138297, + 0.60657406 -0.74719208 -0.27161002, + 0.63981837 -0.72228539 -0.26255715, + 0.62552601 -0.722848 -0.293612, + 0.65731901 -0.69821203 -0.28360501, + 0.64059901 -0.69994497 -0.31576899, + 0.67115998 -0.67573202 -0.30484501, + 0.66749024 -0.67641723 -0.31131411, + 0.70187908 -0.64705503 -0.29780102, + 0.71237063 -0.64384073 -0.27927989, + 0.74565685 -0.61129689 -0.26516393, + 0.75476134 -0.60711128 -0.24849811, + 0.7861228 -0.57200891 -0.23412994, + 0.79372585 -0.56725889 -0.21958295, + 0.8231011 -0.52960104 -0.20500603, + 0.82934928 -0.52455819 -0.19240208, + 0.8567611 -0.48417205 -0.17758901, + 0.86170191 -0.47915593 -0.16697098, + 0.88711011 -0.43585306 -0.15188101, + 0.89080572 -0.43119285 -0.14331095, + 0.91373622 -0.38557008 -0.12814803, + 0.91606086 -0.38195094 -0.12225398, + 0.93657386 -0.33378896 -0.10683799, + 0.93906921 -0.32894009 -0.099737421, + 0.95690852 -0.27789587 -0.084260464, + 0.95882577 -0.27310693 -0.077882282, + 0.97376454 -0.21883389 -0.062405169, + 0.97488666 -0.21507092 -0.057796877, + 0.98646945 -0.15832807 -0.042548317, + 0.98703253 -0.15559892 -0.039441582, + 0.99505335 -0.096296735 -0.024409609, + 0.99525434 -0.094637834 -0.022639807, + 0.99944854 -0.032294385 -0.0077256663, + 0.99947011 -0.031749506 -0.007176321, + 0.99943274 0.032849494 0.007424938, + 0.99945277 0.032342993 0.0069388682, + 0.99461102 0.10137 0.021748001, + 0.99473876 0.10031497 0.020774994, + 0.98423898 0.173169 0.0358629, + 0.98441637 0.17231506 0.03509941, + 0.96705836 0.24943309 0.050807718, + 0.97063679 0.23718694 0.040081389, + 0.94762099 0.31493199 0.0532193, + 0.95414776 0.29695195 0.037703793, + 0.92639261 0.37355989 0.04743078, + 0.93416113 0.35541904 0.031941503, + 0.90124625 0.43156809 0.038785107, + 0.91011912 0.41367605 0.023569005, + 0.87157118 0.48947513 0.027887607, + 0.88034356 0.47410777 0.014735593, + 0.83533573 0.54947484 0.017077994, + 0.84298587 0.53789091 0.006942559, + 0.79099482 0.61177188 0.0078961486, + 0.79559714 0.60582107 0.0024563803, + 0.73582941 0.6771614 0.0027456416, + 0.73527825 0.67775726 0.0033327611, + 0.66721874 0.74485278 0.0036626887, + 0.65853894 0.75244886 0.012130698, + 0.58311099 0.81228697 0.0130954, + 0.56417984 0.82509369 0.030357089, + 0.48489505 0.87398112 0.032155804, + 0.4554998 0.88835156 0.057891473, + 0.37719899 0.92417198 0.0602258, + 0.33950588 0.93600267 0.09292347, + 0.26767102 0.9587971 0.095186412, + 0.2250959 0.96521753 0.13299194, + 0.16445498 0.97715288 0.13463598, + 0.12518504 0.97720337 0.17147106, + 0.078118563 0.98194152 0.17230292, + 0.068927474 0.98093164 0.18171994, + 0.030379912 0.98281634 0.18206906, + 0.022075102 0.98123014 0.19157302, + -0.0091824578 0.98142779 0.19161196, + -0.020668592 0.97823966 0.20644593, + -0.043480314 0.97752339 0.20629507, + -0.04778501 0.97596127 0.21264105, + -0.064449899 0.97504598 0.212442, + -0.067107402 0.97387201 0.216956, + -0.078481779 0.97306174 0.21677496, + -0.083665796 0.97029388 0.22700197, + -0.077332787 0.97079176 0.22711894, + -0.041855317 0.98834538 0.14636105, + 0.054941006 0.99281412 -0.10630901, + -0.039728612 0.98843122 0.14637403, + 0.022183407 0.11980704 -0.99254936, + 0.02076989 0.37641183 -0.92621958, + 0.39137793 -0.92015487 -0.011760498, + 0.39058194 -0.91956586 -0.042946097, + 0.43553206 -0.89919311 -0.041994605, + 0.43389115 -0.89817631 -0.070836723, + 0.47732094 -0.87600887 -0.069088392, + 0.47470123 -0.87472641 -0.097531743, + 0.51679981 -0.85083371 -0.094867662, + 0.51312006 -0.84946012 -0.12298501, + 0.5538801 -0.82400519 -0.11929903, + 0.54905778 -0.82271558 -0.14722292, + 0.58781588 -0.79634482 -0.14250398, + 0.58176297 -0.79530591 -0.17041199, + 0.61872071 -0.76817465 -0.16459793, + 0.61131811 -0.76755619 -0.19273704, + 0.64682406 -0.73967606 -0.18573602, + 0.63794816 -0.73966318 -0.21429105, + 0.67215884 -0.71116281 -0.20603396, + 0.66176325 -0.71195322 -0.23493008, + 0.69436681 -0.68337685 -0.22550094, + 0.68230224 -0.68517125 -0.25495908, + 0.7135756 -0.65659356 -0.24432485, + 0.69955194 -0.65963495 -0.27478898, + 0.73005497 -0.63084 -0.26279399, + 0.71385407 -0.63539404 -0.29442602, + 0.74407393 -0.60618097 -0.28088897, + 0.73987693 -0.60772794 -0.28852898, + 0.77318585 -0.57289189 -0.27198994, + 0.7815538 -0.56870389 -0.25641695, + 0.812751 -0.53112102 -0.239471, + 0.81965387 -0.52646095 -0.22584596, + 0.84886569 -0.48579481 -0.20839992, + 0.85426486 -0.48107794 -0.19696598, + 0.8812539 -0.43740195 -0.17908399, + 0.88532531 -0.43289414 -0.16971105, + 0.90962887 -0.38676193 -0.15162599, + 0.91260475 -0.38261992 -0.14406396, + 0.93418211 -0.33391201 -0.12572402, + 0.93611223 -0.33052608 -0.12019403, + 0.95489049 -0.27907911 -0.10148504, + 0.95587242 -0.27687582 -0.098221943, + 0.97184145 -0.2220761 -0.078781635, + 0.97294611 -0.21876404 -0.074285507, + 0.98538965 -0.16127095 -0.054762583, + 0.98605078 -0.15839295 -0.05114219, + 0.99467033 -0.098118536 -0.031680711, + 0.99489933 -0.096410736 -0.02967051, + 0.99940652 -0.032922786 -0.010131995, + 0.99943078 -0.032366391 -0.0095136678, + 0.99939013 0.033501703 0.0098473607, + 0.99941349 0.032963917 0.0092781642, + 0.9942199 0.10334699 0.029088596, + 0.99442166 0.10181996 0.02753569, + 0.98329014 0.17573301 0.047524106, + 0.98377013 0.17359202 0.045411203, + 0.9657101 0.25117102 0.065705806, + 0.96619636 0.24967209 0.064254224, + 0.939933 0.330587 0.085078202, + 0.93977475 0.33094692 0.085424878, + 0.90431821 0.41331208 0.10668502, + 0.91334611 0.39694005 0.090760507, + 0.8717894 0.47755623 0.10919406, + 0.88582075 0.45567489 0.087647177, + 0.83918846 0.5340513 0.10272306, + 0.85333973 0.51466483 0.083255872, + 0.80116701 0.59076101 0.0955659, + 0.81518728 0.57391018 0.078082733, + 0.75759089 0.64677095 0.08799579, + 0.76925611 0.63456208 0.074673705, + 0.70577061 0.70358557 0.082796045, + 0.71335822 0.69679624 0.074800327, + 0.64384276 0.76078671 0.081669569, + 0.64495492 0.75996089 0.080576994, + 0.57004493 0.81703389 0.086628295, + 0.5630967 0.82113159 0.093085252, + 0.48538512 0.86873621 0.098481819, + 0.46907488 0.87588978 0.11307397, + 0.39203706 0.91237813 0.11778402, + 0.36737803 0.91954613 0.13952902, + 0.29466686 0.94478554 0.14335893, + 0.26511192 0.94916064 0.16973394, + 0.20105195 0.96428376 0.17243795, + 0.17046902 0.96467412 0.20085903, + 0.11765994 0.97220355 0.20242591, + 0.088517442 0.96883249 0.2313621, + 0.047782417 0.97153938 0.23200908, + 0.024662288 0.96606553 0.25711688, + -0.0050567104 0.9663471 0.25719202, + -0.0073616374 0.96558166 0.25999591, + -0.030892396 0.9651469 0.25987896, + -0.032872193 0.96433675 0.26262894, + -0.051177207 0.96359414 0.26242602, + -0.054516513 0.96194124 0.26776305, + -0.066864595 0.96121788 0.26756197, + -0.066296183 0.96155077 0.26650494, + -0.074408814 0.96099925 0.26635307, + -0.073249102 0.96178699 0.26381901, + -0.077334315 0.96148926 0.26373807, + -0.078533106 0.96053112 0.26685703, + -0.06982661 0.96115512 0.26703003, + -0.04263461 0.98217422 0.18307404, + -0.037868299 0.98236299 0.183109, + 0.027571809 0.99762338 -0.063146122, + 0.020244205 0.99779826 -0.063157216, + 0.074918196 0.9439429 -0.32149497, + 0.055990919 0.94511837 -0.32189512, + 0.097311676 0.80920482 -0.57941186, + 0.068203971 0.81117064 -0.58081871, + 0.090666726 0.61939025 -0.77983028, + 0.053585988 0.62105787 -0.7819308, + 0.063083395 0.37574393 -0.9245739, + 0.066458195 0.13832998 -0.98815387, + 0.062407199 0.372188 -0.92605698, + 0.10565203 0.37082812 -0.92267233, + 0.090007119 0.61574709 -0.78278619, + 0.12806295 0.61316574 -0.77950472, + 0.096859612 0.80604911 -0.58386904, + 0.12760098 0.8032369 -0.58183193, + 0.074847691 0.94096786 -0.33011696, + 0.095036283 0.93934387 -0.32954696, + 0.028510408 0.99669534 -0.076063633, + 0.037150815 0.99641234 -0.076042026, + -0.040214099 0.985223 0.16648901, + -0.043821279 0.98507351 0.16646293, + -0.075018272 0.96572465 0.24849191, + -0.082701191 0.96513587 0.24834096, + -0.079901263 0.9669705 0.24204089, + -0.072466664 0.96752155 0.24217889, + -0.072000913 0.96777922 0.24128705, + -0.059968706 0.9685511 0.24148002, + -0.058584973 0.96920151 0.23919888, + -0.041284475 0.97004139 0.23940586, + -0.034505986 0.97265154 0.22969189, + -0.010393696 0.97317863 0.22981592, + -0.0055523487 0.97463375 0.22373694, + 0.024798306 0.97434926 0.22367106, + 0.0303187 0.975582 0.21753301, + 0.06794899 0.97377491 0.21712998, + 0.098884739 0.97755039 0.18605706, + 0.149115 0.97138202 0.184883, + 0.18545005 0.97098625 0.15097703, + 0.248271 0.95718902 0.14883099, + 0.28346407 0.95175827 0.11749203, + 0.35603487 0.92743266 0.11448896, + 0.3869639 0.91794276 0.087407276, + 0.46475512 0.88145226 0.083932623, + 0.48754171 0.87077147 0.063718364, + 0.56601834 0.82219446 0.060163837, + 0.57890832 0.81396341 0.048257824, + 0.65395516 0.75520718 0.044774313, + 0.65751284 0.75231183 0.041275088, + 0.72614509 0.68650907 0.037664905, + 0.72282284 0.68980384 0.04120319, + 0.78421915 0.61938006 0.036996704, + 0.77618414 0.62879807 0.046381503, + 0.83070803 0.55519998 0.040952701, + 0.82017809 0.56950104 0.054558508, + 0.86845589 0.49350694 0.047278192, + 0.8568753 0.51153719 0.063988224, + 0.8991757 0.43420386 0.05431458, + 0.8882677 0.45363286 0.072095878, + 0.9250651 0.37510106 0.059614908, + 0.91502571 0.39569986 0.078419171, + 0.94678545 0.31572515 0.062570028, + 0.94073588 0.33049396 0.076089896, + 0.96665162 0.24956591 0.057457678, + 0.96650964 0.25001892 0.057874978, + 0.98415339 0.17275089 0.039988779, + 0.98384339 0.17419189 0.041343074, + 0.99460614 0.10092101 0.023952603, + 0.99442464 0.10235896 0.02534529, + 0.99943399 0.032655001 0.0080858003, + 0.999412 0.0331861 0.00862101, + 0.99945098 -0.0320687 -0.0083307298, + 0.99942821 -0.032618608 -0.0089127021, + 0.99508178 -0.095554478 -0.026109295, + 0.99486834 -0.097230136 -0.027986409, + 0.98655885 -0.15703098 -0.045199297, + 0.98595434 -0.15981106 -0.048523918, + 0.97395939 -0.21694307 -0.065871023, + 0.97273678 -0.22081894 -0.070866682, + 0.95726264 -0.27538592 -0.088378772, + 0.95550251 -0.27953589 -0.094204955, + 0.93713778 -0.33068591 -0.11144297, + 0.93554461 -0.33362186 -0.11598594, + 0.91453612 -0.38207304 -0.13283102, + 0.91179198 -0.38611999 -0.13981, + 0.88817197 -0.43206 -0.156444, + 0.88424802 -0.436703 -0.165517, + 0.85809809 -0.48015505 -0.18198602, + 0.852947 -0.48501399 -0.192984, + 0.82467359 -0.52553576 -0.20910689, + 0.81813312 -0.53037608 -0.22217003, + 0.78790832 -0.56797415 -0.23792009, + 0.7798745 -0.57248467 -0.25309485, + 0.74757963 -0.60745573 -0.26855588, + 0.73811483 -0.61123788 -0.28561294, + 0.70383316 -0.64357215 -0.30072206, + 0.70781833 -0.64247727 -0.29362616, + 0.67739272 -0.66905969 -0.30577484, + 0.69398379 -0.66589582 -0.27380493, + 0.66304719 -0.69233519 -0.28467605, + 0.67729008 -0.69052309 -0.25388202, + 0.64501995 -0.71722496 -0.26369998, + 0.65722382 -0.71651185 -0.23381095, + 0.62346071 -0.74328166 -0.24254689, + 0.63390476 -0.74344873 -0.21318692, + 0.59895325 -0.76976132 -0.22073208, + 0.60779673 -0.77060664 -0.19169891, + 0.5714522 -0.79636431 -0.19810708, + 0.57876801 -0.79768699 -0.169479, + 0.54062301 -0.82289702 -0.174835, + 0.54655397 -0.82452589 -0.14640999, + 0.50644785 -0.84898984 -0.15075397, + 0.51111972 -0.85076147 -0.12231693, + 0.469641 -0.87387198 -0.12563901, + 0.47316524 -0.87561643 -0.097008742, + 0.43037179 -0.89716256 -0.099395558, + 0.43284392 -0.89870977 -0.070475787, + 0.38857993 -0.9185949 -0.072035089, + 0.39010215 -0.91977733 -0.042779814, + 0.34432104 -0.93783814 -0.043619804, + 0.34504512 -0.93850833 -0.012084804, + 0.36111701 -0.93238902 -0.0156617, + 0.36116108 -0.93250322 0.00077717419, + 0.36122099 -0.93247998 0.00077717402, + 0.36117688 -0.93236566 -0.015668394, + 0.36116892 -0.93236876 -0.015668396, + 0.361213 -0.93248302 0.00077759102, + 0.40649399 -0.91364402 -0.0041613402, + 0.40645009 -0.91354525 -0.015283504, + 0.40644315 -0.91354829 -0.015283505, + 0.43689793 -0.89943886 -0.011402799, + 0.43603975 -0.89893848 -0.042176273, + 0.48011607 -0.87624115 -0.041111402, + 0.47837812 -0.87540221 -0.069465011, + 0.52107894 -0.85083389 -0.067515396, + 0.5183478 -0.84983069 -0.095411859, + 0.55969304 -0.82352614 -0.092458606, + 0.55590612 -0.8225382 -0.11999703, + 0.59522402 -0.79514301 -0.116, + 0.59031892 -0.79434091 -0.14333898, + 0.62779903 -0.76600415 -0.13822502, + 0.62170213 -0.76555818 -0.16555105, + 0.65764803 -0.73630601 -0.159225, + 0.65026474 -0.73639178 -0.18676995, + 0.6848262 -0.70634216 -0.17914805, + 0.67604619 -0.70715517 -0.20710704, + 0.70890397 -0.67687297 -0.19823797, + 0.69869834 -0.67859328 -0.22656511, + 0.73010606 -0.64816207 -0.21640503, + 0.71834618 -0.65099621 -0.24532206, + 0.74878937 -0.62023032 -0.23372811, + 0.73522305 -0.62445009 -0.26364604, + 0.76530802 -0.59297901 -0.250359, + 0.74973392 -0.59886694 -0.28152698, + 0.77905202 -0.56739098 -0.26673099, + 0.77473688 -0.56941897 -0.27485397, + 0.80704713 -0.53177804 -0.25668502, + 0.81420809 -0.52739406 -0.24273603, + 0.84442931 -0.48660117 -0.22396107, + 0.8501488 -0.48199189 -0.21196896, + 0.87800431 -0.43815416 -0.19269007, + 0.88231224 -0.43370008 -0.18283704, + 0.90737867 -0.38730386 -0.16327794, + 0.91045171 -0.38327584 -0.15549093, + 0.9326731 -0.33426303 -0.13560702, + 0.93477237 -0.33077011 -0.12958305, + 0.95403612 -0.27904204 -0.10931902, + 0.95527101 -0.27639401 -0.105184, + 0.97152674 -0.22143695 -0.08426968, + 0.97205937 -0.21991308 -0.082090229, + 0.98491114 -0.16213301 -0.060522009, + 0.98549378 -0.15973096 -0.057341985, + 0.99444926 -0.099029824 -0.035550907, + 0.99470365 -0.09723106 -0.033326689, + 0.99938333 -0.033218011 -0.011385804, + 0.9994095 -0.032647215 -0.010719805, + 0.99936712 0.033797104 0.011097401, + 0.99939185 0.033253796 0.010493799, + 0.99400723 0.10424702 0.032896906, + 0.99421853 0.10272194 0.031267684, + 0.98268074 0.17727596 0.053961489, + 0.98322111 0.17497501 0.051575609, + 0.96457303 0.253052 0.074589901, + 0.9654215 0.25054413 0.072035737, + 0.93856913 0.33165503 0.095356613, + 0.93914187 0.33039597 0.094080187, + 0.90337211 0.41246206 0.11744802, + 0.90240878 0.41408792 0.11911997, + 0.85661787 0.49584293 0.14263798, + 0.86880517 0.47912711 0.12495903, + 0.81697482 0.5580079 0.14553097, + 0.8351621 0.53632808 0.12188701, + 0.77868211 0.61181808 0.13904302, + 0.79570282 0.59393489 0.11873697, + 0.73454195 0.66539693 0.13302298, + 0.75036311 0.65085006 0.11554001, + 0.68454432 0.71774936 0.12741606, + 0.69629294 0.70843893 0.11528399, + 0.62554318 0.77006018 0.12531203, + 0.63179505 0.7659111 0.11922801, + 0.55679011 0.82076818 0.12776703, + 0.5553019 0.82155985 0.12914798, + 0.47835594 0.86751288 0.13637099, + 0.46836078 0.87150156 0.14533792, + 0.39222115 0.90734029 0.15131506, + 0.37405089 0.91217571 0.16739593, + 0.30170503 0.93774211 0.17208701, + 0.27750194 0.94099474 0.19370496, + 0.2128129 0.95702654 0.19700491, + 0.18669796 0.95719779 0.22116993, + 0.13225998 0.96576989 0.22314997, + 0.10735004 0.96288735 0.24763709, + 0.064003207 0.96649814 0.24856603, + 0.041869882 0.96132851 0.27220288, + 0.0092158355 0.9621315 0.27242988, + -0.0070568076 0.95648265 0.29170388, + -0.029812707 0.95608121 0.29158205, + -0.029815992 0.95607978 0.29158595, + -0.047587879 0.95542151 0.29138485, + -0.047471106 0.95548213 0.29120502, + -0.060887106 0.95478612 0.29099202, + -0.061519876 0.95439762 0.29213089, + -0.070072025 0.95385838 0.29196611, + -0.068062082 0.95529479 0.28771394, + -0.072797664 0.95497453 0.28761786, + -0.070544213 0.95683622 0.28193605, + -0.071809441 0.9567495 0.28191113, + -0.07179296 0.95676553 0.28186086, + -0.062134221 0.95738733 0.28204408, + -0.039080597 0.97971386 0.19655398, + -0.033429597 0.9799149 0.19659397, + 0.020027598 0.99840885 -0.052713692, + 0.013859403 0.99851322 -0.052719209, + 0.05639578 0.94743365 -0.31494287, + 0.038940899 0.94822401 -0.31520599, + 0.068731122 0.8136363 -0.57729715, + 0.04041861 0.81489819 -0.57819313, + 0.054007191 0.62295896 -0.78038788, + 0.017606704 0.6237731 -0.78140718, + 0.020774895 0.37643591 -0.92620975, + -0.020414108 0.37643918 -0.92621642, + -0.022484193 0.13188796 -0.99100965, + -0.020979507 0.37912816 -0.92510635, + -0.062646024 0.37846714 -0.92349237, + -0.066943973 0.11880294 -0.99065852, + -0.062488001 0.377639 -0.92384201, + -0.10541102 0.37627006 -0.92049414, + -0.089628607 0.62006104 -0.7794171, + -0.12723592 0.61750662 -0.77620649, + -0.096255198 0.80776298 -0.58159602, + -0.12651995 0.80500972 -0.5796138, + -0.074280314 0.94116926 -0.32967108, + -0.094435766 0.93955863 -0.32910687, + -0.028527504 0.99656713 -0.077718809, + -0.037354905 0.99627709 -0.077696204, + 0.038435083 0.98637652 0.15994993, + 0.041485105 0.98625612 0.15993102, + 0.073687367 0.96681064 0.24463691, + 0.081097305 0.9662531 0.24449603, + 0.07997454 0.96698248 0.24196912, + 0.072412305 0.96754313 0.24210903, + 0.072069593 0.96773291 0.24145196, + 0.060106378 0.96850163 0.24164391, + 0.058021974 0.9694795 0.23820788, + 0.040682785 0.97031164 0.2384119, + 0.034581512 0.97265333 0.22967309, + 0.010470003 0.97318226 0.22979707, + 0.010866503 0.97306025 0.23029506, + -0.018451203 0.97295213 0.23026903, + -0.036502492 0.97697777 0.21019496, + -0.075364999 0.97484899 0.209737, + -0.10324004 0.97793233 0.18163106, + -0.15425992 0.97141755 0.18042091, + -0.18337998 0.97103089 0.15320198, + -0.24583408 0.95746833 0.15106305, + -0.28111407 0.95218122 0.11969103, + -0.35342696 0.92815787 0.11667199, + -0.38513595 0.91856188 0.088962995, + -0.46299222 0.88223439 0.085444741, + -0.48566481 0.87169772 0.065366179, + -0.56422001 0.823313 0.061737899, + -0.57698482 0.81522471 0.049971782, + -0.65220308 0.7566241 0.046379704, + -0.65587419 0.75365716 0.04277901, + -0.72474492 0.68790996 0.039047096, + -0.72163206 0.69098008 0.042352103, + -0.78324789 0.62054497 0.038034897, + -0.7754817 0.62961179 0.047084883, + -0.83016312 0.55596805 0.041577604, + -0.82018483 0.56950086 0.054458588, + -0.86846185 0.49350488 0.047191489, + -0.85753328 0.51055819 0.062984124, + -0.89966023 0.4333061 0.053454012, + -0.88905489 0.45229095 0.07081189, + -0.92558676 0.3739799 0.058551285, + -0.91552269 0.39473486 0.077477068, + -0.94709849 0.31493384 0.061813969, + -0.9409011 0.33011302 0.075700611, + -0.96675134 0.24924909 0.057157118, + -0.96638799 0.25040799 0.058224998, + -0.98409766 0.17301294 0.040229086, + -0.98374826 0.17463204 0.041749511, + -0.99457479 0.10117298 0.024187595, + -0.99441046 0.10247205 0.025445012, + -0.99943274 0.032685094 0.0081160981, + -0.99941236 0.033178013 0.0086128628, + -0.99945134 -0.032061312 -0.0083229728, + -0.99942964 -0.03258219 -0.0088741975, + -0.99509412 -0.095455714 -0.025998704, + -0.99488503 -0.097100899 -0.0278416, + -0.98659962 -0.15683994 -0.044970386, + -0.98599714 -0.15961702 -0.048291907, + -0.974033 -0.21670499 -0.065563798, + -0.97279334 -0.22064307 -0.070639022, + -0.95735776 -0.27514794 -0.088088877, + -0.95551902 -0.27948701 -0.094183303, + -0.93712723 -0.33071509 -0.11144603, + -0.93537575 -0.3339389 -0.11643497, + -0.91436213 -0.38232407 -0.13330501, + -0.91172814 -0.38620305 -0.13999702, + -0.88809812 -0.43213806 -0.15664801, + -0.88432175 -0.4366059 -0.16537896, + -0.858181 -0.48006201 -0.18184, + -0.85312903 -0.484833 -0.192634, + -0.82487214 -0.52537006 -0.20874003, + -0.81839269 -0.53017384 -0.22169593, + -0.78812391 -0.56786793 -0.23745897, + -0.7800442 -0.57241511 -0.25272906, + -0.74779564 -0.60736471 -0.26815987, + -0.73806894 -0.61125493 -0.28569496, + -0.70380425 -0.64356822 -0.30079812, + -0.70858705 -0.64224803 -0.29227003, + -0.67804223 -0.66900724 -0.30444711, + -0.6944592 -0.66583818 -0.27273807, + -0.6632818 -0.69252384 -0.28366894, + -0.67731702 -0.69070601 -0.25331199, + -0.64501238 -0.71744543 -0.26311815, + -0.6570527 -0.71672761 -0.2336309, + -0.62322903 -0.74353403 -0.242369, + -0.63357997 -0.74369496 -0.21329397, + -0.59860873 -0.76999873 -0.22083792, + -0.60740077 -0.77083969 -0.19201693, + -0.57106489 -0.79656285 -0.19842495, + -0.57839012 -0.79788917 -0.16981705, + -0.54026198 -0.823062 -0.175174, + -0.54623497 -0.82470286 -0.14660299, + -0.50614315 -0.84913731 -0.15094706, + -0.5108692 -0.85092533 -0.12222405, + -0.46935713 -0.87403816 -0.12554403, + -0.47291717 -0.87579328 -0.096620835, + -0.4300001 -0.89738423 -0.099002823, + -0.4324581 -0.89891523 -0.070223711, + -0.38805693 -0.91883588 -0.071779892, + -0.38954991 -0.91999775 -0.043070387, + -0.34384087 -0.93800062 -0.043913186, + -0.29742116 -0.95371145 -0.044442821, + -0.34326813 -0.93821937 -0.043720815, + -0.34190887 -0.93690467 -0.072854877, + -0.3871631 -0.91923624 -0.071480915, + -0.38488281 -0.91745657 -0.10069095, + -0.4286719 -0.89806777 -0.098562777, + -0.42531991 -0.89596075 -0.12789597, + -0.46745205 -0.8751471 -0.12492502, + -0.46294394 -0.87289387 -0.15407498, + -0.50367302 -0.850743 -0.150166, + -0.49790683 -0.84851873 -0.17917794, + -0.53725493 -0.8252219 -0.17425798, + -0.5301162 -0.82319927 -0.20327307, + -0.56748885 -0.79937071 -0.19738993, + -0.55884188 -0.79771382 -0.22660194, + -0.594491 -0.77350003 -0.219723, + -0.58422786 -0.77239084 -0.24917895, + -0.61862022 -0.74774224 -0.24122709, + -0.60659885 -0.74737281 -0.27105695, + -0.6399278 -0.72239184 -0.26199695, + -0.62585396 -0.72296596 -0.29262096, + -0.65769953 -0.69825351 -0.28261879, + -0.64117932 -0.70000637 -0.31445214, + -0.67184097 -0.67565495 -0.30351296, + -0.6673612 -0.67649817 -0.31141505, + -0.70184106 -0.64706606 -0.29786703, + -0.71258402 -0.64377099 -0.278896, + -0.74588275 -0.61118776 -0.26477993, + -0.7549969 -0.60698897 -0.24808097, + -0.78636533 -0.57184428 -0.2337171, + -0.79398012 -0.56707704 -0.21913303, + -0.8232879 -0.52946794 -0.20459896, + -0.82939559 -0.52453178 -0.19227391, + -0.85684532 -0.48407617 -0.17744406, + -0.86165071 -0.47919682 -0.16711794, + -0.88702273 -0.43597391 -0.15204397, + -0.89055175 -0.43152991 -0.14387298, + -0.91355973 -0.3858259 -0.12863497, + -0.91606998 -0.38192299 -0.122273, + -0.93656826 -0.33379608 -0.10686503, + -0.93919313 -0.32869104 -0.099390715, + -0.95700324 -0.27766106 -0.083959922, + -0.95893151 -0.27283487 -0.077533662, + -0.97383952 -0.2185819 -0.062116269, + -0.9749611 -0.21481302 -0.057501007, + -0.98651087 -0.15812899 -0.042327695, + -0.98706377 -0.15544397 -0.03927229, + -0.99506599 -0.096192896 -0.024302701, + -0.99525774 -0.094607875 -0.022611795, + -0.9994489 -0.032285195 -0.0077163391, + -0.99946898 -0.031777699 -0.0072047501, + -0.99943167 0.032876387 0.007453857, + -0.99945015 0.032410502 0.0070065008, + -0.99458152 0.10161195 0.021966388, + -0.99471962 0.10047496 0.020918092, + -0.98417938 0.17345606 0.036112312, + -0.9844501 0.17215301 0.034947902, + -0.96713197 0.249192 0.0505872, + -0.97079951 0.23660688 0.039566081, + -0.94792664 0.31412688 0.052529182, + -0.95447779 0.29599294 0.036882292, + -0.9269079 0.37240896 0.046404295, + -0.93447179 0.35466191 0.031262394, + -0.90172511 0.43064007 0.037959702, + -0.91015613 0.41360006 0.023470504, + -0.87160188 0.48942694 0.027773496, + -0.88000643 0.47471923 0.015181308, + -0.83485729 0.5501852 0.017594706, + -0.84229183 0.53896588 0.0077707381, + -0.79010665 0.61290568 0.0088367853, + -0.79456389 0.60716993 0.0035848296, + -0.73454076 0.67855275 0.0040062787, + -0.73390216 0.67923915 0.0046853409, + -0.66560423 0.74628723 0.0051478418, + -0.65699804 0.75377113 0.013518802, + -0.58140588 0.81348282 0.014589696, + -0.56251264 0.82617754 0.031782281, + -0.48316512 0.87488216 0.033655908, + -0.45286679 0.88954759 0.060139369, + -0.37459409 0.92507726 0.062541515, + -0.33690184 0.93671656 0.095179759, + -0.26521596 0.95924985 0.097469382, + -0.23077911 0.96453947 0.12808105, + -0.16953704 0.97694826 0.12972803, + -0.13361797 0.97744375 0.16355395, + -0.085441433 0.98268133 0.16443007, + -0.061075877 0.97999966 0.18939492, + -0.023795288 0.98155451 0.18969591, + -0.021970393 0.98119164 0.19178192, + 0.0092666335 0.98138636 0.19182007, + 0.0198854 0.97844601 0.205543, + 0.042865399 0.97773999 0.205395, + 0.047883902 0.97592199 0.212799, + 0.064578928 0.97500348 0.2125981, + 0.067043774 0.9739145 0.21678489, + 0.078430802 0.973104 0.21660399, + 0.081426874 0.97152263 0.22251593, + 0.075574294 0.97197187 0.22261897, + 0.038573276 0.9896214 0.1384249, + 0.037092295 0.98967689 0.13843298, + -0.050037988 0.99430376 -0.094107077, + -0.039450698 0.99477589 -0.094151787, + -0.11660898 0.93336487 -0.33945897, + -0.094918884 0.93553287 -0.34024796, + -0.15793304 0.79668516 -0.58339512, + -0.12618001 0.80036211 -0.58608806, + -0.16533604 0.60968411 -0.77520919, + -0.12662698 0.61321592 -0.77969986, + -0.14817005 0.37287611 -0.91597432, + -0.10518698 0.37494591 -0.92105979, + -0.11229903 0.13513103 -0.98444325, + -0.11903706 0.10570105 -0.98724747, + -0.11970696 -0.0030240088 -0.99280465, + 0.025181109 0.012208505 -0.99960834, + 0.025736395 0.011992497 -0.99959677, + 0.17369999 -0.0033634296 -0.98479289, + 0.25111195 0.090737276 -0.96369576, + 0.23699594 0.34561691 -0.90795475, + 0.28215593 0.34129792 -0.89660674, + 0.24616885 0.57641166 -0.77919853, + 0.164263 0.91616398 -0.36559701, + 0.14962001 0.91832513 -0.36646003, + 0.239832 0.75989699 -0.60418302, + 0.22130895 0.77979183 -0.58561689, + 0.28812796 0.56949192 -0.76984489, + 0.37463796 0.53356892 -0.75825489, + 0.34393004 0.084004305 -0.93523014, + 0.32706597 0.32340196 -0.88794088, + 0.37301883 0.31752285 -0.8718006, + 0.33136711 0.5429672 -0.77161032, + 0.33103991 0.55345589 -0.76426381, + 0.28814796 0.56164896 -0.7755779, + 0.32759112 0.33064711 -0.88507432, + 0.28166485 0.33578885 -0.89883858, + 0.29746112 0.086104631 -0.95084333, + 0.26503491 0.15271494 -0.95206863, + 0.26817894 -0.0028997294 -0.96336478, + 0.2705971 -0.002899671 -0.96268839, + 0.26748106 0.15135103 -0.95160222, + 0.26561394 0.15141597 -0.95211476, + 0.26871094 -0.0027940292 -0.96321678, + 0.22075494 0.018295696 -0.97515774, + 0.21809793 0.15573093 -0.96342164, + 0.21867797 0.15571399 -0.9632929, + 0.22137192 0.0073574572 -0.97516167, + 0.22968797 0.012513998 -0.97318387, + 0.076766528 -0.0033966212 -0.99704337, + 0.12441798 0.0099633392 -0.99217987, + 0.12295006 0.15346408 -0.98047549, + 0.12389006 0.15344907 -0.98035949, + 0.12536199 0.0143715 -0.99200702, + 0.12836103 0.012773503 -0.99164522, + -0.077207386 0.013421497 -0.99692476, + -0.070451483 0.016561097 -0.99737775, + -0.069772474 0.13946596 -0.98776567, + -0.070757195 0.13945699 -0.98769689, + -0.071452588 0.0089659085 -0.99740374, + -0.017807703 -0.004526481 -0.99983126, + -0.017656699 0.13005298 -0.99134988, + -0.021676205 0.13004403 -0.99127126, + -0.021861689 -0.0035988383 -0.99975455, + -0.0226468 -0.00359884 -0.99973702, + -0.022448802 0.13199502 -0.99099612, + -0.020938993 0.13199896 -0.99102867, + -0.0211237 -0.00312811 -0.99977201, + 0.027092787 0.013141293 -0.99954653, + 0.026814491 0.14354396 -0.98928064, + 0.024922106 0.14355002 -0.98932922, + 0.075782232 0.10331704 -0.99175733, + 0.076189391 -0.0036114596 -0.99708688, + 0.075374387 -0.0036114592 -0.99714875, + 0.07451427 0.15067793 -0.98577064, + 0.075890571 0.15066494 -0.98566765, + 0.11236299 0.10564799 -0.9880349, + 0.10525 0.36844099 -0.92367399, + 0.14892097 0.36636692 -0.91847575, + 0.12746598 0.60892695 -0.78291786, + 0.16657801 0.60535705 -0.77832812, + 0.12722893 0.79817551 -0.58883667, + 0.15904096 0.79447281 -0.58610487, + 0.09552452 0.93512225 -0.3412061, + 0.11727495 0.93293566 -0.34040788, + 0.039150488 0.99499273 -0.091960579, + 0.044289604 0.99477911 -0.091940805, + 0.13670905 0.92613238 -0.35155311, + 0.11838195 0.92833567 -0.35238987, + 0.19235504 0.78438014 -0.58970106, + 0.15900095 0.78913879 -0.59327787, + 0.20612893 0.59580177 -0.77622873, + 0.16607699 0.60042197 -0.7822479, + 0.19307391 0.35912883 -0.91309857, + 0.14827499 0.36196998 -0.92032188, + 0.15798508 0.099778444 -0.98238748, + 0.17109302 0.15647501 -0.97275013, + 0.17322601 -0.0034487206 -0.9848761, + 0.17113298 -0.0034487494 -0.98524189, + 0.16904208 0.15585308 -0.97320849, + 0.17157902 0.15579802 -0.97277313, + 0.20452897 0.096058182 -0.97413588, + 0.19247103 0.35436204 -0.91508609, + 0.23754898 0.35077697 -0.90582889, + 0.2057101 0.58928728 -0.78129637, + 0.24638206 0.58360314 -0.77375919, + 0.19278991 0.77633864 -0.60010868, + 0.21939903 0.77190411 -0.59668106, + 0.13602294 0.92319357 -0.35945982, + 0.15009792 0.92129761 -0.35872182, + 0.054955713 0.99234426 -0.11060203, + 0.059102785 0.99210876 -0.11057597, + 0.072685465 0.9891665 -0.12753995, + -0.03559408 0.99181855 0.12259294, + -0.039414715 0.99167633 0.12257504, + 0.082516149 0.98777241 -0.13227493, + 0.072973907 0.98851013 -0.13237302, + 0.17916194 0.9104737 -0.37274489, + 0.16396302 0.9129231 -0.37374803, + 0.25689399 0.756473 -0.60145998, + 0.25827113 0.76441336 -0.59073532, + 0.27818906 0.74284816 -0.60892314, + 0.17905001 0.90670514 -0.38187307, + 0.19527003 0.90385711 -0.38067305, + 0.083546393 0.98604488 -0.14399798, + 0.093912013 0.98513114 -0.14386502, + -0.02782871 0.99509138 0.094967134, + -0.029665792 0.99503875 0.094962075, + 0.10654704 0.98192137 -0.15645505, + 0.095393419 0.98303926 -0.15663305, + 0.21204093 0.89658773 -0.38880485, + 0.19539091 0.89976656 -0.39018282, + 0.29591399 0.73874003 -0.60555601, + 0.29680413 0.74665523 -0.59532624, + 0.319374 0.72180802 -0.613998, + 0.21240403 0.89216214 -0.39866206, + 0.22979006 0.88856322 -0.39705408, + 0.108479 0.97948498 -0.169828, + 0.12067906 0.97809845 -0.16958807, + -0.012978398 0.99792385 0.063082896, + -0.013842605 0.99791235 0.063082226, + 0.13624901 0.97355002 -0.183403, + 0.12312596 0.97523665 -0.18372095, + 0.24865003 0.8796981 -0.40534505, + 0.23040891 0.88378572 -0.40722784, + 0.33744916 0.71702033 -0.60992628, + 0.33796 0.72572398 -0.59925598, + 0.41894507 0.51289809 -0.74928004, + 0.37519181 0.52359378 -0.76490563, + 0.4184109 0.30343893 -0.85607082, + 0.37258491 0.31003395 -0.87467682, + 0.39012793 0.07996279 -0.91728187, + 0.3581281 0.14551003 -0.92226422, + 0.36197996 -0.0019507898 -0.93218386, + 0.3619121 -0.0019507805 -0.93221027, + 0.35805589 0.14558895 -0.92227966, + 0.35791808 0.14559503 -0.92233223, + 0.36177188 -0.0019340293 -0.93226463, + 0.31543887 0.021920092 -0.94869262, + 0.31192306 0.15045403 -0.93811923, + 0.312601 0.150426 -0.93789798, + 0.31619409 0.0052277213 -0.94868022, + 0.32857892 0.012195298 -0.94439775, + 0.60016102 0.0155575 0.79972798, + 0.57469815 -0.0013878505 0.81836432, + 0.5746941 -0.0040753311 0.81835818, + 0.61111689 -0.012107697 0.79144782, + 0.61101204 -0.027425604 0.7911461, + 0.57226473 -0.028411087 0.81957656, + 0.57221889 -0.034717094 0.8193658, + 0.53615189 -0.035733894 0.84336483, + 0.536134 -0.033747599 0.843458, + 0.59318072 -0.032185886 0.80442566, + 0.59345186 -0.037917692 0.80397582, + 0.64768404 -0.035893902 0.7610631, + 0.64764363 -0.035422176 0.76111954, + 0.60683078 -0.036951084 0.79397172, + 0.60632992 -0.031123497 0.79460388, + 0.54988408 -0.032690205 0.8346011, + 0.54962593 -0.027417697 0.83496088, + 0.49210107 -0.028570503 0.87006915, + 0.49198306 -0.020212801 0.87037009, + 0.4397321 -0.015678603 0.89799225, + 0.43978584 -0.00021612292 0.8981027, + 0.44921607 -0.00021593603 0.89342314, + 0.44915515 -0.016449705 0.89330232, + 0.44832784 -0.016458094 0.89371771, + 0.44838879 -8.1961465e-005 0.89383858, + 0.42377084 0.015796995 0.90563172, + -0.33545291 0.72996581 -0.59550089, + -0.35464591 0.12751397 -0.92626476, + -0.35756403 0.0021829102 -0.93388611, + -0.35698217 0.0018673509 -0.93410939, + -0.35406703 0.12753701 -0.92648309, + -0.39067194 0.069641493 -0.91789186, + -0.36995289 0.33161488 -0.86785167, + -0.41542014 0.32468212 -0.84971029, + -0.37184188 0.5359928 -0.7579217, + -0.41493905 0.52534103 -0.74286103, + -0.37842286 0.70652878 -0.59800774, + -0.45950001 0.503012 -0.73201001, + -0.41577405 0.51506907 -0.74955708, + -0.45991111 0.31042805 -0.83193517, + -0.41515893 0.31804296 -0.85234487, + -0.43640709 0.065648817 -0.89735126, + -0.39408395 0.12903799 -0.90997088, + -0.39740714 -0.00043841015 -0.91764235, + -0.40336791 -0.00043844187 -0.91503775, + -0.4004139 0.12079397 -0.90833777, + -0.40005201 0.120811 -0.90849501, + -0.40300286 -0.00038632084 -0.91519868, + -0.37664691 0.015940497 -0.92621976, + -0.2795369 0.012949395 -0.96004766, + -0.179187 0.013383 -0.983724, + -0.16823801 0.019873302 -0.98554611, + -0.21681599 -0.0026046401 -0.97620898, + -0.21468908 0.13977905 -0.96662837, + -0.21835297 0.13968499 -0.96582091, + -0.220515 -0.00265957 -0.97538, + -0.21612503 -0.0026596703 -0.97636211, + -0.26428393 0.0039990884 -0.96443665, + -0.26183087 0.13598494 -0.95548552, + -0.26192996 0.13598199 -0.95545888, + -0.26431203 0.023533804 -0.96415013, + -0.31109312 -0.0014759806 -0.95037836, + -0.30837598 0.13189898 -0.94207591, + -0.30849484 0.13189495 -0.94203752, + -0.31121299 -0.0014868299 -0.95033902, + -0.31185398 -0.0014868598 -0.95012885, + -0.30915311 0.13131805 -0.94190234, + -0.34445 0.074612997 -0.935835, + -0.32494915 0.34266314 -0.88147044, + -0.37021899 0.33658099 -0.86582398, + -0.32823896 0.55424893 -0.76489687, + -0.37131411 0.54480916 -0.75187027, + -0.29466295 0.75062883 -0.59137988, + -0.096427739 0.98307139 -0.15579607, + 0.022023402 0.99618912 0.084393106, + 0.0241987 0.99613899 0.084388897, + -0.108349 0.98109603 -0.160347, + -0.097002082 0.98225188 -0.16053599, + -0.21147105 0.89693022 -0.3883251, + -0.19468793 0.90012473 -0.38970786, + -0.29376996 0.74231094 -0.60222393, + -0.27611303 0.74638706 -0.60553104, + -0.17843205 0.90696323 -0.38154909, + -0.19451797 0.90414888 -0.38036495, + -0.079135679 0.98758775 -0.13567597, + -0.074006893 0.98797786 -0.13572998, + -0.073681608 0.98868209 -0.13068601, + 0.031965289 0.99303162 0.11342996, + 0.031498212 0.99304634 0.11343203, + 0.073346168 0.97766566 0.19695193, + 0.077509098 0.97735697 0.19689, + 0.071964391 0.97968191 0.18720199, + 0.056020208 0.98068613 0.18739401, + 0.050589081 0.98251861 0.17915894, + 0.028328413 0.98338348 0.17931709, + 0.019407788 0.98568439 0.1674799, + -0.0104861 0.985816 0.167502, + -0.026891295 0.98858678 0.14823297, + -0.066455923 0.98675835 0.14795806, + -0.071065865 0.98715055 0.14311993, + -0.11796904 0.98274237 0.14248104, + -0.14884593 0.98237354 0.11307995, + -0.20759092 0.97179866 0.11186296, + -0.25087902 0.96523714 0.073328711, + -0.32171202 0.94411713 0.071724206, + -0.35965404 0.9322651 0.039126303, + -0.43802786 0.89817071 0.037695386, + -0.47494194 0.8799969 0.0059753489, + -0.5551939 0.83170182 0.0056474088, + -0.58126014 0.81352717 -0.017615603, + -0.65752405 0.7532571 -0.016310502, + -0.67134869 0.74055266 -0.029539986, + -0.73944408 0.67268306 -0.026832704, + -0.74407935 0.66733831 -0.031711414, + -0.80293709 0.59539205 -0.028292503, + -0.80143565 0.59749269 -0.026521986, + -0.85163182 0.5236249 -0.023243094, + -0.84675854 0.53171468 -0.016718091, + -0.88928527 0.45712712 -0.014372904, + -0.88284886 0.46963593 -0.0044765794, + -0.91846037 0.39549515 -0.0037698713, + -0.91192627 0.41027814 0.0079012727, + -0.94157463 0.33674189 0.0064850776, + -0.93554527 0.35268509 0.019193904, + -0.96002752 0.27949187 0.015210592, + -0.95509589 0.29499197 0.027779097, + -0.97491252 0.22160789 0.020868491, + -0.97113866 0.23622391 0.032983787, + -0.98637265 0.16294594 0.022751993, + -0.98456562 0.17229994 0.030713988, + -0.99484622 0.099821925 0.017794104, + -0.99472743 0.10083694 0.018684989, + -0.99946475 0.032166891 0.0059604887, + -0.99944925 0.032575309 0.0063337213, + -0.99948525 -0.031491607 -0.0061230315, + -0.9994669 -0.031976398 -0.0065883691, + -0.9954105 -0.093727753 -0.01931159, + -0.99523199 -0.095274597 -0.0208827, + -0.98748887 -0.15403199 -0.033761498, + -0.9869805 -0.15662707 -0.036571119, + -0.97581136 -0.21288808 -0.049707517, + -0.97477835 -0.21655108 -0.053970519, + -0.96036261 -0.27047992 -0.067410976, + -0.95859712 -0.27516302 -0.073327005, + -0.94135523 -0.32603908 -0.086884625, + -0.93864846 -0.33163714 -0.094636142, + -0.91875011 -0.37968305 -0.10834701, + -0.915272 -0.38542101 -0.117166, + -0.89288568 -0.43081686 -0.13096595, + -0.88948524 -0.43536308 -0.13883503, + -0.86479884 -0.47838289 -0.15255398, + -0.86029559 -0.48328277 -0.16226293, + -0.83358932 -0.5236572 -0.17581806, + -0.82776111 -0.52876806 -0.18765903, + -0.79929799 -0.56632698 -0.20098899, + -0.79211819 -0.57129115 -0.21488404, + -0.76166165 -0.60649073 -0.22812389, + -0.75297481 -0.61103487 -0.24426495, + -0.72053295 -0.64387894 -0.25739497, + -0.71044916 -0.64757818 -0.27550805, + -0.67686325 -0.67735523 -0.2881771, + -0.66523284 -0.67991084 -0.30852294, + -0.63074428 -0.70664233 -0.32065314, + -0.63484716 -0.70621717 -0.31341109, + -0.60367012 -0.72869921 -0.3233881, + -0.62009192 -0.72836894 -0.29148698, + -0.58739793 -0.75136489 -0.30068997, + -0.60135311 -0.75202417 -0.26987806, + -0.56771207 -0.7748431 -0.27806702, + -0.57954603 -0.77628314 -0.24801403, + -0.54472089 -0.79883784 -0.25521994, + -0.55474913 -0.8008762 -0.22550106, + -0.51814514 -0.82328016 -0.23180906, + -0.52654403 -0.82573915 -0.20225303, + -0.48807475 -0.84774256 -0.2076429, + -0.49493283 -0.85044372 -0.17828894, + -0.45506611 -0.87151217 -0.18270604, + -0.46054912 -0.87429017 -0.15333404, + -0.41924614 -0.89422429 -0.15683006, + -0.42347994 -0.8969149 -0.12731199, + -0.38054693 -0.91558391 -0.12996198, + -0.38364407 -0.91801912 -0.10029101, + -0.33906999 -0.935197 -0.102167, + -0.34114012 -0.93720436 -0.072604321, + -0.295733 -0.95241702 -0.073782802, + -0.29694113 -0.95386833 -0.044285715, + -0.25102198 -0.96693987 -0.044892598, + -0.25154608 -0.96772838 -0.015046805, + -0.2650829 -0.96414465 -0.012499696, + -0.26510388 -0.96421951 0.00073161867, + -0.21734807 -0.97609335 -0.0013022604, + -0.21731597 -0.97595388 -0.016966198, + -0.2174339 -0.97592753 -0.016965793, + -0.20505695 -0.97864974 -0.014008996, + -0.204611 -0.97779697 -0.045248602, + -0.25058001 -0.96706098 -0.044751801, + -0.24953791 -0.96549165 -0.074543372, + -0.29500905 -0.95265925 -0.073552616, + -0.293172 -0.95045 -0.103417, + -0.33792698 -0.93564987 -0.10180698, + -0.33512101 -0.93291402 -0.131778, + -0.37886509 -0.91635525 -0.12943903, + -0.37495887 -0.91325969 -0.15925694, + -0.41698092 -0.89540279 -0.15614296, + -0.41185194 -0.89210987 -0.18578999, + -0.45216385 -0.8731997 -0.18185194, + -0.44565988 -0.86985582 -0.21151395, + -0.48463893 -0.84994787 -0.20667297, + -0.47660723 -0.84671044 -0.23648912, + -0.51412117 -0.82610029 -0.2307331, + -0.50445104 -0.82316411 -0.26063403, + -0.54004616 -0.80237627 -0.2540521, + -0.52853411 -0.79989821 -0.28427905, + -0.56249601 -0.77906299 -0.27687401, + -0.54886699 -0.77719802 -0.30774701, + -0.58156288 -0.75636381 -0.29949695, + -0.5654422 -0.75530231 -0.33135113, + -0.59717363 -0.73453659 -0.32224181, + -0.5934943 -0.73461133 -0.32880214, + -0.62843508 -0.70998907 -0.31778103, + -0.64070004 -0.70831805 -0.29629204, + -0.67456877 -0.68102974 -0.2848779, + -0.68556792 -0.67795396 -0.26528296, + -0.71824998 -0.647946 -0.25354099, + -0.72790366 -0.64380568 -0.23594588, + -0.7595287 -0.61074978 -0.22383192, + -0.76772416 -0.60593611 -0.20842505, + -0.79737979 -0.5706619 -0.19629195, + -0.80424285 -0.56545687 -0.18289895, + -0.83193344 -0.52794522 -0.17076507, + -0.83746368 -0.52270681 -0.15947494, + -0.8634339 -0.48250493 -0.14720999, + -0.86775488 -0.47748193 -0.13788599, + -0.89182377 -0.4346239 -0.12550896, + -0.89619511 -0.42839706 -0.11537101, + -0.91798335 -0.38297415 -0.10313804, + -0.92154413 -0.37671107 -0.094049312, + -0.94084275 -0.32875291 -0.08207608, + -0.94334263 -0.32326189 -0.074875467, + -0.96004736 -0.27262008 -0.063145623, + -0.96167487 -0.26805797 -0.057674393, + -0.97564089 -0.21446598 -0.046143796, + -0.97659713 -0.21089803 -0.042192806, + -0.98741221 -0.15509503 -0.031028807, + -0.98788613 -0.15255702 -0.028412905, + -0.99538714 -0.094318718 -0.017566402, + -0.99555051 -0.092838153 -0.016134193, + -0.99948347 -0.031663816 -0.0055028126, + -0.99949878 -0.031239692 -0.0051150587, + -0.99946409 0.032306403 0.0052897106, + -0.99947864 0.031906888 0.0049419482, + -0.99486512 0.10001702 0.015491302, + -0.99548721 0.094290622 0.010702902, + -0.9864735 0.16287492 0.018487891, + -0.98828626 0.15228803 0.0099395532, + -0.97514486 0.22109798 0.014430598, + -0.97799754 0.20856489 0.0046329978, + -0.96050155 0.27820587 0.0061799772, + -0.96443564 0.26428092 -0.0044065984, + -0.94244778 0.3343069 -0.0055742087, + -0.94714445 0.32041314 -0.015903607, + -0.92000109 0.39143407 -0.019428702, + -0.92511237 0.37859714 -0.028833911, + -0.89191312 0.45090106 -0.034340605, + -0.89644122 0.44122311 -0.04141691, + -0.85599661 0.51471877 -0.048315879, + -0.85863811 0.50995207 -0.051860709, + -0.80995101 0.58348799 -0.059339099, + -0.80842584 0.58577687 -0.057559084, + -0.75023651 0.65800059 -0.064655863, + -0.74155098 0.66858101 -0.0556922, + -0.67315978 0.73694474 -0.061386876, + -0.65316409 0.75601012 -0.042724002, + -0.57586998 0.816239 -0.046127599, + -0.54318875 0.83942461 -0.01766959, + -0.46211681 0.88662273 -0.018663093, + -0.42412809 0.90550226 0.013459203, + -0.34580281 0.93820351 0.013945294, + -0.29712304 0.95322722 0.055461116, + -0.228202 0.97197002 0.056551602, + -0.19098096 0.97747678 0.089808278, + -0.13333996 0.98691362 0.090675369, + -0.12541001 0.98721498 0.098381303, + -0.075967766 0.99219555 0.098877557, + -0.052557319 0.99088436 0.12404004, + -0.014447104 0.99215221 0.12419903, + -0.00044913983 0.99000567 0.14102696, + 0.028507609 0.98960334 0.14097005, + 0.037861906 0.98739022 0.15371104, + 0.059225414 0.98636425 0.15355103, + 0.068008408 0.98356915 0.16723202, + 0.066169709 0.9836911 0.16725302, + 0.010679397 0.99754673 0.069184482, + 0.0063930624 0.99867636 0.051037118, + -0.12293702 0.9770081 -0.17418902, + -0.11046203 0.97845125 -0.17444605, + -0.22924709 0.88863331 -0.39721113, + -0.21192305 0.89221025 -0.39881009, + -0.31659389 0.72665977 -0.60969979, + -0.33502609 0.72179317 -0.60561711, + -0.22987789 0.88421255 -0.4066008, + -0.24797897 0.88016587 -0.40473995, + -0.12551394 0.9740085 -0.18855691, + -0.13886406 0.97226048 -0.18821909, + 0.006764459 0.99867386 0.051036894, + -0.0116452 0.99942601 0.031812102, + 0.052340992 0.98978591 0.13260598, + 0.049977493 0.98990589 0.13262199, + 0.011627194 0.99984455 0.013254894, + -0.017283795 0.99976277 0.013253797, + -0.15652594 0.96653062 -0.20326893, + -0.14209098 0.96866375 -0.20371695, + -0.26826093 0.86976981 -0.41416991, + -0.24904011 0.87441641 -0.41638321, + -0.35910201 0.70350802 -0.61328799, + -0.37837094 0.69774592 -0.60826492, + -0.26948506 0.86426318 -0.42476708, + -0.28903595 0.85915983 -0.42225891, + -0.16029498 0.96243489 -0.21914497, + -0.17608191 0.95980853 -0.2185469, + 0.0082578687 0.9974069 0.071492992, + 0.025637405 0.99524826 0.093934923, + 0.031948708 0.99506724 0.093917824, + -0.041885484 0.99909467 -0.0074459771, + -0.032501396 0.99944389 -0.0074485792, + 0.0088594202 0.993411 0.114263, + 0.039221086 0.99268562 0.11417996, + 0.039758399 0.99258 0.11491, + 0.010564899 0.99330986 0.11499499, + -0.0035889996 0.9952209 0.097583085, + -0.0406183 0.99440598 0.097503103, + -0.060836706 0.99530011 0.075343408, + -0.10847698 0.99126285 0.075037792, + -0.14026093 0.98915553 0.043569177, + -0.20063692 0.97871667 0.043109383, + -0.21223308 0.97667533 0.032595113, + -0.28077489 0.95923954 0.032013185, + -0.32233113 0.94662136 -0.0032788811, + -0.39979708 0.91659826 -0.0031748908, + -0.45001706 0.89189011 -0.044908002, + -0.53174615 0.84583229 -0.042588916, + -0.56603396 0.82125789 -0.071701489, + -0.64461076 0.76161373 -0.066494077, + -0.67043942 0.7365064 -0.089829549, + -0.73965734 0.6680333 -0.081478037, + -0.75323629 0.65084124 -0.095084138, + -0.81125629 0.57854921 -0.084522627, + -0.81576014 0.57139707 -0.089670509, + -0.86346745 0.49830571 -0.078200057, + -0.863002 0.499208 -0.077581301, + -0.90187597 0.426871 -0.0663395, + -0.89892799 0.43372801 -0.0617125, + -0.93023038 0.36331713 -0.051694117, + -0.92648202 0.37367901 -0.044666201, + -0.95159054 0.30519584 -0.036480382, + -0.94786787 0.31742898 -0.028023396, + -0.96788561 0.2504169 -0.022107393, + -0.96479326 0.26266807 -0.013399503, + -0.98043466 0.19658892 -0.010028596, + -0.97815746 0.2078581 -0.0017447708, + -0.98972303 0.142993 -0.00120029, + -0.98834378 0.15212896 0.0057719187, + -0.99611413 0.088008806 0.0033391404, + -0.99550277 0.094360575 0.0083856881, + -0.99954313 0.030106204 0.0026755002, + -0.999479 0.031996299 0.0042435299, + -0.99951261 -0.030946089 -0.0041042487, + -0.99949723 -0.031389106 -0.0044898507, + -0.99566603 -0.092064202 -0.0131688, + -0.995529 -0.093358897 -0.0143611, + -0.9882521 -0.15105602 -0.023236401, + -0.98781502 -0.153506 -0.0256387, + -0.9773289 -0.20883398 -0.034879696, + -0.97643661 -0.21233092 -0.038561985, + -0.96289039 -0.26554909 -0.04822712, + -0.96137589 -0.27002397 -0.053323694, + -0.94516736 -0.32039911 -0.063271523, + -0.94285274 -0.32578191 -0.069962785, + -0.92411065 -0.37360689 -0.080233373, + -0.92080873 -0.3797909 -0.088713378, + -0.89962769 -0.42521185 -0.099322863, + -0.89516324 -0.43201607 -0.10975003, + -0.87170202 -0.47494999 -0.120657, + -0.86639702 -0.481554 -0.132144, + -0.84109747 -0.52160132 -0.14313309, + -0.83580017 -0.52700013 -0.15397704, + -0.808788 -0.56449902 -0.164933, + -0.80227417 -0.5698871 -0.17772104, + -0.77336287 -0.60521692 -0.18873897, + -0.76550263 -0.61035371 -0.20365189, + -0.73467624 -0.64354026 -0.21472508, + -0.72550607 -0.64805806 -0.23165002, + -0.69349664 -0.67842072 -0.24250288, + -0.683034 -0.681997 -0.261428, + -0.64990216 -0.70966518 -0.27203405, + -0.63816583 -0.71197784 -0.29297093, + -0.60384578 -0.73713374 -0.30332187, + -0.59104413 -0.73783016 -0.3259961, + -0.55568403 -0.76047313 -0.33600003, + -0.55891395 -0.76067686 -0.33012998, + -0.52738696 -0.77938986 -0.33825198, + -0.54301375 -0.78178465 -0.30651087, + -0.51024109 -0.80069119 -0.31392309, + -0.5233829 -0.8037008 -0.28308195, + -0.488787 -0.82285303 -0.289828, + -0.49984807 -0.82633013 -0.25948104, + -0.46334207 -0.84547514 -0.26549202, + -0.47257075 -0.84926856 -0.23541388, + -0.4347972 -0.86780542 -0.24055211, + -0.44236499 -0.871759 -0.210593, + -0.40306193 -0.88958389 -0.21489897, + -0.40913376 -0.89352345 -0.1850009, + -0.36809102 -0.91047913 -0.18851203, + -0.37281102 -0.91425014 -0.15861501, + -0.33004698 -0.93007088 -0.16135998, + -0.3335759 -0.93353379 -0.13130797, + -0.2896969 -0.94778866 -0.13331296, + -0.29217988 -0.95078862 -0.10311096, + -0.24738294 -0.96326977 -0.10446498, + -0.24896508 -0.96565336 -0.07436493, + -0.20337392 -0.97621065 -0.075177968, + -0.20423996 -0.97787988 -0.045132995, + -0.15811592 -0.9863705 -0.045524877, + -0.15845905 -0.98725337 -0.014883406, + -0.12076201 -0.99254113 -0.016694501, + -0.12077902 -0.99267912 -0.00077198411, + -0.12076104 -0.99268138 -0.0007729893, + -0.12074404 -0.99254334 -0.016694505, + -0.169322 -0.98546797 -0.0135269, + -0.16933702 -0.98555809 0.00053772307, + -0.169314 -0.98556203 0.00053772301, + -0.16929002 -0.98542112 -0.016913401, + -0.16930299 -0.98541886 -0.016913299, + -0.16932696 -0.98555976 0.0005366499, + -0.20454805 -0.97884923 -0.003782881, + -0.30412212 -0.95262635 -0.0035832615, + -0.26509103 -0.96422315 0.00072643004, + -0.265053 -0.96408498 -0.016945601, + -0.29804799 -0.954454 -0.0135997, + -0.31201097 -0.94992787 -0.016920198, + -0.31205505 -0.95006222 -0.0018901405, + -0.31202111 -0.95007336 -0.0018937207, + -0.3119761 -0.94993937 -0.016920406, + -0.358215 -0.93356198 -0.0120033, + -0.3582409 -0.93362874 0.0008514768, + -0.35819808 -0.93364525 0.00085147715, + -0.35814789 -0.93351364 -0.016800994, + -0.35817096 -0.93350488 -0.016800798, + -0.35822204 -0.93363613 0.00085023814, + -0.40361205 -0.91492313 -0.0036278705, + -0.40355909 -0.91480422 -0.016531704, + -0.40351486 -0.91482371 -0.016531995, + -0.40356886 -0.91494572 -0.0025678691, + -0.40045491 -0.91631174 -0.0029416992, + -0.73387474 -0.67927378 -0.0038729587, + -0.75590086 -0.65468591 0.00038891894, + -0.75959253 -0.65030861 -0.010859493, + -0.75877827 -0.65051621 -0.03293021, + -0.7906785 -0.61144865 -0.030952482, + -0.78916752 -0.61199063 -0.051787872, + -0.81895918 -0.5718081 -0.048387609, + -0.8167693 -0.57282215 -0.069012821, + -0.8445279 -0.53166693 -0.064054489, + -0.8417241 -0.53326207 -0.084452406, + -0.86724389 -0.49175495 -0.077878892, + -0.86396772 -0.49398482 -0.097666964, + -0.88748032 -0.45209414 -0.089384429, + -0.8838439 -0.45501295 -0.10854998, + -0.9057287 -0.41228786 -0.098357461, + -0.90182209 -0.41595605 -0.11703701, + -0.922252 -0.37213901 -0.104708, + -0.91818166 -0.37659886 -0.12294596, + -0.93710786 -0.33180597 -0.10832199, + -0.93301874 -0.33703992 -0.12601598, + -0.95055324 -0.29089406 -0.10876203, + -0.94659811 -0.29685703 -0.12580901, + -0.96286315 -0.24858703 -0.10535201, + -0.95918262 -0.25523692 -0.12174895, + -0.97419977 -0.20369996 -0.097165778, + -0.97100425 -0.21086004 -0.11264503, + -0.98434722 -0.15544903 -0.083043724, + -0.9837845 -0.15718308 -0.086380646, + -0.99371433 -0.098107539 -0.053915519, + -0.99420625 -0.095480226 -0.049372211, + -0.99930489 -0.033112697 -0.017122298, + -0.99935448 -0.032265514 -0.015797308, + -0.9992739 0.034220595 0.016754499, + -0.99931961 0.033417188 0.015611494, + -0.99281663 0.10839996 0.050640982, + -0.99329448 0.10561905 0.047019321, + -0.97993052 0.18210891 0.081071064, + -0.98069549 0.17944309 0.077695839, + -0.95931953 0.25907987 0.11217695, + -0.96051788 0.25616997 0.10854699, + -0.93015522 0.33806908 0.14325003, + -0.93163598 0.33538401 0.1399, + -0.89196068 0.41726586 0.17405593, + -0.89350057 0.41510278 0.17130792, + -0.84523112 0.49398807 0.20386302, + 0.64404505 0.69866806 0.31155902, + 0.56597465 0.75295055 0.3357648, + 0.55370104 0.75724012 0.34641403, + 0.47900993 0.79824686 0.36517298, + 0.49639583 0.79401368 0.35090387, + 0.42356908 0.82855821 0.36617008, + 0.44663599 0.82453299 0.34736401, + 0.37600386 0.85393268 0.35974988, + 0.39154306 0.85222811 0.34698904, + 0.32377315 0.87628543 0.35678416, + 0.33384216 0.8758834 0.34839317, + 0.26959905 0.89478624 0.3559131, + 0.2729691 0.89490527 0.35303313, + 0.21316589 0.90885258 0.35853481, + 0.21119992 0.90862268 0.36027688, + 0.15764599 0.91796786 0.36398196, + 0.15159506 0.91673338 0.36962011, + 0.10500798 0.92232478 0.37187392, + 0.096940465 0.91993362 0.37990084, + 0.057688974 0.92274761 0.38106284, + 0.04970482 0.91960335 0.38969114, + 0.01781621 0.92059541 0.39011118, + 0.011073103 0.91724521 0.3981691, + -0.0132616 0.91722101 0.39815801, + -0.017801391 0.9144696 0.40426281, + -0.035715301 0.91403103 0.40406901, + -0.037696607 0.91259825 0.40711609, + -0.049776308 0.9121151 0.40690106, + -0.050150618 0.91179532 0.40757114, + -0.056956608 0.91146213 0.40742207, + -0.055321481 0.91310769 0.40394786, + -0.057881106 0.91297513 0.40388906, + -0.053078901 0.91863698 0.39152101, + -0.053525198 0.91861498 0.39151201, + -0.04977598 0.92384362 0.37951985, + -0.047580793 0.92394286 0.37955993, + -0.044294413 0.92954433 0.36604011, + -0.042033382 0.94273555 0.33088186, + -0.045176014 0.94260633 0.33083612, + -0.041856289 0.94942778 0.31118295, + -0.030533016 0.94981748 0.31131116, + -0.019832497 0.97518188 0.22051497, + -0.012344205 0.97529936 0.22054207, + 0.0054419297 0.99933386 -0.036087796, + 0.0017109505 0.99934721 -0.036088306, + 0.0078153973 0.95168966 -0.30696189, + -0.007346598 0.95169276 -0.30696395, + -0.0013314795 0.99933863 -0.03633929, + -0.0051278519 0.99932635 -0.03633891, + 0.012548106 0.97568345 0.2188251, + 0.019773191 0.97556955 0.21879889, + 0.030551696 0.95014888 0.31029597, + 0.041675396 0.94976687 0.31017098, + -0.79163337 0.57165831 0.2156931, + -0.72609562 0.64332372 0.24273388, + -0.72141182 0.64668983 0.24770394, + -0.65001976 0.70964074 0.27181691, + -0.66790873 0.69934762 0.25457987, + -0.59473032 0.75542939 0.27499512, + -0.62046379 0.74289578 0.2512579, + -0.54630488 0.7934348 0.26835093, + -0.56491238 0.78584146 0.25164914, + -0.49011925 0.8301304 0.26583213, + -0.50288373 0.82600158 0.25461587, + -0.42875615 0.8633343 0.2661241, + -0.43464091 0.8619498 0.26101694, + -0.36249918 0.89198339 0.27011111, + -0.36205217 0.89204741 0.27049911, + -0.29337898 0.91485989 0.27741697, + -0.28611699 0.91520101 0.28380299, + -0.22310993 0.93105465 0.28871992, + -0.211458 0.93043399 0.29929599, + -0.15589593 0.94032162 0.30247587, + -0.14174204 0.93811923 0.3159771, + -0.095059216 0.94339609 0.31775403, + -0.081076123 0.93976927 0.33205509, + -0.042963587 0.94200265 0.33284387, + -0.030625511 0.93750036 0.34663412, + -0.0013644096 0.93793964 0.34679589, + 0.00742525 0.93378901 0.35774699, + 0.028815603 0.9334271 0.35760802, + 0.032339592 0.93138677 0.36259192, + 0.047563877 0.93081957 0.36237082, + 0.049284998 0.92963302 0.36517599, + 0.058778692 0.92915487 0.36498797, + 0.058527485 0.92935878 0.3645089, + 0.063584588 0.92907077 0.36439592, + 0.058820624 0.93356633 0.35354513, + 0.061654806 0.93340611 0.35348502, + 0.058359675 0.93701959 0.34436682, + 0.058072407 0.93703514 0.34437302, + 0.054641809 0.94148827 0.33258709, + 0.051787693 0.94163185 0.33263698, + 0.04877349 0.94637477 0.31936792, + 0.043238178 0.94661653 0.31944886, + 0.031287313 0.94056338 0.3381741, + 0.032891892 0.94051474 0.33815691, + 0.030136907 0.94858623 0.31508109, + 0.018532503 0.94885427 0.31517008, + 0.012071298 0.97478074 0.22283794, + 0.0043310784 0.97484267 0.22285193, + -0.0015409306 0.99938035 -0.035165712, + 0.0018756195 0.99937975 -0.035165694, + -0.0040265401 0.97462499 0.22380801, + -0.011957502 0.97456312 0.22379403, + -0.018454507 0.94839233 0.31656212, + -0.03008501 0.94812435 0.31647313, + -0.032674808 0.94049925 0.3382211, + -0.034632705 0.94043714 0.33819902, + -0.039652199 0.929726 0.36611101, + -0.027794087 0.9227286 0.38444683, + -0.030418508 0.92265826 0.38441709, + -0.02516371 0.93893838 0.34316412, + -0.019830499 0.93905085 0.34320596, + -0.018115299 0.94757789 0.31901097, + -0.0060771308 0.94771612 0.31905702, + -0.0038999682 0.97445154 0.2245639, + 0.0040444699 0.97445101 0.224564, + 0.00620102 0.94795799 0.318335, + 0.018099498 0.9478209 0.31828898, + 0.019869292 0.93903065 0.34325889, + 0.025204388 0.93891752 0.34321785, + 0.030441815 0.92269039 0.38433817, + 0.027712988 0.92276359 0.38436881, + -0.78213573 0.56967282 0.2524609, + -0.71551985 0.6386838 0.28304493, + -0.71468735 0.63921827 0.28394014, + -0.64222407 0.70051605 0.31116802, + -0.64034081 0.7014358 0.31297192, + -0.56579101 0.752994 0.33597699, + -0.5565452 0.75624627 0.34401911, + -0.481971 0.797544 0.36280501, + -0.497953 0.79359698 0.34963799, + -0.42491505 0.82839811 0.36497104, + -0.44830874 0.82425952 0.34585479, + -0.37760007 0.85385013 0.35827103, + -0.39250991 0.85218382 0.34600392, + -0.324763 0.87631798 0.35580301, + -0.33319688 0.87597871 0.34877089, + -0.26877412 0.89488143 0.35629717, + -0.27117005 0.89497024 0.35425308, + -0.21163295 0.90874773 0.35970691, + -0.2093409 0.90847361 0.36173481, + -0.15594397 0.91769278 0.36540592, + -0.14986593 0.9164356 0.37106082, + -0.10349096 0.92192662 0.37328389, + -0.095452316 0.91952109 0.38127407, + -0.056375906 0.92227012 0.38241306, + -0.048706394 0.91922987 0.39069694, + -0.017145397 0.92018676 0.39110392, + -0.0103966 0.91681802 0.39917001, + 0.0138019 0.91677999 0.39915401, + 0.018249389 0.91407347 0.40513775, + 0.036099296 0.91362989 0.40494093, + 0.038047001 0.91221702 0.40793699, + 0.049984802 0.91173702 0.407722, + 0.048724808 0.9128111 0.40546507, + 0.055883985 0.91246879 0.40531191, + 0.053785611 0.91456527 0.40084609, + 0.056998413 0.91440225 0.40077409, + 0.054257382 0.91763163 0.39371085, + 0.054214388 0.91763377 0.39371192, + 0.049788292 0.92382687 0.37955895, + 0.047590394 0.92392588 0.37959993, + 0.0441874 0.92972302 0.36559901, + 0.039805684 0.92989463 0.36566588, + 0.035627212 0.93884933 0.34248012, + 0.046249576 0.9384405 0.34233084, + 0.049527481 0.93305767 0.35630089, + 0.052079018 0.93293637 0.35625511, + 0.055615392 0.92816389 0.36799297, + 0.055396818 0.92817533 0.36799711, + 0.060019422 0.92289639 0.38034216, + 0.057910778 0.92301166 0.38038886, + 0.059646431 0.92131943 0.38420418, + 0.053494319 0.92164135 0.38433814, + 0.054117307 0.9211241 0.38548905, + 0.043162502 0.92161614 0.38569507, + 0.04241021 0.92214823 0.38450509, + 0.026013097 0.92266589 0.38472193, + 0.021019692 0.92563158 0.37784183, + -0.0018932305 0.92583424 0.3779251, + -0.0098829027 0.92970121 0.36818209, + -0.040632591 0.92897874 0.3678959, + -0.050891694 0.93286085 0.35662398, + -0.08963272 0.93031126 0.3556501, + -0.10054997 0.93333364 0.34464189, + -0.14745604 0.92783326 0.3426111, + -0.15762495 0.92965162 0.33301988, + -0.212276 0.91996503 0.32955, + -0.21931793 0.92055565 0.3232289, + -0.2808961 0.90553927 0.31795612, + -0.28268385 0.90552658 0.31640387, + -0.34932089 0.88455969 0.30907789, + -0.34552801 0.88491303 0.31231299, + -0.415685 0.85766101 0.30269399, + -0.40498394 0.8595289 0.31176597, + -0.477662 0.82589298 0.299566, + -0.46045321 0.83021343 0.31421116, + -0.53474593 0.7903049 0.29910696, + -0.50958288 0.79840779 0.3207339, + -0.58418387 0.75312483 0.30254295, + -0.56672513 0.76009417 0.3179301, + -0.64133519 0.7078352 0.29607207, + -0.64824528 0.70424736 0.28950614, + -0.71989167 0.64195973 0.26390088, + -0.72089702 0.64127302 0.262824, + -0.78723967 0.57058471 0.23385189, + -0.77565253 0.58043367 0.24791086, + -0.84962028 0.48500818 0.20715308, + -0.84011912 0.49518806 0.22133403, + -0.89044291 0.41548094 0.18570699, + -0.88862211 0.41790506 0.18896103, + -0.92943966 0.33620289 0.15201794, + -0.92765325 0.33927208 0.15605803, + -0.95906538 0.25727308 0.11834005, + -0.95766562 0.2604889 0.12256496, + -0.97988713 0.18056402 0.084959008, + -0.97858834 0.18480806 0.090614133, + -0.99333364 0.10350297 0.050749183, + -0.99296379 0.10554798 0.053689487, + -0.99932063 0.032848388 0.016709194, + -0.99927467 0.033610187 0.017900795, + -0.99934345 -0.031979416 -0.017032208, + -0.99929237 -0.032792412 -0.018423308, + -0.99399614 -0.095391512 -0.053592507, + -0.99424225 -0.094126225 -0.051212311, + -0.98491663 -0.15198994 -0.082694568, + -0.9866631 -0.14643602 -0.071080409, + -0.97500426 -0.19988304 -0.097023323, + -0.97737598 -0.19423699 -0.083714597, + -0.96386963 -0.24462192 -0.10542996, + -0.96669066 -0.23925892 -0.09090817, + -0.95170701 -0.28698999 -0.109044, + -0.95481789 -0.28208897 -0.093533695, + -0.93837279 -0.32806093 -0.10877698, + -0.94161451 -0.32374784 -0.092462555, + -0.92357963 -0.36866587 -0.10529096, + -0.92680377 -0.36501092 -0.08832708, + -0.90706271 -0.40918586 -0.099016763, + -0.9101519 -0.40619695 -0.081408992, + -0.88877177 -0.44941288 -0.090070181, + -0.89162368 -0.44706085 -0.071719974, + -0.86843014 -0.48955205 -0.078536808, + -0.87091899 -0.487813 -0.0594863, + -0.84554046 -0.52998531 -0.064629041, + -0.84751785 -0.52883387 -0.045257889, + -0.81974488 -0.57064295 -0.048835993, + -0.82113117 -0.56999314 -0.029179607, + -0.79122865 -0.61072069 -0.031264484, + -0.79200584 -0.6104359 -0.0097322185, + -0.78703821 -0.61690414 -0.0004964621, + -0.78709567 -0.61683071 -0.00050021178, + -0.7870363 -0.61678421 -0.012296605, + -0.78697866 -0.61685771 -0.012297994, + -0.75592536 -0.65457529 -0.010392405, + -0.75596589 -0.65461093 0.00038610093, + -0.75588518 -0.65470415 0.0003861021, + -0.75582588 -0.65465295 -0.012523798, + -0.75584215 -0.65463418 -0.012523503, + -0.72493875 -0.68871576 -0.011592996, + -0.72408593 -0.68884593 -0.034509696, + -0.75819969 -0.65120578 -0.032623988, + -0.75658286 -0.65161794 -0.054555692, + -0.78831184 -0.61313087 -0.05133339, + -0.78593445 -0.61397034 -0.073127046, + -0.81565011 -0.57448506 -0.068424009, + -0.81255591 -0.57587993 -0.09008459, + -0.84038419 -0.53547913 -0.083764724, + -0.83670914 -0.53751105 -0.10488001, + -0.86246079 -0.49675587 -0.096927479, + -0.85830343 -0.49950424 -0.11751906, + -0.88224542 -0.4582772 -0.10782005, + -0.87767255 -0.4618338 -0.12806395, + -0.90018731 -0.41966715 -0.11637104, + -0.89528269 -0.42411384 -0.13636896, + -0.91657168 -0.38067585 -0.12240195, + -0.91147971 -0.38604084 -0.14204696, + -0.93146437 -0.34145111 -0.12564005, + -0.926301 -0.347776 -0.144977, + -0.94517475 -0.30142295 -0.12565397, + -0.94006377 -0.30874494 -0.14476398, + -0.95792454 -0.25987187 -0.12184894, + -0.95302188 -0.26821297 -0.14075199, + -0.96997088 -0.21536697 -0.11301999, + -0.96909076 -0.21728295 -0.11683797, + -0.98305899 -0.161431 -0.0868048, + -0.98446602 -0.156901 -0.078796104, + -0.99387854 -0.098727152 -0.049580976, + -0.99435264 -0.09599176 -0.045259785, + -0.99931109 -0.033569206 -0.015827801, + -0.99936026 -0.032671809 -0.014551104, + -0.9992671 0.034967203 0.015573402, + -0.99931902 0.034001801 0.01433, + -0.99328613 0.10660301 0.044927705, + -0.99356723 0.10485803 0.042766713, + -0.98074526 0.18083005 0.073752314, + -0.98139566 0.17843693 0.07087218, + -0.96078002 0.257727 0.102365, + -0.9618299 0.25504097 0.099182881, + -0.93237126 0.33692208 0.13102503, + -0.93369138 0.33440313 0.12804304, + -0.89505631 0.41646716 0.15946606, + -0.89639831 0.41448316 0.15707906, + -0.84824389 0.49523494 0.18768197, + -0.85665613 0.48521805 0.17522502, + -0.78534567 0.58225381 0.21026793, + -0.79327285 0.57480294 0.20079798, + -0.72820175 0.64701974 0.22602592, + -0.74529624 0.63358724 0.20760708, + -0.67670119 0.69965518 0.22925606, + -0.70125723 0.68297327 0.20441608, + -0.63053697 0.743568 0.222553, + -0.64970881 0.73229384 0.20401995, + -0.57645398 0.78715098 0.219304, + -0.59103101 0.77996403 0.205763, + -0.51581407 0.82836014 0.21853003, + -0.52393711 0.82515317 0.21121605, + -0.4485862 0.8658244 0.2216271, + -0.44989893 0.86543888 0.22046897, + -0.37625781 0.89783961 0.2287229, + -0.36992896 0.89903688 0.23427597, + -0.29969499 0.92320502 0.240573, + -0.28731892 0.92421365 0.25154892, + -0.223244 0.94054699 0.25599501, + -0.20654997 0.94007987 0.27126896, + -0.15080199 0.94981086 0.27407697, + -0.13285801 0.94734114 0.29136503, + -0.08680889 0.9522059 0.29286197, + -0.06969519 0.94798088 0.31060398, + -0.03299861 0.94977438 0.31119111, + -0.019540409 0.94499248 0.32650813, + 0.0080197239 0.94514245 0.32656014, + 0.015134407 0.9418695 0.33563814, + 0.035233282 0.94139254 0.33546785, + 0.040075719 0.93865949 0.34250915, + 0.053703588 0.93805873 0.34228891, + 0.055560209 0.93680614 0.34540904, + 0.063872769 0.93633956 0.34523681, + 0.059264291 0.93994987 0.33612797, + 0.065091297 0.93960798 0.33600599, + 0.062459014 0.94198525 0.32979208, + 0.064708382 0.94184977 0.32974491, + 0.061501514 0.94523025 0.3205581, + 0.060694698 0.94527698 0.32057399, + 0.057607975 0.94912052 0.30959886, + 0.054309618 0.94929636 0.30965611, + 0.052640691 0.95183188 0.30206797, + 0.041945413 0.95231426 0.30222207, + 0.027003497 0.97674286 0.21270697, + 0.020186802 0.9769001 0.21274103, + -0.009073467 0.99916565 -0.039819583, + -0.0046741795 0.99919587 -0.039820798, + -0.022883911 0.95115548 -0.30786315, + -0.0071485518 0.95138025 -0.30793607, + -0.012965796 0.81773072 -0.57545483, + 0.013576295 0.81772369 -0.57545084, + 0.0075928573 0.95133764 -0.30805689, + 0.023355495 0.95110577 -0.30798095, + 0.0050218487 0.99921477 -0.039302588, + 0.0093925716 0.99918324 -0.03930131, + -0.020196006 0.97636122 0.21520005, + -0.027272403 0.97619712 0.21516404, + -0.042099796 0.95175385 0.30396098, + -0.052952491 0.95126188 0.30380398, + -0.054225788 0.94932175 0.30959293, + -0.057667024 0.94913846 0.30953315, + -0.060764123 0.94528735 0.32053012, + -0.061419331 0.9452495 0.32051715, + -0.064819388 0.94166279 0.33025691, + -0.062674709 0.94179213 0.33030203, + -0.065073073 0.93962455 0.33596286, + -0.059208523 0.93996835 0.33608612, + -0.061901409 0.93787313 0.34141204, + -0.052903812 0.93835926 0.34158909, + -0.056275785 0.93608177 0.34725192, + -0.04355929 0.93667775 0.34747291, + -0.037404504 0.94020611 0.33854604, + -0.017804109 0.94071549 0.33872914, + -0.0072400565 0.9455955 0.32526386, + 0.020563606 0.94542027 0.3252041, + 0.034161508 0.95021325 0.30972207, + 0.071050078 0.94836563 0.30911887, + 0.08776439 0.95244986 0.29178196, + 0.13411996 0.94750065 0.29026592, + 0.15239307 0.94997048 0.27264011, + 0.20823011 0.94012749 0.26981613, + 0.22504011 0.94054747 0.25441611, + 0.28928787 0.92403358 0.24994887, + 0.30193213 0.92295837 0.23871508, + 0.37220988 0.89857972 0.23240991, + 0.37819892 0.89742476 0.22714394, + 0.4519802 0.86475843 0.21887611, + 0.45020214 0.86528629 0.22044908, + 0.52544278 0.82449156 0.2100559, + 0.51616514 0.82817018 0.21842104, + 0.59126914 0.77980918 0.20566605, + 0.57540989 0.7876128 0.22038494, + 0.64871192 0.73288393 0.20507097, + 0.62875873 0.74454767 0.22430189, + 0.69971365 0.68405569 0.2060789, + 0.67531508 0.70052606 0.23067904, + 0.7441088 0.6345408 0.20894995, + 0.72660279 0.6482138 0.22774394, + 0.79199284 0.57601291 0.20237696, + 0.79656887 0.57161093 0.19682197, + 0.8528803 0.49366117 0.16998206, + 0.85298717 0.49353012 0.16982605, + 0.89980644 0.41254777 0.14195991, + 0.8983779 0.41477394 0.14449799, + 0.93588322 0.33269909 0.11590503, + 0.93445539 0.33556315 0.11912406, + 0.96302938 0.25387409 0.090124227, + 0.96199775 0.25664395 0.093243077, + 0.98199373 0.17755796 0.064509682, + 0.98138112 0.17992401 0.067220211, + 0.99378151 0.10430595 0.038969081, + 0.99353689 0.10590398 0.040851798, + 0.99934453 0.033774886 0.013028493, + 0.99931479 0.034364793 0.013751896, + 0.99936122 -0.033179406 -0.013277503, + 0.99933678 -0.033658691 -0.013895096, + 0.99430627 -0.098497219 -0.040661912, + 0.99424475 -0.098892175 -0.04120189, + 0.98490298 -0.159793 -0.066575304, + 0.98459864 -0.16094995 -0.068269275, + 0.97131479 -0.21891794 -0.092857175, + 0.97052985 -0.22098097 -0.096120588, + 0.95347178 -0.27646095 -0.12025297, + 0.9520731 -0.27918103 -0.12495901, + 0.93169844 -0.33153814 -0.14839308, + 0.92937934 -0.33499512 -0.15502407, + 0.90575802 -0.38460901 -0.177984, + 0.90230685 -0.38860095 -0.18663199, + 0.87542713 -0.43570605 -0.20925502, + 0.87065983 -0.43997189 -0.21994594, + 0.84082133 -0.48418218 -0.24204808, + 0.84500015 -0.48121107 -0.23326103, + 0.8174141 -0.51836103 -0.25126904, + 0.83093441 -0.51026124 -0.22176911, + 0.80341089 -0.54607892 -0.23733696, + 0.81541401 -0.53982699 -0.209014, + 0.78713435 -0.57517332 -0.2227001, + 0.79772019 -0.57049012 -0.19540605, + 0.76848483 -0.60534286 -0.20734295, + 0.7778511 -0.60195106 -0.18056202, + 0.74765301 -0.63608903 -0.19080301, + 0.75586355 -0.63376963 -0.16433589, + 0.72438806 -0.66732305 -0.17303701, + 0.73142606 -0.66589904 -0.14695002, + 0.69824898 -0.699036 -0.154263, + 0.70416623 -0.69833022 -0.12839304, + 0.669038 -0.73097599 -0.134396, + 0.67389804 -0.73081803 -0.10847302, + 0.63720375 -0.7623437 -0.11315196, + 0.64103937 -0.76256245 -0.086989149, + 0.60268575 -0.79283673 -0.090442471, + 0.60552192 -0.7932629 -0.063851692, + 0.56521094 -0.8222869 -0.066187792, + 0.56706518 -0.82274628 -0.039059516, + 0.5245958 -0.85039371 -0.040371984, + 0.525536 -0.85070199 -0.010862, + 0.53602713 -0.84408516 -0.013972904, + 0.53607917 -0.84416729 0.00090149132, + 0.53605598 -0.84418201 0.00090149097, + 0.53600395 -0.84409988 -0.013970798, + 0.53611022 -0.84403241 -0.013969807, + 0.56862807 -0.8225261 -0.010629801, + 0.56766903 -0.82231814 -0.039302904, + 0.60853231 -0.79262435 -0.037883718, + 0.60665894 -0.79235691 -0.064307496, + 0.64545184 -0.76129782 -0.061786685, + 0.64262438 -0.76115549 -0.08761505, + 0.67965925 -0.72871625 -0.083881028, + 0.67588174 -0.72886974 -0.10923696, + 0.711236 -0.695189 -0.10419, + 0.70650506 -0.69580305 -0.12926202, + 0.73981094 -0.66149694 -0.12288898, + 0.73411018 -0.6627292 -0.14789303, + 0.76553112 -0.62795305 -0.14013301, + 0.75882483 -0.62996984 -0.16529596, + 0.78886509 -0.59444404 -0.15597501, + 0.78111315 -0.59742707 -0.18150301, + 0.80998731 -0.56112319 -0.17047405, + 0.80124485 -0.56523293 -0.19626097, + 0.82893282 -0.52840185 -0.18347195, + 0.81918216 -0.53381711 -0.20971404, + 0.84580898 -0.49654299 -0.19507, + 0.83489186 -0.50355893 -0.22222497, + 0.86123186 -0.46494994 -0.20518596, + 0.84913915 -0.47381011 -0.23338106, + 0.87550485 -0.43347794 -0.21351397, + 0.87158227 -0.43687016 -0.22246107, + 0.89943075 -0.3894749 -0.19832696, + 0.9030683 -0.38553315 -0.18929307, + 0.92751056 -0.33553484 -0.16474393, + 0.92996597 -0.33207801 -0.157758, + 0.95097923 -0.27933607 -0.13270202, + 0.95248437 -0.27655309 -0.12764004, + 0.96997935 -0.22080408 -0.10191004, + 0.97077924 -0.21879506 -0.098571524, + 0.98435777 -0.16063195 -0.072367884, + 0.98472285 -0.15929899 -0.070319094, + 0.99419612 -0.098420717 -0.043445602, + 0.99428612 -0.097861014 -0.042641703, + 0.9993369 -0.033379596 -0.014544698, + 0.99934065 -0.033309888 -0.014450395, + 0.99929327 0.034485307 0.014960304, + 0.99931735 0.03403151 0.014375506, + 0.99326462 0.10673596 0.045086887, + 0.99354249 0.10501505 0.04295712, + 0.98067021 0.18110204 0.074080713, + 0.98132509 0.17869902 0.071188509, + 0.96063536 0.2580871 0.10281403, + 0.96172464 0.2553069 0.099518962, + 0.93220335 0.33722112 0.13144904, + 0.93371886 0.33433196 0.12802799, + 0.8950789 0.41641995 0.15946199, + 0.89684486 0.41380495 0.15631598, + 0.84888768 0.49446982 0.18678693, + 0.85025215 0.49287212 0.18479304, + 0.79316539 0.5702433 0.2138021, + 0.79212987 0.57120192 0.21507797, + 0.72667724 0.64291322 0.24208009, + 0.71954823 0.64802325 0.24963209, + 0.64795965 0.71076161 0.27379984, + 0.66653854 0.70014954 0.25596282, + 0.59337765 0.75598854 0.27637681, + 0.61865008 0.74377304 0.25312802, + 0.54427701 0.794173 0.27028099, + 0.5639149 0.78622085 0.25269893, + 0.48898211 0.83045316 0.26691607, + 0.50338495 0.82580286 0.25426996, + 0.42935193 0.86314785 0.26576796, + 0.43641007 0.86147314 0.25963503, + 0.36412802 0.89173013 0.26875302, + 0.36408991 0.89173573 0.26878595, + 0.29549003 0.91469711 0.27570802, + 0.28839493 0.91505575 0.28195995, + 0.22508106 0.93113822 0.28691506, + 0.21326497 0.93054891 0.29765198, + 0.15769202 0.94054413 0.30084902, + 0.14332797 0.93835276 0.31456491, + 0.09626466 0.94373864 0.31637087, + 0.081994221 0.94007325 0.3309671, + 0.043776006 0.94234514 0.33176702, + 0.031743489 0.93798667 0.34521487, + 0.0023232903 0.93845713 0.34538803, + -0.0066796979 0.93423063 0.35660687, + -0.028389391 0.93387467 0.35647187, + -0.034583513 0.93027937 0.36521813, + -0.04923822 0.92970735 0.36499313, + -0.052003227 0.92777842 0.36949018, + -0.060671106 0.92732412 0.36930904, + -0.056448407 0.93075812 0.36125204, + -0.062182523 0.93044037 0.36112911, + -0.058817621 0.93359834 0.35346112, + -0.061624594 0.93343991 0.35340098, + -0.058509573 0.93685758 0.34478182, + -0.058160376 0.93687665 0.34478888, + -0.054639481 0.94145066 0.33269387, + -0.044120003 0.94194114 0.33286703, + -0.049699217 0.93292433 0.35662612, + -0.052210469 0.93280447 0.35658079, + -0.055623986 0.92819577 0.36791092, + -0.055366214 0.92820925 0.36791608, + -0.059017271 0.9240576 0.37766981, + -0.056333594 0.92420089 0.37772894, + -0.060966998 0.91968 0.387907, + -0.055568706 0.9199701 0.38803005, + -0.055467781 0.92005461 0.38784385, + -0.044897903 0.92054415 0.38805005, + -0.042055003 0.92255914 0.38355705, + -0.025611503 0.92307311 0.38377106, + -0.020544093 0.92606962 0.37679285, + 0.0028312714 0.92626143 0.37687117, + 0.010586496 0.92999965 0.36740789, + 0.041386388 0.92925477 0.36711392, + 0.051921718 0.93321937 0.35553613, + 0.090774894 0.93062186 0.35454598, + 0.10206405 0.93371743 0.34315416, + 0.14922705 0.92810935 0.34109312, + 0.15936995 0.92989165 0.33151588, + 0.21418408 0.92007136 0.32801512, + 0.22116406 0.92063522 0.3217411, + 0.28300792 0.90541869 0.31642288, + 0.28441796 0.90540487 0.31519598, + 0.35095909 0.88433522 0.30786207, + 0.34609312 0.88479728 0.31201512, + 0.41633978 0.85745656 0.30237284, + 0.40392107 0.85961813 0.31289703, + 0.47653517 0.82612932 0.30070713, + 0.45868611 0.8305642 0.31586409, + 0.53281289 0.7909658 0.30080494, + 0.50798202 0.798886 0.32207999, + 0.58289403 0.75360799 0.30382499, + 0.56415612 0.76101518 0.32028708, + 0.63890707 0.70904607 0.29841504, + 0.63387406 0.71156508 0.30311504, + 0.72897208 0.62978303 0.26827803, + 0.71675324 0.63790023 0.28168809, + 0.71061701 0.634996 0.302991, + 0.77806264 0.56695271 0.27052388, + 0.77650118 0.5681631 0.27246407, + 0.83703482 0.49335387 0.23658994, + 0.83495229 0.49540618 0.23964009, + 0.88669974 0.41620892 0.20132996, + 0.88450229 0.41896313 0.20524508, + 0.92666191 0.33756596 0.16536899, + 0.9245671 0.34095404 0.17007701, + 0.95728248 0.25874913 0.12907106, + 0.95510721 0.26342905 0.13555603, + 0.98016673 0.17621295 0.090676181, + 0.97930551 0.17889991 0.094633855, + 0.99342334 0.10121103 0.05353862, + 0.99303436 0.10325003 0.05676432, + 0.99931401 0.032452401 0.0178416, + 0.99926823 0.033162907 0.019057203, + 0.99932438 -0.03186661 -0.018312208, + 0.9993521 -0.031440903 -0.017521001, + 0.99442178 -0.092136174 -0.051344387, + 0.99510264 -0.08852987 -0.043968286, + 0.98703176 -0.14376996 -0.071403384, + 0.98834324 -0.13935304 -0.061306916, + 0.97796464 -0.19109492 -0.084069967, + 0.97980189 -0.18650198 -0.072147295, + 0.96748334 -0.23589909 -0.091256529, + 0.9697119 -0.23147596 -0.077960089, + 0.95578891 -0.27867296 -0.093856089, + 0.9582625 -0.27462289 -0.079468764, + 0.94271135 -0.32046211 -0.092733532, + 0.94526374 -0.31694591 -0.077599682, + 0.92795426 -0.36200207 -0.088630825, + 0.93046659 -0.35906583 -0.072826065, + 0.9112857 -0.40355784 -0.08184997, + 0.91365486 -0.40120494 -0.065339394, + 0.89266557 -0.44485879 -0.072448663, + 0.89478689 -0.44307294 -0.055160392, + 0.87182182 -0.48607087 -0.060513485, + 0.87359118 -0.48481613 -0.04232901, + 0.84829456 -0.52751774 -0.046057176, + 0.84959602 -0.52675003 -0.0268532, + 0.8217485 -0.56911135 -0.029012717, + 0.82248461 -0.56873769 -0.0075155464, + 0.84539115 -0.5340631 -0.009513692, + 0.8454293 -0.53408718 -0.00034629513, + 0.84549081 -0.53398991 -0.00035087491, + 0.84545261 -0.53396577 -0.0095121954, + 0.81808686 -0.57505393 -0.006852319, + 0.81810617 -0.5750671 0.00028712105, + 0.81820971 -0.57491982 0.00028712087, + 0.81817091 -0.57489294 -0.0097194491, + 0.81821382 -0.5748319 -0.0097185085, + 0.81825256 -0.57485873 0.00029569786, + 0.79983467 -0.60020769 -0.0039106482, + 0.62061214 0.78411019 -0.0034188309, + 0.61491162 0.78858453 -0.0042678178, + 0.61490566 0.78857654 0.0061698961, + 0.65284902 0.75739402 0.0119339, + 0.65289503 0.75744814 0.00076249411, + 0.65291226 0.7574333 0.00076249329, + 0.65299493 0.75736189 0.00075838389, + 0.68925422 0.72451824 -0.0014307605, + 0.68923515 0.72449815 0.0075772516, + 0.72394776 0.68982178 0.0067511676, + 0.72396374 0.68983775 0.00058712077, + 0.69793767 0.71614861 -0.0037448981, + 0.76786673 0.64059776 -0.0038917686, + 0.78819531 0.61542523 0.00036907016, + 0.78819084 0.61542189 0.0033296593, + 0.78804535 0.61560827 0.0033314317, + 0.78804964 0.61561167 0.00034196384, + 0.78806669 0.61558974 0.00034196489, + 0.7880162 0.6155501 0.011340603, + 0.7921102 0.61030811 0.0092485016, + 0.79182285 0.61035091 0.022097694, + 0.75915581 0.65048283 0.023550594, + 0.75834417 0.65052718 0.041575313, + 0.72318316 0.68925017 0.044050112, + 0.72181219 0.68915421 0.063669316, + 0.68414718 0.72625118 0.067096613, + 0.68212879 0.72586876 0.088401273, + 0.64260119 0.7605812 0.092628926, + 0.63986808 0.75973612 0.11562801, + 0.59867579 0.79187268 0.12051895, + 0.59518379 0.79036272 0.14519995, + 0.5522849 0.81993383 0.15063196, + 0.5480147 0.81752753 0.1769989, + 0.50356495 0.84439391 0.18281499, + 0.49855593 0.84084886 0.21074897, + 0.45361412 0.86445916 0.21666704, + 0.44801578 0.85960561 0.24568288, + 0.402933 0.87999302 0.25150999, + 0.3968901 0.87366116 0.28141505, + 0.351946 0.89094102 0.28698099, + 0.345651 0.88300699 0.31752801, + 0.30117705 0.89731526 0.32267308, + 0.29486006 0.88771427 0.3535831, + 0.25181592 0.89908069 0.35810989, + 0.24571203 0.88781309 0.38911906, + 0.20445704 0.89654422 0.39294508, + 0.19877507 0.8836143 0.42392716, + 0.15955994 0.8900547 0.42701685, + 0.15453398 0.87556785 0.45771194, + 0.11750094 0.88007456 0.46006778, + 0.11334296 0.86417568 0.49025881, + 0.07909546 0.86705559 0.49189276, + 0.076020353 0.85019046 0.52095771, + 0.044450913 0.85181516 0.52195311, + 0.042563718 0.83423543 0.54976326, + 0.013524993 0.83491558 0.55021179, + 0.012888702 0.8167851 0.57679808, + -0.013581402 0.81677812 0.57679206, + -0.014217107 0.83491445 0.55019623, + -0.043227624 0.83421844 0.54973722, + -0.045114711 0.85180116 0.52191913, + -0.076704204 0.85015714 0.52091205, + -0.079774708 0.8670001 0.49188107, + -0.11399395 0.8641026 0.49023676, + -0.11813206 0.87993544 0.46017221, + -0.15514494 0.87541068 0.45780584, + -0.16015296 0.88985878 0.42720291, + -0.19931696 0.88340688 0.42410493, + -0.20497796 0.89630377 0.39322191, + -0.24616504 0.88756913 0.38938907, + -0.25226611 0.89884442 0.35838619, + -0.29521894 0.88748574 0.35385692, + -0.30153093 0.89709377 0.3229579, + -0.34595597 0.88278687 0.31780797, + -0.35227317 0.89076239 0.28713414, + -0.39719009 0.87347716 0.28156307, + -0.40326583 0.87985057 0.25147489, + -0.44829807 0.8594681 0.24564902, + -0.45395306 0.86437315 0.21630003, + -0.49891993 0.84072489 0.21038197, + -0.50398707 0.84430712 0.18205102, + -0.54842484 0.81741369 0.17625295, + -0.55271107 0.81981909 0.14969002, + -0.59561026 0.79020929 0.14428404, + -0.5990811 0.7916972 0.11965503, + -0.6402728 0.75952184 0.11479197, + -0.64295018 0.76034015 0.092184521, + -0.68244517 0.72562319 0.08797542, + -0.68439776 0.72599179 0.067348175, + -0.72200644 0.68892843 0.06390994, + -0.72331619 0.6890282 0.045320012, + -0.75844401 0.65033299 0.042774901, + -0.75921953 0.65031159 0.026084386, + -0.7918399 0.61023796 0.024476996, + -0.7921468 0.61021489 0.011889197, + -0.78997272 0.61300379 0.013018295, + -0.79003954 0.61305565 0.00051308068, + -0.79001987 0.61308092 0.00051308091, + -0.78990668 0.61322677 0.0004920268, + -0.76786703 0.640598 -0.0038019801, + -0.82967287 0.55823594 -0.0039262897, + -0.87131572 0.49059483 0.011211396, + -0.8713702 0.49062613 -0.00026725806, + -0.87142271 0.49053282 -0.00027135291, + -0.87136799 0.490502 0.0112089, + -0.846187 0.53273201 0.0128149, + -0.85041779 0.52586186 0.016090496, + -0.84620416 0.53257513 0.017387304, + -0.84633183 0.53265589 0.00023593094, + -0.8462562 0.53277612 0.00023593106, + -0.84637946 0.53258032 0.00026248716, + -0.84630984 0.53253686 0.012809597, + -0.82482219 0.56513911 0.016918404, + 0.79056501 0.61121798 0.037676401, + 0.78944236 0.61139327 0.054581326, + 0.75626767 0.65167069 0.058176976, + 0.75455689 0.65172893 0.07676769, + 0.71876574 0.69047874 0.081331968, + 0.71635377 0.69027674 0.10176096, + 0.67804515 0.72716117 0.10719802, + 0.67484325 0.72651625 0.12946305, + 0.63464421 0.76081932 0.13557604, + 0.63057625 0.75951529 0.15971906, + 0.58878291 0.79099083 0.16633795, + 0.58383095 0.78878886 0.19223297, + 0.54040498 0.81747901 0.19922499, + 0.53461677 0.81414157 0.22662389, + 0.48994184 0.83982569 0.2337729, + 0.48340613 0.83511215 0.26250005, + 0.43853781 0.85735559 0.26949188, + 0.4314118 0.85107559 0.29925585, + 0.38678595 0.86995685 0.30589497, + 0.37927216 0.86196929 0.33639511, + 0.33518893 0.87768078 0.34252691, + 0.32749289 0.86785072 0.37360889, + 0.28432909 0.8805933 0.37909415, + 0.276741 0.86891598 0.41036499, + 0.23545709 0.87880832 0.41503716, + 0.22820093 0.86525369 0.44638586, + 0.189209 0.87265003 0.45020199, + 0.18257402 0.85737514 0.48122206, + 0.14596197 0.86269283 0.48420689, + 0.14026499 0.84608287 0.51426595, + 0.10621803 0.84969616 0.5164631, + 0.10164298 0.83201182 0.54536688, + 0.070631079 0.83425468 0.54683679, + 0.067285903 0.81571102 0.57453299, + 0.039132886 0.81693769 0.57539684, + 0.037092384 0.79774672 0.60185075, + 0.011782393 0.79824054 0.60222363, + 0.011096899 0.77852786 0.62751192, + -0.011653899 0.77852291 0.62750793, + -0.012341196 0.79827869 0.60216177, + -0.037730299 0.79777098 0.60177898, + -0.039772484 0.81697369 0.57530183, + -0.067946389 0.81573087 0.57442695, + -0.071291104 0.83426911 0.54672909, + -0.10231598 0.83200788 0.54524696, + -0.10687695 0.84964359 0.51641375, + -0.14095996 0.8460058 0.51420289, + -0.14663696 0.8625688 0.48422387, + -0.18321596 0.85723382 0.48122987, + -0.189821 0.87244898 0.45033401, + -0.22876211 0.86504143 0.4465102, + -0.23598894 0.87855375 0.4152739, + -0.2771779 0.8686657 0.41059986, + -0.28474995 0.88033074 0.37938792, + -0.3278501 0.8675912 0.37389809, + -0.33552191 0.87740475 0.34290791, + -0.3795549 0.86169881 0.33676893, + -0.38708785 0.86971873 0.30618989, + -0.431633 0.85086 0.29955, + -0.43878099 0.85716897 0.26969001, + -0.48365787 0.83490783 0.26268595, + -0.49022993 0.83965391 0.23378597, + -0.53489494 0.81395686 0.22663097, + -0.54075485 0.8173368 0.19885896, + -0.58413088 0.78865284 0.19187996, + -0.58915961 0.79088247 0.16551688, + -0.63093883 0.75938082 0.15892395, + -0.63502401 0.76067901 0.134581, + -0.67521703 0.72633904 0.12850502, + -0.67838722 0.72696626 0.10635204, + -0.71668637 0.69005036 0.10095204, + -0.71904594 0.69023895 0.080889791, + -0.75478911 0.65150905 0.076351009, + -0.75643814 0.65145105 0.058420707, + -0.7895813 0.61119324 0.05481052, + -0.79064965 0.61103469 0.038855281, + -0.82141811 0.56917703 0.036193606, + -0.82201314 0.56902504 0.022473002, + -0.79165918 0.6104871 0.024110505, + -0.79096448 0.61058533 0.039506923, + -0.75810766 0.6507687 0.042106882, + -0.75691372 0.65081078 0.059387676, + -0.72150165 0.68954766 0.06292247, + -0.71969396 0.68940991 0.082187191, + -0.68173409 0.72645605 0.086603709, + -0.67920017 0.72597015 0.10795602, + -0.63938272 0.76052564 0.11309495, + -0.63603395 0.75948387 0.13654698, + -0.59454489 0.79137385 0.14228097, + -0.59032786 0.78953785 0.16775896, + -0.54718512 0.81873417 0.17396204, + -0.54208899 0.81583601 0.201373, + -0.49753171 0.84217054 0.20787288, + -0.49171907 0.83801514 0.23652303, + -0.44679806 0.86099809 0.24301003, + -0.44041285 0.85540873 0.27260292, + -0.39560592 0.87505978 0.27886593, + -0.38882083 0.86788857 0.30917284, + -0.34427798 0.88442487 0.31506398, + -0.33730587 0.87556571 0.34584588, + -0.29351106 0.88910824 0.3511951, + -0.28657985 0.87849659 0.38225082, + -0.24446706 0.88913423 0.3868801, + -0.237818 0.87677699 0.41797701, + -0.19768597 0.88486087 0.42183095, + -0.19155601 0.870821 0.45274401, + -0.15361995 0.87671971 0.45581084, + -0.14824201 0.8611201 0.48630905, + -0.112665 0.865197 0.48861101, + -0.10830098 0.84841383 0.51813591, + -0.075646929 0.85098827 0.51970816, + -0.072442807 0.83332109 0.54802203, + -0.042502582 0.83476156 0.54896873, + -0.040536996 0.8163749 0.57609797, + -0.0133083 0.81697398 0.57652098, + -0.012647802 0.79804814 0.60246104, + 0.012030507 0.79805446 0.60246533, + 0.012688106 0.8169294 0.57659829, + 0.039889883 0.81634468 0.57618582, + 0.041857589 0.83476382 0.54901487, + 0.071738392 0.83334386 0.54807997, + 0.074947588 0.85103381 0.51973486, + 0.10763198 0.84847581 0.51817387, + 0.11200196 0.86527872 0.48861882, + 0.14759493 0.8612206 0.48632777, + 0.15299793 0.87688559 0.45570078, + 0.19096592 0.87100267 0.45264384, + 0.19712108 0.88508743 0.42162022, + 0.23730797 0.8770119 0.41777393, + 0.24398409 0.8894043 0.38656414, + 0.28614897 0.87877089 0.38194293, + 0.29309502 0.8893891 0.35083103, + 0.33698398 0.87583286 0.34548298, + 0.3439481 0.88466722 0.31474409, + 0.38850999 0.86813802 0.30886301, + 0.39527506 0.87527311 0.27866602, + 0.44016913 0.85559815 0.27240205, + 0.44651005 0.86114013 0.24303603, + 0.4914543 0.83816248 0.23655114, + 0.49719617 0.84226429 0.20829508, + 0.54176682 0.81594771 0.20178692, + 0.54680294 0.81881887 0.17476298, + 0.58993322 0.7896663 0.16854106, + 0.59413695 0.7915079 0.14323598, + 0.63562071 0.75966263 0.13747394, + 0.63899368 0.76072264 0.11396595, + 0.67885321 0.72617024 0.10878903, + 0.68144029 0.72667533 0.087075941, + 0.71941996 0.68964195 0.082638294, + 0.72129583 0.68978679 0.062661082, + 0.75674289 0.65103191 0.059140492, + 0.75799364 0.6509797 0.040879283, + 0.79089189 0.61075294 0.038353097, + 0.7916199 0.61062896 0.021686198, + 0.82199085 0.56914186 0.020212794, + 0.82136601 0.56932098 0.035093799, + 0.82426244 0.56469029 0.041429818, + 0.84939849 0.52633733 0.038616024, + 0.85040081 0.52594787 0.014044296, + 0.8435244 0.53684962 0.016094988, + 0.84363389 0.53691894 2.4934696e-005, + 0.84458411 0.53542304 2.4931303e-005, + 0.84454614 0.53539908 0.0094767408, + 0.84456891 0.53536296 0.009475939, + 0.84460688 0.53538692 2.9872697e-005, + 0.82967281 0.55823588 -0.0039639492, + 0.88268256 0.46996975 -4.0929881e-005, + 0.86978883 0.49335489 -0.0082656182, + 0.86979568 0.49334282 -0.0082618268, + 0.89294428 0.45016715 -0.00037987615, + 0.89297813 0.45010006 -0.00037107407, + 0.89295626 0.45009011 0.0069436417, + 0.89292288 0.45015594 0.0069450391, + 0.87608558 0.48197675 0.013133493, + 0.8752566 0.48240876 0.034751985, + 0.84878099 0.52737802 0.037991598, + 0.84713686 0.52808493 0.059036691, + 0.8179031 0.57179403 0.063923106, + 0.81616086 0.57224393 0.080115095, + 0.7843492 0.61432815 0.086006925, + 0.78189129 0.61465621 0.10413404, + 0.74754423 0.65488023 0.11094803, + 0.74423903 0.65492707 0.13106802, + 0.70717782 0.6932888 0.13874497, + 0.70289916 0.69284719 0.16092105, + 0.66324103 0.72900099 0.169319, + 0.65791923 0.72782326 0.19343108, + 0.6164819 0.76095384 0.20223595, + 0.61009908 0.7587741 0.22812504, + 0.56728214 0.78865117 0.23710807, + 0.55984485 0.78518581 0.26468295, + 0.51583594 0.81180388 0.27365598, + 0.50744122 0.80677533 0.30268314, + 0.46263 0.83005601 0.31141701, + 0.45343801 0.82321 0.34164199, + 0.40905493 0.84281087 0.34977698, + 0.39927894 0.83395088 0.38092294, + 0.35591888 0.85003972 0.38827085, + 0.34581608 0.83901918 0.4200691, + 0.30374604 0.85194111 0.42653805, + 0.29368386 0.8387776 0.4584778, + 0.25329494 0.84885681 0.46398687, + 0.24372497 0.83379591 0.49536094, + 0.20601603 0.84127909 0.49980706, + 0.19721909 0.8245014 0.53037924, + 0.162378 0.82985801 0.53382498, + 0.15462901 0.81167603 0.56326902, + 0.12272697 0.81534684 0.56581587, + 0.11617804 0.79591531 0.59415627, + 0.087326504 0.79828012 0.59592205, + 0.082132541 0.77786738 0.62303829, + 0.05658618 0.77925372 0.62414879, + 0.052818298 0.758039 0.65006697, + 0.030468693 0.75874585 0.65067381, + 0.0281852 0.736911 0.67540199, + 0.0088891014 0.73717517 0.67564321, + 0.0081297625 0.71494025 0.69913822, + -0.0083658295 0.71493894 0.69913691, + -0.0091295261 0.73728079 0.67552477, + -0.028589897 0.73700994 0.67527694, + -0.030880095 0.75890487 0.65046895, + -0.053311907 0.75818712 0.64985406, + -0.057082817 0.77941328 0.62390423, + -0.082740352 0.77800947 0.62278038, + -0.087933607 0.79841113 0.59565705, + -0.11683901 0.79602611 0.59387803, + -0.12338007 0.81543046 0.56555337, + -0.15532891 0.81173551 0.56299067, + -0.163057 0.82986701 0.53360403, + -0.19790304 0.8244881 0.53014505, + -0.20664811 0.84116542 0.49973723, + -0.24440494 0.83364981 0.49527189, + -0.25393289 0.84864759 0.46402079, + -0.29421493 0.8385728 0.45851189, + -0.30422902 0.85168213 0.42671105, + -0.346237 0.83876097 0.42023799, + -0.35628501 0.84973502 0.38860199, + -0.3996219 0.83364081 0.38124192, + -0.40936416 0.84248531 0.35019913, + -0.45366266 0.82291138 0.34206277, + -0.46285099 0.82976902 0.31185299, + -0.50760204 0.80651313 0.30311203, + -0.51600289 0.81155682 0.27407393, + -0.55998802 0.78494698 0.26508799, + -0.56747121 0.78844428 0.23734409, + -0.61024624 0.75858629 0.22835608, + -0.61669427 0.76079333 0.20219208, + -0.658095 0.72767502 0.193391, + -0.66349095 0.72886992 0.16890399, + -0.7031188 0.69271582 0.16052596, + -0.70746422 0.69315726 0.13794005, + -0.74451822 0.65476322 0.13029905, + -0.74784076 0.65470475 0.10998196, + -0.78215814 0.61447006 0.10322402, + -0.78458631 0.61413527 0.085219428, + -0.81636286 0.57205796 0.07938049, + -0.81806183 0.57161188 0.063519485, + -0.84726757 0.52791679 0.058663972, + -0.848324 0.52750498 0.0456613, + -0.8198275 0.57047737 0.049381129, + -0.81852901 0.57082403 0.064577103, + -0.7871471 0.61285603 0.069332205, + -0.7852158 0.61313486 0.086613275, + -0.75134516 0.65342218 0.092304423, + -0.74864274 0.65349078 0.11173096, + -0.71207297 0.69206291 0.11832599, + -0.70844895 0.69172597 0.14005499, + -0.66930932 0.72820735 0.14744207, + -0.66466391 0.72721893 0.17138998, + -0.62369531 0.76082337 0.17931008, + -0.61804777 0.75893569 0.20502092, + -0.57560688 0.78942883 0.21325795, + -0.56899697 0.78639287 0.24047597, + -0.52516991 0.81379783 0.24885695, + -0.51767009 0.8093552 0.27742007, + -0.47295195 0.83348489 0.28569096, + -0.46468905 0.82738709 0.31542802, + -0.42012492 0.84793681 0.32326192, + -0.41131008 0.84001219 0.3538411, + -0.3674691 0.85709816 0.3610391, + -0.35832399 0.84719998 0.39224499, + -0.31553686 0.86109859 0.39867982, + -0.30632594 0.8491438 0.43025491, + -0.26499006 0.86013716 0.43582609, + -0.25604895 0.84616882 0.46737289, + -0.21703798 0.8544839 0.47196594, + -0.20875303 0.83878911 0.50284708, + -0.172443 0.84483701 0.50647199, + -0.16508301 0.82767397 0.53637999, + -0.13151105 0.83189929 0.53911817, + -0.12526602 0.81348109 0.56794107, + -0.094503015 0.81627011 0.56988806, + -0.089529604 0.79684103 0.59751898, + -0.062014479 0.79851371 0.59877378, + -0.058385979 0.77819669 0.62530077, + -0.033988912 0.77907628 0.62600726, + -0.03178281 0.75810528 0.65135723, + -0.010259097 0.75844884 0.6516518, + -0.0095202541 0.73694956 0.67588061, + 0.0091521107 0.73695207 0.67588305, + 0.0098870276 0.75836784 0.65175182, + 0.031272795 0.75803387 0.65146494, + 0.033475608 0.7789852 0.62614816, + 0.057802483 0.77811885 0.6254518, + 0.061421692 0.79838389 0.59900796, + 0.088906102 0.796727 0.59776402, + 0.093886815 0.81618613 0.57011008, + 0.12459201 0.8134191 0.56817806, + 0.13085295 0.83188671 0.53929782, + 0.16438393 0.82768673 0.53657484, + 0.17177902 0.8449291 0.50654405, + 0.20812903 0.8388961 0.50292706, + 0.2164399 0.8546356 0.47196576, + 0.25544095 0.84634483 0.46738687, + 0.2644411 0.86039728 0.43564615, + 0.30584207 0.84940618 0.4300811, + 0.31509584 0.86140859 0.39835882, + 0.3579641 0.84749919 0.39192709, + 0.36713108 0.85740715 0.36064908, + 0.41102085 0.84031469 0.35345888, + 0.41985521 0.84824139 0.32281315, + 0.46446595 0.82767987 0.31498796, + 0.47270694 0.83374786 0.28532898, + 0.51753104 0.80956912 0.27705503, + 0.52499694 0.81398088 0.24862297, + 0.56881702 0.78658998 0.24025699, + 0.57536697 0.78959203 0.213301, + 0.61783707 0.75909615 0.20506203, + 0.62341094 0.76095891 0.17972298, + 0.66440701 0.72736001 0.17178699, + 0.66898584 0.72833985 0.14825296, + 0.7081508 0.69187385 0.14082997, + 0.71175617 0.69222015 0.11930803, + 0.74833393 0.65368396 0.11266599, + 0.75106567 0.65362573 0.093133755, + 0.78497618 0.61333114 0.08739242, + 0.78695387 0.61305392 0.06977459, + 0.81837457 0.57099873 0.064988069, + 0.81965786 0.57066292 0.050049093, + 0.78901398 0.61202598 0.053676799, + 0.78747714 0.61225206 0.070903905, + 0.75397921 0.65253717 0.075569317, + 0.75177169 0.65259778 0.094632864, + 0.71560895 0.69127095 0.10024098, + 0.7126298 0.69100285 0.12113597, + 0.67390484 0.7277208 0.12757197, + 0.67004275 0.72691977 0.15043394, + 0.62944484 0.76092184 0.15747096, + 0.6246419 0.75935185 0.18222895, + 0.58252293 0.79037386 0.18967398, + 0.57678413 0.78778416 0.21613905, + 0.53316706 0.81586009 0.22384202, + 0.52657217 0.8120113 0.2517131, + 0.48178077 0.8369996 0.25945887, + 0.47442505 0.83164209 0.28860402, + 0.42964101 0.853091 0.29604799, + 0.42169595 0.84602886 0.32620198, + 0.37740806 0.8640461 0.33314803, + 0.36907604 0.85511911 0.36408004, + 0.32555988 0.86995268 0.37039587, + 0.31711692 0.85909081 0.40174592, + 0.27479288 0.87097257 0.4073028, + 0.26649487 0.85811257 0.43888879, + 0.22627997 0.86721689 0.44354495, + 0.21844496 0.85248083 0.47492987, + 0.18072991 0.85919261 0.47866976, + 0.17371206 0.84293127 0.50920618, + 0.13856798 0.84768689 0.51207995, + 0.13259295 0.83016461 0.54152179, + 0.10016398 0.8333478 0.54359788, + 0.095383786 0.81477386 0.57187897, + 0.066118091 0.81671488 0.57324094, + 0.062633216 0.79729819 0.60032713, + 0.036368612 0.79833829 0.60111022, + 0.034252495 0.77832389 0.62692791, + 0.010831896 0.77873468 0.62725979, + 0.010120794 0.75817752 0.65196961, + -0.010596101 0.75817412 0.65196604, + -0.011309703 0.7787922 0.62718016, + -0.034818392 0.77836984 0.62683982, + -0.036940191 0.79841679 0.60097086, + -0.063301302 0.79736 0.60017502, + -0.066779882 0.81673485 0.57313585, + -0.096087985 0.81477386 0.57176095, + -0.10086104 0.83332229 0.54350817, + -0.13331103 0.83011717 0.54141814, + -0.13927199 0.8476029 0.51202792, + -0.17438391 0.84282959 0.50914478, + -0.18138094 0.85904372 0.47869083, + -0.21905193 0.85231769 0.47494283, + -0.22685207 0.86699528 0.44368616, + -0.26701608 0.85788232 0.43902215, + -0.27526906 0.87068319 0.40760008, + -0.31753996 0.85879886 0.40203595, + -0.32596186 0.86964661 0.37076083, + -0.36939913 0.85482532 0.36444211, + -0.37771586 0.8637507 0.33356488, + -0.4219448 0.84574658 0.32661185, + -0.4299019 0.85283279 0.29641294, + -0.47466511 0.83138216 0.28895807, + -0.48205301 0.83677399 0.25968099, + -0.52674121 0.8118313 0.2519401, + -0.53340405 0.8157261 0.22376603, + -0.57700533 0.78764337 0.2160621, + -0.58280408 0.79026109 0.18928003, + -0.624937 0.759202 0.181841, + -0.62980598 0.76078898 0.15666699, + -0.6703828 0.72676581 0.14966097, + -0.67426395 0.72756094 0.12658298, + -0.71296304 0.69082403 0.12019102, + -0.71591604 0.69107807 0.099375218, + -0.7520541 0.65239108 0.093812115, + -0.7542063 0.65232426 0.07514023, + -0.78768599 0.61203003 0.070498802, + -0.78916287 0.61181194 0.053925894, + -0.82020956 0.56985372 0.050227679, + -0.82114768 0.5696038 0.035608288, + -0.84975868 0.5261448 0.03289149, + -0.85207415 0.52202308 0.038230103, + -0.87528926 0.48230812 0.035321608, + -0.87608171 0.48191983 0.015299194, + -0.89435577 0.44725087 0.0097155683, + -0.89435875 0.44724488 0.0097154081, + -0.89440101 0.44726601 -0.000107601, + -0.89439797 0.447272 -0.00010842, + -0.88267571 0.46996582 -0.0039765588, + -0.93389934 0.35747311 0.0067181122, + -0.93392026 0.35748109 -0.00052070414, + -0.93389839 0.35753819 -0.00052847521, + -0.93387741 0.35753018 0.0067195734, + -0.92002267 0.39166185 0.012621395, + -0.91951925 0.39206707 0.027711108, + -0.89816326 0.43856812 0.030997707, + -0.89666528 0.43959415 0.052425619, + -0.8752023 0.48035318 0.05728652, + 0.0044913692 0.64613384 0.76321083, + 0.0032846187 0.60971779 0.79261172, + -0.0032387592 0.60971791 0.79261184, + -0.0048428108 0.6579842 0.75301617, + -0.017245201 0.65789407 0.75291312, + -0.02087909 0.69348067 0.72017264, + -0.036896721 0.6931594 0.71983939, + -0.041069612 0.71709919 0.69576019, + -0.060466591 0.71639097 0.69507396, + -0.066333614 0.73987317 0.66946816, + -0.089355305 0.73854005 0.66826206, + -0.096798576 0.76104283 0.64143884, + -0.12322508 0.75880647 0.63955337, + -0.13214503 0.78015119 0.61147511, + -0.16193296 0.77666581 0.60874289, + -0.17212498 0.79651988 0.57959396, + -0.20537101 0.79135197 0.57583398, + -0.21666002 0.80954009 0.54562205, + -0.25311804 0.8022331 0.54069704, + -0.2652221 0.81849831 0.5096252, + -0.30428705 0.80864519 0.50349009, + -0.31687191 0.82280183 0.47179389, + -0.35805002 0.80999213 0.46444905, + -0.3707591 0.82192719 0.4324041, + -0.41382599 0.80566698 0.42385, + -0.42622691 0.81528485 0.3919709, + -0.47056523 0.79523134 0.38232917, + -0.48218787 0.80253184 0.3513369, + -0.52649516 0.77881527 0.34095412, + -0.53703898 0.78402299 0.31128299, + -0.58072573 0.75664365 0.30041286, + -0.59003723 0.76007229 0.2722981, + -0.63283426 0.72892225 0.26113808, + -0.64080691 0.73089492 0.23485997, + -0.68206179 0.6962328 0.22372194, + -0.68871534 0.69708735 0.19935009, + -0.72750705 0.65965605 0.18864603, + -0.73288107 0.65971005 0.16633701, + -0.76891768 0.61994576 0.15630995, + -0.77313119 0.61948013 0.13606103, + -0.80646813 0.57751209 0.12684302, + -0.80965102 0.576756 0.10871, + -0.84023571 0.53283882 0.10043296, + -0.84251285 0.53198886 0.08461678, + -0.86990511 0.48709607 0.077476308, + -0.87133318 0.48636013 0.065055415, + -0.84491372 0.53018081 0.070916779, + -0.84306782 0.53088689 0.08599858, + -0.8130191 0.57474506 0.093103208, + -0.81037784 0.57539791 0.11047697, + -0.77763289 0.61744094 0.11854898, + -0.77403289 0.61787492 0.13821599, + -0.73861492 0.65786892 0.14716199, + -0.73395699 0.657866 0.16887701, + -0.69579619 0.69568318 0.17858504, + -0.68997592 0.69498897 0.20229597, + -0.64928108 0.73024207 0.21255703, + -0.64223915 0.7285642 0.23816606, + -0.59992993 0.76045185 0.24858998, + -0.59165609 0.7574811 0.27598104, + -0.54826915 0.78577328 0.2862891, + -0.53882623 0.78119934 0.31526816, + -0.49457493 0.80597585 0.32526696, + -0.48412377 0.79951364 0.35553083, + -0.43959087 0.82071084 0.36495692, + -0.42831492 0.81208283 0.3963179, + -0.38472116 0.82952029 0.40482816, + -0.37296617 0.81861144 0.43677419, + -0.33093408 0.83255917 0.44421613, + -0.31916198 0.81945086 0.47606295, + -0.27899197 0.83033991 0.48238894, + -0.26758802 0.81515211 0.51373506, + -0.22973096 0.82337588 0.51891792, + -0.21904702 0.8063001 0.54945308, + -0.18420799 0.8122279 0.55349195, + -0.17449501 0.79344809 0.58308804, + -0.14292201 0.7975381 0.58609408, + -0.13442305 0.77734232 0.61454827, + -0.10602999 0.78003991 0.61668092, + -0.098889187 0.75859791 0.64401096, + -0.073839009 0.76025313 0.64541703, + -0.068196021 0.73781222 0.67155224, + -0.046622802 0.73873001 0.672387, + -0.042555302 0.71554607 0.69726807, + -0.024297597 0.71598291 0.69769496, + -0.021871205 0.69250017 0.7210862, + -0.0068155988 0.69264984 0.72124183, + -0.0056390301 0.65760702 0.75334001, + -0.0074257283 0.65759981 0.75333083, + 0.8127979 0.57491195 0.093999088, + 0.81017429 0.57555115 0.11116904, + 0.777394 0.61759901 0.11929, + 0.773853 0.61801898 0.138579, + 0.73842192 0.65799993 0.14754398, + 0.73382902 0.657996 0.168927, + 0.69563216 0.69583321 0.17864004, + 0.68987209 0.69515008 0.20209603, + 0.64915997 0.73041093 0.21234697, + 0.64217472 0.72875464 0.23775688, + 0.59982902 0.76066899 0.248169, + 0.59158206 0.75772011 0.27548304, + 0.54810894 0.78606689 0.28578898, + 0.53867322 0.78151035 0.31475815, + 0.49436018 0.80631632 0.32474911, + 0.48387101 0.79984599 0.35512701, + 0.43928799 0.82105601 0.36454499, + 0.42795491 0.81239885 0.39605892, + 0.38432607 0.8298341 0.40456006, + 0.37248009 0.81884819 0.43674508, + 0.3303839 0.83279485 0.44418389, + 0.31853691 0.81960583 0.47621489, + 0.27839509 0.83046228 0.48252317, + 0.26692894 0.81518984 0.51401788, + 0.22903992 0.82339573 0.5191918, + 0.21831207 0.80624431 0.54982716, + 0.18351902 0.81214112 0.55384809, + 0.17377606 0.79329032 0.58351725, + 0.14226897 0.79735285 0.58650488, + 0.13374206 0.77707833 0.61503029, + 0.10548998 0.77974784 0.61714286, + 0.098354504 0.75830901 0.64443302, + 0.073376484 0.75994885 0.64582783, + 0.067736767 0.73751265 0.67192769, + 0.04630851 0.73841721 0.6727522, + 0.042251613 0.71528816 0.69755119, + 0.024190506 0.71571815 0.69797015, + 0.021781605 0.69240916 0.72117621, + 0.0068389792 0.69255692 0.72133094, + 0.0060628708 0.66959006 0.74270606, + 0.018412896 0.66948885 0.74259382, + 0.020860413 0.69331944 0.72032839, + 0.036740094 0.69300193 0.71999896, + 0.040875427 0.71672744 0.69615442, + 0.060146131 0.71602833 0.69547534, + 0.065992892 0.73944294 0.66997695, + 0.088860154 0.73812664 0.66878468, + 0.096318662 0.76068968 0.64192975, + 0.12259605 0.75847828 0.64006323, + 0.13151297 0.77982682 0.6120249, + 0.16118494 0.77637368 0.60931379, + 0.171426 0.79633498 0.580055, + 0.20461507 0.79119831 0.57631415, + 0.21594387 0.80945653 0.54602969, + 0.25237191 0.80218172 0.54112184, + 0.26455104 0.81855112 0.50988907, + 0.30359897 0.80872887 0.50377095, + 0.31624508 0.8229562 0.47194511, + 0.35748002 0.81015509 0.46460405, + 0.37027103 0.82216412 0.43237206, + 0.41339681 0.80590266 0.42382079, + 0.42587987 0.81557769 0.39173886, + 0.47023088 0.79553384 0.38211092, + 0.48192883 0.80286968 0.35091987, + 0.52631295 0.77911991 0.34053898, + 0.53688723 0.78432834 0.31077516, + 0.58064216 0.75690728 0.29991013, + 0.58995402 0.76032299 0.27177799, + 0.63276327 0.72916222 0.26064008, + 0.64071983 0.7311188 0.23439994, + 0.68200803 0.696428 0.223278, + 0.68859935 0.69726634 0.1991251, + 0.72743392 0.65979993 0.18842497, + 0.73274696 0.65984893 0.16637698, + 0.76880229 0.62007922 0.15634906, + 0.7729528 0.61962086 0.13643298, + 0.80632102 0.57764101 0.12718999, + 0.80945009 0.57690507 0.10941301, + 0.83913261 0.53440076 0.10135195, + 0.83672571 0.5352568 0.11571596, + 0.80552632 0.57918018 0.12521105, + 0.80185485 0.5800119 0.14357898, + 0.76782387 0.62188995 0.15394598, + 0.76301068 0.62237877 0.17452595, + 0.726273 0.66187602 0.185601, + 0.7201612 0.66176516 0.20841004, + 0.68067294 0.69875497 0.22005898, + 0.67314625 0.69772923 0.24504709, + 0.63123882 0.7317698 0.25700295, + 0.62222201 0.72946602 0.28411099, + 0.57894468 0.75977463 0.29591486, + 0.56846607 0.75582713 0.32491803, + 0.52445704 0.78222209 0.33626404, + 0.51261306 0.7762621 0.36694002, + 0.46821922 0.79885733 0.37762117, + 0.45529187 0.79060584 0.40945292, + 0.41123194 0.80942088 0.41919693, + 0.39767584 0.79875869 0.45148486, + 0.35519391 0.81378984 0.45998189, + 0.34147 0.80074501 0.49214399, + 0.30123398 0.81238091 0.49929494, + 0.28771007 0.79700118 0.53104812, + 0.24995889 0.80577165 0.53689176, + 0.237066 0.78827602 0.56782103, + 0.20219202 0.7946471 0.57241106, + 0.19024003 0.77521712 0.60236806, + 0.15878895 0.77961981 0.60578787, + 0.14805798 0.75854188 0.63458097, + 0.12030499 0.7614249 0.63699192, + 0.11096397 0.73888981 0.66462684, + 0.086764053 0.74067765 0.66623473, + 0.079015896 0.71706992 0.69250792, + 0.058348794 0.71809292 0.69349694, + 0.052371781 0.69399577 0.71807176, + 0.035343193 0.69451481 0.71860981, + 0.0311509 0.67030799 0.74142897, + 0.017392397 0.67053181 0.74167681, + 0.014897208 0.64606929 0.76313335, + 0.013755701 0.64727306 0.76213413, + 0.010018699 0.61017293 0.79220486, + 0.002319111 0.61020225 0.79224229, + 0.00068846566 0.56039578 0.8282246, + -0.00061484874 0.56039584 0.82822472, + -0.0022355302 0.61022109 0.7922281, + -0.009975927 0.61019188 0.79219085, + -0.014919597 0.6590538 0.75194782, + -0.014891801 0.65905404 0.75194812, + -0.95427787 0.29875797 0.0098700486, + -0.9540019 0.29910496 0.020412298, + -0.93777412 0.34644002 0.023642704, + -0.93685198 0.34743601 0.039957602, + -0.91739714 0.39536706 0.045470003, + -0.91544288 0.39702794 0.065826394, + -0.89547521 0.43911713 0.072804518, + -0.89151978 0.44568887 0.08095628, + -0.86696661 0.49034277 0.089067258, + -0.86464202 0.49150199 0.104019, + -0.83616215 0.53659713 0.11356203, + -0.832932 0.53773201 0.130647, + -0.8010729 0.58164597 0.14131598, + -0.79674768 0.5825808 0.16060095, + -0.76202667 0.62425971 0.17209092, + -0.75642884 0.62476689 0.19360195, + -0.71895605 0.66391003 0.20573203, + -0.7119416 0.66370356 0.22942686, + -0.67175925 0.70012021 0.24201509, + -0.66317761 0.69885159 0.26795885, + -0.62070167 0.7320776 0.28069884, + -0.610542 0.72936398 0.308653, + -0.56686085 0.75867683 0.32105792, + -0.55514002 0.75412297 0.35088199, + -0.51096684 0.77936769 0.36262789, + -0.49787799 0.77262598 0.39391199, + -0.45362699 0.79395801 0.40478799, + -0.43963706 0.78486013 0.43670806, + -0.39603317 0.80239034 0.4464612, + -0.38149583 0.79078865 0.47865877, + -0.33982602 0.80457711 0.48700505, + -0.32520908 0.79051518 0.51896513, + -0.28602198 0.80103189 0.52586997, + -0.27174395 0.78462881 0.55723691, + -0.23533803 0.79241014 0.56276304, + -0.22173193 0.77378368 0.59337479, + -0.18842497 0.77932286 0.59762192, + -0.17589802 0.7587961 0.62712705, + -0.14627002 0.76252413 0.63020808, + -0.13499594 0.74021065 0.65868372, + -0.109123 0.74258798 0.66079903, + -0.099401437 0.71896923 0.68789726, + -0.077181064 0.72039264 0.68925864, + -0.069168977 0.69580978 0.71488774, + -0.050614931 0.69658643 0.71568543, + -0.044490401 0.67172098 0.73946702, + -0.031400703 0.67205507 0.73983508, + -0.035348199 0.69483602 0.71829897, + -0.052525688 0.69431084 0.71775579, + -0.058549993 0.71859294 0.69296193, + -0.079425968 0.71755373 0.69195974, + -0.087184876 0.74118084 0.66561985, + -0.11152198 0.73937297 0.66399592, + -0.12085004 0.7618593 0.63636923, + -0.14880098 0.75893986 0.63393092, + -0.15950598 0.77995491 0.60516793, + -0.19096507 0.77553028 0.60173523, + -0.20288397 0.79489189 0.57182592, + -0.23784703 0.78847909 0.56721205, + -0.25067306 0.80587119 0.53640914, + -0.28845203 0.79706609 0.53054804, + -0.30189398 0.81234288 0.49895793, + -0.34213996 0.80067587 0.49179095, + -0.35576597 0.81362587 0.45982993, + -0.3982439 0.79856884 0.45131987, + -0.41168699 0.80914599 0.41928101, + -0.45568511 0.7903372 0.4095341, + -0.46855283 0.79855871 0.37783885, + -0.51286584 0.77599072 0.36716089, + -0.52463681 0.78192472 0.33667487, + -0.5686059 0.75554985 0.32531792, + -0.57904106 0.75949413 0.29644603, + -0.62228692 0.72920996 0.28462598, + -0.6313132 0.73152918 0.25750506, + -0.67316818 0.69753516 0.24553905, + -0.68071979 0.69857579 0.22048195, + -0.72018135 0.66161531 0.20881611, + -0.726345 0.66173601 0.185818, + -0.76306754 0.62225163 0.1747309, + -0.76793814 0.62176007 0.15390101, + -0.8019399 0.57990396 0.14353998, + -0.80567032 0.57905716 0.12485304, + -0.83685768 0.53512281 0.11538096, + -0.83960843 0.53412521 0.098833844, + -0.86750215 0.48913011 0.090507925, + -0.86942631 0.48814818 0.076218732, + -0.89415622 0.44239512 0.069074914, + -0.89595187 0.44113594 0.051664792, + -0.91797924 0.3939361 0.046136912, + -0.91917539 0.39290214 0.027288409, + -0.93804598 0.345678 0.0240086, + -0.93842733 0.34529412 0.011238404, + -0.95026821 0.31138507 0.0054619415, + -0.9502821 0.31139004 0.00040469805, + -0.95034277 0.31120494 0.00040469892, + -0.95032853 0.31120086 0.0054431474, + -0.95031023 0.31125706 0.0054445714, + -0.95032436 0.31126112 0.00040596715, + -0.96439689 0.26439396 -0.0058686091, + -0.96440446 0.26439711 0.0042895218, + -0.96443677 0.26427895 0.0042865989, + -0.97623098 0.21671 0.0031423999, + -0.96763152 0.25222588 0.0084396563, + -0.96744186 0.25252596 0.016937697, + -0.95379835 0.29977411 0.020106807, + -0.95311499 0.300695 0.033975702, + -0.93640512 0.34870204 0.039399903, + -0.93489778 0.35030591 0.057025883, + -0.91461933 0.39906314 0.06496302, + -0.91174722 0.40143308 0.086998023, + -0.91065401 0.404127 0.085969299, + -0.93203676 0.35443291 0.075397782, + -0.93425477 0.35213491 0.056294683, + -0.95166361 0.30329087 0.04848608, + -0.95278025 0.30180606 0.033511907, + -0.96681875 0.25390294 0.028192792, + -0.96729946 0.25308713 0.016693708, + -0.97846925 0.20594504 0.013584303, + -0.97859138 0.20569688 0.006899856, + -0.97624201 0.216682 0.00063632202, + -0.97623748 0.21668111 0.0031392714, + -0.97627562 0.21650892 0.0031350688, + -0.97628021 0.21651004 0.0006356822, + -0.97623563 0.21671093 0.00063568278, + -0.96444523 0.26428106 -0.0010086203, + -0.9601441 0.27948704 -0.0032364305, + -0.92631388 0.37673193 -0.0039558997, + -0.91524887 0.40288895 0.00010190999, + -0.91521841 0.40287519 0.0081784138, + -0.91523731 0.40283215 0.0081772832, + -0.91526777 0.40284592 0.00010035797, + -0.9150449 0.40335193 0.00010035998, + -0.91501391 0.40333793 0.0082542095, + -0.89923614 0.43723905 0.014012402, + -0.89859623 0.43764511 0.031490907, + -0.87477714 0.48327607 0.034774203, + -0.87345582 0.48402789 0.052838787, + -0.8468678 0.52866286 0.057711385, + -0.84540653 0.52923268 0.072115652, + -0.81580317 0.57303411 0.078084312, + -0.8136642 0.5735811 0.09463232, + -0.78143227 0.61566722 0.10157604, + -0.77844167 0.61605573 0.12043194, + -0.74361378 0.65618879 0.12827696, + -0.73961681 0.65622282 0.14946097, + -0.70203978 0.69435579 0.15814593, + -0.69698292 0.69379693 0.18127498, + -0.65682119 0.72955519 0.19061804, + -0.65064174 0.72813475 0.21560393, + -0.60879487 0.76068079 0.22524095, + -0.60146999 0.75811303 0.25198901, + -0.55836612 0.78724515 0.26167205, + -0.54995888 0.78324682 0.28994793, + -0.505831 0.808981 0.299474, + -0.49642387 0.80325282 0.32916293, + -0.45176128 0.8255145 0.33828622, + -0.44158307 0.81782711 0.36900303, + -0.39758918 0.83637041 0.37736917, + -0.38684219 0.82650942 0.40894422, + -0.3441101 0.8415522 0.41638708, + -0.33315888 0.82947671 0.44830084, + -0.29200304 0.84139413 0.45474207, + -0.28129098 0.8272509 0.48634493, + -0.24217394 0.83639783 0.49172187, + -0.23206286 0.82036054 0.52264273, + -0.19571796 0.82707381 0.52691889, + -0.18650502 0.80938214 0.55688107, + -0.15323301 0.81410801 0.56013203, + -0.14511596 0.7949447 0.58907074, + -0.114889 0.79812902 0.59143102, + -0.10806196 0.77775669 0.61920679, + -0.081025794 0.7797659 0.62080592, + -0.075610086 0.75836682 0.6474278, + -0.05194141 0.75951719 0.6484102, + -0.048020221 0.73732138 0.67383331, + -0.027632199 0.73789102 0.67435402, + -0.025258891 0.71506578 0.69860077, + -0.0079877041 0.71527135 0.69880134, + -0.0072078672 0.69229275 0.72158074, + 0.0071290918 0.69229317 0.72158116, + 0.0079051368 0.71513778 0.69893879, + 0.025009809 0.71493626 0.69874221, + 0.02737291 0.73765826 0.67461926, + 0.047617707 0.73709804 0.67410606, + 0.051535219 0.75928432 0.64871526, + 0.075066306 0.75814915 0.64774609, + 0.080481678 0.77955782 0.62113786, + 0.10742898 0.77756882 0.61955291, + 0.11426504 0.79797828 0.59175521, + 0.14441201 0.79481912 0.58941305, + 0.15254697 0.81403184 0.56042987, + 0.18578699 0.80933189 0.55719393, + 0.19503197 0.82708788 0.52715093, + 0.231355 0.82040298 0.52288997, + 0.24151294 0.83651781 0.49184287, + 0.28068998 0.8273809 0.48647094, + 0.29146501 0.84160602 0.45469499, + 0.332609 0.829714 0.44826999, + 0.34364188 0.84187073 0.41612986, + 0.38645285 0.82681769 0.40868884, + 0.397232 0.83669698 0.37702101, + 0.44131094 0.81813091 0.36865497, + 0.45152107 0.82583112 0.33783403, + 0.49624288 0.80354685 0.32871792, + 0.50565398 0.80926299 0.29901099, + 0.54982197 0.78351003 0.289496, + 0.55821687 0.78748983 0.26125395, + 0.60137475 0.75832468 0.2515789, + 0.60864896 0.7608639 0.22501697, + 0.65052009 0.72830707 0.21538903, + 0.65664124 0.72970825 0.19065207, + 0.69681197 0.693959 0.18131199, + 0.70180362 0.69451165 0.15850893, + 0.73940921 0.65637815 0.14980602, + 0.74333596 0.65635091 0.12905498, + 0.77820069 0.61621678 0.12116296, + 0.78117371 0.61584073 0.10250796, + 0.813434 0.57376301 0.095504403, + 0.81560284 0.57321787 0.078825377, + 0.84460282 0.53040189 0.072937489, + 0.8428852 0.5310421 0.08682622, + 0.84471631 0.52734816 0.091423333, + 0.86896002 0.487609 0.0845339, + 0.87196517 0.48606512 0.058458313, + 0.8965717 0.43972984 0.052885681, + 0.89813787 0.43865693 0.030468697, + 0.91950274 0.3921389 0.027237594, + 0.9200331 0.39169106 0.010834701, + 0.93275923 0.36047208 0.0044848612, + 0.93278044 0.36041719 0.0044837622, + 0.93278939 0.36042112 -0.00082284131, + 0.93276811 0.36047602 -0.00083027012, + 0.94931465 0.31432688 0.00056290085, + 0.94935465 0.31420588 0.00056290085, + 0.94932353 0.31429985 0.00056503073, + 0.94931787 0.31429797 0.0034989596, + 0.94934911 0.31420404 0.0034971004, + 0.94930899 0.314325 0.0035087899, + 0.93844324 0.34529808 0.0096782818, + 0.93804109 0.34572002 0.023590904, + 0.91915935 0.39297214 0.02681521, + 0.9179076 0.39405483 0.046546277, + 0.89585489 0.44127893 0.052124493, + 0.8933807 0.44292885 0.07539957, + 0.86774111 0.48996806 0.083407104, + 0.86453581 0.49162087 0.10433998, + 0.83603382 0.5367229 0.11391197, + 0.83285457 0.53783876 0.13070095, + 0.80099291 0.58174294 0.14136998, + 0.79672712 0.58266908 0.16038302, + 0.76196218 0.62439913 0.17187004, + 0.75641382 0.62490886 0.19320196, + 0.71892917 0.66407019 0.20530905, + 0.711936 0.66387498 0.228948, + 0.6717338 0.70031685 0.24151593, + 0.66316628 0.69906336 0.26743412, + 0.62062871 0.73234361 0.28016588, + 0.61043608 0.72963405 0.30822402, + 0.56670588 0.75897783 0.32061991, + 0.55493277 0.75441366 0.35058483, + 0.5106827 0.77969152 0.36233178, + 0.49750289 0.77290982 0.3938289, + 0.45322788 0.7942338 0.4046939, + 0.43910593 0.78505391 0.43689394, + 0.39546993 0.8025679 0.44664094, + 0.38084501 0.79089397 0.47900301, + 0.33914709 0.8046602 0.48734111, + 0.32444811 0.79051328 0.51944417, + 0.28525999 0.80099899 0.52633399, + 0.27088112 0.78447133 0.55787826, + 0.23455903 0.79220414 0.56337804, + 0.22089399 0.77348298 0.59407902, + 0.18772399 0.778974 0.598297, + 0.17512698 0.75831187 0.62792796, + 0.14561391 0.76200551 0.63098663, + 0.13433899 0.73967195 0.65942293, + 0.108628 0.74202102 0.66151702, + 0.098902181 0.71837282 0.68859184, + 0.076877169 0.71977574 0.68993676, + 0.068946242 0.69543439 0.71527439, + 0.050518606 0.69620305 0.71606505, + 0.044492889 0.67174083 0.73944885, + 0.029538803 0.67211306 0.73985904, + 0.025242388 0.64712769 0.76196367, + 0.023445206 0.64920616 0.76025116, + 0.036268804 0.64895707 0.75996011, + 0.042454813 0.67425418 0.73727816, + 0.0587104 0.67369801 0.73667097, + 0.066697091 0.69838893 0.71260393, + 0.086554177 0.69732082 0.71151382, + 0.096506834 0.72171825 0.68542624, + 0.120021 0.71986198 0.683662, + 0.13181101 0.74341708 0.65571105, + 0.15930404 0.74038321 0.65303516, + 0.17256099 0.7623319 0.62375695, + 0.203899 0.75768298 0.61995298, + 0.21834804 0.77768415 0.58951813, + 0.25312284 0.77096051 0.58442163, + 0.26841092 0.78873467 0.55303985, + 0.30635402 0.77941114 0.54650307, + 0.32208097 0.79474688 0.51443297, + 0.36284092 0.7822718 0.50635689, + 0.37859192 0.79503781 0.47390187, + 0.42166525 0.77887845 0.46427026, + 0.43698826 0.78902346 0.43183726, + 0.48109511 0.76902419 0.42089108, + 0.49553999 0.77662897 0.38895699, + 0.53993887 0.75259382 0.37691993, + 0.55312288 0.75785983 0.3459819, + 0.59730113 0.72958416 0.33307409, + 0.60879701 0.73277098 0.30399501, + 0.65196085 0.70037484 0.29055494, + 0.66169405 0.70190704 0.26360503, + 0.70265257 0.66610759 0.25015986, + 0.71064085 0.66641581 0.22556494, + 0.74892777 0.62767178 0.21245092, + 0.75529802 0.62715203 0.190277, + 0.79085129 0.58564723 0.17768405, + 0.79578888 0.58462495 0.15790398, + 0.8283937 0.5407688 0.14605793, + 0.83209282 0.53950787 0.12865797, + 0.86016411 0.49610606 0.11830702, + 0.85746658 0.49737278 0.13180093, + 0.8275739 0.54262793 0.14379299, + 0.82328129 0.5440442 0.16193806, + 0.7898562 0.58780509 0.17496404, + 0.78417218 0.58891809 0.19557504, + 0.74775642 0.63013434 0.20926312, + 0.74045491 0.63064796 0.23239997, + 0.70130521 0.66888922 0.24649209, + 0.69220161 0.66843271 0.27212989, + 0.65043396 0.70349693 0.28640497, + 0.63940191 0.70162994 0.31445298, + 0.59561497 0.73301893 0.32852098, + 0.58266771 0.72927064 0.35869583, + 0.53809595 0.75634587 0.37201297, + 0.52357697 0.75036502 0.40350899, + 0.47909805 0.77307314 0.41572005, + 0.46334288 0.7645818 0.4480269, + 0.41951394 0.78319186 0.45893195, + 0.40291494 0.77199686 0.49160993, + 0.36055401 0.78675902 0.50101, + 0.34361598 0.77281487 0.53355896, + 0.30394804 0.78398919 0.54127312, + 0.28712806 0.76736718 0.57332814, + 0.25062096 0.7755329 0.57942891, + 0.234386 0.756432 0.61063403, + 0.20131503 0.76217711 0.61527103, + 0.18606009 0.74083138 0.64540732, + 0.156688 0.74468398 0.64876401, + 0.14277208 0.72141439 0.67762631, + 0.11745404 0.72383624 0.67990124, + 0.10538496 0.69950378 0.70681578, + 0.084071495 0.70093095 0.70825696, + 0.07405664 0.67618829 0.73299736, + 0.056305367 0.67697459 0.73384959, + 0.048138581 0.65152675 0.75709671, + 0.033954207 0.65190721 0.7575382, + 0.027595496 0.62569195 0.7795819, + 0.019450191 0.6258117 0.77973163, + 0.0026603807 0.61168212 0.79109919, + 0.0071748602 0.61166799 0.79108202, + 0.0021363006 0.56098515 0.82782316, + -0.00042542908 0.5609861 0.82782519, + -0.0019304497 0.51399195 0.85779285, + 0.0020066593 0.51399183 0.85779268, + 0.0005084569 0.56099087 0.82782185, + -0.00208415 0.56098998 0.82782, + -0.0071161389 0.61169595 0.79106086, + -0.017050205 0.61162221 0.79096627, + -0.023436299 0.64926994 0.76019686, + -0.036210611 0.64902222 0.75990731, + -0.04239291 0.67430615 0.73723418, + -0.058728587 0.67374784 0.73662382, + -0.066850081 0.69885474 0.71213275, + -0.086816147 0.69777733 0.71103436, + -0.096894711 0.72246903 0.68458009, + -0.12061197 0.72058481 0.68279582, + -0.13238096 0.74408174 0.65484178, + -0.16004695 0.7410118 0.65213984, + -0.17328005 0.76289618 0.62286711, + -0.20478112 0.7581985 0.61903137, + -0.21914203 0.77805614 0.58873206, + -0.25401303 0.7712841 0.58360803, + -0.26923299 0.78896099 0.55231702, + -0.30718899 0.77960098 0.54576302, + -0.322806 0.794815 0.51387298, + -0.3635911 0.78229731 0.50577921, + -0.37922686 0.79496169 0.47352183, + -0.42230377 0.77876753 0.46387574, + -0.43751606 0.78883713 0.43164307, + -0.48158783 0.7688247 0.42069185, + -0.49590611 0.77636516 0.38901708, + -0.54027092 0.75232887 0.37697294, + -0.55333865 0.75755751 0.34629878, + -0.59746712 0.72930616 0.33338508, + -0.60891104 0.73249006 0.30444303, + -0.65201926 0.70013726 0.29099607, + -0.66171783 0.70167583 0.26415995, + -0.70265007 0.66590905 0.25069502, + -0.71065593 0.66622996 0.22606596, + -0.74891543 0.62752336 0.21293214, + -0.75531363 0.62701172 0.19067691, + -0.7908448 0.58553988 0.17806596, + -0.79581928 0.58451825 0.15814605, + -0.82841516 0.5406751 0.14628303, + -0.83217186 0.53939795 0.12860699, + -0.86131197 0.494223 0.117836, + -0.86404628 0.49289218 0.10237804, + -0.88981271 0.44678986 0.092801973, + -0.89095575 0.44378787 0.096177079, + -0.036955599 0.62896597 0.77655399, + -0.045388188 0.65546679 0.7538588, + -0.06117063 0.65491432 0.75322336, + -0.071363576 0.68030375 0.72944778, + -0.090670824 0.67923319 0.72830015, + -0.10305799 0.70441991 0.70226192, + -0.12631199 0.70251894 0.70036596, + -0.14078397 0.7269398 0.67211485, + -0.16823605 0.72378719 0.66920018, + -0.18424602 0.74641407 0.63946807, + -0.21563508 0.74154925 0.63530022, + -0.23276106 0.76192516 0.60439414, + -0.26778495 0.75483084 0.59876686, + -0.28562319 0.77268147 0.56690633, + -0.32412896 0.76274091 0.55961293, + -0.34218803 0.77782714 0.52715504, + -0.38374186 0.76442373 0.51807183, + -0.4015311 0.77663916 0.48539111, + -0.44490999 0.75945002 0.474648, + -0.46193489 0.7688368 0.44216087, + -0.50635004 0.74752408 0.42990407, + -0.52214593 0.75423187 0.39811793, + -0.56702894 0.72844595 0.38450593, + -0.58124501 0.73275 0.353881, + -0.62562096 0.70249194 0.33926898, + -0.63798165 0.70475256 0.31032783, + -0.68052506 0.67059106 0.29528502, + -0.69083905 0.67125005 0.26863503, + -0.73089194 0.63363492 0.25358197, + -0.73922491 0.63316393 0.22945596, + -0.77655089 0.59235692 0.21466698, + -0.78309488 0.59116691 0.19309098, + -0.81742257 0.54756975 0.1788509, + -0.82239997 0.54599702 0.15983, + -0.85310161 0.50073177 0.14657892, + -0.85678184 0.49903387 0.12996197, + -0.88388222 0.45261312 0.11787203, + -0.88614887 0.45121294 0.10557999, + -0.8606649 0.49577993 0.11600898, + -0.8574847 0.49728781 0.13200295, + -0.82759458 0.54253775 0.14401393, + -0.82326549 0.54395932 0.16230309, + -0.78985286 0.58769393 0.17535199, + -0.78413898 0.58880299 0.196054, + -0.74775219 0.62997317 0.20976305, + -0.74044102 0.630476 0.23291001, + -0.70130366 0.66869271 0.24702889, + -0.69222426 0.66822422 0.27258408, + -0.65050119 0.70324516 0.28687006, + -0.63953096 0.70137691 0.31475496, + -0.59578127 0.73274422 0.32883212, + -0.58295292 0.72902292 0.35873598, + -0.53842294 0.75609189 0.37205598, + -0.52401209 0.75015211 0.40334007, + -0.47960129 0.77285445 0.41554624, + -0.46395782 0.76442671 0.44765484, + -0.42016476 0.78305751 0.45856574, + -0.40370286 0.7719627 0.49101683, + -0.36130902 0.78677613 0.50043905, + -0.34450617 0.77295935 0.53277522, + -0.30477604 0.78419012 0.54051608, + -0.28807783 0.76770651 0.57239664, + -0.25147012 0.77593035 0.57852829, + -0.23532487 0.75695765 0.60962069, + -0.20216404 0.76274818 0.6142841, + -0.18693995 0.74147183 0.64441681, + -0.15739505 0.74537015 0.6478042, + -0.14352797 0.72220683 0.67662179, + -0.11797406 0.72466636 0.67892629, + -0.10575899 0.70005596 0.70621294, + -0.084253773 0.70150077 0.70767075, + -0.074037112 0.67626315 0.73293018, + -0.056305192 0.67704892 0.73378092, + -0.04813559 0.65159082 0.75704181, + -0.033895805 0.65197307 0.75748414, + -0.02835081 0.62914324 0.77677232, + -0.009518669 0.61422193 0.78907585, + -0.012398805 0.61420226 0.78905129, + -0.0038088108 0.56286913 0.82653719, + 0.0013228203 0.56287313 0.8265422, + 0.0060005127 0.51469326 0.85735339, + 0.00329304 0.5147 0.857364, + 0.0026249001 0.53558701 0.84447598, + -0.0025850001 0.53558707 0.8444761, + -0.0032540387 0.5147208 0.85735172, + -0.0058882884 0.51471388 0.85734183, + -0.0012103805 0.56283516 0.82656831, + 0.0038847094 0.56283092 0.82656288, + 0.010443697 0.60219491 0.79828084, + 0.018475002 0.60212505 0.79818809, + 0.0249708 0.62914598 0.77688599, + 0.036956094 0.62891179 0.7765978, + 0.045388788 0.65540582 0.75391179, + 0.061146684 0.65485382 0.75327784, + 0.071352594 0.68027693 0.72947395, + 0.090681709 0.67920506 0.72832507, + 0.10275405 0.70375937 0.70296836, + 0.12583706 0.70188034 0.70109135, + 0.14011493 0.72600162 0.67326772, + 0.16739802 0.72288805 0.67038107, + 0.18345609 0.74561334 0.64062828, + 0.21463896 0.74080896 0.63649994, + 0.23186094 0.7613278 0.60549188, + 0.26676697 0.75429291 0.59989792, + 0.28470808 0.77227527 0.56791919, + 0.32311496 0.76240289 0.56065893, + 0.34132212 0.77763432 0.52800018, + 0.3828271 0.76429218 0.51894212, + 0.40076494 0.77662587 0.48604494, + 0.44415411 0.7594772 0.47531211, + 0.46133488 0.76895881 0.44257489, + 0.5057559 0.7476818 0.43032891, + 0.52170485 0.75445682 0.39826992, + 0.56660306 0.72869104 0.38466907, + 0.58094364 0.7330296 0.35379678, + 0.62537283 0.70275384 0.3391839, + 0.63784093 0.70502591 0.30999598, + 0.68044281 0.67081982 0.29495493, + 0.69080895 0.67147094 0.26815996, + 0.73088825 0.63382226 0.25312409, + 0.73923576 0.63333875 0.22893792, + 0.77659571 0.59247875 0.21416792, + 0.78312802 0.59127897 0.19261301, + 0.81746203 0.54765701 0.17840301, + 0.82241368 0.54608381 0.15946195, + 0.85169029 0.50303715 0.14689206, + 0.84816509 0.50460309 0.16122001, + 0.8165459 0.54989594 0.17569098, + 0.81084234 0.55163324 0.19553909, + 0.7755028 0.59506488 0.21093395, + 0.76800716 0.59634215 0.23354006, + 0.72962719 0.63675719 0.24936806, + 0.72006804 0.63718307 0.27477202, + 0.67902493 0.67410797 0.29069498, + 0.66724873 0.67320567 0.31870586, + 0.62379903 0.70642102 0.33443099, + 0.60990793 0.70369893 0.36444497, + 0.56487995 0.73273695 0.37948295, + 0.54904389 0.72773081 0.41104591, + 0.50388891 0.75208884 0.42480391, + 0.48642507 0.74443609 0.45739007, + 0.44213989 0.76422381 0.46954688, + 0.42344105 0.75365412 0.50269604, + 0.38068083 0.76927966 0.51311874, + 0.36130092 0.75568783 0.54625785, + 0.32081509 0.76759517 0.55486512, + 0.30130994 0.75100082 0.58754587, + 0.26432303 0.75959212 0.59426707, + 0.24521799 0.74015999 0.62612402, + 0.21206805 0.74610519 0.63115317, + 0.19385895 0.7241208 0.66186684, + 0.16474307 0.72803825 0.66544724, + 0.14817706 0.70432222 0.69424325, + 0.12314197 0.7067638 0.69664985, + 0.10896898 0.6825878 0.72263384, + 0.087827995 0.68402296 0.72415394, + 0.075536914 0.65880716 0.74851018, + 0.058137216 0.65957719 0.74938518, + 0.047540579 0.63294768 0.77273363, + 0.033949908 0.63329917 0.77316219, + 0.025290284 0.60583466 0.79518855, + 0.015654607 0.60595429 0.79534537, + 0.0061928914 0.56598812 0.82439017, + -0.0015665402 0.56599808 0.82440513, + -0.0096073011 0.51689309 0.85599613, + -0.009697671 0.51689309 0.85599512, + -0.0078041484 0.53634191 0.84396482, + -0.0040298519 0.53635424 0.84398341, + -0.0026822002 0.57672906 0.81693113, + 0.0027894094 0.57672888 0.81693083, + 0.0041285409 0.53638512 0.84396321, + 0.0079221493 0.53637296 0.84394389, + 0.0098189702 0.51687598 0.856004, + 0.0096824691 0.51687694 0.85600489, + 0.0016403904 0.56603414 0.82438016, + -0.0061586988 0.56602389 0.82436579, + -0.015615996 0.6060099 0.79530382, + -0.025246199 0.60589099 0.795147, + -0.033916481 0.63340163 0.77307951, + -0.047508091 0.63305092 0.7726509, + -0.058116186 0.6597088 0.7492708, + -0.075574696 0.65893596 0.74839294, + -0.087816291 0.68405092 0.72412896, + -0.10893495 0.68261671 0.72261167, + -0.12354501 0.70752907 0.69580108, + -0.14878902 0.70505506 0.69336808, + -0.16554005 0.72901022 0.66418421, + -0.19487996 0.72503597 0.66056395, + -0.2130301 0.74691135 0.62987429, + -0.24631497 0.74090594 0.62480992, + -0.26531094 0.76019084 0.5930599, + -0.30243382 0.75152349 0.58629864, + -0.32180798 0.76797688 0.55376095, + -0.36237404 0.75599414 0.54512209, + -0.38158101 0.76944202 0.51220602, + -0.42436895 0.7537539 0.50176293, + -0.442891 0.76420701 0.46886599, + -0.48718405 0.74436706 0.45669407, + -0.5044812 0.75193727 0.42436916, + -0.54958481 0.72756577 0.41061485, + -0.56529206 0.73252505 0.37927806, + -0.61028373 0.70347977 0.36423889, + -0.62404126 0.70617723 0.33449411, + -0.66742259 0.67299861 0.31877881, + -0.67909992 0.67389995 0.29100198, + -0.72013444 0.63698334 0.27506119, + -0.7296322 0.63657117 0.24982806, + -0.76798266 0.59619969 0.23398389, + -0.77546185 0.59493697 0.21144497, + -0.81079912 0.55152708 0.19601703, + -0.81651253 0.5497967 0.17615589, + -0.8481189 0.50454092 0.16165599, + -0.85235709 0.50264305 0.14435202, + -0.88025409 0.45606807 0.13097602, + -0.88329786 0.45421293 0.11608399, + -0.90771312 0.40652505 0.10389601, + -0.90850478 0.40407291 0.10650898, + -0.92815924 0.35989109 0.094862819, + -0.93117887 0.35686296 0.074529491, + -0.94953322 0.30704206 0.064124614, + -0.95117766 0.30490789 0.04787628, + -0.96579391 0.25617197 0.040223695, + -0.96657866 0.25485691 0.027814891, + -0.97805935 0.20709707 0.022602508, + -0.97837389 0.20640998 0.013391898, + -0.98718053 0.15927292 0.010333596, + -0.9872514 0.15907891 0.005336477, + -0.99279678 0.11980497 0.0011591298, + -0.99275452 0.12015494 0.0011674294, + -0.99277222 0.12000803 0.0011742802, + -0.99277264 0.12000795 0.00079577271, + -0.99275488 0.12015498 0.00079577288, + -0.99279714 0.11980502 0.00080358714, + -0.98568898 0.168567 -0.00157079, + -0.98568809 0.16856702 0.0020409902, + -0.98570651 0.16845892 0.002038389, + -0.98569661 0.16845694 -0.0049467781, + -0.98379266 0.17927894 -0.0033400687, + -0.51552415 0.67640918 0.5260281, + -0.56738198 0.65002799 0.50551099, + -0.59732008 0.65120906 0.46811906, + -0.64905506 0.61770505 0.44403607, + -0.67351919 0.61549813 0.40930909, + -0.72257417 0.5756321 0.38279808, + -0.74170923 0.57124418 0.35149312, + -0.78645188 0.52604496 0.32368198, + -0.80072701 0.52057999 0.29636601, + -0.84039479 0.47099689 0.26813895, + -0.85057509 0.46531206 0.24496303, + -0.88464868 0.41257784 0.21720092, + -0.89156067 0.40727785 0.19810192, + -0.92586958 0.33978084 0.16527092, + -0.92169738 0.37057012 0.11468104, + -0.9428609 0.31829298 0.098502986, + -0.94582635 0.31468311 0.079919331, + -0.96226048 0.26375711 0.066985928, + -0.963835 0.26124901 0.0526402, + -0.97640222 0.21170504 0.042657413, + -0.97715902 0.210106 0.031872001, + -0.98654276 0.16165395 0.024522094, + -0.98684454 0.16077892 0.016972192, + -0.99342674 0.11383697 0.012016897, + -0.99351847 0.11344706 0.0071299234, + -0.99770111 0.06763491 0.0042507006, + -0.997715 0.067537397 0.0018534299, + -0.99746567 0.071147874 0.00048284483, + -0.99746335 0.071147725 -0.0021972607, + -0.99963814 -0.026899004 -6.6760105e-005, + -0.99963289 -0.026898896 -0.0032539896, + -0.99976212 0.021793902 0.00085363613, + -0.99976248 0.021793911 4.8972521e-007, + -0.99975353 0.022202689 9.7440752e-006, + -0.99975312 0.022202702 0.00088522711, + -0.99975502 0.022115201 0.00088522601, + -0.99975187 0.022257298 0.0008770969, + -0.99975234 0.022257308 4.0389714e-005, + -0.99975538 0.022115286 3.7125377e-005, + -0.99975276 0.022237895 1.8643796e-005, + -0.99975049 0.022293689 0.0013799893, + -0.99769109 0.067786105 0.0041959803, + -0.99765903 0.068018898 0.0070668198, + -0.99337953 0.11426394 0.011871395, + -0.9932301 0.11489201 0.017140402, + -0.98640722 0.16252105 0.024245905, + -0.98596323 0.16378304 0.032431409, + -0.97609633 0.21319908 0.042216416, + -0.97506589 0.21531998 0.053700794, + -0.9616679 0.26606697 0.066357292, + -0.95958048 0.26929012 0.081782036, + -0.94182163 0.32160887 0.097670965, + -0.91472131 0.37997514 0.13749105, + -0.93790722 0.3261891 0.11802903, + -0.028384292 0.68896681 0.72423685, + -0.033158813 0.68018925 0.73228621, + -0.0271398 0.68031299 0.73241901, + -0.032106698 0.67241693 0.73947597, + -0.02384631 0.67257226 0.73964721, + -0.028831296 0.66563094 0.74572396, + -0.017545894 0.66580474 0.74591976, + -0.021820294 0.66053879 0.75047481, + -0.0079581486 0.66067493 0.7506299, + -0.011561399 0.65672797 0.75403887, + 0.0060543222 0.65676022 0.75407529, + 0.0033353993 0.6541068 0.7563948, + 0.024086289 0.65392071 0.75617963, + 0.021942893 0.65205878 0.75785071, + 0.047310706 0.65148604 0.75718415, + 0.049778719 0.65338522 0.75538731, + 0.079470791 0.65212697 0.75393289, + 0.11414104 0.67493427 0.72899622, + 0.15160507 0.67152131 0.72531039, + 0.19360197 0.69385093 0.69360596, + 0.23793891 0.68691975 0.68667775, + 0.27565804 0.70238304 0.65625507, + 0.32574615 0.69083935 0.64546931, + 0.35920903 0.70074308 0.61638308, + 0.44015816 0.67421025 0.59304422, + -0.02833919 0.65196574 0.75771868, + -0.033407111 0.64212322 0.76587331, + -0.027587391 0.64223677 0.76600969, + -0.032682408 0.6336782 0.77290618, + -0.024577605 0.63382608 0.77308512, + -0.029180292 0.62705183 0.77843082, + -0.018611901 0.62721097 0.77862698, + -0.022891592 0.62163979 0.7829687, + -0.0092405844 0.62177628 0.78314036, + -0.012616803 0.6178661 0.78618217, + 0.0041398997 0.61790997 0.7862379, + 0.0037883294 0.61754692 0.78652489, + 0.024689296 0.61736292 0.78629088, + 0.0531861 0.64291102 0.76409203, + 0.080298632 0.64174324 0.76270431, + 0.11765494 0.66985971 0.73310661, + 0.15131398 0.66677785 0.72973382, + 0.18713506 0.68894422 0.70024025, + 0.22742587 0.68295556 0.69415361, + 0.26121196 0.69972897 0.66494197, + 0.30666098 0.68996996 0.65566796, + 0.33719015 0.70163035 0.62770832, + 0.38661894 0.68732291 0.61490893, + 0.41346976 0.69467658 0.58861464, + 0.48703876 0.66634268 0.56460673, + 0.88573986 0.40519795 0.22644997, + 0.83915341 0.47478124 0.26533812, + 0.82708484 0.48111889 0.29061195, + 0.78480673 0.53047681 0.32042587, + 0.76784402 0.53642499 0.350234, + 0.72040915 0.58073014 0.37916109, + 0.69779074 0.58520478 0.41306585, + 0.64653569 0.62326169 0.43992779, + 0.61861604 0.62492907 0.47621205, + 0.56532001 0.65609097 0.49995801, + 0.53652889 0.65421385 0.53304887, + 0.46969324 0.68440729 0.55765122, + 0.44084486 0.67935878 0.58662379, + 0.38755372 0.69772351 0.6024816, + 0.35752901 0.68920302 0.630216, + 0.30780998 0.70215195 0.64205593, + 0.27365503 0.68866706 0.67145407, + 0.228605 0.69703799 0.67961597, + 0.19155103 0.67804909 0.70961803, + 0.15229797 0.68278283 0.71457183, + 0.11238395 0.65728372 0.74521667, + 0.08076039 0.65931392 0.74751794, + 0.049125399 0.63489503 0.77103502, + 0.0239738 0.63547999 0.77174503, + 0.022690399 0.63433295 0.77272689, + 0.0021781998 0.63449496 0.77292389, + 0.0052326024 0.6375643 0.77037936, + -0.012239804 0.63752526 0.77033228, + -0.0086614415 0.6415562 0.7670272, + -0.022420403 0.64141905 0.76686311, + -0.018109094 0.64687777 0.76237869, + -0.029087603 0.64671004 0.7621811, + -0.024458304 0.65333807 0.75667113, + -0.032368802 0.65319097 0.75650102, + -0.0272629 0.66153902 0.74941498, + -0.033315782 0.6614176 0.74927759, + -0.028230904 0.67102605 0.74089605, + -0.023289001 0.67111099 0.740991, + -0.031725202 0.65189999 0.75764102, + -0.027030503 0.64417309 0.76440209, + -0.031971198 0.63255793 0.77385288, + -0.028508108 0.63262415 0.77393419, + -0.033538099 0.622594 0.78182602, + -0.027983304 0.62270004 0.78196013, + -0.032751393 0.61448187 0.7882508, + -0.024899995 0.61462188 0.78842884, + -0.029668396 0.60742491 0.79382288, + -0.01916619 0.60758072 0.79402661, + -0.023427894 0.60188788 0.79823685, + -0.0095738405 0.60202605 0.79841912, + -0.0108204 0.600546 0.79951698, + 0.0057043503 0.60057104 0.79955113, + 0.030981185 0.62673467 0.77861667, + 0.053952713 0.62612218 0.77785617, + 0.088199094 0.65612793 0.74947792, + 0.11776204 0.65411222 0.74717426, + 0.15154794 0.67882979 0.71848679, + 0.18683001 0.67466909 0.71408409, + 0.21966296 0.69443291 0.68520892, + 0.26072496 0.68719894 0.67807096, + 0.29141003 0.70200908 0.64981806, + 0.33670691 0.69100881 0.63963681, + 0.36422697 0.70121396 0.61289293, + 0.41312885 0.68567479 0.59931177, + 0.43679994 0.69195992 0.57480192, + 0.48718125 0.67176229 0.55802321, + 0.51377892 0.67600691 0.52824795, + 0.5654397 0.64989972 0.50784677, + 0.59503585 0.65116882 0.47107488, + 0.64690316 0.61784714 0.44696912, + 0.67186284 0.61569387 0.4117299, + 0.72095442 0.57604837 0.38521823, + 0.74053979 0.57162583 0.35333389, + 0.78543919 0.52648014 0.32542908, + 0.79999965 0.52095073 0.29767585, + 0.83978319 0.47139212 0.26935807, + 0.8501429 0.46563494 0.24584797, + 0.88431025 0.41288409 0.21799605, + 0.89371222 0.40557909 0.19179204, + 0.92289013 0.34810403 0.16461301, + 0.92978424 0.34083909 0.13903303, + 0.95148426 0.28490606 0.11621703, + 0.95517087 0.27965096 0.097179987, + 0.97102565 0.22573392 0.078443572, + 0.97283137 0.22224207 0.064867325, + 0.98415375 0.17021495 0.049681887, + 0.98494714 0.16807202 0.040385004, + 0.99255562 0.11842196 0.028454991, + 0.99284863 0.11724196 0.022490993, + 0.99748886 0.069555692 0.013343099, + 0.99756402 0.069026902 0.0100668, + 0.99973851 0.022627989 0.0033000284, + 0.99974412 0.022504402 0.0022897103, + 0.99974614 -0.022418002 -0.0022809203, + 0.99974954 -0.022339288 -0.0013176494, + 0.99771464 -0.067540281 -0.0019320094, + 0.9977029 -0.067623891 -0.0039886995, + 0.98543 -0.17008001 0.00077111198, + 0.98536724 -0.17044304 0.00077111216, + 0.98535633 -0.17044106 -0.0047675418, + 0.98541898 -0.17007899 -0.00475307, + 0.98729199 -0.158913 -0.00108703, + 0.98719966 -0.15922794 -0.0091265766, + 0.51252812 0.66212118 0.54672712, + 0.42037222 0.69965935 0.57772332, + 0.38024607 0.69474703 0.61052406, + 0.31834608 0.71209121 0.6257652, + 0.27755696 0.70220596 0.65564394, + 0.22225803 0.71264309 0.66538805, + 0.21547 0.71032298 0.67008501, + 0.16679704 0.71721917 0.67659116, + 0.165663 0.71674001 0.67737699, + 0.12314397 0.72125083 0.68163985, + 0.12200803 0.72068018 0.6824472, + 0.085222393 0.72346294 0.68508291, + 0.085179172 0.72343779 0.68511474, + 0.053551793 0.72503495 0.68662691, + 0.054274134 0.72551841 0.68605942, + 0.027699396 0.72631097 0.68680793, + 0.029772412 0.72788626 0.68505126, + 0.0075523891 0.72818792 0.68533593, + 0.010326097 0.73057079 0.68275881, + -0.008256929 0.73058492 0.68277192, + -0.0058851708 0.73288405 0.68032807, + -0.020386299 0.73274398 0.68019903, + -0.018016608 0.73534334 0.67745531, + -0.028737608 0.73515916 0.67728519, + -0.022260707 0.74320424 0.66869426, + -0.0311053 0.743029 0.66853601, + -0.024696484 0.75209254 0.65859461, + -0.031559516 0.75194734 0.65846729, + -0.026191304 0.7607221 0.64854908, + -0.031121399 0.76061398 0.648458, + -0.026133705 0.77023619 0.63722318, + -0.024317704 0.7805261 0.62465006, + -0.028718987 0.77018166 0.63717771, + 0.017049203 0.66603905 0.74572206, + 0.026090594 0.66590881 0.7455768, + -0.011615204 0.69803822 0.71596622, + -0.019293796 0.69795585 0.71588081, + -0.012501002 0.73036003 0.68294805, + -0.012032202 0.73036504 0.68295103, + -0.0078625381 0.76208782 0.64742583, + -0.0041857702 0.76210499 0.64744002, + -0.0027556403 0.79336113 0.60874504, + 0.0028835193 0.79336083 0.60874486, + 0.0042854911 0.76209921 0.64744616, + 0.0079760375 0.76208168 0.64743179, + 0.012128104 0.73027724 0.68304324, + 0.012462505 0.73027438 0.68304032, + 0.019182598 0.69812196 0.71572196, + 0.017020091 0.69814956 0.71574956, + 0.023363888 0.72944462 0.68364072, + -0.91519326 0.35391608 0.19278204, + -0.8754921 0.42436007 0.23115402, + -0.8660813 0.43095714 0.2533361, + -0.82736546 0.4842003 0.28463417, + -0.81346118 0.49110413 0.31160507, + -0.76870871 0.54006082 0.34266788, + -0.74939102 0.54631501 0.37410301, + -0.699588 0.58956498 0.40371999, + -0.67379797 0.59400392 0.43949494, + -0.6203953 0.63047928 0.46648222, + -0.59300995 0.63152194 0.49951893, + -0.52404475 0.66798872 0.52836376, + -0.49889219 0.66606522 0.5544942, + -0.44250995 0.68919796 0.57375193, + -0.41392505 0.68388903 0.60080105, + -0.35978809 0.70096016 0.61579812, + -0.32588309 0.69093919 0.64529318, + -0.27576798 0.70249695 0.65608692, + -0.23762503 0.68685603 0.68685007, + -0.19331388 0.6937716 0.69376558, + -0.14663701 0.66882008 0.72881907, + -0.085609704 0.67364705 0.73407805, + -0.078424402 0.66895401 0.73915499, + -0.048366413 0.67023617 0.74057019, + -0.049513187 0.67109084 0.73971981, + -0.023859104 0.67172408 0.74041706, + -0.025562495 0.6731568 0.73905784, + -0.0042495886 0.67337078 0.73929274, + -0.0066385516 0.67563319 0.73720819, + 0.010891496 0.67560774 0.73718077, + 0.0076932199 0.67901403 0.73408502, + 0.021933898 0.67887092 0.73392993, + 0.017823199 0.68380094 0.72945094, + 0.0288516 0.68362498 0.72926301, + 0.024217503 0.68991303 0.72348708, + 0.032364704 0.68975407 0.72332007, + 0.026997009 0.69807124 0.71551925, + 0.032845996 0.69794893 0.71539396, + 0.0279007 0.70680398 0.70685899, + 0.031389315 0.70673138 0.70678538, + 0.026314404 0.71744007 0.69612306, + 0.02806 0.71740597 0.69608998, + 0.017070204 0.70276821 0.71121418, + 0.026010897 0.70263296 0.71107692, + 0.018038401 0.72952509 0.68371606, + 0.011933098 0.73372585 0.67934084, + 0.019895094 0.7336328 0.67925483, + 0.013168395 0.76407772 0.64498979, + 0.012873898 0.76408088 0.64499193, + 0.0087497197 0.793993 0.60786402, + 0.004644658 0.79401469 0.60788077, + 0.0032625394 0.82310981 0.56787288, + -0.0032256094 0.82310987 0.56787294, + -0.0046294024 0.79405737 0.60782528, + -0.0086161839 0.79403633 0.60780931, + -0.012771897 0.7640928 0.64497983, + -0.012577693 0.76409453 0.64498162, + -0.019348593 0.73345578 0.67946178, + -0.011679198 0.7335428 0.67954284, + 0.86656082 0.4235529 0.26396093, + 0.81180698 0.49556699 0.30884099, + 0.79508537 0.50322622 0.33853015, + 0.74725682 0.55138189 0.37092492, + 0.72477818 0.55784214 0.40436208, + 0.67199492 0.59959894 0.43463093, + 0.64960974 0.60283679 0.46324381, + 0.58070773 0.64553171 0.49605176, + 0.55671483 0.64611274 0.52211779, + 0.47856799 0.68293899 0.55187601, + 0.44587693 0.67985195 0.58223295, + 0.38628781 0.70057464 0.59998071, + 0.35013896 0.69297493 0.63022894, + 0.29479 0.70693099 0.64292097, + 0.25141799 0.69274002 0.67594397, + 0.20218897 0.70094794 0.68395293, + 0.16242495 0.6832118 0.71192682, + 0.12083901 0.68733305 0.71622008, + 0.116004 0.68468201 0.71955103, + 0.080062561 0.6871227 0.72211665, + 0.080350608 0.68730503 0.72191107, + 0.049839377 0.68867767 0.72335267, + 0.050719399 0.68931198 0.72268701, + 0.024925191 0.68998575 0.72339374, + 0.026896009 0.69159126 0.72178823, + 0.0051456606 0.69183207 0.72204006, + 0.0078078671 0.69427574 0.71966678, + -0.010132 0.69426101 0.719652, + -0.0061432226 0.69837737 0.71570337, + -0.020576086 0.69824255 0.71556544, + -0.016531499 0.702941 0.71105599, + -0.027714901 0.70276701 0.71087998, + -0.023569405 0.70822215 0.70559621, + -0.032270115 0.70805037 0.70542437, + -0.028083596 0.71434993 0.69922495, + -0.033270493 0.7142368 0.69911283, + -0.027330194 0.7245788 0.68864983, + -0.031226808 0.72449619 0.68857116, + -0.0258746 0.73545903 0.67707503, + -0.027909892 0.7354188 0.67703784, + -0.023279695 0.74694079 0.66448283, + -0.023593305 0.74693519 0.66447818, + -0.018159896 0.76410282 0.64483881, + -0.023623094 0.76401579 0.64476484, + -0.028163403 0.7530371 0.65737504, + -0.025819791 0.75308472 0.65741676, + -0.030953085 0.74288267 0.6687057, + -0.026266696 0.74298191 0.66879594, + -0.032172989 0.73301077 0.67945576, + -0.026346114 0.73313636 0.67957127, + -0.032603096 0.72398692 0.68904293, + -0.024584301 0.72415298 0.689201, + -0.027926017 0.7198754 0.69354141, + -0.016775202 0.72005504 0.69371408, + -0.0202547 0.71613097 0.69767201, + -0.00546464 0.71626699 0.69780499, + -0.008946253 0.71278524 0.70132524, + 0.0092052147 0.71278358 0.70132357, + 0.0060925311 0.71001804 0.70415705, + 0.028049801 0.70975202 0.70389301, + 0.026446505 0.70848906 0.70522606, + 0.052499283 0.70775974 0.70449978, + 0.05166398 0.70717978 0.70514375, + 0.082739107 0.70569706 0.70366603, + 0.082705051 0.70567656 0.70369059, + 0.11922303 0.70305216 0.70107317, + 0.11968606 0.70329535 0.70075035, + 0.16160695 0.69907582 0.69654584, + 0.16752708 0.70170438 0.69249237, + 0.21585198 0.69498396 0.68586093, + 0.25682706 0.70908719 0.65668517, + 0.31217298 0.69703096 0.64551991, + 0.35469392 0.70664585 0.6122449, + 0.41556522 0.68743432 0.59560031, + 0.44930488 0.69106281 0.5661779, + 0.51315308 0.66392606 0.54394507, + 0.54117012 0.66360515 0.51649112, + 0.61956269 0.61943972 0.48211676, + 0.63834822 0.61691624 0.46035418, + 0.70618582 0.56744987 0.4234409, + 0.72466904 0.56259608 0.39792007, + 0.77565211 0.51529509 0.36446503, + 0.79473585 0.50723785 0.3333239, + 0.83964199 0.45390701 0.298278, + 0.85733718 0.44271013 0.26264206, + 0.89653575 0.38097292 0.22601594, + 0.90903974 0.36963892 0.19238995, + 0.93743986 0.30882096 0.16073598, + 0.94395202 0.30055499 0.13646001, + 0.96401238 0.24207509 0.10990804, + 0.9672035 0.23644611 0.092794344, + 0.9810155 0.18052492 0.070847861, + 0.982427 0.17698 0.059289198, + 0.99137622 0.12425903 0.041627511, + 0.99189711 0.12227801 0.034470703, + 0.99717635 0.07227882 0.020375708, + 0.99731237 0.07136362 0.016590005, + 0.99971366 0.023307893 0.005418418, + 0.99972445 0.023078511 0.0042899321, + 0.9997285 -0.022908689 -0.0042583481, + 0.99973625 -0.022739206 -0.0032174806, + 0.99759686 -0.068601891 -0.0097068092, + 0.99764597 -0.0682422 -0.0067424402, + 0.99344277 -0.11377597 -0.011241198, + 0.99352849 -0.11339705 -0.0064996835, + 0.99360234 -0.11293304 -0.00074215827, + 0.99355423 -0.11316703 -0.0065796715, + 0.99769354 -0.067765273 -0.003939948, + 0.99766213 -0.067998707 -0.006817251, + 0.99974436 -0.022499908 -0.0022557408, + 0.99973887 -0.022621399 -0.0032492096, + 0.99973589 0.022747397 0.0032672996, + 0.9997279 0.022919899 0.0043272297, + 0.99745637 0.070042625 0.013223905, + 0.99735433 0.070746325 0.016716406, + 0.99243754 0.11946094 0.028226987, + 0.99204624 0.12099703 0.034698706, + 0.98385751 0.17201991 0.049330879, + 0.98280001 0.174784 0.0596212, + 0.97040212 0.22856303 0.077965707, + 0.96799022 0.23303506 0.093218021, + 0.95030922 0.28904006 0.11562103, + 0.94543701 0.29562399 0.13695, + 0.92084026 0.35381809 0.16390905, + 0.91165215 0.36286002 0.19293302, + 0.8781423 0.42240316 0.22459207, + 0.86541009 0.43142805 0.25482404, + 0.82651883 0.48467788 0.28627595, + 0.81229883 0.49167687 0.3137269, + 0.76734531 0.54056519 0.34492111, + 0.74760115 0.54686713 0.37686709, + 0.69745594 0.59007996 0.40664595, + 0.67206293 0.59435892 0.44166595, + 0.61855006 0.63068008 0.46865606, + 0.59268612 0.63162816 0.49976912, + 0.52392375 0.66796172 0.52851778, + 0.49486059 0.66566145 0.55857652, + 0.41925699 0.69545698 0.58357799, + 0.38313618 0.68841434 0.61586732, + 0.32843116 0.70394337 0.62975931, + 0.29087192 0.69230074 0.66038877, + 0.24099888 0.70225966 0.66988868, + 0.19786395 0.68378782 0.70234179, + 0.15468498 0.68918282 0.70788383, + 0.11724397 0.6685918 0.73432881, + 0.081588492 0.67098993 0.73696393, + 0.077934973 0.66859478 0.73953176, + 0.047954682 0.66986275 0.74093479, + 0.04903131 0.67066616 0.74013716, + 0.023467403 0.67128909 0.74082404, + 0.025453715 0.6729604 0.73924041, + 0.0042040804 0.67317307 0.73947304, + 0.0069310381 0.67575485 0.73709381, + -0.010852204 0.67573124 0.73706824, + -0.0072864909 0.67952406 0.73361707, + -0.021284107 0.67938823 0.73347026, + -0.0168084 0.68474603 0.72858799, + -0.028193092 0.68456984 0.72840184, + -0.023399208 0.69105822 0.72242022, + -0.031943504 0.69089508 0.72224903, + -0.027513312 0.69774538 0.71581733, + -0.033134211 0.69762623 0.71569526, + -0.028561508 0.70581615 0.70781916, + -0.031988211 0.70574325 0.70774525, + -0.026479904 0.71736509 0.69619405, + -0.027900709 0.71733725 0.69616723, + -0.023203913 0.72937042 0.68372542, + -0.017626496 0.7294538 0.68380284, + -0.022977699 0.71152997 0.70227993, + -0.023496896 0.71152097 0.70227194, + -0.028417613 0.69854534 0.71500134, + -0.027340103 0.69856608 0.71502304, + -0.03179701 0.68889624 0.72416222, + -0.021393297 0.67238992 0.73988795, + -0.031813003 0.67220408 0.73968208, + -0.0242368 0.69286799 0.72065699, + -0.018625788 0.69295156 0.7207436, + -0.026178205 0.66605717 0.7454412, + -0.020749206 0.66614217 0.74553621, + -0.028497113 0.64414632 0.76437134, + -0.017460598 0.62802297 0.77799886, + -0.0261855 0.62790298 0.77785099, + -0.017246801 0.66136605 0.74986506, + -0.019230099 0.66134202 0.74983799, + -0.012606502 0.69475806 0.71913308, + -0.011780703 0.69476515 0.71914017, + -0.0075940071 0.72843975 0.68506777, + -0.0040091295 0.72845495 0.68508196, + -0.0025737297 0.76146591 0.64819992, + 0.0026867907 0.76146621 0.6481992, + 0.0040949378 0.7284106 0.68512857, + 0.0077878055 0.72839457 0.68511361, + 0.011927998 0.69502991 0.71888196, + 0.012696705 0.69502324 0.71887523, + 0.0193897 0.66122502 0.749937, + 0.017220503 0.66125107 0.74996704, + 0.026203703 0.62753403 0.77814811, + 0.017694997 0.6276508 0.77829385, + 0.021903589 0.6244787 0.78073466, + 0.027467307 0.62439311 0.78062719, + 0.032223493 0.61290687 0.78949779, + 0.028914392 0.61296886 0.78957784, + 0.033773482 0.60302562 0.79700655, + 0.028135292 0.60313088 0.79714584, + 0.032991599 0.59454399 0.80338597, + 0.025132691 0.59467977 0.80356967, + 0.029687312 0.58762825 0.8085863, + 0.019206593 0.58777875 0.80879372, + 0.017537294 0.59005475 0.80717272, + -0.011806898 0.59010392 0.8072409, + -0.044564091 0.62858784 0.77646083, + -0.066029087 0.6278398 0.77553684, + -0.094657555 0.65620768 0.74861962, + -0.12248904 0.65420425 0.74633324, + -0.15173407 0.67863429 0.71863234, + -0.18427798 0.67482597 0.71459895, + -0.21328114 0.69506443 0.6865834, + -0.25103608 0.68865222 0.68024921, + -0.27816805 0.70423317 0.65320617, + -0.31974608 0.69468117 0.64434516, + -0.34443799 0.70605397 0.61874902, + -0.38932425 0.69273645 0.60707736, + -0.41881484 0.70303476 0.57474881, + -0.46648422 0.68480831 0.55984825, + -0.49796018 0.69216025 0.52244616, + -0.54742694 0.66793895 0.50416392, + -0.57496518 0.67108727 0.46803519, + -0.624717 0.64047098 0.44668299, + -0.64787316 0.64026618 0.41269809, + -0.69625884 0.60331887 0.38888291, + -0.71492434 0.60071927 0.35779819, + -0.75977129 0.55861115 0.33271813, + -0.77419811 0.55457604 0.30506203, + -0.81453913 0.50828308 0.27959704, + -0.8252421 0.50362605 0.25561002, + -0.86069632 0.45399216 0.23041908, + -0.86830068 0.44932786 0.21013893, + -0.89865887 0.39734194 0.18582699, + -0.90564072 0.39148584 0.16295294, + -0.93143326 0.3359701 0.13984403, + -0.93660939 0.33019513 0.11719304, + -0.95607936 0.2762261 0.098038137, + -0.95883602 0.27212399 0.081129901, + -0.97330737 0.21993907 0.065571621, + -0.97467273 0.21721095 0.053221788, + -0.98517686 0.16661298 0.040824097, + -0.98578125 0.16493705 0.032111209, + -0.99294275 0.11640897 0.022663394, + -0.99316233 0.11550404 0.016955605, + -0.99759012 0.068646505 0.010077101, + -0.99764234 0.068271421 0.0069847424, + -0.99974602 0.022419101 0.0022936601, + -0.99974948 0.022343012 0.0013627007, + -0.99975049 -0.022293089 -0.0013596592, + -0.99974948 -0.022311311 -0.0018053508, + -0.99964148 -0.026710114 -0.001903471, + -0.99711353 -0.075925462 -0.00012724694, + -0.99771249 -0.067559533 -0.0023379512, + -0.99770224 -0.067629717 -0.004064911, + -0.99974954 -0.02234179 -0.0013428594, + -0.99974614 -0.022416702 -0.0022592503, + -0.99974424 0.022501405 0.0022677905, + -0.99973875 0.022623995 0.0032694994, + -0.9975661 0.069010004 0.0099729607, + -0.99748951 0.069550067 0.013319293, + -0.99285126 0.11722803 0.022449905, + -0.99255288 0.11842898 0.028521096, + -0.9849419 0.16807999 0.040478297, + -0.98414153 0.17023793 0.049844578, + -0.97281075 0.22226994 0.065079488, + -0.97100753 0.22575089 0.078618661, + -0.95514566 0.27966291 0.097393565, + -0.95149654 0.28485885 0.11623095, + -0.92980623 0.34077409 0.13904503, + -0.92458886 0.34635997 0.15865098, + -0.89809513 0.39985007 0.18315302, + -0.89212775 0.40460593 0.20100296, + -0.86001813 0.45697907 0.22702204, + -0.85123819 0.46213013 0.24865507, + -0.81377769 0.51179379 0.2753779, + -0.80143702 0.51685101 0.30093801, + -0.75897986 0.56268293 0.32762396, + -0.7423988 0.56691587 0.3570019, + -0.69549882 0.60801488 0.38288292, + -0.67411381 0.6104849 0.41578692, + -0.62405121 0.64582324 0.43985516, + -0.59775501 0.64543903 0.47549701, + -0.54688698 0.674043 0.49656901, + -0.51576996 0.66976094 0.53422993, + -0.46606719 0.69166738 0.55170423, + -0.436858 0.68426901 0.583893, + -0.38896191 0.7007938 0.59799391, + -0.36468482 0.69202065 0.62298667, + -0.31931114 0.70429736 0.63403928, + -0.29172596 0.69132596 0.66103292, + -0.2504119 0.69973677 0.66907579, + -0.22027193 0.68204874 0.69734478, + -0.18332204 0.68737316 0.70278817, + -0.15217806 0.66516024 0.73102921, + -0.12101594 0.66805267 0.73420763, + -0.089185268 0.64086574 0.76245469, + -0.06397593 0.6421113 0.76393735, + -0.027911691 0.60537374 0.7954517, + 0.0068991468 0.60559571 0.79574263, + 0.0096967444 0.60228628 0.79822135, + 0.023001995 0.60215491 0.79804784, + 0.018908396 0.60762388 0.79399985, + 0.029463993 0.6074689 0.79379684, + 0.024723111 0.61462831 0.78842938, + 0.032903615 0.6144833 0.78824335, + 0.028173083 0.62264067 0.78200054, + 0.033744194 0.6225329 0.78186584, + 0.028897908 0.6322062 0.77426118, + 0.032072999 0.63214499 0.77418602, + 0.027188282 0.64365166 0.76483554, + 0.028625792 0.6436258 0.76480484, + 0.022021297 0.66246295 0.74877095, + 0.027106509 0.66238022 0.74867725, + 0.03189151 0.65139621 0.75806731, + 0.028821897 0.65145695 0.75813788, + 0.033813305 0.64175004 0.76616812, + 0.028013596 0.64186496 0.76630586, + 0.032888893 0.63366783 0.77290583, + 0.0247199 0.63381702 0.77308798, + 0.029104996 0.62736297 0.77818286, + 0.018749392 0.62751877 0.77837569, + 0.022783987 0.62227064 0.78247052, + 0.0090795392 0.62240595 0.78264189, + 0.012738594 0.61817068 0.78594065, + -0.0043649701 0.61821502 0.78599697, + -0.008224912 0.62218112 0.78283018, + -0.048698589 0.62146389 0.78192782, + -0.088034458 0.65608168 0.74953765, + -0.11758903 0.65406919 0.74723917, + -0.15159799 0.67895395 0.71835893, + -0.18688893 0.67479074 0.71395373, + -0.22004607 0.69474024 0.68477422, + -0.26116693 0.68747884 0.67761683, + -0.29168695 0.70219582 0.64949185, + -0.33729219 0.69110042 0.63922936, + -0.36468112 0.70125026 0.61258125, + -0.41336891 0.68575984 0.59904885, + -0.4367801 0.69197315 0.57480115, + -0.48690981 0.67188376 0.55811381, + -0.48677394 0.66662496 0.56450194, + -0.41371894 0.69476694 0.58833295, + -0.38724807 0.68753207 0.61427903, + -0.33778998 0.70188391 0.62710196, + -0.30716512 0.69020623 0.65518326, + -0.26165912 0.70000035 0.66448027, + -0.227523 0.68306398 0.69401503, + -0.18719395 0.68906176 0.70010877, + -0.15143196 0.66693485 0.7295658, + -0.11746203 0.6700452 0.73296815, + -0.074825302 0.63781899 0.76654297, + -0.028306592 0.63935584 0.76838982, + -0.023026899 0.63465697 0.77245086, + -0.0024069403 0.63482404 0.7726531, + -0.0052649002 0.63769501 0.770271, + 0.011978204 0.63765824 0.7702263, + 0.008418018 0.64166981 0.76693481, + 0.022496402 0.64153004 0.7667681, + 0.018237991 0.64692372 0.76233667, + 0.029241703 0.64675504 0.76213712, + 0.024894385 0.65298259 0.75696355, + 0.032794196 0.65283394 0.75679088, + 0.02794081 0.66078025 0.75005931, + 0.033663988 0.66066378 0.74992675, + 0.028665705 0.67013109 0.74168909, + 0.031876493 0.67006582 0.74161685, + 0.026667709 0.68169725 0.73114824, + 0.028255196 0.68166792 0.73111594, + 0.021575594 0.69968879 0.71412182, + 0.026747797 0.69960093 0.71403295, + 0.031501185 0.68928766 0.72380263, + 0.028112384 0.68935758 0.72387558, + 0.033582997 0.67928493 0.73310596, + 0.027673993 0.67940784 0.73323882, + 0.032675195 0.67143697 0.74034095, + 0.0245058 0.67159402 0.74051398, + 0.029183803 0.66506606 0.74621403, + 0.018198399 0.66523993 0.74640793, + 0.021949599 0.66061395 0.75040489, + 0.0080456808 0.66075206 0.75056112, + 0.011364799 0.65711594 0.75370389, + -0.0060652508 0.65714705 0.75373811, + -0.0033514588 0.65449977 0.7560547, + -0.024469703 0.65430808 0.75583214, + -0.022287399 0.65241295 0.75753587, + -0.047710907 0.65183204 0.75686109, + -0.05392221 0.65659416 0.75231415, + -0.10733102 0.65375221 0.74905819, + -0.15237497 0.68267781 0.71465582, + -0.19128503 0.67798907 0.70974708, + -0.22870497 0.69716793 0.67944896, + -0.27376595 0.68878984 0.67128283, + -0.30832303 0.70242107 0.64151508, + -0.35810274 0.68942553 0.62964654, + -0.38819009 0.6979422 0.60181814, + -0.441284 0.67960602 0.586007, + -0.469569 0.68453997 0.55759299, + -0.53665787 0.65422779 0.53290188, + -0.56725097 0.65617591 0.49765393, + -0.62047189 0.62484986 0.47389588, + -0.64868271 0.6230647 0.43703678, + -0.6999318 0.58470988 0.4101339, + -0.72202778 0.5802508 0.37680885, + -0.76921564 0.53590578 0.34801182, + -0.78581846 0.53002167 0.31869477, + -0.82793719 0.48062712 0.28899407, + -0.83976531 0.47437617 0.2641241, + -0.87603676 0.4213379 0.23459294, + -0.88408625 0.4154231 0.21404505, + -0.91402978 0.36059591 0.18579595, + -0.920968 0.35364401 0.16356599, + -0.94552225 0.29548305 0.13666603, + -0.95032185 0.28899297 0.11563499, + -0.96799576 0.23300594 0.093232878, + -0.97038323 0.22858305 0.078142323, + -0.98278838 0.17480306 0.059757221, + -0.98384446 0.17204809 0.049494222, + -0.99203962 0.12101796 0.03481409, + -0.9924345 0.11947094 0.028292887, + -0.99735314 0.07075271 0.016755601, + -0.99745715 0.070036106 0.013199802, + -0.99972802 0.022918399 0.0043194601, + -0.99973613 0.022742203 0.0032368705, + -0.99973899 -0.022617999 -0.0032192001, + -0.99974447 -0.022497511 -0.0022343011, + -0.99766266 -0.067996681 -0.0067529576, + -0.99769253 -0.067774668 -0.0040150881, + -0.99355203 -0.113179 -0.0067049302, + -0.99360067 -0.11294597 -0.00089569762, + -0.98486513 -0.17322202 -0.0059038708, + -0.98728675 -0.15894195 -0.0015346296, + -0.99219024 -0.12464303 -0.0047618109, + -0.99217767 -0.12474295 -0.004763958, + -0.99218577 -0.12474397 -0.0025230993, + -0.99712014 -0.075832605 0.00090480014, + -0.99711466 -0.075832069 -0.0034489189, + -0.99711013 -0.075892009 -0.0034502305, + -0.99711555 -0.075892366 0.00090248958, + -0.99711311 -0.07592541 0.00090249011, + -0.99963897 -0.0267101 -0.0029139, + -0.99966425 -0.025738705 -0.0030083808, + -0.9970125 0.077167436 -0.0033618417, + -0.99746197 0.071084999 -0.0040689898, + -0.99747014 0.071085505 0.00048139205, + -0.99358237 0.11305103 0.0036763214, + -0.9935469 0.11319198 0.0072263093, + -0.98712379 0.15963295 0.010191097, + -0.98693877 0.16017595 0.017188096, + -0.97789979 0.20788096 0.022307293, + -0.97738588 0.20898996 0.032247897, + -0.96545178 0.25753394 0.039738391, + -0.96429539 0.25942808 0.053212218, + -0.94889152 0.30916587 0.063413873, + -0.94665277 0.31198493 0.080709077, + -0.92706221 0.36295909 0.093896024, + -0.92306888 0.36681798 0.11570799, + -0.89845729 0.41872314 0.13208105, + -0.89330727 0.42254514 0.15315907, + -0.8652916 0.47126576 0.17081892, + -0.85990328 0.47419617 0.18895608, + -0.82781488 0.52114993 0.20766596, + -0.82040012 0.52399606 0.22884902, + -0.78406888 0.56879395 0.24841397, + -0.77426612 0.57114506 0.27259004, + -0.73397326 0.61294621 0.29254112, + -0.72150695 0.61427993 0.31951198, + -0.67831415 0.65186417 0.33906209, + -0.66301006 0.65159607 0.36856502, + -0.61775315 0.68446416 0.3871561, + -0.59957069 0.68197072 0.41884479, + -0.55308604 0.70992208 0.43601206, + -0.53226012 0.70460218 0.46929213, + -0.48565105 0.72755009 0.48457605, + -0.46263281 0.71891767 0.51877576, + -0.417781 0.73675603 0.53164798, + -0.39308518 0.72447336 0.5662353, + -0.35108596 0.73774195 0.57660693, + -0.32552096 0.72175592 0.61082292, + -0.28697506 0.73122317 0.6188361, + -0.26126593 0.71160883 0.6521908, + -0.22690913 0.71798539 0.65803444, + -0.20361388 0.69671559 0.68784356, + -0.1736989 0.7008056 0.6918816, + -0.15361807 0.67915827 0.71773636, + -0.12754105 0.68170321 0.72042626, + -0.108031 0.65697402 0.74613303, + -0.086073026 0.65838915 0.74774015, + -0.06782762 0.63108921 0.77273929, + -0.050318278 0.63174468 0.77354163, + -0.033905305 0.60250306 0.79739612, + -0.021045802 0.60271609 0.79767811, + -0.0067763757 0.57207465 0.8201735, + 0.0013660198 0.57208693 0.82019186, + 0.016232597 0.53272486 0.84613281, + 0.025503496 0.53262192 0.8459689, + 0.022010399 0.54410893 0.83872586, + 0.027305704 0.54403806 0.83861613, + 0.0284271 0.54106998 0.84049702, + 0.015704703 0.54122204 0.84073311, + -0.0024734887 0.58100462 0.81389654, + -0.012776195 0.58095884 0.8138327, + -0.029855404 0.61182809 0.79042715, + -0.045093488 0.61147887 0.78997481, + -0.064185582 0.64044183 0.76531982, + -0.08416266 0.63948768 0.76418066, + -0.10485598 0.6660648 0.73848683, + -0.12935898 0.66412979 0.73634082, + -0.15093809 0.68768442 0.71014643, + -0.17978096 0.68431979 0.70667183, + -0.20142899 0.70438403 0.68063903, + -0.23418203 0.69912708 0.67555904, + -0.25938007 0.71877319 0.6450482, + -0.29622295 0.71084183 0.63793081, + -0.32381397 0.72858894 0.60357493, + -0.36464012 0.71705925 0.59402323, + -0.39151001 0.730892 0.55903202, + -0.43584314 0.71488625 0.54678917, + -0.461164 0.72481501 0.51183099, + -0.50779217 0.70371121 0.49692819, + -0.53086197 0.70999402 0.46270299, + -0.5779807 0.68368071 0.44555479, + -0.59824407 0.68680304 0.41280207, + -0.64452803 0.65531904 0.39387906, + -0.66175205 0.65591604 0.36312303, + -0.70626819 0.6193651 0.34288809, + -0.72033918 0.61810613 0.31473207, + -0.76210499 0.57696402 0.29378301, + -0.77321488 0.57449996 0.26849297, + -0.81101811 0.52999705 0.24769503, + -0.81948602 0.52690601 0.225417, + -0.85294646 0.4799237 0.20531788, + -0.8591429 0.47667494 0.18615699, + -0.88835222 0.4277041 0.16703205, + -0.89270073 0.42462686 0.15092194, + -0.91769826 0.37433708 0.13304803, + -0.91953766 0.36703488 0.14048396, + -0.88771278 0.42997792 0.16457495, + -0.88269323 0.43342108 0.18165605, + -0.85216272 0.48260283 0.20226993, + -0.84505868 0.48618081 0.22249493, + -0.81009483 0.53312391 0.24397793, + -0.80044883 0.5364539 0.26739293, + -0.76106632 0.58055216 0.28937408, + -0.74846405 0.58310807 0.31589004, + -0.70513743 0.62346238 0.33775121, + -0.68921024 0.62459326 0.36725011, + -0.64333481 0.65995681 0.3880429, + -0.62400723 0.65893525 0.42002314, + -0.57674873 0.68887365 0.43910578, + -0.55412692 0.68497992 0.47301793, + -0.50651717 0.70949924 0.48995018, + -0.48094013 0.70207018 0.52516115, + -0.43451384 0.72121775 0.53948385, + -0.4067561 0.70982617 0.5750621, + -0.36321199 0.72394401 0.58649999, + -0.33405915 0.70839435 0.62175727, + -0.29464489 0.71820575 0.63036877, + -0.26778489 0.70047164 0.66153669, + -0.23234008 0.70712823 0.66782326, + -0.20933005 0.68888217 0.69399017, + -0.17748091 0.69330567 0.69844663, + -0.15399306 0.67123824 0.72506922, + -0.12655306 0.67387933 0.72792238, + -0.10353704 0.64839321 0.75423229, + -0.080825381 0.64976382 0.75582683, + -0.059044831 0.62137127 0.78128839, + -0.041258983 0.62192678 0.78198773, + -0.021233898 0.59107393 0.80633789, + -0.0085482579 0.59118485 0.80649084, + 0.013142298 0.55118597 0.83427888, + 0.029404411 0.55099517 0.83399028, + 0.028669603 0.55260503 0.83295012, + 0.031993203 0.55254906 0.83286613, + 0.02734529 0.56462181 0.82489669, + 0.028584987 0.56460267 0.82486761, + 0.022097711 0.58504832 0.81069738, + 0.027356099 0.58497202 0.810592, + 0.032057688 0.57304782 0.81889468, + 0.028829111 0.5731042 0.81897527, + 0.033593096 0.56287092 0.82586187, + 0.028481808 0.56296015 0.82599318, + 0.028628893 0.56268889 0.82617283, + 0.008002284 0.56290132 0.8264854, + -0.017242106 0.60263824 0.79782832, + -0.032642584 0.60240668 0.79752165, + -0.055593815 0.63283515 0.7722882, + -0.076191597 0.63197303 0.771236, + -0.10063598 0.65948182 0.74495381, + -0.12641001 0.65752906 0.74274904, + -0.15163599 0.68160295 0.71583796, + -0.182336 0.67801702 0.71207201, + -0.20746605 0.69824517 0.6851362, + -0.24235909 0.69249523 0.67949426, + -0.26632696 0.70863295 0.65338296, + -0.30469316 0.70022833 0.64563328, + -0.332818 0.71572399 0.61398, + -0.375121 0.70356899 0.60355198, + -0.40559608 0.7166692 0.5673421, + -0.45163289 0.69953883 0.55378085, + -0.47982913 0.70827121 0.51779914, + -0.52772683 0.68570977 0.50130481, + -0.55302793 0.69055092 0.46615395, + -0.6011591 0.6623432 0.44711211, + -0.62291038 0.66391039 0.41377023, + -0.67013699 0.62991601 0.392584, + -0.68813795 0.62898892 0.36171696, + -0.73310697 0.58957499 0.33905101, + -0.74745375 0.58695173 0.31112787, + -0.78853387 0.54337293 0.28802797, + -0.79952866 0.53980476 0.26337188, + -0.83614439 0.49296424 0.24051812, + -0.84426379 0.48905188 0.21919595, + -0.8762641 0.43968707 0.19707003, + -0.8820349 0.43586195 0.17899399, + -0.90941358 0.38471583 0.15798992, + -0.91115344 0.37730819 0.16564408, + -0.87558991 0.44230795 0.19417997, + -0.8689813 0.44652915 0.21326807, + -0.83534187 0.49605593 0.23692296, + -0.82603216 0.50033009 0.25950107, + -0.78763467 0.54695177 0.28368184, + -0.77505589 0.55075991 0.30976096, + -0.73214734 0.59368932 0.33390614, + -0.71580023 0.59633327 0.36334112, + -0.66916108 0.63460207 0.38665706, + -0.64872169 0.63523072 0.4190968, + -0.60020578 0.66763377 0.44047484, + -0.57574493 0.66536993 0.47518495, + -0.52680016 0.69170326 0.49399218, + -0.498658 0.685745 0.53018302, + -0.45072594 0.70620596 0.54600292, + -0.41946909 0.69588315 0.58291709, + -0.37418091 0.7108978 0.59549385, + -0.34513819 0.69788635 0.62756228, + -0.30361584 0.70847666 0.63708568, + -0.27906704 0.69463706 0.66302407, + -0.24097399 0.70205897 0.67010802, + -0.21451297 0.68394393 0.69728392, + -0.18053502 0.68873906 0.70217204, + -0.15339501 0.66651309 0.72954106, + -0.12407006 0.66928428 0.73257434, + -0.096930288 0.64291793 0.75977689, + -0.073300995 0.64422196 0.76131791, + -0.047507383 0.61465174 0.78736669, + -0.029119203 0.61508608 0.78792214, + -0.00019766192 0.57585084 0.81755471, + 0.024546094 0.57567686 0.81730884, + 0.025282605 0.57451403 0.81810415, + 0.033141609 0.57438213 0.81791615, + 0.028294297 0.58316493 0.81186086, + 0.033673603 0.58306807 0.81172514, + 0.028874813 0.59313327 0.80458635, + 0.03197781 0.59307724 0.8045103, + 0.027352612 0.60453427 0.79610938, + 0.028549893 0.60451388 0.79608279, + 0.017937709 0.58832532 0.80842537, + 0.026083605 0.58822012 0.80828017, + 0.017362203 0.62265712 0.7823022, + 0.019491104 0.6226331 0.78227121, + 0.012867101 0.65794504 0.75295609, + 0.011831393 0.65795356 0.75296551, + 0.007707661 0.69309705 0.72080308, + 0.0040487987 0.69311178 0.72081876, + 0.0026377791 0.72779876 0.68578577, + -0.0024482703 0.72779906 0.68578607, + -0.0038736209 0.69297916 0.72094721, + -0.0078488728 0.69296324 0.72093022, + -0.011967893 0.65801859 0.7529065, + -0.012614698 0.65801293 0.7529009, + -0.019219108 0.62288123 0.78208029, + -0.017119203 0.62290508 0.7821101, + -0.025949409 0.58808023 0.80838633, + -0.0178254 0.58818501 0.80852997, + -0.032360006 0.58173811 0.81273216, + 0.0046933494 0.58203691 0.81314886, + 0.029164096 0.61510092 0.78790885, + 0.047554292 0.61466694 0.78735191, + 0.07324709 0.64411592 0.76141286, + 0.096949264 0.64280778 0.75986773, + 0.12397595 0.66906476 0.73279077, + 0.15322998 0.66630393 0.72976696, + 0.18031801 0.68849504 0.70246708, + 0.21425304 0.68371415 0.69758916, + 0.24073809 0.70185524 0.67040622, + 0.27876106 0.69445819 0.66334015, + 0.30361393 0.70847285 0.6370908, + 0.34518519 0.69786936 0.62755531, + 0.37264898 0.71020293 0.59728092, + 0.41780078 0.69532967 0.58477271, + 0.44853494 0.70556092 0.54863495, + 0.49636105 0.68531305 0.53289008, + 0.52500206 0.69146204 0.49623907, + 0.57390785 0.66531682 0.47747588, + 0.59878814 0.66768616 0.44232112, + 0.64736301 0.63540202 0.42093399, + 0.66811401 0.63481098 0.38812199, + 0.71482426 0.59662724 0.36477712, + 0.73142302 0.59397602 0.33498201, + 0.77444988 0.55104393 0.31076998, + 0.78721613 0.54719907 0.28436604, + 0.82567132 0.50059116 0.2601451, + 0.83511418 0.49626613 0.23728506, + 0.88481712 0.42517605 0.19058903, + 0.84413952 0.48922071 0.21929787, + 0.83591491 0.49317995 0.24087296, + 0.79925621 0.54002315 0.26375106, + 0.78811198 0.54363 0.288697, + 0.74695402 0.58721 0.31184, + 0.73238206 0.58985305 0.34013203, + 0.68737119 0.62919319 0.36281809, + 0.66909117 0.6301012 0.39406809, + 0.62181193 0.66400295 0.41527095, + 0.59974122 0.66236424 0.44898114, + 0.55158079 0.69044763 0.46801779, + 0.52591908 0.68547404 0.50352204, + 0.47805583 0.70787477 0.51997679, + 0.44943011 0.69892818 0.55633813, + 0.40349892 0.71587884 0.56982988, + 0.37357387 0.70294279 0.60523874, + 0.33142313 0.71497822 0.61560124, + 0.30468613 0.70022225 0.64564323, + 0.2663399 0.70862275 0.65338874, + 0.24212506 0.69231319 0.6797632, + 0.20727593 0.69804776 0.68539476, + 0.1821209 0.67779368 0.71233964, + 0.15146801 0.68136805 0.71609706, + 0.126312 0.65735698 0.74291801, + 0.10055206 0.65930641 0.74512041, + 0.076143473 0.63183874 0.77135068, + 0.055574406 0.63269907 0.77240109, + 0.032691307 0.60237014 0.79754716, + 0.017335694 0.60260177 0.79785371, + -0.0078786407 0.56292105 0.82647312, + -0.028281193 0.56271386 0.82616782, + -0.028419901 0.56245703 0.82633799, + -0.033768401 0.56236398 0.82620001, + -0.028849 0.572932 0.81909502, + -0.031731084 0.5728817 0.81902361, + -0.027040394 0.58478189 0.81073982, + -0.022056108 0.58485323 0.8108393, + -0.028531307 0.56445414 0.8249712, + -0.027028603 0.56447709 0.82500613, + -0.031689487 0.55236679 0.83299869, + -0.028996792 0.55241185 0.83306682, + -0.029574307 0.55114812 0.83388317, + -0.012980097 0.5513429 0.83417779, + 0.0086142085 0.59114987 0.80651581, + 0.021319499 0.59103799 0.80636197, + 0.041293189 0.62180489 0.7820828, + 0.059018701 0.62125099 0.78138602, + 0.080774359 0.64960873 0.75596565, + 0.103451 0.64824098 0.75437498, + 0.12640493 0.67365956 0.72815156, + 0.15382501 0.67102408 0.72530305, + 0.177311 0.69309598 0.69869798, + 0.20914397 0.68867993 0.69424695, + 0.2323779 0.70710766 0.66783172, + 0.26779595 0.70045584 0.66154879, + 0.29336011 0.71735823 0.63193125, + 0.33266103 0.70763707 0.62336707, + 0.3613649 0.72301382 0.58878386, + 0.404641 0.70909601 0.57744998, + 0.43275678 0.72070765 0.54157376, + 0.47915587 0.7016958 0.5272879, + 0.50506788 0.70928383 0.49175489, + 0.55267102 0.684892 0.47484499, + 0.57562405 0.68888909 0.44055507, + 0.6228984 0.65905648 0.4214763, + 0.64250571 0.66012567 0.38912782, + 0.6884352 0.62482011 0.36831608, + 0.70457 0.62369502 0.338505, + 0.74796695 0.58335495 0.31661096, + 0.76074916 0.58077413 0.28976205, + 0.80017388 0.53667992 0.26776198, + 0.80993563 0.53331274 0.24409388, + 0.8449353 0.48634818 0.22259808, + 0.85211056 0.48273277 0.20217991, + 0.88266826 0.43351009 0.18156505, + 0.88954878 0.4286949 0.15787196, + 0.91646713 0.37546006 0.13826701, + 0.92174089 0.37056896 0.11433399, + 0.94289577 0.3182829 0.098201476, + 0.94583821 0.31469309 0.079740025, + 0.96226901 0.26376399 0.066835202, + 0.96381676 0.26129693 0.052735887, + 0.97639197 0.21173701 0.042733599, + 0.97713536 0.21017107 0.03216831, + 0.98653048 0.16169508 0.02474861, + 0.98683637 0.16081207 0.017135305, + 0.99342334 0.11385503 0.012131805, + 0.99351954 0.11344595 0.0069964766, + 0.99771386 0.067548096 0.0020576299, + 0.99770147 0.067634031 0.0041711619, + 0.99975288 0.022231597 -0.00014091098, + 0.99975061 0.022292893 0.0013540596, + 0.99769163 0.067782879 0.0041171187, + 0.9976579 0.068027593 0.0071347491, + 0.99337578 0.11428397 0.011986197, + 0.99322438 0.11491805 0.017299706, + 0.98639411 0.16256602 0.024472704, + 0.98595786 0.16380298 0.032490198, + 0.97608614 0.21323003 0.042294204, + 0.97507399 0.215314 0.053578701, + 0.96167815 0.26606703 0.066207908, + 0.95960802 0.26926899 0.081526801, + 0.94185877 0.32159191 0.097368479, + 0.93793821 0.3261891 0.11778203, + 0.91475576 0.37999392 0.13720997, + 0.90773928 0.38616014 0.16398107, + 0.87785631 0.44082513 0.18719406, + 0.86881101 0.44670701 0.213589, + 0.87074882 0.43830588 0.22289994, + 0.82488084 0.50389087 0.25625294, + 0.8140173 0.50859916 0.28054008, + 0.77359211 0.55487007 0.30606303, + 0.7589252 0.55894113 0.33409208, + 0.7139504 0.60101634 0.35924122, + 0.69494092 0.60361594 0.39077494, + 0.64652568 0.6404047 0.41459179, + 0.62296695 0.64054495 0.44901493, + 0.57313895 0.67101496 0.47037295, + 0.54510987 0.66772079 0.50695586, + 0.49567118 0.69173026 0.52518517, + 0.46468699 0.68440801 0.56182897, + 0.41715607 0.70246303 0.57665104, + 0.38940495 0.69274396 0.60701692, + 0.34448579 0.70607561 0.61869764, + 0.31959099 0.69460702 0.64450198, + 0.27784488 0.70418763 0.65339267, + 0.25032198 0.68837595 0.68079191, + 0.21303 0.69469202 0.687038, + 0.18423298 0.67458194 0.71484095, + 0.151566 0.67840099 0.71888798, + 0.12247495 0.65409678 0.74642974, + 0.09467712 0.65609819 0.7487132, + 0.066121012 0.62780619 0.77555621, + 0.044632688 0.62855583 0.77648282, + 0.016560499 0.59570593 0.80303186, + 0.0011805505 0.59578729 0.80314136, + -0.017796895 0.56970185 0.82165873, + -0.028366003 0.56956303 0.8214581, + -0.025391696 0.57427591 0.81826788, + -0.03318999 0.57414484 0.81808072, + -0.028345004 0.58292407 0.8120321, + -0.033661503 0.58282804 0.81189811, + -0.028707996 0.59321392 0.80453289, + -0.0318195 0.59315801 0.80445701, + -0.027167706 0.60467315 0.7960102, + -0.028616913 0.60464829 0.79597837, + -0.021948002 0.62464404 0.78060114, + -0.027218901 0.62456298 0.78049999, + -0.032012906 0.6129961 0.78943717, + -0.028718913 0.61305732 0.78951633, + -0.033597995 0.60307992 0.79697287, + -0.028000109 0.60318422 0.79711032, + -0.0330358 0.59428197 0.80357802, + -0.025258405 0.5944171 0.80376017, + -0.029798504 0.58738607 0.80875814, + -0.019638103 0.58753407 0.80896109, + -0.021643803 0.58479106 0.81089514, + -0.0079309605 0.58490908 0.81106013, + 0.013754798 0.61075795 0.79169786, + 0.032880001 0.61048502 0.791345, + 0.064073183 0.64213181 0.76391184, + 0.089336708 0.64088106 0.76242411, + 0.12100397 0.66792381 0.73432684, + 0.15212798 0.66503692 0.73115194, + 0.183258 0.68724102 0.70293403, + 0.219891 0.68197 0.69754201, + 0.24969694 0.69946784 0.66962379, + 0.29146099 0.69098699 0.66150397, + 0.31915492 0.70402884 0.63441581, + 0.3642351 0.69184917 0.62344015, + 0.38904691 0.7008208 0.59790689, + 0.43687099 0.68431699 0.58382702, + 0.46427688 0.69128782 0.5536859, + 0.51401097 0.66950697 0.53623992, + 0.54458004 0.67380506 0.49941906, + 0.59545887 0.64542681 0.4783859, + 0.62230736 0.64591134 0.44219026, + 0.67244154 0.6107406 0.4181127, + 0.69418901 0.60829699 0.38480699, + 0.74122661 0.56727773 0.35885781, + 0.7581377 0.56300783 0.32901287, + 0.80070865 0.51721376 0.30225086, + 0.81325871 0.51210183 0.27633691, + 0.8508057 0.46244782 0.24954291, + 0.86274385 0.45533395 0.21987297, + 0.89638722 0.3991701 0.19275205, + 0.90560269 0.39157686 0.16294594, + 0.93141174 0.33603391 0.13983297, + 0.93664098 0.330194 0.116943, + 0.95610338 0.27621809 0.097826339, + 0.95886397 0.272102 0.080872603, + 0.97332764 0.21991192 0.065361075, + 0.97468138 0.21720207 0.05310002, + 0.98518175 0.16660696 0.040730789, + 0.98577553 0.16495992 0.032169987, + 0.99294037 0.11642204 0.022704208, + 0.99315602 0.115535 0.0171145, + 0.99758822 0.068660915 0.010170903, + 0.99764115 0.068282604 0.0070522511, + 0.99974591 0.022421299 0.0023156898, + 0.99974954 0.022341289 0.0013370194, + 0.99975061 -0.022291793 -0.0013340595, + 0.99975109 -0.022284301 -0.0011502001, + 0.99971747 -0.023764411 -0.00058137032, + 0.99973321 -0.023093805 -0.00056959811, + 0.99967939 0.025311384 0.00062429567, + 0.99967927 0.025311405 0.00090017723, + 0.99967825 0.025348905 0.00090017723, + 0.99967849 0.025348911 -0.0006273383, + 0.99967486 0.025489796 -0.00062482792, + 0.99967474 0.025489794 0.00089211576, + 0.99723238 0.074301332 -0.002641781, + 0.99723577 0.074301586 -0.00034497792, + 0.99723625 0.074294917 -0.00034509908, + 0.99723011 0.074294508 -0.0035303805, + 0.99701309 0.077167407 -0.0031963105, + 0.99966449 -0.025738712 -0.0029279315, + 0.99971187 -0.023764197 -0.0033855096, + 0.99971378 -0.023680694 -0.0033936293, + 0.9997189 -0.023680797 -0.0011743698, + 0.9973501 -0.072750106 -0.00052840105, + 0.99734986 -0.072750092 0.00087720086, + 0.99735725 -0.072648816 0.00087720121, + 0.99735421 -0.072648615 -0.0025891508, + 0.99734014 -0.072842509 -0.0025924603, + 0.99734312 -0.07284271 0.00086972211, + 0.99258047 -0.12157206 -0.0020795108, + 0.99257553 -0.12157094 -0.0037694981, + 0.99258524 -0.12149203 -0.003768171, + 0.99258351 -0.12149194 -0.0042165481, + 0.99171674 -0.12840196 -0.0032953094, + 0.85730779 -0.51478887 -0.0039736889, + 0.87061316 -0.49196813 -4.0984713e-005, + 0.87057728 -0.49194717 -0.0091201039, + 0.8506887 -0.52563083 -0.0064028776, + 0.85001171 -0.52606481 -0.027129991, + 0.87537044 -0.48281124 -0.024899311, + 0.8742218 -0.48364088 -0.042753588, + 0.89709121 -0.44012913 -0.038907107, + 0.89556146 -0.44143972 -0.055682566, + 0.91629523 -0.39735508 -0.05012181, + 0.91450685 -0.39916593 -0.065907292, + 0.93327177 -0.35437292 -0.058511283, + 0.93133622 -0.3566891 -0.073388517, + 0.94807655 -0.31151685 -0.064094469, + 0.94609839 -0.31432012 -0.078107528, + 0.96094251 -0.26857987 -0.066741168, + 0.95902503 -0.27182701 -0.079882197, + 0.97210538 -0.22502908 -0.066129722, + 0.97036701 -0.228617 -0.078244098, + 0.98172379 -0.18005796 -0.061624885, + 0.98031187 -0.18375099 -0.072277993, + 0.98966378 -0.13345397 -0.052493688, + 0.98868054 -0.13694794 -0.061286271, + 0.99576545 -0.083911635 -0.03755182, + 0.99526721 -0.086724222 -0.043843612, + 0.99945635 -0.029425111 -0.014875906, + 0.99937725 -0.030684607 -0.017422503, + 0.99933589 0.031687696 0.017992098, + 0.99930263 0.03218909 0.018924793, + 0.99305767 0.10140196 0.059616677, + 0.99342799 0.099571101 0.056448098, + 0.97975224 0.17417204 0.098740123, + 0.98063922 0.17153305 0.094462521, + 0.9571051 0.25380102 0.13976702, + 0.95826399 0.25140899 0.13610201, + 0.92073661 0.34313086 0.18575591, + 0.92386585 0.33838996 0.17878498, + 0.88030076 0.41946891 0.22162195, + 0.88300329 0.41628414 0.21682407, + 0.8299467 0.49475381 0.25769591, + 0.83226788 0.49260694 0.25429997, + 0.77039129 0.56653517 0.29246411, + 0.77233386 0.56512797 0.29005298, + 0.70336509 0.63239706 0.32457903, + 0.71820098 0.62382799 0.308263, + 0.62114197 0.70259792 0.34718698, + 0.63725895 0.69551092 0.33191198, + 0.56239611 0.74624819 0.3561241, + 0.55644774 0.74819463 0.36134583, + 0.48169187 0.78912884 0.3811149, + 0.46764189 0.7919898 0.39250892, + 0.39597094 0.82276291 0.40775993, + 0.41179994 0.82103986 0.39536595, + 0.34398621 0.84599745 0.40738425, + 0.36424118 0.84508139 0.39136419, + 0.29921016 0.86584544 0.40098017, + 0.31236196 0.86606187 0.39034194, + 0.25084296 0.88253087 0.39776495, + 0.25910187 0.88322359 0.39087382, + 0.20180692 0.89563757 0.39636782, + 0.20408 0.89599502 0.394391, + 0.15236598 0.90457088 0.39816594, + 0.15055408 0.90414143 0.39982718, + 0.10488704 0.90952128 0.40220615, + 0.10035904 0.90805942 0.4066402, + 0.061395615 0.91094524 0.40793309, + 0.055652674 0.90855861 0.4140338, + 0.023465488 0.90971857 0.41456178, + 0.018345598 0.90707791 0.42056295, + -0.0070098024 0.90720832 0.42062315, + -0.010545596 0.90500468 0.42527086, + -0.029546993 0.90465975 0.42510891, + -0.03135521 0.90332031 0.42781916, + -0.044662703 0.90286314 0.42760205, + -0.044372316 0.90311629 0.42709714, + -0.052574575 0.90275657 0.42692679, + -0.051147893 0.90422189 0.42398894, + -0.055033382 0.90403467 0.42390186, + -0.052252583 0.90741068 0.41698384, + -0.052371506 0.90740514 0.41698107, + -0.04780139 0.91400278 0.40288192, + -0.045870278 0.91408557 0.40291882, + -0.042293411 0.92037922 0.38873309, + -0.032420203 0.92071915 0.38887706, + -0.036838185 0.91055572 0.41174185, + -0.024681605 0.90236223 0.43027109, + -0.028681496 0.90226591 0.43022496, + -0.023052195 0.92088175 0.38915992, + -0.018385792 0.92097062 0.38919786, + -0.015125704 0.93806422 0.34613109, + -0.0066220202 0.938151 0.346163, + -0.0059935078 0.94756663 0.31950188, + 0.0059811785 0.94756675 0.31950191, + 0.0065995976 0.93813866 0.34619689, + 0.015197598 0.93805087 0.34616396, + 0.018449407 0.92099434 0.38913915, + 0.023044208 0.92090636 0.38910216, + 0.028672393 0.90229774 0.43015891, + 0.029472992 0.90227675 0.4301489, + 0.035220489 0.90510368 0.42372984, + 0.039153401 0.904971 0.423668, + 0.032420203 0.92071915 0.38887706, + 0.042325988 0.92037779 0.38873291, + 0.046336986 0.91330272 0.40463686, + 0.048714694 0.91319889 0.40459195, + 0.051834311 0.90869826 0.41422307, + 0.051212881 0.90872771 0.41423586, + 0.054336999 0.90495902 0.42201501, + 0.049986977 0.9051646 0.42211178, + 0.052629583 0.90245467 0.42755786, + 0.044608422 0.90280741 0.4277252, + 0.044946201 0.90251201 0.42831299, + 0.031739395 0.9029699 0.42852995, + 0.029952796 0.90429688 0.42585194, + 0.011089003 0.90464723 0.42601708, + 0.007658653 0.90679228 0.42150816, + -0.017710399 0.90667689 0.42145395, + -0.022540199 0.90917987 0.41579294, + -0.05436058 0.90806669 0.41528285, + -0.059911985 0.91038978 0.4093909, + -0.098843016 0.90756214 0.40811905, + -0.103515 0.90908402 0.403548, + -0.14885002 0.90381223 0.40120709, + -0.15089397 0.90430176 0.39933592, + -0.20250691 0.89582258 0.39559183, + -0.20104092 0.89558971 0.39686486, + -0.258167 0.88326299 0.39140299, + -0.25170791 0.88272268 0.39679185, + -0.3133201 0.86616319 0.38934809, + -0.300529 0.86597502 0.399712, + -0.36571997 0.8450489 0.39005294, + -0.345146 0.84601903 0.40635699, + -0.41305384 0.82092172 0.39430186, + -0.39949405 0.82244414 0.40495706, + -0.47108775 0.79135865 0.38965082, + -0.48146611 0.7892192 0.3812131, + -0.55643892 0.74817991 0.36138996, + -0.55932015 0.74724525 0.35886711, + -0.63425964 0.69691658 0.3346968, + -0.63654023 0.69588423 0.33250812, + -0.70944494 0.63589793 0.30384496, + -0.70981592 0.63567495 0.30344498, + -0.77775985 0.5672459 0.27077994, + -0.77690786 0.56790692 0.27183798, + -0.83743918 0.49296612 0.23596606, + -0.83553183 0.49485087 0.23876594, + -0.8871184 0.41568422 0.20056809, + -0.88489312 0.41848207 0.20454103, + -0.92694962 0.33707687 0.16475295, + -0.92485142 0.34047914 0.16948107, + -0.95742309 0.25844103 0.12864402, + -0.95500875 0.26363695 0.13584498, + -0.98012435 0.17635006 0.090867929, + -0.9793005 0.17891809 0.094651945, + -0.99342251 0.10121596 0.053545475, + -0.99305224 0.10315802 0.056618314, + -0.99931562 0.032428388 0.017798394, + -0.99926865 0.033157587 0.019045992, + -0.99932474 -0.031860493 -0.018300897, + -0.99935687 -0.031364396 -0.017378798, + -0.99445689 -0.091970392 -0.050959993, + -0.99512655 -0.088405654 -0.043675076, + -0.98709452 -0.14357392 -0.070929766, + -0.98837286 -0.13925299 -0.061055191, + -0.9780159 -0.19097997 -0.083734691, + -0.97981888 -0.18646398 -0.072014295, + -0.9674955 -0.23590589 -0.091109157, + -0.96969366 -0.23153891 -0.078000069, + -0.95576435 -0.27874207 -0.093901739, + -0.95821553 -0.27473089 -0.079661064, + -0.94264525 -0.32059109 -0.092958622, + -0.94519734 -0.31708112 -0.077856831, + -0.92788512 -0.36211002 -0.088913411, + -0.9304201 -0.35915202 -0.072995208, + -0.91123211 -0.40364105 -0.082037106, + -0.91364479 -0.40124491 -0.065236486, + -0.89264411 -0.44492006 -0.072337404, + -0.8948037 -0.44309485 -0.054711882, + -0.87180102 -0.486168 -0.060030501, + -0.87355012 -0.48491907 -0.041997902, + -0.84823114 -0.52765107 -0.045698803, + -0.84947985 -0.52691495 -0.027287297, + -0.82162321 -0.56926811 -0.029480608, + -0.82234102 -0.56892401 -0.0089902896, + -0.84375143 -0.53673422 -8.8755442e-005, + -0.84373617 -0.53675812 -8.762232e-005, + -0.8436774 -0.53672123 -0.011782406, + -0.84369284 -0.53669685 -0.011781897, + -0.81645203 -0.57735598 -0.0081341499, + -0.81647915 -0.57737505 7.9093908e-005, + -0.81638509 -0.57750803 7.9093807e-005, + -0.81632531 -0.57746619 -0.012080905, + -0.81635088 -0.57742995 -0.012080198, + -0.81641042 -0.57747227 8.4107647e-005, + -0.79983413 -0.60020804 -0.0039601303, + -0.85730779 -0.51478887 -0.0039761988, + -0.86902684 -0.49476489 -0.00030199494, + -0.86905813 -0.49471006 -0.00029468702, + -0.8690027 -0.49467883 -0.011278696, + -0.86897188 -0.49473295 -0.011279799, + -0.85055882 -0.52581888 -0.0080223279, + -0.84990388 -0.52621591 -0.027569296, + -0.87527072 -0.48297083 -0.025303591, + -0.87416899 -0.48376599 -0.042415801, + -0.89707232 -0.44019514 -0.038595516, + -0.8955611 -0.44149807 -0.055225007, + -0.91631091 -0.39737093 -0.049705394, + -0.9144901 -0.39922205 -0.065801211, + -0.93326461 -0.35440788 -0.058414776, + -0.93129289 -0.35676697 -0.073558792, + -0.94804102 -0.31159401 -0.064245, + -0.94604355 -0.31441987 -0.078369163, + -0.96090347 -0.26866412 -0.066964731, + -0.95898664 -0.27190492 -0.080077171, + -0.97207636 -0.22510608 -0.066294722, + -0.97035402 -0.22865801 -0.078286, + -0.98171741 -0.18008189 -0.061654761, + -0.98032779 -0.18371795 -0.072146282, + -0.98967302 -0.133424 -0.0523961, + -0.98870826 -0.13685903 -0.061038315, + -0.99577534 -0.083861232 -0.037401617, + -0.99528927 -0.086614825 -0.043556113, + -0.99945939 -0.029374512 -0.014771606, + -0.99938178 -0.030617192 -0.017283997, + -0.99934113 0.031606104 0.017842302, + -0.9993031 0.032182004 0.018913701, + -0.99306613 0.10135002 0.059564307, + -0.99344623 0.099469021 0.056306716, + -0.97979724 0.17404304 0.09852092, + -0.98063499 0.17154901 0.094477497, + -0.95710033 0.25381109 0.13978204, + -0.95817798 0.25158799 0.13637599, + -0.92056227 0.34339109 0.18613905, + -0.92416024 0.33793709 0.17811905, + -0.88068086 0.41906294 0.22087897, + -0.88340813 0.41583905 0.21602803, + -0.83061314 0.49414805 0.25670904, + -0.83285111 0.49207106 0.25342703, + -0.77113873 0.56601083 0.2915079, + -0.77269346 0.56488156 0.2895748, + -0.70389408 0.63209105 0.32402802, + -0.7038188 0.63213283 0.32410991, + -0.63031894 0.69082493 0.35420197, + -0.62875205 0.69147807 0.35570902, + -0.55338788 0.74066883 0.3810139, + -0.55005407 0.74164408 0.38393307, + -0.47508088 0.78144079 0.40453491, + -0.47132313 0.78212219 0.4076021, + -0.39951995 0.81295091 0.42366794, + -0.38853091 0.81378984 0.43219191, + -0.32248309 0.83599216 0.44398412, + -0.33395299 0.836097 0.43522099, + -0.27239496 0.85347885 0.44426888, + -0.28979391 0.85472369 0.43065885, + -0.23141603 0.86880314 0.43775305, + -0.24192494 0.87019783 0.4292179, + -0.18749493 0.8809337 0.43451285, + -0.19272807 0.88198632 0.43006516, + -0.14338793 0.88954955 0.4337528, + -0.14443804 0.88983929 0.43280914, + -0.10058197 0.89470869 0.43517786, + -0.099317089 0.8942579 0.43639293, + -0.061104391 0.89702189 0.43774194, + -0.058134478 0.89570171 0.44083884, + -0.026350195 0.89690775 0.44143188, + -0.023165492 0.8951847 0.44509286, + 0.0026191499 0.89542186 0.44521093, + 0.0049306788 0.89392775 0.44818389, + 0.02453899 0.89366972 0.44805384, + 0.02556281 0.89288831 0.44955215, + 0.039881088 0.89246976 0.44934088, + 0.039482601 0.89282697 0.44866601, + 0.048701581 0.89246368 0.44848284, + 0.046692003 0.8945781 0.44446605, + 0.051760811 0.89435422 0.44435513, + 0.04830718 0.89863473 0.43602985, + 0.049755581 0.89857072 0.43599886, + 0.046191391 0.90384376 0.4253619, + 0.037254617 0.9041813 0.42552114, + 0.04315529 0.89331675 0.44735089, + 0.043985613 0.89328426 0.44733512, + 0.047817912 0.88746125 0.45839512, + 0.045674413 0.88755029 0.45844117, + 0.048601989 0.88382775 0.46528089, + 0.042745486 0.88406467 0.46540582, + 0.044703476 0.88195556 0.46920776, + 0.034474913 0.88231331 0.46939817, + 0.035477407 0.88139224 0.47105113, + 0.020198107 0.88176727 0.47125217, + 0.020032806 0.88189721 0.47101611, + -0.00010276805 0.88207442 0.47111022, + -0.0012631605 0.88285232 0.46964917, + -0.027073 0.88252902 0.46947801, + -0.028238708 0.88319021 0.46816412, + -0.059581291 0.88197291 0.46751893, + -0.059913371 0.88213056 0.46717879, + -0.096832037 0.8795653 0.46582019, + -0.095436737 0.87902027 0.46713519, + -0.13755597 0.8746568 0.46481588, + -0.13325599 0.87330389 0.46859694, + -0.17991306 0.86678427 0.46509817, + -0.17136802 0.86468714 0.47217506, + -0.22246297 0.85567689 0.46725494, + -0.207587 0.85294801 0.478944, + -0.26239604 0.84138912 0.47245407, + -0.25286394 0.8402288 0.47966188, + -0.31214401 0.825059 0.471003, + -0.32295004 0.8255111 0.46285507, + -0.38925084 0.80345672 0.45048985, + -0.39343885 0.8032347 0.44723585, + -0.46499094 0.77349788 0.43067893, + -0.46947494 0.77281487 0.42702493, + -0.54432493 0.73424095 0.40570995, + -0.54733896 0.73345393 0.40306994, + -0.62277514 0.68568218 0.37681708, + -0.62397796 0.68522292 0.37566093, + -0.69807518 0.62786019 0.3442131, + -0.69727784 0.62827283 0.34507492, + -0.7670123 0.56238818 0.30888811, + -0.76501685 0.56373894 0.31136397, + -0.82798719 0.49085411 0.27110806, + -0.82481098 0.49360901 0.27574801, + -0.87919974 0.41594991 0.23236494, + -0.87474501 0.42085499 0.24021301, + -0.92599738 0.32788011 0.18714605, + -0.92530698 0.328888 0.188785, + -0.95982134 0.24336809 0.13969605, + -0.95865834 0.24567509 0.14359005, + -0.98093462 0.16778193 0.098063961, + -0.98006803 0.17023 0.102413, + -0.9933905 0.098355852 0.05917237, + -0.99379963 0.096375361 0.055443883, + -0.99936676 0.030843593 0.017743995, + -0.99944878 0.029550593 0.015129697, + -0.99947786 -0.028761996 -0.014725998, + -0.99953353 -0.027810987 -0.012621795, + -0.99590266 -0.082347371 -0.037372686, + -0.99626625 -0.080177523 -0.032020207, + -0.98994178 -0.13138497 -0.052470587, + -0.99068165 -0.12863195 -0.044762284, + -0.98212636 -0.17776705 -0.061860524, + -0.98320967 -0.17482294 -0.052303981, + -0.97260851 -0.2226959 -0.066626869, + -0.97394711 -0.21984403 -0.055638008, + -0.96152854 -0.26630887 -0.067397572, + -0.96302187 -0.26371297 -0.055176292, + -0.94871879 -0.30942094 -0.064739682, + -0.95026535 -0.30717912 -0.051350418, + -0.9339509 -0.35250998 -0.058928192, + -0.93543333 -0.35069612 -0.044460416, + -0.91694689 -0.39584094 -0.050183792, + -0.91821778 -0.39452392 -0.035028894, + -0.8975969 -0.43908995 -0.038985796, + -0.89854556 -0.4382638 -0.023251988, + -0.87565821 -0.4822531 -0.025585905, + -0.87624288 -0.48181695 -0.007133069, + -0.8921333 -0.45164615 -0.010673404, + -0.89218402 -0.45167199 0.00025275, + -0.89226103 -0.45152 0.00025274901, + -0.89221013 -0.45149407 -0.010686201, + -0.89220113 -0.45151207 -0.010686501, + -0.89225191 -0.45153794 0.00025345996, + -0.90569532 -0.42391115 -0.0039236615, + -0.94448376 -0.3285439 -0.0030595392, + -0.94883925 -0.3157571 -0.0012636804, + -0.94880462 -0.31574488 -0.0086498773, + -0.94877636 -0.31583011 -0.0086516133, + -0.93853867 -0.34514189 -0.0047142981, + -0.93818736 -0.34560212 -0.019075107, + -0.95392603 -0.299586 -0.0165352, + -0.95342565 -0.30034789 -0.027761592, + -0.96680599 -0.25442699 -0.0235171, + -0.96621066 -0.25552991 -0.033783089, + -0.97741634 -0.20950007 -0.02769761, + -0.97682154 -0.21086289 -0.036829483, + -0.98599499 -0.164288 -0.0286947, + -0.98549926 -0.16575405 -0.036289006, + -0.99255961 -0.11894307 -0.026040616, + -0.99221998 -0.120338 -0.0319096, + -0.99716222 -0.072768614 -0.019295903, + -0.99699855 -0.07386636 -0.02318579, + -0.9996649 -0.024699396 -0.0077528493, + -0.99964076 -0.025172394 -0.0092045786, + -0.99962854 0.025595887 0.0093594352, + -0.99959588 0.026205497 0.011018199, + -0.99613166 0.081004173 0.034058589, + -0.99571741 0.083382145 0.039927077, + -0.98746026 0.14238603 0.068180911, + -0.98581749 0.14753908 0.079976439, + -0.97052699 0.211867 0.114847, + -0.96578765 0.22124393 0.13529696, + -0.93991363 0.29126692 0.17811795, + -0.93455637 0.29851311 0.19363508, + -0.89608228 0.37240213 0.2415641, + -0.89649487 0.37198597 0.24067298, + -0.84469628 0.44939014 0.29075208, + -0.84217215 0.45133907 0.29502404, + -0.77296436 0.53105927 0.34713417, + -0.763955 0.536129 0.35907999, + -0.67354107 0.61413008 0.41132307, + -0.67660105 0.61293805 0.40806606, + -0.60069686 0.66548485 0.44304988, + -0.60229033 0.66505241 0.44153327, + -0.52608496 0.70850295 0.47038093, + -0.52536887 0.7086218 0.47100189, + -0.45089379 0.74335265 0.49408677, + -0.44849986 0.74351275 0.49602082, + -0.37751085 0.77031767 0.51390284, + -0.373317 0.770208 0.51712102, + -0.30851689 0.78973073 0.53022879, + -0.30385885 0.78920066 0.53369677, + -0.24505591 0.80311072 0.5431028, + -0.24052197 0.80221391 0.54644495, + -0.18844196 0.81166983 0.55288488, + -0.18570291 0.81090665 0.55492777, + -0.14028497 0.81710082 0.55916589, + -0.13370599 0.81472886 0.56421596, + -0.095213488 0.81837589 0.56674093, + -0.10083696 0.82083571 0.5621928, + -0.066804081 0.82319772 0.56381083, + -0.076150283 0.82792783 0.55564088, + -0.044982113 0.82949817 0.5566951, + -0.051225401 0.83311403 0.55072403, + -0.023569809 0.83397728 0.55129516, + -0.027669404 0.83669811 0.54696506, + -0.0038351391 0.83701283 0.54716986, + -0.0070028109 0.83942211 0.54343504, + 0.012739495 0.83937472 0.5434038, + 0.0098498603 0.841896 0.53955001, + 0.02562261 0.84166032 0.53939921, + 0.022704598 0.84459388 0.53492594, + 0.034624603 0.8443051 0.53474307, + 0.031554911 0.84788829 0.52923518, + 0.039530884 0.84764773 0.5290848, + 0.03611638 0.85232759 0.52175975, + 0.040744189 0.85217583 0.52166688, + 0.037055004 0.85820913 0.51196104, + 0.038144797 0.85817391 0.51193994, + 0.034587409 0.86531931 0.50002617, + 0.0325705 0.86537802 0.50006002, + 0.020486405 0.85532415 0.5176881, + 0.025768587 0.8552196 0.51762474, + 0.014894309 0.79920548 0.60087335, + 0.022066386 0.7990995 0.60079366, + -0.014828905 0.7994113 0.60060126, + -0.022214798 0.79930186 0.60051894, + -0.015761299 0.8254959 0.56418794, + -0.014747002 0.82550913 0.56419605, + -0.010830396 0.85105067 0.52497184, + -0.0054620388 0.85108781 0.52499491, + -0.0041422513 0.87580729 0.48264319, + 0.0037737382 0.8758086 0.48264375, + 0.0050676297 0.8509829 0.52516896, + 0.010781094 0.85094458 0.52514476, + 0.014675204 0.82542217 0.56432509, + 0.015621006 0.82541031 0.56431717, + 0.017621405 0.82857132 0.55960619, + 0.023955196 0.82846189 0.55953294, + 0.017746398 0.85252386 0.52238697, + 0.015702398 0.85255289 0.52240497, + 0.011902696 0.87623072 0.48174483, + 0.005372928 0.87627971 0.48177281, + 0.0041373093 0.89886075 0.43821487, + -0.0042348308 0.89886022 0.43821511, + -0.0054923506 0.87620515 0.48190707, + -0.012101403 0.87615424 0.48187912, + -0.015880005 0.85270029 0.52215916, + -0.017951103 0.85267019 0.5221411, + -0.024198795 0.8285858 0.55933887, + -0.017595103 0.82870018 0.55941612, + 0.53241092 0.66499496 0.52375597, + 0.43249786 0.70831978 0.55787879, + 0.42608207 0.7081902 0.56295711, + 0.35646287 0.73138076 0.58139181, + 0.35530397 0.73125494 0.58225894, + 0.29205194 0.74819285 0.59574586, + 0.2893039 0.74767077 0.59773874, + 0.23232813 0.75969946 0.60735536, + 0.22974794 0.7590028 0.60920489, + 0.17901498 0.76726687 0.61583692, + 0.17682502 0.76650214 0.61742008, + 0.13246401 0.77191103 0.621777, + 0.13157503 0.77153015 0.62243813, + 0.093221106 0.77490711 0.62516308, + 0.092402495 0.77449089 0.62579995, + 0.059888761 0.7764225 0.62736064, + 0.058150709 0.77539212 0.62879705, + 0.030743385 0.77633965 0.6295647, + 0.028251709 0.7746343 0.63177824, + 0.0064663831 0.77492738 0.63201731, + 0.013210597 0.78017181 0.62542582, + -0.0058646202 0.78022701 0.62546903, + 0.0014900398 0.78664088 0.61740893, + -0.015087508 0.78655237 0.61733931, + -0.0092323795 0.79229987 0.61006194, + -0.023357 0.79211801 0.60992098, + -0.018032894 0.79804969 0.60232174, + -0.029398892 0.79783481 0.6021589, + -0.024608212 0.80396134 0.5941723, + -0.033007298 0.80376691 0.59402794, + -0.028579617 0.81036049 0.58523434, + -0.034082994 0.81022084 0.5851329, + -0.029891608 0.81763315 0.57496309, + -0.032504689 0.81756669 0.57491583, + -0.028650604 0.8259111 0.56307209, + -0.022177398 0.82604688 0.56316495, + -0.0272677 0.81165099 0.58350599, + -0.02706931 0.81165528 0.58350927, + -0.031119185 0.80266362 0.59561968, + -0.028248509 0.80273229 0.59567022, + -0.032753795 0.79454291 0.60632396, + -0.027121987 0.79467666 0.60642672, + -0.032043893 0.78712082 0.6159659, + -0.023891503 0.78730011 0.61610705, + -0.029179012 0.78030735 0.62471527, + -0.018651493 0.78050369 0.62487274, + -0.024547009 0.7736913 0.63308722, + -0.0113438 0.77387488 0.63323694, + -0.01835781 0.76670235 0.64174032, + -0.0033143708 0.76682717 0.64184517, + -0.00989071 0.76083499 0.64886999, + 0.007740688 0.76084983 0.64888179, + 0.008291835 0.76129448 0.64835334, + 0.030745592 0.76096082 0.64806885, + 0.0310419 0.76117003 0.64780903, + 0.058439914 0.76023519 0.6470142, + 0.057975799 0.75994903 0.64739197, + 0.090215042 0.75812536 0.64583832, + 0.090216622 0.7581262 0.64583719, + 0.12792504 0.75497627 0.64315325, + 0.12931995 0.75560772 0.64213175, + 0.17306694 0.75050771 0.63779777, + 0.175069 0.75125498 0.63637, + 0.22521196 0.74343693 0.62974691, + 0.2272909 0.74404866 0.62827569, + 0.28404903 0.73257506 0.61858708, + 0.28558698 0.73290694 0.61748493, + 0.348147 0.716914 0.60400999, + 0.35525182 0.71785963 0.59872669, + 0.42430586 0.69539577 0.5799908, + 0.46091989 0.69635081 0.5501349, + 0.53203988 0.66439682 0.5248909, + 0.56352192 0.66108692 0.49538594, + 0.65209502 0.60669899 0.45462999, + 0.66913676 0.60244477 0.43510485, + 0.74345684 0.54216689 0.39156991, + 0.75203532 0.53880316 0.37965015, + 0.81262869 0.47639781 0.33567789, + 0.82358772 0.47032881 0.31700787, + 0.88030672 0.39338985 0.26514992, + 0.96772754 -0.25198987 -0.0021003091, + 0.96751398 -0.252426 -0.0140658, + 0.9784289 -0.20626397 -0.011493599, + 0.97816211 -0.20689303 -0.019857801, + 0.98690009 -0.16059501 -0.015414102, + 0.98664325 -0.16138105 -0.022167806, + 0.99320126 -0.11532703 -0.015841804, + 0.99301249 -0.11613705 -0.020941209, + 0.99747324 -0.069915816 -0.012606903, + 0.99737948 -0.070579641 -0.015900308, + 0.99971014 -0.023487203 -0.0052912305, + 0.99969625 -0.023778906 -0.0064874012, + 0.9996891 0.024054503 0.006562571, + 0.99967015 0.024437904 0.0079092411, + 0.99687612 0.075144105 0.024320103, + 0.99663574 0.076655887 0.029003292, + 0.99025649 0.13024506 0.049279023, + 0.98933935 0.13345504 0.058287922, + 0.97807598 0.19084001 0.083351202, + 0.97557539 0.19651188 0.098161243, + 0.95745021 0.25818005 0.12896603, + 0.95157689 0.26730296 0.15182398, + 0.92418259 0.33211786 0.18863791, + 0.91174877 0.3454949 0.22214293, + 0.87143898 0.41258001 0.265277, + 0.85955018 0.42159408 0.28884605, + 0.80516118 0.48924413 0.33519509, + 0.80065 0.49174401 0.34226799, + 0.73179626 0.55936718 0.38933614, + 0.72069061 0.56373066 0.40350077, + 0.63573205 0.62768805 0.44928005, + 0.61318988 0.63300985 0.47254288, + 0.51160175 0.68853265 0.51399076, + 0.5084691 0.68884617 0.51667213, + 0.43443686 0.72054279 0.54044682, + 0.43389621 0.72054636 0.54087621, + 0.36385104 0.74493408 0.55918306, + 0.36182502 0.74477005 0.56071407, + 0.29760489 0.76269972 0.57421285, + 0.29471588 0.76222467 0.57632983, + 0.23720297 0.77488786 0.58590394, + 0.23442511 0.77420735 0.58791828, + 0.18308298 0.7829389 0.59454793, + 0.18107298 0.78228688 0.59601992, + 0.13631596 0.78801072 0.60038078, + 0.13452898 0.78728986 0.60172796, + 0.095603876 0.79087281 0.60446686, + 0.092363946 0.78930134 0.60701931, + 0.059801213 0.79127115 0.6085341, + 0.054928094 0.7884829 0.61259896, + 0.028463496 0.78935486 0.61327696, + 0.035241403 0.79380912 0.60714507, + 0.0119913 0.79424602 0.60747802, + 0.019794706 0.80002117 0.59964514, + -0.0011016007 0.80017745 0.59976238, + 0.0048989672 0.80517751 0.59301364, + -0.013082703 0.8051182 0.59297013, + -0.0079415198 0.80996603 0.58642298, + -0.022914292 0.80977869 0.58628774, + -0.018425902 0.81460309 0.57972604, + -0.030229311 0.81436932 0.57955921, + -0.025992295 0.81961781 0.57232088, + -0.034646306 0.81940216 0.57217109, + -0.030572901 0.82529199 0.563878, + -0.035972107 0.82514316 0.56377715, + -0.032000192 0.83197683 0.55388689, + -0.034390815 0.83191043 0.55384326, + -0.030588688 0.83992171 0.54184484, + -0.029958095 0.83993787 0.54185492, + -0.025070289 0.85307556 0.52118474, + -0.032633007 0.85288918 0.52107114, + -0.03620778 0.84554261 0.53267878, + -0.034422606 0.84559619 0.5327121, + -0.038183104 0.8393001 0.54232603, + -0.03309178 0.83945251 0.54242468, + -0.036810704 0.83422911 0.55018806, + -0.028315209 0.83446032 0.55034018, + -0.031896591 0.83016485 0.55660486, + -0.019837195 0.83042383 0.55677891, + -0.023556404 0.82656711 0.56234509, + -0.0078995908 0.82677114 0.56248307, + -0.0119646 0.82309198 0.56778198, + 0.0071534216 0.82312918 0.5678091, + 0.0022107398 0.81919986 0.57350391, + 0.024625694 0.81895381 0.57333088, + 0.018583298 0.81471986 0.57955694, + 0.044274673 0.81406152 0.57908863, + 0.035605099 0.80869401 0.58715099, + 0.064049974 0.80754572 0.58631676, + 0.056827385 0.80360281 0.59244686, + 0.088423595 0.8017509 0.59108096, + 0.095795535 0.80518728 0.58523226, + 0.13477097 0.8015278 0.58257186, + 0.13950898 0.80333084 0.57896191, + 0.18489 0.79727697 0.57459998, + 0.18752196 0.79806489 0.57264996, + 0.23948103 0.78883612 0.56602705, + 0.24209692 0.78941071 0.5641098, + 0.30041599 0.77603197 0.55454898, + 0.30316696 0.7764129 0.55251491, + 0.36777797 0.75765389 0.53916591, + 0.37064898 0.75780791 0.53697896, + 0.44087285 0.73234874 0.51893783, + 0.44260293 0.73228592 0.51755196, + 0.51671684 0.69916278 0.49414083, + 0.51645774 0.69919664 0.49436375, + 0.59308988 0.65740985 0.46481889, + 0.59348613 0.65731716 0.46444413, + 0.69127923 0.59013826 0.41697714, + 0.70628184 0.58435488 0.39961892, + 0.78504109 0.51131403 0.34966904, + 0.79099083 0.50796586 0.34103391, + 0.85209018 0.4345451 0.29174107, + 0.85364389 0.43337694 0.28892297, + 0.9004181 0.36196104 0.24131203, + 0.90844524 0.3538841 0.22247106, + 0.94167399 0.28490499 0.179107, + 0.94989985 0.27314696 0.15192398, + 0.97137064 0.20761593 0.11547595, + 0.97480655 0.20031291 0.098116256, + 0.98781186 0.13978499 0.068468891, + 0.98903799 0.135712 0.058191001, + 0.99623412 0.079687506 0.034168605, + 0.99655133 0.077777326 0.028918812, + 0.99963766 0.02522989 0.0093808658, + 0.99966288 0.024739297 0.0078755394, + 0.99967223 -0.024397006 -0.0077665718, + 0.99969065 -0.024022391 -0.0064505679, + 0.99721533 -0.072024323 -0.019340208, + 0.99733955 -0.071165264 -0.015786992, + 0.9926725 -0.11796794 -0.026169587, + 0.99292701 -0.116897 -0.020761101, + 0.98615777 -0.16325496 -0.028994393, + 0.98651952 -0.16216493 -0.02194869, + 0.97760653 -0.20853989 -0.028225288, + 0.97802174 -0.20757596 -0.019639395, + 0.96700925 -0.25360906 -0.023994705, + 0.96739674 -0.25288394 -0.013901196, + 0.95411855 -0.29897785 -0.016434992, + 0.95440447 -0.29850414 -0.0027344814, + 0.96402186 -0.26574796 -0.0063207392, + 0.96404099 -0.265753 0.00060169498, + 0.96398801 -0.26594499 0.00060169498, + 0.96396887 -0.26593998 -0.0063165692, + 0.96400452 -0.26581088 -0.0063144774, + 0.96402335 -0.26581708 0.00059989624, + 0.97589475 -0.21818195 -0.0051035886, + 0.97589248 -0.2181811 -0.0055636629, + 0.97588533 -0.21821308 -0.0055641821, + 0.97589946 -0.21821611 -0.0014623808, + 0.98542339 -0.17011806 0.0007738173, + 0.98541254 -0.17011593 -0.0047621178, + 0.97865838 -0.20548807 -0.0015760505, + 0.97851026 -0.20587005 -0.011633803, + 0.98714978 -0.15954295 -0.0090158684, + 0.98698527 -0.16005404 -0.015584804, + 0.99339855 -0.11417395 -0.011117394, + 0.99326485 -0.11475599 -0.015998198, + 0.99757373 -0.068951488 -0.0096125482, + 0.99750423 -0.069452211 -0.012714403, + 0.9997251 -0.023064602 -0.0042223604, + 0.99971461 -0.023289593 -0.0053290981, + 0.99970925 0.023508606 0.0053792214, + 0.99969476 0.023806494 0.0066008586, + 0.99712342 0.073038653 0.020251488, + 0.99694276 0.074218087 0.024431594, + 0.99118853 0.12581694 0.041417383, + 0.99049425 0.12835903 0.04944801, + 0.98054385 0.18317798 0.070566289, + 0.97867638 0.18765208 0.083541833, + 0.96301466 0.24615692 0.10958796, + 0.95873934 0.25327209 0.12912105, + 0.93554926 0.3146641 0.16041905, + 0.92664576 0.32514992 0.18869296, + 0.89317709 0.38895407 0.22572003, + 0.87963915 0.40024406 0.25698203, + 0.83928418 0.45750812 0.29374906, + 0.82381082 0.46649787 0.3220489, + 0.77548617 0.51957715 0.35869309, + 0.76089013 0.52536309 0.38084105, + 0.69601226 0.58134919 0.42142615, + 0.68246382 0.58480287 0.43846187, + 0.60502291 0.63703984 0.47762689, + 0.58151865 0.63995564 0.50228769, + 0.49170411 0.68497419 0.53762209, + 0.45431694 0.68453395 0.57009596, + 0.3869651 0.70855016 0.59009713, + 0.34722996 0.70310491 0.62054396, + 0.28499508 0.71866125 0.63427424, + 0.27804807 0.7170012 0.6392172, + 0.22208114 0.72779542 0.64884037, + 0.22043906 0.7272712 0.64998716, + 0.17118606 0.73460627 0.65654325, + 0.16930205 0.73385715 0.65786821, + 0.12617703 0.73865515 0.66216916, + 0.12495007 0.73806942 0.66305441, + 0.087846532 0.74102324 0.66570824, + 0.087344706 0.74074304 0.66608608, + 0.055455714 0.74244016 0.66761321, + 0.056658082 0.74321377 0.66665077, + 0.029514214 0.74408537 0.66743231, + 0.031195082 0.74531657 0.66598058, + 0.008744942 0.74565119 0.6662792, + 0.0097637009 0.74649805 0.66531605, + -0.0085233012 0.74650604 0.66532403, + -0.0073792757 0.74758458 0.66412556, + -0.021454494 0.74743283 0.6639908, + -0.014819709 0.75448549 0.65614945, + -0.026546713 0.75430238 0.6559903, + -0.019989906 0.76216418 0.64707518, + -0.0295847 0.76198298 0.64692098, + -0.023856105 0.76982319 0.63781118, + -0.031613011 0.76965731 0.63767421, + -0.026341714 0.77800936 0.62770027, + -0.031692706 0.77788818 0.62760317, + -0.026934391 0.78679872 0.61662173, + -0.029626789 0.78673869 0.61657476, + -0.025457803 0.79626811 0.60440809, + -0.019781101 0.79637015 0.60448605, + -0.025094204 0.78051114 0.62463808, + -0.012835697 0.76756483 0.6408428, + -0.020516805 0.76746619 0.6407612, + -0.013854604 0.79599231 0.60514826, + -0.013742208 0.79599345 0.60514933, + -0.0096893487 0.82371587 0.56691992, + -0.0050571812 0.82374418 0.56693912, + -0.0036960191 0.8505218 0.52592689, + 0.00363024 0.85052198 0.52592701, + 0.0049740905 0.8237021 0.56700104, + 0.0097418521 0.82367319 0.56698114, + 0.013777095 0.79591173 0.60525578, + 0.014005904 0.79590917 0.60525411, + 0.020668594 0.7672618 0.64100081, + 0.0128681 0.767362 0.64108503, + -0.55924016 0.64372426 0.52236921, + -0.47620595 0.68280393 0.55408192, + -0.44636494 0.67995292 0.58174092, + -0.386758 0.70072001 0.59950799, + -0.34971702 0.69293404 0.63050807, + -0.29439297 0.70686096 0.64317995, + -0.24734098 0.69135892 0.67885596, + -0.1705751 0.70307243 0.69035745, + -0.16229893 0.69941366 0.69604564, + -0.12029105 0.70366424 0.70027626, + -0.11958704 0.70329422 0.70076823, + -0.083287537 0.70591635 0.70338136, + -0.083331332 0.70594323 0.70334923, + -0.051881582 0.70745277 0.70485377, + -0.052308232 0.70774943 0.7045244, + -0.026215097 0.70847595 0.70524794, + -0.027610596 0.70957595 0.70408791, + -0.0056519513 0.70983517 0.70434517, + -0.0077703064 0.71172065 0.70241964, + 0.010259097 0.71170479 0.70240378, + 0.0068204585 0.71515381 0.69893384, + 0.020941092 0.71501374 0.69879675, + 0.016330693 0.72022265 0.69355065, + 0.027692493 0.72004282 0.69337684, + 0.02345551 0.72546124 0.68786323, + 0.0315874 0.725299 0.68770897, + 0.026085794 0.73333782 0.67936385, + 0.032484792 0.73319983 0.67923683, + 0.0266751 0.74300599 0.66875303, + 0.030979693 0.74291384 0.66866982, + 0.025835801 0.75315201 0.65733898, + 0.028251097 0.7531029 0.65729594, + 0.023888305 0.76367718 0.6451562, + 0.018388204 0.76376617 0.64523119, + 0.023696095 0.74694282 0.66446584, + 0.023321487 0.74694955 0.66447157, + 0.027967397 0.73536593 0.67709297, + 0.025850406 0.73540819 0.67713118, + 0.031102911 0.72463626 0.68842924, + 0.027617287 0.72471064 0.68849963, + 0.032854203 0.71560705 0.69773006, + 0.027059095 0.7157318 0.69785082, + 0.031852812 0.70852423 0.70496726, + 0.023417989 0.70868963 0.70513165, + 0.028608503 0.70185304 0.71174705, + 0.017282896 0.70203584 0.71193182, + 0.0215177 0.69710302 0.71664798, + 0.0074723898 0.697245 0.71679401, + 0.010580003 0.69403225 0.71986622, + -0.0073575717 0.69405216 0.7198872, + -0.0048653409 0.69176316 0.72210819, + -0.026644999 0.69152498 0.721861, + -0.025048904 0.69022506 0.72316104, + -0.050915498 0.68954599 0.72245002, + -0.050334711 0.68912816 0.72288918, + -0.080943227 0.68773824 0.72143221, + -0.080566324 0.68750018 0.7217012, + -0.116592 0.68503797 0.71911699, + -0.12455397 0.6893838 0.71360785, + -0.19315703 0.68171006 0.70566404, + -0.24066003 0.70217705 0.67009705, + -0.29049999 0.69224101 0.66061503, + -0.3285698 0.70404559 0.62957263, + -0.38357592 0.6884138 0.61559391, + -0.41600606 0.69479805 0.58668107, + -0.47392705 0.67279506 0.56810206, + -0.50030106 0.67505604 0.54221606, + -0.55967134 0.64610237 0.5189603, + -0.58093983 0.64553875 0.49577081, + -0.64982402 0.60282099 0.462964, + -0.67371792 0.59932095 0.43234095, + -0.72634482 0.55742586 0.40211892, + -0.74904102 0.550807 0.36816999, + -0.79663002 0.50253999 0.335908, + -0.81296617 0.49497512 0.30673406, + -0.85449719 0.44154713 0.27362505, + -0.8655687 0.43417984 0.24955691, + -0.89998072 0.37794685 0.21723492, + -0.90937698 0.369248 0.19154499, + -0.93765086 0.30853596 0.16005099, + -0.94404137 0.30040511 0.13617204, + -0.96406698 0.241961 0.10968, + -0.96720976 0.23641394 0.092809878, + -0.98101735 0.18050906 0.07086312, + -0.98241478 0.17700195 0.059426285, + -0.99136978 0.12427797 0.041724689, + -0.99189013 0.12230202 0.034586605, + -0.99717402 0.072291598 0.0204437, + -0.99731135 0.071369819 0.016629405, + -0.99971354 0.023310289 0.0054313871, + -0.99972451 0.023076689 0.0042821281, + -0.9997285 -0.022907488 -0.0042507281, + -0.99973649 -0.022734512 -0.0031876017, + -0.99759835 -0.068593919 -0.0096175633, + -0.99764675 -0.068237282 -0.0066787484, + -0.99344391 -0.11377698 -0.011135999, + -0.99352539 -0.11341704 -0.0066224225, + -0.98719537 -0.15924506 -0.0092983339, + -0.60572296 0.63697094 0.47683093, + -0.68291318 0.58479512 0.43777213, + -0.69605178 0.58143485 0.42124286, + -0.76106298 0.52530402 0.380577, + -0.77683938 0.51901525 0.35657218, + -0.82493711 0.46587405 0.32006302, + -0.84055215 0.45671812 0.29134306, + -0.88069439 0.39935118 0.25474712, + -0.89073527 0.39104414 0.2316791, + -0.92984986 0.31655297 0.18754597, + -0.92459863 0.33166188 0.18739694, + -0.95188677 0.26680595 0.15075196, + -0.95761162 0.2578769 0.12837195, + -0.97565597 0.196326 0.097731799, + -0.97810811 0.19075203 0.083176509, + -0.989353 0.133405 0.058170401, + -0.99025655 0.13023993 0.049290776, + -0.9966355 0.076655835 0.029011114, + -0.9968735 0.075160235 0.02437821, + -0.99966979 0.024442995 0.0079280883, + -0.99968886 0.024060596 0.0065850192, + -0.9996959 -0.023784596 -0.0065094689, + -0.99971002 -0.0234905 -0.0053038602, + -0.99737823 -0.070588715 -0.015938004, + -0.99747378 -0.069912784 -0.012584398, + -0.99301326 -0.11613703 -0.020904806, + -0.99320555 -0.11530995 -0.015695792, + -0.98664886 -0.16137399 -0.021966098, + -0.98690224 -0.16059504 -0.015269903, + -0.97816133 -0.20691407 -0.019674007, + -0.96770722 -0.25205907 -0.0030206607, + -0.9674989 -0.25246897 -0.014326698, + -0.97841555 -0.20631489 -0.011707595, + -0.97864574 -0.20554195 -0.0022585394, + -0.97850001 -0.205906 -0.0118528, + -0.98714423 -0.15956804 -0.0091853617, + -0.98698747 -0.16005407 -0.015441108, + -0.99340051 -0.11416695 -0.011014194, + -0.99326855 -0.11474495 -0.015851693, + -0.99757546 -0.068939328 -0.0095238043, + -0.99750465 -0.069450781 -0.012691795, + -0.9997251 -0.023063201 -0.0042146905, + -0.99971449 -0.023292311 -0.0053417725, + -0.99970901 0.023511801 0.0053921002, + -0.99969453 0.023812089 0.0066231769, + -0.99712098 0.073054597 0.0203197, + -0.99694037 0.074230827 0.024489509, + -0.99118167 0.12583895 0.041515384, + -0.99049455 0.12835194 0.049459778, + -0.98054522 0.18316504 0.070581414, + -0.97870612 0.18757403 0.083368905, + -0.96306974 0.24604394 0.10935698, + -0.95888209 0.25303003 0.12853402, + -0.9357481 0.31442702 0.15972202, + -0.92903566 0.32248789 0.18136793, + -0.89954799 0.380739 0.214129, + -0.8911373 0.38806614 0.2351151, + -0.85405117 0.44490311 0.26955107, + -0.84091151 0.45314074 0.29585683, + -0.79627663 0.50652874 0.33071485, + -0.77701271 0.51475281 0.36232689, + -0.72622615 0.56215811 0.39569408, + -0.70630091 0.56742895 0.42327693, + -0.63865906 0.61678708 0.46009606, + -0.6203261 0.61926013 0.48136511, + -0.54153186 0.66373885 0.51593989, + -0.51338792 0.66408193 0.54353297, + -0.44978088 0.69115281 0.56568986, + -0.41509986 0.68742377 0.59593678, + -0.35424697 0.70659792 0.61255896, + -0.30893204 0.69626606 0.64790004, + -0.224427 0.71340102 0.66384602, + -0.21626697 0.71062392 0.66950893, + -0.16750795 0.71756476 0.67604876, + -0.16650702 0.71714306 0.67674303, + -0.12358197 0.72172081 0.68106282, + -0.12246796 0.72116274 0.68185478, + -0.085862607 0.72394907 0.68448907, + -0.08505518 0.72347784 0.6850878, + -0.05338772 0.72507322 0.68659925, + -0.053565491 0.72519296 0.68645895, + -0.027279986 0.72596467 0.68719071, + -0.028235197 0.72669291 0.68638194, + -0.0061630686 0.72696882 0.68664283, + -0.008603449 0.72907394 0.68438095, + 0.0095176511 0.72906804 0.68437505, + 0.0052865716 0.7331782 0.68001616, + 0.020018995 0.73304182 0.67988884, + 0.016605094 0.73678076 0.67592776, + 0.027706901 0.73659998 0.67576098, + 0.022168597 0.74346894 0.66840297, + 0.030873396 0.74329692 0.66824895, + 0.024714312 0.75201339 0.65868431, + 0.031888403 0.75186014 0.65855104, + 0.026397301 0.76084203 0.64840001, + 0.031177601 0.760737 0.64831102, + 0.026333295 0.77009881 0.63738084, + 0.029144496 0.7700389 0.63733095, + 0.024806404 0.7802521 0.62497306, + 0.025076395 0.78024679 0.62496889, + 0.01974849 0.79622161 0.60468268, + 0.025880706 0.79611015 0.6045981, + 0.030100793 0.78644782 0.61692286, + 0.027243197 0.7865119 0.61697394, + 0.031904202 0.77776414 0.62774605, + 0.026778495 0.7778818 0.6278398, + 0.031851687 0.76983666 0.63744569, + 0.024009896 0.77000588 0.63758492, + 0.029725803 0.7621811 0.64668107, + 0.02001651 0.76236534 0.64683729, + 0.02646951 0.75462931 0.65561724, + 0.014632598 0.7548129 0.65577692, + 0.020132799 0.74897796 0.66228896, + 0.0059025977 0.74911678 0.66241175, + 0.0080373595 0.74710995 0.66465193, + -0.010516804 0.74709225 0.66463727, + -0.00704154 0.74419802 0.66792202, + -0.029274793 0.7438978 0.66765183, + -0.028007699 0.74296498 0.66874403, + -0.054734994 0.74214292 0.66800296, + -0.05477722 0.74217021 0.66796923, + -0.086371705 0.74050808 0.66647404, + -0.087786399 0.74129999 0.66540802, + -0.12496099 0.73833996 0.66275096, + -0.12666796 0.73915374 0.66151875, + -0.17020302 0.73428303 0.65716004, + -0.17205198 0.73501694 0.65585697, + -0.22171894 0.72757185 0.6492148, + -0.22283 0.72792602 0.64843702, + -0.27855387 0.71714664 0.6388337, + -0.2859039 0.71889776 0.63359678, + -0.377904 0.69458097 0.61216497, + -0.41993299 0.69977701 0.57789999, + -0.48572305 0.67399108 0.55660504, + -0.51675618 0.67397422 0.52794117, + -0.58250606 0.63988209 0.50123608, + -0.58219618 0.63903224 0.50267816, + -0.49054 0.68491 0.53876603, + -0.45331311 0.68441421 0.57103813, + -0.35495204 0.71784008 0.59892803, + -0.34912097 0.71706593 0.60326695, + -0.28619605 0.73320717 0.61684614, + -0.28521699 0.732997 0.617549, + -0.22864407 0.74450421 0.62724423, + -0.22588906 0.7436952 0.62919921, + -0.17593502 0.75151914 0.63581908, + -0.17307694 0.7504527 0.63785976, + -0.129282 0.75555801 0.64219803, + -0.12721597 0.75461984 0.64371181, + -0.08926069 0.75776386 0.64639497, + -0.08819399 0.75719291 0.64720994, + -0.056101616 0.75895816 0.64871818, + -0.056061201 0.75893301 0.64875102, + -0.029145712 0.75980532 0.64949721, + -0.031450089 0.7614367 0.64747578, + -0.0089895902 0.761783 0.64776999, + -0.0098071462 0.76244068 0.64698374, + 0.0084961662 0.76244962 0.64699173, + 0.0032541305 0.76721311 0.64138407, + 0.018176397 0.76709086 0.64128095, + 0.011439401 0.77397811 0.63310903, + 0.024518704 0.77379614 0.63296008, + 0.018660897 0.78056985 0.62478995, + 0.029267311 0.78037131 0.62463123, + 0.024247611 0.78702039 0.61645031, + 0.032382503 0.78683913 0.61630803, + 0.02759731 0.79420328 0.60702527, + 0.032927804 0.79407513 0.60692704, + 0.028375804 0.80237812 0.59614104, + 0.031368203 0.80230612 0.59608805, + 0.027321113 0.81131738 0.58396727, + 0.027211895 0.81131983 0.58396888, + 0.0220381 0.82601303 0.56322002, + 0.028920608 0.82586819 0.56312114, + 0.032856792 0.81733584 0.57522386, + 0.030125389 0.81740671 0.5752728, + 0.034311004 0.80998713 0.58544308, + 0.028885612 0.81012636 0.58554327, + 0.033471808 0.80328017 0.5946601, + 0.025156505 0.80347615 0.59480512, + 0.029761288 0.79757369 0.60248679, + 0.018411897 0.79779184 0.60265189, + 0.023383094 0.79224581 0.60975391, + 0.0093998816 0.79242718 0.6098941, + 0.015183693 0.78674865 0.61708671, + -0.0017423702 0.78683811 0.61715704, + 0.0057276427 0.78032237 0.62535131, + -0.013201701 0.78026712 0.62530708, + -0.0084421411 0.77657515 0.62996805, + -0.030683303 0.77623713 0.62969404, + -0.031374894 0.77670884 0.62907779, + -0.058779016 0.77574819 0.62829918, + -0.057532813 0.77500719 0.62932819, + -0.089802377 0.77315682 0.62782484, + -0.091229931 0.77388728 0.62671822, + -0.12914699 0.77061999 0.62407202, + -0.13184899 0.77178186 0.62206793, + -0.17621902 0.76639509 0.61772609, + -0.17913102 0.76741314 0.61562103, + -0.22992694 0.75913084 0.60897785, + -0.23304194 0.75997084 0.60674191, + -0.29011193 0.74787784 0.59708786, + -0.29315999 0.74845397 0.59487301, + -0.35648996 0.73141593 0.58133096, + -0.357449 0.73151898 0.580612, + -0.42710716 0.70823121 0.56212819, + -0.43077514 0.70830625 0.55922717, + -0.53236622 0.6643973 0.52455926, + -0.56338495 0.66113096 0.49548295, + -0.65217316 0.60661709 0.45462713, + -0.66977698 0.60221601 0.43443599, + -0.74385375 0.54202384 0.39101386, + -0.75221598 0.53873903 0.379383, + -0.81277329 0.47632518 0.33543113, + -0.82470942 0.46968523 0.31504014, + -0.86833417 0.4119021 0.27628306, + -0.88034624 0.4025211 0.25093305, + -0.91518211 0.34202302 0.21321803, + -0.91582012 0.33589402 0.22011103, + -0.8680774 0.41521922 0.27209312, + -0.859662 0.421518 0.28862399, + -0.8053121 0.48916706 0.33494502, + -0.800991 0.49156499 0.34172699, + -0.73222017 0.55921513 0.38875708, + -0.72067899 0.56375599 0.40348601, + -0.63571966 0.62771362 0.44926172, + -0.61259687 0.63316184 0.47310787, + -0.51093298 0.68861598 0.51454401, + -0.50949615 0.68876022 0.51577419, + -0.43546706 0.72056305 0.53959006, + -0.43513578 0.72056562 0.53985375, + -0.3650471 0.74507415 0.55821609, + -0.36274189 0.74489075 0.55996084, + -0.29844901 0.76290399 0.57350302, + -0.29501814 0.76234335 0.57601827, + -0.23743297 0.7750389 0.58561093, + -0.2335339 0.77408272 0.58843678, + -0.18247499 0.78272986 0.59500992, + -0.17885895 0.78155082 0.5976519, + -0.13397604 0.78719831 0.60197121, + -0.13147405 0.78618032 0.60385025, + -0.093055002 0.78962302 0.60649502, + -0.092884526 0.78954017 0.60662913, + -0.06033697 0.79152364 0.60815269, + -0.057736106 0.79004115 0.61032903, + -0.030795395 0.79098588 0.61105895, + -0.035601091 0.79413271 0.60670078, + -0.011995202 0.79457915 0.60704207, + -0.019954 0.80046302 0.59904999, + 0.00087175611 0.80062211 0.59916908, + -0.0048276205 0.80536914 0.59275407, + 0.013252397 0.80530781 0.59270889, + 0.0085587185 0.80973685 0.5867309, + 0.023300294 0.80954683 0.58659285, + 0.018914297 0.81427085 0.58017695, + 0.030854505 0.8140291 0.58000404, + 0.026571088 0.81934357 0.57268667, + 0.034937792 0.8191328 0.57253885, + 0.030978704 0.82487011 0.56447303, + 0.036060296 0.82472986 0.56437594, + 0.032076601 0.83160597 0.55443901, + 0.0343551 0.83154303 0.55439699, + 0.030534185 0.83962357 0.54230976, + 0.029804699 0.83964199 0.54232198, + 0.02488149 0.85292959 0.52143276, + 0.032463208 0.85274416 0.52131909, + 0.036117811 0.84520829 0.53321517, + 0.034633897 0.84525287 0.53324294, + 0.038344793 0.8390258 0.54273885, + 0.03335309 0.8391757 0.54283684, + 0.037192386 0.83377069 0.55085683, + 0.028619893 0.83400583 0.55101287, + 0.032302596 0.82957387 0.55746192, + 0.020370301 0.829835 0.55763698, + 0.023982296 0.82607687 0.56304693, + 0.0086305877 0.82628381 0.5631879, + 0.012533305 0.8227424 0.56827629, + -0.0065534511 0.82278913 0.56830907, + -0.0021766997 0.81930488 0.57335395, + -0.024682701 0.81905699 0.57318097, + -0.018798899 0.8149339 0.57924896, + -0.04439871 0.81427419 0.57878011, + -0.035997495 0.80907786 0.58659792, + -0.064584963 0.80791253 0.58575267, + -0.059518777 0.80515969 0.59006375, + -0.091605693 0.80319786 0.58862692, + -0.096204884 0.80533189 0.58496594, + -0.13514996 0.80166173 0.58229983, + -0.13648498 0.80217189 0.58128494, + -0.18161495 0.79628283 0.5770179, + -0.18540506 0.79743028 0.57422119, + -0.23697905 0.7883842 0.56770712, + -0.24128596 0.78933787 0.56455892, + -0.29962206 0.77600217 0.55502009, + -0.30352002 0.77654314 0.55213803, + -0.3681941 0.75773621 0.53876615, + -0.37159687 0.75791669 0.53616983, + -0.44189996 0.73233992 0.51807594, + -0.44383693 0.73226696 0.51652092, + -0.51793492 0.69901896 0.49306795, + -0.5174771 0.69907916 0.49346313, + -0.59380573 0.65734172 0.46400079, + -0.59275687 0.65758783 0.46499187, + -0.69086325 0.59031224 0.41742015, + -0.70626003 0.58438402 0.39961499, + -0.7850188 0.51134688 0.34967092, + -0.7913543 0.50777817 0.34047011, + -0.85236168 0.43435085 0.29123691, + -0.85376012 0.43329805 0.28869802, + -0.90050685 0.36187497 0.24110997, + -0.90915614 0.35313803 0.22074603, + -0.94215322 0.28422207 0.17766604, + -0.95022589 0.27261597 0.15083499, + -0.97153664 0.20727792 0.11468396, + -0.97488964 0.20012192 0.097680263, + -0.98784953 0.13966393 0.068170473, + -0.98905176 0.13566197 0.058071785, + -0.99623901 0.079656802 0.034098201, + -0.99655122 0.077775717 0.028926907, + -0.99963766 0.025230492 0.0093839159, + -0.99966264 0.024745191 0.0078945374, + -0.99967188 -0.024402196 -0.0077851089, + -0.99969035 -0.024028609 -0.0064727725, + -0.99721265 -0.07204318 -0.019406792, + -0.99733824 -0.071177013 -0.015824504, + -0.99266887 -0.11798499 -0.026231196, + -0.99292815 -0.11689401 -0.020724801, + -0.98615837 -0.16326006 -0.028945211, + -0.98652691 -0.16214699 -0.021748997, + -0.97761351 -0.2085409 -0.027971987, + -0.97802365 -0.20758392 -0.019458592, + -0.96700776 -0.25363493 -0.023775294, + -0.96737736 -0.25294408 -0.014156004, + -0.95409536 -0.29903513 -0.016735505, + -0.95437276 -0.29859295 -0.0038467292, + -0.96314573 -0.26886794 -0.007767078, + -0.96317452 -0.26887587 0.00072052167, + -0.96317345 -0.26888013 0.00072052237, + -0.96314466 -0.2688719 -0.007766997, + -0.96315074 -0.26884994 -0.0077665383, + -0.96317953 -0.26885787 0.00072021165, + -0.97518313 -0.22135402 -0.0045073302, + -0.97517014 -0.22135103 -0.0068519111, + -0.97517765 -0.22131793 -0.0068512177, + -0.97519875 -0.22132294 -0.0018602995, + -0.98488849 -0.17318809 0.00084531243, + -0.98487163 -0.17318495 -0.0058960076, + -0.98491865 -0.17291795 -0.0058903075, + -0.98493534 -0.17292106 0.0008475323, + -0.98488188 -0.17322499 0.00084753189, + -0.99219477 -0.12464397 -0.0036755991, + -0.9917171 -0.12840201 -0.0031744004, + -0.2546649 0.96702164 -0.0038567185, + -0.22211507 0.97502035 0.00041317815, + -0.22210693 0.97498876 0.008082578, + -0.22208592 0.97499365 0.0080826571, + -0.22209311 0.97502548 0.00041480121, + -0.22195707 0.97505635 0.00041480115, + -0.22185303 0.97459811 0.030656904, + -0.2054719 0.97846252 0.01980819, + -0.20520303 0.97769612 0.044745002, + -0.15871096 0.98629278 0.045138389, + -0.15823504 0.98456424 0.074799418, + -0.11246801 0.99080014 0.075273208, + -0.11194903 0.98810124 0.10546802, + -0.066870503 0.99212599 0.105898, + -0.066449881 0.98842365 0.13639295, + -0.022052106 0.99037224 0.13666204, + -0.021876095 0.98565775 0.16733296, + 0.0212526 0.98567098 0.167335, + 0.021425407 0.99038035 0.13670304, + 0.065728173 0.98846555 0.13643894, + 0.066146784 0.99218476 0.10580198, + 0.11127995 0.98818654 0.10537595, + 0.11179895 0.9909035 0.074907564, + 0.15772898 0.9846729 0.07443659, + 0.158208 0.98642099 0.044089399, + 0.20491703 0.97780311 0.043704305, + 0.20519897 0.97858387 0.016340397, + 0.21892197 0.97541088 0.025430197, + 0.21899305 0.97572625 0.0005737741, + 0.21895708 0.97573435 0.00057377422, + 0.21905793 0.97571164 0.00056614081, + 0.25466502 0.96702212 -0.0037548405, + 0.15389703 0.98807925 -0.003899331, + 0.12233499 0.99248886 0.00032403597, + 0.12233002 0.99245411 0.0083854105, + 0.12234601 0.99245214 0.008385391, + 0.12235 0.99248701 0.000322482, + 0.12227194 0.99249655 0.00032248185, + 0.12224501 0.9922781 0.020986103, + 0.11271605 0.99347347 0.017480707, + 0.11255595 0.99262953 0.044919379, + 0.066982806 0.99673414 0.045105204, + 0.066774428 0.99489546 0.075659238, + 0.021742806 0.99688524 0.075810514, + 0.0216421 0.99409801 0.106305, + -0.022299692 0.99408364 0.10630296, + -0.022404192 0.99685967 0.075952873, + -0.067359023 0.99484533 0.075799428, + -0.067566313 0.99666923 0.045665011, + -0.11290604 0.99256438 0.045477014, + -0.11305897 0.99337876 0.020404695, + -0.12533605 0.99180138 0.024919709, + -0.12537506 0.99210948 0.00012096906, + -0.12552199 0.99209088 0.00012096899, + -0.12551698 0.99205387 0.0086383894, + -0.125453 0.99206197 0.0086385198, + -0.12545702 0.99209911 0.00012746002, + -0.153897 0.98807901 -0.0039516301, + -0.10280795 -0.99469352 -0.003915648, + -0.071956687 -0.99740773 0.00026847795, + -0.071947075 -0.99727464 -0.016333994, + -0.11242895 -0.99355352 -0.014528293, + -0.11218097 -0.99263579 -0.045711689, + -0.15779102 -0.98642713 -0.045425802, + -0.15711299 -0.98467785 -0.075664096, + -0.20286396 -0.97632879 -0.075022481, + -0.20155405 -0.97379923 -0.10531402, + -0.24651894 -0.96351975 -0.10420198, + -0.24438488 -0.96029353 -0.13458194, + -0.28831205 -0.94826925 -0.13289703, + -0.28519604 -0.9444831 -0.16314101, + -0.32810196 -0.9308579 -0.16078798, + -0.32384604 -0.92665613 -0.19087203, + -0.36554709 -0.91165423 -0.18778205, + -0.35998204 -0.90717411 -0.21782602, + -0.39983308 -0.89125526 -0.21400404, + -0.39278784 -0.8866387 -0.24410991, + -0.43094891 -0.87000483 -0.23952994, + -0.42227685 -0.86540473 -0.26973492, + -0.45892689 -0.84822685 -0.26438093, + -0.44845301 -0.84381002 -0.294745, + -0.48367682 -0.8262887 -0.2886239, + -0.47112781 -0.82219368 -0.31943089, + -0.50449586 -0.8048088 -0.31267691, + -0.48952094 -0.80115688 -0.34426296, + -0.52096719 -0.78423828 -0.33699211, + -0.51819885 -0.78382671 -0.34217787, + -0.55314302 -0.76350498 -0.33330601, + -0.56635213 -0.76387018 -0.30943105, + -0.60111827 -0.74069625 -0.30004311, + -0.61339593 -0.73926795 -0.27789998, + -0.64716196 -0.71359897 -0.26824996, + -0.65835005 -0.71069205 -0.24797603, + -0.69081897 -0.68266493 -0.23819697, + -0.70082998 -0.67860198 -0.21985599, + -0.73215783 -0.6479758 -0.20993395, + -0.74095309 -0.64306504 -0.19353503, + -0.77107817 -0.60972613 -0.18350105, + -0.77857119 -0.60432112 -0.16918305, + -0.8067919 -0.56895995 -0.15928398, + -0.81307191 -0.56332296 -0.14690599, + -0.83941019 -0.52590913 -0.13715003, + -0.84566432 -0.51904017 -0.12429505, + -0.87036312 -0.47887105 -0.11467601, + -0.87572926 -0.47169212 -0.10298003, + -0.89863425 -0.42860308 -0.093573019, + -0.90278298 -0.42184901 -0.083823197, + -0.92340744 -0.37646118 -0.07480444, + -0.92648125 -0.37035108 -0.066878513, + -0.94470078 -0.32271391 -0.058275986, + -0.94685835 -0.31741512 -0.05202822, + -0.96260822 -0.26733005 -0.043818813, + -0.96402663 -0.2629219 -0.039047986, + -0.97717899 -0.210113 -0.031205, + -0.97799939 -0.20674288 -0.027828783, + -0.98818666 -0.15188494 -0.020444693, + -0.98855478 -0.14973196 -0.018432997, + -0.995646 -0.092516497 -0.0113894, + -0.99579024 -0.09109842 -0.010146203, + -0.9995119 -0.031047896 -0.0034579895, + -0.99957234 -0.029182611 -0.0019100307, + -0.99954325 0.030155307 0.0019737005, + -0.99960554 0.028082987 0.00033868483, + -0.99611777 0.088024579 0.0010615898, + -0.99658579 0.082505479 -0.0030898794, + -0.98975199 0.14269701 -0.0053440998, + -0.99085563 0.13445495 -0.011268497, + -0.98053676 0.19564995 -0.016397197, + -0.98233813 0.18566102 -0.023278601, + -0.96815538 0.24840508 -0.03114571, + -0.97061986 0.23754397 -0.038341098, + -0.95219624 0.30158406 -0.048677411, + -0.95501453 0.29137185 -0.055223975, + -0.93148023 0.35742909 -0.067743719, + -0.93417162 0.34931287 -0.07282728, + -0.90430897 0.41789299 -0.087125197, + -0.9057219 0.41435295 -0.089327089, + -0.8679533 0.48549217 -0.10466404, + -0.86634088 0.48880893 -0.10256398, + -0.81911755 0.56140065 -0.11779493, + -0.81109232 0.5746882 -0.10891604, + -0.75257713 0.64698708 -0.12261902, + -0.73443002 0.67049402 -0.105121, + -0.66393328 0.73876739 -0.11582505, + -0.63638729 0.76589239 -0.091761641, + -0.55665189 0.8248468 -0.098824978, + -0.50987703 0.85813898 -0.060190201, + -0.42767709 0.90171623 -0.063246712, + -0.38488206 0.92253613 -0.028159004, + -0.30715784 0.95121551 -0.029034387, + -0.29220894 0.95621675 -0.016233897, + -0.22102706 0.97512722 -0.016555004, + -0.18036 0.98338097 0.0207904, + -0.12181502 0.99233115 0.020979602, + -0.09442886 0.99435067 0.048475381, + -0.04788889 0.99766779 0.048637088, + -0.027674491 0.99707663 0.071219578, + 0.0084268926 0.99742335 0.071244426, + 0.0096828565 0.99730062 0.072785079, + 0.017247802 0.99719912 0.072777711, + -0.060748093 0.99773389 -0.028927496, + -0.049909413 0.99833423 -0.028944908, + -0.19739808 0.95178539 -0.23481609, + -0.18064506 0.95491636 -0.23558909, + -0.3114621 0.84693831 -0.43091416, + -0.29064584 0.8527956 -0.43389478, + -0.4043479 0.6766268 -0.6153689, + -0.42383492 0.67006785 -0.60940391, + -0.42350894 0.68029892 -0.59819192, + -0.50500017 0.47780117 -0.71880525, + -0.46064407 0.49134505 -0.73918009, + -0.50390887 0.29668593 -0.81120485, + -0.45976299 0.30502799 -0.83401197, + -0.48126793 0.062382493 -0.87435091, + -0.44517004 0.11212701 -0.88839811, + -0.44440988 0.11216497 -0.88877374, + -0.44723314 0.00050209515 -0.89441729, + -0.44799486 0.00090545067 -0.8940357, + -0.46988499 0.015869699 -0.88258499, + 0.025736194 0.012721797 0.99958777, + 0.022738298 0.013895499 0.99964488, + 0.022740507 5.4840919e-005 0.99974138, + 0.072468564 -0.00054014777 0.99737054, + 0.072468191 -0.0034151895 0.99736488, + 0.073298216 -0.0034152006 0.99730426, + 0.073298603 -0.000321981 0.99730998, + 0.072574802 -0.00032202399 0.99736297, + 0.072574385 -0.003526069 0.99735677, + 0.12159596 0.0083419476 0.99254465, + 0.12159994 -0.0011818894 0.99257851, + 0.12171899 -0.0011818699 0.9925639, + 0.12170202 0.016708503 0.9924261, + 0.12836005 0.013161205 0.99164033, + 0.22968695 0.012921398 0.97317874, + 0.21848097 0.005975639 0.97582287, + 0.218483 -0.0043647299 0.97583097, + 0.21830803 -0.0043649403 0.97587013, + 0.21826503 0.020309802 0.97567815, + 0.26576799 -0.0024167399 0.96403402, + 0.2657631 -0.0066678124 0.96401536, + 0.26704288 -0.0066650668 0.96366155, + 0.267048 -0.0024883801 0.96368003, + 0.26480705 -0.0024884306 0.96429825, + 0.3127681 0.0037178008 0.94982225, + 0.312756 -0.0094009601 0.94978702, + 0.31314498 -0.0093995789 0.94965887, + 0.31306785 0.024075389 0.94942552, + 0.35897213 -0.0013704305 0.93334734, + 0.35895488 -0.009785166 0.93330365, + 0.35844019 -0.0097876042 0.93350142, + 0.35845712 -0.0013088705 0.93354535, + 0.35817102 -0.0013088501 0.93365514, + 0.35815504 -0.0097699007 0.93361109, + 0.4004851 -0.014077504 0.91619521, + 0.40445715 -0.013021205 0.91446429, + 0.40449014 0.0019627807 0.91454029, + 0.40478599 0.0021202399 0.91440898, + 0.40475193 -0.013019098 0.91433388, + 0.44633895 -0.017028999 0.8947019, + 0.44644386 -0.02392789 0.89449167, + 0.50461298 -0.023086499 0.86303699, + 0.5048461 -0.027811008 0.8627612, + 0.56230479 -0.02664219 0.82650071, + 0.56277984 -0.032141488 0.82598168, + 0.60938609 -0.030829804 0.79227412, + 0.61159778 -0.05555908 0.78921568, + 0.65563017 -0.053025011 0.75321817, + 0.65868223 -0.091433033 0.74684525, + 0.70015538 -0.086763047 0.70869935, + 0.70253092 -0.12504098 0.70058197, + 0.74141133 -0.11790706 0.66061127, + 0.74296063 -0.15431492 0.65130371, + 0.77907813 -0.14453702 0.61003804, + 0.77983981 -0.17910695 0.59980887, + 0.81281441 -0.16667308 0.55816925, + 0.81292641 -0.1916301 0.54993522, + 0.78546721 -0.20365304 0.58443713, + 0.78534329 -0.22258407 0.57766116, + 0.75555563 -0.23553687 0.61127567, + 0.75521618 -0.25716206 0.6029231, + 0.72329921 -0.27091706 0.63517118, + 0.72270292 -0.29376498 0.62562191, + 0.68843818 -0.30827406 0.6565212, + 0.68752521 -0.33289912 0.64535826, + 0.65056229 -0.34816119 0.67494631, + 0.6492672 -0.3746911 0.66186017, + 0.60965806 -0.39050707 0.68979806, + 0.60794097 -0.418585 0.67468101, + 0.56592411 -0.43465108 0.7005772, + 0.56377393 -0.46395695 0.68330294, + 0.51964009 -0.47994205 0.70684505, + 0.51707995 -0.51005393 0.68736696, + 0.47015375 -0.52593279 0.70876664, + 0.46720412 -0.55690211 0.68671715, + 0.41820306 -0.57214808 0.70551604, + 0.41492501 -0.60365701 0.68076098, + 0.36395413 -0.61796224 0.69689322, + 0.36054319 -0.64908028 0.66985327, + 0.30848601 -0.66194499 0.68312901, + 0.30504307 -0.69275719 0.65348017, + 0.25174996 -0.70399892 0.66408396, + 0.24845603 -0.73420304 0.63183504, + 0.19419597 -0.74354094 0.63987094, + 0.19128397 -0.77261186 0.60537696, + 0.13716002 -0.77970713 0.61093706, + 0.13484003 -0.80729717 0.57453412, + 0.081097499 -0.81205398 0.57792002, + 0.079574689 -0.83788788 0.54001093, + 0.026321905 -0.84026217 0.5415411, + 0.025782997 -0.86444485 0.50206596, + -0.026390703 -0.86443114 0.50205809, + -0.026932299 -0.84026802 0.541502, + -0.080199502 -0.837865 0.53995401, + -0.08172287 -0.8120327 0.57786185, + -0.135415 -0.807253 0.57446098, + -0.13773301 -0.77968514 0.61083609, + -0.19181697 -0.77256989 0.60526192, + -0.19474591 -0.74332666 0.63995272, + -0.24895599 -0.73397601 0.63190198, + -0.25222299 -0.70398992 0.66391397, + -0.30568016 -0.69268835 0.65325528, + -0.30910698 -0.66213095 0.68266791, + -0.36111996 -0.64924592 0.66938192, + -0.36456102 -0.61796308 0.69657505, + -0.41525495 -0.60371196 0.68051094, + -0.41855708 -0.57196414 0.70545518, + -0.46771294 -0.55665392 0.68657196, + -0.47064307 -0.52596205 0.70842004, + -0.51732737 -0.51014334 0.68711448, + -0.5198921 -0.48003113 0.70659918, + -0.56398231 -0.46404621 0.6830703, + -0.56613809 -0.43472406 0.70035905, + -0.60829669 -0.41858578 0.67435968, + -0.61001903 -0.390558 0.68945003, + -0.64943123 -0.37480211 0.66163623, + -0.6507318 -0.34826592 0.67472881, + -0.68766952 -0.33299977 0.64515251, + -0.68858594 -0.30843198 0.65629196, + -0.72282863 -0.29391584 0.62540573, + -0.7234292 -0.27112505 0.63493419, + -0.75531912 -0.25736403 0.60270804, + -0.7556628 -0.23608194 0.61093289, + -0.78543347 -0.22310014 0.57733935, + -0.78556818 -0.20407504 0.58415413, + -0.8130067 -0.19202992 0.54967684, + -0.8129074 -0.16708307 0.55791122, + -0.7799471 -0.17954901 0.59953707, + -0.7792027 -0.14498396 0.60977274, + -0.74311006 -0.15479101 0.65102005, + -0.74160981 -0.11899197 0.6601938, + -0.70260406 -0.12622002 0.70029706, + -0.70029795 -0.088512994 0.70834196, + -0.65882379 -0.093280174 0.74649179, + -0.65573704 -0.054064609 0.7530511, + -0.61168921 -0.056650318 0.78906727, + -0.6094293 -0.031277314 0.79222333, + -0.56303716 -0.032602411 0.82578832, + -0.56251395 -0.026534095 0.82636189, + -0.50507808 -0.027698604 0.86262912, + -0.50482911 -0.022683406 0.86292118, + -0.446962 -0.023506699 0.89424402, + -0.44687012 -0.017475404 0.89442825, + -0.3946929 -0.017948397 0.91863775, + -0.39469206 -0.017277202 0.9186511, + -0.43776199 -0.016906399 0.89893198, + -0.43776879 -0.013996794 0.89897859, + -0.40627205 0.00032300802 0.91375214, + -0.40627179 -0.0011178195 0.9137516, + -0.40506795 -0.0011177598 0.9142859, + -0.4057669 -0.0012179198 0.91397578, + -0.3766461 0.015636804 0.92622524, + -0.46988711 0.015908204 0.88258326, + -0.49360195 -7.2510193e-005 0.86968786, + -0.49359983 -0.0024489891 0.86968571, + -0.49245983 -0.002455299 0.8703317, + -0.53264779 -0.018140491 0.84614259, + -0.53273505 -3.1905904e-005 0.84628212, + -0.5356971 -3.2083306e-005 0.84441018, + -0.5356909 -0.0045745592 0.84440184, + -0.53448176 -0.0045837276 0.84516758, + -0.53448719 -0.00068944925 0.84517628, + -0.55822587 0.015945597 0.82953584, + -0.57565832 0.0018431609 0.81768841, + -0.57630908 0.0017152702 0.81723011, + -0.57629502 -0.0071969898 0.81721002, + -0.5756439 -0.0072034383 0.8176688, + -0.61631197 -0.018280298 0.78728986, + -0.61641473 -0.0013059794 0.78742063, + -0.61566162 -0.0013059292 0.78800952, + -0.61563295 -0.0098189991 0.78797185, + -0.61431134 -0.009835816 0.78900248, + -0.61433989 -0.0020732796 0.78903884, + -0.64049417 0.015668403 0.76780319, + -0.71607494 0.014921698 0.69786394, + -0.7573157 -0.0030624089 0.65304178, + -0.75748652 -0.0030624082 0.65284359, + -0.75731081 -0.021763394 0.65269184, + -0.7929371 -0.023216601 0.60886109, + -0.79231173 -0.049651682 0.60809278, + -0.76245868 -0.052656282 0.64489079, + -0.76237082 -0.055608086 0.64474684, + -0.73473173 -0.058290478 0.67584878, + -0.73469597 -0.0609392 0.67565399, + -0.76877671 -0.057446677 0.63693178, + -0.76868099 -0.063213997 0.63650101, + -0.7942937 -0.060041778 0.60455978, + -0.79445732 -0.055321518 0.60479522, + -0.8223412 -0.051830411 0.56662911, + -0.82315755 -0.016417691 0.56757563, + -0.81744015 -0.027908508 0.57533711, + -0.81775367 -0.0034726288 0.57555783, + -0.81795698 -0.0034726299 0.57526898, + -0.81788987 -0.013263798 0.57522196, + -0.8172521 -0.013291402 0.57612705, + -0.81731981 -0.0033081493 0.57617486, + -0.78857535 0.008142774 0.61488432, + -0.788526 -0.0138293 0.61484599, + -0.78800368 -0.013847295 0.61551476, + -0.78796935 0.016691407 0.61548829, + -0.7840538 0.013696096 0.62054187, + -0.84369189 0.012636698 0.53667897, + -0.84507316 0.013854504 0.53447109, + -0.8450911 -0.012203102 0.53448308, + -0.8448841 -0.012214102 0.53481007, + -0.84489667 0.010934397 0.53481781, + -0.87036216 -0.0037104608 0.49239811, + -0.87031782 0.010762497 0.49237287, + -0.87002289 0.010760199 0.49289393, + -0.87008184 0.010667997 0.49279189, + -0.8764267 -0.019559393 0.48113781, + -0.87614089 -0.033265796 0.48090595, + -0.85092616 -0.036249109 0.52403313, + -0.85035086 -0.053484894 0.52349097, + -0.82431072 -0.057542477 0.56320584, + -0.82406288 -0.06384749 0.56288892, + -0.80008471 -0.06761048 0.59606475, + -0.80021483 -0.061896186 0.59651089, + -0.7811808 -0.064434282 0.6209709, + -0.7811718 -0.063953385 0.62103188, + -0.82234913 -0.058285207 0.56599003, + -0.82277018 -0.066419214 0.56448013, + -0.85213101 -0.0611552 0.51974303, + -0.85323 -0.086586103 0.51429701, + -0.87964827 -0.078964129 0.46902418, + -0.88033402 -0.107361 0.46204501, + -0.90177113 -0.097823516 0.42099807, + -0.90144169 -0.080114469 0.42542285, + -0.8779127 -0.088612773 0.47054982, + -0.87709421 -0.063936017 0.47604412, + -0.85020256 -0.070077471 0.52177078, + -0.84985083 -0.061779186 0.52338988, + -0.81188089 -0.068437293 0.57979792, + -0.81188655 -0.068905659 0.57973462, + -0.82956183 -0.065907784 0.5545119, + -0.82940072 -0.07146918 0.5540638, + -0.85177732 -0.06702362 0.5195992, + -0.85211915 -0.059171308 0.51999205, + -0.87579471 -0.054573782 0.47958881, + -0.87645757 -0.03564588 0.48015776, + -0.89915514 -0.032399505 0.43642905, + -0.89941633 -0.020283407 0.43662214, + -0.91427273 0.012448396 0.40490785, + -0.91418898 0.012447 0.40509701, + -0.91417027 0.012489202 0.40513808, + -0.91423613 -0.0034553804 0.40516707, + -0.91425431 -0.0034553811 0.40512615, + -0.91433787 -0.0034921095 0.40493694, + -0.89329129 0.013905805 0.44926316, + -0.89332622 0.010718203 0.44928113, + -0.89332879 0.010718198 0.44927588, + -0.89332801 0.0108194 0.44927499, + -0.89443469 0.011950395 0.44703886, + -0.89443868 0.011573796 -0.44704086, + -0.891846 0.0089352699 -0.45225099, + -0.89090031 0.04688812 -0.45177215, + -0.8909061 0.046887506 -0.45176107, + -0.89177102 0.0161146 -0.4522, + -0.91301358 -0.0031669587 -0.40791678, + -0.91223741 0.043468721 -0.4073492, + -0.91309577 -0.0031550394 -0.4077329, + -0.91298586 -0.0031550096 -0.40797895, + -0.91211289 0.043832798 -0.40758893, + -0.91214025 0.04382981 -0.4075281, + -0.89959979 -0.0047923592 -0.4366889, + -0.895239 0.100951 -0.43399999, + -0.91711313 0.09031181 -0.38826206, + -0.911035 0.147448 -0.38506401, + -0.93191612 0.12969202 -0.33869204, + -0.92560112 0.17497201 -0.33563003, + -0.94524676 0.15086697 -0.28939193, + -0.93674409 0.20239803 -0.28556204, + -0.95659626 0.16851304 -0.23775406, + -0.95129734 0.19933207 -0.23516008, + -0.96901298 0.15971801 -0.188425, + -0.96937209 0.15725602 -0.18864903, + -0.98477751 0.11129694 -0.13351494, + -0.98558074 0.10206497 -0.13495697, + -0.99384087 0.06684459 -0.088386692, + -0.99391311 0.065284111 -0.088740505, + -0.99798936 0.037559114 -0.051054019, + -0.99795145 0.039070919 -0.050660122, + -0.99979275 0.012433897 -0.016121997, + -0.99978948 0.012850407 -0.015998907, + -0.99980277 -0.012436997 0.015484196, + -0.99979699 -0.0131852 0.0152348, + -0.99824035 -0.038805217 0.044837616, + -0.99818045 -0.041347917 0.043889023, + -0.99517488 -0.067280792 0.071415693, + -0.99497533 -0.072182626 0.069380924, + -0.99053115 -0.098979712 0.095137812, + -0.99006462 -0.10669196 0.091591172, + -0.98409367 -0.13479395 0.11571596, + -0.98318988 -0.14553899 0.11025499, + -0.97570652 -0.17462891 0.13229294, + -0.97412515 -0.18868104 0.12441801, + -0.96493363 -0.21913892 0.14450295, + -0.96239275 -0.23640893 0.13383196, + -0.95126289 -0.26836297 0.15192199, + -0.95134503 -0.26840901 0.151325, + -0.93618113 -0.30620602 0.17263502, + -0.93441337 -0.31481713 0.16661906, + -0.91844773 -0.3495979 0.18502696, + -0.91607869 -0.35951489 0.17761993, + -0.89794672 -0.39457485 0.19494192, + -0.89489186 -0.40564793 0.18605998, + -0.87438661 -0.4410488 0.20229691, + -0.87049073 -0.45333484 0.19165993, + -0.84737539 -0.48908064 0.20677285, + -0.84250313 -0.50248706 0.19415303, + -0.81712091 -0.53772295 0.20776796, + -0.81122285 -0.55191392 0.19315398, + -0.78345299 -0.58656698 0.205282, + -0.77645653 -0.60130966 0.18852589, + -0.74609923 -0.63534021 0.19919507, + -0.73797196 -0.65032494 0.18020798, + -0.70504218 -0.68341219 0.18937604, + -0.69573939 -0.69838142 0.16795911, + -0.6609242 -0.72964817 0.17547904, + -0.65060782 -0.74407381 0.15186697, + -0.61402392 -0.77334386 0.15784098, + -0.60287106 -0.78681815 0.13215101, + -0.56469494 -0.81389987 0.13669899, + -0.55583888 -0.82317883 0.11584397, + -0.51614195 -0.8481459 0.11935698, + -0.50935084 -0.85441768 0.10262597, + -0.47205696 -0.87527686 0.10513099, + -0.46588683 -0.88039273 0.088645473, + -0.42486399 -0.90070301 0.090690397, + -0.42103791 -0.90354079 0.079631075, + -0.37916884 -0.92175466 0.081236273, + -0.37527218 -0.9243564 0.068818927, + -0.33029312 -0.94127333 0.070078425, + -0.33492288 -0.93825662 0.086608671, + -0.37770009 -0.92200822 0.085108824, + -0.38143301 -0.91929001 0.097029597, + -0.42344108 -0.90091926 0.09509062, + -0.42944992 -0.89604676 0.11257397, + -0.46770406 -0.87699109 0.11018001, + -0.47449893 -0.87087387 0.12817699, + -0.51499307 -0.8480581 0.12481902, + -0.52395111 -0.83891916 0.14727503, + -0.56380796 -0.81346589 0.14280699, + -0.57507086 -0.80022085 0.17011796, + -0.61326587 -0.77261084 0.16424796, + -0.62388498 -0.75816798 0.189602, + -0.66025585 -0.72860283 0.18220896, + -0.66996074 -0.71345478 0.20526792, + -0.70449018 -0.68204618 0.19623104, + -0.71316218 -0.66657621 0.21697004, + -0.74565083 -0.63361579 0.20624195, + -0.7532118 -0.61823887 0.22461694, + -0.78310019 -0.58451313 0.21236405, + -0.78959918 -0.56946415 0.22856906, + -0.81684721 -0.53534114 0.21487305, + -0.82230711 -0.52094305 0.22897503, + -0.84716833 -0.48641217 0.21379708, + -0.85163981 -0.47295889 0.22587495, + -0.87423742 -0.4381012 0.2092281, + -0.87777871 -0.42591685 0.21931593, + -0.89784712 -0.39145806 0.20157203, + -0.90066803 -0.380319 0.21013001, + -0.91838765 -0.34633487 0.19135393, + -0.92054677 -0.3364999 0.19839695, + -0.93615079 -0.30287594 0.17857195, + -0.93773276 -0.29450494 0.18418495, + -0.95138234 -0.2611461 0.16332306, + -0.95347834 -0.24776509 0.17173105, + -0.96412688 -0.21816097 0.15121199, + -0.96622711 -0.20140903 0.16074702, + -0.97510189 -0.17332299 0.13833098, + -0.97638911 -0.15991502 0.14522901, + -0.98366433 -0.13326004 0.12102205, + -0.98440588 -0.12294499 0.12581599, + -0.99025297 -0.0973434 0.099616401, + -0.99062365 -0.090207569 0.10260297, + -0.99502653 -0.065771572 0.07480906, + -0.9951871 -0.061220709 0.076516211, + -0.99818343 -0.037639078 0.047042869, + -0.99823421 -0.035175908 0.04786671, + -0.99979633 -0.011952205 0.016264405, + -0.99979991 -0.0114189 0.016422099, + -0.99978626 0.011804903 -0.016977204, + -0.99979055 0.011187894 -0.017137093, + -0.99792689 0.035182297 -0.053890791, + -0.99790812 0.035975005 -0.053713609, + -0.99314278 0.065056086 -0.097134076, + -0.99282289 0.070980392 -0.096251987, + -0.98307014 0.10874902 -0.14746802, + -0.98285389 0.11090598 -0.14730299, + -0.97003734 0.14613506 -0.19409308, + -0.97250938 0.12668805 -0.19538608, + -0.95705754 0.15771693 -0.24324088, + -0.96199113 0.11981201 -0.24539404, + -0.94579297 0.14249 -0.291843, + -0.94990414 0.10684001 -0.29371303, + -0.93208265 0.12383095 -0.34042287, + -0.93638843 0.076555535 -0.34251416, + -0.91704988 0.086983494 -0.38916993, + -0.92033023 -0.0073170117 -0.39107409, + -0.93108064 0.040620286 -0.36254489, + -0.93183076 0.0063884985 -0.3628369, + -0.93193579 0.0065108687 -0.36256492, + -0.93118662 0.040608287 -0.36227387, + -0.93861347 -0.0098496145 -0.34483019, + -0.93630964 0.07284268 -0.34353787, + -0.95290047 0.062908627 -0.29668716, + -0.95000738 0.10120504 -0.29537013, + -0.96488667 0.085140072 -0.24848491, + -0.96230888 0.11303799 -0.24735397, + -0.97532755 0.091758259 -0.20078991, + -0.97268099 0.118511 -0.199617, + -0.98427022 0.090190321 -0.15191403, + -0.98324752 0.10166395 -0.15128992, + -0.9918949 0.07086809 -0.10546198, + -0.99199414 0.069303811 -0.10556801, + -0.99757779 0.038174294 -0.058149487, + -0.99766755 0.034990184 -0.058610771, + -0.99978149 0.010716105 -0.017950209, + -0.99978298 0.0104937 -0.017999601, + -0.99979699 -0.0101479 0.0174064, + -0.99979287 -0.010843699 0.017226098, + -0.99820626 -0.031894606 0.05066701, + -0.99817187 -0.033810295 0.050098594, + -0.99515665 -0.05499028 0.081482172, + -0.99502414 -0.059380908 0.080006011, + -0.9906249 -0.081417695 0.10969698, + -0.99032462 -0.088203073 0.10713296, + -0.98452777 -0.11137597 0.13527897, + -0.98394287 -0.12098698 0.13121998, + -0.97677702 -0.145237 0.15752099, + -0.97573179 -0.15813896 0.15145797, + -0.96707553 -0.18379191 0.17602691, + -0.96536452 -0.19996391 0.16758792, + -0.95507735 -0.22713508 0.19036007, + -0.95509237 -0.22715507 0.19026108, + -0.94114739 -0.25911409 0.21702908, + -0.93995911 -0.26728803 0.21221203, + -0.92519885 -0.29720196 0.23596197, + -0.92361063 -0.30664089 0.23003191, + -0.90683728 -0.33715713 0.2529251, + -0.90474224 -0.34799808 0.24564005, + -0.8857947 -0.37913886 0.2676219, + -0.8830809 -0.39141694 0.25876796, + -0.86167669 -0.42331386 0.27985492, + -0.85824001 -0.43695799 0.269243, + -0.83464301 -0.46891999 0.28893799, + -0.83037668 -0.48383182 0.2763719, + -0.80447012 -0.51577806 0.29462004, + -0.7993952 -0.53144515 0.28023806, + -0.77082682 -0.56350088 0.29714093, + -0.76479101 -0.579997 0.280532, + -0.73346597 -0.61190796 0.29596698, + -0.72646958 -0.62885964 0.27708781, + -0.69287783 -0.65984184 0.29073894, + -0.68487757 -0.6770376 0.26937485, + -0.64913636 -0.70678341 0.28121018, + -0.64033306 -0.72358209 0.25768703, + -0.60243315 -0.75191116 0.26777607, + -0.59276104 -0.76826811 0.24165803, + -0.55263376 -0.79502165 0.25007287, + -0.54241318 -0.8103013 0.22181007, + -0.50112498 -0.83466798 0.22848, + -0.49057412 -0.84855217 0.19823304, + -0.44832385 -0.8704347 0.20334493, + -0.43763113 -0.88272727 0.17109005, + -0.39480183 -0.90198058 0.17482191, + -0.38649407 -0.91034913 0.14794202, + -0.3429521 -0.92718923 0.15067904, + -0.33697513 -0.93259436 0.12928905, + -0.29572001 -0.94622499 0.131179, + -0.28873193 -0.95190877 0.10248698, + -0.24729188 -0.96337354 0.10372095, + -0.24072906 -0.96790922 0.072119713, + -0.19907504 -0.97727525 0.072817512, + -0.19345297 -0.98029691 0.039923295, + -0.15183099 -0.98758787 0.040220197, + -0.14732301 -0.98906714 0.0064871809, + -0.10612198 -0.99433178 0.0065217088, + -0.10282799 -0.99430788 -0.027898395, + -0.062324721 -0.99766338 -0.02799261, + -0.060309224 -0.99618834 -0.063020922, + -0.020375995 -0.99779779 -0.063122682, + -0.019695492 -0.99495465 -0.09837386, + 0.019584894 -0.99495673 -0.098374076, + 0.02026459 -0.9977985 -0.063145772, + 0.060126591 -0.99619788 -0.063044496, + 0.062138472 -0.9976725 -0.028078487, + 0.10260396 -0.99432862 -0.02798439, + 0.10589595 -0.99435651 0.0064147669, + 0.14702407 -0.98911238 0.0063809422, + 0.15152298 -0.98763889 0.040127795, + 0.19313507 -0.98036337 0.039832216, + 0.19876988 -0.97733939 0.072788358, + 0.24037506 -0.96799922 0.072092816, + 0.24695694 -0.96344775 0.10382998, + 0.95511055 -0.22699289 0.19036292, + 0.9411639 -0.25894496 0.21715897, + 0.93997866 -0.2671119 0.21234693, + 0.92516547 -0.29711682 0.23619987, + 0.92359567 -0.30646589 0.23032491, + 0.90684342 -0.33692315 0.2532151, + 0.90472269 -0.34791389 0.24583091, + 0.88576388 -0.37905893 0.26783696, + 0.88304257 -0.39138183 0.25895187, + 0.86162329 -0.42328614 0.2800611, + 0.85814011 -0.43711606 0.26930502, + 0.8345297 -0.46908283 0.2890009, + 0.83026314 -0.48398706 0.27644104, + 0.8043322 -0.51594913 0.29469705, + 0.79922253 -0.53171271 0.28022283, + 0.77062488 -0.56378496 0.29712597, + 0.76452899 -0.580423 0.28036499, + 0.73316973 -0.61234975 0.29578689, + 0.72605598 -0.62954098 0.27662399, + 0.69245499 -0.66050899 0.29023099, + 0.68442804 -0.67770606 0.26883602, + 0.64873272 -0.70739162 0.28061187, + 0.63985026 -0.72427624 0.25693509, + 0.60190922 -0.75261128 0.2669861, + 0.59226906 -0.76885611 0.24099302, + 0.55213505 -0.79558814 0.24937204, + 0.54193485 -0.8107897 0.22119392, + 0.50068623 -0.83510941 0.2278281, + 0.49022093 -0.84884787 0.19783998, + 0.44810921 -0.87064439 0.20292009, + 0.43760589 -0.88270879 0.17124896, + 0.39468616 -0.90199828 0.17499106, + 0.38658705 -0.91017812 0.14874901, + 0.34295088 -0.92705464 0.15150695, + 0.33687699 -0.93256801 0.12973399, + 0.29546204 -0.94624209 0.13163601, + 0.28840807 -0.95199525 0.10259602, + 0.32952413 -0.93901235 0.09833464, + 0.29197299 -0.95122498 0.099613599, + 0.28588399 -0.95536202 0.074523903, + 0.33090085 -0.94080752 0.073388465, + 0.33462101 -0.93835503 0.086709902, + 0.37744313 -0.92210436 0.08520823, + 0.38119492 -0.91937077 0.097199179, + 0.42322099 -0.90100503 0.095257498, + 0.42937708 -0.89600426 0.11318903, + 0.46773994 -0.87689686 0.11077598, + 0.47470105 -0.87060612 0.12924401, + 0.51531106 -0.84771311 0.12584502, + 0.52388203 -0.8389501 0.14734502, + 0.56376207 -0.8134861 0.14287302, + 0.57480294 -0.8005209 0.16961099, + 0.61295706 -0.77295715 0.16377102, + 0.62343293 -0.7587539 0.18874297, + 0.65976417 -0.72924918 0.18140304, + 0.66945183 -0.71418583 0.20438395, + 0.70399636 -0.68279427 0.19540009, + 0.71266001 -0.66740799 0.216061, + 0.74515676 -0.63447076 0.20539792, + 0.7528013 -0.61899126 0.22392008, + 0.78272581 -0.5852499 0.21171395, + 0.78930098 -0.57007998 0.228063, + 0.81652272 -0.53601182 0.21443392, + 0.82205915 -0.52145213 0.22870606, + 0.84697884 -0.48685789 0.21353295, + 0.85151118 -0.47324911 0.22575206, + 0.87409973 -0.43841887 0.20913793, + 0.87770826 -0.42601308 0.21941106, + 0.89779758 -0.39153081 0.20165092, + 0.90061623 -0.3804031 0.21020004, + 0.9183439 -0.34641498 0.19141898, + 0.92053276 -0.33644092 0.19856195, + 0.93614686 -0.30280596 0.17871098, + 0.93773824 -0.29437605 0.18436304, + 0.95140266 -0.2609899 0.16345394, + 0.95349073 -0.24764293 0.17183796, + 0.95355523 -0.24770406 0.17139204, + 0.93907303 -0.282653 0.195574, + 0.93764025 -0.29091305 0.19026405, + 0.92233324 -0.32337508 0.21149504, + 0.92039102 -0.333029 0.204871, + 0.90302825 -0.3658911 0.22508606, + 0.90042377 -0.37712592 0.21682495, + 0.8807826 -0.41050878 0.23601788, + 0.87746227 -0.4229871 0.22614606, + 0.85531086 -0.45691195 0.24428397, + 0.85119772 -0.47043782 0.23270291, + 0.82674581 -0.5042569 0.24943194, + 0.82166886 -0.51891595 0.23576798, + 0.79491663 -0.55237776 0.25097087, + 0.78882718 -0.56784111 0.23517706, + 0.75933719 -0.6011771 0.24898405, + 0.75222737 -0.61707228 0.2310321, + 0.72017092 -0.64974993 0.24326697, + 0.71198493 -0.66585594 0.22296497, + 0.67778981 -0.69720584 0.23346294, + 0.66867298 -0.71298403 0.211022, + 0.63255608 -0.74266905 0.21980803, + 0.62254721 -0.75787431 0.19509408, + 0.58440286 -0.78584385 0.20229396, + 0.57381481 -0.79990572 0.17574795, + 0.53384411 -0.82588416 0.18145505, + 0.52280194 -0.83861285 0.15299198, + 0.48198381 -0.86195368 0.15724994, + 0.47342589 -0.8705548 0.13417298, + 0.43193093 -0.89138186 0.13738298, + 0.42512605 -0.89744514 0.11772902, + 0.38564599 -0.91480899 0.120007, + 0.37974083 -0.91955858 0.10103896, + 0.33429298 -0.93683088 0.10293698, + 0.34074789 -0.93164665 0.12619595, + 0.38152018 -0.91599542 0.12407606, + 0.38802209 -0.91020226 0.14481303, + 0.43055472 -0.89135349 0.14181492, + 0.43897295 -0.88293189 0.16653499, + 0.48071906 -0.8616811 0.16252701, + 0.49156424 -0.84928042 0.19258109, + 0.53266203 -0.82537413 0.18716002, + 0.54325712 -0.81146318 0.21540505, + 0.58328795 -0.7850759 0.20840096, + 0.59348804 -0.76980013 0.23490404, + 0.63153607 -0.74158806 0.22629502, + 0.64097297 -0.72553802 0.250496, + 0.67687893 -0.69579196 0.24022597, + 0.68544376 -0.67929578 0.26215291, + 0.71938759 -0.64802665 0.25008586, + 0.72697717 -0.63148916 0.26967707, + 0.75866163 -0.59913868 0.25586188, + 0.76533109 -0.58267808 0.27341303, + 0.79432201 -0.54996097 0.25806099, + 0.79992503 -0.53428602 0.27323699, + 0.82624054 -0.50153768 0.25648886, + 0.83086932 -0.48684818 0.26950908, + 0.85488719 -0.45390511 0.25127307, + 0.85866314 -0.44028005 0.26239502, + 0.88044101 -0.407307 0.242744, + 0.88348114 -0.39478207 0.25220704, + 0.90275246 -0.36250079 0.23158386, + 0.90508312 -0.35149604 0.23932204, + 0.92211664 -0.31981888 0.21775393, + 0.92388642 -0.31020314 0.2240711, + 0.93890989 -0.27899098 0.20152497, + 0.94020033 -0.27086908 0.20652707, + 0.95336235 -0.24001908 0.18300606, + 0.95508265 -0.22695492 0.19054793, + 0.96538699 -0.199753 0.16771001, + 0.96709001 -0.18361899 0.176128, + 0.97574401 -0.157985 0.15154, + 0.97678912 -0.14505401 0.15761502, + 0.98395336 -0.12082604 0.13128905, + 0.98454249 -0.11110906 0.13539205, + 0.99033511 -0.087985709 0.10721502, + 0.99063563 -0.08114887 0.10979896, + 0.99503064 -0.059179876 0.080073573, + 0.99515724 -0.054970514 0.081488825, + 0.9981721 -0.033797905 0.050102308, + 0.99820709 -0.031843103 0.050682306, + 0.99979287 -0.010825999 0.017230898, + 0.99979788 -0.0099802893 0.017450098, + 0.99978387 0.010320099 -0.018044299, + 0.99978137 0.010723704 -0.017954705, + 0.99766725 0.035004407 -0.058607616, + 0.99757499 0.038270101 -0.058134299, + 0.99198288 0.069486395 -0.10555398, + 0.99181461 0.072109476 -0.10537496, + 0.98307621 0.10345902 -0.15118703, + 0.98390937 0.094417639 -0.15168306, + 0.97205877 0.12404697 -0.19928396, + 0.97544938 0.090500727 -0.20076908, + 0.96246922 0.11152703 -0.24741606, + 0.96546489 0.077440396 -0.24875797, + 0.95085913 0.092032008 -0.29563004, + 0.953655 0.048462 -0.296974, + 0.95354253 0.045175377 -0.29785186, + 0.96726364 0.038054686 -0.2509039, + 0.96547675 0.072967187 -0.25006095, + 0.97736585 0.059260294 -0.20308697, + 0.97560054 0.085345566 -0.20228592, + 0.98563164 0.06565918 -0.15562494, + 0.98395646 0.088653848 -0.15482308, + 0.99219388 0.061967593 -0.10821898, + 0.99194324 0.066181913 -0.10802102, + 0.99723834 0.038799316 -0.063327722, + 0.99728835 0.037335016 -0.063420221, + 0.99974811 0.011385601 -0.019340603, + 0.9997561 0.010412601 -0.019480001, + 0.99978763 -0.0097138463 0.018172795, + 0.99978966 -0.0093557062 0.018252293, + 0.99817878 -0.027517293 0.05368419, + 0.99813855 -0.030192384 0.052988574, + 0.99507111 -0.049092606 0.08615911, + 0.99497712 -0.052772809 0.085061811, + 0.99054134 -0.072338223 0.11659805, + 0.99030685 -0.078711696 0.11444099, + 0.98449862 -0.099393159 0.14451095, + 0.98403174 -0.10865198 0.14098297, + 0.97691089 -0.13041599 0.16922398, + 0.97608048 -0.14278407 0.16395007, + 0.96755362 -0.16593894 0.19053693, + 0.96617055 -0.18167691 0.18305191, + 0.95607752 -0.20647989 0.20804289, + 0.95471627 -0.21891706 0.20147504, + 0.94191426 -0.24712506 0.22743505, + 0.94087863 -0.25497392 0.22301492, + 0.92625713 -0.28368804 0.24813104, + 0.92480421 -0.29321107 0.24241406, + 0.90832078 -0.32236791 0.26651895, + 0.90641272 -0.33324987 0.25953892, + 0.88767499 -0.363291 0.28293601, + 0.8852337 -0.37547284 0.27455691, + 0.86415273 -0.40621385 0.29703587, + 0.86100918 -0.4199841 0.28683907, + 0.83774471 -0.45092785 0.30797389, + 0.83382303 -0.46605301 0.29586101, + 0.80822414 -0.49715805 0.31560704, + 0.8035202 -0.51318812 0.30165106, + 0.77527469 -0.54452282 0.32006887, + 0.76970714 -0.56133908 0.30405504, + 0.73863226 -0.59274024 0.32106313, + 0.73212606 -0.61019808 0.30273703, + 0.69886196 -0.64073396 0.31788698, + 0.69132167 -0.65872473 0.29691085, + 0.65589684 -0.68817484 0.31018493, + 0.64751905 -0.70596105 0.28694603, + 0.60969496 -0.73429692 0.29846296, + 0.60060424 -0.7514953 0.27300107, + 0.56047219 -0.77840132 0.28277609, + 0.55075985 -0.79476881 0.25496295, + 0.50935113 -0.81942618 0.26287305, + 0.49926418 -0.83454031 0.23297609, + 0.45676088 -0.8568278 0.23919794, + 0.4466491 -0.8702662 0.20770505, + 0.40319484 -0.89011371 0.21244192, + 0.39322409 -0.90179825 0.17926204, + 0.34911713 -0.91909635 0.18270005, + 0.34149987 -0.9270196 0.15495993, + 0.29749805 -0.94165725 0.15740605, + 0.29194707 -0.94691223 0.13462603, + 0.24998097 -0.95861089 0.13628899, + 0.24378388 -0.96398455 0.10631595, + 0.20162304 -0.97356021 0.10737202, + 0.19607905 -0.97773522 0.074745916, + 0.15382197 -0.98522377 0.075318389, + 0.14935306 -0.98790836 0.041603714, + 0.10756198 -0.9933179 0.041831598, + 0.10429804 -0.99451834 0.0074395128, + 0.063165314 -0.99797523 0.0074653719, + 0.061169684 -0.99774873 -0.027488992, + 0.020612307 -0.99940836 -0.02753471, + 0.019942999 -0.99781686 -0.062958591, + -0.020093698 -0.99781388 -0.06295839, + -0.020764397 -0.99940687 -0.027471997, + -0.061393887 -0.99773675 -0.027426092, + -0.063389368 -0.99796051 0.0075296364, + -0.10459001 -0.99448711 0.0075034308, + -0.10785501 -0.99328309 0.041905303, + -0.14969102 -0.98785412 0.041676305, + -0.15416592 -0.9851675 0.075351864, + -0.19638103 -0.9776721 0.074778706, + -0.20192292 -0.97350264 0.10732996, + -0.24403585 -0.96392542 0.10627393, + -0.25016606 -0.95861423 0.13592602, + -0.29208884 -0.9469195 0.13426694, + -0.29755703 -0.94176114 0.15667102, + -0.34144989 -0.92715764 0.15424193, + -0.34925187 -0.91905564 0.18264695, + -0.39329582 -0.90177661 0.17921291, + -0.40340006 -0.8899141 0.21288803, + -0.44685984 -0.87005472 0.20813693, + -0.457057 -0.856457 0.239959, + -0.49968505 -0.83408815 0.23369204, + -0.50980163 -0.81887043 0.26372981, + -0.55123174 -0.79417962 0.2557779, + -0.56092 -0.777785 0.28358299, + -0.60113925 -0.75079727 0.27374309, + -0.61016804 -0.73365706 0.29906902, + -0.64792305 -0.70535207 0.28753102, + -0.65626144 -0.68758839 0.31071419, + -0.69175333 -0.65806329 0.29737216, + -0.69918501 -0.640288 0.318075, + -0.73242491 -0.60975492 0.30290696, + -0.73890907 -0.59232306 0.32119602, + -0.76989114 -0.56100208 0.30421102, + -0.7754122 -0.54429913 0.3201161, + -0.80364603 -0.512968 0.30169001, + -0.80831373 -0.49704581 0.31555387, + -0.83394182 -0.46589389 0.29577693, + -0.83782482 -0.45091888 0.30776894, + -0.86106372 -0.41999385 0.28666091, + -0.86419815 -0.40627307 0.29682302, + -0.88526624 -0.3755351 0.27436706, + -0.8877297 -0.36325088 0.2828159, + -0.90639102 -0.33332601 0.25951701, + -0.9082967 -0.32245988 0.26648992, + -0.92483288 -0.29320398 0.24231297, + -0.92625058 -0.28392586 0.24788289, + -0.94086885 -0.25519696 0.22280097, + -0.94190723 -0.24734905 0.22722106, + -0.95470566 -0.21912792 0.20129593, + -0.95607787 -0.20662098 0.20790097, + -0.96615535 -0.18184206 0.18296807, + -0.96753913 -0.16613701 0.19043803, + -0.97606802 -0.14296 0.16387101, + -0.97689354 -0.13071693 0.16909193, + -0.98401737 -0.10891104 0.14088404, + -0.98448187 -0.099763185 0.14436999, + -0.99029934 -0.078992933 0.11431304, + -0.9905439 -0.072378293 0.11655098, + -0.9949761 -0.052814707 0.085047707, + -0.99506825 -0.04921921 0.086119823, + -0.99813735 -0.030271711 0.052967019, + -0.99817288 -0.027944697 0.053572092, + -0.99978876 -0.0095066484 0.018224996, + -0.99978763 -0.0097094066 0.018179994, + -0.9997561 0.010404101 -0.019480802, + -0.99974847 0.011356005 -0.01934441, + -0.99729162 0.037234183 -0.063426577, + -0.99726009 0.038168103 -0.063367605, + -0.99200922 0.065096714 -0.10807502, + -0.99235737 0.059037421 -0.10835804, + -0.98430246 0.084438935 -0.15498008, + -0.98557812 0.06651631 -0.15560001, + -0.97549313 0.086488008 -0.20231903, + -0.97697586 0.065730989 -0.20297197, + -0.96492833 0.080877833 -0.24974409, + -0.96677452 0.050708279 -0.25055087, + -0.9528389 0.060199294 -0.29744598, + -0.95446837 0.0060896822 -0.29825011, + -0.97503275 -0.0016615296 -0.22205494, + -0.96691543 0.01544659 -0.25462884, + -0.96300113 0.0041911504 -0.26946503, + -0.96291673 0.0040769191 -0.26976794, + -0.96238387 0.033510298 -0.26961896, + -0.9624691 0.033498403 -0.26931602, + -0.94783109 -0.040903904 -0.31613803, + -0.94862211 -0.0025675101 -0.31640103, + -0.94855434 -0.002567501 -0.31660411, + -0.94790411 0.037111003 -0.31638703, + -0.94791609 0.037109505 -0.31635103, + -0.94856638 -0.0025759109 -0.31656811, + -0.93560863 0.014747594 -0.35273087, + -0.99209648 -0.00049358222 -0.12547706, + -0.98796374 0.015808497 -0.15387598, + -0.98475635 0.0022355006 -0.17392506, + -0.98474878 0.0022237096 -0.17396796, + -0.98438752 0.027177487 -0.17390391, + -0.98439503 0.027176101 -0.173862, + -0.97434735 -0.03567991 -0.22220308, + -0.97496688 -0.0016680597 -0.22234397, + -0.97503775 -0.0016680496 -0.22203293, + -0.97460186 0.029942296 -0.22193398, + -0.97459686 0.029943096 -0.22195597, + -0.96766925 -0.013614602 -0.25185505, + -0.96671611 0.048181009 -0.25127402, + -0.97809076 0.039203487 -0.20445396, + -0.97698635 0.062394723 -0.20397207, + -0.98641288 0.048056394 -0.15709898, + -0.98565114 0.062657811 -0.15673502, + -0.99286026 0.044279013 -0.11076103, + -0.99234402 0.055268101 -0.110448, + -0.99736178 0.032484893 -0.064917788, + -0.99727809 0.035169505 -0.064804204, + -0.99971545 0.011378306 -0.02096601, + -0.99971867 0.011055997 -0.020985693, + -0.99975711 -0.010273201 0.019499902, + -0.99976325 -0.0094021019 0.019624706, + -0.99808663 -0.026715191 0.05576168, + -0.9980945 -0.026154786 0.055886574, + -0.99495834 -0.042510014 0.090833731, + -0.99487066 -0.046664987 0.089748271, + -0.99035048 -0.063932329 0.12295806, + -0.99018162 -0.069491975 0.12128995, + -0.98429865 -0.08774817 0.15315494, + -0.98392624 -0.096782021 0.15007503, + -0.97677523 -0.11612503 0.18007004, + -0.97612786 -0.12789698 0.17554699, + -0.96763146 -0.14860807 0.2039731, + -0.96654975 -0.16362795 0.19750296, + -0.95658398 -0.18594299 0.224438, + -0.95484865 -0.20451392 0.21549493, + -0.94325286 -0.22859597 0.24086897, + -0.94334435 -0.22872707 0.24038608, + -0.92773157 -0.25728789 0.2704019, + -0.92659891 -0.26637498 0.26544097, + -0.91043133 -0.29301512 0.2919881, + -0.90891325 -0.30364007 0.28579605, + -0.89065313 -0.33109102 0.31163403, + -0.88864487 -0.34339297 0.30395997, + -0.86801517 -0.37180308 0.32910809, + -0.86549544 -0.38536075 0.32002282, + -0.84273767 -0.41413885 0.34392187, + -0.8395738 -0.4291679 0.33306292, + -0.81464785 -0.45816895 0.35556996, + -0.81073612 -0.47460505 0.34272003, + -0.78307688 -0.50420696 0.36409596, + -0.77839428 -0.52166718 0.34923613, + -0.74806798 -0.55145502 0.36917701, + -0.74251705 -0.56986809 0.35202104, + -0.70977926 -0.59930223 0.37020311, + -0.70347196 -0.61799496 0.35101196, + -0.6684286 -0.64673567 0.36733678, + -0.66130221 -0.66568023 0.34575912, + -0.62369078 -0.69367975 0.3603029, + -0.61568093 -0.71281296 0.33590898, + -0.57567984 -0.73966074 0.34856087, + -0.56711769 -0.75807363 0.32202786, + -0.52531594 -0.78317291 0.33269098, + -0.51623088 -0.80082083 0.30363095, + -0.47309917 -0.82378531 0.31233811, + -0.46376112 -0.8401922 0.28107405, + -0.41942185 -0.86089569 0.2879999, + -0.41004816 -0.8757953 0.25464308, + -0.36464688 -0.89411873 0.25996992, + -0.35561982 -0.90711659 0.22510889, + -0.31017888 -0.92269164 0.22897393, + -0.30169705 -0.93374425 0.19261505, + -0.25669008 -0.94656438 0.19525908, + -0.2504279 -0.95405465 0.16451594, + -0.20572902 -0.96437609 0.16629602, + -0.20159605 -0.96912926 0.14194202, + -0.15836105 -0.97695822 0.14308903, + -0.15421793 -0.98170251 0.11170094, + -0.11118405 -0.98742849 0.11235305, + -0.10797296 -0.99106467 0.07831087, + -0.065491073 -0.99475253 0.078602262, + -0.063518383 -0.99702674 0.043624189, + -0.021533089 -0.9988125 0.043702278, + -0.020864099 -0.99974799 0.0082896501, + 0.020564603 -0.99975413 0.0082897013, + 0.021220505 -0.99881923 0.04370261, + 0.063150309 -0.99705011 0.043625202, + 0.065123864 -0.99477643 0.078604452, + 0.10759901 -0.99110514 0.078314409, + 0.11078998 -0.98746789 0.11239499, + 0.15383606 -0.98175734 0.11174504, + 0.15799206 -0.97697335 0.14339304, + 0.20144807 -0.96911633 0.14224005, + 0.2056119 -0.9643175 0.16677992, + 0.25036609 -0.95398837 0.16499406, + 0.25654092 -0.94659364 0.19531293, + 0.30158702 -0.93376911 0.19266704, + 0.30999506 -0.92282325 0.22869305, + 0.35537291 -0.90727979 0.22484094, + 0.36432204 -0.89442509 0.25937104, + 0.4096902 -0.8761304 0.25406611, + 0.41903585 -0.86132473 0.28727791, + 0.46340087 -0.84062481 0.28037393, + 0.47274405 -0.82428211 0.31156403, + 0.51576298 -0.80139399 0.30291301, + 0.52488005 -0.7837531 0.33201203, + 0.56656468 -0.75874567 0.32141784, + 0.57522202 -0.740183 0.34820801, + 0.615327 -0.71328503 0.33555499, + 0.62336421 -0.69414026 0.35998112, + 0.66091108 -0.66620606 0.34549403, + 0.66812098 -0.64707601 0.36729699, + 0.70320183 -0.61832291 0.3509759, + 0.70956105 -0.59949207 0.37031403, + 0.74231964 -0.57005668 0.35213181, + 0.74785644 -0.55170238 0.3692362, + 0.77828914 -0.52182204 0.34923902, + 0.78298271 -0.5043388 0.36411589, + 0.81060171 -0.47478983 0.34278187, + 0.8145628 -0.45814788 0.3557919, + 0.839553 -0.42908499 0.333222, + 0.84269214 -0.41417405 0.34399104, + 0.86542672 -0.38543385 0.32012087, + 0.86799872 -0.37157688 0.32940689, + 0.88859522 -0.34323609 0.30428207, + 0.89060372 -0.33089989 0.31197789, + 0.90890777 -0.30340895 0.28605893, + 0.91042358 -0.29276985 0.29225785, + 0.92662722 -0.26609206 0.26562607, + 0.92773789 -0.25716296 0.27049896, + 0.94207877 -0.23108993 0.24307394, + 0.94289464 -0.22353692 0.24694291, + 0.95548803 -0.19799399 0.21872599, + 0.95658487 -0.18571198 0.22462498, + 0.9552505 -0.1829659 0.23242189, + 0.95658785 -0.16499698 0.24024098, + 0.94362366 -0.18063994 0.2773869, + 0.95515311 -0.16159101 0.24813503, + 0.95616555 -0.14385892 0.25505289, + 0.94289166 -0.15617993 0.29421589, + 0.95459467 -0.13967995 0.26313192, + 0.95529366 -0.12251796 0.26907891, + 0.96552813 -0.10786501 0.23689803, + 0.96592921 -0.094262324 0.24103005, + 0.97483164 -0.081199668 0.20762892, + 0.97506911 -0.069798805 0.21063803, + 0.98272491 -0.058214292 0.17567798, + 0.98267847 -0.060523529 0.17515709, + 0.98849136 -0.049405817 0.14298205, + 0.98832715 -0.054652907 0.14220601, + 0.99335563 -0.041285686 0.10742496, + 0.99327946 -0.043424621 0.10728605, + 0.99324387 -0.041256197 0.10846399, + 0.99748635 -0.025191909 0.066230625, + 0.99759555 -0.01998819 0.066358671, + 0.99973565 -0.0066314274 0.022015693, + 0.99974614 -0.0046407804 0.022048902, + 0.999744 0.00466015 -0.022141, + 0.99974525 0.0043862811 -0.022144005, + 0.99974602 0.00131509 -0.0225005, + 0.99973714 0.0044152304 -0.022500303, + 0.99737614 0.0035449804 -0.072307907, + 0.99738175 -0.0010912998 -0.072308287, + 0.99740964 -0.0010912496 -0.071922176, + 0.99457777 0.015670497 -0.10280798, + 0.99741054 -0.0010972095 -0.071909361, + 0.99734426 0.011586203 -0.071904615, + 0.99362314 0.0051652105 -0.11263402, + 0.99250448 0.018443009 -0.12080906, + 0.99266863 0.0030732388 -0.12082896, + 0.99270451 0.0031391885 -0.12053194, + 0.9925409 0.018415498 -0.12051298, + 0.98553842 0.0049700872 -0.16937889, + 0.9855485 -0.002123679 -0.16937992, + 0.98556024 -0.0021237005 -0.16931204, + 0.9787451 0.015125101 -0.20452203, + 0.98552126 -0.0020443304 -0.16954005, + 0.98521179 0.025137894 -0.16948695, + 0.97767478 0.010330597 -0.20986995, + 0.97557062 0.032611288 -0.21725193, + 0.97607636 0.0052367421 -0.21736507, + 0.97602224 0.0051556015 -0.21761005, + 0.97551554 0.032627486 -0.2174969, + 0.96411586 -0.015261198 -0.26504296, + 0.96422386 -0.0029316195 -0.26507297, + 0.96425164 -0.0029316188 -0.26497191, + 0.95253688 0.014363798 -0.30408397, + 0.964261 -0.00294053 -0.264938, + 0.96357638 0.037790716 -0.26475009, + 0.95444697 0.00059285498 -0.29837999, + 0.94919902 0.042771898 -0.31175601, + 0.95004123 0.0075976318 -0.31203207, + 0.94998038 0.0075200428 -0.31221911, + 0.94913733 0.042785317 -0.31194213, + 0.93359166 -0.011347196 -0.35815889, + 0.93364638 -0.0033985111 -0.35818011, + 0.93358886 -0.0033985095 -0.35832998, + 0.9325099 0.048182491 -0.35791597, + 0.93256766 0.048171081 -0.35776687, + 0.9336459 -0.0034300496 -0.35818097, + 0.9148643 0.014466505 -0.40350214, + 0.9137339 0.051750794 -0.40300393, + 0.91361487 0.051772092 -0.40327093, + 0.91479522 0.010130903 -0.4037911, + 0.9162659 0.011756798 -0.40039793, + 0.99457479 0.015856896 0.10280798, + 0.99718326 -0.00029500405 0.075003013, + 0.99718165 0.0018072593 0.075002871, + 0.99717253 0.0017992092 0.075123765, + 0.99717426 -0.00023888606 0.075123914, + 0.9972015 -0.00023889288 0.074760862, + 0.99714434 -0.010706903 0.07475663, + 0.99770236 -0.0083688926 0.067231022, + 0.99766439 -0.012320993 0.067185462, + 0.99349964 -0.020533593 0.11196797, + 0.99330425 -0.029095007 0.11180403, + 0.98685485 -0.040700197 0.15639998, + 0.9864465 -0.050540924 0.15610607, + 0.97849786 -0.063530892 0.19622897, + 0.97863209 -0.060809009 0.19642203, + 0.97103488 -0.070662595 0.22824997, + 0.97127724 -0.063401014 0.22934906, + 0.96308786 -0.071723893 0.25945598, + 0.96312052 -0.069063172 0.26005587, + 0.95229536 -0.078331031 0.29495412, + 0.95212287 -0.095011182 0.29057696, + 0.926085 -0.138734 0.35088399, + 0.93952709 -0.12592402 0.31848404, + 0.93991852 -0.10610095 0.32449284, + 0.92358786 -0.11001199 0.36726397, + 0.93752915 -0.099830717 0.33327603, + 0.9374941 -0.071983211 0.34047502, + 0.91753101 -0.082255803 0.38906401, + 0.91749114 -0.07624191 0.39038107, + 0.92927676 -0.070803583 0.36253491, + 0.92907941 -0.079815336 0.36116618, + 0.94034022 -0.073418416 0.33222008, + 0.94001138 -0.079610333 0.33172411, + 0.95328176 -0.070494883 0.29374194, + 0.95435798 -0.049300399 0.294568, + 0.96778578 -0.015752897 0.25128195, + 0.96712154 -0.041979481 0.25082588, + 0.97861046 -0.019742109 0.2047731, + 0.97815853 -0.037289683 0.20448789, + 0.96755546 -0.045326624 0.24856012, + 0.96656048 -0.065902829 0.24782611, + 0.95512521 -0.076121815 0.28625405, + 0.95539767 -0.071059279 0.28664592, + 0.94538552 -0.078429766 0.31637785, + 0.94562012 -0.069822505 0.31769103, + 0.93492526 -0.076170214 0.34657308, + 0.93491364 -0.081910968 0.34529287, + 0.95019686 -0.071933895 0.30323496, + 0.95018077 -0.074678883 0.30262095, + 0.95955378 -0.067449786 0.27332595, + 0.95930499 -0.075425901 0.27211201, + 0.96811098 -0.066918299 0.241419, + 0.96790302 -0.070866004 0.241126, + 0.97759688 -0.059350893 0.20194498, + 0.97844666 -0.040098485 0.20256892, + 0.98691875 -0.031305894 0.15814996, + 0.98727489 -0.014140198 0.15839298, + 0.98476046 -0.023916811 0.17226408, + 0.98504114 -0.0014926703 0.17231302, + 0.98502165 -0.0014926594 0.17242394, + 0.98502213 -0.0012383402 0.17242402, + 0.98503977 -0.0012325797 0.17232296, + 0.98503935 -0.0015275106 0.17232306, + 0.97873914 0.015531502 0.20452003, + 0.97538924 0.0038178109 0.22045706, + 0.97535688 0.0037699896 0.22060098, + 0.97535938 -0.0029808511 0.22060208, + 0.97539198 -0.0029732101 0.220458, + 0.9628849 -0.032249197 0.26797897, + 0.96338302 -0.00243529 0.26811799, + 0.9633919 -0.0024352898 0.26808596, + 0.96338511 -0.0044860006 0.26808402, + 0.96334076 -0.0044938191 0.26824296, + 0.95444334 -0.023138108 0.29749411, + 0.95377487 -0.045602396 0.29704198, + 0.93873167 -0.052298281 0.34065789, + 0.93763566 -0.073469967 0.33976689, + 0.92254937 -0.081556126 0.37716216, + 0.92291862 -0.074302368 0.37775686, + 0.91057312 -0.079774305 0.40557706, + 0.91071779 -0.070425183 0.4069809, + 0.88966823 -0.077855818 0.44992113, + 0.88965988 -0.07850989 0.44982395, + 0.90322858 -0.073787861 0.4227688, + 0.90284324 -0.08194492 0.4220891, + 0.91956323 -0.074888013 0.3857401, + 0.92063344 -0.054011725 0.38667417, + 0.93792289 -0.047982294 0.34350896, + 0.93865162 -0.023912391 0.34403688, + 0.9324159 -0.0060061188 0.36133698, + 0.93242812 -0.0031373505 0.36134204, + 0.93256867 -0.0031373189 0.36097887, + 0.93255574 -0.0061944085 0.36097291, + 0.93246424 -0.0062041013 0.36120909, + 0.92039323 -0.024461405 0.39022809, + 0.91963965 -0.049455781 0.38963684, + 0.90019733 -0.054834917 0.43201613, + 0.89920813 -0.074815311 0.43107706, + 0.88079321 -0.080967821 0.4665271, + 0.88116831 -0.072157919 0.46726418, + 0.86631012 -0.076233305 0.49365506, + 0.8663131 -0.075489506 0.49376407, + 0.89742732 -0.066672921 0.43609515, + 0.897726 -0.081606798 0.43292999, + 0.92047256 -0.072391666 0.38404381, + 0.92078578 -0.095140375 0.37828791, + 0.90175903 -0.105426 0.41918501, + 0.90111578 -0.071623184 0.4276219, + 0.87547511 -0.079830505 0.47662407, + 0.87502289 -0.064569093 0.47975594, + 0.84019285 -0.072332993 0.53744197, + 0.84019583 -0.073148683 0.53732687, + 0.85668886 -0.069580793 0.51111895, + 0.85634357 -0.078910865 0.51034176, + 0.87654257 -0.073549964 0.47567177, + 0.87742513 -0.054645706 0.47659105, + 0.89896375 -0.049896687 0.4351719, + 0.89970469 -0.024591891 0.43580586, + 0.89265591 -0.0078721894 0.45066994, + 0.89267814 -0.0035076004 0.45068106, + 0.892515 -0.0035076099 0.451004, + 0.89249361 -0.0077305362 0.45099381, + 0.89248288 -0.0077312589 0.45101494, + 0.87670678 -0.024100395 0.48042089, + 0.87599885 -0.049591593 0.47975695, + 0.85223091 -0.053792093 0.52039295, + 0.85147715 -0.071269505 0.51952606, + 0.82924885 -0.075956687 0.55369389, + 0.8295489 -0.066311896 0.55448294, + 0.81188989 -0.069325194 0.57967997, + 0.81187916 -0.068381518 0.5798071, + 0.84984815 -0.061728913 0.52340013, + 0.85045803 -0.077255897 0.52033901, + 0.87926722 -0.069954813 0.47116411, + 0.88030571 -0.10585696 0.46244583, + 0.90341645 -0.095672742 0.41795376, + 0.90358609 -0.11334702 0.41314006, + 0.88249475 -0.12443697 0.45356187, + 0.88208932 -0.096300036 0.46113417, + 0.85613841 -0.10563505 0.50583422, + 0.85465872 -0.06753698 0.51477879, + 0.8231051 -0.073871911 0.56306404, + 0.82234544 -0.058229428 0.5660013, + 0.78116715 -0.063892111 0.6210441, + 0.7811861 -0.064868905 0.62091905, + 0.8002038 -0.062315885 0.59648186, + 0.79996049 -0.072129458 0.59570163, + 0.82376814 -0.068147607 0.56281608, + 0.82439119 -0.052138012 0.56361413, + 0.8505441 -0.048442706 0.52366805, + 0.85119259 -0.023191189 0.52434075, + 0.84404629 -0.0078907628 0.53621221, + 0.84406716 -0.003637451 0.53622514, + 0.84429199 -0.00363742 0.53587103, + 0.84426987 -0.0080379592 0.53585792, + 0.84383011 -0.0080565009 0.53655005, + 0.84385228 -0.0035142512 0.53656417, + 0.81689441 0.010297605 0.57669532, + 0.81690598 -0.00884654 0.57670301, + 0.81685019 -0.0088484315 0.57678211, + 0.78731364 -0.022865189 0.61612868, + 0.78751481 -0.003482349 0.61628586, + 0.78762901 -0.0034823399 0.61614001, + 0.78759891 -0.009433249 0.61611593, + 0.7875213 -0.0094353436 0.61621523, + 0.7875517 -0.0034635989 0.61623877, + 0.75637269 0.0076799071 0.65409577, + 0.75636017 -0.0096570514 0.65408421, + 0.75571513 -0.0096706413 0.65482908, + 0.7233268 -0.015676897 0.69032782, + 0.72341192 -0.0030529096 0.69040996, + 0.72354478 -0.0030528789 0.69027078, + 0.72351193 -0.010041399 0.69023895, + 0.72635603 -0.0099944398 0.68724602, + 0.68917018 -0.012361903 0.72449416, + 0.68893015 -0.034584809 0.72400218, + 0.65334606 -0.036122702 0.75619709, + 0.65321201 -0.044994 0.75583702, + 0.62098628 -0.046577424 0.78243637, + 0.62098402 -0.044712 0.782547, + 0.67428696 -0.042124797 0.73726696, + 0.67454857 -0.048589669 0.73662961, + 0.72447222 -0.045369416 0.68780923, + 0.72559333 -0.061028231 0.68541229, + 0.7660079 -0.057011392 0.64029795, + 0.7688455 -0.10027794 0.63152266, + 0.8027398 -0.093517974 0.58895087, + 0.80413628 -0.12738304 0.5806362, + 0.83485156 -0.11796094 0.53768778, + 0.8354798 -0.14940196 0.52882189, + 0.863298 -0.137214 0.48568401, + 0.86336589 -0.15865599 0.47898594, + 0.84035385 -0.17043495 0.51454586, + 0.84026015 -0.18553601 0.50945008, + 0.81536841 -0.19811486 0.5439896, + 0.81514484 -0.21518296 0.53780586, + 0.78793103 -0.228744 0.57169998, + 0.78751087 -0.24814297 0.56413794, + 0.75781167 -0.26270789 0.59724867, + 0.75716287 -0.28336698 0.58856392, + 0.72525108 -0.29866204 0.62033206, + 0.72428322 -0.32161212 0.60990125, + 0.69020134 -0.33752516 0.64007729, + 0.68885392 -0.36236197 0.62783295, + 0.65203792 -0.37900093 0.65666193, + 0.65029579 -0.40506691 0.6426788, + 0.61057806 -0.42227605 0.66998309, + 0.60837597 -0.44991595 0.65379995, + 0.56635606 -0.46721306 0.67893505, + 0.56369841 -0.49597237 0.66049647, + 0.51968122 -0.51301324 0.68319029, + 0.51657116 -0.54270118 0.66229123, + 0.46976006 -0.55952907 0.68282706, + 0.46628407 -0.58963805 0.65947407, + 0.41718191 -0.60575986 0.67750585, + 0.41342899 -0.63602602 0.651573, + 0.3627378 -0.65094256 0.66685456, + 0.35883904 -0.68102205 0.63831306, + 0.30710185 -0.69435763 0.65081167, + 0.30323493 -0.72377282 0.61983991, + 0.25011709 -0.73539323 0.62979221, + 0.24649097 -0.76385087 0.59646791, + 0.19250791 -0.77342767 0.60394567, + 0.18934388 -0.80064553 0.56843263, + 0.13572499 -0.80784988 0.57354796, + 0.133238 -0.833408 0.53635699, + 0.08010719 -0.83820289 0.53944296, + 0.07847099 -0.86223388 0.50039494, + 0.026070099 -0.86460698 0.50177199, + 0.02548369 -0.8868897 0.46127781, + -0.026053894 -0.88687676 0.46127087, + -0.026645696 -0.86457491 0.50179696, + -0.079068206 -0.86217409 0.50040406, + -0.08070571 -0.83816409 0.53941405, + -0.13381396 -0.8333447 0.53631181, + -0.13629995 -0.80780572 0.57347381, + -0.18987295 -0.80058181 0.5683459, + -0.19303608 -0.77338231 0.60383523, + -0.24698897 -0.76378685 0.59634393, + -0.25063193 -0.73517883 0.62983781, + -0.30351382 -0.72359359 0.61991262, + -0.30738711 -0.69401622 0.65104121, + -0.35931218 -0.68062031 0.6384753, + -0.36315182 -0.65096968 0.66660273, + -0.41377223 -0.63605338 0.65132844, + -0.41752407 -0.60582703 0.67723507, + -0.46678388 -0.58962989 0.65912783, + -0.47029006 -0.55930704 0.68264407, + -0.51685804 -0.54254907 0.66219205, + -0.51994193 -0.51312095 0.68291092, + -0.56409085 -0.49600783 0.66013473, + -0.56673533 -0.46752122 0.6784063, + -0.60871506 -0.45020807 0.65328306, + -0.6109491 -0.42230409 0.66962719, + -0.65045458 -0.40516776 0.64245462, + -0.65220106 -0.37911505 0.65643406, + -0.68913424 -0.36240512 0.62750024, + -0.69047594 -0.33785897 0.63960493, + -0.72451818 -0.32193208 0.60945314, + -0.72549605 -0.29905102 0.61985809, + -0.75726402 -0.28379199 0.588229, + -0.75792712 -0.26294902 0.59699607, + -0.78760731 -0.24837309 0.5639022, + -0.78802919 -0.22929706 0.57134312, + -0.81521517 -0.21571004 0.5374881, + -0.81545013 -0.19853503 0.54371405, + -0.84032768 -0.18592994 0.50919485, + -0.8404277 -0.17079794 0.51430482, + -0.86336088 -0.15902999 0.47887093, + -0.86330312 -0.13775001 0.48552305, + -0.72613376 -0.018309293 0.68730974, + -0.72570193 -0.043592397 0.68662691, + -0.69182056 -0.045750473 0.72061861, + -0.6918118 -0.046191789 0.72059882, + -0.66060394 -0.048024993 0.74919695, + -0.66060019 -0.049908113 0.7490772, + -0.71212882 -0.04667129 0.70049584, + -0.71238303 -0.053846508 0.69972205, + -0.75983202 -0.049881998 0.64820302, + -0.76037449 -0.057862435 0.64690238, + -0.79504561 -0.054037273 0.60413772, + -0.79665327 -0.080013633 0.59911722, + -0.82822216 -0.074184217 0.55546814, + -0.82961857 -0.10618295 0.54814076, + -0.85817212 -0.097630814 0.50399303, + -0.85883415 -0.12695302 0.49627307, + -0.88437998 -0.11568 0.45220599, + -0.88450873 -0.13490096 0.44659385, + -0.8612234 -0.14696008 0.48651522, + -0.86089784 -0.11747497 0.49502987, + -0.83278471 -0.12782395 0.53863782, + -0.83179456 -0.096558154 0.54662079, + -0.80065298 -0.10422 0.58999401, + -0.79887933 -0.070670925 0.59732527, + -0.76458764 -0.075726464 0.64005572, + -0.76275885 -0.049628191 0.64477593, + -0.72517401 -0.0528423 0.686535, + -0.72461522 -0.045346215 0.68766022, + -0.67455125 -0.048575319 0.73662823, + -0.67427403 -0.041752499 0.73729998, + -0.62098813 -0.044315811 0.78256619, + -0.62098402 -0.0425032 0.78267002, + -0.65346825 -0.041046117 0.7558403, + -0.65346497 -0.0412689 0.755831, + -0.68883294 -0.039522298 0.72384197, + -0.68915522 -0.015995605 0.72443724, + -0.68936819 -0.016100904 0.7242322, + -0.68945599 -0.00227774 0.72432399, + -0.69003677 -0.0022777994 0.72377074, + -0.68996292 -0.014774898 0.72369397, + -0.72434545 -0.014610209 0.68928242, + -0.72441059 0.0057752067 0.68934458, + -0.75888389 -0.0034265495 0.65121692, + -0.75881183 -0.014214696 0.65115482, + -0.75724238 -0.014258207 0.6529783, + -0.76060712 -0.016048701 0.64901406, + -0.76003689 -0.046781197 0.64819396, + -0.72826105 -0.049330909 0.68352205, + -0.72821933 -0.051009625 0.68344331, + -0.69858575 -0.05325608 0.71354175, + -0.69856793 -0.055541992 0.71338493, + -0.74770999 -0.051543001 0.66202199, + -0.74793118 -0.059065115 0.66114318, + -0.79238689 -0.054281592 0.60759896, + -0.79287112 -0.062304508 0.60619605, + -0.82482517 -0.057805713 0.56242514, + -0.82618761 -0.083554961 0.55716479, + -0.85514939 -0.076879337 0.51264924, + -0.85618269 -0.10726596 0.5054158, + -0.88213629 -0.09778294 0.46073219, + -0.88250357 -0.12512794 0.45335481, + -0.90535289 -0.11298399 0.40935394, + -0.90532643 -0.13068706 0.40411019, + -0.88646877 -0.14240196 0.44033489, + -0.8863669 -0.15359598 0.43676293, + -0.86547661 -0.16619092 0.47257876, + -0.8652932 -0.17932504 0.46809211, + -0.8425703 -0.19267708 0.5029422, + -0.84226298 -0.207782 0.49741301, + -0.81754953 -0.22196287 0.5313617, + -0.81706309 -0.23915803 0.52460605, + -0.79008085 -0.25427994 0.55777586, + -0.78936785 -0.27320996 0.54977691, + -0.75985312 -0.28930804 0.58217204, + -0.758856 -0.30999199 0.57274997, + -0.72707105 -0.32679603 0.60379803, + -0.72571898 -0.349388 0.59267199, + -0.69168699 -0.366759 0.62213898, + -0.68989623 -0.39138415 0.60898423, + -0.65320998 -0.40937099 0.636971, + -0.65097082 -0.43530592 0.62188888, + -0.61134988 -0.45380387 0.64831585, + -0.6086663 -0.48066324 0.63125932, + -0.56666487 -0.49915388 0.65554285, + -0.56351489 -0.52701187 0.63616782, + -0.5192709 -0.54519588 0.65811783, + -0.5156132 -0.57427716 0.63588423, + -0.46910781 -0.59191775 0.65541679, + -0.46508089 -0.62124187 0.6306808, + -0.41610208 -0.63811916 0.64781415, + -0.41191593 -0.66678792 0.62106293, + -0.36139488 -0.68229479 0.63550574, + -0.35701013 -0.71126223 0.60551625, + -0.30549002 -0.72504008 0.61724603, + -0.30123103 -0.75293714 0.58510303, + -0.24854809 -0.7648353 0.59434927, + -0.24459302 -0.79161614 0.55992705, + -0.19112803 -0.80136311 0.56682205, + -0.18773399 -0.82657999 0.530586, + -0.13471901 -0.83387113 0.53526604, + -0.13203898 -0.85764891 0.49699494, + -0.079620734 -0.86247742 0.49979323, + -0.077875011 -0.8845681 0.45986405, + -0.026209185 -0.88695747 0.46110672, + -0.025590805 -0.90717024 0.41998509, + 0.025184792 -0.90717971 0.41998884, + 0.02580969 -0.88705969 0.46093282, + 0.077412516 -0.88469225 0.45970312, + 0.079169497 -0.86261702 0.49962401, + 0.13163097 -0.85780382 0.49683589, + 0.13432203 -0.83403915 0.5351041, + 0.187343 -0.826765 0.53043598, + 0.19075502 -0.8015241 0.56672007, + 0.24401493 -0.79183483 0.55986989, + 0.24799988 -0.76486665 0.59453768, + 0.30051988 -0.75303572 0.58534175, + 0.30480096 -0.72491896 0.61772895, + 0.356419 -0.71114999 0.60599601, + 0.36073998 -0.68254894 0.63560492, + 0.41152185 -0.66698474 0.62111276, + 0.41574299 -0.63807702 0.64808601, + 0.46476528 -0.62120533 0.63094938, + 0.46876481 -0.59207773 0.65551776, + 0.51531017 -0.57443619 0.63598621, + 0.51897299 -0.545331 0.65824097, + 0.56325519 -0.52714419 0.63628823, + 0.5664081 -0.49927813 0.65567017, + 0.60842925 -0.48079017 0.63139123, + 0.61113638 -0.45367926 0.64860433, + 0.65080118 -0.43517908 0.62215513, + 0.65303499 -0.40924099 0.63723397, + 0.68961805 -0.39132506 0.60933703, + 0.69140118 -0.3666971 0.62249315, + 0.72558993 -0.34926596 0.59290195, + 0.72693837 -0.32666215 0.60403031, + 0.75874603 -0.30986199 0.57296598, + 0.75975132 -0.28887209 0.5825212, + 0.78918916 -0.27285007 0.55021214, + 0.78989518 -0.25382006 0.5582481, + 0.81699514 -0.23867203 0.52493304, + 0.81747359 -0.2214009 0.53171277, + 0.84220582 -0.20725195 0.49773088, + 0.84250218 -0.19226204 0.50321513, + 0.86523813 -0.17893802 0.46834207, + 0.86541659 -0.16559793 0.47289675, + 0.8863216 -0.15304393 0.43704879, + 0.88641632 -0.14178905 0.44063815, + 0.90523303 -0.13015801 0.40448999, + 0.90527922 -0.12081303 0.40727609, + 0.92376202 -0.108911 0.367154, + 0.92362386 -0.12508999 0.36231396, + 0.90686899 -0.137528 0.39833999, + 0.90672475 -0.14667097 0.3953959, + 0.88806725 -0.15988305 0.4310151, + 0.88783169 -0.17152295 0.42700684, + 0.86718315 -0.18562101 0.46210206, + 0.8668412 -0.19862305 0.45731312, + 0.84426701 -0.213497 0.491561, + 0.84374511 -0.22897303 0.48545405, + 0.81922072 -0.24464391 0.51867783, + 0.8184849 -0.26180598 0.51140994, + 0.79155189 -0.27847198 0.54396594, + 0.79054928 -0.29730511 0.53538918, + 0.76112098 -0.31488499 0.567047, + 0.75976169 -0.33582488 0.5567618, + 0.72812116 -0.3540301 0.58694309, + 0.72635299 -0.37670699 0.57489401, + 0.69215655 -0.39557475 0.60368866, + 0.68995464 -0.41958779 0.58983773, + 0.6532793 -0.43887022 0.6169433, + 0.65057892 -0.46431994 0.60096097, + 0.61089295 -0.48405194 0.62650096, + 0.60769302 -0.51055902 0.60830802, + 0.56576306 -0.53010005 0.63159007, + 0.56203002 -0.55771798 0.61079699, + 0.51766795 -0.57691193 0.63181692, + 0.51351303 -0.604864 0.60864103, + 0.46701187 -0.62331086 0.62720281, + 0.46250299 -0.65138 0.60149401, + 0.41373992 -0.66884881 0.61762488, + 0.40899515 -0.69674623 0.58929425, + 0.35854891 -0.71276081 0.60283887, + 0.35373709 -0.74016017 0.57186812, + 0.30234501 -0.75428802 0.582784, + 0.29769894 -0.78064281 0.5495199, + 0.24541391 -0.79271072 0.55801582, + 0.24117206 -0.81761616 0.5228191, + 0.18842892 -0.8273927 0.52907079, + 0.18476404 -0.8509292 0.49171311, + 0.13239494 -0.85821456 0.49592277, + 0.12953505 -0.88011628 0.45674515, + 0.077827834 -0.88490242 0.45922822, + 0.075993329 -0.90491527 0.41875216, + 0.025329409 -0.90724832 0.41983214, + 0.02467919 -0.92532957 0.37835982, + -0.025164811 -0.92531842 0.37835518, + -0.025822194 -0.90728074 0.41973191, + -0.076507092 -0.9049229 0.41864195, + -0.07835722 -0.88481122 0.45931411, + -0.13008197 -0.87999874 0.45681587, + -0.13293999 -0.85813302 0.49591801, + -0.1853559 -0.85081446 0.4916887, + -0.18901409 -0.8273204 0.52897525, + -0.24191006 -0.81748319 0.52268612, + -0.24615903 -0.79259712 0.55784905, + -0.29820493 -0.78055382 0.5493719, + -0.3028731 -0.75406432 0.5827992, + -0.35421208 -0.73992819 0.57187414, + -0.35898313 -0.71275425 0.60258824, + -0.40940079 -0.69672567 0.5890367, + -0.41416979 -0.66868269 0.6175167, + -0.46288395 -0.65121192 0.60138291, + -0.46735594 -0.62337595 0.62688196, + -0.5139578 -0.60486376 0.60826576, + -0.51812118 -0.57691419 0.63144326, + -0.56227314 -0.55778813 0.6105091, + -0.56603289 -0.52998388 0.63144583, + -0.60792422 -0.51044816 0.60817021, + -0.61112523 -0.48392418 0.62637323, + -0.65076131 -0.46420622 0.6008513, + -0.65344024 -0.43898916 0.61668825, + -0.69022208 -0.41963106 0.58949405, + -0.69242978 -0.39563486 0.60333574, + -0.72647184 -0.37683192 0.57466191, + -0.72824508 -0.35415003 0.58671707, + -0.75986987 -0.33593798 0.55654591, + -0.7612322 -0.3150281 0.56681812, + -0.79064029 -0.29744312 0.53517818, + -0.79164517 -0.27864406 0.54374212, + -0.81855673 -0.26197192 0.51120985, + -0.81928581 -0.24513994 0.51834089, + -0.84379309 -0.22944203 0.48514906, + -0.84432232 -0.21404608 0.49122718, + -0.86688513 -0.19913504 0.45700705, + -0.86723697 -0.18602601 0.46183801, + -0.88787425 -0.17189905 0.42676708, + -0.88811272 -0.16043894 0.43071485, + -0.90671331 -0.14721707 0.39521915, + -0.9068681 -0.13760002 0.39831707, + -0.92358464 -0.12518595 0.36238089, + -0.92611635 -0.13913804 0.35064113, + -0.92616463 -0.13885696 0.35062489, + -0.90820611 -0.15410201 0.38912007, + -0.90794373 -0.16374195 0.38578084, + -0.88952345 -0.17850909 0.42057422, + -0.88915455 -0.18972892 0.4164218, + -0.86867356 -0.2053919 0.45079979, + -0.86812615 -0.21905206 0.44539112, + -0.84575987 -0.23547897 0.47878993, + -0.84503829 -0.25030008 0.47250417, + -0.82060987 -0.26751897 0.50500792, + -0.81961697 -0.28448501 0.497289, + -0.79281729 -0.30263311 0.5290122, + -0.79148614 -0.32164302 0.51970708, + -0.76213586 -0.34070998 0.55051392, + -0.76040918 -0.36150408 0.5395301, + -0.72878933 -0.38115019 0.56885028, + -0.72661865 -0.40348983 0.55607677, + -0.69263303 -0.42360407 0.58379704, + -0.68999106 -0.44716907 0.56916803, + -0.65321332 -0.46777621 0.59539729, + -0.65000683 -0.49289888 0.5783959, + -0.61047322 -0.51372516 0.60283422, + -0.60669905 -0.53998303 0.58338207, + -0.56474012 -0.56059015 0.60564613, + -0.56051594 -0.58711797 0.58404994, + -0.51625806 -0.60717404 0.60400105, + -0.51158184 -0.63411176 0.5798158, + -0.465202 -0.65327698 0.597341, + -0.46018595 -0.68018496 0.57059395, + -0.4113839 -0.69829583 0.58578688, + -0.40613601 -0.72503 0.55622399, + -0.35623398 -0.74136192 0.56875294, + -0.35099912 -0.7671833 0.53687018, + -0.29985902 -0.78160912 0.54696608, + -0.29488105 -0.80613816 0.51301712, + -0.243314 -0.81829798 0.52075601, + -0.23872396 -0.84163588 0.48441693, + -0.18659295 -0.8514728 0.49007887, + -0.18267898 -0.87315589 0.45191494, + -0.13099298 -0.88044786 0.45568895, + -0.12795705 -0.90040028 0.41582015, + -0.077034682 -0.90516573 0.41801992, + -0.075110413 -0.92305821 0.3772561, + -0.02529919 -0.92537659 0.37820381, + -0.024612796 -0.94147891 0.33617198, + 0.024296204 -0.94148612 0.33617502, + 0.024984896 -0.92546189 0.37801594, + 0.074761398 -0.92316002 0.377076, + 0.076696388 -0.90523875 0.4179239, + 0.12741295 -0.90051359 0.4157418, + 0.13044493 -0.88056445 0.45562074, + 0.18211696 -0.87330085 0.45186189, + 0.18603306 -0.85160428 0.49006319, + 0.23818401 -0.84179002 0.48441499, + 0.24275997 -0.81853688 0.52063894, + 0.29451197 -0.80635387 0.51288992, + 0.29951003 -0.78179812 0.54688704, + 0.35047299 -0.76744199 0.53684402, + 0.35572389 -0.74156779 0.56880385, + 0.40569505 -0.72523606 0.55627704, + 0.41098022 -0.69831842 0.58604336, + 0.45967117 -0.68027526 0.57090116, + 0.46468607 -0.65332305 0.59769207, + 0.51128113 -0.63409418 0.58010012, + 0.51593304 -0.60729206 0.60416007, + 0.56022006 -0.58723909 0.58421206, + 0.56447786 -0.56049585 0.60597789, + 0.60634738 -0.53995627 0.58377236, + 0.61011612 -0.51366913 0.60324311, + 0.64984083 -0.49276689 0.57869488, + 0.65301603 -0.46786207 0.59554607, + 0.68981606 -0.44725305 0.56931406, + 0.69245696 -0.42370194 0.58393496, + 0.72646827 -0.40358216 0.55620617, + 0.72866023 -0.38099715 0.5691182, + 0.76030183 -0.36135691 0.5397799, + 0.76202285 -0.34057796 0.55075192, + 0.79139501 -0.32151499 0.519925, + 0.79272413 -0.30247703 0.52924109, + 0.81954068 -0.28433591 0.49749982, + 0.8205319 -0.26731998 0.50523996, + 0.84497631 -0.2501111 0.47271517, + 0.84570682 -0.23497394 0.47913188, + 0.86815387 -0.21852697 0.44559494, + 0.86868715 -0.20505905 0.45092511, + 0.88911772 -0.18945992 0.41662285, + 0.88948476 -0.17812896 0.4208169, + 0.9079603 -0.16335206 0.38590714, + 0.90822172 -0.15357694 0.38929084, + 0.92613935 -0.13841805 0.35086513, + 0.92568791 -0.15437798 0.34535396, + 0.90932488 -0.16980298 0.37986195, + 0.90895498 -0.179544 0.37625101, + 0.8906737 -0.19580093 0.41031986, + 0.89015412 -0.20738003 0.40573305, + 0.86984688 -0.22451997 0.43926895, + 0.86913091 -0.23794398 0.43358293, + 0.84684098 -0.25587201 0.46625099, + 0.84587848 -0.27110514 0.45933828, + 0.82155418 -0.28978705 0.49099112, + 0.82026982 -0.30699995 0.48260587, + 0.79353988 -0.32661298 0.51343793, + 0.7918852 -0.34550309 0.50353312, + 0.76253772 -0.36602589 0.5334428, + 0.76045591 -0.38647595 0.52186495, + 0.72865701 -0.40759701 0.550385, + 0.72608984 -0.42953691 0.53692788, + 0.69208497 -0.45091194 0.56364596, + 0.68894696 -0.47443295 0.54796493, + 0.65224123 -0.49616417 0.57306421, + 0.64852083 -0.52086186 0.55508888, + 0.60871369 -0.54289079 0.5785647, + 0.60446614 -0.5681991 0.55836409, + 0.56249779 -0.58971673 0.57950884, + 0.55772203 -0.61557108 0.55679303, + 0.51362079 -0.63632876 0.5755688, + 0.5083791 -0.66243619 0.55020809, + 0.46200711 -0.68223917 0.56665611, + 0.456397 -0.708314 0.53851002, + 0.40785599 -0.72683799 0.55259401, + 0.40215084 -0.75204068 0.52221584, + 0.35238409 -0.76870018 0.53378409, + 0.34675792 -0.79283082 0.50117689, + 0.29619604 -0.80734611 0.51035309, + 0.29078892 -0.83043271 0.47520882, + 0.23975311 -0.84262443 0.48218524, + 0.23485591 -0.86413068 0.44510785, + 0.183391 -0.873918 0.45015001, + 0.17923494 -0.89372271 0.41125986, + 0.12833002 -0.90092212 0.41457307, + 0.12516597 -0.91872978 0.37452492, + 0.075300604 -0.92338312 0.37642205, + 0.073286012 -0.93924421 0.33533508, + 0.024326297 -0.94149786 0.33613998, + 0.02363299 -0.95547962 0.29410887, + -0.023994191 -0.95547163 0.29410589, + -0.024698604 -0.94151211 0.33607304, + -0.073558293 -0.93924791 0.33526498, + -0.075584091 -0.92325389 0.37668195, + -0.125549 -0.918576 0.37477401, + -0.12870698 -0.90073478 0.4148629, + -0.17964196 -0.89351374 0.41153592, + -0.18378694 -0.8736937 0.45042384, + -0.235275 -0.86388302 0.44536701, + -0.24015303 -0.84239614 0.48238507, + -0.29133603 -0.8301481 0.47537106, + -0.29670405 -0.80721319 0.51026809, + -0.34723991 -0.79267985 0.50108188, + -0.3528901 -0.76842916 0.53384012, + -0.40261105 -0.75176311 0.52226108, + -0.40829515 -0.72663224 0.55254018, + -0.45682916 -0.70808923 0.53843915, + -0.4624238 -0.68206769 0.56652272, + -0.50872803 -0.66227299 0.55008203, + -0.5139308 -0.63635778 0.5752598, + -0.55813193 -0.61552793 0.55642992, + -0.56290698 -0.58972299 0.57910502, + -0.60482389 -0.56820285 0.55797291, + -0.60907429 -0.54293323 0.57814533, + -0.64869076 -0.52098584 0.55477381, + -0.65241373 -0.49631077 0.57274067, + -0.68921691 -0.47449794 0.54756892, + -0.69236016 -0.45099813 0.5632391, + -0.72632283 -0.42962292 0.53654391, + -0.72889775 -0.40767986 0.55000484, + -0.76055562 -0.38662982 0.52160579, + -0.7626431 -0.36617902 0.53318703, + -0.79196972 -0.34565189 0.50329781, + -0.79363 -0.326749 0.51321203, + -0.82034141 -0.30713215 0.48240024, + -0.82162851 -0.28994283 0.49077469, + -0.84594142 -0.27125111 0.45913622, + -0.8469041 -0.25608003 0.46602207, + -0.8691178 -0.23819394 0.43347192, + -0.8698231 -0.22507703 0.43903106, + -0.89017999 -0.207853 0.40543401, + -0.8907131 -0.19610703 0.41008806, + -0.90898371 -0.17982794 0.37604585, + -0.90934676 -0.17040096 0.3795419, + -0.92570078 -0.15492597 0.34507391, + -0.92783666 -0.16758195 0.33321989, + -0.94093966 -0.15212095 0.30247587, + -0.94171649 -0.13153906 0.30962515, + -0.953565 -0.117767 0.27720901, + -0.95398378 -0.10151998 0.28214994, + -0.96449077 -0.08941938 0.24851894, + -0.96472102 -0.076089799 0.25203899, + -0.97391075 -0.065586284 0.21724695, + -0.97388476 -0.067058586 0.21691395, + -0.9808799 -0.057480693 0.18593198, + -0.98067427 -0.063631214 0.18501104, + -0.98707438 -0.052122917 0.15155005, + -0.98708397 -0.051894601 0.151566, + -0.99310154 -0.037982982 0.11093495, + -0.99342161 -0.02727019 0.11121996, + -0.99760789 -0.016461598 0.067137696, + -0.99769449 -0.0093315346 0.067220829, + -0.99974847 -0.0030840114 0.022216011, + -0.99975276 -0.00051836291 0.022230195, + -0.99999577 6.7550784e-005 -0.0028969394, + -0.99999577 0 -0.0028969394, + -0.99969864 0 0.024546791, + -0.99970233 -8.0068232e-005 0.02439801, + -0.99854833 0.015867706 0.05147332, + -0.99854773 0.015906896 -0.05147329, + -0.99705613 0.00052931008 -0.076674409, + -0.99688148 0.01872031 -0.076661035, + -0.99688178 0.018720197 -0.076656185, + -0.99185878 -0.021891195 -0.12544698, + -0.99209636 -0.00047609617 -0.12547804, + -0.99209088 -0.00047609294 -0.12552099, + -0.99182266 0.023256892 -0.12548696, + -0.99182826 0.023255605 -0.12544303, + -0.9872185 -0.013064793 -0.15883593, + -0.98696536 0.027446309 -0.15857506, + -0.99346536 0.019465007 -0.11246204, + -0.99303514 0.035838805 -0.11223602, + -0.99757123 0.021187905 -0.066353716, + -0.99734825 0.030399807 -0.066124812, + -0.99972165 0.0098554567 -0.021437293, + -0.99971563 0.010494497 -0.021411393, + -0.99972564 -0.010308396 0.021031793, + -0.99972862 -0.0099722063 0.021052293, + -0.99782389 -0.028226396 0.059588693, + -0.99786925 -0.025764206 0.059943914, + -0.99471349 -0.040549617 0.094344348, + -0.99473065 -0.039644986 0.094546862, + -0.99009275 -0.054297891 0.12949197, + -0.98994547 -0.060480531 0.12786806, + -0.98394465 -0.076311067 0.16133694, + -0.98368722 -0.084233724 0.15894705, + -0.97643709 -0.10105102 0.19068103, + -0.97593534 -0.11268104 0.18669006, + -0.96738887 -0.13088898 0.21685697, + -0.96655548 -0.14546508 0.2112121, + -0.95658773 -0.16530995 0.24002594, + -0.95525026 -0.18319304 0.23224406, + -0.94374824 -0.20478605 0.25961906, + -0.94242364 -0.21907192 0.25267592, + -0.92815566 -0.24381492 0.28121391, + -0.92715925 -0.25275907 0.27656606, + -0.91109061 -0.27808288 0.30427584, + -0.90974772 -0.28860191 0.29844287, + -0.8916229 -0.31475198 0.32548398, + -0.88985676 -0.3268629 0.3183009, + -0.86942184 -0.35396591 0.3446939, + -0.86711329 -0.36785311 0.33585513, + -0.84463698 -0.39534599 0.360957, + -0.84175819 -0.4105911 0.3505111, + -0.81701201 -0.43855399 0.37438199, + -0.81353682 -0.45483887 0.36232492, + -0.78614187 -0.48341393 0.38508695, + -0.78186184 -0.50122088 0.3707689, + -0.75176209 -0.53014904 0.39216805, + -0.74673384 -0.5487709 0.37581792, + -0.71421999 -0.57748199 0.39548001, + -0.7083382 -0.59695214 0.37670308, + -0.67352092 -0.62510991 0.39447093, + -0.66691202 -0.64474398 0.37354201, + -0.62948406 -0.67232609 0.38952205, + -0.62212205 -0.69203907 0.36612302, + -0.58205801 -0.71875697 0.38025901, + -0.57399893 -0.73827595 0.35422298, + -0.53222471 -0.76329255 0.36622578, + -0.52366012 -0.78211319 0.3377561, + -0.48029682 -0.80522871 0.34773788, + -0.47143295 -0.82297087 0.31696996, + -0.42667592 -0.84396982 0.32505792, + -0.4177618 -0.86028558 0.29220486, + -0.37177783 -0.8790006 0.29856184, + -0.36304504 -0.89368612 0.26367304, + -0.31691602 -0.90968615 0.26839402, + -0.30871388 -0.92239863 0.23211291, + -0.26285398 -0.93566591 0.23545097, + -0.25538093 -0.94638377 0.19783396, + -0.20984395 -0.95704776 0.20006296, + -0.20453303 -0.96428114 0.16831002, + -0.15941101 -0.97250915 0.16974701, + -0.15609807 -0.97708946 0.14467107, + -0.11257097 -0.98292774 0.14553598, + -0.10955297 -0.98748875 0.11341997, + -0.066449374 -0.99127263 0.11385496, + -0.064503774 -0.99476862 0.079212271, + -0.021867506 -0.99660623 0.079358622, + -0.0211966 -0.99881101 0.043900099, + 0.020883892 -0.99881762 0.043900285, + 0.021542188 -0.99661338 0.079357453, + 0.064139716 -0.99479222 0.079212524, + 0.06608662 -0.99129736 0.11385104, + 0.10922702 -0.98752511 0.11341801, + 0.11225501 -0.9829331 0.14574401, + 0.15586691 -0.97709543 0.14487891, + 0.15920793 -0.97245854 0.17022693, + 0.20442307 -0.96422136 0.16878507, + 0.20966797 -0.95705485 0.20021297, + 0.25518292 -0.94640565 0.19798492, + 0.26257005 -0.93580526 0.23521405, + 0.30850798 -0.9225269 0.23187697, + 0.31664899 -0.90993798 0.26785499, + 0.36268404 -0.89398414 0.26315904, + 0.3714121 -0.87935126 0.29798406, + 0.41730493 -0.86069191 0.29166096, + 0.42620701 -0.84443903 0.32445401, + 0.47101077 -0.82343757 0.31638485, + 0.47990417 -0.8056953 0.34719911, + 0.52315998 -0.78265703 0.337271, + 0.53172493 -0.7638889 0.36570796, + 0.573587 -0.73883897 0.35371599, + 0.58174992 -0.71912694 0.38003093, + 0.62175798 -0.69246298 0.36594, + 0.62916708 -0.67265403 0.38946807, + 0.66660219 -0.64508516 0.3735061, + 0.67325592 -0.62533593 0.39456493, + 0.70812404 -0.59715503 0.37678406, + 0.71398991 -0.57774997 0.39550394, + 0.74652499 -0.54903501 0.37584701, + 0.75160718 -0.53022212 0.39236608, + 0.78173584 -0.50128287 0.37095091, + 0.78603011 -0.48340607 0.38532507, + 0.81344861 -0.45482379 0.36254182, + 0.81692368 -0.43852887 0.37460387, + 0.84168983 -0.41055992 0.35071191, + 0.84460187 -0.39511493 0.36129197, + 0.86709273 -0.36762589 0.33615687, + 0.86937088 -0.35389397 0.34489596, + 0.88982344 -0.32678416 0.31847516, + 0.89158624 -0.31468308 0.32565108, + 0.90975541 -0.28848115 0.29853615, + 0.91109622 -0.27796805 0.30436406, + 0.92716509 -0.25265202 0.27664402, + 0.92817461 -0.24357791 0.2813569, + 0.94242066 -0.21889192 0.2528429, + 0.94374686 -0.20453598 0.25982097, + 0.94379061 -0.20461193 0.25960192, + 0.92841202 -0.22999699 0.29180899, + 0.92753577 -0.23887993 0.28742594, + 0.91152424 -0.26285705 0.31627509, + 0.9103353 -0.27336809 0.31074011, + 0.89225912 -0.29823804 0.33901003, + 0.89070398 -0.31026599 0.33223701, + 0.87044513 -0.33598503 0.35977703, + 0.8683998 -0.3498449 0.35141191, + 0.84604341 -0.37612519 0.37781018, + 0.84350181 -0.39127892 0.36797491, + 0.81884414 -0.41815206 0.39324707, + 0.8156687 -0.43487886 0.38152984, + 0.78852791 -0.46230093 0.40558794, + 0.78469849 -0.48018131 0.39201325, + 0.75473416 -0.50818712 0.4148761, + 0.75013787 -0.52728093 0.39908394, + 0.71787292 -0.55510294 0.42014194, + 0.71245307 -0.57521105 0.40192407, + 0.67777395 -0.60271293 0.42114094, + 0.67163503 -0.62314504 0.40074506, + 0.63435704 -0.65019304 0.41813907, + 0.62748694 -0.67081195 0.39531195, + 0.58750379 -0.69716978 0.41084486, + 0.58000118 -0.71758223 0.38558316, + 0.53804904 -0.74250907 0.39897805, + 0.52993494 -0.7626279 0.37090096, + 0.48651493 -0.78567988 0.38211295, + 0.47812918 -0.80470431 0.35191411, + 0.43299007 -0.82587713 0.36117402, + 0.42447609 -0.84368515 0.32865709, + 0.37811586 -0.86261868 0.33603188, + 0.3697761 -0.87879926 0.30162507, + 0.32300192 -0.89514077 0.30723393, + 0.31507897 -0.90952986 0.27107298, + 0.26830903 -0.92320311 0.27514803, + 0.26115108 -0.93551636 0.23792709, + 0.21471104 -0.94654524 0.24073106, + 0.20846196 -0.95686978 0.20234595, + 0.162469 -0.96536499 0.204143, + 0.15825404 -0.97235721 0.17168905, + 0.11306195 -0.9784525 0.17276491, + 0.110635 -0.98295802 0.14681099, + 0.066920027 -0.98681247 0.14738707, + 0.065085106 -0.99129212 0.11447202, + 0.021884687 -0.99316043 0.11468793, + 0.021229891 -0.99660552 0.079541266, + -0.021558087 -0.99659842 0.079540752, + -0.022224594 -0.99315578 0.11466297, + -0.065497503 -0.99126798 0.114446, + -0.067346677 -0.98680967 0.14721094, + -0.11090299 -0.98295391 0.14663598, + -0.11333697 -0.97847164 0.17247593, + -0.15832901 -0.97239512 0.17140502, + -0.16255495 -0.96537077 0.20404695, + -0.20860793 -0.95685863 0.20224793, + -0.21492092 -0.94641763 0.24104491, + -0.26140106 -0.93536925 0.23823106, + -0.26858297 -0.9229849 0.27561197, + -0.31539008 -0.90928823 0.27152205, + -0.32332787 -0.8948307 0.30779389, + -0.37016109 -0.87845325 0.30216005, + -0.37849382 -0.86223257 0.33659685, + -0.4249801 -0.84322816 0.32917809, + -0.43348405 -0.82539815 0.36167604, + -0.47853893 -0.80424488 0.35240698, + -0.48691899 -0.78516901 0.38264799, + -0.53045112 -0.76203817 0.37137508, + -0.53847277 -0.74210465 0.39915884, + -0.58032101 -0.71722102 0.38577399, + -0.58781505 -0.69678408 0.41105404, + -0.62776417 -0.67043519 0.39551109, + -0.63459098 -0.64990097 0.41823801, + -0.67185432 -0.62285328 0.40083119, + -0.6779623 -0.60249031 0.4211562, + -0.71268582 -0.57494086 0.40189791, + -0.71805084 -0.5550279 0.41993693, + -0.75029635 -0.52720523 0.39888617, + -0.7548852 -0.50814313 0.41465509, + -0.78480399 -0.48016399 0.39182299, + -0.78862917 -0.46231312 0.40537709, + -0.8157568 -0.4348889 0.38132992, + -0.81892997 -0.41818601 0.39303201, + -0.8435064 -0.39138919 0.36784717, + -0.8460775 -0.37605876 0.37779975, + -0.86842358 -0.34978881 0.35140881, + -0.87044215 -0.3361091 0.35966808, + -0.89074343 -0.31032515 0.33207616, + -0.89228088 -0.29845697 0.33875996, + -0.91034877 -0.27357593 0.31051794, + -0.91152591 -0.26320297 0.31598198, + -0.92753214 -0.23920304 0.28716904, + -0.92905444 -0.2231441 0.29506716, + -0.91172075 -0.24779494 0.32766291, + -0.91067547 -0.25829485 0.32241881, + -0.89269531 -0.2817651 0.35171512, + -0.89131939 -0.29382914 0.34527418, + -0.87115717 -0.3182151 0.37393108, + -0.86938298 -0.33183101 0.366144, + -0.847175 -0.35679501 0.39368999, + -0.84490788 -0.37207997 0.38430095, + -0.82045114 -0.39768106 0.41074306, + -0.81762868 -0.41445684 0.39963585, + -0.79059786 -0.44079593 0.42503393, + -0.78717536 -0.45881122 0.4121252, + -0.75745183 -0.48571387 0.43628991, + -0.75332987 -0.50500995 0.42125893, + -0.72131783 -0.53185689 0.44365388, + -0.71642596 -0.55229396 0.42626894, + -0.68194598 -0.57900298 0.44688401, + -0.67629719 -0.60016811 0.4271071, + -0.63909876 -0.62664378 0.44594884, + -0.63282436 -0.64786834 0.42402825, + -0.59286809 -0.67381018 0.44100711, + -0.58596295 -0.69503796 0.41661695, + -0.54405802 -0.71966302 0.43137699, + -0.5365901 -0.74065715 0.40434909, + -0.49303883 -0.76362169 0.41688684, + -0.48513281 -0.78405273 0.38717884, + -0.43967584 -0.8053177 0.39767885, + -0.43167686 -0.82448667 0.36589187, + -0.38463894 -0.84371686 0.37442598, + -0.37671509 -0.86151218 0.34041509, + -0.32930192 -0.87815577 0.34699091, + -0.32170308 -0.89430422 0.31101006, + -0.27412394 -0.90833378 0.31588891, + -0.26713109 -0.92260635 0.27827808, + -0.21978003 -0.93398911 0.28171104, + -0.21369302 -0.94615412 0.24316204, + -0.16650794 -0.95500565 0.24543691, + -0.16149999 -0.96518886 0.20573796, + -0.11559495 -0.97147155 0.20707689, + -0.112506 -0.97836101 0.17364401, + -0.067716412 -0.98235226 0.17435205, + -0.066227615 -0.98678124 0.14790803, + -0.022450002 -0.98870313 0.14819601, + -0.021827111 -0.99313748 0.11489806, + 0.021526897 -0.99314386 0.11489899, + 0.022138899 -0.98870701 0.14821699, + 0.06604939 -0.98678988 0.14792998, + 0.067542672 -0.9823485 0.17443991, + 0.11237395 -0.97836053 0.17373191, + 0.11545997 -0.97147673 0.20712796, + 0.16144295 -0.96518779 0.20578796, + 0.16642092 -0.95510352 0.24511488, + 0.21348095 -0.94628179 0.24285094, + 0.21955292 -0.93417364 0.2812759, + 0.26683208 -0.92281938 0.27785808, + 0.27381909 -0.9085983 0.31539211, + 0.32133508 -0.89460224 0.31053305, + 0.32894012 -0.87849027 0.3464871, + 0.37629607 -0.86188412 0.33993703, + 0.38424408 -0.84408915 0.37399209, + 0.43113115 -0.82494229 0.36550811, + 0.43915489 -0.80575484 0.39736891, + 0.48463005 -0.78450614 0.38689005, + 0.49257699 -0.76400799 0.41672501, + 0.53615195 -0.74105293 0.40420493, + 0.54365027 -0.72000444 0.43132126, + 0.58559686 -0.6953758 0.41656792, + 0.59254587 -0.67403281 0.44109988, + 0.63252878 -0.64809376 0.42412484, + 0.63882303 -0.62681508 0.44610307, + 0.67606205 -0.60032904 0.42725307, + 0.6817252 -0.57911313 0.44707811, + 0.71625179 -0.55238479 0.42644385, + 0.72115076 -0.53191584 0.44385484, + 0.75318182 -0.5050689 0.42145291, + 0.75731319 -0.48572412 0.43651909, + 0.78707218 -0.45880613 0.41232809, + 0.79049355 -0.44078273 0.42524174, + 0.81754416 -0.41443908 0.39982709, + 0.8203941 -0.39747506 0.41105607, + 0.84480888 -0.37194297 0.38465095, + 0.84707469 -0.35662389 0.39406085, + 0.86935586 -0.33160397 0.36641398, + 0.87112284 -0.3180069 0.37418792, + 0.89129728 -0.29362813 0.34550211, + 0.89266813 -0.28157803 0.35193402, + 0.91069132 -0.25807109 0.32255313, + 0.91171777 -0.24774495 0.3277089, + 0.92771 -0.22512101 0.29778299, + 0.92846566 -0.21640292 0.3018629, + 0.94265467 -0.19446692 0.27126491, + 0.94365478 -0.18046795 0.27739295, + 0.92828703 -0.20279001 0.31170401, + 0.92766315 -0.21110103 0.30802202, + 0.91168302 -0.232287 0.33893499, + 0.91079128 -0.24265009 0.33403611, + 0.89281541 -0.26472211 0.36442119, + 0.89162499 -0.276761 0.35834101, + 0.8714391 -0.29982302 0.38820106, + 0.86991483 -0.31329092 0.38091591, + 0.84777015 -0.33689708 0.4096171, + 0.8457756 -0.35232282 0.40066481, + 0.8214317 -0.37660286 0.42827585, + 0.81895584 -0.39342692 0.41776392, + 0.7920801 -0.41849205 0.44438004, + 0.78896618 -0.4371371 0.4317911, + 0.75944972 -0.46284083 0.45718086, + 0.75573313 -0.48253405 0.44275105, + 0.72370797 -0.50849003 0.46656701, + 0.71938878 -0.52891183 0.45025784, + 0.68497616 -0.5547691 0.47227013, + 0.679865 -0.57644999 0.453309, + 0.6427207 -0.60220373 0.47356176, + 0.63688993 -0.62450296 0.45206994, + 0.59710389 -0.64978385 0.47036988, + 0.59065497 -0.67215097 0.44647494, + 0.54863811 -0.69642019 0.46259612, + 0.54171509 -0.71840507 0.43639305, + 0.49797988 -0.74116182 0.45021689, + 0.49063671 -0.7626785 0.42142275, + 0.44489995 -0.78387386 0.43313494, + 0.437271 -0.80469 0.401582, + 0.39000976 -0.82391053 0.41117376, + 0.38247514 -0.84326428 0.37764814, + 0.33456814 -0.86006242 0.38517118, + 0.32730603 -0.87786114 0.34961504, + 0.27899107 -0.89214522 0.35530409, + 0.27229699 -0.90811199 0.31809899, + 0.22411007 -0.91976821 0.32218209, + 0.21819989 -0.9338116 0.28352186, + 0.17009506 -0.94292438 0.2862891, + 0.16527404 -0.95484024 0.24691007, + 0.11834797 -0.96135074 0.24859294, + 0.11470605 -0.97132933 0.20823507, + 0.068863109 -0.97546214 0.20912103, + 0.066995576 -0.98225963 0.17514995, + 0.022282902 -0.98422712 0.17550102, + 0.021789799 -0.98868388 0.14842299, + -0.022067498 -0.98867786 0.14842199, + -0.022567293 -0.98424262 0.17537694, + -0.067197897 -0.98226798 0.175026, + -0.069078393 -0.97546786 0.20902297, + -0.11487298 -0.97133088 0.20813598, + -0.11852897 -0.96130776 0.24867295, + -0.16551894 -0.95477867 0.24698392, + -0.17036495 -0.94277966 0.28660491, + -0.21850389 -0.93364757 0.28382784, + -0.22440493 -0.91959363 0.32247487, + -0.27272791 -0.9078877 0.3183699, + -0.27946201 -0.89181 0.355775, + -0.32768998 -0.8775329 0.35007897, + -0.3349379 -0.85971284 0.38562992, + -0.38286906 -0.84289014 0.37808406, + -0.39037219 -0.82356143 0.41152921, + -0.43779784 -0.8042537 0.40188184, + -0.44538978 -0.78350067 0.43330678, + -0.49110207 -0.7622931 0.42157805, + -0.49837899 -0.74094999 0.450124, + -0.54219908 -0.71812308 0.43625605, + -0.54912615 -0.69612515 0.46246111, + -0.59097892 -0.67192596 0.44638494, + -0.59741431 -0.64959031 0.47024325, + -0.63715792 -0.62431794 0.45194793, + -0.64297277 -0.60207379 0.47338483, + -0.68008107 -0.57632709 0.45314106, + -0.68517894 -0.55469996 0.47205696, + -0.71955794 -0.52885091 0.45005894, + -0.72387218 -0.50845712 0.46634811, + -0.75586909 -0.48250806 0.44254705, + -0.75958198 -0.462845 0.45695701, + -0.78907287 -0.43714693 0.43158594, + -0.79215866 -0.41869578 0.44404778, + -0.81901515 -0.39362606 0.41746005, + -0.82152081 -0.37662691 0.4280839, + -0.84584028 -0.35235712 0.40049815, + -0.84781742 -0.33709416 0.40935722, + -0.86994886 -0.31348097 0.38068193, + -0.87147897 -0.300001 0.38797399, + -0.8916533 -0.27693108 0.35813913, + -0.89284778 -0.26488695 0.3642219, + -0.91081625 -0.24280307 0.33385709, + -0.91169399 -0.232649 0.33865699, + -0.9276669 -0.21143697 0.30777997, + -0.92878824 -0.19571005 0.31472209, + -0.91139913 -0.21731503 0.34946504, + -0.91066974 -0.22720595 0.34504792, + -0.89270443 -0.24783312 0.37637419, + -0.89169729 -0.25972009 0.37070411, + -0.8715713 -0.2813161 0.40152815, + -0.87021714 -0.29518303 0.39444807, + -0.84812558 -0.31742784 0.42417279, + -0.84642941 -0.33256614 0.41588122, + -0.82210928 -0.35556713 0.44464415, + -0.81997055 -0.3723008 0.43478772, + -0.79324389 -0.39603993 0.46251094, + -0.79051685 -0.41477695 0.45060295, + -0.76104313 -0.43933505 0.47728205, + -0.75777429 -0.45916218 0.46362519, + -0.72599596 -0.48391894 0.48862293, + -0.72203082 -0.50526386 0.47263089, + -0.68781662 -0.53011078 0.49587375, + -0.68328875 -0.55191284 0.47802582, + -0.64627576 -0.57682383 0.49960181, + -0.64102107 -0.59964108 0.47908506, + -0.60135996 -0.62421596 0.49871895, + -0.59543973 -0.64751476 0.47557983, + -0.55336523 -0.67132229 0.49306524, + -0.54700679 -0.69424963 0.46776178, + -0.50316685 -0.71669179 0.48288289, + -0.49634299 -0.73943698 0.45483699, + -0.45039588 -0.76047784 0.46777889, + -0.44340894 -0.78225988 0.43755895, + -0.39575893 -0.8014909 0.44831595, + -0.38859293 -0.82262486 0.41507095, + -0.3401989 -0.8395378 0.42360491, + -0.33332208 -0.85899317 0.38862208, + -0.28436998 -0.87348086 0.39517695, + -0.27797192 -0.89124668 0.35834488, + -0.22873995 -0.90321374 0.36315691, + -0.22306092 -0.91915864 0.32463989, + -0.17409898 -0.92851585 0.32794496, + -0.16936606 -0.94249934 0.28811508, + -0.12121496 -0.94926363 0.29018191, + -0.11769498 -0.96109986 0.24986997, + -0.070756875 -0.96540064 0.25098792, + -0.068549596 -0.97535187 0.20973697, + -0.023048894 -0.97739178 0.21017596, + -0.022414105 -0.98421323 0.17556204, + 0.022231705 -0.98421723 0.17556304, + 0.022868607 -0.97738636 0.21022107, + 0.068372115 -0.97535425 0.20978405, + 0.070574239 -0.96543646 0.25090212, + 0.11751605 -0.96114337 0.24978709, + 0.12102605 -0.94936037 0.28994408, + 0.16903599 -0.94262791 0.28788796, + 0.17373995 -0.92872179 0.3275519, + 0.22282694 -0.91935378 0.3242479, + 0.22852293 -0.90344071 0.36272889, + 0.27745092 -0.89156371 0.35795987, + 0.28387585 -0.87374157 0.39495581, + 0.33281389 -0.85928172 0.38841984, + 0.33970711 -0.8397963 0.42348716, + 0.38810217 -0.82290739 0.41497022, + 0.39521599 -0.80195999 0.447956, + 0.44300705 -0.78269213 0.43719307, + 0.4500728 -0.76072562 0.4676868, + 0.49601617 -0.73970222 0.45476216, + 0.502837 -0.71702099 0.48273799, + 0.54660803 -0.69463009 0.46766305, + 0.55306596 -0.67135894 0.49335095, + 0.59504968 -0.64762872 0.47591275, + 0.60094178 -0.62442374 0.49896282, + 0.64076531 -0.59977132 0.47926423, + 0.64602774 -0.5769248 0.49980581, + 0.68309069 -0.55199778 0.47821075, + 0.68766022 -0.52998215 0.49622819, + 0.72180879 -0.50520682 0.47303084, + 0.72573996 -0.48401195 0.48891094, + 0.75764531 -0.45917517 0.46382317, + 0.76094401 -0.439147 0.477613, + 0.7904408 -0.41459191 0.45090687, + 0.79313487 -0.39605394 0.46268594, + 0.81988686 -0.37230498 0.43494195, + 0.82204801 -0.35536599 0.44491801, + 0.84637982 -0.33237591 0.41613391, + 0.8480702 -0.3172521 0.42441508, + 0.87017602 -0.29501399 0.394665, + 0.871526 -0.281151 0.40174201, + 0.8916629 -0.25956398 0.37089598, + 0.89266825 -0.24766006 0.3765741, + 0.91068387 -0.22699396 0.34514996, + 0.91141415 -0.21705604 0.34958702, + 0.92741901 -0.197293 0.31775701, + 0.92796433 -0.18875708 0.32133013, + 0.94224674 -0.16963695 0.28878093, + 0.94296426 -0.15574703 0.29421306, + 0.92746139 -0.17494106 0.33047113, + 0.92702961 -0.18305892 0.32726985, + 0.91092777 -0.20140296 0.36006591, + 0.91031432 -0.21141708 0.35585213, + 0.8922649 -0.23061897 0.38817295, + 0.89143729 -0.24230209 0.38292214, + 0.87125069 -0.26245791 0.41477486, + 0.87014133 -0.2759971 0.40826416, + 0.84802014 -0.29681003 0.43905106, + 0.84654516 -0.31236905 0.43103009, + 0.82231158 -0.33391684 0.46076378, + 0.82044983 -0.35095692 0.45132187, + 0.79370368 -0.37341487 0.48020381, + 0.7913903 -0.39190716 0.46915919, + 0.76193321 -0.41520709 0.49705213, + 0.75907034 -0.4353182 0.48405623, + 0.72734958 -0.45889473 0.51027268, + 0.72383791 -0.48067093 0.49498895, + 0.68971622 -0.50443417 0.51945919, + 0.68563807 -0.52693206 0.50223804, + 0.64873284 -0.55087286 0.5250569, + 0.64400202 -0.57431197 0.50539798, + 0.60421473 -0.59818268 0.52640474, + 0.59887171 -0.62214768 0.50426674, + 0.55692786 -0.6452328 0.52297789, + 0.55102295 -0.66944492 0.49821395, + 0.50697196 -0.69148391 0.51461595, + 0.50068724 -0.71530336 0.48749724, + 0.45449001 -0.73606402 0.50164598, + 0.44795206 -0.7592811 0.47205007, + 0.39994317 -0.77837437 0.48392025, + 0.39328009 -0.80083215 0.45166212, + 0.3443211 -0.81775916 0.46120811, + 0.33784002 -0.83885914 0.42682505, + 0.28829896 -0.8534199 0.43423295, + 0.282206 -0.87301701 0.39774501, + 0.232408 -0.88508803 0.40324399, + 0.22698306 -0.90285826 0.36513808, + 0.17714496 -0.91239375 0.36899492, + 0.17258495 -0.92833775 0.32924691, + 0.12365903 -0.93524623 0.33169708, + 0.12021003 -0.94911826 0.29107407, + 0.072281621 -0.95355034 0.29243311, + 0.070139013 -0.96531826 0.25147805, + 0.023483194 -0.96743476 0.25202894, + 0.022731895 -0.97735274 0.21039195, + -0.02287681 -0.97734946 0.2103921, + -0.023627389 -0.96741951 0.25207388, + -0.070354581 -0.96529162 0.25151992, + -0.072498284 -0.95349777 0.29255095, + -0.12049104 -0.94904834 0.29118609, + -0.12394901 -0.9351061 0.33198404, + -0.17302802 -0.92815912 0.32951802, + -0.17756906 -0.91229427 0.36903712, + -0.22745495 -0.90272778 0.3651669, + -0.23290494 -0.88488173 0.4034099, + -0.28274593 -0.87277579 0.39789093, + -0.28883603 -0.85317409 0.43435907, + -0.33833411 -0.83860129 0.42694014, + -0.34486297 -0.81731588 0.46158895, + -0.39382923 -0.80036348 0.45201427, + -0.40039501 -0.77820498 0.48381901, + -0.44837388 -0.75909984 0.47194088, + -0.45492887 -0.73580784 0.50162387, + -0.50109917 -0.71503723 0.48746419, + -0.50736475 -0.69127166 0.51451379, + -0.55122298 -0.66931301 0.49816999, + -0.55714494 -0.64498794 0.52304894, + -0.59919697 -0.621831 0.50427097, + -0.60449189 -0.59806287 0.52622288, + -0.64424294 -0.57419592 0.50522292, + -0.64896315 -0.55080914 0.5248391, + -0.6857236 -0.52694869 0.50210369, + -0.68979859 -0.50445771 0.51932669, + -0.72409081 -0.48056087 0.49472588, + -0.72757703 -0.45897606 0.50987506, + -0.75916111 -0.43547806 0.48377007, + -0.76205385 -0.41517991 0.49688989, + -0.79149789 -0.39187795 0.46900195, + -0.79378819 -0.3735961 0.47992313, + -0.82050812 -0.35113803 0.45107505, + -0.8223784 -0.33406916 0.46053421, + -0.84659618 -0.31251609 0.43082309, + -0.84807402 -0.29697099 0.43883801, + -0.87018681 -0.27614695 0.40806592, + -0.87129813 -0.26262403 0.41457006, + -0.89147371 -0.24245891 0.38273785, + -0.89228791 -0.23102897 0.38787594, + -0.91032797 -0.211799 0.35558999, + -0.91094011 -0.20188802 0.35976303, + -0.92703861 -0.18350092 0.32699686, + -0.92782366 -0.16765194 0.33322087, + -0.91026628 -0.18608107 0.36985013, + -0.90976924 -0.19602405 0.3659161, + -0.89160877 -0.21382296 0.39914092, + -0.89094198 -0.225288 0.39429399, + -0.8707211 -0.24397103 0.42699307, + -0.86982387 -0.25722298 0.42100194, + -0.8476541 -0.27661103 0.45273507, + -0.84645391 -0.29184097 0.44535893, + -0.82213616 -0.31202707 0.47616312, + -0.82057256 -0.32911384 0.4672738, + -0.79386419 -0.35016209 0.49715811, + -0.79186732 -0.36902311 0.48658818, + -0.76260167 -0.39088285 0.51541179, + -0.76012832 -0.41120714 0.50310415, + -0.72848207 -0.43354106 0.53043008, + -0.72547764 -0.45521981 0.51619476, + -0.69135708 -0.47788507 0.54189605, + -0.68770283 -0.50121689 0.52521086, + -0.65094525 -0.52409118 0.54918015, + -0.64677221 -0.54788113 0.53057712, + -0.60704106 -0.57085907 0.55283004, + -0.60225815 -0.59549314 0.53167009, + -0.56035018 -0.61783826 0.55161917, + -0.55502009 -0.64288217 0.52787811, + -0.51099396 -0.66432697 0.54548591, + -0.50520301 -0.689426 0.51909697, + -0.45895207 -0.70976603 0.53441107, + -0.45289993 -0.73431194 0.50563592, + -0.40465924 -0.75317848 0.51862627, + -0.39848515 -0.77698731 0.48734018, + -0.34914681 -0.79383963 0.49791077, + -0.343126 -0.81634998 0.46458301, + -0.29290605 -0.83099616 0.47291812, + -0.28716102 -0.85235614 0.43706706, + -0.23666593 -0.86455482 0.44332188, + -0.2314869 -0.8842696 0.40556282, + -0.18073399 -0.89398998 0.41002101, + -0.17638806 -0.91183931 0.37072411, + -0.12643805 -0.91892934 0.37360713, + -0.12312502 -0.9348191 0.33309704, + -0.073987491 -0.9394049 0.33472997, + -0.071907617 -0.95331025 0.29330707, + -0.024098296 -0.95550686 0.29398298, + -0.023381792 -0.96734667 0.2523759, + 0.023199795 -0.96735078 0.25237694, + 0.023914995 -0.95557576 0.29377395, + 0.071759775 -0.95338464 0.29310089, + 0.07386373 -0.93945533 0.33461612, + 0.12269503 -0.93491125 0.33299708, + 0.12599401 -0.9190591 0.37343803, + 0.17605101 -0.91197199 0.37055799, + 0.18038405 -0.89422327 0.40966615, + 0.23110506 -0.88452524 0.4052231, + 0.236296 -0.86482602 0.44299001, + 0.28673694 -0.85265779 0.43675691, + 0.29248795 -0.83134884 0.47255689, + 0.34254304 -0.8167721 0.46427107, + 0.34864697 -0.79397887 0.49803895, + 0.3980121 -0.77714318 0.48747811, + 0.40416494 -0.7534309 0.51864493, + 0.45245713 -0.73456818 0.50566012, + 0.45852289 -0.7099908 0.53448087, + 0.50482309 -0.68965006 0.51916903, + 0.51063412 -0.66447616 0.54564112, + 0.55470204 -0.64303106 0.52803105, + 0.56003624 -0.61797631 0.55178326, + 0.60198808 -0.59562606 0.53182703, + 0.60677779 -0.5709638 0.55301082, + 0.646559 -0.54797298 0.53074199, + 0.65076894 -0.52395391 0.54951996, + 0.687549 -0.501086 0.52553701, + 0.69117075 -0.47794381 0.54208183, + 0.72532016 -0.45527312 0.5163691, + 0.72832525 -0.43358415 0.5306102, + 0.7600047 -0.41123885 0.50326484, + 0.76249886 -0.39071393 0.51569194, + 0.79178488 -0.36885998 0.48684594, + 0.79377681 -0.34999692 0.49741387, + 0.8205002 -0.32895708 0.46751112, + 0.82205915 -0.31187105 0.47639811, + 0.84639812 -0.29168704 0.44556606, + 0.84759402 -0.27646101 0.452939, + 0.86977786 -0.25707898 0.42118493, + 0.87068915 -0.24354306 0.42730209, + 0.890917 -0.22489101 0.394577, + 0.89158332 -0.21332307 0.39946514, + 0.90975457 -0.1955599 0.36620083, + 0.91023886 -0.18577199 0.37007296, + 0.92643487 -0.16888998 0.33644396, + 0.92678636 -0.16065106 0.33949712, + 0.94128478 -0.14440797 0.30517095, + 0.94172466 -0.13127296 0.30971289, + 0.95357287 -0.11752798 0.27728298, + 0.95399511 -0.10085902 0.28234902, + 0.96450245 -0.088833444 0.24868412, + 0.96472991 -0.074998394 0.25233197, + 0.97394198 -0.064615302 0.217398, + 0.97389954 -0.067079671 0.21684089, + 0.98087889 -0.057516094 0.18592599, + 0.9806655 -0.06387037 0.18497491, + 0.98706549 -0.052325074 0.15153793, + 0.98699635 -0.053916018 0.15143105, + 0.99304247 -0.039497919 0.11093505, + 0.99331814 -0.031015905 0.11116301, + 0.99759173 -0.018640095 0.066807382, + 0.99767262 -0.013158095 0.066903874, + 0.99974537 -0.0043551815 0.022144508, + 0.99975026 -0.0029030507 0.022160305, + 0.99965525 0.0028920607 0.026099505, + 0.9996559 0.0028941098 0.026070897, + 0.99966013 0.00026882804 0.026071103, + 0.99965936 0.00026653608 0.026099609, + 0.9992891 0.029752905 -0.023152502, + 0.99972677 0.0031570494 -0.023162594, + 0.99973178 0.0031406393 -0.022947295, + 0.99973589 0.0012792099 -0.022947399, + 0.99988055 0.015458393 0, + 0.4508118 -0.8926186 0.0008744126, + 0.45076215 -0.89252031 -0.014865106, + 0 1 0, + -0.9609201 -0.27682602 0, + -0.98587126 -0.16750504 0, + -0.9238739 -0.38269693 0, + 0.99842674 -0.056072284 0, + 0.98587126 -0.16750504 0, + 0.9238739 -0.38269693 0, + 0.9609201 -0.27682602 0, + 0 0 -1, + 0.87522501 -0.48371601 0, + 0.96091926 0.27682906 0, + 0.9238739 0.38269693 0, + -0.9238739 0.38269693 0, + -0.96091926 0.27682906 0, + -0.66635692 0.74563295 0, + -0.57866585 0.81556481 0, + 0.27682602 0.9609201 0, + 0.38269693 0.9238739 0, + -0.81556481 0.57866585 0, + -0.74563295 0.66635692 0, + -0.48371601 0.87522501 0, + -0.38269693 0.9238739 0, + -0.27682602 0.9609201 0, + 0.16750504 0.98587126 0, + 0.48371601 0.87522501 0, + 0.57866585 0.81556481 0, + -0.056072284 -0.99842674 0, + 0.056072284 -0.99842674 0, + 0.74563295 -0.66635692 0, + 0.66635692 -0.74563295 0, + -0.48371601 -0.87522501 0, + -0.57866585 -0.81556481 0, + 0.57866585 -0.81556481 0, + 0.48371601 -0.87522501 0, + 0.38269693 -0.9238739 0, + 0.27682602 -0.9609201 0, + 0.16750504 -0.98587126 0, + -0.27682602 -0.9609201 0, + -0.16750504 -0.98587126 0, + -0.38269693 -0.9238739 0, + -0.66635692 -0.74563295 0, + 0.81556481 -0.57866585 0, + 0.66635692 0.74563295 0, + 0.74563295 0.66635692 0, + 0.81556481 0.57866585 0, + -0.87522501 0.48371601 0, + 0.87522501 0.48371601 0, + -0.98587137 0.16750406 0, + -0.99842674 0.056072284 0, + -0.99842674 -0.056072284 0, + 0.98587137 0.16750406 0, + 0.99842674 0.056072284 0, + -0.74563295 -0.66635692 0, + -0.81556481 -0.57866585 0, + -0.87522501 -0.48371601 0, + -0.16750504 0.98587126 0, + 0.056072284 0.99842674 0, + -0.056072284 0.99842674 0, + -0.53740329 0.84328848 0.0078913448, + -0.024670089 -0.00043713779 0.99969554, + 0.024670089 -0.00043706279 0.99969554, + 0.0239159 -0.000109491 0.99971402, + -0.0239159 -0.000109491 0.99971402, + 0.075101294 -0.99717587 6.0073791e-005, + 0.075091295 -0.99704289 -0.016333098 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 3, 6, 4, -1, 4, 7, 8, -1, + 4, 9, 7, -1, 9, 4, 6, -1, + 6, 10, 9, -1, 10, 6, 11, -1, + 11, 12, 10, -1, 12, 11, 13, -1, + 13, 14, 12, -1, 14, 13, 15, -1, + 15, 16, 14, -1, 16, 15, 17, -1, + 17, 18, 16, -1, 18, 17, 19, -1, + 19, 20, 18, -1, 20, 19, 21, -1, + 21, 22, 20, -1, 22, 21, 23, -1, + 23, 24, 22, -1, 24, 23, 25, -1, + 25, 26, 24, -1, 26, 25, 27, -1, + 27, 28, 26, -1, 29, 30, 31, -1, + 29, 31, 28, -1, 28, 27, 29, -1, + 32, 33, 34, -1, 34, 35, 32, -1, + 35, 34, 36, -1, 36, 37, 35, -1, + 37, 36, 38, -1, 38, 39, 37, -1, + 38, 40, 39, -1, 41, 42, 43, -1, + 40, 42, 41, -1, 41, 39, 40, -1, + 41, 43, 39, -1, 39, 43, 29, -1, + 39, 29, 27, -1, 27, 37, 39, -1, + 37, 27, 25, -1, 25, 35, 37, -1, + 35, 25, 23, -1, 23, 32, 35, -1, + 32, 23, 21, -1, 21, 33, 32, -1, + 33, 21, 19, -1, 19, 44, 33, -1, + 44, 19, 17, -1, 17, 45, 44, -1, + 45, 17, 15, -1, 15, 46, 45, -1, + 46, 15, 13, -1, 13, 47, 46, -1, + 47, 13, 11, -1, 11, 48, 47, -1, + 48, 11, 6, -1, 6, 3, 48, -1, + 49, 50, 51, -1, 49, 52, 50, -1, + 52, 49, 53, -1, 53, 54, 52, -1, + 54, 53, 55, -1, 55, 56, 54, -1, + 56, 55, 57, -1, 57, 58, 56, -1, + 58, 57, 59, -1, 59, 60, 58, -1, + 60, 59, 61, -1, 61, 62, 60, -1, + 61, 63, 62, -1, 63, 61, 64, -1, + 64, 65, 63, -1, 65, 66, 67, -1, + 65, 64, 66, -1, 68, 69, 70, -1, + 68, 71, 69, -1, 72, 73, 69, -1, + 69, 74, 72, -1, 74, 69, 71, -1, + 71, 75, 74, -1, 75, 71, 76, -1, + 76, 77, 75, -1, 76, 78, 77, -1, + 76, 79, 78, -1, 79, 76, 71, -1, + 71, 68, 79, -1, 68, 80, 66, -1, + 66, 79, 68, -1, 79, 66, 64, -1, + 64, 78, 79, -1, 78, 64, 61, -1, + 78, 61, 59, -1, 59, 77, 78, -1, + 77, 59, 57, -1, 57, 81, 77, -1, + 81, 57, 55, -1, 55, 82, 81, -1, + 82, 55, 53, -1, 53, 83, 82, -1, + 83, 53, 49, -1, 49, 51, 83, -1, + 84, 85, 86, -1, 85, 84, 87, -1, + 87, 88, 85, -1, 89, 85, 88, -1, + 89, 90, 85, -1, 90, 89, 91, -1, + 89, 88, 91, -1, 92, 93, 94, -1, + 92, 95, 93, -1, 95, 92, 96, -1, + 92, 94, 96, -1, 97, 98, 94, -1, + 98, 96, 94, -1, 99, 100, 101, -1, + 101, 102, 99, -1, 102, 101, 103, -1, + 103, 104, 102, -1, 103, 105, 104, -1, + 106, 107, 108, -1, 108, 109, 106, -1, + 109, 108, 110, -1, 110, 111, 109, -1, + 111, 110, 112, -1, 112, 113, 111, -1, + 113, 112, 114, -1, 114, 115, 113, -1, + 115, 114, 116, -1, 116, 117, 115, -1, + 117, 116, 118, -1, 118, 119, 117, -1, + 119, 118, 120, -1, 120, 121, 119, -1, + 121, 120, 122, -1, 122, 123, 121, -1, + 123, 122, 124, -1, 124, 125, 123, -1, + 125, 124, 126, -1, 126, 127, 125, -1, + 127, 126, 128, -1, 128, 129, 127, -1, + 129, 128, 130, -1, 130, 131, 129, -1, + 131, 130, 132, -1, 132, 133, 131, -1, + 133, 132, 134, -1, 134, 135, 133, -1, + 135, 134, 136, -1, 136, 137, 135, -1, + 137, 136, 138, -1, 138, 139, 137, -1, + 139, 138, 140, -1, 140, 141, 139, -1, + 141, 140, 142, -1, 142, 143, 141, -1, + 143, 142, 144, -1, 144, 145, 143, -1, + 145, 144, 146, -1, 146, 147, 145, -1, + 147, 146, 148, -1, 148, 149, 147, -1, + 149, 148, 150, -1, 150, 151, 149, -1, + 151, 150, 152, -1, 152, 153, 151, -1, + 153, 152, 154, -1, 153, 154, 155, -1, + 155, 156, 153, -1, 156, 155, 157, -1, + 157, 158, 156, -1, 158, 157, 159, -1, + 159, 160, 158, -1, 160, 159, 161, -1, + 161, 162, 160, -1, 162, 161, 163, -1, + 163, 164, 162, -1, 164, 163, 165, -1, + 165, 166, 164, -1, 166, 165, 167, -1, + 167, 168, 166, -1, 168, 167, 169, -1, + 169, 170, 168, -1, 170, 169, 171, -1, + 171, 172, 170, -1, 172, 171, 173, -1, + 173, 174, 172, -1, 174, 173, 175, -1, + 175, 176, 174, -1, 176, 175, 177, -1, + 177, 178, 176, -1, 178, 177, 179, -1, + 179, 180, 178, -1, 180, 179, 181, -1, + 181, 182, 180, -1, 182, 181, 183, -1, + 183, 184, 182, -1, 184, 183, 185, -1, + 185, 186, 184, -1, 186, 185, 187, -1, + 187, 188, 186, -1, 188, 187, 189, -1, + 189, 190, 188, -1, 190, 189, 191, -1, + 191, 192, 190, -1, 192, 191, 193, -1, + 193, 194, 192, -1, 194, 193, 195, -1, + 195, 196, 194, -1, 196, 195, 197, -1, + 197, 198, 196, -1, 198, 197, 199, -1, + 199, 200, 198, -1, 200, 199, 201, -1, + 201, 202, 200, -1, 202, 201, 203, -1, + 204, 205, 206, -1, 207, 206, 205, -1, + 207, 208, 206, -1, 208, 207, 209, -1, + 209, 210, 208, -1, 210, 209, 211, -1, + 211, 212, 210, -1, 212, 211, 213, -1, + 213, 214, 212, -1, 215, 216, 217, -1, + 217, 218, 215, -1, 218, 217, 219, -1, + 219, 220, 218, -1, 220, 219, 221, -1, + 221, 222, 220, -1, 222, 221, 223, -1, + 223, 224, 222, -1, 224, 223, 225, -1, + 225, 214, 224, -1, 214, 225, 226, -1, + 226, 212, 214, -1, 212, 226, 227, -1, + 227, 210, 212, -1, 210, 227, 228, -1, + 228, 208, 210, -1, 208, 228, 229, -1, + 229, 206, 208, -1, 206, 229, 230, -1, + 231, 232, 233, -1, 230, 233, 232, -1, + 230, 234, 233, -1, 234, 230, 229, -1, + 229, 235, 234, -1, 235, 229, 228, -1, + 228, 236, 235, -1, 236, 228, 227, -1, + 227, 237, 236, -1, 237, 227, 226, -1, + 226, 238, 237, -1, 238, 226, 225, -1, + 225, 239, 238, -1, 239, 225, 223, -1, + 223, 240, 239, -1, 240, 223, 221, -1, + 221, 241, 240, -1, 241, 221, 219, -1, + 219, 242, 241, -1, 242, 219, 217, -1, + 217, 243, 242, -1, 243, 217, 216, -1, + 216, 244, 243, -1, 244, 203, 245, -1, + 245, 243, 244, -1, 243, 245, 246, -1, + 246, 242, 243, -1, 242, 246, 247, -1, + 247, 241, 242, -1, 241, 247, 248, -1, + 248, 240, 241, -1, 240, 248, 249, -1, + 249, 239, 240, -1, 239, 249, 250, -1, + 250, 238, 239, -1, 238, 250, 251, -1, + 251, 237, 238, -1, 237, 251, 252, -1, + 252, 236, 237, -1, 236, 252, 253, -1, + 253, 235, 236, -1, 235, 253, 254, -1, + 254, 234, 235, -1, 234, 254, 255, -1, + 255, 233, 234, -1, 233, 255, 256, -1, + 256, 257, 233, -1, 258, 259, 260, -1, + 260, 259, 257, -1, 257, 256, 260, -1, + 261, 262, 263, -1, 263, 264, 261, -1, + 264, 263, 265, -1, 265, 266, 264, -1, + 266, 265, 267, -1, 267, 268, 266, -1, + 268, 267, 269, -1, 269, 270, 268, -1, + 270, 269, 271, -1, 271, 272, 270, -1, + 273, 274, 272, -1, 273, 272, 275, -1, + 272, 271, 275, -1, 276, 271, 277, -1, + 276, 275, 271, -1, 276, 278, 275, -1, + 276, 277, 278, -1, 279, 280, 281, -1, + 280, 279, 282, -1, 283, 284, 285, -1, + 284, 283, 282, -1, 283, 280, 282, -1, + 283, 285, 280, -1, 285, 281, 280, -1, + 281, 285, 286, -1, 286, 287, 281, -1, + 287, 286, 288, -1, 288, 289, 287, -1, + 289, 288, 290, -1, 290, 291, 289, -1, + 291, 290, 292, -1, 292, 293, 291, -1, + 292, 294, 293, -1, 294, 292, 295, -1, + 296, 297, 298, -1, 297, 296, 299, -1, + 299, 300, 297, -1, 300, 299, 301, -1, + 301, 302, 300, -1, 302, 301, 303, -1, + 303, 304, 302, -1, 304, 303, 305, -1, + 305, 306, 304, -1, 306, 305, 295, -1, + 306, 295, 292, -1, 306, 292, 290, -1, + 290, 304, 306, -1, 304, 290, 288, -1, + 288, 302, 304, -1, 302, 288, 286, -1, + 286, 300, 302, -1, 300, 286, 285, -1, + 285, 297, 300, -1, 285, 284, 297, -1, + 307, 297, 284, -1, 284, 282, 307, -1, + 308, 307, 282, -1, 308, 297, 307, -1, + 308, 298, 297, -1, 308, 282, 298, -1, + 278, 298, 282, -1, 309, 298, 278, -1, + 309, 296, 298, -1, 309, 310, 296, -1, + 310, 309, 278, -1, 310, 278, 277, -1, + 277, 271, 310, -1, 271, 296, 310, -1, + 296, 271, 269, -1, 269, 299, 296, -1, + 299, 269, 267, -1, 267, 301, 299, -1, + 301, 267, 265, -1, 265, 303, 301, -1, + 303, 265, 263, -1, 263, 305, 303, -1, + 305, 263, 262, -1, 262, 295, 305, -1, + 262, 311, 295, -1, 262, 261, 311, -1, + 312, 313, 314, -1, 315, 316, 317, -1, + 315, 318, 316, -1, 315, 319, 318, -1, + 315, 317, 319, -1, 320, 321, 322, -1, + 320, 322, 317, -1, 322, 319, 317, -1, + 319, 322, 323, -1, 323, 324, 319, -1, + 324, 323, 325, -1, 325, 326, 324, -1, + 326, 325, 327, -1, 327, 328, 326, -1, + 328, 327, 329, -1, 329, 330, 328, -1, + 330, 329, 331, -1, 331, 332, 330, -1, + 332, 331, 333, -1, 333, 334, 332, -1, + 334, 333, 313, -1, 313, 312, 334, -1, + 312, 335, 311, -1, 311, 334, 312, -1, + 334, 311, 261, -1, 261, 332, 334, -1, + 332, 261, 264, -1, 264, 330, 332, -1, + 330, 264, 266, -1, 266, 328, 330, -1, + 328, 266, 268, -1, 268, 326, 328, -1, + 326, 268, 270, -1, 270, 324, 326, -1, + 324, 270, 272, -1, 272, 319, 324, -1, + 319, 272, 274, -1, 274, 318, 319, -1, + 274, 316, 318, -1, 274, 273, 316, -1, + 273, 275, 316, -1, 316, 275, 278, -1, + 336, 282, 279, -1, 337, 336, 279, -1, + 279, 281, 337, -1, 281, 338, 337, -1, + 338, 281, 287, -1, 287, 339, 338, -1, + 339, 287, 289, -1, 289, 340, 339, -1, + 340, 289, 291, -1, 291, 341, 340, -1, + 341, 291, 293, -1, 293, 342, 341, -1, + 293, 343, 342, -1, 343, 293, 294, -1, + 294, 344, 343, -1, 294, 295, 344, -1, + 345, 344, 295, -1, 345, 295, 311, -1, + 345, 311, 335, -1, 335, 346, 345, -1, + 347, 348, 349, -1, 347, 350, 348, -1, + 351, 352, 353, -1, 354, 355, 356, -1, + 357, 358, 359, -1, 357, 359, 360, -1, + 360, 361, 362, -1, 361, 360, 359, -1, + 359, 363, 361, -1, 363, 359, 364, -1, + 364, 365, 363, -1, 365, 364, 366, -1, + 366, 367, 365, -1, 367, 366, 368, -1, + 368, 369, 367, -1, 369, 368, 370, -1, + 370, 371, 369, -1, 371, 370, 372, -1, + 372, 373, 371, -1, 373, 372, 374, -1, + 374, 375, 373, -1, 375, 376, 377, -1, + 375, 374, 376, -1, 378, 376, 374, -1, + 374, 379, 378, -1, 379, 374, 372, -1, + 372, 380, 379, -1, 380, 372, 370, -1, + 370, 381, 380, -1, 381, 370, 368, -1, + 368, 382, 381, -1, 382, 368, 366, -1, + 366, 383, 382, -1, 383, 366, 364, -1, + 364, 384, 383, -1, 384, 364, 359, -1, + 384, 359, 358, -1, 358, 385, 384, -1, + 386, 387, 388, -1, 387, 386, 389, -1, + 386, 390, 389, -1, 386, 388, 390, -1, + 391, 390, 388, -1, 391, 388, 385, -1, + 385, 358, 391, -1, 392, 393, 391, -1, + 392, 391, 358, -1, 358, 357, 392, -1, + 394, 395, 392, -1, 394, 392, 357, -1, + 357, 360, 394, -1, 396, 397, 394, -1, + 396, 394, 360, -1, 360, 362, 396, -1, + 398, 399, 400, -1, 398, 401, 399, -1, + 398, 402, 401, -1, 398, 400, 402, -1, + 402, 400, 396, -1, 402, 396, 362, -1, + 362, 403, 402, -1, 362, 404, 403, -1, + 404, 362, 361, -1, 361, 405, 404, -1, + 405, 361, 363, -1, 363, 406, 405, -1, + 406, 363, 365, -1, 365, 407, 406, -1, + 407, 365, 367, -1, 367, 408, 407, -1, + 408, 367, 369, -1, 369, 409, 408, -1, + 409, 369, 371, -1, 371, 410, 409, -1, + 410, 371, 373, -1, 373, 411, 410, -1, + 411, 373, 375, -1, 375, 377, 411, -1, + 412, 413, 414, -1, 412, 415, 413, -1, + 412, 416, 415, -1, 412, 414, 416, -1, + 417, 416, 414, -1, 418, 419, 420, -1, + 418, 417, 419, -1, 418, 421, 417, -1, + 418, 420, 421, -1, 422, 421, 420, -1, + 422, 420, 423, -1, 422, 423, 424, -1, + 424, 425, 422, -1, 426, 422, 425, -1, + 426, 421, 422, -1, 426, 417, 421, -1, + 426, 425, 417, -1, 425, 416, 417, -1, + 425, 424, 416, -1, 424, 415, 416, -1, + 424, 427, 415, -1, 427, 424, 423, -1, + 423, 428, 427, -1, 423, 429, 428, -1, + 429, 423, 420, -1, 420, 430, 429, -1, + 420, 419, 430, -1, 431, 430, 419, -1, + 431, 432, 430, -1, 431, 433, 432, -1, + 431, 419, 433, -1, 433, 419, 417, -1, + 434, 435, 436, -1, 434, 437, 435, -1, + 434, 438, 437, -1, 434, 436, 438, -1, + 439, 438, 436, -1, 439, 440, 438, -1, + 440, 439, 441, -1, 441, 442, 440, -1, + 442, 441, 443, -1, 443, 444, 442, -1, + 444, 443, 445, -1, 445, 446, 444, -1, + 445, 447, 446, -1, 447, 445, 448, -1, + 448, 449, 447, -1, 449, 448, 450, -1, + 450, 451, 449, -1, 451, 450, 452, -1, + 452, 453, 451, -1, 452, 454, 453, -1, + 455, 454, 456, -1, 455, 453, 454, -1, + 455, 457, 453, -1, 455, 456, 457, -1, + 458, 459, 460, -1, 461, 462, 463, -1, + 464, 465, 466, -1, 466, 467, 464, -1, + 467, 466, 468, -1, 468, 469, 467, -1, + 469, 468, 470, -1, 470, 471, 469, -1, + 471, 470, 472, -1, 472, 473, 471, -1, + 473, 472, 474, -1, 474, 475, 473, -1, + 475, 474, 476, -1, 476, 477, 475, -1, + 477, 476, 478, -1, 478, 479, 477, -1, + 479, 478, 480, -1, 480, 481, 479, -1, + 481, 480, 482, -1, 482, 483, 481, -1, + 483, 482, 484, -1, 484, 485, 483, -1, + 485, 484, 486, -1, 486, 487, 485, -1, + 487, 486, 488, -1, 488, 489, 487, -1, + 489, 488, 490, -1, 490, 491, 489, -1, + 491, 490, 492, -1, 492, 493, 491, -1, + 493, 492, 494, -1, 494, 495, 493, -1, + 495, 494, 496, -1, 496, 497, 495, -1, + 497, 496, 498, -1, 498, 499, 497, -1, + 499, 498, 500, -1, 500, 501, 499, -1, + 501, 500, 502, -1, 503, 504, 505, -1, + 503, 506, 504, -1, 507, 508, 509, -1, + 509, 510, 507, -1, 510, 509, 511, -1, + 511, 512, 510, -1, 512, 511, 513, -1, + 513, 514, 512, -1, 514, 513, 515, -1, + 515, 516, 514, -1, 516, 515, 517, -1, + 517, 518, 516, -1, 518, 517, 519, -1, + 519, 520, 518, -1, 520, 519, 521, -1, + 521, 522, 520, -1, 522, 521, 523, -1, + 523, 524, 522, -1, 524, 523, 525, -1, + 525, 526, 524, -1, 526, 525, 527, -1, + 527, 528, 526, -1, 528, 527, 529, -1, + 529, 530, 528, -1, 530, 529, 531, -1, + 531, 532, 530, -1, 532, 531, 533, -1, + 533, 534, 532, -1, 534, 533, 535, -1, + 535, 536, 534, -1, 536, 535, 537, -1, + 537, 538, 536, -1, 538, 537, 539, -1, + 539, 540, 538, -1, 540, 539, 541, -1, + 541, 542, 540, -1, 542, 541, 543, -1, + 542, 543, 544, -1, 545, 542, 544, -1, + 545, 546, 542, -1, 546, 545, 547, -1, + 545, 544, 547, -1, 506, 547, 544, -1, + 544, 548, 506, -1, 548, 544, 543, -1, + 548, 543, 549, -1, 549, 506, 548, -1, + 549, 504, 506, -1, 504, 549, 543, -1, + 543, 505, 504, -1, 543, 550, 505, -1, + 550, 543, 541, -1, 541, 551, 550, -1, + 551, 541, 539, -1, 539, 552, 551, -1, + 552, 539, 537, -1, 537, 553, 552, -1, + 553, 537, 535, -1, 535, 554, 553, -1, + 554, 535, 533, -1, 533, 555, 554, -1, + 555, 533, 531, -1, 531, 556, 555, -1, + 556, 531, 529, -1, 529, 557, 556, -1, + 557, 529, 527, -1, 527, 558, 557, -1, + 558, 527, 525, -1, 525, 559, 558, -1, + 559, 525, 523, -1, 523, 560, 559, -1, + 560, 523, 521, -1, 521, 561, 560, -1, + 561, 521, 519, -1, 519, 562, 561, -1, + 562, 519, 517, -1, 517, 563, 562, -1, + 563, 517, 515, -1, 515, 564, 563, -1, + 564, 515, 513, -1, 513, 565, 564, -1, + 565, 513, 511, -1, 511, 566, 565, -1, + 566, 511, 509, -1, 509, 567, 566, -1, + 567, 509, 508, -1, 508, 568, 567, -1, + 568, 508, 502, -1, 569, 502, 508, -1, + 502, 569, 570, -1, 570, 501, 502, -1, + 501, 570, 571, -1, 571, 499, 501, -1, + 499, 571, 572, -1, 572, 497, 499, -1, + 497, 572, 573, -1, 573, 495, 497, -1, + 495, 573, 574, -1, 574, 493, 495, -1, + 493, 574, 575, -1, 575, 491, 493, -1, + 491, 575, 576, -1, 576, 489, 491, -1, + 489, 576, 577, -1, 577, 487, 489, -1, + 487, 577, 578, -1, 578, 485, 487, -1, + 485, 578, 579, -1, 579, 483, 485, -1, + 483, 579, 580, -1, 580, 481, 483, -1, + 481, 580, 581, -1, 581, 479, 481, -1, + 479, 581, 582, -1, 582, 477, 479, -1, + 477, 582, 583, -1, 583, 475, 477, -1, + 475, 583, 584, -1, 584, 473, 475, -1, + 473, 584, 585, -1, 585, 471, 473, -1, + 471, 585, 586, -1, 586, 469, 471, -1, + 469, 586, 462, -1, 462, 467, 469, -1, + 467, 462, 461, -1, 461, 464, 467, -1, + 461, 587, 464, -1, 461, 463, 587, -1, + 588, 589, 590, -1, 588, 590, 591, -1, + 591, 592, 588, -1, 592, 591, 593, -1, + 593, 594, 592, -1, 594, 593, 595, -1, + 595, 596, 594, -1, 595, 597, 596, -1, + 597, 595, 598, -1, 598, 599, 597, -1, + 599, 598, 600, -1, 600, 601, 599, -1, + 602, 603, 604, -1, 605, 606, 603, -1, + 607, 608, 603, -1, 607, 603, 606, -1, + 606, 609, 607, -1, 606, 605, 609, -1, + 610, 611, 601, -1, 610, 612, 611, -1, + 612, 610, 613, -1, 613, 614, 612, -1, + 614, 613, 615, -1, 615, 616, 614, -1, + 616, 615, 617, -1, 617, 618, 616, -1, + 618, 617, 619, -1, 619, 620, 618, -1, + 620, 619, 621, -1, 621, 622, 620, -1, + 622, 621, 623, -1, 623, 624, 622, -1, + 624, 623, 625, -1, 625, 626, 624, -1, + 626, 625, 627, -1, 627, 628, 626, -1, + 628, 627, 629, -1, 629, 630, 628, -1, + 630, 629, 631, -1, 631, 632, 630, -1, + 632, 631, 633, -1, 633, 634, 632, -1, + 634, 633, 635, -1, 635, 636, 634, -1, + 636, 635, 637, -1, 637, 638, 636, -1, + 638, 637, 639, -1, 639, 640, 638, -1, + 640, 639, 641, -1, 641, 642, 640, -1, + 642, 641, 643, -1, 643, 644, 642, -1, + 644, 643, 645, -1, 645, 646, 644, -1, + 646, 645, 647, -1, 647, 648, 646, -1, + 648, 647, 649, -1, 649, 650, 648, -1, + 650, 649, 651, -1, 651, 652, 650, -1, + 652, 651, 653, -1, 653, 654, 652, -1, + 654, 653, 655, -1, 655, 656, 654, -1, + 656, 655, 657, -1, 657, 658, 656, -1, + 658, 657, 659, -1, 659, 660, 658, -1, + 660, 659, 661, -1, 661, 662, 660, -1, + 662, 661, 663, -1, 663, 664, 662, -1, + 664, 663, 665, -1, 665, 666, 664, -1, + 666, 665, 667, -1, 667, 668, 666, -1, + 668, 667, 669, -1, 669, 670, 668, -1, + 670, 669, 671, -1, 671, 672, 670, -1, + 672, 671, 673, -1, 673, 674, 672, -1, + 674, 673, 675, -1, 675, 676, 674, -1, + 676, 675, 677, -1, 677, 678, 676, -1, + 678, 677, 679, -1, 679, 680, 678, -1, + 680, 679, 681, -1, 681, 682, 680, -1, + 682, 681, 609, -1, 609, 683, 682, -1, + 609, 684, 683, -1, 684, 609, 605, -1, + 605, 603, 684, -1, 684, 603, 602, -1, + 602, 683, 684, -1, 602, 604, 683, -1, + 683, 604, 685, -1, 683, 685, 686, -1, + 686, 682, 683, -1, 682, 686, 687, -1, + 687, 680, 682, -1, 680, 687, 688, -1, + 688, 678, 680, -1, 678, 688, 689, -1, + 689, 676, 678, -1, 676, 689, 690, -1, + 690, 674, 676, -1, 674, 690, 691, -1, + 691, 672, 674, -1, 672, 691, 692, -1, + 692, 670, 672, -1, 670, 692, 693, -1, + 693, 668, 670, -1, 668, 693, 694, -1, + 694, 666, 668, -1, 666, 694, 695, -1, + 695, 664, 666, -1, 664, 695, 696, -1, + 696, 662, 664, -1, 662, 696, 697, -1, + 697, 660, 662, -1, 660, 697, 698, -1, + 698, 658, 660, -1, 658, 698, 699, -1, + 699, 656, 658, -1, 656, 699, 700, -1, + 700, 654, 656, -1, 654, 700, 701, -1, + 701, 652, 654, -1, 652, 701, 702, -1, + 702, 650, 652, -1, 650, 702, 703, -1, + 703, 648, 650, -1, 648, 703, 704, -1, + 704, 646, 648, -1, 646, 704, 705, -1, + 705, 644, 646, -1, 644, 705, 706, -1, + 706, 642, 644, -1, 642, 706, 707, -1, + 707, 640, 642, -1, 640, 707, 708, -1, + 708, 638, 640, -1, 638, 708, 709, -1, + 709, 636, 638, -1, 636, 709, 710, -1, + 710, 634, 636, -1, 634, 710, 711, -1, + 711, 632, 634, -1, 632, 711, 712, -1, + 712, 630, 632, -1, 630, 712, 713, -1, + 713, 628, 630, -1, 628, 713, 714, -1, + 714, 626, 628, -1, 626, 714, 715, -1, + 715, 624, 626, -1, 624, 715, 716, -1, + 716, 622, 624, -1, 622, 716, 717, -1, + 717, 620, 622, -1, 620, 717, 718, -1, + 718, 618, 620, -1, 618, 718, 719, -1, + 719, 616, 618, -1, 616, 719, 720, -1, + 720, 614, 616, -1, 614, 720, 721, -1, + 721, 612, 614, -1, 612, 721, 722, -1, + 722, 611, 612, -1, 611, 722, 723, -1, + 723, 724, 611, -1, 724, 601, 611, -1, + 724, 599, 601, -1, 599, 724, 725, -1, + 725, 597, 599, -1, 597, 725, 726, -1, + 726, 596, 597, -1, 596, 726, 727, -1, + 596, 727, 728, -1, 728, 594, 596, -1, + 594, 728, 729, -1, 729, 592, 594, -1, + 592, 729, 587, -1, 587, 588, 592, -1, + 588, 587, 463, -1, 463, 589, 588, -1, + 589, 463, 730, -1, 730, 731, 589, -1, + 731, 730, 732, -1, 732, 733, 731, -1, + 733, 732, 734, -1, 734, 735, 733, -1, + 735, 734, 736, -1, 736, 737, 735, -1, + 737, 736, 738, -1, 738, 739, 737, -1, + 739, 738, 740, -1, 740, 741, 739, -1, + 741, 740, 742, -1, 742, 743, 741, -1, + 743, 742, 744, -1, 744, 745, 743, -1, + 745, 744, 746, -1, 746, 747, 745, -1, + 747, 746, 748, -1, 748, 749, 747, -1, + 749, 748, 750, -1, 750, 751, 749, -1, + 751, 750, 752, -1, 752, 753, 751, -1, + 753, 752, 754, -1, 754, 755, 753, -1, + 755, 754, 756, -1, 756, 757, 755, -1, + 757, 756, 758, -1, 758, 759, 757, -1, + 759, 758, 760, -1, 760, 761, 759, -1, + 761, 760, 762, -1, 762, 763, 761, -1, + 763, 762, 764, -1, 764, 765, 763, -1, + 765, 764, 766, -1, 766, 767, 765, -1, + 768, 769, 770, -1, 768, 771, 769, -1, + 771, 768, 772, -1, 772, 773, 771, -1, + 773, 772, 774, -1, 774, 775, 773, -1, + 775, 774, 776, -1, 776, 777, 775, -1, + 777, 776, 778, -1, 778, 779, 777, -1, + 779, 778, 780, -1, 780, 781, 779, -1, + 781, 780, 782, -1, 782, 783, 781, -1, + 783, 782, 784, -1, 784, 785, 783, -1, + 785, 784, 786, -1, 786, 787, 785, -1, + 787, 786, 788, -1, 788, 789, 787, -1, + 789, 788, 790, -1, 790, 791, 789, -1, + 791, 790, 792, -1, 792, 793, 791, -1, + 793, 792, 794, -1, 794, 795, 793, -1, + 795, 794, 796, -1, 796, 797, 795, -1, + 797, 796, 798, -1, 798, 799, 797, -1, + 799, 798, 800, -1, 800, 801, 799, -1, + 801, 800, 767, -1, 767, 766, 801, -1, + 766, 802, 801, -1, 802, 766, 764, -1, + 764, 803, 802, -1, 803, 764, 762, -1, + 762, 804, 803, -1, 804, 762, 760, -1, + 760, 805, 804, -1, 805, 760, 758, -1, + 758, 806, 805, -1, 806, 758, 756, -1, + 756, 807, 806, -1, 807, 756, 754, -1, + 754, 808, 807, -1, 808, 754, 752, -1, + 752, 809, 808, -1, 809, 752, 750, -1, + 750, 810, 809, -1, 810, 750, 748, -1, + 748, 811, 810, -1, 811, 748, 746, -1, + 746, 812, 811, -1, 812, 746, 744, -1, + 744, 813, 812, -1, 813, 744, 742, -1, + 742, 814, 813, -1, 814, 742, 740, -1, + 740, 815, 814, -1, 815, 740, 738, -1, + 738, 816, 815, -1, 816, 738, 736, -1, + 736, 817, 816, -1, 817, 736, 734, -1, + 734, 818, 817, -1, 818, 734, 732, -1, + 732, 819, 818, -1, 819, 732, 730, -1, + 730, 820, 819, -1, 820, 730, 463, -1, + 820, 463, 462, -1, 820, 462, 586, -1, + 586, 819, 820, -1, 819, 586, 585, -1, + 585, 818, 819, -1, 818, 585, 584, -1, + 584, 817, 818, -1, 817, 584, 583, -1, + 583, 816, 817, -1, 816, 583, 582, -1, + 582, 815, 816, -1, 815, 582, 581, -1, + 581, 814, 815, -1, 814, 581, 580, -1, + 580, 813, 814, -1, 813, 580, 579, -1, + 579, 812, 813, -1, 812, 579, 578, -1, + 578, 811, 812, -1, 811, 578, 577, -1, + 577, 810, 811, -1, 810, 577, 576, -1, + 576, 809, 810, -1, 809, 576, 575, -1, + 575, 808, 809, -1, 808, 575, 574, -1, + 574, 807, 808, -1, 807, 574, 573, -1, + 573, 806, 807, -1, 806, 573, 572, -1, + 572, 805, 806, -1, 805, 572, 571, -1, + 571, 804, 805, -1, 804, 571, 570, -1, + 570, 803, 804, -1, 803, 570, 569, -1, + 569, 802, 803, -1, 802, 569, 508, -1, + 508, 507, 802, -1, 507, 801, 802, -1, + 801, 507, 510, -1, 510, 799, 801, -1, + 799, 510, 512, -1, 512, 797, 799, -1, + 797, 512, 514, -1, 514, 795, 797, -1, + 795, 514, 516, -1, 516, 793, 795, -1, + 793, 516, 518, -1, 518, 791, 793, -1, + 791, 518, 520, -1, 520, 789, 791, -1, + 789, 520, 522, -1, 522, 787, 789, -1, + 787, 522, 524, -1, 524, 785, 787, -1, + 785, 524, 526, -1, 526, 783, 785, -1, + 783, 526, 528, -1, 528, 781, 783, -1, + 781, 528, 530, -1, 530, 779, 781, -1, + 779, 530, 532, -1, 532, 777, 779, -1, + 777, 532, 534, -1, 534, 775, 777, -1, + 775, 534, 536, -1, 536, 773, 775, -1, + 773, 536, 538, -1, 538, 771, 773, -1, + 771, 538, 540, -1, 540, 769, 771, -1, + 769, 540, 542, -1, 769, 542, 546, -1, + 546, 821, 769, -1, 821, 546, 547, -1, + 821, 547, 822, -1, 822, 769, 821, -1, + 822, 770, 769, -1, 770, 822, 547, -1, + 770, 547, 823, -1, 823, 768, 770, -1, + 823, 824, 768, -1, 823, 825, 824, -1, + 825, 823, 547, -1, 826, 827, 825, -1, + 828, 829, 830, -1, 831, 832, 833, -1, + 834, 835, 836, -1, 837, 838, 839, -1, + 837, 839, 840, -1, 840, 841, 837, -1, + 841, 840, 842, -1, 842, 843, 841, -1, + 844, 842, 845, -1, 844, 846, 842, -1, + 846, 843, 842, -1, 846, 847, 843, -1, + 846, 844, 847, -1, 844, 845, 847, -1, + 847, 845, 836, -1, 848, 836, 835, -1, + 835, 849, 848, -1, 835, 850, 849, -1, + 835, 834, 850, -1, 850, 834, 851, -1, + 851, 852, 850, -1, 852, 851, 853, -1, + 853, 854, 852, -1, 854, 853, 855, -1, + 855, 856, 854, -1, 856, 855, 831, -1, + 831, 833, 856, -1, 857, 858, 859, -1, + 858, 857, 860, -1, 860, 861, 858, -1, + 861, 860, 862, -1, 862, 863, 861, -1, + 863, 862, 864, -1, 864, 865, 863, -1, + 865, 864, 866, -1, 866, 867, 865, -1, + 867, 866, 868, -1, 868, 869, 867, -1, + 869, 868, 870, -1, 870, 871, 869, -1, + 871, 870, 872, -1, 872, 873, 871, -1, + 873, 872, 874, -1, 874, 875, 873, -1, + 875, 874, 876, -1, 876, 877, 875, -1, + 877, 876, 878, -1, 878, 879, 877, -1, + 879, 878, 880, -1, 880, 881, 879, -1, + 881, 880, 882, -1, 882, 883, 881, -1, + 883, 882, 884, -1, 884, 885, 883, -1, + 885, 884, 886, -1, 886, 887, 885, -1, + 887, 886, 888, -1, 888, 889, 887, -1, + 889, 888, 890, -1, 890, 891, 889, -1, + 891, 890, 892, -1, 892, 893, 891, -1, + 893, 892, 894, -1, 895, 896, 897, -1, + 897, 898, 895, -1, 898, 897, 899, -1, + 899, 900, 898, -1, 900, 899, 901, -1, + 901, 902, 900, -1, 902, 901, 903, -1, + 903, 904, 902, -1, 904, 903, 905, -1, + 905, 906, 904, -1, 906, 894, 907, -1, + 907, 904, 906, -1, 904, 907, 908, -1, + 908, 902, 904, -1, 902, 908, 909, -1, + 909, 900, 902, -1, 900, 909, 910, -1, + 910, 898, 900, -1, 898, 910, 911, -1, + 911, 895, 898, -1, 895, 911, 912, -1, + 912, 913, 895, -1, 914, 895, 913, -1, + 914, 896, 895, -1, 896, 914, 915, -1, + 914, 913, 915, -1, 916, 915, 913, -1, + 916, 913, 912, -1, 916, 912, 917, -1, + 917, 915, 916, -1, 917, 918, 915, -1, + 917, 912, 918, -1, 919, 918, 912, -1, + 912, 920, 919, -1, 920, 912, 911, -1, + 911, 921, 920, -1, 921, 911, 910, -1, + 910, 922, 921, -1, 922, 910, 909, -1, + 909, 923, 922, -1, 923, 909, 908, -1, + 908, 924, 923, -1, 924, 908, 907, -1, + 907, 925, 924, -1, 925, 907, 894, -1, + 894, 926, 925, -1, 926, 894, 892, -1, + 892, 927, 926, -1, 927, 892, 890, -1, + 890, 928, 927, -1, 928, 890, 888, -1, + 888, 929, 928, -1, 929, 888, 886, -1, + 886, 930, 929, -1, 930, 886, 884, -1, + 884, 931, 930, -1, 931, 884, 882, -1, + 882, 932, 931, -1, 932, 882, 880, -1, + 880, 933, 932, -1, 933, 880, 878, -1, + 878, 934, 933, -1, 934, 878, 876, -1, + 876, 935, 934, -1, 935, 876, 874, -1, + 874, 936, 935, -1, 936, 874, 872, -1, + 872, 937, 936, -1, 937, 872, 870, -1, + 870, 938, 937, -1, 938, 870, 868, -1, + 868, 939, 938, -1, 939, 868, 866, -1, + 866, 940, 939, -1, 940, 866, 864, -1, + 864, 941, 940, -1, 941, 864, 862, -1, + 862, 942, 941, -1, 942, 862, 860, -1, + 860, 943, 942, -1, 943, 860, 857, -1, + 857, 944, 943, -1, 857, 859, 944, -1, + 945, 944, 859, -1, 945, 859, 946, -1, + 946, 947, 945, -1, 947, 946, 948, -1, + 948, 949, 947, -1, 949, 948, 950, -1, + 950, 951, 949, -1, 951, 950, 952, -1, + 952, 953, 951, -1, 952, 954, 953, -1, + 954, 952, 955, -1, 955, 956, 954, -1, + 956, 955, 957, -1, 957, 958, 956, -1, + 958, 957, 959, -1, 959, 960, 958, -1, + 960, 961, 962, -1, 960, 959, 961, -1, + 963, 964, 965, -1, 964, 963, 966, -1, + 966, 967, 964, -1, 967, 966, 968, -1, + 968, 969, 967, -1, 969, 968, 970, -1, + 970, 971, 969, -1, 971, 970, 972, -1, + 972, 973, 971, -1, 973, 972, 974, -1, + 974, 975, 973, -1, 975, 974, 976, -1, + 976, 977, 975, -1, 977, 976, 978, -1, + 978, 979, 977, -1, 979, 978, 980, -1, + 980, 981, 979, -1, 981, 980, 982, -1, + 982, 983, 981, -1, 983, 982, 984, -1, + 984, 985, 983, -1, 985, 984, 986, -1, + 986, 987, 985, -1, 987, 986, 988, -1, + 988, 989, 987, -1, 989, 988, 990, -1, + 990, 991, 989, -1, 991, 990, 992, -1, + 992, 993, 991, -1, 993, 992, 994, -1, + 994, 995, 993, -1, 995, 994, 996, -1, + 996, 997, 995, -1, 997, 996, 998, -1, + 998, 999, 997, -1, 1000, 1001, 1002, -1, + 1000, 1002, 1003, -1, 1003, 1004, 1000, -1, + 1004, 1003, 1005, -1, 1005, 1006, 1004, -1, + 1006, 1005, 1007, -1, 1007, 1008, 1006, -1, + 1008, 1007, 1009, -1, 1009, 1010, 1008, -1, + 1009, 1011, 1010, -1, 1011, 1009, 1012, -1, + 1012, 1013, 1011, -1, 1013, 1012, 1014, -1, + 1014, 1015, 1013, -1, 1015, 1014, 1016, -1, + 1016, 1017, 1015, -1, 1017, 1016, 1018, -1, + 1018, 1019, 1017, -1, 1019, 1018, 1020, -1, + 1020, 1021, 1019, -1, 1021, 1020, 1022, -1, + 1022, 1023, 1021, -1, 1023, 1022, 1024, -1, + 1024, 1025, 1023, -1, 1025, 1024, 1026, -1, + 1026, 1027, 1025, -1, 1027, 1026, 1028, -1, + 1028, 1029, 1027, -1, 1029, 1028, 1030, -1, + 1030, 1031, 1029, -1, 1031, 1030, 1032, -1, + 1032, 1033, 1031, -1, 1033, 1032, 1034, -1, + 1034, 1035, 1033, -1, 1035, 1034, 1036, -1, + 1036, 1037, 1035, -1, 1037, 1036, 1038, -1, + 1038, 1039, 1037, -1, 1039, 1038, 1040, -1, + 1040, 1041, 1039, -1, 1041, 1040, 1042, -1, + 1042, 1043, 1041, -1, 1043, 1042, 1044, -1, + 1044, 1045, 1043, -1, 1045, 1044, 1046, -1, + 1046, 1047, 1045, -1, 1047, 1046, 1048, -1, + 1048, 1049, 1047, -1, 1049, 1048, 1050, -1, + 1050, 1051, 1049, -1, 1051, 1050, 1052, -1, + 1052, 1053, 1051, -1, 1053, 1052, 1054, -1, + 1054, 1055, 1053, -1, 1055, 1054, 1056, -1, + 1055, 1056, 999, -1, 1055, 999, 998, -1, + 998, 1053, 1055, -1, 1053, 998, 996, -1, + 996, 1051, 1053, -1, 1051, 996, 994, -1, + 994, 1049, 1051, -1, 1049, 994, 992, -1, + 992, 1047, 1049, -1, 1047, 992, 990, -1, + 990, 1045, 1047, -1, 1045, 990, 988, -1, + 988, 1043, 1045, -1, 1043, 988, 986, -1, + 986, 1041, 1043, -1, 1041, 986, 984, -1, + 984, 1039, 1041, -1, 1039, 984, 982, -1, + 982, 1037, 1039, -1, 1037, 982, 980, -1, + 980, 1035, 1037, -1, 1035, 980, 978, -1, + 978, 1033, 1035, -1, 1033, 978, 976, -1, + 976, 1031, 1033, -1, 1031, 976, 974, -1, + 974, 1029, 1031, -1, 1029, 974, 972, -1, + 972, 1027, 1029, -1, 1027, 972, 970, -1, + 970, 1025, 1027, -1, 1025, 970, 968, -1, + 968, 1023, 1025, -1, 1023, 968, 966, -1, + 966, 1021, 1023, -1, 1021, 966, 963, -1, + 963, 1019, 1021, -1, 963, 965, 1019, -1, + 1057, 1019, 965, -1, 1057, 1017, 1019, -1, + 1017, 1057, 961, -1, 961, 1015, 1017, -1, + 1015, 961, 959, -1, 959, 1013, 1015, -1, + 1013, 959, 957, -1, 957, 1011, 1013, -1, + 1011, 957, 955, -1, 955, 1010, 1011, -1, + 1010, 955, 952, -1, 1010, 952, 950, -1, + 950, 1008, 1010, -1, 1008, 950, 948, -1, + 948, 1006, 1008, -1, 1006, 948, 946, -1, + 946, 1004, 1006, -1, 1004, 946, 859, -1, + 859, 1000, 1004, -1, 1000, 859, 858, -1, + 858, 1001, 1000, -1, 1001, 858, 861, -1, + 861, 1058, 1001, -1, 1058, 861, 863, -1, + 863, 1059, 1058, -1, 1059, 863, 865, -1, + 865, 1060, 1059, -1, 1060, 865, 867, -1, + 867, 1061, 1060, -1, 1061, 867, 869, -1, + 869, 1062, 1061, -1, 1062, 869, 871, -1, + 871, 1063, 1062, -1, 1063, 871, 873, -1, + 873, 1064, 1063, -1, 1064, 873, 875, -1, + 875, 1065, 1064, -1, 1065, 875, 877, -1, + 877, 1066, 1065, -1, 1066, 877, 879, -1, + 879, 1067, 1066, -1, 1067, 879, 881, -1, + 881, 1068, 1067, -1, 1068, 881, 883, -1, + 883, 1069, 1068, -1, 1069, 883, 885, -1, + 885, 1070, 1069, -1, 1070, 885, 887, -1, + 887, 1071, 1070, -1, 1071, 887, 889, -1, + 889, 1072, 1071, -1, 1072, 889, 891, -1, + 891, 1073, 1072, -1, 1073, 891, 893, -1, + 893, 1074, 1073, -1, 1074, 893, 894, -1, + 894, 906, 1074, -1, 1075, 1074, 906, -1, + 1074, 1075, 1076, -1, 1076, 1073, 1074, -1, + 1073, 1076, 1077, -1, 1077, 1072, 1073, -1, + 1072, 1077, 1078, -1, 1078, 1071, 1072, -1, + 1071, 1078, 1079, -1, 1079, 1070, 1071, -1, + 1070, 1079, 1080, -1, 1080, 1069, 1070, -1, + 1069, 1080, 1081, -1, 1081, 1068, 1069, -1, + 1068, 1081, 1082, -1, 1082, 1067, 1068, -1, + 1067, 1082, 1083, -1, 1083, 1066, 1067, -1, + 1066, 1083, 1084, -1, 1084, 1065, 1066, -1, + 1065, 1084, 1085, -1, 1085, 1064, 1065, -1, + 1064, 1085, 1086, -1, 1086, 1063, 1064, -1, + 1063, 1086, 1087, -1, 1087, 1062, 1063, -1, + 1062, 1087, 1088, -1, 1088, 1061, 1062, -1, + 1061, 1088, 1089, -1, 1089, 1060, 1061, -1, + 1060, 1089, 1090, -1, 1090, 1059, 1060, -1, + 1059, 1090, 1091, -1, 1091, 1058, 1059, -1, + 1058, 1091, 1092, -1, 1092, 1001, 1058, -1, + 1092, 1002, 1001, -1, 1092, 1093, 1002, -1, + 1093, 1092, 1091, -1, 1091, 1094, 1093, -1, + 1094, 1091, 1090, -1, 1090, 1095, 1094, -1, + 1095, 1090, 1089, -1, 1089, 1096, 1095, -1, + 1096, 1089, 1088, -1, 1088, 1097, 1096, -1, + 1097, 1088, 1087, -1, 1087, 1098, 1097, -1, + 1098, 1087, 1086, -1, 1086, 1099, 1098, -1, + 1099, 1086, 1085, -1, 1085, 1100, 1099, -1, + 1100, 1085, 1084, -1, 1084, 1101, 1100, -1, + 1101, 1084, 1083, -1, 1083, 1102, 1101, -1, + 1102, 1083, 1082, -1, 1082, 1103, 1102, -1, + 1103, 1082, 1081, -1, 1081, 1104, 1103, -1, + 1104, 1081, 1080, -1, 1080, 1105, 1104, -1, + 1105, 1080, 1079, -1, 1079, 1106, 1105, -1, + 1106, 1079, 1078, -1, 1078, 1107, 1106, -1, + 1107, 1078, 1077, -1, 1077, 1108, 1107, -1, + 1108, 1077, 1076, -1, 1076, 1109, 1108, -1, + 1109, 1076, 1075, -1, 1075, 1110, 1109, -1, + 1110, 1075, 906, -1, 906, 905, 1110, -1, + 833, 1111, 1110, -1, 833, 1110, 905, -1, + 905, 856, 833, -1, 856, 905, 903, -1, + 903, 854, 856, -1, 854, 903, 901, -1, + 901, 852, 854, -1, 852, 901, 899, -1, + 899, 850, 852, -1, 850, 899, 897, -1, + 897, 849, 850, -1, 1112, 849, 897, -1, + 1112, 848, 849, -1, 1112, 1113, 848, -1, + 1113, 1112, 897, -1, 1113, 897, 896, -1, + 1113, 896, 915, -1, 915, 848, 1113, -1, + 1114, 1115, 1116, -1, 1114, 1117, 1115, -1, + 1118, 1119, 1120, -1, 1118, 1121, 1119, -1, + 1118, 1122, 1121, -1, 1118, 1120, 1122, -1, + 1123, 1124, 1125, -1, 1126, 1124, 1127, -1, + 1126, 1125, 1124, -1, 1126, 1128, 1125, -1, + 1126, 1127, 1128, -1, 1129, 1130, 1131, -1, + 1132, 1133, 1134, -1, 1135, 1136, 1133, -1, + 1136, 1135, 1137, -1, 1138, 1139, 1140, -1, + 1141, 1142, 1143, -1, 1142, 1141, 1144, -1, + 1145, 1144, 1141, -1, 1141, 1146, 1145, -1, + 1141, 1143, 1146, -1, 1147, 1143, 1148, -1, + 1147, 1146, 1143, -1, 1147, 1145, 1146, -1, + 1147, 1148, 1145, -1, 1149, 1145, 1148, -1, + 1150, 1151, 1152, -1, 1151, 1150, 1149, -1, + 1151, 1149, 1148, -1, 1148, 1152, 1151, -1, + 1152, 1148, 1143, -1, 1153, 1154, 1155, -1, + 1155, 1156, 1153, -1, 1156, 1157, 1158, -1, + 1157, 1156, 1159, -1, 1159, 1160, 1157, -1, + 1160, 1159, 1161, -1, 1161, 1162, 1160, -1, + 1161, 1163, 1162, -1, 1164, 1165, 1163, -1, + 1163, 1166, 1164, -1, 1166, 1163, 1161, -1, + 1161, 1167, 1166, -1, 1167, 1161, 1159, -1, + 1159, 1168, 1167, -1, 1168, 1159, 1156, -1, + 1156, 1155, 1168, -1, 1169, 1170, 1171, -1, + 1171, 1172, 1169, -1, 1172, 1171, 1173, -1, + 1173, 1174, 1172, -1, 1174, 1173, 1175, -1, + 1175, 1176, 1174, -1, 1176, 1175, 1177, -1, + 1177, 1178, 1176, -1, 1178, 1177, 1179, -1, + 1180, 1178, 1179, -1, 1180, 1181, 1178, -1, + 1181, 1180, 1182, -1, 1180, 1179, 1182, -1, + 1179, 1183, 1182, -1, 1183, 1179, 1177, -1, + 1183, 1177, 1184, -1, 1177, 1155, 1184, -1, + 1155, 1177, 1175, -1, 1175, 1168, 1155, -1, + 1168, 1175, 1173, -1, 1173, 1167, 1168, -1, + 1167, 1173, 1171, -1, 1171, 1166, 1167, -1, + 1166, 1171, 1170, -1, 1170, 1164, 1166, -1, + 1170, 1185, 1164, -1, 1170, 1169, 1185, -1, + 1186, 1187, 1188, -1, 1189, 1190, 1191, -1, + 1192, 1193, 1194, -1, 1195, 1196, 1197, -1, + 1195, 1197, 1198, -1, 1198, 1199, 1195, -1, + 1199, 1198, 1200, -1, 1200, 1201, 1199, -1, + 1201, 1200, 1202, -1, 1202, 1203, 1201, -1, + 1203, 1202, 1204, -1, 1204, 1205, 1203, -1, + 1205, 1204, 1206, -1, 1206, 1207, 1205, -1, + 1207, 1206, 1208, -1, 1208, 1209, 1207, -1, + 1209, 1208, 1210, -1, 1210, 1211, 1209, -1, + 1211, 1210, 1212, -1, 1212, 1213, 1211, -1, + 1213, 1212, 1214, -1, 1214, 1215, 1213, -1, + 1215, 1214, 1216, -1, 1216, 1217, 1215, -1, + 1217, 1216, 1218, -1, 1218, 1219, 1217, -1, + 1219, 1218, 1220, -1, 1220, 1221, 1219, -1, + 1221, 1220, 1222, -1, 1222, 1223, 1221, -1, + 1223, 1222, 1224, -1, 1223, 1224, 1225, -1, + 1225, 1226, 1223, -1, 1226, 1225, 1227, -1, + 1227, 1228, 1226, -1, 1228, 1227, 1229, -1, + 1229, 1230, 1228, -1, 1230, 1229, 1231, -1, + 1231, 1232, 1230, -1, 1232, 1231, 1233, -1, + 1233, 1234, 1232, -1, 1234, 1233, 1235, -1, + 1235, 1236, 1234, -1, 1236, 1235, 1237, -1, + 1237, 1238, 1236, -1, 1238, 1237, 1239, -1, + 1239, 1240, 1238, -1, 1240, 1239, 1241, -1, + 1241, 1242, 1240, -1, 1242, 1241, 1243, -1, + 1243, 1244, 1242, -1, 1244, 1243, 1245, -1, + 1245, 1246, 1244, -1, 1246, 1245, 1247, -1, + 1247, 1248, 1246, -1, 1248, 1247, 1249, -1, + 1249, 1250, 1248, -1, 1250, 1249, 1251, -1, + 1250, 1251, 1252, -1, 1253, 1252, 1251, -1, + 1252, 1253, 1254, -1, 1255, 1256, 1257, -1, + 1258, 1259, 1260, -1, 1261, 1262, 1263, -1, + 1264, 1263, 1262, -1, 1265, 1263, 1264, -1, + 1265, 1264, 1266, -1, 1266, 1267, 1265, -1, + 1268, 1267, 1266, -1, 1269, 1270, 1271, -1, + 1271, 1272, 1269, -1, 1272, 1271, 1273, -1, + 1273, 1274, 1272, -1, 1274, 1273, 1275, -1, + 1275, 1276, 1274, -1, 1276, 1275, 1277, -1, + 1277, 1278, 1276, -1, 1278, 1277, 1279, -1, + 1279, 1280, 1278, -1, 1280, 1279, 1281, -1, + 1281, 1282, 1280, -1, 1282, 1281, 1283, -1, + 1283, 1284, 1282, -1, 1283, 1285, 1284, -1, + 1285, 1283, 1286, -1, 1286, 1287, 1285, -1, + 1287, 1286, 1288, -1, 1288, 1289, 1287, -1, + 1289, 1288, 1290, -1, 1290, 1291, 1289, -1, + 1291, 1290, 1292, -1, 1292, 1293, 1291, -1, + 1293, 1292, 1294, -1, 1294, 1295, 1293, -1, + 1295, 1294, 1296, -1, 1296, 1297, 1295, -1, + 1298, 1299, 1300, -1, 1298, 1267, 1299, -1, + 1298, 1301, 1267, -1, 1298, 1300, 1301, -1, + 1302, 1301, 1300, -1, 1302, 1300, 1297, -1, + 1297, 1296, 1302, -1, 1303, 1304, 1305, -1, + 1304, 1306, 1305, -1, 1302, 1305, 1306, -1, + 1305, 1302, 1296, -1, 1296, 1307, 1305, -1, + 1307, 1296, 1294, -1, 1294, 1308, 1307, -1, + 1308, 1294, 1292, -1, 1292, 1309, 1308, -1, + 1309, 1292, 1290, -1, 1290, 1310, 1309, -1, + 1310, 1290, 1288, -1, 1288, 1311, 1310, -1, + 1311, 1288, 1286, -1, 1286, 1312, 1311, -1, + 1312, 1286, 1283, -1, 1312, 1283, 1281, -1, + 1281, 1313, 1312, -1, 1313, 1281, 1279, -1, + 1279, 1314, 1313, -1, 1314, 1279, 1277, -1, + 1277, 1315, 1314, -1, 1315, 1277, 1275, -1, + 1275, 1316, 1315, -1, 1316, 1275, 1273, -1, + 1273, 1317, 1316, -1, 1317, 1273, 1271, -1, + 1271, 1318, 1317, -1, 1318, 1271, 1270, -1, + 1270, 1319, 1318, -1, 1320, 1319, 1270, -1, + 1320, 1270, 1321, -1, 1270, 1322, 1321, -1, + 1270, 1269, 1322, -1, 1322, 1323, 1324, -1, + 1322, 1325, 1323, -1, 1325, 1322, 1269, -1, + 1269, 1326, 1325, -1, 1326, 1269, 1272, -1, + 1272, 1327, 1326, -1, 1327, 1272, 1274, -1, + 1274, 1328, 1327, -1, 1328, 1274, 1276, -1, + 1276, 1329, 1328, -1, 1329, 1276, 1278, -1, + 1278, 1330, 1329, -1, 1330, 1278, 1280, -1, + 1280, 1331, 1330, -1, 1331, 1280, 1282, -1, + 1282, 1332, 1331, -1, 1332, 1282, 1284, -1, + 1284, 1333, 1332, -1, 1284, 1334, 1333, -1, + 1334, 1284, 1285, -1, 1285, 1335, 1334, -1, + 1335, 1285, 1287, -1, 1287, 1336, 1335, -1, + 1336, 1287, 1289, -1, 1289, 1337, 1336, -1, + 1337, 1289, 1291, -1, 1291, 1338, 1337, -1, + 1338, 1291, 1293, -1, 1293, 1339, 1338, -1, + 1339, 1293, 1295, -1, 1295, 1340, 1339, -1, + 1340, 1295, 1297, -1, 1297, 1341, 1340, -1, + 1341, 1297, 1300, -1, 1300, 1342, 1341, -1, + 1300, 1299, 1342, -1, 1343, 1342, 1299, -1, + 1343, 1299, 1267, -1, 1343, 1267, 1268, -1, + 1268, 1342, 1343, -1, 1268, 1266, 1342, -1, + 1342, 1266, 1264, -1, 1342, 1264, 1344, -1, + 1344, 1341, 1342, -1, 1341, 1344, 1345, -1, + 1345, 1340, 1341, -1, 1340, 1345, 1346, -1, + 1346, 1339, 1340, -1, 1339, 1346, 1347, -1, + 1347, 1338, 1339, -1, 1338, 1347, 1348, -1, + 1348, 1337, 1338, -1, 1337, 1348, 1349, -1, + 1349, 1336, 1337, -1, 1336, 1349, 1350, -1, + 1350, 1335, 1336, -1, 1335, 1350, 1351, -1, + 1351, 1334, 1335, -1, 1334, 1351, 1352, -1, + 1352, 1333, 1334, -1, 1333, 1352, 1353, -1, + 1333, 1353, 1354, -1, 1354, 1332, 1333, -1, + 1332, 1354, 1355, -1, 1355, 1331, 1332, -1, + 1331, 1355, 1356, -1, 1356, 1330, 1331, -1, + 1330, 1356, 1357, -1, 1357, 1329, 1330, -1, + 1329, 1357, 1358, -1, 1358, 1328, 1329, -1, + 1328, 1358, 1359, -1, 1359, 1327, 1328, -1, + 1327, 1359, 1360, -1, 1360, 1326, 1327, -1, + 1326, 1360, 1361, -1, 1361, 1325, 1326, -1, + 1325, 1361, 1362, -1, 1362, 1323, 1325, -1, + 1323, 1362, 1260, -1, 1323, 1260, 1259, -1, + 1363, 1323, 1259, -1, 1363, 1364, 1323, -1, + 1364, 1324, 1323, -1, 1364, 1365, 1324, -1, + 1364, 1363, 1365, -1, 1363, 1259, 1365, -1, + 1259, 1258, 1365, -1, 1366, 1365, 1258, -1, + 1258, 1367, 1366, -1, 1258, 1260, 1367, -1, + 1260, 1368, 1367, -1, 1260, 1369, 1368, -1, + 1369, 1260, 1362, -1, 1362, 1370, 1369, -1, + 1370, 1362, 1361, -1, 1361, 1371, 1370, -1, + 1371, 1361, 1360, -1, 1360, 1372, 1371, -1, + 1372, 1360, 1359, -1, 1359, 1373, 1372, -1, + 1373, 1359, 1358, -1, 1358, 1374, 1373, -1, + 1374, 1358, 1357, -1, 1357, 1375, 1374, -1, + 1375, 1357, 1356, -1, 1356, 1376, 1375, -1, + 1376, 1356, 1355, -1, 1355, 1377, 1376, -1, + 1377, 1355, 1354, -1, 1354, 1378, 1377, -1, + 1378, 1354, 1353, -1, 1353, 1379, 1378, -1, + 1353, 1380, 1379, -1, 1380, 1353, 1352, -1, + 1352, 1381, 1380, -1, 1381, 1352, 1351, -1, + 1351, 1382, 1381, -1, 1382, 1351, 1350, -1, + 1350, 1383, 1382, -1, 1383, 1350, 1349, -1, + 1349, 1384, 1383, -1, 1384, 1349, 1348, -1, + 1348, 1385, 1384, -1, 1385, 1348, 1347, -1, + 1347, 1386, 1385, -1, 1386, 1347, 1346, -1, + 1346, 1387, 1386, -1, 1387, 1346, 1345, -1, + 1345, 1388, 1387, -1, 1388, 1345, 1344, -1, + 1344, 1389, 1388, -1, 1389, 1344, 1264, -1, + 1264, 1262, 1389, -1, 1262, 1390, 1391, -1, + 1262, 1391, 1392, -1, 1392, 1389, 1262, -1, + 1389, 1392, 1393, -1, 1393, 1388, 1389, -1, + 1388, 1393, 1394, -1, 1394, 1387, 1388, -1, + 1387, 1394, 1395, -1, 1395, 1386, 1387, -1, + 1386, 1395, 1396, -1, 1396, 1385, 1386, -1, + 1385, 1396, 1397, -1, 1397, 1384, 1385, -1, + 1384, 1397, 1398, -1, 1398, 1383, 1384, -1, + 1383, 1398, 1399, -1, 1399, 1382, 1383, -1, + 1382, 1399, 1400, -1, 1400, 1381, 1382, -1, + 1381, 1400, 1401, -1, 1401, 1380, 1381, -1, + 1380, 1401, 1402, -1, 1402, 1379, 1380, -1, + 1379, 1402, 1403, -1, 1379, 1403, 1404, -1, + 1404, 1378, 1379, -1, 1378, 1404, 1405, -1, + 1405, 1377, 1378, -1, 1377, 1405, 1406, -1, + 1406, 1376, 1377, -1, 1376, 1406, 1407, -1, + 1407, 1375, 1376, -1, 1375, 1407, 1408, -1, + 1408, 1374, 1375, -1, 1374, 1408, 1409, -1, + 1409, 1373, 1374, -1, 1373, 1409, 1410, -1, + 1410, 1372, 1373, -1, 1372, 1410, 1411, -1, + 1411, 1371, 1372, -1, 1371, 1411, 1412, -1, + 1412, 1370, 1371, -1, 1370, 1412, 1413, -1, + 1413, 1369, 1370, -1, 1369, 1413, 1414, -1, + 1414, 1368, 1369, -1, 1368, 1414, 1257, -1, + 1368, 1257, 1256, -1, 1415, 1368, 1256, -1, + 1415, 1416, 1368, -1, 1416, 1367, 1368, -1, + 1416, 1366, 1367, -1, 1416, 1415, 1366, -1, + 1415, 1256, 1366, -1, 1256, 1255, 1366, -1, + 1254, 1366, 1255, -1, 1255, 1417, 1254, -1, + 1255, 1257, 1417, -1, 1417, 1257, 1418, -1, + 1418, 1254, 1417, -1, 1418, 1419, 1254, -1, + 1419, 1252, 1254, -1, 1419, 1250, 1252, -1, + 1419, 1418, 1250, -1, 1250, 1418, 1257, -1, + 1257, 1248, 1250, -1, 1248, 1257, 1414, -1, + 1414, 1246, 1248, -1, 1246, 1414, 1413, -1, + 1413, 1244, 1246, -1, 1244, 1413, 1412, -1, + 1412, 1242, 1244, -1, 1242, 1412, 1411, -1, + 1411, 1240, 1242, -1, 1240, 1411, 1410, -1, + 1410, 1238, 1240, -1, 1238, 1410, 1409, -1, + 1409, 1236, 1238, -1, 1236, 1409, 1408, -1, + 1408, 1234, 1236, -1, 1234, 1408, 1407, -1, + 1407, 1232, 1234, -1, 1232, 1407, 1406, -1, + 1406, 1230, 1232, -1, 1230, 1406, 1405, -1, + 1405, 1228, 1230, -1, 1228, 1405, 1404, -1, + 1404, 1226, 1228, -1, 1226, 1404, 1403, -1, + 1403, 1223, 1226, -1, 1403, 1221, 1223, -1, + 1221, 1403, 1402, -1, 1402, 1219, 1221, -1, + 1219, 1402, 1401, -1, 1401, 1217, 1219, -1, + 1217, 1401, 1400, -1, 1400, 1215, 1217, -1, + 1215, 1400, 1399, -1, 1399, 1213, 1215, -1, + 1213, 1399, 1398, -1, 1398, 1211, 1213, -1, + 1211, 1398, 1397, -1, 1397, 1209, 1211, -1, + 1209, 1397, 1396, -1, 1396, 1207, 1209, -1, + 1207, 1396, 1395, -1, 1395, 1205, 1207, -1, + 1205, 1395, 1394, -1, 1394, 1203, 1205, -1, + 1203, 1394, 1393, -1, 1393, 1201, 1203, -1, + 1201, 1393, 1392, -1, 1392, 1199, 1201, -1, + 1199, 1392, 1391, -1, 1391, 1195, 1199, -1, + 1195, 1391, 1420, -1, 1421, 1420, 1391, -1, + 1420, 1421, 1422, -1, 1420, 1422, 1423, -1, + 1423, 1195, 1420, -1, 1423, 1196, 1195, -1, + 1196, 1423, 1422, -1, 1196, 1422, 1424, -1, + 1424, 1197, 1196, -1, 1424, 1425, 1197, -1, + 1425, 1426, 1197, -1, 1192, 1197, 1426, -1, + 1197, 1192, 1427, -1, 1427, 1198, 1197, -1, + 1198, 1427, 1428, -1, 1428, 1200, 1198, -1, + 1200, 1428, 1429, -1, 1429, 1202, 1200, -1, + 1202, 1429, 1430, -1, 1430, 1204, 1202, -1, + 1204, 1430, 1431, -1, 1431, 1206, 1204, -1, + 1206, 1431, 1432, -1, 1432, 1208, 1206, -1, + 1208, 1432, 1433, -1, 1433, 1210, 1208, -1, + 1210, 1433, 1434, -1, 1434, 1212, 1210, -1, + 1212, 1434, 1435, -1, 1435, 1214, 1212, -1, + 1214, 1435, 1436, -1, 1436, 1216, 1214, -1, + 1216, 1436, 1437, -1, 1437, 1218, 1216, -1, + 1218, 1437, 1438, -1, 1438, 1220, 1218, -1, + 1220, 1438, 1439, -1, 1439, 1222, 1220, -1, + 1222, 1439, 1440, -1, 1440, 1224, 1222, -1, + 1224, 1440, 1441, -1, 1224, 1441, 1442, -1, + 1442, 1225, 1224, -1, 1225, 1442, 1443, -1, + 1443, 1227, 1225, -1, 1227, 1443, 1444, -1, + 1444, 1229, 1227, -1, 1229, 1444, 1445, -1, + 1445, 1231, 1229, -1, 1231, 1445, 1446, -1, + 1446, 1233, 1231, -1, 1233, 1446, 1447, -1, + 1447, 1235, 1233, -1, 1235, 1447, 1448, -1, + 1448, 1237, 1235, -1, 1237, 1448, 1449, -1, + 1449, 1239, 1237, -1, 1239, 1449, 1450, -1, + 1450, 1241, 1239, -1, 1241, 1450, 1451, -1, + 1451, 1243, 1241, -1, 1243, 1451, 1452, -1, + 1452, 1245, 1243, -1, 1245, 1452, 1453, -1, + 1453, 1247, 1245, -1, 1247, 1453, 1454, -1, + 1454, 1249, 1247, -1, 1249, 1454, 1455, -1, + 1455, 1251, 1249, -1, 1251, 1455, 1456, -1, + 1456, 1457, 1251, -1, 1458, 1457, 1456, -1, + 1458, 1456, 1459, -1, 1456, 1460, 1459, -1, + 1456, 1461, 1460, -1, 1461, 1456, 1455, -1, + 1455, 1462, 1461, -1, 1462, 1455, 1454, -1, + 1454, 1463, 1462, -1, 1463, 1454, 1453, -1, + 1453, 1464, 1463, -1, 1464, 1453, 1452, -1, + 1452, 1465, 1464, -1, 1465, 1452, 1451, -1, + 1451, 1466, 1465, -1, 1466, 1451, 1450, -1, + 1450, 1467, 1466, -1, 1467, 1450, 1449, -1, + 1449, 1468, 1467, -1, 1468, 1449, 1448, -1, + 1448, 1469, 1468, -1, 1469, 1448, 1447, -1, + 1447, 1470, 1469, -1, 1470, 1447, 1446, -1, + 1446, 1471, 1470, -1, 1471, 1446, 1445, -1, + 1445, 1472, 1471, -1, 1472, 1445, 1444, -1, + 1444, 1473, 1472, -1, 1473, 1444, 1443, -1, + 1443, 1474, 1473, -1, 1474, 1443, 1442, -1, + 1442, 1475, 1474, -1, 1475, 1442, 1441, -1, + 1441, 1476, 1475, -1, 1441, 1477, 1476, -1, + 1477, 1441, 1440, -1, 1440, 1478, 1477, -1, + 1478, 1440, 1439, -1, 1439, 1479, 1478, -1, + 1479, 1439, 1438, -1, 1438, 1480, 1479, -1, + 1480, 1438, 1437, -1, 1437, 1481, 1480, -1, + 1481, 1437, 1436, -1, 1436, 1482, 1481, -1, + 1482, 1436, 1435, -1, 1435, 1483, 1482, -1, + 1483, 1435, 1434, -1, 1434, 1484, 1483, -1, + 1484, 1434, 1433, -1, 1433, 1485, 1484, -1, + 1485, 1433, 1432, -1, 1432, 1486, 1485, -1, + 1486, 1432, 1431, -1, 1431, 1487, 1486, -1, + 1487, 1431, 1430, -1, 1430, 1488, 1487, -1, + 1488, 1430, 1429, -1, 1429, 1489, 1488, -1, + 1489, 1429, 1428, -1, 1428, 1490, 1489, -1, + 1490, 1428, 1427, -1, 1427, 1491, 1490, -1, + 1491, 1427, 1192, -1, 1192, 1194, 1491, -1, + 1492, 1493, 1194, -1, 1494, 1194, 1493, -1, + 1194, 1494, 1495, -1, 1495, 1491, 1194, -1, + 1491, 1495, 1496, -1, 1496, 1490, 1491, -1, + 1490, 1496, 1497, -1, 1497, 1489, 1490, -1, + 1489, 1497, 1498, -1, 1498, 1488, 1489, -1, + 1488, 1498, 1499, -1, 1499, 1487, 1488, -1, + 1487, 1499, 1500, -1, 1500, 1486, 1487, -1, + 1486, 1500, 1501, -1, 1501, 1485, 1486, -1, + 1485, 1501, 1502, -1, 1502, 1484, 1485, -1, + 1484, 1502, 1503, -1, 1503, 1483, 1484, -1, + 1483, 1503, 1504, -1, 1504, 1482, 1483, -1, + 1482, 1504, 1505, -1, 1505, 1481, 1482, -1, + 1481, 1505, 1506, -1, 1506, 1480, 1481, -1, + 1480, 1506, 1507, -1, 1507, 1479, 1480, -1, + 1479, 1507, 1508, -1, 1508, 1478, 1479, -1, + 1478, 1508, 1509, -1, 1509, 1477, 1478, -1, + 1477, 1509, 1510, -1, 1510, 1476, 1477, -1, + 1476, 1510, 1511, -1, 1476, 1511, 1512, -1, + 1512, 1475, 1476, -1, 1475, 1512, 1513, -1, + 1513, 1474, 1475, -1, 1474, 1513, 1514, -1, + 1514, 1473, 1474, -1, 1473, 1514, 1515, -1, + 1515, 1472, 1473, -1, 1472, 1515, 1516, -1, + 1516, 1471, 1472, -1, 1471, 1516, 1517, -1, + 1517, 1470, 1471, -1, 1470, 1517, 1518, -1, + 1518, 1469, 1470, -1, 1469, 1518, 1519, -1, + 1519, 1468, 1469, -1, 1468, 1519, 1520, -1, + 1520, 1467, 1468, -1, 1467, 1520, 1521, -1, + 1521, 1466, 1467, -1, 1466, 1521, 1522, -1, + 1522, 1465, 1466, -1, 1465, 1522, 1523, -1, + 1523, 1464, 1465, -1, 1464, 1523, 1524, -1, + 1524, 1463, 1464, -1, 1463, 1524, 1525, -1, + 1525, 1462, 1463, -1, 1462, 1525, 1526, -1, + 1526, 1461, 1462, -1, 1461, 1526, 1527, -1, + 1527, 1460, 1461, -1, 1460, 1527, 1528, -1, + 1528, 1529, 1460, -1, 1529, 1530, 1531, -1, + 1529, 1528, 1530, -1, 1532, 1530, 1528, -1, + 1532, 1531, 1530, -1, 1532, 1533, 1531, -1, + 1532, 1528, 1533, -1, 1534, 1533, 1528, -1, + 1528, 1535, 1534, -1, 1535, 1528, 1527, -1, + 1527, 1536, 1535, -1, 1536, 1527, 1526, -1, + 1526, 1537, 1536, -1, 1537, 1526, 1525, -1, + 1525, 1538, 1537, -1, 1538, 1525, 1524, -1, + 1524, 1539, 1538, -1, 1539, 1524, 1523, -1, + 1523, 1540, 1539, -1, 1540, 1523, 1522, -1, + 1522, 1541, 1540, -1, 1541, 1522, 1521, -1, + 1521, 1542, 1541, -1, 1542, 1521, 1520, -1, + 1520, 1543, 1542, -1, 1543, 1520, 1519, -1, + 1519, 1544, 1543, -1, 1544, 1519, 1518, -1, + 1518, 1545, 1544, -1, 1545, 1518, 1517, -1, + 1517, 1546, 1545, -1, 1546, 1517, 1516, -1, + 1516, 1547, 1546, -1, 1547, 1516, 1515, -1, + 1515, 1548, 1547, -1, 1548, 1515, 1514, -1, + 1514, 1549, 1548, -1, 1549, 1514, 1513, -1, + 1513, 1550, 1549, -1, 1550, 1513, 1512, -1, + 1512, 1551, 1550, -1, 1551, 1512, 1511, -1, + 1511, 1552, 1551, -1, 1511, 1553, 1552, -1, + 1553, 1511, 1510, -1, 1510, 1554, 1553, -1, + 1554, 1510, 1509, -1, 1509, 1555, 1554, -1, + 1555, 1509, 1508, -1, 1508, 1556, 1555, -1, + 1556, 1508, 1507, -1, 1507, 1557, 1556, -1, + 1557, 1507, 1506, -1, 1506, 1558, 1557, -1, + 1558, 1506, 1505, -1, 1505, 1559, 1558, -1, + 1559, 1505, 1504, -1, 1504, 1560, 1559, -1, + 1560, 1504, 1503, -1, 1503, 1561, 1560, -1, + 1561, 1503, 1502, -1, 1502, 1562, 1561, -1, + 1562, 1502, 1501, -1, 1501, 1563, 1562, -1, + 1563, 1501, 1500, -1, 1500, 1564, 1563, -1, + 1564, 1500, 1499, -1, 1499, 1565, 1564, -1, + 1565, 1499, 1498, -1, 1498, 1566, 1565, -1, + 1566, 1498, 1497, -1, 1497, 1567, 1566, -1, + 1567, 1497, 1496, -1, 1496, 1568, 1567, -1, + 1568, 1496, 1495, -1, 1495, 1569, 1568, -1, + 1569, 1495, 1494, -1, 1494, 1570, 1569, -1, + 1571, 1572, 1570, -1, 1571, 1570, 1573, -1, + 1570, 1494, 1573, -1, 1574, 1575, 1573, -1, + 1574, 1573, 1494, -1, 1574, 1494, 1493, -1, + 1493, 1575, 1574, -1, 1493, 1492, 1575, -1, + 1575, 1576, 1577, -1, 1576, 1575, 1492, -1, + 1576, 1492, 1194, -1, 1576, 1194, 1193, -1, + 1193, 1577, 1576, -1, 1193, 1578, 1577, -1, + 1578, 1193, 1192, -1, 1578, 1192, 1426, -1, + 1426, 1577, 1578, -1, 1426, 1425, 1577, -1, + 1425, 1424, 1577, -1, 1577, 1424, 1422, -1, + 1422, 1579, 1580, -1, 1579, 1422, 1421, -1, + 1390, 1580, 1579, -1, 1581, 1580, 1390, -1, + 1581, 1390, 1262, -1, 1581, 1262, 1261, -1, + 1261, 1580, 1581, -1, 1261, 1263, 1580, -1, + 1263, 1265, 1580, -1, 1580, 1265, 1267, -1, + 1582, 1267, 1301, -1, 1301, 1583, 1582, -1, + 1583, 1301, 1302, -1, 1583, 1302, 1306, -1, + 1306, 1582, 1583, -1, 1306, 1304, 1582, -1, + 1304, 1303, 1582, -1, 1303, 1584, 1582, -1, + 1303, 1305, 1584, -1, 1585, 1584, 1305, -1, + 1585, 1305, 1307, -1, 1307, 1586, 1585, -1, + 1586, 1307, 1308, -1, 1308, 1587, 1586, -1, + 1587, 1308, 1309, -1, 1309, 1588, 1587, -1, + 1588, 1309, 1310, -1, 1310, 1589, 1588, -1, + 1589, 1310, 1311, -1, 1311, 1590, 1589, -1, + 1590, 1311, 1312, -1, 1590, 1312, 1313, -1, + 1313, 1591, 1590, -1, 1591, 1313, 1314, -1, + 1314, 1592, 1591, -1, 1592, 1314, 1315, -1, + 1315, 1593, 1592, -1, 1593, 1315, 1316, -1, + 1316, 1594, 1593, -1, 1594, 1316, 1317, -1, + 1317, 1595, 1594, -1, 1595, 1317, 1318, -1, + 1596, 1597, 1595, -1, 1596, 1595, 1598, -1, + 1595, 1318, 1598, -1, 1599, 1598, 1318, -1, + 1599, 1600, 1598, -1, 1599, 1601, 1600, -1, + 1599, 1318, 1601, -1, 1601, 1318, 1319, -1, + 1319, 1600, 1601, -1, 1319, 1320, 1600, -1, + 1320, 1321, 1600, -1, 1321, 1602, 1600, -1, + 1602, 1321, 1322, -1, 1602, 1322, 1324, -1, + 1602, 1324, 1365, -1, 1365, 1600, 1602, -1, + 1603, 1604, 1605, -1, 1603, 1606, 1604, -1, + 1603, 1607, 1606, -1, 1603, 1605, 1607, -1, + 1605, 1608, 1609, -1, 1609, 1607, 1605, -1, + 1610, 1611, 1612, -1, 1612, 1613, 1610, -1, + 1614, 1615, 1616, -1, 1615, 1614, 1617, -1, + 1617, 1618, 1615, -1, 1618, 1617, 1619, -1, + 1619, 1620, 1618, -1, 1620, 1619, 1621, -1, + 1621, 1622, 1620, -1, 1622, 1621, 1623, -1, + 1623, 1624, 1622, -1, 1624, 1623, 1625, -1, + 1625, 1626, 1624, -1, 1626, 1625, 1627, -1, + 1627, 1628, 1626, -1, 1628, 1627, 1629, -1, + 1629, 1630, 1628, -1, 1630, 1629, 1631, -1, + 1631, 1632, 1630, -1, 1632, 1631, 1633, -1, + 1633, 1634, 1632, -1, 1634, 1633, 1635, -1, + 1635, 1636, 1634, -1, 1636, 1635, 1637, -1, + 1637, 1613, 1636, -1, 1613, 1637, 1638, -1, + 1638, 1610, 1613, -1, 1610, 1638, 1639, -1, + 1610, 1639, 1640, -1, 1641, 1640, 1639, -1, + 1642, 1641, 1639, -1, 1642, 1639, 1643, -1, + 1643, 1644, 1642, -1, 1645, 1644, 1643, -1, + 1646, 1647, 1648, -1, 1647, 1646, 1649, -1, + 1649, 1650, 1647, -1, 1650, 1649, 1651, -1, + 1651, 1652, 1650, -1, 1652, 1651, 1653, -1, + 1653, 1654, 1652, -1, 1654, 1653, 1655, -1, + 1655, 1656, 1654, -1, 1656, 1655, 1657, -1, + 1657, 1658, 1656, -1, 1658, 1657, 1659, -1, + 1659, 1660, 1658, -1, 1660, 1659, 1661, -1, + 1661, 1662, 1660, -1, 1662, 1661, 1663, -1, + 1663, 1664, 1662, -1, 1664, 1663, 1665, -1, + 1665, 1666, 1664, -1, 1666, 1665, 1667, -1, + 1667, 1668, 1666, -1, 1668, 1667, 1669, -1, + 1669, 1670, 1668, -1, 1670, 1669, 1671, -1, + 1671, 1672, 1670, -1, 1672, 1671, 1673, -1, + 1673, 1674, 1672, -1, 1674, 1673, 1675, -1, + 1675, 1676, 1674, -1, 1676, 1675, 1677, -1, + 1676, 1677, 1678, -1, 1679, 1644, 1680, -1, + 1644, 1679, 1681, -1, 1682, 1683, 1681, -1, + 1682, 1681, 1679, -1, 1679, 1677, 1682, -1, + 1679, 1680, 1677, -1, 1680, 1678, 1677, -1, + 1678, 1680, 1644, -1, 1678, 1644, 1645, -1, + 1645, 1676, 1678, -1, 1645, 1643, 1676, -1, + 1676, 1643, 1639, -1, 1639, 1674, 1676, -1, + 1674, 1639, 1638, -1, 1638, 1672, 1674, -1, + 1672, 1638, 1637, -1, 1637, 1670, 1672, -1, + 1670, 1637, 1635, -1, 1635, 1668, 1670, -1, + 1668, 1635, 1633, -1, 1633, 1666, 1668, -1, + 1666, 1633, 1631, -1, 1631, 1664, 1666, -1, + 1664, 1631, 1629, -1, 1629, 1662, 1664, -1, + 1662, 1629, 1627, -1, 1627, 1660, 1662, -1, + 1660, 1627, 1625, -1, 1625, 1658, 1660, -1, + 1658, 1625, 1623, -1, 1623, 1656, 1658, -1, + 1656, 1623, 1621, -1, 1621, 1654, 1656, -1, + 1654, 1621, 1619, -1, 1619, 1652, 1654, -1, + 1652, 1619, 1617, -1, 1617, 1650, 1652, -1, + 1650, 1617, 1614, -1, 1614, 1647, 1650, -1, + 1647, 1614, 1616, -1, 1616, 1648, 1647, -1, + 1648, 1616, 1684, -1, 1684, 1685, 1648, -1, + 1685, 1684, 1686, -1, 1687, 1688, 1689, -1, + 1688, 1687, 1686, -1, 1686, 1690, 1688, -1, + 1690, 1686, 1684, -1, 1684, 1691, 1690, -1, + 1691, 1684, 1616, -1, 1616, 1692, 1691, -1, + 1692, 1616, 1615, -1, 1615, 1693, 1692, -1, + 1693, 1615, 1618, -1, 1618, 1694, 1693, -1, + 1694, 1618, 1620, -1, 1620, 1695, 1694, -1, + 1695, 1620, 1622, -1, 1622, 1696, 1695, -1, + 1696, 1622, 1624, -1, 1624, 1697, 1696, -1, + 1697, 1624, 1626, -1, 1626, 1698, 1697, -1, + 1698, 1626, 1628, -1, 1628, 1699, 1698, -1, + 1699, 1628, 1630, -1, 1630, 1700, 1699, -1, + 1700, 1630, 1632, -1, 1632, 1701, 1700, -1, + 1701, 1632, 1634, -1, 1634, 1702, 1701, -1, + 1702, 1634, 1636, -1, 1636, 1703, 1702, -1, + 1703, 1636, 1613, -1, 1613, 1612, 1703, -1, + 1704, 1705, 1612, -1, 1706, 1612, 1705, -1, + 1706, 1703, 1612, -1, 1703, 1706, 1707, -1, + 1707, 1702, 1703, -1, 1702, 1707, 1708, -1, + 1708, 1701, 1702, -1, 1701, 1708, 1709, -1, + 1709, 1700, 1701, -1, 1700, 1709, 1710, -1, + 1710, 1699, 1700, -1, 1699, 1710, 1711, -1, + 1711, 1698, 1699, -1, 1698, 1711, 1712, -1, + 1712, 1697, 1698, -1, 1697, 1712, 1713, -1, + 1713, 1696, 1697, -1, 1696, 1713, 1714, -1, + 1714, 1695, 1696, -1, 1695, 1714, 1715, -1, + 1715, 1694, 1695, -1, 1694, 1715, 1716, -1, + 1716, 1693, 1694, -1, 1693, 1716, 1717, -1, + 1717, 1692, 1693, -1, 1692, 1717, 1718, -1, + 1718, 1691, 1692, -1, 1691, 1718, 1719, -1, + 1719, 1690, 1691, -1, 1690, 1719, 1720, -1, + 1720, 1688, 1690, -1, 1688, 1720, 1721, -1, + 1721, 1689, 1688, -1, 1689, 1721, 1722, -1, + 1722, 1723, 1689, -1, 1723, 1722, 1724, -1, + 1724, 1725, 1723, -1, 1725, 1724, 1726, -1, + 1726, 1727, 1725, -1, 1727, 1726, 1728, -1, + 1728, 1729, 1727, -1, 1729, 1728, 1730, -1, + 1730, 1731, 1729, -1, 1731, 1730, 1732, -1, + 1732, 1733, 1731, -1, 1734, 1735, 1736, -1, + 1735, 1734, 1733, -1, 1733, 1732, 1735, -1, + 1737, 1735, 1732, -1, 1732, 1738, 1737, -1, + 1738, 1732, 1730, -1, 1730, 1739, 1738, -1, + 1739, 1730, 1728, -1, 1728, 1740, 1739, -1, + 1740, 1728, 1726, -1, 1726, 1741, 1740, -1, + 1741, 1726, 1724, -1, 1724, 1742, 1741, -1, + 1742, 1724, 1722, -1, 1722, 1743, 1742, -1, + 1743, 1722, 1721, -1, 1721, 1744, 1743, -1, + 1744, 1721, 1720, -1, 1720, 1745, 1744, -1, + 1745, 1720, 1719, -1, 1719, 1746, 1745, -1, + 1746, 1719, 1718, -1, 1718, 1747, 1746, -1, + 1747, 1718, 1717, -1, 1717, 1748, 1747, -1, + 1748, 1717, 1716, -1, 1716, 1749, 1748, -1, + 1749, 1716, 1715, -1, 1715, 1750, 1749, -1, + 1750, 1715, 1714, -1, 1714, 1751, 1750, -1, + 1751, 1714, 1713, -1, 1713, 1752, 1751, -1, + 1752, 1713, 1712, -1, 1712, 1753, 1752, -1, + 1753, 1712, 1711, -1, 1711, 1754, 1753, -1, + 1754, 1711, 1710, -1, 1710, 1755, 1754, -1, + 1755, 1710, 1709, -1, 1709, 1756, 1755, -1, + 1756, 1709, 1708, -1, 1708, 1757, 1756, -1, + 1757, 1708, 1707, -1, 1707, 1758, 1757, -1, + 1758, 1707, 1706, -1, 1758, 1706, 1759, -1, + 1760, 1759, 1706, -1, 1760, 1761, 1759, -1, + 1762, 1761, 1760, -1, 1760, 1706, 1762, -1, + 1762, 1706, 1705, -1, 1705, 1761, 1762, -1, + 1705, 1704, 1761, -1, 1761, 1763, 1764, -1, + 1763, 1761, 1704, -1, 1704, 1612, 1763, -1, + 1763, 1612, 1611, -1, 1611, 1764, 1763, -1, + 1611, 1765, 1764, -1, 1765, 1611, 1610, -1, + 1765, 1610, 1640, -1, 1640, 1764, 1765, -1, + 1640, 1641, 1764, -1, 1641, 1642, 1764, -1, + 1764, 1642, 1644, -1, 1186, 1766, 1767, -1, + 1766, 1186, 1768, -1, 1768, 1769, 1766, -1, + 1769, 1768, 1770, -1, 1770, 1771, 1769, -1, + 1771, 1770, 1772, -1, 1772, 1773, 1771, -1, + 1773, 1772, 1774, -1, 1774, 1775, 1773, -1, + 1775, 1774, 1776, -1, 1776, 1777, 1775, -1, + 1777, 1776, 1778, -1, 1778, 1779, 1777, -1, + 1779, 1778, 1780, -1, 1780, 1781, 1779, -1, + 1781, 1780, 1782, -1, 1782, 1783, 1781, -1, + 1783, 1782, 1784, -1, 1784, 1785, 1783, -1, + 1785, 1784, 1786, -1, 1786, 1787, 1785, -1, + 1787, 1786, 1788, -1, 1788, 1789, 1787, -1, + 1789, 1788, 1790, -1, 1790, 1791, 1789, -1, + 1791, 1790, 1792, -1, 1792, 1793, 1791, -1, + 1793, 1792, 1794, -1, 1794, 1795, 1793, -1, + 1795, 1794, 1796, -1, 1796, 1797, 1795, -1, + 1797, 1796, 1798, -1, 1798, 1799, 1797, -1, + 1799, 1798, 1800, -1, 1800, 1801, 1799, -1, + 1801, 1800, 1802, -1, 1802, 1803, 1801, -1, + 1803, 1802, 1804, -1, 1804, 1805, 1803, -1, + 1805, 1804, 1806, -1, 1806, 1807, 1805, -1, + 1807, 1806, 1808, -1, 1808, 1809, 1807, -1, + 1809, 1808, 1810, -1, 1810, 1811, 1809, -1, + 1811, 1810, 1812, -1, 1812, 1813, 1811, -1, + 1813, 1812, 1814, -1, 1814, 1815, 1813, -1, + 1815, 1814, 1816, -1, 1816, 1817, 1815, -1, + 1817, 1816, 1818, -1, 1818, 1819, 1817, -1, + 1819, 1818, 1820, -1, 1820, 1821, 1819, -1, + 1821, 1820, 1822, -1, 1822, 1823, 1821, -1, + 1823, 1822, 1824, -1, 1824, 1825, 1823, -1, + 1825, 1824, 1826, -1, 1826, 1827, 1825, -1, + 1827, 1826, 1828, -1, 1828, 1829, 1827, -1, + 1829, 1828, 1830, -1, 1830, 1831, 1829, -1, + 1831, 1830, 1832, -1, 1832, 1833, 1831, -1, + 1833, 1832, 1834, -1, 1834, 1835, 1833, -1, + 1835, 1834, 1836, -1, 1836, 1837, 1835, -1, + 1837, 1836, 1838, -1, 1838, 1839, 1837, -1, + 1839, 1838, 1840, -1, 1840, 1841, 1839, -1, + 1841, 1840, 1842, -1, 1842, 1843, 1841, -1, + 1843, 1842, 1844, -1, 1844, 1845, 1843, -1, + 1845, 1844, 1846, -1, 1846, 1847, 1845, -1, + 1847, 1846, 1848, -1, 1848, 1849, 1847, -1, + 1849, 1848, 1850, -1, 1850, 1851, 1849, -1, + 1851, 1850, 1852, -1, 1852, 1853, 1851, -1, + 1853, 1852, 1854, -1, 1854, 1855, 1853, -1, + 1855, 1854, 1856, -1, 1856, 1857, 1855, -1, + 1857, 1856, 1858, -1, 1858, 1859, 1857, -1, + 1859, 1858, 1860, -1, 1860, 1861, 1859, -1, + 1861, 1860, 1862, -1, 1862, 1863, 1861, -1, + 1863, 1862, 1864, -1, 1864, 1865, 1863, -1, + 1865, 1864, 1866, -1, 1866, 1867, 1865, -1, + 1867, 1866, 1868, -1, 1868, 1869, 1867, -1, + 1869, 1868, 1870, -1, 1870, 1871, 1869, -1, + 1871, 1870, 1872, -1, 1872, 1873, 1871, -1, + 1873, 1872, 1874, -1, 1874, 1875, 1873, -1, + 1875, 1876, 1877, -1, 1877, 1873, 1875, -1, + 1873, 1877, 1878, -1, 1878, 1871, 1873, -1, + 1871, 1878, 1879, -1, 1879, 1869, 1871, -1, + 1869, 1879, 1880, -1, 1880, 1867, 1869, -1, + 1867, 1880, 1881, -1, 1881, 1865, 1867, -1, + 1865, 1881, 1882, -1, 1882, 1863, 1865, -1, + 1863, 1882, 1883, -1, 1883, 1861, 1863, -1, + 1861, 1883, 1884, -1, 1884, 1859, 1861, -1, + 1859, 1884, 1885, -1, 1885, 1857, 1859, -1, + 1857, 1885, 1886, -1, 1886, 1855, 1857, -1, + 1855, 1886, 1887, -1, 1887, 1853, 1855, -1, + 1853, 1887, 1888, -1, 1888, 1851, 1853, -1, + 1851, 1888, 1889, -1, 1889, 1849, 1851, -1, + 1849, 1889, 1890, -1, 1890, 1847, 1849, -1, + 1847, 1890, 1891, -1, 1891, 1845, 1847, -1, + 1845, 1891, 1892, -1, 1892, 1843, 1845, -1, + 1843, 1892, 1893, -1, 1893, 1841, 1843, -1, + 1841, 1893, 1894, -1, 1894, 1839, 1841, -1, + 1839, 1894, 1895, -1, 1895, 1837, 1839, -1, + 1837, 1895, 1896, -1, 1896, 1835, 1837, -1, + 1835, 1896, 1897, -1, 1897, 1833, 1835, -1, + 1833, 1897, 1898, -1, 1898, 1831, 1833, -1, + 1831, 1898, 1899, -1, 1899, 1829, 1831, -1, + 1829, 1899, 1900, -1, 1900, 1827, 1829, -1, + 1827, 1900, 1901, -1, 1901, 1825, 1827, -1, + 1825, 1901, 1902, -1, 1902, 1823, 1825, -1, + 1823, 1902, 1903, -1, 1903, 1821, 1823, -1, + 1821, 1903, 1904, -1, 1904, 1819, 1821, -1, + 1819, 1904, 1905, -1, 1905, 1817, 1819, -1, + 1817, 1905, 1906, -1, 1906, 1815, 1817, -1, + 1815, 1906, 1907, -1, 1907, 1813, 1815, -1, + 1813, 1907, 1908, -1, 1908, 1811, 1813, -1, + 1811, 1908, 1909, -1, 1909, 1809, 1811, -1, + 1809, 1909, 1910, -1, 1910, 1807, 1809, -1, + 1807, 1910, 1911, -1, 1911, 1805, 1807, -1, + 1805, 1911, 1912, -1, 1912, 1803, 1805, -1, + 1803, 1912, 1913, -1, 1913, 1801, 1803, -1, + 1801, 1913, 1914, -1, 1914, 1799, 1801, -1, + 1799, 1914, 1915, -1, 1915, 1797, 1799, -1, + 1797, 1915, 1916, -1, 1916, 1795, 1797, -1, + 1795, 1916, 1917, -1, 1917, 1793, 1795, -1, + 1793, 1917, 1918, -1, 1918, 1791, 1793, -1, + 1791, 1918, 1919, -1, 1919, 1789, 1791, -1, + 1789, 1919, 1920, -1, 1920, 1787, 1789, -1, + 1787, 1920, 1921, -1, 1921, 1785, 1787, -1, + 1785, 1921, 1922, -1, 1922, 1783, 1785, -1, + 1783, 1922, 1923, -1, 1923, 1781, 1783, -1, + 1781, 1923, 1924, -1, 1924, 1779, 1781, -1, + 1779, 1924, 1925, -1, 1925, 1777, 1779, -1, + 1777, 1925, 1926, -1, 1926, 1775, 1777, -1, + 1775, 1926, 1927, -1, 1927, 1773, 1775, -1, + 1773, 1927, 1928, -1, 1928, 1771, 1773, -1, + 1771, 1928, 1929, -1, 1929, 1769, 1771, -1, + 1769, 1929, 1930, -1, 1930, 1766, 1769, -1, + 1766, 1930, 1931, -1, 1932, 1933, 1930, -1, + 1933, 1931, 1930, -1, 1933, 1934, 1931, -1, + 1933, 1932, 1934, -1, 1935, 1936, 1937, -1, + 1938, 1939, 1940, -1, 1939, 1938, 1941, -1, + 1937, 1934, 1942, -1, 1941, 1937, 1943, -1, + 1944, 1941, 1945, -1, 1946, 1947, 1944, -1, + 1947, 1948, 1944, -1, 1948, 1949, 1944, -1, + 1948, 1950, 1949, -1, 1948, 1947, 1950, -1, + 1947, 1946, 1950, -1, 1951, 1952, 1953, -1, + 1953, 1954, 1951, -1, 1954, 1953, 1955, -1, + 1955, 1956, 1954, -1, 1956, 1955, 1957, -1, + 1957, 1958, 1956, -1, 1958, 1957, 1959, -1, + 1959, 1960, 1958, -1, 1960, 1959, 1961, -1, + 1961, 1962, 1960, -1, 1962, 1961, 1963, -1, + 1963, 1964, 1962, -1, 1964, 1963, 1965, -1, + 1965, 1966, 1964, -1, 1966, 1965, 1967, -1, + 1967, 1968, 1966, -1, 1968, 1967, 1969, -1, + 1969, 1970, 1968, -1, 1970, 1969, 1971, -1, + 1971, 1972, 1970, -1, 1972, 1971, 1973, -1, + 1973, 1974, 1972, -1, 1974, 1973, 1975, -1, + 1975, 1976, 1974, -1, 1976, 1975, 1950, -1, + 1950, 1977, 1976, -1, 1950, 1946, 1977, -1, + 1978, 1977, 1946, -1, 1946, 1944, 1978, -1, + 1978, 1944, 1945, -1, 1945, 1977, 1978, -1, + 1945, 1979, 1977, -1, 1979, 1945, 1941, -1, + 1979, 1941, 1938, -1, 1938, 1940, 1979, -1, + 1940, 1977, 1979, -1, 1977, 1940, 1980, -1, + 1980, 1976, 1977, -1, 1976, 1980, 1981, -1, + 1981, 1974, 1976, -1, 1974, 1981, 1982, -1, + 1982, 1972, 1974, -1, 1972, 1982, 1983, -1, + 1983, 1970, 1972, -1, 1970, 1983, 1984, -1, + 1984, 1968, 1970, -1, 1968, 1984, 1985, -1, + 1985, 1966, 1968, -1, 1966, 1985, 1986, -1, + 1986, 1964, 1966, -1, 1964, 1986, 1987, -1, + 1987, 1962, 1964, -1, 1962, 1987, 1988, -1, + 1988, 1960, 1962, -1, 1960, 1988, 1989, -1, + 1989, 1958, 1960, -1, 1958, 1989, 1990, -1, + 1990, 1956, 1958, -1, 1956, 1990, 1991, -1, + 1991, 1954, 1956, -1, 1954, 1991, 1992, -1, + 1992, 1951, 1954, -1, 1951, 1992, 1993, -1, + 1993, 1952, 1951, -1, 1952, 1993, 1994, -1, + 1994, 1995, 1952, -1, 1995, 1994, 1996, -1, + 1996, 1997, 1995, -1, 1998, 1999, 2000, -1, + 2000, 2001, 1998, -1, 2001, 2000, 2002, -1, + 2002, 2003, 2001, -1, 2003, 2002, 2004, -1, + 2004, 2005, 2003, -1, 2005, 2004, 2006, -1, + 2006, 2007, 2005, -1, 2007, 2006, 2008, -1, + 2008, 2009, 2007, -1, 2009, 2008, 2010, -1, + 2010, 2011, 2009, -1, 2011, 2010, 2012, -1, + 2012, 2013, 2011, -1, 2013, 2012, 1997, -1, + 1997, 1996, 2013, -1, 2014, 2013, 1996, -1, + 1996, 2015, 2014, -1, 2015, 1996, 1994, -1, + 1994, 2016, 2015, -1, 2017, 2015, 2016, -1, + 2016, 2018, 2017, -1, 2018, 2016, 2019, -1, + 2019, 2020, 2018, -1, 2020, 2019, 2021, -1, + 2021, 2022, 2020, -1, 2022, 2021, 2023, -1, + 2023, 2024, 2022, -1, 2024, 2023, 2025, -1, + 2025, 2026, 2024, -1, 2026, 2025, 2027, -1, + 2027, 2028, 2026, -1, 2028, 2027, 2029, -1, + 2029, 2030, 2028, -1, 2030, 2029, 2031, -1, + 2031, 2032, 2030, -1, 2032, 2031, 2033, -1, + 2033, 2034, 2032, -1, 2034, 2033, 2035, -1, + 2035, 2036, 2034, -1, 2036, 2035, 2037, -1, + 2037, 2038, 2036, -1, 2038, 2037, 2039, -1, + 2039, 2040, 2038, -1, 2040, 2039, 2041, -1, + 2041, 2042, 2040, -1, 2042, 2041, 2043, -1, + 2043, 2044, 2042, -1, 2044, 2043, 2045, -1, + 2045, 2046, 2044, -1, 2046, 2045, 2047, -1, + 2047, 2048, 2046, -1, 2049, 2050, 2051, -1, + 2050, 2049, 2048, -1, 2048, 2047, 2050, -1, + 2050, 2052, 2053, -1, 2052, 2050, 2047, -1, + 2047, 2054, 2052, -1, 2054, 2047, 2045, -1, + 2045, 2055, 2054, -1, 2055, 2045, 2043, -1, + 2043, 2056, 2055, -1, 2056, 2043, 2041, -1, + 2041, 2057, 2056, -1, 2057, 2041, 2039, -1, + 2039, 2058, 2057, -1, 2058, 2039, 2037, -1, + 2037, 2059, 2058, -1, 2059, 2037, 2035, -1, + 2035, 2060, 2059, -1, 2060, 2035, 2033, -1, + 2033, 2061, 2060, -1, 2061, 2033, 2031, -1, + 2031, 2062, 2061, -1, 2062, 2031, 2029, -1, + 2029, 2063, 2062, -1, 2063, 2029, 2027, -1, + 2027, 2064, 2063, -1, 2064, 2027, 2025, -1, + 2025, 2065, 2064, -1, 2065, 2025, 2023, -1, + 2023, 2066, 2065, -1, 2066, 2023, 2021, -1, + 2021, 2067, 2066, -1, 2067, 2021, 2019, -1, + 2019, 2068, 2067, -1, 2068, 2019, 2016, -1, + 2016, 1994, 2068, -1, 2068, 1994, 1993, -1, + 1993, 2067, 2068, -1, 2067, 1993, 1992, -1, + 1992, 2066, 2067, -1, 2066, 1992, 1991, -1, + 1991, 2065, 2066, -1, 2065, 1991, 1990, -1, + 1990, 2064, 2065, -1, 2064, 1990, 1989, -1, + 1989, 2063, 2064, -1, 2063, 1989, 1988, -1, + 1988, 2062, 2063, -1, 2062, 1988, 1987, -1, + 1987, 2061, 2062, -1, 2061, 1987, 1986, -1, + 1986, 2060, 2061, -1, 2060, 1986, 1985, -1, + 1985, 2059, 2060, -1, 2059, 1985, 1984, -1, + 1984, 2058, 2059, -1, 2058, 1984, 1983, -1, + 1983, 2057, 2058, -1, 2057, 1983, 1982, -1, + 1982, 2056, 2057, -1, 2056, 1982, 1981, -1, + 1981, 2055, 2056, -1, 2055, 1981, 1980, -1, + 1980, 2054, 2055, -1, 2054, 1980, 1940, -1, + 1940, 2052, 2054, -1, 1940, 1939, 2052, -1, + 2069, 2052, 1939, -1, 1939, 1941, 2069, -1, + 2069, 1941, 1943, -1, 1943, 2052, 2069, -1, + 1943, 2053, 2052, -1, 2053, 1943, 1937, -1, + 2053, 1937, 1936, -1, 1936, 2050, 2053, -1, + 1936, 1935, 2050, -1, 1935, 2051, 2050, -1, + 1935, 1937, 2051, -1, 2051, 1937, 1942, -1, + 1942, 2049, 2051, -1, 1942, 2070, 2049, -1, + 2070, 1942, 1934, -1, 2070, 1934, 1932, -1, + 1932, 1930, 2070, -1, 1930, 2049, 2070, -1, + 2049, 1930, 1929, -1, 1929, 2048, 2049, -1, + 2048, 1929, 1928, -1, 1928, 2046, 2048, -1, + 2046, 1928, 1927, -1, 1927, 2044, 2046, -1, + 2044, 1927, 1926, -1, 1926, 2042, 2044, -1, + 2042, 1926, 1925, -1, 1925, 2040, 2042, -1, + 2040, 1925, 1924, -1, 1924, 2038, 2040, -1, + 2038, 1924, 1923, -1, 1923, 2036, 2038, -1, + 2036, 1923, 1922, -1, 1922, 2034, 2036, -1, + 2034, 1922, 1921, -1, 1921, 2032, 2034, -1, + 2032, 1921, 1920, -1, 1920, 2030, 2032, -1, + 2030, 1920, 1919, -1, 1919, 2028, 2030, -1, + 2028, 1919, 1918, -1, 1918, 2026, 2028, -1, + 2026, 1918, 1917, -1, 1917, 2024, 2026, -1, + 2024, 1917, 1916, -1, 1916, 2022, 2024, -1, + 2022, 1916, 1915, -1, 1915, 2020, 2022, -1, + 2020, 1915, 1914, -1, 1914, 2018, 2020, -1, + 2018, 1914, 1913, -1, 1913, 2017, 2018, -1, + 2017, 1913, 1912, -1, 1912, 2015, 2017, -1, + 2015, 1912, 1911, -1, 1911, 2014, 2015, -1, + 2014, 1911, 1910, -1, 1910, 2013, 2014, -1, + 2013, 1910, 1909, -1, 1909, 2011, 2013, -1, + 2011, 1909, 1908, -1, 1908, 2009, 2011, -1, + 2009, 1908, 1907, -1, 1907, 2007, 2009, -1, + 2007, 1907, 1906, -1, 1906, 2005, 2007, -1, + 2005, 1906, 1905, -1, 1905, 2003, 2005, -1, + 2003, 1905, 1904, -1, 1904, 2001, 2003, -1, + 2001, 1904, 1903, -1, 1903, 1998, 2001, -1, + 1998, 1903, 1902, -1, 1902, 1999, 1998, -1, + 1999, 1902, 1901, -1, 1901, 2071, 1999, -1, + 2071, 1901, 1900, -1, 1900, 2072, 2071, -1, + 2072, 1900, 1899, -1, 1899, 2073, 2072, -1, + 2073, 1899, 1898, -1, 1898, 2074, 2073, -1, + 2074, 1898, 1897, -1, 1897, 2075, 2074, -1, + 2075, 1897, 1896, -1, 1896, 2076, 2075, -1, + 2076, 1896, 1895, -1, 1895, 2077, 2076, -1, + 2077, 1895, 1894, -1, 1894, 2078, 2077, -1, + 2078, 1894, 1893, -1, 1893, 2079, 2078, -1, + 2079, 1893, 1892, -1, 1892, 2080, 2079, -1, + 2080, 1892, 1891, -1, 1891, 2081, 2080, -1, + 2081, 1891, 1890, -1, 1890, 2082, 2081, -1, + 2082, 1890, 1889, -1, 1889, 2083, 2082, -1, + 2083, 1889, 1888, -1, 1888, 2084, 2083, -1, + 2084, 1888, 1887, -1, 1887, 2085, 2084, -1, + 2085, 1887, 1886, -1, 1886, 2086, 2085, -1, + 2086, 1886, 1885, -1, 1885, 2087, 2086, -1, + 2087, 1885, 1884, -1, 1884, 2088, 2087, -1, + 2088, 1884, 1883, -1, 1883, 2089, 2088, -1, + 2089, 1883, 1882, -1, 1882, 2090, 2089, -1, + 2090, 1882, 1881, -1, 1881, 2091, 2090, -1, + 2091, 1881, 1880, -1, 1880, 2092, 2091, -1, + 2092, 1880, 1879, -1, 1879, 2093, 2092, -1, + 2093, 1879, 1878, -1, 1878, 2094, 2093, -1, + 2094, 1878, 1877, -1, 1877, 2095, 2094, -1, + 2095, 1877, 1876, -1, 2095, 1876, 2096, -1, + 2096, 2097, 2095, -1, 2097, 2096, 2098, -1, + 2098, 2099, 2097, -1, 2099, 2098, 2100, -1, + 2100, 2101, 2099, -1, 2101, 2100, 2102, -1, + 2102, 2103, 2101, -1, 2103, 2102, 2104, -1, + 2104, 2105, 2103, -1, 2105, 2104, 2106, -1, + 2106, 2107, 2105, -1, 2107, 2106, 2108, -1, + 2108, 2109, 2107, -1, 2109, 2108, 2110, -1, + 2110, 2111, 2109, -1, 2111, 2110, 2112, -1, + 2112, 2113, 2111, -1, 2113, 2112, 2114, -1, + 2114, 2115, 2113, -1, 2115, 2114, 2116, -1, + 2116, 2117, 2115, -1, 2117, 2116, 2118, -1, + 2118, 2119, 2117, -1, 2119, 2118, 2120, -1, + 2120, 2121, 2119, -1, 2121, 2120, 2122, -1, + 2122, 2123, 2121, -1, 2123, 2122, 2124, -1, + 2124, 2125, 2123, -1, 2125, 2124, 2126, -1, + 2126, 2127, 2125, -1, 2127, 2126, 2128, -1, + 2128, 2129, 2127, -1, 2129, 2128, 2130, -1, + 2130, 2131, 2129, -1, 2131, 2130, 2132, -1, + 2132, 2133, 2131, -1, 2133, 2132, 2134, -1, + 2134, 2135, 2133, -1, 2135, 2134, 2136, -1, + 2136, 2137, 2135, -1, 2137, 2136, 2138, -1, + 2138, 2139, 2137, -1, 2139, 2138, 2140, -1, + 2140, 2141, 2139, -1, 2141, 2140, 2142, -1, + 2142, 2143, 2141, -1, 2143, 2142, 2144, -1, + 2144, 2145, 2143, -1, 2145, 2144, 2146, -1, + 2146, 2147, 2145, -1, 2147, 2146, 2148, -1, + 2148, 2149, 2147, -1, 2149, 2148, 2150, -1, + 2150, 2151, 2149, -1, 2151, 2150, 2152, -1, + 2152, 2153, 2151, -1, 2153, 2152, 2154, -1, + 2154, 2155, 2153, -1, 2155, 2154, 2156, -1, + 2156, 2157, 2155, -1, 2157, 2156, 2158, -1, + 2158, 2159, 2157, -1, 2159, 2158, 2160, -1, + 2160, 2161, 2159, -1, 2161, 2160, 2162, -1, + 2162, 2163, 2161, -1, 2163, 2162, 2164, -1, + 2164, 2165, 2163, -1, 2165, 2164, 2166, -1, + 2166, 2167, 2165, -1, 2167, 2166, 2168, -1, + 2168, 2169, 2167, -1, 2169, 2168, 2170, -1, + 2170, 2171, 2169, -1, 2171, 2170, 2172, -1, + 2172, 2173, 2171, -1, 2173, 2172, 2174, -1, + 2174, 2175, 2173, -1, 2175, 2174, 2176, -1, + 2176, 2177, 2175, -1, 2177, 2176, 2178, -1, + 2178, 2179, 2177, -1, 2179, 2178, 2180, -1, + 2180, 2181, 2179, -1, 2181, 2180, 2182, -1, + 2182, 2183, 2181, -1, 2183, 2182, 2184, -1, + 2184, 2185, 2183, -1, 2185, 2184, 2186, -1, + 2186, 2187, 2185, -1, 2187, 2186, 2188, -1, + 2188, 2189, 2187, -1, 2189, 2188, 2190, -1, + 2190, 2191, 2189, -1, 2191, 2190, 2192, -1, + 2192, 2193, 2191, -1, 2193, 2192, 2194, -1, + 2194, 2195, 2193, -1, 2195, 2194, 2196, -1, + 2196, 2197, 2195, -1, 2197, 2196, 2198, -1, + 2198, 2199, 2197, -1, 2199, 2198, 2200, -1, + 2200, 2201, 2199, -1, 2201, 2200, 2202, -1, + 2202, 2203, 2201, -1, 2204, 2205, 1607, -1, + 2206, 2205, 2204, -1, 2207, 2203, 2202, -1, + 2207, 2204, 2203, -1, 2203, 2204, 2208, -1, + 2208, 2201, 2203, -1, 2208, 2209, 2201, -1, + 2209, 2208, 1681, -1, 1681, 2208, 2204, -1, + 2210, 1190, 2211, -1, 2212, 2210, 2211, -1, + 2212, 2211, 2213, -1, 2212, 2213, 2214, -1, + 2214, 2210, 2212, -1, 2215, 2216, 2217, -1, + 2216, 2215, 2210, -1, 2216, 2210, 2214, -1, + 2214, 2213, 2216, -1, 2213, 2217, 2216, -1, + 2217, 2213, 2218, -1, 2218, 2219, 2217, -1, + 2219, 2218, 2220, -1, 2220, 2221, 2219, -1, + 2221, 2220, 2222, -1, 2222, 2223, 2221, -1, + 2223, 2222, 2224, -1, 2224, 2225, 2223, -1, + 2225, 2224, 2226, -1, 2226, 2227, 2225, -1, + 2227, 2226, 2228, -1, 2228, 2229, 2227, -1, + 2229, 2228, 2230, -1, 2230, 2231, 2229, -1, + 2231, 2230, 2232, -1, 2232, 2233, 2231, -1, + 2233, 2232, 2234, -1, 2234, 2235, 2233, -1, + 2235, 2234, 2236, -1, 2236, 2237, 2235, -1, + 2237, 2236, 2238, -1, 2238, 2239, 2237, -1, + 2239, 2238, 2240, -1, 2240, 2241, 2239, -1, + 2241, 2240, 2242, -1, 2242, 2243, 2241, -1, + 2243, 2242, 2244, -1, 2244, 2245, 2243, -1, + 2245, 2244, 2246, -1, 2246, 2247, 2245, -1, + 2247, 2246, 2248, -1, 2248, 2249, 2247, -1, + 2249, 2248, 2250, -1, 2250, 2251, 2249, -1, + 2251, 2250, 2252, -1, 2252, 2253, 2251, -1, + 2253, 2252, 2254, -1, 2254, 2255, 2253, -1, + 2255, 2254, 2256, -1, 2256, 2257, 2255, -1, + 2257, 2256, 2258, -1, 2258, 2259, 2257, -1, + 2259, 2258, 2260, -1, 2260, 2261, 2259, -1, + 2261, 2260, 2262, -1, 2262, 2263, 2261, -1, + 2263, 2262, 2264, -1, 2264, 2265, 2263, -1, + 2265, 2264, 2266, -1, 2266, 2267, 2265, -1, + 2267, 2266, 2268, -1, 2268, 2269, 2267, -1, + 2269, 2268, 2270, -1, 2270, 2271, 2269, -1, + 2271, 2270, 2272, -1, 2272, 2273, 2271, -1, + 2273, 2272, 2274, -1, 2274, 2275, 2273, -1, + 2275, 2274, 2276, -1, 2276, 2277, 2275, -1, + 2277, 2276, 2278, -1, 2278, 2279, 2277, -1, + 2279, 2278, 2280, -1, 2280, 2281, 2279, -1, + 2281, 2280, 2282, -1, 2282, 2283, 2281, -1, + 2283, 2282, 2284, -1, 2284, 2285, 2283, -1, + 2285, 2284, 2286, -1, 2286, 2287, 2285, -1, + 2287, 2286, 2288, -1, 2288, 2289, 2287, -1, + 2289, 2288, 2290, -1, 2290, 2291, 2289, -1, + 2291, 2290, 2292, -1, 2292, 2293, 2291, -1, + 2293, 2292, 2294, -1, 2294, 2295, 2293, -1, + 2295, 2294, 2296, -1, 2296, 2297, 2295, -1, + 2297, 2296, 2298, -1, 2298, 2299, 2297, -1, + 2299, 2298, 2300, -1, 2300, 2301, 2299, -1, + 2301, 2300, 2302, -1, 2302, 2303, 2301, -1, + 2304, 2305, 2306, -1, 2305, 2304, 2307, -1, + 2307, 2308, 2305, -1, 2308, 2307, 2309, -1, + 2309, 2310, 2308, -1, 2310, 2309, 2311, -1, + 2311, 2312, 2310, -1, 2313, 2314, 2312, -1, + 2312, 2311, 2313, -1, 2315, 2316, 2317, -1, + 2318, 2319, 2320, -1, 2319, 2318, 2321, -1, + 2319, 2321, 2322, -1, 2323, 2322, 2321, -1, + 2323, 2324, 2322, -1, 2325, 2326, 2327, -1, + 2327, 2328, 2325, -1, 2328, 2327, 2329, -1, + 2329, 2330, 2328, -1, 2330, 2329, 2331, -1, + 2331, 2332, 2330, -1, 2332, 2331, 2333, -1, + 2333, 2334, 2332, -1, 2334, 2333, 2335, -1, + 2335, 2336, 2334, -1, 2336, 2335, 2337, -1, + 2337, 2338, 2336, -1, 2338, 2337, 2339, -1, + 2339, 2340, 2338, -1, 2340, 2339, 2341, -1, + 2341, 2342, 2340, -1, 2342, 2341, 2343, -1, + 2343, 2344, 2342, -1, 2344, 2343, 2345, -1, + 2345, 2346, 2344, -1, 2346, 2345, 2347, -1, + 2347, 2348, 2346, -1, 2348, 2347, 2349, -1, + 2349, 2350, 2348, -1, 2350, 2349, 2351, -1, + 2351, 2352, 2350, -1, 2352, 2351, 2353, -1, + 2353, 2354, 2352, -1, 2354, 2353, 2355, -1, + 2355, 2356, 2354, -1, 2356, 2355, 2357, -1, + 2357, 2358, 2356, -1, 2358, 2357, 2359, -1, + 2359, 2360, 2358, -1, 2360, 2359, 2361, -1, + 2361, 2362, 2360, -1, 2362, 2361, 2363, -1, + 2363, 2364, 2362, -1, 2364, 2363, 2365, -1, + 2365, 2366, 2364, -1, 2366, 2365, 2367, -1, + 2367, 2368, 2366, -1, 2368, 2367, 2369, -1, + 2369, 2370, 2368, -1, 2370, 2369, 2371, -1, + 2371, 2372, 2370, -1, 2372, 2371, 2373, -1, + 2373, 2374, 2372, -1, 2374, 2373, 2375, -1, + 2375, 2376, 2374, -1, 2376, 2375, 2377, -1, + 2377, 2378, 2376, -1, 2378, 2377, 2379, -1, + 2379, 2380, 2378, -1, 2380, 2379, 2381, -1, + 2381, 2382, 2380, -1, 2382, 2381, 2383, -1, + 2383, 2384, 2382, -1, 2384, 2383, 2385, -1, + 2385, 2386, 2384, -1, 2386, 2385, 2387, -1, + 2387, 2388, 2386, -1, 2388, 2387, 2389, -1, + 2389, 2390, 2388, -1, 2390, 2389, 2391, -1, + 2391, 2392, 2390, -1, 2392, 2391, 2393, -1, + 2393, 2394, 2392, -1, 2394, 2393, 2395, -1, + 2395, 2396, 2394, -1, 2396, 2395, 2397, -1, + 2397, 2398, 2396, -1, 2398, 2397, 2399, -1, + 2399, 2400, 2398, -1, 2400, 2399, 2401, -1, + 2401, 2402, 2400, -1, 2402, 2401, 2403, -1, + 2403, 2404, 2402, -1, 2404, 2403, 2405, -1, + 2405, 2406, 2404, -1, 2405, 2407, 2406, -1, + 2407, 2405, 2408, -1, 2408, 2409, 2407, -1, + 2409, 2408, 2410, -1, 2410, 2411, 2409, -1, + 2411, 2410, 2412, -1, 2412, 2413, 2411, -1, + 2413, 2412, 2414, -1, 2414, 2415, 2413, -1, + 2415, 2414, 2416, -1, 2416, 2417, 2415, -1, + 2417, 2416, 2418, -1, 2418, 2419, 2417, -1, + 2419, 2418, 2420, -1, 2420, 2421, 2419, -1, + 2421, 2420, 2422, -1, 2422, 2423, 2421, -1, + 2423, 2422, 2424, -1, 2424, 2425, 2423, -1, + 2425, 2424, 2426, -1, 2426, 2427, 2425, -1, + 2427, 2426, 2428, -1, 2428, 2429, 2427, -1, + 2429, 2428, 2430, -1, 2430, 2431, 2429, -1, + 2431, 2430, 2432, -1, 2432, 2433, 2431, -1, + 2433, 2432, 2434, -1, 2434, 2435, 2433, -1, + 2435, 2434, 2436, -1, 2436, 2437, 2435, -1, + 2437, 2436, 2438, -1, 2438, 2439, 2437, -1, + 2439, 2438, 2440, -1, 2440, 2441, 2439, -1, + 2441, 2440, 2442, -1, 2442, 2443, 2441, -1, + 2443, 2442, 2444, -1, 2444, 2445, 2443, -1, + 2445, 2444, 2446, -1, 2446, 2447, 2445, -1, + 2447, 2446, 2448, -1, 2448, 2449, 2447, -1, + 2449, 2448, 2450, -1, 2450, 2451, 2449, -1, + 2451, 2450, 2452, -1, 2452, 2453, 2451, -1, + 2453, 2452, 2454, -1, 2454, 2455, 2453, -1, + 2455, 2454, 2456, -1, 2456, 2457, 2455, -1, + 2457, 2456, 2458, -1, 2458, 2459, 2457, -1, + 2459, 2458, 2460, -1, 2460, 2461, 2459, -1, + 2461, 2460, 2462, -1, 2462, 2463, 2461, -1, + 2463, 2462, 2464, -1, 2464, 2465, 2463, -1, + 2465, 2464, 2466, -1, 2466, 2467, 2465, -1, + 2467, 2466, 2468, -1, 2468, 2469, 2467, -1, + 2469, 2468, 2470, -1, 2470, 2471, 2469, -1, + 2471, 2470, 2472, -1, 2472, 2473, 2471, -1, + 2473, 2472, 2474, -1, 2474, 2475, 2473, -1, + 2475, 2474, 2476, -1, 2476, 2477, 2475, -1, + 2477, 2476, 2478, -1, 2478, 2479, 2477, -1, + 2479, 2478, 2480, -1, 2480, 2481, 2479, -1, + 2481, 2480, 2482, -1, 2482, 2483, 2481, -1, + 2483, 2482, 2484, -1, 2484, 2485, 2483, -1, + 2485, 2484, 2486, -1, 2486, 2487, 2485, -1, + 2487, 2486, 2488, -1, 2488, 2489, 2487, -1, + 2489, 2488, 2490, -1, 2490, 2491, 2489, -1, + 2491, 2490, 2492, -1, 2492, 2493, 2491, -1, + 2493, 2492, 2494, -1, 2494, 2495, 2493, -1, + 2495, 2494, 2496, -1, 2496, 2497, 2495, -1, + 2498, 2499, 2500, -1, 2498, 2500, 2497, -1, + 2497, 2496, 2498, -1, 2501, 2498, 2496, -1, + 2498, 2501, 2502, -1, 2502, 2499, 2498, -1, + 2503, 2504, 2499, -1, 2499, 2502, 2503, -1, + 2505, 2506, 2507, -1, 2508, 2509, 2510, -1, + 2511, 2512, 2506, -1, 2506, 2512, 2510, -1, + 2513, 2514, 2515, -1, 2513, 2515, 2516, -1, + 2517, 2515, 2518, -1, 2517, 2516, 2515, -1, + 2519, 2517, 2520, -1, 2519, 2516, 2517, -1, + 2519, 2521, 2516, -1, 2519, 2520, 2521, -1, + 2522, 2523, 2524, -1, 2525, 2526, 2527, -1, + 2525, 2521, 2528, -1, 2529, 2525, 2528, -1, + 2528, 2522, 2529, -1, 2528, 2523, 2522, -1, + 2523, 2528, 2521, -1, 2530, 2523, 2521, -1, + 2530, 2524, 2523, -1, 2530, 2531, 2524, -1, + 2531, 2530, 2521, -1, 2531, 2521, 2520, -1, + 2520, 2524, 2531, -1, 2524, 2520, 2517, -1, + 2517, 2518, 2524, -1, 2532, 2533, 2534, -1, + 2532, 2535, 2533, -1, 2535, 2532, 2536, -1, + 2536, 2537, 2535, -1, 2537, 2536, 2538, -1, + 2538, 2539, 2537, -1, 2539, 2538, 2540, -1, + 2540, 2541, 2539, -1, 2541, 2540, 2542, -1, + 2542, 2543, 2541, -1, 2543, 2542, 2544, -1, + 2544, 2545, 2543, -1, 2545, 2544, 2546, -1, + 2546, 2547, 2545, -1, 2547, 2546, 2548, -1, + 2548, 2549, 2547, -1, 2549, 2548, 2550, -1, + 2550, 2518, 2549, -1, 2518, 2550, 2551, -1, + 2551, 2524, 2518, -1, 2551, 2522, 2524, -1, + 2551, 2552, 2522, -1, 2552, 2551, 2550, -1, + 2550, 2553, 2552, -1, 2553, 2550, 2548, -1, + 2548, 2554, 2553, -1, 2554, 2548, 2546, -1, + 2546, 2555, 2554, -1, 2555, 2546, 2544, -1, + 2544, 2556, 2555, -1, 2556, 2544, 2542, -1, + 2542, 2557, 2556, -1, 2557, 2542, 2540, -1, + 2540, 2558, 2557, -1, 2558, 2540, 2538, -1, + 2538, 2559, 2558, -1, 2559, 2538, 2536, -1, + 2536, 2560, 2559, -1, 2560, 2536, 2532, -1, + 2532, 2534, 2560, -1, 2561, 2562, 2563, -1, + 2563, 2564, 2561, -1, 2564, 2563, 2565, -1, + 2565, 2566, 2564, -1, 2566, 2565, 2567, -1, + 2567, 2568, 2566, -1, 2568, 2567, 2569, -1, + 2569, 2570, 2568, -1, 2570, 2569, 2571, -1, + 2571, 2572, 2570, -1, 2572, 2571, 2573, -1, + 2573, 2574, 2572, -1, 2575, 2576, 2574, -1, + 2574, 2573, 2575, -1, 2577, 2575, 2573, -1, + 2573, 2578, 2577, -1, 2578, 2573, 2571, -1, + 2571, 2579, 2578, -1, 2579, 2571, 2569, -1, + 2569, 2580, 2579, -1, 2580, 2569, 2567, -1, + 2567, 2581, 2580, -1, 2581, 2567, 2565, -1, + 2565, 2582, 2581, -1, 2582, 2565, 2563, -1, + 2563, 2583, 2582, -1, 2583, 2563, 2562, -1, + 2562, 2584, 2583, -1, 2562, 2585, 2584, -1, + 2562, 2561, 2585, -1, 2586, 2587, 2588, -1, + 2589, 2590, 2591, -1, 2589, 2591, 2592, -1, + 2588, 2592, 2591, -1, 2591, 2593, 2588, -1, + 2593, 2591, 2594, -1, 2594, 2595, 2593, -1, + 2595, 2594, 2596, -1, 2596, 2597, 2595, -1, + 2597, 2596, 2598, -1, 2598, 2599, 2597, -1, + 2599, 2598, 2600, -1, 2600, 2601, 2599, -1, + 2601, 2600, 2602, -1, 2602, 2603, 2601, -1, + 2603, 2602, 2604, -1, 2604, 2605, 2603, -1, + 2605, 2604, 2606, -1, 2606, 2607, 2605, -1, + 2607, 2606, 2608, -1, 2608, 2609, 2607, -1, + 2609, 2608, 2610, -1, 2610, 2611, 2609, -1, + 2611, 2610, 2612, -1, 2611, 2612, 2613, -1, + 2611, 2613, 2614, -1, 2614, 2609, 2611, -1, + 2609, 2614, 2615, -1, 2615, 2607, 2609, -1, + 2607, 2615, 2616, -1, 2616, 2605, 2607, -1, + 2605, 2616, 2617, -1, 2617, 2603, 2605, -1, + 2603, 2617, 2618, -1, 2618, 2601, 2603, -1, + 2601, 2618, 2619, -1, 2619, 2599, 2601, -1, + 2599, 2619, 2620, -1, 2620, 2597, 2599, -1, + 2597, 2620, 2621, -1, 2621, 2595, 2597, -1, + 2595, 2621, 2622, -1, 2622, 2593, 2595, -1, + 2593, 2622, 2623, -1, 2623, 2588, 2593, -1, + 2623, 2586, 2588, -1, 2623, 2624, 2586, -1, + 2624, 2623, 2622, -1, 2622, 2625, 2624, -1, + 2625, 2622, 2621, -1, 2621, 2626, 2625, -1, + 2626, 2621, 2620, -1, 2620, 2627, 2626, -1, + 2627, 2620, 2619, -1, 2619, 2628, 2627, -1, + 2628, 2619, 2618, -1, 2618, 2629, 2628, -1, + 2629, 2618, 2617, -1, 2617, 2630, 2629, -1, + 2630, 2617, 2616, -1, 2616, 2631, 2630, -1, + 2631, 2616, 2615, -1, 2615, 2632, 2631, -1, + 2632, 2615, 2614, -1, 2614, 2633, 2632, -1, + 2633, 2614, 2613, -1, 2633, 2613, 2634, -1, + 2634, 2635, 2633, -1, 2635, 2634, 2636, -1, + 2636, 2637, 2635, -1, 2637, 2636, 2638, -1, + 2638, 2639, 2637, -1, 2639, 2638, 2640, -1, + 2640, 2641, 2639, -1, 2641, 2640, 2642, -1, + 2642, 2643, 2641, -1, 2643, 2642, 2644, -1, + 2644, 2645, 2643, -1, 2645, 2644, 2646, -1, + 2646, 2647, 2645, -1, 2647, 2646, 2648, -1, + 2648, 2649, 2647, -1, 2649, 2648, 2650, -1, + 2650, 2651, 2649, -1, 2651, 2650, 2652, -1, + 2652, 2653, 2651, -1, 2653, 2652, 2654, -1, + 2654, 2655, 2653, -1, 2655, 2654, 2656, -1, + 2656, 2657, 2655, -1, 2657, 2656, 2658, -1, + 2658, 2659, 2657, -1, 2659, 2658, 2660, -1, + 2659, 2660, 2661, -1, 2661, 2662, 2659, -1, + 2662, 2661, 2663, -1, 2663, 2664, 2662, -1, + 2664, 2663, 2665, -1, 2665, 2666, 2664, -1, + 2666, 2665, 2667, -1, 2667, 2668, 2666, -1, + 2668, 2667, 2669, -1, 2669, 2670, 2668, -1, + 2670, 2669, 2671, -1, 2671, 2672, 2670, -1, + 2672, 2671, 2673, -1, 2673, 2674, 2672, -1, + 2674, 2673, 2675, -1, 2675, 2676, 2674, -1, + 2676, 2675, 2677, -1, 2677, 2678, 2676, -1, + 2678, 2677, 2679, -1, 2679, 2680, 2678, -1, + 2680, 2679, 2681, -1, 2681, 2682, 2680, -1, + 2682, 2681, 2683, -1, 2683, 2684, 2682, -1, + 2684, 2683, 2685, -1, 2685, 2686, 2684, -1, + 2686, 2685, 2585, -1, 2686, 2585, 2561, -1, + 2561, 2687, 2686, -1, 2687, 2561, 2564, -1, + 2564, 2688, 2687, -1, 2688, 2564, 2566, -1, + 2566, 2689, 2688, -1, 2689, 2566, 2568, -1, + 2568, 2690, 2689, -1, 2690, 2568, 2570, -1, + 2570, 2691, 2690, -1, 2691, 2570, 2572, -1, + 2572, 2692, 2691, -1, 2692, 2572, 2574, -1, + 2574, 2693, 2692, -1, 2693, 2574, 2576, -1, + 2576, 2694, 2693, -1, 2695, 2696, 2697, -1, + 2698, 2699, 2696, -1, 2699, 2697, 2696, -1, + 2699, 2700, 2697, -1, 2699, 2698, 2700, -1, + 2698, 2701, 2700, -1, 2698, 2696, 2701, -1, + 2696, 2702, 2701, -1, 2702, 2696, 2694, -1, + 2694, 2576, 2702, -1, 2702, 2703, 2704, -1, + 2703, 2702, 2576, -1, 2576, 2575, 2703, -1, + 2705, 2703, 2706, -1, 2703, 2707, 2706, -1, + 2707, 2703, 2575, -1, 2575, 2577, 2707, -1, + 2707, 2708, 2709, -1, 2710, 2708, 2711, -1, + 2711, 2712, 2710, -1, 2712, 2711, 2713, -1, + 2713, 2714, 2712, -1, 2714, 2713, 2715, -1, + 2715, 2716, 2714, -1, 2716, 2715, 2717, -1, + 2717, 2718, 2716, -1, 2718, 2717, 2719, -1, + 2719, 2720, 2718, -1, 2720, 2719, 2721, -1, + 2721, 2722, 2720, -1, 2722, 2721, 2723, -1, + 2723, 2724, 2722, -1, 2724, 2723, 2725, -1, + 2725, 2726, 2724, -1, 2725, 2727, 2726, -1, + 2725, 2728, 2727, -1, 2728, 2725, 2723, -1, + 2723, 2729, 2728, -1, 2729, 2723, 2721, -1, + 2721, 2730, 2729, -1, 2730, 2721, 2719, -1, + 2719, 2731, 2730, -1, 2731, 2719, 2717, -1, + 2717, 2732, 2731, -1, 2732, 2717, 2715, -1, + 2715, 2733, 2732, -1, 2733, 2715, 2713, -1, + 2713, 2734, 2733, -1, 2734, 2713, 2711, -1, + 2711, 2735, 2734, -1, 2735, 2711, 2708, -1, + 2735, 2708, 2707, -1, 2735, 2707, 2577, -1, + 2577, 2734, 2735, -1, 2734, 2577, 2578, -1, + 2578, 2733, 2734, -1, 2733, 2578, 2579, -1, + 2579, 2732, 2733, -1, 2732, 2579, 2580, -1, + 2580, 2731, 2732, -1, 2731, 2580, 2581, -1, + 2581, 2730, 2731, -1, 2730, 2581, 2582, -1, + 2582, 2729, 2730, -1, 2729, 2582, 2583, -1, + 2583, 2728, 2729, -1, 2728, 2583, 2584, -1, + 2584, 2727, 2728, -1, 2584, 2736, 2727, -1, + 2736, 2584, 2585, -1, 2585, 2737, 2736, -1, + 2737, 2585, 2685, -1, 2685, 2738, 2737, -1, + 2738, 2685, 2683, -1, 2683, 2739, 2738, -1, + 2739, 2683, 2681, -1, 2681, 2740, 2739, -1, + 2740, 2681, 2679, -1, 2679, 2741, 2740, -1, + 2741, 2679, 2677, -1, 2677, 2742, 2741, -1, + 2742, 2677, 2675, -1, 2675, 2743, 2742, -1, + 2743, 2675, 2673, -1, 2673, 2744, 2743, -1, + 2744, 2673, 2671, -1, 2671, 2745, 2744, -1, + 2745, 2671, 2669, -1, 2669, 2746, 2745, -1, + 2746, 2669, 2667, -1, 2667, 2747, 2746, -1, + 2747, 2667, 2665, -1, 2665, 2748, 2747, -1, + 2748, 2665, 2663, -1, 2663, 2749, 2748, -1, + 2749, 2663, 2661, -1, 2661, 2750, 2749, -1, + 2750, 2661, 2660, -1, 2660, 2751, 2750, -1, + 2660, 2752, 2751, -1, 2752, 2660, 2658, -1, + 2658, 2753, 2752, -1, 2753, 2658, 2656, -1, + 2656, 2754, 2753, -1, 2754, 2656, 2654, -1, + 2654, 2755, 2754, -1, 2755, 2654, 2652, -1, + 2652, 2756, 2755, -1, 2756, 2652, 2650, -1, + 2650, 2757, 2756, -1, 2757, 2650, 2648, -1, + 2648, 2758, 2757, -1, 2758, 2648, 2646, -1, + 2646, 2759, 2758, -1, 2759, 2646, 2644, -1, + 2644, 2760, 2759, -1, 2760, 2644, 2642, -1, + 2642, 2761, 2760, -1, 2761, 2642, 2640, -1, + 2640, 2762, 2761, -1, 2762, 2640, 2638, -1, + 2638, 2763, 2762, -1, 2763, 2638, 2636, -1, + 2636, 2764, 2763, -1, 2764, 2636, 2634, -1, + 2634, 2765, 2764, -1, 2765, 2634, 2613, -1, + 2613, 2766, 2765, -1, 2766, 2613, 2612, -1, + 2612, 2534, 2766, -1, 2612, 2560, 2534, -1, + 2560, 2612, 2610, -1, 2610, 2559, 2560, -1, + 2559, 2610, 2608, -1, 2608, 2558, 2559, -1, + 2558, 2608, 2606, -1, 2606, 2557, 2558, -1, + 2557, 2606, 2604, -1, 2604, 2556, 2557, -1, + 2556, 2604, 2602, -1, 2602, 2555, 2556, -1, + 2555, 2602, 2600, -1, 2600, 2554, 2555, -1, + 2554, 2600, 2598, -1, 2598, 2553, 2554, -1, + 2553, 2598, 2596, -1, 2596, 2552, 2553, -1, + 2552, 2596, 2594, -1, 2594, 2522, 2552, -1, + 2522, 2594, 2591, -1, 2591, 2529, 2522, -1, + 2529, 2591, 2590, -1, 2590, 2525, 2529, -1, + 2590, 2589, 2525, -1, 2589, 2592, 2525, -1, + 2592, 2526, 2525, -1, 2526, 2592, 2588, -1, + 2526, 2588, 2587, -1, 2587, 2527, 2526, -1, + 2767, 2527, 2587, -1, 2767, 2587, 2586, -1, + 2767, 2586, 2768, -1, 2768, 2527, 2767, -1, + 2768, 2769, 2527, -1, 2768, 2586, 2769, -1, + 2770, 2769, 2586, -1, 2586, 2771, 2770, -1, + 2771, 2586, 2624, -1, 2624, 2772, 2771, -1, + 2772, 2624, 2625, -1, 2625, 2773, 2772, -1, + 2773, 2625, 2626, -1, 2626, 2774, 2773, -1, + 2774, 2626, 2627, -1, 2627, 2775, 2774, -1, + 2775, 2627, 2628, -1, 2628, 2776, 2775, -1, + 2776, 2628, 2629, -1, 2629, 2777, 2776, -1, + 2777, 2629, 2630, -1, 2630, 2778, 2777, -1, + 2778, 2630, 2631, -1, 2631, 2779, 2778, -1, + 2779, 2631, 2632, -1, 2632, 2780, 2779, -1, + 2780, 2632, 2633, -1, 2780, 2633, 2635, -1, + 2635, 2781, 2780, -1, 2781, 2635, 2637, -1, + 2637, 2782, 2781, -1, 2782, 2637, 2639, -1, + 2639, 2783, 2782, -1, 2783, 2639, 2641, -1, + 2641, 2784, 2783, -1, 2784, 2641, 2643, -1, + 2643, 2785, 2784, -1, 2785, 2643, 2645, -1, + 2645, 2786, 2785, -1, 2786, 2645, 2647, -1, + 2647, 2787, 2786, -1, 2787, 2647, 2649, -1, + 2649, 2788, 2787, -1, 2788, 2649, 2651, -1, + 2651, 2789, 2788, -1, 2789, 2651, 2653, -1, + 2653, 2790, 2789, -1, 2790, 2653, 2655, -1, + 2655, 2791, 2790, -1, 2791, 2655, 2657, -1, + 2657, 2792, 2791, -1, 2792, 2657, 2659, -1, + 2792, 2659, 2662, -1, 2662, 2793, 2792, -1, + 2793, 2662, 2664, -1, 2664, 2794, 2793, -1, + 2794, 2664, 2666, -1, 2666, 2795, 2794, -1, + 2795, 2666, 2668, -1, 2668, 2796, 2795, -1, + 2796, 2668, 2670, -1, 2670, 2797, 2796, -1, + 2797, 2670, 2672, -1, 2672, 2798, 2797, -1, + 2798, 2672, 2674, -1, 2674, 2799, 2798, -1, + 2799, 2674, 2676, -1, 2676, 2800, 2799, -1, + 2800, 2676, 2678, -1, 2678, 2801, 2800, -1, + 2801, 2678, 2680, -1, 2680, 2802, 2801, -1, + 2802, 2680, 2682, -1, 2682, 2803, 2802, -1, + 2803, 2682, 2684, -1, 2684, 2804, 2803, -1, + 2804, 2684, 2686, -1, 2804, 2686, 2687, -1, + 2687, 2805, 2804, -1, 2805, 2687, 2688, -1, + 2688, 2806, 2805, -1, 2806, 2688, 2689, -1, + 2689, 2807, 2806, -1, 2807, 2689, 2690, -1, + 2690, 2808, 2807, -1, 2808, 2690, 2691, -1, + 2691, 2809, 2808, -1, 2809, 2691, 2692, -1, + 2692, 2810, 2809, -1, 2810, 2692, 2693, -1, + 2693, 2811, 2810, -1, 2811, 2693, 2694, -1, + 2694, 2812, 2811, -1, 2812, 2694, 2696, -1, + 2696, 2695, 2812, -1, 2813, 2814, 2815, -1, + 2815, 2816, 2813, -1, 2816, 2815, 2817, -1, + 2817, 2818, 2816, -1, 2818, 2817, 2819, -1, + 2819, 2820, 2818, -1, 2820, 2819, 2821, -1, + 2821, 2822, 2820, -1, 2822, 2821, 2823, -1, + 2823, 2824, 2822, -1, 2824, 2823, 2825, -1, + 2825, 2826, 2824, -1, 2826, 2825, 2827, -1, + 2827, 2828, 2826, -1, 2828, 2827, 2829, -1, + 2829, 2830, 2828, -1, 2829, 2831, 2830, -1, + 2829, 2832, 2831, -1, 2832, 2829, 2827, -1, + 2827, 2833, 2832, -1, 2833, 2827, 2825, -1, + 2825, 2834, 2833, -1, 2834, 2825, 2823, -1, + 2823, 2835, 2834, -1, 2835, 2823, 2821, -1, + 2821, 2836, 2835, -1, 2836, 2821, 2819, -1, + 2819, 2837, 2836, -1, 2837, 2819, 2817, -1, + 2817, 2838, 2837, -1, 2838, 2817, 2815, -1, + 2815, 2839, 2838, -1, 2839, 2815, 2814, -1, + 2814, 2840, 2839, -1, 2841, 2842, 2843, -1, + 2842, 2841, 2844, -1, 2842, 2844, 2845, -1, + 2842, 2845, 2846, -1, 2846, 2843, 2842, -1, + 2846, 2847, 2843, -1, 2846, 2848, 2847, -1, + 2848, 2846, 2845, -1, 2845, 2849, 2848, -1, + 2845, 2850, 2849, -1, 2850, 2845, 2844, -1, + 2844, 2851, 2850, -1, 2844, 2852, 2851, -1, + 2852, 2844, 2841, -1, 2841, 2853, 2852, -1, + 2841, 2843, 2853, -1, 2854, 2855, 2856, -1, + 2856, 2857, 2854, -1, 2857, 2856, 2858, -1, + 2858, 2859, 2857, -1, 2859, 2858, 2860, -1, + 2860, 2861, 2859, -1, 2860, 2862, 2861, -1, + 2860, 2863, 2862, -1, 2863, 2860, 2858, -1, + 2858, 2864, 2863, -1, 2864, 2858, 2856, -1, + 2856, 2865, 2864, -1, 2865, 2856, 2855, -1, + 2865, 2855, 2866, -1, 2866, 2867, 2865, -1, + 2867, 2866, 2868, -1, 2868, 2869, 2867, -1, + 2869, 2868, 2870, -1, 2869, 2870, 2853, -1, + 2869, 2853, 2843, -1, 2843, 2867, 2869, -1, + 2867, 2843, 2847, -1, 2847, 2865, 2867, -1, + 2847, 2864, 2865, -1, 2864, 2847, 2848, -1, + 2848, 2863, 2864, -1, 2863, 2848, 2849, -1, + 2849, 2862, 2863, -1, 2849, 2871, 2862, -1, + 2871, 2849, 2850, -1, 2850, 2872, 2871, -1, + 2872, 2850, 2851, -1, 2851, 2873, 2872, -1, + 2851, 2874, 2873, -1, 2874, 2851, 2852, -1, + 2852, 2875, 2874, -1, 2875, 2852, 2853, -1, + 2853, 2876, 2875, -1, 2876, 2853, 2870, -1, + 2870, 2877, 2876, -1, 2870, 2878, 2877, -1, + 2878, 2870, 2868, -1, 2868, 2879, 2878, -1, + 2879, 2868, 2866, -1, 2866, 2880, 2879, -1, + 2880, 2866, 2855, -1, 2855, 2881, 2880, -1, + 2855, 2854, 2881, -1, 2882, 2881, 2854, -1, + 2854, 2883, 2882, -1, 2883, 2854, 2857, -1, + 2857, 2884, 2883, -1, 2884, 2857, 2859, -1, + 2859, 2885, 2884, -1, 2885, 2859, 2861, -1, + 2861, 2886, 2885, -1, 2861, 2887, 2886, -1, + 2887, 2861, 2862, -1, 2862, 2888, 2887, -1, + 2888, 2862, 2871, -1, 2871, 2889, 2888, -1, + 2889, 2871, 2872, -1, 2872, 2890, 2889, -1, + 2890, 2872, 2873, -1, 2873, 2891, 2890, -1, + 2873, 2892, 2891, -1, 2892, 2873, 2874, -1, + 2874, 2893, 2892, -1, 2893, 2874, 2875, -1, + 2875, 2894, 2893, -1, 2894, 2875, 2876, -1, + 2876, 2895, 2894, -1, 2895, 2876, 2877, -1, + 2877, 2896, 2895, -1, 2877, 2897, 2896, -1, + 2897, 2877, 2878, -1, 2878, 2898, 2897, -1, + 2898, 2878, 2879, -1, 2879, 2899, 2898, -1, + 2899, 2879, 2880, -1, 2880, 2900, 2899, -1, + 2900, 2880, 2881, -1, 2881, 2901, 2900, -1, + 2881, 2882, 2901, -1, 2902, 2901, 2882, -1, + 2882, 2903, 2902, -1, 2903, 2882, 2883, -1, + 2883, 2904, 2903, -1, 2904, 2883, 2884, -1, + 2884, 2905, 2904, -1, 2905, 2884, 2885, -1, + 2885, 2906, 2905, -1, 2906, 2885, 2886, -1, + 2886, 2907, 2906, -1, 2886, 2908, 2907, -1, + 2908, 2886, 2887, -1, 2887, 2909, 2908, -1, + 2909, 2887, 2888, -1, 2888, 2910, 2909, -1, + 2910, 2888, 2889, -1, 2889, 2911, 2910, -1, + 2911, 2889, 2890, -1, 2890, 2912, 2911, -1, + 2912, 2890, 2891, -1, 2891, 2913, 2912, -1, + 2891, 2914, 2913, -1, 2914, 2891, 2892, -1, + 2892, 2915, 2914, -1, 2915, 2892, 2893, -1, + 2893, 2916, 2915, -1, 2916, 2893, 2894, -1, + 2894, 2917, 2916, -1, 2917, 2894, 2895, -1, + 2895, 2918, 2917, -1, 2918, 2895, 2896, -1, + 2896, 2919, 2918, -1, 2896, 2920, 2919, -1, + 2920, 2896, 2897, -1, 2897, 2921, 2920, -1, + 2921, 2897, 2898, -1, 2898, 2922, 2921, -1, + 2922, 2898, 2899, -1, 2899, 2923, 2922, -1, + 2923, 2899, 2900, -1, 2900, 2924, 2923, -1, + 2924, 2900, 2901, -1, 2901, 2925, 2924, -1, + 2901, 2902, 2925, -1, 2926, 2925, 2902, -1, + 2902, 2927, 2926, -1, 2927, 2902, 2903, -1, + 2903, 2928, 2927, -1, 2928, 2903, 2904, -1, + 2904, 2929, 2928, -1, 2929, 2904, 2905, -1, + 2905, 2930, 2929, -1, 2930, 2905, 2906, -1, + 2906, 2931, 2930, -1, 2931, 2906, 2907, -1, + 2907, 2932, 2931, -1, 2907, 2933, 2932, -1, + 2933, 2907, 2908, -1, 2908, 2934, 2933, -1, + 2934, 2908, 2909, -1, 2909, 2935, 2934, -1, + 2935, 2909, 2910, -1, 2910, 2936, 2935, -1, + 2936, 2910, 2911, -1, 2911, 2937, 2936, -1, + 2937, 2911, 2912, -1, 2912, 2938, 2937, -1, + 2938, 2912, 2913, -1, 2913, 2939, 2938, -1, + 2913, 2940, 2939, -1, 2940, 2913, 2914, -1, + 2914, 2941, 2940, -1, 2941, 2914, 2915, -1, + 2915, 2942, 2941, -1, 2942, 2915, 2916, -1, + 2916, 2943, 2942, -1, 2943, 2916, 2917, -1, + 2917, 2944, 2943, -1, 2944, 2917, 2918, -1, + 2918, 2945, 2944, -1, 2945, 2918, 2919, -1, + 2919, 2946, 2945, -1, 2919, 2947, 2946, -1, + 2947, 2919, 2920, -1, 2920, 2948, 2947, -1, + 2948, 2920, 2921, -1, 2921, 2949, 2948, -1, + 2949, 2921, 2922, -1, 2922, 2950, 2949, -1, + 2950, 2922, 2923, -1, 2923, 2951, 2950, -1, + 2951, 2923, 2924, -1, 2924, 2952, 2951, -1, + 2952, 2924, 2925, -1, 2925, 2953, 2952, -1, + 2925, 2926, 2953, -1, 2954, 2953, 2926, -1, + 2926, 2955, 2954, -1, 2955, 2926, 2927, -1, + 2927, 2956, 2955, -1, 2956, 2927, 2928, -1, + 2928, 2957, 2956, -1, 2957, 2928, 2929, -1, + 2929, 2958, 2957, -1, 2958, 2929, 2930, -1, + 2930, 2959, 2958, -1, 2959, 2930, 2931, -1, + 2931, 2960, 2959, -1, 2960, 2931, 2932, -1, + 2932, 2961, 2960, -1, 2932, 2962, 2961, -1, + 2962, 2932, 2933, -1, 2933, 2963, 2962, -1, + 2963, 2933, 2934, -1, 2934, 2964, 2963, -1, + 2964, 2934, 2935, -1, 2935, 2965, 2964, -1, + 2965, 2935, 2936, -1, 2936, 2966, 2965, -1, + 2966, 2936, 2937, -1, 2937, 2967, 2966, -1, + 2967, 2937, 2938, -1, 2938, 2968, 2967, -1, + 2968, 2938, 2939, -1, 2939, 2969, 2968, -1, + 2939, 2970, 2969, -1, 2970, 2939, 2940, -1, + 2940, 2971, 2970, -1, 2971, 2940, 2941, -1, + 2941, 2972, 2971, -1, 2972, 2941, 2942, -1, + 2942, 2973, 2972, -1, 2973, 2942, 2943, -1, + 2943, 2974, 2973, -1, 2974, 2943, 2944, -1, + 2944, 2975, 2974, -1, 2975, 2944, 2945, -1, + 2945, 2976, 2975, -1, 2976, 2945, 2946, -1, + 2946, 2977, 2976, -1, 2946, 2978, 2977, -1, + 2978, 2946, 2947, -1, 2947, 2979, 2978, -1, + 2979, 2947, 2948, -1, 2948, 2980, 2979, -1, + 2980, 2948, 2949, -1, 2949, 2981, 2980, -1, + 2981, 2949, 2950, -1, 2950, 2982, 2981, -1, + 2982, 2950, 2951, -1, 2951, 2983, 2982, -1, + 2983, 2951, 2952, -1, 2952, 2984, 2983, -1, + 2984, 2952, 2953, -1, 2953, 2985, 2984, -1, + 2953, 2954, 2985, -1, 2986, 2985, 2954, -1, + 2954, 2987, 2986, -1, 2987, 2954, 2955, -1, + 2955, 2988, 2987, -1, 2988, 2955, 2956, -1, + 2956, 2989, 2988, -1, 2989, 2956, 2957, -1, + 2957, 2990, 2989, -1, 2990, 2957, 2958, -1, + 2958, 2991, 2990, -1, 2991, 2958, 2959, -1, + 2959, 2992, 2991, -1, 2992, 2959, 2960, -1, + 2960, 2993, 2992, -1, 2993, 2960, 2961, -1, + 2961, 2994, 2993, -1, 2961, 2995, 2994, -1, + 2995, 2961, 2962, -1, 2962, 2996, 2995, -1, + 2996, 2962, 2963, -1, 2963, 2997, 2996, -1, + 2997, 2963, 2964, -1, 2964, 2998, 2997, -1, + 2998, 2964, 2965, -1, 2965, 2999, 2998, -1, + 2999, 2965, 2966, -1, 2966, 3000, 2999, -1, + 3000, 2966, 2967, -1, 2967, 3001, 3000, -1, + 3001, 2967, 2968, -1, 2968, 3002, 3001, -1, + 3002, 2968, 2969, -1, 2969, 3003, 3002, -1, + 2969, 3004, 3003, -1, 3004, 2969, 2970, -1, + 2970, 3005, 3004, -1, 3005, 2970, 2971, -1, + 2971, 3006, 3005, -1, 3006, 2971, 2972, -1, + 2972, 3007, 3006, -1, 3007, 2972, 2973, -1, + 2973, 3008, 3007, -1, 3008, 2973, 2974, -1, + 2974, 3009, 3008, -1, 3009, 2974, 2975, -1, + 2975, 3010, 3009, -1, 3010, 2975, 2976, -1, + 2976, 3011, 3010, -1, 3011, 2976, 2977, -1, + 2977, 3012, 3011, -1, 2977, 3013, 3012, -1, + 3013, 2977, 2978, -1, 2978, 3014, 3013, -1, + 3014, 2978, 2979, -1, 2979, 3015, 3014, -1, + 3015, 2979, 2980, -1, 2980, 3016, 3015, -1, + 3016, 2980, 2981, -1, 2981, 3017, 3016, -1, + 3017, 2981, 2982, -1, 2982, 3018, 3017, -1, + 3018, 2982, 2983, -1, 2983, 3019, 3018, -1, + 3019, 2983, 2984, -1, 2984, 3020, 3019, -1, + 3020, 2984, 2985, -1, 2986, 2839, 2840, -1, + 2839, 2986, 2987, -1, 2987, 2838, 2839, -1, + 2838, 2987, 2988, -1, 2988, 2837, 2838, -1, + 2837, 2988, 2989, -1, 2989, 2836, 2837, -1, + 2836, 2989, 2990, -1, 2990, 2835, 2836, -1, + 2835, 2990, 2991, -1, 2991, 2834, 2835, -1, + 2834, 2991, 2992, -1, 2992, 2833, 2834, -1, + 2833, 2992, 2993, -1, 2993, 2832, 2833, -1, + 2832, 2993, 2994, -1, 2994, 2831, 2832, -1, + 2994, 3021, 2831, -1, 3021, 2994, 2995, -1, + 2995, 3022, 3021, -1, 3022, 2995, 2996, -1, + 2996, 3023, 3022, -1, 3023, 2996, 2997, -1, + 2997, 3024, 3023, -1, 3024, 2997, 2998, -1, + 2998, 3025, 3024, -1, 3025, 2998, 2999, -1, + 2999, 3026, 3025, -1, 3026, 2999, 3000, -1, + 3000, 3027, 3026, -1, 3027, 3000, 3001, -1, + 3001, 3028, 3027, -1, 3028, 3001, 3002, -1, + 3002, 3029, 3028, -1, 3029, 3002, 3003, -1, + 3003, 3030, 3029, -1, 3003, 3031, 3030, -1, + 3031, 3003, 3004, -1, 3004, 3032, 3031, -1, + 3032, 3004, 3005, -1, 3005, 3033, 3032, -1, + 3033, 3005, 3006, -1, 3006, 3034, 3033, -1, + 3034, 3006, 3007, -1, 3007, 3035, 3034, -1, + 3035, 3007, 3008, -1, 3008, 3036, 3035, -1, + 3036, 3008, 3009, -1, 3009, 3037, 3036, -1, + 3037, 3009, 3010, -1, 3010, 3038, 3037, -1, + 3038, 3010, 3011, -1, 3011, 3039, 3038, -1, + 3039, 3011, 3012, -1, 3012, 3040, 3039, -1, + 3012, 3041, 3040, -1, 3041, 3012, 3013, -1, + 3013, 3042, 3041, -1, 3042, 3013, 3014, -1, + 3014, 3043, 3042, -1, 3043, 3014, 3015, -1, + 3015, 3044, 3043, -1, 3044, 3015, 3016, -1, + 3016, 3045, 3044, -1, 3045, 3016, 3017, -1, + 3017, 3046, 3045, -1, 3046, 3017, 3018, -1, + 3018, 3047, 3046, -1, 3047, 3018, 3019, -1, + 3019, 3048, 3047, -1, 3048, 3019, 3020, -1, + 3020, 3049, 3048, -1, 3050, 3051, 3049, -1, + 3050, 2840, 3051, -1, 2840, 2814, 3052, -1, + 3053, 3054, 3052, -1, 3053, 3052, 2814, -1, + 2814, 2813, 3053, -1, 3053, 2695, 3055, -1, + 2695, 3053, 2813, -1, 2813, 2812, 2695, -1, + 2812, 2813, 2816, -1, 2816, 2811, 2812, -1, + 2811, 2816, 2818, -1, 2818, 2810, 2811, -1, + 2810, 2818, 2820, -1, 2820, 2809, 2810, -1, + 2809, 2820, 2822, -1, 2822, 2808, 2809, -1, + 2808, 2822, 2824, -1, 2824, 2807, 2808, -1, + 2807, 2824, 2826, -1, 2826, 2806, 2807, -1, + 2806, 2826, 2828, -1, 2828, 2805, 2806, -1, + 2805, 2828, 2830, -1, 2830, 2804, 2805, -1, + 2830, 2803, 2804, -1, 2803, 2830, 2831, -1, + 2831, 2802, 2803, -1, 2802, 2831, 3021, -1, + 3021, 2801, 2802, -1, 2801, 3021, 3022, -1, + 3022, 2800, 2801, -1, 2800, 3022, 3023, -1, + 3023, 2799, 2800, -1, 2799, 3023, 3024, -1, + 3024, 2798, 2799, -1, 2798, 3024, 3025, -1, + 3025, 2797, 2798, -1, 2797, 3025, 3026, -1, + 3026, 2796, 2797, -1, 2796, 3026, 3027, -1, + 3027, 2795, 2796, -1, 2795, 3027, 3028, -1, + 3028, 2794, 2795, -1, 2794, 3028, 3029, -1, + 3029, 2793, 2794, -1, 2793, 3029, 3030, -1, + 3030, 2792, 2793, -1, 3030, 2791, 2792, -1, + 2791, 3030, 3031, -1, 3031, 2790, 2791, -1, + 2790, 3031, 3032, -1, 3032, 2789, 2790, -1, + 2789, 3032, 3033, -1, 3033, 2788, 2789, -1, + 2788, 3033, 3034, -1, 3034, 2787, 2788, -1, + 2787, 3034, 3035, -1, 3035, 2786, 2787, -1, + 2786, 3035, 3036, -1, 3036, 2785, 2786, -1, + 2785, 3036, 3037, -1, 3037, 2784, 2785, -1, + 2784, 3037, 3038, -1, 3038, 2783, 2784, -1, + 2783, 3038, 3039, -1, 3039, 2782, 2783, -1, + 2782, 3039, 3040, -1, 3040, 2781, 2782, -1, + 2781, 3040, 3056, -1, 3056, 2780, 2781, -1, + 3056, 2779, 2780, -1, 2779, 3056, 3057, -1, + 3057, 2778, 2779, -1, 2778, 3057, 3058, -1, + 3058, 2777, 2778, -1, 2777, 3058, 3059, -1, + 3059, 2776, 2777, -1, 2776, 3059, 3060, -1, + 3060, 2775, 2776, -1, 2775, 3060, 3061, -1, + 3061, 2774, 2775, -1, 2774, 3061, 3062, -1, + 3062, 2773, 2774, -1, 2773, 3062, 3063, -1, + 3063, 2772, 2773, -1, 2772, 3063, 3064, -1, + 3064, 2771, 2772, -1, 2771, 3064, 3065, -1, + 3065, 2770, 2771, -1, 3066, 3067, 2770, -1, + 2770, 3065, 3066, -1, 3066, 3068, 3069, -1, + 3066, 3070, 3068, -1, 3070, 3066, 3065, -1, + 3065, 3071, 3070, -1, 3071, 3065, 3064, -1, + 3064, 3072, 3071, -1, 3072, 3064, 3063, -1, + 3063, 3073, 3072, -1, 3073, 3063, 3062, -1, + 3062, 3074, 3073, -1, 3074, 3062, 3061, -1, + 3061, 3075, 3074, -1, 3075, 3061, 3060, -1, + 3060, 3076, 3075, -1, 3076, 3060, 3059, -1, + 3059, 3077, 3076, -1, 3077, 3059, 3058, -1, + 3058, 3078, 3077, -1, 3078, 3058, 3057, -1, + 3057, 3079, 3078, -1, 3079, 3057, 3056, -1, + 3079, 3056, 3040, -1, 3079, 3040, 3041, -1, + 3041, 3078, 3079, -1, 3078, 3041, 3042, -1, + 3042, 3077, 3078, -1, 3077, 3042, 3043, -1, + 3043, 3076, 3077, -1, 3076, 3043, 3044, -1, + 3044, 3075, 3076, -1, 3075, 3044, 3045, -1, + 3045, 3074, 3075, -1, 3074, 3045, 3046, -1, + 3046, 3073, 3074, -1, 3073, 3046, 3047, -1, + 3047, 3072, 3073, -1, 3072, 3047, 3048, -1, + 3048, 3071, 3072, -1, 3071, 3048, 3049, -1, + 3049, 3070, 3071, -1, 3052, 3080, 3068, -1, + 3081, 3082, 3083, -1, 3081, 3080, 3082, -1, + 3081, 3068, 3080, -1, 3081, 3083, 3068, -1, + 3083, 3069, 3068, -1, 3069, 3083, 3082, -1, + 3069, 3082, 3084, -1, 3084, 3066, 3069, -1, + 3084, 3067, 3066, -1, 3084, 3082, 3067, -1, + 3067, 3082, 3085, -1, 3085, 2770, 3067, -1, + 3085, 2769, 2770, -1, 3085, 2527, 2769, -1, + 2527, 3085, 3082, -1, 2510, 2509, 3086, -1, + 3087, 3086, 3088, -1, 3086, 3087, 3089, -1, + 3090, 3091, 3092, -1, 3093, 3094, 3095, -1, + 3095, 3096, 3093, -1, 3096, 3095, 3097, -1, + 3097, 3098, 3096, -1, 3098, 3097, 3099, -1, + 3099, 3100, 3098, -1, 3100, 3099, 3101, -1, + 3101, 3102, 3100, -1, 3102, 3101, 3103, -1, + 3103, 3104, 3102, -1, 3104, 3103, 3090, -1, + 3090, 3092, 3104, -1, 3105, 3106, 3107, -1, + 3107, 3108, 3105, -1, 3108, 3107, 3109, -1, + 3109, 3110, 3108, -1, 3110, 3109, 3111, -1, + 3111, 3112, 3110, -1, 3112, 3111, 3113, -1, + 3113, 3114, 3112, -1, 3115, 3116, 3117, -1, + 3117, 3118, 3115, -1, 3118, 3117, 3114, -1, + 3114, 3113, 3118, -1, 3113, 3119, 3118, -1, + 3119, 3113, 3111, -1, 3111, 3120, 3119, -1, + 3120, 3111, 3109, -1, 3109, 3121, 3120, -1, + 3121, 3109, 3107, -1, 3107, 3122, 3121, -1, + 3122, 3107, 3106, -1, 3106, 3123, 3122, -1, + 3123, 3106, 3124, -1, 3124, 3125, 3123, -1, + 3125, 3124, 3126, -1, 3126, 3127, 3125, -1, + 3127, 3126, 3128, -1, 3128, 3129, 3127, -1, + 3130, 3131, 3132, -1, 3132, 3133, 3130, -1, + 3133, 3132, 3134, -1, 3134, 3132, 3135, -1, + 3134, 3135, 3136, -1, 3136, 3137, 3134, -1, + 3137, 3136, 3138, -1, 3138, 3139, 3137, -1, + 3140, 3137, 3139, -1, 3139, 3141, 3140, -1, + 3142, 3143, 3141, -1, 3141, 3139, 3142, -1, + 3144, 3142, 3139, -1, 3139, 3138, 3144, -1, + 3145, 3144, 3138, -1, 3138, 3146, 3145, -1, + 3146, 3138, 3136, -1, 3136, 3147, 3146, -1, + 3147, 3136, 3135, -1, 3135, 3148, 3147, -1, + 3149, 3150, 3151, -1, 3151, 3152, 3149, -1, + 3152, 3151, 3153, -1, 3153, 3154, 3152, -1, + 3154, 3153, 3155, -1, 3155, 3156, 3154, -1, + 3156, 3155, 3148, -1, 3148, 3157, 3156, -1, + 3157, 3148, 3135, -1, 3157, 3135, 3132, -1, + 3157, 3132, 3131, -1, 3131, 3156, 3157, -1, + 3156, 3131, 3158, -1, 3158, 3154, 3156, -1, + 3154, 3158, 3159, -1, 3159, 3152, 3154, -1, + 3152, 3159, 3160, -1, 3160, 3149, 3152, -1, + 3149, 3160, 3161, -1, 3161, 3150, 3149, -1, + 3150, 3161, 3162, -1, 3162, 3163, 3150, -1, + 3163, 3162, 3164, -1, 3164, 3165, 3163, -1, + 3165, 3164, 3166, -1, 3166, 3167, 3165, -1, + 3167, 3166, 3168, -1, 3168, 3169, 3167, -1, + 3169, 3168, 3170, -1, 3170, 3171, 3169, -1, + 3171, 3170, 3172, -1, 3172, 3173, 3171, -1, + 3173, 3172, 3174, -1, 3174, 3175, 3173, -1, + 3175, 3174, 3176, -1, 3176, 3177, 3175, -1, + 3177, 3176, 3178, -1, 3178, 3179, 3177, -1, + 3179, 3178, 3180, -1, 3180, 3181, 3179, -1, + 3181, 3180, 3182, -1, 3182, 3183, 3181, -1, + 3183, 3182, 3184, -1, 3184, 3185, 3183, -1, + 3185, 3184, 3186, -1, 3186, 3187, 3185, -1, + 3187, 3186, 3188, -1, 3188, 3189, 3187, -1, + 3190, 3191, 3192, -1, 3191, 3190, 3193, -1, + 3193, 3194, 3191, -1, 3194, 3193, 3195, -1, + 3195, 3196, 3194, -1, 3196, 3195, 3197, -1, + 3197, 3198, 3196, -1, 3198, 3197, 3199, -1, + 3199, 3200, 3198, -1, 3200, 3199, 3201, -1, + 3201, 3202, 3200, -1, 3202, 3201, 3203, -1, + 3203, 3204, 3202, -1, 3204, 3203, 3205, -1, + 3205, 3206, 3204, -1, 3206, 3205, 3207, -1, + 3207, 3208, 3206, -1, 3208, 3207, 3209, -1, + 3209, 3210, 3208, -1, 3210, 3209, 3211, -1, + 3211, 3212, 3210, -1, 3212, 3211, 3213, -1, + 3213, 3214, 3212, -1, 3214, 3213, 3215, -1, + 3215, 3216, 3214, -1, 3216, 3215, 3217, -1, + 3217, 3218, 3216, -1, 3217, 3219, 3218, -1, + 3219, 3217, 3220, -1, 3220, 3221, 3219, -1, + 3221, 3220, 3222, -1, 3222, 3223, 3221, -1, + 3223, 3222, 3224, -1, 3224, 3225, 3223, -1, + 3225, 3224, 3226, -1, 3226, 3227, 3225, -1, + 3227, 3226, 3228, -1, 3228, 3229, 3227, -1, + 3229, 3228, 3230, -1, 3230, 3231, 3229, -1, + 3231, 3230, 3232, -1, 3232, 3233, 3231, -1, + 3233, 3232, 3234, -1, 3234, 3235, 3233, -1, + 3235, 3234, 3236, -1, 3236, 3237, 3235, -1, + 3237, 3236, 3238, -1, 3238, 3239, 3237, -1, + 3239, 3238, 3240, -1, 3240, 3241, 3239, -1, + 3241, 3240, 3242, -1, 3242, 3243, 3241, -1, + 3243, 3242, 3244, -1, 3244, 3245, 3243, -1, + 3245, 3244, 3246, -1, 3246, 3247, 3245, -1, + 3247, 3246, 3248, -1, 3248, 3249, 3247, -1, + 3249, 3248, 3250, -1, 3250, 3251, 3249, -1, + 3251, 3250, 3252, -1, 3252, 3253, 3251, -1, + 3253, 3252, 3254, -1, 3254, 3255, 3253, -1, + 3255, 3254, 3256, -1, 3256, 3257, 3255, -1, + 3257, 3256, 3258, -1, 3258, 3259, 3257, -1, + 3259, 3258, 3260, -1, 3260, 3261, 3259, -1, + 3261, 3260, 3262, -1, 3262, 3263, 3261, -1, + 3263, 3262, 3189, -1, 3189, 3188, 3263, -1, + 3263, 3188, 3264, -1, 3264, 3261, 3263, -1, + 3261, 3264, 3265, -1, 3265, 3259, 3261, -1, + 3259, 3265, 3266, -1, 3266, 3257, 3259, -1, + 3257, 3266, 3267, -1, 3267, 3255, 3257, -1, + 3255, 3267, 3268, -1, 3268, 3253, 3255, -1, + 3253, 3268, 3269, -1, 3269, 3251, 3253, -1, + 3251, 3269, 3270, -1, 3270, 3249, 3251, -1, + 3249, 3270, 3271, -1, 3271, 3247, 3249, -1, + 3247, 3271, 3272, -1, 3272, 3245, 3247, -1, + 3245, 3272, 3273, -1, 3273, 3243, 3245, -1, + 3243, 3273, 3274, -1, 3274, 3241, 3243, -1, + 3241, 3274, 3275, -1, 3275, 3239, 3241, -1, + 3239, 3275, 3276, -1, 3276, 3237, 3239, -1, + 3237, 3276, 3277, -1, 3277, 3235, 3237, -1, + 3235, 3277, 3278, -1, 3278, 3233, 3235, -1, + 3233, 3278, 3279, -1, 3279, 3231, 3233, -1, + 3231, 3279, 3280, -1, 3280, 3229, 3231, -1, + 3229, 3280, 3281, -1, 3281, 3227, 3229, -1, + 3227, 3281, 3282, -1, 3282, 3225, 3227, -1, + 3225, 3282, 3283, -1, 3283, 3223, 3225, -1, + 3223, 3283, 3284, -1, 3284, 3221, 3223, -1, + 3221, 3284, 3285, -1, 3285, 3219, 3221, -1, + 3219, 3285, 3286, -1, 3286, 3218, 3219, -1, + 3218, 3286, 3287, -1, 3218, 3287, 3288, -1, + 3288, 3216, 3218, -1, 3216, 3288, 3289, -1, + 3289, 3214, 3216, -1, 3214, 3289, 3290, -1, + 3290, 3212, 3214, -1, 3212, 3290, 3291, -1, + 3291, 3210, 3212, -1, 3210, 3291, 3292, -1, + 3292, 3208, 3210, -1, 3208, 3292, 3293, -1, + 3293, 3206, 3208, -1, 3206, 3293, 3294, -1, + 3294, 3204, 3206, -1, 3204, 3294, 3295, -1, + 3295, 3202, 3204, -1, 3202, 3295, 3296, -1, + 3296, 3200, 3202, -1, 3200, 3296, 3297, -1, + 3297, 3198, 3200, -1, 3198, 3297, 3298, -1, + 3298, 3196, 3198, -1, 3196, 3298, 3299, -1, + 3299, 3194, 3196, -1, 3194, 3299, 3300, -1, + 3300, 3191, 3194, -1, 3191, 3300, 3301, -1, + 3301, 3192, 3191, -1, 3192, 3301, 3129, -1, + 3129, 3128, 3192, -1, 3302, 3192, 3128, -1, + 3192, 3302, 3303, -1, 3303, 3190, 3192, -1, + 3190, 3303, 3304, -1, 3304, 3193, 3190, -1, + 3193, 3304, 3305, -1, 3305, 3195, 3193, -1, + 3195, 3305, 3306, -1, 3306, 3197, 3195, -1, + 3197, 3306, 3307, -1, 3307, 3199, 3197, -1, + 3199, 3307, 3308, -1, 3308, 3201, 3199, -1, + 3201, 3308, 3309, -1, 3309, 3203, 3201, -1, + 3203, 3309, 3310, -1, 3310, 3205, 3203, -1, + 3205, 3310, 3311, -1, 3311, 3207, 3205, -1, + 3207, 3311, 3312, -1, 3312, 3209, 3207, -1, + 3209, 3312, 3313, -1, 3313, 3211, 3209, -1, + 3211, 3313, 3314, -1, 3314, 3213, 3211, -1, + 3213, 3314, 3315, -1, 3315, 3215, 3213, -1, + 3215, 3315, 3316, -1, 3316, 3217, 3215, -1, + 3316, 3220, 3217, -1, 3220, 3316, 3317, -1, + 3317, 3222, 3220, -1, 3222, 3317, 3318, -1, + 3318, 3224, 3222, -1, 3224, 3318, 3319, -1, + 3319, 3226, 3224, -1, 3226, 3319, 3320, -1, + 3320, 3228, 3226, -1, 3228, 3320, 3321, -1, + 3321, 3230, 3228, -1, 3230, 3321, 3322, -1, + 3322, 3232, 3230, -1, 3232, 3322, 3323, -1, + 3323, 3234, 3232, -1, 3234, 3323, 3324, -1, + 3324, 3236, 3234, -1, 3236, 3324, 3325, -1, + 3325, 3238, 3236, -1, 3238, 3325, 3326, -1, + 3326, 3240, 3238, -1, 3240, 3326, 3327, -1, + 3327, 3242, 3240, -1, 3242, 3327, 3328, -1, + 3328, 3244, 3242, -1, 3244, 3328, 3329, -1, + 3329, 3246, 3244, -1, 3246, 3329, 3330, -1, + 3330, 3248, 3246, -1, 3248, 3330, 3331, -1, + 3331, 3250, 3248, -1, 3250, 3331, 3332, -1, + 3332, 3252, 3250, -1, 3252, 3332, 3333, -1, + 3333, 3254, 3252, -1, 3254, 3333, 3334, -1, + 3334, 3256, 3254, -1, 3256, 3334, 3335, -1, + 3335, 3258, 3256, -1, 3258, 3335, 3336, -1, + 3336, 3260, 3258, -1, 3260, 3336, 3337, -1, + 3337, 3262, 3260, -1, 3262, 3337, 3338, -1, + 3338, 3189, 3262, -1, 3189, 3338, 3339, -1, + 3339, 3187, 3189, -1, 3340, 3187, 3339, -1, + 3339, 3341, 3340, -1, 3341, 3339, 3338, -1, + 3338, 3342, 3341, -1, 3342, 3338, 3337, -1, + 3337, 3343, 3342, -1, 3343, 3337, 3336, -1, + 3336, 3344, 3343, -1, 3345, 3346, 3347, -1, + 3347, 3348, 3345, -1, 3348, 3347, 3349, -1, + 3349, 3350, 3348, -1, 3350, 3349, 3351, -1, + 3351, 3352, 3350, -1, 3353, 3350, 3352, -1, + 3352, 3354, 3353, -1, 3354, 3352, 3355, -1, + 3355, 3356, 3354, -1, 3356, 3355, 3357, -1, + 3357, 3358, 3356, -1, 3358, 3357, 3359, -1, + 3359, 3360, 3358, -1, 3360, 3359, 3361, -1, + 3361, 3362, 3360, -1, 3362, 3361, 3344, -1, + 3344, 3336, 3362, -1, 3362, 3336, 3335, -1, + 3335, 3360, 3362, -1, 3360, 3335, 3334, -1, + 3334, 3358, 3360, -1, 3358, 3334, 3333, -1, + 3333, 3356, 3358, -1, 3356, 3333, 3332, -1, + 3332, 3354, 3356, -1, 3354, 3332, 3331, -1, + 3331, 3353, 3354, -1, 3353, 3331, 3330, -1, + 3330, 3363, 3353, -1, 3364, 3365, 3366, -1, + 3365, 3364, 3367, -1, 3367, 3368, 3365, -1, + 3368, 3367, 3369, -1, 3369, 3370, 3368, -1, + 3370, 3369, 3371, -1, 3371, 3372, 3370, -1, + 3372, 3371, 3373, -1, 3374, 3373, 3375, -1, + 3373, 3374, 3376, -1, 3376, 3372, 3373, -1, + 3372, 3376, 3377, -1, 3377, 3370, 3372, -1, + 3370, 3377, 3378, -1, 3378, 3368, 3370, -1, + 3368, 3378, 3379, -1, 3379, 3365, 3368, -1, + 3365, 3379, 3380, -1, 3380, 3366, 3365, -1, + 3366, 3380, 3381, -1, 3381, 3382, 3366, -1, + 3382, 3381, 3383, -1, 3383, 3384, 3382, -1, + 3384, 3383, 3385, -1, 3385, 3386, 3384, -1, + 3386, 3385, 3387, -1, 3387, 3388, 3386, -1, + 3388, 3387, 3389, -1, 3389, 3390, 3388, -1, + 3390, 3389, 3391, -1, 3391, 3392, 3390, -1, + 3392, 3391, 3393, -1, 3393, 3394, 3392, -1, + 3394, 3393, 3395, -1, 3395, 3396, 3394, -1, + 3396, 3395, 3397, -1, 3397, 3398, 3396, -1, + 3398, 3397, 3399, -1, 3399, 3400, 3398, -1, + 3399, 3401, 3400, -1, 3401, 3399, 3402, -1, + 3402, 3403, 3401, -1, 3403, 3402, 3404, -1, + 3404, 3405, 3403, -1, 3405, 3404, 3406, -1, + 3406, 3407, 3405, -1, 3407, 3406, 3408, -1, + 3408, 3409, 3407, -1, 3409, 3408, 3410, -1, + 3410, 3411, 3409, -1, 3411, 3410, 3412, -1, + 3412, 3413, 3411, -1, 3413, 3412, 3414, -1, + 3414, 3415, 3413, -1, 3415, 3414, 3416, -1, + 3416, 3417, 3415, -1, 3417, 3416, 3418, -1, + 3418, 3419, 3417, -1, 3419, 3418, 3420, -1, + 3420, 3421, 3419, -1, 3421, 3420, 3422, -1, + 3422, 3423, 3421, -1, 3423, 3422, 3424, -1, + 3424, 3425, 3423, -1, 3425, 3424, 3363, -1, + 3363, 3330, 3425, -1, 3425, 3330, 3329, -1, + 3329, 3423, 3425, -1, 3423, 3329, 3328, -1, + 3328, 3421, 3423, -1, 3421, 3328, 3327, -1, + 3327, 3419, 3421, -1, 3419, 3327, 3326, -1, + 3326, 3417, 3419, -1, 3417, 3326, 3325, -1, + 3325, 3415, 3417, -1, 3415, 3325, 3324, -1, + 3324, 3413, 3415, -1, 3413, 3324, 3323, -1, + 3323, 3411, 3413, -1, 3411, 3323, 3322, -1, + 3322, 3409, 3411, -1, 3409, 3322, 3321, -1, + 3321, 3407, 3409, -1, 3407, 3321, 3320, -1, + 3320, 3405, 3407, -1, 3405, 3320, 3319, -1, + 3319, 3403, 3405, -1, 3403, 3319, 3318, -1, + 3318, 3401, 3403, -1, 3401, 3318, 3317, -1, + 3317, 3400, 3401, -1, 3400, 3317, 3316, -1, + 3400, 3316, 3315, -1, 3315, 3398, 3400, -1, + 3398, 3315, 3314, -1, 3314, 3396, 3398, -1, + 3396, 3314, 3313, -1, 3313, 3394, 3396, -1, + 3394, 3313, 3312, -1, 3312, 3392, 3394, -1, + 3392, 3312, 3311, -1, 3311, 3390, 3392, -1, + 3390, 3311, 3310, -1, 3310, 3388, 3390, -1, + 3388, 3310, 3309, -1, 3309, 3386, 3388, -1, + 3386, 3309, 3308, -1, 3308, 3384, 3386, -1, + 3384, 3308, 3307, -1, 3307, 3382, 3384, -1, + 3382, 3307, 3306, -1, 3306, 3366, 3382, -1, + 3366, 3306, 3305, -1, 3305, 3364, 3366, -1, + 3364, 3305, 3304, -1, 3304, 3367, 3364, -1, + 3367, 3304, 3303, -1, 3303, 3369, 3367, -1, + 3369, 3303, 3302, -1, 3302, 3371, 3369, -1, + 3371, 3302, 3128, -1, 3128, 3373, 3371, -1, + 3373, 3128, 3126, -1, 3126, 3375, 3373, -1, + 3375, 3126, 3124, -1, 3124, 3426, 3375, -1, + 3426, 3124, 3106, -1, 3106, 3105, 3426, -1, + 3427, 3426, 3105, -1, 3105, 3428, 3427, -1, + 3428, 3105, 3108, -1, 3108, 3429, 3428, -1, + 3429, 3108, 3110, -1, 3110, 3430, 3429, -1, + 3430, 3110, 3112, -1, 3112, 3431, 3430, -1, + 3431, 3112, 3114, -1, 3114, 3432, 3431, -1, + 3432, 3114, 3117, -1, 3117, 3433, 3432, -1, + 3433, 3117, 3116, -1, 3116, 3434, 3433, -1, + 3434, 3116, 3435, -1, 3436, 3437, 3438, -1, + 3439, 3440, 3441, -1, 3441, 3442, 3439, -1, + 3442, 3441, 3443, -1, 3443, 3444, 3442, -1, + 3445, 3446, 3447, -1, 3446, 3445, 3444, -1, + 3444, 3443, 3446, -1, 3443, 3448, 3446, -1, + 3448, 3443, 3441, -1, 3441, 3449, 3448, -1, + 3449, 3441, 3440, -1, 3440, 3450, 3449, -1, + 3450, 3440, 3451, -1, 3451, 3452, 3450, -1, + 3452, 3451, 3453, -1, 3453, 3454, 3452, -1, + 3454, 3453, 3455, -1, 3455, 3456, 3454, -1, + 3456, 3455, 3457, -1, 3457, 3458, 3456, -1, + 3458, 3457, 3438, -1, 3458, 3438, 3437, -1, + 3459, 3458, 3437, -1, 3459, 3460, 3458, -1, + 3460, 3459, 3461, -1, 3459, 3437, 3461, -1, + 3437, 3436, 3461, -1, 3462, 3463, 3464, -1, + 3465, 3466, 3467, -1, 3467, 3466, 3468, -1, + 3468, 3469, 3467, -1, 3470, 3471, 3472, -1, + 3470, 3473, 3471, -1, 3474, 3473, 3470, -1, + 3470, 3472, 3474, -1, 3475, 3476, 3477, -1, + 3475, 3478, 3476, -1, 3478, 3475, 3479, -1, + 3479, 3480, 3478, -1, 3480, 3479, 3481, -1, + 3481, 3482, 3480, -1, 3482, 3481, 3483, -1, + 3483, 3484, 3482, -1, 3484, 3483, 3485, -1, + 3484, 3485, 3486, -1, 3484, 3486, 3487, -1, + 3487, 3482, 3484, -1, 3482, 3487, 3488, -1, + 3488, 3480, 3482, -1, 3480, 3488, 3489, -1, + 3489, 3478, 3480, -1, 3478, 3489, 3490, -1, + 3490, 3476, 3478, -1, 3476, 3490, 3491, -1, + 3491, 3492, 3476, -1, 3492, 3491, 3493, -1, + 3493, 3494, 3492, -1, 3493, 3495, 3494, -1, + 3495, 3493, 3496, -1, 3496, 3472, 3495, -1, + 3472, 3496, 3469, -1, 3472, 3469, 3497, -1, + 3497, 3474, 3472, -1, 3497, 3473, 3474, -1, + 3497, 3498, 3473, -1, 3498, 3497, 3469, -1, + 3498, 3469, 3468, -1, 3468, 3473, 3498, -1, + 3473, 3468, 3466, -1, 3499, 3500, 3501, -1, + 3502, 3500, 3499, -1, 3499, 3503, 3502, -1, + 3499, 3501, 3503, -1, 3503, 3501, 3504, -1, + 3504, 3505, 3503, -1, 3505, 3504, 3506, -1, + 3506, 3507, 3505, -1, 3507, 3506, 3508, -1, + 3509, 3510, 3511, -1, 3509, 3512, 3510, -1, + 3513, 3514, 3515, -1, 3513, 3516, 3514, -1, + 3516, 3513, 3517, -1, 3517, 3518, 3516, -1, + 3518, 3517, 3519, -1, 3519, 3520, 3518, -1, + 3520, 3519, 3521, -1, 3521, 3522, 3520, -1, + 3522, 3521, 3523, -1, 3523, 3524, 3522, -1, + 3524, 3523, 3525, -1, 3525, 3526, 3524, -1, + 3526, 3525, 3527, -1, 3527, 3528, 3526, -1, + 3528, 3527, 3529, -1, 3529, 3530, 3528, -1, + 3530, 3529, 3531, -1, 3531, 3532, 3530, -1, + 3532, 3531, 3533, -1, 3533, 3534, 3532, -1, + 3534, 3533, 3535, -1, 3535, 3536, 3534, -1, + 3536, 3535, 3537, -1, 3537, 3538, 3536, -1, + 3538, 3537, 3539, -1, 3539, 3540, 3538, -1, + 3540, 3539, 3541, -1, 3541, 3542, 3540, -1, + 3542, 3541, 3543, -1, 3543, 3544, 3542, -1, + 3544, 3543, 3545, -1, 3545, 3546, 3544, -1, + 3546, 3545, 3547, -1, 3547, 3548, 3546, -1, + 3548, 3547, 3549, -1, 3549, 3550, 3548, -1, + 3550, 3549, 3551, -1, 3551, 3552, 3550, -1, + 3552, 3551, 3553, -1, 3553, 3554, 3552, -1, + 3554, 3553, 3555, -1, 3555, 3556, 3554, -1, + 3556, 3555, 3557, -1, 3557, 3558, 3556, -1, + 3558, 3557, 3559, -1, 3559, 3560, 3558, -1, + 3560, 3559, 3561, -1, 3561, 3562, 3560, -1, + 3562, 3561, 3563, -1, 3563, 3564, 3562, -1, + 3564, 3563, 3565, -1, 3565, 3566, 3564, -1, + 3566, 3565, 3567, -1, 3567, 3568, 3566, -1, + 3568, 3567, 3569, -1, 3569, 3570, 3568, -1, + 3570, 3569, 3571, -1, 3571, 3572, 3570, -1, + 3572, 3571, 3573, -1, 3573, 3574, 3572, -1, + 3574, 3573, 3575, -1, 3575, 3576, 3574, -1, + 3576, 3575, 3577, -1, 3577, 3578, 3576, -1, + 3578, 3577, 3579, -1, 3579, 3580, 3578, -1, + 3580, 3579, 3581, -1, 3581, 3582, 3580, -1, + 3582, 3581, 3583, -1, 3583, 3584, 3582, -1, + 3584, 3583, 3585, -1, 3585, 3586, 3584, -1, + 3586, 3585, 3587, -1, 3587, 3588, 3586, -1, + 3588, 3587, 3589, -1, 3589, 3590, 3588, -1, + 3590, 3589, 3591, -1, 3591, 3592, 3590, -1, + 3592, 3591, 3593, -1, 3593, 3594, 3592, -1, + 3594, 3593, 3595, -1, 3595, 3596, 3594, -1, + 3596, 3595, 3597, -1, 3597, 3598, 3596, -1, + 3598, 3597, 3599, -1, 3599, 3600, 3598, -1, + 3600, 3599, 3601, -1, 3601, 3602, 3600, -1, + 3602, 3601, 3603, -1, 3603, 3604, 3602, -1, + 3604, 3603, 3605, -1, 3605, 3606, 3604, -1, + 3606, 3605, 3607, -1, 3607, 3608, 3606, -1, + 3608, 3607, 3609, -1, 3609, 3610, 3608, -1, + 3610, 3609, 3512, -1, 3512, 3509, 3610, -1, + 3611, 3509, 3612, -1, 3611, 3610, 3509, -1, + 3610, 3611, 3613, -1, 3613, 3608, 3610, -1, + 3608, 3613, 3614, -1, 3614, 3606, 3608, -1, + 3606, 3614, 3615, -1, 3615, 3604, 3606, -1, + 3604, 3615, 3616, -1, 3616, 3602, 3604, -1, + 3602, 3616, 3617, -1, 3617, 3600, 3602, -1, + 3600, 3617, 3618, -1, 3618, 3598, 3600, -1, + 3598, 3618, 3619, -1, 3619, 3596, 3598, -1, + 3596, 3619, 3620, -1, 3620, 3594, 3596, -1, + 3594, 3620, 3621, -1, 3621, 3592, 3594, -1, + 3592, 3621, 3622, -1, 3622, 3590, 3592, -1, + 3590, 3622, 3623, -1, 3623, 3588, 3590, -1, + 3588, 3623, 3624, -1, 3624, 3586, 3588, -1, + 3586, 3624, 3625, -1, 3625, 3584, 3586, -1, + 3584, 3625, 3626, -1, 3626, 3582, 3584, -1, + 3582, 3626, 3627, -1, 3627, 3580, 3582, -1, + 3580, 3627, 3628, -1, 3628, 3578, 3580, -1, + 3578, 3628, 3629, -1, 3629, 3576, 3578, -1, + 3576, 3629, 3630, -1, 3630, 3574, 3576, -1, + 3574, 3630, 3631, -1, 3631, 3572, 3574, -1, + 3572, 3631, 3632, -1, 3632, 3570, 3572, -1, + 3570, 3632, 3633, -1, 3633, 3568, 3570, -1, + 3568, 3633, 3634, -1, 3634, 3566, 3568, -1, + 3566, 3634, 3635, -1, 3635, 3564, 3566, -1, + 3564, 3635, 3636, -1, 3636, 3562, 3564, -1, + 3562, 3636, 3637, -1, 3637, 3560, 3562, -1, + 3560, 3637, 3638, -1, 3638, 3558, 3560, -1, + 3558, 3638, 3639, -1, 3639, 3556, 3558, -1, + 3556, 3639, 3640, -1, 3640, 3554, 3556, -1, + 3554, 3640, 3641, -1, 3641, 3552, 3554, -1, + 3552, 3641, 3642, -1, 3642, 3550, 3552, -1, + 3550, 3642, 3643, -1, 3643, 3548, 3550, -1, + 3548, 3643, 3644, -1, 3644, 3546, 3548, -1, + 3546, 3644, 3645, -1, 3645, 3544, 3546, -1, + 3544, 3645, 3646, -1, 3646, 3542, 3544, -1, + 3542, 3646, 3647, -1, 3647, 3540, 3542, -1, + 3540, 3647, 3648, -1, 3648, 3538, 3540, -1, + 3538, 3648, 3649, -1, 3649, 3536, 3538, -1, + 3536, 3649, 3650, -1, 3650, 3534, 3536, -1, + 3534, 3650, 3651, -1, 3651, 3532, 3534, -1, + 3532, 3651, 3652, -1, 3652, 3530, 3532, -1, + 3530, 3652, 3653, -1, 3653, 3528, 3530, -1, + 3528, 3653, 3654, -1, 3654, 3526, 3528, -1, + 3526, 3654, 3655, -1, 3655, 3524, 3526, -1, + 3524, 3655, 3656, -1, 3656, 3522, 3524, -1, + 3522, 3656, 3657, -1, 3657, 3520, 3522, -1, + 3520, 3657, 3658, -1, 3658, 3518, 3520, -1, + 3518, 3658, 3659, -1, 3659, 3516, 3518, -1, + 3516, 3659, 3660, -1, 3660, 3514, 3516, -1, + 3661, 3662, 3514, -1, 3514, 3660, 3661, -1, + 3663, 3664, 3665, -1, 3663, 3666, 3664, -1, + 3667, 3668, 3669, -1, 3669, 3670, 3667, -1, + 3670, 3669, 3671, -1, 3671, 3672, 3670, -1, + 3672, 3671, 3673, -1, 3673, 3674, 3672, -1, + 3674, 3673, 3666, -1, 3666, 3663, 3674, -1, + 3675, 3663, 3676, -1, 3675, 3674, 3663, -1, + 3674, 3675, 3677, -1, 3677, 3672, 3674, -1, + 3672, 3677, 3678, -1, 3678, 3670, 3672, -1, + 3670, 3678, 3679, -1, 3679, 3667, 3670, -1, + 3680, 3681, 3667, -1, 3667, 3679, 3680, -1, + 3682, 3683, 3684, -1, 3684, 3685, 3682, -1, + 3686, 3687, 3688, -1, 3686, 3689, 3687, -1, + 3686, 3690, 3689, -1, 3686, 3688, 3690, -1, + 3690, 3688, 3682, -1, 3682, 3691, 3690, -1, + 3691, 3682, 3685, -1, 3685, 3692, 3691, -1, + 3692, 3693, 3694, -1, 3692, 3685, 3693, -1, + 3693, 3695, 3696, -1, 3693, 3697, 3695, -1, + 3697, 3693, 3685, -1, 3685, 3684, 3697, -1, + 3684, 3698, 3680, -1, 3680, 3697, 3684, -1, + 3697, 3680, 3679, -1, 3679, 3695, 3697, -1, + 3695, 3679, 3678, -1, 3678, 3699, 3695, -1, + 3699, 3678, 3677, -1, 3699, 3677, 3700, -1, + 3701, 3702, 3703, -1, 3703, 3704, 3701, -1, + 3705, 3706, 3707, -1, 3705, 3707, 3708, -1, + 3709, 3708, 3707, -1, 3709, 3710, 3708, -1, + 3711, 3712, 3713, -1, 3712, 3711, 3714, -1, + 3714, 3715, 3712, -1, 3715, 3714, 3716, -1, + 3716, 3717, 3715, -1, 3717, 3716, 3718, -1, + 3718, 3719, 3717, -1, 3719, 3718, 3720, -1, + 3720, 3721, 3719, -1, 3721, 3720, 3722, -1, + 3722, 3723, 3721, -1, 3723, 3722, 3710, -1, + 3710, 3709, 3723, -1, 3724, 3709, 3725, -1, + 3724, 3723, 3709, -1, 3723, 3724, 3726, -1, + 3726, 3721, 3723, -1, 3721, 3726, 3727, -1, + 3727, 3719, 3721, -1, 3719, 3727, 3728, -1, + 3728, 3717, 3719, -1, 3717, 3728, 3729, -1, + 3729, 3715, 3717, -1, 3715, 3729, 3730, -1, + 3730, 3712, 3715, -1, 3712, 3730, 3731, -1, + 3731, 3713, 3712, -1, 3713, 3731, 3732, -1, + 3732, 3733, 3713, -1, 3733, 3732, 3734, -1, + 3734, 3735, 3733, -1, 3735, 3734, 3736, -1, + 3736, 3737, 3735, -1, 3737, 3736, 3738, -1, + 3738, 3739, 3737, -1, 3739, 3738, 3740, -1, + 3740, 3741, 3739, -1, 3741, 3740, 3742, -1, + 3742, 3743, 3741, -1, 3743, 3742, 3744, -1, + 3744, 3745, 3743, -1, 3745, 3744, 3746, -1, + 3746, 3747, 3745, -1, 3747, 3746, 3748, -1, + 3748, 3749, 3747, -1, 3749, 3748, 3750, -1, + 3750, 3751, 3749, -1, 3751, 3750, 3752, -1, + 3752, 3753, 3751, -1, 3753, 3752, 3754, -1, + 3754, 3755, 3753, -1, 3755, 3754, 3756, -1, + 3756, 3757, 3755, -1, 3757, 3756, 3758, -1, + 3758, 3759, 3757, -1, 3759, 3758, 3760, -1, + 3760, 3761, 3759, -1, 3761, 3760, 3762, -1, + 3762, 3763, 3761, -1, 3763, 3762, 3764, -1, + 3764, 3765, 3763, -1, 3765, 3764, 3766, -1, + 3766, 3767, 3765, -1, 3767, 3766, 3768, -1, + 3768, 3769, 3767, -1, 3769, 3768, 3770, -1, + 3770, 3771, 3769, -1, 3771, 3770, 3772, -1, + 3772, 3773, 3771, -1, 3773, 3772, 3774, -1, + 3774, 3775, 3773, -1, 3775, 3774, 3776, -1, + 3776, 3777, 3775, -1, 3777, 3776, 3778, -1, + 3778, 3779, 3777, -1, 3779, 3778, 3780, -1, + 3780, 3781, 3779, -1, 3781, 3780, 3782, -1, + 3782, 3783, 3781, -1, 3783, 3782, 3784, -1, + 3784, 3785, 3783, -1, 3785, 3784, 3786, -1, + 3786, 3787, 3785, -1, 3787, 3786, 3788, -1, + 3788, 3789, 3787, -1, 3789, 3788, 3790, -1, + 3790, 3791, 3789, -1, 3791, 3790, 3792, -1, + 3792, 3793, 3791, -1, 3793, 3792, 3794, -1, + 3794, 3795, 3793, -1, 3795, 3794, 3796, -1, + 3796, 3797, 3795, -1, 3797, 3796, 3798, -1, + 3798, 3799, 3797, -1, 3799, 3798, 3800, -1, + 3800, 3801, 3799, -1, 3801, 3800, 3802, -1, + 3802, 3803, 3801, -1, 3803, 3802, 3804, -1, + 3804, 3805, 3803, -1, 3805, 3804, 3806, -1, + 3806, 3807, 3805, -1, 3807, 3806, 3808, -1, + 3808, 3704, 3807, -1, 3704, 3808, 3809, -1, + 3809, 3701, 3704, -1, 3810, 3811, 3701, -1, + 3701, 3809, 3810, -1, 3812, 3813, 3810, -1, + 3810, 3814, 3812, -1, 3814, 3810, 3809, -1, + 3809, 3815, 3814, -1, 3815, 3809, 3808, -1, + 3808, 3816, 3815, -1, 3816, 3808, 3806, -1, + 3806, 3817, 3816, -1, 3817, 3806, 3804, -1, + 3804, 3818, 3817, -1, 3818, 3804, 3802, -1, + 3802, 3819, 3818, -1, 3819, 3802, 3800, -1, + 3800, 3820, 3819, -1, 3820, 3800, 3798, -1, + 3798, 3821, 3820, -1, 3821, 3798, 3796, -1, + 3796, 3822, 3821, -1, 3822, 3796, 3794, -1, + 3794, 3823, 3822, -1, 3823, 3794, 3792, -1, + 3792, 3824, 3823, -1, 3824, 3792, 3790, -1, + 3790, 3825, 3824, -1, 3825, 3790, 3788, -1, + 3788, 3826, 3825, -1, 3826, 3788, 3786, -1, + 3786, 3827, 3826, -1, 3827, 3786, 3784, -1, + 3784, 3828, 3827, -1, 3828, 3784, 3782, -1, + 3782, 3829, 3828, -1, 3829, 3782, 3780, -1, + 3780, 3830, 3829, -1, 3830, 3780, 3778, -1, + 3778, 3831, 3830, -1, 3831, 3778, 3776, -1, + 3776, 3832, 3831, -1, 3832, 3776, 3774, -1, + 3774, 3833, 3832, -1, 3833, 3774, 3772, -1, + 3772, 3834, 3833, -1, 3834, 3772, 3770, -1, + 3770, 3835, 3834, -1, 3835, 3770, 3768, -1, + 3768, 3836, 3835, -1, 3836, 3768, 3766, -1, + 3766, 3837, 3836, -1, 3837, 3766, 3764, -1, + 3764, 3838, 3837, -1, 3838, 3764, 3762, -1, + 3762, 3839, 3838, -1, 3839, 3762, 3760, -1, + 3760, 3840, 3839, -1, 3840, 3760, 3758, -1, + 3758, 3841, 3840, -1, 3841, 3758, 3756, -1, + 3756, 3842, 3841, -1, 3842, 3756, 3754, -1, + 3754, 3843, 3842, -1, 3843, 3754, 3752, -1, + 3752, 3844, 3843, -1, 3844, 3752, 3750, -1, + 3750, 3845, 3844, -1, 3845, 3750, 3748, -1, + 3748, 3846, 3845, -1, 3846, 3748, 3746, -1, + 3746, 3847, 3846, -1, 3847, 3746, 3744, -1, + 3744, 3848, 3847, -1, 3848, 3744, 3742, -1, + 3742, 3849, 3848, -1, 3849, 3742, 3740, -1, + 3740, 3850, 3849, -1, 3850, 3740, 3738, -1, + 3738, 3851, 3850, -1, 3851, 3738, 3736, -1, + 3736, 3852, 3851, -1, 3852, 3736, 3734, -1, + 3734, 3853, 3852, -1, 3853, 3734, 3732, -1, + 3732, 3854, 3853, -1, 3854, 3732, 3731, -1, + 3731, 3855, 3854, -1, 3855, 3731, 3730, -1, + 3730, 3856, 3855, -1, 3856, 3730, 3729, -1, + 3729, 3857, 3856, -1, 3857, 3729, 3728, -1, + 3728, 3858, 3857, -1, 3858, 3728, 3727, -1, + 3727, 3859, 3858, -1, 3859, 3727, 3726, -1, + 3726, 3860, 3859, -1, 3860, 3726, 3724, -1, + 3860, 3724, 3861, -1, 3862, 3863, 3864, -1, + 3863, 3862, 3865, -1, 3865, 3861, 3863, -1, + 3861, 3865, 3866, -1, 3866, 3860, 3861, -1, + 3866, 3867, 3860, -1, 3866, 3868, 3867, -1, + 3868, 3866, 3865, -1, 3865, 3700, 3868, -1, + 3700, 3865, 3862, -1, 3862, 3699, 3700, -1, + 3862, 3864, 3699, -1, 3869, 3699, 3864, -1, + 3869, 3695, 3699, -1, 3869, 3696, 3695, -1, + 3869, 3870, 3696, -1, 3870, 3869, 3864, -1, + 3864, 3871, 3870, -1, 3871, 3864, 3863, -1, + 3863, 3872, 3871, -1, 3872, 3863, 3861, -1, + 3872, 3861, 3724, -1, 3872, 3724, 3725, -1, + 3725, 3871, 3872, -1, 3871, 3725, 3873, -1, + 3873, 3870, 3871, -1, 3870, 3873, 3874, -1, + 3874, 3696, 3870, -1, 3696, 3874, 3875, -1, + 3875, 3693, 3696, -1, 3875, 3694, 3693, -1, + 3875, 3876, 3694, -1, 3876, 3875, 3874, -1, + 3874, 3877, 3876, -1, 3877, 3874, 3873, -1, + 3873, 3878, 3877, -1, 3878, 3873, 3725, -1, + 3878, 3725, 3709, -1, 3878, 3709, 3707, -1, + 3707, 3877, 3878, -1, 3877, 3707, 3706, -1, + 3706, 3876, 3877, -1, 3876, 3706, 3879, -1, + 3879, 3694, 3876, -1, 3694, 3879, 3880, -1, + 3880, 3692, 3694, -1, 3880, 3881, 3692, -1, + 3880, 3882, 3881, -1, 3882, 3880, 3879, -1, + 3879, 3883, 3882, -1, 3883, 3879, 3706, -1, + 3706, 3705, 3883, -1, 3705, 3884, 3883, -1, + 3705, 3708, 3884, -1, 3884, 3885, 3886, -1, + 3884, 3887, 3885, -1, 3887, 3884, 3708, -1, + 3708, 3888, 3887, -1, 3888, 3708, 3710, -1, + 3710, 3889, 3888, -1, 3889, 3710, 3722, -1, + 3722, 3890, 3889, -1, 3890, 3722, 3720, -1, + 3720, 3891, 3890, -1, 3891, 3720, 3718, -1, + 3718, 3892, 3891, -1, 3892, 3718, 3716, -1, + 3716, 3893, 3892, -1, 3893, 3716, 3714, -1, + 3714, 3894, 3893, -1, 3894, 3714, 3711, -1, + 3711, 3895, 3894, -1, 3895, 3711, 3713, -1, + 3713, 3896, 3895, -1, 3896, 3713, 3733, -1, + 3733, 3897, 3896, -1, 3897, 3733, 3735, -1, + 3735, 3898, 3897, -1, 3898, 3735, 3737, -1, + 3737, 3899, 3898, -1, 3899, 3737, 3739, -1, + 3739, 3900, 3899, -1, 3900, 3739, 3741, -1, + 3741, 3901, 3900, -1, 3901, 3741, 3743, -1, + 3743, 3902, 3901, -1, 3902, 3743, 3745, -1, + 3745, 3903, 3902, -1, 3903, 3745, 3747, -1, + 3747, 3904, 3903, -1, 3904, 3747, 3749, -1, + 3749, 3905, 3904, -1, 3905, 3749, 3751, -1, + 3751, 3906, 3905, -1, 3906, 3751, 3753, -1, + 3753, 3907, 3906, -1, 3907, 3753, 3755, -1, + 3755, 3908, 3907, -1, 3908, 3755, 3757, -1, + 3757, 3909, 3908, -1, 3909, 3757, 3759, -1, + 3759, 3910, 3909, -1, 3910, 3759, 3761, -1, + 3761, 3911, 3910, -1, 3911, 3761, 3763, -1, + 3763, 3912, 3911, -1, 3912, 3763, 3765, -1, + 3765, 3913, 3912, -1, 3913, 3765, 3767, -1, + 3767, 3914, 3913, -1, 3914, 3767, 3769, -1, + 3769, 3915, 3914, -1, 3915, 3769, 3771, -1, + 3771, 3916, 3915, -1, 3916, 3771, 3773, -1, + 3773, 3917, 3916, -1, 3917, 3773, 3775, -1, + 3775, 3918, 3917, -1, 3918, 3775, 3777, -1, + 3777, 3919, 3918, -1, 3919, 3777, 3779, -1, + 3779, 3920, 3919, -1, 3920, 3779, 3781, -1, + 3781, 3921, 3920, -1, 3921, 3781, 3783, -1, + 3783, 3922, 3921, -1, 3922, 3783, 3785, -1, + 3785, 3923, 3922, -1, 3923, 3785, 3787, -1, + 3787, 3924, 3923, -1, 3924, 3787, 3789, -1, + 3789, 3925, 3924, -1, 3925, 3789, 3791, -1, + 3791, 3926, 3925, -1, 3926, 3791, 3793, -1, + 3793, 3927, 3926, -1, 3927, 3793, 3795, -1, + 3795, 3928, 3927, -1, 3928, 3795, 3797, -1, + 3797, 3929, 3928, -1, 3929, 3797, 3799, -1, + 3799, 3930, 3929, -1, 3930, 3799, 3801, -1, + 3801, 3931, 3930, -1, 3931, 3801, 3803, -1, + 3803, 3932, 3931, -1, 3932, 3803, 3805, -1, + 3805, 3933, 3932, -1, 3933, 3805, 3807, -1, + 3807, 3934, 3933, -1, 3934, 3807, 3704, -1, + 3704, 3703, 3934, -1, 3703, 3935, 3661, -1, + 3661, 3934, 3703, -1, 3934, 3661, 3660, -1, + 3660, 3933, 3934, -1, 3933, 3660, 3659, -1, + 3659, 3932, 3933, -1, 3932, 3659, 3658, -1, + 3658, 3931, 3932, -1, 3931, 3658, 3657, -1, + 3657, 3930, 3931, -1, 3930, 3657, 3656, -1, + 3656, 3929, 3930, -1, 3929, 3656, 3655, -1, + 3655, 3928, 3929, -1, 3928, 3655, 3654, -1, + 3654, 3927, 3928, -1, 3927, 3654, 3653, -1, + 3653, 3926, 3927, -1, 3926, 3653, 3652, -1, + 3652, 3925, 3926, -1, 3925, 3652, 3651, -1, + 3651, 3924, 3925, -1, 3924, 3651, 3650, -1, + 3650, 3923, 3924, -1, 3923, 3650, 3649, -1, + 3649, 3922, 3923, -1, 3922, 3649, 3648, -1, + 3648, 3921, 3922, -1, 3921, 3648, 3647, -1, + 3647, 3920, 3921, -1, 3920, 3647, 3646, -1, + 3646, 3919, 3920, -1, 3919, 3646, 3645, -1, + 3645, 3918, 3919, -1, 3918, 3645, 3644, -1, + 3644, 3917, 3918, -1, 3917, 3644, 3643, -1, + 3643, 3916, 3917, -1, 3916, 3643, 3642, -1, + 3642, 3915, 3916, -1, 3915, 3642, 3641, -1, + 3641, 3914, 3915, -1, 3914, 3641, 3640, -1, + 3640, 3913, 3914, -1, 3913, 3640, 3639, -1, + 3639, 3912, 3913, -1, 3912, 3639, 3638, -1, + 3638, 3911, 3912, -1, 3911, 3638, 3637, -1, + 3637, 3910, 3911, -1, 3910, 3637, 3636, -1, + 3636, 3909, 3910, -1, 3909, 3636, 3635, -1, + 3635, 3908, 3909, -1, 3908, 3635, 3634, -1, + 3634, 3907, 3908, -1, 3907, 3634, 3633, -1, + 3633, 3906, 3907, -1, 3906, 3633, 3632, -1, + 3632, 3905, 3906, -1, 3905, 3632, 3631, -1, + 3631, 3904, 3905, -1, 3904, 3631, 3630, -1, + 3630, 3903, 3904, -1, 3903, 3630, 3629, -1, + 3629, 3902, 3903, -1, 3902, 3629, 3628, -1, + 3628, 3901, 3902, -1, 3901, 3628, 3627, -1, + 3627, 3900, 3901, -1, 3900, 3627, 3626, -1, + 3626, 3899, 3900, -1, 3899, 3626, 3625, -1, + 3625, 3898, 3899, -1, 3898, 3625, 3624, -1, + 3624, 3897, 3898, -1, 3897, 3624, 3623, -1, + 3623, 3896, 3897, -1, 3896, 3623, 3622, -1, + 3622, 3895, 3896, -1, 3895, 3622, 3621, -1, + 3621, 3894, 3895, -1, 3894, 3621, 3620, -1, + 3620, 3893, 3894, -1, 3893, 3620, 3619, -1, + 3619, 3892, 3893, -1, 3892, 3619, 3618, -1, + 3618, 3891, 3892, -1, 3891, 3618, 3617, -1, + 3617, 3890, 3891, -1, 3890, 3617, 3616, -1, + 3616, 3889, 3890, -1, 3889, 3616, 3615, -1, + 3615, 3888, 3889, -1, 3888, 3615, 3614, -1, + 3614, 3887, 3888, -1, 3887, 3614, 3613, -1, + 3613, 3885, 3887, -1, 3885, 3613, 3611, -1, + 3885, 3611, 3936, -1, 3937, 3938, 3507, -1, + 3937, 3939, 3938, -1, 3939, 3937, 3940, -1, + 3940, 3936, 3939, -1, 3936, 3940, 3941, -1, + 3941, 3885, 3936, -1, 3941, 3886, 3885, -1, + 3941, 3942, 3886, -1, 3942, 3941, 3940, -1, + 3940, 3943, 3942, -1, 3943, 3940, 3937, -1, + 3937, 3507, 3943, -1, 3507, 3508, 3943, -1, + 3944, 3943, 3508, -1, 3944, 3942, 3943, -1, + 3942, 3944, 3945, -1, 3945, 3886, 3942, -1, + 3886, 3945, 3946, -1, 3946, 3884, 3886, -1, + 3946, 3883, 3884, -1, 3946, 3882, 3883, -1, + 3882, 3946, 3945, -1, 3945, 3881, 3882, -1, + 3881, 3945, 3944, -1, 3944, 3508, 3881, -1, + 3508, 3692, 3881, -1, 3508, 3691, 3692, -1, + 3691, 3508, 3506, -1, 3506, 3690, 3691, -1, + 3690, 3506, 3504, -1, 3504, 3689, 3690, -1, + 3689, 3504, 3947, -1, 3947, 3687, 3689, -1, + 3947, 3948, 3687, -1, 3948, 3947, 3504, -1, + 3948, 3504, 3501, -1, 3501, 3687, 3948, -1, + 3687, 3501, 3500, -1, 3464, 3688, 3687, -1, + 3688, 3464, 3463, -1, 3463, 3682, 3688, -1, + 3463, 3462, 3682, -1, 3462, 3683, 3682, -1, + 3683, 3462, 3464, -1, 3683, 3464, 3949, -1, + 3949, 3684, 3683, -1, 3949, 3698, 3684, -1, + 3698, 3949, 3464, -1, 3464, 3950, 3698, -1, + 3951, 3952, 3950, -1, 3952, 3698, 3950, -1, + 3952, 3680, 3698, -1, 3952, 3951, 3680, -1, + 3951, 3681, 3680, -1, 3681, 3951, 3950, -1, + 3681, 3950, 3953, -1, 3953, 3667, 3681, -1, + 3953, 3668, 3667, -1, 3668, 3953, 3950, -1, + 3950, 3954, 3668, -1, 3955, 3956, 3957, -1, + 3957, 3958, 3955, -1, 3955, 3959, 3960, -1, + 3955, 3961, 3959, -1, 3961, 3955, 3958, -1, + 3958, 3962, 3961, -1, 3962, 3958, 3963, -1, + 3963, 3964, 3962, -1, 3964, 3963, 3965, -1, + 3965, 3966, 3964, -1, 3966, 3965, 3967, -1, + 3967, 3968, 3966, -1, 3968, 3967, 3969, -1, + 3969, 3970, 3968, -1, 3970, 3969, 3971, -1, + 3971, 3972, 3970, -1, 3972, 3971, 3973, -1, + 3973, 3974, 3972, -1, 3974, 3973, 3975, -1, + 3975, 3976, 3974, -1, 3976, 3975, 3977, -1, + 3977, 3978, 3976, -1, 3978, 3977, 3979, -1, + 3979, 3980, 3978, -1, 3980, 3979, 3981, -1, + 3981, 3982, 3980, -1, 3982, 3981, 3983, -1, + 3983, 3984, 3982, -1, 3984, 3983, 3985, -1, + 3985, 3986, 3984, -1, 3986, 3985, 3987, -1, + 3987, 3988, 3986, -1, 3988, 3987, 3989, -1, + 3989, 3990, 3988, -1, 3991, 3992, 3990, -1, + 3992, 3991, 3993, -1, 3993, 3994, 3992, -1, + 3994, 3993, 3995, -1, 3995, 3996, 3994, -1, + 3996, 3995, 3997, -1, 3997, 3998, 3996, -1, + 3998, 3997, 3999, -1, 3999, 4000, 3998, -1, + 4000, 3999, 4001, -1, 4001, 4002, 4000, -1, + 4002, 4001, 4003, -1, 4003, 4004, 4002, -1, + 4004, 4003, 4005, -1, 4005, 4006, 4004, -1, + 4006, 4005, 4007, -1, 4007, 4008, 4006, -1, + 4008, 4007, 4009, -1, 4009, 4010, 4008, -1, + 4010, 4009, 4011, -1, 4011, 4012, 4010, -1, + 4012, 4011, 4013, -1, 4013, 4014, 4012, -1, + 4014, 4013, 4015, -1, 4015, 4016, 4014, -1, + 4016, 4015, 4017, -1, 4017, 4018, 4016, -1, + 4018, 4017, 4019, -1, 4020, 4021, 4022, -1, + 4022, 4023, 4020, -1, 4022, 4024, 4023, -1, + 4024, 4022, 4025, -1, 4025, 4022, 4021, -1, + 4021, 4026, 4025, -1, 4027, 4028, 4029, -1, + 4028, 4027, 4030, -1, 4030, 4031, 4028, -1, + 4031, 4030, 4032, -1, 4032, 4033, 4031, -1, + 4033, 4032, 4026, -1, 4026, 4021, 4033, -1, + 4034, 4021, 4035, -1, 4034, 4033, 4021, -1, + 4033, 4034, 4036, -1, 4036, 4031, 4033, -1, + 4031, 4036, 4037, -1, 4037, 4028, 4031, -1, + 4028, 4037, 4038, -1, 4038, 4029, 4028, -1, + 4029, 4038, 4039, -1, 4039, 4040, 4029, -1, + 4040, 4039, 4041, -1, 4041, 4042, 4040, -1, + 4042, 4041, 4043, -1, 4043, 4044, 4042, -1, + 4044, 4043, 4045, -1, 4045, 4046, 4044, -1, + 4046, 4045, 4047, -1, 4047, 4048, 4046, -1, + 4048, 4047, 4049, -1, 4049, 4050, 4048, -1, + 4050, 4049, 4051, -1, 4051, 4052, 4050, -1, + 4052, 4051, 4053, -1, 4053, 4054, 4052, -1, + 4054, 4053, 4055, -1, 4055, 4056, 4054, -1, + 4056, 4055, 4057, -1, 4057, 4058, 4056, -1, + 4058, 4057, 4059, -1, 4059, 4060, 4058, -1, + 4060, 4059, 4061, -1, 4061, 4062, 4060, -1, + 4062, 4061, 4063, -1, 4063, 4064, 4062, -1, + 4064, 4063, 4065, -1, 4065, 4066, 4064, -1, + 4067, 4068, 4069, -1, 4067, 4069, 4070, -1, + 4070, 4071, 4067, -1, 4071, 4070, 4072, -1, + 4072, 4073, 4071, -1, 4073, 4072, 4074, -1, + 4074, 4075, 4073, -1, 4075, 4074, 4076, -1, + 4076, 4077, 4075, -1, 4077, 4076, 4078, -1, + 4078, 4079, 4077, -1, 4079, 4078, 4080, -1, + 4080, 4081, 4079, -1, 4081, 4080, 4082, -1, + 4082, 4083, 4081, -1, 4082, 4084, 4083, -1, + 4084, 4082, 4085, -1, 4085, 4086, 4084, -1, + 4086, 4085, 4087, -1, 4087, 4088, 4086, -1, + 4088, 4087, 4089, -1, 4089, 4090, 4088, -1, + 4090, 4089, 4091, -1, 4091, 4092, 4090, -1, + 4092, 4091, 4093, -1, 4093, 4094, 4092, -1, + 4094, 4093, 4095, -1, 4095, 4096, 4094, -1, + 4096, 4095, 4097, -1, 4097, 4098, 4096, -1, + 4098, 4097, 4099, -1, 4099, 4100, 4098, -1, + 4101, 4102, 4103, -1, 4103, 4104, 4101, -1, + 4104, 4103, 4105, -1, 4105, 4106, 4104, -1, + 4106, 4105, 4107, -1, 4107, 4108, 4106, -1, + 4108, 4107, 4109, -1, 4109, 4110, 4108, -1, + 4110, 4109, 4111, -1, 4111, 4112, 4110, -1, + 4112, 4111, 4113, -1, 4113, 4114, 4112, -1, + 4114, 4113, 4115, -1, 4115, 4116, 4114, -1, + 4116, 4115, 4117, -1, 4117, 4118, 4116, -1, + 4118, 4117, 4119, -1, 4119, 4120, 4118, -1, + 4120, 4119, 4121, -1, 4121, 4122, 4120, -1, + 4123, 4124, 4125, -1, 4124, 4123, 4126, -1, + 4126, 4127, 4124, -1, 4127, 4126, 4128, -1, + 4128, 4129, 4127, -1, 4129, 4128, 4130, -1, + 4130, 4131, 4129, -1, 4131, 4130, 4132, -1, + 4132, 4133, 4131, -1, 4133, 4132, 4134, -1, + 4134, 4135, 4133, -1, 4135, 4134, 4136, -1, + 4136, 4137, 4135, -1, 4137, 4136, 4138, -1, + 4138, 4139, 4137, -1, 4139, 4138, 4140, -1, + 4140, 4141, 4139, -1, 4141, 4140, 4142, -1, + 4142, 4143, 4141, -1, 4143, 4142, 4144, -1, + 4144, 4145, 4143, -1, 4145, 4144, 4146, -1, + 4146, 4147, 4145, -1, 4147, 4146, 4148, -1, + 4148, 4149, 4147, -1, 4149, 4148, 4150, -1, + 4150, 4151, 4149, -1, 4151, 4150, 4152, -1, + 4152, 4153, 4151, -1, 4153, 4152, 4154, -1, + 4154, 4155, 4153, -1, 4155, 4154, 4156, -1, + 4156, 4157, 4155, -1, 4158, 4157, 4156, -1, + 4156, 4159, 4158, -1, 4159, 4156, 4154, -1, + 4154, 4160, 4159, -1, 4160, 4154, 4152, -1, + 4152, 4161, 4160, -1, 4161, 4152, 4150, -1, + 4150, 4162, 4161, -1, 4162, 4150, 4148, -1, + 4148, 4163, 4162, -1, 4163, 4148, 4146, -1, + 4146, 4164, 4163, -1, 4164, 4146, 4144, -1, + 4144, 4165, 4164, -1, 4165, 4144, 4142, -1, + 4142, 4166, 4165, -1, 4166, 4142, 4140, -1, + 4140, 4167, 4166, -1, 4167, 4140, 4138, -1, + 4138, 4168, 4167, -1, 4168, 4138, 4136, -1, + 4136, 4169, 4168, -1, 4169, 4136, 4134, -1, + 4134, 4170, 4169, -1, 4170, 4134, 4132, -1, + 4132, 4171, 4170, -1, 4171, 4132, 4130, -1, + 4130, 4172, 4171, -1, 4172, 4130, 4128, -1, + 4128, 4173, 4172, -1, 4173, 4128, 4126, -1, + 4126, 4174, 4173, -1, 4174, 4126, 4123, -1, + 4123, 4175, 4174, -1, 4123, 4125, 4175, -1, + 4176, 4175, 4125, -1, 4176, 4177, 4175, -1, + 4178, 4179, 4180, -1, 4178, 4180, 4181, -1, + 4181, 4182, 4178, -1, 4182, 4181, 4183, -1, + 4183, 4184, 4182, -1, 4184, 4183, 4185, -1, + 4185, 4186, 4184, -1, 4186, 4185, 4187, -1, + 4187, 4188, 4186, -1, 4188, 4187, 4189, -1, + 4189, 4190, 4188, -1, 4190, 4189, 4191, -1, + 4191, 4192, 4190, -1, 4191, 4193, 4192, -1, + 4193, 4191, 4194, -1, 4194, 4195, 4193, -1, + 4195, 4194, 4196, -1, 4196, 4197, 4195, -1, + 4197, 4196, 4198, -1, 4198, 4199, 4197, -1, + 4199, 4198, 4200, -1, 4200, 4201, 4199, -1, + 4201, 4200, 4202, -1, 4202, 4203, 4201, -1, + 4203, 4202, 4177, -1, 4177, 4176, 4203, -1, + 4204, 4176, 4205, -1, 4204, 4203, 4176, -1, + 4203, 4204, 4206, -1, 4206, 4201, 4203, -1, + 4201, 4206, 4207, -1, 4207, 4199, 4201, -1, + 4199, 4207, 4208, -1, 4208, 4197, 4199, -1, + 4197, 4208, 4209, -1, 4209, 4195, 4197, -1, + 4195, 4209, 4210, -1, 4210, 4193, 4195, -1, + 4193, 4210, 4211, -1, 4211, 4192, 4193, -1, + 4192, 4211, 4212, -1, 4192, 4212, 4213, -1, + 4213, 4190, 4192, -1, 4190, 4213, 4214, -1, + 4214, 4188, 4190, -1, 4188, 4214, 4215, -1, + 4215, 4186, 4188, -1, 4186, 4215, 4216, -1, + 4216, 4184, 4186, -1, 4184, 4216, 4217, -1, + 4217, 4182, 4184, -1, 4182, 4217, 4218, -1, + 4218, 4178, 4182, -1, 4218, 4219, 4178, -1, + 4220, 4221, 4222, -1, 4221, 4220, 4223, -1, + 4223, 4224, 4221, -1, 4224, 4223, 4225, -1, + 4225, 4226, 4224, -1, 4226, 4225, 4227, -1, + 4227, 4228, 4226, -1, 4228, 4227, 4229, -1, + 4229, 4230, 4228, -1, 4230, 4229, 4231, -1, + 4231, 4232, 4230, -1, 4232, 4231, 4219, -1, + 4219, 4233, 4232, -1, 4233, 4219, 4218, -1, + 4218, 4234, 4233, -1, 4234, 4218, 4217, -1, + 4217, 4235, 4234, -1, 4235, 4217, 4216, -1, + 4216, 4236, 4235, -1, 4236, 4216, 4215, -1, + 4215, 4237, 4236, -1, 4237, 4215, 4214, -1, + 4214, 4238, 4237, -1, 4238, 4214, 4213, -1, + 4213, 4239, 4238, -1, 4239, 4213, 4212, -1, + 4212, 4240, 4239, -1, 4212, 4241, 4240, -1, + 4241, 4212, 4211, -1, 4211, 4242, 4241, -1, + 4242, 4211, 4210, -1, 4210, 4243, 4242, -1, + 4243, 4210, 4209, -1, 4209, 4244, 4243, -1, + 4244, 4209, 4208, -1, 4208, 4245, 4244, -1, + 4245, 4208, 4207, -1, 4207, 4246, 4245, -1, + 4246, 4207, 4206, -1, 4206, 4247, 4246, -1, + 4247, 4206, 4204, -1, 4204, 4248, 4247, -1, + 4248, 4204, 4205, -1, 4205, 4249, 4248, -1, + 4249, 4205, 4250, -1, 4250, 4251, 4249, -1, + 4251, 4250, 4252, -1, 4252, 4253, 4251, -1, + 4253, 4252, 4254, -1, 4254, 4255, 4253, -1, + 4255, 4254, 4256, -1, 4256, 4257, 4255, -1, + 4257, 4256, 4258, -1, 4258, 4259, 4257, -1, + 4259, 4258, 4260, -1, 4260, 4261, 4259, -1, + 4261, 4260, 4262, -1, 4262, 4263, 4261, -1, + 4263, 4262, 4264, -1, 4264, 4265, 4263, -1, + 4265, 4264, 4266, -1, 4266, 4267, 4265, -1, + 4267, 4266, 4268, -1, 4268, 4269, 4267, -1, + 4269, 4268, 4270, -1, 4270, 4271, 4269, -1, + 4271, 4270, 4272, -1, 4272, 4273, 4271, -1, + 4273, 4272, 4274, -1, 4274, 4275, 4273, -1, + 4275, 4274, 4276, -1, 4276, 4277, 4275, -1, + 4277, 4276, 4278, -1, 4278, 4279, 4277, -1, + 4279, 4278, 4280, -1, 4280, 4281, 4279, -1, + 4279, 4281, 4122, -1, 4122, 4277, 4279, -1, + 4277, 4122, 4121, -1, 4121, 4275, 4277, -1, + 4275, 4121, 4119, -1, 4119, 4273, 4275, -1, + 4273, 4119, 4117, -1, 4117, 4271, 4273, -1, + 4271, 4117, 4115, -1, 4115, 4269, 4271, -1, + 4269, 4115, 4113, -1, 4113, 4267, 4269, -1, + 4267, 4113, 4111, -1, 4111, 4265, 4267, -1, + 4265, 4111, 4109, -1, 4109, 4263, 4265, -1, + 4263, 4109, 4107, -1, 4107, 4261, 4263, -1, + 4261, 4107, 4105, -1, 4105, 4259, 4261, -1, + 4259, 4105, 4103, -1, 4103, 4257, 4259, -1, + 4257, 4103, 4102, -1, 4102, 4255, 4257, -1, + 4255, 4102, 4282, -1, 4282, 4253, 4255, -1, + 4253, 4282, 4283, -1, 4283, 4251, 4253, -1, + 4251, 4283, 4284, -1, 4284, 4249, 4251, -1, + 4249, 4284, 4285, -1, 4285, 4248, 4249, -1, + 4285, 4286, 4248, -1, 4285, 4287, 4286, -1, + 4287, 4285, 4284, -1, 4284, 4288, 4287, -1, + 4288, 4284, 4283, -1, 4283, 4289, 4288, -1, + 4289, 4283, 4282, -1, 4282, 4290, 4289, -1, + 4290, 4282, 4102, -1, 4102, 4101, 4290, -1, + 4290, 4101, 4291, -1, 4291, 4289, 4290, -1, + 4289, 4291, 4292, -1, 4292, 4288, 4289, -1, + 4288, 4292, 4293, -1, 4293, 4287, 4288, -1, + 4287, 4293, 4294, -1, 4294, 4286, 4287, -1, + 4286, 4294, 4100, -1, 4100, 4099, 4286, -1, + 4099, 4248, 4286, -1, 4099, 4247, 4248, -1, + 4247, 4099, 4097, -1, 4097, 4246, 4247, -1, + 4246, 4097, 4095, -1, 4095, 4245, 4246, -1, + 4245, 4095, 4093, -1, 4093, 4244, 4245, -1, + 4244, 4093, 4091, -1, 4091, 4243, 4244, -1, + 4243, 4091, 4089, -1, 4089, 4242, 4243, -1, + 4242, 4089, 4087, -1, 4087, 4241, 4242, -1, + 4241, 4087, 4085, -1, 4085, 4240, 4241, -1, + 4240, 4085, 4082, -1, 4240, 4082, 4080, -1, + 4080, 4239, 4240, -1, 4239, 4080, 4078, -1, + 4078, 4238, 4239, -1, 4238, 4078, 4076, -1, + 4076, 4237, 4238, -1, 4237, 4076, 4074, -1, + 4074, 4236, 4237, -1, 4236, 4074, 4072, -1, + 4072, 4235, 4236, -1, 4235, 4072, 4070, -1, + 4070, 4234, 4235, -1, 4234, 4070, 4069, -1, + 4069, 4233, 4234, -1, 4069, 4295, 4233, -1, + 4296, 4297, 4298, -1, 4297, 4296, 4299, -1, + 4299, 4300, 4297, -1, 4300, 4299, 4301, -1, + 4301, 4302, 4300, -1, 4302, 4301, 4303, -1, + 4303, 4304, 4302, -1, 4304, 4303, 4305, -1, + 4305, 4306, 4304, -1, 4306, 4305, 4307, -1, + 4307, 4308, 4306, -1, 4308, 4307, 4295, -1, + 4295, 4309, 4308, -1, 4309, 4295, 4069, -1, + 4309, 4069, 4068, -1, 4309, 4068, 4310, -1, + 4310, 4308, 4309, -1, 4308, 4310, 4311, -1, + 4311, 4306, 4308, -1, 4306, 4311, 4312, -1, + 4312, 4304, 4306, -1, 4304, 4312, 4313, -1, + 4313, 4302, 4304, -1, 4302, 4313, 4314, -1, + 4314, 4300, 4302, -1, 4300, 4314, 4315, -1, + 4315, 4297, 4300, -1, 4297, 4315, 4316, -1, + 4316, 4298, 4297, -1, 4298, 4316, 4317, -1, + 4317, 4318, 4298, -1, 4318, 4317, 4319, -1, + 4319, 4320, 4318, -1, 4320, 4319, 4321, -1, + 4321, 4322, 4320, -1, 4322, 4321, 4323, -1, + 4323, 4324, 4322, -1, 4324, 4323, 4325, -1, + 4325, 4326, 4324, -1, 4326, 4325, 4327, -1, + 4327, 4328, 4326, -1, 4328, 4327, 4329, -1, + 4329, 4330, 4328, -1, 4330, 4329, 4331, -1, + 4331, 4332, 4330, -1, 4332, 4331, 4333, -1, + 4333, 4334, 4332, -1, 4335, 4334, 4066, -1, + 4334, 4335, 4336, -1, 4336, 4332, 4334, -1, + 4332, 4336, 4337, -1, 4337, 4330, 4332, -1, + 4330, 4337, 4338, -1, 4338, 4328, 4330, -1, + 4328, 4338, 4339, -1, 4339, 4326, 4328, -1, + 4326, 4339, 4340, -1, 4340, 4324, 4326, -1, + 4324, 4340, 4341, -1, 4341, 4322, 4324, -1, + 4322, 4341, 4342, -1, 4342, 4320, 4322, -1, + 4320, 4342, 4343, -1, 4343, 4318, 4320, -1, + 4318, 4343, 4344, -1, 4344, 4298, 4318, -1, + 4298, 4344, 4345, -1, 4345, 4296, 4298, -1, + 4296, 4345, 4346, -1, 4346, 4299, 4296, -1, + 4299, 4346, 4347, -1, 4347, 4301, 4299, -1, + 4301, 4347, 4348, -1, 4348, 4303, 4301, -1, + 4303, 4348, 4349, -1, 4349, 4305, 4303, -1, + 4305, 4349, 4350, -1, 4350, 4307, 4305, -1, + 4307, 4350, 4351, -1, 4351, 4295, 4307, -1, + 4351, 4233, 4295, -1, 4351, 4232, 4233, -1, + 4232, 4351, 4350, -1, 4350, 4230, 4232, -1, + 4230, 4350, 4349, -1, 4349, 4228, 4230, -1, + 4228, 4349, 4348, -1, 4348, 4226, 4228, -1, + 4226, 4348, 4347, -1, 4347, 4224, 4226, -1, + 4224, 4347, 4346, -1, 4346, 4221, 4224, -1, + 4221, 4346, 4345, -1, 4345, 4222, 4221, -1, + 4222, 4345, 4344, -1, 4344, 4352, 4222, -1, + 4352, 4344, 4343, -1, 4343, 4353, 4352, -1, + 4353, 4343, 4342, -1, 4342, 4354, 4353, -1, + 4354, 4342, 4341, -1, 4341, 4355, 4354, -1, + 4355, 4341, 4340, -1, 4340, 4356, 4355, -1, + 4356, 4340, 4339, -1, 4339, 4357, 4356, -1, + 4357, 4339, 4338, -1, 4338, 4358, 4357, -1, + 4358, 4338, 4337, -1, 4337, 4359, 4358, -1, + 4359, 4337, 4336, -1, 4336, 4360, 4359, -1, + 4360, 4336, 4335, -1, 4335, 4361, 4360, -1, + 4361, 4335, 4066, -1, 4066, 4065, 4361, -1, + 4362, 4361, 4065, -1, 4361, 4362, 4363, -1, + 4363, 4360, 4361, -1, 4360, 4363, 4364, -1, + 4364, 4359, 4360, -1, 4359, 4364, 4365, -1, + 4365, 4358, 4359, -1, 4358, 4365, 4366, -1, + 4366, 4357, 4358, -1, 4357, 4366, 4367, -1, + 4367, 4356, 4357, -1, 4356, 4367, 4368, -1, + 4368, 4355, 4356, -1, 4355, 4368, 4369, -1, + 4369, 4354, 4355, -1, 4354, 4369, 4370, -1, + 4370, 4353, 4354, -1, 4353, 4370, 4371, -1, + 4371, 4352, 4353, -1, 4352, 4371, 4372, -1, + 4372, 4222, 4352, -1, 4222, 4372, 4373, -1, + 4373, 4220, 4222, -1, 4220, 4373, 4374, -1, + 4374, 4223, 4220, -1, 4223, 4374, 4375, -1, + 4375, 4225, 4223, -1, 4225, 4375, 4376, -1, + 4376, 4227, 4225, -1, 4227, 4376, 4377, -1, + 4377, 4229, 4227, -1, 4229, 4377, 4378, -1, + 4378, 4231, 4229, -1, 4231, 4378, 4379, -1, + 4379, 4219, 4231, -1, 4379, 4178, 4219, -1, + 4379, 4179, 4178, -1, 4179, 4379, 4378, -1, + 4378, 4380, 4179, -1, 4380, 4378, 4377, -1, + 4377, 4381, 4380, -1, 4381, 4377, 4376, -1, + 4376, 4019, 4381, -1, 4019, 4376, 4375, -1, + 4375, 4018, 4019, -1, 4018, 4375, 4374, -1, + 4374, 4016, 4018, -1, 4016, 4374, 4373, -1, + 4373, 4014, 4016, -1, 4014, 4373, 4372, -1, + 4372, 4012, 4014, -1, 4012, 4372, 4371, -1, + 4371, 4010, 4012, -1, 4010, 4371, 4370, -1, + 4370, 4008, 4010, -1, 4008, 4370, 4369, -1, + 4369, 4006, 4008, -1, 4006, 4369, 4368, -1, + 4368, 4004, 4006, -1, 4004, 4368, 4367, -1, + 4367, 4002, 4004, -1, 4002, 4367, 4366, -1, + 4366, 4000, 4002, -1, 4000, 4366, 4365, -1, + 4365, 3998, 4000, -1, 3998, 4365, 4364, -1, + 4364, 3996, 3998, -1, 3996, 4364, 4363, -1, + 4363, 3994, 3996, -1, 3994, 4363, 4362, -1, + 4362, 3992, 3994, -1, 3992, 4362, 4065, -1, + 4065, 3990, 3992, -1, 3990, 4065, 4063, -1, + 4063, 3988, 3990, -1, 3988, 4063, 4061, -1, + 4061, 3986, 3988, -1, 3986, 4061, 4059, -1, + 4059, 3984, 3986, -1, 3984, 4059, 4057, -1, + 4057, 3982, 3984, -1, 3982, 4057, 4055, -1, + 4055, 3980, 3982, -1, 3980, 4055, 4053, -1, + 4053, 3978, 3980, -1, 3978, 4053, 4051, -1, + 4051, 3976, 3978, -1, 3976, 4051, 4049, -1, + 4049, 3974, 3976, -1, 3974, 4049, 4047, -1, + 4047, 3972, 3974, -1, 3972, 4047, 4045, -1, + 4045, 3970, 3972, -1, 3970, 4045, 4043, -1, + 4043, 3968, 3970, -1, 3968, 4043, 4041, -1, + 4041, 3966, 3968, -1, 3966, 4041, 4039, -1, + 4039, 3964, 3966, -1, 3964, 4039, 4038, -1, + 4038, 3962, 3964, -1, 3962, 4038, 4037, -1, + 4037, 3961, 3962, -1, 3961, 4037, 4036, -1, + 4036, 3959, 3961, -1, 3959, 4036, 4034, -1, + 4034, 4382, 3959, -1, 4383, 3959, 4382, -1, + 4382, 4384, 4383, -1, 4382, 4385, 4384, -1, + 4385, 4382, 4034, -1, 4385, 4034, 4035, -1, + 4035, 4384, 4385, -1, 4035, 4386, 4384, -1, + 4386, 4035, 4021, -1, 4386, 4021, 4020, -1, + 4386, 4020, 4023, -1, 4023, 4384, 4386, -1, + 3461, 4023, 4387, -1, 4388, 4389, 96, -1, + 4388, 96, 4390, -1, 4390, 4391, 4388, -1, + 4390, 4392, 4391, -1, 4392, 4390, 4393, -1, + 4393, 4390, 96, -1, 4394, 4395, 4393, -1, + 4394, 4393, 4396, -1, 4396, 4397, 4394, -1, + 4396, 4398, 4397, -1, 4398, 4396, 4399, -1, + 4399, 4396, 4393, -1, 4400, 4401, 4402, -1, + 4401, 4400, 4399, -1, 4403, 3466, 4404, -1, + 3466, 4403, 4401, -1, 3954, 3461, 3436, -1, + 3436, 4405, 3954, -1, 3436, 3438, 4405, -1, + 4405, 3438, 4406, -1, 4406, 3954, 4405, -1, + 4406, 4407, 3954, -1, 4407, 4408, 3954, -1, + 4408, 3668, 3954, -1, 4408, 3669, 3668, -1, + 4408, 4407, 3669, -1, 4407, 4406, 3669, -1, + 3669, 4406, 3438, -1, 3438, 3671, 3669, -1, + 3671, 3438, 3457, -1, 3457, 3673, 3671, -1, + 3673, 3457, 3455, -1, 3455, 3666, 3673, -1, + 3666, 3455, 3453, -1, 3453, 3664, 3666, -1, + 3664, 3453, 3451, -1, 3451, 4409, 3664, -1, + 4409, 3451, 3440, -1, 3440, 3439, 4409, -1, + 4410, 4409, 3439, -1, 4409, 4410, 4411, -1, + 4411, 3664, 4409, -1, 4411, 3665, 3664, -1, + 4411, 4412, 3665, -1, 4412, 4411, 4410, -1, + 4410, 4413, 4412, -1, 4413, 4410, 3439, -1, + 3439, 4414, 4413, -1, 4414, 3439, 3442, -1, + 3442, 4415, 4414, -1, 4415, 3442, 3444, -1, + 3444, 4416, 4415, -1, 4416, 3444, 3445, -1, + 3445, 4417, 4416, -1, 4417, 3445, 3447, -1, + 3447, 4418, 4417, -1, 4418, 3447, 4419, -1, + 4419, 4420, 4418, -1, 4420, 4419, 4421, -1, + 4421, 4422, 4420, -1, 4422, 4421, 4423, -1, + 4423, 4424, 4422, -1, 4424, 4423, 4425, -1, + 4425, 4426, 4424, -1, 4426, 4425, 4427, -1, + 4427, 4428, 4426, -1, 4428, 4427, 4429, -1, + 4429, 4430, 4428, -1, 4430, 4429, 4431, -1, + 4431, 4432, 4430, -1, 4432, 4431, 4433, -1, + 4433, 4434, 4432, -1, 4434, 4433, 4435, -1, + 4435, 4436, 4434, -1, 4436, 4435, 4437, -1, + 4437, 4438, 4436, -1, 4438, 4437, 4439, -1, + 4439, 4440, 4438, -1, 4440, 4439, 4441, -1, + 4441, 4442, 4440, -1, 4442, 4441, 3435, -1, + 3435, 4443, 4442, -1, 4443, 3435, 3116, -1, + 3116, 3115, 4443, -1, 3115, 4444, 4443, -1, + 4444, 3115, 3118, -1, 3118, 4445, 4444, -1, + 4445, 3118, 3119, -1, 3119, 4446, 4445, -1, + 4446, 3119, 3120, -1, 3120, 4447, 4446, -1, + 4447, 3120, 3121, -1, 3121, 4448, 4447, -1, + 4448, 3121, 3122, -1, 3122, 4449, 4448, -1, + 4449, 3122, 3123, -1, 3123, 4450, 4449, -1, + 4450, 3123, 3125, -1, 3125, 4451, 4450, -1, + 4451, 3125, 3127, -1, 3127, 4452, 4451, -1, + 4452, 3127, 3129, -1, 3129, 4453, 4452, -1, + 4453, 3129, 3301, -1, 3301, 4454, 4453, -1, + 4454, 3301, 3300, -1, 3300, 4455, 4454, -1, + 4455, 3300, 3299, -1, 3299, 4456, 4455, -1, + 4456, 3299, 3298, -1, 3298, 4457, 4456, -1, + 4457, 3298, 3297, -1, 3297, 4458, 4457, -1, + 4458, 3297, 3296, -1, 3296, 4459, 4458, -1, + 4459, 3296, 3295, -1, 3295, 4460, 4459, -1, + 4460, 3295, 3294, -1, 3294, 4461, 4460, -1, + 4461, 3294, 3293, -1, 3293, 4462, 4461, -1, + 4462, 3293, 3292, -1, 3292, 4463, 4462, -1, + 4463, 3292, 3291, -1, 3291, 4464, 4463, -1, + 4464, 3291, 3290, -1, 3290, 4465, 4464, -1, + 4465, 3290, 3289, -1, 3289, 4466, 4465, -1, + 4466, 3289, 3288, -1, 3288, 4467, 4466, -1, + 4467, 3288, 3287, -1, 3287, 4468, 4467, -1, + 3287, 4469, 4468, -1, 4469, 3287, 3286, -1, + 3286, 4470, 4469, -1, 4470, 3286, 3285, -1, + 3285, 4471, 4470, -1, 4471, 3285, 3284, -1, + 3284, 4472, 4471, -1, 4472, 3284, 3283, -1, + 3283, 4473, 4472, -1, 4473, 3283, 3282, -1, + 3282, 4474, 4473, -1, 4474, 3282, 3281, -1, + 3281, 4475, 4474, -1, 4475, 3281, 3280, -1, + 3280, 4476, 4475, -1, 4476, 3280, 3279, -1, + 3279, 4477, 4476, -1, 4477, 3279, 3278, -1, + 3278, 4478, 4477, -1, 4478, 3278, 3277, -1, + 3277, 4479, 4478, -1, 4479, 3277, 3276, -1, + 3276, 4480, 4479, -1, 4480, 3276, 3275, -1, + 3275, 4481, 4480, -1, 4481, 3275, 3274, -1, + 3274, 4482, 4481, -1, 4482, 3274, 3273, -1, + 3273, 4483, 4482, -1, 4483, 3273, 3272, -1, + 3272, 4484, 4483, -1, 4484, 3272, 3271, -1, + 3271, 4485, 4484, -1, 4485, 3271, 3270, -1, + 3270, 4486, 4485, -1, 4486, 3270, 3269, -1, + 3269, 4487, 4486, -1, 4487, 3269, 3268, -1, + 3268, 4488, 4487, -1, 4488, 3268, 3267, -1, + 3267, 4489, 4488, -1, 4489, 3267, 3266, -1, + 3266, 4490, 4489, -1, 4490, 3266, 3265, -1, + 3265, 4491, 4490, -1, 4491, 3265, 3264, -1, + 3264, 4492, 4491, -1, 4492, 3264, 3188, -1, + 3188, 4493, 4492, -1, 4493, 3188, 3186, -1, + 3186, 4494, 4493, -1, 4494, 3186, 3184, -1, + 3184, 4495, 4494, -1, 4495, 3184, 3182, -1, + 3182, 4496, 4495, -1, 4496, 3182, 3180, -1, + 3180, 4497, 4496, -1, 4497, 3180, 3178, -1, + 3178, 4498, 4497, -1, 4498, 3178, 3176, -1, + 3176, 4499, 4498, -1, 4499, 3176, 3174, -1, + 3174, 4500, 4499, -1, 4500, 3174, 3172, -1, + 3172, 4501, 4500, -1, 4501, 3172, 3170, -1, + 3170, 4502, 4501, -1, 4502, 3170, 3168, -1, + 3168, 4503, 4502, -1, 4503, 3168, 3166, -1, + 3166, 4504, 4503, -1, 4504, 3166, 3164, -1, + 3164, 4505, 4504, -1, 4505, 3164, 3162, -1, + 3162, 4506, 4505, -1, 4506, 3162, 3161, -1, + 3161, 4507, 4506, -1, 4507, 3161, 3160, -1, + 3160, 4508, 4507, -1, 4508, 3160, 3159, -1, + 3159, 4509, 4508, -1, 4509, 3159, 3158, -1, + 3158, 4510, 4509, -1, 4510, 3158, 3131, -1, + 3131, 3130, 4510, -1, 3130, 4511, 4510, -1, + 4511, 3130, 3133, -1, 3133, 4512, 4511, -1, + 3133, 3134, 4512, -1, 4513, 4512, 3134, -1, + 4513, 3134, 3137, -1, 3137, 3140, 4513, -1, + 4514, 4515, 4513, -1, 4514, 4513, 3140, -1, + 3140, 4516, 4514, -1, 4516, 3140, 3141, -1, + 3141, 4517, 4516, -1, 4517, 3141, 3143, -1, + 3143, 4518, 4517, -1, 4519, 4520, 4521, -1, + 4520, 4519, 4518, -1, 4518, 3143, 4520, -1, + 4522, 4523, 4520, -1, 4522, 4520, 3143, -1, + 3143, 3142, 4522, -1, 4522, 4524, 4525, -1, + 4524, 4522, 3142, -1, 3142, 3144, 4524, -1, + 4526, 4527, 4524, -1, 4526, 4524, 3144, -1, + 3144, 3145, 4526, -1, 4526, 3092, 4528, -1, + 3092, 4526, 3145, -1, 3145, 3104, 3092, -1, + 3104, 3145, 3146, -1, 3146, 3102, 3104, -1, + 3102, 3146, 3147, -1, 3147, 3100, 3102, -1, + 3100, 3147, 3148, -1, 3148, 3098, 3100, -1, + 3098, 3148, 3155, -1, 3155, 3096, 3098, -1, + 3096, 3155, 3153, -1, 3153, 3093, 3096, -1, + 3093, 3153, 3151, -1, 3151, 3094, 3093, -1, + 3094, 3151, 3150, -1, 3150, 4529, 3094, -1, + 4529, 3150, 3163, -1, 3163, 4530, 4529, -1, + 4530, 3163, 3165, -1, 3165, 4531, 4530, -1, + 4531, 3165, 3167, -1, 3167, 4532, 4531, -1, + 4532, 3167, 3169, -1, 3169, 4533, 4532, -1, + 4533, 3169, 3171, -1, 3171, 4534, 4533, -1, + 4534, 3171, 3173, -1, 3173, 4535, 4534, -1, + 4535, 3173, 3175, -1, 3175, 4536, 4535, -1, + 4536, 3175, 3177, -1, 3177, 4537, 4536, -1, + 4537, 3177, 3179, -1, 3179, 4538, 4537, -1, + 4538, 3179, 3181, -1, 3181, 4539, 4538, -1, + 4539, 3181, 3183, -1, 3183, 4540, 4539, -1, + 4540, 3183, 3185, -1, 3185, 4541, 4540, -1, + 4541, 3185, 3187, -1, 3187, 3340, 4541, -1, + 4542, 4541, 3340, -1, 3340, 4543, 4542, -1, + 4543, 3340, 3341, -1, 3341, 4544, 4543, -1, + 4544, 3341, 3342, -1, 3342, 4545, 4544, -1, + 4545, 3342, 3343, -1, 3343, 4546, 4545, -1, + 4546, 3343, 3344, -1, 3344, 4547, 4546, -1, + 4547, 3344, 3361, -1, 3361, 4548, 4547, -1, + 4548, 3361, 3359, -1, 3359, 4549, 4548, -1, + 4549, 3359, 3357, -1, 3357, 4550, 4549, -1, + 4550, 3357, 3355, -1, 3355, 4551, 4550, -1, + 4552, 4553, 4554, -1, 4554, 4555, 4552, -1, + 4555, 4554, 4556, -1, 4556, 4557, 4555, -1, + 4557, 4556, 4558, -1, 4558, 4559, 4557, -1, + 4559, 4558, 4560, -1, 4560, 4561, 4559, -1, + 4561, 4560, 4551, -1, 4551, 3355, 4561, -1, + 4561, 3355, 3352, -1, 3352, 4559, 4561, -1, + 4559, 3352, 3351, -1, 3351, 4557, 4559, -1, + 4557, 3351, 3349, -1, 3349, 4555, 4557, -1, + 4555, 3349, 3347, -1, 3347, 4552, 4555, -1, + 4552, 3347, 3346, -1, 3346, 4553, 4552, -1, + 4553, 3346, 4562, -1, 4562, 4563, 4553, -1, + 4563, 4562, 4564, -1, 4564, 4565, 4563, -1, + 4565, 4564, 4566, -1, 4566, 4567, 4565, -1, + 4567, 4566, 4568, -1, 4568, 4569, 4567, -1, + 4569, 4568, 4570, -1, 4570, 4571, 4569, -1, + 4571, 4570, 4572, -1, 4572, 4573, 4571, -1, + 4573, 4572, 4574, -1, 4574, 4575, 4573, -1, + 4575, 4574, 4576, -1, 4576, 4577, 4575, -1, + 4577, 4576, 4578, -1, 4578, 4579, 4577, -1, + 4579, 4578, 4580, -1, 4579, 4580, 4581, -1, + 4581, 4582, 4579, -1, 4582, 4581, 4583, -1, + 4583, 4584, 4582, -1, 4584, 4583, 4585, -1, + 4585, 4586, 4584, -1, 4586, 4585, 4587, -1, + 4587, 4588, 4586, -1, 4588, 4587, 4589, -1, + 4589, 4590, 4588, -1, 4590, 4589, 4591, -1, + 4591, 4592, 4590, -1, 4592, 4591, 4593, -1, + 4593, 4594, 4592, -1, 4594, 4593, 4595, -1, + 4595, 4596, 4594, -1, 4595, 4597, 4596, -1, + 4598, 4599, 4600, -1, 4599, 4598, 4601, -1, + 4601, 4602, 4599, -1, 4602, 4601, 4603, -1, + 4603, 4604, 4602, -1, 4604, 4603, 4605, -1, + 4605, 4606, 4604, -1, 4606, 4605, 4607, -1, + 4607, 4608, 4606, -1, 4608, 4607, 4609, -1, + 4609, 4610, 4608, -1, 4610, 4609, 4597, -1, + 4597, 4611, 4610, -1, 4611, 4597, 4595, -1, + 4595, 4612, 4611, -1, 4612, 4595, 4593, -1, + 4593, 4613, 4612, -1, 4613, 4593, 4591, -1, + 4591, 4614, 4613, -1, 4614, 4591, 4589, -1, + 4589, 4615, 4614, -1, 4615, 4589, 4587, -1, + 4587, 4616, 4615, -1, 4616, 4587, 4585, -1, + 4585, 4617, 4616, -1, 4617, 4585, 4583, -1, + 4583, 4618, 4617, -1, 4618, 4583, 4581, -1, + 4581, 4619, 4618, -1, 4619, 4581, 4580, -1, + 4580, 4620, 4619, -1, 4580, 4621, 4620, -1, + 4621, 4580, 4578, -1, 4578, 4622, 4621, -1, + 4622, 4578, 4576, -1, 4576, 4623, 4622, -1, + 4623, 4576, 4574, -1, 4574, 4624, 4623, -1, + 4624, 4574, 4572, -1, 4572, 4625, 4624, -1, + 4625, 4572, 4570, -1, 4570, 4626, 4625, -1, + 4626, 4570, 4568, -1, 4568, 4627, 4626, -1, + 4627, 4568, 4566, -1, 4566, 4628, 4627, -1, + 4628, 4566, 4564, -1, 4564, 4629, 4628, -1, + 4629, 4564, 4562, -1, 4562, 4630, 4629, -1, + 4630, 4562, 3346, -1, 3346, 3345, 4630, -1, + 4631, 4630, 3345, -1, 3345, 4632, 4631, -1, + 4632, 3345, 3348, -1, 3348, 4633, 4632, -1, + 4633, 3348, 3350, -1, 3350, 3353, 4633, -1, + 4633, 3353, 3363, -1, 3363, 4632, 4633, -1, + 4632, 3363, 3424, -1, 3424, 4631, 4632, -1, + 4631, 3424, 3422, -1, 3422, 4630, 4631, -1, + 4630, 3422, 3420, -1, 3420, 4629, 4630, -1, + 4629, 3420, 3418, -1, 3418, 4628, 4629, -1, + 4628, 3418, 3416, -1, 3416, 4627, 4628, -1, + 4627, 3416, 3414, -1, 3414, 4626, 4627, -1, + 4626, 3414, 3412, -1, 3412, 4625, 4626, -1, + 4625, 3412, 3410, -1, 3410, 4624, 4625, -1, + 4624, 3410, 3408, -1, 3408, 4623, 4624, -1, + 4623, 3408, 3406, -1, 3406, 4622, 4623, -1, + 4622, 3406, 3404, -1, 3404, 4621, 4622, -1, + 4621, 3404, 3402, -1, 3402, 4620, 4621, -1, + 4620, 3402, 3399, -1, 4620, 3399, 3397, -1, + 3397, 4619, 4620, -1, 4619, 3397, 3395, -1, + 3395, 4618, 4619, -1, 4618, 3395, 3393, -1, + 3393, 4617, 4618, -1, 4617, 3393, 3391, -1, + 3391, 4616, 4617, -1, 4616, 3391, 3389, -1, + 3389, 4615, 4616, -1, 4615, 3389, 3387, -1, + 3387, 4614, 4615, -1, 4614, 3387, 3385, -1, + 3385, 4613, 4614, -1, 4613, 3385, 3383, -1, + 3383, 4612, 4613, -1, 4612, 3383, 3381, -1, + 3381, 4611, 4612, -1, 4611, 3381, 3380, -1, + 3380, 4610, 4611, -1, 4610, 3380, 3379, -1, + 3379, 4608, 4610, -1, 4608, 3379, 3378, -1, + 3378, 4606, 4608, -1, 4606, 3378, 3377, -1, + 3377, 4604, 4606, -1, 4604, 3377, 3376, -1, + 3376, 4602, 4604, -1, 4602, 3376, 3374, -1, + 3374, 4599, 4602, -1, 4599, 3374, 3375, -1, + 3375, 4600, 4599, -1, 4600, 3375, 3426, -1, + 3426, 3427, 4600, -1, 4634, 4600, 3427, -1, + 4600, 4634, 4635, -1, 4635, 4598, 4600, -1, + 4598, 4635, 4636, -1, 4636, 4601, 4598, -1, + 4601, 4636, 4637, -1, 4637, 4603, 4601, -1, + 4603, 4637, 4638, -1, 4638, 4605, 4603, -1, + 4605, 4638, 4639, -1, 4639, 4607, 4605, -1, + 4607, 4639, 4640, -1, 4640, 4609, 4607, -1, + 4609, 4640, 4641, -1, 4641, 4597, 4609, -1, + 4641, 4596, 4597, -1, 4641, 4642, 4596, -1, + 4642, 4641, 4640, -1, 4640, 4643, 4642, -1, + 4643, 4640, 4639, -1, 4639, 4644, 4643, -1, + 4644, 4639, 4638, -1, 4638, 4645, 4644, -1, + 4645, 4638, 4637, -1, 4637, 4646, 4645, -1, + 4646, 4637, 4636, -1, 4636, 4647, 4646, -1, + 4647, 4636, 4635, -1, 4635, 4648, 4647, -1, + 4648, 4635, 4634, -1, 4634, 4649, 4648, -1, + 4649, 4634, 3427, -1, 3427, 4650, 4649, -1, + 4650, 3427, 3428, -1, 3428, 4651, 4650, -1, + 4651, 3428, 3429, -1, 3429, 4652, 4651, -1, + 4652, 3429, 3430, -1, 3430, 4653, 4652, -1, + 4653, 3430, 3431, -1, 3431, 4654, 4653, -1, + 4654, 3431, 3432, -1, 3432, 4655, 4654, -1, + 4655, 3432, 3433, -1, 3433, 4656, 4655, -1, + 4656, 3433, 3434, -1, 3434, 4657, 4656, -1, + 4657, 3434, 3435, -1, 3435, 4658, 4657, -1, + 4658, 3435, 4441, -1, 4441, 4659, 4658, -1, + 4659, 4441, 4439, -1, 4439, 4660, 4659, -1, + 4660, 4439, 4437, -1, 4437, 4661, 4660, -1, + 4661, 4437, 4435, -1, 4435, 4662, 4661, -1, + 4662, 4435, 4433, -1, 4433, 4663, 4662, -1, + 4663, 4433, 4431, -1, 4431, 4664, 4663, -1, + 4664, 4431, 4429, -1, 4429, 4665, 4664, -1, + 4665, 4429, 4427, -1, 4427, 4666, 4665, -1, + 4666, 4427, 4425, -1, 4425, 4667, 4666, -1, + 4667, 4425, 4423, -1, 4423, 4668, 4667, -1, + 4668, 4423, 4421, -1, 4421, 4669, 4668, -1, + 4669, 4421, 4419, -1, 4419, 4670, 4669, -1, + 4670, 4419, 3447, -1, 3447, 4671, 4670, -1, + 4671, 3447, 3446, -1, 3446, 4672, 4671, -1, + 4672, 3446, 3448, -1, 3448, 4673, 4672, -1, + 4673, 3448, 3449, -1, 3449, 4674, 4673, -1, + 4674, 3449, 3450, -1, 3450, 4675, 4674, -1, + 4675, 3450, 3452, -1, 3452, 4676, 4675, -1, + 4676, 3452, 3454, -1, 3454, 4677, 4676, -1, + 4677, 3454, 3456, -1, 3456, 4678, 4677, -1, + 4678, 3456, 3458, -1, 3458, 3460, 4678, -1, + 4679, 4678, 3460, -1, 3460, 3461, 4679, -1, + 4679, 3461, 4387, -1, 4387, 4678, 4679, -1, + 4387, 4680, 4678, -1, 4680, 4387, 4023, -1, + 4680, 4023, 4024, -1, 4024, 4025, 4680, -1, + 4025, 4678, 4680, -1, 4025, 4677, 4678, -1, + 4677, 4025, 4026, -1, 4026, 4676, 4677, -1, + 4676, 4026, 4032, -1, 4032, 4675, 4676, -1, + 4675, 4032, 4030, -1, 4030, 4674, 4675, -1, + 4674, 4030, 4027, -1, 4027, 4673, 4674, -1, + 4673, 4027, 4029, -1, 4029, 4672, 4673, -1, + 4672, 4029, 4040, -1, 4040, 4671, 4672, -1, + 4671, 4040, 4042, -1, 4042, 4670, 4671, -1, + 4670, 4042, 4044, -1, 4044, 4669, 4670, -1, + 4669, 4044, 4046, -1, 4046, 4668, 4669, -1, + 4668, 4046, 4048, -1, 4048, 4667, 4668, -1, + 4667, 4048, 4050, -1, 4050, 4666, 4667, -1, + 4666, 4050, 4052, -1, 4052, 4665, 4666, -1, + 4665, 4052, 4054, -1, 4054, 4664, 4665, -1, + 4664, 4054, 4056, -1, 4056, 4663, 4664, -1, + 4663, 4056, 4058, -1, 4058, 4662, 4663, -1, + 4662, 4058, 4060, -1, 4060, 4661, 4662, -1, + 4661, 4060, 4062, -1, 4062, 4660, 4661, -1, + 4660, 4062, 4064, -1, 4064, 4659, 4660, -1, + 4659, 4064, 4066, -1, 4066, 4658, 4659, -1, + 4658, 4066, 4334, -1, 4334, 4333, 4658, -1, + 4333, 4657, 4658, -1, 4657, 4333, 4331, -1, + 4331, 4656, 4657, -1, 4656, 4331, 4329, -1, + 4329, 4655, 4656, -1, 4655, 4329, 4327, -1, + 4327, 4654, 4655, -1, 4654, 4327, 4325, -1, + 4325, 4653, 4654, -1, 4653, 4325, 4323, -1, + 4323, 4652, 4653, -1, 4652, 4323, 4321, -1, + 4321, 4651, 4652, -1, 4651, 4321, 4319, -1, + 4319, 4650, 4651, -1, 4650, 4319, 4317, -1, + 4317, 4649, 4650, -1, 4649, 4317, 4316, -1, + 4316, 4648, 4649, -1, 4648, 4316, 4315, -1, + 4315, 4647, 4648, -1, 4647, 4315, 4314, -1, + 4314, 4646, 4647, -1, 4646, 4314, 4313, -1, + 4313, 4645, 4646, -1, 4645, 4313, 4312, -1, + 4312, 4644, 4645, -1, 4644, 4312, 4311, -1, + 4311, 4643, 4644, -1, 4643, 4311, 4310, -1, + 4310, 4642, 4643, -1, 4642, 4310, 4068, -1, + 4068, 4596, 4642, -1, 4596, 4068, 4067, -1, + 4067, 4594, 4596, -1, 4594, 4067, 4071, -1, + 4071, 4592, 4594, -1, 4592, 4071, 4073, -1, + 4073, 4590, 4592, -1, 4590, 4073, 4075, -1, + 4075, 4588, 4590, -1, 4588, 4075, 4077, -1, + 4077, 4586, 4588, -1, 4586, 4077, 4079, -1, + 4079, 4584, 4586, -1, 4584, 4079, 4081, -1, + 4081, 4582, 4584, -1, 4582, 4081, 4083, -1, + 4083, 4579, 4582, -1, 4083, 4577, 4579, -1, + 4577, 4083, 4084, -1, 4084, 4575, 4577, -1, + 4575, 4084, 4086, -1, 4086, 4573, 4575, -1, + 4573, 4086, 4088, -1, 4088, 4571, 4573, -1, + 4571, 4088, 4090, -1, 4090, 4569, 4571, -1, + 4569, 4090, 4092, -1, 4092, 4567, 4569, -1, + 4567, 4092, 4094, -1, 4094, 4565, 4567, -1, + 4565, 4094, 4096, -1, 4096, 4563, 4565, -1, + 4563, 4096, 4098, -1, 4098, 4553, 4563, -1, + 4553, 4098, 4100, -1, 4100, 4554, 4553, -1, + 4554, 4100, 4294, -1, 4294, 4556, 4554, -1, + 4556, 4294, 4293, -1, 4293, 4558, 4556, -1, + 4558, 4293, 4292, -1, 4292, 4560, 4558, -1, + 4560, 4292, 4291, -1, 4291, 4551, 4560, -1, + 4551, 4291, 4101, -1, 4101, 4550, 4551, -1, + 4550, 4101, 4104, -1, 4104, 4549, 4550, -1, + 4549, 4104, 4106, -1, 4106, 4548, 4549, -1, + 4548, 4106, 4108, -1, 4108, 4547, 4548, -1, + 4547, 4108, 4110, -1, 4110, 4546, 4547, -1, + 4546, 4110, 4112, -1, 4112, 4545, 4546, -1, + 4545, 4112, 4114, -1, 4114, 4544, 4545, -1, + 4544, 4114, 4116, -1, 4116, 4543, 4544, -1, + 4543, 4116, 4118, -1, 4118, 4542, 4543, -1, + 4542, 4118, 4120, -1, 4120, 4541, 4542, -1, + 4541, 4120, 4122, -1, 4122, 4540, 4541, -1, + 4540, 4122, 4281, -1, 4281, 4539, 4540, -1, + 4539, 4281, 4681, -1, 4681, 4538, 4539, -1, + 4538, 4681, 4682, -1, 4682, 4537, 4538, -1, + 4537, 4682, 4683, -1, 4683, 4536, 4537, -1, + 4536, 4683, 4684, -1, 4684, 4535, 4536, -1, + 4535, 4684, 4685, -1, 4685, 4534, 4535, -1, + 4534, 4685, 4686, -1, 4686, 4533, 4534, -1, + 4533, 4686, 4687, -1, 4687, 4532, 4533, -1, + 4532, 4687, 4688, -1, 4688, 4531, 4532, -1, + 4531, 4688, 4689, -1, 4689, 4530, 4531, -1, + 4530, 4689, 4690, -1, 4690, 4529, 4530, -1, + 4529, 4690, 4691, -1, 4691, 3094, 4529, -1, + 3094, 4691, 4692, -1, 4692, 3095, 3094, -1, + 3095, 4692, 4693, -1, 4693, 3097, 3095, -1, + 3097, 4693, 4694, -1, 4694, 3099, 3097, -1, + 3099, 4694, 4695, -1, 4695, 3101, 3099, -1, + 3101, 4695, 4696, -1, 4696, 3103, 3101, -1, + 3103, 4696, 4697, -1, 4697, 3090, 3103, -1, + 4697, 4698, 3090, -1, 4699, 3090, 4698, -1, + 4699, 4698, 3089, -1, 4699, 3089, 4700, -1, + 4700, 3090, 4699, -1, 4700, 3091, 3090, -1, + 4700, 3089, 3091, -1, 3091, 3089, 3087, -1, + 3087, 3092, 3091, -1, 3087, 3088, 3092, -1, + 3088, 4528, 3092, -1, 4528, 3088, 3086, -1, + 4528, 3086, 4701, -1, 4701, 4526, 4528, -1, + 4701, 4527, 4526, -1, 4527, 4701, 3086, -1, + 4527, 3086, 2509, -1, 2509, 4524, 4527, -1, + 2509, 2508, 4524, -1, 2508, 4525, 4524, -1, + 4525, 2508, 2510, -1, 4525, 2510, 4702, -1, + 4702, 4522, 4525, -1, 4702, 4523, 4522, -1, + 4523, 4702, 2510, -1, 4523, 2510, 2512, -1, + 2512, 4520, 4523, -1, 2512, 2511, 4520, -1, + 2511, 4521, 4520, -1, 4521, 2511, 2506, -1, + 4521, 2506, 2505, -1, 2505, 4519, 4521, -1, + 2505, 2507, 4519, -1, 4703, 4704, 4705, -1, + 4703, 4705, 2507, -1, 4705, 4519, 2507, -1, + 4519, 4705, 4706, -1, 4706, 4518, 4519, -1, + 4518, 4706, 4707, -1, 4707, 4517, 4518, -1, + 4517, 4707, 4708, -1, 4708, 4516, 4517, -1, + 4516, 4708, 4709, -1, 4709, 4514, 4516, -1, + 4709, 4710, 4514, -1, 4711, 4712, 4713, -1, + 4712, 4711, 4714, -1, 4714, 4715, 4712, -1, + 4715, 4714, 4710, -1, 4710, 4716, 4715, -1, + 4716, 4710, 4709, -1, 4716, 4709, 2503, -1, + 4716, 2503, 2502, -1, 2502, 4715, 4716, -1, + 4715, 2502, 2501, -1, 2501, 4712, 4715, -1, + 4712, 2501, 2496, -1, 2496, 4713, 4712, -1, + 4713, 2496, 2494, -1, 2494, 4717, 4713, -1, + 4717, 2494, 2492, -1, 2492, 4718, 4717, -1, + 4718, 2492, 2490, -1, 2490, 4719, 4718, -1, + 4719, 2490, 2488, -1, 2488, 4720, 4719, -1, + 4720, 2488, 2486, -1, 2486, 4721, 4720, -1, + 4721, 2486, 2484, -1, 2484, 4722, 4721, -1, + 4722, 2484, 2482, -1, 2482, 4723, 4722, -1, + 4723, 2482, 2480, -1, 2480, 4724, 4723, -1, + 4724, 2480, 2478, -1, 2478, 4725, 4724, -1, + 4725, 2478, 2476, -1, 2476, 4726, 4725, -1, + 4726, 2476, 2474, -1, 2474, 4727, 4726, -1, + 4727, 2474, 2472, -1, 2472, 4728, 4727, -1, + 4728, 2472, 2470, -1, 2470, 4729, 4728, -1, + 4729, 2470, 2468, -1, 2468, 4730, 4729, -1, + 4730, 2468, 2466, -1, 2466, 4731, 4730, -1, + 4731, 2466, 2464, -1, 2464, 4732, 4731, -1, + 4732, 2464, 2462, -1, 2462, 4733, 4732, -1, + 4733, 2462, 2460, -1, 2460, 4734, 4733, -1, + 4734, 2460, 2458, -1, 2458, 4735, 4734, -1, + 4735, 2458, 2456, -1, 2456, 4736, 4735, -1, + 4736, 2456, 2454, -1, 2454, 4737, 4736, -1, + 4737, 2454, 2452, -1, 2452, 4738, 4737, -1, + 4738, 2452, 2450, -1, 2450, 4739, 4738, -1, + 4739, 2450, 2448, -1, 2448, 4740, 4739, -1, + 4740, 2448, 2446, -1, 2446, 4741, 4740, -1, + 4741, 2446, 2444, -1, 2444, 4742, 4741, -1, + 4742, 2444, 2442, -1, 2442, 4743, 4742, -1, + 4743, 2442, 2440, -1, 2440, 4744, 4743, -1, + 4744, 2440, 2438, -1, 2438, 4745, 4744, -1, + 4745, 2438, 2436, -1, 2436, 4746, 4745, -1, + 4746, 2436, 2434, -1, 2434, 4747, 4746, -1, + 4747, 2434, 2432, -1, 2432, 4748, 4747, -1, + 4748, 2432, 2430, -1, 2430, 4749, 4748, -1, + 4749, 2430, 2428, -1, 2428, 4750, 4749, -1, + 4750, 2428, 2426, -1, 2426, 4751, 4750, -1, + 4751, 2426, 2424, -1, 2424, 4752, 4751, -1, + 4752, 2424, 2422, -1, 2422, 4753, 4752, -1, + 4753, 2422, 2420, -1, 2420, 4754, 4753, -1, + 4754, 2420, 2418, -1, 2418, 4755, 4754, -1, + 4755, 2418, 2416, -1, 2416, 4756, 4755, -1, + 4756, 2416, 2414, -1, 2414, 4757, 4756, -1, + 4757, 2414, 2412, -1, 2412, 4758, 4757, -1, + 4758, 2412, 2410, -1, 2410, 4759, 4758, -1, + 4759, 2410, 2408, -1, 2408, 4760, 4759, -1, + 4760, 2408, 2405, -1, 4760, 2405, 2403, -1, + 2403, 4761, 4760, -1, 4761, 2403, 2401, -1, + 2401, 4762, 4761, -1, 4762, 2401, 2399, -1, + 2399, 4763, 4762, -1, 4763, 2399, 2397, -1, + 2397, 4764, 4763, -1, 4764, 2397, 2395, -1, + 2395, 4765, 4764, -1, 4765, 2395, 2393, -1, + 2393, 4766, 4765, -1, 4766, 2393, 2391, -1, + 2391, 4767, 4766, -1, 4767, 2391, 2389, -1, + 2389, 4768, 4767, -1, 4768, 2389, 2387, -1, + 2387, 4769, 4768, -1, 4769, 2387, 2385, -1, + 2385, 4770, 4769, -1, 4770, 2385, 2383, -1, + 2383, 4771, 4770, -1, 4771, 2383, 2381, -1, + 2381, 4772, 4771, -1, 4772, 2381, 2379, -1, + 2379, 4773, 4772, -1, 4773, 2379, 2377, -1, + 2377, 4774, 4773, -1, 4774, 2377, 2375, -1, + 2375, 4775, 4774, -1, 4775, 2375, 2373, -1, + 2373, 4776, 4775, -1, 4776, 2373, 2371, -1, + 2371, 4777, 4776, -1, 4777, 2371, 2369, -1, + 2369, 4778, 4777, -1, 4778, 2369, 2367, -1, + 2367, 4779, 4778, -1, 4779, 2367, 2365, -1, + 2365, 4780, 4779, -1, 4780, 2365, 2363, -1, + 2363, 4781, 4780, -1, 4781, 2363, 2361, -1, + 2361, 4782, 4781, -1, 4782, 2361, 2359, -1, + 2359, 4783, 4782, -1, 4783, 2359, 2357, -1, + 2357, 4784, 4783, -1, 4784, 2357, 2355, -1, + 2355, 4785, 4784, -1, 4785, 2355, 2353, -1, + 2353, 4786, 4785, -1, 4786, 2353, 2351, -1, + 2351, 4787, 4786, -1, 4787, 2351, 2349, -1, + 2349, 4788, 4787, -1, 4788, 2349, 2347, -1, + 2347, 4789, 4788, -1, 4789, 2347, 2345, -1, + 2345, 4790, 4789, -1, 4790, 2345, 2343, -1, + 2343, 4791, 4790, -1, 4791, 2343, 2341, -1, + 2341, 4792, 4791, -1, 4792, 2341, 2339, -1, + 2339, 4793, 4792, -1, 4793, 2339, 2337, -1, + 2337, 4794, 4793, -1, 4794, 2337, 2335, -1, + 2335, 4795, 4794, -1, 4795, 2335, 2333, -1, + 2333, 4796, 4795, -1, 4796, 2333, 2331, -1, + 2331, 4797, 4796, -1, 4797, 2331, 2329, -1, + 2329, 4798, 4797, -1, 4798, 2329, 2327, -1, + 2327, 4799, 4798, -1, 4799, 2327, 2326, -1, + 2326, 4800, 4799, -1, 4800, 2326, 4801, -1, + 4801, 4802, 4800, -1, 4802, 4801, 4803, -1, + 4803, 4804, 4802, -1, 4804, 4803, 4805, -1, + 4805, 4806, 4804, -1, 4806, 4805, 4807, -1, + 4807, 4808, 4806, -1, 4808, 4807, 2324, -1, + 2324, 2323, 4808, -1, 4809, 2323, 4810, -1, + 4809, 4808, 2323, -1, 4808, 4809, 4811, -1, + 4811, 4806, 4808, -1, 4806, 4811, 4812, -1, + 4812, 4804, 4806, -1, 4804, 4812, 4813, -1, + 4813, 4802, 4804, -1, 4802, 4813, 4814, -1, + 4814, 4800, 4802, -1, 4800, 4814, 4815, -1, + 4815, 4799, 4800, -1, 4799, 4815, 4816, -1, + 4816, 4798, 4799, -1, 4798, 4816, 4817, -1, + 4817, 4797, 4798, -1, 4797, 4817, 4818, -1, + 4818, 4796, 4797, -1, 4796, 4818, 4819, -1, + 4819, 4795, 4796, -1, 4795, 4819, 4820, -1, + 4820, 4794, 4795, -1, 4794, 4820, 4821, -1, + 4821, 4793, 4794, -1, 4793, 4821, 4822, -1, + 4822, 4792, 4793, -1, 4792, 4822, 4823, -1, + 4823, 4791, 4792, -1, 4791, 4823, 4824, -1, + 4824, 4790, 4791, -1, 4790, 4824, 4825, -1, + 4825, 4789, 4790, -1, 4789, 4825, 4826, -1, + 4826, 4788, 4789, -1, 4788, 4826, 4827, -1, + 4827, 4787, 4788, -1, 4787, 4827, 4828, -1, + 4828, 4786, 4787, -1, 4786, 4828, 4829, -1, + 4829, 4785, 4786, -1, 4785, 4829, 4830, -1, + 4830, 4784, 4785, -1, 4784, 4830, 4831, -1, + 4831, 4783, 4784, -1, 4783, 4831, 4832, -1, + 4832, 4782, 4783, -1, 4782, 4832, 4833, -1, + 4833, 4781, 4782, -1, 4781, 4833, 4834, -1, + 4834, 4780, 4781, -1, 4780, 4834, 4835, -1, + 4835, 4779, 4780, -1, 4779, 4835, 4836, -1, + 4836, 4778, 4779, -1, 4778, 4836, 4837, -1, + 4837, 4777, 4778, -1, 4777, 4837, 4838, -1, + 4838, 4776, 4777, -1, 4776, 4838, 4839, -1, + 4839, 4775, 4776, -1, 4775, 4839, 4840, -1, + 4840, 4774, 4775, -1, 4774, 4840, 4841, -1, + 4841, 4773, 4774, -1, 4773, 4841, 4842, -1, + 4842, 4772, 4773, -1, 4772, 4842, 4843, -1, + 4843, 4771, 4772, -1, 4771, 4843, 4844, -1, + 4844, 4770, 4771, -1, 4770, 4844, 4845, -1, + 4845, 4769, 4770, -1, 4769, 4845, 4846, -1, + 4846, 4768, 4769, -1, 4768, 4846, 4847, -1, + 4847, 4767, 4768, -1, 4767, 4847, 4848, -1, + 4848, 4766, 4767, -1, 4766, 4848, 4849, -1, + 4849, 4765, 4766, -1, 4765, 4849, 4850, -1, + 4850, 4764, 4765, -1, 4764, 4850, 4851, -1, + 4851, 4763, 4764, -1, 4763, 4851, 4852, -1, + 4852, 4762, 4763, -1, 4762, 4852, 4853, -1, + 4853, 4761, 4762, -1, 4761, 4853, 4854, -1, + 4854, 4760, 4761, -1, 4854, 4759, 4760, -1, + 4759, 4854, 4855, -1, 4855, 4758, 4759, -1, + 4758, 4855, 4856, -1, 4856, 4757, 4758, -1, + 4757, 4856, 4857, -1, 4857, 4756, 4757, -1, + 4756, 4857, 4858, -1, 4858, 4755, 4756, -1, + 4755, 4858, 4859, -1, 4859, 4754, 4755, -1, + 4754, 4859, 4860, -1, 4860, 4753, 4754, -1, + 4753, 4860, 4861, -1, 4861, 4752, 4753, -1, + 4752, 4861, 4862, -1, 4862, 4751, 4752, -1, + 4751, 4862, 4863, -1, 4863, 4750, 4751, -1, + 4750, 4863, 4864, -1, 4864, 4749, 4750, -1, + 4749, 4864, 4865, -1, 4865, 4748, 4749, -1, + 4748, 4865, 4866, -1, 4866, 4747, 4748, -1, + 4747, 4866, 4867, -1, 4867, 4746, 4747, -1, + 4746, 4867, 4868, -1, 4868, 4745, 4746, -1, + 4745, 4868, 4869, -1, 4869, 4744, 4745, -1, + 4744, 4869, 4870, -1, 4870, 4743, 4744, -1, + 4743, 4870, 4871, -1, 4871, 4742, 4743, -1, + 4742, 4871, 4872, -1, 4872, 4741, 4742, -1, + 4741, 4872, 4873, -1, 4873, 4740, 4741, -1, + 4740, 4873, 4874, -1, 4874, 4739, 4740, -1, + 4739, 4874, 4875, -1, 4875, 4738, 4739, -1, + 4738, 4875, 4876, -1, 4876, 4737, 4738, -1, + 4737, 4876, 4877, -1, 4877, 4736, 4737, -1, + 4736, 4877, 4878, -1, 4878, 4735, 4736, -1, + 4735, 4878, 4879, -1, 4879, 4734, 4735, -1, + 4734, 4879, 4880, -1, 4880, 4733, 4734, -1, + 4733, 4880, 4881, -1, 4881, 4732, 4733, -1, + 4732, 4881, 4882, -1, 4882, 4731, 4732, -1, + 4731, 4882, 4883, -1, 4883, 4730, 4731, -1, + 4730, 4883, 4884, -1, 4884, 4729, 4730, -1, + 4729, 4884, 4885, -1, 4885, 4728, 4729, -1, + 4728, 4885, 4886, -1, 4886, 4727, 4728, -1, + 4727, 4886, 4887, -1, 4887, 4726, 4727, -1, + 4726, 4887, 4888, -1, 4888, 4725, 4726, -1, + 4725, 4888, 4889, -1, 4889, 4724, 4725, -1, + 4724, 4889, 4890, -1, 4890, 4723, 4724, -1, + 4723, 4890, 4891, -1, 4891, 4722, 4723, -1, + 4722, 4891, 4892, -1, 4892, 4721, 4722, -1, + 4721, 4892, 4893, -1, 4893, 4720, 4721, -1, + 4720, 4893, 4894, -1, 4894, 4719, 4720, -1, + 4719, 4894, 4895, -1, 4895, 4718, 4719, -1, + 4718, 4895, 4896, -1, 4896, 4717, 4718, -1, + 4717, 4896, 2317, -1, 2317, 4713, 4717, -1, + 4713, 2317, 2316, -1, 2316, 4711, 4713, -1, + 4711, 2316, 4897, -1, 4897, 4714, 4711, -1, + 4714, 4897, 4898, -1, 4898, 4710, 4714, -1, + 4898, 4514, 4710, -1, 4898, 4515, 4514, -1, + 4515, 4898, 4897, -1, 4897, 4899, 4515, -1, + 4899, 4897, 2316, -1, 2316, 2315, 4899, -1, + 4899, 2315, 4900, -1, 4900, 4515, 4899, -1, + 4900, 4513, 4515, -1, 4900, 4512, 4513, -1, + 4512, 4900, 2315, -1, 2315, 4511, 4512, -1, + 4511, 2315, 2317, -1, 2317, 4510, 4511, -1, + 4510, 2317, 4896, -1, 4896, 4509, 4510, -1, + 4509, 4896, 4895, -1, 4895, 4508, 4509, -1, + 4508, 4895, 4894, -1, 4894, 4507, 4508, -1, + 4507, 4894, 4893, -1, 4893, 4506, 4507, -1, + 4506, 4893, 4892, -1, 4892, 4505, 4506, -1, + 4505, 4892, 4891, -1, 4891, 4504, 4505, -1, + 4504, 4891, 4890, -1, 4890, 4503, 4504, -1, + 4503, 4890, 4889, -1, 4889, 4502, 4503, -1, + 4502, 4889, 4888, -1, 4888, 4501, 4502, -1, + 4501, 4888, 4887, -1, 4887, 4500, 4501, -1, + 4500, 4887, 4886, -1, 4886, 4499, 4500, -1, + 4499, 4886, 4885, -1, 4885, 4498, 4499, -1, + 4498, 4885, 4884, -1, 4884, 4497, 4498, -1, + 4497, 4884, 4883, -1, 4883, 4496, 4497, -1, + 4496, 4883, 4882, -1, 4882, 4495, 4496, -1, + 4495, 4882, 4881, -1, 4881, 4494, 4495, -1, + 4494, 4881, 4880, -1, 4880, 4493, 4494, -1, + 4493, 4880, 4879, -1, 4879, 4492, 4493, -1, + 4492, 4879, 4878, -1, 4878, 4491, 4492, -1, + 4491, 4878, 4877, -1, 4877, 4490, 4491, -1, + 4490, 4877, 4876, -1, 4876, 4489, 4490, -1, + 4489, 4876, 4875, -1, 4875, 4488, 4489, -1, + 4488, 4875, 4874, -1, 4874, 4487, 4488, -1, + 4487, 4874, 4873, -1, 4873, 4486, 4487, -1, + 4486, 4873, 4872, -1, 4872, 4485, 4486, -1, + 4485, 4872, 4871, -1, 4871, 4484, 4485, -1, + 4484, 4871, 4870, -1, 4870, 4483, 4484, -1, + 4483, 4870, 4869, -1, 4869, 4482, 4483, -1, + 4482, 4869, 4868, -1, 4868, 4481, 4482, -1, + 4481, 4868, 4867, -1, 4867, 4480, 4481, -1, + 4480, 4867, 4866, -1, 4866, 4479, 4480, -1, + 4479, 4866, 4865, -1, 4865, 4478, 4479, -1, + 4478, 4865, 4864, -1, 4864, 4477, 4478, -1, + 4477, 4864, 4863, -1, 4863, 4476, 4477, -1, + 4476, 4863, 4862, -1, 4862, 4475, 4476, -1, + 4475, 4862, 4861, -1, 4861, 4474, 4475, -1, + 4474, 4861, 4860, -1, 4860, 4473, 4474, -1, + 4473, 4860, 4859, -1, 4859, 4472, 4473, -1, + 4472, 4859, 4858, -1, 4858, 4471, 4472, -1, + 4471, 4858, 4857, -1, 4857, 4470, 4471, -1, + 4470, 4857, 4856, -1, 4856, 4469, 4470, -1, + 4469, 4856, 4855, -1, 4855, 4468, 4469, -1, + 4468, 4855, 4854, -1, 4468, 4854, 4853, -1, + 4853, 4467, 4468, -1, 4467, 4853, 4852, -1, + 4852, 4466, 4467, -1, 4466, 4852, 4851, -1, + 4851, 4465, 4466, -1, 4465, 4851, 4850, -1, + 4850, 4464, 4465, -1, 4464, 4850, 4849, -1, + 4849, 4463, 4464, -1, 4463, 4849, 4848, -1, + 4848, 4462, 4463, -1, 4462, 4848, 4847, -1, + 4847, 4461, 4462, -1, 4461, 4847, 4846, -1, + 4846, 4460, 4461, -1, 4460, 4846, 4845, -1, + 4845, 4459, 4460, -1, 4459, 4845, 4844, -1, + 4844, 4458, 4459, -1, 4458, 4844, 4843, -1, + 4843, 4457, 4458, -1, 4457, 4843, 4842, -1, + 4842, 4456, 4457, -1, 4456, 4842, 4841, -1, + 4841, 4455, 4456, -1, 4455, 4841, 4840, -1, + 4840, 4454, 4455, -1, 4454, 4840, 4839, -1, + 4839, 4453, 4454, -1, 4453, 4839, 4838, -1, + 4838, 4452, 4453, -1, 4452, 4838, 4837, -1, + 4837, 4451, 4452, -1, 4451, 4837, 4836, -1, + 4836, 4450, 4451, -1, 4450, 4836, 4835, -1, + 4835, 4449, 4450, -1, 4449, 4835, 4834, -1, + 4834, 4448, 4449, -1, 4448, 4834, 4833, -1, + 4833, 4447, 4448, -1, 4447, 4833, 4832, -1, + 4832, 4446, 4447, -1, 4446, 4832, 4831, -1, + 4831, 4445, 4446, -1, 4445, 4831, 4830, -1, + 4830, 4444, 4445, -1, 4444, 4830, 4829, -1, + 4829, 4443, 4444, -1, 4443, 4829, 4828, -1, + 4828, 4442, 4443, -1, 4442, 4828, 4827, -1, + 4827, 4440, 4442, -1, 4440, 4827, 4826, -1, + 4826, 4438, 4440, -1, 4438, 4826, 4825, -1, + 4825, 4436, 4438, -1, 4436, 4825, 4824, -1, + 4824, 4434, 4436, -1, 4434, 4824, 4823, -1, + 4823, 4432, 4434, -1, 4432, 4823, 4822, -1, + 4822, 4430, 4432, -1, 4430, 4822, 4821, -1, + 4821, 4428, 4430, -1, 4428, 4821, 4820, -1, + 4820, 4426, 4428, -1, 4426, 4820, 4819, -1, + 4819, 4424, 4426, -1, 4424, 4819, 4818, -1, + 4818, 4422, 4424, -1, 4422, 4818, 4817, -1, + 4817, 4420, 4422, -1, 4420, 4817, 4816, -1, + 4816, 4418, 4420, -1, 4418, 4816, 4815, -1, + 4815, 4417, 4418, -1, 4417, 4815, 4814, -1, + 4814, 4416, 4417, -1, 4416, 4814, 4813, -1, + 4813, 4415, 4416, -1, 4415, 4813, 4812, -1, + 4812, 4414, 4415, -1, 4414, 4812, 4811, -1, + 4811, 4413, 4414, -1, 4413, 4811, 4809, -1, + 4809, 4412, 4413, -1, 4412, 4809, 4810, -1, + 4810, 3665, 4412, -1, 3665, 4810, 4901, -1, + 4901, 3663, 3665, -1, 4901, 3676, 3663, -1, + 4901, 4902, 3676, -1, 4902, 4901, 4810, -1, + 4902, 4810, 2323, -1, 4902, 2323, 2321, -1, + 2321, 3676, 4902, -1, 3676, 2321, 2318, -1, + 2318, 3675, 3676, -1, 2318, 2320, 3675, -1, + 4903, 3675, 2320, -1, 4903, 3677, 3675, -1, + 4903, 3700, 3677, -1, 4903, 3868, 3700, -1, + 3868, 4903, 2320, -1, 2320, 3867, 3868, -1, + 3867, 2320, 2319, -1, 2319, 2322, 3867, -1, + 2322, 3860, 3867, -1, 2322, 3859, 3860, -1, + 3859, 2322, 2324, -1, 2324, 3858, 3859, -1, + 3858, 2324, 4807, -1, 4807, 3857, 3858, -1, + 3857, 4807, 4805, -1, 4805, 3856, 3857, -1, + 3856, 4805, 4803, -1, 4803, 3855, 3856, -1, + 3855, 4803, 4801, -1, 4801, 3854, 3855, -1, + 3854, 4801, 2326, -1, 2326, 2325, 3854, -1, + 2325, 3853, 3854, -1, 3853, 2325, 2328, -1, + 2328, 3852, 3853, -1, 3852, 2328, 2330, -1, + 2330, 3851, 3852, -1, 3851, 2330, 2332, -1, + 2332, 3850, 3851, -1, 3850, 2332, 2334, -1, + 2334, 3849, 3850, -1, 3849, 2334, 2336, -1, + 2336, 3848, 3849, -1, 3848, 2336, 2338, -1, + 2338, 3847, 3848, -1, 3847, 2338, 2340, -1, + 2340, 3846, 3847, -1, 3846, 2340, 2342, -1, + 2342, 3845, 3846, -1, 3845, 2342, 2344, -1, + 2344, 3844, 3845, -1, 3844, 2344, 2346, -1, + 2346, 3843, 3844, -1, 3843, 2346, 2348, -1, + 2348, 3842, 3843, -1, 3842, 2348, 2350, -1, + 2350, 3841, 3842, -1, 3841, 2350, 2352, -1, + 2352, 3840, 3841, -1, 3840, 2352, 2354, -1, + 2354, 3839, 3840, -1, 3839, 2354, 2356, -1, + 2356, 3838, 3839, -1, 3838, 2356, 2358, -1, + 2358, 3837, 3838, -1, 3837, 2358, 2360, -1, + 2360, 3836, 3837, -1, 3836, 2360, 2362, -1, + 2362, 3835, 3836, -1, 3835, 2362, 2364, -1, + 2364, 3834, 3835, -1, 3834, 2364, 2366, -1, + 2366, 3833, 3834, -1, 3833, 2366, 2368, -1, + 2368, 3832, 3833, -1, 3832, 2368, 2370, -1, + 2370, 3831, 3832, -1, 3831, 2370, 2372, -1, + 2372, 3830, 3831, -1, 3830, 2372, 2374, -1, + 2374, 3829, 3830, -1, 3829, 2374, 2376, -1, + 2376, 3828, 3829, -1, 3828, 2376, 2378, -1, + 2378, 3827, 3828, -1, 3827, 2378, 2380, -1, + 2380, 3826, 3827, -1, 3826, 2380, 2382, -1, + 2382, 3825, 3826, -1, 3825, 2382, 2384, -1, + 2384, 3824, 3825, -1, 3824, 2384, 2386, -1, + 2386, 3823, 3824, -1, 3823, 2386, 2388, -1, + 2388, 3822, 3823, -1, 3822, 2388, 2390, -1, + 2390, 3821, 3822, -1, 3821, 2390, 2392, -1, + 2392, 3820, 3821, -1, 3820, 2392, 2394, -1, + 2394, 3819, 3820, -1, 3819, 2394, 2396, -1, + 2396, 3818, 3819, -1, 3818, 2396, 2398, -1, + 2398, 3817, 3818, -1, 3817, 2398, 2400, -1, + 2400, 3816, 3817, -1, 3816, 2400, 2402, -1, + 2402, 3815, 3816, -1, 3815, 2402, 2404, -1, + 2404, 3814, 3815, -1, 3814, 2404, 2406, -1, + 2406, 3812, 3814, -1, 2406, 4904, 3812, -1, + 4904, 2406, 2407, -1, 2407, 4905, 4904, -1, + 4905, 2407, 2409, -1, 2409, 4906, 4905, -1, + 4906, 2409, 2411, -1, 2411, 4907, 4906, -1, + 4907, 2411, 2413, -1, 2413, 4908, 4907, -1, + 4908, 2413, 2415, -1, 2415, 4909, 4908, -1, + 4909, 2415, 2417, -1, 2417, 4910, 4909, -1, + 4910, 2417, 2419, -1, 2419, 4911, 4910, -1, + 4911, 2419, 2421, -1, 2421, 4912, 4911, -1, + 4912, 2421, 2423, -1, 2423, 4913, 4912, -1, + 4913, 2423, 2425, -1, 2425, 4914, 4913, -1, + 4914, 2425, 2427, -1, 2427, 4915, 4914, -1, + 4915, 2427, 2429, -1, 2429, 4916, 4915, -1, + 4916, 2429, 2431, -1, 2431, 4917, 4916, -1, + 4917, 2431, 2433, -1, 2433, 4918, 4917, -1, + 4918, 2433, 2435, -1, 2435, 4919, 4918, -1, + 4919, 2435, 2437, -1, 2437, 4920, 4919, -1, + 4920, 2437, 2439, -1, 2439, 4921, 4920, -1, + 4921, 2439, 2441, -1, 2441, 4922, 4921, -1, + 4922, 2441, 2443, -1, 2443, 4923, 4922, -1, + 4923, 2443, 2445, -1, 2445, 4924, 4923, -1, + 4924, 2445, 2447, -1, 2447, 4925, 4924, -1, + 4925, 2447, 2449, -1, 2449, 4926, 4925, -1, + 4926, 2449, 2451, -1, 2451, 4927, 4926, -1, + 4927, 2451, 2453, -1, 2453, 4928, 4927, -1, + 4928, 2453, 2455, -1, 2455, 4929, 4928, -1, + 4929, 2455, 2457, -1, 2457, 4930, 4929, -1, + 4930, 2457, 2459, -1, 2459, 4931, 4930, -1, + 4931, 2459, 2461, -1, 2461, 4932, 4931, -1, + 4932, 2461, 2463, -1, 2463, 4933, 4932, -1, + 4933, 2463, 2465, -1, 2465, 4934, 4933, -1, + 4934, 2465, 2467, -1, 2467, 4935, 4934, -1, + 4935, 2467, 2469, -1, 2469, 4936, 4935, -1, + 4936, 2469, 2471, -1, 2471, 4937, 4936, -1, + 4937, 2471, 2473, -1, 2473, 4938, 4937, -1, + 4938, 2473, 2475, -1, 2475, 4939, 4938, -1, + 4939, 2475, 2477, -1, 2477, 4940, 4939, -1, + 4940, 2477, 2479, -1, 2479, 4941, 4940, -1, + 4941, 2479, 2481, -1, 2481, 4942, 4941, -1, + 4942, 2481, 2483, -1, 2483, 4943, 4942, -1, + 4943, 2483, 2485, -1, 2485, 4944, 4943, -1, + 4944, 2485, 2487, -1, 2487, 4945, 4944, -1, + 4946, 4947, 4948, -1, 4946, 4948, 4949, -1, + 4949, 4950, 4946, -1, 4950, 4949, 4951, -1, + 4951, 4952, 4950, -1, 4952, 4951, 4953, -1, + 4953, 4954, 4952, -1, 4954, 4953, 4955, -1, + 4955, 4956, 4954, -1, 4956, 4955, 4957, -1, + 4957, 4958, 4956, -1, 4958, 4957, 4959, -1, + 4959, 4960, 4958, -1, 4960, 4959, 4945, -1, + 4945, 2487, 4960, -1, 4960, 2487, 2489, -1, + 2489, 4958, 4960, -1, 4958, 2489, 2491, -1, + 2491, 4956, 4958, -1, 4956, 2491, 2493, -1, + 2493, 4954, 4956, -1, 4954, 2493, 2495, -1, + 2495, 4952, 4954, -1, 4952, 2495, 2497, -1, + 2497, 4950, 4952, -1, 4950, 2497, 2500, -1, + 2500, 4946, 4950, -1, 2500, 4961, 4946, -1, + 4962, 4963, 4964, -1, 4962, 4964, 4965, -1, + 4962, 4965, 4966, -1, 4962, 4966, 4967, -1, + 4967, 4963, 4962, -1, 4963, 4967, 4961, -1, + 4961, 4968, 4963, -1, 4968, 4961, 2500, -1, + 4968, 2500, 2499, -1, 4968, 2499, 2504, -1, + 2504, 4963, 4968, -1, 2504, 4964, 4963, -1, + 2504, 2503, 4964, -1, 4964, 2503, 4709, -1, + 4964, 4709, 4708, -1, 4708, 4965, 4964, -1, + 4965, 4708, 4707, -1, 4707, 4969, 4965, -1, + 4969, 4707, 4706, -1, 4706, 4970, 4969, -1, + 4970, 4706, 4705, -1, 4705, 4971, 4970, -1, + 4971, 4705, 4704, -1, 4972, 4973, 4971, -1, + 4972, 4974, 4973, -1, 4972, 4975, 4974, -1, + 4972, 4971, 4975, -1, 4975, 4971, 4704, -1, + 4704, 4974, 4975, -1, 4704, 4703, 4974, -1, + 4703, 2507, 4974, -1, 4974, 2507, 2506, -1, + 4976, 4973, 4974, -1, 4977, 4978, 4979, -1, + 4980, 4981, 4982, -1, 4980, 4982, 4983, -1, + 4983, 4984, 4980, -1, 4984, 4983, 4979, -1, + 4979, 4985, 4984, -1, 4985, 4979, 4978, -1, + 4986, 4987, 4985, -1, 4986, 4976, 4987, -1, + 4986, 4988, 4976, -1, 4986, 4985, 4988, -1, + 4988, 4985, 4978, -1, 4978, 4976, 4988, -1, + 4978, 4977, 4976, -1, 4977, 4973, 4976, -1, + 4977, 4979, 4973, -1, 4979, 4971, 4973, -1, + 4971, 4979, 4983, -1, 4983, 4970, 4971, -1, + 4970, 4983, 4982, -1, 4982, 4969, 4970, -1, + 4969, 4982, 4989, -1, 4989, 4965, 4969, -1, + 4989, 4966, 4965, -1, 4990, 4966, 4989, -1, + 4966, 4990, 4991, -1, 4991, 4967, 4966, -1, + 4967, 4991, 4992, -1, 4992, 4961, 4967, -1, + 4992, 4946, 4961, -1, 4992, 4947, 4946, -1, + 4947, 4992, 4991, -1, 4991, 4993, 4947, -1, + 4993, 4991, 4990, -1, 4990, 4994, 4993, -1, + 4990, 4989, 4994, -1, 4995, 4994, 4989, -1, + 4995, 4989, 4982, -1, 4995, 4982, 4981, -1, + 4995, 4981, 4996, -1, 4996, 4994, 4995, -1, + 4994, 4996, 4997, -1, 4997, 4993, 4994, -1, + 4993, 4997, 4998, -1, 4998, 4947, 4993, -1, + 4998, 4948, 4947, -1, 4998, 4999, 4948, -1, + 4999, 4998, 4997, -1, 4997, 5000, 4999, -1, + 5000, 4997, 4996, -1, 4996, 5001, 5000, -1, + 5001, 4996, 4981, -1, 4981, 5002, 5001, -1, + 5002, 4981, 4980, -1, 5002, 4980, 2313, -1, + 5002, 2313, 2311, -1, 2311, 5001, 5002, -1, + 5001, 2311, 2309, -1, 2309, 5000, 5001, -1, + 5000, 2309, 2307, -1, 2307, 4999, 5000, -1, + 4999, 2307, 2304, -1, 2304, 4948, 4999, -1, + 4948, 2304, 2306, -1, 2306, 4949, 4948, -1, + 4949, 2306, 5003, -1, 5003, 4951, 4949, -1, + 4951, 5003, 5004, -1, 5004, 4953, 4951, -1, + 4953, 5004, 5005, -1, 5005, 4955, 4953, -1, + 4955, 5005, 2303, -1, 2303, 4957, 4955, -1, + 4957, 2303, 2302, -1, 2302, 4959, 4957, -1, + 4959, 2302, 2300, -1, 2300, 4945, 4959, -1, + 4945, 2300, 2298, -1, 2298, 4944, 4945, -1, + 4944, 2298, 2296, -1, 2296, 4943, 4944, -1, + 4943, 2296, 2294, -1, 2294, 4942, 4943, -1, + 4942, 2294, 2292, -1, 2292, 4941, 4942, -1, + 4941, 2292, 2290, -1, 2290, 4940, 4941, -1, + 4940, 2290, 2288, -1, 2288, 4939, 4940, -1, + 4939, 2288, 2286, -1, 2286, 4938, 4939, -1, + 4938, 2286, 2284, -1, 2284, 4937, 4938, -1, + 4937, 2284, 2282, -1, 2282, 4936, 4937, -1, + 4936, 2282, 2280, -1, 2280, 4935, 4936, -1, + 4935, 2280, 2278, -1, 2278, 4934, 4935, -1, + 4934, 2278, 2276, -1, 2276, 4933, 4934, -1, + 4933, 2276, 2274, -1, 2274, 4932, 4933, -1, + 4932, 2274, 2272, -1, 2272, 4931, 4932, -1, + 4931, 2272, 2270, -1, 2270, 4930, 4931, -1, + 4930, 2270, 2268, -1, 2268, 4929, 4930, -1, + 4929, 2268, 2266, -1, 2266, 4928, 4929, -1, + 4928, 2266, 2264, -1, 2264, 4927, 4928, -1, + 4927, 2264, 2262, -1, 2262, 4926, 4927, -1, + 4926, 2262, 2260, -1, 2260, 4925, 4926, -1, + 4925, 2260, 2258, -1, 2258, 4924, 4925, -1, + 4924, 2258, 2256, -1, 2256, 4923, 4924, -1, + 4923, 2256, 2254, -1, 2254, 4922, 4923, -1, + 4922, 2254, 2252, -1, 2252, 4921, 4922, -1, + 4921, 2252, 2250, -1, 2250, 4920, 4921, -1, + 4920, 2250, 2248, -1, 2248, 4919, 4920, -1, + 4919, 2248, 2246, -1, 2246, 4918, 4919, -1, + 4918, 2246, 2244, -1, 2244, 4917, 4918, -1, + 4917, 2244, 2242, -1, 2242, 4916, 4917, -1, + 4916, 2242, 2240, -1, 2240, 4915, 4916, -1, + 4915, 2240, 2238, -1, 2238, 4914, 4915, -1, + 4914, 2238, 2236, -1, 2236, 4913, 4914, -1, + 4913, 2236, 2234, -1, 2234, 4912, 4913, -1, + 4912, 2234, 2232, -1, 2232, 4911, 4912, -1, + 4911, 2232, 2230, -1, 2230, 4910, 4911, -1, + 4910, 2230, 2228, -1, 2228, 4909, 4910, -1, + 4909, 2228, 2226, -1, 2226, 4908, 4909, -1, + 4908, 2226, 2224, -1, 2224, 4907, 4908, -1, + 4907, 2224, 2222, -1, 2222, 4906, 4907, -1, + 4906, 2222, 2220, -1, 2220, 4905, 4906, -1, + 4905, 2220, 2218, -1, 2218, 4904, 4905, -1, + 4904, 2218, 2213, -1, 2213, 3812, 4904, -1, + 3812, 2213, 2211, -1, 2211, 3813, 3812, -1, + 3813, 2211, 1190, -1, 3813, 1190, 1189, -1, + 1189, 3810, 3813, -1, 1189, 1191, 3810, -1, + 1191, 3811, 3810, -1, 3811, 1191, 1190, -1, + 1190, 5006, 3702, -1, 5007, 5006, 5008, -1, + 5007, 3702, 5006, -1, 5007, 3703, 3702, -1, + 5007, 5008, 3703, -1, 5008, 3935, 3703, -1, + 3935, 5008, 5006, -1, 3935, 5006, 5009, -1, + 5009, 3661, 3935, -1, 5009, 3662, 3661, -1, + 3662, 5009, 5006, -1, 5006, 1609, 3662, -1, + 5010, 5011, 1609, -1, 5011, 3662, 1609, -1, + 5011, 3514, 3662, -1, 5011, 5010, 3514, -1, + 5010, 3515, 3514, -1, 3515, 5010, 1609, -1, + 3515, 1609, 1608, -1, 1608, 3513, 3515, -1, + 1608, 1605, 3513, -1, 3513, 1605, 1604, -1, + 1604, 3517, 3513, -1, 3517, 1604, 5012, -1, + 5012, 3519, 3517, -1, 3519, 5012, 5013, -1, + 5013, 3521, 3519, -1, 3521, 5013, 5014, -1, + 5014, 3523, 3521, -1, 3523, 5014, 5015, -1, + 5015, 3525, 3523, -1, 3525, 5015, 5016, -1, + 5016, 3527, 3525, -1, 3527, 5016, 5017, -1, + 5017, 3529, 3527, -1, 3529, 5017, 5018, -1, + 5018, 3531, 3529, -1, 3531, 5018, 5019, -1, + 5019, 3533, 3531, -1, 3533, 5019, 5020, -1, + 5020, 3535, 3533, -1, 3535, 5020, 5021, -1, + 5021, 3537, 3535, -1, 3537, 5021, 5022, -1, + 5022, 3539, 3537, -1, 3539, 5022, 5023, -1, + 5023, 3541, 3539, -1, 3541, 5023, 5024, -1, + 5024, 3543, 3541, -1, 3543, 5024, 5025, -1, + 5025, 3545, 3543, -1, 3545, 5025, 5026, -1, + 5026, 3547, 3545, -1, 3547, 5026, 5027, -1, + 5027, 3549, 3547, -1, 3549, 5027, 5028, -1, + 5028, 3551, 3549, -1, 3551, 5028, 5029, -1, + 5029, 3553, 3551, -1, 3553, 5029, 5030, -1, + 5030, 3555, 3553, -1, 3555, 5030, 5031, -1, + 5031, 3557, 3555, -1, 3557, 5031, 5032, -1, + 5032, 3559, 3557, -1, 3559, 5032, 5033, -1, + 5033, 3561, 3559, -1, 3561, 5033, 5034, -1, + 5034, 3563, 3561, -1, 3563, 5034, 5035, -1, + 5035, 3565, 3563, -1, 3565, 5035, 5036, -1, + 5036, 3567, 3565, -1, 3567, 5036, 5037, -1, + 5037, 3569, 3567, -1, 3569, 5037, 5038, -1, + 5038, 3571, 3569, -1, 3571, 5038, 5039, -1, + 5039, 3573, 3571, -1, 3573, 5039, 5040, -1, + 5040, 3575, 3573, -1, 3575, 5040, 5041, -1, + 5041, 3577, 3575, -1, 3577, 5041, 5042, -1, + 5042, 3579, 3577, -1, 3579, 5042, 5043, -1, + 5043, 3581, 3579, -1, 3581, 5043, 5044, -1, + 5044, 3583, 3581, -1, 3583, 5044, 5045, -1, + 5045, 3585, 3583, -1, 3585, 5045, 5046, -1, + 5046, 3587, 3585, -1, 3587, 5046, 5047, -1, + 5047, 3589, 3587, -1, 3589, 5047, 5048, -1, + 5048, 3591, 3589, -1, 3591, 5048, 5049, -1, + 5049, 3593, 3591, -1, 3593, 5049, 5050, -1, + 5050, 3595, 3593, -1, 3595, 5050, 5051, -1, + 5051, 3597, 3595, -1, 3597, 5051, 5052, -1, + 5052, 3599, 3597, -1, 3599, 5052, 5053, -1, + 5053, 3601, 3599, -1, 3601, 5053, 5054, -1, + 5054, 3603, 3601, -1, 3603, 5054, 5055, -1, + 5055, 3605, 3603, -1, 3605, 5055, 5056, -1, + 5056, 3607, 3605, -1, 3607, 5056, 5057, -1, + 5057, 3609, 3607, -1, 3609, 5057, 5058, -1, + 5058, 3512, 3609, -1, 3512, 5058, 5059, -1, + 5059, 3510, 3512, -1, 3510, 5059, 5060, -1, + 5060, 5061, 3510, -1, 5061, 5062, 5063, -1, + 5061, 5060, 5062, -1, 5064, 5065, 5066, -1, + 5066, 5067, 5064, -1, 5068, 5069, 5070, -1, + 5070, 5071, 5068, -1, 5071, 5070, 5072, -1, + 5072, 5073, 5071, -1, 5073, 5072, 5074, -1, + 5074, 5075, 5073, -1, 5075, 5074, 5076, -1, + 5076, 5077, 5075, -1, 5077, 5076, 5078, -1, + 5078, 5079, 5077, -1, 5079, 5078, 5080, -1, + 5080, 5081, 5079, -1, 5081, 5080, 5082, -1, + 5082, 5083, 5081, -1, 5083, 5082, 5084, -1, + 5084, 5085, 5083, -1, 5085, 5084, 5086, -1, + 5086, 5087, 5085, -1, 5087, 5086, 5088, -1, + 5088, 5089, 5087, -1, 5089, 5088, 5090, -1, + 5090, 5091, 5089, -1, 5091, 5090, 5092, -1, + 5092, 5093, 5091, -1, 5093, 5092, 5094, -1, + 5094, 5095, 5093, -1, 5095, 5094, 5096, -1, + 5096, 5097, 5095, -1, 5097, 5096, 5098, -1, + 5098, 5099, 5097, -1, 5099, 5098, 5100, -1, + 5100, 5101, 5099, -1, 5101, 5100, 5102, -1, + 5102, 5103, 5101, -1, 5103, 5102, 5104, -1, + 5104, 5105, 5103, -1, 5105, 5104, 5106, -1, + 5106, 5107, 5105, -1, 5107, 5106, 5108, -1, + 5108, 5109, 5107, -1, 5109, 5108, 5110, -1, + 5110, 5111, 5109, -1, 5111, 5110, 5112, -1, + 5112, 5113, 5111, -1, 5113, 5112, 5114, -1, + 5114, 5115, 5113, -1, 5115, 5114, 5116, -1, + 5116, 5117, 5115, -1, 5117, 5116, 5118, -1, + 5118, 5119, 5117, -1, 5119, 5118, 5120, -1, + 5120, 5121, 5119, -1, 5121, 5120, 5122, -1, + 5122, 5123, 5121, -1, 5123, 5122, 5124, -1, + 5124, 5125, 5123, -1, 5125, 5124, 5126, -1, + 5126, 5127, 5125, -1, 5127, 5126, 5128, -1, + 5128, 5129, 5127, -1, 5129, 5128, 5130, -1, + 5130, 5131, 5129, -1, 5131, 5130, 5132, -1, + 5132, 5133, 5131, -1, 5133, 5132, 5134, -1, + 5134, 5135, 5133, -1, 5135, 5134, 5136, -1, + 5136, 5137, 5135, -1, 5137, 5136, 5138, -1, + 5138, 5139, 5137, -1, 5139, 5138, 5140, -1, + 5140, 5141, 5139, -1, 5141, 5140, 5142, -1, + 5142, 5143, 5141, -1, 5143, 5142, 5144, -1, + 5144, 5145, 5143, -1, 5145, 5144, 5146, -1, + 5146, 5147, 5145, -1, 5147, 5146, 5148, -1, + 5148, 5149, 5147, -1, 5149, 5148, 5150, -1, + 5150, 5151, 5149, -1, 5151, 5150, 5152, -1, + 5152, 5153, 5151, -1, 5153, 5152, 5154, -1, + 5154, 5155, 5153, -1, 5155, 5154, 5156, -1, + 5156, 5157, 5155, -1, 5157, 5156, 5158, -1, + 5158, 5159, 5157, -1, 5159, 5158, 5160, -1, + 5160, 5161, 5159, -1, 5161, 5160, 5162, -1, + 5162, 5163, 5161, -1, 5163, 5162, 5164, -1, + 5164, 5165, 5163, -1, 5165, 5164, 5166, -1, + 5166, 5167, 5165, -1, 5167, 5166, 5168, -1, + 5168, 5169, 5167, -1, 5169, 5168, 5170, -1, + 5170, 5171, 5169, -1, 5171, 5170, 5172, -1, + 5172, 5173, 5171, -1, 5173, 5172, 5174, -1, + 5174, 5175, 5173, -1, 5175, 5174, 5176, -1, + 5176, 5177, 5175, -1, 5177, 5176, 5067, -1, + 5067, 5066, 5177, -1, 5178, 5066, 5179, -1, + 5178, 5177, 5066, -1, 5177, 5178, 5180, -1, + 5180, 5175, 5177, -1, 5175, 5180, 5181, -1, + 5181, 5173, 5175, -1, 5173, 5181, 5182, -1, + 5182, 5171, 5173, -1, 5171, 5182, 5183, -1, + 5183, 5169, 5171, -1, 5169, 5183, 5062, -1, + 5062, 5167, 5169, -1, 5167, 5062, 5060, -1, + 5060, 5165, 5167, -1, 5165, 5060, 5059, -1, + 5059, 5163, 5165, -1, 5163, 5059, 5058, -1, + 5058, 5161, 5163, -1, 5161, 5058, 5057, -1, + 5057, 5159, 5161, -1, 5159, 5057, 5056, -1, + 5056, 5157, 5159, -1, 5157, 5056, 5055, -1, + 5055, 5155, 5157, -1, 5155, 5055, 5054, -1, + 5054, 5153, 5155, -1, 5153, 5054, 5053, -1, + 5053, 5151, 5153, -1, 5151, 5053, 5052, -1, + 5052, 5149, 5151, -1, 5149, 5052, 5051, -1, + 5051, 5147, 5149, -1, 5147, 5051, 5050, -1, + 5050, 5145, 5147, -1, 5145, 5050, 5049, -1, + 5049, 5143, 5145, -1, 5143, 5049, 5048, -1, + 5048, 5141, 5143, -1, 5141, 5048, 5047, -1, + 5047, 5139, 5141, -1, 5139, 5047, 5046, -1, + 5046, 5137, 5139, -1, 5137, 5046, 5045, -1, + 5045, 5135, 5137, -1, 5135, 5045, 5044, -1, + 5044, 5133, 5135, -1, 5133, 5044, 5043, -1, + 5043, 5131, 5133, -1, 5131, 5043, 5042, -1, + 5042, 5129, 5131, -1, 5129, 5042, 5041, -1, + 5041, 5127, 5129, -1, 5127, 5041, 5040, -1, + 5040, 5125, 5127, -1, 5125, 5040, 5039, -1, + 5039, 5123, 5125, -1, 5123, 5039, 5038, -1, + 5038, 5121, 5123, -1, 5121, 5038, 5037, -1, + 5037, 5119, 5121, -1, 5119, 5037, 5036, -1, + 5036, 5117, 5119, -1, 5117, 5036, 5035, -1, + 5035, 5115, 5117, -1, 5115, 5035, 5034, -1, + 5034, 5113, 5115, -1, 5113, 5034, 5033, -1, + 5033, 5111, 5113, -1, 5111, 5033, 5032, -1, + 5032, 5109, 5111, -1, 5109, 5032, 5031, -1, + 5031, 5107, 5109, -1, 5107, 5031, 5030, -1, + 5030, 5105, 5107, -1, 5105, 5030, 5029, -1, + 5029, 5103, 5105, -1, 5103, 5029, 5028, -1, + 5028, 5101, 5103, -1, 5101, 5028, 5027, -1, + 5027, 5099, 5101, -1, 5099, 5027, 5026, -1, + 5026, 5097, 5099, -1, 5097, 5026, 5025, -1, + 5025, 5095, 5097, -1, 5095, 5025, 5024, -1, + 5024, 5093, 5095, -1, 5093, 5024, 5023, -1, + 5023, 5091, 5093, -1, 5091, 5023, 5022, -1, + 5022, 5089, 5091, -1, 5089, 5022, 5021, -1, + 5021, 5087, 5089, -1, 5087, 5021, 5020, -1, + 5020, 5085, 5087, -1, 5085, 5020, 5019, -1, + 5019, 5083, 5085, -1, 5083, 5019, 5018, -1, + 5018, 5081, 5083, -1, 5081, 5018, 5017, -1, + 5017, 5079, 5081, -1, 5079, 5017, 5016, -1, + 5016, 5077, 5079, -1, 5077, 5016, 5015, -1, + 5015, 5075, 5077, -1, 5075, 5015, 5014, -1, + 5014, 5073, 5075, -1, 5073, 5014, 5013, -1, + 5013, 5071, 5073, -1, 5071, 5013, 5012, -1, + 5012, 5068, 5071, -1, 5068, 5012, 1604, -1, + 1604, 1606, 5068, -1, 5184, 5068, 1606, -1, + 5184, 1606, 1607, -1, 5184, 1607, 5185, -1, + 5185, 5068, 5184, -1, 5185, 5069, 5068, -1, + 5185, 1607, 5069, -1, 5069, 1607, 2205, -1, + 2205, 5070, 5069, -1, 2205, 2206, 5070, -1, + 5070, 2206, 2202, -1, 2202, 5072, 5070, -1, + 5072, 2202, 2200, -1, 2200, 5074, 5072, -1, + 5074, 2200, 2198, -1, 2198, 5076, 5074, -1, + 5076, 2198, 2196, -1, 2196, 5078, 5076, -1, + 5078, 2196, 2194, -1, 2194, 5080, 5078, -1, + 5080, 2194, 2192, -1, 2192, 5082, 5080, -1, + 5082, 2192, 2190, -1, 2190, 5084, 5082, -1, + 5084, 2190, 2188, -1, 2188, 5086, 5084, -1, + 5086, 2188, 2186, -1, 2186, 5088, 5086, -1, + 5088, 2186, 2184, -1, 2184, 5090, 5088, -1, + 5090, 2184, 2182, -1, 2182, 5092, 5090, -1, + 5092, 2182, 2180, -1, 2180, 5094, 5092, -1, + 5094, 2180, 2178, -1, 2178, 5096, 5094, -1, + 5096, 2178, 2176, -1, 2176, 5098, 5096, -1, + 5098, 2176, 2174, -1, 2174, 5100, 5098, -1, + 5100, 2174, 2172, -1, 2172, 5102, 5100, -1, + 5102, 2172, 2170, -1, 2170, 5104, 5102, -1, + 5104, 2170, 2168, -1, 2168, 5106, 5104, -1, + 5106, 2168, 2166, -1, 2166, 5108, 5106, -1, + 5108, 2166, 2164, -1, 2164, 5110, 5108, -1, + 5110, 2164, 2162, -1, 2162, 5112, 5110, -1, + 5112, 2162, 2160, -1, 2160, 5114, 5112, -1, + 5114, 2160, 2158, -1, 2158, 5116, 5114, -1, + 5116, 2158, 2156, -1, 2156, 5118, 5116, -1, + 5118, 2156, 2154, -1, 2154, 5120, 5118, -1, + 5120, 2154, 2152, -1, 2152, 5122, 5120, -1, + 5122, 2152, 2150, -1, 2150, 5124, 5122, -1, + 5124, 2150, 2148, -1, 2148, 5126, 5124, -1, + 5126, 2148, 2146, -1, 2146, 5128, 5126, -1, + 5128, 2146, 2144, -1, 2144, 5130, 5128, -1, + 5130, 2144, 2142, -1, 2142, 5132, 5130, -1, + 5132, 2142, 2140, -1, 2140, 5134, 5132, -1, + 5134, 2140, 2138, -1, 2138, 5136, 5134, -1, + 5136, 2138, 2136, -1, 2136, 5138, 5136, -1, + 5138, 2136, 2134, -1, 2134, 5140, 5138, -1, + 5140, 2134, 2132, -1, 2132, 5142, 5140, -1, + 5142, 2132, 2130, -1, 2130, 5144, 5142, -1, + 5144, 2130, 2128, -1, 2128, 5146, 5144, -1, + 5146, 2128, 2126, -1, 2126, 5148, 5146, -1, + 5148, 2126, 2124, -1, 2124, 5150, 5148, -1, + 5150, 2124, 2122, -1, 2122, 5152, 5150, -1, + 5152, 2122, 2120, -1, 2120, 5154, 5152, -1, + 5154, 2120, 2118, -1, 2118, 5156, 5154, -1, + 5156, 2118, 2116, -1, 2116, 5158, 5156, -1, + 5158, 2116, 2114, -1, 2114, 5160, 5158, -1, + 5160, 2114, 2112, -1, 2112, 5162, 5160, -1, + 5162, 2112, 2110, -1, 2110, 5164, 5162, -1, + 5164, 2110, 2108, -1, 2108, 5166, 5164, -1, + 5166, 2108, 2106, -1, 2106, 5168, 5166, -1, + 5168, 2106, 2104, -1, 2104, 5170, 5168, -1, + 5170, 2104, 2102, -1, 2102, 5172, 5170, -1, + 5172, 2102, 2100, -1, 2100, 5174, 5172, -1, + 5174, 2100, 2098, -1, 2098, 5176, 5174, -1, + 5176, 2098, 2096, -1, 2096, 5067, 5176, -1, + 5067, 2096, 1876, -1, 1876, 5064, 5067, -1, + 1876, 1875, 5064, -1, 5186, 5187, 5064, -1, + 5186, 5064, 1875, -1, 1875, 1874, 5186, -1, + 5186, 5188, 5189, -1, 5188, 5186, 1874, -1, + 1874, 5190, 5188, -1, 5190, 1874, 1872, -1, + 1872, 5191, 5190, -1, 5191, 1872, 1870, -1, + 1870, 5192, 5191, -1, 5192, 1870, 1868, -1, + 1868, 5193, 5192, -1, 5193, 1868, 1866, -1, + 1866, 5194, 5193, -1, 5194, 1866, 1864, -1, + 1864, 5195, 5194, -1, 5195, 1864, 1862, -1, + 1862, 5196, 5195, -1, 5196, 1862, 1860, -1, + 1860, 5197, 5196, -1, 5197, 1860, 1858, -1, + 1858, 5198, 5197, -1, 5198, 1858, 1856, -1, + 1856, 5199, 5198, -1, 5199, 1856, 1854, -1, + 1854, 5200, 5199, -1, 5200, 1854, 1852, -1, + 1852, 5201, 5200, -1, 5201, 1852, 1850, -1, + 1850, 5202, 5201, -1, 5202, 1850, 1848, -1, + 1848, 5203, 5202, -1, 5203, 1848, 1846, -1, + 1846, 5204, 5203, -1, 5204, 1846, 1844, -1, + 1844, 5205, 5204, -1, 5205, 1844, 1842, -1, + 1842, 5206, 5205, -1, 5206, 1842, 1840, -1, + 1840, 5207, 5206, -1, 5207, 1840, 1838, -1, + 1838, 5208, 5207, -1, 5208, 1838, 1836, -1, + 1836, 5209, 5208, -1, 5209, 1836, 1834, -1, + 1834, 5210, 5209, -1, 5210, 1834, 1832, -1, + 1832, 5211, 5210, -1, 5211, 1832, 1830, -1, + 1830, 5212, 5211, -1, 5212, 1830, 1828, -1, + 1828, 5213, 5212, -1, 5213, 1828, 1826, -1, + 1826, 5214, 5213, -1, 5214, 1826, 1824, -1, + 1824, 5215, 5214, -1, 5215, 1824, 1822, -1, + 1822, 5216, 5215, -1, 5216, 1822, 1820, -1, + 1820, 5217, 5216, -1, 5217, 1820, 1818, -1, + 1818, 5218, 5217, -1, 5218, 1818, 1816, -1, + 1816, 5219, 5218, -1, 5219, 1816, 1814, -1, + 1814, 5220, 5219, -1, 5220, 1814, 1812, -1, + 1812, 5221, 5220, -1, 5221, 1812, 1810, -1, + 1810, 5222, 5221, -1, 5222, 1810, 1808, -1, + 1808, 5223, 5222, -1, 5223, 1808, 1806, -1, + 1806, 5224, 5223, -1, 5224, 1806, 1804, -1, + 1804, 5225, 5224, -1, 5225, 1804, 1802, -1, + 1802, 5226, 5225, -1, 5226, 1802, 1800, -1, + 1800, 5227, 5226, -1, 5227, 1800, 1798, -1, + 1798, 5228, 5227, -1, 5228, 1798, 1796, -1, + 1796, 5229, 5228, -1, 5229, 1796, 1794, -1, + 1794, 5230, 5229, -1, 5230, 1794, 1792, -1, + 1792, 5231, 5230, -1, 5231, 1792, 1790, -1, + 1790, 5232, 5231, -1, 5232, 1790, 1788, -1, + 1788, 5233, 5232, -1, 5233, 1788, 1786, -1, + 1786, 5234, 5233, -1, 5234, 1786, 1784, -1, + 1784, 5235, 5234, -1, 5235, 1784, 1782, -1, + 1782, 5236, 5235, -1, 5236, 1782, 1780, -1, + 1780, 5237, 5236, -1, 5237, 1780, 1778, -1, + 1778, 5238, 5237, -1, 5238, 1778, 1776, -1, + 1776, 5239, 5238, -1, 5239, 1776, 1774, -1, + 1774, 5240, 5239, -1, 5240, 1774, 1772, -1, + 1772, 5241, 5240, -1, 5241, 1772, 1770, -1, + 1770, 5242, 5241, -1, 5242, 1770, 1768, -1, + 1768, 5243, 5242, -1, 5243, 1768, 1186, -1, + 1186, 1188, 5243, -1, 1188, 1137, 5244, -1, + 5244, 5243, 1188, -1, 5243, 5244, 5245, -1, + 5245, 5242, 5243, -1, 5242, 5245, 5246, -1, + 5246, 5241, 5242, -1, 5241, 5246, 5247, -1, + 5247, 5240, 5241, -1, 5240, 5247, 5248, -1, + 5248, 5239, 5240, -1, 5239, 5248, 5249, -1, + 5249, 5238, 5239, -1, 5238, 5249, 5250, -1, + 5250, 5237, 5238, -1, 5237, 5250, 5251, -1, + 5251, 5236, 5237, -1, 5236, 5251, 5252, -1, + 5252, 5235, 5236, -1, 5235, 5252, 5253, -1, + 5253, 5234, 5235, -1, 5234, 5253, 5254, -1, + 5254, 5233, 5234, -1, 5233, 5254, 5255, -1, + 5255, 5232, 5233, -1, 5232, 5255, 5256, -1, + 5256, 5231, 5232, -1, 5231, 5256, 5257, -1, + 5257, 5230, 5231, -1, 5230, 5257, 5258, -1, + 5258, 5229, 5230, -1, 5229, 5258, 5259, -1, + 5259, 5228, 5229, -1, 5228, 5259, 5260, -1, + 5260, 5227, 5228, -1, 5227, 5260, 5261, -1, + 5261, 5226, 5227, -1, 5226, 5261, 5262, -1, + 5262, 5225, 5226, -1, 5225, 5262, 5263, -1, + 5263, 5224, 5225, -1, 5224, 5263, 5264, -1, + 5264, 5223, 5224, -1, 5223, 5264, 5265, -1, + 5265, 5222, 5223, -1, 5222, 5265, 5266, -1, + 5266, 5221, 5222, -1, 5221, 5266, 5267, -1, + 5267, 5220, 5221, -1, 5220, 5267, 5268, -1, + 5268, 5219, 5220, -1, 5219, 5268, 5269, -1, + 5269, 5218, 5219, -1, 5218, 5269, 5270, -1, + 5270, 5217, 5218, -1, 5217, 5270, 5271, -1, + 5271, 5216, 5217, -1, 5216, 5271, 5272, -1, + 5272, 5215, 5216, -1, 5215, 5272, 5273, -1, + 5273, 5214, 5215, -1, 5214, 5273, 5274, -1, + 5274, 5213, 5214, -1, 5213, 5274, 5275, -1, + 5275, 5212, 5213, -1, 5212, 5275, 5276, -1, + 5276, 5211, 5212, -1, 5211, 5276, 5277, -1, + 5277, 5210, 5211, -1, 5210, 5277, 5278, -1, + 5278, 5209, 5210, -1, 5209, 5278, 5279, -1, + 5279, 5208, 5209, -1, 5208, 5279, 5280, -1, + 5280, 5207, 5208, -1, 5207, 5280, 5281, -1, + 5281, 5206, 5207, -1, 5206, 5281, 5282, -1, + 5282, 5205, 5206, -1, 5205, 5282, 5283, -1, + 5283, 5204, 5205, -1, 5204, 5283, 5284, -1, + 5284, 5203, 5204, -1, 5203, 5284, 5285, -1, + 5285, 5202, 5203, -1, 5202, 5285, 5286, -1, + 5286, 5201, 5202, -1, 5201, 5286, 5287, -1, + 5287, 5200, 5201, -1, 5200, 5287, 5288, -1, + 5288, 5199, 5200, -1, 5199, 5288, 5289, -1, + 5289, 5198, 5199, -1, 5198, 5289, 5290, -1, + 5290, 5197, 5198, -1, 5197, 5290, 5291, -1, + 5291, 5196, 5197, -1, 5196, 5291, 5292, -1, + 5292, 5195, 5196, -1, 5195, 5292, 1185, -1, + 1185, 5194, 5195, -1, 5194, 1185, 1169, -1, + 1169, 5193, 5194, -1, 5193, 1169, 1172, -1, + 1172, 5192, 5193, -1, 5192, 1172, 1174, -1, + 1174, 5191, 5192, -1, 5191, 1174, 1176, -1, + 1176, 5190, 5191, -1, 5190, 1176, 1178, -1, + 1178, 5188, 5190, -1, 1178, 1181, 5188, -1, + 5293, 5188, 1181, -1, 1181, 1182, 5293, -1, + 5294, 5295, 5296, -1, 5296, 5295, 5297, -1, + 5298, 5299, 5300, -1, 5301, 5302, 5303, -1, + 5303, 5304, 5301, -1, 5304, 5303, 5305, -1, + 5305, 5306, 5304, -1, 5307, 5308, 5309, -1, + 5308, 5307, 5310, -1, 5308, 5310, 5311, -1, + 5306, 5311, 5310, -1, 5306, 5305, 5311, -1, + 5312, 5313, 5314, -1, 5315, 5316, 5317, -1, + 5317, 5318, 5315, -1, 5318, 5317, 5313, -1, + 5313, 5312, 5318, -1, 5311, 5318, 5312, -1, + 5318, 5311, 5305, -1, 5305, 5315, 5318, -1, + 5315, 5305, 5303, -1, 5303, 5319, 5315, -1, + 5319, 5303, 5320, -1, 5320, 5321, 5319, -1, + 5320, 5322, 5321, -1, 5322, 5320, 5303, -1, + 5322, 5303, 5302, -1, 5302, 5321, 5322, -1, + 5302, 5323, 5321, -1, 5323, 5302, 5301, -1, + 5323, 5301, 5298, -1, 5298, 5300, 5323, -1, + 5300, 5321, 5323, -1, 5324, 5325, 5296, -1, + 5324, 5296, 5326, -1, 5326, 5327, 5324, -1, + 5326, 5328, 5327, -1, 5326, 5300, 5328, -1, + 5300, 5326, 5296, -1, 1182, 5297, 5329, -1, + 5329, 5293, 1182, -1, 5329, 5188, 5293, -1, + 5329, 5189, 5188, -1, 5189, 5329, 5297, -1, + 5330, 5189, 5297, -1, 5330, 5186, 5189, -1, + 5330, 5187, 5186, -1, 5187, 5330, 5297, -1, + 5187, 5297, 5331, -1, 5331, 5064, 5187, -1, + 5331, 5065, 5064, -1, 5065, 5331, 5297, -1, + 5065, 5297, 5295, -1, 5295, 5066, 5065, -1, + 5295, 5294, 5066, -1, 5294, 5179, 5066, -1, + 5179, 5294, 5296, -1, 5179, 5296, 5325, -1, + 5325, 5178, 5179, -1, 5325, 5324, 5178, -1, + 5178, 5324, 5327, -1, 5327, 5180, 5178, -1, + 5180, 5327, 5332, -1, 5332, 5181, 5180, -1, + 5181, 5332, 5333, -1, 5333, 5182, 5181, -1, + 5182, 5333, 5334, -1, 5334, 5183, 5182, -1, + 5183, 5334, 5335, -1, 5335, 5062, 5183, -1, + 5335, 5063, 5062, -1, 5335, 5336, 5063, -1, + 5336, 5335, 5334, -1, 5334, 5337, 5336, -1, + 5337, 5334, 5333, -1, 5333, 5338, 5337, -1, + 5338, 5333, 5332, -1, 5332, 5339, 5338, -1, + 5339, 5332, 5327, -1, 5327, 5328, 5339, -1, + 5340, 5339, 5328, -1, 5340, 5328, 5300, -1, + 5340, 5300, 5299, -1, 5299, 5339, 5340, -1, + 5299, 5298, 5339, -1, 5339, 5298, 5301, -1, + 5301, 5338, 5339, -1, 5338, 5301, 5304, -1, + 5304, 5337, 5338, -1, 5337, 5304, 5306, -1, + 5306, 5336, 5337, -1, 5336, 5306, 5310, -1, + 5310, 5063, 5336, -1, 5063, 5310, 5307, -1, + 5307, 5061, 5063, -1, 5307, 5309, 5061, -1, + 5341, 5061, 5309, -1, 5341, 3510, 5061, -1, + 5341, 3511, 3510, -1, 5341, 5342, 3511, -1, + 5342, 5341, 5309, -1, 5309, 5343, 5342, -1, + 5343, 5309, 5308, -1, 5308, 5311, 5343, -1, + 5311, 5312, 5343, -1, 5344, 5343, 5312, -1, + 5344, 5342, 5343, -1, 5342, 5344, 5345, -1, + 5345, 3511, 5342, -1, 3511, 5345, 5346, -1, + 5346, 3509, 3511, -1, 5346, 3612, 3509, -1, + 5346, 5347, 3612, -1, 5347, 5346, 5345, -1, + 5345, 5348, 5347, -1, 5348, 5345, 5344, -1, + 5344, 5312, 5348, -1, 5312, 5314, 5348, -1, + 5349, 5348, 5314, -1, 5349, 5347, 5348, -1, + 5347, 5349, 5350, -1, 5350, 3612, 5347, -1, + 3612, 5350, 5351, -1, 5351, 3611, 3612, -1, + 5351, 3936, 3611, -1, 5351, 3939, 3936, -1, + 3939, 5351, 5350, -1, 5350, 3938, 3939, -1, + 3938, 5350, 5349, -1, 5349, 5314, 3938, -1, + 5314, 3507, 3938, -1, 5314, 3505, 3507, -1, + 3505, 5314, 5313, -1, 5313, 3503, 3505, -1, + 3503, 5313, 5317, -1, 5317, 3502, 3503, -1, + 3502, 5317, 5352, -1, 5352, 3500, 3502, -1, + 5352, 5353, 3500, -1, 5353, 5352, 5317, -1, + 5353, 5317, 5316, -1, 5316, 3500, 5353, -1, + 5316, 5354, 3500, -1, 5354, 5316, 5315, -1, + 5354, 5315, 5319, -1, 5354, 5319, 5321, -1, + 5321, 3500, 5354, -1, 1143, 3471, 3473, -1, + 3471, 1143, 1142, -1, 1142, 1144, 3471, -1, + 1144, 3472, 3471, -1, 1144, 3495, 3472, -1, + 3495, 1144, 1145, -1, 1145, 3494, 3495, -1, + 3494, 1145, 1149, -1, 3494, 1149, 5355, -1, + 5355, 3492, 3494, -1, 3492, 5355, 5356, -1, + 5356, 3476, 3492, -1, 5356, 3477, 3476, -1, + 5356, 5357, 3477, -1, 5357, 5356, 5355, -1, + 5355, 5358, 5357, -1, 5358, 5355, 1149, -1, + 1149, 5359, 5358, -1, 5359, 1149, 1150, -1, + 5360, 5359, 1150, -1, 5360, 1150, 1152, -1, + 5360, 1152, 5361, -1, 5361, 5359, 5360, -1, + 5361, 5362, 5359, -1, 5361, 1152, 5362, -1, + 1152, 1140, 5362, -1, 5363, 5364, 5365, -1, + 5366, 5367, 5368, -1, 5367, 5366, 5369, -1, + 5366, 5370, 5369, -1, 5366, 5368, 5370, -1, + 5368, 5371, 5370, -1, 5371, 5368, 5372, -1, + 5372, 5373, 5371, -1, 5373, 5372, 5363, -1, + 5363, 5365, 5373, -1, 5365, 5374, 5375, -1, + 5365, 5375, 5376, -1, 5376, 5373, 5365, -1, + 5373, 5376, 5377, -1, 5377, 5371, 5373, -1, + 5371, 5377, 5378, -1, 5378, 5379, 5371, -1, + 5379, 5378, 5380, -1, 5379, 5380, 5381, -1, + 5381, 5371, 5379, -1, 5381, 5370, 5371, -1, + 5370, 5381, 5380, -1, 5380, 5369, 5370, -1, + 5382, 5383, 5369, -1, 5382, 1182, 1183, -1, + 1183, 1184, 5382, -1, 1184, 5384, 5382, -1, + 5384, 1184, 1155, -1, 5384, 1155, 1154, -1, + 1154, 5382, 5384, -1, 1154, 1153, 5382, -1, + 1153, 5383, 5382, -1, 5383, 1153, 1156, -1, + 5383, 1156, 1158, -1, 1158, 5369, 5383, -1, + 1158, 5385, 5369, -1, 5385, 1158, 1157, -1, + 5385, 1157, 5386, -1, 5386, 5369, 5385, -1, + 5386, 5367, 5369, -1, 5367, 5386, 1157, -1, + 1157, 5368, 5367, -1, 5368, 1157, 1160, -1, + 1160, 5372, 5368, -1, 5372, 1160, 1162, -1, + 1162, 5363, 5372, -1, 1162, 5387, 5363, -1, + 5388, 5389, 5390, -1, 5388, 5390, 5391, -1, + 5388, 5391, 5392, -1, 5388, 5392, 5393, -1, + 5393, 5389, 5388, -1, 5389, 5393, 5387, -1, + 5387, 5394, 5389, -1, 5394, 5387, 1162, -1, + 5394, 1162, 1163, -1, 5394, 1163, 1165, -1, + 1165, 5389, 5394, -1, 1165, 5390, 5389, -1, + 1165, 1164, 5390, -1, 5390, 1164, 1185, -1, + 5390, 1185, 5292, -1, 5292, 5391, 5390, -1, + 5391, 5292, 5291, -1, 5291, 5395, 5391, -1, + 5395, 5291, 5290, -1, 5290, 5396, 5395, -1, + 5396, 5290, 5289, -1, 5289, 5397, 5396, -1, + 5397, 5289, 5288, -1, 5288, 5398, 5397, -1, + 5398, 5288, 5287, -1, 5287, 5399, 5398, -1, + 5399, 5287, 5286, -1, 5286, 5400, 5399, -1, + 5400, 5286, 5285, -1, 5285, 5401, 5400, -1, + 5401, 5285, 5284, -1, 5284, 5402, 5401, -1, + 5402, 5284, 5283, -1, 5283, 5403, 5402, -1, + 5403, 5283, 5282, -1, 5282, 5404, 5403, -1, + 5404, 5282, 5281, -1, 5281, 5405, 5404, -1, + 5405, 5281, 5280, -1, 5280, 5406, 5405, -1, + 5406, 5280, 5279, -1, 5279, 5407, 5406, -1, + 5407, 5279, 5278, -1, 5278, 5408, 5407, -1, + 5408, 5278, 5277, -1, 5277, 5409, 5408, -1, + 5409, 5277, 5276, -1, 5276, 5410, 5409, -1, + 5410, 5276, 5275, -1, 5275, 5411, 5410, -1, + 5411, 5275, 5274, -1, 5274, 5412, 5411, -1, + 5412, 5274, 5273, -1, 5273, 5413, 5412, -1, + 5413, 5273, 5272, -1, 5272, 5414, 5413, -1, + 5414, 5272, 5271, -1, 5271, 5415, 5414, -1, + 5415, 5271, 5270, -1, 5270, 5416, 5415, -1, + 5416, 5270, 5269, -1, 5269, 5417, 5416, -1, + 5417, 5269, 5268, -1, 5268, 5418, 5417, -1, + 5418, 5268, 5267, -1, 5267, 5419, 5418, -1, + 5419, 5267, 5266, -1, 5266, 5420, 5419, -1, + 5420, 5266, 5265, -1, 5265, 5421, 5420, -1, + 5421, 5265, 5264, -1, 5264, 5422, 5421, -1, + 5422, 5264, 5263, -1, 5263, 5423, 5422, -1, + 5423, 5263, 5262, -1, 5262, 5424, 5423, -1, + 5424, 5262, 5261, -1, 5261, 5425, 5424, -1, + 5425, 5261, 5260, -1, 5260, 5426, 5425, -1, + 5426, 5260, 5259, -1, 5259, 5427, 5426, -1, + 5427, 5259, 5258, -1, 5258, 5428, 5427, -1, + 5428, 5258, 5257, -1, 5257, 5429, 5428, -1, + 5429, 5257, 5256, -1, 5256, 5430, 5429, -1, + 5430, 5256, 5255, -1, 5255, 5431, 5430, -1, + 5431, 5255, 5254, -1, 5254, 5432, 5431, -1, + 5432, 5254, 5253, -1, 5253, 5433, 5432, -1, + 5433, 5253, 5252, -1, 5252, 5434, 5433, -1, + 5434, 5252, 5251, -1, 5251, 5435, 5434, -1, + 5435, 5251, 5250, -1, 5250, 5436, 5435, -1, + 5436, 5250, 5249, -1, 5249, 5437, 5436, -1, + 5437, 5249, 5248, -1, 5248, 5438, 5437, -1, + 5438, 5248, 5247, -1, 5247, 5439, 5438, -1, + 5439, 5247, 5246, -1, 5246, 5440, 5439, -1, + 5440, 5246, 5245, -1, 5245, 5441, 5440, -1, + 5441, 5245, 5244, -1, 5244, 5442, 5441, -1, + 5442, 5244, 1137, -1, 1137, 5443, 5442, -1, + 1137, 1135, 5443, -1, 5444, 5443, 1135, -1, + 1135, 1133, 5444, -1, 5444, 1133, 1132, -1, + 1132, 5443, 5444, -1, 1132, 1134, 5443, -1, + 5445, 5443, 1134, -1, 5443, 5445, 5446, -1, + 5446, 5442, 5443, -1, 5442, 5446, 5447, -1, + 5447, 5441, 5442, -1, 5441, 5447, 5448, -1, + 5448, 5440, 5441, -1, 5440, 5448, 5449, -1, + 5449, 5439, 5440, -1, 5439, 5449, 5450, -1, + 5450, 5438, 5439, -1, 5438, 5450, 5451, -1, + 5451, 5437, 5438, -1, 5437, 5451, 5452, -1, + 5452, 5436, 5437, -1, 5436, 5452, 5453, -1, + 5453, 5435, 5436, -1, 5435, 5453, 5454, -1, + 5454, 5434, 5435, -1, 5434, 5454, 5455, -1, + 5455, 5433, 5434, -1, 5433, 5455, 5456, -1, + 5456, 5432, 5433, -1, 5432, 5456, 5457, -1, + 5457, 5431, 5432, -1, 5431, 5457, 5458, -1, + 5458, 5430, 5431, -1, 5430, 5458, 5459, -1, + 5459, 5429, 5430, -1, 5429, 5459, 5460, -1, + 5460, 5428, 5429, -1, 5428, 5460, 5461, -1, + 5461, 5427, 5428, -1, 5427, 5461, 5462, -1, + 5462, 5426, 5427, -1, 5426, 5462, 5463, -1, + 5463, 5425, 5426, -1, 5425, 5463, 5464, -1, + 5464, 5424, 5425, -1, 5424, 5464, 5465, -1, + 5465, 5423, 5424, -1, 5423, 5465, 5466, -1, + 5466, 5422, 5423, -1, 5422, 5466, 5467, -1, + 5467, 5421, 5422, -1, 5421, 5467, 5468, -1, + 5468, 5420, 5421, -1, 5420, 5468, 5469, -1, + 5469, 5419, 5420, -1, 5419, 5469, 5470, -1, + 5470, 5418, 5419, -1, 5418, 5470, 5471, -1, + 5471, 5417, 5418, -1, 5417, 5471, 5472, -1, + 5472, 5416, 5417, -1, 5416, 5472, 5473, -1, + 5473, 5415, 5416, -1, 5415, 5473, 5474, -1, + 5474, 5414, 5415, -1, 5414, 5474, 5475, -1, + 5475, 5413, 5414, -1, 5413, 5475, 5476, -1, + 5476, 5412, 5413, -1, 5412, 5476, 5477, -1, + 5477, 5411, 5412, -1, 5411, 5477, 5478, -1, + 5478, 5410, 5411, -1, 5410, 5478, 5479, -1, + 5479, 5409, 5410, -1, 5409, 5479, 5480, -1, + 5480, 5408, 5409, -1, 5408, 5480, 5481, -1, + 5481, 5407, 5408, -1, 5407, 5481, 5482, -1, + 5482, 5406, 5407, -1, 5406, 5482, 5483, -1, + 5483, 5405, 5406, -1, 5405, 5483, 5484, -1, + 5484, 5404, 5405, -1, 5404, 5484, 5485, -1, + 5485, 5403, 5404, -1, 5403, 5485, 5486, -1, + 5486, 5402, 5403, -1, 5402, 5486, 5487, -1, + 5487, 5401, 5402, -1, 5401, 5487, 5488, -1, + 5488, 5400, 5401, -1, 5400, 5488, 5489, -1, + 5489, 5399, 5400, -1, 5399, 5489, 5490, -1, + 5490, 5398, 5399, -1, 5398, 5490, 5491, -1, + 5491, 5397, 5398, -1, 5397, 5491, 1131, -1, + 1131, 5396, 5397, -1, 5396, 1131, 1130, -1, + 1130, 5395, 5396, -1, 5395, 1130, 5492, -1, + 5492, 5391, 5395, -1, 5492, 5392, 5391, -1, + 5493, 5392, 5492, -1, 5392, 5493, 5494, -1, + 5494, 5393, 5392, -1, 5393, 5494, 5495, -1, + 5495, 5387, 5393, -1, 5495, 5363, 5387, -1, + 5495, 5364, 5363, -1, 5364, 5495, 5494, -1, + 5494, 5496, 5364, -1, 5496, 5494, 5493, -1, + 5493, 5497, 5496, -1, 5493, 5492, 5497, -1, + 5498, 5497, 5492, -1, 5498, 5492, 1130, -1, + 1130, 1129, 5498, -1, 5498, 1129, 5499, -1, + 5499, 5497, 5498, -1, 5497, 5499, 5500, -1, + 5500, 5496, 5497, -1, 5496, 5500, 5501, -1, + 5501, 5364, 5496, -1, 5501, 5365, 5364, -1, + 5501, 5374, 5365, -1, 5374, 5501, 5500, -1, + 5500, 5502, 5374, -1, 5502, 5500, 5499, -1, + 5499, 5503, 5502, -1, 5504, 5505, 5506, -1, + 5505, 5504, 5507, -1, 5507, 5508, 5505, -1, + 5508, 5507, 5503, -1, 5503, 5499, 5508, -1, + 5508, 5499, 1129, -1, 1129, 5505, 5508, -1, + 5505, 1129, 1131, -1, 1131, 5506, 5505, -1, + 5506, 1131, 5491, -1, 5491, 5509, 5506, -1, + 5509, 5491, 5490, -1, 5490, 5510, 5509, -1, + 5510, 5490, 5489, -1, 5489, 5511, 5510, -1, + 5511, 5489, 5488, -1, 5488, 5512, 5511, -1, + 5512, 5488, 5487, -1, 5487, 5513, 5512, -1, + 5513, 5487, 5486, -1, 5486, 5514, 5513, -1, + 5514, 5486, 5485, -1, 5485, 5515, 5514, -1, + 5515, 5485, 5484, -1, 5484, 5516, 5515, -1, + 5516, 5484, 5483, -1, 5483, 5517, 5516, -1, + 5517, 5483, 5482, -1, 5482, 5518, 5517, -1, + 5518, 5482, 5481, -1, 5481, 5519, 5518, -1, + 5519, 5481, 5480, -1, 5480, 5520, 5519, -1, + 5520, 5480, 5479, -1, 5479, 5521, 5520, -1, + 5521, 5479, 5478, -1, 5478, 5522, 5521, -1, + 5522, 5478, 5477, -1, 5477, 5523, 5522, -1, + 5523, 5477, 5476, -1, 5476, 5524, 5523, -1, + 5524, 5476, 5475, -1, 5475, 5525, 5524, -1, + 5525, 5475, 5474, -1, 5474, 5526, 5525, -1, + 5526, 5474, 5473, -1, 5473, 5527, 5526, -1, + 5527, 5473, 5472, -1, 5472, 5528, 5527, -1, + 5528, 5472, 5471, -1, 5471, 5529, 5528, -1, + 5529, 5471, 5470, -1, 5470, 5530, 5529, -1, + 5530, 5470, 5469, -1, 5469, 5531, 5530, -1, + 5531, 5469, 5468, -1, 5468, 5532, 5531, -1, + 5532, 5468, 5467, -1, 5467, 5533, 5532, -1, + 5533, 5467, 5466, -1, 5466, 5534, 5533, -1, + 5534, 5466, 5465, -1, 5465, 5535, 5534, -1, + 5535, 5465, 5464, -1, 5464, 5536, 5535, -1, + 5536, 5464, 5463, -1, 5463, 5537, 5536, -1, + 5537, 5463, 5462, -1, 5462, 5538, 5537, -1, + 5538, 5462, 5461, -1, 5461, 5539, 5538, -1, + 5539, 5461, 5460, -1, 5460, 5540, 5539, -1, + 5540, 5460, 5459, -1, 5459, 5541, 5540, -1, + 5541, 5459, 5458, -1, 5458, 5542, 5541, -1, + 5542, 5458, 5457, -1, 5457, 5543, 5542, -1, + 5543, 5457, 5456, -1, 5456, 5544, 5543, -1, + 5544, 5456, 5455, -1, 5455, 5545, 5544, -1, + 5545, 5455, 5454, -1, 5454, 5546, 5545, -1, + 5546, 5454, 5453, -1, 5453, 5547, 5546, -1, + 5547, 5453, 5452, -1, 5452, 5548, 5547, -1, + 5548, 5452, 5451, -1, 5451, 5549, 5548, -1, + 5549, 5451, 5450, -1, 5450, 5550, 5549, -1, + 5550, 5450, 5449, -1, 5449, 5551, 5550, -1, + 5551, 5449, 5448, -1, 5448, 5552, 5551, -1, + 5552, 5448, 5447, -1, 5447, 5553, 5552, -1, + 5553, 5447, 5446, -1, 5446, 5554, 5553, -1, + 5554, 5446, 5445, -1, 5445, 5555, 5554, -1, + 5555, 5445, 5556, -1, 5557, 5558, 5555, -1, + 5557, 5559, 5558, -1, 5560, 5559, 5557, -1, + 5557, 5555, 5560, -1, 5560, 5555, 5556, -1, + 5556, 5559, 5560, -1, 5556, 5561, 5559, -1, + 5561, 5556, 5445, -1, 5561, 5445, 1134, -1, + 1134, 5559, 5561, -1, 5559, 1134, 1133, -1, + 1133, 5562, 5563, -1, 5562, 1133, 1136, -1, + 1136, 1137, 5562, -1, 1137, 1188, 5562, -1, + 5564, 5562, 1188, -1, 5564, 5563, 5562, -1, + 5565, 5563, 5564, -1, 5564, 1188, 5565, -1, + 5565, 1188, 1187, -1, 1187, 5563, 5565, -1, + 1187, 5566, 5563, -1, 5566, 1187, 1186, -1, + 5566, 1186, 1767, -1, 1767, 5563, 5566, -1, + 1767, 5567, 5563, -1, 5567, 1767, 1766, -1, + 5567, 1766, 1931, -1, 1931, 1934, 5567, -1, + 1934, 5563, 5567, -1, 5568, 1944, 1949, -1, + 1949, 5569, 5568, -1, 5570, 5571, 5572, -1, + 5570, 5572, 5573, -1, 5573, 5574, 5570, -1, + 5574, 5573, 5575, -1, 5575, 5576, 5574, -1, + 5576, 5575, 5577, -1, 5577, 5578, 5576, -1, + 5578, 5577, 5579, -1, 5579, 5580, 5578, -1, + 5580, 5579, 5581, -1, 5581, 5582, 5580, -1, + 5582, 5581, 5583, -1, 5583, 5584, 5582, -1, + 5584, 5583, 5585, -1, 5585, 5586, 5584, -1, + 5586, 5585, 5587, -1, 5587, 5588, 5586, -1, + 5588, 5587, 5589, -1, 5589, 5590, 5588, -1, + 5590, 5589, 5591, -1, 5591, 5592, 5590, -1, + 5592, 5591, 5593, -1, 5593, 5594, 5592, -1, + 5594, 5593, 5595, -1, 5595, 5596, 5594, -1, + 5596, 5595, 5597, -1, 5597, 5598, 5596, -1, + 5598, 5597, 5599, -1, 5599, 5600, 5598, -1, + 5600, 5599, 5601, -1, 5601, 5602, 5600, -1, + 5602, 5601, 5603, -1, 5603, 5604, 5602, -1, + 5604, 5603, 5605, -1, 5605, 5606, 5604, -1, + 5606, 5605, 5607, -1, 5607, 5608, 5606, -1, + 5608, 5607, 5609, -1, 5609, 5610, 5608, -1, + 5610, 5609, 5611, -1, 5611, 5612, 5610, -1, + 5612, 5611, 5613, -1, 5613, 5614, 5612, -1, + 5615, 5616, 5617, -1, 5616, 5615, 5618, -1, + 5618, 5619, 5616, -1, 5619, 5618, 5620, -1, + 5620, 5621, 5619, -1, 5621, 5620, 5622, -1, + 5622, 5623, 5621, -1, 5623, 5622, 5624, -1, + 5624, 5625, 5623, -1, 5625, 5624, 5626, -1, + 5626, 5627, 5625, -1, 5627, 5626, 5628, -1, + 5628, 5629, 5627, -1, 5629, 5628, 5630, -1, + 5630, 5631, 5629, -1, 5631, 5630, 5632, -1, + 5632, 5633, 5631, -1, 5633, 5632, 5634, -1, + 5634, 5635, 5633, -1, 5635, 5634, 5636, -1, + 5636, 5637, 5635, -1, 5637, 5636, 5638, -1, + 5638, 5639, 5637, -1, 5639, 5638, 5640, -1, + 5640, 5641, 5639, -1, 5641, 5640, 5642, -1, + 5642, 5643, 5641, -1, 5643, 5642, 5644, -1, + 5644, 5645, 5643, -1, 5645, 5644, 5646, -1, + 5646, 5647, 5645, -1, 5647, 5646, 5648, -1, + 5648, 5649, 5647, -1, 5649, 5648, 5650, -1, + 5650, 5651, 5649, -1, 5651, 5650, 5652, -1, + 5652, 5653, 5651, -1, 5654, 5655, 5653, -1, + 5654, 5653, 5656, -1, 5656, 5657, 5654, -1, + 5657, 5656, 5658, -1, 5658, 5659, 5657, -1, + 5659, 5658, 5660, -1, 5660, 5661, 5659, -1, + 5661, 5660, 5662, -1, 5662, 5663, 5661, -1, + 5662, 5664, 5663, -1, 5664, 5662, 5665, -1, + 5665, 5666, 5664, -1, 5666, 5665, 5667, -1, + 5667, 5668, 5666, -1, 5668, 5667, 5669, -1, + 5669, 5670, 5668, -1, 5671, 5614, 5672, -1, + 5672, 5673, 5671, -1, 5673, 5672, 5674, -1, + 5674, 5675, 5673, -1, 5675, 5674, 5676, -1, + 5676, 5677, 5675, -1, 5677, 5676, 5678, -1, + 5678, 5679, 5677, -1, 5679, 5678, 5680, -1, + 5680, 5681, 5679, -1, 5681, 5680, 5682, -1, + 5682, 5683, 5681, -1, 5683, 5682, 5684, -1, + 5684, 5685, 5683, -1, 5685, 5684, 5686, -1, + 5686, 5687, 5685, -1, 5687, 5686, 5688, -1, + 5688, 5689, 5687, -1, 5689, 5688, 5690, -1, + 5690, 5691, 5689, -1, 5691, 5690, 5692, -1, + 5692, 5693, 5691, -1, 5693, 5692, 5694, -1, + 5694, 5695, 5693, -1, 5695, 5694, 5696, -1, + 5696, 5697, 5695, -1, 5697, 5696, 5698, -1, + 5698, 5699, 5697, -1, 5699, 5698, 5700, -1, + 5700, 5701, 5699, -1, 5701, 5700, 5702, -1, + 5702, 5703, 5701, -1, 5703, 5702, 5704, -1, + 5704, 5705, 5703, -1, 5705, 5704, 5706, -1, + 5706, 5707, 5705, -1, 5707, 5706, 5708, -1, + 5708, 5709, 5707, -1, 5709, 5708, 5710, -1, + 5710, 5711, 5709, -1, 5711, 5710, 5670, -1, + 5670, 5669, 5711, -1, 5669, 5712, 5711, -1, + 5669, 5713, 5712, -1, 5713, 5669, 5667, -1, + 5667, 5714, 5713, -1, 5714, 5667, 5665, -1, + 5665, 5715, 5714, -1, 5715, 5665, 5662, -1, + 5715, 5662, 5660, -1, 5660, 5716, 5715, -1, + 5716, 5660, 5658, -1, 5658, 5717, 5716, -1, + 5717, 5658, 5656, -1, 5656, 5718, 5717, -1, + 5718, 5656, 5653, -1, 5653, 5652, 5718, -1, + 5718, 5652, 5719, -1, 5718, 5719, 5720, -1, + 5720, 5717, 5718, -1, 5717, 5720, 5721, -1, + 5721, 5716, 5717, -1, 5716, 5721, 5722, -1, + 5722, 5715, 5716, -1, 5722, 5714, 5715, -1, + 5714, 5722, 5723, -1, 5723, 5713, 5714, -1, + 5713, 5723, 5724, -1, 5724, 5712, 5713, -1, + 5712, 5724, 5725, -1, 5712, 5725, 5726, -1, + 5727, 5728, 5729, -1, 5729, 5730, 5727, -1, + 5730, 5729, 5731, -1, 5731, 5732, 5730, -1, + 5732, 5731, 5733, -1, 5733, 5734, 5732, -1, + 5734, 5733, 5735, -1, 5735, 5736, 5734, -1, + 5736, 5735, 5737, -1, 5737, 5738, 5736, -1, + 5738, 5737, 5739, -1, 5739, 5740, 5738, -1, + 5740, 5739, 5741, -1, 5741, 5742, 5740, -1, + 5742, 5741, 5743, -1, 5743, 5744, 5742, -1, + 5744, 5743, 5745, -1, 5745, 5746, 5744, -1, + 5746, 5745, 5747, -1, 5747, 5748, 5746, -1, + 5748, 5747, 5749, -1, 5749, 5750, 5748, -1, + 5750, 5749, 5751, -1, 5751, 5752, 5750, -1, + 5752, 5751, 5753, -1, 5753, 5754, 5752, -1, + 5754, 5753, 5755, -1, 5755, 5756, 5754, -1, + 5756, 5755, 5757, -1, 5757, 5758, 5756, -1, + 5758, 5757, 5759, -1, 5759, 5760, 5758, -1, + 5760, 5759, 5761, -1, 5761, 5762, 5760, -1, + 5762, 5761, 5763, -1, 5763, 5764, 5762, -1, + 5764, 5763, 5765, -1, 5765, 5766, 5764, -1, + 5766, 5765, 5767, -1, 5767, 5726, 5766, -1, + 5726, 5767, 5768, -1, 5768, 5712, 5726, -1, + 5768, 5711, 5712, -1, 5768, 5709, 5711, -1, + 5709, 5768, 5767, -1, 5767, 5707, 5709, -1, + 5707, 5767, 5765, -1, 5765, 5705, 5707, -1, + 5705, 5765, 5763, -1, 5763, 5703, 5705, -1, + 5703, 5763, 5761, -1, 5761, 5701, 5703, -1, + 5701, 5761, 5759, -1, 5759, 5699, 5701, -1, + 5699, 5759, 5757, -1, 5757, 5697, 5699, -1, + 5697, 5757, 5755, -1, 5755, 5695, 5697, -1, + 5695, 5755, 5753, -1, 5753, 5693, 5695, -1, + 5693, 5753, 5751, -1, 5751, 5691, 5693, -1, + 5691, 5751, 5749, -1, 5749, 5689, 5691, -1, + 5689, 5749, 5747, -1, 5747, 5687, 5689, -1, + 5687, 5747, 5745, -1, 5745, 5685, 5687, -1, + 5685, 5745, 5743, -1, 5743, 5683, 5685, -1, + 5683, 5743, 5741, -1, 5741, 5681, 5683, -1, + 5681, 5741, 5739, -1, 5739, 5679, 5681, -1, + 5679, 5739, 5737, -1, 5737, 5677, 5679, -1, + 5677, 5737, 5735, -1, 5735, 5675, 5677, -1, + 5675, 5735, 5733, -1, 5733, 5673, 5675, -1, + 5673, 5733, 5731, -1, 5731, 5671, 5673, -1, + 5671, 5731, 5729, -1, 5729, 5614, 5671, -1, + 5614, 5729, 5728, -1, 5728, 5612, 5614, -1, + 5612, 5728, 5769, -1, 5769, 5610, 5612, -1, + 5610, 5769, 5770, -1, 5770, 5608, 5610, -1, + 5608, 5770, 5771, -1, 5771, 5606, 5608, -1, + 5606, 5771, 5772, -1, 5772, 5604, 5606, -1, + 5604, 5772, 5773, -1, 5773, 5602, 5604, -1, + 5602, 5773, 5774, -1, 5774, 5600, 5602, -1, + 5600, 5774, 5775, -1, 5775, 5598, 5600, -1, + 5598, 5775, 5776, -1, 5776, 5596, 5598, -1, + 5596, 5776, 5777, -1, 5777, 5594, 5596, -1, + 5594, 5777, 5778, -1, 5778, 5592, 5594, -1, + 5592, 5778, 5779, -1, 5779, 5590, 5592, -1, + 5590, 5779, 5780, -1, 5780, 5588, 5590, -1, + 5588, 5780, 5781, -1, 5781, 5586, 5588, -1, + 5586, 5781, 5782, -1, 5782, 5584, 5586, -1, + 5584, 5782, 5783, -1, 5783, 5582, 5584, -1, + 5582, 5783, 5784, -1, 5784, 5580, 5582, -1, + 5580, 5784, 5785, -1, 5785, 5578, 5580, -1, + 5578, 5785, 5786, -1, 5786, 5576, 5578, -1, + 5576, 5786, 5787, -1, 5787, 5574, 5576, -1, + 5574, 5787, 5788, -1, 5788, 5570, 5574, -1, + 5788, 5789, 5570, -1, 5790, 5791, 5568, -1, + 5791, 5789, 5568, -1, 5791, 5570, 5789, -1, + 5791, 5790, 5570, -1, 5790, 5571, 5570, -1, + 5571, 5790, 5568, -1, 5571, 5568, 5569, -1, + 5569, 5572, 5571, -1, 5569, 1949, 5572, -1, + 5572, 1949, 1950, -1, 5572, 1950, 1975, -1, + 1975, 5573, 5572, -1, 5573, 1975, 1973, -1, + 1973, 5575, 5573, -1, 5575, 1973, 1971, -1, + 1971, 5577, 5575, -1, 5577, 1971, 1969, -1, + 1969, 5579, 5577, -1, 5579, 1969, 1967, -1, + 1967, 5581, 5579, -1, 5581, 1967, 1965, -1, + 1965, 5583, 5581, -1, 5583, 1965, 1963, -1, + 1963, 5585, 5583, -1, 5585, 1963, 1961, -1, + 1961, 5587, 5585, -1, 5587, 1961, 1959, -1, + 1959, 5589, 5587, -1, 5589, 1959, 1957, -1, + 1957, 5591, 5589, -1, 5591, 1957, 1955, -1, + 1955, 5593, 5591, -1, 5593, 1955, 1953, -1, + 1953, 5595, 5593, -1, 5595, 1953, 1952, -1, + 1952, 5597, 5595, -1, 5597, 1952, 1995, -1, + 1995, 5599, 5597, -1, 5599, 1995, 1997, -1, + 1997, 5601, 5599, -1, 5601, 1997, 2012, -1, + 2012, 5603, 5601, -1, 5603, 2012, 2010, -1, + 2010, 5605, 5603, -1, 5605, 2010, 2008, -1, + 2008, 5607, 5605, -1, 5607, 2008, 2006, -1, + 2006, 5609, 5607, -1, 5609, 2006, 2004, -1, + 2004, 5611, 5609, -1, 5611, 2004, 2002, -1, + 2002, 5613, 5611, -1, 5613, 2002, 2000, -1, + 2000, 5614, 5613, -1, 5614, 2000, 1999, -1, + 1999, 5672, 5614, -1, 5672, 1999, 2071, -1, + 2071, 5674, 5672, -1, 5674, 2071, 2072, -1, + 2072, 5676, 5674, -1, 5676, 2072, 2073, -1, + 2073, 5678, 5676, -1, 5678, 2073, 2074, -1, + 2074, 5680, 5678, -1, 5680, 2074, 2075, -1, + 2075, 5682, 5680, -1, 5682, 2075, 2076, -1, + 2076, 5684, 5682, -1, 5684, 2076, 2077, -1, + 2077, 5686, 5684, -1, 5686, 2077, 2078, -1, + 2078, 5688, 5686, -1, 5688, 2078, 2079, -1, + 2079, 5690, 5688, -1, 5690, 2079, 2080, -1, + 2080, 5692, 5690, -1, 5692, 2080, 2081, -1, + 2081, 5694, 5692, -1, 5694, 2081, 2082, -1, + 2082, 5696, 5694, -1, 5696, 2082, 2083, -1, + 2083, 5698, 5696, -1, 5698, 2083, 2084, -1, + 2084, 5700, 5698, -1, 5700, 2084, 2085, -1, + 2085, 5702, 5700, -1, 5702, 2085, 2086, -1, + 2086, 5704, 5702, -1, 5704, 2086, 2087, -1, + 2087, 5706, 5704, -1, 5706, 2087, 2088, -1, + 2088, 5708, 5706, -1, 5708, 2088, 2089, -1, + 2089, 5710, 5708, -1, 5710, 2089, 2090, -1, + 2090, 5670, 5710, -1, 5670, 2090, 2091, -1, + 2091, 5668, 5670, -1, 5668, 2091, 2092, -1, + 2092, 5666, 5668, -1, 5666, 2092, 2093, -1, + 2093, 5664, 5666, -1, 5664, 2093, 2094, -1, + 2094, 5663, 5664, -1, 5663, 2094, 2095, -1, + 5663, 2095, 2097, -1, 2097, 5661, 5663, -1, + 5661, 2097, 2099, -1, 2099, 5659, 5661, -1, + 5659, 2099, 2101, -1, 2101, 5657, 5659, -1, + 5657, 2101, 2103, -1, 2103, 5654, 5657, -1, + 5654, 2103, 2105, -1, 2105, 5655, 5654, -1, + 5655, 2105, 2107, -1, 2107, 5792, 5655, -1, + 5792, 2107, 2109, -1, 2109, 5793, 5792, -1, + 5793, 2109, 2111, -1, 2111, 5794, 5793, -1, + 5794, 2111, 2113, -1, 2113, 5795, 5794, -1, + 5795, 2113, 2115, -1, 2115, 5796, 5795, -1, + 5796, 2115, 2117, -1, 2117, 5797, 5796, -1, + 5797, 2117, 2119, -1, 2119, 5798, 5797, -1, + 5798, 2119, 2121, -1, 2121, 5799, 5798, -1, + 5799, 2121, 2123, -1, 2123, 5800, 5799, -1, + 5800, 2123, 2125, -1, 2125, 5801, 5800, -1, + 5801, 2125, 2127, -1, 2127, 5802, 5801, -1, + 5802, 2127, 2129, -1, 2129, 5803, 5802, -1, + 5803, 2129, 2131, -1, 2131, 5804, 5803, -1, + 5804, 2131, 2133, -1, 2133, 5805, 5804, -1, + 5805, 2133, 2135, -1, 2135, 5806, 5805, -1, + 5806, 2135, 2137, -1, 2137, 5807, 5806, -1, + 5807, 2137, 2139, -1, 2139, 5808, 5807, -1, + 5808, 2139, 2141, -1, 2141, 5809, 5808, -1, + 5809, 2141, 2143, -1, 2143, 5810, 5809, -1, + 5810, 2143, 2145, -1, 2145, 5811, 5810, -1, + 5811, 2145, 2147, -1, 2147, 5812, 5811, -1, + 5812, 2147, 2149, -1, 2149, 5813, 5812, -1, + 5813, 2149, 2151, -1, 2151, 5814, 5813, -1, + 5814, 2151, 2153, -1, 2153, 5815, 5814, -1, + 5815, 2153, 2155, -1, 2155, 5816, 5815, -1, + 5816, 2155, 2157, -1, 2157, 5817, 5816, -1, + 5817, 2157, 2159, -1, 2159, 5818, 5817, -1, + 5818, 2159, 2161, -1, 2161, 5819, 5818, -1, + 5819, 2161, 2163, -1, 2163, 5820, 5819, -1, + 5820, 2163, 2165, -1, 2165, 5821, 5820, -1, + 5821, 2165, 2167, -1, 2167, 5822, 5821, -1, + 5822, 2167, 2169, -1, 2169, 5823, 5822, -1, + 5823, 2169, 2171, -1, 2171, 5824, 5823, -1, + 5824, 2171, 2173, -1, 2173, 5825, 5824, -1, + 5825, 2173, 2175, -1, 2175, 5826, 5825, -1, + 5826, 2175, 2177, -1, 2177, 5827, 5826, -1, + 5827, 2177, 2179, -1, 2179, 5828, 5827, -1, + 5828, 2179, 2181, -1, 2181, 5829, 5828, -1, + 5829, 2181, 2183, -1, 2183, 5830, 5829, -1, + 5830, 2183, 2185, -1, 2185, 5831, 5830, -1, + 5831, 2185, 2187, -1, 2187, 5832, 5831, -1, + 5832, 2187, 2189, -1, 2189, 5833, 5832, -1, + 5833, 2189, 2191, -1, 2191, 5834, 5833, -1, + 5834, 2191, 2193, -1, 2193, 5835, 5834, -1, + 5835, 2193, 2195, -1, 2195, 5836, 5835, -1, + 5836, 2195, 2197, -1, 2197, 5837, 5836, -1, + 5837, 2197, 2199, -1, 2199, 5838, 5837, -1, + 5838, 2199, 2201, -1, 2201, 2209, 5838, -1, + 5839, 5838, 2209, -1, 5839, 2209, 1681, -1, + 5839, 1681, 1683, -1, 1683, 5838, 5839, -1, + 1683, 1682, 5838, -1, 5838, 1682, 1677, -1, + 1677, 5837, 5838, -1, 5837, 1677, 1675, -1, + 1675, 5836, 5837, -1, 5836, 1675, 1673, -1, + 1673, 5835, 5836, -1, 5835, 1673, 1671, -1, + 1671, 5834, 5835, -1, 5834, 1671, 1669, -1, + 1669, 5833, 5834, -1, 5833, 1669, 1667, -1, + 1667, 5832, 5833, -1, 5832, 1667, 1665, -1, + 1665, 5831, 5832, -1, 5831, 1665, 1663, -1, + 1663, 5830, 5831, -1, 5830, 1663, 1661, -1, + 1661, 5829, 5830, -1, 5829, 1661, 1659, -1, + 1659, 5828, 5829, -1, 5828, 1659, 1657, -1, + 1657, 5827, 5828, -1, 5827, 1657, 1655, -1, + 1655, 5826, 5827, -1, 5826, 1655, 1653, -1, + 1653, 5825, 5826, -1, 5825, 1653, 1651, -1, + 1651, 5824, 5825, -1, 5824, 1651, 1649, -1, + 1649, 5823, 5824, -1, 5823, 1649, 1646, -1, + 1646, 5822, 5823, -1, 5822, 1646, 1648, -1, + 1648, 5821, 5822, -1, 5821, 1648, 1685, -1, + 1685, 5820, 5821, -1, 5820, 1685, 1686, -1, + 1686, 5819, 5820, -1, 5819, 1686, 1687, -1, + 1687, 5818, 5819, -1, 5818, 1687, 1689, -1, + 1689, 5817, 5818, -1, 5817, 1689, 1723, -1, + 1723, 5816, 5817, -1, 5816, 1723, 1725, -1, + 1725, 5815, 5816, -1, 5815, 1725, 1727, -1, + 1727, 5814, 5815, -1, 5814, 1727, 1729, -1, + 1729, 5813, 5814, -1, 5813, 1729, 1731, -1, + 1731, 5812, 5813, -1, 5812, 1731, 1733, -1, + 1733, 5811, 5812, -1, 5811, 1733, 1734, -1, + 1734, 5810, 5811, -1, 5810, 1734, 1736, -1, + 1736, 5809, 5810, -1, 5809, 1736, 5840, -1, + 5840, 5808, 5809, -1, 5808, 5840, 5841, -1, + 5841, 5807, 5808, -1, 5807, 5841, 5842, -1, + 5842, 5806, 5807, -1, 5806, 5842, 5843, -1, + 5843, 5805, 5806, -1, 5805, 5843, 5844, -1, + 5844, 5804, 5805, -1, 5804, 5844, 5845, -1, + 5845, 5803, 5804, -1, 5803, 5845, 5846, -1, + 5846, 5802, 5803, -1, 5802, 5846, 5847, -1, + 5847, 5801, 5802, -1, 5801, 5847, 5848, -1, + 5848, 5800, 5801, -1, 5800, 5848, 5849, -1, + 5849, 5799, 5800, -1, 5799, 5849, 5850, -1, + 5850, 5798, 5799, -1, 5798, 5850, 5851, -1, + 5851, 5797, 5798, -1, 5797, 5851, 5852, -1, + 5852, 5796, 5797, -1, 5796, 5852, 5853, -1, + 5853, 5795, 5796, -1, 5795, 5853, 5854, -1, + 5854, 5794, 5795, -1, 5794, 5854, 5855, -1, + 5855, 5793, 5794, -1, 5793, 5855, 5856, -1, + 5856, 5792, 5793, -1, 5792, 5856, 5857, -1, + 5857, 5655, 5792, -1, 5857, 5653, 5655, -1, + 5857, 5651, 5653, -1, 5651, 5857, 5856, -1, + 5856, 5649, 5651, -1, 5649, 5856, 5855, -1, + 5855, 5647, 5649, -1, 5647, 5855, 5854, -1, + 5854, 5645, 5647, -1, 5645, 5854, 5853, -1, + 5853, 5643, 5645, -1, 5643, 5853, 5852, -1, + 5852, 5641, 5643, -1, 5641, 5852, 5851, -1, + 5851, 5639, 5641, -1, 5639, 5851, 5850, -1, + 5850, 5637, 5639, -1, 5637, 5850, 5849, -1, + 5849, 5635, 5637, -1, 5635, 5849, 5848, -1, + 5848, 5633, 5635, -1, 5633, 5848, 5847, -1, + 5847, 5631, 5633, -1, 5631, 5847, 5846, -1, + 5846, 5629, 5631, -1, 5629, 5846, 5845, -1, + 5845, 5627, 5629, -1, 5627, 5845, 5844, -1, + 5844, 5625, 5627, -1, 5625, 5844, 5843, -1, + 5843, 5623, 5625, -1, 5623, 5843, 5842, -1, + 5842, 5621, 5623, -1, 5621, 5842, 5841, -1, + 5841, 5619, 5621, -1, 5619, 5841, 5840, -1, + 5840, 5616, 5619, -1, 5616, 5840, 1736, -1, + 1736, 5617, 5616, -1, 5617, 1736, 1735, -1, + 1735, 1737, 5617, -1, 1737, 5858, 5617, -1, + 5858, 1737, 1738, -1, 1738, 5859, 5858, -1, + 5859, 1738, 1739, -1, 1739, 5860, 5859, -1, + 5860, 1739, 1740, -1, 1740, 5861, 5860, -1, + 5861, 1740, 1741, -1, 1741, 5862, 5861, -1, + 5862, 1741, 1742, -1, 1742, 5863, 5862, -1, + 5863, 1742, 1743, -1, 1743, 5864, 5863, -1, + 5864, 1743, 1744, -1, 1744, 5865, 5864, -1, + 5865, 1744, 1745, -1, 1745, 5866, 5865, -1, + 5866, 1745, 1746, -1, 1746, 5867, 5866, -1, + 5867, 1746, 1747, -1, 1747, 5868, 5867, -1, + 5868, 1747, 1748, -1, 1748, 5869, 5868, -1, + 5869, 1748, 1749, -1, 1749, 5870, 5869, -1, + 5870, 1749, 1750, -1, 1750, 5871, 5870, -1, + 5871, 1750, 1751, -1, 1751, 5872, 5871, -1, + 5872, 1751, 1752, -1, 1752, 5873, 5872, -1, + 5873, 1752, 1753, -1, 1753, 5874, 5873, -1, + 5874, 1753, 1754, -1, 1754, 5875, 5874, -1, + 5875, 1754, 1755, -1, 1755, 5876, 5875, -1, + 5876, 1755, 1756, -1, 1756, 5877, 5876, -1, + 5877, 1756, 1757, -1, 1757, 5878, 5877, -1, + 5878, 1757, 1758, -1, 5878, 1758, 5879, -1, + 5880, 5881, 5878, -1, 5880, 5882, 5881, -1, + 5883, 5882, 5880, -1, 5880, 5878, 5883, -1, + 5883, 5878, 5879, -1, 5879, 5882, 5883, -1, + 5879, 5884, 5882, -1, 5884, 5879, 1758, -1, + 5884, 1758, 1759, -1, 1759, 5882, 5884, -1, + 5882, 1759, 1761, -1, 5885, 1254, 1253, -1, + 1253, 5886, 5885, -1, 1253, 1251, 5886, -1, + 5886, 1251, 1457, -1, 1457, 5885, 5886, -1, + 1457, 1458, 5885, -1, 1458, 1459, 5885, -1, + 1459, 5887, 5885, -1, 5887, 1459, 1460, -1, + 5887, 1460, 1529, -1, 1529, 1531, 5887, -1, + 1531, 5885, 5887, -1, 1127, 1531, 1533, -1, + 5888, 1127, 1533, -1, 5888, 1533, 1534, -1, + 5888, 1534, 5889, -1, 5889, 1127, 5888, -1, + 5889, 1128, 1127, -1, 5889, 1125, 1128, -1, + 1125, 5889, 1534, -1, 1534, 5890, 1125, -1, + 5890, 1534, 1535, -1, 1535, 5891, 5890, -1, + 5891, 1535, 1536, -1, 1536, 5892, 5891, -1, + 5892, 1536, 1537, -1, 1537, 5893, 5892, -1, + 5893, 1537, 1538, -1, 1538, 5894, 5893, -1, + 5894, 1538, 1539, -1, 1539, 5895, 5894, -1, + 5895, 1539, 1540, -1, 1540, 5896, 5895, -1, + 5896, 1540, 1541, -1, 1541, 5897, 5896, -1, + 5897, 1541, 1542, -1, 1542, 5898, 5897, -1, + 5898, 1542, 1543, -1, 1543, 5899, 5898, -1, + 5899, 1543, 1544, -1, 1544, 5900, 5899, -1, + 5900, 1544, 1545, -1, 1545, 5901, 5900, -1, + 5901, 1545, 1546, -1, 1546, 5902, 5901, -1, + 5902, 1546, 1547, -1, 1547, 5903, 5902, -1, + 5903, 1547, 1548, -1, 1548, 5904, 5903, -1, + 5904, 1548, 1549, -1, 1549, 5905, 5904, -1, + 5905, 1549, 1550, -1, 1550, 5906, 5905, -1, + 5906, 1550, 1551, -1, 1551, 5907, 5906, -1, + 5907, 1551, 1552, -1, 1552, 5908, 5907, -1, + 1552, 5909, 5908, -1, 5909, 1552, 1553, -1, + 1553, 5910, 5909, -1, 5910, 1553, 1554, -1, + 1554, 5911, 5910, -1, 5911, 1554, 1555, -1, + 1555, 5912, 5911, -1, 5912, 1555, 1556, -1, + 1556, 5913, 5912, -1, 5913, 1556, 1557, -1, + 1557, 5914, 5913, -1, 5914, 1557, 1558, -1, + 1558, 5915, 5914, -1, 5915, 1558, 1559, -1, + 1559, 5916, 5915, -1, 5916, 1559, 1560, -1, + 1560, 5917, 5916, -1, 5917, 1560, 1561, -1, + 1561, 5918, 5917, -1, 5918, 1561, 1562, -1, + 1562, 5919, 5918, -1, 5919, 1562, 1563, -1, + 1563, 5920, 5919, -1, 5920, 1563, 1564, -1, + 1564, 5921, 5920, -1, 5921, 1564, 1565, -1, + 1565, 5922, 5921, -1, 5922, 1565, 1566, -1, + 1566, 5923, 5922, -1, 5923, 1566, 1567, -1, + 1567, 5924, 5923, -1, 5924, 1567, 1568, -1, + 1568, 5925, 5924, -1, 5925, 1568, 1569, -1, + 1569, 5926, 5925, -1, 5926, 1569, 1570, -1, + 1570, 1120, 5926, -1, 1120, 1570, 1572, -1, + 1572, 1122, 1120, -1, 1572, 1121, 1122, -1, + 1572, 1571, 1121, -1, 1571, 1573, 1121, -1, + 1121, 1573, 1575, -1, 5927, 1119, 1121, -1, + 5928, 5929, 5930, -1, 5928, 5927, 5929, -1, + 5928, 5931, 5927, -1, 5928, 5930, 5931, -1, + 5932, 5933, 5934, -1, 5930, 5934, 5933, -1, + 5933, 5931, 5930, -1, 5933, 5927, 5931, -1, + 5933, 5932, 5927, -1, 5932, 1119, 5927, -1, + 5932, 5934, 1119, -1, 5934, 1120, 1119, -1, + 5935, 5936, 5937, -1, 5937, 5938, 5935, -1, + 5938, 5937, 5939, -1, 5939, 5940, 5938, -1, + 5940, 5939, 5941, -1, 5941, 5942, 5940, -1, + 5942, 5941, 5943, -1, 5943, 5944, 5942, -1, + 5944, 5943, 5945, -1, 5945, 5946, 5944, -1, + 5946, 5945, 5947, -1, 5947, 5948, 5946, -1, + 5948, 5947, 5949, -1, 5949, 5950, 5948, -1, + 5950, 5949, 5951, -1, 5951, 5952, 5950, -1, + 5952, 5951, 5953, -1, 5953, 5954, 5952, -1, + 5954, 5953, 5955, -1, 5955, 5956, 5954, -1, + 5956, 5955, 5957, -1, 5957, 5958, 5956, -1, + 5958, 5957, 5959, -1, 5959, 5960, 5958, -1, + 5960, 5959, 5961, -1, 5961, 5962, 5960, -1, + 5962, 5961, 5963, -1, 5963, 5964, 5962, -1, + 5964, 5963, 5965, -1, 5965, 5966, 5964, -1, + 5966, 5965, 5967, -1, 5967, 5968, 5966, -1, + 5968, 5967, 5969, -1, 5969, 5970, 5968, -1, + 5970, 5969, 5971, -1, 5971, 5972, 5970, -1, + 5972, 5971, 5973, -1, 5973, 5974, 5972, -1, + 5973, 5975, 5974, -1, 5975, 5973, 5976, -1, + 5976, 5977, 5975, -1, 5977, 5976, 5978, -1, + 5978, 5979, 5977, -1, 5979, 5978, 5980, -1, + 5980, 5981, 5979, -1, 5981, 5980, 5982, -1, + 5982, 5983, 5981, -1, 5983, 5982, 5984, -1, + 5984, 5985, 5983, -1, 5985, 5984, 5986, -1, + 5986, 5987, 5985, -1, 5987, 5986, 5988, -1, + 5988, 5989, 5987, -1, 5989, 5988, 5990, -1, + 5990, 5991, 5989, -1, 5991, 5990, 5992, -1, + 5992, 5993, 5991, -1, 5993, 5992, 5994, -1, + 5994, 5995, 5993, -1, 5995, 5994, 5996, -1, + 5996, 5997, 5995, -1, 5997, 5996, 5998, -1, + 5998, 5999, 5997, -1, 5999, 5998, 6000, -1, + 6000, 6001, 5999, -1, 6001, 6000, 6002, -1, + 6002, 6003, 6001, -1, 6003, 6002, 6004, -1, + 6004, 6005, 6003, -1, 6005, 6004, 6006, -1, + 6006, 6007, 6005, -1, 6007, 6006, 6008, -1, + 6008, 6009, 6007, -1, 6009, 6008, 6010, -1, + 6010, 6011, 6009, -1, 6011, 6010, 6012, -1, + 6012, 5934, 6011, -1, 6012, 1120, 5934, -1, + 6012, 5926, 1120, -1, 5926, 6012, 6010, -1, + 6010, 5925, 5926, -1, 5925, 6010, 6008, -1, + 6008, 5924, 5925, -1, 5924, 6008, 6006, -1, + 6006, 5923, 5924, -1, 5923, 6006, 6004, -1, + 6004, 5922, 5923, -1, 5922, 6004, 6002, -1, + 6002, 5921, 5922, -1, 5921, 6002, 6000, -1, + 6000, 5920, 5921, -1, 5920, 6000, 5998, -1, + 5998, 5919, 5920, -1, 5919, 5998, 5996, -1, + 5996, 5918, 5919, -1, 5918, 5996, 5994, -1, + 5994, 5917, 5918, -1, 5917, 5994, 5992, -1, + 5992, 5916, 5917, -1, 5916, 5992, 5990, -1, + 5990, 5915, 5916, -1, 5915, 5990, 5988, -1, + 5988, 5914, 5915, -1, 5914, 5988, 5986, -1, + 5986, 5913, 5914, -1, 5913, 5986, 5984, -1, + 5984, 5912, 5913, -1, 5912, 5984, 5982, -1, + 5982, 5911, 5912, -1, 5911, 5982, 5980, -1, + 5980, 5910, 5911, -1, 5910, 5980, 5978, -1, + 5978, 5909, 5910, -1, 5909, 5978, 5976, -1, + 5976, 5908, 5909, -1, 5908, 5976, 5973, -1, + 5908, 5973, 5971, -1, 5971, 5907, 5908, -1, + 5907, 5971, 5969, -1, 5969, 5906, 5907, -1, + 5906, 5969, 5967, -1, 5967, 5905, 5906, -1, + 5905, 5967, 5965, -1, 5965, 5904, 5905, -1, + 5904, 5965, 5963, -1, 5963, 5903, 5904, -1, + 5903, 5963, 5961, -1, 5961, 5902, 5903, -1, + 5902, 5961, 5959, -1, 5959, 5901, 5902, -1, + 5901, 5959, 5957, -1, 5957, 5900, 5901, -1, + 5900, 5957, 5955, -1, 5955, 5899, 5900, -1, + 5899, 5955, 5953, -1, 5953, 5898, 5899, -1, + 5898, 5953, 5951, -1, 5951, 5897, 5898, -1, + 5897, 5951, 5949, -1, 5949, 5896, 5897, -1, + 5896, 5949, 5947, -1, 5947, 5895, 5896, -1, + 5895, 5947, 5945, -1, 5945, 5894, 5895, -1, + 5894, 5945, 5943, -1, 5943, 5893, 5894, -1, + 5893, 5943, 5941, -1, 5941, 5892, 5893, -1, + 5892, 5941, 5939, -1, 5939, 5891, 5892, -1, + 5891, 5939, 5937, -1, 5937, 5890, 5891, -1, + 5890, 5937, 5936, -1, 5936, 1125, 5890, -1, + 5936, 1123, 1125, -1, 5936, 5935, 1123, -1, + 1123, 5935, 6013, -1, 1123, 6013, 1115, -1, + 1115, 6014, 1123, -1, 6014, 1115, 1117, -1, + 6014, 1117, 6015, -1, 6014, 6015, 6016, -1, + 6016, 1123, 6014, -1, 6016, 1124, 1123, -1, + 6016, 6015, 1124, -1, 6015, 1127, 1124, -1, + 847, 6015, 1117, -1, 1117, 1114, 847, -1, + 1114, 1116, 847, -1, 1116, 6017, 847, -1, + 6017, 843, 847, -1, 6017, 841, 843, -1, + 6017, 1116, 841, -1, 841, 1116, 1115, -1, + 1115, 837, 841, -1, 837, 1115, 6013, -1, + 6013, 838, 837, -1, 838, 6013, 6018, -1, + 6018, 6019, 838, -1, 6019, 6018, 6020, -1, + 6020, 6021, 6019, -1, 6021, 6020, 6022, -1, + 6022, 6023, 6021, -1, 6023, 6022, 6024, -1, + 6024, 6025, 6023, -1, 6025, 6024, 6026, -1, + 6026, 6027, 6025, -1, 6027, 6026, 6028, -1, + 6028, 6029, 6027, -1, 6029, 6028, 6030, -1, + 6030, 6031, 6029, -1, 6031, 6030, 6032, -1, + 6032, 6033, 6031, -1, 6033, 6032, 6034, -1, + 6034, 6035, 6033, -1, 6035, 6034, 6036, -1, + 6036, 6037, 6035, -1, 6037, 6036, 6038, -1, + 6038, 6039, 6037, -1, 6039, 6038, 6040, -1, + 6040, 6041, 6039, -1, 6041, 6040, 6042, -1, + 6042, 6043, 6041, -1, 6043, 6042, 6044, -1, + 6044, 6045, 6043, -1, 6045, 6044, 6046, -1, + 6046, 6047, 6045, -1, 6047, 6046, 6048, -1, + 6048, 6049, 6047, -1, 6049, 6048, 6050, -1, + 6050, 6051, 6049, -1, 6051, 6050, 6052, -1, + 6052, 6053, 6051, -1, 6053, 6052, 6054, -1, + 6054, 6055, 6053, -1, 6055, 6054, 6056, -1, + 6056, 6057, 6055, -1, 6056, 6058, 6057, -1, + 6058, 6056, 6059, -1, 6059, 6060, 6058, -1, + 6060, 6059, 6061, -1, 6061, 6062, 6060, -1, + 6062, 6061, 6063, -1, 6063, 6064, 6062, -1, + 6064, 6063, 6065, -1, 6065, 6066, 6064, -1, + 6066, 6065, 6067, -1, 6067, 6068, 6066, -1, + 6068, 6067, 6069, -1, 6069, 6070, 6068, -1, + 6070, 6069, 6071, -1, 6071, 6072, 6070, -1, + 6072, 6071, 6073, -1, 6073, 6074, 6072, -1, + 6074, 6073, 6075, -1, 6075, 6076, 6074, -1, + 6076, 6075, 6077, -1, 6077, 6078, 6076, -1, + 6078, 6077, 6079, -1, 6079, 6080, 6078, -1, + 6080, 6079, 6081, -1, 6081, 6082, 6080, -1, + 6082, 6081, 6083, -1, 6083, 6084, 6082, -1, + 6084, 6083, 6085, -1, 6085, 6086, 6084, -1, + 6086, 6085, 6087, -1, 6087, 6088, 6086, -1, + 6088, 6087, 6089, -1, 6089, 6090, 6088, -1, + 6090, 6089, 6091, -1, 6091, 6092, 6090, -1, + 6092, 6091, 6093, -1, 6093, 6094, 6092, -1, + 6094, 6093, 6095, -1, 6095, 6096, 6094, -1, + 6096, 6095, 6097, -1, 6097, 6098, 6096, -1, + 6097, 6099, 6098, -1, 6097, 6100, 6099, -1, + 6100, 6097, 6095, -1, 6095, 6101, 6100, -1, + 6101, 6095, 6093, -1, 6093, 6102, 6101, -1, + 6102, 6093, 6091, -1, 6091, 6103, 6102, -1, + 6103, 6091, 6089, -1, 6089, 6104, 6103, -1, + 6104, 6089, 6087, -1, 6087, 6105, 6104, -1, + 6105, 6087, 6085, -1, 6085, 6106, 6105, -1, + 6106, 6085, 6083, -1, 6083, 6107, 6106, -1, + 6107, 6083, 6081, -1, 6081, 6108, 6107, -1, + 6108, 6081, 6079, -1, 6079, 6109, 6108, -1, + 6109, 6079, 6077, -1, 6077, 6110, 6109, -1, + 6110, 6077, 6075, -1, 6075, 6111, 6110, -1, + 6111, 6075, 6073, -1, 6073, 6112, 6111, -1, + 6112, 6073, 6071, -1, 6071, 6113, 6112, -1, + 6113, 6071, 6069, -1, 6069, 6114, 6113, -1, + 6114, 6069, 6067, -1, 6067, 6115, 6114, -1, + 6115, 6067, 6065, -1, 6065, 6116, 6115, -1, + 6116, 6065, 6063, -1, 6063, 6117, 6116, -1, + 6117, 6063, 6061, -1, 6061, 6118, 6117, -1, + 6118, 6061, 6059, -1, 6059, 6119, 6118, -1, + 6119, 6059, 6056, -1, 6119, 6056, 6054, -1, + 6054, 6120, 6119, -1, 6120, 6054, 6052, -1, + 6052, 6121, 6120, -1, 6121, 6052, 6050, -1, + 6050, 6122, 6121, -1, 6122, 6050, 6048, -1, + 6048, 6123, 6122, -1, 6123, 6048, 6046, -1, + 6046, 6124, 6123, -1, 6124, 6046, 6044, -1, + 6044, 6125, 6124, -1, 6125, 6044, 6042, -1, + 6042, 6126, 6125, -1, 6126, 6042, 6040, -1, + 6040, 6127, 6126, -1, 6127, 6040, 6038, -1, + 6038, 6128, 6127, -1, 6128, 6038, 6036, -1, + 6036, 6129, 6128, -1, 6129, 6036, 6034, -1, + 6034, 6130, 6129, -1, 6130, 6034, 6032, -1, + 6032, 6131, 6130, -1, 6131, 6032, 6030, -1, + 6030, 6132, 6131, -1, 6132, 6030, 6028, -1, + 6028, 6133, 6132, -1, 6133, 6028, 6026, -1, + 6026, 6134, 6133, -1, 6134, 6026, 6024, -1, + 6024, 6135, 6134, -1, 6135, 6024, 6022, -1, + 6022, 6136, 6135, -1, 6136, 6022, 6020, -1, + 6020, 6137, 6136, -1, 6137, 6020, 6018, -1, + 6018, 6138, 6137, -1, 6138, 6018, 6013, -1, + 6138, 6013, 5935, -1, 6138, 5935, 5938, -1, + 5938, 6137, 6138, -1, 6137, 5938, 5940, -1, + 5940, 6136, 6137, -1, 6136, 5940, 5942, -1, + 5942, 6135, 6136, -1, 6135, 5942, 5944, -1, + 5944, 6134, 6135, -1, 6134, 5944, 5946, -1, + 5946, 6133, 6134, -1, 6133, 5946, 5948, -1, + 5948, 6132, 6133, -1, 6132, 5948, 5950, -1, + 5950, 6131, 6132, -1, 6131, 5950, 5952, -1, + 5952, 6130, 6131, -1, 6130, 5952, 5954, -1, + 5954, 6129, 6130, -1, 6129, 5954, 5956, -1, + 5956, 6128, 6129, -1, 6128, 5956, 5958, -1, + 5958, 6127, 6128, -1, 6127, 5958, 5960, -1, + 5960, 6126, 6127, -1, 6126, 5960, 5962, -1, + 5962, 6125, 6126, -1, 6125, 5962, 5964, -1, + 5964, 6124, 6125, -1, 6124, 5964, 5966, -1, + 5966, 6123, 6124, -1, 6123, 5966, 5968, -1, + 5968, 6122, 6123, -1, 6122, 5968, 5970, -1, + 5970, 6121, 6122, -1, 6121, 5970, 5972, -1, + 5972, 6120, 6121, -1, 6120, 5972, 5974, -1, + 5974, 6119, 6120, -1, 5974, 6118, 6119, -1, + 6118, 5974, 5975, -1, 5975, 6117, 6118, -1, + 6117, 5975, 5977, -1, 5977, 6116, 6117, -1, + 6116, 5977, 5979, -1, 5979, 6115, 6116, -1, + 6115, 5979, 5981, -1, 5981, 6114, 6115, -1, + 6114, 5981, 5983, -1, 5983, 6113, 6114, -1, + 6113, 5983, 5985, -1, 5985, 6112, 6113, -1, + 6112, 5985, 5987, -1, 5987, 6111, 6112, -1, + 6111, 5987, 5989, -1, 5989, 6110, 6111, -1, + 6110, 5989, 5991, -1, 5991, 6109, 6110, -1, + 6109, 5991, 5993, -1, 5993, 6108, 6109, -1, + 6108, 5993, 5995, -1, 5995, 6107, 6108, -1, + 6107, 5995, 5997, -1, 5997, 6106, 6107, -1, + 6106, 5997, 5999, -1, 5999, 6105, 6106, -1, + 6105, 5999, 6001, -1, 6001, 6104, 6105, -1, + 6104, 6001, 6003, -1, 6003, 6103, 6104, -1, + 6103, 6003, 6005, -1, 6005, 6102, 6103, -1, + 6102, 6005, 6007, -1, 6007, 6101, 6102, -1, + 6101, 6007, 6009, -1, 6009, 6100, 6101, -1, + 6100, 6009, 6011, -1, 6011, 6099, 6100, -1, + 6099, 6011, 5934, -1, 5934, 5930, 6099, -1, + 5930, 6098, 6099, -1, 5930, 6139, 6098, -1, + 6139, 5930, 5929, -1, 6140, 6139, 5929, -1, + 6140, 6141, 6139, -1, 6140, 6142, 6141, -1, + 6140, 5929, 6142, -1, 6142, 5929, 5927, -1, + 6143, 6144, 6145, -1, 6144, 6143, 6146, -1, + 6143, 6147, 6146, -1, 6143, 6145, 6147, -1, + 6145, 6148, 6147, -1, 6148, 6145, 6149, -1, + 6149, 6150, 6148, -1, 6150, 6149, 6151, -1, + 6150, 6151, 6152, -1, 6153, 6154, 6155, -1, + 6155, 6156, 6153, -1, 6155, 6157, 6156, -1, + 6157, 6155, 6158, -1, 6158, 6159, 6157, -1, + 6159, 6158, 6160, -1, 6160, 6161, 6159, -1, + 6161, 6160, 6162, -1, 6162, 6163, 6161, -1, + 6163, 6162, 6164, -1, 6164, 6165, 6163, -1, + 6165, 6164, 6166, -1, 6166, 6167, 6165, -1, + 6167, 6166, 6168, -1, 6168, 6169, 6167, -1, + 6169, 6168, 6170, -1, 6170, 6171, 6169, -1, + 6171, 6170, 6172, -1, 6172, 6173, 6171, -1, + 6173, 6172, 6174, -1, 6174, 6175, 6173, -1, + 6175, 6174, 6176, -1, 6176, 6177, 6175, -1, + 6177, 6176, 6178, -1, 6178, 6179, 6177, -1, + 6179, 6178, 6180, -1, 6180, 6181, 6179, -1, + 6181, 6180, 6182, -1, 6182, 6183, 6181, -1, + 6183, 6182, 6184, -1, 6184, 6185, 6183, -1, + 6185, 6184, 6186, -1, 6186, 6187, 6185, -1, + 6187, 6186, 6188, -1, 6188, 6189, 6187, -1, + 6189, 6188, 6190, -1, 6190, 6191, 6189, -1, + 6191, 6190, 6192, -1, 6192, 6193, 6191, -1, + 6193, 6192, 6194, -1, 6194, 6195, 6193, -1, + 6195, 6194, 6196, -1, 6196, 6197, 6195, -1, + 6197, 6196, 6198, -1, 6198, 6151, 6197, -1, + 6198, 6152, 6151, -1, 6198, 6199, 6152, -1, + 6199, 6198, 6196, -1, 6196, 6200, 6199, -1, + 6200, 6196, 6194, -1, 6194, 6201, 6200, -1, + 6201, 6194, 6192, -1, 6192, 6202, 6201, -1, + 6202, 6192, 6190, -1, 6190, 6203, 6202, -1, + 6203, 6190, 6188, -1, 6188, 6204, 6203, -1, + 6204, 6188, 6186, -1, 6186, 6205, 6204, -1, + 6205, 6186, 6184, -1, 6184, 6206, 6205, -1, + 6206, 6184, 6182, -1, 6182, 6207, 6206, -1, + 6207, 6182, 6180, -1, 6180, 6208, 6207, -1, + 6208, 6180, 6178, -1, 6178, 6209, 6208, -1, + 6209, 6178, 6176, -1, 6176, 6210, 6209, -1, + 6210, 6176, 6174, -1, 6174, 6211, 6210, -1, + 6211, 6174, 6172, -1, 6172, 6212, 6211, -1, + 6212, 6172, 6170, -1, 6170, 6213, 6212, -1, + 6213, 6170, 6168, -1, 6168, 6214, 6213, -1, + 6214, 6168, 6166, -1, 6166, 6215, 6214, -1, + 6215, 6166, 6164, -1, 6164, 6216, 6215, -1, + 6216, 6164, 6162, -1, 6162, 6217, 6216, -1, + 6217, 6162, 6160, -1, 6160, 6218, 6217, -1, + 6218, 6160, 6158, -1, 6158, 6219, 6218, -1, + 6219, 6158, 6155, -1, 6155, 6154, 6219, -1, + 6220, 6221, 6222, -1, 6222, 6223, 6220, -1, + 6223, 6222, 6224, -1, 6224, 6225, 6223, -1, + 6225, 6224, 6226, -1, 6226, 6227, 6225, -1, + 6227, 6226, 6228, -1, 6228, 6229, 6227, -1, + 6229, 6228, 6230, -1, 6230, 6231, 6229, -1, + 6231, 6230, 6232, -1, 6232, 6233, 6231, -1, + 6233, 6232, 6234, -1, 6234, 6235, 6233, -1, + 6235, 6234, 6236, -1, 6236, 6237, 6235, -1, + 6237, 6236, 6238, -1, 6238, 6239, 6237, -1, + 6239, 6238, 6240, -1, 6240, 6241, 6239, -1, + 6241, 6240, 6242, -1, 6242, 6243, 6241, -1, + 6243, 6242, 6244, -1, 6244, 6245, 6243, -1, + 6245, 6244, 6246, -1, 6246, 6247, 6245, -1, + 6247, 6246, 6248, -1, 6248, 6249, 6247, -1, + 6249, 6248, 6250, -1, 6250, 6251, 6249, -1, + 6251, 6250, 6252, -1, 6252, 6253, 6251, -1, + 6253, 6252, 6254, -1, 6254, 6255, 6253, -1, + 6255, 6254, 6256, -1, 6256, 6257, 6255, -1, + 6257, 6256, 6258, -1, 6258, 6259, 6257, -1, + 6259, 6258, 6219, -1, 6259, 6219, 6154, -1, + 6259, 6154, 6260, -1, 6260, 6257, 6259, -1, + 6257, 6260, 6261, -1, 6261, 6255, 6257, -1, + 6255, 6261, 6262, -1, 6262, 6253, 6255, -1, + 6253, 6262, 6263, -1, 6263, 6251, 6253, -1, + 6251, 6263, 6264, -1, 6264, 6249, 6251, -1, + 6249, 6264, 6265, -1, 6265, 6247, 6249, -1, + 6247, 6265, 6266, -1, 6266, 6245, 6247, -1, + 6245, 6266, 6267, -1, 6267, 6243, 6245, -1, + 6243, 6267, 6268, -1, 6268, 6241, 6243, -1, + 6241, 6268, 6269, -1, 6269, 6239, 6241, -1, + 6239, 6269, 6270, -1, 6270, 6237, 6239, -1, + 6237, 6270, 6271, -1, 6271, 6235, 6237, -1, + 6235, 6271, 6272, -1, 6272, 6233, 6235, -1, + 6233, 6272, 6273, -1, 6273, 6231, 6233, -1, + 6231, 6273, 6274, -1, 6274, 6229, 6231, -1, + 6229, 6274, 6275, -1, 6275, 6227, 6229, -1, + 6227, 6275, 6276, -1, 6276, 6225, 6227, -1, + 6225, 6276, 6277, -1, 6277, 6223, 6225, -1, + 6223, 6277, 6278, -1, 6278, 6220, 6223, -1, + 6278, 6279, 6220, -1, 6278, 6280, 6279, -1, + 6280, 6278, 6277, -1, 6277, 6281, 6280, -1, + 6281, 6277, 6276, -1, 6276, 6282, 6281, -1, + 6282, 6276, 6275, -1, 6275, 6283, 6282, -1, + 6283, 6275, 6274, -1, 6274, 6284, 6283, -1, + 6284, 6274, 6273, -1, 6273, 6285, 6284, -1, + 6285, 6273, 6272, -1, 6272, 6286, 6285, -1, + 6286, 6272, 6271, -1, 6271, 6287, 6286, -1, + 6287, 6271, 6270, -1, 6270, 6288, 6287, -1, + 6288, 6270, 6269, -1, 6269, 6289, 6288, -1, + 6289, 6269, 6268, -1, 6268, 6290, 6289, -1, + 6290, 6268, 6267, -1, 6267, 6291, 6290, -1, + 6291, 6267, 6266, -1, 6266, 6292, 6291, -1, + 6292, 6266, 6265, -1, 6265, 6293, 6292, -1, + 6293, 6265, 6264, -1, 6264, 6294, 6293, -1, + 6294, 6264, 6263, -1, 6263, 6295, 6294, -1, + 6295, 6263, 6262, -1, 6262, 6296, 6295, -1, + 6296, 6262, 6261, -1, 6261, 6297, 6296, -1, + 6297, 6261, 6260, -1, 6260, 6298, 6297, -1, + 6298, 6260, 6154, -1, 6154, 6153, 6298, -1, + 6299, 6298, 6153, -1, 6153, 6300, 6299, -1, + 6300, 6153, 6156, -1, 6156, 6301, 6300, -1, + 6156, 6302, 6301, -1, 6302, 6156, 6157, -1, + 6157, 6303, 6302, -1, 6303, 6157, 6159, -1, + 6303, 6159, 6304, -1, 6305, 6306, 6307, -1, + 6306, 6305, 6308, -1, 6308, 6309, 6306, -1, + 6309, 6308, 6310, -1, 6310, 6311, 6309, -1, + 6311, 6310, 6312, -1, 6311, 6312, 6313, -1, + 6314, 6313, 6312, -1, 6314, 6315, 6313, -1, + 6315, 6314, 6316, -1, 6316, 6317, 6315, -1, + 6317, 6316, 6318, -1, 6318, 6319, 6317, -1, + 6319, 6318, 6320, -1, 6320, 6321, 6319, -1, + 6321, 6320, 6322, -1, 6322, 6323, 6321, -1, + 6323, 6322, 6324, -1, 6324, 6325, 6323, -1, + 6325, 6324, 6326, -1, 6326, 6327, 6325, -1, + 6327, 6326, 6328, -1, 6328, 6329, 6327, -1, + 6329, 6328, 6330, -1, 6330, 6331, 6329, -1, + 6331, 6330, 6332, -1, 6332, 6333, 6331, -1, + 6333, 6332, 6334, -1, 6334, 6335, 6333, -1, + 6335, 6334, 6336, -1, 6336, 6337, 6335, -1, + 6337, 6336, 6338, -1, 6338, 6339, 6337, -1, + 6339, 6338, 6340, -1, 6340, 6341, 6339, -1, + 6341, 6340, 6342, -1, 6342, 6343, 6341, -1, + 6343, 6342, 6344, -1, 6344, 6345, 6343, -1, + 6345, 6344, 6346, -1, 6346, 6347, 6345, -1, + 6347, 6346, 6348, -1, 6348, 6349, 6347, -1, + 6349, 6348, 6350, -1, 6350, 6351, 6349, -1, + 6351, 6350, 6304, -1, 6351, 6304, 6159, -1, + 6351, 6159, 6161, -1, 6161, 6349, 6351, -1, + 6349, 6161, 6163, -1, 6163, 6347, 6349, -1, + 6347, 6163, 6165, -1, 6165, 6345, 6347, -1, + 6345, 6165, 6167, -1, 6167, 6343, 6345, -1, + 6343, 6167, 6169, -1, 6169, 6341, 6343, -1, + 6341, 6169, 6171, -1, 6171, 6339, 6341, -1, + 6339, 6171, 6173, -1, 6173, 6337, 6339, -1, + 6337, 6173, 6175, -1, 6175, 6335, 6337, -1, + 6335, 6175, 6177, -1, 6177, 6333, 6335, -1, + 6333, 6177, 6179, -1, 6179, 6331, 6333, -1, + 6331, 6179, 6181, -1, 6181, 6329, 6331, -1, + 6329, 6181, 6183, -1, 6183, 6327, 6329, -1, + 6327, 6183, 6185, -1, 6185, 6325, 6327, -1, + 6325, 6185, 6187, -1, 6187, 6323, 6325, -1, + 6323, 6187, 6189, -1, 6189, 6321, 6323, -1, + 6321, 6189, 6191, -1, 6191, 6319, 6321, -1, + 6319, 6191, 6193, -1, 6193, 6317, 6319, -1, + 6317, 6193, 6195, -1, 6195, 6315, 6317, -1, + 6315, 6195, 6197, -1, 6197, 6313, 6315, -1, + 6313, 6197, 6151, -1, 6151, 6311, 6313, -1, + 6311, 6151, 6149, -1, 6149, 6309, 6311, -1, + 6309, 6149, 6145, -1, 6145, 6306, 6309, -1, + 6306, 6145, 6144, -1, 6352, 6306, 6144, -1, + 6352, 6144, 6146, -1, 6352, 6146, 6353, -1, + 6353, 6306, 6352, -1, 6353, 6307, 6306, -1, + 6353, 6146, 6307, -1, 6307, 6146, 6354, -1, + 6354, 6305, 6307, -1, 6354, 6355, 6305, -1, + 6356, 6357, 6355, -1, 6357, 6305, 6355, -1, + 6305, 6357, 6358, -1, 6358, 6308, 6305, -1, + 6308, 6358, 6359, -1, 6359, 6310, 6308, -1, + 6310, 6359, 6360, -1, 6360, 6312, 6310, -1, + 6312, 6360, 6361, -1, 6362, 6361, 6360, -1, + 6360, 6363, 6362, -1, 6363, 6360, 6359, -1, + 6359, 6364, 6363, -1, 6364, 6359, 6358, -1, + 6358, 6365, 6364, -1, 6365, 6358, 6357, -1, + 6357, 6366, 6365, -1, 6366, 6357, 6367, -1, + 6367, 6368, 6369, -1, 6368, 6367, 6357, -1, + 6368, 6357, 6356, -1, 6356, 6369, 6368, -1, + 6356, 6355, 6369, -1, 6355, 6354, 6369, -1, + 6369, 6354, 6146, -1, 6142, 6146, 6147, -1, + 6147, 6370, 6142, -1, 6370, 6147, 6148, -1, + 6370, 6148, 6371, -1, 6371, 6142, 6370, -1, + 6371, 6141, 6142, -1, 6371, 6148, 6141, -1, + 6148, 6139, 6141, -1, 6139, 6148, 6150, -1, + 6150, 6098, 6139, -1, 6098, 6150, 6152, -1, + 6152, 6096, 6098, -1, 6096, 6152, 6199, -1, + 6199, 6094, 6096, -1, 6094, 6199, 6200, -1, + 6200, 6092, 6094, -1, 6092, 6200, 6201, -1, + 6201, 6090, 6092, -1, 6090, 6201, 6202, -1, + 6202, 6088, 6090, -1, 6088, 6202, 6203, -1, + 6203, 6086, 6088, -1, 6086, 6203, 6204, -1, + 6204, 6084, 6086, -1, 6084, 6204, 6205, -1, + 6205, 6082, 6084, -1, 6082, 6205, 6206, -1, + 6206, 6080, 6082, -1, 6080, 6206, 6207, -1, + 6207, 6078, 6080, -1, 6078, 6207, 6208, -1, + 6208, 6076, 6078, -1, 6076, 6208, 6209, -1, + 6209, 6074, 6076, -1, 6074, 6209, 6210, -1, + 6210, 6072, 6074, -1, 6072, 6210, 6211, -1, + 6211, 6070, 6072, -1, 6070, 6211, 6212, -1, + 6212, 6068, 6070, -1, 6068, 6212, 6213, -1, + 6213, 6066, 6068, -1, 6066, 6213, 6214, -1, + 6214, 6064, 6066, -1, 6064, 6214, 6215, -1, + 6215, 6062, 6064, -1, 6062, 6215, 6216, -1, + 6216, 6060, 6062, -1, 6060, 6216, 6217, -1, + 6217, 6058, 6060, -1, 6058, 6217, 6218, -1, + 6218, 6057, 6058, -1, 6057, 6218, 6219, -1, + 6057, 6219, 6258, -1, 6258, 6055, 6057, -1, + 6055, 6258, 6256, -1, 6256, 6053, 6055, -1, + 6053, 6256, 6254, -1, 6254, 6051, 6053, -1, + 6051, 6254, 6252, -1, 6252, 6049, 6051, -1, + 6049, 6252, 6250, -1, 6250, 6047, 6049, -1, + 6047, 6250, 6248, -1, 6248, 6045, 6047, -1, + 6045, 6248, 6246, -1, 6246, 6043, 6045, -1, + 6043, 6246, 6244, -1, 6244, 6041, 6043, -1, + 6041, 6244, 6242, -1, 6242, 6039, 6041, -1, + 6039, 6242, 6240, -1, 6240, 6037, 6039, -1, + 6037, 6240, 6238, -1, 6238, 6035, 6037, -1, + 6035, 6238, 6236, -1, 6236, 6033, 6035, -1, + 6033, 6236, 6234, -1, 6234, 6031, 6033, -1, + 6031, 6234, 6232, -1, 6232, 6029, 6031, -1, + 6029, 6232, 6230, -1, 6230, 6027, 6029, -1, + 6027, 6230, 6228, -1, 6228, 6025, 6027, -1, + 6025, 6228, 6226, -1, 6226, 6023, 6025, -1, + 6023, 6226, 6224, -1, 6224, 6021, 6023, -1, + 6021, 6224, 6222, -1, 6222, 6019, 6021, -1, + 6019, 6222, 6221, -1, 6221, 838, 6019, -1, + 6221, 839, 838, -1, 6221, 6220, 839, -1, + 839, 6220, 6279, -1, 839, 6279, 6372, -1, + 6372, 840, 839, -1, 840, 6372, 6373, -1, + 6373, 842, 840, -1, 842, 6373, 6374, -1, + 6374, 845, 842, -1, 6375, 6374, 6376, -1, + 6375, 845, 6374, -1, 6375, 836, 845, -1, + 6375, 6376, 836, -1, 6377, 836, 6376, -1, + 6377, 6378, 836, -1, 6378, 834, 836, -1, + 6378, 851, 834, -1, 6378, 6377, 851, -1, + 6377, 6376, 851, -1, 851, 6376, 6374, -1, + 6374, 853, 851, -1, 853, 6374, 6373, -1, + 6373, 855, 853, -1, 855, 6373, 6372, -1, + 6372, 831, 855, -1, 831, 6372, 6279, -1, + 6279, 832, 831, -1, 832, 6279, 6280, -1, + 6280, 6379, 832, -1, 6379, 6280, 6281, -1, + 6281, 6380, 6379, -1, 6380, 6281, 6282, -1, + 6282, 6381, 6380, -1, 6381, 6282, 6283, -1, + 6283, 6382, 6381, -1, 6382, 6283, 6284, -1, + 6284, 6383, 6382, -1, 6383, 6284, 6285, -1, + 6285, 6384, 6383, -1, 6384, 6285, 6286, -1, + 6286, 6385, 6384, -1, 6385, 6286, 6287, -1, + 6287, 6386, 6385, -1, 6386, 6287, 6288, -1, + 6288, 6387, 6386, -1, 6387, 6288, 6289, -1, + 6289, 6388, 6387, -1, 6388, 6289, 6290, -1, + 6290, 6389, 6388, -1, 6389, 6290, 6291, -1, + 6291, 6390, 6389, -1, 6390, 6291, 6292, -1, + 6292, 6391, 6390, -1, 6391, 6292, 6293, -1, + 6293, 6392, 6391, -1, 6392, 6293, 6294, -1, + 6294, 6393, 6392, -1, 6393, 6294, 6295, -1, + 6295, 6394, 6393, -1, 6394, 6295, 6296, -1, + 6296, 6395, 6394, -1, 6395, 6296, 6297, -1, + 6297, 6396, 6395, -1, 6396, 6297, 6298, -1, + 6298, 6299, 6396, -1, 6397, 6396, 6299, -1, + 6396, 6397, 6398, -1, 6398, 6395, 6396, -1, + 6395, 6398, 6399, -1, 6399, 6394, 6395, -1, + 6394, 6399, 6400, -1, 6400, 6393, 6394, -1, + 6393, 6400, 6401, -1, 6401, 6392, 6393, -1, + 6392, 6401, 6402, -1, 6402, 6391, 6392, -1, + 6391, 6402, 6403, -1, 6403, 6390, 6391, -1, + 6390, 6403, 6404, -1, 6404, 6389, 6390, -1, + 6389, 6404, 6405, -1, 6405, 6388, 6389, -1, + 6388, 6405, 6406, -1, 6406, 6387, 6388, -1, + 6387, 6406, 6407, -1, 6407, 6386, 6387, -1, + 6386, 6407, 6408, -1, 6408, 6385, 6386, -1, + 6385, 6408, 6409, -1, 6409, 6384, 6385, -1, + 6384, 6409, 6410, -1, 6410, 6383, 6384, -1, + 6383, 6410, 6411, -1, 6411, 6382, 6383, -1, + 6382, 6411, 6412, -1, 6412, 6381, 6382, -1, + 6381, 6412, 6413, -1, 6413, 6380, 6381, -1, + 6380, 6413, 6414, -1, 6414, 6379, 6380, -1, + 6379, 6414, 6415, -1, 6415, 832, 6379, -1, + 6415, 833, 832, -1, 6415, 1111, 833, -1, + 1111, 6415, 6414, -1, 6414, 6416, 1111, -1, + 6416, 6414, 6413, -1, 6413, 6417, 6416, -1, + 6417, 6413, 6412, -1, 6412, 6418, 6417, -1, + 6418, 6412, 6411, -1, 6411, 6419, 6418, -1, + 6419, 6411, 6410, -1, 6410, 6420, 6419, -1, + 6420, 6410, 6409, -1, 6409, 6421, 6420, -1, + 6421, 6409, 6408, -1, 6408, 6422, 6421, -1, + 6422, 6408, 6407, -1, 6407, 6423, 6422, -1, + 6423, 6407, 6406, -1, 6406, 6424, 6423, -1, + 6424, 6406, 6405, -1, 6405, 6425, 6424, -1, + 6425, 6405, 6404, -1, 6404, 6426, 6425, -1, + 6426, 6404, 6403, -1, 6403, 6427, 6426, -1, + 6427, 6403, 6402, -1, 6402, 6428, 6427, -1, + 6428, 6402, 6401, -1, 6401, 6429, 6428, -1, + 6429, 6401, 6400, -1, 6400, 6430, 6429, -1, + 6430, 6400, 6399, -1, 6399, 6431, 6430, -1, + 6431, 6399, 6398, -1, 6398, 6432, 6431, -1, + 6432, 6398, 6397, -1, 6397, 6433, 6432, -1, + 6397, 6299, 6433, -1, 6434, 6433, 6299, -1, + 6434, 6299, 6300, -1, 6300, 6435, 6434, -1, + 6435, 6300, 6301, -1, 6301, 6436, 6435, -1, + 6301, 6437, 6436, -1, 6437, 6301, 6302, -1, + 6302, 6438, 6437, -1, 6438, 6302, 6303, -1, + 6303, 6439, 6438, -1, 6439, 6303, 6304, -1, + 6304, 6440, 6439, -1, 6440, 6304, 6350, -1, + 6350, 6441, 6440, -1, 6441, 6350, 6348, -1, + 6348, 6442, 6441, -1, 6442, 6348, 6346, -1, + 6346, 6443, 6442, -1, 6443, 6346, 6344, -1, + 6344, 6444, 6443, -1, 6444, 6344, 6342, -1, + 6342, 6445, 6444, -1, 6445, 6342, 6340, -1, + 6340, 6446, 6445, -1, 6446, 6340, 6338, -1, + 6338, 6447, 6446, -1, 6447, 6338, 6336, -1, + 6336, 6448, 6447, -1, 6448, 6336, 6334, -1, + 6334, 6449, 6448, -1, 6449, 6334, 6332, -1, + 6332, 6450, 6449, -1, 6450, 6332, 6330, -1, + 6330, 6451, 6450, -1, 6451, 6330, 6328, -1, + 6328, 6452, 6451, -1, 6452, 6328, 6326, -1, + 6326, 6453, 6452, -1, 6453, 6326, 6324, -1, + 6324, 6454, 6453, -1, 6454, 6324, 6322, -1, + 6322, 6455, 6454, -1, 6455, 6322, 6320, -1, + 6320, 6456, 6455, -1, 6456, 6320, 6318, -1, + 6318, 6457, 6456, -1, 6457, 6318, 6316, -1, + 6316, 6458, 6457, -1, 6458, 6316, 6314, -1, + 6314, 6312, 6458, -1, 6312, 6361, 6458, -1, + 6459, 6460, 6461, -1, 6460, 6459, 6462, -1, + 6462, 6463, 6460, -1, 6463, 6462, 6464, -1, + 6464, 6465, 6463, -1, 6465, 6464, 6466, -1, + 6466, 6467, 6465, -1, 6467, 6466, 6468, -1, + 6468, 6469, 6467, -1, 6469, 6468, 6470, -1, + 6470, 6471, 6469, -1, 6471, 6470, 6472, -1, + 6472, 6473, 6471, -1, 6473, 6472, 6474, -1, + 6474, 6475, 6473, -1, 6475, 6474, 6476, -1, + 6476, 6477, 6475, -1, 6477, 6476, 6478, -1, + 6478, 6479, 6477, -1, 6479, 6478, 6480, -1, + 6480, 6481, 6479, -1, 6481, 6480, 6482, -1, + 6482, 6483, 6481, -1, 6483, 6482, 6484, -1, + 6484, 6485, 6483, -1, 6485, 6484, 6486, -1, + 6486, 6487, 6485, -1, 6487, 6486, 6488, -1, + 6488, 6489, 6487, -1, 6489, 6488, 6490, -1, + 6490, 6491, 6489, -1, 6491, 6490, 6492, -1, + 6492, 6493, 6491, -1, 6493, 6492, 6494, -1, + 6494, 6495, 6493, -1, 6495, 6494, 6496, -1, + 6496, 6361, 6495, -1, 6496, 6458, 6361, -1, + 6496, 6457, 6458, -1, 6457, 6496, 6494, -1, + 6494, 6456, 6457, -1, 6456, 6494, 6492, -1, + 6492, 6455, 6456, -1, 6455, 6492, 6490, -1, + 6490, 6454, 6455, -1, 6454, 6490, 6488, -1, + 6488, 6453, 6454, -1, 6453, 6488, 6486, -1, + 6486, 6452, 6453, -1, 6452, 6486, 6484, -1, + 6484, 6451, 6452, -1, 6451, 6484, 6482, -1, + 6482, 6450, 6451, -1, 6450, 6482, 6480, -1, + 6480, 6449, 6450, -1, 6449, 6480, 6478, -1, + 6478, 6448, 6449, -1, 6448, 6478, 6476, -1, + 6476, 6447, 6448, -1, 6447, 6476, 6474, -1, + 6474, 6446, 6447, -1, 6446, 6474, 6472, -1, + 6472, 6445, 6446, -1, 6445, 6472, 6470, -1, + 6470, 6444, 6445, -1, 6444, 6470, 6468, -1, + 6468, 6443, 6444, -1, 6443, 6468, 6466, -1, + 6466, 6442, 6443, -1, 6442, 6466, 6464, -1, + 6464, 6441, 6442, -1, 6441, 6464, 6462, -1, + 6462, 6440, 6441, -1, 6440, 6462, 6459, -1, + 6459, 6439, 6440, -1, 6459, 6461, 6439, -1, + 6497, 6439, 6461, -1, 6497, 6438, 6439, -1, + 6438, 6497, 6498, -1, 6498, 6437, 6438, -1, + 6437, 6498, 6499, -1, 6499, 6436, 6437, -1, + 6436, 6499, 6500, -1, 6436, 6500, 6501, -1, + 6501, 6435, 6436, -1, 6435, 6501, 6502, -1, + 6502, 6434, 6435, -1, 6434, 6502, 6503, -1, + 6503, 6433, 6434, -1, 6433, 6503, 6504, -1, + 6504, 6432, 6433, -1, 6432, 6504, 6505, -1, + 6505, 6431, 6432, -1, 6431, 6505, 6506, -1, + 6506, 6430, 6431, -1, 6430, 6506, 6507, -1, + 6507, 6429, 6430, -1, 6429, 6507, 6508, -1, + 6508, 6428, 6429, -1, 6428, 6508, 6509, -1, + 6509, 6427, 6428, -1, 6427, 6509, 6510, -1, + 6510, 6426, 6427, -1, 6426, 6510, 6511, -1, + 6511, 6425, 6426, -1, 6425, 6511, 6512, -1, + 6512, 6424, 6425, -1, 6424, 6512, 6513, -1, + 6513, 6423, 6424, -1, 6423, 6513, 6514, -1, + 6514, 6422, 6423, -1, 6422, 6514, 6515, -1, + 6515, 6421, 6422, -1, 6421, 6515, 6516, -1, + 6516, 6420, 6421, -1, 6420, 6516, 6517, -1, + 6517, 6419, 6420, -1, 6419, 6517, 6518, -1, + 6518, 6418, 6419, -1, 6418, 6518, 6519, -1, + 6519, 6417, 6418, -1, 6417, 6519, 6520, -1, + 6520, 6416, 6417, -1, 6416, 6520, 6521, -1, + 6521, 1111, 6416, -1, 6521, 1110, 1111, -1, + 6521, 1109, 1110, -1, 1109, 6521, 6520, -1, + 6520, 1108, 1109, -1, 1108, 6520, 6519, -1, + 6519, 1107, 1108, -1, 1107, 6519, 6518, -1, + 6518, 1106, 1107, -1, 1106, 6518, 6517, -1, + 6517, 1105, 1106, -1, 1105, 6517, 6516, -1, + 6516, 1104, 1105, -1, 1104, 6516, 6515, -1, + 6515, 1103, 1104, -1, 1103, 6515, 6514, -1, + 6514, 1102, 1103, -1, 1102, 6514, 6513, -1, + 6513, 1101, 1102, -1, 1101, 6513, 6512, -1, + 6512, 1100, 1101, -1, 1100, 6512, 6511, -1, + 6511, 1099, 1100, -1, 1099, 6511, 6510, -1, + 6510, 1098, 1099, -1, 1098, 6510, 6509, -1, + 6509, 1097, 1098, -1, 1097, 6509, 6508, -1, + 6508, 1096, 1097, -1, 1096, 6508, 6507, -1, + 6507, 1095, 1096, -1, 1095, 6507, 6506, -1, + 6506, 1094, 1095, -1, 1094, 6506, 6505, -1, + 6505, 1093, 1094, -1, 1093, 6505, 6504, -1, + 6504, 1002, 1093, -1, 1002, 6504, 6503, -1, + 6503, 1003, 1002, -1, 1003, 6503, 6502, -1, + 6502, 1005, 1003, -1, 1005, 6502, 6501, -1, + 6501, 1007, 1005, -1, 1007, 6501, 6500, -1, + 6500, 1009, 1007, -1, 6500, 1012, 1009, -1, + 1012, 6500, 6499, -1, 6499, 1014, 1012, -1, + 1014, 6499, 6498, -1, 6498, 1016, 1014, -1, + 1016, 6498, 6497, -1, 6497, 1018, 1016, -1, + 1018, 6497, 6461, -1, 6461, 1020, 1018, -1, + 1020, 6461, 6460, -1, 6460, 1022, 1020, -1, + 1022, 6460, 6463, -1, 6463, 1024, 1022, -1, + 1024, 6463, 6465, -1, 6465, 1026, 1024, -1, + 1026, 6465, 6467, -1, 6467, 1028, 1026, -1, + 1028, 6467, 6469, -1, 6469, 1030, 1028, -1, + 1030, 6469, 6471, -1, 6471, 1032, 1030, -1, + 1032, 6471, 6473, -1, 6473, 1034, 1032, -1, + 1034, 6473, 6475, -1, 6475, 1036, 1034, -1, + 1036, 6475, 6477, -1, 6477, 1038, 1036, -1, + 1038, 6477, 6479, -1, 6479, 1040, 1038, -1, + 1040, 6479, 6481, -1, 6481, 1042, 1040, -1, + 1042, 6481, 6483, -1, 6483, 1044, 1042, -1, + 1044, 6483, 6485, -1, 6485, 1046, 1044, -1, + 1046, 6485, 6487, -1, 6487, 1048, 1046, -1, + 1048, 6487, 6489, -1, 6489, 1050, 1048, -1, + 1050, 6489, 6491, -1, 6491, 1052, 1050, -1, + 1052, 6491, 6493, -1, 6493, 1054, 1052, -1, + 1054, 6493, 6495, -1, 6495, 1056, 1054, -1, + 1056, 6495, 6361, -1, 6361, 6362, 1056, -1, + 6362, 999, 1056, -1, 6362, 6522, 999, -1, + 6522, 6362, 6363, -1, 6363, 6523, 6522, -1, + 6523, 6363, 6364, -1, 6364, 6524, 6523, -1, + 6524, 6364, 6365, -1, 6365, 6525, 6524, -1, + 6525, 6365, 6366, -1, 6366, 6526, 6525, -1, + 6526, 6366, 6527, -1, 6528, 6526, 6527, -1, + 6528, 6529, 6526, -1, 6529, 6530, 6526, -1, + 6529, 6531, 6530, -1, 6529, 6528, 6531, -1, + 6528, 6527, 6531, -1, 6527, 6532, 6531, -1, + 6532, 6527, 6366, -1, 6532, 6366, 6367, -1, + 6532, 6367, 6369, -1, 6369, 6531, 6532, -1, + 6533, 6534, 6535, -1, 6535, 6536, 6533, -1, + 6536, 6535, 6537, -1, 6537, 6538, 6536, -1, + 6538, 6537, 6539, -1, 6539, 6540, 6538, -1, + 6540, 6539, 6541, -1, 6541, 6542, 6540, -1, + 6542, 6541, 6543, -1, 6543, 6544, 6542, -1, + 6544, 6543, 6545, -1, 6545, 6546, 6544, -1, + 6546, 6545, 6547, -1, 6547, 6548, 6546, -1, + 6549, 6550, 6551, -1, 6551, 6552, 6549, -1, + 6552, 6551, 6553, -1, 6553, 6554, 6552, -1, + 6554, 6553, 6555, -1, 6555, 6556, 6554, -1, + 6556, 6555, 6557, -1, 6557, 6558, 6556, -1, + 6558, 6557, 6559, -1, 6559, 6560, 6558, -1, + 6560, 6559, 6561, -1, 6561, 6562, 6560, -1, + 6562, 6561, 6563, -1, 6564, 6563, 6561, -1, + 6563, 6564, 6565, -1, 6566, 6567, 6568, -1, + 6566, 6565, 6567, -1, 6566, 6569, 6565, -1, + 6569, 6566, 6568, -1, 6569, 6568, 6570, -1, + 6570, 6565, 6569, -1, 6570, 6571, 6565, -1, + 6571, 6563, 6565, -1, 6571, 6562, 6563, -1, + 6571, 6570, 6562, -1, 6562, 6570, 6568, -1, + 6562, 6568, 6572, -1, 6572, 6560, 6562, -1, + 6560, 6572, 6573, -1, 6573, 6558, 6560, -1, + 6558, 6573, 6574, -1, 6574, 6556, 6558, -1, + 6556, 6574, 6575, -1, 6575, 6554, 6556, -1, + 6554, 6575, 6576, -1, 6576, 6552, 6554, -1, + 6552, 6576, 6577, -1, 6577, 6549, 6552, -1, + 6578, 6579, 6549, -1, 6549, 6577, 6578, -1, + 6580, 6581, 6582, -1, 6582, 6583, 6580, -1, + 6583, 6582, 6584, -1, 6584, 6585, 6583, -1, + 6585, 6584, 6586, -1, 6586, 6587, 6585, -1, + 6587, 6586, 6588, -1, 6588, 6589, 6587, -1, + 6589, 6588, 6590, -1, 6590, 6591, 6589, -1, + 6591, 6590, 6592, -1, 6592, 6593, 6591, -1, + 6593, 6592, 6594, -1, 6594, 6595, 6593, -1, + 6595, 6594, 6596, -1, 6596, 6597, 6595, -1, + 6597, 6596, 6598, -1, 6598, 6599, 6597, -1, + 6599, 6598, 6600, -1, 6600, 6601, 6599, -1, + 6601, 6600, 6602, -1, 6602, 6603, 6601, -1, + 6603, 6602, 6604, -1, 6604, 6605, 6603, -1, + 6605, 6604, 6606, -1, 6607, 6608, 6609, -1, + 6609, 6610, 6607, -1, 6610, 6609, 6611, -1, + 6611, 6612, 6610, -1, 6612, 6611, 6613, -1, + 6613, 6614, 6612, -1, 6614, 6613, 6615, -1, + 6615, 6616, 6614, -1, 6616, 6615, 6617, -1, + 6617, 6618, 6616, -1, 6618, 6617, 6619, -1, + 6619, 6620, 6618, -1, 6620, 6619, 6621, -1, + 6621, 6622, 6620, -1, 6622, 6621, 6623, -1, + 6623, 6624, 6622, -1, 6624, 6623, 6625, -1, + 6625, 6626, 6624, -1, 6626, 6625, 6627, -1, + 6627, 6628, 6626, -1, 6628, 6627, 6629, -1, + 6629, 6630, 6628, -1, 6630, 6629, 6631, -1, + 6631, 6632, 6630, -1, 6632, 6631, 6633, -1, + 6634, 6635, 6636, -1, 6635, 6634, 6637, -1, + 6637, 6638, 6635, -1, 6638, 6637, 6639, -1, + 6639, 6640, 6638, -1, 6640, 6639, 6641, -1, + 6641, 6642, 6640, -1, 6642, 6641, 6643, -1, + 6643, 6644, 6642, -1, 6644, 6643, 6633, -1, + 6633, 6606, 6644, -1, 6606, 6633, 6631, -1, + 6631, 6605, 6606, -1, 6605, 6631, 6629, -1, + 6629, 6603, 6605, -1, 6603, 6629, 6627, -1, + 6627, 6601, 6603, -1, 6601, 6627, 6625, -1, + 6625, 6599, 6601, -1, 6599, 6625, 6623, -1, + 6623, 6597, 6599, -1, 6597, 6623, 6621, -1, + 6621, 6595, 6597, -1, 6595, 6621, 6619, -1, + 6619, 6593, 6595, -1, 6593, 6619, 6617, -1, + 6617, 6591, 6593, -1, 6591, 6617, 6615, -1, + 6615, 6589, 6591, -1, 6589, 6615, 6613, -1, + 6613, 6587, 6589, -1, 6587, 6613, 6611, -1, + 6611, 6585, 6587, -1, 6585, 6611, 6609, -1, + 6609, 6583, 6585, -1, 6583, 6609, 6608, -1, + 6608, 6580, 6583, -1, 6608, 6645, 6580, -1, + 6608, 6607, 6645, -1, 6646, 6645, 6607, -1, + 6607, 6647, 6646, -1, 6647, 6607, 6610, -1, + 6610, 6648, 6647, -1, 6648, 6610, 6612, -1, + 6612, 6649, 6648, -1, 6649, 6612, 6614, -1, + 6614, 6650, 6649, -1, 6650, 6614, 6616, -1, + 6616, 6651, 6650, -1, 6651, 6616, 6618, -1, + 6618, 6652, 6651, -1, 6652, 6618, 6620, -1, + 6620, 6653, 6652, -1, 6653, 6620, 6622, -1, + 6622, 6654, 6653, -1, 6654, 6622, 6624, -1, + 6624, 6655, 6654, -1, 6655, 6624, 6626, -1, + 6626, 6656, 6655, -1, 6656, 6626, 6628, -1, + 6628, 6657, 6656, -1, 6657, 6628, 6630, -1, + 6630, 6658, 6657, -1, 6658, 6630, 6632, -1, + 6632, 6659, 6658, -1, 6659, 6632, 6633, -1, + 6633, 6660, 6659, -1, 6660, 6633, 6643, -1, + 6643, 6661, 6660, -1, 6661, 6643, 6641, -1, + 6641, 6662, 6661, -1, 6662, 6641, 6639, -1, + 6639, 6663, 6662, -1, 6663, 6639, 6637, -1, + 6637, 6664, 6663, -1, 6664, 6637, 6634, -1, + 6634, 6665, 6664, -1, 6665, 6634, 6636, -1, + 6636, 6666, 6665, -1, 6666, 6636, 6667, -1, + 6667, 6668, 6666, -1, 6668, 6667, 6669, -1, + 6669, 6670, 6668, -1, 6670, 6669, 6671, -1, + 6671, 6672, 6670, -1, 6672, 6671, 6673, -1, + 6673, 6674, 6672, -1, 6674, 6673, 6675, -1, + 6675, 6676, 6674, -1, 6676, 6675, 6677, -1, + 6677, 6678, 6676, -1, 6678, 6677, 6679, -1, + 6679, 6680, 6678, -1, 6680, 6679, 6681, -1, + 6681, 6682, 6680, -1, 6683, 6684, 6682, -1, + 6682, 6681, 6683, -1, 6685, 826, 6686, -1, + 6685, 6687, 826, -1, 6687, 6685, 6688, -1, + 6685, 6686, 6688, -1, 6689, 6688, 6686, -1, + 6689, 6690, 6688, -1, 6691, 6692, 6693, -1, + 6692, 6691, 6694, -1, 6694, 6695, 6692, -1, + 6695, 6694, 6696, -1, 6696, 6697, 6695, -1, + 6697, 6696, 6698, -1, 6698, 6699, 6697, -1, + 6699, 6698, 6700, -1, 6700, 6701, 6699, -1, + 6701, 6700, 6702, -1, 6702, 6703, 6701, -1, + 6703, 6702, 6704, -1, 6704, 6705, 6703, -1, + 6705, 6704, 6706, -1, 6706, 6707, 6705, -1, + 6707, 6706, 6708, -1, 6708, 6709, 6707, -1, + 6709, 6708, 6710, -1, 6710, 6711, 6709, -1, + 6711, 6710, 6712, -1, 6712, 6713, 6711, -1, + 6713, 6712, 6714, -1, 6714, 6715, 6713, -1, + 6715, 6714, 6716, -1, 6716, 6717, 6715, -1, + 6717, 6716, 6718, -1, 6718, 6719, 6717, -1, + 6719, 6718, 6720, -1, 6720, 6721, 6719, -1, + 6721, 6720, 6722, -1, 6722, 6723, 6721, -1, + 6724, 6725, 6723, -1, 6723, 6722, 6724, -1, + 6726, 6727, 6728, -1, 6726, 6729, 6727, -1, + 6730, 6731, 6732, -1, 6730, 6732, 6733, -1, + 6733, 6734, 6730, -1, 6734, 6733, 6735, -1, + 6735, 6736, 6734, -1, 6736, 6735, 6737, -1, + 6737, 6738, 6736, -1, 6737, 6739, 6738, -1, + 6739, 6737, 6740, -1, 6740, 6741, 6739, -1, + 6741, 6740, 6742, -1, 6742, 6743, 6741, -1, + 6743, 6742, 6729, -1, 6729, 6726, 6743, -1, + 6744, 6745, 6746, -1, 6747, 6748, 6749, -1, + 6749, 6750, 6747, -1, 6750, 6749, 6751, -1, + 6751, 6752, 6750, -1, 6752, 6751, 6753, -1, + 6753, 6754, 6752, -1, 6754, 6753, 6755, -1, + 6755, 6756, 6754, -1, 6756, 6755, 6757, -1, + 6757, 6758, 6756, -1, 6758, 6757, 6759, -1, + 6759, 6760, 6758, -1, 6760, 6759, 6761, -1, + 6761, 6762, 6760, -1, 6762, 6761, 6763, -1, + 6763, 6764, 6762, -1, 6764, 6763, 6765, -1, + 6765, 6766, 6764, -1, 6766, 6765, 6767, -1, + 6767, 6768, 6766, -1, 6768, 6767, 6769, -1, + 6769, 6770, 6768, -1, 6770, 6769, 6771, -1, + 6771, 6772, 6770, -1, 6772, 6771, 6773, -1, + 6773, 6774, 6772, -1, 6774, 6773, 6775, -1, + 6775, 6776, 6774, -1, 6776, 6775, 6777, -1, + 6777, 6778, 6776, -1, 6778, 6777, 6779, -1, + 6779, 6780, 6778, -1, 6780, 6779, 6781, -1, + 6781, 6782, 6780, -1, 6782, 6781, 6783, -1, + 6783, 6784, 6782, -1, 6784, 6783, 6785, -1, + 6785, 6786, 6784, -1, 6786, 6785, 6787, -1, + 6787, 6788, 6786, -1, 6788, 6787, 6745, -1, + 6745, 6744, 6788, -1, 6744, 6726, 6788, -1, + 6744, 6743, 6726, -1, 6744, 6746, 6743, -1, + 6789, 6743, 6746, -1, 6789, 6741, 6743, -1, + 6741, 6789, 6790, -1, 6790, 6739, 6741, -1, + 6739, 6790, 6791, -1, 6791, 6738, 6739, -1, + 6738, 6791, 6792, -1, 6738, 6792, 6793, -1, + 6793, 6736, 6738, -1, 6736, 6793, 6794, -1, + 6794, 6734, 6736, -1, 6734, 6794, 6795, -1, + 6795, 6730, 6734, -1, 6795, 6796, 6730, -1, + 6797, 6798, 6799, -1, 6798, 6797, 6800, -1, + 6800, 6801, 6798, -1, 6801, 6800, 6802, -1, + 6802, 6803, 6801, -1, 6803, 6802, 6804, -1, + 6804, 6805, 6803, -1, 6805, 6804, 6806, -1, + 6806, 6807, 6805, -1, 6807, 6806, 6808, -1, + 6808, 6809, 6807, -1, 6809, 6808, 6810, -1, + 6810, 6811, 6809, -1, 6811, 6810, 6812, -1, + 6812, 6813, 6811, -1, 6813, 6812, 6814, -1, + 6814, 6815, 6813, -1, 6815, 6814, 6816, -1, + 6816, 6817, 6815, -1, 6817, 6816, 6818, -1, + 6818, 6819, 6817, -1, 6819, 6818, 6820, -1, + 6820, 6821, 6819, -1, 6821, 6820, 6822, -1, + 6822, 6823, 6821, -1, 6823, 6822, 6824, -1, + 6824, 6825, 6823, -1, 6825, 6824, 6826, -1, + 6826, 6827, 6825, -1, 6827, 6826, 6828, -1, + 6828, 6829, 6827, -1, 6829, 6828, 6830, -1, + 6830, 6831, 6829, -1, 6831, 6830, 6832, -1, + 6832, 6833, 6831, -1, 6833, 6832, 6834, -1, + 6834, 6835, 6833, -1, 6835, 6834, 6836, -1, + 6836, 6837, 6835, -1, 6837, 6836, 6796, -1, + 6796, 6838, 6837, -1, 6838, 6796, 6795, -1, + 6838, 6795, 6724, -1, 6838, 6724, 6722, -1, + 6722, 6837, 6838, -1, 6837, 6722, 6720, -1, + 6720, 6835, 6837, -1, 6835, 6720, 6718, -1, + 6718, 6833, 6835, -1, 6833, 6718, 6716, -1, + 6716, 6831, 6833, -1, 6831, 6716, 6714, -1, + 6714, 6829, 6831, -1, 6829, 6714, 6712, -1, + 6712, 6827, 6829, -1, 6827, 6712, 6710, -1, + 6710, 6825, 6827, -1, 6825, 6710, 6708, -1, + 6708, 6823, 6825, -1, 6823, 6708, 6706, -1, + 6706, 6821, 6823, -1, 6821, 6706, 6704, -1, + 6704, 6819, 6821, -1, 6819, 6704, 6702, -1, + 6702, 6817, 6819, -1, 6817, 6702, 6700, -1, + 6700, 6815, 6817, -1, 6815, 6700, 6698, -1, + 6698, 6813, 6815, -1, 6813, 6698, 6696, -1, + 6696, 6811, 6813, -1, 6811, 6696, 6694, -1, + 6694, 6809, 6811, -1, 6809, 6694, 6691, -1, + 6691, 6807, 6809, -1, 6807, 6691, 6693, -1, + 6693, 6805, 6807, -1, 6805, 6693, 6839, -1, + 6839, 6803, 6805, -1, 6803, 6839, 6840, -1, + 6840, 6801, 6803, -1, 6801, 6840, 6841, -1, + 6841, 6798, 6801, -1, 6798, 6841, 6842, -1, + 6842, 6799, 6798, -1, 6799, 6842, 6843, -1, + 6843, 6844, 6799, -1, 6844, 6843, 6845, -1, + 6845, 6846, 6844, -1, 6846, 6845, 6847, -1, + 6847, 6848, 6846, -1, 6848, 6847, 6849, -1, + 6849, 6850, 6848, -1, 6850, 6849, 6851, -1, + 6851, 6852, 6850, -1, 6852, 6851, 6853, -1, + 6853, 6854, 6852, -1, 6854, 6853, 6855, -1, + 6855, 6856, 6854, -1, 6856, 6855, 6857, -1, + 6857, 6858, 6856, -1, 6858, 6857, 6859, -1, + 6859, 6860, 6858, -1, 6860, 6859, 6690, -1, + 6690, 6689, 6860, -1, 6683, 6689, 6861, -1, + 6683, 6860, 6689, -1, 6860, 6683, 6681, -1, + 6681, 6858, 6860, -1, 6858, 6681, 6679, -1, + 6679, 6856, 6858, -1, 6856, 6679, 6677, -1, + 6677, 6854, 6856, -1, 6854, 6677, 6675, -1, + 6675, 6852, 6854, -1, 6852, 6675, 6673, -1, + 6673, 6850, 6852, -1, 6850, 6673, 6671, -1, + 6671, 6848, 6850, -1, 6848, 6671, 6669, -1, + 6669, 6846, 6848, -1, 6846, 6669, 6667, -1, + 6667, 6844, 6846, -1, 6844, 6667, 6636, -1, + 6636, 6799, 6844, -1, 6799, 6636, 6635, -1, + 6635, 6797, 6799, -1, 6797, 6635, 6638, -1, + 6638, 6800, 6797, -1, 6800, 6638, 6640, -1, + 6640, 6802, 6800, -1, 6802, 6640, 6642, -1, + 6642, 6804, 6802, -1, 6804, 6642, 6644, -1, + 6644, 6806, 6804, -1, 6806, 6644, 6606, -1, + 6606, 6808, 6806, -1, 6808, 6606, 6604, -1, + 6604, 6810, 6808, -1, 6810, 6604, 6602, -1, + 6602, 6812, 6810, -1, 6812, 6602, 6600, -1, + 6600, 6814, 6812, -1, 6814, 6600, 6598, -1, + 6598, 6816, 6814, -1, 6816, 6598, 6596, -1, + 6596, 6818, 6816, -1, 6818, 6596, 6594, -1, + 6594, 6820, 6818, -1, 6820, 6594, 6592, -1, + 6592, 6822, 6820, -1, 6822, 6592, 6590, -1, + 6590, 6824, 6822, -1, 6824, 6590, 6588, -1, + 6588, 6826, 6824, -1, 6826, 6588, 6586, -1, + 6586, 6828, 6826, -1, 6828, 6586, 6584, -1, + 6584, 6830, 6828, -1, 6830, 6584, 6582, -1, + 6582, 6832, 6830, -1, 6832, 6582, 6581, -1, + 6581, 6834, 6832, -1, 6834, 6581, 6862, -1, + 6862, 6836, 6834, -1, 6836, 6862, 6863, -1, + 6863, 6796, 6836, -1, 6863, 6730, 6796, -1, + 6863, 6731, 6730, -1, 6731, 6863, 6862, -1, + 6862, 6864, 6731, -1, 6864, 6862, 6581, -1, + 6581, 6580, 6864, -1, 6864, 6580, 6645, -1, + 6864, 6645, 6865, -1, 6865, 6731, 6864, -1, + 6865, 6732, 6731, -1, 6865, 6866, 6732, -1, + 6866, 6865, 6645, -1, 6645, 6646, 6866, -1, + 6866, 6646, 6867, -1, 6866, 6867, 6868, -1, + 6868, 6732, 6866, -1, 6732, 6868, 6869, -1, + 6869, 6733, 6732, -1, 6733, 6869, 6870, -1, + 6870, 6735, 6733, -1, 6735, 6870, 6871, -1, + 6871, 6737, 6735, -1, 6871, 6740, 6737, -1, + 6740, 6871, 6872, -1, 6872, 6742, 6740, -1, + 6742, 6872, 6873, -1, 6873, 6729, 6742, -1, + 6729, 6873, 6874, -1, 6874, 6727, 6729, -1, + 6727, 6874, 6875, -1, 6727, 6875, 6876, -1, + 6877, 6876, 6875, -1, 6877, 6878, 6876, -1, + 6878, 6877, 6879, -1, 6879, 6880, 6878, -1, + 6880, 6879, 6881, -1, 6881, 6882, 6880, -1, + 6882, 6881, 6883, -1, 6883, 6884, 6882, -1, + 6884, 6883, 6885, -1, 6885, 6886, 6884, -1, + 6886, 6885, 6887, -1, 6887, 6888, 6886, -1, + 6888, 6887, 6889, -1, 6889, 6890, 6888, -1, + 6890, 6889, 6891, -1, 6891, 6892, 6890, -1, + 6892, 6891, 6893, -1, 6893, 6894, 6892, -1, + 6894, 6893, 6895, -1, 6895, 6896, 6894, -1, + 6896, 6895, 6897, -1, 6897, 6898, 6896, -1, + 6898, 6897, 6899, -1, 6899, 6900, 6898, -1, + 6900, 6899, 6901, -1, 6901, 6902, 6900, -1, + 6902, 6901, 6903, -1, 6903, 6904, 6902, -1, + 6904, 6903, 6905, -1, 6905, 6906, 6904, -1, + 6906, 6905, 6907, -1, 6907, 6908, 6906, -1, + 6908, 6907, 6909, -1, 6909, 6910, 6908, -1, + 6910, 6909, 6911, -1, 6911, 6912, 6910, -1, + 6912, 6911, 6913, -1, 6913, 6914, 6912, -1, + 6914, 6913, 6915, -1, 6915, 6916, 6914, -1, + 6916, 6915, 6578, -1, 6578, 6917, 6916, -1, + 6917, 6578, 6577, -1, 6577, 6918, 6917, -1, + 6918, 6577, 6576, -1, 6576, 6919, 6918, -1, + 6919, 6576, 6575, -1, 6575, 6920, 6919, -1, + 6920, 6575, 6574, -1, 6574, 6921, 6920, -1, + 6921, 6574, 6573, -1, 6573, 6922, 6921, -1, + 6922, 6573, 6572, -1, 6572, 6923, 6922, -1, + 6923, 6572, 6568, -1, 6568, 6924, 6923, -1, + 6924, 6568, 6567, -1, 6567, 6925, 6924, -1, + 6925, 6926, 6924, -1, 6927, 6924, 6926, -1, + 6924, 6927, 6928, -1, 6928, 6923, 6924, -1, + 6923, 6928, 6929, -1, 6929, 6922, 6923, -1, + 6922, 6929, 6930, -1, 6930, 6921, 6922, -1, + 6921, 6930, 6931, -1, 6931, 6920, 6921, -1, + 6920, 6931, 6932, -1, 6932, 6919, 6920, -1, + 6919, 6932, 6933, -1, 6933, 6918, 6919, -1, + 6918, 6933, 6934, -1, 6934, 6917, 6918, -1, + 6917, 6934, 6548, -1, 6548, 6916, 6917, -1, + 6916, 6548, 6547, -1, 6547, 6914, 6916, -1, + 6914, 6547, 6545, -1, 6545, 6912, 6914, -1, + 6912, 6545, 6543, -1, 6543, 6910, 6912, -1, + 6910, 6543, 6541, -1, 6541, 6908, 6910, -1, + 6908, 6541, 6539, -1, 6539, 6906, 6908, -1, + 6906, 6539, 6537, -1, 6537, 6904, 6906, -1, + 6904, 6537, 6535, -1, 6535, 6902, 6904, -1, + 6902, 6535, 6534, -1, 6534, 6900, 6902, -1, + 6900, 6534, 6935, -1, 6935, 6898, 6900, -1, + 6898, 6935, 6936, -1, 6936, 6896, 6898, -1, + 6896, 6936, 6937, -1, 6937, 6894, 6896, -1, + 6894, 6937, 6938, -1, 6938, 6892, 6894, -1, + 6892, 6938, 6939, -1, 6939, 6890, 6892, -1, + 6890, 6939, 6940, -1, 6940, 6888, 6890, -1, + 6888, 6940, 6941, -1, 6941, 6886, 6888, -1, + 6886, 6941, 6942, -1, 6942, 6884, 6886, -1, + 6884, 6942, 6943, -1, 6943, 6882, 6884, -1, + 6882, 6943, 6944, -1, 6944, 6880, 6882, -1, + 6880, 6944, 6945, -1, 6945, 6878, 6880, -1, + 6878, 6945, 6946, -1, 6946, 6876, 6878, -1, + 6876, 6946, 6947, -1, 6947, 6727, 6876, -1, + 6947, 6728, 6727, -1, 6947, 6948, 6728, -1, + 6948, 6947, 6946, -1, 6946, 6949, 6948, -1, + 6949, 6946, 6945, -1, 6945, 6950, 6949, -1, + 6950, 6945, 6944, -1, 6944, 6951, 6950, -1, + 6951, 6944, 6943, -1, 6943, 6952, 6951, -1, + 6952, 6943, 6942, -1, 6942, 6953, 6952, -1, + 6953, 6942, 6941, -1, 6941, 6954, 6953, -1, + 6954, 6941, 6940, -1, 6940, 6955, 6954, -1, + 6955, 6940, 6939, -1, 6939, 6956, 6955, -1, + 6956, 6939, 6938, -1, 6938, 6957, 6956, -1, + 6957, 6938, 6937, -1, 6937, 6958, 6957, -1, + 6958, 6937, 6936, -1, 6936, 6959, 6958, -1, + 6959, 6936, 6935, -1, 6935, 6960, 6959, -1, + 6960, 6935, 6534, -1, 6534, 6533, 6960, -1, + 6960, 6533, 6961, -1, 6961, 6959, 6960, -1, + 6959, 6961, 6962, -1, 6962, 6958, 6959, -1, + 6958, 6962, 6963, -1, 6963, 6957, 6958, -1, + 6957, 6963, 6964, -1, 6964, 6956, 6957, -1, + 6956, 6964, 6965, -1, 6965, 6955, 6956, -1, + 6955, 6965, 6966, -1, 6966, 6954, 6955, -1, + 6954, 6966, 6967, -1, 6967, 6953, 6954, -1, + 6953, 6967, 6968, -1, 6968, 6952, 6953, -1, + 6952, 6968, 6969, -1, 6969, 6951, 6952, -1, + 6951, 6969, 6970, -1, 6970, 6950, 6951, -1, + 6950, 6970, 6971, -1, 6971, 6949, 6950, -1, + 6949, 6971, 6972, -1, 6972, 6948, 6949, -1, + 6948, 6972, 6973, -1, 6973, 6728, 6948, -1, + 6728, 6973, 6974, -1, 6974, 6726, 6728, -1, + 6974, 6788, 6726, -1, 6974, 6786, 6788, -1, + 6786, 6974, 6973, -1, 6973, 6784, 6786, -1, + 6784, 6973, 6972, -1, 6972, 6782, 6784, -1, + 6782, 6972, 6971, -1, 6971, 6780, 6782, -1, + 6780, 6971, 6970, -1, 6970, 6778, 6780, -1, + 6778, 6970, 6969, -1, 6969, 6776, 6778, -1, + 6776, 6969, 6968, -1, 6968, 6774, 6776, -1, + 6774, 6968, 6967, -1, 6967, 6772, 6774, -1, + 6772, 6967, 6966, -1, 6966, 6770, 6772, -1, + 6770, 6966, 6965, -1, 6965, 6768, 6770, -1, + 6768, 6965, 6964, -1, 6964, 6766, 6768, -1, + 6766, 6964, 6963, -1, 6963, 6764, 6766, -1, + 6764, 6963, 6962, -1, 6962, 6762, 6764, -1, + 6762, 6962, 6961, -1, 6961, 6760, 6762, -1, + 6760, 6961, 6533, -1, 6533, 6758, 6760, -1, + 6758, 6533, 6536, -1, 6536, 6756, 6758, -1, + 6756, 6536, 6538, -1, 6538, 6754, 6756, -1, + 6754, 6538, 6540, -1, 6540, 6752, 6754, -1, + 6752, 6540, 6542, -1, 6542, 6750, 6752, -1, + 6750, 6542, 6544, -1, 6544, 6747, 6750, -1, + 6747, 6544, 6546, -1, 6546, 6748, 6747, -1, + 6748, 6546, 6548, -1, 6548, 6975, 6748, -1, + 6975, 6548, 6934, -1, 6934, 6976, 6975, -1, + 6976, 6934, 6933, -1, 6933, 6977, 6976, -1, + 6977, 6933, 6932, -1, 6932, 6978, 6977, -1, + 6978, 6932, 6931, -1, 6931, 6979, 6978, -1, + 6979, 6931, 6930, -1, 6930, 6980, 6979, -1, + 6980, 6930, 6929, -1, 6929, 6981, 6980, -1, + 6981, 6929, 6928, -1, 6928, 6982, 6981, -1, + 6982, 6928, 6927, -1, 6927, 6983, 6982, -1, + 6927, 6984, 6983, -1, 6985, 6986, 6987, -1, + 6983, 6987, 6986, -1, 6988, 6987, 6983, -1, + 6988, 6983, 6984, -1, 6984, 6989, 6988, -1, + 6984, 6990, 6989, -1, 6990, 6984, 6927, -1, + 6990, 6927, 6926, -1, 6926, 6989, 6990, -1, + 6926, 6925, 6989, -1, 6925, 6567, 6989, -1, + 6989, 6567, 6565, -1, 6531, 6565, 6564, -1, + 6564, 6530, 6531, -1, 6564, 6561, 6530, -1, + 6561, 6526, 6530, -1, 6526, 6561, 6559, -1, + 6559, 6525, 6526, -1, 6525, 6559, 6557, -1, + 6557, 6524, 6525, -1, 6524, 6557, 6555, -1, + 6555, 6523, 6524, -1, 6523, 6555, 6553, -1, + 6553, 6522, 6523, -1, 6522, 6553, 6551, -1, + 6551, 999, 6522, -1, 999, 6551, 6550, -1, + 6550, 997, 999, -1, 997, 6550, 6991, -1, + 6991, 995, 997, -1, 995, 6991, 6992, -1, + 6992, 993, 995, -1, 993, 6992, 6993, -1, + 6993, 991, 993, -1, 991, 6993, 6994, -1, + 6994, 989, 991, -1, 989, 6994, 6995, -1, + 6995, 987, 989, -1, 987, 6995, 6996, -1, + 6996, 985, 987, -1, 985, 6996, 6997, -1, + 6997, 983, 985, -1, 983, 6997, 6998, -1, + 6998, 981, 983, -1, 981, 6998, 6999, -1, + 6999, 979, 981, -1, 979, 6999, 7000, -1, + 7000, 977, 979, -1, 977, 7000, 7001, -1, + 7001, 975, 977, -1, 975, 7001, 7002, -1, + 7002, 973, 975, -1, 973, 7002, 7003, -1, + 7003, 971, 973, -1, 971, 7003, 7004, -1, + 7004, 969, 971, -1, 969, 7004, 7005, -1, + 7005, 967, 969, -1, 967, 7005, 7006, -1, + 7006, 964, 967, -1, 964, 7006, 7007, -1, + 7007, 965, 964, -1, 965, 7007, 7008, -1, + 7008, 1057, 965, -1, 1057, 7008, 7009, -1, + 7009, 961, 1057, -1, 7009, 962, 961, -1, + 7009, 7010, 962, -1, 7010, 7009, 7008, -1, + 7008, 7011, 7010, -1, 7011, 7008, 7007, -1, + 7007, 7012, 7011, -1, 7012, 7007, 7006, -1, + 7006, 7013, 7012, -1, 7013, 7006, 7005, -1, + 7005, 7014, 7013, -1, 7014, 7005, 7004, -1, + 7004, 7015, 7014, -1, 7015, 7004, 7003, -1, + 7003, 7016, 7015, -1, 7016, 7003, 7002, -1, + 7002, 7017, 7016, -1, 7017, 7002, 7001, -1, + 7001, 7018, 7017, -1, 7018, 7001, 7000, -1, + 7000, 7019, 7018, -1, 7019, 7000, 6999, -1, + 6999, 7020, 7019, -1, 7020, 6999, 6998, -1, + 6998, 7021, 7020, -1, 7021, 6998, 6997, -1, + 6997, 7022, 7021, -1, 7022, 6997, 6996, -1, + 6996, 7023, 7022, -1, 7023, 6996, 6995, -1, + 6995, 7024, 7023, -1, 7024, 6995, 6994, -1, + 6994, 7025, 7024, -1, 7025, 6994, 6993, -1, + 6993, 7026, 7025, -1, 7026, 6993, 6992, -1, + 6992, 7027, 7026, -1, 7027, 6992, 6991, -1, + 6991, 7028, 7027, -1, 7028, 6991, 6550, -1, + 6550, 6549, 7028, -1, 7028, 6549, 6579, -1, + 6579, 7027, 7028, -1, 7027, 6579, 7029, -1, + 7029, 7026, 7027, -1, 7026, 7029, 7030, -1, + 7030, 7025, 7026, -1, 7025, 7030, 7031, -1, + 7031, 7024, 7025, -1, 7024, 7031, 7032, -1, + 7032, 7023, 7024, -1, 7023, 7032, 7033, -1, + 7033, 7022, 7023, -1, 7022, 7033, 7034, -1, + 7034, 7021, 7022, -1, 7021, 7034, 7035, -1, + 7035, 7020, 7021, -1, 7020, 7035, 7036, -1, + 7036, 7019, 7020, -1, 7019, 7036, 7037, -1, + 7037, 7018, 7019, -1, 7018, 7037, 7038, -1, + 7038, 7017, 7018, -1, 7017, 7038, 7039, -1, + 7039, 7016, 7017, -1, 7016, 7039, 7040, -1, + 7040, 7015, 7016, -1, 7015, 7040, 7041, -1, + 7041, 7014, 7015, -1, 7014, 7041, 7042, -1, + 7042, 7013, 7014, -1, 7013, 7042, 7043, -1, + 7043, 7012, 7013, -1, 7012, 7043, 7044, -1, + 7044, 7011, 7012, -1, 7011, 7044, 7045, -1, + 7045, 7010, 7011, -1, 7010, 7045, 7046, -1, + 7046, 962, 7010, -1, 962, 7046, 7047, -1, + 7047, 960, 962, -1, 7047, 7048, 960, -1, + 7047, 7049, 7048, -1, 7049, 7047, 7046, -1, + 7046, 7050, 7049, -1, 7050, 7046, 7045, -1, + 7045, 7051, 7050, -1, 7051, 7045, 7044, -1, + 7044, 7052, 7051, -1, 7052, 7044, 7043, -1, + 7043, 7053, 7052, -1, 7053, 7043, 7042, -1, + 7042, 7054, 7053, -1, 7054, 7042, 7041, -1, + 7041, 7055, 7054, -1, 7055, 7041, 7040, -1, + 7040, 7056, 7055, -1, 7056, 7040, 7039, -1, + 7039, 7057, 7056, -1, 7057, 7039, 7038, -1, + 7038, 7058, 7057, -1, 7058, 7038, 7037, -1, + 7037, 7059, 7058, -1, 7059, 7037, 7036, -1, + 7036, 7060, 7059, -1, 7060, 7036, 7035, -1, + 7035, 7061, 7060, -1, 7061, 7035, 7034, -1, + 7034, 7062, 7061, -1, 7062, 7034, 7033, -1, + 7033, 7063, 7062, -1, 7063, 7033, 7032, -1, + 7032, 7064, 7063, -1, 7064, 7032, 7031, -1, + 7031, 7065, 7064, -1, 7065, 7031, 7030, -1, + 7030, 7066, 7065, -1, 7066, 7030, 7029, -1, + 7029, 7067, 7066, -1, 7067, 7029, 6579, -1, + 6579, 6578, 7067, -1, 7067, 6578, 6915, -1, + 6915, 7066, 7067, -1, 7066, 6915, 6913, -1, + 6913, 7065, 7066, -1, 7065, 6913, 6911, -1, + 6911, 7064, 7065, -1, 7064, 6911, 6909, -1, + 6909, 7063, 7064, -1, 7063, 6909, 6907, -1, + 6907, 7062, 7063, -1, 7062, 6907, 6905, -1, + 6905, 7061, 7062, -1, 7061, 6905, 6903, -1, + 6903, 7060, 7061, -1, 7060, 6903, 6901, -1, + 6901, 7059, 7060, -1, 7059, 6901, 6899, -1, + 6899, 7058, 7059, -1, 7058, 6899, 6897, -1, + 6897, 7057, 7058, -1, 7057, 6897, 6895, -1, + 6895, 7056, 7057, -1, 7056, 6895, 6893, -1, + 6893, 7055, 7056, -1, 7055, 6893, 6891, -1, + 6891, 7054, 7055, -1, 7054, 6891, 6889, -1, + 6889, 7053, 7054, -1, 7053, 6889, 6887, -1, + 6887, 7052, 7053, -1, 7052, 6887, 6885, -1, + 6885, 7051, 7052, -1, 7051, 6885, 6883, -1, + 6883, 7050, 7051, -1, 7050, 6883, 6881, -1, + 6881, 7049, 7050, -1, 7049, 6881, 6879, -1, + 6879, 7048, 7049, -1, 7048, 6879, 6877, -1, + 6877, 6875, 7048, -1, 6875, 960, 7048, -1, + 6875, 958, 960, -1, 958, 6875, 6874, -1, + 6874, 956, 958, -1, 956, 6874, 6873, -1, + 6873, 954, 956, -1, 954, 6873, 6872, -1, + 6872, 953, 954, -1, 953, 6872, 6871, -1, + 953, 6871, 6870, -1, 6870, 951, 953, -1, + 951, 6870, 6869, -1, 6869, 949, 951, -1, + 949, 6869, 6868, -1, 6868, 947, 949, -1, + 947, 6868, 6867, -1, 6867, 945, 947, -1, + 6867, 7068, 945, -1, 7069, 7070, 7071, -1, + 7070, 7069, 7072, -1, 7072, 7073, 7070, -1, + 7073, 7072, 7074, -1, 7074, 7075, 7073, -1, + 7075, 7074, 7076, -1, 7076, 7077, 7075, -1, + 7077, 7076, 7078, -1, 7078, 7079, 7077, -1, + 7079, 7078, 7080, -1, 7080, 7081, 7079, -1, + 7081, 7080, 7082, -1, 7082, 7083, 7081, -1, + 7083, 7082, 7084, -1, 7084, 7085, 7083, -1, + 7085, 7084, 7086, -1, 7086, 7087, 7085, -1, + 7087, 7086, 7088, -1, 7088, 7089, 7087, -1, + 7089, 7088, 7090, -1, 7090, 7091, 7089, -1, + 7091, 7090, 7092, -1, 7092, 7093, 7091, -1, + 7093, 7092, 7094, -1, 7094, 7095, 7093, -1, + 7095, 7094, 7096, -1, 7096, 7097, 7095, -1, + 7097, 7096, 7098, -1, 7098, 7099, 7097, -1, + 7100, 7099, 7101, -1, 7099, 7100, 7102, -1, + 7102, 7097, 7099, -1, 7097, 7102, 7103, -1, + 7103, 7095, 7097, -1, 7095, 7103, 7104, -1, + 7104, 7093, 7095, -1, 7093, 7104, 7105, -1, + 7105, 7091, 7093, -1, 7091, 7105, 7106, -1, + 7106, 7089, 7091, -1, 7089, 7106, 7107, -1, + 7107, 7087, 7089, -1, 7087, 7107, 7108, -1, + 7108, 7085, 7087, -1, 7085, 7108, 7109, -1, + 7109, 7083, 7085, -1, 7083, 7109, 7110, -1, + 7110, 7081, 7083, -1, 7081, 7110, 7111, -1, + 7111, 7079, 7081, -1, 7079, 7111, 7112, -1, + 7112, 7077, 7079, -1, 7077, 7112, 7113, -1, + 7113, 7075, 7077, -1, 7075, 7113, 7114, -1, + 7114, 7073, 7075, -1, 7073, 7114, 7115, -1, + 7115, 7070, 7073, -1, 7070, 7115, 7116, -1, + 7116, 7071, 7070, -1, 7071, 7116, 7117, -1, + 7117, 7118, 7071, -1, 7118, 7117, 7119, -1, + 7119, 7120, 7118, -1, 7120, 7119, 7121, -1, + 7121, 7068, 7120, -1, 7121, 945, 7068, -1, + 7121, 944, 945, -1, 944, 7121, 7119, -1, + 7119, 943, 944, -1, 943, 7119, 7117, -1, + 7117, 942, 943, -1, 942, 7117, 7116, -1, + 7116, 941, 942, -1, 941, 7116, 7115, -1, + 7115, 940, 941, -1, 940, 7115, 7114, -1, + 7114, 939, 940, -1, 939, 7114, 7113, -1, + 7113, 938, 939, -1, 938, 7113, 7112, -1, + 7112, 937, 938, -1, 937, 7112, 7111, -1, + 7111, 936, 937, -1, 936, 7111, 7110, -1, + 7110, 935, 936, -1, 935, 7110, 7109, -1, + 7109, 934, 935, -1, 934, 7109, 7108, -1, + 7108, 933, 934, -1, 933, 7108, 7107, -1, + 7107, 932, 933, -1, 932, 7107, 7106, -1, + 7106, 931, 932, -1, 931, 7106, 7105, -1, + 7105, 930, 931, -1, 930, 7105, 7104, -1, + 7104, 929, 930, -1, 929, 7104, 7103, -1, + 7103, 928, 929, -1, 928, 7103, 7102, -1, + 7102, 927, 928, -1, 927, 7102, 7100, -1, + 7100, 926, 927, -1, 926, 7100, 7101, -1, + 7101, 925, 926, -1, 925, 7101, 7122, -1, + 7122, 924, 925, -1, 924, 7122, 7123, -1, + 7123, 923, 924, -1, 923, 7123, 7124, -1, + 7124, 922, 923, -1, 922, 7124, 7125, -1, + 7125, 921, 922, -1, 921, 7125, 7126, -1, + 7126, 920, 921, -1, 920, 7126, 7127, -1, + 7127, 919, 920, -1, 7128, 7129, 919, -1, + 919, 7127, 7128, -1, 7128, 7130, 7131, -1, + 7128, 7132, 7130, -1, 7132, 7128, 7127, -1, + 7127, 7133, 7132, -1, 7133, 7127, 7126, -1, + 7126, 7134, 7133, -1, 7134, 7126, 7125, -1, + 7125, 7135, 7134, -1, 7135, 7125, 7124, -1, + 7124, 7136, 7135, -1, 7136, 7124, 7123, -1, + 7123, 7137, 7136, -1, 7137, 7123, 7122, -1, + 7122, 7138, 7137, -1, 7138, 7122, 7101, -1, + 7101, 7139, 7138, -1, 7139, 7101, 7099, -1, + 7099, 7098, 7139, -1, 7098, 7140, 7139, -1, + 7140, 7098, 7096, -1, 7096, 7141, 7140, -1, + 7141, 7096, 7094, -1, 7094, 7142, 7141, -1, + 7142, 7094, 7092, -1, 7092, 7143, 7142, -1, + 7143, 7092, 7090, -1, 7090, 7144, 7143, -1, + 7144, 7090, 7088, -1, 7088, 7145, 7144, -1, + 7145, 7088, 7086, -1, 7086, 7146, 7145, -1, + 7146, 7086, 7084, -1, 7084, 7147, 7146, -1, + 7147, 7084, 7082, -1, 7082, 7148, 7147, -1, + 7148, 7082, 7080, -1, 7080, 7149, 7148, -1, + 7149, 7080, 7078, -1, 7078, 7150, 7149, -1, + 7150, 7078, 7076, -1, 7076, 7151, 7150, -1, + 7151, 7076, 7074, -1, 7074, 7152, 7151, -1, + 7152, 7074, 7072, -1, 7072, 7153, 7152, -1, + 7153, 7072, 7069, -1, 7069, 7154, 7153, -1, + 7154, 7069, 7071, -1, 7071, 7155, 7154, -1, + 7155, 7071, 7118, -1, 7118, 7156, 7155, -1, + 7156, 7118, 7120, -1, 7120, 7157, 7156, -1, + 7157, 7120, 7068, -1, 7068, 7158, 7157, -1, + 7158, 7068, 6867, -1, 7158, 6867, 6646, -1, + 7158, 6646, 6647, -1, 6647, 7157, 7158, -1, + 7157, 6647, 6648, -1, 6648, 7156, 7157, -1, + 7156, 6648, 6649, -1, 6649, 7155, 7156, -1, + 7155, 6649, 6650, -1, 6650, 7154, 7155, -1, + 7154, 6650, 6651, -1, 6651, 7153, 7154, -1, + 7153, 6651, 6652, -1, 6652, 7152, 7153, -1, + 7152, 6652, 6653, -1, 6653, 7151, 7152, -1, + 7151, 6653, 6654, -1, 6654, 7150, 7151, -1, + 7150, 6654, 6655, -1, 6655, 7149, 7150, -1, + 7149, 6655, 6656, -1, 6656, 7148, 7149, -1, + 7148, 6656, 6657, -1, 6657, 7147, 7148, -1, + 7147, 6657, 6658, -1, 6658, 7146, 7147, -1, + 7146, 6658, 6659, -1, 6659, 7145, 7146, -1, + 7145, 6659, 6660, -1, 6660, 7144, 7145, -1, + 7144, 6660, 6661, -1, 6661, 7143, 7144, -1, + 7143, 6661, 6662, -1, 6662, 7142, 7143, -1, + 7142, 6662, 6663, -1, 6663, 7141, 7142, -1, + 7141, 6663, 6664, -1, 6664, 7140, 7141, -1, + 7140, 6664, 6665, -1, 6665, 7139, 7140, -1, + 7139, 6665, 6666, -1, 6666, 7138, 7139, -1, + 7138, 6666, 6668, -1, 6668, 7137, 7138, -1, + 7137, 6668, 6670, -1, 6670, 7136, 7137, -1, + 7136, 6670, 6672, -1, 6672, 7135, 7136, -1, + 7135, 6672, 6674, -1, 6674, 7134, 7135, -1, + 7134, 6674, 6676, -1, 6676, 7133, 7134, -1, + 7133, 6676, 6678, -1, 6678, 7132, 7133, -1, + 7132, 6678, 6680, -1, 6680, 7130, 7132, -1, + 7130, 6680, 6682, -1, 6682, 7159, 7130, -1, + 829, 7130, 7159, -1, 829, 828, 7130, -1, + 828, 7131, 7130, -1, 7131, 828, 830, -1, + 7131, 830, 7160, -1, 7160, 7128, 7131, -1, + 7160, 7129, 7128, -1, 7160, 830, 7129, -1, + 7129, 830, 7161, -1, 7161, 919, 7129, -1, + 7161, 918, 919, -1, 7161, 915, 918, -1, + 915, 7161, 830, -1, 7162, 830, 829, -1, + 829, 7159, 7162, -1, 7163, 7162, 7159, -1, + 7159, 6682, 7163, -1, 7163, 6682, 6684, -1, + 6684, 7162, 7163, -1, 6684, 7164, 7162, -1, + 7164, 6684, 6683, -1, 7164, 6683, 6861, -1, + 6861, 7162, 7164, -1, 6861, 7165, 7162, -1, + 7165, 6861, 6689, -1, 7165, 6689, 6686, -1, + 6686, 826, 7165, -1, 826, 7162, 7165, -1, + 506, 5881, 5882, -1, 5881, 506, 503, -1, + 503, 505, 5881, -1, 505, 5878, 5881, -1, + 505, 5877, 5878, -1, 5877, 505, 550, -1, + 550, 5876, 5877, -1, 5876, 550, 551, -1, + 551, 5875, 5876, -1, 5875, 551, 552, -1, + 552, 5874, 5875, -1, 5874, 552, 553, -1, + 553, 5873, 5874, -1, 5873, 553, 554, -1, + 554, 5872, 5873, -1, 5872, 554, 555, -1, + 555, 5871, 5872, -1, 5871, 555, 556, -1, + 556, 5870, 5871, -1, 5870, 556, 557, -1, + 557, 5869, 5870, -1, 5869, 557, 558, -1, + 558, 5868, 5869, -1, 5868, 558, 559, -1, + 559, 5867, 5868, -1, 5867, 559, 560, -1, + 560, 5866, 5867, -1, 5866, 560, 561, -1, + 561, 5865, 5866, -1, 5865, 561, 562, -1, + 562, 5864, 5865, -1, 5864, 562, 563, -1, + 563, 5863, 5864, -1, 5863, 563, 564, -1, + 564, 5862, 5863, -1, 5862, 564, 565, -1, + 565, 5861, 5862, -1, 5861, 565, 566, -1, + 566, 5860, 5861, -1, 5860, 566, 567, -1, + 567, 5859, 5860, -1, 5859, 567, 568, -1, + 568, 5858, 5859, -1, 5858, 568, 502, -1, + 502, 5617, 5858, -1, 5617, 502, 500, -1, + 500, 5615, 5617, -1, 5615, 500, 498, -1, + 498, 5618, 5615, -1, 5618, 498, 496, -1, + 496, 5620, 5618, -1, 5620, 496, 494, -1, + 494, 5622, 5620, -1, 5622, 494, 492, -1, + 492, 5624, 5622, -1, 5624, 492, 490, -1, + 490, 5626, 5624, -1, 5626, 490, 488, -1, + 488, 5628, 5626, -1, 5628, 488, 486, -1, + 486, 5630, 5628, -1, 5630, 486, 484, -1, + 484, 5632, 5630, -1, 5632, 484, 482, -1, + 482, 5634, 5632, -1, 5634, 482, 480, -1, + 480, 5636, 5634, -1, 5636, 480, 478, -1, + 478, 5638, 5636, -1, 5638, 478, 476, -1, + 476, 5640, 5638, -1, 5640, 476, 474, -1, + 474, 5642, 5640, -1, 5642, 474, 472, -1, + 472, 5644, 5642, -1, 5644, 472, 470, -1, + 470, 5646, 5644, -1, 5646, 470, 468, -1, + 468, 5648, 5646, -1, 5648, 468, 466, -1, + 466, 5650, 5648, -1, 5650, 466, 465, -1, + 465, 5652, 5650, -1, 465, 5719, 5652, -1, + 465, 464, 5719, -1, 5719, 464, 587, -1, + 5719, 587, 729, -1, 729, 5720, 5719, -1, + 5720, 729, 728, -1, 728, 5721, 5720, -1, + 5721, 728, 727, -1, 727, 5722, 5721, -1, + 727, 5723, 5722, -1, 5723, 727, 726, -1, + 726, 5724, 5723, -1, 5724, 726, 725, -1, + 725, 5725, 5724, -1, 5725, 725, 724, -1, + 724, 723, 5725, -1, 7166, 723, 7167, -1, + 7166, 5725, 723, -1, 7166, 5726, 5725, -1, + 7166, 5766, 5726, -1, 5766, 7166, 7167, -1, + 7167, 5764, 5766, -1, 5764, 7167, 7168, -1, + 7168, 5762, 5764, -1, 5762, 7168, 7169, -1, + 7169, 5760, 5762, -1, 5760, 7169, 7170, -1, + 7170, 5758, 5760, -1, 5758, 7170, 7171, -1, + 7171, 5756, 5758, -1, 5756, 7171, 7172, -1, + 7172, 5754, 5756, -1, 5754, 7172, 7173, -1, + 7173, 5752, 5754, -1, 5752, 7173, 7174, -1, + 7174, 5750, 5752, -1, 5750, 7174, 7175, -1, + 7175, 5748, 5750, -1, 5748, 7175, 7176, -1, + 7176, 5746, 5748, -1, 5746, 7176, 7177, -1, + 7177, 5744, 5746, -1, 5744, 7177, 7178, -1, + 7178, 5742, 5744, -1, 5742, 7178, 7179, -1, + 7179, 5740, 5742, -1, 5740, 7179, 7180, -1, + 7180, 5738, 5740, -1, 5738, 7180, 7181, -1, + 7181, 5736, 5738, -1, 5736, 7181, 7182, -1, + 7182, 5734, 5736, -1, 5734, 7182, 7183, -1, + 7183, 5732, 5734, -1, 5732, 7183, 7184, -1, + 7184, 5730, 5732, -1, 5730, 7184, 7185, -1, + 7185, 5727, 5730, -1, 5727, 7185, 7186, -1, + 7186, 5728, 5727, -1, 5728, 7186, 7187, -1, + 7187, 5769, 5728, -1, 5769, 7187, 7188, -1, + 7188, 5770, 5769, -1, 5770, 7188, 7189, -1, + 7189, 5771, 5770, -1, 5771, 7189, 7190, -1, + 7190, 5772, 5771, -1, 5772, 7190, 7191, -1, + 7191, 5773, 5772, -1, 5773, 7191, 7192, -1, + 7192, 5774, 5773, -1, 5774, 7192, 7193, -1, + 7193, 5775, 5774, -1, 5775, 7193, 7194, -1, + 7194, 5776, 5775, -1, 5776, 7194, 7195, -1, + 7195, 5777, 5776, -1, 5777, 7195, 7196, -1, + 7196, 5778, 5777, -1, 5778, 7196, 7197, -1, + 7197, 5779, 5778, -1, 5779, 7197, 7198, -1, + 7198, 5780, 5779, -1, 5780, 7198, 7199, -1, + 7199, 5781, 5780, -1, 5781, 7199, 7200, -1, + 7200, 5782, 5781, -1, 5782, 7200, 7201, -1, + 7201, 5783, 5782, -1, 5783, 7201, 7202, -1, + 7202, 5784, 5783, -1, 5784, 7202, 7203, -1, + 7203, 5785, 5784, -1, 5785, 7203, 7204, -1, + 7204, 5786, 5785, -1, 5786, 7204, 7205, -1, + 7205, 5787, 5786, -1, 5787, 7205, 7206, -1, + 7206, 5788, 5787, -1, 7206, 7207, 5788, -1, + 7208, 7209, 7210, -1, 7211, 7209, 7208, -1, + 7208, 7206, 7211, -1, 7208, 7210, 7206, -1, + 7210, 7207, 7206, -1, 7207, 7210, 7209, -1, + 7207, 7209, 7212, -1, 7212, 5788, 7207, -1, + 7212, 5789, 5788, -1, 7212, 7209, 5789, -1, + 7209, 5568, 5789, -1, 7209, 7211, 7213, -1, + 7214, 7213, 7211, -1, 7215, 7213, 7214, -1, + 7214, 7216, 7215, -1, 7214, 7211, 7216, -1, + 7216, 7211, 7206, -1, 7216, 7206, 7205, -1, + 7205, 7217, 7216, -1, 7217, 7205, 7204, -1, + 7204, 7218, 7217, -1, 7218, 7204, 7203, -1, + 7203, 7219, 7218, -1, 7219, 7203, 7202, -1, + 7202, 7220, 7219, -1, 7220, 7202, 7201, -1, + 7201, 7221, 7220, -1, 7221, 7201, 7200, -1, + 7200, 7222, 7221, -1, 7222, 7200, 7199, -1, + 7199, 7223, 7222, -1, 7223, 7199, 7198, -1, + 7198, 7224, 7223, -1, 7224, 7198, 7197, -1, + 7197, 7225, 7224, -1, 7225, 7197, 7196, -1, + 7196, 7226, 7225, -1, 7226, 7196, 7195, -1, + 7195, 7227, 7226, -1, 7227, 7195, 7194, -1, + 7194, 7228, 7227, -1, 7228, 7194, 7193, -1, + 7193, 7229, 7228, -1, 7229, 7193, 7192, -1, + 7192, 7230, 7229, -1, 7230, 7192, 7191, -1, + 7191, 7231, 7230, -1, 7231, 7191, 7190, -1, + 7190, 7232, 7231, -1, 7232, 7190, 7189, -1, + 7189, 7233, 7232, -1, 7233, 7189, 7188, -1, + 7188, 7234, 7233, -1, 7234, 7188, 7187, -1, + 7187, 7235, 7234, -1, 7235, 7187, 7186, -1, + 7186, 7236, 7235, -1, 7236, 7186, 7185, -1, + 7185, 7237, 7236, -1, 7237, 7185, 7184, -1, + 7184, 7238, 7237, -1, 7238, 7184, 7183, -1, + 7183, 7239, 7238, -1, 7239, 7183, 7182, -1, + 7182, 7240, 7239, -1, 7240, 7182, 7181, -1, + 7181, 7241, 7240, -1, 7241, 7181, 7180, -1, + 7180, 7242, 7241, -1, 7242, 7180, 7179, -1, + 7179, 7243, 7242, -1, 7243, 7179, 7178, -1, + 7178, 7244, 7243, -1, 7244, 7178, 7177, -1, + 7177, 7245, 7244, -1, 7245, 7177, 7176, -1, + 7176, 7246, 7245, -1, 7246, 7176, 7175, -1, + 7175, 7247, 7246, -1, 7247, 7175, 7174, -1, + 7174, 7248, 7247, -1, 7248, 7174, 7173, -1, + 7173, 7249, 7248, -1, 7249, 7173, 7172, -1, + 7172, 7250, 7249, -1, 7250, 7172, 7171, -1, + 7171, 7251, 7250, -1, 7251, 7171, 7170, -1, + 7170, 7252, 7251, -1, 7252, 7170, 7169, -1, + 7169, 7253, 7252, -1, 7253, 7169, 7168, -1, + 7168, 7254, 7253, -1, 7254, 7168, 7167, -1, + 7254, 7167, 723, -1, 7254, 723, 722, -1, + 722, 7253, 7254, -1, 7253, 722, 721, -1, + 721, 7252, 7253, -1, 7252, 721, 720, -1, + 720, 7251, 7252, -1, 7251, 720, 719, -1, + 719, 7250, 7251, -1, 7250, 719, 718, -1, + 718, 7249, 7250, -1, 7249, 718, 717, -1, + 717, 7248, 7249, -1, 7248, 717, 716, -1, + 716, 7247, 7248, -1, 7247, 716, 715, -1, + 715, 7246, 7247, -1, 7246, 715, 714, -1, + 714, 7245, 7246, -1, 7245, 714, 713, -1, + 713, 7244, 7245, -1, 7244, 713, 712, -1, + 712, 7243, 7244, -1, 7243, 712, 711, -1, + 711, 7242, 7243, -1, 7242, 711, 710, -1, + 710, 7241, 7242, -1, 7241, 710, 709, -1, + 709, 7240, 7241, -1, 7240, 709, 708, -1, + 708, 7239, 7240, -1, 7239, 708, 707, -1, + 707, 7238, 7239, -1, 7238, 707, 706, -1, + 706, 7237, 7238, -1, 7237, 706, 705, -1, + 705, 7236, 7237, -1, 7236, 705, 704, -1, + 704, 7235, 7236, -1, 7235, 704, 703, -1, + 703, 7234, 7235, -1, 7234, 703, 702, -1, + 702, 7233, 7234, -1, 7233, 702, 701, -1, + 701, 7232, 7233, -1, 7232, 701, 700, -1, + 700, 7231, 7232, -1, 7231, 700, 699, -1, + 699, 7230, 7231, -1, 7230, 699, 698, -1, + 698, 7229, 7230, -1, 7229, 698, 697, -1, + 697, 7228, 7229, -1, 7228, 697, 696, -1, + 696, 7227, 7228, -1, 7227, 696, 695, -1, + 695, 7226, 7227, -1, 7226, 695, 694, -1, + 694, 7225, 7226, -1, 7225, 694, 693, -1, + 693, 7224, 7225, -1, 7224, 693, 692, -1, + 692, 7223, 7224, -1, 7223, 692, 691, -1, + 691, 7222, 7223, -1, 7222, 691, 690, -1, + 690, 7221, 7222, -1, 7221, 690, 689, -1, + 689, 7220, 7221, -1, 7220, 689, 688, -1, + 688, 7219, 7220, -1, 7219, 688, 687, -1, + 687, 7218, 7219, -1, 7218, 687, 686, -1, + 686, 7217, 7218, -1, 7217, 686, 685, -1, + 685, 7216, 7217, -1, 685, 7215, 7216, -1, + 7215, 685, 7255, -1, 7255, 7213, 7215, -1, + 7255, 7256, 7213, -1, 7256, 7255, 685, -1, + 7256, 685, 604, -1, 604, 7213, 7256, -1, + 7213, 604, 603, -1, 459, 603, 608, -1, + 7257, 459, 608, -1, 608, 7258, 7257, -1, + 608, 607, 7258, -1, 7258, 607, 609, -1, + 7258, 609, 681, -1, 681, 7259, 7258, -1, + 7259, 681, 679, -1, 679, 7260, 7259, -1, + 7260, 679, 677, -1, 677, 7261, 7260, -1, + 7261, 677, 675, -1, 675, 7262, 7261, -1, + 7262, 675, 673, -1, 673, 7263, 7262, -1, + 7263, 673, 671, -1, 671, 7264, 7263, -1, + 7264, 671, 669, -1, 669, 7265, 7264, -1, + 7265, 669, 667, -1, 667, 7266, 7265, -1, + 7266, 667, 665, -1, 665, 7267, 7266, -1, + 7267, 665, 663, -1, 663, 7268, 7267, -1, + 7268, 663, 661, -1, 661, 7269, 7268, -1, + 7269, 661, 659, -1, 659, 7270, 7269, -1, + 7270, 659, 657, -1, 657, 7271, 7270, -1, + 7271, 657, 655, -1, 655, 7272, 7271, -1, + 7272, 655, 653, -1, 653, 7273, 7272, -1, + 7273, 653, 651, -1, 651, 7274, 7273, -1, + 7274, 651, 649, -1, 649, 7275, 7274, -1, + 7275, 649, 647, -1, 647, 7276, 7275, -1, + 7276, 647, 645, -1, 645, 7277, 7276, -1, + 7277, 645, 643, -1, 643, 7278, 7277, -1, + 7278, 643, 641, -1, 641, 7279, 7278, -1, + 7279, 641, 639, -1, 639, 7280, 7279, -1, + 7280, 639, 637, -1, 637, 7281, 7280, -1, + 7281, 637, 635, -1, 635, 7282, 7281, -1, + 7282, 635, 633, -1, 633, 7283, 7282, -1, + 7283, 633, 631, -1, 631, 7284, 7283, -1, + 7284, 631, 629, -1, 629, 7285, 7284, -1, + 7285, 629, 627, -1, 627, 7286, 7285, -1, + 7286, 627, 625, -1, 625, 7287, 7286, -1, + 7287, 625, 623, -1, 623, 7288, 7287, -1, + 7288, 623, 621, -1, 621, 7289, 7288, -1, + 7289, 621, 619, -1, 619, 7290, 7289, -1, + 7290, 619, 617, -1, 617, 7291, 7290, -1, + 7291, 617, 615, -1, 615, 7292, 7291, -1, + 7292, 615, 613, -1, 613, 7293, 7292, -1, + 7293, 613, 610, -1, 610, 601, 7293, -1, + 601, 7294, 7293, -1, 601, 600, 7294, -1, + 7295, 7296, 7297, -1, 7295, 7298, 7296, -1, + 7299, 7300, 7301, -1, 7299, 7301, 7302, -1, + 7302, 7303, 7299, -1, 7303, 7302, 7304, -1, + 7304, 7305, 7303, -1, 7305, 7304, 7306, -1, + 7306, 7307, 7305, -1, 7306, 7308, 7307, -1, + 7308, 7306, 7309, -1, 7309, 7310, 7308, -1, + 7310, 7309, 7298, -1, 7298, 7295, 7310, -1, + 7294, 7295, 7311, -1, 7294, 7310, 7295, -1, + 7310, 7294, 600, -1, 600, 7308, 7310, -1, + 7308, 600, 598, -1, 598, 7307, 7308, -1, + 7307, 598, 595, -1, 7307, 595, 593, -1, + 593, 7305, 7307, -1, 7305, 593, 591, -1, + 591, 7303, 7305, -1, 7303, 591, 590, -1, + 590, 7299, 7303, -1, 590, 7312, 7299, -1, + 7313, 7314, 7315, -1, 7314, 7313, 7316, -1, + 7316, 7317, 7314, -1, 7317, 7316, 7318, -1, + 7318, 7319, 7317, -1, 7319, 7318, 7320, -1, + 7320, 7321, 7319, -1, 7321, 7320, 7322, -1, + 7322, 7323, 7321, -1, 7323, 7322, 7324, -1, + 7324, 7325, 7323, -1, 7325, 7324, 7326, -1, + 7326, 7327, 7325, -1, 7327, 7326, 7328, -1, + 7328, 7329, 7327, -1, 7329, 7328, 7330, -1, + 7330, 7331, 7329, -1, 7331, 7330, 7332, -1, + 7332, 7333, 7331, -1, 7333, 7332, 7334, -1, + 7334, 7335, 7333, -1, 7335, 7334, 7336, -1, + 7336, 7337, 7335, -1, 7337, 7336, 7338, -1, + 7338, 7339, 7337, -1, 7339, 7338, 7340, -1, + 7340, 7341, 7339, -1, 7341, 7340, 7342, -1, + 7342, 7343, 7341, -1, 7343, 7342, 7344, -1, + 7344, 7345, 7343, -1, 7345, 7344, 7346, -1, + 7346, 7347, 7345, -1, 7347, 7346, 7348, -1, + 7348, 7312, 7347, -1, 7348, 7299, 7312, -1, + 7348, 7300, 7299, -1, 7300, 7348, 7346, -1, + 7346, 7349, 7300, -1, 7349, 7346, 7344, -1, + 7344, 7350, 7349, -1, 7350, 7344, 7342, -1, + 7342, 7351, 7350, -1, 7351, 7342, 7340, -1, + 7340, 7352, 7351, -1, 7352, 7340, 7338, -1, + 7338, 7353, 7352, -1, 7353, 7338, 7336, -1, + 7336, 7354, 7353, -1, 7354, 7336, 7334, -1, + 7334, 7355, 7354, -1, 7355, 7334, 7332, -1, + 7332, 7356, 7355, -1, 7356, 7332, 7330, -1, + 7330, 7357, 7356, -1, 7357, 7330, 7328, -1, + 7328, 7358, 7357, -1, 7358, 7328, 7326, -1, + 7326, 7359, 7358, -1, 7359, 7326, 7324, -1, + 7324, 7360, 7359, -1, 7360, 7324, 7322, -1, + 7322, 7361, 7360, -1, 7361, 7322, 7320, -1, + 7320, 7362, 7361, -1, 7362, 7320, 7318, -1, + 7318, 7363, 7362, -1, 7363, 7318, 7316, -1, + 7316, 7364, 7363, -1, 7364, 7316, 7313, -1, + 7313, 7365, 7364, -1, 7365, 7313, 7315, -1, + 7315, 7366, 7365, -1, 7366, 7315, 7367, -1, + 7367, 7368, 7366, -1, 7368, 7367, 7369, -1, + 7369, 7370, 7368, -1, 7370, 7369, 7371, -1, + 7371, 7372, 7370, -1, 7372, 7371, 7373, -1, + 7374, 7375, 7376, -1, 7374, 7377, 7375, -1, + 7377, 7374, 7378, -1, 7378, 7379, 7377, -1, + 7379, 7378, 7380, -1, 7380, 7381, 7379, -1, + 7381, 7380, 7382, -1, 7382, 7383, 7381, -1, + 7383, 7382, 7384, -1, 7384, 7385, 7383, -1, + 7385, 7384, 7386, -1, 7386, 7387, 7385, -1, + 7387, 7386, 7388, -1, 7388, 7389, 7387, -1, + 7389, 7388, 7390, -1, 7390, 7391, 7389, -1, + 7391, 7390, 7392, -1, 7392, 7393, 7391, -1, + 7393, 7392, 7394, -1, 7394, 7395, 7393, -1, + 7395, 7394, 7396, -1, 7396, 7397, 7395, -1, + 7397, 7396, 7373, -1, 7373, 7398, 7397, -1, + 7398, 7373, 7371, -1, 7371, 7399, 7398, -1, + 7399, 7371, 7369, -1, 7369, 7400, 7399, -1, + 7369, 7367, 7400, -1, 7401, 7400, 7367, -1, + 7401, 7367, 7315, -1, 7315, 7402, 7401, -1, + 7402, 7315, 7314, -1, 7314, 7403, 7402, -1, + 7403, 7314, 7317, -1, 7317, 7404, 7403, -1, + 7404, 7317, 7319, -1, 7319, 7405, 7404, -1, + 7405, 7319, 7321, -1, 7321, 7406, 7405, -1, + 7406, 7321, 7323, -1, 7323, 7407, 7406, -1, + 7407, 7323, 7325, -1, 7325, 7408, 7407, -1, + 7408, 7325, 7327, -1, 7327, 7409, 7408, -1, + 7409, 7327, 7329, -1, 7329, 7410, 7409, -1, + 7410, 7329, 7331, -1, 7331, 7411, 7410, -1, + 7411, 7331, 7333, -1, 7333, 7412, 7411, -1, + 7412, 7333, 7335, -1, 7335, 7413, 7412, -1, + 7413, 7335, 7337, -1, 7337, 7414, 7413, -1, + 7414, 7337, 7339, -1, 7339, 7415, 7414, -1, + 7415, 7339, 7341, -1, 7341, 7416, 7415, -1, + 7416, 7341, 7343, -1, 7343, 7417, 7416, -1, + 7417, 7343, 7345, -1, 7345, 7418, 7417, -1, + 7418, 7345, 7347, -1, 7347, 7419, 7418, -1, + 7419, 7347, 7312, -1, 7312, 7420, 7419, -1, + 7420, 7312, 590, -1, 7420, 590, 589, -1, + 7420, 589, 731, -1, 731, 7419, 7420, -1, + 7419, 731, 733, -1, 733, 7418, 7419, -1, + 7418, 733, 735, -1, 735, 7417, 7418, -1, + 7417, 735, 737, -1, 737, 7416, 7417, -1, + 7416, 737, 739, -1, 739, 7415, 7416, -1, + 7415, 739, 741, -1, 741, 7414, 7415, -1, + 7414, 741, 743, -1, 743, 7413, 7414, -1, + 7413, 743, 745, -1, 745, 7412, 7413, -1, + 7412, 745, 747, -1, 747, 7411, 7412, -1, + 7411, 747, 749, -1, 749, 7410, 7411, -1, + 7410, 749, 751, -1, 751, 7409, 7410, -1, + 7409, 751, 753, -1, 753, 7408, 7409, -1, + 7408, 753, 755, -1, 755, 7407, 7408, -1, + 7407, 755, 757, -1, 757, 7406, 7407, -1, + 7406, 757, 759, -1, 759, 7405, 7406, -1, + 7405, 759, 761, -1, 761, 7404, 7405, -1, + 7404, 761, 763, -1, 763, 7403, 7404, -1, + 7403, 763, 765, -1, 765, 7402, 7403, -1, + 7402, 765, 767, -1, 767, 7401, 7402, -1, + 7401, 767, 800, -1, 800, 7400, 7401, -1, + 7400, 800, 798, -1, 798, 7399, 7400, -1, + 7399, 798, 796, -1, 796, 7398, 7399, -1, + 7398, 796, 794, -1, 794, 7397, 7398, -1, + 7397, 794, 792, -1, 792, 7395, 7397, -1, + 7395, 792, 790, -1, 790, 7393, 7395, -1, + 7393, 790, 788, -1, 788, 7391, 7393, -1, + 7391, 788, 786, -1, 786, 7389, 7391, -1, + 7389, 786, 784, -1, 784, 7387, 7389, -1, + 7387, 784, 782, -1, 782, 7385, 7387, -1, + 7385, 782, 780, -1, 780, 7383, 7385, -1, + 7383, 780, 778, -1, 778, 7381, 7383, -1, + 7381, 778, 776, -1, 776, 7379, 7381, -1, + 7379, 776, 774, -1, 774, 7377, 7379, -1, + 7377, 774, 772, -1, 772, 7375, 7377, -1, + 7375, 772, 768, -1, 7375, 768, 824, -1, + 824, 7421, 7375, -1, 7421, 824, 825, -1, + 7421, 825, 7422, -1, 7422, 7375, 7421, -1, + 7422, 7376, 7375, -1, 7376, 7422, 825, -1, + 7376, 825, 827, -1, 827, 7374, 7376, -1, + 827, 7423, 7374, -1, 827, 826, 7423, -1, + 7423, 826, 6687, -1, 6687, 6688, 7423, -1, + 6688, 7374, 7423, -1, 6688, 7378, 7374, -1, + 7378, 6688, 6690, -1, 6690, 7380, 7378, -1, + 7380, 6690, 6859, -1, 6859, 7382, 7380, -1, + 7382, 6859, 6857, -1, 6857, 7384, 7382, -1, + 7384, 6857, 6855, -1, 6855, 7386, 7384, -1, + 7386, 6855, 6853, -1, 6853, 7388, 7386, -1, + 7388, 6853, 6851, -1, 6851, 7390, 7388, -1, + 7390, 6851, 6849, -1, 6849, 7392, 7390, -1, + 7392, 6849, 6847, -1, 6847, 7394, 7392, -1, + 7394, 6847, 6845, -1, 6845, 7396, 7394, -1, + 7396, 6845, 6843, -1, 6843, 7373, 7396, -1, + 7373, 6843, 6842, -1, 6842, 7372, 7373, -1, + 7372, 6842, 6841, -1, 6841, 7370, 7372, -1, + 7370, 6841, 6840, -1, 6840, 7368, 7370, -1, + 7368, 6840, 6839, -1, 6839, 7366, 7368, -1, + 7366, 6839, 6693, -1, 6693, 7365, 7366, -1, + 7365, 6693, 6692, -1, 6692, 7364, 7365, -1, + 7364, 6692, 6695, -1, 6695, 7363, 7364, -1, + 7363, 6695, 6697, -1, 6697, 7362, 7363, -1, + 7362, 6697, 6699, -1, 6699, 7361, 7362, -1, + 7361, 6699, 6701, -1, 6701, 7360, 7361, -1, + 7360, 6701, 6703, -1, 6703, 7359, 7360, -1, + 7359, 6703, 6705, -1, 6705, 7358, 7359, -1, + 7358, 6705, 6707, -1, 6707, 7357, 7358, -1, + 7357, 6707, 6709, -1, 6709, 7356, 7357, -1, + 7356, 6709, 6711, -1, 6711, 7355, 7356, -1, + 7355, 6711, 6713, -1, 6713, 7354, 7355, -1, + 7354, 6713, 6715, -1, 6715, 7353, 7354, -1, + 7353, 6715, 6717, -1, 6717, 7352, 7353, -1, + 7352, 6717, 6719, -1, 6719, 7351, 7352, -1, + 7351, 6719, 6721, -1, 6721, 7350, 7351, -1, + 7350, 6721, 6723, -1, 6723, 7349, 7350, -1, + 7349, 6723, 6725, -1, 6725, 7300, 7349, -1, + 6725, 7301, 7300, -1, 6725, 6724, 7301, -1, + 7301, 6724, 6795, -1, 7301, 6795, 6794, -1, + 6794, 7302, 7301, -1, 7302, 6794, 6793, -1, + 6793, 7304, 7302, -1, 7304, 6793, 6792, -1, + 6792, 7306, 7304, -1, 6792, 7309, 7306, -1, + 7309, 6792, 6791, -1, 6791, 7298, 7309, -1, + 7298, 6791, 6790, -1, 6790, 7296, 7298, -1, + 7296, 6790, 6789, -1, 7296, 6789, 7424, -1, + 7425, 7426, 7427, -1, 7427, 7428, 7425, -1, + 7428, 7427, 7429, -1, 7429, 7430, 7428, -1, + 7430, 7429, 7431, -1, 7431, 7432, 7430, -1, + 7432, 7431, 7433, -1, 7433, 7434, 7432, -1, + 7434, 7433, 7435, -1, 7435, 7436, 7434, -1, + 7436, 7435, 7437, -1, 7437, 7438, 7436, -1, + 7438, 7437, 7439, -1, 7439, 7440, 7438, -1, + 7440, 7439, 7441, -1, 7441, 7442, 7440, -1, + 7442, 7441, 7443, -1, 7443, 7444, 7442, -1, + 7444, 7443, 7445, -1, 7445, 7446, 7444, -1, + 7446, 7445, 7447, -1, 7447, 7448, 7446, -1, + 7448, 7447, 7449, -1, 7449, 7450, 7448, -1, + 7450, 7449, 7451, -1, 7451, 7452, 7450, -1, + 7452, 7451, 7453, -1, 7453, 7454, 7452, -1, + 7454, 7453, 7455, -1, 7455, 7456, 7454, -1, + 7456, 7455, 7457, -1, 7457, 7458, 7456, -1, + 7458, 7457, 7424, -1, 7458, 7424, 6789, -1, + 7458, 6789, 6746, -1, 6746, 7456, 7458, -1, + 7456, 6746, 6745, -1, 6745, 7454, 7456, -1, + 7454, 6745, 6787, -1, 6787, 7452, 7454, -1, + 7452, 6787, 6785, -1, 6785, 7450, 7452, -1, + 7450, 6785, 6783, -1, 6783, 7448, 7450, -1, + 7448, 6783, 6781, -1, 6781, 7446, 7448, -1, + 7446, 6781, 6779, -1, 6779, 7444, 7446, -1, + 7444, 6779, 6777, -1, 6777, 7442, 7444, -1, + 7442, 6777, 6775, -1, 6775, 7440, 7442, -1, + 7440, 6775, 6773, -1, 6773, 7438, 7440, -1, + 7438, 6773, 6771, -1, 6771, 7436, 7438, -1, + 7436, 6771, 6769, -1, 6769, 7434, 7436, -1, + 7434, 6769, 6767, -1, 6767, 7432, 7434, -1, + 7432, 6767, 6765, -1, 6765, 7430, 7432, -1, + 7430, 6765, 6763, -1, 6763, 7428, 7430, -1, + 7428, 6763, 6761, -1, 6761, 7425, 7428, -1, + 7425, 6761, 6759, -1, 6759, 7426, 7425, -1, + 7426, 6759, 6757, -1, 6757, 7459, 7426, -1, + 7459, 6757, 6755, -1, 6755, 7460, 7459, -1, + 7460, 6755, 6753, -1, 6753, 7461, 7460, -1, + 7461, 6753, 6751, -1, 6751, 7462, 7461, -1, + 7462, 6751, 6749, -1, 6749, 7463, 7462, -1, + 7463, 6749, 6748, -1, 6748, 7464, 7463, -1, + 7464, 6748, 6975, -1, 6975, 7465, 7464, -1, + 7465, 6975, 6976, -1, 6976, 7466, 7465, -1, + 7466, 6976, 6977, -1, 6977, 7467, 7466, -1, + 7467, 6977, 6978, -1, 6978, 7468, 7467, -1, + 7468, 6978, 6979, -1, 6979, 7469, 7468, -1, + 7469, 6979, 6980, -1, 6980, 7470, 7469, -1, + 7470, 6980, 6981, -1, 6981, 7471, 7470, -1, + 7471, 6981, 6982, -1, 6982, 7472, 7471, -1, + 7472, 6982, 6983, -1, 6983, 6986, 7472, -1, + 7473, 7474, 7475, -1, 7475, 7476, 7473, -1, + 7476, 7475, 7477, -1, 7477, 7478, 7476, -1, + 7478, 7477, 7479, -1, 7479, 7480, 7478, -1, + 7480, 7479, 7481, -1, 7481, 7482, 7480, -1, + 7482, 7481, 7483, -1, 7483, 7484, 7482, -1, + 7485, 7482, 7484, -1, 7484, 7486, 7485, -1, + 7486, 7484, 7487, -1, 7487, 7488, 7486, -1, + 7488, 7487, 7489, -1, 7489, 7490, 7488, -1, + 7490, 7489, 7491, -1, 7491, 7492, 7490, -1, + 7492, 7491, 7493, -1, 7493, 7494, 7492, -1, + 7494, 7493, 7495, -1, 7495, 7496, 7494, -1, + 7496, 7495, 7497, -1, 7497, 7498, 7496, -1, + 7498, 7497, 7499, -1, 7499, 7500, 7498, -1, + 7500, 7499, 7501, -1, 7501, 7502, 7500, -1, + 7502, 7501, 7503, -1, 7503, 7504, 7502, -1, + 7505, 7506, 7507, -1, 7505, 7507, 7504, -1, + 7504, 7503, 7505, -1, 6986, 7508, 7505, -1, + 6986, 7505, 7503, -1, 7503, 7472, 6986, -1, + 7472, 7503, 7501, -1, 7501, 7471, 7472, -1, + 7471, 7501, 7499, -1, 7499, 7470, 7471, -1, + 7470, 7499, 7497, -1, 7497, 7469, 7470, -1, + 7469, 7497, 7495, -1, 7495, 7468, 7469, -1, + 7468, 7495, 7493, -1, 7493, 7467, 7468, -1, + 7467, 7493, 7491, -1, 7491, 7466, 7467, -1, + 7466, 7491, 7489, -1, 7489, 7465, 7466, -1, + 7465, 7489, 7487, -1, 7487, 7464, 7465, -1, + 7464, 7487, 7484, -1, 7484, 7463, 7464, -1, + 7463, 7484, 7483, -1, 7483, 7462, 7463, -1, + 7462, 7483, 7481, -1, 7481, 7461, 7462, -1, + 7461, 7481, 7479, -1, 7479, 7460, 7461, -1, + 7460, 7479, 7477, -1, 7477, 7459, 7460, -1, + 7459, 7477, 7475, -1, 7475, 7426, 7459, -1, + 7426, 7475, 7474, -1, 7474, 7427, 7426, -1, + 7427, 7474, 7509, -1, 7509, 7429, 7427, -1, + 7429, 7509, 7510, -1, 7510, 7431, 7429, -1, + 7431, 7510, 7511, -1, 7511, 7433, 7431, -1, + 7433, 7511, 7512, -1, 7512, 7435, 7433, -1, + 7435, 7512, 7513, -1, 7513, 7437, 7435, -1, + 7437, 7513, 7514, -1, 7514, 7439, 7437, -1, + 7439, 7514, 7515, -1, 7515, 7441, 7439, -1, + 7441, 7515, 7516, -1, 7516, 7443, 7441, -1, + 7443, 7516, 7517, -1, 7517, 7445, 7443, -1, + 7445, 7517, 7518, -1, 7518, 7447, 7445, -1, + 7447, 7518, 7519, -1, 7519, 7449, 7447, -1, + 7449, 7519, 7520, -1, 7520, 7451, 7449, -1, + 7451, 7520, 7521, -1, 7521, 7453, 7451, -1, + 7453, 7521, 7522, -1, 7522, 7455, 7453, -1, + 7455, 7522, 7523, -1, 7523, 7457, 7455, -1, + 7457, 7523, 7524, -1, 7524, 7424, 7457, -1, + 7424, 7524, 7525, -1, 7525, 7296, 7424, -1, + 7525, 7297, 7296, -1, 7525, 7526, 7297, -1, + 7526, 7525, 7524, -1, 7524, 7527, 7526, -1, + 7527, 7524, 7523, -1, 7523, 7528, 7527, -1, + 7528, 7523, 7522, -1, 7522, 7529, 7528, -1, + 7529, 7522, 7521, -1, 7521, 7530, 7529, -1, + 7530, 7521, 7520, -1, 7520, 7531, 7530, -1, + 7531, 7520, 7519, -1, 7519, 7532, 7531, -1, + 7532, 7519, 7518, -1, 7518, 7533, 7532, -1, + 7533, 7518, 7517, -1, 7517, 7534, 7533, -1, + 7534, 7517, 7516, -1, 7516, 7535, 7534, -1, + 7535, 7516, 7515, -1, 7515, 7536, 7535, -1, + 7536, 7515, 7514, -1, 7514, 7537, 7536, -1, + 7537, 7514, 7513, -1, 7513, 7538, 7537, -1, + 7538, 7513, 7512, -1, 7512, 7539, 7538, -1, + 7539, 7512, 7511, -1, 7511, 7540, 7539, -1, + 7540, 7511, 7510, -1, 7510, 7541, 7540, -1, + 7541, 7510, 7509, -1, 7509, 7542, 7541, -1, + 7542, 7509, 7474, -1, 7474, 7473, 7542, -1, + 7542, 7473, 7543, -1, 7543, 7541, 7542, -1, + 7541, 7543, 7544, -1, 7544, 7540, 7541, -1, + 7540, 7544, 7545, -1, 7545, 7539, 7540, -1, + 7539, 7545, 7546, -1, 7546, 7538, 7539, -1, + 7538, 7546, 7547, -1, 7547, 7537, 7538, -1, + 7537, 7547, 7548, -1, 7548, 7536, 7537, -1, + 7536, 7548, 7549, -1, 7549, 7535, 7536, -1, + 7535, 7549, 7550, -1, 7550, 7534, 7535, -1, + 7534, 7550, 7551, -1, 7551, 7533, 7534, -1, + 7533, 7551, 7552, -1, 7552, 7532, 7533, -1, + 7532, 7552, 7553, -1, 7553, 7531, 7532, -1, + 7531, 7553, 7554, -1, 7554, 7530, 7531, -1, + 7530, 7554, 7555, -1, 7555, 7529, 7530, -1, + 7529, 7555, 7556, -1, 7556, 7528, 7529, -1, + 7528, 7556, 7557, -1, 7557, 7527, 7528, -1, + 7527, 7557, 7558, -1, 7558, 7526, 7527, -1, + 7526, 7558, 7559, -1, 7559, 7297, 7526, -1, + 7297, 7559, 7560, -1, 7560, 7295, 7297, -1, + 7560, 7311, 7295, -1, 7560, 7561, 7311, -1, + 7561, 7560, 7559, -1, 7559, 7562, 7561, -1, + 7562, 7559, 7558, -1, 7558, 7563, 7562, -1, + 7563, 7558, 7557, -1, 7557, 7564, 7563, -1, + 7564, 7557, 7556, -1, 7556, 7565, 7564, -1, + 7565, 7556, 7555, -1, 7555, 7566, 7565, -1, + 7566, 7555, 7554, -1, 7554, 7567, 7566, -1, + 7567, 7554, 7553, -1, 7553, 7568, 7567, -1, + 7568, 7553, 7552, -1, 7552, 7569, 7568, -1, + 7569, 7552, 7551, -1, 7551, 7570, 7569, -1, + 7570, 7551, 7550, -1, 7550, 7571, 7570, -1, + 7571, 7550, 7549, -1, 7549, 7572, 7571, -1, + 7572, 7549, 7548, -1, 7548, 7573, 7572, -1, + 7573, 7548, 7547, -1, 7547, 7574, 7573, -1, + 7574, 7547, 7546, -1, 7546, 7575, 7574, -1, + 7575, 7546, 7545, -1, 7545, 7576, 7575, -1, + 7576, 7545, 7544, -1, 7544, 7577, 7576, -1, + 7577, 7544, 7543, -1, 7543, 7578, 7577, -1, + 7578, 7543, 7473, -1, 7473, 7579, 7578, -1, + 7579, 7473, 7476, -1, 7476, 7580, 7579, -1, + 7580, 7476, 7478, -1, 7478, 7581, 7580, -1, + 7581, 7478, 7480, -1, 7480, 7582, 7581, -1, + 7582, 7480, 7482, -1, 7482, 7485, 7582, -1, + 7582, 7485, 7583, -1, 7583, 7581, 7582, -1, + 7581, 7583, 7584, -1, 7584, 7580, 7581, -1, + 7580, 7584, 7585, -1, 7585, 7579, 7580, -1, + 7579, 7585, 7586, -1, 7586, 7578, 7579, -1, + 7578, 7586, 7587, -1, 7587, 7577, 7578, -1, + 7577, 7587, 7588, -1, 7588, 7576, 7577, -1, + 7576, 7588, 7589, -1, 7589, 7575, 7576, -1, + 7575, 7589, 7590, -1, 7590, 7574, 7575, -1, + 7574, 7590, 7591, -1, 7591, 7573, 7574, -1, + 7573, 7591, 7592, -1, 7592, 7572, 7573, -1, + 7572, 7592, 7593, -1, 7593, 7571, 7572, -1, + 7571, 7593, 7594, -1, 7594, 7570, 7571, -1, + 7570, 7594, 7595, -1, 7595, 7569, 7570, -1, + 7569, 7595, 7596, -1, 7596, 7568, 7569, -1, + 7568, 7596, 7597, -1, 7597, 7567, 7568, -1, + 7567, 7597, 7598, -1, 7598, 7566, 7567, -1, + 7566, 7598, 7599, -1, 7599, 7565, 7566, -1, + 7565, 7599, 7600, -1, 7600, 7564, 7565, -1, + 7564, 7600, 7601, -1, 7601, 7563, 7564, -1, + 7563, 7601, 7602, -1, 7602, 7562, 7563, -1, + 7562, 7602, 7603, -1, 7603, 7561, 7562, -1, + 7561, 7603, 7604, -1, 7604, 7311, 7561, -1, + 7311, 7604, 7605, -1, 7605, 7294, 7311, -1, + 7605, 7293, 7294, -1, 7605, 7292, 7293, -1, + 7292, 7605, 7604, -1, 7604, 7291, 7292, -1, + 7291, 7604, 7603, -1, 7603, 7290, 7291, -1, + 7290, 7603, 7602, -1, 7602, 7289, 7290, -1, + 7289, 7602, 7601, -1, 7601, 7288, 7289, -1, + 7288, 7601, 7600, -1, 7600, 7287, 7288, -1, + 7287, 7600, 7599, -1, 7599, 7286, 7287, -1, + 7286, 7599, 7598, -1, 7598, 7285, 7286, -1, + 7285, 7598, 7597, -1, 7597, 7284, 7285, -1, + 7284, 7597, 7596, -1, 7596, 7283, 7284, -1, + 7283, 7596, 7595, -1, 7595, 7282, 7283, -1, + 7282, 7595, 7594, -1, 7594, 7281, 7282, -1, + 7281, 7594, 7593, -1, 7593, 7280, 7281, -1, + 7280, 7593, 7592, -1, 7592, 7279, 7280, -1, + 7279, 7592, 7591, -1, 7591, 7278, 7279, -1, + 7278, 7591, 7590, -1, 7590, 7277, 7278, -1, + 7277, 7590, 7589, -1, 7589, 7276, 7277, -1, + 7276, 7589, 7588, -1, 7588, 7275, 7276, -1, + 7275, 7588, 7587, -1, 7587, 7274, 7275, -1, + 7274, 7587, 7586, -1, 7586, 7273, 7274, -1, + 7273, 7586, 7585, -1, 7585, 7272, 7273, -1, + 7272, 7585, 7584, -1, 7584, 7271, 7272, -1, + 7271, 7584, 7583, -1, 7583, 7270, 7271, -1, + 7270, 7583, 7485, -1, 7485, 7269, 7270, -1, + 7269, 7485, 7486, -1, 7486, 7268, 7269, -1, + 7268, 7486, 7488, -1, 7488, 7267, 7268, -1, + 7267, 7488, 7490, -1, 7490, 7266, 7267, -1, + 7266, 7490, 7492, -1, 7492, 7265, 7266, -1, + 7265, 7492, 7494, -1, 7494, 7264, 7265, -1, + 7264, 7494, 7496, -1, 7496, 7263, 7264, -1, + 7263, 7496, 7498, -1, 7498, 7262, 7263, -1, + 7262, 7498, 7500, -1, 7500, 7261, 7262, -1, + 7261, 7500, 7502, -1, 7502, 7260, 7261, -1, + 7260, 7502, 7504, -1, 7504, 7259, 7260, -1, + 7259, 7504, 7507, -1, 7507, 7258, 7259, -1, + 7507, 7257, 7258, -1, 7257, 7507, 7606, -1, + 7606, 459, 7257, -1, 7606, 7607, 459, -1, + 7607, 7606, 7507, -1, 7607, 7507, 7506, -1, + 7506, 459, 7607, -1, 7506, 460, 459, -1, + 460, 7506, 7505, -1, 460, 7505, 7508, -1, + 7508, 458, 460, -1, 7508, 7608, 458, -1, + 7608, 7508, 6986, -1, 7608, 6986, 6985, -1, + 6985, 458, 7608, -1, 6985, 6987, 458, -1, + 6987, 6988, 458, -1, 458, 6988, 6989, -1, + 456, 1582, 1584, -1, 1584, 7609, 456, -1, + 7609, 1584, 1585, -1, 7609, 1585, 7610, -1, + 7610, 456, 7609, -1, 7610, 457, 456, -1, + 7610, 453, 457, -1, 453, 7610, 1585, -1, + 453, 1585, 1586, -1, 1586, 451, 453, -1, + 451, 1586, 1587, -1, 1587, 449, 451, -1, + 449, 1587, 1588, -1, 1588, 447, 449, -1, + 447, 1588, 1589, -1, 1589, 446, 447, -1, + 446, 1589, 1590, -1, 446, 1590, 1591, -1, + 1591, 444, 446, -1, 444, 1591, 1592, -1, + 1592, 442, 444, -1, 442, 1592, 1593, -1, + 1593, 440, 442, -1, 440, 1593, 1594, -1, + 1594, 438, 440, -1, 438, 1594, 1595, -1, + 438, 1595, 1597, -1, 1597, 437, 438, -1, + 1597, 435, 437, -1, 1597, 1596, 435, -1, + 1596, 1598, 435, -1, 435, 1598, 1600, -1, + 414, 436, 435, -1, 7611, 436, 414, -1, + 7611, 439, 436, -1, 7611, 7612, 439, -1, + 7612, 7611, 414, -1, 7612, 414, 413, -1, + 7612, 413, 415, -1, 415, 439, 7612, -1, + 415, 441, 439, -1, 441, 415, 427, -1, + 427, 443, 441, -1, 443, 427, 428, -1, + 428, 445, 443, -1, 428, 448, 445, -1, + 448, 428, 429, -1, 429, 450, 448, -1, + 450, 429, 430, -1, 430, 452, 450, -1, + 430, 7613, 452, -1, 7613, 430, 432, -1, + 7613, 432, 433, -1, 7613, 433, 7614, -1, + 7614, 452, 7613, -1, 7614, 454, 452, -1, + 454, 7614, 433, -1, 433, 456, 454, -1, + 2210, 5558, 5559, -1, 5558, 2210, 2215, -1, + 2215, 2217, 5558, -1, 2217, 5555, 5558, -1, + 5555, 2217, 2219, -1, 2219, 5554, 5555, -1, + 5554, 2219, 2221, -1, 2221, 5553, 5554, -1, + 5553, 2221, 2223, -1, 2223, 5552, 5553, -1, + 5552, 2223, 2225, -1, 2225, 5551, 5552, -1, + 5551, 2225, 2227, -1, 2227, 5550, 5551, -1, + 5550, 2227, 2229, -1, 2229, 5549, 5550, -1, + 5549, 2229, 2231, -1, 2231, 5548, 5549, -1, + 5548, 2231, 2233, -1, 2233, 5547, 5548, -1, + 5547, 2233, 2235, -1, 2235, 5546, 5547, -1, + 5546, 2235, 2237, -1, 2237, 5545, 5546, -1, + 5545, 2237, 2239, -1, 2239, 5544, 5545, -1, + 5544, 2239, 2241, -1, 2241, 5543, 5544, -1, + 5543, 2241, 2243, -1, 2243, 5542, 5543, -1, + 5542, 2243, 2245, -1, 2245, 5541, 5542, -1, + 5541, 2245, 2247, -1, 2247, 5540, 5541, -1, + 5540, 2247, 2249, -1, 2249, 5539, 5540, -1, + 5539, 2249, 2251, -1, 2251, 5538, 5539, -1, + 5538, 2251, 2253, -1, 2253, 5537, 5538, -1, + 5537, 2253, 2255, -1, 2255, 5536, 5537, -1, + 5536, 2255, 2257, -1, 2257, 5535, 5536, -1, + 5535, 2257, 2259, -1, 2259, 5534, 5535, -1, + 5534, 2259, 2261, -1, 2261, 5533, 5534, -1, + 5533, 2261, 2263, -1, 2263, 5532, 5533, -1, + 5532, 2263, 2265, -1, 2265, 5531, 5532, -1, + 5531, 2265, 2267, -1, 2267, 5530, 5531, -1, + 5530, 2267, 2269, -1, 2269, 5529, 5530, -1, + 5529, 2269, 2271, -1, 2271, 5528, 5529, -1, + 5528, 2271, 2273, -1, 2273, 5527, 5528, -1, + 5527, 2273, 2275, -1, 2275, 5526, 5527, -1, + 5526, 2275, 2277, -1, 2277, 5525, 5526, -1, + 5525, 2277, 2279, -1, 2279, 5524, 5525, -1, + 5524, 2279, 2281, -1, 2281, 5523, 5524, -1, + 5523, 2281, 2283, -1, 2283, 5522, 5523, -1, + 5522, 2283, 2285, -1, 2285, 5521, 5522, -1, + 5521, 2285, 2287, -1, 2287, 5520, 5521, -1, + 5520, 2287, 2289, -1, 2289, 5519, 5520, -1, + 5519, 2289, 2291, -1, 2291, 5518, 5519, -1, + 5518, 2291, 2293, -1, 2293, 5517, 5518, -1, + 5517, 2293, 2295, -1, 2295, 5516, 5517, -1, + 5516, 2295, 2297, -1, 2297, 5515, 5516, -1, + 5515, 2297, 2299, -1, 2299, 5514, 5515, -1, + 5514, 2299, 2301, -1, 2301, 5513, 5514, -1, + 5513, 2301, 2303, -1, 2303, 5512, 5513, -1, + 5512, 2303, 5005, -1, 5005, 5511, 5512, -1, + 5511, 5005, 5004, -1, 5004, 5510, 5511, -1, + 5510, 5004, 5003, -1, 5003, 5509, 5510, -1, + 5509, 5003, 2306, -1, 2306, 5506, 5509, -1, + 5506, 2306, 2305, -1, 2305, 5504, 5506, -1, + 5504, 2305, 2308, -1, 2308, 5507, 5504, -1, + 5507, 2308, 2310, -1, 2310, 5503, 5507, -1, + 5503, 2310, 2312, -1, 2312, 5502, 5503, -1, + 5502, 2312, 2314, -1, 2314, 5374, 5502, -1, + 2314, 5375, 5374, -1, 2314, 2313, 5375, -1, + 5375, 2313, 4980, -1, 5375, 4980, 4984, -1, + 4984, 5376, 5375, -1, 5376, 4984, 4985, -1, + 4985, 5377, 5376, -1, 5377, 4985, 4987, -1, + 7615, 5377, 4987, -1, 7615, 5378, 5377, -1, + 7615, 5380, 5378, -1, 7615, 4987, 5380, -1, + 5380, 4987, 4976, -1, 7616, 3082, 3080, -1, + 7617, 7616, 3080, -1, 3080, 3052, 7617, -1, + 7617, 3052, 3054, -1, 3054, 7616, 7617, -1, + 3054, 7618, 7616, -1, 7618, 3054, 3053, -1, + 7618, 3053, 3055, -1, 3055, 7616, 7618, -1, + 3055, 7619, 7616, -1, 7619, 3055, 2695, -1, + 7619, 2695, 2697, -1, 2697, 2700, 7619, -1, + 2700, 7616, 7619, -1, 2700, 7620, 1138, -1, + 7620, 2700, 2701, -1, 7620, 2701, 2702, -1, + 7620, 2702, 2704, -1, 2704, 1138, 7620, -1, + 7621, 1138, 2704, -1, 7621, 2704, 2703, -1, + 7621, 2703, 2705, -1, 2705, 1138, 7621, -1, + 2705, 2706, 1138, -1, 2706, 1139, 1138, -1, + 1139, 2706, 2707, -1, 1139, 2707, 2709, -1, + 2709, 1140, 1139, -1, 7622, 1140, 2709, -1, + 7622, 2709, 2708, -1, 7622, 2708, 7623, -1, + 7623, 1140, 7622, -1, 7623, 7624, 1140, -1, + 7623, 2708, 7624, -1, 2708, 2710, 7624, -1, + 7625, 7624, 2710, -1, 7625, 1140, 7624, -1, + 7625, 5362, 1140, -1, 7625, 2710, 5362, -1, + 2710, 5359, 5362, -1, 5359, 2710, 2712, -1, + 2712, 5358, 5359, -1, 5358, 2712, 2714, -1, + 2714, 5357, 5358, -1, 5357, 2714, 2716, -1, + 2716, 3477, 5357, -1, 3477, 2716, 2718, -1, + 2718, 3475, 3477, -1, 3475, 2718, 2720, -1, + 2720, 3479, 3475, -1, 3479, 2720, 2722, -1, + 2722, 3481, 3479, -1, 3481, 2722, 2724, -1, + 2724, 3483, 3481, -1, 3483, 2724, 2726, -1, + 2726, 3485, 3483, -1, 2726, 7626, 3485, -1, + 7626, 2726, 2727, -1, 2727, 7627, 7626, -1, + 7627, 2727, 2736, -1, 2736, 7628, 7627, -1, + 7628, 2736, 2737, -1, 2737, 7629, 7628, -1, + 7629, 2737, 2738, -1, 2738, 7630, 7629, -1, + 7630, 2738, 2739, -1, 2739, 7631, 7630, -1, + 7631, 2739, 2740, -1, 2740, 7632, 7631, -1, + 7632, 2740, 2741, -1, 2741, 7633, 7632, -1, + 7633, 2741, 2742, -1, 2742, 7634, 7633, -1, + 7634, 2742, 2743, -1, 2743, 7635, 7634, -1, + 7635, 2743, 2744, -1, 2744, 7636, 7635, -1, + 7636, 2744, 2745, -1, 2745, 7637, 7636, -1, + 7637, 2745, 2746, -1, 2746, 7638, 7637, -1, + 7638, 2746, 2747, -1, 2747, 7639, 7638, -1, + 7639, 2747, 2748, -1, 2748, 7640, 7639, -1, + 7640, 2748, 2749, -1, 2749, 7641, 7640, -1, + 7641, 2749, 2750, -1, 2750, 7642, 7641, -1, + 7642, 2750, 2751, -1, 2751, 7643, 7642, -1, + 2751, 7644, 7643, -1, 7644, 2751, 2752, -1, + 2752, 7645, 7644, -1, 7645, 2752, 2753, -1, + 2753, 7646, 7645, -1, 7646, 2753, 2754, -1, + 2754, 7647, 7646, -1, 7647, 2754, 2755, -1, + 2755, 7648, 7647, -1, 7648, 2755, 2756, -1, + 2756, 7649, 7648, -1, 7649, 2756, 2757, -1, + 2757, 7650, 7649, -1, 7650, 2757, 2758, -1, + 2758, 7651, 7650, -1, 7651, 2758, 2759, -1, + 2759, 7652, 7651, -1, 7652, 2759, 2760, -1, + 2760, 7653, 7652, -1, 7653, 2760, 2761, -1, + 2761, 7654, 7653, -1, 7654, 2761, 2762, -1, + 2762, 7655, 7654, -1, 7655, 2762, 2763, -1, + 2763, 7656, 7655, -1, 7656, 2763, 2764, -1, + 2764, 7657, 7656, -1, 7657, 2764, 2765, -1, + 2765, 7658, 7657, -1, 7658, 2765, 2766, -1, + 2766, 7659, 7658, -1, 7659, 2766, 2534, -1, + 2534, 7660, 7659, -1, 7660, 2534, 2533, -1, + 2533, 377, 7660, -1, 2533, 411, 377, -1, + 411, 2533, 2535, -1, 2535, 410, 411, -1, + 410, 2535, 2537, -1, 2537, 409, 410, -1, + 409, 2537, 2539, -1, 2539, 408, 409, -1, + 408, 2539, 2541, -1, 2541, 407, 408, -1, + 407, 2541, 2543, -1, 2543, 406, 407, -1, + 406, 2543, 2545, -1, 2545, 405, 406, -1, + 405, 2545, 2547, -1, 2547, 404, 405, -1, + 404, 2547, 2549, -1, 2549, 403, 404, -1, + 403, 2549, 2518, -1, 403, 2518, 2515, -1, + 2515, 402, 403, -1, 2515, 401, 402, -1, + 401, 2515, 2514, -1, 2514, 399, 401, -1, + 2514, 2513, 399, -1, 2513, 2516, 399, -1, + 399, 2516, 2521, -1, 355, 400, 399, -1, + 400, 355, 354, -1, 354, 396, 400, -1, + 354, 356, 396, -1, 356, 397, 396, -1, + 397, 356, 355, -1, 397, 355, 7661, -1, + 7661, 394, 397, -1, 7661, 395, 394, -1, + 7661, 355, 395, -1, 355, 7662, 395, -1, + 7663, 7662, 7664, -1, 7663, 395, 7662, -1, + 7663, 392, 395, -1, 7663, 7664, 392, -1, + 7664, 393, 392, -1, 393, 7664, 7662, -1, + 393, 7662, 7665, -1, 7665, 391, 393, -1, + 7665, 390, 391, -1, 390, 7665, 7662, -1, + 7662, 389, 390, -1, 389, 7666, 7667, -1, + 7668, 7669, 7666, -1, 7668, 7666, 7670, -1, + 7670, 7671, 7668, -1, 7672, 7671, 7673, -1, + 7671, 7672, 7674, -1, 7674, 7675, 7671, -1, + 7675, 7674, 7676, -1, 7676, 7677, 7675, -1, + 7676, 7678, 7677, -1, 7676, 7679, 7678, -1, + 7679, 7676, 7674, -1, 7674, 7680, 7679, -1, + 7680, 7674, 7672, -1, 7672, 352, 7680, -1, + 7672, 7681, 352, -1, 7682, 352, 7681, -1, + 7681, 7683, 7682, -1, 7681, 7684, 7683, -1, + 7684, 7681, 7672, -1, 7684, 7672, 7673, -1, + 7673, 7683, 7684, -1, 7673, 7685, 7683, -1, + 7685, 7673, 7671, -1, 7685, 7671, 7670, -1, + 7670, 7666, 7685, -1, 7666, 7683, 7685, -1, + 7683, 348, 7686, -1, 7686, 7682, 7683, -1, + 7686, 352, 7682, -1, 7686, 353, 352, -1, + 353, 7686, 348, -1, 353, 348, 350, -1, + 350, 351, 353, -1, 350, 347, 351, -1, + 347, 349, 351, -1, 7687, 351, 349, -1, + 351, 7687, 7688, -1, 7688, 352, 351, -1, + 352, 7688, 7689, -1, 7689, 7680, 352, -1, + 7680, 7689, 7690, -1, 7690, 7679, 7680, -1, + 7679, 7690, 7691, -1, 7691, 7678, 7679, -1, + 7691, 7692, 7678, -1, 7692, 7691, 7693, -1, + 7693, 7694, 7692, -1, 7694, 7693, 7695, -1, + 7695, 7696, 7694, -1, 7696, 7695, 7697, -1, + 7697, 346, 7696, -1, 7697, 345, 346, -1, + 7697, 344, 345, -1, 344, 7697, 7695, -1, + 7695, 343, 344, -1, 343, 7695, 7693, -1, + 7693, 342, 343, -1, 342, 7693, 7691, -1, + 342, 7691, 7690, -1, 7690, 341, 342, -1, + 341, 7690, 7689, -1, 7689, 340, 341, -1, + 340, 7689, 7688, -1, 7688, 339, 340, -1, + 339, 7688, 7687, -1, 7687, 338, 339, -1, + 338, 7687, 7698, -1, 7699, 338, 7698, -1, + 7699, 7700, 338, -1, 7700, 337, 338, -1, + 7700, 336, 337, -1, 7700, 7699, 336, -1, + 7699, 7698, 336, -1, 7698, 7701, 336, -1, + 7701, 7698, 7687, -1, 7701, 7687, 349, -1, + 7701, 349, 348, -1, 348, 336, 7701, -1, + 3089, 7702, 7703, -1, 7702, 3089, 4698, -1, + 7702, 4698, 4697, -1, 7702, 4697, 7704, -1, + 7704, 7703, 7702, -1, 7705, 7703, 7704, -1, + 7706, 7707, 7708, -1, 7706, 7708, 7703, -1, + 7706, 7703, 7705, -1, 7705, 7707, 7706, -1, + 7705, 7704, 7707, -1, 7707, 7704, 4697, -1, + 7707, 4697, 4696, -1, 4696, 7709, 7707, -1, + 7709, 4696, 4695, -1, 4695, 7710, 7709, -1, + 7710, 4695, 4694, -1, 4694, 7711, 7710, -1, + 7711, 4694, 4693, -1, 4693, 7712, 7711, -1, + 7712, 4693, 4692, -1, 4692, 7713, 7712, -1, + 7713, 4692, 4691, -1, 4691, 7714, 7713, -1, + 7714, 4691, 4690, -1, 4690, 7715, 7714, -1, + 7715, 4690, 4689, -1, 4689, 7716, 7715, -1, + 7716, 4689, 4688, -1, 4688, 7717, 7716, -1, + 7717, 4688, 4687, -1, 4687, 7718, 7717, -1, + 7718, 4687, 4686, -1, 4686, 7719, 7718, -1, + 7719, 4686, 4685, -1, 4685, 7720, 7719, -1, + 7720, 4685, 4684, -1, 4684, 7721, 7720, -1, + 7721, 4684, 4683, -1, 4683, 7722, 7721, -1, + 7722, 4683, 4682, -1, 4682, 7723, 7722, -1, + 7723, 4682, 4681, -1, 4681, 7724, 7723, -1, + 7724, 4681, 4281, -1, 4281, 4280, 7724, -1, + 7725, 7724, 4280, -1, 4280, 7726, 7725, -1, + 7726, 4280, 4278, -1, 4278, 7727, 7726, -1, + 7727, 4278, 4276, -1, 4276, 7728, 7727, -1, + 7728, 4276, 4274, -1, 4274, 7729, 7728, -1, + 7729, 4274, 4272, -1, 4272, 7730, 7729, -1, + 7730, 4272, 4270, -1, 4270, 7731, 7730, -1, + 7731, 4270, 4268, -1, 4268, 7732, 7731, -1, + 7732, 4268, 4266, -1, 4266, 7733, 7732, -1, + 7733, 4266, 4264, -1, 4264, 7734, 7733, -1, + 7734, 4264, 4262, -1, 4262, 7735, 7734, -1, + 7735, 4262, 4260, -1, 4260, 7736, 7735, -1, + 7736, 4260, 4258, -1, 4258, 7737, 7736, -1, + 7737, 4258, 4256, -1, 4256, 7738, 7737, -1, + 7738, 4256, 4254, -1, 4254, 7739, 7738, -1, + 7739, 4254, 4252, -1, 4252, 7740, 7739, -1, + 7740, 4252, 4250, -1, 4250, 7741, 7740, -1, + 7741, 4250, 4205, -1, 7741, 4205, 4176, -1, + 7741, 4176, 4125, -1, 4125, 7740, 7741, -1, + 7740, 4125, 4124, -1, 4124, 7739, 7740, -1, + 7739, 4124, 4127, -1, 4127, 7738, 7739, -1, + 7738, 4127, 4129, -1, 4129, 7737, 7738, -1, + 7737, 4129, 4131, -1, 4131, 7736, 7737, -1, + 7736, 4131, 4133, -1, 4133, 7735, 7736, -1, + 7735, 4133, 4135, -1, 4135, 7734, 7735, -1, + 7734, 4135, 4137, -1, 4137, 7733, 7734, -1, + 7733, 4137, 4139, -1, 4139, 7732, 7733, -1, + 7732, 4139, 4141, -1, 4141, 7731, 7732, -1, + 7731, 4141, 4143, -1, 4143, 7730, 7731, -1, + 7730, 4143, 4145, -1, 4145, 7729, 7730, -1, + 7729, 4145, 4147, -1, 4147, 7728, 7729, -1, + 7728, 4147, 4149, -1, 4149, 7727, 7728, -1, + 7727, 4149, 4151, -1, 4151, 7726, 7727, -1, + 7726, 4151, 4153, -1, 4153, 7725, 7726, -1, + 7725, 4153, 4155, -1, 4155, 7724, 7725, -1, + 7724, 4155, 4157, -1, 4157, 7723, 7724, -1, + 7723, 4157, 7742, -1, 7742, 7722, 7723, -1, + 7722, 7742, 7743, -1, 7743, 7721, 7722, -1, + 7721, 7743, 7744, -1, 7744, 7720, 7721, -1, + 7720, 7744, 7745, -1, 7745, 7719, 7720, -1, + 7719, 7745, 7746, -1, 7746, 7718, 7719, -1, + 7718, 7746, 7747, -1, 7747, 7717, 7718, -1, + 7717, 7747, 7748, -1, 7748, 7716, 7717, -1, + 7716, 7748, 7749, -1, 7749, 7715, 7716, -1, + 7715, 7749, 7750, -1, 7750, 7714, 7715, -1, + 7714, 7750, 7751, -1, 7751, 7713, 7714, -1, + 7713, 7751, 7752, -1, 7752, 7712, 7713, -1, + 7712, 7752, 7753, -1, 7753, 7711, 7712, -1, + 7711, 7753, 7754, -1, 7754, 7710, 7711, -1, + 7710, 7754, 7755, -1, 7755, 7709, 7710, -1, + 7709, 7755, 7756, -1, 7756, 7707, 7709, -1, + 7756, 7708, 7707, -1, 7757, 7708, 7756, -1, + 7757, 7703, 7708, -1, 7757, 7758, 7703, -1, + 7757, 7756, 7758, -1, 7759, 7758, 7756, -1, + 7759, 7756, 7755, -1, 7755, 7760, 7759, -1, + 7760, 7755, 7754, -1, 7754, 7761, 7760, -1, + 7761, 7754, 7753, -1, 7753, 7762, 7761, -1, + 7762, 7753, 7752, -1, 7752, 7763, 7762, -1, + 7763, 7752, 7751, -1, 7751, 7764, 7763, -1, + 7764, 7751, 7750, -1, 7750, 7765, 7764, -1, + 7765, 7750, 7749, -1, 7749, 7766, 7765, -1, + 7766, 7749, 7748, -1, 7748, 7767, 7766, -1, + 7767, 7748, 7747, -1, 7747, 7768, 7767, -1, + 7768, 7747, 7746, -1, 7746, 7769, 7768, -1, + 7769, 7746, 7745, -1, 7745, 7770, 7769, -1, + 7770, 7745, 7744, -1, 7744, 7771, 7770, -1, + 7771, 7744, 7743, -1, 7743, 7772, 7771, -1, + 7772, 7743, 7742, -1, 7742, 7773, 7772, -1, + 7773, 7742, 4157, -1, 4157, 4158, 7773, -1, + 7774, 7773, 4158, -1, 4158, 7775, 7774, -1, + 7775, 4158, 4159, -1, 4159, 7776, 7775, -1, + 7776, 4159, 4160, -1, 4160, 7777, 7776, -1, + 7777, 4160, 4161, -1, 4161, 7778, 7777, -1, + 7778, 4161, 4162, -1, 4162, 7779, 7778, -1, + 7779, 4162, 4163, -1, 4163, 7780, 7779, -1, + 7780, 4163, 4164, -1, 4164, 7781, 7780, -1, + 7781, 4164, 4165, -1, 4165, 7782, 7781, -1, + 7782, 4165, 4166, -1, 4166, 7783, 7782, -1, + 7783, 4166, 4167, -1, 4167, 7784, 7783, -1, + 7784, 4167, 4168, -1, 4168, 7785, 7784, -1, + 7785, 4168, 4169, -1, 4169, 7786, 7785, -1, + 7786, 4169, 4170, -1, 4170, 7787, 7786, -1, + 7787, 4170, 4171, -1, 4171, 7788, 7787, -1, + 7788, 4171, 4172, -1, 4172, 7789, 7788, -1, + 7789, 4172, 4173, -1, 4173, 7790, 7789, -1, + 7790, 4173, 4174, -1, 4174, 7791, 7790, -1, + 7791, 4174, 4175, -1, 4175, 7792, 7791, -1, + 7792, 4175, 4177, -1, 4177, 7793, 7792, -1, + 7793, 4177, 4202, -1, 4202, 7794, 7793, -1, + 7794, 4202, 4200, -1, 4200, 7795, 7794, -1, + 7795, 4200, 4198, -1, 4198, 7796, 7795, -1, + 7796, 4198, 4196, -1, 4196, 7797, 7796, -1, + 7797, 4196, 4194, -1, 4194, 7798, 7797, -1, + 7798, 4194, 4191, -1, 7798, 4191, 4189, -1, + 4189, 7799, 7798, -1, 7799, 4189, 4187, -1, + 4187, 7800, 7799, -1, 7800, 4187, 4185, -1, + 4185, 7801, 7800, -1, 7801, 4185, 4183, -1, + 4183, 7802, 7801, -1, 7802, 4183, 4181, -1, + 4181, 7803, 7802, -1, 7803, 4181, 4180, -1, + 4180, 7804, 7803, -1, 7805, 7806, 7807, -1, + 7806, 7805, 7808, -1, 7808, 7809, 7806, -1, + 7809, 7808, 7810, -1, 7810, 7811, 7809, -1, + 7811, 7810, 7812, -1, 7812, 7813, 7811, -1, + 7813, 7812, 7814, -1, 7814, 7815, 7813, -1, + 7815, 7814, 7816, -1, 7816, 7817, 7815, -1, + 7817, 7816, 7818, -1, 7818, 7819, 7817, -1, + 7819, 7818, 7820, -1, 7820, 7821, 7819, -1, + 7821, 7820, 7822, -1, 7822, 7823, 7821, -1, + 7823, 7822, 7824, -1, 7824, 7825, 7823, -1, + 7825, 7824, 7826, -1, 7826, 7827, 7825, -1, + 7827, 7826, 7828, -1, 7828, 7829, 7827, -1, + 7829, 7828, 7830, -1, 7830, 7831, 7829, -1, + 7831, 7830, 7832, -1, 7832, 7833, 7831, -1, + 7833, 7832, 7834, -1, 7834, 7835, 7833, -1, + 7835, 7834, 7836, -1, 7836, 7837, 7835, -1, + 7837, 7836, 7838, -1, 7838, 7839, 7837, -1, + 7839, 7838, 7840, -1, 7840, 7841, 7839, -1, + 7841, 7840, 7804, -1, 7804, 4180, 7841, -1, + 7842, 7843, 7841, -1, 7842, 7841, 4180, -1, + 7842, 4180, 4179, -1, 7842, 4179, 4380, -1, + 4380, 7843, 7842, -1, 7843, 4380, 4381, -1, + 4381, 7844, 7843, -1, 7844, 4381, 4019, -1, + 4019, 7845, 7844, -1, 7845, 4019, 4017, -1, + 4017, 7846, 7845, -1, 7846, 4017, 4015, -1, + 4015, 7847, 7846, -1, 7847, 4015, 4013, -1, + 4013, 7848, 7847, -1, 7848, 4013, 4011, -1, + 4011, 7849, 7848, -1, 7849, 4011, 4009, -1, + 4009, 7850, 7849, -1, 7850, 4009, 4007, -1, + 4007, 7851, 7850, -1, 7851, 4007, 4005, -1, + 4005, 7852, 7851, -1, 7852, 4005, 4003, -1, + 4003, 7853, 7852, -1, 7853, 4003, 4001, -1, + 4001, 7854, 7853, -1, 7854, 4001, 3999, -1, + 3999, 7855, 7854, -1, 7855, 3999, 3997, -1, + 3997, 7856, 7855, -1, 7856, 3997, 3995, -1, + 3995, 7857, 7856, -1, 7857, 3995, 3993, -1, + 3993, 7858, 7857, -1, 7858, 3993, 3991, -1, + 3991, 7859, 7858, -1, 7859, 3991, 3990, -1, + 3990, 3989, 7859, -1, 7860, 7859, 3989, -1, + 7859, 7860, 7861, -1, 7861, 7858, 7859, -1, + 7858, 7861, 7862, -1, 7862, 7857, 7858, -1, + 7857, 7862, 7863, -1, 7863, 7856, 7857, -1, + 7856, 7863, 7864, -1, 7864, 7855, 7856, -1, + 7855, 7864, 7865, -1, 7865, 7854, 7855, -1, + 7854, 7865, 7866, -1, 7866, 7853, 7854, -1, + 7853, 7866, 7867, -1, 7867, 7852, 7853, -1, + 7852, 7867, 7868, -1, 7868, 7851, 7852, -1, + 7851, 7868, 7869, -1, 7869, 7850, 7851, -1, + 7850, 7869, 7870, -1, 7870, 7849, 7850, -1, + 7849, 7870, 7871, -1, 7871, 7848, 7849, -1, + 7848, 7871, 7872, -1, 7872, 7847, 7848, -1, + 7847, 7872, 7873, -1, 7873, 7846, 7847, -1, + 7846, 7873, 7874, -1, 7874, 7845, 7846, -1, + 7845, 7874, 7875, -1, 7875, 7844, 7845, -1, + 7844, 7875, 7876, -1, 7876, 7843, 7844, -1, + 7876, 7841, 7843, -1, 7876, 7839, 7841, -1, + 7839, 7876, 7875, -1, 7875, 7837, 7839, -1, + 7837, 7875, 7874, -1, 7874, 7835, 7837, -1, + 7835, 7874, 7873, -1, 7873, 7833, 7835, -1, + 7833, 7873, 7872, -1, 7872, 7831, 7833, -1, + 7831, 7872, 7871, -1, 7871, 7829, 7831, -1, + 7829, 7871, 7870, -1, 7870, 7827, 7829, -1, + 7827, 7870, 7869, -1, 7869, 7825, 7827, -1, + 7825, 7869, 7868, -1, 7868, 7823, 7825, -1, + 7823, 7868, 7867, -1, 7867, 7821, 7823, -1, + 7821, 7867, 7866, -1, 7866, 7819, 7821, -1, + 7819, 7866, 7865, -1, 7865, 7817, 7819, -1, + 7817, 7865, 7864, -1, 7864, 7815, 7817, -1, + 7815, 7864, 7863, -1, 7863, 7813, 7815, -1, + 7813, 7863, 7862, -1, 7862, 7811, 7813, -1, + 7811, 7862, 7861, -1, 7861, 7809, 7811, -1, + 7809, 7861, 7860, -1, 7860, 7806, 7809, -1, + 7806, 7860, 3989, -1, 3989, 7807, 7806, -1, + 7807, 3989, 3987, -1, 3987, 7877, 7807, -1, + 7877, 3987, 3985, -1, 3985, 7878, 7877, -1, + 7878, 3985, 3983, -1, 3983, 7879, 7878, -1, + 7879, 3983, 3981, -1, 3981, 7880, 7879, -1, + 7880, 3981, 3979, -1, 3979, 7881, 7880, -1, + 7881, 3979, 3977, -1, 3977, 7882, 7881, -1, + 7882, 3977, 3975, -1, 3975, 7883, 7882, -1, + 7883, 3975, 3973, -1, 3973, 7884, 7883, -1, + 7884, 3973, 3971, -1, 3971, 7885, 7884, -1, + 7885, 3971, 3969, -1, 3969, 7886, 7885, -1, + 7886, 3969, 3967, -1, 3967, 7887, 7886, -1, + 7887, 3967, 3965, -1, 3965, 7888, 7887, -1, + 7888, 3965, 3963, -1, 3963, 7889, 7888, -1, + 7889, 3963, 3958, -1, 3958, 3957, 7889, -1, + 260, 7889, 3957, -1, 7889, 260, 256, -1, + 256, 7888, 7889, -1, 7888, 256, 255, -1, + 255, 7887, 7888, -1, 7887, 255, 254, -1, + 254, 7886, 7887, -1, 7886, 254, 253, -1, + 253, 7885, 7886, -1, 7885, 253, 252, -1, + 252, 7884, 7885, -1, 7884, 252, 251, -1, + 251, 7883, 7884, -1, 7883, 251, 250, -1, + 250, 7882, 7883, -1, 7882, 250, 249, -1, + 249, 7881, 7882, -1, 7881, 249, 248, -1, + 248, 7880, 7881, -1, 7880, 248, 247, -1, + 247, 7879, 7880, -1, 7879, 247, 246, -1, + 246, 7878, 7879, -1, 7878, 246, 245, -1, + 245, 7877, 7878, -1, 7877, 245, 203, -1, + 203, 7807, 7877, -1, 7807, 203, 201, -1, + 201, 7805, 7807, -1, 7805, 201, 199, -1, + 199, 7808, 7805, -1, 7808, 199, 197, -1, + 197, 7810, 7808, -1, 7810, 197, 195, -1, + 195, 7812, 7810, -1, 7812, 195, 193, -1, + 193, 7814, 7812, -1, 7814, 193, 191, -1, + 191, 7816, 7814, -1, 7816, 191, 189, -1, + 189, 7818, 7816, -1, 7818, 189, 187, -1, + 187, 7820, 7818, -1, 7820, 187, 185, -1, + 185, 7822, 7820, -1, 7822, 185, 183, -1, + 183, 7824, 7822, -1, 7824, 183, 181, -1, + 181, 7826, 7824, -1, 7826, 181, 179, -1, + 179, 7828, 7826, -1, 7828, 179, 177, -1, + 177, 7830, 7828, -1, 7830, 177, 175, -1, + 175, 7832, 7830, -1, 7832, 175, 173, -1, + 173, 7834, 7832, -1, 7834, 173, 171, -1, + 171, 7836, 7834, -1, 7836, 171, 169, -1, + 169, 7838, 7836, -1, 7838, 169, 167, -1, + 167, 7840, 7838, -1, 7840, 167, 165, -1, + 165, 7804, 7840, -1, 7804, 165, 163, -1, + 163, 7803, 7804, -1, 7803, 163, 161, -1, + 161, 7802, 7803, -1, 7802, 161, 159, -1, + 159, 7801, 7802, -1, 7801, 159, 157, -1, + 157, 7800, 7801, -1, 7800, 157, 155, -1, + 155, 7799, 7800, -1, 7799, 155, 154, -1, + 154, 7798, 7799, -1, 154, 7797, 7798, -1, + 7797, 154, 152, -1, 152, 7796, 7797, -1, + 7796, 152, 150, -1, 150, 7795, 7796, -1, + 7795, 150, 148, -1, 148, 7794, 7795, -1, + 7794, 148, 146, -1, 146, 7793, 7794, -1, + 7793, 146, 144, -1, 144, 7792, 7793, -1, + 7792, 144, 142, -1, 142, 7791, 7792, -1, + 7791, 142, 140, -1, 140, 7790, 7791, -1, + 7790, 140, 138, -1, 138, 7789, 7790, -1, + 7789, 138, 136, -1, 136, 7788, 7789, -1, + 7788, 136, 134, -1, 134, 7787, 7788, -1, + 7787, 134, 132, -1, 132, 7786, 7787, -1, + 7786, 132, 130, -1, 130, 7785, 7786, -1, + 7785, 130, 128, -1, 128, 7784, 7785, -1, + 7784, 128, 126, -1, 126, 7783, 7784, -1, + 7783, 126, 124, -1, 124, 7782, 7783, -1, + 7782, 124, 122, -1, 122, 7781, 7782, -1, + 7781, 122, 120, -1, 120, 7780, 7781, -1, + 7780, 120, 118, -1, 118, 7779, 7780, -1, + 7779, 118, 116, -1, 116, 7778, 7779, -1, + 7778, 116, 114, -1, 114, 7777, 7778, -1, + 7777, 114, 112, -1, 112, 7776, 7777, -1, + 7776, 112, 110, -1, 110, 7775, 7776, -1, + 7775, 110, 108, -1, 108, 7774, 7775, -1, + 7774, 108, 107, -1, 107, 7773, 7774, -1, + 7773, 107, 7890, -1, 7890, 7772, 7773, -1, + 7772, 7890, 7891, -1, 7891, 7771, 7772, -1, + 7771, 7891, 7892, -1, 7892, 7770, 7771, -1, + 7770, 7892, 7893, -1, 7893, 7769, 7770, -1, + 7769, 7893, 7894, -1, 7894, 7768, 7769, -1, + 7768, 7894, 7895, -1, 7895, 7767, 7768, -1, + 7767, 7895, 7896, -1, 7896, 7766, 7767, -1, + 7766, 7896, 7897, -1, 7897, 7765, 7766, -1, + 7765, 7897, 7898, -1, 7898, 7764, 7765, -1, + 7764, 7898, 7899, -1, 7899, 7763, 7764, -1, + 7763, 7899, 7900, -1, 7900, 7762, 7763, -1, + 7762, 7900, 7901, -1, 7901, 7761, 7762, -1, + 7761, 7901, 7902, -1, 7902, 7760, 7761, -1, + 7760, 7902, 7903, -1, 7903, 7759, 7760, -1, + 7759, 7903, 7904, -1, 7905, 7906, 7907, -1, + 7906, 7908, 7907, -1, 7909, 7910, 7908, -1, + 7910, 7907, 7908, -1, 7910, 7903, 7907, -1, + 7910, 7909, 7903, -1, 7909, 7904, 7903, -1, + 7904, 7909, 7908, -1, 7904, 7908, 7911, -1, + 7911, 7759, 7904, -1, 7911, 7758, 7759, -1, + 7911, 7908, 7758, -1, 7908, 7703, 7758, -1, + 7912, 2, 7913, -1, 2, 7906, 7913, -1, + 7914, 7906, 7915, -1, 7914, 7913, 7906, -1, + 7914, 103, 7913, -1, 7914, 7915, 103, -1, + 7915, 105, 103, -1, 105, 7915, 7906, -1, + 105, 7906, 7905, -1, 7905, 104, 105, -1, + 7905, 7907, 104, -1, 104, 7907, 7903, -1, + 104, 7903, 7902, -1, 7902, 102, 104, -1, + 102, 7902, 7901, -1, 7901, 99, 102, -1, + 99, 7901, 7900, -1, 7900, 100, 99, -1, + 100, 7900, 7899, -1, 7899, 7916, 100, -1, + 7916, 7899, 7898, -1, 7898, 7917, 7916, -1, + 7917, 7898, 7897, -1, 7897, 7918, 7917, -1, + 7918, 7897, 7896, -1, 7896, 7919, 7918, -1, + 7919, 7896, 7895, -1, 7895, 7920, 7919, -1, + 7920, 7895, 7894, -1, 7894, 7921, 7920, -1, + 7921, 7894, 7893, -1, 7893, 7922, 7921, -1, + 7922, 7893, 7892, -1, 7892, 7923, 7922, -1, + 7923, 7892, 7891, -1, 7891, 7924, 7923, -1, + 7924, 7891, 7890, -1, 7890, 7925, 7924, -1, + 7925, 7890, 107, -1, 107, 106, 7925, -1, + 7926, 7925, 106, -1, 106, 7927, 7926, -1, + 7927, 106, 109, -1, 109, 7928, 7927, -1, + 7928, 109, 111, -1, 111, 7929, 7928, -1, + 7929, 111, 113, -1, 113, 7930, 7929, -1, + 7930, 113, 115, -1, 115, 7931, 7930, -1, + 7931, 115, 117, -1, 117, 7932, 7931, -1, + 7932, 117, 119, -1, 119, 7933, 7932, -1, + 7933, 119, 121, -1, 121, 7934, 7933, -1, + 7934, 121, 123, -1, 123, 7935, 7934, -1, + 7935, 123, 125, -1, 125, 7936, 7935, -1, + 7936, 125, 127, -1, 127, 7937, 7936, -1, + 7937, 127, 129, -1, 129, 7938, 7937, -1, + 7938, 129, 131, -1, 131, 7939, 7938, -1, + 7939, 131, 133, -1, 133, 7940, 7939, -1, + 7940, 133, 135, -1, 135, 7941, 7940, -1, + 7941, 135, 137, -1, 137, 7942, 7941, -1, + 7942, 137, 139, -1, 139, 7943, 7942, -1, + 7943, 139, 141, -1, 141, 7944, 7943, -1, + 7944, 141, 143, -1, 143, 7945, 7944, -1, + 7945, 143, 145, -1, 145, 7946, 7945, -1, + 7946, 145, 147, -1, 147, 7947, 7946, -1, + 7947, 147, 149, -1, 149, 7948, 7947, -1, + 7948, 149, 151, -1, 151, 7949, 7948, -1, + 7949, 151, 153, -1, 7949, 153, 156, -1, + 156, 7950, 7949, -1, 7950, 156, 158, -1, + 158, 7951, 7950, -1, 7951, 158, 160, -1, + 160, 7952, 7951, -1, 7952, 160, 162, -1, + 162, 7953, 7952, -1, 7953, 162, 164, -1, + 164, 7954, 7953, -1, 7954, 164, 166, -1, + 166, 7955, 7954, -1, 7955, 166, 168, -1, + 168, 7956, 7955, -1, 7956, 168, 170, -1, + 170, 7957, 7956, -1, 7957, 170, 172, -1, + 172, 7958, 7957, -1, 7958, 172, 174, -1, + 174, 7959, 7958, -1, 7959, 174, 176, -1, + 176, 7960, 7959, -1, 7960, 176, 178, -1, + 178, 7961, 7960, -1, 7961, 178, 180, -1, + 180, 7962, 7961, -1, 7962, 180, 182, -1, + 182, 7963, 7962, -1, 7963, 182, 184, -1, + 184, 7964, 7963, -1, 7964, 184, 186, -1, + 186, 7965, 7964, -1, 7965, 186, 188, -1, + 188, 7966, 7965, -1, 7966, 188, 190, -1, + 190, 7967, 7966, -1, 7967, 190, 192, -1, + 192, 7968, 7967, -1, 7968, 192, 194, -1, + 194, 7969, 7968, -1, 7969, 194, 196, -1, + 196, 7970, 7969, -1, 7970, 196, 198, -1, + 198, 7971, 7970, -1, 7971, 198, 200, -1, + 200, 7972, 7971, -1, 7972, 200, 202, -1, + 202, 7973, 7972, -1, 7973, 202, 203, -1, + 203, 244, 7973, -1, 7974, 7973, 244, -1, + 244, 216, 7974, -1, 7975, 7976, 7974, -1, + 7975, 7974, 216, -1, 216, 215, 7975, -1, + 7977, 7978, 7975, -1, 7977, 7975, 215, -1, + 215, 7979, 7977, -1, 7979, 215, 218, -1, + 218, 7980, 7979, -1, 7980, 218, 220, -1, + 220, 7981, 7980, -1, 7981, 220, 222, -1, + 222, 7982, 7981, -1, 7982, 222, 224, -1, + 224, 7983, 7982, -1, 7983, 224, 214, -1, + 214, 213, 7983, -1, 213, 7984, 7983, -1, + 7984, 213, 211, -1, 211, 7985, 7984, -1, + 7985, 211, 209, -1, 209, 7986, 7985, -1, + 7986, 209, 207, -1, 207, 7987, 7986, -1, + 7988, 7989, 7987, -1, 7987, 207, 7988, -1, + 7988, 207, 205, -1, 205, 7989, 7988, -1, + 205, 204, 7989, -1, 7989, 7990, 7991, -1, + 7990, 7989, 204, -1, 204, 206, 7990, -1, + 206, 230, 7990, -1, 7992, 7990, 230, -1, + 7992, 7991, 7990, -1, 7993, 7991, 7992, -1, + 7992, 230, 7993, -1, 7993, 230, 232, -1, + 232, 7991, 7993, -1, 232, 231, 7991, -1, + 7991, 7994, 7995, -1, 7994, 7991, 231, -1, + 231, 233, 7994, -1, 233, 257, 7994, -1, + 7996, 7994, 257, -1, 7996, 7995, 7994, -1, + 7997, 7995, 7996, -1, 7996, 257, 7997, -1, + 7997, 257, 259, -1, 259, 7995, 7997, -1, + 259, 258, 7995, -1, 7995, 7998, 7999, -1, + 7998, 7995, 258, -1, 258, 260, 7998, -1, + 260, 3957, 7998, -1, 8000, 7998, 3957, -1, + 8000, 7999, 7998, -1, 8001, 7999, 8000, -1, + 8000, 3957, 8001, -1, 8001, 3957, 3956, -1, + 3956, 7999, 8001, -1, 3956, 8002, 7999, -1, + 8002, 3956, 3955, -1, 8002, 3955, 3960, -1, + 3960, 7999, 8002, -1, 3960, 8003, 7999, -1, + 8003, 3960, 3959, -1, 8003, 3959, 4383, -1, + 4383, 4384, 8003, -1, 4384, 7999, 8003, -1, + 8004, 91, 88, -1, 8005, 8004, 88, -1, + 8005, 88, 87, -1, 8005, 87, 8006, -1, + 8006, 8004, 8005, -1, 8006, 8007, 8004, -1, + 8006, 8008, 8007, -1, 8008, 8006, 87, -1, + 87, 8009, 8008, -1, 8009, 87, 84, -1, + 84, 8010, 8009, -1, 8010, 84, 86, -1, + 86, 8011, 8010, -1, 8011, 86, 8012, -1, + 8012, 8013, 8011, -1, 8013, 8012, 8014, -1, + 8014, 8015, 8013, -1, 8015, 8014, 8016, -1, + 8016, 8017, 8015, -1, 8017, 8016, 8018, -1, + 8018, 8019, 8017, -1, 8020, 8021, 8022, -1, + 8020, 8022, 8019, -1, 8019, 8018, 8020, -1, + 8020, 8023, 8024, -1, 8023, 8020, 8018, -1, + 8023, 8018, 8025, -1, 8025, 8026, 8023, -1, + 8025, 8027, 8026, -1, 8027, 8025, 8028, -1, + 8028, 8029, 8027, -1, 8029, 8028, 8030, -1, + 8030, 8031, 8029, -1, 8031, 8030, 8032, -1, + 8032, 8033, 8031, -1, 8033, 8034, 8035, -1, + 8033, 8032, 8034, -1, 8036, 8037, 8034, -1, + 8034, 8038, 8036, -1, 8038, 8034, 8032, -1, + 8032, 8039, 8038, -1, 8039, 8032, 8030, -1, + 8030, 8040, 8039, -1, 8040, 8030, 8028, -1, + 8028, 8041, 8040, -1, 8041, 8028, 8025, -1, + 8041, 8025, 8018, -1, 8041, 8018, 8016, -1, + 8016, 8040, 8041, -1, 8040, 8016, 8014, -1, + 8014, 8039, 8040, -1, 8039, 8014, 8012, -1, + 8012, 8038, 8039, -1, 8038, 8012, 86, -1, + 86, 8036, 8038, -1, 8036, 86, 85, -1, + 85, 8042, 8036, -1, 8042, 85, 90, -1, + 8042, 90, 91, -1, 8042, 91, 8043, -1, + 8043, 8036, 8042, -1, 8043, 8037, 8036, -1, + 8037, 8043, 91, -1, 91, 98, 8037, -1, + 8044, 8045, 98, -1, 8045, 8037, 98, -1, + 8045, 8034, 8037, -1, 8045, 8044, 8034, -1, + 8044, 8035, 8034, -1, 8035, 8044, 98, -1, + 8035, 98, 97, -1, 97, 8033, 8035, -1, + 97, 94, 8033, -1, 8033, 94, 93, -1, + 93, 8031, 8033, -1, 8031, 93, 8046, -1, + 8046, 8029, 8031, -1, 8029, 8046, 8047, -1, + 8047, 8027, 8029, -1, 8027, 8047, 8048, -1, + 8048, 8026, 8027, -1, 8048, 8049, 8026, -1, + 8048, 8050, 8049, -1, 8050, 8048, 8047, -1, + 8047, 8051, 8050, -1, 8051, 8047, 8046, -1, + 8046, 8052, 8051, -1, 8052, 8046, 93, -1, + 93, 95, 8052, -1, 8053, 8052, 95, -1, + 8053, 95, 96, -1, 8053, 96, 4389, -1, + 4389, 8052, 8053, -1, 4389, 4388, 8052, -1, + 8052, 4388, 4391, -1, 4391, 8051, 8052, -1, + 8051, 4391, 8054, -1, 8054, 8050, 8051, -1, + 8050, 8054, 8055, -1, 8055, 8049, 8050, -1, + 8049, 8055, 8056, -1, 8049, 8056, 8057, -1, + 8057, 8026, 8049, -1, 8026, 8057, 8058, -1, + 8058, 8023, 8026, -1, 8058, 8024, 8023, -1, + 8058, 8059, 8024, -1, 8059, 8058, 8057, -1, + 8057, 8060, 8059, -1, 8060, 8057, 8056, -1, + 8056, 8061, 8060, -1, 8056, 8062, 8061, -1, + 8062, 8056, 8055, -1, 8055, 8063, 8062, -1, + 8063, 8055, 8054, -1, 8054, 8064, 8063, -1, + 8064, 8054, 4391, -1, 4391, 4392, 8064, -1, + 8065, 8064, 4392, -1, 8065, 4392, 4393, -1, + 8065, 4393, 4395, -1, 4395, 8064, 8065, -1, + 4395, 4394, 8064, -1, 8064, 4394, 4397, -1, + 4397, 8063, 8064, -1, 8063, 4397, 8066, -1, + 8066, 8062, 8063, -1, 8062, 8066, 8067, -1, + 8067, 8061, 8062, -1, 8061, 8067, 8068, -1, + 8061, 8068, 8069, -1, 8069, 8060, 8061, -1, + 8060, 8069, 8070, -1, 8070, 8059, 8060, -1, + 8059, 8070, 8071, -1, 8071, 8024, 8059, -1, + 8071, 51, 8024, -1, 8071, 83, 51, -1, + 83, 8071, 8070, -1, 8070, 82, 83, -1, + 82, 8070, 8069, -1, 8069, 81, 82, -1, + 81, 8069, 8068, -1, 8068, 77, 81, -1, + 8068, 75, 77, -1, 75, 8068, 8067, -1, + 8067, 74, 75, -1, 74, 8067, 8066, -1, + 8066, 72, 74, -1, 72, 8066, 4397, -1, + 4397, 4398, 72, -1, 8072, 72, 4398, -1, + 8072, 4398, 4399, -1, 8072, 4399, 8073, -1, + 8073, 72, 8072, -1, 8073, 73, 72, -1, + 8073, 4399, 73, -1, 73, 4399, 4400, -1, + 4400, 69, 73, -1, 4400, 4402, 69, -1, + 4402, 70, 69, -1, 70, 4402, 4401, -1, + 70, 4401, 8074, -1, 8074, 68, 70, -1, + 8074, 80, 68, -1, 8074, 4401, 80, -1, + 80, 4401, 4403, -1, 4403, 66, 80, -1, + 4403, 4404, 66, -1, 4404, 67, 66, -1, + 67, 4404, 3466, -1, 67, 3466, 3465, -1, + 3465, 65, 67, -1, 3465, 3467, 65, -1, + 65, 3467, 3469, -1, 3469, 63, 65, -1, + 63, 3469, 3496, -1, 3496, 62, 63, -1, + 62, 3496, 3493, -1, 62, 3493, 3491, -1, + 3491, 60, 62, -1, 60, 3491, 3490, -1, + 3490, 58, 60, -1, 58, 3490, 3489, -1, + 3489, 56, 58, -1, 56, 3489, 3488, -1, + 3488, 54, 56, -1, 54, 3488, 3487, -1, + 3487, 52, 54, -1, 52, 3487, 3486, -1, + 3486, 50, 52, -1, 3486, 8075, 50, -1, + 8075, 3486, 3485, -1, 3485, 8076, 8075, -1, + 8076, 3485, 7626, -1, 7626, 8077, 8076, -1, + 8077, 7626, 7627, -1, 7627, 8078, 8077, -1, + 8078, 7627, 7628, -1, 7628, 8079, 8078, -1, + 8079, 7628, 7629, -1, 7629, 8080, 8079, -1, + 8080, 7629, 7630, -1, 7630, 8081, 8080, -1, + 8081, 7630, 7631, -1, 7631, 8082, 8081, -1, + 8082, 7631, 7632, -1, 7632, 8083, 8082, -1, + 8083, 7632, 7633, -1, 7633, 8084, 8083, -1, + 8084, 7633, 7634, -1, 7634, 8085, 8084, -1, + 8085, 7634, 7635, -1, 7635, 8086, 8085, -1, + 8086, 7635, 7636, -1, 7636, 8087, 8086, -1, + 8087, 7636, 7637, -1, 7637, 8088, 8087, -1, + 8088, 7637, 7638, -1, 7638, 8089, 8088, -1, + 8089, 7638, 7639, -1, 7639, 8090, 8089, -1, + 8090, 7639, 7640, -1, 7640, 8091, 8090, -1, + 8091, 7640, 7641, -1, 7641, 8092, 8091, -1, + 8092, 7641, 7642, -1, 7642, 8093, 8092, -1, + 8093, 7642, 7643, -1, 7643, 8094, 8093, -1, + 7643, 8095, 8094, -1, 8095, 7643, 7644, -1, + 7644, 8096, 8095, -1, 8096, 7644, 7645, -1, + 7645, 8097, 8096, -1, 8097, 7645, 7646, -1, + 7646, 8098, 8097, -1, 8098, 7646, 7647, -1, + 7647, 8099, 8098, -1, 8099, 7647, 7648, -1, + 7648, 8100, 8099, -1, 8100, 7648, 7649, -1, + 7649, 8101, 8100, -1, 8101, 7649, 7650, -1, + 7650, 8102, 8101, -1, 8102, 7650, 7651, -1, + 7651, 8103, 8102, -1, 8103, 7651, 7652, -1, + 7652, 8104, 8103, -1, 8104, 7652, 7653, -1, + 7653, 8105, 8104, -1, 8105, 7653, 7654, -1, + 7654, 8106, 8105, -1, 8106, 7654, 7655, -1, + 7655, 8107, 8106, -1, 8107, 7655, 7656, -1, + 7656, 8108, 8107, -1, 8108, 7656, 7657, -1, + 7657, 8109, 8108, -1, 8109, 7657, 7658, -1, + 7658, 8110, 8109, -1, 8110, 7658, 7659, -1, + 7659, 8111, 8110, -1, 8111, 7659, 7660, -1, + 7660, 8112, 8111, -1, 8112, 7660, 377, -1, + 377, 8113, 8112, -1, 8113, 377, 376, -1, + 376, 8114, 8113, -1, 376, 378, 8114, -1, + 8115, 8116, 8117, -1, 8116, 8115, 8118, -1, + 8118, 8119, 8116, -1, 8119, 8118, 8120, -1, + 8120, 8121, 8119, -1, 8120, 8122, 8121, -1, + 8122, 8120, 8123, -1, 8123, 8124, 8122, -1, + 8124, 8123, 8125, -1, 8125, 8126, 8124, -1, + 8126, 8125, 8127, -1, 8127, 8128, 8126, -1, + 8128, 8127, 8129, -1, 8129, 8130, 8128, -1, + 8130, 8129, 8131, -1, 8131, 8132, 8130, -1, + 8132, 8131, 8133, -1, 8132, 8133, 8114, -1, + 8132, 8114, 378, -1, 378, 8130, 8132, -1, + 8130, 378, 379, -1, 379, 8128, 8130, -1, + 8128, 379, 380, -1, 380, 8126, 8128, -1, + 8126, 380, 381, -1, 381, 8124, 8126, -1, + 8124, 381, 382, -1, 382, 8122, 8124, -1, + 8122, 382, 383, -1, 383, 8121, 8122, -1, + 8121, 383, 384, -1, 8121, 384, 385, -1, + 385, 8119, 8121, -1, 8119, 385, 388, -1, + 388, 8116, 8119, -1, 388, 8134, 8116, -1, + 8134, 388, 387, -1, 8134, 387, 389, -1, + 8134, 389, 7667, -1, 7667, 8116, 8134, -1, + 7667, 8117, 8116, -1, 8117, 7667, 7666, -1, + 8117, 7666, 7669, -1, 7669, 8115, 8117, -1, + 7669, 7668, 8115, -1, 8115, 7668, 7671, -1, + 8115, 7671, 7675, -1, 7675, 8118, 8115, -1, + 8118, 7675, 7677, -1, 7677, 8120, 8118, -1, + 7677, 8123, 8120, -1, 8123, 7677, 7678, -1, + 7678, 8125, 8123, -1, 8125, 7678, 7692, -1, + 7692, 8127, 8125, -1, 8127, 7692, 7694, -1, + 7694, 8129, 8127, -1, 8129, 7694, 7696, -1, + 7696, 8131, 8129, -1, 8131, 7696, 346, -1, + 346, 8133, 8131, -1, 8133, 346, 335, -1, + 8133, 335, 8135, -1, 8135, 8114, 8133, -1, + 8114, 8135, 8136, -1, 8136, 8113, 8114, -1, + 8113, 8136, 8137, -1, 8137, 8112, 8113, -1, + 8112, 8137, 8138, -1, 8138, 8111, 8112, -1, + 8111, 8138, 8139, -1, 8139, 8110, 8111, -1, + 8110, 8139, 8140, -1, 8140, 8109, 8110, -1, + 8109, 8140, 8141, -1, 8141, 8108, 8109, -1, + 8108, 8141, 8142, -1, 8142, 8107, 8108, -1, + 8107, 8142, 8143, -1, 8143, 8106, 8107, -1, + 8106, 8143, 8144, -1, 8144, 8105, 8106, -1, + 8105, 8144, 8145, -1, 8145, 8104, 8105, -1, + 8104, 8145, 8146, -1, 8146, 8103, 8104, -1, + 8103, 8146, 8147, -1, 8147, 8102, 8103, -1, + 8102, 8147, 8148, -1, 8148, 8101, 8102, -1, + 8101, 8148, 8149, -1, 8149, 8100, 8101, -1, + 8100, 8149, 8150, -1, 8150, 8099, 8100, -1, + 8099, 8150, 8151, -1, 8151, 8098, 8099, -1, + 8098, 8151, 8152, -1, 8152, 8097, 8098, -1, + 8097, 8152, 8153, -1, 8153, 8096, 8097, -1, + 8096, 8153, 8154, -1, 8154, 8095, 8096, -1, + 8095, 8154, 8155, -1, 8155, 8094, 8095, -1, + 8094, 8155, 8156, -1, 8094, 8156, 8157, -1, + 8157, 8093, 8094, -1, 8093, 8157, 8158, -1, + 8158, 8092, 8093, -1, 8092, 8158, 8159, -1, + 8159, 8091, 8092, -1, 8091, 8159, 8160, -1, + 8160, 8090, 8091, -1, 8090, 8160, 8161, -1, + 8161, 8089, 8090, -1, 8089, 8161, 8162, -1, + 8162, 8088, 8089, -1, 8088, 8162, 8163, -1, + 8163, 8087, 8088, -1, 8087, 8163, 8164, -1, + 8164, 8086, 8087, -1, 8086, 8164, 8165, -1, + 8165, 8085, 8086, -1, 8085, 8165, 8166, -1, + 8166, 8084, 8085, -1, 8084, 8166, 8167, -1, + 8167, 8083, 8084, -1, 8083, 8167, 8168, -1, + 8168, 8082, 8083, -1, 8082, 8168, 8169, -1, + 8169, 8081, 8082, -1, 8081, 8169, 8170, -1, + 8170, 8080, 8081, -1, 8080, 8170, 8171, -1, + 8171, 8079, 8080, -1, 8079, 8171, 8172, -1, + 8172, 8078, 8079, -1, 8078, 8172, 8173, -1, + 8173, 8077, 8078, -1, 8077, 8173, 8174, -1, + 8174, 8076, 8077, -1, 8076, 8174, 8175, -1, + 8175, 8075, 8076, -1, 8075, 8175, 8176, -1, + 8176, 50, 8075, -1, 50, 8176, 8177, -1, + 8177, 51, 50, -1, 51, 8177, 8178, -1, + 8178, 8024, 51, -1, 8178, 8020, 8024, -1, + 8178, 8021, 8020, -1, 8021, 8178, 8177, -1, + 8177, 8179, 8021, -1, 8179, 8177, 8176, -1, + 8176, 8180, 8179, -1, 8180, 8176, 8175, -1, + 8175, 8181, 8180, -1, 8181, 8175, 8174, -1, + 8174, 8182, 8181, -1, 8182, 8174, 8173, -1, + 8173, 8183, 8182, -1, 8183, 8173, 8172, -1, + 8172, 8184, 8183, -1, 8184, 8172, 8171, -1, + 8171, 8185, 8184, -1, 8185, 8171, 8170, -1, + 8170, 8186, 8185, -1, 8186, 8170, 8169, -1, + 8169, 8187, 8186, -1, 8187, 8169, 8168, -1, + 8168, 8188, 8187, -1, 8188, 8168, 8167, -1, + 8167, 8189, 8188, -1, 8189, 8167, 8166, -1, + 8166, 8190, 8189, -1, 8190, 8166, 8165, -1, + 8165, 8191, 8190, -1, 8191, 8165, 8164, -1, + 8164, 8192, 8191, -1, 8192, 8164, 8163, -1, + 8163, 8193, 8192, -1, 8193, 8163, 8162, -1, + 8162, 8194, 8193, -1, 8194, 8162, 8161, -1, + 8161, 8195, 8194, -1, 8195, 8161, 8160, -1, + 8160, 8196, 8195, -1, 8196, 8160, 8159, -1, + 8159, 8197, 8196, -1, 8197, 8159, 8158, -1, + 8158, 8198, 8197, -1, 8198, 8158, 8157, -1, + 8157, 8199, 8198, -1, 8199, 8157, 8156, -1, + 8156, 8200, 8199, -1, 8156, 8201, 8200, -1, + 8201, 8156, 8155, -1, 8155, 8202, 8201, -1, + 8202, 8155, 8154, -1, 8154, 8203, 8202, -1, + 8203, 8154, 8153, -1, 8153, 8204, 8203, -1, + 8204, 8153, 8152, -1, 8152, 8205, 8204, -1, + 8205, 8152, 8151, -1, 8151, 8206, 8205, -1, + 8206, 8151, 8150, -1, 8150, 8207, 8206, -1, + 8207, 8150, 8149, -1, 8149, 8208, 8207, -1, + 8208, 8149, 8148, -1, 8148, 8209, 8208, -1, + 8209, 8148, 8147, -1, 8147, 8210, 8209, -1, + 8210, 8147, 8146, -1, 8146, 8211, 8210, -1, + 8211, 8146, 8145, -1, 8145, 8212, 8211, -1, + 8212, 8145, 8144, -1, 8144, 8213, 8212, -1, + 8213, 8144, 8143, -1, 8143, 8214, 8213, -1, + 8214, 8143, 8142, -1, 8142, 8215, 8214, -1, + 8215, 8142, 8141, -1, 8141, 8216, 8215, -1, + 8216, 8141, 8140, -1, 8140, 8217, 8216, -1, + 8217, 8140, 8139, -1, 8139, 8218, 8217, -1, + 8218, 8139, 8138, -1, 8138, 8219, 8218, -1, + 8219, 8138, 8137, -1, 8137, 8220, 8219, -1, + 8220, 8137, 8136, -1, 8136, 8221, 8220, -1, + 8221, 8136, 8135, -1, 8135, 8222, 8221, -1, + 8222, 8135, 335, -1, 335, 312, 8222, -1, + 312, 314, 8222, -1, 8223, 8222, 314, -1, + 8223, 8221, 8222, -1, 8221, 8223, 8224, -1, + 8224, 8220, 8221, -1, 8220, 8224, 8225, -1, + 8225, 8219, 8220, -1, 8219, 8225, 8226, -1, + 8226, 8218, 8219, -1, 8218, 8226, 8227, -1, + 8227, 8217, 8218, -1, 8217, 8227, 8228, -1, + 8228, 8216, 8217, -1, 8216, 8228, 8229, -1, + 8229, 8215, 8216, -1, 8215, 8229, 8230, -1, + 8230, 8214, 8215, -1, 8214, 8230, 8231, -1, + 8231, 8213, 8214, -1, 8213, 8231, 8232, -1, + 8232, 8212, 8213, -1, 8212, 8232, 8233, -1, + 8233, 8211, 8212, -1, 8211, 8233, 8234, -1, + 8234, 8210, 8211, -1, 8210, 8234, 8235, -1, + 8235, 8209, 8210, -1, 8209, 8235, 8236, -1, + 8236, 8208, 8209, -1, 8208, 8236, 8237, -1, + 8237, 8207, 8208, -1, 8207, 8237, 8238, -1, + 8238, 8206, 8207, -1, 8206, 8238, 8239, -1, + 8239, 8205, 8206, -1, 8205, 8239, 8240, -1, + 8240, 8204, 8205, -1, 8204, 8240, 8241, -1, + 8241, 8203, 8204, -1, 8203, 8241, 8242, -1, + 8242, 8202, 8203, -1, 8202, 8242, 8243, -1, + 8243, 8201, 8202, -1, 8201, 8243, 8244, -1, + 8244, 8200, 8201, -1, 8200, 8244, 8245, -1, + 8200, 8245, 8246, -1, 8246, 8199, 8200, -1, + 8199, 8246, 8247, -1, 8247, 8198, 8199, -1, + 8198, 8247, 8248, -1, 8248, 8197, 8198, -1, + 8197, 8248, 8249, -1, 8249, 8196, 8197, -1, + 8196, 8249, 8250, -1, 8250, 8195, 8196, -1, + 8195, 8250, 8251, -1, 8251, 8194, 8195, -1, + 8194, 8251, 8252, -1, 8252, 8193, 8194, -1, + 8193, 8252, 8253, -1, 8253, 8192, 8193, -1, + 8192, 8253, 8254, -1, 8254, 8191, 8192, -1, + 8191, 8254, 8255, -1, 8255, 8190, 8191, -1, + 8190, 8255, 8256, -1, 8256, 8189, 8190, -1, + 8189, 8256, 8257, -1, 8257, 8188, 8189, -1, + 8188, 8257, 8258, -1, 8258, 8187, 8188, -1, + 8187, 8258, 8259, -1, 8259, 8186, 8187, -1, + 8186, 8259, 8260, -1, 8260, 8185, 8186, -1, + 8185, 8260, 8261, -1, 8261, 8184, 8185, -1, + 8184, 8261, 8262, -1, 8262, 8183, 8184, -1, + 8183, 8262, 8263, -1, 8263, 8182, 8183, -1, + 8182, 8263, 8264, -1, 8264, 8181, 8182, -1, + 8181, 8264, 8265, -1, 8265, 8180, 8181, -1, + 8180, 8265, 8266, -1, 8266, 8179, 8180, -1, + 8179, 8266, 8267, -1, 8267, 8021, 8179, -1, + 8267, 8022, 8021, -1, 8267, 8268, 8022, -1, + 8268, 8267, 8266, -1, 8266, 8269, 8268, -1, + 8269, 8266, 8265, -1, 8265, 8270, 8269, -1, + 8270, 8265, 8264, -1, 8264, 8271, 8270, -1, + 8271, 8264, 8263, -1, 8263, 8272, 8271, -1, + 8272, 8263, 8262, -1, 8262, 8273, 8272, -1, + 8273, 8262, 8261, -1, 8261, 8274, 8273, -1, + 8274, 8261, 8260, -1, 8260, 8275, 8274, -1, + 8275, 8260, 8259, -1, 8259, 8276, 8275, -1, + 8276, 8259, 8258, -1, 8258, 8277, 8276, -1, + 8277, 8258, 8257, -1, 8257, 8278, 8277, -1, + 8278, 8257, 8256, -1, 8256, 8279, 8278, -1, + 8279, 8256, 8255, -1, 8255, 8280, 8279, -1, + 8280, 8255, 8254, -1, 8254, 8281, 8280, -1, + 8281, 8254, 8253, -1, 8253, 8282, 8281, -1, + 8282, 8253, 8252, -1, 8252, 8283, 8282, -1, + 8283, 8252, 8251, -1, 8251, 8284, 8283, -1, + 8284, 8251, 8250, -1, 8250, 8285, 8284, -1, + 8285, 8250, 8249, -1, 8249, 8286, 8285, -1, + 8286, 8249, 8248, -1, 8248, 8287, 8286, -1, + 8287, 8248, 8247, -1, 8247, 8288, 8287, -1, + 8288, 8247, 8246, -1, 8246, 8289, 8288, -1, + 8289, 8246, 8245, -1, 8245, 8290, 8289, -1, + 8245, 8291, 8290, -1, 8291, 8245, 8244, -1, + 8244, 8292, 8291, -1, 8292, 8244, 8243, -1, + 8243, 8293, 8292, -1, 8293, 8243, 8242, -1, + 8242, 8294, 8293, -1, 8294, 8242, 8241, -1, + 8241, 8295, 8294, -1, 8295, 8241, 8240, -1, + 8240, 8296, 8295, -1, 8296, 8240, 8239, -1, + 8239, 8297, 8296, -1, 8297, 8239, 8238, -1, + 8238, 8298, 8297, -1, 8298, 8238, 8237, -1, + 8237, 8299, 8298, -1, 8299, 8237, 8236, -1, + 8236, 8300, 8299, -1, 8300, 8236, 8235, -1, + 8235, 8301, 8300, -1, 8301, 8235, 8234, -1, + 8234, 8302, 8301, -1, 8302, 8234, 8233, -1, + 8233, 8303, 8302, -1, 8303, 8233, 8232, -1, + 8232, 8304, 8303, -1, 8304, 8232, 8231, -1, + 8231, 8305, 8304, -1, 8305, 8231, 8230, -1, + 8230, 8306, 8305, -1, 8306, 8230, 8229, -1, + 8229, 8307, 8306, -1, 8307, 8229, 8228, -1, + 8228, 8308, 8307, -1, 8308, 8228, 8227, -1, + 8227, 8309, 8308, -1, 8309, 8227, 8226, -1, + 8226, 8310, 8309, -1, 8310, 8226, 8225, -1, + 8225, 8311, 8310, -1, 8311, 8225, 8224, -1, + 8224, 8312, 8311, -1, 8312, 8224, 8223, -1, + 8223, 314, 8312, -1, 314, 3, 8312, -1, + 314, 48, 3, -1, 48, 314, 313, -1, + 313, 47, 48, -1, 47, 313, 333, -1, + 333, 46, 47, -1, 46, 333, 331, -1, + 331, 45, 46, -1, 45, 331, 329, -1, + 329, 44, 45, -1, 44, 329, 327, -1, + 327, 33, 44, -1, 33, 327, 325, -1, + 325, 34, 33, -1, 34, 325, 323, -1, + 323, 36, 34, -1, 36, 323, 322, -1, + 322, 38, 36, -1, 38, 322, 321, -1, + 321, 40, 38, -1, 321, 42, 40, -1, + 321, 320, 42, -1, 320, 317, 42, -1, + 42, 317, 316, -1, 2, 43, 42, -1, + 43, 2, 1, -1, 1, 29, 43, -1, + 1, 0, 29, -1, 0, 30, 29, -1, + 30, 0, 2, -1, 30, 2, 7912, -1, + 7912, 31, 30, -1, 7912, 7913, 31, -1, + 31, 7913, 103, -1, 31, 103, 101, -1, + 101, 28, 31, -1, 28, 101, 100, -1, + 100, 26, 28, -1, 26, 100, 7916, -1, + 7916, 24, 26, -1, 24, 7916, 7917, -1, + 7917, 22, 24, -1, 22, 7917, 7918, -1, + 7918, 20, 22, -1, 20, 7918, 7919, -1, + 7919, 18, 20, -1, 18, 7919, 7920, -1, + 7920, 16, 18, -1, 16, 7920, 7921, -1, + 7921, 14, 16, -1, 14, 7921, 7922, -1, + 7922, 12, 14, -1, 12, 7922, 7923, -1, + 7923, 10, 12, -1, 10, 7923, 7924, -1, + 7924, 9, 10, -1, 9, 7924, 7925, -1, + 7925, 7, 9, -1, 7, 7925, 7926, -1, + 7926, 8313, 7, -1, 8313, 7926, 7927, -1, + 7927, 8314, 8313, -1, 8314, 7927, 7928, -1, + 7928, 8315, 8314, -1, 8315, 7928, 7929, -1, + 7929, 8316, 8315, -1, 8316, 7929, 7930, -1, + 7930, 8317, 8316, -1, 8317, 7930, 7931, -1, + 7931, 8318, 8317, -1, 8318, 7931, 7932, -1, + 7932, 8319, 8318, -1, 8319, 7932, 7933, -1, + 7933, 8320, 8319, -1, 8320, 7933, 7934, -1, + 7934, 8321, 8320, -1, 8321, 7934, 7935, -1, + 7935, 8322, 8321, -1, 8322, 7935, 7936, -1, + 7936, 8323, 8322, -1, 8323, 7936, 7937, -1, + 7937, 8324, 8323, -1, 8324, 7937, 7938, -1, + 7938, 8325, 8324, -1, 8325, 7938, 7939, -1, + 7939, 8326, 8325, -1, 8326, 7939, 7940, -1, + 7940, 8327, 8326, -1, 8327, 7940, 7941, -1, + 7941, 8328, 8327, -1, 8328, 7941, 7942, -1, + 7942, 8329, 8328, -1, 8329, 7942, 7943, -1, + 7943, 8330, 8329, -1, 8330, 7943, 7944, -1, + 7944, 8331, 8330, -1, 8331, 7944, 7945, -1, + 7945, 8332, 8331, -1, 8332, 7945, 7946, -1, + 7946, 8333, 8332, -1, 8333, 7946, 7947, -1, + 7947, 8334, 8333, -1, 8334, 7947, 7948, -1, + 7948, 8335, 8334, -1, 8335, 7948, 7949, -1, + 8335, 7949, 7950, -1, 7950, 8336, 8335, -1, + 8336, 7950, 7951, -1, 7951, 8337, 8336, -1, + 8337, 7951, 7952, -1, 7952, 8338, 8337, -1, + 8338, 7952, 7953, -1, 7953, 8339, 8338, -1, + 8339, 7953, 7954, -1, 7954, 8340, 8339, -1, + 8340, 7954, 7955, -1, 7955, 8341, 8340, -1, + 8341, 7955, 7956, -1, 7956, 8342, 8341, -1, + 8342, 7956, 7957, -1, 7957, 8343, 8342, -1, + 8343, 7957, 7958, -1, 7958, 8344, 8343, -1, + 8344, 7958, 7959, -1, 7959, 8345, 8344, -1, + 8345, 7959, 7960, -1, 7960, 8346, 8345, -1, + 8346, 7960, 7961, -1, 7961, 8347, 8346, -1, + 8347, 7961, 7962, -1, 7962, 8348, 8347, -1, + 8348, 7962, 7963, -1, 7963, 8349, 8348, -1, + 8349, 7963, 7964, -1, 7964, 8350, 8349, -1, + 8350, 7964, 7965, -1, 7965, 8351, 8350, -1, + 8351, 7965, 7966, -1, 7966, 8352, 8351, -1, + 8352, 7966, 7967, -1, 7967, 8353, 8352, -1, + 8353, 7967, 7968, -1, 7968, 8354, 8353, -1, + 8354, 7968, 7969, -1, 7969, 8355, 8354, -1, + 8355, 7969, 7970, -1, 7970, 8356, 8355, -1, + 8356, 7970, 7971, -1, 7971, 8357, 8356, -1, + 8357, 7971, 7972, -1, 7972, 8358, 8357, -1, + 8358, 7972, 7973, -1, 7973, 7974, 8358, -1, + 8359, 8358, 7974, -1, 8358, 8359, 8360, -1, + 8360, 8357, 8358, -1, 8357, 8360, 8361, -1, + 8361, 8356, 8357, -1, 8356, 8361, 8362, -1, + 8362, 8355, 8356, -1, 8355, 8362, 8363, -1, + 8363, 8354, 8355, -1, 8354, 8363, 8364, -1, + 8364, 8353, 8354, -1, 8353, 8364, 8365, -1, + 8365, 8352, 8353, -1, 8352, 8365, 8366, -1, + 8366, 8351, 8352, -1, 8351, 8366, 8367, -1, + 8367, 8350, 8351, -1, 8350, 8367, 8368, -1, + 8368, 8349, 8350, -1, 8349, 8368, 8369, -1, + 8369, 8348, 8349, -1, 8348, 8369, 8370, -1, + 8370, 8347, 8348, -1, 8347, 8370, 8371, -1, + 8371, 8346, 8347, -1, 8346, 8371, 8372, -1, + 8372, 8345, 8346, -1, 8345, 8372, 8373, -1, + 8373, 8344, 8345, -1, 8344, 8373, 8374, -1, + 8374, 8343, 8344, -1, 8343, 8374, 8375, -1, + 8375, 8342, 8343, -1, 8342, 8375, 8376, -1, + 8376, 8341, 8342, -1, 8341, 8376, 8377, -1, + 8377, 8340, 8341, -1, 8340, 8377, 8378, -1, + 8378, 8339, 8340, -1, 8339, 8378, 8379, -1, + 8379, 8338, 8339, -1, 8338, 8379, 8380, -1, + 8380, 8337, 8338, -1, 8337, 8380, 8381, -1, + 8381, 8336, 8337, -1, 8336, 8381, 8382, -1, + 8382, 8335, 8336, -1, 8382, 8334, 8335, -1, + 8334, 8382, 8383, -1, 8383, 8333, 8334, -1, + 8333, 8383, 8384, -1, 8384, 8332, 8333, -1, + 8332, 8384, 8385, -1, 8385, 8331, 8332, -1, + 8331, 8385, 8386, -1, 8386, 8330, 8331, -1, + 8330, 8386, 8387, -1, 8387, 8329, 8330, -1, + 8329, 8387, 8388, -1, 8388, 8328, 8329, -1, + 8328, 8388, 8389, -1, 8389, 8327, 8328, -1, + 8327, 8389, 8390, -1, 8390, 8326, 8327, -1, + 8326, 8390, 8391, -1, 8391, 8325, 8326, -1, + 8325, 8391, 8392, -1, 8392, 8324, 8325, -1, + 8324, 8392, 8393, -1, 8393, 8323, 8324, -1, + 8323, 8393, 8394, -1, 8394, 8322, 8323, -1, + 8322, 8394, 8395, -1, 8395, 8321, 8322, -1, + 8321, 8395, 8396, -1, 8396, 8320, 8321, -1, + 8320, 8396, 8397, -1, 8397, 8319, 8320, -1, + 8319, 8397, 8398, -1, 8398, 8318, 8319, -1, + 8318, 8398, 8399, -1, 8399, 8317, 8318, -1, + 8317, 8399, 8400, -1, 8400, 8316, 8317, -1, + 8316, 8400, 8401, -1, 8401, 8315, 8316, -1, + 8315, 8401, 8402, -1, 8402, 8314, 8315, -1, + 8314, 8402, 8403, -1, 8403, 8313, 8314, -1, + 8313, 8403, 8404, -1, 8404, 7, 8313, -1, + 8404, 8, 7, -1, 8404, 8405, 8, -1, + 8405, 8404, 8403, -1, 8403, 8406, 8405, -1, + 8406, 8403, 8402, -1, 8402, 8407, 8406, -1, + 8407, 8402, 8401, -1, 8401, 8408, 8407, -1, + 8408, 8401, 8400, -1, 8400, 8409, 8408, -1, + 8409, 8400, 8399, -1, 8399, 8410, 8409, -1, + 8410, 8399, 8398, -1, 8398, 8411, 8410, -1, + 8411, 8398, 8397, -1, 8397, 8412, 8411, -1, + 8412, 8397, 8396, -1, 8396, 8413, 8412, -1, + 8413, 8396, 8395, -1, 8395, 8414, 8413, -1, + 8414, 8395, 8394, -1, 8394, 8415, 8414, -1, + 8415, 8394, 8393, -1, 8393, 8416, 8415, -1, + 8416, 8393, 8392, -1, 8392, 8417, 8416, -1, + 8417, 8392, 8391, -1, 8391, 8418, 8417, -1, + 8418, 8391, 8390, -1, 8390, 8419, 8418, -1, + 8419, 8390, 8389, -1, 8389, 8420, 8419, -1, + 8420, 8389, 8388, -1, 8388, 8421, 8420, -1, + 8421, 8388, 8387, -1, 8387, 8422, 8421, -1, + 8422, 8387, 8386, -1, 8386, 8423, 8422, -1, + 8423, 8386, 8385, -1, 8385, 8424, 8423, -1, + 8424, 8385, 8384, -1, 8384, 8425, 8424, -1, + 8425, 8384, 8383, -1, 8383, 8426, 8425, -1, + 8426, 8383, 8382, -1, 8426, 8382, 8381, -1, + 8381, 8427, 8426, -1, 8427, 8381, 8380, -1, + 8380, 8428, 8427, -1, 8428, 8380, 8379, -1, + 8379, 8429, 8428, -1, 8429, 8379, 8378, -1, + 8378, 8430, 8429, -1, 8430, 8378, 8377, -1, + 8377, 8431, 8430, -1, 8431, 8377, 8376, -1, + 8376, 8432, 8431, -1, 8432, 8376, 8375, -1, + 8375, 8433, 8432, -1, 8433, 8375, 8374, -1, + 8374, 8434, 8433, -1, 8434, 8374, 8373, -1, + 8373, 8435, 8434, -1, 8435, 8373, 8372, -1, + 8372, 8436, 8435, -1, 8436, 8372, 8371, -1, + 8371, 8437, 8436, -1, 8437, 8371, 8370, -1, + 8370, 8438, 8437, -1, 8438, 8370, 8369, -1, + 8369, 8439, 8438, -1, 8439, 8369, 8368, -1, + 8368, 8440, 8439, -1, 8440, 8368, 8367, -1, + 8367, 8441, 8440, -1, 8441, 8367, 8366, -1, + 8366, 8442, 8441, -1, 8442, 8366, 8365, -1, + 8365, 8443, 8442, -1, 8443, 8365, 8364, -1, + 8364, 8444, 8443, -1, 8444, 8364, 8363, -1, + 8363, 8445, 8444, -1, 8445, 8363, 8362, -1, + 8362, 8446, 8445, -1, 8446, 8362, 8361, -1, + 8361, 8447, 8446, -1, 8447, 8361, 8360, -1, + 8360, 8448, 8447, -1, 8448, 8360, 8359, -1, + 8359, 8449, 8448, -1, 8449, 8359, 7974, -1, + 8449, 7974, 7976, -1, 8449, 7976, 8450, -1, + 8450, 8448, 8449, -1, 8448, 8450, 8451, -1, + 8451, 8447, 8448, -1, 8447, 8451, 8452, -1, + 8452, 8446, 8447, -1, 8446, 8452, 8453, -1, + 8453, 8445, 8446, -1, 8445, 8453, 8454, -1, + 8454, 8444, 8445, -1, 8444, 8454, 8455, -1, + 8455, 8443, 8444, -1, 8443, 8455, 8456, -1, + 8456, 8442, 8443, -1, 8442, 8456, 8457, -1, + 8457, 8441, 8442, -1, 8441, 8457, 8458, -1, + 8458, 8440, 8441, -1, 8440, 8458, 8459, -1, + 8459, 8439, 8440, -1, 8439, 8459, 8460, -1, + 8460, 8438, 8439, -1, 8438, 8460, 8461, -1, + 8461, 8437, 8438, -1, 8437, 8461, 8462, -1, + 8462, 8436, 8437, -1, 8436, 8462, 8463, -1, + 8463, 8435, 8436, -1, 8435, 8463, 8464, -1, + 8464, 8434, 8435, -1, 8434, 8464, 8465, -1, + 8465, 8433, 8434, -1, 8433, 8465, 8466, -1, + 8466, 8432, 8433, -1, 8432, 8466, 8467, -1, + 8467, 8431, 8432, -1, 8431, 8467, 8468, -1, + 8468, 8430, 8431, -1, 8430, 8468, 8469, -1, + 8469, 8429, 8430, -1, 8429, 8469, 8470, -1, + 8470, 8428, 8429, -1, 8428, 8470, 8471, -1, + 8471, 8427, 8428, -1, 8427, 8471, 8472, -1, + 8472, 8426, 8427, -1, 8472, 8425, 8426, -1, + 8425, 8472, 8473, -1, 8473, 8424, 8425, -1, + 8424, 8473, 8474, -1, 8474, 8423, 8424, -1, + 8423, 8474, 8475, -1, 8475, 8422, 8423, -1, + 8422, 8475, 8476, -1, 8476, 8421, 8422, -1, + 8421, 8476, 8477, -1, 8477, 8420, 8421, -1, + 8420, 8477, 8478, -1, 8478, 8419, 8420, -1, + 8419, 8478, 8479, -1, 8479, 8418, 8419, -1, + 8418, 8479, 8480, -1, 8480, 8417, 8418, -1, + 8417, 8480, 8481, -1, 8481, 8416, 8417, -1, + 8416, 8481, 8482, -1, 8482, 8415, 8416, -1, + 8415, 8482, 8483, -1, 8483, 8414, 8415, -1, + 8414, 8483, 8484, -1, 8484, 8413, 8414, -1, + 8413, 8484, 8485, -1, 8485, 8412, 8413, -1, + 8412, 8485, 8486, -1, 8486, 8411, 8412, -1, + 8411, 8486, 8487, -1, 8487, 8410, 8411, -1, + 8410, 8487, 8488, -1, 8488, 8409, 8410, -1, + 8409, 8488, 8489, -1, 8489, 8408, 8409, -1, + 8408, 8489, 8490, -1, 8490, 8407, 8408, -1, + 8407, 8490, 8491, -1, 8491, 8406, 8407, -1, + 8406, 8491, 8492, -1, 8492, 8405, 8406, -1, + 8405, 8492, 8493, -1, 8493, 8, 8405, -1, + 8, 8493, 8494, -1, 8494, 4, 8, -1, + 8494, 5, 4, -1, 8494, 8495, 5, -1, + 8495, 8494, 8493, -1, 8493, 8496, 8495, -1, + 8496, 8493, 8492, -1, 8492, 8497, 8496, -1, + 8497, 8492, 8491, -1, 8491, 8498, 8497, -1, + 8498, 8491, 8490, -1, 8490, 8499, 8498, -1, + 8499, 8490, 8489, -1, 8489, 8500, 8499, -1, + 8500, 8489, 8488, -1, 8488, 8501, 8500, -1, + 8501, 8488, 8487, -1, 8487, 8502, 8501, -1, + 8502, 8487, 8486, -1, 8486, 8503, 8502, -1, + 8503, 8486, 8485, -1, 8485, 8504, 8503, -1, + 8504, 8485, 8484, -1, 8484, 8505, 8504, -1, + 8505, 8484, 8483, -1, 8483, 8506, 8505, -1, + 8506, 8483, 8482, -1, 8482, 8507, 8506, -1, + 8507, 8482, 8481, -1, 8481, 8508, 8507, -1, + 8508, 8481, 8480, -1, 8480, 8509, 8508, -1, + 8509, 8480, 8479, -1, 8479, 8510, 8509, -1, + 8510, 8479, 8478, -1, 8478, 8511, 8510, -1, + 8511, 8478, 8477, -1, 8477, 8512, 8511, -1, + 8512, 8477, 8476, -1, 8476, 8513, 8512, -1, + 8513, 8476, 8475, -1, 8475, 8514, 8513, -1, + 8514, 8475, 8474, -1, 8474, 8515, 8514, -1, + 8515, 8474, 8473, -1, 8473, 8516, 8515, -1, + 8516, 8473, 8472, -1, 8516, 8472, 8471, -1, + 8471, 8517, 8516, -1, 8517, 8471, 8470, -1, + 8470, 8518, 8517, -1, 8518, 8470, 8469, -1, + 8469, 8519, 8518, -1, 8519, 8469, 8468, -1, + 8468, 8520, 8519, -1, 8520, 8468, 8467, -1, + 8467, 8521, 8520, -1, 8521, 8467, 8466, -1, + 8466, 8522, 8521, -1, 8522, 8466, 8465, -1, + 8465, 8523, 8522, -1, 8523, 8465, 8464, -1, + 8464, 8524, 8523, -1, 8524, 8464, 8463, -1, + 8463, 8525, 8524, -1, 8525, 8463, 8462, -1, + 8462, 8526, 8525, -1, 8526, 8462, 8461, -1, + 8461, 8527, 8526, -1, 8527, 8461, 8460, -1, + 8460, 8528, 8527, -1, 8528, 8460, 8459, -1, + 8459, 8529, 8528, -1, 8529, 8459, 8458, -1, + 8458, 8530, 8529, -1, 8530, 8458, 8457, -1, + 8457, 8531, 8530, -1, 8531, 8457, 8456, -1, + 8456, 8532, 8531, -1, 8532, 8456, 8455, -1, + 8455, 8533, 8532, -1, 8533, 8455, 8454, -1, + 8454, 8534, 8533, -1, 8534, 8454, 8453, -1, + 8453, 8535, 8534, -1, 8535, 8453, 8452, -1, + 8452, 8536, 8535, -1, 8536, 8452, 8451, -1, + 8451, 8537, 8536, -1, 8537, 8451, 8450, -1, + 8450, 8538, 8537, -1, 8538, 8450, 7976, -1, + 7976, 8539, 8538, -1, 8539, 7976, 7975, -1, + 8539, 7975, 7978, -1, 8539, 7978, 8540, -1, + 8540, 8538, 8539, -1, 8538, 8540, 8541, -1, + 8541, 8537, 8538, -1, 8537, 8541, 8542, -1, + 8542, 8536, 8537, -1, 8536, 8542, 8543, -1, + 8543, 8535, 8536, -1, 8535, 8543, 8544, -1, + 8544, 8534, 8535, -1, 8534, 8544, 8545, -1, + 8545, 8533, 8534, -1, 8533, 8545, 8546, -1, + 8546, 8532, 8533, -1, 8532, 8546, 8547, -1, + 8547, 8531, 8532, -1, 8531, 8547, 8548, -1, + 8548, 8530, 8531, -1, 8530, 8548, 8549, -1, + 8549, 8529, 8530, -1, 8529, 8549, 8550, -1, + 8550, 8528, 8529, -1, 8528, 8550, 8551, -1, + 8551, 8527, 8528, -1, 8527, 8551, 8552, -1, + 8552, 8526, 8527, -1, 8526, 8552, 8553, -1, + 8553, 8525, 8526, -1, 8525, 8553, 8554, -1, + 8554, 8524, 8525, -1, 8524, 8554, 8555, -1, + 8555, 8523, 8524, -1, 8523, 8555, 8556, -1, + 8556, 8522, 8523, -1, 8522, 8556, 8557, -1, + 8557, 8521, 8522, -1, 8521, 8557, 8558, -1, + 8558, 8520, 8521, -1, 8520, 8558, 8559, -1, + 8559, 8519, 8520, -1, 8519, 8559, 8560, -1, + 8560, 8518, 8519, -1, 8518, 8560, 8561, -1, + 8561, 8517, 8518, -1, 8517, 8561, 8562, -1, + 8562, 8516, 8517, -1, 8562, 8515, 8516, -1, + 8515, 8562, 8563, -1, 8563, 8514, 8515, -1, + 8514, 8563, 8564, -1, 8564, 8513, 8514, -1, + 8513, 8564, 8565, -1, 8565, 8512, 8513, -1, + 8512, 8565, 8566, -1, 8566, 8511, 8512, -1, + 8511, 8566, 8567, -1, 8567, 8510, 8511, -1, + 8510, 8567, 8568, -1, 8568, 8509, 8510, -1, + 8509, 8568, 8569, -1, 8569, 8508, 8509, -1, + 8508, 8569, 8570, -1, 8570, 8507, 8508, -1, + 8507, 8570, 8571, -1, 8571, 8506, 8507, -1, + 8506, 8571, 8572, -1, 8572, 8505, 8506, -1, + 8505, 8572, 8573, -1, 8573, 8504, 8505, -1, + 8504, 8573, 8574, -1, 8574, 8503, 8504, -1, + 8503, 8574, 8575, -1, 8575, 8502, 8503, -1, + 8502, 8575, 8576, -1, 8576, 8501, 8502, -1, + 8501, 8576, 8577, -1, 8577, 8500, 8501, -1, + 8500, 8577, 8578, -1, 8578, 8499, 8500, -1, + 8499, 8578, 8579, -1, 8579, 8498, 8499, -1, + 8498, 8579, 8580, -1, 8580, 8497, 8498, -1, + 8497, 8580, 8581, -1, 8581, 8496, 8497, -1, + 8496, 8581, 8582, -1, 8582, 8495, 8496, -1, + 8495, 8582, 8583, -1, 8583, 5, 8495, -1, + 5, 8583, 8584, -1, 8584, 3, 5, -1, + 8584, 8312, 3, -1, 8584, 8311, 8312, -1, + 8311, 8584, 8583, -1, 8583, 8310, 8311, -1, + 8310, 8583, 8582, -1, 8582, 8309, 8310, -1, + 8309, 8582, 8581, -1, 8581, 8308, 8309, -1, + 8308, 8581, 8580, -1, 8580, 8307, 8308, -1, + 8307, 8580, 8579, -1, 8579, 8306, 8307, -1, + 8306, 8579, 8578, -1, 8578, 8305, 8306, -1, + 8305, 8578, 8577, -1, 8577, 8304, 8305, -1, + 8304, 8577, 8576, -1, 8576, 8303, 8304, -1, + 8303, 8576, 8575, -1, 8575, 8302, 8303, -1, + 8302, 8575, 8574, -1, 8574, 8301, 8302, -1, + 8301, 8574, 8573, -1, 8573, 8300, 8301, -1, + 8300, 8573, 8572, -1, 8572, 8299, 8300, -1, + 8299, 8572, 8571, -1, 8571, 8298, 8299, -1, + 8298, 8571, 8570, -1, 8570, 8297, 8298, -1, + 8297, 8570, 8569, -1, 8569, 8296, 8297, -1, + 8296, 8569, 8568, -1, 8568, 8295, 8296, -1, + 8295, 8568, 8567, -1, 8567, 8294, 8295, -1, + 8294, 8567, 8566, -1, 8566, 8293, 8294, -1, + 8293, 8566, 8565, -1, 8565, 8292, 8293, -1, + 8292, 8565, 8564, -1, 8564, 8291, 8292, -1, + 8291, 8564, 8563, -1, 8563, 8290, 8291, -1, + 8290, 8563, 8562, -1, 8290, 8562, 8561, -1, + 8561, 8289, 8290, -1, 8289, 8561, 8560, -1, + 8560, 8288, 8289, -1, 8288, 8560, 8559, -1, + 8559, 8287, 8288, -1, 8287, 8559, 8558, -1, + 8558, 8286, 8287, -1, 8286, 8558, 8557, -1, + 8557, 8285, 8286, -1, 8285, 8557, 8556, -1, + 8556, 8284, 8285, -1, 8284, 8556, 8555, -1, + 8555, 8283, 8284, -1, 8283, 8555, 8554, -1, + 8554, 8282, 8283, -1, 8282, 8554, 8553, -1, + 8553, 8281, 8282, -1, 8281, 8553, 8552, -1, + 8552, 8280, 8281, -1, 8280, 8552, 8551, -1, + 8551, 8279, 8280, -1, 8279, 8551, 8550, -1, + 8550, 8278, 8279, -1, 8278, 8550, 8549, -1, + 8549, 8277, 8278, -1, 8277, 8549, 8548, -1, + 8548, 8276, 8277, -1, 8276, 8548, 8547, -1, + 8547, 8275, 8276, -1, 8275, 8547, 8546, -1, + 8546, 8274, 8275, -1, 8274, 8546, 8545, -1, + 8545, 8273, 8274, -1, 8273, 8545, 8544, -1, + 8544, 8272, 8273, -1, 8272, 8544, 8543, -1, + 8543, 8271, 8272, -1, 8271, 8543, 8542, -1, + 8542, 8270, 8271, -1, 8270, 8542, 8541, -1, + 8541, 8269, 8270, -1, 8269, 8541, 8540, -1, + 8540, 8268, 8269, -1, 8268, 8540, 7978, -1, + 7978, 8022, 8268, -1, 8022, 7978, 7977, -1, + 7977, 8019, 8022, -1, 8019, 7977, 7979, -1, + 7979, 8017, 8019, -1, 8017, 7979, 7980, -1, + 7980, 8015, 8017, -1, 8015, 7980, 7981, -1, + 7981, 8013, 8015, -1, 8013, 7981, 7982, -1, + 7982, 8011, 8013, -1, 8011, 7982, 7983, -1, + 7983, 8010, 8011, -1, 8010, 7983, 7984, -1, + 7984, 8009, 8010, -1, 8009, 7984, 7985, -1, + 7985, 8008, 8009, -1, 8008, 7985, 7986, -1, + 7986, 8585, 8008, -1, 8586, 8008, 8585, -1, + 8586, 8007, 8008, -1, 8586, 8004, 8007, -1, + 8586, 8585, 8004, -1, 8585, 8587, 8004, -1, + 8587, 8585, 7986, -1, 8587, 7986, 7987, -1, + 8587, 7987, 7989, -1, 7989, 8004, 8587, -1, + 2206, 2204, 8588, -1, 8588, 2204, 2207, -1, + 2206, 8588, 2202, -1, 2202, 8588, 2207, -1, + 278, 282, 316, -1, 316, 282, 336, -1, + 316, 336, 42, -1, 42, 336, 2, -1, + 2, 336, 7906, -1, 7906, 336, 7908, -1, + 7908, 336, 7703, -1, 7703, 336, 3089, -1, + 3089, 336, 3086, -1, 3086, 336, 348, -1, + 3086, 348, 7683, -1, 7683, 7666, 3086, -1, + 3086, 7666, 389, -1, 3086, 389, 7662, -1, + 7662, 355, 3086, -1, 3086, 355, 399, -1, + 3086, 399, 2521, -1, 2521, 2525, 3086, -1, + 3086, 2525, 2527, -1, 3086, 2527, 3082, -1, + 3086, 3082, 2510, -1, 2510, 3082, 2506, -1, + 2506, 3082, 4974, -1, 4974, 3082, 4976, -1, + 4976, 3082, 5380, -1, 5380, 3082, 7616, -1, + 5380, 7616, 2700, -1, 2700, 1138, 5380, -1, + 5380, 1138, 1140, -1, 5380, 1140, 1152, -1, + 5380, 1152, 5369, -1, 5369, 1152, 5382, -1, + 5382, 1152, 1182, -1, 1182, 1152, 5297, -1, + 5297, 1152, 5296, -1, 5296, 1152, 5300, -1, + 5300, 1152, 5321, -1, 5321, 1152, 3500, -1, + 1152, 1143, 3500, -1, 3500, 1143, 3473, -1, + 3500, 3473, 3466, -1, 3500, 3466, 3687, -1, + 3687, 3466, 3464, -1, 3464, 3466, 3950, -1, + 3950, 3466, 3954, -1, 3954, 3466, 3461, -1, + 3461, 3466, 4401, -1, 3461, 4401, 4399, -1, + 4399, 4393, 3461, -1, 3461, 4393, 96, -1, + 3461, 96, 4023, -1, 4023, 96, 4384, -1, + 4384, 96, 7999, -1, 7999, 96, 98, -1, + 7999, 98, 91, -1, 91, 8004, 7999, -1, + 7999, 8004, 7995, -1, 7995, 8004, 7991, -1, + 7991, 8004, 7989, -1, 8589, 8590, 8591, -1, + 8591, 8590, 8592, -1, 8591, 8593, 8589, -1, + 8589, 8593, 8594, -1, 8590, 8595, 8592, -1, + 8592, 8595, 8596, -1, 8597, 8598, 8599, -1, + 8599, 8598, 8600, -1, 8599, 8601, 8597, -1, + 8597, 8601, 8602, -1, 8603, 8604, 8605, -1, + 8605, 8604, 8606, -1, 8605, 8602, 8603, -1, + 8603, 8602, 8601, -1, 8602, 8605, 8597, -1, + 8597, 8605, 8606, -1, 8597, 8606, 8607, -1, + 8597, 8607, 8598, -1, 8598, 8607, 8608, -1, + 8608, 8607, 8609, -1, 8609, 8607, 8610, -1, + 8610, 8607, 8611, -1, 8611, 8607, 8612, -1, + 8612, 8607, 8613, -1, 8613, 8607, 8614, -1, + 8614, 8607, 8615, -1, 8615, 8607, 8616, -1, + 8607, 8617, 8616, -1, 8616, 8617, 8618, -1, + 8616, 8618, 8619, -1, 8619, 8620, 8616, -1, + 8616, 8620, 8621, -1, 8616, 8621, 8622, -1, + 8622, 8623, 8616, -1, 8616, 8623, 8624, -1, + 8616, 8624, 8625, -1, 8616, 8625, 8626, -1, + 8626, 8625, 8627, -1, 8627, 8625, 8628, -1, + 8628, 8625, 8629, -1, 8629, 8625, 8630, -1, + 8630, 8625, 8631, -1, 8631, 8625, 8632, -1, + 8632, 8625, 8633, -1, 8632, 8633, 8634, -1, + 8634, 8635, 8632, -1, 8632, 8635, 8636, -1, + 8632, 8636, 8637, -1, 8637, 8638, 8632, -1, + 8632, 8638, 8639, -1, 8632, 8639, 8640, -1, + 8640, 8641, 8632, -1, 8632, 8641, 8595, -1, + 8632, 8595, 8590, -1, 8590, 8589, 8632, -1, + 8632, 8589, 8594, -1, 8632, 8594, 8642, -1, + 8642, 8594, 8643, -1, 8643, 8594, 8644, -1, + 8644, 8594, 8645, -1, 8645, 8594, 8646, -1, + 8646, 8594, 8647, -1, 8647, 8594, 8648, -1, + 8648, 8594, 8649, -1, 8649, 8594, 8650, -1, + 8650, 8594, 8651, -1, 8651, 8594, 8652, -1, + 8652, 8594, 8653, -1, 8604, 8654, 8606, -1, + 8606, 8654, 8607, -1, 8655, 8656, 8610, -1, + 8610, 8656, 8609, -1, 8610, 8611, 8655, -1, + 8655, 8611, 8657, -1, 8658, 8659, 8650, -1, + 8650, 8659, 8649, -1, 8650, 8651, 8658, -1, + 8658, 8651, 8660, -1, 8645, 8646, 8661, -1, + 8661, 8646, 8662, -1, 8661, 8663, 8645, -1, + 8645, 8663, 8644, -1, 8627, 8628, 8664, -1, + 8664, 8628, 8665, -1, 8664, 8666, 8627, -1, + 8627, 8666, 8626, -1, 8647, 8648, 8667, -1, + 8667, 8648, 8668, -1, 8667, 8662, 8647, -1, + 8647, 8662, 8646, -1, 8663, 8669, 8644, -1, + 8644, 8669, 8643, -1, 8669, 8670, 8643, -1, + 8643, 8670, 8642, -1, 8670, 8671, 8642, -1, + 8642, 8671, 8632, -1, 8628, 8629, 8665, -1, + 8665, 8629, 8672, -1, 8666, 8673, 8626, -1, + 8626, 8673, 8616, -1, 8673, 8674, 8616, -1, + 8616, 8674, 8615, -1, 8675, 8676, 8625, -1, + 8625, 8676, 8633, -1, 8625, 8624, 8675, -1, + 8675, 8624, 8677, -1, 8618, 8617, 8678, -1, + 8678, 8617, 8679, -1, 8678, 8680, 8618, -1, + 8618, 8680, 8619, -1, 8637, 8636, 8681, -1, + 8681, 8636, 8682, -1, 8681, 8683, 8637, -1, + 8637, 8683, 8638, -1, 8620, 8619, 8684, -1, + 8684, 8619, 8680, -1, 8684, 8685, 8620, -1, + 8620, 8685, 8621, -1, 8685, 8686, 8621, -1, + 8621, 8686, 8622, -1, 8623, 8622, 8687, -1, + 8687, 8622, 8686, -1, 8687, 8677, 8623, -1, + 8623, 8677, 8624, -1, 8688, 8689, 8634, -1, + 8634, 8689, 8635, -1, 8634, 8633, 8688, -1, + 8688, 8633, 8676, -1, 8689, 8682, 8635, -1, + 8635, 8682, 8636, -1, 8683, 8690, 8638, -1, + 8638, 8690, 8639, -1, 8617, 8607, 8679, -1, + 8679, 8607, 8654, -1, 8674, 8691, 8615, -1, + 8615, 8691, 8614, -1, 8691, 8692, 8614, -1, + 8614, 8692, 8613, -1, 8692, 8693, 8613, -1, + 8613, 8693, 8612, -1, 8648, 8649, 8668, -1, + 8668, 8649, 8659, -1, 8693, 8657, 8612, -1, + 8612, 8657, 8611, -1, 8651, 8652, 8660, -1, + 8660, 8652, 8694, -1, 8695, 8694, 8653, -1, + 8653, 8694, 8652, -1, 8653, 8594, 8695, -1, + 8695, 8594, 8593, -1, 8656, 8696, 8609, -1, + 8609, 8696, 8608, -1, 8696, 8600, 8608, -1, + 8608, 8600, 8598, -1, 8690, 8697, 8639, -1, + 8639, 8697, 8640, -1, 8697, 8698, 8640, -1, + 8640, 8698, 8641, -1, 8698, 8596, 8641, -1, + 8641, 8596, 8595, -1, 8671, 8699, 8632, -1, + 8632, 8699, 8631, -1, 8629, 8630, 8672, -1, + 8672, 8630, 8700, -1, 8630, 8631, 8700, -1, + 8700, 8631, 8699, -1, 1421, 1391, 1579, -1, + 1579, 1391, 1390, -1, 2985, 3050, 3020, -1, + 3020, 3050, 3049, -1, 2985, 2986, 3050, -1, + 3050, 2986, 2840, -1, 2840, 3052, 3051, -1, + 3051, 3052, 3068, -1, 3049, 3051, 3070, -1, + 3070, 3051, 3068, -1, 3811, 1190, 8701, -1, + 8701, 1190, 3702, -1, 3811, 8701, 3701, -1, + 3701, 8701, 3702, -1, 433, 417, 8700, -1, + 8700, 417, 414, -1, 8700, 414, 8672, -1, + 8672, 414, 435, -1, 8672, 435, 8665, -1, + 8665, 435, 1600, -1, 8665, 1600, 8664, -1, + 8664, 1600, 1365, -1, 8664, 1365, 8666, -1, + 8666, 1365, 1366, -1, 8666, 1366, 8673, -1, + 8673, 1366, 1254, -1, 8673, 1254, 8674, -1, + 8674, 1254, 5885, -1, 8674, 5885, 8691, -1, + 8691, 5885, 1531, -1, 8691, 1531, 8692, -1, + 8692, 1531, 1127, -1, 8692, 1127, 8693, -1, + 8693, 1127, 6015, -1, 8693, 6015, 8657, -1, + 8657, 6015, 847, -1, 8657, 847, 8655, -1, + 8655, 847, 836, -1, 8655, 836, 848, -1, + 8655, 848, 8656, -1, 8656, 848, 915, -1, + 8656, 915, 8696, -1, 8696, 915, 830, -1, + 8696, 830, 8600, -1, 8600, 830, 7162, -1, + 8600, 7162, 8599, -1, 8599, 7162, 826, -1, + 8599, 826, 8601, -1, 8601, 826, 825, -1, + 8601, 825, 8603, -1, 8603, 825, 547, -1, + 8603, 547, 8604, -1, 8604, 547, 506, -1, + 8604, 506, 8654, -1, 8654, 506, 5882, -1, + 8654, 5882, 8679, -1, 8679, 5882, 1761, -1, + 8679, 1761, 8678, -1, 8678, 1761, 1764, -1, + 8678, 1764, 8680, -1, 8680, 1764, 1644, -1, + 8680, 1644, 1681, -1, 8680, 1681, 8684, -1, + 8684, 1681, 2204, -1, 8684, 2204, 8685, -1, + 8685, 2204, 1607, -1, 8685, 1607, 8686, -1, + 8686, 1607, 1609, -1, 8686, 1609, 8687, -1, + 8687, 1609, 5006, -1, 8687, 5006, 8677, -1, + 8677, 5006, 1190, -1, 8677, 1190, 8675, -1, + 8675, 1190, 2210, -1, 8675, 2210, 8676, -1, + 8676, 2210, 5559, -1, 8676, 5559, 8688, -1, + 8688, 5559, 1133, -1, 8688, 1133, 8689, -1, + 8689, 1133, 5563, -1, 8689, 5563, 8682, -1, + 8682, 5563, 1934, -1, 8682, 1934, 8681, -1, + 8681, 1934, 1937, -1, 8681, 1937, 8683, -1, + 8683, 1937, 1941, -1, 8683, 1941, 1944, -1, + 8683, 1944, 8690, -1, 8690, 1944, 5568, -1, + 8690, 5568, 8697, -1, 8697, 5568, 7209, -1, + 8697, 7209, 8698, -1, 8698, 7209, 7213, -1, + 8698, 7213, 8596, -1, 8596, 7213, 603, -1, + 8596, 603, 8592, -1, 8592, 603, 459, -1, + 8592, 459, 8591, -1, 8591, 459, 458, -1, + 8591, 458, 8593, -1, 8593, 458, 6989, -1, + 8593, 6989, 8695, -1, 8695, 6989, 6565, -1, + 8695, 6565, 8694, -1, 8694, 6565, 6531, -1, + 8694, 6531, 8660, -1, 8660, 6531, 6369, -1, + 8660, 6369, 8658, -1, 8658, 6369, 6146, -1, + 8658, 6146, 6142, -1, 8658, 6142, 8659, -1, + 8659, 6142, 5927, -1, 8659, 5927, 8668, -1, + 8668, 5927, 1121, -1, 8668, 1121, 8667, -1, + 8667, 1121, 1575, -1, 8667, 1575, 8662, -1, + 8662, 1575, 1577, -1, 8662, 1577, 8661, -1, + 8661, 1577, 1422, -1, 8661, 1422, 8663, -1, + 8663, 1422, 1580, -1, 8663, 1580, 8669, -1, + 8669, 1580, 1267, -1, 8669, 1267, 8670, -1, + 8670, 1267, 1582, -1, 8670, 1582, 8671, -1, + 8671, 1582, 456, -1, 8671, 456, 8699, -1, + 8699, 456, 433, -1, 8699, 433, 8700, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5712, 5712, 5712, -1, 5713, 5713, 5713, -1, + 5714, 5714, 5714, -1, 5715, 5715, 5715, -1, + 5716, 5716, 5716, -1, 5717, 5717, 5717, -1, + 5718, 5718, 5718, -1, 5719, 5719, 5719, -1, + 5720, 5720, 5720, -1, 5721, 5721, 5721, -1, + 5722, 5722, 5722, -1, 5723, 5723, 5723, -1, + 5724, 5724, 5724, -1, 5725, 5725, 5725, -1, + 5726, 5726, 5726, -1, 5727, 5727, 5727, -1, + 5728, 5728, 5728, -1, 5729, 5729, 5729, -1, + 5730, 5730, 5730, -1, 5731, 5731, 5731, -1, + 5732, 5732, 5732, -1, 5733, 5733, 5733, -1, + 5734, 5734, 5734, -1, 5735, 5735, 5735, -1, + 5736, 5736, 5736, -1, 5737, 5737, 5737, -1, + 5738, 5738, 5738, -1, 5739, 5739, 5739, -1, + 5740, 5740, 5740, -1, 5741, 5741, 5741, -1, + 5742, 5742, 5742, -1, 5743, 5743, 5743, -1, + 5744, 5744, 5744, -1, 5745, 5745, 5745, -1, + 5746, 5746, 5746, -1, 5747, 5747, 5747, -1, + 5748, 5748, 5748, -1, 5749, 5749, 5749, -1, + 5750, 5750, 5750, -1, 5751, 5751, 5751, -1, + 5752, 5752, 5752, -1, 5753, 5753, 5753, -1, + 5754, 5754, 5754, -1, 5755, 5755, 5755, -1, + 5756, 5756, 5756, -1, 5757, 5757, 5757, -1, + 5758, 5758, 5758, -1, 5759, 5759, 5759, -1, + 5760, 5760, 5760, -1, 5761, 5761, 5761, -1, + 5762, 5762, 5762, -1, 5763, 5763, 5763, -1, + 5764, 5764, 5764, -1, 5765, 5765, 5765, -1, + 5766, 5766, 5766, -1, 5767, 5767, 5767, -1, + 5768, 5768, 5768, -1, 5769, 5769, 5769, -1, + 5770, 5770, 5770, -1, 5771, 5771, 5771, -1, + 5772, 5772, 5772, -1, 5773, 5773, 5773, -1, + 5774, 5774, 5774, -1, 5775, 5775, 5775, -1, + 5776, 5776, 5776, -1, 5777, 5777, 5777, -1, + 5778, 5778, 5778, -1, 5779, 5779, 5779, -1, + 5780, 5780, 5780, -1, 5781, 5781, 5781, -1, + 5782, 5782, 5782, -1, 5783, 5783, 5783, -1, + 5784, 5784, 5784, -1, 5785, 5785, 5785, -1, + 5786, 5786, 5786, -1, 5787, 5787, 5787, -1, + 5788, 5788, 5788, -1, 5789, 5789, 5789, -1, + 5790, 5790, 5790, -1, 5791, 5791, 5791, -1, + 5792, 5792, 5792, -1, 5793, 5793, 5793, -1, + 5794, 5794, 5794, -1, 5795, 5795, 5795, -1, + 5796, 5796, 5796, -1, 5797, 5797, 5797, -1, + 5798, 5798, 5798, -1, 5799, 5799, 5799, -1, + 5800, 5800, 5800, -1, 5801, 5801, 5801, -1, + 5802, 5802, 5802, -1, 5803, 5803, 5803, -1, + 5804, 5804, 5804, -1, 5805, 5805, 5805, -1, + 5806, 5806, 5806, -1, 5807, 5807, 5807, -1, + 5808, 5808, 5808, -1, 5809, 5809, 5809, -1, + 5810, 5810, 5810, -1, 5811, 5811, 5811, -1, + 5812, 5812, 5812, -1, 5813, 5813, 5813, -1, + 5814, 5814, 5814, -1, 5815, 5815, 5815, -1, + 5816, 5816, 5816, -1, 5817, 5817, 5817, -1, + 5818, 5818, 5818, -1, 5819, 5819, 5819, -1, + 5820, 5820, 5820, -1, 5821, 5821, 5821, -1, + 5822, 5822, 5822, -1, 5823, 5823, 5823, -1, + 5824, 5824, 5824, -1, 5825, 5825, 5825, -1, + 5826, 5826, 5826, -1, 5827, 5827, 5827, -1, + 5828, 5828, 5828, -1, 5829, 5829, 5829, -1, + 5830, 5830, 5830, -1, 5831, 5831, 5831, -1, + 5832, 5832, 5832, -1, 5833, 5833, 5833, -1, + 5834, 5834, 5834, -1, 5835, 5835, 5835, -1, + 5836, 5836, 5836, -1, 5837, 5837, 5837, -1, + 5838, 5838, 5838, -1, 5839, 5839, 5839, -1, + 5840, 5840, 5840, -1, 5841, 5841, 5841, -1, + 5842, 5842, 5842, -1, 5843, 5843, 5843, -1, + 5844, 5844, 5844, -1, 5845, 5845, 5845, -1, + 5846, 5846, 5846, -1, 5847, 5847, 5847, -1, + 5848, 5848, 5848, -1, 5849, 5849, 5849, -1, + 5850, 5850, 5850, -1, 5851, 5851, 5851, -1, + 5852, 5852, 5852, -1, 5853, 5853, 5853, -1, + 5854, 5854, 5854, -1, 5855, 5855, 5855, -1, + 5856, 5856, 5856, -1, 5857, 5857, 5857, -1, + 5858, 5858, 5858, -1, 5859, 5859, 5859, -1, + 5860, 5860, 5860, -1, 5861, 5861, 5861, -1, + 5862, 5862, 5862, -1, 5863, 5863, 5863, -1, + 5864, 5864, 5864, -1, 5865, 5865, 5865, -1, + 5866, 5866, 5866, -1, 5867, 5867, 5867, -1, + 5868, 5868, 5868, -1, 5869, 5869, 5869, -1, + 5870, 5870, 5870, -1, 5871, 5871, 5871, -1, + 5872, 5872, 5872, -1, 5873, 5873, 5873, -1, + 5874, 5874, 5874, -1, 5875, 5875, 5875, -1, + 5876, 5876, 5876, -1, 5877, 5877, 5877, -1, + 5878, 5878, 5878, -1, 5879, 5879, 5879, -1, + 5880, 5880, 5880, -1, 5881, 5881, 5881, -1, + 5882, 5882, 5882, -1, 5883, 5883, 5883, -1, + 5884, 5884, 5884, -1, 5885, 5885, 5885, -1, + 5886, 5886, 5886, -1, 5887, 5887, 5887, -1, + 5888, 5888, 5888, -1, 5889, 5889, 5889, -1, + 5890, 5890, 5890, -1, 5891, 5891, 5891, -1, + 5892, 5892, 5892, -1, 5893, 5893, 5893, -1, + 5894, 5894, 5894, -1, 5895, 5895, 5895, -1, + 5896, 5896, 5896, -1, 5897, 5897, 5897, -1, + 5898, 5898, 5898, -1, 5899, 5899, 5899, -1, + 5900, 5900, 5900, -1, 5901, 5901, 5901, -1, + 5902, 5902, 5902, -1, 5903, 5903, 5903, -1, + 5904, 5904, 5904, -1, 5905, 5905, 5905, -1, + 5906, 5906, 5906, -1, 5907, 5907, 5907, -1, + 5908, 5908, 5908, -1, 5909, 5909, 5909, -1, + 5910, 5910, 5910, -1, 5911, 5911, 5911, -1, + 5912, 5912, 5912, -1, 5913, 5913, 5913, -1, + 5914, 5914, 5914, -1, 5915, 5915, 5915, -1, + 5916, 5916, 5916, -1, 5917, 5917, 5917, -1, + 5918, 5918, 5918, -1, 5919, 5919, 5919, -1, + 5920, 5920, 5920, -1, 5921, 5921, 5921, -1, + 5922, 5922, 5922, -1, 5923, 5923, 5923, -1, + 5924, 5924, 5924, -1, 5925, 5925, 5925, -1, + 5926, 5926, 5926, -1, 5927, 5927, 5927, -1, + 5928, 5928, 5928, -1, 5929, 5929, 5929, -1, + 5930, 5930, 5930, -1, 5931, 5931, 5931, -1, + 5932, 5932, 5932, -1, 5933, 5933, 5933, -1, + 5934, 5934, 5934, -1, 5935, 5935, 5935, -1, + 5936, 5936, 5936, -1, 5937, 5937, 5937, -1, + 5938, 5938, 5938, -1, 5939, 5939, 5939, -1, + 5940, 5940, 5940, -1, 5941, 5941, 5941, -1, + 5942, 5942, 5942, -1, 5943, 5943, 5943, -1, + 5944, 5944, 5944, -1, 5945, 5945, 5945, -1, + 5946, 5946, 5946, -1, 5947, 5947, 5947, -1, + 5948, 5948, 5948, -1, 5949, 5949, 5949, -1, + 5950, 5950, 5950, -1, 5951, 5951, 5951, -1, + 5952, 5952, 5952, -1, 5953, 5953, 5953, -1, + 5954, 5954, 5954, -1, 5955, 5955, 5955, -1, + 5956, 5956, 5956, -1, 5957, 5957, 5957, -1, + 5958, 5958, 5958, -1, 5959, 5959, 5959, -1, + 5960, 5960, 5960, -1, 5961, 5961, 5961, -1, + 5962, 5962, 5962, -1, 5963, 5963, 5963, -1, + 5964, 5964, 5964, -1, 5965, 5965, 5965, -1, + 5966, 5966, 5966, -1, 5967, 5967, 5967, -1, + 5968, 5968, 5968, -1, 5969, 5969, 5969, -1, + 5970, 5970, 5970, -1, 5971, 5971, 5971, -1, + 5972, 5972, 5972, -1, 5973, 5973, 5973, -1, + 5974, 5974, 5974, -1, 5975, 5975, 5975, -1, + 5976, 5976, 5976, -1, 5977, 5977, 5977, -1, + 5978, 5978, 5978, -1, 5979, 5979, 5979, -1, + 5980, 5980, 5980, -1, 5981, 5981, 5981, -1, + 5982, 5982, 5982, -1, 5983, 5983, 5983, -1, + 5984, 5984, 5984, -1, 5985, 5985, 5985, -1, + 5986, 5986, 5986, -1, 5987, 5987, 5987, -1, + 5988, 5988, 5988, -1, 5989, 5989, 5989, -1, + 5990, 5990, 5990, -1, 5991, 5991, 5991, -1, + 5992, 5992, 5992, -1, 5993, 5993, 5993, -1, + 5994, 5994, 5994, -1, 5995, 5995, 5995, -1, + 5996, 5996, 5996, -1, 5997, 5997, 5997, -1, + 5998, 5998, 5998, -1, 5999, 5999, 5999, -1, + 6000, 6000, 6000, -1, 6001, 6001, 6001, -1, + 6002, 6002, 6002, -1, 6003, 6003, 6003, -1, + 6004, 6004, 6004, -1, 6005, 6005, 6005, -1, + 6006, 6006, 6006, -1, 6007, 6007, 6007, -1, + 6008, 6008, 6008, -1, 6009, 6009, 6009, -1, + 6010, 6010, 6010, -1, 6011, 6011, 6011, -1, + 6012, 6012, 6012, -1, 6013, 6013, 6013, -1, + 6014, 6014, 6014, -1, 6015, 6015, 6015, -1, + 6016, 6016, 6016, -1, 6017, 6017, 6017, -1, + 6018, 6018, 6018, -1, 6019, 6019, 6019, -1, + 6020, 6020, 6020, -1, 6021, 6021, 6021, -1, + 6022, 6022, 6022, -1, 6023, 6023, 6023, -1, + 6024, 6024, 6024, -1, 6025, 6025, 6025, -1, + 6026, 6026, 6026, -1, 6027, 6027, 6027, -1, + 6028, 6028, 6028, -1, 6029, 6029, 6029, -1, + 6030, 6030, 6030, -1, 6031, 6031, 6031, -1, + 6032, 6032, 6032, -1, 6033, 6033, 6033, -1, + 6034, 6034, 6034, -1, 6035, 6035, 6035, -1, + 6036, 6036, 6036, -1, 6037, 6037, 6037, -1, + 6038, 6038, 6038, -1, 6039, 6039, 6039, -1, + 6040, 6040, 6040, -1, 6041, 6041, 6041, -1, + 6042, 6042, 6042, -1, 6043, 6043, 6043, -1, + 6044, 6044, 6044, -1, 6045, 6045, 6045, -1, + 6046, 6046, 6046, -1, 6047, 6047, 6047, -1, + 6048, 6048, 6048, -1, 6049, 6049, 6049, -1, + 6050, 6050, 6050, -1, 6051, 6051, 6051, -1, + 6052, 6052, 6052, -1, 6053, 6053, 6053, -1, + 6054, 6054, 6054, -1, 6055, 6055, 6055, -1, + 6056, 6056, 6056, -1, 6057, 6057, 6057, -1, + 6058, 6058, 6058, -1, 6059, 6059, 6059, -1, + 6060, 6060, 6060, -1, 6061, 6061, 6061, -1, + 6062, 6062, 6062, -1, 6063, 6063, 6063, -1, + 6064, 6064, 6064, -1, 6065, 6065, 6065, -1, + 6066, 6066, 6066, -1, 6067, 6067, 6067, -1, + 6068, 6068, 6068, -1, 6069, 6069, 6069, -1, + 6070, 6070, 6070, -1, 6071, 6071, 6071, -1, + 6072, 6072, 6072, -1, 6073, 6073, 6073, -1, + 6074, 6074, 6074, -1, 6075, 6075, 6075, -1, + 6076, 6076, 6076, -1, 6077, 6077, 6077, -1, + 6078, 6078, 6078, -1, 6079, 6079, 6079, -1, + 6080, 6080, 6080, -1, 6081, 6081, 6081, -1, + 6082, 6082, 6082, -1, 6083, 6083, 6083, -1, + 6084, 6084, 6084, -1, 6085, 6085, 6085, -1, + 6086, 6086, 6086, -1, 6087, 6087, 6087, -1, + 6088, 6088, 6088, -1, 6089, 6089, 6089, -1, + 6090, 6090, 6090, -1, 6091, 6091, 6091, -1, + 6092, 6092, 6092, -1, 6093, 6093, 6093, -1, + 6094, 6094, 6094, -1, 6095, 6095, 6095, -1, + 6096, 6096, 6096, -1, 6097, 6097, 6097, -1, + 6098, 6098, 6098, -1, 6099, 6099, 6099, -1, + 6100, 6100, 6100, -1, 6101, 6101, 6101, -1, + 6102, 6102, 6102, -1, 6103, 6103, 6103, -1, + 6104, 6104, 6104, -1, 6105, 6105, 6105, -1, + 6106, 6106, 6106, -1, 6107, 6107, 6107, -1, + 6108, 6108, 6108, -1, 6109, 6109, 6109, -1, + 6110, 6110, 6110, -1, 6111, 6111, 6111, -1, + 6112, 6112, 6112, -1, 6113, 6113, 6113, -1, + 6114, 6114, 6114, -1, 6115, 6115, 6115, -1, + 6116, 6116, 6116, -1, 6117, 6117, 6117, -1, + 6118, 6118, 6118, -1, 6119, 6119, 6119, -1, + 6120, 6120, 6120, -1, 6121, 6121, 6121, -1, + 6122, 6122, 6122, -1, 6123, 6123, 6123, -1, + 6124, 6124, 6124, -1, 6125, 6125, 6125, -1, + 6126, 6126, 6126, -1, 6127, 6127, 6127, -1, + 6128, 6128, 6128, -1, 6129, 6129, 6129, -1, + 6130, 6130, 6130, -1, 6131, 6131, 6131, -1, + 6132, 6132, 6132, -1, 6133, 6133, 6133, -1, + 6134, 6134, 6134, -1, 6135, 6135, 6135, -1, + 6136, 6136, 6136, -1, 6137, 6137, 6137, -1, + 6138, 6138, 6138, -1, 6139, 6139, 6139, -1, + 6140, 6140, 6140, -1, 6141, 6141, 6141, -1, + 6142, 6142, 6142, -1, 6143, 6143, 6143, -1, + 6144, 6144, 6144, -1, 6145, 6145, 6145, -1, + 6146, 6146, 6146, -1, 6147, 6147, 6147, -1, + 6148, 6148, 6148, -1, 6149, 6149, 6149, -1, + 6150, 6150, 6150, -1, 6151, 6151, 6151, -1, + 6152, 6152, 6152, -1, 6153, 6153, 6153, -1, + 6154, 6154, 6154, -1, 6155, 6155, 6155, -1, + 6156, 6156, 6156, -1, 6157, 6157, 6157, -1, + 6158, 6158, 6158, -1, 6159, 6159, 6159, -1, + 6160, 6160, 6160, -1, 6161, 6161, 6161, -1, + 6162, 6162, 6162, -1, 6163, 6163, 6163, -1, + 6164, 6164, 6164, -1, 6165, 6165, 6165, -1, + 6166, 6166, 6166, -1, 6167, 6167, 6167, -1, + 6168, 6168, 6168, -1, 6169, 6169, 6169, -1, + 6170, 6170, 6170, -1, 6171, 6171, 6171, -1, + 6172, 6172, 6172, -1, 6173, 6173, 6173, -1, + 6174, 6174, 6174, -1, 6175, 6175, 6175, -1, + 6176, 6176, 6176, -1, 6177, 6177, 6177, -1, + 6178, 6178, 6178, -1, 6179, 6179, 6179, -1, + 6180, 6180, 6180, -1, 6181, 6181, 6181, -1, + 6182, 6182, 6182, -1, 6183, 6183, 6183, -1, + 6184, 6184, 6184, -1, 6185, 6185, 6185, -1, + 6186, 6186, 6186, -1, 6187, 6187, 6187, -1, + 6188, 6188, 6188, -1, 6189, 6189, 6189, -1, + 6190, 6190, 6190, -1, 6191, 6191, 6191, -1, + 6192, 6192, 6192, -1, 6193, 6193, 6193, -1, + 6194, 6194, 6194, -1, 6195, 6195, 6195, -1, + 6196, 6196, 6196, -1, 6197, 6197, 6197, -1, + 6198, 6198, 6198, -1, 6199, 6199, 6199, -1, + 6200, 6200, 6200, -1, 6201, 6201, 6201, -1, + 6202, 6202, 6202, -1, 6203, 6203, 6203, -1, + 6204, 6204, 6204, -1, 6205, 6205, 6205, -1, + 6206, 6206, 6206, -1, 6207, 6207, 6207, -1, + 6208, 6208, 6208, -1, 6209, 6209, 6209, -1, + 6210, 6210, 6210, -1, 6211, 6211, 6211, -1, + 6212, 6212, 6212, -1, 6213, 6213, 6213, -1, + 6214, 6214, 6214, -1, 6215, 6215, 6215, -1, + 6216, 6216, 6216, -1, 6217, 6217, 6217, -1, + 6218, 6218, 6218, -1, 6219, 6219, 6219, -1, + 6220, 6220, 6220, -1, 6221, 6221, 6221, -1, + 6222, 6222, 6222, -1, 6223, 6223, 6223, -1, + 6224, 6224, 6224, -1, 6225, 6225, 6225, -1, + 6226, 6226, 6226, -1, 6227, 6227, 6227, -1, + 6228, 6228, 6228, -1, 6229, 6229, 6229, -1, + 6230, 6230, 6230, -1, 6231, 6231, 6231, -1, + 6232, 6232, 6232, -1, 6233, 6233, 6233, -1, + 6234, 6234, 6234, -1, 6235, 6235, 6235, -1, + 6236, 6236, 6236, -1, 6237, 6237, 6237, -1, + 6238, 6238, 6238, -1, 6239, 6239, 6239, -1, + 6240, 6240, 6240, -1, 6241, 6241, 6241, -1, + 6242, 6242, 6242, -1, 6243, 6243, 6243, -1, + 6244, 6244, 6244, -1, 6245, 6245, 6245, -1, + 6246, 6246, 6246, -1, 6247, 6247, 6247, -1, + 6248, 6248, 6248, -1, 6249, 6249, 6249, -1, + 6250, 6250, 6250, -1, 6251, 6251, 6251, -1, + 6252, 6252, 6252, -1, 6253, 6253, 6253, -1, + 6254, 6254, 6254, -1, 6255, 6255, 6255, -1, + 6256, 6256, 6256, -1, 6257, 6257, 6257, -1, + 6258, 6258, 6258, -1, 6259, 6259, 6259, -1, + 6260, 6260, 6260, -1, 6261, 6261, 6261, -1, + 6262, 6262, 6262, -1, 6263, 6263, 6263, -1, + 6264, 6264, 6264, -1, 6265, 6265, 6265, -1, + 6266, 6266, 6266, -1, 6267, 6267, 6267, -1, + 6268, 6268, 6268, -1, 6269, 6269, 6269, -1, + 6270, 6270, 6270, -1, 6271, 6271, 6271, -1, + 6272, 6272, 6272, -1, 6273, 6273, 6273, -1, + 6274, 6274, 6274, -1, 6275, 6275, 6275, -1, + 6276, 6276, 6276, -1, 6277, 6277, 6277, -1, + 6278, 6278, 6278, -1, 6279, 6279, 6279, -1, + 6280, 6280, 6280, -1, 6281, 6281, 6281, -1, + 6282, 6282, 6282, -1, 6283, 6283, 6283, -1, + 6284, 6284, 6284, -1, 6285, 6285, 6285, -1, + 6286, 6286, 6286, -1, 6287, 6287, 6287, -1, + 6288, 6288, 6288, -1, 6289, 6289, 6289, -1, + 6290, 6290, 6290, -1, 6291, 6291, 6291, -1, + 6292, 6292, 6292, -1, 6293, 6293, 6293, -1, + 6294, 6294, 6294, -1, 6295, 6295, 6295, -1, + 6296, 6296, 6296, -1, 6297, 6297, 6297, -1, + 6298, 6298, 6298, -1, 6299, 6299, 6299, -1, + 6300, 6300, 6300, -1, 6301, 6301, 6301, -1, + 6302, 6302, 6302, -1, 6303, 6303, 6303, -1, + 6304, 6304, 6304, -1, 6305, 6305, 6305, -1, + 6306, 6306, 6306, -1, 6307, 6307, 6307, -1, + 6308, 6308, 6308, -1, 6309, 6309, 6309, -1, + 6310, 6310, 6310, -1, 6311, 6311, 6311, -1, + 6312, 6312, 6312, -1, 6313, 6313, 6313, -1, + 6314, 6314, 6314, -1, 6315, 6315, 6315, -1, + 6316, 6316, 6316, -1, 6317, 6317, 6317, -1, + 6318, 6318, 6318, -1, 6319, 6319, 6319, -1, + 6320, 6320, 6320, -1, 6321, 6321, 6321, -1, + 6322, 6322, 6322, -1, 6323, 6323, 6323, -1, + 6324, 6324, 6324, -1, 6325, 6325, 6325, -1, + 6326, 6326, 6326, -1, 6327, 6327, 6327, -1, + 6328, 6328, 6328, -1, 6329, 6329, 6329, -1, + 6330, 6330, 6330, -1, 6331, 6331, 6331, -1, + 6332, 6332, 6332, -1, 6333, 6333, 6333, -1, + 6334, 6334, 6334, -1, 6335, 6335, 6335, -1, + 6336, 6336, 6336, -1, 6337, 6337, 6337, -1, + 6338, 6338, 6338, -1, 6339, 6339, 6339, -1, + 6340, 6340, 6340, -1, 6341, 6341, 6341, -1, + 6342, 6342, 6342, -1, 6343, 6343, 6343, -1, + 6344, 6344, 6344, -1, 6345, 6345, 6345, -1, + 6346, 6346, 6346, -1, 6347, 6347, 6347, -1, + 6348, 6348, 6348, -1, 6349, 6349, 6349, -1, + 6350, 6350, 6350, -1, 6351, 6351, 6351, -1, + 6352, 6352, 6352, -1, 6353, 6353, 6353, -1, + 6354, 6354, 6354, -1, 6355, 6355, 6355, -1, + 6356, 6356, 6356, -1, 6357, 6357, 6357, -1, + 6358, 6358, 6358, -1, 6359, 6359, 6359, -1, + 6360, 6360, 6360, -1, 6361, 6361, 6361, -1, + 6362, 6362, 6362, -1, 6363, 6363, 6363, -1, + 6364, 6364, 6364, -1, 6365, 6365, 6365, -1, + 6366, 6366, 6366, -1, 6367, 6367, 6367, -1, + 6368, 6368, 6368, -1, 6369, 6369, 6369, -1, + 6370, 6370, 6370, -1, 6371, 6371, 6371, -1, + 6372, 6372, 6372, -1, 6373, 6373, 6373, -1, + 6374, 6374, 6374, -1, 6375, 6375, 6375, -1, + 6376, 6376, 6376, -1, 6377, 6377, 6377, -1, + 6378, 6378, 6378, -1, 6379, 6379, 6379, -1, + 6380, 6380, 6380, -1, 6381, 6381, 6381, -1, + 6382, 6382, 6382, -1, 6383, 6383, 6383, -1, + 6384, 6384, 6384, -1, 6385, 6385, 6385, -1, + 6386, 6386, 6386, -1, 6387, 6387, 6387, -1, + 6388, 6388, 6388, -1, 6389, 6389, 6389, -1, + 6390, 6390, 6390, -1, 6391, 6391, 6391, -1, + 6392, 6392, 6392, -1, 6393, 6393, 6393, -1, + 6394, 6394, 6394, -1, 6395, 6395, 6395, -1, + 6396, 6396, 6396, -1, 6397, 6397, 6397, -1, + 6398, 6398, 6398, -1, 6399, 6399, 6399, -1, + 6400, 6400, 6400, -1, 6401, 6401, 6401, -1, + 6402, 6402, 6402, -1, 6403, 6403, 6403, -1, + 6404, 6404, 6404, -1, 6405, 6405, 6405, -1, + 6406, 6406, 6406, -1, 6407, 6407, 6407, -1, + 6408, 6408, 6408, -1, 6409, 6409, 6409, -1, + 6410, 6410, 6410, -1, 6411, 6411, 6411, -1, + 6412, 6412, 6412, -1, 6413, 6413, 6413, -1, + 6414, 6414, 6414, -1, 6415, 6415, 6415, -1, + 6416, 6416, 6416, -1, 6417, 6417, 6417, -1, + 6418, 6418, 6418, -1, 6419, 6419, 6419, -1, + 6420, 6420, 6420, -1, 6421, 6421, 6421, -1, + 6422, 6422, 6422, -1, 6423, 6423, 6423, -1, + 6424, 6424, 6424, -1, 6425, 6425, 6425, -1, + 6426, 6426, 6426, -1, 6427, 6427, 6427, -1, + 6428, 6428, 6428, -1, 6429, 6429, 6429, -1, + 6430, 6430, 6430, -1, 6431, 6431, 6431, -1, + 6432, 6432, 6432, -1, 6433, 6433, 6433, -1, + 6434, 6434, 6434, -1, 6435, 6435, 6435, -1, + 6436, 6436, 6436, -1, 6437, 6437, 6437, -1, + 6438, 6438, 6438, -1, 6439, 6439, 6439, -1, + 6440, 6440, 6440, -1, 6441, 6441, 6441, -1, + 6442, 6442, 6442, -1, 6443, 6443, 6443, -1, + 6444, 6444, 6444, -1, 6445, 6445, 6445, -1, + 6446, 6446, 6446, -1, 6447, 6447, 6447, -1, + 6448, 6448, 6448, -1, 6449, 6449, 6449, -1, + 6450, 6450, 6450, -1, 6451, 6451, 6451, -1, + 6452, 6452, 6452, -1, 6453, 6453, 6453, -1, + 6454, 6454, 6454, -1, 6455, 6455, 6455, -1, + 6456, 6456, 6456, -1, 6457, 6457, 6457, -1, + 6458, 6458, 6458, -1, 6459, 6459, 6459, -1, + 6460, 6460, 6460, -1, 6461, 6461, 6461, -1, + 6462, 6462, 6462, -1, 6463, 6463, 6463, -1, + 6464, 6464, 6464, -1, 6465, 6465, 6465, -1, + 6466, 6466, 6466, -1, 6467, 6467, 6467, -1, + 6468, 6468, 6468, -1, 6469, 6469, 6469, -1, + 6470, 6470, 6470, -1, 6471, 6471, 6471, -1, + 6472, 6472, 6472, -1, 6473, 6473, 6473, -1, + 6474, 6474, 6474, -1, 6475, 6475, 6475, -1, + 6476, 6476, 6476, -1, 6477, 6477, 6477, -1, + 6478, 6478, 6478, -1, 6479, 6479, 6479, -1, + 6480, 6480, 6480, -1, 6481, 6481, 6481, -1, + 6482, 6482, 6482, -1, 6483, 6483, 6483, -1, + 6484, 6484, 6484, -1, 6485, 6485, 6485, -1, + 6486, 6486, 6486, -1, 6487, 6487, 6487, -1, + 6488, 6488, 6488, -1, 6489, 6489, 6489, -1, + 6490, 6490, 6490, -1, 6491, 6491, 6491, -1, + 6492, 6492, 6492, -1, 6493, 6493, 6493, -1, + 6494, 6494, 6494, -1, 6495, 6495, 6495, -1, + 6496, 6496, 6496, -1, 6497, 6497, 6497, -1, + 6498, 6498, 6498, -1, 6499, 6499, 6499, -1, + 6500, 6500, 6500, -1, 6501, 6501, 6501, -1, + 6502, 6502, 6502, -1, 6503, 6503, 6503, -1, + 6504, 6504, 6504, -1, 6505, 6505, 6505, -1, + 6506, 6506, 6506, -1, 6507, 6507, 6507, -1, + 6508, 6508, 6508, -1, 6509, 6509, 6509, -1, + 6510, 6510, 6510, -1, 6511, 6511, 6511, -1, + 6512, 6512, 6512, -1, 6513, 6513, 6513, -1, + 6514, 6514, 6514, -1, 6515, 6515, 6515, -1, + 6516, 6516, 6516, -1, 6517, 6517, 6517, -1, + 6518, 6518, 6518, -1, 6519, 6519, 6519, -1, + 6520, 6520, 6520, -1, 6521, 6521, 6521, -1, + 6522, 6522, 6522, -1, 6523, 6523, 6523, -1, + 6524, 6524, 6524, -1, 6525, 6525, 6525, -1, + 6526, 6526, 6526, -1, 6527, 6527, 6527, -1, + 6528, 6528, 6528, -1, 6529, 6529, 6529, -1, + 6530, 6530, 6530, -1, 6531, 6531, 6531, -1, + 6532, 6532, 6532, -1, 6533, 6533, 6533, -1, + 6534, 6534, 6534, -1, 6535, 6535, 6535, -1, + 6536, 6536, 6536, -1, 6537, 6537, 6537, -1, + 6538, 6538, 6538, -1, 6539, 6539, 6539, -1, + 6540, 6540, 6540, -1, 6541, 6541, 6541, -1, + 6542, 6542, 6542, -1, 6543, 6543, 6543, -1, + 6544, 6544, 6544, -1, 6545, 6545, 6545, -1, + 6546, 6546, 6546, -1, 6547, 6547, 6547, -1, + 6548, 6548, 6548, -1, 6549, 6549, 6549, -1, + 6550, 6550, 6550, -1, 6551, 6551, 6551, -1, + 6552, 6552, 6552, -1, 6553, 6553, 6553, -1, + 6554, 6554, 6554, -1, 6555, 6555, 6555, -1, + 6556, 6556, 6556, -1, 6557, 6557, 6557, -1, + 6558, 6558, 6558, -1, 6559, 6559, 6559, -1, + 6560, 6560, 6560, -1, 6561, 6561, 6561, -1, + 6562, 6562, 6562, -1, 6563, 6563, 6563, -1, + 6564, 6564, 6564, -1, 6565, 6565, 6565, -1, + 6566, 6566, 6566, -1, 6567, 6567, 6567, -1, + 6568, 6568, 6568, -1, 6569, 6569, 6569, -1, + 6570, 6570, 6570, -1, 6571, 6571, 6571, -1, + 6572, 6572, 6572, -1, 6573, 6573, 6573, -1, + 6574, 6574, 6574, -1, 6575, 6575, 6575, -1, + 6576, 6576, 6576, -1, 6577, 6577, 6577, -1, + 6578, 6578, 6578, -1, 6579, 6579, 6579, -1, + 6580, 6580, 6580, -1, 6581, 6581, 6581, -1, + 6582, 6582, 6582, -1, 6583, 6583, 6583, -1, + 6584, 6584, 6584, -1, 6585, 6585, 6585, -1, + 6586, 6586, 6586, -1, 6587, 6587, 6587, -1, + 6588, 6588, 6588, -1, 6589, 6589, 6589, -1, + 6590, 6590, 6590, -1, 6591, 6591, 6591, -1, + 6592, 6592, 6592, -1, 6593, 6593, 6593, -1, + 6594, 6594, 6594, -1, 6595, 6595, 6595, -1, + 6596, 6596, 6596, -1, 6597, 6597, 6597, -1, + 6598, 6598, 6598, -1, 6599, 6599, 6599, -1, + 6600, 6600, 6600, -1, 6601, 6601, 6601, -1, + 6602, 6602, 6602, -1, 6603, 6603, 6603, -1, + 6604, 6604, 6604, -1, 6605, 6605, 6605, -1, + 6606, 6606, 6606, -1, 6607, 6607, 6607, -1, + 6608, 6608, 6608, -1, 6609, 6609, 6609, -1, + 6610, 6610, 6610, -1, 6611, 6611, 6611, -1, + 6612, 6612, 6612, -1, 6613, 6613, 6613, -1, + 6614, 6614, 6614, -1, 6615, 6615, 6615, -1, + 6616, 6616, 6616, -1, 6617, 6617, 6617, -1, + 6618, 6618, 6618, -1, 6619, 6619, 6619, -1, + 6620, 6620, 6620, -1, 6621, 6621, 6621, -1, + 6622, 6622, 6622, -1, 6623, 6623, 6623, -1, + 6624, 6624, 6624, -1, 6625, 6625, 6625, -1, + 6626, 6626, 6626, -1, 6627, 6627, 6627, -1, + 6628, 6628, 6628, -1, 6629, 6629, 6629, -1, + 6630, 6630, 6630, -1, 6631, 6631, 6631, -1, + 6632, 6632, 6632, -1, 6633, 6633, 6633, -1, + 6634, 6634, 6634, -1, 6635, 6635, 6635, -1, + 6636, 6636, 6636, -1, 6637, 6637, 6637, -1, + 6638, 6638, 6638, -1, 6639, 6639, 6639, -1, + 6640, 6640, 6640, -1, 6641, 6641, 6641, -1, + 6642, 6642, 6642, -1, 6643, 6643, 6643, -1, + 6644, 6644, 6644, -1, 6645, 6645, 6645, -1, + 6646, 6646, 6646, -1, 6647, 6647, 6647, -1, + 6648, 6648, 6648, -1, 6649, 6649, 6649, -1, + 6650, 6650, 6650, -1, 6651, 6651, 6651, -1, + 6652, 6652, 6652, -1, 6653, 6653, 6653, -1, + 6654, 6654, 6654, -1, 6655, 6655, 6655, -1, + 6656, 6656, 6656, -1, 6657, 6657, 6657, -1, + 6658, 6658, 6658, -1, 6659, 6659, 6659, -1, + 6660, 6660, 6660, -1, 6661, 6661, 6661, -1, + 6662, 6662, 6662, -1, 6663, 6663, 6663, -1, + 6664, 6664, 6664, -1, 6665, 6665, 6665, -1, + 6666, 6666, 6666, -1, 6667, 6667, 6667, -1, + 6668, 6668, 6668, -1, 6669, 6669, 6669, -1, + 6670, 6670, 6670, -1, 6671, 6671, 6671, -1, + 6672, 6672, 6672, -1, 6673, 6673, 6673, -1, + 6674, 6674, 6674, -1, 6675, 6675, 6675, -1, + 6676, 6676, 6676, -1, 6677, 6677, 6677, -1, + 6678, 6678, 6678, -1, 6679, 6679, 6679, -1, + 6680, 6680, 6680, -1, 6681, 6681, 6681, -1, + 6682, 6682, 6682, -1, 6683, 6683, 6683, -1, + 6684, 6684, 6684, -1, 6685, 6685, 6685, -1, + 6686, 6686, 6686, -1, 6687, 6687, 6687, -1, + 6688, 6688, 6688, -1, 6689, 6689, 6689, -1, + 6690, 6690, 6690, -1, 6691, 6691, 6691, -1, + 6692, 6692, 6692, -1, 6693, 6693, 6693, -1, + 6694, 6694, 6694, -1, 6695, 6695, 6695, -1, + 6696, 6696, 6696, -1, 6697, 6697, 6697, -1, + 6698, 6698, 6698, -1, 6699, 6699, 6699, -1, + 6700, 6700, 6700, -1, 6701, 6701, 6701, -1, + 6702, 6702, 6702, -1, 6703, 6703, 6703, -1, + 6704, 6704, 6704, -1, 6705, 6705, 6705, -1, + 6706, 6706, 6706, -1, 6707, 6707, 6707, -1, + 6708, 6708, 6708, -1, 6709, 6709, 6709, -1, + 6710, 6710, 6710, -1, 6711, 6711, 6711, -1, + 6712, 6712, 6712, -1, 6713, 6713, 6713, -1, + 6714, 6714, 6714, -1, 6715, 6715, 6715, -1, + 6716, 6716, 6716, -1, 6717, 6717, 6717, -1, + 6718, 6718, 6718, -1, 6719, 6719, 6719, -1, + 6720, 6720, 6720, -1, 6721, 6721, 6721, -1, + 6722, 6722, 6722, -1, 6723, 6723, 6723, -1, + 6724, 6724, 6724, -1, 6725, 6725, 6725, -1, + 6726, 6726, 6726, -1, 6727, 6727, 6727, -1, + 6728, 6728, 6728, -1, 6729, 6729, 6729, -1, + 6730, 6730, 6730, -1, 6731, 6731, 6731, -1, + 6732, 6732, 6732, -1, 6733, 6733, 6733, -1, + 6734, 6734, 6734, -1, 6735, 6735, 6735, -1, + 6736, 6736, 6736, -1, 6737, 6737, 6737, -1, + 6738, 6738, 6738, -1, 6739, 6739, 6739, -1, + 6740, 6740, 6740, -1, 6741, 6741, 6741, -1, + 6742, 6742, 6742, -1, 6743, 6743, 6743, -1, + 6744, 6744, 6744, -1, 6745, 6745, 6745, -1, + 6746, 6746, 6746, -1, 6747, 6747, 6747, -1, + 6748, 6748, 6748, -1, 6749, 6749, 6749, -1, + 6750, 6750, 6750, -1, 6751, 6751, 6751, -1, + 6752, 6752, 6752, -1, 6753, 6753, 6753, -1, + 6754, 6754, 6754, -1, 6755, 6755, 6755, -1, + 6756, 6756, 6756, -1, 6757, 6757, 6757, -1, + 6758, 6758, 6758, -1, 6759, 6759, 6759, -1, + 6760, 6760, 6760, -1, 6761, 6761, 6761, -1, + 6762, 6762, 6762, -1, 6763, 6763, 6763, -1, + 6764, 6764, 6764, -1, 6765, 6765, 6765, -1, + 6766, 6766, 6766, -1, 6767, 6767, 6767, -1, + 6768, 6768, 6768, -1, 6769, 6769, 6769, -1, + 6770, 6770, 6770, -1, 6771, 6771, 6771, -1, + 6772, 6772, 6772, -1, 6773, 6773, 6773, -1, + 6774, 6774, 6774, -1, 6775, 6775, 6775, -1, + 6776, 6776, 6776, -1, 6777, 6777, 6777, -1, + 6778, 6778, 6778, -1, 6779, 6779, 6779, -1, + 6780, 6780, 6780, -1, 6781, 6781, 6781, -1, + 6782, 6782, 6782, -1, 6783, 6783, 6783, -1, + 6784, 6784, 6784, -1, 6785, 6785, 6785, -1, + 6786, 6786, 6786, -1, 6787, 6787, 6787, -1, + 6788, 6788, 6788, -1, 6789, 6789, 6789, -1, + 6790, 6790, 6790, -1, 6791, 6791, 6791, -1, + 6792, 6792, 6792, -1, 6793, 6793, 6793, -1, + 6794, 6794, 6794, -1, 6795, 6795, 6795, -1, + 6796, 6796, 6796, -1, 6797, 6797, 6797, -1, + 6798, 6798, 6798, -1, 6799, 6799, 6799, -1, + 6800, 6800, 6800, -1, 6801, 6801, 6801, -1, + 6802, 6802, 6802, -1, 6803, 6803, 6803, -1, + 6804, 6804, 6804, -1, 6805, 6805, 6805, -1, + 6806, 6806, 6806, -1, 6807, 6807, 6807, -1, + 6808, 6808, 6808, -1, 6809, 6809, 6809, -1, + 6810, 6810, 6810, -1, 6811, 6811, 6811, -1, + 6812, 6812, 6812, -1, 6813, 6813, 6813, -1, + 6814, 6814, 6814, -1, 6815, 6815, 6815, -1, + 6816, 6816, 6816, -1, 6817, 6817, 6817, -1, + 6818, 6818, 6818, -1, 6819, 6819, 6819, -1, + 6820, 6820, 6820, -1, 6821, 6821, 6821, -1, + 6822, 6822, 6822, -1, 6823, 6823, 6823, -1, + 6824, 6824, 6824, -1, 6825, 6825, 6825, -1, + 6826, 6826, 6826, -1, 6827, 6827, 6827, -1, + 6828, 6828, 6828, -1, 6829, 6829, 6829, -1, + 6830, 6830, 6830, -1, 6831, 6831, 6831, -1, + 6832, 6832, 6832, -1, 6833, 6833, 6833, -1, + 6834, 6834, 6834, -1, 6835, 6835, 6835, -1, + 6836, 6836, 6836, -1, 6837, 6837, 6837, -1, + 6838, 6838, 6838, -1, 6839, 6839, 6839, -1, + 6840, 6840, 6840, -1, 6841, 6841, 6841, -1, + 6842, 6842, 6842, -1, 6843, 6843, 6843, -1, + 6844, 6844, 6844, -1, 6845, 6845, 6845, -1, + 6846, 6846, 6846, -1, 6847, 6847, 6847, -1, + 6848, 6848, 6848, -1, 6849, 6849, 6849, -1, + 6850, 6850, 6850, -1, 6851, 6851, 6851, -1, + 6852, 6852, 6852, -1, 6853, 6853, 6853, -1, + 6854, 6854, 6854, -1, 6855, 6855, 6855, -1, + 6856, 6856, 6856, -1, 6857, 6857, 6857, -1, + 6858, 6858, 6858, -1, 6859, 6859, 6859, -1, + 6860, 6860, 6860, -1, 6861, 6861, 6861, -1, + 6862, 6862, 6862, -1, 6863, 6863, 6863, -1, + 6864, 6864, 6864, -1, 6865, 6865, 6865, -1, + 6866, 6866, 6866, -1, 6867, 6867, 6867, -1, + 6868, 6868, 6868, -1, 6869, 6869, 6869, -1, + 6870, 6870, 6870, -1, 6871, 6871, 6871, -1, + 6872, 6872, 6872, -1, 6873, 6873, 6873, -1, + 6874, 6874, 6874, -1, 6875, 6875, 6875, -1, + 6876, 6876, 6876, -1, 6877, 6877, 6877, -1, + 6878, 6878, 6878, -1, 6879, 6879, 6879, -1, + 6880, 6880, 6880, -1, 6881, 6881, 6881, -1, + 6882, 6882, 6882, -1, 6883, 6883, 6883, -1, + 6884, 6884, 6884, -1, 6885, 6885, 6885, -1, + 6886, 6886, 6886, -1, 6887, 6887, 6887, -1, + 6888, 6888, 6888, -1, 6889, 6889, 6889, -1, + 6890, 6890, 6890, -1, 6891, 6891, 6891, -1, + 6892, 6892, 6892, -1, 6893, 6893, 6893, -1, + 6894, 6894, 6894, -1, 6895, 6895, 6895, -1, + 6896, 6896, 6896, -1, 6897, 6897, 6897, -1, + 6898, 6898, 6898, -1, 6899, 6899, 6899, -1, + 6900, 6900, 6900, -1, 6901, 6901, 6901, -1, + 6902, 6902, 6902, -1, 6903, 6903, 6903, -1, + 6904, 6904, 6904, -1, 6905, 6905, 6905, -1, + 6906, 6906, 6906, -1, 6907, 6907, 6907, -1, + 6908, 6908, 6908, -1, 6909, 6909, 6909, -1, + 6910, 6910, 6910, -1, 6911, 6911, 6911, -1, + 6912, 6912, 6912, -1, 6913, 6913, 6913, -1, + 6914, 6914, 6914, -1, 6915, 6915, 6915, -1, + 6916, 6916, 6916, -1, 6917, 6917, 6917, -1, + 6918, 6918, 6918, -1, 6919, 6919, 6919, -1, + 6920, 6920, 6920, -1, 6921, 6921, 6921, -1, + 6922, 6922, 6922, -1, 6923, 6923, 6923, -1, + 6924, 6924, 6924, -1, 6925, 6925, 6925, -1, + 6926, 6926, 6926, -1, 6927, 6927, 6927, -1, + 6928, 6928, 6928, -1, 6929, 6929, 6929, -1, + 6930, 6930, 6930, -1, 6931, 6931, 6931, -1, + 6932, 6932, 6932, -1, 6933, 6933, 6933, -1, + 6934, 6934, 6934, -1, 6935, 6935, 6935, -1, + 6936, 6936, 6936, -1, 6937, 6937, 6937, -1, + 6938, 6938, 6938, -1, 6939, 6939, 6939, -1, + 6940, 6940, 6940, -1, 6941, 6941, 6941, -1, + 6942, 6942, 6942, -1, 6943, 6943, 6943, -1, + 6944, 6944, 6944, -1, 6945, 6945, 6945, -1, + 6946, 6946, 6946, -1, 6947, 6947, 6947, -1, + 6948, 6948, 6948, -1, 6949, 6949, 6949, -1, + 6950, 6950, 6950, -1, 6951, 6951, 6951, -1, + 6952, 6952, 6952, -1, 6953, 6953, 6953, -1, + 6954, 6954, 6954, -1, 6955, 6955, 6955, -1, + 6956, 6956, 6956, -1, 6957, 6957, 6957, -1, + 6958, 6958, 6958, -1, 6959, 6959, 6959, -1, + 6960, 6960, 6960, -1, 6961, 6961, 6961, -1, + 6962, 6962, 6962, -1, 6963, 6963, 6963, -1, + 6964, 6964, 6964, -1, 6965, 6965, 6965, -1, + 6966, 6966, 6966, -1, 6967, 6967, 6967, -1, + 6968, 6968, 6968, -1, 6969, 6969, 6969, -1, + 6970, 6970, 6970, -1, 6971, 6971, 6971, -1, + 6972, 6972, 6972, -1, 6973, 6973, 6973, -1, + 6974, 6974, 6974, -1, 6975, 6975, 6975, -1, + 6976, 6976, 6976, -1, 6977, 6977, 6977, -1, + 6978, 6978, 6978, -1, 6979, 6979, 6979, -1, + 6980, 6980, 6980, -1, 6981, 6981, 6981, -1, + 6982, 6982, 6982, -1, 6983, 6983, 6983, -1, + 6984, 6984, 6984, -1, 6985, 6985, 6985, -1, + 6986, 6986, 6986, -1, 6987, 6987, 6987, -1, + 6988, 6988, 6988, -1, 6989, 6989, 6989, -1, + 6990, 6990, 6990, -1, 6991, 6991, 6991, -1, + 6992, 6992, 6992, -1, 6993, 6993, 6993, -1, + 6994, 6994, 6994, -1, 6995, 6995, 6995, -1, + 6996, 6996, 6996, -1, 6997, 6997, 6997, -1, + 6998, 6998, 6998, -1, 6999, 6999, 6999, -1, + 7000, 7000, 7000, -1, 7001, 7001, 7001, -1, + 7002, 7002, 7002, -1, 7003, 7003, 7003, -1, + 7004, 7004, 7004, -1, 7005, 7005, 7005, -1, + 7006, 7006, 7006, -1, 7007, 7007, 7007, -1, + 7008, 7008, 7008, -1, 7009, 7009, 7009, -1, + 7010, 7010, 7010, -1, 7011, 7011, 7011, -1, + 7012, 7012, 7012, -1, 7013, 7013, 7013, -1, + 7014, 7014, 7014, -1, 7015, 7015, 7015, -1, + 7016, 7016, 7016, -1, 7017, 7017, 7017, -1, + 7018, 7018, 7018, -1, 7019, 7019, 7019, -1, + 7020, 7020, 7020, -1, 7021, 7021, 7021, -1, + 7022, 7022, 7022, -1, 7023, 7023, 7023, -1, + 7024, 7024, 7024, -1, 7025, 7025, 7025, -1, + 7026, 7026, 7026, -1, 7027, 7027, 7027, -1, + 7028, 7028, 7028, -1, 7029, 7029, 7029, -1, + 7030, 7030, 7030, -1, 7031, 7031, 7031, -1, + 7032, 7032, 7032, -1, 7033, 7033, 7033, -1, + 7034, 7034, 7034, -1, 7035, 7035, 7035, -1, + 7036, 7036, 7036, -1, 7037, 7037, 7037, -1, + 7038, 7038, 7038, -1, 7039, 7039, 7039, -1, + 7040, 7040, 7040, -1, 7041, 7041, 7041, -1, + 7042, 7042, 7042, -1, 7043, 7043, 7043, -1, + 7044, 7044, 7044, -1, 7045, 7045, 7045, -1, + 7046, 7046, 7046, -1, 7047, 7047, 7047, -1, + 7048, 7048, 7048, -1, 7049, 7049, 7049, -1, + 7050, 7050, 7050, -1, 7051, 7051, 7051, -1, + 7052, 7052, 7052, -1, 7053, 7053, 7053, -1, + 7054, 7054, 7054, -1, 7055, 7055, 7055, -1, + 7056, 7056, 7056, -1, 7057, 7057, 7057, -1, + 7058, 7058, 7058, -1, 7059, 7059, 7059, -1, + 7060, 7060, 7060, -1, 7061, 7061, 7061, -1, + 7062, 7062, 7062, -1, 7063, 7063, 7063, -1, + 7064, 7064, 7064, -1, 7065, 7065, 7065, -1, + 7066, 7066, 7066, -1, 7067, 7067, 7067, -1, + 7068, 7068, 7068, -1, 7069, 7069, 7069, -1, + 7070, 7070, 7070, -1, 7071, 7071, 7071, -1, + 7072, 7072, 7072, -1, 7073, 7073, 7073, -1, + 7074, 7074, 7074, -1, 7075, 7075, 7075, -1, + 7076, 7076, 7076, -1, 7077, 7077, 7077, -1, + 7078, 7078, 7078, -1, 7079, 7079, 7079, -1, + 7080, 7080, 7080, -1, 7081, 7081, 7081, -1, + 7082, 7082, 7082, -1, 7083, 7083, 7083, -1, + 7084, 7084, 7084, -1, 7085, 7085, 7085, -1, + 7086, 7086, 7086, -1, 7087, 7087, 7087, -1, + 7088, 7088, 7088, -1, 7089, 7089, 7089, -1, + 7090, 7090, 7090, -1, 7091, 7091, 7091, -1, + 7092, 7092, 7092, -1, 7093, 7093, 7093, -1, + 7094, 7094, 7094, -1, 7095, 7095, 7095, -1, + 7096, 7096, 7096, -1, 7097, 7097, 7097, -1, + 7098, 7098, 7098, -1, 7099, 7099, 7099, -1, + 7100, 7100, 7100, -1, 7101, 7101, 7101, -1, + 7102, 7102, 7102, -1, 7103, 7103, 7103, -1, + 7104, 7104, 7104, -1, 7105, 7105, 7105, -1, + 7106, 7106, 7106, -1, 7107, 7107, 7107, -1, + 7108, 7108, 7108, -1, 7109, 7109, 7109, -1, + 7110, 7110, 7110, -1, 7111, 7111, 7111, -1, + 7112, 7112, 7112, -1, 7113, 7113, 7113, -1, + 7114, 7114, 7114, -1, 7115, 7115, 7115, -1, + 7116, 7116, 7116, -1, 7117, 7117, 7117, -1, + 7118, 7118, 7118, -1, 7119, 7119, 7119, -1, + 7120, 7120, 7120, -1, 7121, 7121, 7121, -1, + 7122, 7122, 7122, -1, 7123, 7123, 7123, -1, + 7124, 7124, 7124, -1, 7125, 7125, 7125, -1, + 7126, 7126, 7126, -1, 7127, 7127, 7127, -1, + 7128, 7128, 7128, -1, 7129, 7129, 7129, -1, + 7130, 7130, 7130, -1, 7131, 7131, 7131, -1, + 7132, 7132, 7132, -1, 7133, 7133, 7133, -1, + 7134, 7134, 7134, -1, 7135, 7135, 7135, -1, + 7136, 7136, 7136, -1, 7137, 7137, 7137, -1, + 7138, 7138, 7138, -1, 7139, 7139, 7139, -1, + 7140, 7140, 7140, -1, 7141, 7141, 7141, -1, + 7142, 7142, 7142, -1, 7143, 7143, 7143, -1, + 7144, 7144, 7144, -1, 7145, 7145, 7145, -1, + 7146, 7146, 7146, -1, 7147, 7147, 7147, -1, + 7148, 7148, 7148, -1, 7149, 7149, 7149, -1, + 7150, 7150, 7150, -1, 7151, 7151, 7151, -1, + 7152, 7152, 7152, -1, 7153, 7153, 7153, -1, + 7154, 7154, 7154, -1, 7155, 7155, 7155, -1, + 7156, 7156, 7156, -1, 7157, 7157, 7157, -1, + 7158, 7158, 7158, -1, 7159, 7159, 7159, -1, + 7160, 7160, 7160, -1, 7161, 7161, 7161, -1, + 7162, 7162, 7162, -1, 7163, 7163, 7163, -1, + 7164, 7164, 7164, -1, 7165, 7165, 7165, -1, + 7166, 7166, 7166, -1, 7167, 7167, 7167, -1, + 7168, 7168, 7168, -1, 7169, 7169, 7169, -1, + 7170, 7170, 7170, -1, 7171, 7171, 7171, -1, + 7172, 7172, 7172, -1, 7173, 7173, 7173, -1, + 7174, 7174, 7174, -1, 7175, 7175, 7175, -1, + 7176, 7176, 7176, -1, 7177, 7177, 7177, -1, + 7178, 7178, 7178, -1, 7179, 7179, 7179, -1, + 7180, 7180, 7180, -1, 7181, 7181, 7181, -1, + 7182, 7182, 7182, -1, 7183, 7183, 7183, -1, + 7184, 7184, 7184, -1, 7185, 7185, 7185, -1, + 7186, 7186, 7186, -1, 7187, 7187, 7187, -1, + 7188, 7188, 7188, -1, 7189, 7189, 7189, -1, + 7190, 7190, 7190, -1, 7191, 7191, 7191, -1, + 7192, 7192, 7192, -1, 7193, 7193, 7193, -1, + 7194, 7194, 7194, -1, 7195, 7195, 7195, -1, + 7196, 7196, 7196, -1, 7197, 7197, 7197, -1, + 7198, 7198, 7198, -1, 7199, 7199, 7199, -1, + 7200, 7200, 7200, -1, 7201, 7201, 7201, -1, + 7202, 7202, 7202, -1, 7203, 7203, 7203, -1, + 7204, 7204, 7204, -1, 7205, 7205, 7205, -1, + 7206, 7206, 7206, -1, 7207, 7207, 7207, -1, + 7208, 7208, 7208, -1, 7209, 7209, 7209, -1, + 7210, 7210, 7210, -1, 7211, 7211, 7211, -1, + 7212, 7212, 7212, -1, 7213, 7213, 7213, -1, + 7214, 7214, 7214, -1, 7215, 7215, 7215, -1, + 7216, 7216, 7216, -1, 7217, 7217, 7217, -1, + 7218, 7218, 7218, -1, 7219, 7219, 7219, -1, + 7220, 7220, 7220, -1, 7221, 7221, 7221, -1, + 7222, 7222, 7222, -1, 7223, 7223, 7223, -1, + 7224, 7224, 7224, -1, 7225, 7225, 7225, -1, + 7226, 7226, 7226, -1, 7227, 7227, 7227, -1, + 7228, 7228, 7228, -1, 7229, 7229, 7229, -1, + 7230, 7230, 7230, -1, 7231, 7231, 7231, -1, + 7232, 7232, 7232, -1, 7233, 7233, 7233, -1, + 7234, 7234, 7234, -1, 7235, 7235, 7235, -1, + 7236, 7236, 7236, -1, 7237, 7237, 7237, -1, + 7238, 7238, 7238, -1, 7239, 7239, 7239, -1, + 7240, 7240, 7240, -1, 7241, 7241, 7241, -1, + 7242, 7242, 7242, -1, 7243, 7243, 7243, -1, + 7244, 7244, 7244, -1, 7245, 7245, 7245, -1, + 7246, 7246, 7246, -1, 7247, 7247, 7247, -1, + 7248, 7248, 7248, -1, 7249, 7249, 7249, -1, + 7250, 7250, 7250, -1, 7251, 7251, 7251, -1, + 7252, 7252, 7252, -1, 7253, 7253, 7253, -1, + 7254, 7254, 7254, -1, 7255, 7255, 7255, -1, + 7256, 7256, 7256, -1, 7257, 7257, 7257, -1, + 7258, 7258, 7258, -1, 7259, 7259, 7259, -1, + 7260, 7260, 7260, -1, 7261, 7261, 7261, -1, + 7262, 7262, 7262, -1, 7263, 7263, 7263, -1, + 7264, 7264, 7264, -1, 7265, 7265, 7265, -1, + 7266, 7266, 7266, -1, 7267, 7267, 7267, -1, + 7268, 7268, 7268, -1, 7269, 7269, 7269, -1, + 7270, 7270, 7270, -1, 7271, 7271, 7271, -1, + 7272, 7272, 7272, -1, 7273, 7273, 7273, -1, + 7274, 7274, 7274, -1, 7275, 7275, 7275, -1, + 7276, 7276, 7276, -1, 7277, 7277, 7277, -1, + 7278, 7278, 7278, -1, 7279, 7279, 7279, -1, + 7280, 7280, 7280, -1, 7281, 7281, 7281, -1, + 7282, 7282, 7282, -1, 7283, 7283, 7283, -1, + 7284, 7284, 7284, -1, 7285, 7285, 7285, -1, + 7286, 7286, 7286, -1, 7287, 7287, 7287, -1, + 7288, 7288, 7288, -1, 7289, 7289, 7289, -1, + 7290, 7290, 7290, -1, 7291, 7291, 7291, -1, + 7292, 7292, 7292, -1, 7293, 7293, 7293, -1, + 7294, 7294, 7294, -1, 7295, 7295, 7295, -1, + 7296, 7296, 7296, -1, 7297, 7297, 7297, -1, + 7298, 7298, 7298, -1, 7299, 7299, 7299, -1, + 7300, 7300, 7300, -1, 7301, 7301, 7301, -1, + 7302, 7302, 7302, -1, 7303, 7303, 7303, -1, + 7304, 7304, 7304, -1, 7305, 7305, 7305, -1, + 7306, 7306, 7306, -1, 7307, 7307, 7307, -1, + 7308, 7308, 7308, -1, 7309, 7309, 7309, -1, + 7310, 7310, 7310, -1, 7311, 7311, 7311, -1, + 7312, 7312, 7312, -1, 7313, 7313, 7313, -1, + 7314, 7314, 7314, -1, 7315, 7315, 7315, -1, + 7316, 7316, 7316, -1, 7317, 7317, 7317, -1, + 7318, 7318, 7318, -1, 7319, 7319, 7319, -1, + 7320, 7320, 7320, -1, 7321, 7321, 7321, -1, + 7322, 7322, 7322, -1, 7323, 7323, 7323, -1, + 7324, 7324, 7324, -1, 7325, 7325, 7325, -1, + 7326, 7326, 7326, -1, 7327, 7327, 7327, -1, + 7328, 7328, 7328, -1, 7329, 7329, 7329, -1, + 7330, 7330, 7330, -1, 7331, 7331, 7331, -1, + 7332, 7332, 7332, -1, 7333, 7333, 7333, -1, + 7334, 7334, 7334, -1, 7335, 7335, 7335, -1, + 7336, 7336, 7336, -1, 7337, 7337, 7337, -1, + 7338, 7338, 7338, -1, 7339, 7339, 7339, -1, + 7340, 7340, 7340, -1, 7341, 7341, 7341, -1, + 7342, 7342, 7342, -1, 7343, 7343, 7343, -1, + 7344, 7344, 7344, -1, 7345, 7345, 7345, -1, + 7346, 7346, 7346, -1, 7347, 7347, 7347, -1, + 7348, 7348, 7348, -1, 7349, 7349, 7349, -1, + 7350, 7350, 7350, -1, 7351, 7351, 7351, -1, + 7352, 7352, 7352, -1, 7353, 7353, 7353, -1, + 7354, 7354, 7354, -1, 7355, 7355, 7355, -1, + 7356, 7356, 7356, -1, 7357, 7357, 7357, -1, + 7358, 7358, 7358, -1, 7359, 7359, 7359, -1, + 7360, 7360, 7360, -1, 7361, 7361, 7361, -1, + 7362, 7362, 7362, -1, 7363, 7363, 7363, -1, + 7364, 7364, 7364, -1, 7365, 7365, 7365, -1, + 7366, 7366, 7366, -1, 7367, 7367, 7367, -1, + 7368, 7368, 7368, -1, 7369, 7369, 7369, -1, + 7370, 7370, 7370, -1, 7371, 7371, 7371, -1, + 7372, 7372, 7372, -1, 7373, 7373, 7373, -1, + 7374, 7374, 7374, -1, 7375, 7375, 7375, -1, + 7376, 7376, 7376, -1, 7377, 7377, 7377, -1, + 7378, 7378, 7378, -1, 7379, 7379, 7379, -1, + 7380, 7380, 7380, -1, 7381, 7381, 7381, -1, + 7382, 7382, 7382, -1, 7383, 7383, 7383, -1, + 7384, 7384, 7384, -1, 7385, 7385, 7385, -1, + 7386, 7386, 7386, -1, 7387, 7387, 7387, -1, + 7388, 7388, 7388, -1, 7389, 7389, 7389, -1, + 7390, 7390, 7390, -1, 7391, 7391, 7391, -1, + 7392, 7392, 7392, -1, 7393, 7393, 7393, -1, + 7394, 7394, 7394, -1, 7395, 7395, 7395, -1, + 7396, 7396, 7396, -1, 7397, 7397, 7397, -1, + 7398, 7398, 7398, -1, 7399, 7399, 7399, -1, + 7400, 7400, 7400, -1, 7401, 7401, 7401, -1, + 7402, 7402, 7402, -1, 7403, 7403, 7403, -1, + 7404, 7404, 7404, -1, 7405, 7405, 7405, -1, + 7406, 7406, 7406, -1, 7407, 7407, 7407, -1, + 7408, 7408, 7408, -1, 7409, 7409, 7409, -1, + 7410, 7410, 7410, -1, 7411, 7411, 7411, -1, + 7412, 7412, 7412, -1, 7413, 7413, 7413, -1, + 7414, 7414, 7414, -1, 7415, 7415, 7415, -1, + 7416, 7416, 7416, -1, 7417, 7417, 7417, -1, + 7418, 7418, 7418, -1, 7419, 7419, 7419, -1, + 7420, 7420, 7420, -1, 7421, 7421, 7421, -1, + 7422, 7422, 7422, -1, 7423, 7423, 7423, -1, + 7424, 7424, 7424, -1, 7425, 7425, 7425, -1, + 7426, 7426, 7426, -1, 7427, 7427, 7427, -1, + 7428, 7428, 7428, -1, 7429, 7429, 7429, -1, + 7430, 7430, 7430, -1, 7431, 7431, 7431, -1, + 7432, 7432, 7432, -1, 7433, 7433, 7433, -1, + 7434, 7434, 7434, -1, 7435, 7435, 7435, -1, + 7436, 7436, 7436, -1, 7437, 7437, 7437, -1, + 7438, 7438, 7438, -1, 7439, 7439, 7439, -1, + 7440, 7440, 7440, -1, 7441, 7441, 7441, -1, + 7442, 7442, 7442, -1, 7443, 7443, 7443, -1, + 7444, 7444, 7444, -1, 7445, 7445, 7445, -1, + 7446, 7446, 7446, -1, 7447, 7447, 7447, -1, + 7448, 7448, 7448, -1, 7449, 7449, 7449, -1, + 7450, 7450, 7450, -1, 7451, 7451, 7451, -1, + 7452, 7452, 7452, -1, 7453, 7453, 7453, -1, + 7454, 7454, 7454, -1, 7455, 7455, 7455, -1, + 7456, 7456, 7456, -1, 7457, 7457, 7457, -1, + 7458, 7458, 7458, -1, 7459, 7459, 7459, -1, + 7460, 7460, 7460, -1, 7461, 7461, 7461, -1, + 7462, 7462, 7462, -1, 7463, 7463, 7463, -1, + 7464, 7464, 7464, -1, 7465, 7465, 7465, -1, + 7466, 7466, 7466, -1, 7467, 7467, 7467, -1, + 7468, 7468, 7468, -1, 7469, 7469, 7469, -1, + 7470, 7470, 7470, -1, 7471, 7471, 7471, -1, + 7472, 7472, 7472, -1, 7473, 7473, 7473, -1, + 7474, 7474, 7474, -1, 7475, 7475, 7475, -1, + 7476, 7476, 7476, -1, 7477, 7477, 7477, -1, + 7478, 7478, 7478, -1, 7479, 7479, 7479, -1, + 7480, 7480, 7480, -1, 7481, 7481, 7481, -1, + 7482, 7482, 7482, -1, 7483, 7483, 7483, -1, + 7484, 7484, 7484, -1, 7485, 7485, 7485, -1, + 7486, 7486, 7486, -1, 7487, 7487, 7487, -1, + 7488, 7488, 7488, -1, 7489, 7489, 7489, -1, + 7490, 7490, 7490, -1, 7491, 7491, 7491, -1, + 7492, 7492, 7492, -1, 7493, 7493, 7493, -1, + 7494, 7494, 7494, -1, 7495, 7495, 7495, -1, + 7496, 7496, 7496, -1, 7497, 7497, 7497, -1, + 7498, 7498, 7498, -1, 7499, 7499, 7499, -1, + 7500, 7500, 7500, -1, 7501, 7501, 7501, -1, + 7502, 7502, 7502, -1, 7503, 7503, 7503, -1, + 7504, 7504, 7504, -1, 7505, 7505, 7505, -1, + 7506, 7506, 7506, -1, 7507, 7507, 7507, -1, + 7508, 7508, 7508, -1, 7509, 7509, 7509, -1, + 7510, 7510, 7510, -1, 7511, 7511, 7511, -1, + 7512, 7512, 7512, -1, 7513, 7513, 7513, -1, + 7514, 7514, 7514, -1, 7515, 7515, 7515, -1, + 7516, 7516, 7516, -1, 7517, 7517, 7517, -1, + 7518, 7518, 7518, -1, 7519, 7519, 7519, -1, + 7520, 7520, 7520, -1, 7521, 7521, 7521, -1, + 7522, 7522, 7522, -1, 7523, 7523, 7523, -1, + 7524, 7524, 7524, -1, 7525, 7525, 7525, -1, + 7526, 7526, 7526, -1, 7527, 7527, 7527, -1, + 7528, 7528, 7528, -1, 7529, 7529, 7529, -1, + 7530, 7530, 7530, -1, 7531, 7531, 7531, -1, + 7532, 7532, 7532, -1, 7533, 7533, 7533, -1, + 7534, 7534, 7534, -1, 7535, 7535, 7535, -1, + 7536, 7536, 7536, -1, 7537, 7537, 7537, -1, + 7538, 7538, 7538, -1, 7539, 7539, 7539, -1, + 7540, 7540, 7540, -1, 7541, 7541, 7541, -1, + 7542, 7542, 7542, -1, 7543, 7543, 7543, -1, + 7544, 7544, 7544, -1, 7545, 7545, 7545, -1, + 7546, 7546, 7546, -1, 7547, 7547, 7547, -1, + 7548, 7548, 7548, -1, 7549, 7549, 7549, -1, + 7550, 7550, 7550, -1, 7551, 7551, 7551, -1, + 7552, 7552, 7552, -1, 7553, 7553, 7553, -1, + 7554, 7554, 7554, -1, 7555, 7555, 7555, -1, + 7556, 7556, 7556, -1, 7557, 7557, 7557, -1, + 7558, 7558, 7558, -1, 7559, 7559, 7559, -1, + 7560, 7560, 7560, -1, 7561, 7561, 7561, -1, + 7562, 7562, 7562, -1, 7563, 7563, 7563, -1, + 7564, 7564, 7564, -1, 7565, 7565, 7565, -1, + 7566, 7566, 7566, -1, 7567, 7567, 7567, -1, + 7568, 7568, 7568, -1, 7569, 7569, 7569, -1, + 7570, 7570, 7570, -1, 7571, 7571, 7571, -1, + 7572, 7572, 7572, -1, 7573, 7573, 7573, -1, + 7574, 7574, 7574, -1, 7575, 7575, 7575, -1, + 7576, 7576, 7576, -1, 7577, 7577, 7577, -1, + 7578, 7578, 7578, -1, 7579, 7579, 7579, -1, + 7580, 7580, 7580, -1, 7581, 7581, 7581, -1, + 7582, 7582, 7582, -1, 7583, 7583, 7583, -1, + 7584, 7584, 7584, -1, 7585, 7585, 7585, -1, + 7586, 7586, 7586, -1, 7587, 7587, 7587, -1, + 7588, 7588, 7588, -1, 7589, 7589, 7589, -1, + 7590, 7590, 7590, -1, 7591, 7591, 7591, -1, + 7592, 7592, 7592, -1, 7593, 7593, 7593, -1, + 7594, 7594, 7594, -1, 7595, 7595, 7595, -1, + 7596, 7596, 7596, -1, 7597, 7597, 7597, -1, + 7598, 7598, 7598, -1, 7599, 7599, 7599, -1, + 7600, 7600, 7600, -1, 7601, 7601, 7601, -1, + 7602, 7602, 7602, -1, 7603, 7603, 7603, -1, + 7604, 7604, 7604, -1, 7605, 7605, 7605, -1, + 7606, 7606, 7606, -1, 7607, 7607, 7607, -1, + 7608, 7608, 7608, -1, 7609, 7609, 7609, -1, + 7610, 7610, 7610, -1, 7611, 7611, 7611, -1, + 7612, 7612, 7612, -1, 7613, 7613, 7613, -1, + 7614, 7614, 7614, -1, 7615, 7615, 7615, -1, + 7616, 7616, 7616, -1, 7617, 7617, 7617, -1, + 7618, 7618, 7618, -1, 7619, 7619, 7619, -1, + 7620, 7620, 7620, -1, 7621, 7621, 7621, -1, + 7622, 7622, 7622, -1, 7623, 7623, 7623, -1, + 7624, 7624, 7624, -1, 7625, 7625, 7625, -1, + 7626, 7626, 7626, -1, 7627, 7627, 7627, -1, + 7628, 7628, 7628, -1, 7629, 7629, 7629, -1, + 7630, 7630, 7630, -1, 7631, 7631, 7631, -1, + 7632, 7632, 7632, -1, 7633, 7633, 7633, -1, + 7634, 7634, 7634, -1, 7635, 7635, 7635, -1, + 7636, 7636, 7636, -1, 7637, 7637, 7637, -1, + 7638, 7638, 7638, -1, 7639, 7639, 7639, -1, + 7640, 7640, 7640, -1, 7641, 7641, 7641, -1, + 7642, 7642, 7642, -1, 7643, 7643, 7643, -1, + 7644, 7644, 7644, -1, 7645, 7645, 7645, -1, + 7646, 7646, 7646, -1, 7647, 7647, 7647, -1, + 7648, 7648, 7648, -1, 7649, 7649, 7649, -1, + 7650, 7650, 7650, -1, 7651, 7651, 7651, -1, + 7652, 7652, 7652, -1, 7653, 7653, 7653, -1, + 7654, 7654, 7654, -1, 7655, 7655, 7655, -1, + 7656, 7656, 7656, -1, 7657, 7657, 7657, -1, + 7658, 7658, 7658, -1, 7659, 7659, 7659, -1, + 7660, 7660, 7660, -1, 7661, 7661, 7661, -1, + 7662, 7662, 7662, -1, 7663, 7663, 7663, -1, + 7664, 7664, 7664, -1, 7665, 7665, 7665, -1, + 7666, 7666, 7666, -1, 7667, 7667, 7667, -1, + 7668, 7668, 7668, -1, 7669, 7669, 7669, -1, + 7670, 7670, 7670, -1, 7671, 7671, 7671, -1, + 7672, 7672, 7672, -1, 7673, 7673, 7673, -1, + 7674, 7674, 7674, -1, 7675, 7675, 7675, -1, + 7676, 7676, 7676, -1, 7677, 7677, 7677, -1, + 7678, 7678, 7678, -1, 7679, 7679, 7679, -1, + 7680, 7680, 7680, -1, 7681, 7681, 7681, -1, + 7682, 7682, 7682, -1, 7683, 7683, 7683, -1, + 7684, 7684, 7684, -1, 7685, 7685, 7685, -1, + 7686, 7686, 7686, -1, 7687, 7687, 7687, -1, + 7688, 7688, 7688, -1, 7689, 7689, 7689, -1, + 7690, 7690, 7690, -1, 7691, 7691, 7691, -1, + 7692, 7692, 7692, -1, 7693, 7693, 7693, -1, + 7694, 7694, 7694, -1, 7695, 7695, 7695, -1, + 7696, 7696, 7696, -1, 7697, 7697, 7697, -1, + 7698, 7698, 7698, -1, 7699, 7699, 7699, -1, + 7700, 7700, 7700, -1, 7701, 7701, 7701, -1, + 7702, 7702, 7702, -1, 7703, 7703, 7703, -1, + 7704, 7704, 7704, -1, 7705, 7705, 7705, -1, + 7706, 7706, 7706, -1, 7707, 7707, 7707, -1, + 7708, 7708, 7708, -1, 7709, 7709, 7709, -1, + 7710, 7710, 7710, -1, 7711, 7711, 7711, -1, + 7712, 7712, 7712, -1, 7713, 7713, 7713, -1, + 7714, 7714, 7714, -1, 7715, 7715, 7715, -1, + 7716, 7716, 7716, -1, 7717, 7717, 7717, -1, + 7718, 7718, 7718, -1, 7719, 7719, 7719, -1, + 7720, 7720, 7720, -1, 7721, 7721, 7721, -1, + 7722, 7722, 7722, -1, 7723, 7723, 7723, -1, + 7724, 7724, 7724, -1, 7725, 7725, 7725, -1, + 7726, 7726, 7726, -1, 7727, 7727, 7727, -1, + 7728, 7728, 7728, -1, 7729, 7729, 7729, -1, + 7730, 7730, 7730, -1, 7731, 7731, 7731, -1, + 7732, 7732, 7732, -1, 7733, 7733, 7733, -1, + 7734, 7734, 7734, -1, 7735, 7735, 7735, -1, + 7736, 7736, 7736, -1, 7737, 7737, 7737, -1, + 7738, 7738, 7738, -1, 7739, 7739, 7739, -1, + 7740, 7740, 7740, -1, 7741, 7741, 7741, -1, + 7742, 7742, 7742, -1, 7743, 7743, 7743, -1, + 7744, 7744, 7744, -1, 7745, 7745, 7745, -1, + 7746, 7746, 7746, -1, 7747, 7747, 7747, -1, + 7748, 7748, 7748, -1, 7749, 7749, 7749, -1, + 7750, 7750, 7750, -1, 7751, 7751, 7751, -1, + 7752, 7752, 7752, -1, 7753, 7753, 7753, -1, + 7754, 7754, 7754, -1, 7755, 7755, 7755, -1, + 7756, 7756, 7756, -1, 7757, 7757, 7757, -1, + 7758, 7758, 7758, -1, 7759, 7759, 7759, -1, + 7760, 7760, 7760, -1, 7761, 7761, 7761, -1, + 7762, 7762, 7762, -1, 7763, 7763, 7763, -1, + 7764, 7764, 7764, -1, 7765, 7765, 7765, -1, + 7766, 7766, 7766, -1, 7767, 7767, 7767, -1, + 7768, 7768, 7768, -1, 7769, 7769, 7769, -1, + 7770, 7770, 7770, -1, 7771, 7771, 7771, -1, + 7772, 7772, 7772, -1, 7773, 7773, 7773, -1, + 7774, 7774, 7774, -1, 7775, 7775, 7775, -1, + 7776, 7776, 7776, -1, 7777, 7777, 7777, -1, + 7778, 7778, 7778, -1, 7779, 7779, 7779, -1, + 7780, 7780, 7780, -1, 7781, 7781, 7781, -1, + 7782, 7782, 7782, -1, 7783, 7783, 7783, -1, + 7784, 7784, 7784, -1, 7785, 7785, 7785, -1, + 7786, 7786, 7786, -1, 7787, 7787, 7787, -1, + 7788, 7788, 7788, -1, 7789, 7789, 7789, -1, + 7790, 7790, 7790, -1, 7791, 7791, 7791, -1, + 7792, 7792, 7792, -1, 7793, 7793, 7793, -1, + 7794, 7794, 7794, -1, 7795, 7795, 7795, -1, + 7796, 7796, 7796, -1, 7797, 7797, 7797, -1, + 7798, 7798, 7798, -1, 7799, 7799, 7799, -1, + 7800, 7800, 7800, -1, 7801, 7801, 7801, -1, + 7802, 7802, 7802, -1, 7803, 7803, 7803, -1, + 7804, 7804, 7804, -1, 7805, 7805, 7805, -1, + 7806, 7806, 7806, -1, 7807, 7807, 7807, -1, + 7808, 7808, 7808, -1, 7809, 7809, 7809, -1, + 7810, 7810, 7810, -1, 7811, 7811, 7811, -1, + 7812, 7812, 7812, -1, 7813, 7813, 7813, -1, + 7814, 7814, 7814, -1, 7815, 7815, 7815, -1, + 7816, 7816, 7816, -1, 7817, 7817, 7817, -1, + 7818, 7818, 7818, -1, 7819, 7819, 7819, -1, + 7820, 7820, 7820, -1, 7821, 7821, 7821, -1, + 7822, 7822, 7822, -1, 7823, 7823, 7823, -1, + 7824, 7824, 7824, -1, 7825, 7825, 7825, -1, + 7826, 7826, 7826, -1, 7827, 7827, 7827, -1, + 7828, 7828, 7828, -1, 7829, 7829, 7829, -1, + 7830, 7830, 7830, -1, 7831, 7831, 7831, -1, + 7832, 7832, 7832, -1, 7833, 7833, 7833, -1, + 7834, 7834, 7834, -1, 7835, 7835, 7835, -1, + 7836, 7836, 7836, -1, 7837, 7837, 7837, -1, + 7838, 7838, 7838, -1, 7839, 7839, 7839, -1, + 7840, 7840, 7840, -1, 7841, 7841, 7841, -1, + 7842, 7842, 7842, -1, 7843, 7843, 7843, -1, + 7844, 7844, 7844, -1, 7845, 7845, 7845, -1, + 7846, 7846, 7846, -1, 7847, 7847, 7847, -1, + 7848, 7848, 7848, -1, 7849, 7849, 7849, -1, + 7850, 7850, 7850, -1, 7851, 7851, 7851, -1, + 7852, 7852, 7852, -1, 7853, 7853, 7853, -1, + 7854, 7854, 7854, -1, 7855, 7855, 7855, -1, + 7856, 7856, 7856, -1, 7857, 7857, 7857, -1, + 7858, 7858, 7858, -1, 7859, 7859, 7859, -1, + 7860, 7860, 7860, -1, 7861, 7861, 7861, -1, + 7862, 7862, 7862, -1, 7863, 7863, 7863, -1, + 7864, 7864, 7864, -1, 7865, 7865, 7865, -1, + 7866, 7866, 7866, -1, 7867, 7867, 7867, -1, + 7868, 7868, 7868, -1, 7869, 7869, 7869, -1, + 7870, 7870, 7870, -1, 7871, 7871, 7871, -1, + 7872, 7872, 7872, -1, 7873, 7873, 7873, -1, + 7874, 7874, 7874, -1, 7875, 7875, 7875, -1, + 7876, 7876, 7876, -1, 7877, 7877, 7877, -1, + 7878, 7878, 7878, -1, 7879, 7879, 7879, -1, + 7880, 7880, 7880, -1, 7881, 7881, 7881, -1, + 7882, 7882, 7882, -1, 7883, 7883, 7883, -1, + 7884, 7884, 7884, -1, 7885, 7885, 7885, -1, + 7886, 7886, 7886, -1, 7887, 7887, 7887, -1, + 7888, 7888, 7888, -1, 7889, 7889, 7889, -1, + 7890, 7890, 7890, -1, 7891, 7891, 7891, -1, + 7892, 7892, 7892, -1, 7893, 7893, 7893, -1, + 7894, 7894, 7894, -1, 7895, 7895, 7895, -1, + 7896, 7896, 7896, -1, 7897, 7897, 7897, -1, + 7898, 7898, 7898, -1, 7899, 7899, 7899, -1, + 7900, 7900, 7900, -1, 7901, 7901, 7901, -1, + 7902, 7902, 7902, -1, 7903, 7903, 7903, -1, + 7904, 7904, 7904, -1, 7905, 7905, 7905, -1, + 7906, 7906, 7906, -1, 7907, 7907, 7907, -1, + 7908, 7908, 7908, -1, 7909, 7909, 7909, -1, + 7910, 7910, 7910, -1, 7911, 7911, 7911, -1, + 7912, 7912, 7912, -1, 7913, 7913, 7913, -1, + 7914, 7914, 7914, -1, 7915, 7915, 7915, -1, + 7916, 7916, 7916, -1, 7917, 7917, 7917, -1, + 7918, 7918, 7918, -1, 7919, 7919, 7919, -1, + 7920, 7920, 7920, -1, 7921, 7921, 7921, -1, + 7922, 7922, 7922, -1, 7923, 7923, 7923, -1, + 7924, 7924, 7924, -1, 7925, 7925, 7925, -1, + 7926, 7926, 7926, -1, 7927, 7927, 7927, -1, + 7928, 7928, 7928, -1, 7929, 7929, 7929, -1, + 7930, 7930, 7930, -1, 7931, 7931, 7931, -1, + 7932, 7932, 7932, -1, 7933, 7933, 7933, -1, + 7934, 7934, 7934, -1, 7935, 7935, 7935, -1, + 7936, 7936, 7936, -1, 7937, 7937, 7937, -1, + 7938, 7938, 7938, -1, 7939, 7939, 7939, -1, + 7940, 7940, 7940, -1, 7941, 7941, 7941, -1, + 7942, 7942, 7942, -1, 7943, 7943, 7943, -1, + 7944, 7944, 7944, -1, 7945, 7945, 7945, -1, + 7946, 7946, 7946, -1, 7947, 7947, 7947, -1, + 7948, 7948, 7948, -1, 7949, 7949, 7949, -1, + 7950, 7950, 7950, -1, 7951, 7951, 7951, -1, + 7952, 7952, 7952, -1, 7953, 7953, 7953, -1, + 7954, 7954, 7954, -1, 7955, 7955, 7955, -1, + 7956, 7956, 7956, -1, 7957, 7957, 7957, -1, + 7958, 7958, 7958, -1, 7959, 7959, 7959, -1, + 7960, 7960, 7960, -1, 7961, 7961, 7961, -1, + 7962, 7962, 7962, -1, 7963, 7963, 7963, -1, + 7964, 7964, 7964, -1, 7965, 7965, 7965, -1, + 7966, 7966, 7966, -1, 7967, 7967, 7967, -1, + 7968, 7968, 7968, -1, 7969, 7969, 7969, -1, + 7970, 7970, 7970, -1, 7971, 7971, 7971, -1, + 7972, 7972, 7972, -1, 7973, 7973, 7973, -1, + 7974, 7974, 7974, -1, 7975, 7975, 7975, -1, + 7976, 7976, 7976, -1, 7977, 7977, 7977, -1, + 7978, 7978, 7978, -1, 7979, 7979, 7979, -1, + 7980, 7980, 7980, -1, 7981, 7981, 7981, -1, + 7982, 7982, 7982, -1, 7983, 7983, 7983, -1, + 7984, 7984, 7984, -1, 7985, 7985, 7985, -1, + 7986, 7986, 7986, -1, 7987, 7987, 7987, -1, + 7988, 7988, 7988, -1, 7989, 7989, 7989, -1, + 7990, 7990, 7990, -1, 7991, 7991, 7991, -1, + 7992, 7992, 7992, -1, 7993, 7993, 7993, -1, + 7994, 7994, 7994, -1, 7995, 7995, 7995, -1, + 7996, 7996, 7996, -1, 7997, 7997, 7997, -1, + 7998, 7998, 7998, -1, 7999, 7999, 7999, -1, + 8000, 8000, 8000, -1, 8001, 8001, 8001, -1, + 8002, 8002, 8002, -1, 8003, 8003, 8003, -1, + 8004, 8004, 8004, -1, 8005, 8005, 8005, -1, + 8006, 8006, 8006, -1, 8007, 8007, 8007, -1, + 8008, 8008, 8008, -1, 8009, 8009, 8009, -1, + 8010, 8010, 8010, -1, 8011, 8011, 8011, -1, + 8012, 8012, 8012, -1, 8013, 8013, 8013, -1, + 8014, 8014, 8014, -1, 8015, 8015, 8015, -1, + 8016, 8016, 8016, -1, 8017, 8017, 8017, -1, + 8018, 8018, 8018, -1, 8019, 8019, 8019, -1, + 8020, 8020, 8020, -1, 8021, 8021, 8021, -1, + 8022, 8022, 8022, -1, 8023, 8023, 8023, -1, + 8024, 8024, 8024, -1, 8025, 8025, 8025, -1, + 8026, 8026, 8026, -1, 8027, 8027, 8027, -1, + 8028, 8028, 8028, -1, 8029, 8029, 8029, -1, + 8030, 8030, 8030, -1, 8031, 8031, 8031, -1, + 8032, 8032, 8032, -1, 8033, 8033, 8033, -1, + 8034, 8034, 8034, -1, 8035, 8035, 8035, -1, + 8036, 8036, 8036, -1, 8037, 8037, 8037, -1, + 8038, 8038, 8038, -1, 8039, 8039, 8039, -1, + 8040, 8040, 8040, -1, 8041, 8041, 8041, -1, + 8042, 8042, 8042, -1, 8043, 8043, 8043, -1, + 8044, 8044, 8044, -1, 8045, 8045, 8045, -1, + 8046, 8046, 8046, -1, 8047, 8047, 8047, -1, + 8048, 8048, 8048, -1, 8049, 8049, 8049, -1, + 8050, 8050, 8050, -1, 8051, 8051, 8051, -1, + 8052, 8052, 8052, -1, 8053, 8053, 8053, -1, + 8054, 8054, 8054, -1, 8055, 8055, 8055, -1, + 8056, 8056, 8056, -1, 8057, 8057, 8057, -1, + 8058, 8058, 8058, -1, 8059, 8059, 8059, -1, + 8060, 8060, 8060, -1, 8061, 8061, 8061, -1, + 8062, 8062, 8062, -1, 8063, 8063, 8063, -1, + 8064, 8064, 8064, -1, 8065, 8065, 8065, -1, + 8066, 8066, 8066, -1, 8067, 8067, 8067, -1, + 8068, 8068, 8068, -1, 8069, 8069, 8069, -1, + 8070, 8070, 8070, -1, 8071, 8071, 8071, -1, + 8072, 8072, 8072, -1, 8073, 8073, 8073, -1, + 8074, 8074, 8074, -1, 8075, 8075, 8075, -1, + 8076, 8076, 8076, -1, 8077, 8077, 8077, -1, + 8078, 8078, 8078, -1, 8079, 8079, 8079, -1, + 8080, 8080, 8080, -1, 8081, 8081, 8081, -1, + 8082, 8082, 8082, -1, 8083, 8083, 8083, -1, + 8084, 8084, 8084, -1, 8085, 8085, 8085, -1, + 8086, 8086, 8086, -1, 8087, 8087, 8087, -1, + 8088, 8088, 8088, -1, 8089, 8089, 8089, -1, + 8090, 8090, 8090, -1, 8091, 8091, 8091, -1, + 8092, 8092, 8092, -1, 8093, 8093, 8093, -1, + 8094, 8094, 8094, -1, 8095, 8095, 8095, -1, + 8096, 8096, 8096, -1, 8097, 8097, 8097, -1, + 8098, 8098, 8098, -1, 8099, 8099, 8099, -1, + 8100, 8100, 8100, -1, 8101, 8101, 8101, -1, + 8102, 8102, 8102, -1, 8103, 8103, 8103, -1, + 8104, 8104, 8104, -1, 8105, 8105, 8105, -1, + 8106, 8106, 8106, -1, 8107, 8107, 8107, -1, + 8108, 8108, 8108, -1, 8109, 8109, 8109, -1, + 8110, 8110, 8110, -1, 8111, 8111, 8111, -1, + 8112, 8112, 8112, -1, 8113, 8113, 8113, -1, + 8114, 8114, 8114, -1, 8115, 8115, 8115, -1, + 8116, 8116, 8116, -1, 8117, 8117, 8117, -1, + 8118, 8118, 8118, -1, 8119, 8119, 8119, -1, + 8120, 8120, 8120, -1, 8121, 8121, 8121, -1, + 8122, 8122, 8122, -1, 8123, 8123, 8123, -1, + 8124, 8124, 8124, -1, 8125, 8125, 8125, -1, + 8126, 8126, 8126, -1, 8127, 8127, 8127, -1, + 8128, 8128, 8128, -1, 8129, 8129, 8129, -1, + 8130, 8130, 8130, -1, 8131, 8131, 8131, -1, + 8132, 8132, 8132, -1, 8133, 8133, 8133, -1, + 8134, 8134, 8134, -1, 8135, 8135, 8135, -1, + 8136, 8136, 8136, -1, 8137, 8137, 8137, -1, + 8138, 8138, 8138, -1, 8139, 8139, 8139, -1, + 8140, 8140, 8140, -1, 8141, 8141, 8141, -1, + 8142, 8142, 8142, -1, 8143, 8143, 8143, -1, + 8144, 8144, 8144, -1, 8145, 8145, 8145, -1, + 8146, 8146, 8146, -1, 8147, 8147, 8147, -1, + 8148, 8148, 8148, -1, 8149, 8149, 8149, -1, + 8150, 8150, 8150, -1, 8151, 8151, 8151, -1, + 8152, 8152, 8152, -1, 8153, 8153, 8153, -1, + 8154, 8154, 8154, -1, 8155, 8155, 8155, -1, + 8156, 8156, 8156, -1, 8157, 8157, 8157, -1, + 8158, 8158, 8158, -1, 8159, 8159, 8159, -1, + 8160, 8160, 8160, -1, 8161, 8161, 8161, -1, + 8162, 8162, 8162, -1, 8163, 8163, 8163, -1, + 8164, 8164, 8164, -1, 8165, 8165, 8165, -1, + 8166, 8166, 8166, -1, 8167, 8167, 8167, -1, + 8168, 8168, 8168, -1, 8169, 8169, 8169, -1, + 8170, 8170, 8170, -1, 8171, 8171, 8171, -1, + 8172, 8172, 8172, -1, 8173, 8173, 8173, -1, + 8174, 8174, 8174, -1, 8175, 8175, 8175, -1, + 8176, 8176, 8176, -1, 8177, 8177, 8177, -1, + 8178, 8178, 8178, -1, 8179, 8179, 8179, -1, + 8180, 8180, 8180, -1, 8181, 8181, 8181, -1, + 8182, 8182, 8182, -1, 8183, 8183, 8183, -1, + 8184, 8184, 8184, -1, 8185, 8185, 8185, -1, + 8186, 8186, 8186, -1, 8187, 8187, 8187, -1, + 8188, 8188, 8188, -1, 8189, 8189, 8189, -1, + 8190, 8190, 8190, -1, 8191, 8191, 8191, -1, + 8192, 8192, 8192, -1, 8193, 8193, 8193, -1, + 8194, 8194, 8194, -1, 8195, 8195, 8195, -1, + 8196, 8196, 8196, -1, 8197, 8197, 8197, -1, + 8198, 8198, 8198, -1, 8199, 8199, 8199, -1, + 8200, 8200, 8200, -1, 8201, 8201, 8201, -1, + 8202, 8202, 8202, -1, 8203, 8203, 8203, -1, + 8204, 8204, 8204, -1, 8205, 8205, 8205, -1, + 8206, 8206, 8206, -1, 8207, 8207, 8207, -1, + 8208, 8208, 8208, -1, 8209, 8209, 8209, -1, + 8210, 8210, 8210, -1, 8211, 8211, 8211, -1, + 8212, 8212, 8212, -1, 8213, 8213, 8213, -1, + 8214, 8214, 8214, -1, 8215, 8215, 8215, -1, + 8216, 8216, 8216, -1, 8217, 8217, 8217, -1, + 8218, 8218, 8218, -1, 8219, 8219, 8219, -1, + 8220, 8220, 8220, -1, 8221, 8221, 8221, -1, + 8222, 8222, 8222, -1, 8223, 8223, 8223, -1, + 8224, 8224, 8224, -1, 8225, 8225, 8225, -1, + 8226, 8226, 8226, -1, 8227, 8227, 8227, -1, + 8228, 8228, 8228, -1, 8229, 8229, 8229, -1, + 8230, 8230, 8230, -1, 8231, 8231, 8231, -1, + 8232, 8232, 8232, -1, 8233, 8233, 8233, -1, + 8234, 8234, 8234, -1, 8235, 8235, 8235, -1, + 8236, 8236, 8236, -1, 8237, 8237, 8237, -1, + 8238, 8238, 8238, -1, 8239, 8239, 8239, -1, + 8240, 8240, 8240, -1, 8241, 8241, 8241, -1, + 8242, 8242, 8242, -1, 8243, 8243, 8243, -1, + 8244, 8244, 8244, -1, 8245, 8245, 8245, -1, + 8246, 8246, 8246, -1, 8247, 8247, 8247, -1, + 8248, 8248, 8248, -1, 8249, 8249, 8249, -1, + 8250, 8250, 8250, -1, 8251, 8251, 8251, -1, + 8252, 8252, 8252, -1, 8253, 8253, 8253, -1, + 8254, 8254, 8254, -1, 8255, 8255, 8255, -1, + 8256, 8256, 8256, -1, 8257, 8257, 8257, -1, + 8258, 8258, 8258, -1, 8259, 8259, 8259, -1, + 8260, 8260, 8260, -1, 8261, 8261, 8261, -1, + 8262, 8262, 8262, -1, 8263, 8263, 8263, -1, + 8264, 8264, 8264, -1, 8265, 8265, 8265, -1, + 8266, 8266, 8266, -1, 8267, 8267, 8267, -1, + 8268, 8268, 8268, -1, 8269, 8269, 8269, -1, + 8270, 8270, 8270, -1, 8271, 8271, 8271, -1, + 8272, 8272, 8272, -1, 8273, 8273, 8273, -1, + 8274, 8274, 8274, -1, 8275, 8275, 8275, -1, + 8276, 8276, 8276, -1, 8277, 8277, 8277, -1, + 8278, 8278, 8278, -1, 8279, 8279, 8279, -1, + 8280, 8280, 8280, -1, 8281, 8281, 8281, -1, + 8282, 8282, 8282, -1, 8283, 8283, 8283, -1, + 8284, 8284, 8284, -1, 8285, 8285, 8285, -1, + 8286, 8286, 8286, -1, 8287, 8287, 8287, -1, + 8288, 8288, 8288, -1, 8289, 8289, 8289, -1, + 8290, 8290, 8290, -1, 8291, 8291, 8291, -1, + 8292, 8292, 8292, -1, 8293, 8293, 8293, -1, + 8294, 8294, 8294, -1, 8295, 8295, 8295, -1, + 8296, 8296, 8296, -1, 8297, 8297, 8297, -1, + 8298, 8298, 8298, -1, 8299, 8299, 8299, -1, + 8300, 8300, 8300, -1, 8301, 8301, 8301, -1, + 8302, 8302, 8302, -1, 8303, 8303, 8303, -1, + 8304, 8304, 8304, -1, 8305, 8305, 8305, -1, + 8306, 8306, 8306, -1, 8307, 8307, 8307, -1, + 8308, 8308, 8308, -1, 8309, 8309, 8309, -1, + 8310, 8310, 8310, -1, 8311, 8311, 8311, -1, + 8312, 8312, 8312, -1, 8313, 8313, 8313, -1, + 8314, 8314, 8314, -1, 8315, 8315, 8315, -1, + 8316, 8316, 8316, -1, 8317, 8317, 8317, -1, + 8318, 8318, 8318, -1, 8319, 8319, 8319, -1, + 8320, 8320, 8320, -1, 8321, 8321, 8321, -1, + 8322, 8322, 8322, -1, 8323, 8323, 8323, -1, + 8324, 8324, 8324, -1, 8325, 8325, 8325, -1, + 8326, 8326, 8326, -1, 8327, 8327, 8327, -1, + 8328, 8328, 8328, -1, 8329, 8329, 8329, -1, + 8330, 8330, 8330, -1, 8331, 8331, 8331, -1, + 8332, 8332, 8332, -1, 8333, 8333, 8333, -1, + 8334, 8334, 8334, -1, 8335, 8335, 8335, -1, + 8336, 8336, 8336, -1, 8337, 8337, 8337, -1, + 8338, 8338, 8338, -1, 8339, 8339, 8339, -1, + 8340, 8340, 8340, -1, 8341, 8341, 8341, -1, + 8342, 8342, 8342, -1, 8343, 8343, 8343, -1, + 8344, 8344, 8344, -1, 8345, 8345, 8345, -1, + 8346, 8346, 8346, -1, 8347, 8347, 8347, -1, + 8348, 8348, 8348, -1, 8349, 8349, 8349, -1, + 8350, 8350, 8350, -1, 8351, 8351, 8351, -1, + 8352, 8352, 8352, -1, 8353, 8353, 8353, -1, + 8354, 8354, 8354, -1, 8355, 8355, 8355, -1, + 8356, 8356, 8356, -1, 8357, 8357, 8357, -1, + 8358, 8358, 8358, -1, 8359, 8359, 8359, -1, + 8360, 8360, 8360, -1, 8361, 8361, 8361, -1, + 8362, 8362, 8362, -1, 8363, 8363, 8363, -1, + 8364, 8364, 8364, -1, 8365, 8365, 8365, -1, + 8366, 8366, 8366, -1, 8367, 8367, 8367, -1, + 8368, 8368, 8368, -1, 8369, 8369, 8369, -1, + 8370, 8370, 8370, -1, 8371, 8371, 8371, -1, + 8372, 8372, 8372, -1, 8373, 8373, 8373, -1, + 8374, 8374, 8374, -1, 8375, 8375, 8375, -1, + 8376, 8376, 8376, -1, 8377, 8377, 8377, -1, + 8378, 8378, 8378, -1, 8379, 8379, 8379, -1, + 8380, 8380, 8380, -1, 8381, 8381, 8381, -1, + 8382, 8382, 8382, -1, 8383, 8383, 8383, -1, + 8384, 8384, 8384, -1, 8385, 8385, 8385, -1, + 8386, 8386, 8386, -1, 8387, 8387, 8387, -1, + 8388, 8388, 8388, -1, 8389, 8389, 8389, -1, + 8390, 8390, 8390, -1, 8391, 8391, 8391, -1, + 8392, 8392, 8392, -1, 8393, 8393, 8393, -1, + 8394, 8394, 8394, -1, 8395, 8395, 8395, -1, + 8396, 8396, 8396, -1, 8397, 8397, 8397, -1, + 8398, 8398, 8398, -1, 8399, 8399, 8399, -1, + 8400, 8400, 8400, -1, 8401, 8401, 8401, -1, + 8402, 8402, 8402, -1, 8403, 8403, 8403, -1, + 8404, 8404, 8404, -1, 8405, 8405, 8405, -1, + 8406, 8406, 8406, -1, 8407, 8407, 8407, -1, + 8408, 8408, 8408, -1, 8409, 8409, 8409, -1, + 8410, 8410, 8410, -1, 8411, 8411, 8411, -1, + 8412, 8412, 8412, -1, 8413, 8413, 8413, -1, + 8414, 8414, 8414, -1, 8415, 8415, 8415, -1, + 8416, 8416, 8416, -1, 8417, 8417, 8417, -1, + 8418, 8418, 8418, -1, 8419, 8419, 8419, -1, + 8420, 8420, 8420, -1, 8421, 8421, 8421, -1, + 8422, 8422, 8422, -1, 8423, 8423, 8423, -1, + 8424, 8424, 8424, -1, 8425, 8425, 8425, -1, + 8426, 8426, 8426, -1, 8427, 8427, 8427, -1, + 8428, 8428, 8428, -1, 8429, 8429, 8429, -1, + 8430, 8430, 8430, -1, 8431, 8431, 8431, -1, + 8432, 8432, 8432, -1, 8433, 8433, 8433, -1, + 8434, 8434, 8434, -1, 8435, 8435, 8435, -1, + 8436, 8436, 8436, -1, 8437, 8437, 8437, -1, + 8438, 8438, 8438, -1, 8439, 8439, 8439, -1, + 8440, 8440, 8440, -1, 8441, 8441, 8441, -1, + 8442, 8442, 8442, -1, 8443, 8443, 8443, -1, + 8444, 8444, 8444, -1, 8445, 8445, 8445, -1, + 8446, 8446, 8446, -1, 8447, 8447, 8447, -1, + 8448, 8448, 8448, -1, 8449, 8449, 8449, -1, + 8450, 8450, 8450, -1, 8451, 8451, 8451, -1, + 8452, 8452, 8452, -1, 8453, 8453, 8453, -1, + 8454, 8454, 8454, -1, 8455, 8455, 8455, -1, + 8456, 8456, 8456, -1, 8457, 8457, 8457, -1, + 8458, 8458, 8458, -1, 8459, 8459, 8459, -1, + 8460, 8460, 8460, -1, 8461, 8461, 8461, -1, + 8462, 8462, 8462, -1, 8463, 8463, 8463, -1, + 8464, 8464, 8464, -1, 8465, 8465, 8465, -1, + 8466, 8466, 8466, -1, 8467, 8467, 8467, -1, + 8468, 8468, 8468, -1, 8469, 8469, 8469, -1, + 8470, 8470, 8470, -1, 8471, 8471, 8471, -1, + 8472, 8472, 8472, -1, 8473, 8473, 8473, -1, + 8474, 8474, 8474, -1, 8475, 8475, 8475, -1, + 8476, 8476, 8476, -1, 8477, 8477, 8477, -1, + 8478, 8478, 8478, -1, 8479, 8479, 8479, -1, + 8480, 8480, 8480, -1, 8481, 8481, 8481, -1, + 8482, 8482, 8482, -1, 8483, 8483, 8483, -1, + 8484, 8484, 8484, -1, 8485, 8485, 8485, -1, + 8486, 8486, 8486, -1, 8487, 8487, 8487, -1, + 8488, 8488, 8488, -1, 8489, 8489, 8489, -1, + 8490, 8490, 8490, -1, 8491, 8491, 8491, -1, + 8492, 8492, 8492, -1, 8493, 8493, 8493, -1, + 8494, 8494, 8494, -1, 8495, 8495, 8495, -1, + 8496, 8496, 8496, -1, 8497, 8497, 8497, -1, + 8498, 8498, 8498, -1, 8499, 8499, 8499, -1, + 8500, 8500, 8500, -1, 8501, 8501, 8501, -1, + 8502, 8502, 8502, -1, 8503, 8503, 8503, -1, + 8504, 8504, 8504, -1, 8505, 8505, 8505, -1, + 8506, 8506, 8506, -1, 8507, 8507, 8507, -1, + 8508, 8508, 8508, -1, 8509, 8509, 8509, -1, + 8510, 8510, 8510, -1, 8511, 8511, 8511, -1, + 8512, 8512, 8512, -1, 8513, 8513, 8513, -1, + 8514, 8514, 8514, -1, 8515, 8515, 8515, -1, + 8516, 8516, 8516, -1, 8517, 8517, 8517, -1, + 8518, 8518, 8518, -1, 8519, 8519, 8519, -1, + 8520, 8520, 8520, -1, 8521, 8521, 8521, -1, + 8522, 8522, 8522, -1, 8523, 8523, 8523, -1, + 8524, 8524, 8524, -1, 8525, 8525, 8525, -1, + 8526, 8526, 8526, -1, 8527, 8527, 8527, -1, + 8528, 8528, 8528, -1, 8529, 8529, 8529, -1, + 8530, 8530, 8530, -1, 8531, 8531, 8531, -1, + 8532, 8532, 8532, -1, 8533, 8533, 8533, -1, + 8534, 8534, 8534, -1, 8535, 8535, 8535, -1, + 8536, 8536, 8536, -1, 8537, 8537, 8537, -1, + 8538, 8538, 8538, -1, 8539, 8539, 8539, -1, + 8540, 8540, 8540, -1, 8541, 8541, 8541, -1, + 8542, 8542, 8542, -1, 8543, 8543, 8543, -1, + 8544, 8544, 8544, -1, 8545, 8545, 8545, -1, + 8546, 8546, 8546, -1, 8547, 8547, 8547, -1, + 8548, 8548, 8548, -1, 8549, 8549, 8549, -1, + 8550, 8550, 8550, -1, 8551, 8551, 8551, -1, + 8552, 8552, 8552, -1, 8553, 8553, 8553, -1, + 8554, 8554, 8554, -1, 8555, 8555, 8555, -1, + 8556, 8556, 8556, -1, 8557, 8557, 8557, -1, + 8558, 8558, 8558, -1, 8559, 8559, 8559, -1, + 8560, 8560, 8560, -1, 8561, 8561, 8561, -1, + 8562, 8562, 8562, -1, 8563, 8563, 8563, -1, + 8564, 8564, 8564, -1, 8565, 8565, 8565, -1, + 8566, 8566, 8566, -1, 8567, 8567, 8567, -1, + 8568, 8568, 8568, -1, 8569, 8569, 8569, -1, + 8570, 8570, 8570, -1, 8571, 8571, 8571, -1, + 8572, 8572, 8572, -1, 8573, 8573, 8573, -1, + 8574, 8574, 8574, -1, 8575, 8575, 8575, -1, + 8576, 8576, 8576, -1, 8577, 8577, 8577, -1, + 8578, 8578, 8578, -1, 8579, 8579, 8579, -1, + 8580, 8580, 8580, -1, 8581, 8581, 8581, -1, + 8582, 8582, 8582, -1, 8583, 8583, 8583, -1, + 8584, 8584, 8584, -1, 8585, 8585, 8585, -1, + 8586, 8586, 8586, -1, 8587, 8587, 8587, -1, + 8588, 8588, 8588, -1, 8589, 8589, 8589, -1, + 8590, 8590, 8590, -1, 8591, 8591, 8591, -1, + 8592, 8592, 8592, -1, 8593, 8593, 8593, -1, + 8594, 8594, 8594, -1, 8595, 8595, 8595, -1, + 8596, 8596, 8596, -1, 8597, 8597, 8597, -1, + 8598, 8598, 8598, -1, 8599, 8599, 8599, -1, + 8600, 8600, 8600, -1, 8601, 8601, 8601, -1, + 8602, 8602, 8602, -1, 8603, 8603, 8603, -1, + 8604, 8604, 8604, -1, 8605, 8605, 8605, -1, + 8606, 8606, 8606, -1, 8607, 8607, 8607, -1, + 8608, 8608, 8608, -1, 8609, 8609, 8609, -1, + 8610, 8610, 8610, -1, 8611, 8611, 8611, -1, + 8612, 8612, 8612, -1, 8613, 8613, 8613, -1, + 8614, 8614, 8614, -1, 8615, 8615, 8615, -1, + 8616, 8616, 8616, -1, 8617, 8617, 8617, -1, + 8618, 8618, 8618, -1, 8619, 8619, 8619, -1, + 8620, 8620, 8620, -1, 8621, 8621, 8621, -1, + 8622, 8622, 8622, -1, 8623, 8623, 8623, -1, + 8624, 8624, 8624, -1, 8625, 8625, 8625, -1, + 8626, 8626, 8626, -1, 8627, 8627, 8627, -1, + 8628, 8628, 8628, -1, 8629, 8629, 8629, -1, + 8630, 8630, 8630, -1, 8631, 8631, 8631, -1, + 8632, 8632, 8632, -1, 8633, 8633, 8633, -1, + 8634, 8634, 8634, -1, 8635, 8635, 8635, -1, + 8636, 8636, 8636, -1, 8637, 8637, 8637, -1, + 8638, 8638, 8638, -1, 8639, 8639, 8639, -1, + 8640, 8640, 8640, -1, 8641, 8641, 8641, -1, + 8642, 8642, 8642, -1, 8643, 8643, 8643, -1, + 8644, 8644, 8644, -1, 8645, 8645, 8645, -1, + 8646, 8646, 8646, -1, 8647, 8647, 8647, -1, + 8648, 8648, 8648, -1, 8649, 8649, 8649, -1, + 8650, 8650, 8650, -1, 8651, 8651, 8651, -1, + 8652, 8652, 8652, -1, 8653, 8653, 8653, -1, + 8654, 8654, 8654, -1, 8655, 8655, 8655, -1, + 8656, 8656, 8656, -1, 8657, 8657, 8657, -1, + 8658, 8658, 8658, -1, 8659, 8659, 8659, -1, + 8660, 8660, 8660, -1, 8661, 8661, 8661, -1, + 8662, 8662, 8662, -1, 8663, 8663, 8663, -1, + 8664, 8664, 8664, -1, 8665, 8665, 8665, -1, + 8666, 8666, 8666, -1, 8667, 8667, 8667, -1, + 8668, 8668, 8668, -1, 8669, 8669, 8669, -1, + 8670, 8670, 8670, -1, 8671, 8671, 8671, -1, + 8672, 8672, 8672, -1, 8673, 8673, 8673, -1, + 8674, 8674, 8674, -1, 8675, 8675, 8675, -1, + 8676, 8676, 8676, -1, 8677, 8677, 8677, -1, + 8678, 8678, 8678, -1, 8679, 8679, 8679, -1, + 8680, 8680, 8680, -1, 8681, 8681, 8681, -1, + 8682, 8682, 8682, -1, 8683, 8683, 8683, -1, + 8684, 8684, 8684, -1, 8685, 8685, 8685, -1, + 8686, 8686, 8686, -1, 8687, 8687, 8687, -1, + 8688, 8688, 8688, -1, 8689, 8689, 8689, -1, + 8690, 8690, 8690, -1, 8691, 8691, 8691, -1, + 8692, 8692, 8692, -1, 8693, 8693, 8693, -1, + 8694, 8694, 8694, -1, 8695, 8695, 8695, -1, + 8696, 8696, 8696, -1, 8697, 8697, 8697, -1, + 8698, 8698, 8698, -1, 8699, 8699, 8699, -1, + 8700, 8700, 8700, -1, 8701, 8701, 8701, -1, + 8702, 8702, 8702, -1, 8703, 8703, 8703, -1, + 8704, 8704, 8704, -1, 8705, 8705, 8705, -1, + 8706, 8706, 8706, -1, 8707, 8707, 8707, -1, + 8708, 8708, 8708, -1, 8709, 8709, 8709, -1, + 8710, 8710, 8710, -1, 8711, 8711, 8711, -1, + 8712, 8712, 8712, -1, 8713, 8713, 8713, -1, + 8714, 8714, 8714, -1, 8715, 8715, 8715, -1, + 8716, 8716, 8716, -1, 8717, 8717, 8717, -1, + 8718, 8718, 8718, -1, 8719, 8719, 8719, -1, + 8720, 8720, 8720, -1, 8721, 8721, 8721, -1, + 8722, 8722, 8722, -1, 8723, 8723, 8723, -1, + 8724, 8724, 8724, -1, 8725, 8725, 8725, -1, + 8726, 8726, 8726, -1, 8727, 8727, 8727, -1, + 8728, 8728, 8728, -1, 8729, 8729, 8729, -1, + 8730, 8730, 8730, -1, 8731, 8731, 8731, -1, + 8732, 8732, 8732, -1, 8733, 8733, 8733, -1, + 8734, 8734, 8734, -1, 8735, 8735, 8735, -1, + 8736, 8736, 8736, -1, 8737, 8737, 8737, -1, + 8738, 8738, 8738, -1, 8739, 8739, 8739, -1, + 8740, 8740, 8740, -1, 8741, 8741, 8741, -1, + 8742, 8742, 8742, -1, 8743, 8743, 8743, -1, + 8744, 8744, 8744, -1, 8745, 8745, 8745, -1, + 8746, 8746, 8746, -1, 8747, 8747, 8747, -1, + 8748, 8748, 8748, -1, 8749, 8749, 8749, -1, + 8750, 8750, 8750, -1, 8751, 8751, 8751, -1, + 8752, 8752, 8752, -1, 8753, 8753, 8753, -1, + 8754, 8754, 8754, -1, 8755, 8755, 8755, -1, + 8756, 8756, 8756, -1, 8757, 8757, 8757, -1, + 8758, 8758, 8758, -1, 8759, 8759, 8759, -1, + 8760, 8760, 8760, -1, 8761, 8761, 8761, -1, + 8762, 8762, 8762, -1, 8763, 8763, 8763, -1, + 8764, 8764, 8764, -1, 8765, 8765, 8765, -1, + 8766, 8766, 8766, -1, 8767, 8767, 8767, -1, + 8768, 8768, 8768, -1, 8769, 8769, 8769, -1, + 8770, 8770, 8770, -1, 8771, 8771, 8771, -1, + 8772, 8772, 8772, -1, 8773, 8773, 8773, -1, + 8774, 8774, 8774, -1, 8775, 8775, 8775, -1, + 8776, 8776, 8776, -1, 8777, 8777, 8777, -1, + 8778, 8778, 8778, -1, 8779, 8779, 8779, -1, + 8780, 8780, 8780, -1, 8781, 8781, 8781, -1, + 8782, 8782, 8782, -1, 8783, 8783, 8783, -1, + 8784, 8784, 8784, -1, 8785, 8785, 8785, -1, + 8786, 8786, 8786, -1, 8787, 8787, 8787, -1, + 8788, 8788, 8788, -1, 8789, 8789, 8789, -1, + 8790, 8790, 8790, -1, 8791, 8791, 8791, -1, + 8792, 8792, 8792, -1, 8793, 8793, 8793, -1, + 8794, 8794, 8794, -1, 8795, 8795, 8795, -1, + 8796, 8796, 8796, -1, 8797, 8797, 8797, -1, + 8798, 8798, 8798, -1, 8799, 8799, 8799, -1, + 8800, 8800, 8800, -1, 8801, 8801, 8801, -1, + 8802, 8802, 8802, -1, 8803, 8803, 8803, -1, + 8804, 8804, 8804, -1, 8805, 8805, 8805, -1, + 8806, 8806, 8806, -1, 8807, 8807, 8807, -1, + 8808, 8808, 8808, -1, 8809, 8809, 8809, -1, + 8810, 8810, 8810, -1, 8811, 8811, 8811, -1, + 8812, 8812, 8812, -1, 8813, 8813, 8813, -1, + 8814, 8814, 8814, -1, 8815, 8815, 8815, -1, + 8816, 8816, 8816, -1, 8817, 8817, 8817, -1, + 8818, 8818, 8818, -1, 8819, 8819, 8819, -1, + 8820, 8820, 8820, -1, 8821, 8821, 8821, -1, + 8822, 8822, 8822, -1, 8823, 8823, 8823, -1, + 8824, 8824, 8824, -1, 8825, 8825, 8825, -1, + 8826, 8826, 8826, -1, 8827, 8827, 8827, -1, + 8828, 8828, 8828, -1, 8829, 8829, 8829, -1, + 8830, 8830, 8830, -1, 8831, 8831, 8831, -1, + 8832, 8832, 8832, -1, 8833, 8833, 8833, -1, + 8834, 8834, 8834, -1, 8835, 8835, 8835, -1, + 8836, 8836, 8836, -1, 8837, 8837, 8837, -1, + 8838, 8838, 8838, -1, 8839, 8839, 8839, -1, + 8840, 8840, 8840, -1, 8841, 8841, 8841, -1, + 8842, 8842, 8842, -1, 8843, 8843, 8843, -1, + 8844, 8844, 8844, -1, 8845, 8845, 8845, -1, + 8846, 8846, 8846, -1, 8847, 8847, 8847, -1, + 8848, 8848, 8848, -1, 8849, 8849, 8849, -1, + 8850, 8850, 8850, -1, 8851, 8851, 8851, -1, + 8852, 8852, 8852, -1, 8853, 8853, 8853, -1, + 8854, 8854, 8854, -1, 8855, 8855, 8855, -1, + 8856, 8856, 8856, -1, 8857, 8857, 8857, -1, + 8858, 8858, 8858, -1, 8859, 8859, 8859, -1, + 8860, 8860, 8860, -1, 8861, 8861, 8861, -1, + 8862, 8862, 8862, -1, 8863, 8863, 8863, -1, + 8864, 8864, 8864, -1, 8865, 8865, 8865, -1, + 8866, 8866, 8866, -1, 8867, 8867, 8867, -1, + 8868, 8868, 8868, -1, 8869, 8869, 8869, -1, + 8870, 8870, 8870, -1, 8871, 8871, 8871, -1, + 8872, 8872, 8872, -1, 8873, 8873, 8873, -1, + 8874, 8874, 8874, -1, 8875, 8875, 8875, -1, + 8876, 8876, 8876, -1, 8877, 8877, 8877, -1, + 8878, 8878, 8878, -1, 8879, 8879, 8879, -1, + 8880, 8880, 8880, -1, 8881, 8881, 8881, -1, + 8882, 8882, 8882, -1, 8883, 8883, 8883, -1, + 8884, 8884, 8884, -1, 8885, 8885, 8885, -1, + 8886, 8886, 8886, -1, 8887, 8887, 8887, -1, + 8888, 8888, 8888, -1, 8889, 8889, 8889, -1, + 8890, 8890, 8890, -1, 8891, 8891, 8891, -1, + 8892, 8892, 8892, -1, 8893, 8893, 8893, -1, + 8894, 8894, 8894, -1, 8895, 8895, 8895, -1, + 8896, 8896, 8896, -1, 8897, 8897, 8897, -1, + 8898, 8898, 8898, -1, 8899, 8899, 8899, -1, + 8900, 8900, 8900, -1, 8901, 8901, 8901, -1, + 8902, 8902, 8902, -1, 8903, 8903, 8903, -1, + 8904, 8904, 8904, -1, 8905, 8905, 8905, -1, + 8906, 8906, 8906, -1, 8907, 8907, 8907, -1, + 8908, 8908, 8908, -1, 8909, 8909, 8909, -1, + 8910, 8910, 8910, -1, 8911, 8911, 8911, -1, + 8912, 8912, 8912, -1, 8913, 8913, 8913, -1, + 8914, 8914, 8914, -1, 8915, 8915, 8915, -1, + 8916, 8916, 8916, -1, 8917, 8917, 8917, -1, + 8918, 8918, 8918, -1, 8919, 8919, 8919, -1, + 8920, 8920, 8920, -1, 8921, 8921, 8921, -1, + 8922, 8922, 8922, -1, 8923, 8923, 8923, -1, + 8924, 8924, 8924, -1, 8925, 8925, 8925, -1, + 8926, 8926, 8926, -1, 8927, 8927, 8927, -1, + 8928, 8928, 8928, -1, 8929, 8929, 8929, -1, + 8930, 8930, 8930, -1, 8931, 8931, 8931, -1, + 8932, 8932, 8932, -1, 8933, 8933, 8933, -1, + 8934, 8934, 8934, -1, 8935, 8935, 8935, -1, + 8936, 8936, 8936, -1, 8937, 8937, 8937, -1, + 8938, 8938, 8938, -1, 8939, 8939, 8939, -1, + 8940, 8940, 8940, -1, 8941, 8941, 8941, -1, + 8942, 8942, 8942, -1, 8943, 8943, 8943, -1, + 8944, 8944, 8944, -1, 8945, 8945, 8945, -1, + 8946, 8946, 8946, -1, 8947, 8947, 8947, -1, + 8948, 8948, 8948, -1, 8949, 8949, 8949, -1, + 8950, 8950, 8950, -1, 8951, 8951, 8951, -1, + 8952, 8952, 8952, -1, 8953, 8953, 8953, -1, + 8954, 8954, 8954, -1, 8955, 8955, 8955, -1, + 8956, 8956, 8956, -1, 8957, 8957, 8957, -1, + 8958, 8958, 8958, -1, 8959, 8959, 8959, -1, + 8960, 8960, 8960, -1, 8961, 8961, 8961, -1, + 8962, 8962, 8962, -1, 8963, 8963, 8963, -1, + 8964, 8964, 8964, -1, 8965, 8965, 8965, -1, + 8966, 8966, 8966, -1, 8967, 8967, 8967, -1, + 8968, 8968, 8968, -1, 8969, 8969, 8969, -1, + 8970, 8970, 8970, -1, 8971, 8971, 8971, -1, + 8972, 8972, 8972, -1, 8973, 8973, 8973, -1, + 8974, 8974, 8974, -1, 8975, 8975, 8975, -1, + 8976, 8976, 8976, -1, 8977, 8977, 8977, -1, + 8978, 8978, 8978, -1, 8979, 8979, 8979, -1, + 8980, 8980, 8980, -1, 8981, 8981, 8981, -1, + 8982, 8982, 8982, -1, 8983, 8983, 8983, -1, + 8984, 8984, 8984, -1, 8985, 8985, 8985, -1, + 8986, 8986, 8986, -1, 8987, 8987, 8987, -1, + 8988, 8988, 8988, -1, 8989, 8989, 8989, -1, + 8990, 8990, 8990, -1, 8991, 8991, 8991, -1, + 8992, 8992, 8992, -1, 8993, 8993, 8993, -1, + 8994, 8994, 8994, -1, 8995, 8995, 8995, -1, + 8996, 8996, 8996, -1, 8997, 8997, 8997, -1, + 8998, 8998, 8998, -1, 8999, 8999, 8999, -1, + 9000, 9000, 9000, -1, 9001, 9001, 9001, -1, + 9002, 9002, 9002, -1, 9003, 9003, 9003, -1, + 9004, 9004, 9004, -1, 9005, 9005, 9005, -1, + 9006, 9006, 9006, -1, 9007, 9007, 9007, -1, + 9008, 9008, 9008, -1, 9009, 9009, 9009, -1, + 9010, 9010, 9010, -1, 9011, 9011, 9011, -1, + 9012, 9012, 9012, -1, 9013, 9013, 9013, -1, + 9014, 9014, 9014, -1, 9015, 9015, 9015, -1, + 9016, 9016, 9016, -1, 9017, 9017, 9017, -1, + 9018, 9018, 9018, -1, 9019, 9019, 9019, -1, + 9020, 9020, 9020, -1, 9021, 9021, 9021, -1, + 9022, 9022, 9022, -1, 9023, 9023, 9023, -1, + 9024, 9024, 9024, -1, 9025, 9025, 9025, -1, + 9026, 9026, 9026, -1, 9027, 9027, 9027, -1, + 9028, 9028, 9028, -1, 9029, 9029, 9029, -1, + 9030, 9030, 9030, -1, 9031, 9031, 9031, -1, + 9032, 9032, 9032, -1, 9033, 9033, 9033, -1, + 9034, 9034, 9034, -1, 9035, 9035, 9035, -1, + 9036, 9036, 9036, -1, 9037, 9037, 9037, -1, + 9038, 9038, 9038, -1, 9039, 9039, 9039, -1, + 9040, 9040, 9040, -1, 9041, 9041, 9041, -1, + 9042, 9042, 9042, -1, 9043, 9043, 9043, -1, + 9044, 9044, 9044, -1, 9045, 9045, 9045, -1, + 9046, 9046, 9046, -1, 9047, 9047, 9047, -1, + 9048, 9048, 9048, -1, 9049, 9049, 9049, -1, + 9050, 9050, 9050, -1, 9051, 9051, 9051, -1, + 9052, 9052, 9052, -1, 9053, 9053, 9053, -1, + 9054, 9054, 9054, -1, 9055, 9055, 9055, -1, + 9056, 9056, 9056, -1, 9057, 9057, 9057, -1, + 9058, 9058, 9058, -1, 9059, 9059, 9059, -1, + 9060, 9060, 9060, -1, 9061, 9061, 9061, -1, + 9062, 9062, 9062, -1, 9063, 9063, 9063, -1, + 9064, 9064, 9064, -1, 9065, 9065, 9065, -1, + 9066, 9066, 9066, -1, 9067, 9067, 9067, -1, + 9068, 9068, 9068, -1, 9069, 9069, 9069, -1, + 9070, 9070, 9070, -1, 9071, 9071, 9071, -1, + 9072, 9072, 9072, -1, 9073, 9073, 9073, -1, + 9074, 9074, 9074, -1, 9075, 9075, 9075, -1, + 9076, 9076, 9076, -1, 9077, 9077, 9077, -1, + 9078, 9078, 9078, -1, 9079, 9079, 9079, -1, + 9080, 9080, 9080, -1, 9081, 9081, 9081, -1, + 9082, 9082, 9082, -1, 9083, 9083, 9083, -1, + 9084, 9084, 9084, -1, 9085, 9085, 9085, -1, + 9086, 9086, 9086, -1, 9087, 9087, 9087, -1, + 9088, 9088, 9088, -1, 9089, 9089, 9089, -1, + 9090, 9090, 9090, -1, 9091, 9091, 9091, -1, + 9092, 9092, 9092, -1, 9093, 9093, 9093, -1, + 9094, 9094, 9094, -1, 9095, 9095, 9095, -1, + 9096, 9096, 9096, -1, 9097, 9097, 9097, -1, + 9098, 9098, 9098, -1, 9099, 9099, 9099, -1, + 9100, 9100, 9100, -1, 9101, 9101, 9101, -1, + 9102, 9102, 9102, -1, 9103, 9103, 9103, -1, + 9104, 9104, 9104, -1, 9105, 9105, 9105, -1, + 9106, 9106, 9106, -1, 9107, 9107, 9107, -1, + 9108, 9108, 9108, -1, 9109, 9109, 9109, -1, + 9110, 9110, 9110, -1, 9111, 9111, 9111, -1, + 9112, 9112, 9112, -1, 9113, 9113, 9113, -1, + 9114, 9114, 9114, -1, 9115, 9115, 9115, -1, + 9116, 9116, 9116, -1, 9117, 9117, 9117, -1, + 9118, 9118, 9118, -1, 9119, 9119, 9119, -1, + 9120, 9120, 9120, -1, 9121, 9121, 9121, -1, + 9122, 9122, 9122, -1, 9123, 9123, 9123, -1, + 9124, 9124, 9124, -1, 9125, 9125, 9125, -1, + 9126, 9126, 9126, -1, 9127, 9127, 9127, -1, + 9128, 9128, 9128, -1, 9129, 9129, 9129, -1, + 9130, 9130, 9130, -1, 9131, 9131, 9131, -1, + 9132, 9132, 9132, -1, 9133, 9133, 9133, -1, + 9134, 9134, 9134, -1, 9135, 9135, 9135, -1, + 9136, 9136, 9136, -1, 9137, 9137, 9137, -1, + 9138, 9138, 9138, -1, 9139, 9139, 9139, -1, + 9140, 9140, 9140, -1, 9141, 9141, 9141, -1, + 9142, 9142, 9142, -1, 9143, 9143, 9143, -1, + 9144, 9144, 9144, -1, 9145, 9145, 9145, -1, + 9146, 9146, 9146, -1, 9147, 9147, 9147, -1, + 9148, 9148, 9148, -1, 9149, 9149, 9149, -1, + 9150, 9150, 9150, -1, 9151, 9151, 9151, -1, + 9152, 9152, 9152, -1, 9153, 9153, 9153, -1, + 9154, 9154, 9154, -1, 9155, 9155, 9155, -1, + 9156, 9156, 9156, -1, 9157, 9157, 9157, -1, + 9158, 9158, 9158, -1, 9159, 9159, 9159, -1, + 9160, 9160, 9160, -1, 9161, 9161, 9161, -1, + 9162, 9162, 9162, -1, 9163, 9163, 9163, -1, + 9164, 9164, 9164, -1, 9165, 9165, 9165, -1, + 9166, 9166, 9166, -1, 9167, 9167, 9167, -1, + 9168, 9168, 9168, -1, 9169, 9169, 9169, -1, + 9170, 9170, 9170, -1, 9171, 9171, 9171, -1, + 9172, 9172, 9172, -1, 9173, 9173, 9173, -1, + 9174, 9174, 9174, -1, 9175, 9175, 9175, -1, + 9176, 9176, 9176, -1, 9177, 9177, 9177, -1, + 9178, 9178, 9178, -1, 9179, 9179, 9179, -1, + 9180, 9180, 9180, -1, 9181, 9181, 9181, -1, + 9182, 9182, 9182, -1, 9183, 9183, 9183, -1, + 9184, 9184, 9184, -1, 9185, 9185, 9185, -1, + 9186, 9186, 9186, -1, 9187, 9187, 9187, -1, + 9188, 9188, 9188, -1, 9189, 9189, 9189, -1, + 9190, 9190, 9190, -1, 9191, 9191, 9191, -1, + 9192, 9192, 9192, -1, 9193, 9193, 9193, -1, + 9194, 9194, 9194, -1, 9195, 9195, 9195, -1, + 9196, 9196, 9196, -1, 9197, 9197, 9197, -1, + 9198, 9198, 9198, -1, 9199, 9199, 9199, -1, + 9200, 9200, 9200, -1, 9201, 9201, 9201, -1, + 9202, 9202, 9202, -1, 9203, 9203, 9203, -1, + 9204, 9204, 9204, -1, 9205, 9205, 9205, -1, + 9206, 9206, 9206, -1, 9207, 9207, 9207, -1, + 9208, 9208, 9208, -1, 9209, 9209, 9209, -1, + 9210, 9210, 9210, -1, 9211, 9211, 9211, -1, + 9212, 9212, 9212, -1, 9213, 9213, 9213, -1, + 9214, 9214, 9214, -1, 9215, 9215, 9215, -1, + 9216, 9216, 9216, -1, 9217, 9217, 9217, -1, + 9218, 9218, 9218, -1, 9219, 9219, 9219, -1, + 9220, 9220, 9220, -1, 9221, 9221, 9221, -1, + 9222, 9222, 9222, -1, 9223, 9223, 9223, -1, + 9224, 9224, 9224, -1, 9225, 9225, 9225, -1, + 9226, 9226, 9226, -1, 9227, 9227, 9227, -1, + 9228, 9228, 9228, -1, 9229, 9229, 9229, -1, + 9230, 9230, 9230, -1, 9231, 9231, 9231, -1, + 9232, 9232, 9232, -1, 9233, 9233, 9233, -1, + 9234, 9234, 9234, -1, 9235, 9235, 9235, -1, + 9236, 9236, 9236, -1, 9237, 9237, 9237, -1, + 9238, 9238, 9238, -1, 9239, 9239, 9239, -1, + 9240, 9240, 9240, -1, 9241, 9241, 9241, -1, + 9242, 9242, 9242, -1, 9243, 9243, 9243, -1, + 9244, 9244, 9244, -1, 9245, 9245, 9245, -1, + 9246, 9246, 9246, -1, 9247, 9247, 9247, -1, + 9248, 9248, 9248, -1, 9249, 9249, 9249, -1, + 9250, 9250, 9250, -1, 9251, 9251, 9251, -1, + 9252, 9252, 9252, -1, 9253, 9253, 9253, -1, + 9254, 9254, 9254, -1, 9255, 9255, 9255, -1, + 9256, 9256, 9256, -1, 9257, 9257, 9257, -1, + 9258, 9258, 9258, -1, 9259, 9259, 9259, -1, + 9260, 9260, 9260, -1, 9261, 9261, 9261, -1, + 9262, 9262, 9262, -1, 9263, 9263, 9263, -1, + 9264, 9264, 9264, -1, 9265, 9265, 9265, -1, + 9266, 9266, 9266, -1, 9267, 9267, 9267, -1, + 9268, 9268, 9268, -1, 9269, 9269, 9269, -1, + 9270, 9270, 9270, -1, 9271, 9271, 9271, -1, + 9272, 9272, 9272, -1, 9273, 9273, 9273, -1, + 9274, 9274, 9274, -1, 9275, 9275, 9275, -1, + 9276, 9276, 9276, -1, 9277, 9277, 9277, -1, + 9278, 9278, 9278, -1, 9279, 9279, 9279, -1, + 9280, 9280, 9280, -1, 9281, 9281, 9281, -1, + 9282, 9282, 9282, -1, 9283, 9283, 9283, -1, + 9284, 9284, 9284, -1, 9285, 9285, 9285, -1, + 9286, 9286, 9286, -1, 9287, 9287, 9287, -1, + 9288, 9288, 9288, -1, 9289, 9289, 9289, -1, + 9290, 9290, 9290, -1, 9291, 9291, 9291, -1, + 9292, 9292, 9292, -1, 9293, 9293, 9293, -1, + 9294, 9294, 9294, -1, 9295, 9295, 9295, -1, + 9296, 9296, 9296, -1, 9297, 9297, 9297, -1, + 9298, 9298, 9298, -1, 9299, 9299, 9299, -1, + 9300, 9300, 9300, -1, 9301, 9301, 9301, -1, + 9302, 9302, 9302, -1, 9303, 9303, 9303, -1, + 9304, 9304, 9304, -1, 9305, 9305, 9305, -1, + 9306, 9306, 9306, -1, 9307, 9307, 9307, -1, + 9308, 9308, 9308, -1, 9309, 9309, 9309, -1, + 9310, 9310, 9310, -1, 9311, 9311, 9311, -1, + 9312, 9312, 9312, -1, 9313, 9313, 9313, -1, + 9314, 9314, 9314, -1, 9315, 9315, 9315, -1, + 9316, 9316, 9316, -1, 9317, 9317, 9317, -1, + 9318, 9318, 9318, -1, 9319, 9319, 9319, -1, + 9320, 9320, 9320, -1, 9321, 9321, 9321, -1, + 9322, 9322, 9322, -1, 9323, 9323, 9323, -1, + 9324, 9324, 9324, -1, 9325, 9325, 9325, -1, + 9326, 9326, 9326, -1, 9327, 9327, 9327, -1, + 9328, 9328, 9328, -1, 9329, 9329, 9329, -1, + 9330, 9330, 9330, -1, 9331, 9331, 9331, -1, + 9332, 9332, 9332, -1, 9333, 9333, 9333, -1, + 9334, 9334, 9334, -1, 9335, 9335, 9335, -1, + 9336, 9336, 9336, -1, 9337, 9337, 9337, -1, + 9338, 9338, 9338, -1, 9339, 9339, 9339, -1, + 9340, 9340, 9340, -1, 9341, 9341, 9341, -1, + 9342, 9342, 9342, -1, 9343, 9343, 9343, -1, + 9344, 9344, 9344, -1, 9345, 9345, 9345, -1, + 9346, 9346, 9346, -1, 9347, 9347, 9347, -1, + 9348, 9348, 9348, -1, 9349, 9349, 9349, -1, + 9350, 9350, 9350, -1, 9351, 9351, 9351, -1, + 9352, 9352, 9352, -1, 9353, 9353, 9353, -1, + 9354, 9354, 9354, -1, 9355, 9355, 9355, -1, + 9356, 9356, 9356, -1, 9357, 9357, 9357, -1, + 9358, 9358, 9358, -1, 9359, 9359, 9359, -1, + 9360, 9360, 9360, -1, 9361, 9361, 9361, -1, + 9362, 9362, 9362, -1, 9363, 9363, 9363, -1, + 9364, 9364, 9364, -1, 9365, 9365, 9365, -1, + 9366, 9366, 9366, -1, 9367, 9367, 9367, -1, + 9368, 9368, 9368, -1, 9369, 9369, 9369, -1, + 9370, 9370, 9370, -1, 9371, 9371, 9371, -1, + 9372, 9372, 9372, -1, 9373, 9373, 9373, -1, + 9374, 9374, 9374, -1, 9375, 9375, 9375, -1, + 9376, 9376, 9376, -1, 9377, 9377, 9377, -1, + 9378, 9378, 9378, -1, 9379, 9379, 9379, -1, + 9380, 9380, 9380, -1, 9381, 9381, 9381, -1, + 9382, 9382, 9382, -1, 9383, 9383, 9383, -1, + 9384, 9384, 9384, -1, 9385, 9385, 9385, -1, + 9386, 9386, 9386, -1, 9387, 9387, 9387, -1, + 9388, 9388, 9388, -1, 9389, 9389, 9389, -1, + 9390, 9390, 9390, -1, 9391, 9391, 9391, -1, + 9392, 9392, 9392, -1, 9393, 9393, 9393, -1, + 9394, 9394, 9394, -1, 9395, 9395, 9395, -1, + 9396, 9396, 9396, -1, 9397, 9397, 9397, -1, + 9398, 9398, 9398, -1, 9399, 9399, 9399, -1, + 9400, 9400, 9400, -1, 9401, 9401, 9401, -1, + 9402, 9402, 9402, -1, 9403, 9403, 9403, -1, + 9404, 9404, 9404, -1, 9405, 9405, 9405, -1, + 9406, 9406, 9406, -1, 9407, 9407, 9407, -1, + 9408, 9408, 9408, -1, 9409, 9409, 9409, -1, + 9410, 9410, 9410, -1, 9411, 9411, 9411, -1, + 9412, 9412, 9412, -1, 9413, 9413, 9413, -1, + 9414, 9414, 9414, -1, 9415, 9415, 9415, -1, + 9416, 9416, 9416, -1, 9417, 9417, 9417, -1, + 9418, 9418, 9418, -1, 9419, 9419, 9419, -1, + 9420, 9420, 9420, -1, 9421, 9421, 9421, -1, + 9422, 9422, 9422, -1, 9423, 9423, 9423, -1, + 9424, 9424, 9424, -1, 9425, 9425, 9425, -1, + 9426, 9426, 9426, -1, 9427, 9427, 9427, -1, + 9428, 9428, 9428, -1, 9429, 9429, 9429, -1, + 9430, 9430, 9430, -1, 9431, 9431, 9431, -1, + 9432, 9432, 9432, -1, 9433, 9433, 9433, -1, + 9434, 9434, 9434, -1, 9435, 9435, 9435, -1, + 9436, 9436, 9436, -1, 9437, 9437, 9437, -1, + 9438, 9438, 9438, -1, 9439, 9439, 9439, -1, + 9440, 9440, 9440, -1, 9441, 9441, 9441, -1, + 9442, 9442, 9442, -1, 9443, 9443, 9443, -1, + 9444, 9444, 9444, -1, 9445, 9445, 9445, -1, + 9446, 9446, 9446, -1, 9447, 9447, 9447, -1, + 9448, 9448, 9448, -1, 9449, 9449, 9449, -1, + 9450, 9450, 9450, -1, 9451, 9451, 9451, -1, + 9452, 9452, 9452, -1, 9453, 9453, 9453, -1, + 9454, 9454, 9454, -1, 9455, 9455, 9455, -1, + 9456, 9456, 9456, -1, 9457, 9457, 9457, -1, + 9458, 9458, 9458, -1, 9459, 9459, 9459, -1, + 9460, 9460, 9460, -1, 9461, 9461, 9461, -1, + 9462, 9462, 9462, -1, 9463, 9463, 9463, -1, + 9464, 9464, 9464, -1, 9465, 9465, 9465, -1, + 9466, 9466, 9466, -1, 9467, 9467, 9467, -1, + 9468, 9468, 9468, -1, 9469, 9469, 9469, -1, + 9470, 9470, 9470, -1, 9471, 9471, 9471, -1, + 9472, 9472, 9472, -1, 9473, 9473, 9473, -1, + 9474, 9474, 9474, -1, 9475, 9475, 9475, -1, + 9476, 9476, 9476, -1, 9477, 9477, 9477, -1, + 9478, 9478, 9478, -1, 9479, 9479, 9479, -1, + 9480, 9480, 9480, -1, 9481, 9481, 9481, -1, + 9482, 9482, 9482, -1, 9483, 9483, 9483, -1, + 9484, 9484, 9484, -1, 9485, 9485, 9485, -1, + 9486, 9486, 9486, -1, 9487, 9487, 9487, -1, + 9488, 9488, 9488, -1, 9489, 9489, 9489, -1, + 9490, 9490, 9490, -1, 9491, 9491, 9491, -1, + 9492, 9492, 9492, -1, 9493, 9493, 9493, -1, + 9494, 9494, 9494, -1, 9495, 9495, 9495, -1, + 9496, 9496, 9496, -1, 9497, 9497, 9497, -1, + 9498, 9498, 9498, -1, 9499, 9499, 9499, -1, + 9500, 9500, 9500, -1, 9501, 9501, 9501, -1, + 9502, 9502, 9502, -1, 9503, 9503, 9503, -1, + 9504, 9504, 9504, -1, 9505, 9505, 9505, -1, + 9506, 9506, 9506, -1, 9507, 9507, 9507, -1, + 9508, 9508, 9508, -1, 9509, 9509, 9509, -1, + 9510, 9510, 9510, -1, 9511, 9511, 9511, -1, + 9512, 9512, 9512, -1, 9513, 9513, 9513, -1, + 9514, 9514, 9514, -1, 9515, 9515, 9515, -1, + 9516, 9516, 9516, -1, 9517, 9517, 9517, -1, + 9518, 9518, 9518, -1, 9519, 9519, 9519, -1, + 9520, 9520, 9520, -1, 9521, 9521, 9521, -1, + 9522, 9522, 9522, -1, 9523, 9523, 9523, -1, + 9524, 9524, 9524, -1, 9525, 9525, 9525, -1, + 9526, 9526, 9526, -1, 9527, 9527, 9527, -1, + 9528, 9528, 9528, -1, 9529, 9529, 9529, -1, + 9530, 9530, 9530, -1, 9531, 9531, 9531, -1, + 9532, 9532, 9532, -1, 9533, 9533, 9533, -1, + 9534, 9534, 9534, -1, 9535, 9535, 9535, -1, + 9536, 9536, 9536, -1, 9537, 9537, 9537, -1, + 9538, 9538, 9538, -1, 9539, 9539, 9539, -1, + 9540, 9540, 9540, -1, 9541, 9541, 9541, -1, + 9542, 9542, 9542, -1, 9543, 9543, 9543, -1, + 9544, 9544, 9544, -1, 9545, 9545, 9545, -1, + 9546, 9546, 9546, -1, 9547, 9547, 9547, -1, + 9548, 9548, 9548, -1, 9549, 9549, 9549, -1, + 9550, 9550, 9550, -1, 9551, 9551, 9551, -1, + 9552, 9552, 9552, -1, 9553, 9553, 9553, -1, + 9554, 9554, 9554, -1, 9555, 9555, 9555, -1, + 9556, 9556, 9556, -1, 9557, 9557, 9557, -1, + 9558, 9558, 9558, -1, 9559, 9559, 9559, -1, + 9560, 9560, 9560, -1, 9561, 9561, 9561, -1, + 9562, 9562, 9562, -1, 9563, 9563, 9563, -1, + 9564, 9564, 9564, -1, 9565, 9565, 9565, -1, + 9566, 9566, 9566, -1, 9567, 9567, 9567, -1, + 9568, 9568, 9568, -1, 9569, 9569, 9569, -1, + 9570, 9570, 9570, -1, 9571, 9571, 9571, -1, + 9572, 9572, 9572, -1, 9573, 9573, 9573, -1, + 9574, 9574, 9574, -1, 9575, 9575, 9575, -1, + 9576, 9576, 9576, -1, 9577, 9577, 9577, -1, + 9578, 9578, 9578, -1, 9579, 9579, 9579, -1, + 9580, 9580, 9580, -1, 9581, 9581, 9581, -1, + 9582, 9582, 9582, -1, 9583, 9583, 9583, -1, + 9584, 9584, 9584, -1, 9585, 9585, 9585, -1, + 9586, 9586, 9586, -1, 9587, 9587, 9587, -1, + 9588, 9588, 9588, -1, 9589, 9589, 9589, -1, + 9590, 9590, 9590, -1, 9591, 9591, 9591, -1, + 9592, 9592, 9592, -1, 9593, 9593, 9593, -1, + 9594, 9594, 9594, -1, 9595, 9595, 9595, -1, + 9596, 9596, 9596, -1, 9597, 9597, 9597, -1, + 9598, 9598, 9598, -1, 9599, 9599, 9599, -1, + 9600, 9600, 9600, -1, 9601, 9601, 9601, -1, + 9602, 9602, 9602, -1, 9603, 9603, 9603, -1, + 9604, 9604, 9604, -1, 9605, 9605, 9605, -1, + 9606, 9606, 9606, -1, 9607, 9607, 9607, -1, + 9608, 9608, 9608, -1, 9609, 9609, 9609, -1, + 9610, 9610, 9610, -1, 9611, 9611, 9611, -1, + 9612, 9612, 9612, -1, 9613, 9613, 9613, -1, + 9614, 9614, 9614, -1, 9615, 9615, 9615, -1, + 9616, 9616, 9616, -1, 9617, 9617, 9617, -1, + 9618, 9618, 9618, -1, 9619, 9619, 9619, -1, + 9620, 9620, 9620, -1, 9621, 9621, 9621, -1, + 9622, 9622, 9622, -1, 9623, 9623, 9623, -1, + 9624, 9624, 9624, -1, 9625, 9625, 9625, -1, + 9626, 9626, 9626, -1, 9627, 9627, 9627, -1, + 9628, 9628, 9628, -1, 9629, 9629, 9629, -1, + 9630, 9630, 9630, -1, 9631, 9631, 9631, -1, + 9632, 9632, 9632, -1, 9633, 9633, 9633, -1, + 9634, 9634, 9634, -1, 9635, 9635, 9635, -1, + 9636, 9636, 9636, -1, 9637, 9637, 9637, -1, + 9638, 9638, 9638, -1, 9639, 9639, 9639, -1, + 9640, 9640, 9640, -1, 9641, 9641, 9641, -1, + 9642, 9642, 9642, -1, 9643, 9643, 9643, -1, + 9644, 9644, 9644, -1, 9645, 9645, 9645, -1, + 9646, 9646, 9646, -1, 9647, 9647, 9647, -1, + 9648, 9648, 9648, -1, 9649, 9649, 9649, -1, + 9650, 9650, 9650, -1, 9651, 9651, 9651, -1, + 9652, 9652, 9652, -1, 9653, 9653, 9653, -1, + 9654, 9654, 9654, -1, 9655, 9655, 9655, -1, + 9656, 9656, 9656, -1, 9657, 9657, 9657, -1, + 9658, 9658, 9658, -1, 9659, 9659, 9659, -1, + 9660, 9660, 9660, -1, 9661, 9661, 9661, -1, + 9662, 9662, 9662, -1, 9663, 9663, 9663, -1, + 9664, 9664, 9664, -1, 9665, 9665, 9665, -1, + 9666, 9666, 9666, -1, 9667, 9667, 9667, -1, + 9668, 9668, 9668, -1, 9669, 9669, 9669, -1, + 9670, 9670, 9670, -1, 9671, 9671, 9671, -1, + 9672, 9672, 9672, -1, 9673, 9673, 9673, -1, + 9674, 9674, 9674, -1, 9675, 9675, 9675, -1, + 9676, 9676, 9676, -1, 9677, 9677, 9677, -1, + 9678, 9678, 9678, -1, 9679, 9679, 9679, -1, + 9680, 9680, 9680, -1, 9681, 9681, 9681, -1, + 9682, 9682, 9682, -1, 9683, 9683, 9683, -1, + 9684, 9684, 9684, -1, 9685, 9685, 9685, -1, + 9686, 9686, 9686, -1, 9687, 9687, 9687, -1, + 9688, 9688, 9688, -1, 9689, 9689, 9689, -1, + 9690, 9690, 9690, -1, 9691, 9691, 9691, -1, + 9692, 9692, 9692, -1, 9693, 9693, 9693, -1, + 9694, 9694, 9694, -1, 9695, 9695, 9695, -1, + 9696, 9696, 9696, -1, 9697, 9697, 9697, -1, + 9698, 9698, 9698, -1, 9699, 9699, 9699, -1, + 9700, 9700, 9700, -1, 9701, 9701, 9701, -1, + 9702, 9702, 9702, -1, 9703, 9703, 9703, -1, + 9704, 9704, 9704, -1, 9705, 9705, 9705, -1, + 9706, 9706, 9706, -1, 9707, 9707, 9707, -1, + 9708, 9708, 9708, -1, 9709, 9709, 9709, -1, + 9710, 9710, 9710, -1, 9711, 9711, 9711, -1, + 9712, 9712, 9712, -1, 9713, 9713, 9713, -1, + 9714, 9714, 9714, -1, 9715, 9715, 9715, -1, + 9716, 9716, 9716, -1, 9717, 9717, 9717, -1, + 9718, 9718, 9718, -1, 9719, 9719, 9719, -1, + 9720, 9720, 9720, -1, 9721, 9721, 9721, -1, + 9722, 9722, 9722, -1, 9723, 9723, 9723, -1, + 9724, 9724, 9724, -1, 9725, 9725, 9725, -1, + 9726, 9726, 9726, -1, 9727, 9727, 9727, -1, + 9728, 9728, 9728, -1, 9729, 9729, 9729, -1, + 9730, 9730, 9730, -1, 9731, 9731, 9731, -1, + 9732, 9732, 9732, -1, 9733, 9733, 9733, -1, + 9734, 9734, 9734, -1, 9735, 9735, 9735, -1, + 9736, 9736, 9736, -1, 9737, 9737, 9737, -1, + 9738, 9738, 9738, -1, 9739, 9739, 9739, -1, + 9740, 9740, 9740, -1, 9741, 9741, 9741, -1, + 9742, 9742, 9742, -1, 9743, 9743, 9743, -1, + 9744, 9744, 9744, -1, 9745, 9745, 9745, -1, + 9746, 9746, 9746, -1, 9747, 9747, 9747, -1, + 9748, 9748, 9748, -1, 9749, 9749, 9749, -1, + 9750, 9750, 9750, -1, 9751, 9751, 9751, -1, + 9752, 9752, 9752, -1, 9753, 9753, 9753, -1, + 9754, 9754, 9754, -1, 9755, 9755, 9755, -1, + 9756, 9756, 9756, -1, 9757, 9757, 9757, -1, + 9758, 9758, 9758, -1, 9759, 9759, 9759, -1, + 9760, 9760, 9760, -1, 9761, 9761, 9761, -1, + 9762, 9762, 9762, -1, 9763, 9763, 9763, -1, + 9764, 9764, 9764, -1, 9765, 9765, 9765, -1, + 9766, 9766, 9766, -1, 9767, 9767, 9767, -1, + 9768, 9768, 9768, -1, 9769, 9769, 9769, -1, + 9770, 9770, 9770, -1, 9771, 9771, 9771, -1, + 9772, 9772, 9772, -1, 9773, 9773, 9773, -1, + 9774, 9774, 9774, -1, 9775, 9775, 9775, -1, + 9776, 9776, 9776, -1, 9777, 9777, 9777, -1, + 9778, 9778, 9778, -1, 9779, 9779, 9779, -1, + 9780, 9780, 9780, -1, 9781, 9781, 9781, -1, + 9782, 9782, 9782, -1, 9783, 9783, 9783, -1, + 9784, 9784, 9784, -1, 9785, 9785, 9785, -1, + 9786, 9786, 9786, -1, 9787, 9787, 9787, -1, + 9788, 9788, 9788, -1, 9789, 9789, 9789, -1, + 9790, 9790, 9790, -1, 9791, 9791, 9791, -1, + 9792, 9792, 9792, -1, 9793, 9793, 9793, -1, + 9794, 9794, 9794, -1, 9795, 9795, 9795, -1, + 9796, 9796, 9796, -1, 9797, 9797, 9797, -1, + 9798, 9798, 9798, -1, 9799, 9799, 9799, -1, + 9800, 9800, 9800, -1, 9801, 9801, 9801, -1, + 9802, 9802, 9802, -1, 9803, 9803, 9803, -1, + 9804, 9804, 9804, -1, 9805, 9805, 9805, -1, + 9806, 9806, 9806, -1, 9807, 9807, 9807, -1, + 9808, 9808, 9808, -1, 9809, 9809, 9809, -1, + 9810, 9810, 9810, -1, 9811, 9811, 9811, -1, + 9812, 9812, 9812, -1, 9813, 9813, 9813, -1, + 9814, 9814, 9814, -1, 9815, 9815, 9815, -1, + 9816, 9816, 9816, -1, 9817, 9817, 9817, -1, + 9818, 9818, 9818, -1, 9819, 9819, 9819, -1, + 9820, 9820, 9820, -1, 9821, 9821, 9821, -1, + 9822, 9822, 9822, -1, 9823, 9823, 9823, -1, + 9824, 9824, 9824, -1, 9825, 9825, 9825, -1, + 9826, 9826, 9826, -1, 9827, 9827, 9827, -1, + 9828, 9828, 9828, -1, 9829, 9829, 9829, -1, + 9830, 9830, 9830, -1, 9831, 9831, 9831, -1, + 9832, 9832, 9832, -1, 9833, 9833, 9833, -1, + 9834, 9834, 9834, -1, 9835, 9835, 9835, -1, + 9836, 9836, 9836, -1, 9837, 9837, 9837, -1, + 9838, 9838, 9838, -1, 9839, 9839, 9839, -1, + 9840, 9840, 9840, -1, 9841, 9841, 9841, -1, + 9842, 9842, 9842, -1, 9843, 9843, 9843, -1, + 9844, 9844, 9844, -1, 9845, 9845, 9845, -1, + 9846, 9846, 9846, -1, 9847, 9847, 9847, -1, + 9848, 9848, 9848, -1, 9849, 9849, 9849, -1, + 9850, 9850, 9850, -1, 9851, 9851, 9851, -1, + 9852, 9852, 9852, -1, 9853, 9853, 9853, -1, + 9854, 9854, 9854, -1, 9855, 9855, 9855, -1, + 9856, 9856, 9856, -1, 9857, 9857, 9857, -1, + 9858, 9858, 9858, -1, 9859, 9859, 9859, -1, + 9860, 9860, 9860, -1, 9861, 9861, 9861, -1, + 9862, 9862, 9862, -1, 9863, 9863, 9863, -1, + 9864, 9864, 9864, -1, 9865, 9865, 9865, -1, + 9866, 9866, 9866, -1, 9867, 9867, 9867, -1, + 9868, 9868, 9868, -1, 9869, 9869, 9869, -1, + 9870, 9870, 9870, -1, 9871, 9871, 9871, -1, + 9872, 9872, 9872, -1, 9873, 9873, 9873, -1, + 9874, 9874, 9874, -1, 9875, 9875, 9875, -1, + 9876, 9876, 9876, -1, 9877, 9877, 9877, -1, + 9878, 9878, 9878, -1, 9879, 9879, 9879, -1, + 9880, 9880, 9880, -1, 9881, 9881, 9881, -1, + 9882, 9882, 9882, -1, 9883, 9883, 9883, -1, + 9884, 9884, 9884, -1, 9885, 9885, 9885, -1, + 9886, 9886, 9886, -1, 9887, 9887, 9887, -1, + 9888, 9888, 9888, -1, 9889, 9889, 9889, -1, + 9890, 9890, 9890, -1, 9891, 9891, 9891, -1, + 9892, 9892, 9892, -1, 9893, 9893, 9893, -1, + 9894, 9894, 9894, -1, 9895, 9895, 9895, -1, + 9896, 9896, 9896, -1, 9897, 9897, 9897, -1, + 9898, 9898, 9898, -1, 9899, 9899, 9899, -1, + 9900, 9900, 9900, -1, 9901, 9901, 9901, -1, + 9902, 9902, 9902, -1, 9903, 9903, 9903, -1, + 9904, 9904, 9904, -1, 9905, 9905, 9905, -1, + 9906, 9906, 9906, -1, 9907, 9907, 9907, -1, + 9908, 9908, 9908, -1, 9909, 9909, 9909, -1, + 9910, 9910, 9910, -1, 9911, 9911, 9911, -1, + 9912, 9912, 9912, -1, 9913, 9913, 9913, -1, + 9914, 9914, 9914, -1, 9915, 9915, 9915, -1, + 9916, 9916, 9916, -1, 9917, 9917, 9917, -1, + 9918, 9918, 9918, -1, 9919, 9919, 9919, -1, + 9920, 9920, 9920, -1, 9921, 9921, 9921, -1, + 9922, 9922, 9922, -1, 9923, 9923, 9923, -1, + 9924, 9924, 9924, -1, 9925, 9925, 9925, -1, + 9926, 9926, 9926, -1, 9927, 9927, 9927, -1, + 9928, 9928, 9928, -1, 9929, 9929, 9929, -1, + 9930, 9930, 9930, -1, 9931, 9931, 9931, -1, + 9932, 9932, 9932, -1, 9933, 9933, 9933, -1, + 9934, 9934, 9934, -1, 9935, 9935, 9935, -1, + 9936, 9936, 9936, -1, 9937, 9937, 9937, -1, + 9938, 9938, 9938, -1, 9939, 9939, 9939, -1, + 9940, 9940, 9940, -1, 9941, 9941, 9941, -1, + 9942, 9942, 9942, -1, 9943, 9943, 9943, -1, + 9944, 9944, 9944, -1, 9945, 9945, 9945, -1, + 9946, 9946, 9946, -1, 9947, 9947, 9947, -1, + 9948, 9948, 9948, -1, 9949, 9949, 9949, -1, + 9950, 9950, 9950, -1, 9951, 9951, 9951, -1, + 9952, 9952, 9952, -1, 9953, 9953, 9953, -1, + 9954, 9954, 9954, -1, 9955, 9955, 9955, -1, + 9956, 9956, 9956, -1, 9957, 9957, 9957, -1, + 9958, 9958, 9958, -1, 9959, 9959, 9959, -1, + 9960, 9960, 9960, -1, 9961, 9961, 9961, -1, + 9962, 9962, 9962, -1, 9963, 9963, 9963, -1, + 9964, 9964, 9964, -1, 9965, 9965, 9965, -1, + 9966, 9966, 9966, -1, 9967, 9967, 9967, -1, + 9968, 9968, 9968, -1, 9969, 9969, 9969, -1, + 9970, 9970, 9970, -1, 9971, 9971, 9971, -1, + 9972, 9972, 9972, -1, 9973, 9973, 9973, -1, + 9974, 9974, 9974, -1, 9975, 9975, 9975, -1, + 9976, 9976, 9976, -1, 9977, 9977, 9977, -1, + 9978, 9978, 9978, -1, 9979, 9979, 9979, -1, + 9980, 9980, 9980, -1, 9981, 9981, 9981, -1, + 9982, 9982, 9982, -1, 9983, 9983, 9983, -1, + 9984, 9984, 9984, -1, 9985, 9985, 9985, -1, + 9986, 9986, 9986, -1, 9987, 9987, 9987, -1, + 9988, 9988, 9988, -1, 9989, 9989, 9989, -1, + 9990, 9990, 9990, -1, 9991, 9991, 9991, -1, + 9992, 9992, 9992, -1, 9993, 9993, 9993, -1, + 9994, 9994, 9994, -1, 9995, 9995, 9995, -1, + 9996, 9996, 9996, -1, 9997, 9997, 9997, -1, + 9998, 9998, 9998, -1, 9999, 9999, 9999, -1, + 10000, 10000, 10000, -1, 10001, 10001, 10001, -1, + 10002, 10002, 10002, -1, 10003, 10003, 10003, -1, + 10004, 10004, 10004, -1, 10005, 10005, 10005, -1, + 10006, 10006, 10006, -1, 10007, 10007, 10007, -1, + 10008, 10008, 10008, -1, 10009, 10009, 10009, -1, + 10010, 10010, 10010, -1, 10011, 10011, 10011, -1, + 10012, 10012, 10012, -1, 10013, 10013, 10013, -1, + 10014, 10014, 10014, -1, 10015, 10015, 10015, -1, + 10016, 10016, 10016, -1, 10017, 10017, 10017, -1, + 10018, 10018, 10018, -1, 10019, 10019, 10019, -1, + 10020, 10020, 10020, -1, 10021, 10021, 10021, -1, + 10022, 10022, 10022, -1, 10023, 10023, 10023, -1, + 10024, 10024, 10024, -1, 10025, 10025, 10025, -1, + 10026, 10026, 10026, -1, 10027, 10027, 10027, -1, + 10028, 10028, 10028, -1, 10029, 10029, 10029, -1, + 10030, 10030, 10030, -1, 10031, 10031, 10031, -1, + 10032, 10032, 10032, -1, 10033, 10033, 10033, -1, + 10034, 10034, 10034, -1, 10035, 10035, 10035, -1, + 10036, 10036, 10036, -1, 10037, 10037, 10037, -1, + 10038, 10038, 10038, -1, 10039, 10039, 10039, -1, + 10040, 10040, 10040, -1, 10041, 10041, 10041, -1, + 10042, 10042, 10042, -1, 10043, 10043, 10043, -1, + 10044, 10044, 10044, -1, 10045, 10045, 10045, -1, + 10046, 10046, 10046, -1, 10047, 10047, 10047, -1, + 10048, 10048, 10048, -1, 10049, 10049, 10049, -1, + 10050, 10050, 10050, -1, 10051, 10051, 10051, -1, + 10052, 10052, 10052, -1, 10053, 10053, 10053, -1, + 10054, 10054, 10054, -1, 10055, 10055, 10055, -1, + 10056, 10056, 10056, -1, 10057, 10057, 10057, -1, + 10058, 10058, 10058, -1, 10059, 10059, 10059, -1, + 10060, 10060, 10060, -1, 10061, 10061, 10061, -1, + 10062, 10062, 10062, -1, 10063, 10063, 10063, -1, + 10064, 10064, 10064, -1, 10065, 10065, 10065, -1, + 10066, 10066, 10066, -1, 10067, 10067, 10067, -1, + 10068, 10068, 10068, -1, 10069, 10069, 10069, -1, + 10070, 10070, 10070, -1, 10071, 10071, 10071, -1, + 10072, 10072, 10072, -1, 10073, 10073, 10073, -1, + 10074, 10074, 10074, -1, 10075, 10075, 10075, -1, + 10076, 10076, 10076, -1, 10077, 10077, 10077, -1, + 10078, 10078, 10078, -1, 10079, 10079, 10079, -1, + 10080, 10080, 10080, -1, 10081, 10081, 10081, -1, + 10082, 10082, 10082, -1, 10083, 10083, 10083, -1, + 10084, 10084, 10084, -1, 10085, 10085, 10085, -1, + 10086, 10086, 10086, -1, 10087, 10087, 10087, -1, + 10088, 10088, 10088, -1, 10089, 10089, 10089, -1, + 10090, 10090, 10090, -1, 10091, 10091, 10091, -1, + 10092, 10092, 10092, -1, 10093, 10093, 10093, -1, + 10094, 10094, 10094, -1, 10095, 10095, 10095, -1, + 10096, 10096, 10096, -1, 10097, 10097, 10097, -1, + 10098, 10098, 10098, -1, 10099, 10099, 10099, -1, + 10100, 10100, 10100, -1, 10101, 10101, 10101, -1, + 10102, 10102, 10102, -1, 10103, 10103, 10103, -1, + 10104, 10104, 10104, -1, 10105, 10105, 10105, -1, + 10106, 10106, 10106, -1, 10107, 10107, 10107, -1, + 10108, 10108, 10108, -1, 10109, 10109, 10109, -1, + 10110, 10110, 10110, -1, 10111, 10111, 10111, -1, + 10112, 10112, 10112, -1, 10113, 10113, 10113, -1, + 10114, 10114, 10114, -1, 10115, 10115, 10115, -1, + 10116, 10116, 10116, -1, 10117, 10117, 10117, -1, + 10118, 10118, 10118, -1, 10119, 10119, 10119, -1, + 10120, 10120, 10120, -1, 10121, 10121, 10121, -1, + 10122, 10122, 10122, -1, 10123, 10123, 10123, -1, + 10124, 10124, 10124, -1, 10125, 10125, 10125, -1, + 10126, 10126, 10126, -1, 10127, 10127, 10127, -1, + 10128, 10128, 10128, -1, 10129, 10129, 10129, -1, + 10130, 10130, 10130, -1, 10131, 10131, 10131, -1, + 10132, 10132, 10132, -1, 10133, 10133, 10133, -1, + 10134, 10134, 10134, -1, 10135, 10135, 10135, -1, + 10136, 10136, 10136, -1, 10137, 10137, 10137, -1, + 10138, 10138, 10138, -1, 10139, 10139, 10139, -1, + 10140, 10140, 10140, -1, 10141, 10141, 10141, -1, + 10142, 10142, 10142, -1, 10143, 10143, 10143, -1, + 10144, 10144, 10144, -1, 10145, 10145, 10145, -1, + 10146, 10146, 10146, -1, 10147, 10147, 10147, -1, + 10148, 10148, 10148, -1, 10149, 10149, 10149, -1, + 10150, 10150, 10150, -1, 10151, 10151, 10151, -1, + 10152, 10152, 10152, -1, 10153, 10153, 10153, -1, + 10154, 10154, 10154, -1, 10155, 10155, 10155, -1, + 10156, 10156, 10156, -1, 10157, 10157, 10157, -1, + 10158, 10158, 10158, -1, 10159, 10159, 10159, -1, + 10160, 10160, 10160, -1, 10161, 10161, 10161, -1, + 10162, 10162, 10162, -1, 10163, 10163, 10163, -1, + 10164, 10164, 10164, -1, 10165, 10165, 10165, -1, + 10166, 10166, 10166, -1, 10167, 10167, 10167, -1, + 10168, 10168, 10168, -1, 10169, 10169, 10169, -1, + 10170, 10170, 10170, -1, 10171, 10171, 10171, -1, + 10172, 10172, 10172, -1, 10173, 10173, 10173, -1, + 10174, 10174, 10174, -1, 10175, 10175, 10175, -1, + 10176, 10176, 10176, -1, 10177, 10177, 10177, -1, + 10178, 10178, 10178, -1, 10179, 10179, 10179, -1, + 10180, 10180, 10180, -1, 10181, 10181, 10181, -1, + 10182, 10182, 10182, -1, 10183, 10183, 10183, -1, + 10184, 10184, 10184, -1, 10185, 10185, 10185, -1, + 10186, 10186, 10186, -1, 10187, 10187, 10187, -1, + 10188, 10188, 10188, -1, 10189, 10189, 10189, -1, + 10190, 10190, 10190, -1, 10191, 10191, 10191, -1, + 10192, 10192, 10192, -1, 10193, 10193, 10193, -1, + 10194, 10194, 10194, -1, 10195, 10195, 10195, -1, + 10196, 10196, 10196, -1, 10197, 10197, 10197, -1, + 10198, 10198, 10198, -1, 10199, 10199, 10199, -1, + 10200, 10200, 10200, -1, 10201, 10201, 10201, -1, + 10202, 10202, 10202, -1, 10203, 10203, 10203, -1, + 10204, 10204, 10204, -1, 10205, 10205, 10205, -1, + 10206, 10206, 10206, -1, 10207, 10207, 10207, -1, + 10208, 10208, 10208, -1, 10209, 10209, 10209, -1, + 10210, 10210, 10210, -1, 10211, 10211, 10211, -1, + 10212, 10212, 10212, -1, 10213, 10213, 10213, -1, + 10214, 10214, 10214, -1, 10215, 10215, 10215, -1, + 10216, 10216, 10216, -1, 10217, 10217, 10217, -1, + 10218, 10218, 10218, -1, 10219, 10219, 10219, -1, + 10220, 10220, 10220, -1, 10221, 10221, 10221, -1, + 10222, 10222, 10222, -1, 10223, 10223, 10223, -1, + 10224, 10224, 10224, -1, 10225, 10225, 10225, -1, + 10226, 10226, 10226, -1, 10227, 10227, 10227, -1, + 10228, 10228, 10228, -1, 10229, 10229, 10229, -1, + 10230, 10230, 10230, -1, 10231, 10231, 10231, -1, + 10232, 10232, 10232, -1, 10233, 10233, 10233, -1, + 10234, 10234, 10234, -1, 10235, 10235, 10235, -1, + 10236, 10236, 10236, -1, 10237, 10237, 10237, -1, + 10238, 10238, 10238, -1, 10239, 10239, 10239, -1, + 10240, 10240, 10240, -1, 10241, 10241, 10241, -1, + 10242, 10242, 10242, -1, 10243, 10243, 10243, -1, + 10244, 10244, 10244, -1, 10245, 10245, 10245, -1, + 10246, 10246, 10246, -1, 10247, 10247, 10247, -1, + 10248, 10248, 10248, -1, 10249, 10249, 10249, -1, + 10250, 10250, 10250, -1, 10251, 10251, 10251, -1, + 10252, 10252, 10252, -1, 10253, 10253, 10253, -1, + 10254, 10254, 10254, -1, 10255, 10255, 10255, -1, + 10256, 10256, 10256, -1, 10257, 10257, 10257, -1, + 10258, 10258, 10258, -1, 10259, 10259, 10259, -1, + 10260, 10260, 10260, -1, 10261, 10261, 10261, -1, + 10262, 10262, 10262, -1, 10263, 10263, 10263, -1, + 10264, 10264, 10264, -1, 10265, 10265, 10265, -1, + 10266, 10266, 10266, -1, 10267, 10267, 10267, -1, + 10268, 10268, 10268, -1, 10269, 10269, 10269, -1, + 10270, 10270, 10270, -1, 10271, 10271, 10271, -1, + 10272, 10272, 10272, -1, 10273, 10273, 10273, -1, + 10274, 10274, 10274, -1, 10275, 10275, 10275, -1, + 10276, 10276, 10276, -1, 10277, 10277, 10277, -1, + 10278, 10278, 10278, -1, 10279, 10279, 10279, -1, + 10280, 10280, 10280, -1, 10281, 10281, 10281, -1, + 10282, 10282, 10282, -1, 10283, 10283, 10283, -1, + 10284, 10284, 10284, -1, 10285, 10285, 10285, -1, + 10286, 10286, 10286, -1, 10287, 10287, 10287, -1, + 10288, 10288, 10288, -1, 10289, 10289, 10289, -1, + 10290, 10290, 10290, -1, 10291, 10291, 10291, -1, + 10292, 10292, 10292, -1, 10293, 10293, 10293, -1, + 10294, 10294, 10294, -1, 10295, 10295, 10295, -1, + 10296, 10296, 10296, -1, 10297, 10297, 10297, -1, + 10298, 10298, 10298, -1, 10299, 10299, 10299, -1, + 10300, 10300, 10300, -1, 10301, 10301, 10301, -1, + 10302, 10302, 10302, -1, 10303, 10303, 10303, -1, + 10304, 10304, 10304, -1, 10305, 10305, 10305, -1, + 10306, 10306, 10306, -1, 10307, 10307, 10307, -1, + 10308, 10308, 10308, -1, 10309, 10309, 10309, -1, + 10310, 10310, 10310, -1, 10311, 10311, 10311, -1, + 10312, 10312, 10312, -1, 10313, 10313, 10313, -1, + 10314, 10314, 10314, -1, 10315, 10315, 10315, -1, + 10316, 10316, 10316, -1, 10317, 10317, 10317, -1, + 10318, 10318, 10318, -1, 10319, 10319, 10319, -1, + 10320, 10320, 10320, -1, 10321, 10321, 10321, -1, + 10322, 10322, 10322, -1, 10323, 10323, 10323, -1, + 10324, 10324, 10324, -1, 10325, 10325, 10325, -1, + 10326, 10326, 10326, -1, 10327, 10327, 10327, -1, + 10328, 10328, 10328, -1, 10329, 10329, 10329, -1, + 10330, 10330, 10330, -1, 10331, 10331, 10331, -1, + 10332, 10332, 10332, -1, 10333, 10333, 10333, -1, + 10334, 10334, 10334, -1, 10335, 10335, 10335, -1, + 10336, 10336, 10336, -1, 10337, 10337, 10337, -1, + 10338, 10338, 10338, -1, 10339, 10339, 10339, -1, + 10340, 10340, 10340, -1, 10341, 10341, 10341, -1, + 10342, 10342, 10342, -1, 10343, 10343, 10343, -1, + 10344, 10344, 10344, -1, 10345, 10345, 10345, -1, + 10346, 10346, 10346, -1, 10347, 10347, 10347, -1, + 10348, 10348, 10348, -1, 10349, 10349, 10349, -1, + 10350, 10350, 10350, -1, 10351, 10351, 10351, -1, + 10352, 10352, 10352, -1, 10353, 10353, 10353, -1, + 10354, 10354, 10354, -1, 10355, 10355, 10355, -1, + 10356, 10356, 10356, -1, 10357, 10357, 10357, -1, + 10358, 10358, 10358, -1, 10359, 10359, 10359, -1, + 10360, 10360, 10360, -1, 10361, 10361, 10361, -1, + 10362, 10362, 10362, -1, 10363, 10363, 10363, -1, + 10364, 10364, 10364, -1, 10365, 10365, 10365, -1, + 10366, 10366, 10366, -1, 10367, 10367, 10367, -1, + 10368, 10368, 10368, -1, 10369, 10369, 10369, -1, + 10370, 10370, 10370, -1, 10371, 10371, 10371, -1, + 10372, 10372, 10372, -1, 10373, 10373, 10373, -1, + 10374, 10374, 10374, -1, 10375, 10375, 10375, -1, + 10376, 10376, 10376, -1, 10377, 10377, 10377, -1, + 10378, 10378, 10378, -1, 10379, 10379, 10379, -1, + 10380, 10380, 10380, -1, 10381, 10381, 10381, -1, + 10382, 10382, 10382, -1, 10383, 10383, 10383, -1, + 10384, 10384, 10384, -1, 10385, 10385, 10385, -1, + 10386, 10386, 10386, -1, 10387, 10387, 10387, -1, + 10388, 10388, 10388, -1, 10389, 10389, 10389, -1, + 10390, 10390, 10390, -1, 10391, 10391, 10391, -1, + 10392, 10392, 10392, -1, 10393, 10393, 10393, -1, + 10394, 10394, 10394, -1, 10395, 10395, 10395, -1, + 10396, 10396, 10396, -1, 10397, 10397, 10397, -1, + 10398, 10398, 10398, -1, 10399, 10399, 10399, -1, + 10400, 10400, 10400, -1, 10401, 10401, 10401, -1, + 10402, 10402, 10402, -1, 10403, 10403, 10403, -1, + 10404, 10404, 10404, -1, 10405, 10405, 10405, -1, + 10406, 10406, 10406, -1, 10407, 10407, 10407, -1, + 10408, 10408, 10408, -1, 10409, 10409, 10409, -1, + 10410, 10410, 10410, -1, 10411, 10411, 10411, -1, + 10412, 10412, 10412, -1, 10413, 10413, 10413, -1, + 10414, 10414, 10414, -1, 10415, 10415, 10415, -1, + 10416, 10416, 10416, -1, 10417, 10417, 10417, -1, + 10418, 10418, 10418, -1, 10419, 10419, 10419, -1, + 10420, 10420, 10420, -1, 10421, 10421, 10421, -1, + 10422, 10422, 10422, -1, 10423, 10423, 10423, -1, + 10424, 10424, 10424, -1, 10425, 10425, 10425, -1, + 10426, 10426, 10426, -1, 10427, 10427, 10427, -1, + 10428, 10428, 10428, -1, 10429, 10429, 10429, -1, + 10430, 10430, 10430, -1, 10431, 10431, 10431, -1, + 10432, 10432, 10432, -1, 10433, 10433, 10433, -1, + 10434, 10434, 10434, -1, 10435, 10435, 10435, -1, + 10436, 10436, 10436, -1, 10437, 10437, 10437, -1, + 10438, 10438, 10438, -1, 10439, 10439, 10439, -1, + 10440, 10440, 10440, -1, 10441, 10441, 10441, -1, + 10442, 10442, 10442, -1, 10443, 10443, 10443, -1, + 10444, 10444, 10444, -1, 10445, 10445, 10445, -1, + 10446, 10446, 10446, -1, 10447, 10447, 10447, -1, + 10448, 10448, 10448, -1, 10449, 10449, 10449, -1, + 10450, 10450, 10450, -1, 10451, 10451, 10451, -1, + 10452, 10452, 10452, -1, 10453, 10453, 10453, -1, + 10454, 10454, 10454, -1, 10455, 10455, 10455, -1, + 10456, 10456, 10456, -1, 10457, 10457, 10457, -1, + 10458, 10458, 10458, -1, 10459, 10459, 10459, -1, + 10460, 10460, 10460, -1, 10461, 10461, 10461, -1, + 10462, 10462, 10462, -1, 10463, 10463, 10463, -1, + 10464, 10464, 10464, -1, 10465, 10465, 10465, -1, + 10466, 10466, 10466, -1, 10467, 10467, 10467, -1, + 10468, 10468, 10468, -1, 10469, 10469, 10469, -1, + 10470, 10470, 10470, -1, 10471, 10471, 10471, -1, + 10472, 10472, 10472, -1, 10473, 10473, 10473, -1, + 10474, 10474, 10474, -1, 10475, 10475, 10475, -1, + 10476, 10476, 10476, -1, 10477, 10477, 10477, -1, + 10478, 10478, 10478, -1, 10479, 10479, 10479, -1, + 10480, 10480, 10480, -1, 10481, 10481, 10481, -1, + 10482, 10482, 10482, -1, 10483, 10483, 10483, -1, + 10484, 10484, 10484, -1, 10485, 10485, 10485, -1, + 10486, 10486, 10486, -1, 10487, 10487, 10487, -1, + 10488, 10488, 10488, -1, 10489, 10489, 10489, -1, + 10490, 10490, 10490, -1, 10491, 10491, 10491, -1, + 10492, 10492, 10492, -1, 10493, 10493, 10493, -1, + 10494, 10494, 10494, -1, 10495, 10495, 10495, -1, + 10496, 10496, 10496, -1, 10497, 10497, 10497, -1, + 10498, 10498, 10498, -1, 10499, 10499, 10499, -1, + 10500, 10500, 10500, -1, 10501, 10501, 10501, -1, + 10502, 10502, 10502, -1, 10503, 10503, 10503, -1, + 10504, 10504, 10504, -1, 10505, 10505, 10505, -1, + 10506, 10506, 10506, -1, 10507, 10507, 10507, -1, + 10508, 10508, 10508, -1, 10509, 10509, 10509, -1, + 10510, 10510, 10510, -1, 10511, 10511, 10511, -1, + 10512, 10512, 10512, -1, 10513, 10513, 10513, -1, + 10514, 10514, 10514, -1, 10515, 10515, 10515, -1, + 10516, 10516, 10516, -1, 10517, 10517, 10517, -1, + 10518, 10518, 10518, -1, 10519, 10519, 10519, -1, + 10520, 10520, 10520, -1, 10521, 10521, 10521, -1, + 10522, 10522, 10522, -1, 10523, 10523, 10523, -1, + 10524, 10524, 10524, -1, 10525, 10525, 10525, -1, + 10526, 10526, 10526, -1, 10527, 10527, 10527, -1, + 10528, 10528, 10528, -1, 10529, 10529, 10529, -1, + 10530, 10530, 10530, -1, 10531, 10531, 10531, -1, + 10532, 10532, 10532, -1, 10533, 10533, 10533, -1, + 10534, 10534, 10534, -1, 10535, 10535, 10535, -1, + 10536, 10536, 10536, -1, 10537, 10537, 10537, -1, + 10538, 10538, 10538, -1, 10539, 10539, 10539, -1, + 10540, 10540, 10540, -1, 10541, 10541, 10541, -1, + 10542, 10542, 10542, -1, 10543, 10543, 10543, -1, + 10544, 10544, 10544, -1, 10545, 10545, 10545, -1, + 10546, 10546, 10546, -1, 10547, 10547, 10547, -1, + 10548, 10548, 10548, -1, 10549, 10549, 10549, -1, + 10550, 10550, 10550, -1, 10551, 10551, 10551, -1, + 10552, 10552, 10552, -1, 10553, 10553, 10553, -1, + 10554, 10554, 10554, -1, 10555, 10555, 10555, -1, + 10556, 10556, 10556, -1, 10557, 10557, 10557, -1, + 10558, 10558, 10558, -1, 10559, 10559, 10559, -1, + 10560, 10560, 10560, -1, 10561, 10561, 10561, -1, + 10562, 10562, 10562, -1, 10563, 10563, 10563, -1, + 10564, 10564, 10564, -1, 10565, 10565, 10565, -1, + 10566, 10566, 10566, -1, 10567, 10567, 10567, -1, + 10568, 10568, 10568, -1, 10569, 10569, 10569, -1, + 10570, 10570, 10570, -1, 10571, 10571, 10571, -1, + 10572, 10572, 10572, -1, 10573, 10573, 10573, -1, + 10574, 10574, 10574, -1, 10575, 10575, 10575, -1, + 10576, 10576, 10576, -1, 10577, 10577, 10577, -1, + 10578, 10578, 10578, -1, 10579, 10579, 10579, -1, + 10580, 10580, 10580, -1, 10581, 10581, 10581, -1, + 10582, 10582, 10582, -1, 10583, 10583, 10583, -1, + 10584, 10584, 10584, -1, 10585, 10585, 10585, -1, + 10586, 10586, 10586, -1, 10587, 10587, 10587, -1, + 10588, 10588, 10588, -1, 10589, 10589, 10589, -1, + 10590, 10590, 10590, -1, 10591, 10591, 10591, -1, + 10592, 10592, 10592, -1, 10593, 10593, 10593, -1, + 10594, 10594, 10594, -1, 10595, 10595, 10595, -1, + 10596, 10596, 10596, -1, 10597, 10597, 10597, -1, + 10598, 10598, 10598, -1, 10599, 10599, 10599, -1, + 10600, 10600, 10600, -1, 10601, 10601, 10601, -1, + 10602, 10602, 10602, -1, 10603, 10603, 10603, -1, + 10604, 10604, 10604, -1, 10605, 10605, 10605, -1, + 10606, 10606, 10606, -1, 10607, 10607, 10607, -1, + 10608, 10608, 10608, -1, 10609, 10609, 10609, -1, + 10610, 10610, 10610, -1, 10611, 10611, 10611, -1, + 10612, 10612, 10612, -1, 10613, 10613, 10613, -1, + 10614, 10614, 10614, -1, 10615, 10615, 10615, -1, + 10616, 10616, 10616, -1, 10617, 10617, 10617, -1, + 10618, 10618, 10618, -1, 10619, 10619, 10619, -1, + 10620, 10620, 10620, -1, 10621, 10621, 10621, -1, + 10622, 10622, 10622, -1, 10623, 10623, 10623, -1, + 10624, 10624, 10624, -1, 10625, 10625, 10625, -1, + 10626, 10626, 10626, -1, 10627, 10627, 10627, -1, + 10628, 10628, 10628, -1, 10629, 10629, 10629, -1, + 10630, 10630, 10630, -1, 10631, 10631, 10631, -1, + 10632, 10632, 10632, -1, 10633, 10633, 10633, -1, + 10634, 10634, 10634, -1, 10635, 10635, 10635, -1, + 10636, 10636, 10636, -1, 10637, 10637, 10637, -1, + 10638, 10638, 10638, -1, 10639, 10639, 10639, -1, + 10640, 10640, 10640, -1, 10641, 10641, 10641, -1, + 10642, 10642, 10642, -1, 10643, 10643, 10643, -1, + 10644, 10644, 10644, -1, 10645, 10645, 10645, -1, + 10646, 10646, 10646, -1, 10647, 10647, 10647, -1, + 10648, 10648, 10648, -1, 10649, 10649, 10649, -1, + 10650, 10650, 10650, -1, 10651, 10651, 10651, -1, + 10652, 10652, 10652, -1, 10653, 10653, 10653, -1, + 10654, 10654, 10654, -1, 10655, 10655, 10655, -1, + 10656, 10656, 10656, -1, 10657, 10657, 10657, -1, + 10658, 10658, 10658, -1, 10659, 10659, 10659, -1, + 10660, 10660, 10660, -1, 10661, 10661, 10661, -1, + 10662, 10662, 10662, -1, 10663, 10663, 10663, -1, + 10664, 10664, 10664, -1, 10665, 10665, 10665, -1, + 10666, 10666, 10666, -1, 10667, 10667, 10667, -1, + 10668, 10668, 10668, -1, 10669, 10669, 10669, -1, + 10670, 10670, 10670, -1, 10671, 10671, 10671, -1, + 10672, 10672, 10672, -1, 10673, 10673, 10673, -1, + 10674, 10674, 10674, -1, 10675, 10675, 10675, -1, + 10676, 10676, 10676, -1, 10677, 10677, 10677, -1, + 10678, 10678, 10678, -1, 10679, 10679, 10679, -1, + 10680, 10680, 10680, -1, 10681, 10681, 10681, -1, + 10682, 10682, 10682, -1, 10683, 10683, 10683, -1, + 10684, 10684, 10684, -1, 10685, 10685, 10685, -1, + 10686, 10686, 10686, -1, 10687, 10687, 10687, -1, + 10688, 10688, 10688, -1, 10689, 10689, 10689, -1, + 10690, 10690, 10690, -1, 10691, 10691, 10691, -1, + 10692, 10692, 10692, -1, 10693, 10693, 10693, -1, + 10694, 10694, 10694, -1, 10695, 10695, 10695, -1, + 10696, 10696, 10696, -1, 10697, 10697, 10697, -1, + 10698, 10698, 10698, -1, 10699, 10699, 10699, -1, + 10700, 10700, 10700, -1, 10701, 10701, 10701, -1, + 10702, 10702, 10702, -1, 10703, 10703, 10703, -1, + 10704, 10704, 10704, -1, 10705, 10705, 10705, -1, + 10706, 10706, 10706, -1, 10707, 10707, 10707, -1, + 10708, 10708, 10708, -1, 10709, 10709, 10709, -1, + 10710, 10710, 10710, -1, 10711, 10711, 10711, -1, + 10712, 10712, 10712, -1, 10713, 10713, 10713, -1, + 10714, 10714, 10714, -1, 10715, 10715, 10715, -1, + 10716, 10716, 10716, -1, 10717, 10717, 10717, -1, + 10718, 10718, 10718, -1, 10719, 10719, 10719, -1, + 10720, 10720, 10720, -1, 10721, 10721, 10721, -1, + 10722, 10722, 10722, -1, 10723, 10723, 10723, -1, + 10724, 10724, 10724, -1, 10725, 10725, 10725, -1, + 10726, 10726, 10726, -1, 10727, 10727, 10727, -1, + 10728, 10728, 10728, -1, 10729, 10729, 10729, -1, + 10730, 10730, 10730, -1, 10731, 10731, 10731, -1, + 10732, 10732, 10732, -1, 10733, 10733, 10733, -1, + 10734, 10734, 10734, -1, 10735, 10735, 10735, -1, + 10736, 10736, 10736, -1, 10737, 10737, 10737, -1, + 10738, 10738, 10738, -1, 10739, 10739, 10739, -1, + 10740, 10740, 10740, -1, 10741, 10741, 10741, -1, + 10742, 10742, 10742, -1, 10743, 10743, 10743, -1, + 10744, 10744, 10744, -1, 10745, 10745, 10745, -1, + 10746, 10746, 10746, -1, 10747, 10747, 10747, -1, + 10748, 10748, 10748, -1, 10749, 10749, 10749, -1, + 10750, 10750, 10750, -1, 10751, 10751, 10751, -1, + 10752, 10752, 10752, -1, 10753, 10753, 10753, -1, + 10754, 10754, 10754, -1, 10755, 10755, 10755, -1, + 10756, 10756, 10756, -1, 10757, 10757, 10757, -1, + 10758, 10758, 10758, -1, 10759, 10759, 10759, -1, + 10760, 10760, 10760, -1, 10761, 10761, 10761, -1, + 10762, 10762, 10762, -1, 10763, 10763, 10763, -1, + 10764, 10764, 10764, -1, 10765, 10765, 10765, -1, + 10766, 10766, 10766, -1, 10767, 10767, 10767, -1, + 10768, 10768, 10768, -1, 10769, 10769, 10769, -1, + 10770, 10770, 10770, -1, 10771, 10771, 10771, -1, + 10772, 10772, 10772, -1, 10773, 10773, 10773, -1, + 10774, 10774, 10774, -1, 10775, 10775, 10775, -1, + 10776, 10776, 10776, -1, 10777, 10777, 10777, -1, + 10778, 10778, 10778, -1, 10779, 10779, 10779, -1, + 10780, 10780, 10780, -1, 10781, 10781, 10781, -1, + 10782, 10782, 10782, -1, 10783, 10783, 10783, -1, + 10784, 10784, 10784, -1, 10785, 10785, 10785, -1, + 10786, 10786, 10786, -1, 10787, 10787, 10787, -1, + 10788, 10788, 10788, -1, 10789, 10789, 10789, -1, + 10790, 10790, 10790, -1, 10791, 10791, 10791, -1, + 10792, 10792, 10792, -1, 10793, 10793, 10793, -1, + 10794, 10794, 10794, -1, 10795, 10795, 10795, -1, + 10796, 10796, 10796, -1, 10797, 10797, 10797, -1, + 10798, 10798, 10798, -1, 10799, 10799, 10799, -1, + 10800, 10800, 10800, -1, 10801, 10801, 10801, -1, + 10802, 10802, 10802, -1, 10803, 10803, 10803, -1, + 10804, 10804, 10804, -1, 10805, 10805, 10805, -1, + 10806, 10806, 10806, -1, 10807, 10807, 10807, -1, + 10808, 10808, 10808, -1, 10809, 10809, 10809, -1, + 10810, 10810, 10810, -1, 10811, 10811, 10811, -1, + 10812, 10812, 10812, -1, 10813, 10813, 10813, -1, + 10814, 10814, 10814, -1, 10815, 10815, 10815, -1, + 10816, 10816, 10816, -1, 10817, 10817, 10817, -1, + 10818, 10818, 10818, -1, 10819, 10819, 10819, -1, + 10820, 10820, 10820, -1, 10821, 10821, 10821, -1, + 10822, 10822, 10822, -1, 10823, 10823, 10823, -1, + 10824, 10824, 10824, -1, 10825, 10825, 10825, -1, + 10826, 10826, 10826, -1, 10827, 10827, 10827, -1, + 10828, 10828, 10828, -1, 10829, 10829, 10829, -1, + 10830, 10830, 10830, -1, 10831, 10831, 10831, -1, + 10832, 10832, 10832, -1, 10833, 10833, 10833, -1, + 10834, 10834, 10834, -1, 10835, 10835, 10835, -1, + 10836, 10836, 10836, -1, 10837, 10837, 10837, -1, + 10838, 10838, 10838, -1, 10839, 10839, 10839, -1, + 10840, 10840, 10840, -1, 10841, 10841, 10841, -1, + 10842, 10842, 10842, -1, 10843, 10843, 10843, -1, + 10844, 10844, 10844, -1, 10845, 10845, 10845, -1, + 10846, 10846, 10846, -1, 10847, 10847, 10847, -1, + 10848, 10848, 10848, -1, 10849, 10849, 10849, -1, + 10850, 10850, 10850, -1, 10851, 10851, 10851, -1, + 10852, 10852, 10852, -1, 10853, 10853, 10853, -1, + 10854, 10854, 10854, -1, 10855, 10855, 10855, -1, + 10856, 10856, 10856, -1, 10857, 10857, 10857, -1, + 10858, 10858, 10858, -1, 10859, 10859, 10859, -1, + 10860, 10860, 10860, -1, 10861, 10861, 10861, -1, + 10862, 10862, 10862, -1, 10863, 10863, 10863, -1, + 10864, 10864, 10864, -1, 10865, 10865, 10865, -1, + 10866, 10866, 10866, -1, 10867, 10867, 10867, -1, + 10868, 10868, 10868, -1, 10869, 10869, 10869, -1, + 10870, 10870, 10870, -1, 10871, 10871, 10871, -1, + 10872, 10872, 10872, -1, 10873, 10873, 10873, -1, + 10874, 10874, 10874, -1, 10875, 10875, 10875, -1, + 10876, 10876, 10876, -1, 10877, 10877, 10877, -1, + 10878, 10878, 10878, -1, 10879, 10879, 10879, -1, + 10880, 10880, 10880, -1, 10881, 10881, 10881, -1, + 10882, 10882, 10882, -1, 10883, 10883, 10883, -1, + 10884, 10884, 10884, -1, 10885, 10885, 10885, -1, + 10886, 10886, 10886, -1, 10887, 10887, 10887, -1, + 10888, 10888, 10888, -1, 10889, 10889, 10889, -1, + 10890, 10890, 10890, -1, 10891, 10891, 10891, -1, + 10892, 10892, 10892, -1, 10893, 10893, 10893, -1, + 10894, 10894, 10894, -1, 10895, 10895, 10895, -1, + 10896, 10896, 10896, -1, 10897, 10897, 10897, -1, + 10898, 10898, 10898, -1, 10899, 10899, 10899, -1, + 10900, 10900, 10900, -1, 10901, 10901, 10901, -1, + 10902, 10902, 10902, -1, 10903, 10903, 10903, -1, + 10904, 10904, 10904, -1, 10905, 10905, 10905, -1, + 10906, 10906, 10906, -1, 10907, 10907, 10907, -1, + 10908, 10908, 10908, -1, 10909, 10909, 10909, -1, + 10910, 10910, 10910, -1, 10911, 10911, 10911, -1, + 10912, 10912, 10912, -1, 10913, 10913, 10913, -1, + 10914, 10914, 10914, -1, 10915, 10915, 10915, -1, + 10916, 10916, 10916, -1, 10917, 10917, 10917, -1, + 10918, 10918, 10918, -1, 10919, 10919, 10919, -1, + 10920, 10920, 10920, -1, 10921, 10921, 10921, -1, + 10922, 10922, 10922, -1, 10923, 10923, 10923, -1, + 10924, 10924, 10924, -1, 10925, 10925, 10925, -1, + 10926, 10926, 10926, -1, 10927, 10927, 10927, -1, + 10928, 10928, 10928, -1, 10929, 10929, 10929, -1, + 10930, 10930, 10930, -1, 10931, 10931, 10931, -1, + 10932, 10932, 10932, -1, 10933, 10933, 10933, -1, + 10934, 10934, 10934, -1, 10935, 10935, 10935, -1, + 10936, 10936, 10936, -1, 10937, 10937, 10937, -1, + 10938, 10938, 10938, -1, 10939, 10939, 10939, -1, + 10940, 10940, 10940, -1, 10941, 10941, 10941, -1, + 10942, 10942, 10942, -1, 10943, 10943, 10943, -1, + 10944, 10944, 10944, -1, 10945, 10945, 10945, -1, + 10946, 10946, 10946, -1, 10947, 10947, 10947, -1, + 10948, 10948, 10948, -1, 10949, 10949, 10949, -1, + 10950, 10950, 10950, -1, 10951, 10951, 10951, -1, + 10952, 10952, 10952, -1, 10953, 10953, 10953, -1, + 10954, 10954, 10954, -1, 10955, 10955, 10955, -1, + 10956, 10956, 10956, -1, 10957, 10957, 10957, -1, + 10958, 10958, 10958, -1, 10959, 10959, 10959, -1, + 10960, 10960, 10960, -1, 10961, 10961, 10961, -1, + 10962, 10962, 10962, -1, 10963, 10963, 10963, -1, + 10964, 10964, 10964, -1, 10965, 10965, 10965, -1, + 10966, 10966, 10966, -1, 10967, 10967, 10967, -1, + 10968, 10968, 10968, -1, 10969, 10969, 10969, -1, + 10970, 10970, 10970, -1, 10971, 10971, 10971, -1, + 10972, 10972, 10972, -1, 10973, 10973, 10973, -1, + 10974, 10974, 10974, -1, 10975, 10975, 10975, -1, + 10976, 10976, 10976, -1, 10977, 10977, 10977, -1, + 10978, 10978, 10978, -1, 10979, 10979, 10979, -1, + 10980, 10980, 10980, -1, 10981, 10981, 10981, -1, + 10982, 10982, 10982, -1, 10983, 10983, 10983, -1, + 10984, 10984, 10984, -1, 10985, 10985, 10985, -1, + 10986, 10986, 10986, -1, 10987, 10987, 10987, -1, + 10988, 10988, 10988, -1, 10989, 10989, 10989, -1, + 10990, 10990, 10990, -1, 10991, 10991, 10991, -1, + 10992, 10992, 10992, -1, 10993, 10993, 10993, -1, + 10994, 10994, 10994, -1, 10995, 10995, 10995, -1, + 10996, 10996, 10996, -1, 10997, 10997, 10997, -1, + 10998, 10998, 10998, -1, 10999, 10999, 10999, -1, + 11000, 11000, 11000, -1, 11001, 11001, 11001, -1, + 11002, 11002, 11002, -1, 11003, 11003, 11003, -1, + 11004, 11004, 11004, -1, 11005, 11005, 11005, -1, + 11006, 11006, 11006, -1, 11007, 11007, 11007, -1, + 11008, 11008, 11008, -1, 11009, 11009, 11009, -1, + 11010, 11010, 11010, -1, 11011, 11011, 11011, -1, + 11012, 11012, 11012, -1, 11013, 11013, 11013, -1, + 11014, 11014, 11014, -1, 11015, 11015, 11015, -1, + 11016, 11016, 11016, -1, 11017, 11017, 11017, -1, + 11018, 11018, 11018, -1, 11019, 11019, 11019, -1, + 11020, 11020, 11020, -1, 11021, 11021, 11021, -1, + 11022, 11022, 11022, -1, 11023, 11023, 11023, -1, + 11024, 11024, 11024, -1, 11025, 11025, 11025, -1, + 11026, 11026, 11026, -1, 11027, 11027, 11027, -1, + 11028, 11028, 11028, -1, 11029, 11029, 11029, -1, + 11030, 11030, 11030, -1, 11031, 11031, 11031, -1, + 11032, 11032, 11032, -1, 11033, 11033, 11033, -1, + 11034, 11034, 11034, -1, 11035, 11035, 11035, -1, + 11036, 11036, 11036, -1, 11037, 11037, 11037, -1, + 11038, 11038, 11038, -1, 11039, 11039, 11039, -1, + 11040, 11040, 11040, -1, 11041, 11041, 11041, -1, + 11042, 11042, 11042, -1, 11043, 11043, 11043, -1, + 11044, 11044, 11044, -1, 11045, 11045, 11045, -1, + 11046, 11046, 11046, -1, 11047, 11047, 11047, -1, + 11048, 11048, 11048, -1, 11049, 11049, 11049, -1, + 11050, 11050, 11050, -1, 11051, 11051, 11051, -1, + 11052, 11052, 11052, -1, 11053, 11053, 11053, -1, + 11054, 11054, 11054, -1, 11055, 11055, 11055, -1, + 11056, 11056, 11056, -1, 11057, 11057, 11057, -1, + 11058, 11058, 11058, -1, 11059, 11059, 11059, -1, + 11060, 11060, 11060, -1, 11061, 11061, 11061, -1, + 11062, 11062, 11062, -1, 11063, 11063, 11063, -1, + 11064, 11064, 11064, -1, 11065, 11065, 11065, -1, + 11066, 11066, 11066, -1, 11067, 11067, 11067, -1, + 11068, 11068, 11068, -1, 11069, 11069, 11069, -1, + 11070, 11070, 11070, -1, 11071, 11071, 11071, -1, + 11072, 11072, 11072, -1, 11073, 11073, 11073, -1, + 11074, 11074, 11074, -1, 11075, 11075, 11075, -1, + 11076, 11076, 11076, -1, 11077, 11077, 11077, -1, + 11078, 11078, 11078, -1, 11079, 11079, 11079, -1, + 11080, 11080, 11080, -1, 11081, 11081, 11081, -1, + 11082, 11082, 11082, -1, 11083, 11083, 11083, -1, + 11084, 11084, 11084, -1, 11085, 11085, 11085, -1, + 11086, 11086, 11086, -1, 11087, 11087, 11087, -1, + 11088, 11088, 11088, -1, 11089, 11089, 11089, -1, + 11090, 11090, 11090, -1, 11091, 11091, 11091, -1, + 11092, 11092, 11092, -1, 11093, 11093, 11093, -1, + 11094, 11094, 11094, -1, 11095, 11095, 11095, -1, + 11096, 11096, 11096, -1, 11097, 11097, 11097, -1, + 11098, 11098, 11098, -1, 11099, 11099, 11099, -1, + 11100, 11100, 11100, -1, 11101, 11101, 11101, -1, + 11102, 11102, 11102, -1, 11103, 11103, 11103, -1, + 11104, 11104, 11104, -1, 11105, 11105, 11105, -1, + 11106, 11106, 11106, -1, 11107, 11107, 11107, -1, + 11108, 11108, 11108, -1, 11109, 11109, 11109, -1, + 11110, 11110, 11110, -1, 11111, 11111, 11111, -1, + 11112, 11112, 11112, -1, 11113, 11113, 11113, -1, + 11114, 11114, 11114, -1, 11115, 11115, 11115, -1, + 11116, 11116, 11116, -1, 11117, 11117, 11117, -1, + 11118, 11118, 11118, -1, 11119, 11119, 11119, -1, + 11120, 11120, 11120, -1, 11121, 11121, 11121, -1, + 11122, 11122, 11122, -1, 11123, 11123, 11123, -1, + 11124, 11124, 11124, -1, 11125, 11125, 11125, -1, + 11126, 11126, 11126, -1, 11127, 11127, 11127, -1, + 11128, 11128, 11128, -1, 11129, 11129, 11129, -1, + 11130, 11130, 11130, -1, 11131, 11131, 11131, -1, + 11132, 11132, 11132, -1, 11133, 11133, 11133, -1, + 11134, 11134, 11134, -1, 11135, 11135, 11135, -1, + 11136, 11136, 11136, -1, 11137, 11137, 11137, -1, + 11138, 11138, 11138, -1, 11139, 11139, 11139, -1, + 11140, 11140, 11140, -1, 11141, 11141, 11141, -1, + 11142, 11142, 11142, -1, 11143, 11143, 11143, -1, + 11144, 11144, 11144, -1, 11145, 11145, 11145, -1, + 11146, 11146, 11146, -1, 11147, 11147, 11147, -1, + 11148, 11148, 11148, -1, 11149, 11149, 11149, -1, + 11150, 11150, 11150, -1, 11151, 11151, 11151, -1, + 11152, 11152, 11152, -1, 11153, 11153, 11153, -1, + 11154, 11154, 11154, -1, 11155, 11155, 11155, -1, + 11156, 11156, 11156, -1, 11157, 11157, 11157, -1, + 11158, 11158, 11158, -1, 11159, 11159, 11159, -1, + 11160, 11160, 11160, -1, 11161, 11161, 11161, -1, + 11162, 11162, 11162, -1, 11163, 11163, 11163, -1, + 11164, 11164, 11164, -1, 11165, 11165, 11165, -1, + 11166, 11166, 11166, -1, 11167, 11167, 11167, -1, + 11168, 11168, 11168, -1, 11169, 11169, 11169, -1, + 11170, 11170, 11170, -1, 11171, 11171, 11171, -1, + 11172, 11172, 11172, -1, 11173, 11173, 11173, -1, + 11174, 11174, 11174, -1, 11175, 11175, 11175, -1, + 11176, 11176, 11176, -1, 11177, 11177, 11177, -1, + 11178, 11178, 11178, -1, 11179, 11179, 11179, -1, + 11180, 11180, 11180, -1, 11181, 11181, 11181, -1, + 11182, 11182, 11182, -1, 11183, 11183, 11183, -1, + 11184, 11184, 11184, -1, 11185, 11185, 11185, -1, + 11186, 11186, 11186, -1, 11187, 11187, 11187, -1, + 11188, 11188, 11188, -1, 11189, 11189, 11189, -1, + 11190, 11190, 11190, -1, 11191, 11191, 11191, -1, + 11192, 11192, 11192, -1, 11193, 11193, 11193, -1, + 11194, 11194, 11194, -1, 11195, 11195, 11195, -1, + 11196, 11196, 11196, -1, 11197, 11197, 11197, -1, + 11198, 11198, 11198, -1, 11199, 11199, 11199, -1, + 11200, 11200, 11200, -1, 11201, 11201, 11201, -1, + 11202, 11202, 11202, -1, 11203, 11203, 11203, -1, + 11204, 11204, 11204, -1, 11205, 11205, 11205, -1, + 11206, 11206, 11206, -1, 11207, 11207, 11207, -1, + 11208, 11208, 11208, -1, 11209, 11209, 11209, -1, + 11210, 11210, 11210, -1, 11211, 11211, 11211, -1, + 11212, 11212, 11212, -1, 11213, 11213, 11213, -1, + 11214, 11214, 11214, -1, 11215, 11215, 11215, -1, + 11216, 11216, 11216, -1, 11217, 11217, 11217, -1, + 11218, 11218, 11218, -1, 11219, 11219, 11219, -1, + 11220, 11220, 11220, -1, 11221, 11221, 11221, -1, + 11222, 11222, 11222, -1, 11223, 11223, 11223, -1, + 11224, 11224, 11224, -1, 11225, 11225, 11225, -1, + 11226, 11226, 11226, -1, 11227, 11227, 11227, -1, + 11228, 11228, 11228, -1, 11229, 11229, 11229, -1, + 11230, 11230, 11230, -1, 11231, 11231, 11231, -1, + 11232, 11232, 11232, -1, 11233, 11233, 11233, -1, + 11234, 11234, 11234, -1, 11235, 11235, 11235, -1, + 11236, 11236, 11236, -1, 11237, 11237, 11237, -1, + 11238, 11238, 11238, -1, 11239, 11239, 11239, -1, + 11240, 11240, 11240, -1, 11241, 11241, 11241, -1, + 11242, 11242, 11242, -1, 11243, 11243, 11243, -1, + 11244, 11244, 11244, -1, 11245, 11245, 11245, -1, + 11246, 11246, 11246, -1, 11247, 11247, 11247, -1, + 11248, 11248, 11248, -1, 11249, 11249, 11249, -1, + 11250, 11250, 11250, -1, 11251, 11251, 11251, -1, + 11252, 11252, 11252, -1, 11253, 11253, 11253, -1, + 11254, 11254, 11254, -1, 11255, 11255, 11255, -1, + 11256, 11256, 11256, -1, 11257, 11257, 11257, -1, + 11258, 11258, 11258, -1, 11259, 11259, 11259, -1, + 11260, 11260, 11260, -1, 11261, 11261, 11261, -1, + 11262, 11262, 11262, -1, 11263, 11263, 11263, -1, + 11264, 11264, 11264, -1, 11265, 11265, 11265, -1, + 11266, 11266, 11266, -1, 11267, 11267, 11267, -1, + 11268, 11268, 11268, -1, 11269, 11269, 11269, -1, + 11270, 11270, 11270, -1, 11271, 11271, 11271, -1, + 11272, 11272, 11272, -1, 11273, 11273, 11273, -1, + 11274, 11274, 11274, -1, 11275, 11275, 11275, -1, + 11276, 11276, 11276, -1, 11277, 11277, 11277, -1, + 11278, 11278, 11278, -1, 11279, 11279, 11279, -1, + 11280, 11280, 11280, -1, 11281, 11281, 11281, -1, + 11282, 11282, 11282, -1, 11283, 11283, 11283, -1, + 11284, 11284, 11284, -1, 11285, 11285, 11285, -1, + 11286, 11286, 11286, -1, 11287, 11287, 11287, -1, + 11288, 11288, 11288, -1, 11289, 11289, 11289, -1, + 11290, 11290, 11290, -1, 11291, 11291, 11291, -1, + 11292, 11292, 11292, -1, 11293, 11293, 11293, -1, + 11294, 11294, 11294, -1, 11295, 11295, 11295, -1, + 11296, 11296, 11296, -1, 11297, 11297, 11297, -1, + 11298, 11298, 11298, -1, 11299, 11299, 11299, -1, + 11300, 11300, 11300, -1, 11301, 11301, 11301, -1, + 11302, 11302, 11302, -1, 11303, 11303, 11303, -1, + 11304, 11304, 11304, -1, 11305, 11305, 11305, -1, + 11306, 11306, 11306, -1, 11307, 11307, 11307, -1, + 11308, 11308, 11308, -1, 11309, 11309, 11309, -1, + 11310, 11310, 11310, -1, 11311, 11311, 11311, -1, + 11312, 11312, 11312, -1, 11313, 11313, 11313, -1, + 11314, 11314, 11314, -1, 11315, 11315, 11315, -1, + 11316, 11316, 11316, -1, 11317, 11317, 11317, -1, + 11318, 11318, 11318, -1, 11319, 11319, 11319, -1, + 11320, 11320, 11320, -1, 11321, 11321, 11321, -1, + 11322, 11322, 11322, -1, 11323, 11323, 11323, -1, + 11324, 11324, 11324, -1, 11325, 11325, 11325, -1, + 11326, 11326, 11326, -1, 11327, 11327, 11327, -1, + 11328, 11328, 11328, -1, 11329, 11329, 11329, -1, + 11330, 11330, 11330, -1, 11331, 11331, 11331, -1, + 11332, 11332, 11332, -1, 11333, 11333, 11333, -1, + 11334, 11334, 11334, -1, 11335, 11335, 11335, -1, + 11336, 11336, 11336, -1, 11337, 11337, 11337, -1, + 11338, 11338, 11338, -1, 11339, 11339, 11339, -1, + 11340, 11340, 11340, -1, 11341, 11341, 11341, -1, + 11342, 11342, 11342, -1, 11343, 11343, 11343, -1, + 11344, 11344, 11344, -1, 11345, 11345, 11345, -1, + 11346, 11346, 11346, -1, 11347, 11347, 11347, -1, + 11348, 11348, 11348, -1, 11349, 11349, 11349, -1, + 11350, 11350, 11350, -1, 11351, 11351, 11351, -1, + 11352, 11352, 11352, -1, 11353, 11353, 11353, -1, + 11354, 11354, 11354, -1, 11355, 11355, 11355, -1, + 11356, 11356, 11356, -1, 11357, 11357, 11357, -1, + 11358, 11358, 11358, -1, 11359, 11359, 11359, -1, + 11360, 11360, 11360, -1, 11361, 11361, 11361, -1, + 11362, 11362, 11362, -1, 11363, 11363, 11363, -1, + 11364, 11364, 11364, -1, 11365, 11365, 11365, -1, + 11366, 11366, 11366, -1, 11367, 11367, 11367, -1, + 11368, 11368, 11368, -1, 11369, 11369, 11369, -1, + 11370, 11370, 11370, -1, 11371, 11371, 11371, -1, + 11372, 11372, 11372, -1, 11373, 11373, 11373, -1, + 11374, 11374, 11374, -1, 11375, 11375, 11375, -1, + 11376, 11376, 11376, -1, 11377, 11377, 11377, -1, + 11378, 11378, 11378, -1, 11379, 11379, 11379, -1, + 11380, 11380, 11380, -1, 11381, 11381, 11381, -1, + 11382, 11382, 11382, -1, 11383, 11383, 11383, -1, + 11384, 11384, 11384, -1, 11385, 11385, 11385, -1, + 11386, 11386, 11386, -1, 11387, 11387, 11387, -1, + 11388, 11388, 11388, -1, 11389, 11389, 11389, -1, + 11390, 11390, 11390, -1, 11391, 11391, 11391, -1, + 11392, 11392, 11392, -1, 11393, 11393, 11393, -1, + 11394, 11394, 11394, -1, 11395, 11395, 11395, -1, + 11396, 11396, 11396, -1, 11397, 11397, 11397, -1, + 11398, 11398, 11398, -1, 11399, 11399, 11399, -1, + 11400, 11400, 11400, -1, 11401, 11401, 11401, -1, + 11402, 11402, 11402, -1, 11403, 11403, 11403, -1, + 11404, 11404, 11404, -1, 11405, 11405, 11405, -1, + 11406, 11406, 11406, -1, 11407, 11407, 11407, -1, + 11408, 11408, 11408, -1, 11409, 11409, 11409, -1, + 11410, 11410, 11410, -1, 11411, 11411, 11411, -1, + 11412, 11412, 11412, -1, 11413, 11413, 11413, -1, + 11414, 11414, 11414, -1, 11415, 11415, 11415, -1, + 11416, 11416, 11416, -1, 11417, 11417, 11417, -1, + 11418, 11418, 11418, -1, 11419, 11419, 11419, -1, + 11420, 11420, 11420, -1, 11421, 11421, 11421, -1, + 11422, 11422, 11422, -1, 11423, 11423, 11423, -1, + 11424, 11424, 11424, -1, 11425, 11425, 11425, -1, + 11426, 11426, 11426, -1, 11427, 11427, 11427, -1, + 11428, 11428, 11428, -1, 11429, 11429, 11429, -1, + 11430, 11430, 11430, -1, 11431, 11431, 11431, -1, + 11432, 11432, 11432, -1, 11433, 11433, 11433, -1, + 11434, 11434, 11434, -1, 11435, 11435, 11435, -1, + 11436, 11436, 11436, -1, 11437, 11437, 11437, -1, + 11438, 11438, 11438, -1, 11439, 11439, 11439, -1, + 11440, 11440, 11440, -1, 11441, 11441, 11441, -1, + 11442, 11442, 11442, -1, 11443, 11443, 11443, -1, + 11444, 11444, 11444, -1, 11445, 11445, 11445, -1, + 11446, 11446, 11446, -1, 11447, 11447, 11447, -1, + 11448, 11448, 11448, -1, 11449, 11449, 11449, -1, + 11450, 11450, 11450, -1, 11451, 11451, 11451, -1, + 11452, 11452, 11452, -1, 11453, 11453, 11453, -1, + 11454, 11454, 11454, -1, 11455, 11455, 11455, -1, + 11456, 11456, 11456, -1, 11457, 11457, 11457, -1, + 11458, 11458, 11458, -1, 11459, 11459, 11459, -1, + 11460, 11460, 11460, -1, 11461, 11461, 11461, -1, + 11462, 11462, 11462, -1, 11463, 11463, 11463, -1, + 11464, 11464, 11464, -1, 11465, 11465, 11465, -1, + 11466, 11466, 11466, -1, 11467, 11467, 11467, -1, + 11468, 11468, 11468, -1, 11469, 11469, 11469, -1, + 11470, 11470, 11470, -1, 11471, 11471, 11471, -1, + 11472, 11472, 11472, -1, 11473, 11473, 11473, -1, + 11474, 11474, 11474, -1, 11475, 11475, 11475, -1, + 11476, 11476, 11476, -1, 11477, 11477, 11477, -1, + 11478, 11478, 11478, -1, 11479, 11479, 11479, -1, + 11480, 11480, 11480, -1, 11481, 11481, 11481, -1, + 11482, 11482, 11482, -1, 11483, 11483, 11483, -1, + 11484, 11484, 11484, -1, 11485, 11485, 11485, -1, + 11486, 11486, 11486, -1, 11487, 11487, 11487, -1, + 11488, 11488, 11488, -1, 11489, 11489, 11489, -1, + 11490, 11490, 11490, -1, 11491, 11491, 11491, -1, + 11492, 11492, 11492, -1, 11493, 11493, 11493, -1, + 11494, 11494, 11494, -1, 11495, 11495, 11495, -1, + 11496, 11496, 11496, -1, 11497, 11497, 11497, -1, + 11498, 11498, 11498, -1, 11499, 11499, 11499, -1, + 11500, 11500, 11500, -1, 11501, 11501, 11501, -1, + 11502, 11502, 11502, -1, 11503, 11503, 11503, -1, + 11504, 11504, 11504, -1, 11505, 11505, 11505, -1, + 11506, 11506, 11506, -1, 11507, 11507, 11507, -1, + 11508, 11508, 11508, -1, 11509, 11509, 11509, -1, + 11510, 11510, 11510, -1, 11511, 11511, 11511, -1, + 11512, 11512, 11512, -1, 11513, 11513, 11513, -1, + 11514, 11514, 11514, -1, 11515, 11515, 11515, -1, + 11516, 11516, 11516, -1, 11517, 11517, 11517, -1, + 11518, 11518, 11518, -1, 11519, 11519, 11519, -1, + 11520, 11520, 11520, -1, 11521, 11521, 11521, -1, + 11522, 11522, 11522, -1, 11523, 11523, 11523, -1, + 11524, 11524, 11524, -1, 11525, 11525, 11525, -1, + 11526, 11526, 11526, -1, 11527, 11527, 11527, -1, + 11528, 11528, 11528, -1, 11529, 11529, 11529, -1, + 11530, 11530, 11530, -1, 11531, 11531, 11531, -1, + 11532, 11532, 11532, -1, 11533, 11533, 11533, -1, + 11534, 11534, 11534, -1, 11535, 11535, 11535, -1, + 11536, 11536, 11536, -1, 11537, 11537, 11537, -1, + 11538, 11538, 11538, -1, 11539, 11539, 11539, -1, + 11540, 11540, 11540, -1, 11541, 11541, 11541, -1, + 11542, 11542, 11542, -1, 11543, 11543, 11543, -1, + 11544, 11544, 11544, -1, 11545, 11545, 11545, -1, + 11546, 11546, 11546, -1, 11547, 11547, 11547, -1, + 11548, 11548, 11548, -1, 11549, 11549, 11549, -1, + 11550, 11550, 11550, -1, 11551, 11551, 11551, -1, + 11552, 11552, 11552, -1, 11553, 11553, 11553, -1, + 11554, 11554, 11554, -1, 11555, 11555, 11555, -1, + 11556, 11556, 11556, -1, 11557, 11557, 11557, -1, + 11558, 11558, 11558, -1, 11559, 11559, 11559, -1, + 11560, 11560, 11560, -1, 11561, 11561, 11561, -1, + 11562, 11562, 11562, -1, 11563, 11563, 11563, -1, + 11564, 11564, 11564, -1, 11565, 11565, 11565, -1, + 11566, 11566, 11566, -1, 11567, 11567, 11567, -1, + 11568, 11568, 11568, -1, 11569, 11569, 11569, -1, + 11570, 11570, 11570, -1, 11571, 11571, 11571, -1, + 11572, 11572, 11572, -1, 11573, 11573, 11573, -1, + 11574, 11574, 11574, -1, 11575, 11575, 11575, -1, + 11576, 11576, 11576, -1, 11577, 11577, 11577, -1, + 11578, 11578, 11578, -1, 11579, 11579, 11579, -1, + 11580, 11580, 11580, -1, 11581, 11581, 11581, -1, + 11582, 11582, 11582, -1, 11583, 11583, 11583, -1, + 11584, 11584, 11584, -1, 11585, 11585, 11585, -1, + 11586, 11586, 11586, -1, 11587, 11587, 11587, -1, + 11588, 11588, 11588, -1, 11589, 11589, 11589, -1, + 11590, 11590, 11590, -1, 11591, 11591, 11591, -1, + 11592, 11592, 11592, -1, 11593, 11593, 11593, -1, + 11594, 11594, 11594, -1, 11595, 11595, 11595, -1, + 11596, 11596, 11596, -1, 11597, 11597, 11597, -1, + 11598, 11598, 11598, -1, 11599, 11599, 11599, -1, + 11600, 11600, 11600, -1, 11601, 11601, 11601, -1, + 11602, 11602, 11602, -1, 11603, 11603, 11603, -1, + 11604, 11604, 11604, -1, 11605, 11605, 11605, -1, + 11606, 11606, 11606, -1, 11607, 11607, 11607, -1, + 11608, 11608, 11608, -1, 11609, 11609, 11609, -1, + 11610, 11610, 11610, -1, 11611, 11611, 11611, -1, + 11612, 11612, 11612, -1, 11613, 11613, 11613, -1, + 11614, 11614, 11614, -1, 11615, 11615, 11615, -1, + 11616, 11616, 11616, -1, 11617, 11617, 11617, -1, + 11618, 11618, 11618, -1, 11619, 11619, 11619, -1, + 11620, 11620, 11620, -1, 11621, 11621, 11621, -1, + 11622, 11622, 11622, -1, 11623, 11623, 11623, -1, + 11624, 11624, 11624, -1, 11625, 11625, 11625, -1, + 11626, 11626, 11626, -1, 11627, 11627, 11627, -1, + 11628, 11628, 11628, -1, 11629, 11629, 11629, -1, + 11630, 11630, 11630, -1, 11631, 11631, 11631, -1, + 11632, 11632, 11632, -1, 11633, 11633, 11633, -1, + 11634, 11634, 11634, -1, 11635, 11635, 11635, -1, + 11636, 11636, 11636, -1, 11637, 11637, 11637, -1, + 11638, 11638, 11638, -1, 11639, 11639, 11639, -1, + 11640, 11640, 11640, -1, 11641, 11641, 11641, -1, + 11642, 11642, 11642, -1, 11643, 11643, 11643, -1, + 11644, 11644, 11644, -1, 11645, 11645, 11645, -1, + 11646, 11646, 11646, -1, 11647, 11647, 11647, -1, + 11648, 11648, 11648, -1, 11649, 11649, 11649, -1, + 11650, 11650, 11650, -1, 11651, 11651, 11651, -1, + 11652, 11652, 11652, -1, 11653, 11653, 11653, -1, + 11654, 11654, 11654, -1, 11655, 11655, 11655, -1, + 11656, 11656, 11656, -1, 11657, 11657, 11657, -1, + 11658, 11658, 11658, -1, 11659, 11659, 11659, -1, + 11660, 11660, 11660, -1, 11661, 11661, 11661, -1, + 11662, 11662, 11662, -1, 11663, 11663, 11663, -1, + 11664, 11664, 11664, -1, 11665, 11665, 11665, -1, + 11666, 11666, 11666, -1, 11667, 11667, 11667, -1, + 11668, 11668, 11668, -1, 11669, 11669, 11669, -1, + 11670, 11670, 11670, -1, 11671, 11671, 11671, -1, + 11672, 11672, 11672, -1, 11673, 11673, 11673, -1, + 11674, 11674, 11674, -1, 11675, 11675, 11675, -1, + 11676, 11676, 11676, -1, 11677, 11677, 11677, -1, + 11678, 11678, 11678, -1, 11679, 11679, 11679, -1, + 11680, 11680, 11680, -1, 11681, 11681, 11681, -1, + 11682, 11682, 11682, -1, 11683, 11683, 11683, -1, + 11684, 11684, 11684, -1, 11685, 11685, 11685, -1, + 11686, 11686, 11686, -1, 11687, 11687, 11687, -1, + 11688, 11688, 11688, -1, 11689, 11689, 11689, -1, + 11690, 11690, 11690, -1, 11691, 11691, 11691, -1, + 11692, 11692, 11692, -1, 11693, 11693, 11693, -1, + 11694, 11694, 11694, -1, 11695, 11695, 11695, -1, + 11696, 11696, 11696, -1, 11697, 11697, 11697, -1, + 11698, 11698, 11698, -1, 11699, 11699, 11699, -1, + 11700, 11700, 11700, -1, 11701, 11701, 11701, -1, + 11702, 11702, 11702, -1, 11703, 11703, 11703, -1, + 11704, 11704, 11704, -1, 11705, 11705, 11705, -1, + 11706, 11706, 11706, -1, 11707, 11707, 11707, -1, + 11708, 11708, 11708, -1, 11709, 11709, 11709, -1, + 11710, 11710, 11710, -1, 11711, 11711, 11711, -1, + 11712, 11712, 11712, -1, 11713, 11713, 11713, -1, + 11714, 11714, 11714, -1, 11715, 11715, 11715, -1, + 11716, 11716, 11716, -1, 11717, 11717, 11717, -1, + 11718, 11718, 11718, -1, 11719, 11719, 11719, -1, + 11720, 11720, 11720, -1, 11721, 11721, 11721, -1, + 11722, 11722, 11722, -1, 11723, 11723, 11723, -1, + 11724, 11724, 11724, -1, 11725, 11725, 11725, -1, + 11726, 11726, 11726, -1, 11727, 11727, 11727, -1, + 11728, 11728, 11728, -1, 11729, 11729, 11729, -1, + 11730, 11730, 11730, -1, 11731, 11731, 11731, -1, + 11732, 11732, 11732, -1, 11733, 11733, 11733, -1, + 11734, 11734, 11734, -1, 11735, 11735, 11735, -1, + 11736, 11736, 11736, -1, 11737, 11737, 11737, -1, + 11738, 11738, 11738, -1, 11739, 11739, 11739, -1, + 11740, 11740, 11740, -1, 11741, 11741, 11741, -1, + 11742, 11742, 11742, -1, 11743, 11743, 11743, -1, + 11744, 11744, 11744, -1, 11745, 11745, 11745, -1, + 11746, 11746, 11746, -1, 11747, 11747, 11747, -1, + 11748, 11748, 11748, -1, 11749, 11749, 11749, -1, + 11750, 11750, 11750, -1, 11751, 11751, 11751, -1, + 11752, 11752, 11752, -1, 11753, 11753, 11753, -1, + 11754, 11754, 11754, -1, 11755, 11755, 11755, -1, + 11756, 11756, 11756, -1, 11757, 11757, 11757, -1, + 11758, 11758, 11758, -1, 11759, 11759, 11759, -1, + 11760, 11760, 11760, -1, 11761, 11761, 11761, -1, + 11762, 11762, 11762, -1, 11763, 11763, 11763, -1, + 11764, 11764, 11764, -1, 11765, 11765, 11765, -1, + 11766, 11766, 11766, -1, 11767, 11767, 11767, -1, + 11768, 11768, 11768, -1, 11769, 11769, 11769, -1, + 11770, 11770, 11770, -1, 11771, 11771, 11771, -1, + 11772, 11772, 11772, -1, 11773, 11773, 11773, -1, + 11774, 11774, 11774, -1, 11775, 11775, 11775, -1, + 11776, 11776, 11776, -1, 11777, 11777, 11777, -1, + 11778, 11778, 11778, -1, 11779, 11779, 11779, -1, + 11780, 11780, 11780, -1, 11781, 11781, 11781, -1, + 11782, 11782, 11782, -1, 11783, 11783, 11783, -1, + 11784, 11784, 11784, -1, 11785, 11785, 11785, -1, + 11786, 11786, 11786, -1, 11787, 11787, 11787, -1, + 11788, 11788, 11788, -1, 11789, 11789, 11789, -1, + 11790, 11790, 11790, -1, 11791, 11791, 11791, -1, + 11792, 11792, 11792, -1, 11793, 11793, 11793, -1, + 11794, 11794, 11794, -1, 11795, 11795, 11795, -1, + 11796, 11796, 11796, -1, 11797, 11797, 11797, -1, + 11798, 11798, 11798, -1, 11799, 11799, 11799, -1, + 11800, 11800, 11800, -1, 11801, 11801, 11801, -1, + 11802, 11802, 11802, -1, 11803, 11803, 11803, -1, + 11804, 11804, 11804, -1, 11805, 11805, 11805, -1, + 11806, 11806, 11806, -1, 11807, 11807, 11807, -1, + 11808, 11808, 11808, -1, 11809, 11809, 11809, -1, + 11810, 11810, 11810, -1, 11811, 11811, 11811, -1, + 11812, 11812, 11812, -1, 11813, 11813, 11813, -1, + 11814, 11814, 11814, -1, 11815, 11815, 11815, -1, + 11816, 11816, 11816, -1, 11817, 11817, 11817, -1, + 11818, 11818, 11818, -1, 11819, 11819, 11819, -1, + 11820, 11820, 11820, -1, 11821, 11821, 11821, -1, + 11822, 11822, 11822, -1, 11823, 11823, 11823, -1, + 11824, 11824, 11824, -1, 11825, 11825, 11825, -1, + 11826, 11826, 11826, -1, 11827, 11827, 11827, -1, + 11828, 11828, 11828, -1, 11829, 11829, 11829, -1, + 11830, 11830, 11830, -1, 11831, 11831, 11831, -1, + 11832, 11832, 11832, -1, 11833, 11833, 11833, -1, + 11834, 11834, 11834, -1, 11835, 11835, 11835, -1, + 11836, 11836, 11836, -1, 11837, 11837, 11837, -1, + 11838, 11838, 11838, -1, 11839, 11839, 11839, -1, + 11840, 11840, 11840, -1, 11841, 11841, 11841, -1, + 11842, 11842, 11842, -1, 11843, 11843, 11843, -1, + 11844, 11844, 11844, -1, 11845, 11845, 11845, -1, + 11846, 11846, 11846, -1, 11847, 11847, 11847, -1, + 11848, 11848, 11848, -1, 11849, 11849, 11849, -1, + 11850, 11850, 11850, -1, 11851, 11851, 11851, -1, + 11852, 11852, 11852, -1, 11853, 11853, 11853, -1, + 11854, 11854, 11854, -1, 11855, 11855, 11855, -1, + 11856, 11856, 11856, -1, 11857, 11857, 11857, -1, + 11858, 11858, 11858, -1, 11859, 11859, 11859, -1, + 11860, 11860, 11860, -1, 11861, 11861, 11861, -1, + 11862, 11862, 11862, -1, 11863, 11863, 11863, -1, + 11864, 11864, 11864, -1, 11865, 11865, 11865, -1, + 11866, 11866, 11866, -1, 11867, 11867, 11867, -1, + 11868, 11868, 11868, -1, 11869, 11869, 11869, -1, + 11870, 11870, 11870, -1, 11871, 11871, 11871, -1, + 11872, 11872, 11872, -1, 11873, 11873, 11873, -1, + 11874, 11874, 11874, -1, 11875, 11875, 11875, -1, + 11876, 11876, 11876, -1, 11877, 11877, 11877, -1, + 11878, 11878, 11878, -1, 11879, 11879, 11879, -1, + 11880, 11880, 11880, -1, 11881, 11881, 11881, -1, + 11882, 11882, 11882, -1, 11883, 11883, 11883, -1, + 11884, 11884, 11884, -1, 11885, 11885, 11885, -1, + 11886, 11886, 11886, -1, 11887, 11887, 11887, -1, + 11888, 11888, 11888, -1, 11889, 11889, 11889, -1, + 11890, 11890, 11890, -1, 11891, 11891, 11891, -1, + 11892, 11892, 11892, -1, 11893, 11893, 11893, -1, + 11894, 11894, 11894, -1, 11895, 11895, 11895, -1, + 11896, 11896, 11896, -1, 11897, 11897, 11897, -1, + 11898, 11898, 11898, -1, 11899, 11899, 11899, -1, + 11900, 11900, 11900, -1, 11901, 11901, 11901, -1, + 11902, 11902, 11902, -1, 11903, 11903, 11903, -1, + 11904, 11904, 11904, -1, 11905, 11905, 11905, -1, + 11906, 11906, 11906, -1, 11907, 11907, 11907, -1, + 11908, 11908, 11908, -1, 11909, 11909, 11909, -1, + 11910, 11910, 11910, -1, 11911, 11911, 11911, -1, + 11912, 11912, 11912, -1, 11913, 11913, 11913, -1, + 11914, 11914, 11914, -1, 11915, 11915, 11915, -1, + 11916, 11916, 11916, -1, 11917, 11917, 11917, -1, + 11918, 11918, 11918, -1, 11919, 11919, 11919, -1, + 11920, 11920, 11920, -1, 11921, 11921, 11921, -1, + 11922, 11922, 11922, -1, 11923, 11923, 11923, -1, + 11924, 11924, 11924, -1, 11925, 11925, 11925, -1, + 11926, 11926, 11926, -1, 11927, 11927, 11927, -1, + 11928, 11928, 11928, -1, 11929, 11929, 11929, -1, + 11930, 11930, 11930, -1, 11931, 11931, 11931, -1, + 11932, 11932, 11932, -1, 11933, 11933, 11933, -1, + 11934, 11934, 11934, -1, 11935, 11935, 11935, -1, + 11936, 11936, 11936, -1, 11937, 11937, 11937, -1, + 11938, 11938, 11938, -1, 11939, 11939, 11939, -1, + 11940, 11940, 11940, -1, 11941, 11941, 11941, -1, + 11942, 11942, 11942, -1, 11943, 11943, 11943, -1, + 11944, 11944, 11944, -1, 11945, 11945, 11945, -1, + 11946, 11946, 11946, -1, 11947, 11947, 11947, -1, + 11948, 11948, 11948, -1, 11949, 11949, 11949, -1, + 11950, 11950, 11950, -1, 11951, 11951, 11951, -1, + 11952, 11952, 11952, -1, 11953, 11953, 11953, -1, + 11954, 11954, 11954, -1, 11955, 11955, 11955, -1, + 11956, 11956, 11956, -1, 11957, 11957, 11957, -1, + 11958, 11958, 11958, -1, 11959, 11959, 11959, -1, + 11960, 11960, 11960, -1, 11961, 11961, 11961, -1, + 11962, 11962, 11962, -1, 11963, 11963, 11963, -1, + 11964, 11964, 11964, -1, 11965, 11965, 11965, -1, + 11966, 11966, 11966, -1, 11967, 11967, 11967, -1, + 11968, 11968, 11968, -1, 11969, 11969, 11969, -1, + 11970, 11970, 11970, -1, 11971, 11971, 11971, -1, + 11972, 11972, 11972, -1, 11973, 11973, 11973, -1, + 11974, 11974, 11974, -1, 11975, 11975, 11975, -1, + 11976, 11976, 11976, -1, 11977, 11977, 11977, -1, + 11978, 11978, 11978, -1, 11979, 11979, 11979, -1, + 11980, 11980, 11980, -1, 11981, 11981, 11981, -1, + 11982, 11982, 11982, -1, 11983, 11983, 11983, -1, + 11984, 11984, 11984, -1, 11985, 11985, 11985, -1, + 11986, 11986, 11986, -1, 11987, 11987, 11987, -1, + 11988, 11988, 11988, -1, 11989, 11989, 11989, -1, + 11990, 11990, 11990, -1, 11991, 11991, 11991, -1, + 11992, 11992, 11992, -1, 11993, 11993, 11993, -1, + 11994, 11994, 11994, -1, 11995, 11995, 11995, -1, + 11996, 11996, 11996, -1, 11997, 11997, 11997, -1, + 11998, 11998, 11998, -1, 11999, 11999, 11999, -1, + 12000, 12000, 12000, -1, 12001, 12001, 12001, -1, + 12002, 12002, 12002, -1, 12003, 12003, 12003, -1, + 12004, 12004, 12004, -1, 12005, 12005, 12005, -1, + 12006, 12006, 12006, -1, 12007, 12007, 12007, -1, + 12008, 12008, 12008, -1, 12009, 12009, 12009, -1, + 12010, 12010, 12010, -1, 12011, 12011, 12011, -1, + 12012, 12012, 12012, -1, 12013, 12013, 12013, -1, + 12014, 12014, 12014, -1, 12015, 12015, 12015, -1, + 12016, 12016, 12016, -1, 12017, 12017, 12017, -1, + 12018, 12018, 12018, -1, 12019, 12019, 12019, -1, + 12020, 12020, 12020, -1, 12021, 12021, 12021, -1, + 12022, 12022, 12022, -1, 12023, 12023, 12023, -1, + 12024, 12024, 12024, -1, 12025, 12025, 12025, -1, + 12026, 12026, 12026, -1, 12027, 12027, 12027, -1, + 12028, 12028, 12028, -1, 12029, 12029, 12029, -1, + 12030, 12030, 12030, -1, 12031, 12031, 12031, -1, + 12032, 12032, 12032, -1, 12033, 12033, 12033, -1, + 12034, 12034, 12034, -1, 12035, 12035, 12035, -1, + 12036, 12036, 12036, -1, 12037, 12037, 12037, -1, + 12038, 12038, 12038, -1, 12039, 12039, 12039, -1, + 12040, 12040, 12040, -1, 12041, 12041, 12041, -1, + 12042, 12042, 12042, -1, 12043, 12043, 12043, -1, + 12044, 12044, 12044, -1, 12045, 12045, 12045, -1, + 12046, 12046, 12046, -1, 12047, 12047, 12047, -1, + 12048, 12048, 12048, -1, 12049, 12049, 12049, -1, + 12050, 12050, 12050, -1, 12051, 12051, 12051, -1, + 12052, 12052, 12052, -1, 12053, 12053, 12053, -1, + 12054, 12054, 12054, -1, 12055, 12055, 12055, -1, + 12056, 12056, 12056, -1, 12057, 12057, 12057, -1, + 12058, 12058, 12058, -1, 12059, 12059, 12059, -1, + 12060, 12060, 12060, -1, 12061, 12061, 12061, -1, + 12062, 12062, 12062, -1, 12063, 12063, 12063, -1, + 12064, 12064, 12064, -1, 12065, 12065, 12065, -1, + 12066, 12066, 12066, -1, 12067, 12067, 12067, -1, + 12068, 12068, 12068, -1, 12069, 12069, 12069, -1, + 12070, 12070, 12070, -1, 12071, 12071, 12071, -1, + 12072, 12072, 12072, -1, 12073, 12073, 12073, -1, + 12074, 12074, 12074, -1, 12075, 12075, 12075, -1, + 12076, 12076, 12076, -1, 12077, 12077, 12077, -1, + 12078, 12078, 12078, -1, 12079, 12079, 12079, -1, + 12080, 12080, 12080, -1, 12081, 12081, 12081, -1, + 12082, 12082, 12082, -1, 12083, 12083, 12083, -1, + 12084, 12084, 12084, -1, 12085, 12085, 12085, -1, + 12086, 12086, 12086, -1, 12087, 12087, 12087, -1, + 12088, 12088, 12088, -1, 12089, 12089, 12089, -1, + 12090, 12090, 12090, -1, 12091, 12091, 12091, -1, + 12092, 12092, 12092, -1, 12093, 12093, 12093, -1, + 12094, 12094, 12094, -1, 12095, 12095, 12095, -1, + 12096, 12096, 12096, -1, 12097, 12097, 12097, -1, + 12098, 12098, 12098, -1, 12099, 12099, 12099, -1, + 12100, 12100, 12100, -1, 12101, 12101, 12101, -1, + 12102, 12102, 12102, -1, 12103, 12103, 12103, -1, + 12104, 12104, 12104, -1, 12105, 12105, 12105, -1, + 12106, 12106, 12106, -1, 12107, 12107, 12107, -1, + 12108, 12108, 12108, -1, 12109, 12109, 12109, -1, + 12110, 12110, 12110, -1, 12111, 12111, 12111, -1, + 12112, 12112, 12112, -1, 12113, 12113, 12113, -1, + 12114, 12114, 12114, -1, 12115, 12115, 12115, -1, + 12116, 12116, 12116, -1, 12117, 12117, 12117, -1, + 12118, 12118, 12118, -1, 12119, 12119, 12119, -1, + 12120, 12120, 12120, -1, 12121, 12121, 12121, -1, + 12122, 12122, 12122, -1, 12123, 12123, 12123, -1, + 12124, 12124, 12124, -1, 12125, 12125, 12125, -1, + 12126, 12126, 12126, -1, 12127, 12127, 12127, -1, + 12128, 12128, 12128, -1, 12129, 12129, 12129, -1, + 12130, 12130, 12130, -1, 12131, 12131, 12131, -1, + 12132, 12132, 12132, -1, 12133, 12133, 12133, -1, + 12134, 12134, 12134, -1, 12135, 12135, 12135, -1, + 12136, 12136, 12136, -1, 12137, 12137, 12137, -1, + 12138, 12138, 12138, -1, 12139, 12139, 12139, -1, + 12140, 12140, 12140, -1, 12141, 12141, 12141, -1, + 12142, 12142, 12142, -1, 12143, 12143, 12143, -1, + 12144, 12144, 12144, -1, 12145, 12145, 12145, -1, + 12146, 12146, 12146, -1, 12147, 12147, 12147, -1, + 12148, 12148, 12148, -1, 12149, 12149, 12149, -1, + 12150, 12150, 12150, -1, 12151, 12151, 12151, -1, + 12152, 12152, 12152, -1, 12153, 12153, 12153, -1, + 12154, 12154, 12154, -1, 12155, 12155, 12155, -1, + 12156, 12156, 12156, -1, 12157, 12157, 12157, -1, + 12158, 12158, 12158, -1, 12159, 12159, 12159, -1, + 12160, 12160, 12160, -1, 12161, 12161, 12161, -1, + 12162, 12162, 12162, -1, 12163, 12163, 12163, -1, + 12164, 12164, 12164, -1, 12165, 12165, 12165, -1, + 12166, 12166, 12166, -1, 12167, 12167, 12167, -1, + 12168, 12168, 12168, -1, 12169, 12169, 12169, -1, + 12170, 12170, 12170, -1, 12171, 12171, 12171, -1, + 12172, 12172, 12172, -1, 12173, 12173, 12173, -1, + 12174, 12174, 12174, -1, 12175, 12175, 12175, -1, + 12176, 12176, 12176, -1, 12177, 12177, 12177, -1, + 12178, 12178, 12178, -1, 12179, 12179, 12179, -1, + 12180, 12180, 12180, -1, 12181, 12181, 12181, -1, + 12182, 12182, 12182, -1, 12183, 12183, 12183, -1, + 12184, 12184, 12184, -1, 12185, 12185, 12185, -1, + 12186, 12186, 12186, -1, 12187, 12187, 12187, -1, + 12188, 12188, 12188, -1, 12189, 12189, 12189, -1, + 12190, 12190, 12190, -1, 12191, 12191, 12191, -1, + 12192, 12192, 12192, -1, 12193, 12193, 12193, -1, + 12194, 12194, 12194, -1, 12195, 12195, 12195, -1, + 12196, 12196, 12196, -1, 12197, 12197, 12197, -1, + 12198, 12198, 12198, -1, 12199, 12199, 12199, -1, + 12200, 12200, 12200, -1, 12201, 12201, 12201, -1, + 12202, 12202, 12202, -1, 12203, 12203, 12203, -1, + 12204, 12204, 12204, -1, 12205, 12205, 12205, -1, + 12206, 12206, 12206, -1, 12207, 12207, 12207, -1, + 12208, 12208, 12208, -1, 12209, 12209, 12209, -1, + 12210, 12210, 12210, -1, 12211, 12211, 12211, -1, + 12212, 12212, 12212, -1, 12213, 12213, 12213, -1, + 12214, 12214, 12214, -1, 12215, 12215, 12215, -1, + 12216, 12216, 12216, -1, 12217, 12217, 12217, -1, + 12218, 12218, 12218, -1, 12219, 12219, 12219, -1, + 12220, 12220, 12220, -1, 12221, 12221, 12221, -1, + 12222, 12222, 12222, -1, 12223, 12223, 12223, -1, + 12224, 12224, 12224, -1, 12225, 12225, 12225, -1, + 12226, 12226, 12226, -1, 12227, 12227, 12227, -1, + 12228, 12228, 12228, -1, 12229, 12229, 12229, -1, + 12230, 12230, 12230, -1, 12231, 12231, 12231, -1, + 12232, 12232, 12232, -1, 12233, 12233, 12233, -1, + 12234, 12234, 12234, -1, 12235, 12235, 12235, -1, + 12236, 12236, 12236, -1, 12237, 12237, 12237, -1, + 12238, 12238, 12238, -1, 12239, 12239, 12239, -1, + 12240, 12240, 12240, -1, 12241, 12241, 12241, -1, + 12242, 12242, 12242, -1, 12243, 12243, 12243, -1, + 12244, 12244, 12244, -1, 12245, 12245, 12245, -1, + 12246, 12246, 12246, -1, 12247, 12247, 12247, -1, + 12248, 12248, 12248, -1, 12249, 12249, 12249, -1, + 12250, 12250, 12250, -1, 12251, 12251, 12251, -1, + 12252, 12252, 12252, -1, 12253, 12253, 12253, -1, + 12254, 12254, 12254, -1, 12255, 12255, 12255, -1, + 12256, 12256, 12256, -1, 12257, 12257, 12257, -1, + 12258, 12258, 12258, -1, 12259, 12259, 12259, -1, + 12260, 12260, 12260, -1, 12261, 12261, 12261, -1, + 12262, 12262, 12262, -1, 12263, 12263, 12263, -1, + 12264, 12264, 12264, -1, 12265, 12265, 12265, -1, + 12266, 12266, 12266, -1, 12267, 12267, 12267, -1, + 12268, 12268, 12268, -1, 12269, 12269, 12269, -1, + 12270, 12270, 12270, -1, 12271, 12271, 12271, -1, + 12272, 12272, 12272, -1, 12273, 12273, 12273, -1, + 12274, 12274, 12274, -1, 12275, 12275, 12275, -1, + 12276, 12276, 12276, -1, 12277, 12277, 12277, -1, + 12278, 12278, 12278, -1, 12279, 12279, 12279, -1, + 12280, 12280, 12280, -1, 12281, 12281, 12281, -1, + 12282, 12282, 12282, -1, 12283, 12283, 12283, -1, + 12284, 12284, 12284, -1, 12285, 12285, 12285, -1, + 12286, 12286, 12286, -1, 12287, 12287, 12287, -1, + 12288, 12288, 12288, -1, 12289, 12289, 12289, -1, + 12290, 12290, 12290, -1, 12291, 12291, 12291, -1, + 12292, 12292, 12292, -1, 12293, 12293, 12293, -1, + 12294, 12294, 12294, -1, 12295, 12295, 12295, -1, + 12296, 12296, 12296, -1, 12297, 12297, 12297, -1, + 12298, 12298, 12298, -1, 12299, 12299, 12299, -1, + 12300, 12300, 12300, -1, 12301, 12301, 12301, -1, + 12302, 12302, 12302, -1, 12303, 12303, 12303, -1, + 12304, 12304, 12304, -1, 12305, 12305, 12305, -1, + 12306, 12306, 12306, -1, 12307, 12307, 12307, -1, + 12308, 12308, 12308, -1, 12309, 12309, 12309, -1, + 12310, 12310, 12310, -1, 12311, 12311, 12311, -1, + 12312, 12312, 12312, -1, 12313, 12313, 12313, -1, + 12314, 12314, 12314, -1, 12315, 12315, 12315, -1, + 12316, 12316, 12316, -1, 12317, 12317, 12317, -1, + 12318, 12318, 12318, -1, 12319, 12319, 12319, -1, + 12320, 12320, 12320, -1, 12321, 12321, 12321, -1, + 12322, 12322, 12322, -1, 12323, 12323, 12323, -1, + 12324, 12324, 12324, -1, 12325, 12325, 12325, -1, + 12326, 12326, 12326, -1, 12327, 12327, 12327, -1, + 12328, 12328, 12328, -1, 12329, 12329, 12329, -1, + 12330, 12330, 12330, -1, 12331, 12331, 12331, -1, + 12332, 12332, 12332, -1, 12333, 12333, 12333, -1, + 12334, 12334, 12334, -1, 12335, 12335, 12335, -1, + 12336, 12336, 12336, -1, 12337, 12337, 12337, -1, + 12338, 12338, 12338, -1, 12339, 12339, 12339, -1, + 12340, 12340, 12340, -1, 12341, 12341, 12341, -1, + 12342, 12342, 12342, -1, 12343, 12343, 12343, -1, + 12344, 12344, 12344, -1, 12345, 12345, 12345, -1, + 12346, 12346, 12346, -1, 12347, 12347, 12347, -1, + 12348, 12348, 12348, -1, 12349, 12349, 12349, -1, + 12350, 12350, 12350, -1, 12351, 12351, 12351, -1, + 12352, 12352, 12352, -1, 12353, 12353, 12353, -1, + 12354, 12354, 12354, -1, 12355, 12355, 12355, -1, + 12356, 12356, 12356, -1, 12357, 12357, 12357, -1, + 12358, 12358, 12358, -1, 12359, 12359, 12359, -1, + 12360, 12360, 12360, -1, 12361, 12361, 12361, -1, + 12362, 12362, 12362, -1, 12363, 12363, 12363, -1, + 12364, 12364, 12364, -1, 12365, 12365, 12365, -1, + 12366, 12366, 12366, -1, 12367, 12367, 12367, -1, + 12368, 12368, 12368, -1, 12369, 12369, 12369, -1, + 12370, 12370, 12370, -1, 12371, 12371, 12371, -1, + 12372, 12372, 12372, -1, 12373, 12373, 12373, -1, + 12374, 12374, 12374, -1, 12375, 12375, 12375, -1, + 12376, 12376, 12376, -1, 12377, 12377, 12377, -1, + 12378, 12378, 12378, -1, 12379, 12379, 12379, -1, + 12380, 12380, 12380, -1, 12381, 12381, 12381, -1, + 12382, 12382, 12382, -1, 12383, 12383, 12383, -1, + 12384, 12384, 12384, -1, 12385, 12385, 12385, -1, + 12386, 12386, 12386, -1, 12387, 12387, 12387, -1, + 12388, 12388, 12388, -1, 12389, 12389, 12389, -1, + 12390, 12390, 12390, -1, 12391, 12391, 12391, -1, + 12392, 12392, 12392, -1, 12393, 12393, 12393, -1, + 12394, 12394, 12394, -1, 12395, 12395, 12395, -1, + 12396, 12396, 12396, -1, 12397, 12397, 12397, -1, + 12398, 12398, 12398, -1, 12399, 12399, 12399, -1, + 12400, 12400, 12400, -1, 12401, 12401, 12401, -1, + 12402, 12402, 12402, -1, 12403, 12403, 12403, -1, + 12404, 12404, 12404, -1, 12405, 12405, 12405, -1, + 12406, 12406, 12406, -1, 12407, 12407, 12407, -1, + 12408, 12408, 12408, -1, 12409, 12409, 12409, -1, + 12410, 12410, 12410, -1, 12411, 12411, 12411, -1, + 12412, 12412, 12412, -1, 12413, 12413, 12413, -1, + 12414, 12414, 12414, -1, 12415, 12415, 12415, -1, + 12416, 12416, 12416, -1, 12417, 12417, 12417, -1, + 12418, 12418, 12418, -1, 12419, 12419, 12419, -1, + 12420, 12420, 12420, -1, 12421, 12421, 12421, -1, + 12422, 12422, 12422, -1, 12423, 12423, 12423, -1, + 12424, 12424, 12424, -1, 12425, 12425, 12425, -1, + 12426, 12426, 12426, -1, 12427, 12427, 12427, -1, + 12428, 12428, 12428, -1, 12429, 12429, 12429, -1, + 12430, 12430, 12430, -1, 12431, 12431, 12431, -1, + 12432, 12432, 12432, -1, 12433, 12433, 12433, -1, + 12434, 12434, 12434, -1, 12435, 12435, 12435, -1, + 12436, 12436, 12436, -1, 12437, 12437, 12437, -1, + 12438, 12438, 12438, -1, 12439, 12439, 12439, -1, + 12440, 12440, 12440, -1, 12441, 12441, 12441, -1, + 12442, 12442, 12442, -1, 12443, 12443, 12443, -1, + 12444, 12444, 12444, -1, 12445, 12445, 12445, -1, + 12446, 12446, 12446, -1, 12447, 12447, 12447, -1, + 12448, 12448, 12448, -1, 12449, 12449, 12449, -1, + 12450, 12450, 12450, -1, 12451, 12451, 12451, -1, + 12452, 12452, 12452, -1, 12453, 12453, 12453, -1, + 12454, 12454, 12454, -1, 12455, 12455, 12455, -1, + 12456, 12456, 12456, -1, 12457, 12457, 12457, -1, + 12458, 12458, 12458, -1, 12459, 12459, 12459, -1, + 12460, 12460, 12460, -1, 12461, 12461, 12461, -1, + 12462, 12462, 12462, -1, 12463, 12463, 12463, -1, + 12464, 12464, 12464, -1, 12465, 12465, 12465, -1, + 12466, 12466, 12466, -1, 12467, 12467, 12467, -1, + 12468, 12468, 12468, -1, 12469, 12469, 12469, -1, + 12470, 12470, 12470, -1, 12471, 12471, 12471, -1, + 12472, 12472, 12472, -1, 12473, 12473, 12473, -1, + 12474, 12474, 12474, -1, 12475, 12475, 12475, -1, + 12476, 12476, 12476, -1, 12477, 12477, 12477, -1, + 12478, 12478, 12478, -1, 12479, 12479, 12479, -1, + 12480, 12480, 12480, -1, 12481, 12481, 12481, -1, + 12482, 12482, 12482, -1, 12483, 12483, 12483, -1, + 12484, 12484, 12484, -1, 12485, 12485, 12485, -1, + 12486, 12486, 12486, -1, 12487, 12487, 12487, -1, + 12488, 12488, 12488, -1, 12489, 12489, 12489, -1, + 12490, 12490, 12490, -1, 12491, 12491, 12491, -1, + 12492, 12492, 12492, -1, 12493, 12493, 12493, -1, + 12494, 12494, 12494, -1, 12495, 12495, 12495, -1, + 12496, 12496, 12496, -1, 12497, 12497, 12497, -1, + 12498, 12498, 12498, -1, 12499, 12499, 12499, -1, + 12500, 12500, 12500, -1, 12501, 12501, 12501, -1, + 12502, 12502, 12502, -1, 12503, 12503, 12503, -1, + 12504, 12504, 12504, -1, 12505, 12505, 12505, -1, + 12506, 12506, 12506, -1, 12507, 12507, 12507, -1, + 12508, 12508, 12508, -1, 12509, 12509, 12509, -1, + 12510, 12510, 12510, -1, 12511, 12511, 12511, -1, + 12512, 12512, 12512, -1, 12513, 12513, 12513, -1, + 12514, 12514, 12514, -1, 12515, 12515, 12515, -1, + 12516, 12516, 12516, -1, 12517, 12517, 12517, -1, + 12518, 12518, 12518, -1, 12519, 12519, 12519, -1, + 12520, 12520, 12520, -1, 12521, 12521, 12521, -1, + 12522, 12522, 12522, -1, 12523, 12523, 12523, -1, + 12524, 12524, 12524, -1, 12525, 12525, 12525, -1, + 12526, 12526, 12526, -1, 12527, 12527, 12527, -1, + 12528, 12528, 12528, -1, 12529, 12529, 12529, -1, + 12530, 12530, 12530, -1, 12531, 12531, 12531, -1, + 12532, 12532, 12532, -1, 12533, 12533, 12533, -1, + 12534, 12534, 12534, -1, 12535, 12535, 12535, -1, + 12536, 12536, 12536, -1, 12537, 12537, 12537, -1, + 12538, 12538, 12538, -1, 12539, 12539, 12539, -1, + 12540, 12540, 12540, -1, 12541, 12541, 12541, -1, + 12542, 12542, 12542, -1, 12543, 12543, 12543, -1, + 12544, 12544, 12544, -1, 12545, 12545, 12545, -1, + 12546, 12546, 12546, -1, 12547, 12547, 12547, -1, + 12548, 12548, 12548, -1, 12549, 12549, 12549, -1, + 12550, 12550, 12550, -1, 12551, 12551, 12551, -1, + 12552, 12552, 12552, -1, 12553, 12553, 12553, -1, + 12554, 12554, 12554, -1, 12555, 12555, 12555, -1, + 12556, 12556, 12556, -1, 12557, 12557, 12557, -1, + 12558, 12558, 12558, -1, 12559, 12559, 12559, -1, + 12560, 12560, 12560, -1, 12561, 12561, 12561, -1, + 12562, 12562, 12562, -1, 12563, 12563, 12563, -1, + 12564, 12564, 12564, -1, 12565, 12565, 12565, -1, + 12566, 12566, 12566, -1, 12567, 12567, 12567, -1, + 12568, 12568, 12568, -1, 12569, 12569, 12569, -1, + 12570, 12570, 12570, -1, 12571, 12571, 12571, -1, + 12572, 12572, 12572, -1, 12573, 12573, 12573, -1, + 12574, 12574, 12574, -1, 12575, 12575, 12575, -1, + 12576, 12576, 12576, -1, 12577, 12577, 12577, -1, + 12578, 12578, 12578, -1, 12579, 12579, 12579, -1, + 12580, 12580, 12580, -1, 12581, 12581, 12581, -1, + 12582, 12582, 12582, -1, 12583, 12583, 12583, -1, + 12584, 12584, 12584, -1, 12585, 12585, 12585, -1, + 12586, 12586, 12586, -1, 12587, 12587, 12587, -1, + 12588, 12588, 12588, -1, 12589, 12589, 12589, -1, + 12590, 12590, 12590, -1, 12591, 12591, 12591, -1, + 12592, 12592, 12592, -1, 12593, 12593, 12593, -1, + 12594, 12594, 12594, -1, 12595, 12595, 12595, -1, + 12596, 12596, 12596, -1, 12597, 12597, 12597, -1, + 12598, 12598, 12598, -1, 12599, 12599, 12599, -1, + 12600, 12600, 12600, -1, 12601, 12601, 12601, -1, + 12602, 12602, 12602, -1, 12603, 12603, 12603, -1, + 12604, 12604, 12604, -1, 12605, 12605, 12605, -1, + 12606, 12606, 12606, -1, 12607, 12607, 12607, -1, + 12608, 12608, 12608, -1, 12609, 12609, 12609, -1, + 12610, 12610, 12610, -1, 12611, 12611, 12611, -1, + 12612, 12612, 12612, -1, 12613, 12613, 12613, -1, + 12614, 12614, 12614, -1, 12615, 12615, 12615, -1, + 12616, 12616, 12616, -1, 12617, 12617, 12617, -1, + 12618, 12618, 12618, -1, 12619, 12619, 12619, -1, + 12620, 12620, 12620, -1, 12621, 12621, 12621, -1, + 12622, 12622, 12622, -1, 12623, 12623, 12623, -1, + 12624, 12624, 12624, -1, 12625, 12625, 12625, -1, + 12626, 12626, 12626, -1, 12627, 12627, 12627, -1, + 12628, 12628, 12628, -1, 12629, 12629, 12629, -1, + 12630, 12630, 12630, -1, 12631, 12631, 12631, -1, + 12632, 12632, 12632, -1, 12633, 12633, 12633, -1, + 12634, 12634, 12634, -1, 12635, 12635, 12635, -1, + 12636, 12636, 12636, -1, 12637, 12637, 12637, -1, + 12638, 12638, 12638, -1, 12639, 12639, 12639, -1, + 12640, 12640, 12640, -1, 12641, 12641, 12641, -1, + 12642, 12642, 12642, -1, 12643, 12643, 12643, -1, + 12644, 12644, 12644, -1, 12645, 12645, 12645, -1, + 12646, 12646, 12646, -1, 12647, 12647, 12647, -1, + 12648, 12648, 12648, -1, 12649, 12649, 12649, -1, + 12650, 12650, 12650, -1, 12651, 12651, 12651, -1, + 12652, 12652, 12652, -1, 12653, 12653, 12653, -1, + 12654, 12654, 12654, -1, 12655, 12655, 12655, -1, + 12656, 12656, 12656, -1, 12657, 12657, 12657, -1, + 12658, 12658, 12658, -1, 12659, 12659, 12659, -1, + 12660, 12660, 12660, -1, 12661, 12661, 12661, -1, + 12662, 12662, 12662, -1, 12663, 12663, 12663, -1, + 12664, 12664, 12664, -1, 12665, 12665, 12665, -1, + 12666, 12666, 12666, -1, 12667, 12667, 12667, -1, + 12668, 12668, 12668, -1, 12669, 12669, 12669, -1, + 12670, 12670, 12670, -1, 12671, 12671, 12671, -1, + 12672, 12672, 12672, -1, 12673, 12673, 12673, -1, + 12674, 12674, 12674, -1, 12675, 12675, 12675, -1, + 12676, 12676, 12676, -1, 12677, 12677, 12677, -1, + 12678, 12678, 12678, -1, 12679, 12679, 12679, -1, + 12680, 12680, 12680, -1, 12681, 12681, 12681, -1, + 12682, 12682, 12682, -1, 12683, 12683, 12683, -1, + 12684, 12684, 12684, -1, 12685, 12685, 12685, -1, + 12686, 12686, 12686, -1, 12687, 12687, 12687, -1, + 12688, 12688, 12688, -1, 12689, 12689, 12689, -1, + 12690, 12690, 12690, -1, 12691, 12691, 12691, -1, + 12692, 12692, 12692, -1, 12693, 12693, 12693, -1, + 12694, 12694, 12694, -1, 12695, 12695, 12695, -1, + 12696, 12696, 12696, -1, 12697, 12697, 12697, -1, + 12698, 12698, 12698, -1, 12699, 12699, 12699, -1, + 12700, 12700, 12700, -1, 12701, 12701, 12701, -1, + 12702, 12702, 12702, -1, 12703, 12703, 12703, -1, + 12704, 12704, 12704, -1, 12705, 12705, 12705, -1, + 12706, 12706, 12706, -1, 12707, 12707, 12707, -1, + 12708, 12708, 12708, -1, 12709, 12709, 12709, -1, + 12710, 12710, 12710, -1, 12711, 12711, 12711, -1, + 12712, 12712, 12712, -1, 12713, 12713, 12713, -1, + 12714, 12714, 12714, -1, 12715, 12715, 12715, -1, + 12716, 12716, 12716, -1, 12717, 12717, 12717, -1, + 12718, 12718, 12718, -1, 12719, 12719, 12719, -1, + 12720, 12720, 12720, -1, 12721, 12721, 12721, -1, + 12722, 12722, 12722, -1, 12723, 12723, 12723, -1, + 12724, 12724, 12724, -1, 12725, 12725, 12725, -1, + 12726, 12726, 12726, -1, 12727, 12727, 12727, -1, + 12728, 12728, 12728, -1, 12729, 12729, 12729, -1, + 12730, 12730, 12730, -1, 12731, 12731, 12731, -1, + 12732, 12732, 12732, -1, 12733, 12733, 12733, -1, + 12734, 12734, 12734, -1, 12735, 12735, 12735, -1, + 12736, 12736, 12736, -1, 12737, 12737, 12737, -1, + 12738, 12738, 12738, -1, 12739, 12739, 12739, -1, + 12740, 12740, 12740, -1, 12741, 12741, 12741, -1, + 12742, 12742, 12742, -1, 12743, 12743, 12743, -1, + 12744, 12744, 12744, -1, 12745, 12745, 12745, -1, + 12746, 12746, 12746, -1, 12747, 12747, 12747, -1, + 12748, 12748, 12748, -1, 12749, 12749, 12749, -1, + 12750, 12750, 12750, -1, 12751, 12751, 12751, -1, + 12752, 12752, 12752, -1, 12753, 12753, 12753, -1, + 12754, 12754, 12754, -1, 12755, 12755, 12755, -1, + 12756, 12756, 12756, -1, 12757, 12757, 12757, -1, + 12758, 12758, 12758, -1, 12759, 12759, 12759, -1, + 12760, 12760, 12760, -1, 12761, 12761, 12761, -1, + 12762, 12762, 12762, -1, 12763, 12763, 12763, -1, + 12764, 12764, 12764, -1, 12765, 12765, 12765, -1, + 12766, 12766, 12766, -1, 12767, 12767, 12767, -1, + 12768, 12768, 12768, -1, 12769, 12769, 12769, -1, + 12770, 12770, 12770, -1, 12771, 12771, 12771, -1, + 12772, 12772, 12772, -1, 12773, 12773, 12773, -1, + 12774, 12774, 12774, -1, 12775, 12775, 12775, -1, + 12776, 12776, 12776, -1, 12777, 12777, 12777, -1, + 12778, 12778, 12778, -1, 12779, 12779, 12779, -1, + 12780, 12780, 12780, -1, 12781, 12781, 12781, -1, + 12782, 12782, 12782, -1, 12783, 12783, 12783, -1, + 12784, 12784, 12784, -1, 12785, 12785, 12785, -1, + 12786, 12786, 12786, -1, 12787, 12787, 12787, -1, + 12788, 12788, 12788, -1, 12789, 12789, 12789, -1, + 12790, 12790, 12790, -1, 12791, 12791, 12791, -1, + 12792, 12792, 12792, -1, 12793, 12793, 12793, -1, + 12794, 12794, 12794, -1, 12795, 12795, 12795, -1, + 12796, 12796, 12796, -1, 12797, 12797, 12797, -1, + 12798, 12798, 12798, -1, 12799, 12799, 12799, -1, + 12800, 12800, 12800, -1, 12801, 12801, 12801, -1, + 12802, 12802, 12802, -1, 12803, 12803, 12803, -1, + 12804, 12804, 12804, -1, 12805, 12805, 12805, -1, + 12806, 12806, 12806, -1, 12807, 12807, 12807, -1, + 12808, 12808, 12808, -1, 12809, 12809, 12809, -1, + 12810, 12810, 12810, -1, 12811, 12811, 12811, -1, + 12812, 12812, 12812, -1, 12813, 12813, 12813, -1, + 12814, 12814, 12814, -1, 12815, 12815, 12815, -1, + 12816, 12816, 12816, -1, 12817, 12817, 12817, -1, + 12818, 12818, 12818, -1, 12819, 12819, 12819, -1, + 12820, 12820, 12820, -1, 12821, 12821, 12821, -1, + 12822, 12822, 12822, -1, 12823, 12823, 12823, -1, + 12824, 12824, 12824, -1, 12825, 12825, 12825, -1, + 12826, 12826, 12826, -1, 12827, 12827, 12827, -1, + 12828, 12828, 12828, -1, 12829, 12829, 12829, -1, + 12830, 12830, 12830, -1, 12831, 12831, 12831, -1, + 12832, 12832, 12832, -1, 12833, 12833, 12833, -1, + 12834, 12834, 12834, -1, 12835, 12835, 12835, -1, + 12836, 12836, 12836, -1, 12837, 12837, 12837, -1, + 12838, 12838, 12838, -1, 12839, 12839, 12839, -1, + 12840, 12840, 12840, -1, 12841, 12841, 12841, -1, + 12842, 12842, 12842, -1, 12843, 12843, 12843, -1, + 12844, 12844, 12844, -1, 12845, 12845, 12845, -1, + 12846, 12846, 12846, -1, 12847, 12847, 12847, -1, + 12848, 12848, 12848, -1, 12849, 12849, 12849, -1, + 12850, 12850, 12850, -1, 12851, 12851, 12851, -1, + 12852, 12852, 12852, -1, 12853, 12853, 12853, -1, + 12854, 12854, 12854, -1, 12855, 12855, 12855, -1, + 12856, 12856, 12856, -1, 12857, 12857, 12857, -1, + 12858, 12858, 12858, -1, 12859, 12859, 12859, -1, + 12860, 12860, 12860, -1, 12861, 12861, 12861, -1, + 12862, 12862, 12862, -1, 12863, 12863, 12863, -1, + 12864, 12864, 12864, -1, 12865, 12865, 12865, -1, + 12866, 12866, 12866, -1, 12867, 12867, 12867, -1, + 12868, 12868, 12868, -1, 12869, 12869, 12869, -1, + 12870, 12870, 12870, -1, 12871, 12871, 12871, -1, + 12872, 12872, 12872, -1, 12873, 12873, 12873, -1, + 12874, 12874, 12874, -1, 12875, 12875, 12875, -1, + 12876, 12876, 12876, -1, 12877, 12877, 12877, -1, + 12878, 12878, 12878, -1, 12879, 12879, 12879, -1, + 12880, 12880, 12880, -1, 12881, 12881, 12881, -1, + 12882, 12882, 12882, -1, 12883, 12883, 12883, -1, + 12884, 12884, 12884, -1, 12885, 12885, 12885, -1, + 12886, 12886, 12886, -1, 12887, 12887, 12887, -1, + 12888, 12888, 12888, -1, 12889, 12889, 12889, -1, + 12890, 12890, 12890, -1, 12891, 12891, 12891, -1, + 12892, 12892, 12892, -1, 12893, 12893, 12893, -1, + 12894, 12894, 12894, -1, 12895, 12895, 12895, -1, + 12896, 12896, 12896, -1, 12897, 12897, 12897, -1, + 12898, 12898, 12898, -1, 12899, 12899, 12899, -1, + 12900, 12900, 12900, -1, 12901, 12901, 12901, -1, + 12902, 12902, 12902, -1, 12903, 12903, 12903, -1, + 12904, 12904, 12904, -1, 12905, 12905, 12905, -1, + 12906, 12906, 12906, -1, 12907, 12907, 12907, -1, + 12908, 12908, 12908, -1, 12909, 12909, 12909, -1, + 12910, 12910, 12910, -1, 12911, 12911, 12911, -1, + 12912, 12912, 12912, -1, 12913, 12913, 12913, -1, + 12914, 12914, 12914, -1, 12915, 12915, 12915, -1, + 12916, 12916, 12916, -1, 12917, 12917, 12917, -1, + 12918, 12918, 12918, -1, 12919, 12919, 12919, -1, + 12920, 12920, 12920, -1, 12921, 12921, 12921, -1, + 12922, 12922, 12922, -1, 12923, 12923, 12923, -1, + 12924, 12924, 12924, -1, 12925, 12925, 12925, -1, + 12926, 12926, 12926, -1, 12927, 12927, 12927, -1, + 12928, 12928, 12928, -1, 12929, 12929, 12929, -1, + 12930, 12930, 12930, -1, 12931, 12931, 12931, -1, + 12932, 12932, 12932, -1, 12933, 12933, 12933, -1, + 12934, 12934, 12934, -1, 12935, 12935, 12935, -1, + 12936, 12936, 12936, -1, 12937, 12937, 12937, -1, + 12938, 12938, 12938, -1, 12939, 12939, 12939, -1, + 12940, 12940, 12940, -1, 12941, 12941, 12941, -1, + 12942, 12942, 12942, -1, 12943, 12943, 12943, -1, + 12944, 12944, 12944, -1, 12945, 12945, 12945, -1, + 12946, 12946, 12946, -1, 12947, 12947, 12947, -1, + 12948, 12948, 12948, -1, 12949, 12949, 12949, -1, + 12950, 12950, 12950, -1, 12951, 12951, 12951, -1, + 12952, 12952, 12952, -1, 12953, 12953, 12953, -1, + 12954, 12954, 12954, -1, 12955, 12955, 12955, -1, + 12956, 12956, 12956, -1, 12957, 12957, 12957, -1, + 12958, 12958, 12958, -1, 12959, 12959, 12959, -1, + 12960, 12960, 12960, -1, 12961, 12961, 12961, -1, + 12962, 12962, 12962, -1, 12963, 12963, 12963, -1, + 12964, 12964, 12964, -1, 12965, 12965, 12965, -1, + 12966, 12966, 12966, -1, 12967, 12967, 12967, -1, + 12968, 12968, 12968, -1, 12969, 12969, 12969, -1, + 12970, 12970, 12970, -1, 12971, 12971, 12971, -1, + 12972, 12972, 12972, -1, 12973, 12973, 12973, -1, + 12974, 12974, 12974, -1, 12975, 12975, 12975, -1, + 12976, 12976, 12976, -1, 12977, 12977, 12977, -1, + 12978, 12978, 12978, -1, 12979, 12979, 12979, -1, + 12980, 12980, 12980, -1, 12981, 12981, 12981, -1, + 12982, 12982, 12982, -1, 12983, 12983, 12983, -1, + 12984, 12984, 12984, -1, 12985, 12985, 12985, -1, + 12986, 12986, 12986, -1, 12987, 12987, 12987, -1, + 12988, 12988, 12988, -1, 12989, 12989, 12989, -1, + 12990, 12990, 12990, -1, 12991, 12991, 12991, -1, + 12992, 12992, 12992, -1, 12993, 12993, 12993, -1, + 12994, 12994, 12994, -1, 12995, 12995, 12995, -1, + 12996, 12996, 12996, -1, 12997, 12997, 12997, -1, + 12998, 12998, 12998, -1, 12999, 12999, 12999, -1, + 13000, 13000, 13000, -1, 13001, 13001, 13001, -1, + 13002, 13002, 13002, -1, 13003, 13003, 13003, -1, + 13004, 13004, 13004, -1, 13005, 13005, 13005, -1, + 13006, 13006, 13006, -1, 13007, 13007, 13007, -1, + 13008, 13008, 13008, -1, 13009, 13009, 13009, -1, + 13010, 13010, 13010, -1, 13011, 13011, 13011, -1, + 13012, 13012, 13012, -1, 13013, 13013, 13013, -1, + 13014, 13014, 13014, -1, 13015, 13015, 13015, -1, + 13016, 13016, 13016, -1, 13017, 13017, 13017, -1, + 13018, 13018, 13018, -1, 13019, 13019, 13019, -1, + 13020, 13020, 13020, -1, 13021, 13021, 13021, -1, + 13022, 13022, 13022, -1, 13023, 13023, 13023, -1, + 13024, 13024, 13024, -1, 13025, 13025, 13025, -1, + 13026, 13026, 13026, -1, 13027, 13027, 13027, -1, + 13028, 13028, 13028, -1, 13029, 13029, 13029, -1, + 13030, 13030, 13030, -1, 13031, 13031, 13031, -1, + 13032, 13032, 13032, -1, 13033, 13033, 13033, -1, + 13034, 13034, 13034, -1, 13035, 13035, 13035, -1, + 13036, 13036, 13036, -1, 13037, 13037, 13037, -1, + 13038, 13038, 13038, -1, 13039, 13039, 13039, -1, + 13040, 13040, 13040, -1, 13041, 13041, 13041, -1, + 13042, 13042, 13042, -1, 13043, 13043, 13043, -1, + 13044, 13044, 13044, -1, 13045, 13045, 13045, -1, + 13046, 13046, 13046, -1, 13047, 13047, 13047, -1, + 13048, 13048, 13048, -1, 13049, 13049, 13049, -1, + 13050, 13050, 13050, -1, 13051, 13051, 13051, -1, + 13052, 13052, 13052, -1, 13053, 13053, 13053, -1, + 13054, 13054, 13054, -1, 13055, 13055, 13055, -1, + 13056, 13056, 13056, -1, 13057, 13057, 13057, -1, + 13058, 13058, 13058, -1, 13059, 13059, 13059, -1, + 13060, 13060, 13060, -1, 13061, 13061, 13061, -1, + 13062, 13062, 13062, -1, 13063, 13063, 13063, -1, + 13064, 13064, 13064, -1, 13065, 13065, 13065, -1, + 13066, 13066, 13066, -1, 13067, 13067, 13067, -1, + 13068, 13068, 13068, -1, 13069, 13069, 13069, -1, + 13070, 13070, 13070, -1, 13071, 13071, 13071, -1, + 13072, 13072, 13072, -1, 13073, 13073, 13073, -1, + 13074, 13074, 13074, -1, 13075, 13075, 13075, -1, + 13076, 13076, 13076, -1, 13077, 13077, 13077, -1, + 13078, 13078, 13078, -1, 13079, 13079, 13079, -1, + 13080, 13080, 13080, -1, 13081, 13081, 13081, -1, + 13082, 13082, 13082, -1, 13083, 13083, 13083, -1, + 13084, 13084, 13084, -1, 13085, 13085, 13085, -1, + 13086, 13086, 13086, -1, 13087, 13087, 13087, -1, + 13088, 13088, 13088, -1, 13089, 13089, 13089, -1, + 13090, 13090, 13090, -1, 13091, 13091, 13091, -1, + 13092, 13092, 13092, -1, 13093, 13093, 13093, -1, + 13094, 13094, 13094, -1, 13095, 13095, 13095, -1, + 13096, 13096, 13096, -1, 13097, 13097, 13097, -1, + 13098, 13098, 13098, -1, 13099, 13099, 13099, -1, + 13100, 13100, 13100, -1, 13101, 13101, 13101, -1, + 13102, 13102, 13102, -1, 13103, 13103, 13103, -1, + 13104, 13104, 13104, -1, 13105, 13105, 13105, -1, + 13106, 13106, 13106, -1, 13107, 13107, 13107, -1, + 13108, 13108, 13108, -1, 13109, 13109, 13109, -1, + 13110, 13110, 13110, -1, 13111, 13111, 13111, -1, + 13112, 13112, 13112, -1, 13113, 13113, 13113, -1, + 13114, 13114, 13114, -1, 13115, 13115, 13115, -1, + 13116, 13116, 13116, -1, 13117, 13117, 13117, -1, + 13118, 13118, 13118, -1, 13119, 13119, 13119, -1, + 13120, 13120, 13120, -1, 13121, 13121, 13121, -1, + 13122, 13122, 13122, -1, 13123, 13123, 13123, -1, + 13124, 13124, 13124, -1, 13125, 13125, 13125, -1, + 13126, 13126, 13126, -1, 13127, 13127, 13127, -1, + 13128, 13128, 13128, -1, 13129, 13129, 13129, -1, + 13130, 13130, 13130, -1, 13131, 13131, 13131, -1, + 13132, 13132, 13132, -1, 13133, 13133, 13133, -1, + 13134, 13134, 13134, -1, 13135, 13135, 13135, -1, + 13136, 13136, 13136, -1, 13137, 13137, 13137, -1, + 13138, 13138, 13138, -1, 13139, 13139, 13139, -1, + 13140, 13140, 13140, -1, 13141, 13141, 13141, -1, + 13142, 13142, 13142, -1, 13143, 13143, 13143, -1, + 13144, 13144, 13144, -1, 13145, 13145, 13145, -1, + 13146, 13146, 13146, -1, 13147, 13147, 13147, -1, + 13148, 13148, 13148, -1, 13149, 13149, 13149, -1, + 13150, 13150, 13150, -1, 13151, 13151, 13151, -1, + 13152, 13152, 13152, -1, 13153, 13153, 13153, -1, + 13154, 13154, 13154, -1, 13155, 13155, 13155, -1, + 13156, 13156, 13156, -1, 13157, 13157, 13157, -1, + 13158, 13158, 13158, -1, 13159, 13159, 13159, -1, + 13160, 13160, 13160, -1, 13161, 13161, 13161, -1, + 13162, 13162, 13162, -1, 13163, 13163, 13163, -1, + 13164, 13164, 13164, -1, 13165, 13165, 13165, -1, + 13166, 13166, 13166, -1, 13167, 13167, 13167, -1, + 13168, 13168, 13168, -1, 13169, 13169, 13169, -1, + 13170, 13170, 13170, -1, 13171, 13171, 13171, -1, + 13172, 13172, 13172, -1, 13173, 13173, 13173, -1, + 13174, 13174, 13174, -1, 13175, 13175, 13175, -1, + 13176, 13176, 13176, -1, 13177, 13177, 13177, -1, + 13178, 13178, 13178, -1, 13179, 13179, 13179, -1, + 13180, 13180, 13180, -1, 13181, 13181, 13181, -1, + 13182, 13182, 13182, -1, 13183, 13183, 13183, -1, + 13184, 13184, 13184, -1, 13185, 13185, 13185, -1, + 13186, 13186, 13186, -1, 13187, 13187, 13187, -1, + 13188, 13188, 13188, -1, 13189, 13189, 13189, -1, + 13190, 13190, 13190, -1, 13191, 13191, 13191, -1, + 13192, 13192, 13192, -1, 13193, 13193, 13193, -1, + 13194, 13194, 13194, -1, 13195, 13195, 13195, -1, + 13196, 13196, 13196, -1, 13197, 13197, 13197, -1, + 13198, 13198, 13198, -1, 13199, 13199, 13199, -1, + 13200, 13200, 13200, -1, 13201, 13201, 13201, -1, + 13202, 13202, 13202, -1, 13203, 13203, 13203, -1, + 13204, 13204, 13204, -1, 13205, 13205, 13205, -1, + 13206, 13206, 13206, -1, 13207, 13207, 13207, -1, + 13208, 13208, 13208, -1, 13209, 13209, 13209, -1, + 13210, 13210, 13210, -1, 13211, 13211, 13211, -1, + 13212, 13212, 13212, -1, 13213, 13213, 13213, -1, + 13214, 13214, 13214, -1, 13215, 13215, 13215, -1, + 13216, 13216, 13216, -1, 13217, 13217, 13217, -1, + 13218, 13218, 13218, -1, 13219, 13219, 13219, -1, + 13220, 13220, 13220, -1, 13221, 13221, 13221, -1, + 13222, 13222, 13222, -1, 13223, 13223, 13223, -1, + 13224, 13224, 13224, -1, 13225, 13225, 13225, -1, + 13226, 13226, 13226, -1, 13227, 13227, 13227, -1, + 13228, 13228, 13228, -1, 13229, 13229, 13229, -1, + 13230, 13230, 13230, -1, 13231, 13231, 13231, -1, + 13232, 13232, 13232, -1, 13233, 13233, 13233, -1, + 13234, 13234, 13234, -1, 13235, 13235, 13235, -1, + 13236, 13236, 13236, -1, 13237, 13237, 13237, -1, + 13238, 13238, 13238, -1, 13239, 13239, 13239, -1, + 13240, 13240, 13240, -1, 13241, 13241, 13241, -1, + 13242, 13242, 13242, -1, 13243, 13243, 13243, -1, + 13244, 13244, 13244, -1, 13245, 13245, 13245, -1, + 13246, 13246, 13246, -1, 13247, 13247, 13247, -1, + 13248, 13248, 13248, -1, 13249, 13249, 13249, -1, + 13250, 13250, 13250, -1, 13251, 13251, 13251, -1, + 13252, 13252, 13252, -1, 13253, 13253, 13253, -1, + 13254, 13254, 13254, -1, 13255, 13255, 13255, -1, + 13256, 13256, 13256, -1, 13257, 13257, 13257, -1, + 13258, 13258, 13258, -1, 13259, 13259, 13259, -1, + 13260, 13260, 13260, -1, 13261, 13261, 13261, -1, + 13262, 13262, 13262, -1, 13263, 13263, 13263, -1, + 13264, 13264, 13264, -1, 13265, 13265, 13265, -1, + 13266, 13266, 13266, -1, 13267, 13267, 13267, -1, + 13268, 13268, 13268, -1, 13269, 13269, 13269, -1, + 13270, 13270, 13270, -1, 13271, 13271, 13271, -1, + 13272, 13272, 13272, -1, 13273, 13273, 13273, -1, + 13274, 13274, 13274, -1, 13275, 13275, 13275, -1, + 13276, 13276, 13276, -1, 13277, 13277, 13277, -1, + 13278, 13278, 13278, -1, 13279, 13279, 13279, -1, + 13280, 13280, 13280, -1, 13281, 13281, 13281, -1, + 13282, 13282, 13282, -1, 13283, 13283, 13283, -1, + 13284, 13284, 13284, -1, 13285, 13285, 13285, -1, + 13286, 13286, 13286, -1, 13287, 13287, 13287, -1, + 13288, 13288, 13288, -1, 13289, 13289, 13289, -1, + 13290, 13290, 13290, -1, 13291, 13291, 13291, -1, + 13292, 13292, 13292, -1, 13293, 13293, 13293, -1, + 13294, 13294, 13294, -1, 13295, 13295, 13295, -1, + 13296, 13296, 13296, -1, 13297, 13297, 13297, -1, + 13298, 13298, 13298, -1, 13299, 13299, 13299, -1, + 13300, 13300, 13300, -1, 13301, 13301, 13301, -1, + 13302, 13302, 13302, -1, 13303, 13303, 13303, -1, + 13304, 13304, 13304, -1, 13305, 13305, 13305, -1, + 13306, 13306, 13306, -1, 13307, 13307, 13307, -1, + 13308, 13308, 13308, -1, 13309, 13309, 13309, -1, + 13310, 13310, 13310, -1, 13311, 13311, 13311, -1, + 13312, 13312, 13312, -1, 13313, 13313, 13313, -1, + 13314, 13314, 13314, -1, 13315, 13315, 13315, -1, + 13316, 13316, 13316, -1, 13317, 13317, 13317, -1, + 13318, 13318, 13318, -1, 13319, 13319, 13319, -1, + 13320, 13320, 13320, -1, 13321, 13321, 13321, -1, + 13322, 13322, 13322, -1, 13323, 13323, 13323, -1, + 13324, 13324, 13324, -1, 13325, 13325, 13325, -1, + 13326, 13326, 13326, -1, 13327, 13327, 13327, -1, + 13328, 13328, 13328, -1, 13329, 13329, 13329, -1, + 13330, 13330, 13330, -1, 13331, 13331, 13331, -1, + 13332, 13332, 13332, -1, 13333, 13333, 13333, -1, + 13334, 13334, 13334, -1, 13335, 13335, 13335, -1, + 13336, 13336, 13336, -1, 13337, 13337, 13337, -1, + 13338, 13338, 13338, -1, 13339, 13339, 13339, -1, + 13340, 13340, 13340, -1, 13341, 13341, 13341, -1, + 13342, 13342, 13342, -1, 13343, 13343, 13343, -1, + 13344, 13344, 13344, -1, 13345, 13345, 13345, -1, + 13346, 13346, 13346, -1, 13347, 13347, 13347, -1, + 13348, 13348, 13348, -1, 13349, 13349, 13349, -1, + 13350, 13350, 13350, -1, 13351, 13351, 13351, -1, + 13352, 13352, 13352, -1, 13353, 13353, 13353, -1, + 13354, 13354, 13354, -1, 13355, 13355, 13355, -1, + 13356, 13356, 13356, -1, 13357, 13357, 13357, -1, + 13358, 13358, 13358, -1, 13359, 13359, 13359, -1, + 13360, 13360, 13360, -1, 13361, 13361, 13361, -1, + 13362, 13362, 13362, -1, 13363, 13363, 13363, -1, + 13364, 13364, 13364, -1, 13365, 13365, 13365, -1, + 13366, 13366, 13366, -1, 13367, 13367, 13367, -1, + 13368, 13368, 13368, -1, 13369, 13369, 13369, -1, + 13370, 13370, 13370, -1, 13371, 13371, 13371, -1, + 13372, 13372, 13372, -1, 13373, 13373, 13373, -1, + 13374, 13374, 13374, -1, 13375, 13375, 13375, -1, + 13376, 13376, 13376, -1, 13377, 13377, 13377, -1, + 13378, 13378, 13378, -1, 13379, 13379, 13379, -1, + 13380, 13380, 13380, -1, 13381, 13381, 13381, -1, + 13382, 13382, 13382, -1, 13383, 13383, 13383, -1, + 13384, 13384, 13384, -1, 13385, 13385, 13385, -1, + 13386, 13386, 13386, -1, 13387, 13387, 13387, -1, + 13388, 13388, 13388, -1, 13389, 13389, 13389, -1, + 13390, 13390, 13390, -1, 13391, 13391, 13391, -1, + 13392, 13392, 13392, -1, 13393, 13393, 13393, -1, + 13394, 13394, 13394, -1, 13395, 13395, 13395, -1, + 13396, 13396, 13396, -1, 13397, 13397, 13397, -1, + 13398, 13398, 13398, -1, 13399, 13399, 13399, -1, + 13400, 13400, 13400, -1, 13401, 13401, 13401, -1, + 13402, 13402, 13402, -1, 13403, 13403, 13403, -1, + 13404, 13404, 13404, -1, 13405, 13405, 13405, -1, + 13406, 13406, 13406, -1, 13407, 13407, 13407, -1, + 13408, 13408, 13408, -1, 13409, 13409, 13409, -1, + 13410, 13410, 13410, -1, 13411, 13411, 13411, -1, + 13412, 13412, 13412, -1, 13413, 13413, 13413, -1, + 13414, 13414, 13414, -1, 13415, 13415, 13415, -1, + 13416, 13416, 13416, -1, 13417, 13417, 13417, -1, + 13418, 13418, 13418, -1, 13419, 13419, 13419, -1, + 13420, 13420, 13420, -1, 13421, 13421, 13421, -1, + 13422, 13422, 13422, -1, 13423, 13423, 13423, -1, + 13424, 13424, 13424, -1, 13425, 13425, 13425, -1, + 13426, 13426, 13426, -1, 13427, 13427, 13427, -1, + 13428, 13428, 13428, -1, 13429, 13429, 13429, -1, + 13430, 13430, 13430, -1, 13431, 13431, 13431, -1, + 13432, 13432, 13432, -1, 13433, 13433, 13433, -1, + 13434, 13434, 13434, -1, 13435, 13435, 13435, -1, + 13436, 13436, 13436, -1, 13437, 13437, 13437, -1, + 13438, 13438, 13438, -1, 13439, 13439, 13439, -1, + 13440, 13440, 13440, -1, 13441, 13441, 13441, -1, + 13442, 13442, 13442, -1, 13443, 13443, 13443, -1, + 13444, 13444, 13444, -1, 13445, 13445, 13445, -1, + 13446, 13446, 13446, -1, 13447, 13447, 13447, -1, + 13448, 13448, 13448, -1, 13449, 13449, 13449, -1, + 13450, 13450, 13450, -1, 13451, 13451, 13451, -1, + 13452, 13452, 13452, -1, 13453, 13453, 13453, -1, + 13454, 13454, 13454, -1, 13455, 13455, 13455, -1, + 13456, 13456, 13456, -1, 13457, 13457, 13457, -1, + 13458, 13458, 13458, -1, 13459, 13459, 13459, -1, + 13460, 13460, 13460, -1, 13461, 13461, 13461, -1, + 13462, 13462, 13462, -1, 13463, 13463, 13463, -1, + 13464, 13464, 13464, -1, 13465, 13465, 13465, -1, + 13466, 13466, 13466, -1, 13467, 13467, 13467, -1, + 13468, 13468, 13468, -1, 13469, 13469, 13469, -1, + 13470, 13470, 13470, -1, 13471, 13471, 13471, -1, + 13472, 13472, 13472, -1, 13473, 13473, 13473, -1, + 13474, 13474, 13474, -1, 13475, 13475, 13475, -1, + 13476, 13476, 13476, -1, 13477, 13477, 13477, -1, + 13478, 13478, 13478, -1, 13479, 13479, 13479, -1, + 13480, 13480, 13480, -1, 13481, 13481, 13481, -1, + 13482, 13482, 13482, -1, 13483, 13483, 13483, -1, + 13484, 13484, 13484, -1, 13485, 13485, 13485, -1, + 13486, 13486, 13486, -1, 13487, 13487, 13487, -1, + 13488, 13488, 13488, -1, 13489, 13489, 13489, -1, + 13490, 13490, 13490, -1, 13491, 13491, 13491, -1, + 13492, 13492, 13492, -1, 13493, 13493, 13493, -1, + 13494, 13494, 13494, -1, 13495, 13495, 13495, -1, + 13496, 13496, 13496, -1, 13497, 13497, 13497, -1, + 13498, 13498, 13498, -1, 13499, 13499, 13499, -1, + 13500, 13500, 13500, -1, 13501, 13501, 13501, -1, + 13502, 13502, 13502, -1, 13503, 13503, 13503, -1, + 13504, 13504, 13504, -1, 13505, 13505, 13505, -1, + 13506, 13506, 13506, -1, 13507, 13507, 13507, -1, + 13508, 13508, 13508, -1, 13509, 13509, 13509, -1, + 13510, 13510, 13510, -1, 13511, 13511, 13511, -1, + 13512, 13512, 13512, -1, 13513, 13513, 13513, -1, + 13514, 13514, 13514, -1, 13515, 13515, 13515, -1, + 13516, 13516, 13516, -1, 13517, 13517, 13517, -1, + 13518, 13518, 13518, -1, 13519, 13519, 13519, -1, + 13520, 13520, 13520, -1, 13521, 13521, 13521, -1, + 13522, 13522, 13522, -1, 13523, 13523, 13523, -1, + 13524, 13524, 13524, -1, 13525, 13525, 13525, -1, + 13526, 13526, 13526, -1, 13527, 13527, 13527, -1, + 13528, 13528, 13528, -1, 13529, 13529, 13529, -1, + 13530, 13530, 13530, -1, 13531, 13531, 13531, -1, + 13532, 13532, 13532, -1, 13533, 13533, 13533, -1, + 13534, 13534, 13534, -1, 13535, 13535, 13535, -1, + 13536, 13536, 13536, -1, 13537, 13537, 13537, -1, + 13538, 13538, 13538, -1, 13539, 13539, 13539, -1, + 13540, 13540, 13540, -1, 13541, 13541, 13541, -1, + 13542, 13542, 13542, -1, 13543, 13543, 13543, -1, + 13544, 13544, 13544, -1, 13545, 13545, 13545, -1, + 13546, 13546, 13546, -1, 13547, 13547, 13547, -1, + 13548, 13548, 13548, -1, 13549, 13549, 13549, -1, + 13550, 13550, 13550, -1, 13551, 13551, 13551, -1, + 13552, 13552, 13552, -1, 13553, 13553, 13553, -1, + 13554, 13554, 13554, -1, 13555, 13555, 13555, -1, + 13556, 13556, 13556, -1, 13557, 13557, 13557, -1, + 13558, 13558, 13558, -1, 13559, 13559, 13559, -1, + 13560, 13560, 13560, -1, 13561, 13561, 13561, -1, + 13562, 13562, 13562, -1, 13563, 13563, 13563, -1, + 13564, 13564, 13564, -1, 13565, 13565, 13565, -1, + 13566, 13566, 13566, -1, 13567, 13567, 13567, -1, + 13568, 13568, 13568, -1, 13569, 13569, 13569, -1, + 13570, 13570, 13570, -1, 13571, 13571, 13571, -1, + 13572, 13572, 13572, -1, 13573, 13573, 13573, -1, + 13574, 13574, 13574, -1, 13575, 13575, 13575, -1, + 13576, 13576, 13576, -1, 13577, 13577, 13577, -1, + 13578, 13578, 13578, -1, 13579, 13579, 13579, -1, + 13580, 13580, 13580, -1, 13581, 13581, 13581, -1, + 13582, 13582, 13582, -1, 13583, 13583, 13583, -1, + 13584, 13584, 13584, -1, 13585, 13585, 13585, -1, + 13586, 13586, 13586, -1, 13587, 13587, 13587, -1, + 13588, 13588, 13588, -1, 13589, 13589, 13589, -1, + 13590, 13590, 13590, -1, 13591, 13591, 13591, -1, + 13592, 13592, 13592, -1, 13593, 13593, 13593, -1, + 13594, 13594, 13594, -1, 13595, 13595, 13595, -1, + 13596, 13596, 13596, -1, 13597, 13597, 13597, -1, + 13598, 13598, 13598, -1, 13599, 13599, 13599, -1, + 13600, 13600, 13600, -1, 13601, 13601, 13601, -1, + 13602, 13602, 13602, -1, 13603, 13603, 13603, -1, + 13604, 13604, 13604, -1, 13605, 13605, 13605, -1, + 13606, 13606, 13606, -1, 13607, 13607, 13607, -1, + 13608, 13608, 13608, -1, 13609, 13609, 13609, -1, + 13610, 13610, 13610, -1, 13611, 13611, 13611, -1, + 13612, 13612, 13612, -1, 13613, 13613, 13613, -1, + 13614, 13614, 13614, -1, 13615, 13615, 13615, -1, + 13616, 13616, 13616, -1, 13617, 13617, 13617, -1, + 13618, 13618, 13618, -1, 13619, 13619, 13619, -1, + 13620, 13620, 13620, -1, 13621, 13621, 13621, -1, + 13622, 13622, 13622, -1, 13623, 13623, 13623, -1, + 13624, 13624, 13624, -1, 13625, 13625, 13625, -1, + 13626, 13626, 13626, -1, 13627, 13627, 13627, -1, + 13628, 13628, 13628, -1, 13629, 13629, 13629, -1, + 13630, 13630, 13630, -1, 13631, 13631, 13631, -1, + 13632, 13632, 13632, -1, 13633, 13633, 13633, -1, + 13634, 13634, 13634, -1, 13635, 13635, 13635, -1, + 13636, 13636, 13636, -1, 13637, 13637, 13637, -1, + 13638, 13638, 13638, -1, 13639, 13639, 13639, -1, + 13640, 13640, 13640, -1, 13641, 13641, 13641, -1, + 13642, 13642, 13642, -1, 13643, 13643, 13643, -1, + 13644, 13644, 13644, -1, 13645, 13645, 13645, -1, + 13646, 13646, 13646, -1, 13647, 13647, 13647, -1, + 13648, 13648, 13648, -1, 13649, 13649, 13649, -1, + 13650, 13650, 13650, -1, 13651, 13651, 13651, -1, + 13652, 13652, 13652, -1, 13653, 13653, 13653, -1, + 13654, 13654, 13654, -1, 13655, 13655, 13655, -1, + 13656, 13656, 13656, -1, 13657, 13657, 13657, -1, + 13658, 13658, 13658, -1, 13659, 13659, 13659, -1, + 13660, 13660, 13660, -1, 13661, 13661, 13661, -1, + 13662, 13662, 13662, -1, 13663, 13663, 13663, -1, + 13664, 13664, 13664, -1, 13665, 13665, 13665, -1, + 13666, 13666, 13666, -1, 13667, 13667, 13667, -1, + 13668, 13668, 13668, -1, 13669, 13669, 13669, -1, + 13670, 13670, 13670, -1, 13671, 13671, 13671, -1, + 13672, 13672, 13672, -1, 13673, 13673, 13673, -1, + 13674, 13674, 13674, -1, 13675, 13675, 13675, -1, + 13676, 13676, 13676, -1, 13677, 13677, 13677, -1, + 13678, 13678, 13678, -1, 13679, 13679, 13679, -1, + 13680, 13680, 13680, -1, 13681, 13681, 13681, -1, + 13682, 13682, 13682, -1, 13683, 13683, 13683, -1, + 13684, 13684, 13684, -1, 13685, 13685, 13685, -1, + 13686, 13686, 13686, -1, 13687, 13687, 13687, -1, + 13688, 13688, 13688, -1, 13689, 13689, 13689, -1, + 13690, 13690, 13690, -1, 13691, 13691, 13691, -1, + 13692, 13692, 13692, -1, 13693, 13693, 13693, -1, + 13694, 13694, 13694, -1, 13695, 13695, 13695, -1, + 13696, 13696, 13696, -1, 13697, 13697, 13697, -1, + 13698, 13698, 13698, -1, 13699, 13699, 13699, -1, + 13700, 13700, 13700, -1, 13701, 13701, 13701, -1, + 13702, 13702, 13702, -1, 13703, 13703, 13703, -1, + 13704, 13704, 13704, -1, 13705, 13705, 13705, -1, + 13706, 13706, 13706, -1, 13707, 13707, 13707, -1, + 13708, 13708, 13708, -1, 13709, 13709, 13709, -1, + 13710, 13710, 13710, -1, 13711, 13711, 13711, -1, + 13712, 13712, 13712, -1, 13713, 13713, 13713, -1, + 13714, 13714, 13714, -1, 13715, 13715, 13715, -1, + 13716, 13716, 13716, -1, 13717, 13717, 13717, -1, + 13718, 13718, 13718, -1, 13719, 13719, 13719, -1, + 13720, 13720, 13720, -1, 13721, 13721, 13721, -1, + 13722, 13722, 13722, -1, 13723, 13723, 13723, -1, + 13724, 13724, 13724, -1, 13725, 13725, 13725, -1, + 13726, 13726, 13726, -1, 13727, 13727, 13727, -1, + 13728, 13728, 13728, -1, 13729, 13729, 13729, -1, + 13730, 13730, 13730, -1, 13731, 13731, 13731, -1, + 13732, 13732, 13732, -1, 13733, 13733, 13733, -1, + 13734, 13734, 13734, -1, 13735, 13735, 13735, -1, + 13736, 13736, 13736, -1, 13737, 13737, 13737, -1, + 13738, 13738, 13738, -1, 13739, 13739, 13739, -1, + 13740, 13740, 13740, -1, 13741, 13741, 13741, -1, + 13742, 13742, 13742, -1, 13743, 13743, 13743, -1, + 13744, 13744, 13744, -1, 13745, 13745, 13745, -1, + 13746, 13746, 13746, -1, 13747, 13747, 13747, -1, + 13748, 13748, 13748, -1, 13749, 13749, 13749, -1, + 13750, 13750, 13750, -1, 13751, 13751, 13751, -1, + 13752, 13752, 13752, -1, 13753, 13753, 13753, -1, + 13754, 13754, 13754, -1, 13755, 13755, 13755, -1, + 13756, 13756, 13756, -1, 13757, 13757, 13757, -1, + 13758, 13758, 13758, -1, 13759, 13759, 13759, -1, + 13760, 13760, 13760, -1, 13761, 13761, 13761, -1, + 13762, 13762, 13762, -1, 13763, 13763, 13763, -1, + 13764, 13764, 13764, -1, 13765, 13765, 13765, -1, + 13766, 13766, 13766, -1, 13767, 13767, 13767, -1, + 13768, 13768, 13768, -1, 13769, 13769, 13769, -1, + 13770, 13770, 13770, -1, 13771, 13771, 13771, -1, + 13772, 13772, 13772, -1, 13773, 13773, 13773, -1, + 13774, 13774, 13774, -1, 13775, 13775, 13775, -1, + 13776, 13776, 13776, -1, 13777, 13777, 13777, -1, + 13778, 13778, 13778, -1, 13779, 13779, 13779, -1, + 13780, 13780, 13780, -1, 13781, 13781, 13781, -1, + 13782, 13782, 13782, -1, 13783, 13783, 13783, -1, + 13784, 13784, 13784, -1, 13785, 13785, 13785, -1, + 13786, 13786, 13786, -1, 13787, 13787, 13787, -1, + 13788, 13788, 13788, -1, 13789, 13789, 13789, -1, + 13790, 13790, 13790, -1, 13791, 13791, 13791, -1, + 13792, 13792, 13792, -1, 13793, 13793, 13793, -1, + 13794, 13794, 13794, -1, 13795, 13795, 13795, -1, + 13796, 13796, 13796, -1, 13797, 13797, 13797, -1, + 13798, 13798, 13798, -1, 13799, 13799, 13799, -1, + 13800, 13800, 13800, -1, 13801, 13801, 13801, -1, + 13802, 13802, 13802, -1, 13803, 13803, 13803, -1, + 13804, 13804, 13804, -1, 13805, 13805, 13805, -1, + 13806, 13806, 13806, -1, 13807, 13807, 13807, -1, + 13808, 13808, 13808, -1, 13809, 13809, 13809, -1, + 13810, 13810, 13810, -1, 13811, 13811, 13811, -1, + 13812, 13812, 13812, -1, 13813, 13813, 13813, -1, + 13814, 13814, 13814, -1, 13815, 13815, 13815, -1, + 13816, 13816, 13816, -1, 13817, 13817, 13817, -1, + 13818, 13818, 13818, -1, 13819, 13819, 13819, -1, + 13820, 13820, 13820, -1, 13821, 13821, 13821, -1, + 13822, 13822, 13822, -1, 13823, 13823, 13823, -1, + 13824, 13824, 13824, -1, 13825, 13825, 13825, -1, + 13826, 13826, 13826, -1, 13827, 13827, 13827, -1, + 13828, 13828, 13828, -1, 13829, 13829, 13829, -1, + 13830, 13830, 13830, -1, 13831, 13831, 13831, -1, + 13832, 13832, 13832, -1, 13833, 13833, 13833, -1, + 13834, 13834, 13834, -1, 13835, 13835, 13835, -1, + 13836, 13836, 13836, -1, 13837, 13837, 13837, -1, + 13838, 13838, 13838, -1, 13839, 13839, 13839, -1, + 13840, 13840, 13840, -1, 13841, 13841, 13841, -1, + 13842, 13842, 13842, -1, 13843, 13843, 13843, -1, + 13844, 13844, 13844, -1, 13845, 13845, 13845, -1, + 13846, 13846, 13846, -1, 13847, 13847, 13847, -1, + 13848, 13848, 13848, -1, 13849, 13849, 13849, -1, + 13850, 13850, 13850, -1, 13851, 13851, 13851, -1, + 13852, 13852, 13852, -1, 13853, 13853, 13853, -1, + 13854, 13854, 13854, -1, 13855, 13855, 13855, -1, + 13856, 13856, 13856, -1, 13857, 13857, 13857, -1, + 13858, 13858, 13858, -1, 13859, 13859, 13859, -1, + 13860, 13860, 13860, -1, 13861, 13861, 13861, -1, + 13862, 13862, 13862, -1, 13863, 13863, 13863, -1, + 13864, 13864, 13864, -1, 13865, 13865, 13865, -1, + 13866, 13866, 13866, -1, 13867, 13867, 13867, -1, + 13868, 13868, 13868, -1, 13869, 13869, 13869, -1, + 13870, 13870, 13870, -1, 13871, 13871, 13871, -1, + 13872, 13872, 13872, -1, 13873, 13873, 13873, -1, + 13874, 13874, 13874, -1, 13875, 13875, 13875, -1, + 13876, 13876, 13876, -1, 13877, 13877, 13877, -1, + 13878, 13878, 13878, -1, 13879, 13879, 13879, -1, + 13880, 13880, 13880, -1, 13881, 13881, 13881, -1, + 13882, 13882, 13882, -1, 13883, 13883, 13883, -1, + 13884, 13884, 13884, -1, 13885, 13885, 13885, -1, + 13886, 13886, 13886, -1, 13887, 13887, 13887, -1, + 13888, 13888, 13888, -1, 13889, 13889, 13889, -1, + 13890, 13890, 13890, -1, 13891, 13891, 13891, -1, + 13892, 13892, 13892, -1, 13893, 13893, 13893, -1, + 13894, 13894, 13894, -1, 13895, 13895, 13895, -1, + 13896, 13896, 13896, -1, 13897, 13897, 13897, -1, + 13898, 13898, 13898, -1, 13899, 13899, 13899, -1, + 13900, 13900, 13900, -1, 13901, 13901, 13901, -1, + 13902, 13902, 13902, -1, 13903, 13903, 13903, -1, + 13904, 13904, 13904, -1, 13905, 13905, 13905, -1, + 13906, 13906, 13906, -1, 13907, 13907, 13907, -1, + 13908, 13908, 13908, -1, 13909, 13909, 13909, -1, + 13910, 13910, 13910, -1, 13911, 13911, 13911, -1, + 13912, 13912, 13912, -1, 13913, 13913, 13913, -1, + 13914, 13914, 13914, -1, 13915, 13915, 13915, -1, + 13916, 13916, 13916, -1, 13917, 13917, 13917, -1, + 13918, 13918, 13918, -1, 13919, 13919, 13919, -1, + 13920, 13920, 13920, -1, 13921, 13921, 13921, -1, + 13922, 13922, 13922, -1, 13923, 13923, 13923, -1, + 13924, 13924, 13924, -1, 13925, 13925, 13925, -1, + 13926, 13926, 13926, -1, 13927, 13927, 13927, -1, + 13928, 13928, 13928, -1, 13929, 13929, 13929, -1, + 13930, 13930, 13930, -1, 13931, 13931, 13931, -1, + 13932, 13932, 13932, -1, 13933, 13933, 13933, -1, + 13934, 13934, 13934, -1, 13935, 13935, 13935, -1, + 13936, 13936, 13936, -1, 13937, 13937, 13937, -1, + 13938, 13938, 13938, -1, 13939, 13939, 13939, -1, + 13940, 13940, 13940, -1, 13941, 13941, 13941, -1, + 13942, 13942, 13942, -1, 13943, 13943, 13943, -1, + 13944, 13944, 13944, -1, 13945, 13945, 13945, -1, + 13946, 13946, 13946, -1, 13947, 13947, 13947, -1, + 13948, 13948, 13948, -1, 13949, 13949, 13949, -1, + 13950, 13950, 13950, -1, 13951, 13951, 13951, -1, + 13952, 13952, 13952, -1, 13953, 13953, 13953, -1, + 13954, 13954, 13954, -1, 13955, 13955, 13955, -1, + 13956, 13956, 13956, -1, 13957, 13957, 13957, -1, + 13958, 13958, 13958, -1, 13959, 13959, 13959, -1, + 13960, 13960, 13960, -1, 13961, 13961, 13961, -1, + 13962, 13962, 13962, -1, 13963, 13963, 13963, -1, + 13964, 13964, 13964, -1, 13965, 13965, 13965, -1, + 13966, 13966, 13966, -1, 13967, 13967, 13967, -1, + 13968, 13968, 13968, -1, 13969, 13969, 13969, -1, + 13970, 13970, 13970, -1, 13971, 13971, 13971, -1, + 13972, 13972, 13972, -1, 13973, 13973, 13973, -1, + 13974, 13974, 13974, -1, 13975, 13975, 13975, -1, + 13976, 13976, 13976, -1, 13977, 13977, 13977, -1, + 13978, 13978, 13978, -1, 13979, 13979, 13979, -1, + 13980, 13980, 13980, -1, 13981, 13981, 13981, -1, + 13982, 13982, 13982, -1, 13983, 13983, 13983, -1, + 13984, 13984, 13984, -1, 13985, 13985, 13985, -1, + 13986, 13986, 13986, -1, 13987, 13987, 13987, -1, + 13988, 13988, 13988, -1, 13989, 13989, 13989, -1, + 13990, 13990, 13990, -1, 13991, 13991, 13991, -1, + 13992, 13992, 13992, -1, 13993, 13993, 13993, -1, + 13994, 13994, 13994, -1, 13995, 13995, 13995, -1, + 13996, 13996, 13996, -1, 13997, 13997, 13997, -1, + 13998, 13998, 13998, -1, 13999, 13999, 13999, -1, + 14000, 14000, 14000, -1, 14001, 14001, 14001, -1, + 14002, 14002, 14002, -1, 14003, 14003, 14003, -1, + 14004, 14004, 14004, -1, 14005, 14005, 14005, -1, + 14006, 14006, 14006, -1, 14007, 14007, 14007, -1, + 14008, 14008, 14008, -1, 14009, 14009, 14009, -1, + 14010, 14010, 14010, -1, 14011, 14011, 14011, -1, + 14012, 14012, 14012, -1, 14013, 14013, 14013, -1, + 14014, 14014, 14014, -1, 14015, 14015, 14015, -1, + 14016, 14016, 14016, -1, 14017, 14017, 14017, -1, + 14018, 14018, 14018, -1, 14019, 14019, 14019, -1, + 14020, 14020, 14020, -1, 14021, 14021, 14021, -1, + 14022, 14022, 14022, -1, 14023, 14023, 14023, -1, + 14024, 14024, 14024, -1, 14025, 14025, 14025, -1, + 14026, 14026, 14026, -1, 14027, 14027, 14027, -1, + 14028, 14028, 14028, -1, 14029, 14029, 14029, -1, + 14030, 14030, 14030, -1, 14031, 14031, 14031, -1, + 14032, 14032, 14032, -1, 14033, 14033, 14033, -1, + 14034, 14034, 14034, -1, 14035, 14035, 14035, -1, + 14036, 14036, 14036, -1, 14037, 14037, 14037, -1, + 14038, 14038, 14038, -1, 14039, 14039, 14039, -1, + 14040, 14040, 14040, -1, 14041, 14041, 14041, -1, + 14042, 14042, 14042, -1, 14043, 14043, 14043, -1, + 14044, 14044, 14044, -1, 14045, 14045, 14045, -1, + 14046, 14046, 14046, -1, 14047, 14047, 14047, -1, + 14048, 14048, 14048, -1, 14049, 14049, 14049, -1, + 14050, 14050, 14050, -1, 14051, 14051, 14051, -1, + 14052, 14052, 14052, -1, 14053, 14053, 14053, -1, + 14054, 14054, 14054, -1, 14055, 14055, 14055, -1, + 14056, 14056, 14056, -1, 14057, 14057, 14057, -1, + 14058, 14058, 14058, -1, 14059, 14059, 14059, -1, + 14060, 14060, 14060, -1, 14061, 14061, 14061, -1, + 14062, 14062, 14062, -1, 14063, 14063, 14063, -1, + 14064, 14064, 14064, -1, 14065, 14065, 14065, -1, + 14066, 14066, 14066, -1, 14067, 14067, 14067, -1, + 14068, 14068, 14068, -1, 14069, 14069, 14069, -1, + 14070, 14070, 14070, -1, 14071, 14071, 14071, -1, + 14072, 14072, 14072, -1, 14073, 14073, 14073, -1, + 14074, 14074, 14074, -1, 14075, 14075, 14075, -1, + 14076, 14076, 14076, -1, 14077, 14077, 14077, -1, + 14078, 14078, 14078, -1, 14079, 14079, 14079, -1, + 14080, 14080, 14080, -1, 14081, 14081, 14081, -1, + 14082, 14082, 14082, -1, 14083, 14083, 14083, -1, + 14084, 14084, 14084, -1, 14085, 14085, 14085, -1, + 14086, 14086, 14086, -1, 14087, 14087, 14087, -1, + 14088, 14088, 14088, -1, 14089, 14089, 14089, -1, + 14090, 14090, 14090, -1, 14091, 14091, 14091, -1, + 14092, 14092, 14092, -1, 14093, 14093, 14093, -1, + 14094, 14094, 14094, -1, 14095, 14095, 14095, -1, + 14096, 14096, 14096, -1, 14097, 14097, 14097, -1, + 14098, 14098, 14098, -1, 14099, 14099, 14099, -1, + 14100, 14100, 14100, -1, 14101, 14101, 14101, -1, + 14102, 14102, 14102, -1, 14103, 14103, 14103, -1, + 14104, 14104, 14104, -1, 14105, 14105, 14105, -1, + 14106, 14106, 14106, -1, 14107, 14107, 14107, -1, + 14108, 14108, 14108, -1, 14109, 14109, 14109, -1, + 14110, 14110, 14110, -1, 14111, 14111, 14111, -1, + 14112, 14112, 14112, -1, 14113, 14113, 14113, -1, + 14114, 14114, 14114, -1, 14115, 14115, 14115, -1, + 14116, 14116, 14116, -1, 14117, 14117, 14117, -1, + 14118, 14118, 14118, -1, 14119, 14119, 14119, -1, + 14120, 14120, 14120, -1, 14121, 14121, 14121, -1, + 14122, 14122, 14122, -1, 14123, 14123, 14123, -1, + 14124, 14124, 14124, -1, 14125, 14125, 14125, -1, + 14126, 14126, 14126, -1, 14127, 14127, 14127, -1, + 14128, 14128, 14128, -1, 14129, 14129, 14129, -1, + 14130, 14130, 14130, -1, 14131, 14131, 14131, -1, + 14132, 14132, 14132, -1, 14133, 14133, 14133, -1, + 14134, 14134, 14134, -1, 14135, 14135, 14135, -1, + 14136, 14136, 14136, -1, 14137, 14137, 14137, -1, + 14138, 14138, 14138, -1, 14139, 14139, 14139, -1, + 14140, 14140, 14140, -1, 14141, 14141, 14141, -1, + 14142, 14142, 14142, -1, 14143, 14143, 14143, -1, + 14144, 14144, 14144, -1, 14145, 14145, 14145, -1, + 14146, 14146, 14146, -1, 14147, 14147, 14147, -1, + 14148, 14148, 14148, -1, 14149, 14149, 14149, -1, + 14150, 14150, 14150, -1, 14151, 14151, 14151, -1, + 14152, 14152, 14152, -1, 14153, 14153, 14153, -1, + 14154, 14154, 14154, -1, 14155, 14155, 14155, -1, + 14156, 14156, 14156, -1, 14157, 14157, 14157, -1, + 14158, 14158, 14158, -1, 14159, 14159, 14159, -1, + 14160, 14160, 14160, -1, 14161, 14161, 14161, -1, + 14162, 14162, 14162, -1, 14163, 14163, 14163, -1, + 14164, 14164, 14164, -1, 14165, 14165, 14165, -1, + 14166, 14166, 14166, -1, 14167, 14167, 14167, -1, + 14168, 14168, 14168, -1, 14169, 14169, 14169, -1, + 14170, 14170, 14170, -1, 14171, 14171, 14171, -1, + 14172, 14172, 14172, -1, 14173, 14173, 14173, -1, + 14174, 14174, 14174, -1, 14175, 14175, 14175, -1, + 14176, 14176, 14176, -1, 14177, 14177, 14177, -1, + 14178, 14178, 14178, -1, 14179, 14179, 14179, -1, + 14180, 14180, 14180, -1, 14181, 14181, 14181, -1, + 14182, 14182, 14182, -1, 14183, 14183, 14183, -1, + 14184, 14184, 14184, -1, 14185, 14185, 14185, -1, + 14186, 14186, 14186, -1, 14187, 14187, 14187, -1, + 14188, 14188, 14188, -1, 14189, 14189, 14189, -1, + 14190, 14190, 14190, -1, 14191, 14191, 14191, -1, + 14192, 14192, 14192, -1, 14193, 14193, 14193, -1, + 14194, 14194, 14194, -1, 14195, 14195, 14195, -1, + 14196, 14196, 14196, -1, 14197, 14197, 14197, -1, + 14198, 14198, 14198, -1, 14199, 14199, 14199, -1, + 14200, 14200, 14200, -1, 14201, 14201, 14201, -1, + 14202, 14202, 14202, -1, 14203, 14203, 14203, -1, + 14204, 14204, 14204, -1, 14205, 14205, 14205, -1, + 14206, 14206, 14206, -1, 14207, 14207, 14207, -1, + 14208, 14208, 14208, -1, 14209, 14209, 14209, -1, + 14210, 14210, 14210, -1, 14211, 14211, 14211, -1, + 14212, 14212, 14212, -1, 14213, 14213, 14213, -1, + 14214, 14214, 14214, -1, 14215, 14215, 14215, -1, + 14216, 14216, 14216, -1, 14217, 14217, 14217, -1, + 14218, 14218, 14218, -1, 14219, 14219, 14219, -1, + 14220, 14220, 14220, -1, 14221, 14221, 14221, -1, + 14222, 14222, 14222, -1, 14223, 14223, 14223, -1, + 14224, 14224, 14224, -1, 14225, 14225, 14225, -1, + 14226, 14226, 14226, -1, 14227, 14227, 14227, -1, + 14228, 14228, 14228, -1, 14229, 14229, 14229, -1, + 14230, 14230, 14230, -1, 14231, 14231, 14231, -1, + 14232, 14232, 14232, -1, 14233, 14233, 14233, -1, + 14234, 14234, 14234, -1, 14235, 14235, 14235, -1, + 14236, 14236, 14236, -1, 14237, 14237, 14237, -1, + 14238, 14238, 14238, -1, 14239, 14239, 14239, -1, + 14240, 14240, 14240, -1, 14241, 14241, 14241, -1, + 14242, 14242, 14242, -1, 14243, 14243, 14243, -1, + 14244, 14244, 14244, -1, 14245, 14245, 14245, -1, + 14246, 14246, 14246, -1, 14247, 14247, 14247, -1, + 14248, 14248, 14248, -1, 14249, 14249, 14249, -1, + 14250, 14250, 14250, -1, 14251, 14251, 14251, -1, + 14252, 14252, 14252, -1, 14253, 14253, 14253, -1, + 14254, 14254, 14254, -1, 14255, 14255, 14255, -1, + 14256, 14256, 14256, -1, 14257, 14257, 14257, -1, + 14258, 14258, 14258, -1, 14259, 14259, 14259, -1, + 14260, 14260, 14260, -1, 14261, 14261, 14261, -1, + 14262, 14262, 14262, -1, 14263, 14263, 14263, -1, + 14264, 14264, 14264, -1, 14265, 14265, 14265, -1, + 14266, 14266, 14266, -1, 14267, 14267, 14267, -1, + 14268, 14268, 14268, -1, 14269, 14269, 14269, -1, + 14270, 14270, 14270, -1, 14271, 14271, 14271, -1, + 14272, 14272, 14272, -1, 14273, 14273, 14273, -1, + 14274, 14274, 14274, -1, 14275, 14275, 14275, -1, + 14276, 14276, 14276, -1, 14277, 14277, 14277, -1, + 14278, 14278, 14278, -1, 14279, 14279, 14279, -1, + 14280, 14280, 14280, -1, 14281, 14281, 14281, -1, + 14282, 14282, 14282, -1, 14283, 14283, 14283, -1, + 14284, 14284, 14284, -1, 14285, 14285, 14285, -1, + 14286, 14286, 14286, -1, 14287, 14287, 14287, -1, + 14288, 14288, 14288, -1, 14289, 14289, 14289, -1, + 14290, 14290, 14290, -1, 14291, 14291, 14291, -1, + 14292, 14292, 14292, -1, 14293, 14293, 14293, -1, + 14294, 14294, 14294, -1, 14295, 14295, 14295, -1, + 14296, 14296, 14296, -1, 14297, 14297, 14297, -1, + 14298, 14298, 14298, -1, 14299, 14299, 14299, -1, + 14300, 14300, 14300, -1, 14301, 14301, 14301, -1, + 14302, 14302, 14302, -1, 14303, 14303, 14303, -1, + 14304, 14304, 14304, -1, 14305, 14305, 14305, -1, + 14306, 14306, 14306, -1, 14307, 14307, 14307, -1, + 14308, 14308, 14308, -1, 14309, 14309, 14309, -1, + 14310, 14310, 14310, -1, 14311, 14311, 14311, -1, + 14312, 14312, 14312, -1, 14313, 14313, 14313, -1, + 14314, 14314, 14314, -1, 14315, 14315, 14315, -1, + 14316, 14316, 14316, -1, 14317, 14317, 14317, -1, + 14318, 14318, 14318, -1, 14319, 14319, 14319, -1, + 14320, 14320, 14320, -1, 14321, 14321, 14321, -1, + 14322, 14322, 14322, -1, 14323, 14323, 14323, -1, + 14324, 14324, 14324, -1, 14325, 14325, 14325, -1, + 14326, 14326, 14326, -1, 14327, 14327, 14327, -1, + 14328, 14328, 14328, -1, 14329, 14329, 14329, -1, + 14330, 14330, 14330, -1, 14331, 14331, 14331, -1, + 14332, 14332, 14332, -1, 14333, 14333, 14333, -1, + 14334, 14334, 14334, -1, 14335, 14335, 14335, -1, + 14336, 14336, 14336, -1, 14337, 14337, 14337, -1, + 14338, 14338, 14338, -1, 14339, 14339, 14339, -1, + 14340, 14340, 14340, -1, 14341, 14341, 14341, -1, + 14342, 14342, 14342, -1, 14343, 14343, 14343, -1, + 14344, 14344, 14344, -1, 14345, 14345, 14345, -1, + 14346, 14346, 14346, -1, 14347, 14347, 14347, -1, + 14348, 14348, 14348, -1, 14349, 14349, 14349, -1, + 14350, 14350, 14350, -1, 14351, 14351, 14351, -1, + 14352, 14352, 14352, -1, 14353, 14353, 14353, -1, + 14354, 14354, 14354, -1, 14355, 14355, 14355, -1, + 14356, 14356, 14356, -1, 14357, 14357, 14357, -1, + 14358, 14358, 14358, -1, 14359, 14359, 14359, -1, + 14360, 14360, 14360, -1, 14361, 14361, 14361, -1, + 14362, 14362, 14362, -1, 14363, 14363, 14363, -1, + 14364, 14364, 14364, -1, 14365, 14365, 14365, -1, + 14366, 14366, 14366, -1, 14367, 14367, 14367, -1, + 14368, 14368, 14368, -1, 14369, 14369, 14369, -1, + 14370, 14370, 14370, -1, 14371, 14371, 14371, -1, + 14372, 14372, 14372, -1, 14373, 14373, 14373, -1, + 14374, 14374, 14374, -1, 14375, 14375, 14375, -1, + 14376, 14376, 14376, -1, 14377, 14377, 14377, -1, + 14378, 14378, 14378, -1, 14379, 14379, 14379, -1, + 14380, 14380, 14380, -1, 14381, 14381, 14381, -1, + 14382, 14382, 14382, -1, 14383, 14383, 14383, -1, + 14384, 14384, 14384, -1, 14385, 14385, 14385, -1, + 14386, 14386, 14386, -1, 14387, 14387, 14387, -1, + 14388, 14388, 14388, -1, 14389, 14389, 14389, -1, + 14390, 14390, 14390, -1, 14391, 14391, 14391, -1, + 14392, 14392, 14392, -1, 14393, 14393, 14393, -1, + 14394, 14394, 14394, -1, 14395, 14395, 14395, -1, + 14396, 14396, 14396, -1, 14397, 14397, 14397, -1, + 14398, 14398, 14398, -1, 14399, 14399, 14399, -1, + 14400, 14400, 14400, -1, 14401, 14401, 14401, -1, + 14402, 14402, 14402, -1, 14403, 14403, 14403, -1, + 14404, 14404, 14404, -1, 14405, 14405, 14405, -1, + 14406, 14406, 14406, -1, 14407, 14407, 14407, -1, + 14408, 14408, 14408, -1, 14409, 14409, 14409, -1, + 14410, 14410, 14410, -1, 14411, 14411, 14411, -1, + 14412, 14412, 14412, -1, 14413, 14413, 14413, -1, + 14414, 14414, 14414, -1, 14415, 14415, 14415, -1, + 14416, 14416, 14416, -1, 14417, 14417, 14417, -1, + 14418, 14418, 14418, -1, 14419, 14419, 14419, -1, + 14420, 14420, 14420, -1, 14421, 14421, 14421, -1, + 14422, 14422, 14422, -1, 14423, 14423, 14423, -1, + 14424, 14424, 14424, -1, 14425, 14425, 14425, -1, + 14426, 14426, 14426, -1, 14427, 14427, 14427, -1, + 14428, 14428, 14428, -1, 14429, 14429, 14429, -1, + 14430, 14430, 14430, -1, 14431, 14431, 14431, -1, + 14432, 14432, 14432, -1, 14433, 14433, 14433, -1, + 14434, 14434, 14434, -1, 14435, 14435, 14435, -1, + 14436, 14436, 14436, -1, 14437, 14437, 14437, -1, + 14438, 14438, 14438, -1, 14439, 14439, 14439, -1, + 14440, 14440, 14440, -1, 14441, 14441, 14441, -1, + 14442, 14442, 14442, -1, 14443, 14443, 14443, -1, + 14444, 14444, 14444, -1, 14445, 14445, 14445, -1, + 14446, 14446, 14446, -1, 14447, 14447, 14447, -1, + 14448, 14448, 14448, -1, 14449, 14449, 14449, -1, + 14450, 14450, 14450, -1, 14451, 14451, 14451, -1, + 14452, 14452, 14452, -1, 14453, 14453, 14453, -1, + 14454, 14454, 14454, -1, 14455, 14455, 14455, -1, + 14456, 14456, 14456, -1, 14457, 14457, 14457, -1, + 14458, 14458, 14458, -1, 14459, 14459, 14459, -1, + 14460, 14460, 14460, -1, 14461, 14461, 14461, -1, + 14462, 14462, 14462, -1, 14463, 14463, 14463, -1, + 14464, 14464, 14464, -1, 14465, 14465, 14465, -1, + 14466, 14466, 14466, -1, 14467, 14467, 14467, -1, + 14468, 14468, 14468, -1, 14469, 14469, 14469, -1, + 14470, 14470, 14470, -1, 14471, 14471, 14471, -1, + 14472, 14472, 14472, -1, 14473, 14473, 14473, -1, + 14474, 14474, 14474, -1, 14475, 14475, 14475, -1, + 14476, 14476, 14476, -1, 14477, 14477, 14477, -1, + 14478, 14478, 14478, -1, 14479, 14479, 14479, -1, + 14480, 14480, 14480, -1, 14481, 14481, 14481, -1, + 14482, 14482, 14482, -1, 14483, 14483, 14483, -1, + 14484, 14484, 14484, -1, 14485, 14485, 14485, -1, + 14486, 14486, 14486, -1, 14487, 14487, 14487, -1, + 14488, 14488, 14488, -1, 14489, 14489, 14489, -1, + 14490, 14490, 14490, -1, 14491, 14491, 14491, -1, + 14492, 14492, 14492, -1, 14493, 14493, 14493, -1, + 14494, 14494, 14494, -1, 14495, 14495, 14495, -1, + 14496, 14496, 14496, -1, 14497, 14497, 14497, -1, + 14498, 14498, 14498, -1, 14499, 14499, 14499, -1, + 14500, 14500, 14500, -1, 14501, 14501, 14501, -1, + 14502, 14502, 14502, -1, 14503, 14503, 14503, -1, + 14504, 14504, 14504, -1, 14505, 14505, 14505, -1, + 14506, 14506, 14506, -1, 14507, 14507, 14507, -1, + 14508, 14508, 14508, -1, 14509, 14509, 14509, -1, + 14510, 14510, 14510, -1, 14511, 14511, 14511, -1, + 14512, 14512, 14512, -1, 14513, 14513, 14513, -1, + 14514, 14514, 14514, -1, 14515, 14515, 14515, -1, + 14516, 14516, 14516, -1, 14517, 14517, 14517, -1, + 14518, 14518, 14518, -1, 14519, 14519, 14519, -1, + 14520, 14520, 14520, -1, 14521, 14521, 14521, -1, + 14522, 14522, 14522, -1, 14523, 14523, 14523, -1, + 14524, 14524, 14524, -1, 14525, 14525, 14525, -1, + 14526, 14526, 14526, -1, 14527, 14527, 14527, -1, + 14528, 14528, 14528, -1, 14529, 14529, 14529, -1, + 14530, 14530, 14530, -1, 14531, 14531, 14531, -1, + 14532, 14532, 14532, -1, 14533, 14533, 14533, -1, + 14534, 14534, 14534, -1, 14535, 14535, 14535, -1, + 14536, 14536, 14536, -1, 14537, 14537, 14537, -1, + 14538, 14538, 14538, -1, 14539, 14539, 14539, -1, + 14540, 14540, 14540, -1, 14541, 14541, 14541, -1, + 14542, 14542, 14542, -1, 14543, 14543, 14543, -1, + 14544, 14544, 14544, -1, 14545, 14545, 14545, -1, + 14546, 14546, 14546, -1, 14547, 14547, 14547, -1, + 14548, 14548, 14548, -1, 14549, 14549, 14549, -1, + 14550, 14550, 14550, -1, 14551, 14551, 14551, -1, + 14552, 14552, 14552, -1, 14553, 14553, 14553, -1, + 14554, 14554, 14554, -1, 14555, 14555, 14555, -1, + 14556, 14556, 14556, -1, 14557, 14557, 14557, -1, + 14558, 14558, 14558, -1, 14559, 14559, 14559, -1, + 14560, 14560, 14560, -1, 14561, 14561, 14561, -1, + 14562, 14562, 14562, -1, 14563, 14563, 14563, -1, + 14564, 14564, 14564, -1, 14565, 14565, 14565, -1, + 14566, 14566, 14566, -1, 14567, 14567, 14567, -1, + 14568, 14568, 14568, -1, 14569, 14569, 14569, -1, + 14570, 14570, 14570, -1, 14571, 14571, 14571, -1, + 14572, 14572, 14572, -1, 14573, 14573, 14573, -1, + 14574, 14574, 14574, -1, 14575, 14575, 14575, -1, + 14576, 14576, 14576, -1, 14577, 14577, 14577, -1, + 14578, 14578, 14578, -1, 14579, 14579, 14579, -1, + 14580, 14580, 14580, -1, 14581, 14581, 14581, -1, + 14582, 14582, 14582, -1, 14583, 14583, 14583, -1, + 14584, 14584, 14584, -1, 14585, 14585, 14585, -1, + 14586, 14586, 14586, -1, 14587, 14587, 14587, -1, + 14588, 14588, 14588, -1, 14589, 14589, 14589, -1, + 14590, 14590, 14590, -1, 14591, 14591, 14591, -1, + 14592, 14592, 14592, -1, 14593, 14593, 14593, -1, + 14594, 14594, 14594, -1, 14595, 14595, 14595, -1, + 14596, 14596, 14596, -1, 14597, 14597, 14597, -1, + 14598, 14598, 14598, -1, 14599, 14599, 14599, -1, + 14600, 14600, 14600, -1, 14601, 14601, 14601, -1, + 14602, 14602, 14602, -1, 14603, 14603, 14603, -1, + 14604, 14604, 14604, -1, 14605, 14605, 14605, -1, + 14606, 14606, 14606, -1, 14607, 14607, 14607, -1, + 14608, 14608, 14608, -1, 14609, 14609, 14609, -1, + 14610, 14610, 14610, -1, 14611, 14611, 14611, -1, + 14612, 14612, 14612, -1, 14613, 14613, 14613, -1, + 14614, 14614, 14614, -1, 14615, 14615, 14615, -1, + 14616, 14616, 14616, -1, 14617, 14617, 14617, -1, + 14618, 14618, 14618, -1, 14619, 14619, 14619, -1, + 14620, 14620, 14620, -1, 14621, 14621, 14621, -1, + 14622, 14622, 14622, -1, 14623, 14623, 14623, -1, + 14624, 14624, 14624, -1, 14625, 14625, 14625, -1, + 14626, 14626, 14626, -1, 14627, 14627, 14627, -1, + 14628, 14628, 14628, -1, 14629, 14629, 14629, -1, + 14630, 14630, 14630, -1, 14631, 14631, 14631, -1, + 14632, 14632, 14632, -1, 14633, 14633, 14633, -1, + 14634, 14634, 14634, -1, 14635, 14635, 14635, -1, + 14636, 14636, 14636, -1, 14637, 14637, 14637, -1, + 14638, 14638, 14638, -1, 14639, 14639, 14639, -1, + 14640, 14640, 14640, -1, 14641, 14641, 14641, -1, + 14642, 14642, 14642, -1, 14643, 14643, 14643, -1, + 14644, 14644, 14644, -1, 14645, 14645, 14645, -1, + 14646, 14646, 14646, -1, 14647, 14647, 14647, -1, + 14648, 14648, 14648, -1, 14649, 14649, 14649, -1, + 14650, 14650, 14650, -1, 14651, 14651, 14651, -1, + 14652, 14652, 14652, -1, 14653, 14653, 14653, -1, + 14654, 14654, 14654, -1, 14655, 14655, 14655, -1, + 14656, 14656, 14656, -1, 14657, 14657, 14657, -1, + 14658, 14658, 14658, -1, 14659, 14659, 14659, -1, + 14660, 14660, 14660, -1, 14661, 14661, 14661, -1, + 14662, 14662, 14662, -1, 14663, 14663, 14663, -1, + 14664, 14664, 14664, -1, 14665, 14665, 14665, -1, + 14666, 14666, 14666, -1, 14667, 14667, 14667, -1, + 14668, 14668, 14668, -1, 14669, 14669, 14669, -1, + 14670, 14670, 14670, -1, 14671, 14671, 14671, -1, + 14672, 14672, 14672, -1, 14673, 14673, 14673, -1, + 14674, 14674, 14674, -1, 14675, 14675, 14675, -1, + 14676, 14676, 14676, -1, 14677, 14677, 14677, -1, + 14678, 14678, 14678, -1, 14679, 14679, 14679, -1, + 14680, 14680, 14680, -1, 14681, 14681, 14681, -1, + 14682, 14682, 14682, -1, 14683, 14683, 14683, -1, + 14684, 14684, 14684, -1, 14685, 14685, 14685, -1, + 14686, 14686, 14686, -1, 14687, 14687, 14687, -1, + 14688, 14688, 14688, -1, 14689, 14689, 14689, -1, + 14690, 14690, 14690, -1, 14691, 14691, 14691, -1, + 14692, 14692, 14692, -1, 14693, 14693, 14693, -1, + 14694, 14694, 14694, -1, 14695, 14695, 14695, -1, + 14696, 14696, 14696, -1, 14697, 14697, 14697, -1, + 14698, 14698, 14698, -1, 14699, 14699, 14699, -1, + 14700, 14700, 14700, -1, 14701, 14701, 14701, -1, + 14702, 14702, 14702, -1, 14703, 14703, 14703, -1, + 14704, 14704, 14704, -1, 14705, 14705, 14705, -1, + 14706, 14706, 14706, -1, 14707, 14707, 14707, -1, + 14708, 14708, 14708, -1, 14709, 14709, 14709, -1, + 14710, 14710, 14710, -1, 14711, 14711, 14711, -1, + 14712, 14712, 14712, -1, 14713, 14713, 14713, -1, + 14714, 14714, 14714, -1, 14715, 14715, 14715, -1, + 14716, 14716, 14716, -1, 14717, 14717, 14717, -1, + 14718, 14718, 14718, -1, 14719, 14719, 14719, -1, + 14720, 14720, 14720, -1, 14721, 14721, 14721, -1, + 14722, 14722, 14722, -1, 14723, 14723, 14723, -1, + 14724, 14724, 14724, -1, 14725, 14725, 14725, -1, + 14726, 14726, 14726, -1, 14727, 14727, 14727, -1, + 14728, 14728, 14728, -1, 14729, 14729, 14729, -1, + 14730, 14730, 14730, -1, 14731, 14731, 14731, -1, + 14732, 14732, 14732, -1, 14733, 14733, 14733, -1, + 14734, 14734, 14734, -1, 14735, 14735, 14735, -1, + 14736, 14736, 14736, -1, 14737, 14737, 14737, -1, + 14738, 14738, 14738, -1, 14739, 14739, 14739, -1, + 14740, 14740, 14740, -1, 14741, 14741, 14741, -1, + 14742, 14742, 14742, -1, 14743, 14743, 14743, -1, + 14744, 14744, 14744, -1, 14745, 14745, 14745, -1, + 14746, 14746, 14746, -1, 14747, 14747, 14747, -1, + 14748, 14748, 14748, -1, 14749, 14749, 14749, -1, + 14750, 14750, 14750, -1, 14751, 14751, 14751, -1, + 14752, 14752, 14752, -1, 14753, 14753, 14753, -1, + 14754, 14754, 14754, -1, 14755, 14755, 14755, -1, + 14756, 14756, 14756, -1, 14757, 14757, 14757, -1, + 14758, 14758, 14758, -1, 14759, 14759, 14759, -1, + 14760, 14760, 14760, -1, 14761, 14761, 14761, -1, + 14762, 14762, 14762, -1, 14763, 14763, 14763, -1, + 14764, 14764, 14764, -1, 14765, 14765, 14765, -1, + 14766, 14766, 14766, -1, 14767, 14767, 14767, -1, + 14768, 14768, 14768, -1, 14769, 14769, 14769, -1, + 14770, 14770, 14770, -1, 14771, 14771, 14771, -1, + 14772, 14772, 14772, -1, 14773, 14773, 14773, -1, + 14774, 14774, 14774, -1, 14775, 14775, 14775, -1, + 14776, 14776, 14776, -1, 14777, 14777, 14777, -1, + 14778, 14778, 14778, -1, 14779, 14779, 14779, -1, + 14780, 14780, 14780, -1, 14781, 14781, 14781, -1, + 14782, 14782, 14782, -1, 14783, 14783, 14783, -1, + 14784, 14784, 14784, -1, 14785, 14785, 14785, -1, + 14786, 14786, 14786, -1, 14787, 14787, 14787, -1, + 14788, 14788, 14788, -1, 14789, 14789, 14789, -1, + 14790, 14790, 14790, -1, 14791, 14791, 14791, -1, + 14792, 14792, 14792, -1, 14793, 14793, 14793, -1, + 14794, 14794, 14794, -1, 14795, 14795, 14795, -1, + 14796, 14796, 14796, -1, 14797, 14797, 14797, -1, + 14798, 14798, 14798, -1, 14799, 14799, 14799, -1, + 14800, 14800, 14800, -1, 14801, 14801, 14801, -1, + 14802, 14802, 14802, -1, 14803, 14803, 14803, -1, + 14804, 14804, 14804, -1, 14805, 14805, 14805, -1, + 14806, 14806, 14806, -1, 14807, 14807, 14807, -1, + 14808, 14808, 14808, -1, 14809, 14809, 14809, -1, + 14810, 14810, 14810, -1, 14811, 14811, 14811, -1, + 14812, 14812, 14812, -1, 14813, 14813, 14813, -1, + 14814, 14814, 14814, -1, 14815, 14815, 14815, -1, + 14816, 14816, 14816, -1, 14817, 14817, 14817, -1, + 14818, 14818, 14818, -1, 14819, 14819, 14819, -1, + 14820, 14820, 14820, -1, 14821, 14821, 14821, -1, + 14822, 14822, 14822, -1, 14823, 14823, 14823, -1, + 14824, 14824, 14824, -1, 14825, 14825, 14825, -1, + 14826, 14826, 14826, -1, 14827, 14827, 14827, -1, + 14828, 14828, 14828, -1, 14829, 14829, 14829, -1, + 14830, 14830, 14830, -1, 14831, 14831, 14831, -1, + 14832, 14832, 14832, -1, 14833, 14833, 14833, -1, + 14834, 14834, 14834, -1, 14835, 14835, 14835, -1, + 14836, 14836, 14836, -1, 14837, 14837, 14837, -1, + 14838, 14838, 14838, -1, 14839, 14839, 14839, -1, + 14840, 14840, 14840, -1, 14841, 14841, 14841, -1, + 14842, 14842, 14842, -1, 14843, 14843, 14843, -1, + 14844, 14844, 14844, -1, 14845, 14845, 14845, -1, + 14846, 14846, 14846, -1, 14847, 14847, 14847, -1, + 14848, 14848, 14848, -1, 14849, 14849, 14849, -1, + 14850, 14850, 14850, -1, 14851, 14851, 14851, -1, + 14852, 14852, 14852, -1, 14853, 14853, 14853, -1, + 14854, 14854, 14854, -1, 14855, 14855, 14855, -1, + 14856, 14856, 14856, -1, 14857, 14857, 14857, -1, + 14858, 14858, 14858, -1, 14859, 14859, 14859, -1, + 14860, 14860, 14860, -1, 14861, 14861, 14861, -1, + 14862, 14862, 14862, -1, 14863, 14863, 14863, -1, + 14864, 14864, 14864, -1, 14865, 14865, 14865, -1, + 14866, 14866, 14866, -1, 14867, 14867, 14867, -1, + 14868, 14868, 14868, -1, 14869, 14869, 14869, -1, + 14870, 14870, 14870, -1, 14871, 14871, 14871, -1, + 14872, 14872, 14872, -1, 14873, 14873, 14873, -1, + 14874, 14874, 14874, -1, 14875, 14875, 14875, -1, + 14876, 14876, 14876, -1, 14877, 14877, 14877, -1, + 14878, 14878, 14878, -1, 14879, 14879, 14879, -1, + 14880, 14880, 14880, -1, 14881, 14881, 14881, -1, + 14882, 14882, 14882, -1, 14883, 14883, 14883, -1, + 14884, 14884, 14884, -1, 14885, 14885, 14885, -1, + 14886, 14886, 14886, -1, 14887, 14887, 14887, -1, + 14888, 14888, 14888, -1, 14889, 14889, 14889, -1, + 14890, 14890, 14890, -1, 14891, 14891, 14891, -1, + 14892, 14892, 14892, -1, 14893, 14893, 14893, -1, + 14894, 14894, 14894, -1, 14895, 14895, 14895, -1, + 14896, 14896, 14896, -1, 14897, 14897, 14897, -1, + 14898, 14898, 14898, -1, 14899, 14899, 14899, -1, + 14900, 14900, 14900, -1, 14901, 14901, 14901, -1, + 14902, 14902, 14902, -1, 14903, 14903, 14903, -1, + 14904, 14904, 14904, -1, 14905, 14905, 14905, -1, + 14906, 14906, 14906, -1, 14907, 14907, 14907, -1, + 14908, 14908, 14908, -1, 14909, 14909, 14909, -1, + 14910, 14910, 14910, -1, 14911, 14911, 14911, -1, + 14912, 14912, 14912, -1, 14913, 14913, 14913, -1, + 14914, 14914, 14914, -1, 14915, 14915, 14915, -1, + 14916, 14916, 14916, -1, 14917, 14917, 14917, -1, + 14918, 14918, 14918, -1, 14919, 14919, 14919, -1, + 14920, 14920, 14920, -1, 14921, 14921, 14921, -1, + 14922, 14922, 14922, -1, 14923, 14923, 14923, -1, + 14924, 14924, 14924, -1, 14925, 14925, 14925, -1, + 14926, 14926, 14926, -1, 14927, 14927, 14927, -1, + 14928, 14928, 14928, -1, 14929, 14929, 14929, -1, + 14930, 14930, 14930, -1, 14931, 14931, 14931, -1, + 14932, 14932, 14932, -1, 14933, 14933, 14933, -1, + 14934, 14934, 14934, -1, 14935, 14935, 14935, -1, + 14936, 14936, 14936, -1, 14937, 14937, 14937, -1, + 14938, 14938, 14938, -1, 14939, 14939, 14939, -1, + 14940, 14940, 14940, -1, 14941, 14941, 14941, -1, + 14942, 14942, 14942, -1, 14943, 14943, 14943, -1, + 14944, 14944, 14944, -1, 14945, 14945, 14945, -1, + 14946, 14946, 14946, -1, 14947, 14947, 14947, -1, + 14948, 14948, 14948, -1, 14949, 14949, 14949, -1, + 14950, 14950, 14950, -1, 14951, 14951, 14951, -1, + 14952, 14952, 14952, -1, 14953, 14953, 14953, -1, + 14954, 14954, 14954, -1, 14955, 14955, 14955, -1, + 14956, 14956, 14956, -1, 14957, 14957, 14957, -1, + 14958, 14958, 14958, -1, 14959, 14959, 14959, -1, + 14960, 14960, 14960, -1, 14961, 14961, 14961, -1, + 14962, 14962, 14962, -1, 14963, 14963, 14963, -1, + 14964, 14964, 14964, -1, 14965, 14965, 14965, -1, + 14966, 14966, 14966, -1, 14967, 14967, 14967, -1, + 14968, 14968, 14968, -1, 14969, 14969, 14969, -1, + 14970, 14970, 14970, -1, 14971, 14971, 14971, -1, + 14972, 14972, 14972, -1, 14973, 14973, 14973, -1, + 14974, 14974, 14974, -1, 14975, 14975, 14975, -1, + 14976, 14976, 14976, -1, 14977, 14977, 14977, -1, + 14978, 14978, 14978, -1, 14979, 14979, 14979, -1, + 14980, 14980, 14980, -1, 14981, 14981, 14981, -1, + 14982, 14982, 14982, -1, 14983, 14983, 14983, -1, + 14984, 14984, 14984, -1, 14985, 14985, 14985, -1, + 14986, 14986, 14986, -1, 14987, 14987, 14987, -1, + 14988, 14988, 14988, -1, 14989, 14989, 14989, -1, + 14990, 14990, 14990, -1, 14991, 14991, 14991, -1, + 14992, 14992, 14992, -1, 14993, 14993, 14993, -1, + 14994, 14994, 14994, -1, 14995, 14995, 14995, -1, + 14996, 14996, 14996, -1, 14997, 14997, 14997, -1, + 14998, 14998, 14998, -1, 14999, 14999, 14999, -1, + 15000, 15000, 15000, -1, 15001, 15001, 15001, -1, + 15002, 15002, 15002, -1, 15003, 15003, 15003, -1, + 15004, 15004, 15004, -1, 15005, 15005, 15005, -1, + 15006, 15006, 15006, -1, 15007, 15007, 15007, -1, + 15008, 15008, 15008, -1, 15009, 15009, 15009, -1, + 15010, 15010, 15010, -1, 15011, 15011, 15011, -1, + 15012, 15012, 15012, -1, 15013, 15013, 15013, -1, + 15014, 15014, 15014, -1, 15015, 15015, 15015, -1, + 15016, 15016, 15016, -1, 15017, 15017, 15017, -1, + 15018, 15018, 15018, -1, 15019, 15019, 15019, -1, + 15020, 15020, 15020, -1, 15021, 15021, 15021, -1, + 15022, 15022, 15022, -1, 15023, 15023, 15023, -1, + 15024, 15024, 15024, -1, 15025, 15025, 15025, -1, + 15026, 15026, 15026, -1, 15027, 15027, 15027, -1, + 15028, 15028, 15028, -1, 15029, 15029, 15029, -1, + 15030, 15030, 15030, -1, 15031, 15031, 15031, -1, + 15032, 15032, 15032, -1, 15033, 15033, 15033, -1, + 15034, 15034, 15034, -1, 15035, 15035, 15035, -1, + 15036, 15036, 15036, -1, 15037, 15037, 15037, -1, + 15038, 15038, 15038, -1, 15039, 15039, 15039, -1, + 15040, 15040, 15040, -1, 15041, 15041, 15041, -1, + 15042, 15042, 15042, -1, 15043, 15043, 15043, -1, + 15044, 15044, 15044, -1, 15045, 15045, 15045, -1, + 15046, 15046, 15046, -1, 15047, 15047, 15047, -1, + 15048, 15048, 15048, -1, 15049, 15049, 15049, -1, + 15050, 15050, 15050, -1, 15051, 15051, 15051, -1, + 15052, 15052, 15052, -1, 15053, 15053, 15053, -1, + 15054, 15054, 15054, -1, 15055, 15055, 15055, -1, + 15056, 15056, 15056, -1, 15057, 15057, 15057, -1, + 15058, 15058, 15058, -1, 15059, 15059, 15059, -1, + 15060, 15060, 15060, -1, 15061, 15061, 15061, -1, + 15062, 15062, 15062, -1, 15063, 15063, 15063, -1, + 15064, 15064, 15064, -1, 15065, 15065, 15065, -1, + 15066, 15066, 15066, -1, 15067, 15067, 15067, -1, + 15068, 15068, 15068, -1, 15069, 15069, 15069, -1, + 15070, 15070, 15070, -1, 15071, 15071, 15071, -1, + 15072, 15072, 15072, -1, 15073, 15073, 15073, -1, + 15074, 15074, 15074, -1, 15075, 15075, 15075, -1, + 15076, 15076, 15076, -1, 15077, 15077, 15077, -1, + 15078, 15078, 15078, -1, 15079, 15079, 15079, -1, + 15080, 15080, 15080, -1, 15081, 15081, 15081, -1, + 15082, 15082, 15082, -1, 15083, 15083, 15083, -1, + 15084, 15084, 15084, -1, 15085, 15085, 15085, -1, + 15086, 15086, 15086, -1, 15087, 15087, 15087, -1, + 15088, 15088, 15088, -1, 15089, 15089, 15089, -1, + 15090, 15090, 15090, -1, 15091, 15091, 15091, -1, + 15092, 15092, 15092, -1, 15093, 15093, 15093, -1, + 15094, 15094, 15094, -1, 15095, 15095, 15095, -1, + 15096, 15096, 15096, -1, 15097, 15097, 15097, -1, + 15098, 15098, 15098, -1, 15099, 15099, 15099, -1, + 15100, 15100, 15100, -1, 15101, 15101, 15101, -1, + 15102, 15102, 15102, -1, 15103, 15103, 15103, -1, + 15104, 15104, 15104, -1, 15105, 15105, 15105, -1, + 15106, 15106, 15106, -1, 15107, 15107, 15107, -1, + 15108, 15108, 15108, -1, 15109, 15109, 15109, -1, + 15110, 15110, 15110, -1, 15111, 15111, 15111, -1, + 15112, 15112, 15112, -1, 15113, 15113, 15113, -1, + 15114, 15114, 15114, -1, 15115, 15115, 15115, -1, + 15116, 15116, 15116, -1, 15117, 15117, 15117, -1, + 15118, 15118, 15118, -1, 15119, 15119, 15119, -1, + 15120, 15120, 15120, -1, 15121, 15121, 15121, -1, + 15122, 15122, 15122, -1, 15123, 15123, 15123, -1, + 15124, 15124, 15124, -1, 15125, 15125, 15125, -1, + 15126, 15126, 15126, -1, 15127, 15127, 15127, -1, + 15128, 15128, 15128, -1, 15129, 15129, 15129, -1, + 15130, 15130, 15130, -1, 15131, 15131, 15131, -1, + 15132, 15132, 15132, -1, 15133, 15133, 15133, -1, + 15134, 15134, 15134, -1, 15135, 15135, 15135, -1, + 15136, 15136, 15136, -1, 15137, 15137, 15137, -1, + 15138, 15138, 15138, -1, 15139, 15139, 15139, -1, + 15140, 15140, 15140, -1, 15141, 15141, 15141, -1, + 15142, 15142, 15142, -1, 15143, 15143, 15143, -1, + 15144, 15144, 15144, -1, 15145, 15145, 15145, -1, + 15146, 15146, 15146, -1, 15147, 15147, 15147, -1, + 15148, 15148, 15148, -1, 15149, 15149, 15149, -1, + 15150, 15150, 15150, -1, 15151, 15151, 15151, -1, + 15152, 15152, 15152, -1, 15153, 15153, 15153, -1, + 15154, 15154, 15154, -1, 15155, 15155, 15155, -1, + 15156, 15156, 15156, -1, 15157, 15157, 15157, -1, + 15158, 15158, 15158, -1, 15159, 15159, 15159, -1, + 15160, 15160, 15160, -1, 15161, 15161, 15161, -1, + 15162, 15162, 15162, -1, 15163, 15163, 15163, -1, + 15164, 15164, 15164, -1, 15165, 15165, 15165, -1, + 15166, 15166, 15166, -1, 15167, 15167, 15167, -1, + 15168, 15168, 15168, -1, 15169, 15169, 15169, -1, + 15170, 15170, 15170, -1, 15171, 15171, 15171, -1, + 15172, 15172, 15172, -1, 15173, 15173, 15173, -1, + 15174, 15174, 15174, -1, 15175, 15175, 15175, -1, + 15176, 15176, 15176, -1, 15177, 15177, 15177, -1, + 15178, 15178, 15178, -1, 15179, 15179, 15179, -1, + 15180, 15180, 15180, -1, 15181, 15181, 15181, -1, + 15182, 15182, 15182, -1, 15183, 15183, 15183, -1, + 15184, 15184, 15184, -1, 15185, 15185, 15185, -1, + 15186, 15186, 15186, -1, 15187, 15187, 15187, -1, + 15188, 15188, 15188, -1, 15189, 15189, 15189, -1, + 15190, 15190, 15190, -1, 15191, 15191, 15191, -1, + 15192, 15192, 15192, -1, 15193, 15193, 15193, -1, + 15194, 15194, 15194, -1, 15195, 15195, 15195, -1, + 15196, 15196, 15196, -1, 15197, 15197, 15197, -1, + 15198, 15198, 15198, -1, 15199, 15199, 15199, -1, + 15200, 15200, 15200, -1, 15201, 15201, 15201, -1, + 15202, 15202, 15202, -1, 15203, 15203, 15203, -1, + 15204, 15204, 15204, -1, 15205, 15205, 15205, -1, + 15206, 15206, 15206, -1, 15207, 15207, 15207, -1, + 15208, 15208, 15208, -1, 15209, 15209, 15209, -1, + 15210, 15210, 15210, -1, 15211, 15211, 15211, -1, + 15212, 15212, 15212, -1, 15213, 15213, 15213, -1, + 15214, 15214, 15214, -1, 15215, 15215, 15215, -1, + 15216, 15216, 15216, -1, 15217, 15217, 15217, -1, + 15218, 15218, 15218, -1, 15219, 15219, 15219, -1, + 15220, 15220, 15220, -1, 15221, 15221, 15221, -1, + 15222, 15222, 15222, -1, 15223, 15223, 15223, -1, + 15224, 15224, 15224, -1, 15225, 15225, 15225, -1, + 15226, 15226, 15226, -1, 15227, 15227, 15227, -1, + 15228, 15228, 15228, -1, 15229, 15229, 15229, -1, + 15230, 15230, 15230, -1, 15231, 15231, 15231, -1, + 15232, 15232, 15232, -1, 15233, 15233, 15233, -1, + 15234, 15234, 15234, -1, 15235, 15235, 15235, -1, + 15236, 15236, 15236, -1, 15237, 15237, 15237, -1, + 15238, 15238, 15238, -1, 15239, 15239, 15239, -1, + 15240, 15240, 15240, -1, 15241, 15241, 15241, -1, + 15242, 15242, 15242, -1, 15243, 15243, 15243, -1, + 15244, 15244, 15244, -1, 15245, 15245, 15245, -1, + 15246, 15246, 15246, -1, 15247, 15247, 15247, -1, + 15248, 15248, 15248, -1, 15249, 15249, 15249, -1, + 15250, 15250, 15250, -1, 15251, 15251, 15251, -1, + 15252, 15252, 15252, -1, 15253, 15253, 15253, -1, + 15254, 15254, 15254, -1, 15255, 15255, 15255, -1, + 15256, 15256, 15256, -1, 15257, 15257, 15257, -1, + 15258, 15258, 15258, -1, 15259, 15259, 15259, -1, + 15260, 15260, 15260, -1, 15261, 15261, 15261, -1, + 15262, 15262, 15262, -1, 15263, 15263, 15263, -1, + 15264, 15264, 15264, -1, 15265, 15265, 15265, -1, + 15266, 15266, 15266, -1, 15267, 15267, 15267, -1, + 15268, 15268, 15268, -1, 15269, 15269, 15269, -1, + 15270, 15270, 15270, -1, 15271, 15271, 15271, -1, + 15272, 15272, 15272, -1, 15273, 15273, 15273, -1, + 15274, 15274, 15274, -1, 15275, 15275, 15275, -1, + 15276, 15276, 15276, -1, 15277, 15277, 15277, -1, + 15278, 15278, 15278, -1, 15279, 15279, 15279, -1, + 15280, 15280, 15280, -1, 15281, 15281, 15281, -1, + 15282, 15282, 15282, -1, 15283, 15283, 15283, -1, + 15284, 15284, 15284, -1, 15285, 15285, 15285, -1, + 15286, 15286, 15286, -1, 15287, 15287, 15287, -1, + 15288, 15288, 15288, -1, 15289, 15289, 15289, -1, + 15290, 15290, 15290, -1, 15291, 15291, 15291, -1, + 15292, 15292, 15292, -1, 15293, 15293, 15293, -1, + 15294, 15294, 15294, -1, 15295, 15295, 15295, -1, + 15296, 15296, 15296, -1, 15297, 15297, 15297, -1, + 15298, 15298, 15298, -1, 15299, 15299, 15299, -1, + 15300, 15300, 15300, -1, 15301, 15301, 15301, -1, + 15302, 15302, 15302, -1, 15303, 15303, 15303, -1, + 15304, 15304, 15304, -1, 15305, 15305, 15305, -1, + 15306, 15306, 15306, -1, 15307, 15307, 15307, -1, + 15308, 15308, 15308, -1, 15309, 15309, 15309, -1, + 15310, 15310, 15310, -1, 15311, 15311, 15311, -1, + 15312, 15312, 15312, -1, 15313, 15313, 15313, -1, + 15314, 15314, 15314, -1, 15315, 15315, 15315, -1, + 15316, 15316, 15316, -1, 15317, 15317, 15317, -1, + 15318, 15318, 15318, -1, 15319, 15319, 15319, -1, + 15320, 15320, 15320, -1, 15321, 15321, 15321, -1, + 15322, 15322, 15322, -1, 15323, 15323, 15323, -1, + 15324, 15324, 15324, -1, 15325, 15325, 15325, -1, + 15326, 15326, 15326, -1, 15327, 15327, 15327, -1, + 15328, 15328, 15328, -1, 15329, 15329, 15329, -1, + 15330, 15330, 15330, -1, 15331, 15331, 15331, -1, + 15332, 15332, 15332, -1, 15333, 15333, 15333, -1, + 15334, 15334, 15334, -1, 15335, 15335, 15335, -1, + 15336, 15336, 15336, -1, 15337, 15337, 15337, -1, + 15338, 15338, 15338, -1, 15339, 15339, 15339, -1, + 15340, 15340, 15340, -1, 15341, 15341, 15341, -1, + 15342, 15342, 15342, -1, 15343, 15343, 15343, -1, + 15344, 15344, 15344, -1, 15345, 15345, 15345, -1, + 15346, 15346, 15346, -1, 15347, 15347, 15347, -1, + 15348, 15348, 15348, -1, 15349, 15349, 15349, -1, + 15350, 15350, 15350, -1, 15351, 15351, 15351, -1, + 15352, 15352, 15352, -1, 15353, 15353, 15353, -1, + 15354, 15354, 15354, -1, 15355, 15355, 15355, -1, + 15356, 15356, 15356, -1, 15357, 15357, 15357, -1, + 15358, 15358, 15358, -1, 15359, 15359, 15359, -1, + 15360, 15360, 15360, -1, 15361, 15361, 15361, -1, + 15362, 15362, 15362, -1, 15363, 15363, 15363, -1, + 15364, 15364, 15364, -1, 15365, 15365, 15365, -1, + 15366, 15366, 15366, -1, 15367, 15367, 15367, -1, + 15368, 15368, 15368, -1, 15369, 15369, 15369, -1, + 15370, 15370, 15370, -1, 15371, 15371, 15371, -1, + 15372, 15372, 15372, -1, 15373, 15373, 15373, -1, + 15374, 15374, 15374, -1, 15375, 15375, 15375, -1, + 15376, 15376, 15376, -1, 15377, 15377, 15377, -1, + 15378, 15378, 15378, -1, 15379, 15379, 15379, -1, + 15380, 15380, 15380, -1, 15381, 15381, 15381, -1, + 15382, 15382, 15382, -1, 15383, 15383, 15383, -1, + 15384, 15384, 15384, -1, 15385, 15385, 15385, -1, + 15386, 15386, 15386, -1, 15387, 15387, 15387, -1, + 15388, 15388, 15388, -1, 15389, 15389, 15389, -1, + 15390, 15390, 15390, -1, 15391, 15391, 15391, -1, + 15392, 15392, 15392, -1, 15393, 15393, 15393, -1, + 15394, 15394, 15394, -1, 15395, 15395, 15395, -1, + 15396, 15396, 15396, -1, 15397, 15397, 15397, -1, + 15398, 15398, 15398, -1, 15399, 15399, 15399, -1, + 15400, 15400, 15400, -1, 15401, 15401, 15401, -1, + 15402, 15402, 15402, -1, 15403, 15403, 15403, -1, + 15404, 15404, 15404, -1, 15405, 15405, 15405, -1, + 15406, 15406, 15406, -1, 15407, 15407, 15407, -1, + 15408, 15408, 15408, -1, 15409, 15409, 15409, -1, + 15410, 15410, 15410, -1, 15411, 15411, 15411, -1, + 15412, 15412, 15412, -1, 15413, 15413, 15413, -1, + 15414, 15414, 15414, -1, 15415, 15415, 15415, -1, + 15416, 15416, 15416, -1, 15417, 15417, 15417, -1, + 15418, 15418, 15418, -1, 15419, 15419, 15419, -1, + 15420, 15420, 15420, -1, 15421, 15421, 15421, -1, + 15422, 15422, 15422, -1, 15423, 15423, 15423, -1, + 15424, 15424, 15424, -1, 15425, 15425, 15425, -1, + 15426, 15426, 15426, -1, 15427, 15427, 15427, -1, + 15428, 15428, 15428, -1, 15429, 15429, 15429, -1, + 15430, 15430, 15430, -1, 15431, 15431, 15431, -1, + 15432, 15432, 15432, -1, 15433, 15433, 15433, -1, + 15434, 15434, 15434, -1, 15435, 15435, 15435, -1, + 15436, 15436, 15436, -1, 15437, 15437, 15437, -1, + 15438, 15438, 15438, -1, 15439, 15439, 15439, -1, + 15440, 15440, 15440, -1, 15441, 15441, 15441, -1, + 15442, 15442, 15442, -1, 15443, 15443, 15443, -1, + 15444, 15444, 15444, -1, 15445, 15445, 15445, -1, + 15446, 15446, 15446, -1, 15447, 15447, 15447, -1, + 15448, 15448, 15448, -1, 15449, 15449, 15449, -1, + 15450, 15450, 15450, -1, 15451, 15451, 15451, -1, + 15452, 15452, 15452, -1, 15453, 15453, 15453, -1, + 15454, 15454, 15454, -1, 15455, 15455, 15455, -1, + 15456, 15456, 15456, -1, 15457, 15457, 15457, -1, + 15458, 15458, 15458, -1, 15459, 15459, 15459, -1, + 15460, 15460, 15460, -1, 15461, 15461, 15461, -1, + 15462, 15462, 15462, -1, 15463, 15463, 15463, -1, + 15464, 15464, 15464, -1, 15465, 15465, 15465, -1, + 15466, 15466, 15466, -1, 15467, 15467, 15467, -1, + 15468, 15468, 15468, -1, 15469, 15469, 15469, -1, + 15470, 15470, 15470, -1, 15471, 15471, 15471, -1, + 15472, 15472, 15472, -1, 15473, 15473, 15473, -1, + 15474, 15474, 15474, -1, 15475, 15475, 15475, -1, + 15476, 15476, 15476, -1, 15477, 15477, 15477, -1, + 15478, 15478, 15478, -1, 15479, 15479, 15479, -1, + 15480, 15480, 15480, -1, 15481, 15481, 15481, -1, + 15482, 15482, 15482, -1, 15483, 15483, 15483, -1, + 15484, 15484, 15484, -1, 15485, 15485, 15485, -1, + 15486, 15486, 15486, -1, 15487, 15487, 15487, -1, + 15488, 15488, 15488, -1, 15489, 15489, 15489, -1, + 15490, 15490, 15490, -1, 15491, 15491, 15491, -1, + 15492, 15492, 15492, -1, 15493, 15493, 15493, -1, + 15494, 15494, 15494, -1, 15495, 15495, 15495, -1, + 15496, 15496, 15496, -1, 15497, 15497, 15497, -1, + 15498, 15498, 15498, -1, 15499, 15499, 15499, -1, + 15500, 15500, 15500, -1, 15501, 15501, 15501, -1, + 15502, 15502, 15502, -1, 15503, 15503, 15503, -1, + 15504, 15504, 15504, -1, 15505, 15505, 15505, -1, + 15506, 15506, 15506, -1, 15507, 15507, 15507, -1, + 15508, 15508, 15508, -1, 15509, 15509, 15509, -1, + 15510, 15510, 15510, -1, 15511, 15511, 15511, -1, + 15512, 15512, 15512, -1, 15513, 15513, 15513, -1, + 15514, 15514, 15514, -1, 15515, 15515, 15515, -1, + 15516, 15516, 15516, -1, 15517, 15517, 15517, -1, + 15518, 15518, 15518, -1, 15519, 15519, 15519, -1, + 15520, 15520, 15520, -1, 15521, 15521, 15521, -1, + 15522, 15522, 15522, -1, 15523, 15523, 15523, -1, + 15524, 15524, 15524, -1, 15525, 15525, 15525, -1, + 15526, 15526, 15526, -1, 15527, 15527, 15527, -1, + 15528, 15528, 15528, -1, 15529, 15529, 15529, -1, + 15530, 15530, 15530, -1, 15531, 15531, 15531, -1, + 15532, 15532, 15532, -1, 15533, 15533, 15533, -1, + 15534, 15534, 15534, -1, 15535, 15535, 15535, -1, + 15536, 15536, 15536, -1, 15537, 15537, 15537, -1, + 15538, 15538, 15538, -1, 15539, 15539, 15539, -1, + 15540, 15540, 15540, -1, 15541, 15541, 15541, -1, + 15542, 15542, 15542, -1, 15543, 15543, 15543, -1, + 15544, 15544, 15544, -1, 15545, 15545, 15545, -1, + 15546, 15546, 15546, -1, 15547, 15547, 15547, -1, + 15548, 15548, 15548, -1, 15549, 15549, 15549, -1, + 15550, 15550, 15550, -1, 15551, 15551, 15551, -1, + 15552, 15552, 15552, -1, 15553, 15553, 15553, -1, + 15554, 15554, 15554, -1, 15555, 15555, 15555, -1, + 15556, 15556, 15556, -1, 15557, 15557, 15557, -1, + 15558, 15558, 15558, -1, 15559, 15559, 15559, -1, + 15560, 15560, 15560, -1, 15561, 15561, 15561, -1, + 15562, 15562, 15562, -1, 15563, 15563, 15563, -1, + 15564, 15564, 15564, -1, 15565, 15565, 15565, -1, + 15566, 15566, 15566, -1, 15567, 15567, 15567, -1, + 15568, 15568, 15568, -1, 15569, 15569, 15569, -1, + 15570, 15570, 15570, -1, 15571, 15571, 15571, -1, + 15572, 15572, 15572, -1, 15573, 15573, 15573, -1, + 15574, 15574, 15574, -1, 15575, 15575, 15575, -1, + 15576, 15576, 15576, -1, 15577, 15577, 15577, -1, + 15578, 15578, 15578, -1, 15579, 15579, 15579, -1, + 15580, 15580, 15580, -1, 15581, 15581, 15581, -1, + 15582, 15582, 15582, -1, 15583, 15583, 15583, -1, + 15584, 15584, 15584, -1, 15585, 15585, 15585, -1, + 15586, 15586, 15586, -1, 15587, 15587, 15587, -1, + 15588, 15588, 15588, -1, 15589, 15589, 15589, -1, + 15590, 15590, 15590, -1, 15591, 15591, 15591, -1, + 15592, 15592, 15592, -1, 15593, 15593, 15593, -1, + 15594, 15594, 15594, -1, 15595, 15595, 15595, -1, + 15596, 15596, 15596, -1, 15597, 15597, 15597, -1, + 15598, 15598, 15598, -1, 15599, 15599, 15599, -1, + 15600, 15600, 15600, -1, 15601, 15601, 15601, -1, + 15602, 15602, 15602, -1, 15603, 15603, 15603, -1, + 15604, 15604, 15604, -1, 15605, 15605, 15605, -1, + 15606, 15606, 15606, -1, 15607, 15607, 15607, -1, + 15608, 15608, 15608, -1, 15609, 15609, 15609, -1, + 15610, 15610, 15610, -1, 15611, 15611, 15611, -1, + 15612, 15612, 15612, -1, 15613, 15613, 15613, -1, + 15614, 15614, 15614, -1, 15615, 15615, 15615, -1, + 15616, 15616, 15616, -1, 15617, 15617, 15617, -1, + 15618, 15618, 15618, -1, 15619, 15619, 15619, -1, + 15620, 15620, 15620, -1, 15621, 15621, 15621, -1, + 15622, 15622, 15622, -1, 15623, 15623, 15623, -1, + 15624, 15624, 15624, -1, 15625, 15625, 15625, -1, + 15626, 15626, 15626, -1, 15627, 15627, 15627, -1, + 15628, 15628, 15628, -1, 15629, 15629, 15629, -1, + 15630, 15630, 15630, -1, 15631, 15631, 15631, -1, + 15632, 15632, 15632, -1, 15633, 15633, 15633, -1, + 15634, 15634, 15634, -1, 15635, 15635, 15635, -1, + 15636, 15636, 15636, -1, 15637, 15637, 15637, -1, + 15638, 15638, 15638, -1, 15639, 15639, 15639, -1, + 15640, 15640, 15640, -1, 15641, 15641, 15641, -1, + 15642, 15642, 15642, -1, 15643, 15643, 15643, -1, + 15644, 15644, 15644, -1, 15645, 15645, 15645, -1, + 15646, 15646, 15646, -1, 15647, 15647, 15647, -1, + 15648, 15648, 15648, -1, 15649, 15649, 15649, -1, + 15650, 15650, 15650, -1, 15651, 15651, 15651, -1, + 15652, 15652, 15652, -1, 15653, 15653, 15653, -1, + 15654, 15654, 15654, -1, 15655, 15655, 15655, -1, + 15656, 15656, 15656, -1, 15657, 15657, 15657, -1, + 15658, 15658, 15658, -1, 15659, 15659, 15659, -1, + 15660, 15660, 15660, -1, 15661, 15661, 15661, -1, + 15662, 15662, 15662, -1, 15663, 15663, 15663, -1, + 15664, 15664, 15664, -1, 15665, 15665, 15665, -1, + 15666, 15666, 15666, -1, 15667, 15667, 15667, -1, + 15668, 15668, 15668, -1, 15669, 15669, 15669, -1, + 15670, 15670, 15670, -1, 15671, 15671, 15671, -1, + 15672, 15672, 15672, -1, 15673, 15673, 15673, -1, + 15674, 15674, 15674, -1, 15675, 15675, 15675, -1, + 15676, 15676, 15676, -1, 15677, 15677, 15677, -1, + 15678, 15678, 15678, -1, 15679, 15679, 15679, -1, + 15680, 15680, 15680, -1, 15681, 15681, 15681, -1, + 15682, 15682, 15682, -1, 15683, 15683, 15683, -1, + 15684, 15684, 15684, -1, 15685, 15685, 15685, -1, + 15686, 15686, 15686, -1, 15687, 15687, 15687, -1, + 15688, 15688, 15688, -1, 15689, 15689, 15689, -1, + 15690, 15690, 15690, -1, 15691, 15691, 15691, -1, + 15692, 15692, 15692, -1, 15693, 15693, 15693, -1, + 15694, 15694, 15694, -1, 15695, 15695, 15695, -1, + 15696, 15696, 15696, -1, 15697, 15697, 15697, -1, + 15698, 15698, 15698, -1, 15699, 15699, 15699, -1, + 15700, 15700, 15700, -1, 15701, 15701, 15701, -1, + 15702, 15702, 15702, -1, 15703, 15703, 15703, -1, + 15704, 15704, 15704, -1, 15705, 15705, 15705, -1, + 15706, 15706, 15706, -1, 15707, 15707, 15707, -1, + 15708, 15708, 15708, -1, 15709, 15709, 15709, -1, + 15710, 15710, 15710, -1, 15711, 15711, 15711, -1, + 15712, 15712, 15712, -1, 15713, 15713, 15713, -1, + 15714, 15714, 15714, -1, 15715, 15715, 15715, -1, + 15716, 15716, 15716, -1, 15717, 15717, 15717, -1, + 15718, 15718, 15718, -1, 15719, 15719, 15719, -1, + 15720, 15720, 15720, -1, 15721, 15721, 15721, -1, + 15722, 15722, 15722, -1, 15723, 15723, 15723, -1, + 15724, 15724, 15724, -1, 15725, 15725, 15725, -1, + 15726, 15726, 15726, -1, 15727, 15727, 15727, -1, + 15728, 15728, 15728, -1, 15729, 15729, 15729, -1, + 15730, 15730, 15730, -1, 15731, 15731, 15731, -1, + 15732, 15732, 15732, -1, 15733, 15733, 15733, -1, + 15734, 15734, 15734, -1, 15735, 15735, 15735, -1, + 15736, 15736, 15736, -1, 15737, 15737, 15737, -1, + 15738, 15738, 15738, -1, 15739, 15739, 15739, -1, + 15740, 15740, 15740, -1, 15741, 15741, 15741, -1, + 15742, 15742, 15742, -1, 15743, 15743, 15743, -1, + 15744, 15744, 15744, -1, 15745, 15745, 15745, -1, + 15746, 15746, 15746, -1, 15747, 15747, 15747, -1, + 15748, 15748, 15748, -1, 15749, 15749, 15749, -1, + 15750, 15750, 15750, -1, 15751, 15751, 15751, -1, + 15752, 15752, 15752, -1, 15753, 15753, 15753, -1, + 15754, 15754, 15754, -1, 15755, 15755, 15755, -1, + 15756, 15756, 15756, -1, 15757, 15757, 15757, -1, + 15758, 15758, 15758, -1, 15759, 15759, 15759, -1, + 15760, 15760, 15760, -1, 15761, 15761, 15761, -1, + 15762, 15762, 15762, -1, 15763, 15763, 15763, -1, + 15764, 15764, 15764, -1, 15765, 15765, 15765, -1, + 15766, 15766, 15766, -1, 15767, 15767, 15767, -1, + 15768, 15768, 15768, -1, 15769, 15769, 15769, -1, + 15770, 15770, 15770, -1, 15771, 15771, 15771, -1, + 15772, 15772, 15772, -1, 15773, 15773, 15773, -1, + 15774, 15774, 15774, -1, 15775, 15775, 15775, -1, + 15776, 15776, 15776, -1, 15777, 15777, 15777, -1, + 15778, 15778, 15778, -1, 15779, 15779, 15779, -1, + 15780, 15780, 15780, -1, 15781, 15781, 15781, -1, + 15782, 15782, 15782, -1, 15783, 15783, 15783, -1, + 15784, 15784, 15784, -1, 15785, 15785, 15785, -1, + 15786, 15786, 15786, -1, 15787, 15787, 15787, -1, + 15788, 15788, 15788, -1, 15789, 15789, 15789, -1, + 15790, 15790, 15790, -1, 15791, 15791, 15791, -1, + 15792, 15792, 15792, -1, 15793, 15793, 15793, -1, + 15794, 15794, 15794, -1, 15795, 15795, 15795, -1, + 15796, 15796, 15796, -1, 15797, 15797, 15797, -1, + 15798, 15798, 15798, -1, 15799, 15799, 15799, -1, + 15800, 15800, 15800, -1, 15801, 15801, 15801, -1, + 15802, 15802, 15802, -1, 15803, 15803, 15803, -1, + 15804, 15804, 15804, -1, 15805, 15805, 15805, -1, + 15806, 15806, 15806, -1, 15807, 15807, 15807, -1, + 15808, 15808, 15808, -1, 15809, 15809, 15809, -1, + 15810, 15810, 15810, -1, 15811, 15811, 15811, -1, + 15812, 15812, 15812, -1, 15813, 15813, 15813, -1, + 15814, 15814, 15814, -1, 15815, 15815, 15815, -1, + 15816, 15816, 15816, -1, 15817, 15817, 15817, -1, + 15818, 15818, 15818, -1, 15819, 15819, 15819, -1, + 15820, 15820, 15820, -1, 15821, 15821, 15821, -1, + 15822, 15822, 15822, -1, 15823, 15823, 15823, -1, + 15824, 15824, 15824, -1, 15825, 15825, 15825, -1, + 15826, 15826, 15826, -1, 15827, 15827, 15827, -1, + 15828, 15828, 15828, -1, 15829, 15829, 15829, -1, + 15830, 15830, 15830, -1, 15831, 15831, 15831, -1, + 15832, 15832, 15832, -1, 15833, 15833, 15833, -1, + 15834, 15834, 15834, -1, 15835, 15835, 15835, -1, + 15836, 15836, 15836, -1, 15837, 15837, 15837, -1, + 15838, 15838, 15838, -1, 15839, 15839, 15839, -1, + 15840, 15840, 15840, -1, 15841, 15841, 15841, -1, + 15842, 15842, 15842, -1, 15843, 15843, 15843, -1, + 15844, 15844, 15844, -1, 15845, 15845, 15845, -1, + 15846, 15846, 15846, -1, 15847, 15847, 15847, -1, + 15848, 15848, 15848, -1, 15849, 15849, 15849, -1, + 15850, 15850, 15850, -1, 15851, 15851, 15851, -1, + 15852, 15852, 15852, -1, 15853, 15853, 15853, -1, + 15854, 15854, 15854, -1, 15855, 15855, 15855, -1, + 15856, 15856, 15856, -1, 15857, 15857, 15857, -1, + 15858, 15858, 15858, -1, 15859, 15859, 15859, -1, + 15860, 15860, 15860, -1, 15861, 15861, 15861, -1, + 15862, 15862, 15862, -1, 15863, 15863, 15863, -1, + 15864, 15864, 15864, -1, 15865, 15865, 15865, -1, + 15866, 15866, 15866, -1, 15867, 15867, 15867, -1, + 15868, 15868, 15868, -1, 15869, 15869, 15869, -1, + 15870, 15870, 15870, -1, 15871, 15871, 15871, -1, + 15872, 15872, 15872, -1, 15873, 15873, 15873, -1, + 15874, 15874, 15874, -1, 15875, 15875, 15875, -1, + 15876, 15876, 15876, -1, 15877, 15877, 15877, -1, + 15878, 15878, 15878, -1, 15879, 15879, 15879, -1, + 15880, 15880, 15880, -1, 15881, 15881, 15881, -1, + 15882, 15882, 15882, -1, 15883, 15883, 15883, -1, + 15884, 15884, 15884, -1, 15885, 15885, 15885, -1, + 15886, 15886, 15886, -1, 15887, 15887, 15887, -1, + 15888, 15888, 15888, -1, 15889, 15889, 15889, -1, + 15890, 15890, 15890, -1, 15891, 15891, 15891, -1, + 15892, 15892, 15892, -1, 15893, 15893, 15893, -1, + 15894, 15894, 15894, -1, 15895, 15895, 15895, -1, + 15896, 15896, 15896, -1, 15897, 15897, 15897, -1, + 15898, 15898, 15898, -1, 15899, 15899, 15899, -1, + 15900, 15900, 15900, -1, 15901, 15901, 15901, -1, + 15902, 15902, 15902, -1, 15903, 15903, 15903, -1, + 15904, 15904, 15904, -1, 15905, 15905, 15905, -1, + 15906, 15906, 15906, -1, 15907, 15907, 15907, -1, + 15908, 15908, 15908, -1, 15909, 15909, 15909, -1, + 15910, 15910, 15910, -1, 15911, 15911, 15911, -1, + 15912, 15912, 15912, -1, 15913, 15913, 15913, -1, + 15914, 15914, 15914, -1, 15915, 15915, 15915, -1, + 15916, 15916, 15916, -1, 15917, 15917, 15917, -1, + 15918, 15918, 15918, -1, 15919, 15919, 15919, -1, + 15920, 15920, 15920, -1, 15921, 15921, 15921, -1, + 15922, 15922, 15922, -1, 15923, 15923, 15923, -1, + 15924, 15924, 15924, -1, 15925, 15925, 15925, -1, + 15926, 15926, 15926, -1, 15927, 15927, 15927, -1, + 15928, 15928, 15928, -1, 15929, 15929, 15929, -1, + 15930, 15930, 15930, -1, 15931, 15931, 15931, -1, + 15932, 15932, 15932, -1, 15933, 15933, 15933, -1, + 15934, 15934, 15934, -1, 15935, 15935, 15935, -1, + 15936, 15936, 15936, -1, 15937, 15937, 15937, -1, + 15938, 15938, 15938, -1, 15939, 15939, 15939, -1, + 15940, 15940, 15940, -1, 15941, 15941, 15941, -1, + 15942, 15942, 15942, -1, 15943, 15943, 15943, -1, + 15944, 15944, 15944, -1, 15945, 15945, 15945, -1, + 15946, 15946, 15946, -1, 15947, 15947, 15947, -1, + 15948, 15948, 15948, -1, 15949, 15949, 15949, -1, + 15950, 15950, 15950, -1, 15951, 15951, 15951, -1, + 15952, 15952, 15952, -1, 15953, 15953, 15953, -1, + 15954, 15954, 15954, -1, 15955, 15955, 15955, -1, + 15956, 15956, 15956, -1, 15957, 15957, 15957, -1, + 15958, 15958, 15958, -1, 15959, 15959, 15959, -1, + 15960, 15960, 15960, -1, 15961, 15961, 15961, -1, + 15962, 15962, 15962, -1, 15963, 15963, 15963, -1, + 15964, 15964, 15964, -1, 15965, 15965, 15965, -1, + 15966, 15966, 15966, -1, 15967, 15967, 15967, -1, + 15968, 15968, 15968, -1, 15969, 15969, 15969, -1, + 15970, 15970, 15970, -1, 15971, 15971, 15971, -1, + 15972, 15972, 15972, -1, 15973, 15973, 15973, -1, + 15974, 15974, 15974, -1, 15975, 15975, 15975, -1, + 15976, 15976, 15976, -1, 15977, 15977, 15977, -1, + 15978, 15978, 15978, -1, 15979, 15979, 15979, -1, + 15980, 15980, 15980, -1, 15981, 15981, 15981, -1, + 15982, 15982, 15982, -1, 15983, 15983, 15983, -1, + 15984, 15984, 15984, -1, 15985, 15985, 15985, -1, + 15986, 15986, 15986, -1, 15987, 15987, 15987, -1, + 15988, 15988, 15988, -1, 15989, 15989, 15989, -1, + 15990, 15990, 15990, -1, 15991, 15991, 15991, -1, + 15992, 15992, 15992, -1, 15993, 15993, 15993, -1, + 15994, 15994, 15994, -1, 15995, 15995, 15995, -1, + 15996, 15996, 15996, -1, 15997, 15997, 15997, -1, + 15998, 15998, 15998, -1, 15999, 15999, 15999, -1, + 16000, 16000, 16000, -1, 16001, 16001, 16001, -1, + 16002, 16002, 16002, -1, 16003, 16003, 16003, -1, + 16004, 16004, 16004, -1, 16005, 16005, 16005, -1, + 16006, 16006, 16006, -1, 16007, 16007, 16007, -1, + 16008, 16008, 16008, -1, 16009, 16009, 16009, -1, + 16010, 16010, 16010, -1, 16011, 16011, 16011, -1, + 16012, 16012, 16012, -1, 16013, 16013, 16013, -1, + 16014, 16014, 16014, -1, 16015, 16015, 16015, -1, + 16016, 16016, 16016, -1, 16017, 16017, 16017, -1, + 16018, 16018, 16018, -1, 16019, 16019, 16019, -1, + 16020, 16020, 16020, -1, 16021, 16021, 16021, -1, + 16022, 16022, 16022, -1, 16023, 16023, 16023, -1, + 16024, 16024, 16024, -1, 16025, 16025, 16025, -1, + 16026, 16026, 16026, -1, 16027, 16027, 16027, -1, + 16028, 16028, 16028, -1, 16029, 16029, 16029, -1, + 16030, 16030, 16030, -1, 16031, 16031, 16031, -1, + 16032, 16032, 16032, -1, 16033, 16033, 16033, -1, + 16034, 16034, 16034, -1, 16035, 16035, 16035, -1, + 16036, 16036, 16036, -1, 16037, 16037, 16037, -1, + 16038, 16038, 16038, -1, 16039, 16039, 16039, -1, + 16040, 16040, 16040, -1, 16041, 16041, 16041, -1, + 16042, 16042, 16042, -1, 16043, 16043, 16043, -1, + 16044, 16044, 16044, -1, 16045, 16045, 16045, -1, + 16046, 16046, 16046, -1, 16047, 16047, 16047, -1, + 16048, 16048, 16048, -1, 16049, 16049, 16049, -1, + 16050, 16050, 16050, -1, 16051, 16051, 16051, -1, + 16052, 16052, 16052, -1, 16053, 16053, 16053, -1, + 16054, 16054, 16054, -1, 16055, 16055, 16055, -1, + 16056, 16056, 16056, -1, 16057, 16057, 16057, -1, + 16058, 16058, 16058, -1, 16059, 16059, 16059, -1, + 16060, 16060, 16060, -1, 16061, 16061, 16061, -1, + 16062, 16062, 16062, -1, 16063, 16063, 16063, -1, + 16064, 16064, 16064, -1, 16065, 16065, 16065, -1, + 16066, 16066, 16066, -1, 16067, 16067, 16067, -1, + 16068, 16068, 16068, -1, 16069, 16069, 16069, -1, + 16070, 16070, 16070, -1, 16071, 16071, 16071, -1, + 16072, 16072, 16072, -1, 16073, 16073, 16073, -1, + 16074, 16074, 16074, -1, 16075, 16075, 16075, -1, + 16076, 16076, 16076, -1, 16077, 16077, 16077, -1, + 16078, 16078, 16078, -1, 16079, 16079, 16079, -1, + 16080, 16080, 16080, -1, 16081, 16081, 16081, -1, + 16082, 16082, 16082, -1, 16083, 16083, 16083, -1, + 16084, 16084, 16084, -1, 16085, 16085, 16085, -1, + 16086, 16086, 16086, -1, 16087, 16087, 16087, -1, + 16088, 16088, 16088, -1, 16089, 16089, 16089, -1, + 16090, 16090, 16090, -1, 16091, 16091, 16091, -1, + 16092, 16092, 16092, -1, 16093, 16093, 16093, -1, + 16094, 16094, 16094, -1, 16095, 16095, 16095, -1, + 16096, 16096, 16096, -1, 16097, 16097, 16097, -1, + 16098, 16098, 16098, -1, 16099, 16099, 16099, -1, + 16100, 16100, 16100, -1, 16101, 16101, 16101, -1, + 16102, 16102, 16102, -1, 16103, 16103, 16103, -1, + 16104, 16104, 16104, -1, 16105, 16105, 16105, -1, + 16106, 16106, 16106, -1, 16107, 16107, 16107, -1, + 16108, 16108, 16108, -1, 16109, 16109, 16109, -1, + 16110, 16110, 16110, -1, 16111, 16111, 16111, -1, + 16112, 16112, 16112, -1, 16113, 16113, 16113, -1, + 16114, 16114, 16114, -1, 16115, 16115, 16115, -1, + 16116, 16116, 16116, -1, 16117, 16117, 16117, -1, + 16118, 16118, 16118, -1, 16119, 16119, 16119, -1, + 16120, 16120, 16120, -1, 16121, 16121, 16121, -1, + 16122, 16122, 16122, -1, 16123, 16123, 16123, -1, + 16124, 16124, 16124, -1, 16125, 16125, 16125, -1, + 16126, 16126, 16126, -1, 16127, 16127, 16127, -1, + 16128, 16128, 16128, -1, 16129, 16129, 16129, -1, + 16130, 16130, 16130, -1, 16131, 16131, 16131, -1, + 16132, 16132, 16132, -1, 16133, 16133, 16133, -1, + 16134, 16134, 16134, -1, 16135, 16135, 16135, -1, + 16136, 16136, 16136, -1, 16137, 16137, 16137, -1, + 16138, 16138, 16138, -1, 16139, 16139, 16139, -1, + 16140, 16140, 16140, -1, 16141, 16141, 16141, -1, + 16142, 16142, 16142, -1, 16143, 16143, 16143, -1, + 16144, 16144, 16144, -1, 16145, 16145, 16145, -1, + 16146, 16146, 16146, -1, 16147, 16147, 16147, -1, + 16148, 16148, 16148, -1, 16149, 16149, 16149, -1, + 16150, 16150, 16150, -1, 16151, 16151, 16151, -1, + 16152, 16152, 16152, -1, 16153, 16153, 16153, -1, + 16154, 16154, 16154, -1, 16155, 16155, 16155, -1, + 16156, 16156, 16156, -1, 16157, 16157, 16157, -1, + 16158, 16158, 16158, -1, 16159, 16159, 16159, -1, + 16160, 16160, 16160, -1, 16161, 16161, 16161, -1, + 16162, 16162, 16162, -1, 16163, 16163, 16163, -1, + 16164, 16164, 16164, -1, 16165, 16165, 16165, -1, + 16166, 16166, 16166, -1, 16167, 16167, 16167, -1, + 16168, 16168, 16168, -1, 16169, 16169, 16169, -1, + 16170, 16170, 16170, -1, 16171, 16171, 16171, -1, + 16172, 16172, 16172, -1, 16173, 16173, 16173, -1, + 16174, 16174, 16174, -1, 16175, 16175, 16175, -1, + 16176, 16176, 16176, -1, 16177, 16177, 16177, -1, + 16178, 16178, 16178, -1, 16179, 16179, 16179, -1, + 16180, 16180, 16180, -1, 16181, 16181, 16181, -1, + 16182, 16182, 16182, -1, 16183, 16183, 16183, -1, + 16184, 16184, 16184, -1, 16185, 16185, 16185, -1, + 16186, 16186, 16186, -1, 16187, 16187, 16187, -1, + 16188, 16188, 16188, -1, 16189, 16189, 16189, -1, + 16190, 16190, 16190, -1, 16191, 16191, 16191, -1, + 16192, 16192, 16192, -1, 16193, 16193, 16193, -1, + 16194, 16194, 16194, -1, 16195, 16195, 16195, -1, + 16196, 16196, 16196, -1, 16197, 16197, 16197, -1, + 16198, 16198, 16198, -1, 16199, 16199, 16199, -1, + 16200, 16200, 16200, -1, 16201, 16201, 16201, -1, + 16202, 16202, 16202, -1, 16203, 16203, 16203, -1, + 16204, 16204, 16204, -1, 16205, 16205, 16205, -1, + 16206, 16206, 16206, -1, 16207, 16207, 16207, -1, + 16208, 16208, 16208, -1, 16209, 16209, 16209, -1, + 16210, 16210, 16210, -1, 16211, 16211, 16211, -1, + 16212, 16212, 16212, -1, 16213, 16213, 16213, -1, + 16214, 16214, 16214, -1, 16215, 16215, 16215, -1, + 16216, 16216, 16216, -1, 16217, 16217, 16217, -1, + 16218, 16218, 16218, -1, 16219, 16219, 16219, -1, + 16220, 16220, 16220, -1, 16221, 16221, 16221, -1, + 16222, 16222, 16222, -1, 16223, 16223, 16223, -1, + 16224, 16224, 16224, -1, 16225, 16225, 16225, -1, + 16226, 16226, 16226, -1, 16227, 16227, 16227, -1, + 16228, 16228, 16228, -1, 16229, 16229, 16229, -1, + 16230, 16230, 16230, -1, 16231, 16231, 16231, -1, + 16232, 16232, 16232, -1, 16233, 16233, 16233, -1, + 16234, 16234, 16234, -1, 16235, 16235, 16235, -1, + 16236, 16236, 16236, -1, 16237, 16237, 16237, -1, + 16238, 16238, 16238, -1, 16239, 16239, 16239, -1, + 16240, 16240, 16240, -1, 16241, 16241, 16241, -1, + 16242, 16242, 16242, -1, 16243, 16243, 16243, -1, + 16244, 16244, 16244, -1, 16245, 16245, 16245, -1, + 16246, 16246, 16246, -1, 16247, 16247, 16247, -1, + 16248, 16248, 16248, -1, 16249, 16249, 16249, -1, + 16250, 16250, 16250, -1, 16251, 16251, 16251, -1, + 16252, 16252, 16252, -1, 16253, 16253, 16253, -1, + 16254, 16254, 16254, -1, 16255, 16255, 16255, -1, + 16256, 16256, 16256, -1, 16257, 16257, 16257, -1, + 16258, 16258, 16258, -1, 16259, 16259, 16259, -1, + 16260, 16260, 16260, -1, 16261, 16261, 16261, -1, + 16262, 16262, 16262, -1, 16263, 16263, 16263, -1, + 16264, 16264, 16264, -1, 16265, 16265, 16265, -1, + 16266, 16266, 16266, -1, 16267, 16267, 16267, -1, + 16268, 16268, 16268, -1, 16269, 16269, 16269, -1, + 16270, 16270, 16270, -1, 16271, 16271, 16271, -1, + 16272, 16272, 16272, -1, 16273, 16273, 16273, -1, + 16274, 16274, 16274, -1, 16275, 16275, 16275, -1, + 16276, 16276, 16276, -1, 16277, 16277, 16277, -1, + 16278, 16278, 16278, -1, 16279, 16279, 16279, -1, + 16280, 16280, 16280, -1, 16281, 16281, 16281, -1, + 16282, 16282, 16282, -1, 16283, 16283, 16283, -1, + 16284, 16284, 16284, -1, 16285, 16285, 16285, -1, + 16286, 16286, 16286, -1, 16287, 16287, 16287, -1, + 16288, 16288, 16288, -1, 16289, 16289, 16289, -1, + 16290, 16290, 16290, -1, 16291, 16291, 16291, -1, + 16292, 16292, 16292, -1, 16293, 16293, 16293, -1, + 16294, 16294, 16294, -1, 16295, 16295, 16295, -1, + 16296, 16296, 16296, -1, 16297, 16297, 16297, -1, + 16298, 16298, 16298, -1, 16299, 16299, 16299, -1, + 16300, 16300, 16300, -1, 16301, 16301, 16301, -1, + 16302, 16302, 16302, -1, 16303, 16303, 16303, -1, + 16304, 16304, 16304, -1, 16305, 16305, 16305, -1, + 16306, 16306, 16306, -1, 16307, 16307, 16307, -1, + 16308, 16308, 16308, -1, 16309, 16309, 16309, -1, + 16310, 16310, 16310, -1, 16311, 16311, 16311, -1, + 16312, 16312, 16312, -1, 16313, 16313, 16313, -1, + 16314, 16314, 16314, -1, 16315, 16315, 16315, -1, + 16316, 16316, 16316, -1, 16317, 16317, 16317, -1, + 16318, 16318, 16318, -1, 16319, 16319, 16319, -1, + 16320, 16320, 16320, -1, 16321, 16321, 16321, -1, + 16322, 16322, 16322, -1, 16323, 16323, 16323, -1, + 16324, 16324, 16324, -1, 16325, 16325, 16325, -1, + 16326, 16326, 16326, -1, 16327, 16327, 16327, -1, + 16328, 16328, 16328, -1, 16329, 16329, 16329, -1, + 16330, 16330, 16330, -1, 16331, 16331, 16331, -1, + 16332, 16332, 16332, -1, 16333, 16333, 16333, -1, + 16334, 16334, 16334, -1, 16335, 16335, 16335, -1, + 16336, 16336, 16336, -1, 16337, 16337, 16337, -1, + 16338, 16338, 16338, -1, 16339, 16339, 16339, -1, + 16340, 16340, 16340, -1, 16341, 16341, 16341, -1, + 16342, 16342, 16342, -1, 16343, 16343, 16343, -1, + 16344, 16344, 16344, -1, 16345, 16345, 16345, -1, + 16346, 16346, 16346, -1, 16347, 16347, 16347, -1, + 16348, 16348, 16348, -1, 16349, 16349, 16349, -1, + 16350, 16350, 16350, -1, 16351, 16351, 16351, -1, + 16352, 16352, 16352, -1, 16353, 16353, 16353, -1, + 16354, 16354, 16354, -1, 16355, 16355, 16355, -1, + 16356, 16356, 16356, -1, 16357, 16357, 16357, -1, + 16358, 16358, 16358, -1, 16359, 16359, 16359, -1, + 16360, 16360, 16360, -1, 16361, 16361, 16361, -1, + 16362, 16362, 16362, -1, 16363, 16363, 16363, -1, + 16364, 16364, 16364, -1, 16365, 16365, 16365, -1, + 16366, 16366, 16366, -1, 16367, 16367, 16367, -1, + 16368, 16368, 16368, -1, 16369, 16369, 16369, -1, + 16370, 16370, 16370, -1, 16371, 16371, 16371, -1, + 16372, 16372, 16372, -1, 16373, 16373, 16373, -1, + 16374, 16374, 16374, -1, 16375, 16375, 16375, -1, + 16376, 16376, 16376, -1, 16377, 16377, 16377, -1, + 16378, 16378, 16378, -1, 16379, 16379, 16379, -1, + 16380, 16380, 16380, -1, 16381, 16381, 16381, -1, + 16382, 16382, 16382, -1, 16383, 16383, 16383, -1, + 16384, 16384, 16384, -1, 16385, 16385, 16385, -1, + 16386, 16386, 16386, -1, 16387, 16387, 16387, -1, + 16388, 16388, 16388, -1, 16389, 16389, 16389, -1, + 16390, 16390, 16390, -1, 16391, 16391, 16391, -1, + 16392, 16392, 16392, -1, 16393, 16393, 16393, -1, + 16394, 16394, 16394, -1, 16395, 16395, 16395, -1, + 16396, 16396, 16396, -1, 16397, 16397, 16397, -1, + 16398, 16398, 16398, -1, 16399, 16399, 16399, -1, + 16400, 16400, 16400, -1, 16401, 16401, 16401, -1, + 16402, 16402, 16402, -1, 16403, 16403, 16403, -1, + 16404, 16404, 16404, -1, 16405, 16405, 16405, -1, + 16406, 16406, 16406, -1, 16407, 16407, 16407, -1, + 16408, 16408, 16408, -1, 16409, 16409, 16409, -1, + 16410, 16410, 16410, -1, 16411, 16411, 16411, -1, + 16412, 16412, 16412, -1, 16413, 16413, 16413, -1, + 16414, 16414, 16414, -1, 16415, 16415, 16415, -1, + 16416, 16416, 16416, -1, 16417, 16417, 16417, -1, + 16418, 16418, 16418, -1, 16419, 16419, 16419, -1, + 16420, 16420, 16420, -1, 16421, 16421, 16421, -1, + 16422, 16422, 16422, -1, 16423, 16423, 16423, -1, + 16424, 16424, 16424, -1, 16425, 16425, 16425, -1, + 16426, 16426, 16426, -1, 16427, 16427, 16427, -1, + 16428, 16428, 16428, -1, 16429, 16429, 16429, -1, + 16430, 16430, 16430, -1, 16431, 16431, 16431, -1, + 16432, 16432, 16432, -1, 16433, 16433, 16433, -1, + 16434, 16434, 16434, -1, 16435, 16435, 16435, -1, + 16436, 16436, 16436, -1, 16437, 16437, 16437, -1, + 16438, 16438, 16438, -1, 16439, 16439, 16439, -1, + 16440, 16440, 16440, -1, 16441, 16441, 16441, -1, + 16442, 16442, 16442, -1, 16443, 16443, 16443, -1, + 16444, 16444, 16444, -1, 16445, 16445, 16445, -1, + 16446, 16446, 16446, -1, 16447, 16447, 16447, -1, + 16448, 16448, 16448, -1, 16449, 16449, 16449, -1, + 16450, 16450, 16450, -1, 16451, 16451, 16451, -1, + 16452, 16452, 16452, -1, 16453, 16453, 16453, -1, + 16454, 16454, 16454, -1, 16455, 16455, 16455, -1, + 16456, 16456, 16456, -1, 16457, 16457, 16457, -1, + 16458, 16458, 16458, -1, 16459, 16459, 16459, -1, + 16460, 16460, 16460, -1, 16461, 16461, 16461, -1, + 16462, 16462, 16462, -1, 16463, 16463, 16463, -1, + 16464, 16464, 16464, -1, 16465, 16465, 16465, -1, + 16466, 16466, 16466, -1, 16467, 16467, 16467, -1, + 16468, 16468, 16468, -1, 16469, 16469, 16469, -1, + 16470, 16470, 16470, -1, 16471, 16471, 16471, -1, + 16472, 16472, 16472, -1, 16473, 16473, 16473, -1, + 16474, 16474, 16474, -1, 16475, 16475, 16475, -1, + 16476, 16476, 16476, -1, 16477, 16477, 16477, -1, + 16478, 16478, 16478, -1, 16479, 16479, 16479, -1, + 16480, 16480, 16480, -1, 16481, 16481, 16481, -1, + 16482, 16482, 16482, -1, 16483, 16483, 16483, -1, + 16484, 16484, 16484, -1, 16485, 16485, 16485, -1, + 16486, 16486, 16486, -1, 16487, 16487, 16487, -1, + 16488, 16488, 16488, -1, 16489, 16489, 16489, -1, + 16490, 16490, 16490, -1, 16491, 16491, 16491, -1, + 16492, 16492, 16492, -1, 16493, 16493, 16493, -1, + 16494, 16494, 16494, -1, 16495, 16495, 16495, -1, + 16496, 16496, 16496, -1, 16497, 16497, 16497, -1, + 16498, 16498, 16498, -1, 16499, 16499, 16499, -1, + 16500, 16500, 16500, -1, 16501, 16501, 16501, -1, + 16502, 16502, 16502, -1, 16503, 16503, 16503, -1, + 16504, 16504, 16504, -1, 16505, 16505, 16505, -1, + 16506, 16506, 16506, -1, 16507, 16507, 16507, -1, + 16508, 16508, 16508, -1, 16509, 16509, 16509, -1, + 16510, 16510, 16510, -1, 16511, 16511, 16511, -1, + 16512, 16512, 16512, -1, 16513, 16513, 16513, -1, + 16514, 16514, 16514, -1, 16515, 16515, 16515, -1, + 16516, 16516, 16516, -1, 16517, 16517, 16517, -1, + 16518, 16518, 16518, -1, 16519, 16519, 16519, -1, + 16520, 16520, 16520, -1, 16521, 16521, 16521, -1, + 16522, 16522, 16522, -1, 16523, 16523, 16523, -1, + 16524, 16524, 16524, -1, 16525, 16525, 16525, -1, + 16526, 16526, 16526, -1, 16527, 16527, 16527, -1, + 16528, 16528, 16528, -1, 16529, 16529, 16529, -1, + 16530, 16530, 16530, -1, 16531, 16531, 16531, -1, + 16532, 16532, 16532, -1, 16533, 16533, 16533, -1, + 16534, 16534, 16534, -1, 16535, 16535, 16535, -1, + 16536, 16536, 16536, -1, 16537, 16537, 16537, -1, + 16538, 16538, 16538, -1, 16539, 16539, 16539, -1, + 16540, 16540, 16540, -1, 16541, 16541, 16541, -1, + 16542, 16542, 16542, -1, 16543, 16543, 16543, -1, + 16544, 16544, 16544, -1, 16545, 16545, 16545, -1, + 16546, 16546, 16546, -1, 16547, 16547, 16547, -1, + 16548, 16548, 16548, -1, 16549, 16549, 16549, -1, + 16550, 16550, 16550, -1, 16551, 16551, 16551, -1, + 16552, 16552, 16552, -1, 16553, 16553, 16553, -1, + 16554, 16554, 16554, -1, 16555, 16555, 16555, -1, + 16556, 16556, 16556, -1, 16557, 16557, 16557, -1, + 16558, 16558, 16558, -1, 16559, 16559, 16559, -1, + 16560, 16560, 16560, -1, 16561, 16561, 16561, -1, + 16562, 16562, 16562, -1, 16563, 16563, 16563, -1, + 16564, 16564, 16564, -1, 16565, 16565, 16565, -1, + 16566, 16566, 16566, -1, 16567, 16567, 16567, -1, + 16568, 16568, 16568, -1, 16569, 16569, 16569, -1, + 16570, 16570, 16570, -1, 16571, 16571, 16571, -1, + 16572, 16572, 16572, -1, 16573, 16573, 16573, -1, + 16574, 16574, 16574, -1, 16575, 16575, 16575, -1, + 16576, 16576, 16576, -1, 16577, 16577, 16577, -1, + 16578, 16578, 16578, -1, 16579, 16579, 16579, -1, + 16580, 16580, 16580, -1, 16581, 16581, 16581, -1, + 16582, 16582, 16582, -1, 16583, 16583, 16583, -1, + 16584, 16584, 16584, -1, 16585, 16585, 16585, -1, + 16586, 16586, 16586, -1, 16587, 16587, 16587, -1, + 16588, 16588, 16588, -1, 16589, 16589, 16589, -1, + 16590, 16590, 16590, -1, 16591, 16591, 16591, -1, + 16592, 16592, 16592, -1, 16593, 16593, 16593, -1, + 16594, 16594, 16594, -1, 16595, 16595, 16595, -1, + 16596, 16596, 16596, -1, 16597, 16597, 16597, -1, + 16598, 16598, 16598, -1, 16599, 16599, 16599, -1, + 16600, 16600, 16600, -1, 16601, 16601, 16601, -1, + 16602, 16602, 16602, -1, 16603, 16603, 16603, -1, + 16604, 16604, 16604, -1, 16605, 16605, 16605, -1, + 16606, 16606, 16606, -1, 16607, 16607, 16607, -1, + 16608, 16608, 16608, -1, 16609, 16609, 16609, -1, + 16610, 16610, 16610, -1, 16611, 16611, 16611, -1, + 16612, 16612, 16612, -1, 16613, 16613, 16613, -1, + 16614, 16614, 16614, -1, 16615, 16615, 16615, -1, + 16616, 16616, 16616, -1, 16617, 16617, 16617, -1, + 16618, 16618, 16618, -1, 16619, 16619, 16619, -1, + 16620, 16620, 16620, -1, 16621, 16621, 16621, -1, + 16622, 16622, 16622, -1, 16623, 16623, 16623, -1, + 16624, 16624, 16624, -1, 16625, 16625, 16625, -1, + 16626, 16626, 16626, -1, 16627, 16627, 16627, -1, + 16628, 16628, 16628, -1, 16629, 16629, 16629, -1, + 16630, 16630, 16630, -1, 16631, 16631, 16631, -1, + 16632, 16632, 16632, -1, 16633, 16633, 16633, -1, + 16634, 16634, 16634, -1, 16635, 16635, 16635, -1, + 16636, 16636, 16636, -1, 16637, 16637, 16637, -1, + 16638, 16638, 16638, -1, 16639, 16639, 16639, -1, + 16640, 16640, 16640, -1, 16641, 16641, 16641, -1, + 16642, 16642, 16642, -1, 16643, 16643, 16643, -1, + 16644, 16644, 16644, -1, 16645, 16645, 16645, -1, + 16646, 16646, 16646, -1, 16647, 16647, 16647, -1, + 16648, 16648, 16648, -1, 16649, 16649, 16649, -1, + 16650, 16650, 16650, -1, 16651, 16651, 16651, -1, + 16652, 16652, 16652, -1, 16653, 16653, 16653, -1, + 16654, 16654, 16654, -1, 16655, 16655, 16655, -1, + 16656, 16656, 16656, -1, 16657, 16657, 16657, -1, + 16658, 16658, 16658, -1, 16659, 16659, 16659, -1, + 16660, 16660, 16660, -1, 16661, 16661, 16661, -1, + 16662, 16662, 16662, -1, 16663, 16663, 16663, -1, + 16664, 16664, 16664, -1, 16665, 16665, 16665, -1, + 16666, 16666, 16666, -1, 16667, 16667, 16667, -1, + 16668, 16668, 16668, -1, 16669, 16669, 16669, -1, + 16670, 16670, 16670, -1, 16671, 16671, 16671, -1, + 16672, 16672, 16672, -1, 16673, 16673, 16673, -1, + 16674, 16674, 16674, -1, 16675, 16675, 16675, -1, + 16676, 16676, 16676, -1, 16677, 16677, 16677, -1, + 16678, 16678, 16678, -1, 16679, 16679, 16679, -1, + 16680, 16680, 16680, -1, 16681, 16681, 16681, -1, + 16682, 16682, 16682, -1, 16683, 16683, 16683, -1, + 16684, 16684, 16684, -1, 16685, 16685, 16685, -1, + 16686, 16686, 16686, -1, 16687, 16687, 16687, -1, + 16688, 16688, 16688, -1, 16689, 16689, 16689, -1, + 16690, 16690, 16690, -1, 16691, 16691, 16691, -1, + 16692, 16692, 16692, -1, 16693, 16693, 16693, -1, + 16694, 16694, 16694, -1, 16695, 16695, 16695, -1, + 16696, 16696, 16696, -1, 16697, 16697, 16697, -1, + 16698, 16698, 16698, -1, 16699, 16699, 16699, -1, + 16700, 16700, 16700, -1, 16701, 16701, 16701, -1, + 16702, 16702, 16702, -1, 16703, 16703, 16703, -1, + 16704, 16704, 16704, -1, 16705, 16705, 16705, -1, + 16706, 16706, 16706, -1, 16707, 16707, 16707, -1, + 16708, 16708, 16708, -1, 16709, 16709, 16709, -1, + 16710, 16710, 16710, -1, 16711, 16711, 16711, -1, + 16712, 16712, 16712, -1, 16713, 16713, 16713, -1, + 16714, 16714, 16714, -1, 16715, 16715, 16715, -1, + 16716, 16716, 16716, -1, 16717, 16717, 16717, -1, + 16718, 16718, 16718, -1, 16719, 16719, 16719, -1, + 16720, 16720, 16720, -1, 16721, 16721, 16721, -1, + 16722, 16722, 16722, -1, 16723, 16723, 16723, -1, + 16724, 16724, 16724, -1, 16725, 16725, 16725, -1, + 16726, 16726, 16726, -1, 16727, 16727, 16727, -1, + 16728, 16728, 16728, -1, 16729, 16729, 16729, -1, + 16730, 16730, 16730, -1, 16731, 16731, 16731, -1, + 16732, 16732, 16732, -1, 16733, 16733, 16733, -1, + 16734, 16734, 16734, -1, 16735, 16735, 16735, -1, + 16736, 16736, 16736, -1, 16737, 16737, 16737, -1, + 16738, 16738, 16738, -1, 16739, 16739, 16739, -1, + 16740, 16740, 16740, -1, 16741, 16741, 16741, -1, + 16742, 16742, 16742, -1, 16743, 16743, 16743, -1, + 16744, 16744, 16744, -1, 16745, 16745, 16745, -1, + 16746, 16746, 16746, -1, 16747, 16747, 16747, -1, + 16748, 16748, 16748, -1, 16749, 16749, 16749, -1, + 16750, 16750, 16750, -1, 16751, 16751, 16751, -1, + 16752, 16752, 16752, -1, 16753, 16753, 16753, -1, + 16754, 16754, 16754, -1, 16755, 16755, 16755, -1, + 16756, 16756, 16756, -1, 16757, 16757, 16757, -1, + 16758, 16758, 16758, -1, 16759, 16759, 16759, -1, + 16760, 16760, 16760, -1, 16761, 16761, 16761, -1, + 16762, 16762, 16762, -1, 16763, 16763, 16763, -1, + 16764, 16764, 16764, -1, 16765, 16765, 16765, -1, + 16766, 16766, 16766, -1, 16767, 16767, 16767, -1, + 16768, 16768, 16768, -1, 16769, 16769, 16769, -1, + 16770, 16770, 16770, -1, 16771, 16771, 16771, -1, + 16772, 16772, 16772, -1, 16773, 16773, 16773, -1, + 16774, 16774, 16774, -1, 16775, 16775, 16775, -1, + 16776, 16776, 16776, -1, 16777, 16777, 16777, -1, + 16778, 16778, 16778, -1, 16779, 16779, 16779, -1, + 16780, 16780, 16780, -1, 16781, 16781, 16781, -1, + 16782, 16782, 16782, -1, 16783, 16783, 16783, -1, + 16784, 16784, 16784, -1, 16785, 16785, 16785, -1, + 16786, 16786, 16786, -1, 16787, 16787, 16787, -1, + 16788, 16788, 16788, -1, 16789, 16789, 16789, -1, + 16790, 16790, 16790, -1, 16791, 16791, 16791, -1, + 16792, 16792, 16792, -1, 16793, 16793, 16793, -1, + 16794, 16794, 16794, -1, 16795, 16795, 16795, -1, + 16796, 16796, 16796, -1, 16797, 16797, 16797, -1, + 16798, 16798, 16798, -1, 16799, 16799, 16799, -1, + 16800, 16800, 16800, -1, 16801, 16801, 16801, -1, + 16802, 16802, 16802, -1, 16803, 16803, 16803, -1, + 16804, 16804, 16804, -1, 16805, 16805, 16805, -1, + 16806, 16806, 16806, -1, 16807, 16807, 16807, -1, + 16808, 16808, 16808, -1, 16809, 16809, 16809, -1, + 16810, 16810, 16810, -1, 16811, 16811, 16811, -1, + 16812, 16812, 16812, -1, 16813, 16813, 16813, -1, + 16814, 16814, 16814, -1, 16815, 16815, 16815, -1, + 16816, 16816, 16816, -1, 16817, 16817, 16817, -1, + 16818, 16818, 16818, -1, 16819, 16819, 16819, -1, + 16820, 16820, 16820, -1, 16821, 16821, 16821, -1, + 16822, 16822, 16822, -1, 16823, 16823, 16823, -1, + 16824, 16824, 16824, -1, 16825, 16825, 16825, -1, + 16826, 16826, 16826, -1, 16827, 16827, 16827, -1, + 16828, 16828, 16828, -1, 16829, 16829, 16829, -1, + 16830, 16830, 16830, -1, 16831, 16831, 16831, -1, + 16832, 16832, 16832, -1, 16833, 16833, 16833, -1, + 16834, 16834, 16834, -1, 16835, 16835, 16835, -1, + 16836, 16836, 16836, -1, 16837, 16837, 16837, -1, + 16838, 16838, 16838, -1, 16839, 16839, 16839, -1, + 16840, 16840, 16840, -1, 16841, 16841, 16841, -1, + 16842, 16842, 16842, -1, 16843, 16843, 16843, -1, + 16844, 16844, 16844, -1, 16845, 16845, 16845, -1, + 16846, 16846, 16846, -1, 16847, 16847, 16847, -1, + 16848, 16848, 16848, -1, 16849, 16849, 16849, -1, + 16850, 16850, 16850, -1, 16851, 16851, 16851, -1, + 16852, 16852, 16852, -1, 16853, 16853, 16853, -1, + 16854, 16854, 16854, -1, 16855, 16855, 16855, -1, + 16856, 16856, 16856, -1, 16857, 16857, 16857, -1, + 16858, 16858, 16858, -1, 16859, 16859, 16859, -1, + 16860, 16860, 16860, -1, 16861, 16861, 16861, -1, + 16862, 16862, 16862, -1, 16863, 16863, 16863, -1, + 16864, 16864, 16864, -1, 16865, 16865, 16865, -1, + 16866, 16866, 16866, -1, 16867, 16867, 16867, -1, + 16868, 16868, 16868, -1, 16869, 16869, 16869, -1, + 16870, 16870, 16870, -1, 16871, 16871, 16871, -1, + 16872, 16872, 16872, -1, 16873, 16873, 16873, -1, + 16874, 16874, 16874, -1, 16875, 16875, 16875, -1, + 16876, 16876, 16876, -1, 16877, 16877, 16877, -1, + 16878, 16878, 16878, -1, 16879, 16879, 16879, -1, + 16880, 16880, 16880, -1, 16881, 16881, 16881, -1, + 16882, 16882, 16882, -1, 16883, 16883, 16883, -1, + 16884, 16884, 16884, -1, 16885, 16885, 16885, -1, + 16886, 16886, 16886, -1, 16887, 16887, 16887, -1, + 16888, 16888, 16888, -1, 16889, 16889, 16889, -1, + 16890, 16890, 16890, -1, 16891, 16891, 16891, -1, + 16892, 16892, 16892, -1, 16893, 16893, 16893, -1, + 16894, 16894, 16894, -1, 16895, 16895, 16895, -1, + 16896, 16896, 16896, -1, 16897, 16897, 16897, -1, + 16898, 16898, 16898, -1, 16899, 16899, 16899, -1, + 16900, 16900, 16900, -1, 16901, 16901, 16901, -1, + 16902, 16902, 16902, -1, 16903, 16903, 16903, -1, + 16904, 16904, 16904, -1, 16905, 16905, 16905, -1, + 16906, 16906, 16906, -1, 16907, 16907, 16907, -1, + 16908, 16908, 16908, -1, 16909, 16909, 16909, -1, + 16910, 16910, 16910, -1, 16911, 16911, 16911, -1, + 16912, 16912, 16912, -1, 16913, 16913, 16913, -1, + 16914, 16914, 16914, -1, 16915, 16915, 16915, -1, + 16916, 16916, 16916, -1, 16917, 16917, 16917, -1, + 16918, 16918, 16918, -1, 16919, 16919, 16919, -1, + 16920, 16920, 16920, -1, 16921, 16921, 16921, -1, + 16922, 16922, 16922, -1, 16923, 16923, 16923, -1, + 16924, 16924, 16924, -1, 16925, 16925, 16925, -1, + 16926, 16926, 16926, -1, 16927, 16927, 16927, -1, + 16928, 16928, 16928, -1, 16929, 16929, 16929, -1, + 16930, 16930, 16930, -1, 16931, 16931, 16931, -1, + 16932, 16932, 16932, -1, 16933, 16933, 16933, -1, + 16934, 16934, 16934, -1, 16935, 16935, 16935, -1, + 16936, 16936, 16936, -1, 16937, 16937, 16937, -1, + 16938, 16938, 16938, -1, 16939, 16939, 16939, -1, + 16940, 16940, 16940, -1, 16941, 16941, 16941, -1, + 16942, 16942, 16942, -1, 16943, 16943, 16943, -1, + 16944, 16944, 16944, -1, 16945, 16945, 16945, -1, + 16946, 16946, 16946, -1, 16947, 16947, 16947, -1, + 16948, 16948, 16948, -1, 16949, 16949, 16949, -1, + 16950, 16950, 16950, -1, 16951, 16951, 16951, -1, + 16952, 16952, 16952, -1, 16953, 16953, 16953, -1, + 16954, 16954, 16954, -1, 16955, 16955, 16955, -1, + 16956, 16956, 16956, -1, 16957, 16957, 16957, -1, + 16958, 16958, 16958, -1, 16959, 16959, 16959, -1, + 16960, 16960, 16960, -1, 16961, 16961, 16961, -1, + 16962, 16962, 16962, -1, 16963, 16963, 16963, -1, + 16964, 16964, 16964, -1, 16965, 16965, 16965, -1, + 16966, 16966, 16966, -1, 16967, 16967, 16967, -1, + 16968, 16968, 16968, -1, 16969, 16969, 16969, -1, + 16970, 16970, 16970, -1, 16971, 16971, 16971, -1, + 16972, 16972, 16972, -1, 16973, 16973, 16973, -1, + 16974, 16974, 16974, -1, 16975, 16975, 16975, -1, + 16976, 16976, 16976, -1, 16977, 16977, 16977, -1, + 16978, 16978, 16978, -1, 16979, 16979, 16979, -1, + 16980, 16980, 16980, -1, 16981, 16981, 16981, -1, + 16982, 16982, 16982, -1, 16983, 16983, 16983, -1, + 16984, 16984, 16984, -1, 16985, 16985, 16985, -1, + 16986, 16986, 16986, -1, 16987, 16987, 16987, -1, + 16988, 16988, 16988, -1, 16989, 16989, 16989, -1, + 16990, 16990, 16990, -1, 16991, 16991, 16991, -1, + 16992, 16992, 16992, -1, 16993, 16993, 16993, -1, + 16994, 16994, 16994, -1, 16995, 16995, 16995, -1, + 16996, 16996, 16996, -1, 16997, 16997, 16997, -1, + 16998, 16998, 16998, -1, 16999, 16999, 16999, -1, + 17000, 17000, 17000, -1, 17001, 17001, 17001, -1, + 17002, 17002, 17002, -1, 17003, 17003, 17003, -1, + 17004, 17004, 17004, -1, 17005, 17005, 17005, -1, + 17006, 17006, 17006, -1, 17007, 17007, 17007, -1, + 17008, 17008, 17008, -1, 17009, 17009, 17009, -1, + 17010, 17010, 17010, -1, 17011, 17011, 17011, -1, + 17012, 17012, 17012, -1, 17013, 17013, 17013, -1, + 17014, 17014, 17014, -1, 17015, 17015, 17015, -1, + 17016, 17016, 17016, -1, 17017, 17017, 17017, -1, + 17018, 17018, 17018, -1, 17019, 17019, 17019, -1, + 17020, 17020, 17020, -1, 17021, 17021, 17021, -1, + 17022, 17022, 17022, -1, 17023, 17023, 17023, -1, + 17024, 17024, 17024, -1, 17025, 17025, 17025, -1, + 17026, 17026, 17026, -1, 17027, 17027, 17027, -1, + 17028, 17028, 17028, -1, 17029, 17029, 17029, -1, + 17030, 17030, 17030, -1, 17031, 17031, 17031, -1, + 17032, 17032, 17032, -1, 17033, 17033, 17033, -1, + 17034, 17034, 17034, -1, 17035, 17035, 17035, -1, + 17036, 17036, 17036, -1, 17037, 17037, 17037, -1, + 17038, 17038, 17038, -1, 17039, 17039, 17039, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17041, 17041, 17041, -1, 17041, 17041, 17041, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17043, 17043, 17043, -1, + 17043, 17043, 17043, -1, 17044, 17044, 17044, -1, + 17044, 17044, 17044, -1, 17045, 17045, 17045, -1, + 17045, 17045, 17045, -1, 17046, 17046, 17046, -1, + 17046, 17046, 17046, -1, 17047, 17047, 17047, -1, + 17047, 17047, 17047, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17049, 17049, 17049, -1, + 17049, 17049, 17049, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17051, 17051, 17051, -1, + 17051, 17051, 17051, -1, 17052, 17052, 17052, -1, + 17052, 17052, 17052, -1, 17053, 17053, 17053, -1, + 17053, 17053, 17053, -1, 17054, 17054, 17054, -1, + 17054, 17054, 17054, -1, 17055, 17055, 17055, -1, + 17055, 17055, 17055, -1, 17056, 17056, 17056, -1, + 17056, 17056, 17056, -1, 17057, 17057, 17057, -1, + 17057, 17057, 17057, -1, 17058, 17058, 17058, -1, + 17058, 17058, 17058, -1, 17059, 17059, 17059, -1, + 17059, 17059, 17059, -1, 17060, 17060, 17060, -1, + 17060, 17060, 17060, -1, 17061, 17061, 17061, -1, + 17061, 17061, 17061, -1, 17062, 17062, 17062, -1, + 17062, 17062, 17062, -1, 17063, 17063, 17063, -1, + 17063, 17063, 17063, -1, 17064, 17064, 17064, -1, + 17064, 17064, 17064, -1, 17065, 17065, 17065, -1, + 17065, 17065, 17065, -1, 17066, 17066, 17066, -1, + 17066, 17066, 17066, -1, 17067, 17067, 17067, -1, + 17067, 17067, 17067, -1, 17068, 17068, 17068, -1, + 17068, 17068, 17068, -1, 17069, 17069, 17069, -1, + 17069, 17069, 17069, -1, 17070, 17070, 17070, -1, + 17070, 17070, 17070, -1, 17071, 17071, 17071, -1, + 17071, 17071, 17071, -1, 17072, 17072, 17072, -1, + 17072, 17072, 17072, -1, 17073, 17073, 17073, -1, + 17073, 17073, 17073, -1, 17074, 17074, 17074, -1, + 17074, 17074, 17074, -1, 17075, 17075, 17075, -1, + 17075, 17075, 17075, -1, 17076, 17076, 17076, -1, + 17076, 17076, 17076, -1, 17077, 17077, 17077, -1, + 17077, 17077, 17077, -1, 17078, 17078, 17078, -1, + 17078, 17078, 17078, -1, 17079, 17079, 17079, -1, + 17079, 17079, 17079, -1, 17080, 17080, 17080, -1, + 17080, 17080, 17080, -1, 17081, 17081, 17081, -1, + 17081, 17081, 17081, -1, 17082, 17082, 17082, -1, + 17082, 17082, 17082, -1, 17083, 17083, 17083, -1, + 17083, 17083, 17083, -1, 17084, 17084, 17084, -1, + 17084, 17084, 17084, -1, 17085, 17085, 17085, -1, + 17085, 17085, 17085, -1, 17086, 17086, 17086, -1, + 17086, 17086, 17086, -1, 17087, 17087, 17087, -1, + 17087, 17087, 17087, -1, 17088, 17088, 17088, -1, + 17088, 17088, 17088, -1, 17089, 17089, 17089, -1, + 17089, 17089, 17089, -1, 17090, 17090, 17090, -1, + 17090, 17090, 17090, -1, 17091, 17091, 17091, -1, + 17091, 17091, 17091, -1, 17092, 17092, 17092, -1, + 17092, 17092, 17092, -1, 17093, 17093, 17093, -1, + 17093, 17093, 17093, -1, 17094, 17094, 17094, -1, + 17094, 17094, 17094, -1, 17095, 17095, 17095, -1, + 17095, 17095, 17095, -1, 17096, 17096, 17096, -1, + 17096, 17096, 17096, -1, 17097, 17097, 17097, -1, + 17097, 17097, 17097, -1, 17098, 17098, 17098, -1, + 17098, 17098, 17098, -1, 17099, 17099, 17099, -1, + 17099, 17099, 17099, -1, 17100, 17100, 17100, -1, + 17100, 17100, 17100, -1, 17101, 17101, 17101, -1, + 17101, 17101, 17101, -1, 17102, 17102, 17102, -1, + 17102, 17102, 17102, -1, 17103, 17103, 17103, -1, + 17103, 17103, 17103, -1, 17104, 17104, 17104, -1, + 17104, 17104, 17104, -1, 17105, 17105, 17105, -1, + 17105, 17105, 17105, -1, 17106, 17106, 17106, -1, + 17106, 17106, 17106, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1, + 17050, 17050, 17050, -1, 17050, 17050, 17050, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } ] + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link4.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link4.wrl new file mode 100644 index 0000000..a11bb95 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link4.wrl @@ -0,0 +1,44121 @@ +#VRML V2.0 utf8 + + +Group { + children [ + Group { + children + Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.059316002 -0.208491 0.0092001203, + 0.058772299 -0.191489 0.0122281, + 0.058072701 -0.20848601 0.0152511, + 0.028020401 -0.20854101 -0.052889202, + 0.0307144 -0.191539 -0.051389899, + 0.033327099 -0.208538 -0.049727, + -0.036173999 -0.208536 -0.047703002, + -0.040904202 -0.208533 -0.043729801, + -0.038590301 -0.191535 -0.045790799, + -0.054897901 -0.208479 0.024377899, + -0.056071501 -0.19148099 0.0215063, + -0.0570965 -0.20848399 0.018604999, + 0.0109552 -0.208451 0.059157401, + 0.0079039196 -0.191451 0.0596296, + 0.0048316298 -0.208451 0.059971102, + 0.028376499 -0.20845599 0.053031601, + 0.0256174 -0.19145501 0.0544088, + 0.0227904 -0.208454 0.055669099, + 0.033661801 -0.208459 0.0498337, + 0.031060301 -0.191457 0.0514872, + 0.038590301 -0.208462 0.0461093, + 0.036173999 -0.19146 0.048021499, + 0.0431097 -0.208465 0.0418979, + 0.040904202 -0.19146299 0.044048298, + 0.047172099 -0.208469 0.037244201, + 0.045200799 -0.191467 0.039609902, + 0.0471096 -0.191469 0.0371815, + 0.049018301 -0.191471 0.0347532, + 0.033617198 -0.191459 0.0497544, + 0.0283389 -0.191456 0.052948002, + 0.022760199 -0.19145399 0.055582002, + 0.019903 -0.19145299 0.056755301, + 0.0169627 -0.208452 0.057718299, + 0.016940201 -0.19145299 0.057628501, + 0.0139775 -0.191452 0.058501702, + -0.0449345 -0.20846701 0.039926399, + -0.040608101 -0.208463 0.044335902, + -0.042828102 -0.19146501 0.042173401, + -0.0358513 -0.20846 0.048277199, + -0.038280498 -0.191462 0.046354301, + -0.0307144 -0.20845699 0.0517084, + -0.033327099 -0.191459 0.050045501, + -0.025251999 -0.208455 0.054593299, + -0.028020401 -0.191456 0.053207699, + -0.0195219 -0.208453 0.056901298, + -0.0224167 -0.19145399 0.055807602, + -0.0135848 -0.208452 0.058607899, + -0.016575299 -0.191452 0.0578175, + -0.0075038001 -0.208451 0.059694901, + -0.0105583 -0.191451 0.059216201, + -0.0013432 -0.208451 0.060151, + -0.0044293702 -0.191451 0.0599888, + 0.0017465299 -0.191451 0.060127102, + 0.0109407 -0.191451 0.0590657, + 0.0048252302 -0.191451 0.059878301, + -0.00134142 -0.191451 0.060057901, + -0.0135668 -0.191452 0.058516901, + -0.019495999 -0.19145299 0.056812599, + -0.0252185 -0.19145501 0.054507699, + -0.030673699 -0.191457 0.0516266, + -0.0405543 -0.19146299 0.044263799, + -0.0469217 -0.191469 0.037547, + -0.048784502 -0.208471 0.035095502, + -0.048719902 -0.191471 0.0350357, + -0.050517999 -0.19147301 0.032524299, + -0.0521175 -0.20847499 0.0298943, + -0.0520484 -0.191475 0.029841401, + -0.053578701 -0.191477 0.0271584, + -0.0523162 -0.20852201 -0.029211201, + -0.050734501 -0.191524 -0.0318789, + -0.049018301 -0.208526 -0.034434699, + -0.0550595 -0.208517 -0.0236762, + -0.053759102 -0.19152001 -0.026492501, + -0.0572192 -0.20851301 -0.0178886, + -0.0562139 -0.191515 -0.0208237, + -0.058772299 -0.208508 -0.0119096, + -0.058072701 -0.19151001 -0.0149326, + -0.0597024 -0.20850299 -0.0058025299, + -0.059316002 -0.191506 -0.0088815596, + -0.059999701 -0.208498 0.00036775399, + -0.0599305 -0.19150101 -0.00273475, + -0.0596609 -0.20849299 0.0065359101, + -0.059909701 -0.191496 0.00344266, + -0.058689699 -0.208488 0.0126365, + -0.059253901 -0.19149099 0.0095851803, + -0.057969999 -0.191486 0.0156278, + -0.054825101 -0.191479 0.0243323, + -0.057020701 -0.191484 0.018567, + -0.0586119 -0.191488 0.0126065, + -0.059920099 -0.191498 0.00035394699, + -0.0596232 -0.191503 -0.0058081602, + -0.058694299 -0.191508 -0.0119071, + -0.057143301 -0.191513 -0.017878201, + -0.048953298 -0.191526 -0.0344023, + -0.047172099 -0.19152801 -0.0369257, + -0.045200799 -0.20852999 -0.0392914, + -0.0451409 -0.19153 -0.039252602, + -0.0431097 -0.191532 -0.041579399, + 0.0105583 -0.208545 -0.0588977, + 0.0135848 -0.19154499 -0.058289401, + 0.016575299 -0.208544 -0.057498999, + 0.0044293702 -0.208546 -0.059670299, + 0.0075038001 -0.19154599 -0.0593764, + -0.0017465299 -0.208546 -0.059808601, + 0.0013432 -0.19154599 -0.059832498, + -0.0079039196 -0.208546 -0.059311099, + -0.0048316298 -0.19154599 -0.0596526, + -0.0139775 -0.208545 -0.058183201, + -0.0109552 -0.19154499 -0.0588389, + -0.019903 -0.208543 -0.056436799, + -0.0169627 -0.191544 -0.057399798, + -0.0256174 -0.208542 -0.054090299, + -0.0227904 -0.191543 -0.055350602, + -0.031060301 -0.20853899 -0.051168699, + -0.028376499 -0.19154 -0.0527131, + -0.033661801 -0.19153801 -0.049515199, + -0.040849999 -0.191533 -0.043685101, + -0.036125999 -0.19153599 -0.047653001, + -0.0310192 -0.191539 -0.051114202, + -0.0255835 -0.191541 -0.054031901, + -0.019876599 -0.191543 -0.056375202, + -0.013959 -0.19154499 -0.058119301, + -0.0078934403 -0.19154599 -0.059245799, + -0.00174422 -0.19154599 -0.0597426, + 0.0044235 -0.19154599 -0.059604399, + 0.0165534 -0.191544 -0.057436101, + 0.0195219 -0.191544 -0.056582801, + 0.0224167 -0.208543 -0.055489101, + 0.022387 -0.191543 -0.055428799, + 0.025251999 -0.191542 -0.054274801, + 0.059909701 -0.208501 -0.00312414, + 0.059253901 -0.208506 -0.0092666801, + 0.0596609 -0.191503 -0.0062174001, + 0.057969999 -0.20851099 -0.0153093, + 0.058689699 -0.191508 -0.012318, + 0.056071501 -0.208515 -0.021187801, + 0.0570965 -0.191513 -0.0182865, + 0.053578701 -0.20852 -0.026839901, + 0.054897901 -0.19151799 -0.0240594, + 0.050517999 -0.208524 -0.032205801, + 0.0521175 -0.191522 -0.029575801, + 0.0469217 -0.208528 -0.037228499, + 0.048784502 -0.191526 -0.034777001, + 0.042828102 -0.20853201 -0.041854899, + 0.0449345 -0.19153 -0.039607901, + 0.038280498 -0.208535 -0.0460358, + 0.040608101 -0.191534 -0.044017401, + 0.0358513 -0.19153699 -0.047958702, + 0.0279832 -0.191541 -0.052832399, + 0.033282898 -0.19153801 -0.049674299, + 0.0382297 -0.191535 -0.045988001, + 0.042771298 -0.191532 -0.041812699, + 0.046859499 -0.19152801 -0.037192501, + 0.053507701 -0.19152001 -0.026817599, + 0.0559972 -0.191515 -0.021173, + 0.057893101 -0.19151101 -0.0153022, + 0.059175301 -0.191506 -0.0092677101, + 0.0599305 -0.208496 0.00305326, + 0.059999701 -0.19149899 -4.9242499e-005, + 0.059850998 -0.191496 0.00303591, + 0.0597024 -0.191494 0.0061210501, + 0.053759102 -0.20847701 0.026811, + 0.0523162 -0.191475 0.0295297, + 0.050734501 -0.208473 0.032197401, + 0.0562139 -0.208482 0.0211422, + 0.0550595 -0.191479 0.023994699, + 0.0572192 -0.191484 0.018207099, + 0.059237301 -0.19149099 0.0091745798, + 0.057995699 -0.191486 0.0152176, + 0.056139302 -0.19148199 0.021100899, + 0.0536878 -0.191477 0.026762201, + 0.0506672 -0.19147301 0.032141399, + -0.044874899 -0.191467 0.0398602, + -0.059581801 -0.191493 0.0065139299, + 0.050450999 -0.191524 -0.032176401, + 0.059830301 -0.19150101 -0.00313332, + 0.020008201 -0.208462 0.045988198, + 0.0147519 -0.20846 0.047940299, + 0.020008201 -0.191462 0.045974702, + 0.0147519 -0.19146 0.047926798, + 0.0250128 -0.19146401 0.043446399, + 0.0250128 -0.208464 0.0434599, + 0.0297029 -0.191466 0.040373601, + 0.0297029 -0.20846599 0.040387101, + 0.0340195 -0.191469 0.036795001, + 0.0340195 -0.208469 0.036808498, + 0.037908301 -0.19147199 0.032755598, + 0.041320302 -0.191476 0.028306199, + 0.037908301 -0.208472 0.032769099, + 0.041320302 -0.20847601 0.0283197, + 0.044212699 -0.19148 0.023502801, + 0.044212699 -0.20848 0.023516299, + 0.043052498 -0.19146501 0.041829102, + 0.0385391 -0.191462 0.046034899, + 0.0093101496 -0.208459 0.0492916, + 0.0093101496 -0.191459 0.049278099, + -0.036642499 -0.208471 0.034185499, + -0.040221099 -0.20847499 0.029868901, + -0.036642499 -0.191471 0.034171999, + -0.040221099 -0.191475 0.0298554, + -0.0326031 -0.191468 0.038060799, + -0.0326031 -0.20846801 0.0380743, + -0.028153701 -0.19146501 0.0414728, + -0.028153701 -0.208465 0.041486301, + -0.0233503 -0.19146299 0.044365201, + -0.0233503 -0.208463 0.044378702, + 0.0037513 -0.191459 0.050011601, + 0.0037513 -0.208459 0.050025102, + -0.00185474 -0.208459 0.0501316, + -0.00185474 -0.191459 0.0501181, + -0.0074374499 -0.208459 0.049609698, + -0.0074374499 -0.191459 0.049596202, + -0.0129266 -0.20846 0.048466101, + -0.0129266 -0.19146 0.048452601, + -0.0182532 -0.208461 0.046715099, + -0.0182532 -0.191461 0.046701599, + -0.035803799 -0.19146 0.048199899, + -0.043293901 -0.208478 0.025178799, + -0.043293901 -0.191478 0.025165301, + -0.045822199 -0.208482 0.0201742, + -0.045822199 -0.19148199 0.020160699, + -0.041320302 -0.191521 -0.0280012, + -0.044212699 -0.191517 -0.0231978, + -0.041320302 -0.20852099 -0.0279877, + -0.044212699 -0.208517 -0.023184299, + -0.037908301 -0.208524 -0.032437101, + -0.037908301 -0.191524 -0.032450601, + -0.0465491 -0.191513 -0.018100699, + -0.0465491 -0.20851301 -0.018087201, + -0.048300099 -0.19150899 -0.0127741, + -0.048300099 -0.208509 -0.0127606, + -0.049443699 -0.191504 -0.0072849598, + -0.049443699 -0.20850401 -0.0072714202, + -0.0477743 -0.191487 0.0149044, + -0.0477743 -0.208487 0.0149179, + -0.049125601 -0.208491 0.0094762202, + -0.049125601 -0.19149099 0.0094626797, + -0.049859099 -0.20849501 0.0039173202, + -0.049859099 -0.191495 0.0039037899, + -0.049965601 -0.2085 -0.0016887099, + -0.049965601 -0.19149999 -0.00170225, + -0.0340195 -0.208528 -0.0364765, + -0.0340195 -0.19152801 -0.036490001, + 0.0129266 -0.19153699 -0.0481476, + 0.0074374499 -0.19153801 -0.049291201, + 0.0129266 -0.208537 -0.0481341, + 0.0074374499 -0.208538 -0.0492777, + 0.0182532 -0.208535 -0.046383101, + 0.0182532 -0.191535 -0.046396598, + 0.00185474 -0.19153801 -0.049813099, + 0.00185474 -0.208538 -0.049799599, + -0.0037513 -0.19153801 -0.049706601, + -0.0037513 -0.208538 -0.0496931, + -0.0093101496 -0.19153699 -0.048973098, + -0.0093101496 -0.208537 -0.048959602, + -0.0297029 -0.19153 -0.0400686, + -0.0297029 -0.20852999 -0.0400551, + -0.0250128 -0.208533 -0.043127902, + -0.0250128 -0.191533 -0.043141399, + -0.020008201 -0.208535 -0.0456562, + -0.020008201 -0.191535 -0.045669701, + -0.0147519 -0.208536 -0.047608301, + -0.0147519 -0.19153599 -0.047621801, + 0.0233503 -0.208534 -0.0440467, + 0.0233503 -0.191534 -0.0440602, + 0.049859099 -0.208501 -0.0035852699, + 0.049965601 -0.208497 0.00202076, + 0.049859099 -0.19150101 -0.0035988099, + 0.049965601 -0.191497 0.00200723, + 0.049125601 -0.191506 -0.0091576604, + 0.049125601 -0.208506 -0.0091441199, + 0.0477743 -0.19151001 -0.0145994, + 0.0477743 -0.20851 -0.0145859, + 0.045822199 -0.191514 -0.0198557, + 0.045822199 -0.208514 -0.0198422, + 0.028153701 -0.191531 -0.041167799, + 0.028153701 -0.20853101 -0.041154299, + 0.0326031 -0.208529 -0.037742302, + 0.0326031 -0.19152901 -0.037755799, + 0.036642499 -0.208525 -0.033853501, + 0.036642499 -0.191525 -0.033867002, + 0.040221099 -0.20852201 -0.029536899, + 0.040221099 -0.191522 -0.0295504, + 0.043293901 -0.208518 -0.0248468, + 0.043293901 -0.19151799 -0.0248603, + 0.049443699 -0.208492 0.0076034698, + 0.049443699 -0.19149201 0.0075899302, + 0.048300099 -0.191488 0.0130791, + 0.048300099 -0.208488 0.0130926, + 0.0465491 -0.20848399 0.018419201, + 0.0465491 -0.191484 0.0184057, + -0.0074938498 -0.191451 0.059602499, + -0.054986499 -0.191517 -0.023658101, + -0.052246802 -0.191522 -0.029185699, + 0.0105443 -0.19154499 -0.058832899 ] + + } + normal + Normal { + vector [ 0.97952574 -0.004520549 0.20126796, + 0.51189011 -0.0053594015 -0.85903418, + -0.64316899 -0.0052897702 -0.765706, + -0.93450958 -0.0043944181 0.35591081, + 0.13172005 -0.0038898115 0.99127936, + 0.42695105 -0.0039598006 0.90426612, + 0.51766694 -0.0039966195 0.85557288, + 0.60289294 -0.0040452196 0.79781187, + 0.68173021 -0.0040957513 0.73159224, + 0.75333673 -0.0041559688 0.65762174, + 0.78619182 0.0051710187 0.61796087, + 0.78618872 0.0051710182 0.61796474, + 0.56103611 0.0053352416 0.82777417, + 0.56099981 0.0053352583 0.82779872, + 0.47294718 0.0053807218 0.88107431, + 0.47293377 0.0053807171 0.88108158, + 0.3798331 0.0054162815 0.92503923, + 0.37986091 0.0054162587 0.92502779, + 0.33171692 -0.0039322791 0.94337076, + 0.28269696 0.0054429094 0.95919389, + 0.28270486 0.0054429071 0.9591915, + 0.23295707 -0.0039046309 0.97247922, + -0.7137928 -0.0041238889 0.7003448, + -0.63800579 -0.0040677493 0.77002084, + -0.55543393 -0.0040218495 0.8315509, + -0.46700287 -0.0039769192 0.88424677, + -0.37361312 -0.0039421315 0.92757636, + -0.27625698 -0.0039107394 0.9610759, + -0.17596301 -0.0038951705 0.98438913, + -0.073832206 -0.0038862205 0.99726313, + 0.029121911 -0.0038855013 0.99956834, + 0.18259694 0.005461318 0.98317266, + 0.18256705 0.0054613315 0.98317826, + 0.080517709 0.0054735104 0.99673814, + 0.080550566 0.0054734973 0.99673551, + -0.0224046 0.0054796198 0.99973398, + -0.022371294 0.0054796184 0.99973476, + -0.22640406 0.0054556816 0.97401822, + -0.2264331 0.0054556727 0.97401148, + -0.32533985 0.0054313871 0.9455815, + -0.32536796 0.0054313797 0.9455719, + -0.42085779 0.0053987871 0.90711057, + -0.42087278 0.0053987773 0.9071036, + -0.51189774 0.0053609475 0.85902959, + -0.51188278 0.0053609577 0.85903859, + -0.67680424 0.0052656117 0.73614424, + -0.67678708 0.0052656205 0.73616004, + -0.78202099 -0.0041815299 0.62323803, + -0.81304801 0.0051388 0.582174, + -0.81307441 0.0051387725 0.58213729, + -0.84195113 -0.0042502303 0.53953707, + -0.868608 0.0050734901 0.49547401, + -0.86863017 0.0050734612 0.49543512, + -0.89297521 -0.0043189409 0.45008513, + -0.84556383 -0.0051031988 -0.5338499, + -0.89597899 -0.0050309999 -0.44406801, + -0.9368844 -0.0049586524 -0.34960419, + -0.96786863 -0.004877008 -0.2514089, + -0.98858953 -0.0047996677 -0.15055792, + -0.99883038 -0.004717262 -0.04812222, + -0.99848402 -0.00463385 0.054847401, + -0.98755312 -0.0045563206 0.15722002, + -0.96615964 -0.0044768788 0.2579059, + -0.91495675 0.0050014388 0.40352091, + -0.91495132 0.0050014518 0.40353316, + -0.9515999 0.0049306997 0.30729997, + -0.95158702 0.00493073 0.30734, + -0.97815663 0.0048437282 0.20781292, + -0.97815001 0.00484375 0.207844, + -0.99998337 0.0046848617 0.0033641811, + -0.99998337 0.0046848617 0.0033629611, + -0.99502754 0.0046027577 -0.099493459, + -0.99503088 0.0046027894 -0.099460684, + -0.97952336 0.0045234016 -0.20128007, + -0.97952914 0.0045234202 -0.20125203, + -0.95364535 0.0044412115 -0.30090013, + -0.95364279 0.0044411989 -0.30090794, + -0.816962 0.0042215101 -0.57667601, + -0.81696284 0.0042215092 -0.57667488, + -0.78619009 -0.0051714503 -0.61796308, + -0.7533437 0.0041539888 -0.65761375, + -0.75332981 0.0041539692 -0.65762985, + -0.71848291 -0.0052336496 -0.69552493, + 0.22641894 -0.0054583987 -0.97401476, + 0.12506604 -0.005467982 -0.99213338, + 0.022387907 -0.0054766019 -0.99973434, + -0.080534093 -0.0054705096 -0.99673688, + -0.1825819 -0.0054640765 -0.9831754, + -0.2827009 -0.0054421984 -0.95919263, + -0.37984681 -0.0054135872 -0.92503357, + -0.47294083 -0.0053820983 -0.88107771, + -0.56101775 -0.0053391778 -0.82778656, + -0.68173122 0.0040957415 -0.73159122, + -0.68173021 0.0040957415 -0.73159224, + -0.60288495 0.0040470297 -0.79781789, + -0.60290086 0.004047039 -0.79780585, + -0.51768619 0.0039926316 -0.85556132, + -0.51764816 0.0039926115 -0.85558432, + -0.42697006 0.0039560003 -0.90425712, + -0.42693207 0.0039559905 -0.90427512, + -0.33172199 0.0039313999 -0.94336897, + -0.33171186 0.003931398 -0.94337255, + -0.23294593 0.003906779 -0.97248179, + -0.23296909 0.0039067916 -0.97247636, + -0.13173701 0.0038867304 -0.9912771, + -0.13170394 0.0038867281 -0.99128151, + -0.029137997 0.0038825795 -0.99956787, + -0.029105792 0.003882579 -0.99956876, + 0.073848195 0.0038891295 -0.99726188, + 0.073816217 0.0038891309 -0.99726427, + 0.27625209 0.0039098114 -0.96107733, + 0.2762621 0.0039098118 -0.96107447, + 0.32535389 -0.0054340381 -0.94557667, + 0.37360692 0.0039410591 -0.92757875, + 0.37361813 0.0039410614 -0.92757434, + 0.42086509 -0.0054003112 -0.90710723, + 0.99433821 -0.0047639911 -0.10615502, + 0.97815323 -0.0048408308 -0.20782904, + 0.95159352 -0.0049269078 -0.30731985, + 0.91495413 -0.0050002607 -0.40352705, + 0.86861885 -0.0050774785 -0.49545488, + 0.81306088 -0.0051428196 -0.58215594, + 0.74890685 -0.0052075288 -0.66265482, + 0.67679596 -0.0052634696 -0.73615193, + 0.5975197 -0.0053171678 -0.80183667, + 0.46698913 0.003974231 -0.88425422, + 0.46701601 0.0039742398 -0.88423997, + 0.55542612 0.0040200409 -0.8315562, + 0.5554418 0.0040200488 -0.83154571, + 0.63801616 0.0040700608 -0.7700122, + 0.63799596 0.0040700496 -0.77002889, + 0.71378481 0.0041218391 -0.70035285, + 0.71380079 0.0041218586 -0.70033675, + 0.78201485 0.004179629 -0.62324589, + 0.78202814 0.0041796407 -0.62322909, + 0.89297473 0.0043188389 -0.45008588, + 0.89297575 0.0043188389 -0.45008388, + 0.93450767 0.0043933485 -0.35591587, + 0.93451178 0.0043933592 -0.35590491, + 0.96616077 0.004477629 -0.25790194, + 0.96615863 0.0044776187 -0.25790992, + 0.98755312 0.0045563704 -0.15722002, + 0.98755324 0.0045563709 -0.15721904, + 0.99998337 -0.0046849716 -0.0033635711, + 0.99882954 0.0047200378 0.048137378, + 0.99883109 0.0047200206 0.048106909, + 0.99502933 -0.004599662 0.099476241, + 0.87192881 -0.0042928089 0.48961389, + 0.91764462 -0.0043626786 0.39737785, + 0.9536441 -0.0044420003 0.30090404, + 0.98858738 0.0048028217 0.15057206, + 0.98859179 0.0048027989 0.15054297, + 0.96786475 0.004879849 0.25142395, + 0.9678725 0.0048798178 0.25139388, + 0.93687922 0.0049613914 0.34961808, + 0.93689001 0.00496135 0.34958899, + 0.89597243 0.0050336225 0.44408122, + 0.89598531 0.005033602 0.44405514, + 0.84555185 0.0051072985 0.53386891, + 0.84557581 0.0051072687 0.53383088, + 0.81696284 -0.0042214389 0.57667488, + -0.74890685 0.0052075186 0.66265482, + -0.99433821 0.0047639911 0.10615502, + 0.84195113 0.0042502605 -0.53953707, + 0.99848402 0.00463385 -0.054847401, + -0.34814897 -0.00074646686 -0.93743891, + -0.45092005 -0.00071073405 -0.89256412, + -0.54802299 -0.00066606101 -0.83646297, + -0.63822806 -0.00061301608 -0.7698471, + -0.7935378 -0.00048455488 -0.60852087, + -0.72040915 -0.00055226113 -0.69354916, + -0.85667658 -0.0004107648 -0.51585376, + 0.71848291 0.0052336496 0.69552493, + 0.64316899 0.0052897702 0.765706, + -0.24100088 -0.00077281165 -0.97052455, + 0.76984751 -0.00050820969 -0.63822764, + 0.69354916 -0.00057364913 -0.72040915, + 0.60852075 -0.00063187978 -0.79353768, + 0.51585412 -0.00068215717 -0.85667616, + -0.13081801 -0.00078944012 -0.99140614, + -0.018993707 -0.0007961393 -0.99981934, + 0.093079343 -0.00079282635 -0.99565846, + 0.20395903 -0.00077954412 -0.97897911, + 0.31228685 -0.00075645867 -0.94998753, + 0.41668814 -0.00072386023 -0.90904927, + -0.5975197 0.0053171678 0.80183667, + 0.83646315 -0.00043638112 -0.5480231, + 0.8925643 -0.00035906013 -0.45092013, + 0.85667658 0.0004107648 0.51585376, + 0.7935378 0.00048455488 0.60852087, + 0.90904957 0.00033180186 0.41668779, + 0.94998777 0.00024866895 0.31228694, + 0.97897947 0.00016240907 0.20395911, + 0.93743914 -0.00027722502 -0.34814903, + 0.97052437 -0.00019190708 -0.2410031, + 0.9914065 -0.00010416695 -0.13081694, + 0.99981964 -1.5124295e-005 -0.018993692, + 0.99565876 7.4117284e-005 0.093079075, + 0.72040915 0.00055226113 0.69354916, + -0.20395903 0.00077954412 0.97897911, + -0.31228685 0.00075645867 0.94998753, + -0.093079343 0.00079282635 0.99565846, + 0.018993707 0.0007961393 0.99981934, + 0.13081801 0.00078944012 0.99140614, + 0.63822806 0.00061301608 0.7698471, + 0.54802299 0.00066606101 0.83646297, + 0.45092005 0.00071073405 0.89256412, + 0.34814897 0.00074646686 0.93743891, + 0.24100088 0.00077281165 0.97052455, + -0.41668814 0.00072386023 0.90904927, + -0.99981964 1.5124295e-005 0.018993692, + -0.99140638 0.00010416804 0.13081804, + -0.97052491 0.00019190497 0.24100097, + -0.93743914 0.00027722502 0.34814903, + -0.51585412 0.00068215717 0.85667616, + -0.60852075 0.00063187978 0.79353768, + -0.69354916 0.00057364913 0.72040915, + -0.76984751 0.00050820969 0.63822764, + -0.83646315 0.00043638112 0.5480231, + -0.8925643 0.00035906013 0.45092013, + -0.99565876 -7.4117284e-005 -0.093079075, + -0.97897941 -0.00016240889 -0.20395888, + -0.94998777 -0.00024866895 -0.31228694, + -0.90904957 -0.00033180186 -0.41668779, + -0.12506703 0.0054678712 0.99213326, + -0.91764462 0.0043627787 -0.39737785, + -0.87192881 0.0042928993 -0.48961389, + 0.17596301 0.0038950504 -0.98438913, + 0 0.99999964 -0.00079628272, + 0 -0.99999964 0.00079628272 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 9, 10, 11, -1, + 12, 13, 14, -1, 15, 16, 17, -1, + 15, 18, 19, -1, 18, 20, 21, -1, + 20, 22, 23, -1, 24, 25, 22, -1, + 26, 24, 27, -1, 26, 25, 24, -1, + 28, 18, 21, -1, 28, 19, 18, -1, + 29, 15, 19, -1, 29, 16, 15, -1, + 30, 17, 16, -1, 30, 31, 17, -1, + 17, 31, 32, -1, 33, 32, 31, -1, + 33, 34, 32, -1, 32, 34, 12, -1, + 35, 36, 37, -1, 38, 39, 36, -1, + 40, 41, 38, -1, 40, 42, 43, -1, + 44, 45, 42, -1, 44, 46, 47, -1, + 48, 49, 46, -1, 50, 51, 48, -1, + 50, 14, 52, -1, 53, 12, 34, -1, + 53, 13, 12, -1, 54, 14, 13, -1, + 54, 52, 14, -1, 55, 50, 52, -1, + 55, 51, 50, -1, 56, 46, 49, -1, + 56, 47, 46, -1, 57, 44, 47, -1, + 57, 45, 44, -1, 58, 42, 45, -1, + 58, 43, 42, -1, 59, 40, 43, -1, + 59, 41, 40, -1, 60, 36, 39, -1, + 60, 37, 36, -1, 35, 61, 62, -1, + 63, 62, 61, -1, 63, 64, 62, -1, + 62, 64, 65, -1, 66, 65, 64, -1, + 66, 67, 65, -1, 9, 65, 67, -1, + 68, 69, 70, -1, 71, 72, 68, -1, + 73, 74, 71, -1, 73, 75, 76, -1, + 77, 78, 75, -1, 77, 79, 80, -1, + 79, 81, 82, -1, 81, 83, 84, -1, + 11, 85, 83, -1, 86, 9, 67, -1, + 86, 10, 9, -1, 87, 11, 10, -1, + 87, 85, 11, -1, 88, 83, 85, -1, + 88, 84, 83, -1, 89, 79, 82, -1, + 89, 80, 79, -1, 90, 77, 80, -1, + 90, 78, 77, -1, 91, 75, 78, -1, + 91, 76, 75, -1, 92, 73, 76, -1, + 92, 74, 73, -1, 93, 70, 69, -1, + 93, 94, 70, -1, 95, 70, 94, -1, + 96, 95, 94, -1, 96, 97, 95, -1, + 7, 95, 97, -1, 98, 99, 100, -1, + 101, 102, 98, -1, 103, 104, 101, -1, + 105, 106, 103, -1, 107, 108, 105, -1, + 109, 110, 107, -1, 111, 112, 109, -1, + 111, 113, 114, -1, 113, 6, 115, -1, + 116, 7, 97, -1, 116, 8, 7, -1, + 117, 6, 8, -1, 117, 115, 6, -1, + 118, 113, 115, -1, 118, 114, 113, -1, + 119, 111, 114, -1, 119, 112, 111, -1, + 120, 109, 112, -1, 120, 110, 109, -1, + 121, 107, 110, -1, 121, 108, 107, -1, + 122, 105, 108, -1, 122, 106, 105, -1, + 123, 103, 106, -1, 123, 104, 103, -1, + 124, 101, 104, -1, 124, 102, 101, -1, + 125, 100, 99, -1, 125, 126, 100, -1, + 127, 100, 126, -1, 128, 127, 126, -1, + 128, 129, 127, -1, 127, 129, 3, -1, + 130, 131, 132, -1, 133, 134, 131, -1, + 135, 136, 133, -1, 137, 138, 135, -1, + 139, 140, 137, -1, 139, 141, 142, -1, + 141, 143, 144, -1, 145, 146, 143, -1, + 5, 147, 145, -1, 148, 3, 129, -1, + 148, 4, 3, -1, 149, 5, 4, -1, + 149, 147, 5, -1, 150, 145, 147, -1, + 150, 146, 145, -1, 151, 143, 146, -1, + 151, 144, 143, -1, 152, 141, 144, -1, + 152, 142, 141, -1, 153, 137, 140, -1, + 153, 138, 137, -1, 154, 135, 138, -1, + 154, 136, 135, -1, 155, 133, 136, -1, + 155, 134, 133, -1, 156, 131, 134, -1, + 156, 132, 131, -1, 157, 130, 158, -1, + 159, 157, 158, -1, 159, 160, 157, -1, + 157, 160, 0, -1, 161, 162, 163, -1, + 161, 164, 165, -1, 164, 2, 166, -1, + 167, 0, 160, -1, 167, 1, 0, -1, + 168, 2, 1, -1, 168, 166, 2, -1, + 169, 164, 166, -1, 169, 165, 164, -1, + 170, 161, 165, -1, 170, 162, 161, -1, + 171, 163, 162, -1, 171, 27, 163, -1, + 163, 27, 24, -1, 37, 172, 35, -1, + 35, 172, 61, -1, 84, 173, 81, -1, + 81, 173, 82, -1, 142, 174, 139, -1, + 139, 174, 140, -1, 132, 175, 130, -1, + 130, 175, 158, -1, 176, 177, 178, -1, + 178, 177, 179, -1, 178, 180, 176, -1, + 176, 180, 181, -1, 180, 182, 181, -1, + 181, 182, 183, -1, 182, 184, 183, -1, + 183, 184, 185, -1, 186, 187, 188, -1, + 188, 187, 189, -1, 188, 185, 186, -1, + 186, 185, 184, -1, 187, 190, 189, -1, + 189, 190, 191, -1, 25, 192, 22, -1, + 22, 192, 23, -1, 23, 193, 20, -1, + 20, 193, 21, -1, 177, 194, 179, -1, + 179, 194, 195, -1, 196, 197, 198, -1, + 198, 197, 199, -1, 198, 200, 196, -1, + 196, 200, 201, -1, 200, 202, 201, -1, + 201, 202, 203, -1, 202, 204, 203, -1, + 203, 204, 205, -1, 206, 195, 207, -1, + 207, 195, 194, -1, 207, 208, 206, -1, + 206, 208, 209, -1, 208, 210, 209, -1, + 209, 210, 211, -1, 210, 212, 211, -1, + 211, 212, 213, -1, 212, 214, 213, -1, + 213, 214, 215, -1, 214, 205, 215, -1, + 215, 205, 204, -1, 41, 216, 38, -1, + 38, 216, 39, -1, 197, 217, 199, -1, + 199, 217, 218, -1, 217, 219, 218, -1, + 218, 219, 220, -1, 221, 222, 223, -1, + 223, 222, 224, -1, 223, 225, 221, -1, + 221, 225, 226, -1, 222, 227, 224, -1, + 224, 227, 228, -1, 227, 229, 228, -1, + 228, 229, 230, -1, 229, 231, 230, -1, + 230, 231, 232, -1, 233, 220, 234, -1, + 234, 220, 219, -1, 234, 235, 233, -1, + 233, 235, 236, -1, 235, 237, 236, -1, + 236, 237, 238, -1, 237, 239, 238, -1, + 238, 239, 240, -1, 239, 232, 240, -1, + 240, 232, 231, -1, 225, 241, 226, -1, + 226, 241, 242, -1, 243, 244, 245, -1, + 245, 244, 246, -1, 245, 247, 243, -1, + 243, 247, 248, -1, 244, 249, 246, -1, + 246, 249, 250, -1, 249, 251, 250, -1, + 250, 251, 252, -1, 251, 253, 252, -1, + 252, 253, 254, -1, 255, 242, 256, -1, + 256, 242, 241, -1, 256, 257, 255, -1, + 255, 257, 258, -1, 257, 259, 258, -1, + 258, 259, 260, -1, 259, 261, 260, -1, + 260, 261, 262, -1, 261, 254, 262, -1, + 262, 254, 253, -1, 247, 263, 248, -1, + 248, 263, 264, -1, 265, 266, 267, -1, + 267, 266, 268, -1, 267, 269, 265, -1, + 265, 269, 270, -1, 269, 271, 270, -1, + 270, 271, 272, -1, 271, 273, 272, -1, + 272, 273, 274, -1, 275, 264, 276, -1, + 276, 264, 263, -1, 276, 277, 275, -1, + 275, 277, 278, -1, 277, 279, 278, -1, + 278, 279, 280, -1, 279, 281, 280, -1, + 280, 281, 282, -1, 281, 283, 282, -1, + 282, 283, 284, -1, 283, 274, 284, -1, + 284, 274, 273, -1, 266, 285, 268, -1, + 268, 285, 286, -1, 287, 286, 288, -1, + 288, 286, 285, -1, 288, 289, 287, -1, + 287, 289, 290, -1, 289, 191, 290, -1, + 290, 191, 190, -1, 51, 291, 48, -1, + 48, 291, 49, -1, 74, 292, 71, -1, + 71, 292, 72, -1, 72, 293, 68, -1, + 68, 293, 69, -1, 102, 294, 98, -1, + 98, 294, 99, -1, 184, 182, 193, -1, + 193, 182, 21, -1, 21, 182, 28, -1, + 28, 182, 180, -1, 28, 180, 19, -1, + 19, 180, 29, -1, 180, 178, 29, -1, + 29, 178, 16, -1, 16, 178, 30, -1, + 30, 178, 31, -1, 178, 179, 31, -1, + 31, 179, 33, -1, 33, 179, 34, -1, + 34, 179, 195, -1, 34, 195, 53, -1, + 53, 195, 13, -1, 195, 206, 13, -1, + 13, 206, 54, -1, 54, 206, 52, -1, + 52, 206, 209, -1, 52, 209, 55, -1, + 55, 209, 51, -1, 209, 211, 51, -1, + 51, 211, 291, -1, 291, 211, 49, -1, + 49, 211, 56, -1, 211, 213, 56, -1, + 56, 213, 47, -1, 47, 213, 57, -1, + 57, 213, 215, -1, 57, 215, 45, -1, + 45, 215, 58, -1, 215, 204, 58, -1, + 58, 204, 43, -1, 43, 204, 59, -1, + 59, 204, 202, -1, 59, 202, 41, -1, + 41, 202, 216, -1, 202, 200, 216, -1, + 216, 200, 39, -1, 39, 200, 60, -1, + 60, 200, 198, -1, 60, 198, 37, -1, + 37, 198, 172, -1, 172, 198, 61, -1, + 61, 198, 199, -1, 61, 199, 63, -1, + 63, 199, 64, -1, 199, 218, 64, -1, + 64, 218, 66, -1, 66, 218, 67, -1, + 67, 218, 220, -1, 67, 220, 86, -1, + 86, 220, 10, -1, 220, 233, 10, -1, + 10, 233, 87, -1, 87, 233, 85, -1, + 85, 233, 236, -1, 85, 236, 88, -1, + 88, 236, 84, -1, 84, 236, 173, -1, + 173, 236, 238, -1, 173, 238, 82, -1, + 82, 238, 89, -1, 238, 240, 89, -1, + 89, 240, 80, -1, 80, 240, 90, -1, + 90, 240, 231, -1, 90, 231, 78, -1, + 78, 231, 91, -1, 231, 229, 91, -1, + 91, 229, 76, -1, 76, 229, 92, -1, + 92, 229, 227, -1, 92, 227, 74, -1, + 74, 227, 292, -1, 227, 222, 292, -1, + 292, 222, 72, -1, 72, 222, 293, -1, + 293, 222, 221, -1, 293, 221, 69, -1, + 69, 221, 93, -1, 93, 221, 94, -1, + 94, 221, 226, -1, 94, 226, 96, -1, + 96, 226, 97, -1, 226, 242, 97, -1, + 97, 242, 116, -1, 116, 242, 8, -1, + 8, 242, 255, -1, 8, 255, 117, -1, + 117, 255, 115, -1, 255, 258, 115, -1, + 115, 258, 118, -1, 118, 258, 114, -1, + 114, 258, 119, -1, 258, 260, 119, -1, + 119, 260, 112, -1, 112, 260, 120, -1, + 120, 260, 262, -1, 120, 262, 110, -1, + 110, 262, 121, -1, 262, 253, 121, -1, + 121, 253, 108, -1, 108, 253, 122, -1, + 122, 253, 251, -1, 122, 251, 106, -1, + 106, 251, 123, -1, 251, 249, 123, -1, + 123, 249, 104, -1, 104, 249, 124, -1, + 124, 249, 244, -1, 124, 244, 102, -1, + 102, 244, 294, -1, 244, 243, 294, -1, + 294, 243, 99, -1, 99, 243, 125, -1, + 125, 243, 126, -1, 243, 248, 126, -1, + 126, 248, 128, -1, 128, 248, 129, -1, + 129, 248, 264, -1, 129, 264, 148, -1, + 148, 264, 4, -1, 264, 275, 4, -1, + 4, 275, 149, -1, 149, 275, 147, -1, + 147, 275, 278, -1, 147, 278, 150, -1, + 150, 278, 146, -1, 146, 278, 151, -1, + 151, 278, 280, -1, 151, 280, 144, -1, + 144, 280, 152, -1, 280, 282, 152, -1, + 152, 282, 142, -1, 142, 282, 174, -1, + 174, 282, 284, -1, 174, 284, 140, -1, + 140, 284, 153, -1, 284, 273, 153, -1, + 153, 273, 138, -1, 138, 273, 154, -1, + 154, 273, 271, -1, 154, 271, 136, -1, + 136, 271, 155, -1, 271, 269, 155, -1, + 155, 269, 134, -1, 134, 269, 156, -1, + 156, 269, 267, -1, 156, 267, 132, -1, + 132, 267, 175, -1, 175, 267, 158, -1, + 158, 267, 268, -1, 158, 268, 159, -1, + 159, 268, 160, -1, 268, 286, 160, -1, + 160, 286, 167, -1, 167, 286, 1, -1, + 1, 286, 287, -1, 1, 287, 168, -1, + 168, 287, 166, -1, 287, 290, 166, -1, + 166, 290, 169, -1, 169, 290, 165, -1, + 165, 290, 170, -1, 290, 190, 170, -1, + 170, 190, 162, -1, 162, 190, 171, -1, + 171, 190, 187, -1, 171, 187, 27, -1, + 27, 187, 26, -1, 187, 186, 26, -1, + 26, 186, 25, -1, 25, 186, 192, -1, + 192, 186, 184, -1, 192, 184, 23, -1, + 23, 184, 193, -1, 15, 17, 176, -1, + 176, 17, 177, -1, 17, 32, 177, -1, + 177, 32, 194, -1, 32, 12, 194, -1, + 194, 12, 14, -1, 194, 14, 207, -1, + 207, 14, 50, -1, 207, 50, 208, -1, + 208, 50, 48, -1, 208, 48, 210, -1, + 210, 48, 46, -1, 210, 46, 212, -1, + 212, 46, 44, -1, 212, 44, 214, -1, + 214, 44, 42, -1, 214, 42, 205, -1, + 205, 42, 40, -1, 205, 40, 203, -1, + 203, 40, 38, -1, 203, 38, 201, -1, + 201, 38, 36, -1, 201, 36, 196, -1, + 196, 36, 35, -1, 196, 35, 197, -1, + 197, 35, 62, -1, 197, 62, 217, -1, + 217, 62, 65, -1, 217, 65, 219, -1, + 219, 65, 9, -1, 219, 9, 11, -1, + 219, 11, 234, -1, 234, 11, 83, -1, + 234, 83, 235, -1, 235, 83, 81, -1, + 235, 81, 237, -1, 237, 81, 79, -1, + 237, 79, 239, -1, 239, 79, 77, -1, + 239, 77, 232, -1, 232, 77, 75, -1, + 232, 75, 230, -1, 230, 75, 73, -1, + 230, 73, 228, -1, 228, 73, 71, -1, + 228, 71, 224, -1, 224, 71, 68, -1, + 224, 68, 223, -1, 223, 68, 70, -1, + 223, 70, 225, -1, 225, 70, 95, -1, + 225, 95, 241, -1, 241, 95, 7, -1, + 241, 7, 6, -1, 241, 6, 256, -1, + 256, 6, 113, -1, 256, 113, 257, -1, + 257, 113, 111, -1, 257, 111, 259, -1, + 259, 111, 109, -1, 259, 109, 261, -1, + 261, 109, 107, -1, 261, 107, 254, -1, + 254, 107, 105, -1, 254, 105, 252, -1, + 252, 105, 103, -1, 252, 103, 250, -1, + 250, 103, 101, -1, 250, 101, 246, -1, + 246, 101, 98, -1, 246, 98, 245, -1, + 245, 98, 100, -1, 245, 100, 247, -1, + 247, 100, 127, -1, 247, 127, 263, -1, + 263, 127, 3, -1, 263, 3, 5, -1, + 263, 5, 276, -1, 276, 5, 145, -1, + 276, 145, 277, -1, 277, 145, 143, -1, + 277, 143, 279, -1, 279, 143, 141, -1, + 279, 141, 281, -1, 281, 141, 139, -1, + 281, 139, 283, -1, 283, 139, 137, -1, + 283, 137, 274, -1, 274, 137, 135, -1, + 274, 135, 272, -1, 272, 135, 133, -1, + 272, 133, 270, -1, 270, 133, 131, -1, + 270, 131, 265, -1, 265, 131, 130, -1, + 265, 130, 266, -1, 266, 130, 157, -1, + 266, 157, 285, -1, 285, 157, 0, -1, + 285, 0, 2, -1, 285, 2, 288, -1, + 288, 2, 164, -1, 288, 164, 289, -1, + 289, 164, 161, -1, 289, 161, 191, -1, + 191, 161, 163, -1, 191, 163, 189, -1, + 189, 163, 24, -1, 189, 24, 188, -1, + 188, 24, 22, -1, 188, 22, 185, -1, + 185, 22, 20, -1, 185, 20, 183, -1, + 183, 20, 18, -1, 183, 18, 181, -1, + 181, 18, 15, -1, 181, 15, 176, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 161, 161, 161, -1, 162, 162, 162, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 163, 163, 163, -1, 164, 164, 164, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 165, 165, 165, -1, 166, 166, 166, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 167, 167, 167, -1, 168, 168, 168, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 169, 169, 169, -1, 170, 170, 170, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 171, 171, 171, -1, 172, 172, 172, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 173, 173, 173, -1, 174, 174, 174, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 177, 177, 177, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 179, 179, 179, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 181, 181, 181, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 187, 187, 187, -1, 188, 188, 188, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 190, 190, 190, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 191, 191, 191, -1, 192, 192, 192, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 194, 194, 194, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 195, 195, 195, -1, 196, 196, 196, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 197, 197, 197, -1, 198, 198, 198, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 200, 200, 200, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 201, 201, 201, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 203, 203, 203, -1, 204, 204, 204, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 205, 205, 205, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 207, 207, 207, -1, 208, 208, 208, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 209, 209, 209, -1, 210, 210, 210, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 211, 211, 211, -1, 212, 212, 212, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 213, 213, 213, -1, 214, 214, 214, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 215, 215, 215, -1, 216, 216, 216, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 217, 217, 217, -1, 218, 218, 218, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 219, 219, 219, -1, 220, 220, 220, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 221, 221, 221, -1, 222, 222, 222, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 224, 224, 224, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 225, 225, 225, -1, 226, 226, 226, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1, + 229, 229, 229, -1, 229, 229, 229, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + + } + + }, + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.0078125 0.1875 0.65625 + ambientIntensity 0.46584472 + specularColor 0 0.1 0.5 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.059011199 -0.17149 0.0108905, + -0.058998398 -0.164345 0.0112011, + -0.059330199 -0.171491 0.0090767602, + -0.059445001 -0.16446 0.0084259603, + -0.050208401 -0.171472 0.032962002, + -0.0497806 -0.19147199 0.033647101, + -0.049818899 -0.171472 0.033574201, + -0.0583959 -0.19150899 -0.0136288, + -0.057670102 -0.17151099 -0.0163697, + -0.056669399 -0.191514 -0.01956, + -0.0081428103 -0.119973 -0.0370203, + -0.0109179 -0.11973 -0.036569301, + -0.0081428103 -0.11849 -0.035389699, + -0.0109179 -0.121281 -0.038160399, + -0.0137106 -0.120975 -0.037569098, + -0.0137106 -0.122596 -0.0391175, + -0.0165099 -0.122232 -0.038382798, + -0.0165099 -0.123923 -0.0398858, + -0.019305199 -0.123507 -0.0390056, + -0.019305199 -0.12526999 -0.040460698, + -0.0220857 -0.124804 -0.039432298, + -0.0220857 -0.12663899 -0.040837299, + -0.0248404 -0.126131 -0.039659299, + -0.0248404 -0.128038 -0.041011501, + -0.027557701 -0.12749401 -0.0396851, + -0.027557701 -0.129473 -0.040982299, + -0.0302257 -0.12890001 -0.039509699, + -0.0302257 -0.130952 -0.040749401, + -0.0328326 -0.130357 -0.039132599, + -0.0328326 -0.13248201 -0.040312499, + -0.035366699 -0.13187 -0.0385544, + -0.035366699 -0.134067 -0.0396723, + -0.0378174 -0.133449 -0.037778899, + -0.0378174 -0.135717 -0.038832501, + -0.040174201 -0.13509899 -0.0368108, + -0.040174201 -0.13744 -0.037799198, + -0.0424264 -0.13682701 -0.035656098, + -0.0424264 -0.139239 -0.036578201, + -0.044564299 -0.13864 -0.0343211, + -0.044564299 -0.141119 -0.035176098, + -0.0465803 -0.140542 -0.032814901, + -0.0465803 -0.143089 -0.0336021, + -0.048467699 -0.142538 -0.031147201, + -0.048467699 -0.145151 -0.031865399, + -0.050219599 -0.144633 -0.029327599, + -0.050219599 -0.147311 -0.029975999, + -0.051830001 -0.14683101 -0.0273658, + -0.051830001 -0.149572 -0.027943499, + -0.0532961 -0.14913499 -0.025272699, + -0.0532961 -0.15193599 -0.025779201, + -0.0546159 -0.148689 -0.0225525, + -0.0546159 -0.154406 -0.023495801, + -0.055787299 -0.15406699 -0.020739101, + -0.055787299 -0.15990201 -0.0214056, + -0.056809202 -0.15967201 -0.018624101, + -0.0576833 -0.15944199 -0.0158277, + -0.056809202 -0.153724 -0.0179567, + -0.055787299 -0.148237 -0.019795001, + -0.0546159 -0.142998 -0.021323999, + -0.055787299 -0.142435 -0.0185655, + -0.056809202 -0.147782 -0.0170116, + -0.0576833 -0.15338001 -0.0151595, + -0.058412101 -0.15921 -0.0130273, + -0.058986001 -0.171507 -0.0107792, + -0.059372 -0.171505 -0.0085220505, + -0.058998398 -0.16525801 -0.010636, + -0.0588759 -0.171508 -0.0114234, + -0.058412101 -0.16537499 -0.013429, + -0.058383498 -0.171509 -0.0136419, + -0.0582381 -0.17151 -0.0142969, + -0.0576833 -0.165492 -0.0162287, + -0.056809202 -0.165609 -0.0190244, + -0.057460099 -0.17151199 -0.0171357, + -0.0557741 -0.171516 -0.021943999, + -0.056543902 -0.171514 -0.0199329, + -0.055787299 -0.16572601 -0.021805299, + -0.056661699 -0.171514 -0.0195734, + -0.0546159 -0.16013101 -0.024161501, + -0.0532961 -0.154741 -0.026215, + -0.051830001 -0.152319 -0.028449601, + -0.050219599 -0.14999899 -0.0305533, + -0.048467699 -0.14777701 -0.032513302, + -0.0465803 -0.14565299 -0.034319699, + -0.044564299 -0.143619 -0.035962701, + -0.0424264 -0.141671 -0.0374327, + -0.040174201 -0.139806 -0.038720801, + -0.0378174 -0.138016 -0.039820202, + -0.035366699 -0.136297 -0.040725201, + -0.0328326 -0.13464101 -0.041429698, + -0.0302257 -0.13304301 -0.041928701, + -0.027557701 -0.131494 -0.0422213, + -0.0248404 -0.129989 -0.042307999, + -0.0220857 -0.128521 -0.042188801, + -0.019305199 -0.127083 -0.041864902, + -0.0165099 -0.12566701 -0.041340299, + -0.0137106 -0.124272 -0.040619899, + -0.0109179 -0.122889 -0.039708398, + -0.0081428103 -0.121514 -0.038610999, + -0.0053973799 -0.120143 -0.037335299, + -0.0053973799 -0.117249 -0.034038201, + -0.00268824 -0.117358 -0.034223098, + -0.00268824 -0.11471 -0.030792199, + 0 -0.114749 -0.0308518, + 0 -0.112351 -0.027314801, + 0.00268824 -0.11471 -0.0307917, + 0.00268824 -0.117358 -0.034222901, + 0.0053973799 -0.117249 -0.034037799, + 0.0053973799 -0.118667 -0.035704799, + 0.051830001 -0.160577 -0.029585101, + 0.050219599 -0.15809099 -0.0318923, + 0.051830001 -0.155066 -0.028914699, + 0.0137073 -0.171545 -0.0582611, + 0.0122706 -0.171545 -0.058583502, + 0.0137106 -0.169404 -0.058247499, + 0.058412101 -0.15921199 -0.0130678, + 0.058412101 -0.165379 -0.0134622, + 0.0576833 -0.15944301 -0.015867701, + 0.0576833 -0.153375 -0.0151927, + 0.056809202 -0.15371899 -0.0179893, + 0.056809202 -0.14777 -0.017035, + 0.055787299 -0.14822599 -0.0198179, + 0.055787299 -0.142418 -0.018585401, + 0.0546159 -0.14298201 -0.021343499, + 0.0546159 -0.137339 -0.019835699, + 0.0546159 -0.14867701 -0.022575, + 0.055787299 -0.154062 -0.020771099, + 0.056809202 -0.159674 -0.0186635, + 0.0576833 -0.16549601 -0.016261499, + 0.0581921 -0.17151 -0.0144812, + 0.0583972 -0.171509 -0.0135706, + 0.0583813 -0.171509 -0.0136414, + 0.0583959 -0.19150899 -0.0136288, + 0.058839001 -0.171508 -0.0116097, + 0.058998398 -0.165263 -0.0106695, + 0.059445001 -0.16514701 -0.0078944303, + 0.059344199 -0.171505 -0.0087099401, + 0.058998398 -0.15898199 -0.0102746, + 0.058412101 -0.15302899 -0.0123918, + 0.0576833 -0.147312 -0.0142372, + 0.056809202 -0.14184999 -0.015801501, + 0.055787299 -0.136663 -0.0170766, + 0.0546159 -0.131771 -0.018054999, + 0.0532961 -0.12985601 -0.019787, + 0.0532961 -0.12719101 -0.0187291, + 0.051830001 -0.128066 -0.021404101, + 0.051830001 -0.125488 -0.020281, + 0.050219599 -0.126398 -0.0228955, + 0.050219599 -0.123907 -0.0217088, + 0.048467699 -0.124845 -0.0242514, + 0.048467699 -0.122444 -0.023003601, + 0.0465803 -0.123403 -0.0254634, + 0.0465803 -0.121093 -0.0241569, + 0.044564299 -0.122066 -0.026523599, + 0.044564299 -0.119847 -0.0251607, + 0.0424264 -0.120826 -0.027423801, + 0.0424264 -0.118702 -0.026007099, + 0.040174201 -0.119677 -0.0281568, + 0.040174201 -0.117647 -0.026688799, + 0.0378174 -0.11861 -0.028717799, + 0.0378174 -0.116675 -0.027201099, + 0.035366699 -0.11762 -0.029102501, + 0.035366699 -0.115778 -0.0275397, + 0.0328326 -0.116694 -0.029306799, + 0.0328326 -0.114946 -0.0277026, + 0.0302257 -0.115824 -0.029329, + 0.0302257 -0.114165 -0.0276947, + 0.027557701 -0.114998 -0.029176099, + 0.027557701 -0.113424 -0.027515, + 0.0248404 -0.114205 -0.0288474, + 0.0248404 -0.112718 -0.0271594, + 0.0220857 -0.113441 -0.0283392, + 0.0220857 -0.112039 -0.0266247, + 0.019305199 -0.112696 -0.0276499, + 0.019305199 -0.11138 -0.0259101, + 0.0165099 -0.111966 -0.0267823, + 0.0165099 -0.110733 -0.025018901, + 0.0137106 -0.108962 -0.022126, + 0.0137106 -0.111243 -0.025741, + 0.0109179 -0.109406 -0.0226958, + 0.0137106 -0.112454 -0.0275096, + 0.0165099 -0.113258 -0.0285268, + 0.019305199 -0.114071 -0.029368401, + 0.0220857 -0.114899 -0.030029999, + 0.0248404 -0.115748 -0.0305096, + 0.027557701 -0.116622 -0.0308096, + 0.0302257 -0.117535 -0.030931, + 0.0328326 -0.118495 -0.0308675, + 0.035366699 -0.119513 -0.0306172, + 0.0378174 -0.120596 -0.030184001, + 0.040174201 -0.121755 -0.029572001, + 0.0424264 -0.122995 -0.0287853, + 0.044564299 -0.124326 -0.0278288, + 0.0465803 -0.125752 -0.0267101, + 0.048467699 -0.12728199 -0.0254371, + 0.050219599 -0.128922 -0.0240178, + 0.051830001 -0.130676 -0.022461301, + 0.0532961 -0.132549 -0.020778, + 0.0532961 -0.135267 -0.0217016, + 0.051830001 -0.133314 -0.0234515, + 0.050219599 -0.131477 -0.0250741, + 0.048467699 -0.12975401 -0.0265585, + 0.0465803 -0.12813801 -0.027894801, + 0.044564299 -0.126625 -0.029074499, + 0.0424264 -0.12520701 -0.0300893, + 0.040174201 -0.123878 -0.0309321, + 0.0378174 -0.122631 -0.031597599, + 0.035366699 -0.121458 -0.032081801, + 0.0328326 -0.12035 -0.032380302, + 0.0302257 -0.119301 -0.032489698, + 0.027557701 -0.118301 -0.032409701, + 0.0248404 -0.117342 -0.032142598, + 0.0220857 -0.116413 -0.031693399, + 0.019305199 -0.115504 -0.031061601, + 0.0165099 -0.114611 -0.0302487, + 0.0137106 -0.113727 -0.0292581, + 0.0109179 -0.114104 -0.029846299, + 0.0137106 -0.11506 -0.0309829, + 0.0165099 -0.116022 -0.0319441, + 0.019305199 -0.116993 -0.0327259, + 0.0220857 -0.11798 -0.033325698, + 0.0248404 -0.11899 -0.0337409, + 0.027557701 -0.120034 -0.033966601, + 0.0302257 -0.121121 -0.0340009, + 0.0328326 -0.122257 -0.033843301, + 0.035366699 -0.123451 -0.033493899, + 0.0378174 -0.124711 -0.032956399, + 0.040174201 -0.12604401 -0.0322349, + 0.0424264 -0.12745801 -0.031333901, + 0.044564299 -0.128961 -0.030258199, + 0.0465803 -0.130558 -0.0290154, + 0.048467699 -0.132256 -0.0276141, + 0.050219599 -0.13406099 -0.0260638, + 0.051830001 -0.135977 -0.0243745, + 0.0532961 -0.138006 -0.022557501, + 0.0532961 -0.143539 -0.0240642, + 0.051830001 -0.14136501 -0.026017001, + 0.0532961 -0.149124 -0.0252946, + 0.051830001 -0.146817 -0.0273849, + 0.0546159 -0.154402 -0.023527199, + 0.055787299 -0.159905 -0.0214443, + 0.056809202 -0.16561399 -0.0190567, + 0.0574052 -0.17151199 -0.0173175, + 0.057668298 -0.17151099 -0.016369199, + 0.056669399 -0.191514 -0.01956, + 0.051438902 -0.191523 -0.0307351, + 0.0528998 -0.17152099 -0.028176101, + 0.054342099 -0.19151901 -0.0252824, + 0.051818501 -0.17152201 -0.0300825, + 0.0514476 -0.171523 -0.0307364, + 0.051830001 -0.16607 -0.0299765, + 0.048459999 -0.171527 -0.035224698, + 0.048175599 -0.171527 -0.035628099, + 0.048467699 -0.16891199 -0.035208099, + 0.0479904 -0.19152699 -0.035860401, + 0.049871601 -0.171525 -0.0332224, + 0.050219599 -0.166179 -0.032583099, + -0.0484627 -0.171527 -0.035226699, + -0.0479904 -0.19152699 -0.035860401, + -0.049977001 -0.171525 -0.033064399, + -0.048288502 -0.171527 -0.035475399, + -0.048467699 -0.168909 -0.035191, + -0.050219599 -0.16617499 -0.0325545, + 0.048467699 -0.163647 -0.034956399, + 0.048467699 -0.16628499 -0.0351169, + 0.0465803 -0.1638 -0.037406798, + 0.0465803 -0.161204 -0.037177101, + 0.044564299 -0.16139901 -0.039533801, + 0.044564299 -0.158847 -0.039235201, + 0.0424264 -0.159079 -0.041487601, + 0.0424264 -0.156571 -0.0411199, + 0.040174201 -0.156835 -0.043258399, + 0.040174201 -0.15437201 -0.0428215, + 0.0378174 -0.154661 -0.0448386, + 0.0378174 -0.152243 -0.044332098, + 0.035366699 -0.15255199 -0.046220802, + 0.035366699 -0.150181 -0.045644701, + 0.0328326 -0.15050299 -0.047398102, + 0.0328326 -0.148178 -0.046752602, + 0.0302257 -0.148508 -0.048364699, + 0.0302257 -0.146228 -0.0476503, + 0.027557701 -0.146559 -0.049118102, + 0.027557701 -0.144327 -0.048335399, + 0.0248404 -0.144651 -0.049656902, + 0.0248404 -0.14246701 -0.0488066, + 0.0220857 -0.14277899 -0.049979702, + 0.0220857 -0.140644 -0.0490622, + 0.019305199 -0.140936 -0.050085701, + 0.019305199 -0.13885 -0.049102001, + 0.0165099 -0.139118 -0.049977399, + 0.0165099 -0.13708 -0.048928, + 0.0137106 -0.13732 -0.049658101, + 0.0137106 -0.135331 -0.048544001, + 0.0109179 -0.135537 -0.0491312, + 0.0109179 -0.133597 -0.0479545, + 0.0081428103 -0.133763 -0.0484019, + 0.0081428103 -0.131873 -0.0471652, + 0.0053973799 -0.13199501 -0.0474777, + 0.0053973799 -0.130154 -0.046183299, + 0.00268824 -0.13022999 -0.046366502, + 0.00268824 -0.128438 -0.045016699, + 0 -0.128465 -0.045076299, + 0 -0.12672199 -0.043673601, + -0.00268824 -0.12843899 -0.045015499, + -0.00268824 -0.13023099 -0.046365101, + -0.0053973799 -0.130156 -0.046180502, + -0.0053973799 -0.131997 -0.047474701, + -0.0081428103 -0.13187601 -0.0471607, + -0.0081428103 -0.133766 -0.048397198, + -0.0109179 -0.13360199 -0.047948301, + -0.0109179 -0.13554101 -0.0491249, + -0.0137106 -0.135336 -0.048535999, + -0.0137106 -0.137325 -0.049650401, + -0.0165099 -0.137086 -0.048918702, + -0.0165099 -0.13912401 -0.0499686, + -0.019305199 -0.13885701 -0.0490916, + -0.019305199 -0.140944 -0.050076202, + -0.0220857 -0.140652 -0.0490514, + -0.0220857 -0.14278699 -0.0499698, + -0.0248404 -0.14247601 -0.048795499, + -0.0248404 -0.14466 -0.049646899, + -0.027557701 -0.144337 -0.048324302, + -0.027557701 -0.146568 -0.049107801, + -0.0302257 -0.146238 -0.047639102, + -0.0302257 -0.148517 -0.048353899, + -0.0328326 -0.14818799 -0.0467408, + -0.0328326 -0.15051199 -0.047386099, + -0.035366699 -0.15019 -0.045631599, + -0.035366699 -0.15256 -0.046206299, + -0.0378174 -0.15225101 -0.044316601, + -0.0378174 -0.154667 -0.044820201, + -0.040174201 -0.154378 -0.042801999, + -0.040174201 -0.156838 -0.043235298, + -0.0424264 -0.156574 -0.041095499, + -0.0424264 -0.15908 -0.04146, + -0.044564299 -0.158848 -0.039206099, + -0.044564299 -0.16139799 -0.0395029, + -0.0465803 -0.161203 -0.037144799, + -0.0465803 -0.16379701 -0.037375402, + -0.048467699 -0.163644 -0.034923699, + -0.048467699 -0.166281 -0.035089299, + -0.0465803 -0.166384 -0.0375407, + -0.044564299 -0.16394401 -0.039733201, + -0.0424264 -0.161584 -0.0417565, + -0.040174201 -0.1593 -0.043599501, + -0.0378174 -0.157086 -0.045253199, + -0.035366699 -0.154938 -0.0467095, + -0.0328326 -0.15284701 -0.047960401, + -0.0302257 -0.15080801 -0.048998699, + -0.027557701 -0.148816 -0.049822301, + -0.0248404 -0.146865 -0.050430201, + -0.0220857 -0.14494701 -0.050820898, + -0.019305199 -0.143059 -0.050994299, + -0.0165099 -0.141194 -0.050953001, + -0.0137106 -0.139348 -0.050700098, + -0.0109179 -0.13751601 -0.050239, + -0.0081428103 -0.13569599 -0.049573701, + -0.0053973799 -0.133881 -0.048711199, + -0.00268824 -0.13206799 -0.047659401, + 0 -0.130255 -0.046425901, + 0.00268824 -0.13206699 -0.047660898, + 0.0053973799 -0.13387901 -0.048714299, + 0.0081428103 -0.135693 -0.049578398, + 0.0109179 -0.137512 -0.050245099, + 0.0137106 -0.13934299 -0.0507074, + 0.0165099 -0.141188 -0.0509611, + 0.019305199 -0.143051 -0.051002901, + 0.0220857 -0.14493901 -0.050829802, + 0.0248404 -0.14685699 -0.050439399, + 0.027557701 -0.148808 -0.049832199, + 0.0302257 -0.1508 -0.0490098, + 0.0328326 -0.152841 -0.047973901, + 0.035366699 -0.15493301 -0.0467267, + 0.0378174 -0.157083 -0.045274898, + 0.040174201 -0.159299 -0.043625701, + 0.0424264 -0.161586 -0.0417859, + 0.044564299 -0.163947 -0.039763201, + 0.0465803 -0.16638801 -0.037567198, + 0.050219599 -0.16079199 -0.0321922, + 0.051438499 -0.171523 -0.030750699, + 0.050209399 -0.171524 -0.032689501, + 0.055419099 -0.171517 -0.0228574, + 0.058983799 -0.171507 -0.0107787, + 0.059503399 -0.191504 -0.0075514098, + 0.059431799 -0.171505 -0.0080046104, + 0.0594863 -0.17150401 -0.0075652199, + 0.059706699 -0.17150301 -0.0057888799, + 0.059757002 -0.165032 -0.0051489202, + 0.059445001 -0.158751 -0.00749892, + 0.058998398 -0.152685 -0.0095976796, + 0.058412101 -0.146853 -0.0114353, + 0.0576833 -0.141278 -0.0130026, + 0.056809202 -0.13598099 -0.0142914, + 0.055787299 -0.130981 -0.0152945, + 0.0546159 -0.12629899 -0.0160046, + 0.0532961 -0.124555 -0.017604999, + 0.051830001 -0.122942 -0.019093299, + 0.050219599 -0.121452 -0.02046, + 0.048467699 -0.120081 -0.0216958, + 0.0465803 -0.118824 -0.0227925, + 0.044564299 -0.117674 -0.0237423, + 0.0424264 -0.116625 -0.0245372, + 0.040174201 -0.115666 -0.025170101, + 0.0378174 -0.114792 -0.025636099, + 0.035366699 -0.113991 -0.0259332, + 0.0328326 -0.113251 -0.0260674, + 0.0302257 -0.112557 -0.026035, + 0.027557701 -0.111903 -0.025830301, + 0.0248404 -0.111286 -0.025449499, + 0.0220857 -0.110694 -0.0248906, + 0.019305199 -0.110124 -0.024152899, + 0.0165099 -0.108411 -0.0214177, + 0.0137106 -0.107778 -0.020303, + 0.0109179 -0.107024 -0.019061901, + 0.0081428103 -0.107387 -0.0194853, + 0.0081428103 -0.104836 -0.0159376, + 0.0053973799 -0.105107 -0.0162246, + 0.0053973799 -0.102382 -0.0127762, + 0.00268824 -0.102552 -0.0129386, + 0.00268824 -0.099652201 -0.0096088396, + 0 -0.099710897 -0.0096597699, + 0 -0.096640401 -0.0064657698, + -0.00268824 -0.099652998 -0.0096094003, + -0.00268824 -0.102553 -0.0129395, + -0.0053973799 -0.102384 -0.0127779, + -0.0053973799 -0.105108 -0.0162262, + -0.0081428103 -0.104836 -0.015939999, + -0.0081428103 -0.107387 -0.019486699, + -0.0109179 -0.107024 -0.019063801, + -0.0109179 -0.109406 -0.0226967, + -0.0137106 -0.107778 -0.0203047, + -0.0137106 -0.111243 -0.025743, + -0.0137106 -0.113728 -0.029260401, + -0.0165099 -0.111966 -0.0267852, + -0.0109179 -0.111652 -0.026323499, + -0.0081428103 -0.109743 -0.023130501, + -0.0053973799 -0.107641 -0.0197822, + -0.00268824 -0.105267 -0.016394099, + 0 -0.102607 -0.012992, + 0.00268824 -0.105267 -0.0163933, + 0.0053973799 -0.107641 -0.0197812, + 0.0081428103 -0.109744 -0.023129901, + 0.0109179 -0.111652 -0.026321899, + 0.0081428103 -0.111964 -0.026764501, + 0.0053973799 -0.109979 -0.023433199, + 0.00268824 -0.10779 -0.019955, + 0 -0.10532 -0.0164485, + -0.00268824 -0.10779 -0.019955499, + -0.0053973799 -0.109979 -0.0234337, + -0.0081428103 -0.111964 -0.0267656, + -0.0109179 -0.114104 -0.029848101, + -0.0137106 -0.115061 -0.030984599, + -0.0165099 -0.114612 -0.0302507, + -0.0165099 -0.116022 -0.031945299, + -0.019305199 -0.115504 -0.031063, + -0.019305199 -0.116993 -0.032726601, + -0.0220857 -0.116413 -0.031694099, + -0.0220857 -0.11798 -0.033326801, + -0.0248404 -0.117342 -0.032143801, + -0.0248404 -0.118992 -0.033739801, + -0.027557701 -0.118303 -0.032408498, + -0.027557701 -0.120038 -0.033961602, + -0.0302257 -0.119306 -0.0324842, + -0.0302257 -0.121128 -0.033992101, + -0.0328326 -0.120358 -0.032370701, + -0.0328326 -0.122266 -0.033830699, + -0.035366699 -0.121468 -0.0320682, + -0.035366699 -0.123463 -0.033477701, + -0.0378174 -0.122644 -0.031580199, + -0.0378174 -0.124724 -0.032936901, + -0.040174201 -0.123892 -0.0309113, + -0.040174201 -0.126059 -0.0322126, + -0.0424264 -0.125222 -0.030065799, + -0.0424264 -0.127474 -0.0313095, + -0.044564299 -0.126642 -0.0290488, + -0.044564299 -0.128978 -0.0302324, + -0.0465803 -0.12815601 -0.0278678, + -0.0465803 -0.130576 -0.0289892, + -0.048467699 -0.12977301 -0.026531201, + -0.048467699 -0.132274 -0.0275883, + -0.050219599 -0.131496 -0.025047399, + -0.050219599 -0.13407999 -0.026039099, + -0.051830001 -0.133333 -0.023426, + -0.051830001 -0.135996 -0.024351399, + -0.0532961 -0.135287 -0.0216779, + -0.0532961 -0.138024 -0.022536, + -0.0546159 -0.13735799 -0.0198137, + -0.0546159 -0.14017101 -0.0206037, + -0.055787299 -0.136682 -0.017054001, + -0.0546159 -0.134564 -0.018955, + -0.0532961 -0.132569 -0.0207517, + -0.051830001 -0.130696 -0.022433599, + -0.050219599 -0.128942 -0.0239894, + -0.048467699 -0.12730099 -0.025408899, + -0.0465803 -0.12577 -0.026683301, + -0.044564299 -0.124342 -0.027804101, + -0.0424264 -0.12301 -0.0287634, + -0.040174201 -0.121768 -0.0295534, + -0.0378174 -0.120607 -0.0301695, + -0.035366699 -0.119522 -0.030606899, + -0.0328326 -0.118501 -0.0308614, + -0.0302257 -0.117537 -0.0309297, + -0.027557701 -0.116623 -0.030811001, + -0.0248404 -0.115748 -0.030510399, + -0.0220857 -0.114899 -0.030031599, + -0.019305199 -0.114072 -0.029370699, + -0.0165099 -0.113259 -0.028529599, + -0.019305199 -0.112696 -0.0276531, + -0.0220857 -0.113441 -0.028341901, + -0.0248404 -0.114205 -0.028849199, + -0.027557701 -0.114998 -0.029177001, + -0.0302257 -0.115824 -0.029330499, + -0.0328326 -0.116696 -0.0293053, + -0.035366699 -0.117625 -0.0290961, + -0.0378174 -0.118619 -0.0287068, + -0.040174201 -0.119689 -0.028141299, + -0.0424264 -0.12084 -0.027404301, + -0.044564299 -0.122082 -0.026500501, + -0.0465803 -0.12342 -0.0254375, + -0.048467699 -0.124863 -0.024223501, + -0.050219599 -0.126417 -0.0228664, + -0.051830001 -0.128086 -0.0213749, + -0.0532961 -0.129876 -0.019758601, + -0.0546159 -0.131791 -0.0180282, + -0.059445001 -0.15875 -0.0074576801, + -0.059757002 -0.15852299 -0.00471139, + -0.059445001 -0.152348 -0.0067869802, + -0.058998398 -0.15268999 -0.0095637804, + -0.058998398 -0.14640699 -0.0086158803, + -0.058412101 -0.146865 -0.0114114, + -0.058412101 -0.140723 -0.0101787, + -0.0576833 -0.141295 -0.012982, + -0.0576833 -0.135315 -0.0114682, + -0.056809202 -0.13600001 -0.0142685, + -0.056809202 -0.13020501 -0.0124802, + -0.055787299 -0.13100199 -0.0152671, + -0.048467699 -0.106853 -0.0127047, + -0.0465803 -0.108189 -0.0151796, + -0.048467699 -0.108938 -0.0143237, + -0.050219599 -0.107614 -0.0117675, + -0.050219599 -0.109807 -0.0133419, + -0.051830001 -0.108504 -0.0107152, + -0.051830001 -0.110804 -0.0122425, + -0.0532961 -0.10953 -0.00955672, + -0.0532961 -0.111935 -0.0110344, + -0.0546159 -0.110696 -0.0083012199, + -0.0546159 -0.113205 -0.0097267404, + -0.055787299 -0.112009 -0.0069578802, + -0.055787299 -0.114618 -0.0083288299, + -0.056809202 -0.113471 -0.00553576, + -0.056809202 -0.116178 -0.00684981, + -0.0576833 -0.117887 -0.0052982201, + 0.0597477 -0.17149401 0.00553325, + 0.059803601 -0.17149501 0.0047658202, + 0.059757002 -0.16458 0.0056464798, + 0.0165099 -0.0989765 -0.0092998203, + 0.0165099 -0.097448699 -0.00769587, + 0.019305199 -0.098145299 -0.0085421, + 0.019305199 -0.099655896 -0.0101655, + 0.0220857 -0.0987112 -0.00926085, + 0.0220857 -0.100205 -0.0109015, + 0.0248404 -0.099153697 -0.00984425, + 0.0248404 -0.100634 -0.0115, + 0.027557701 -0.099485703 -0.0102875, + 0.027557701 -0.100957 -0.0119565, + 0.0302257 -0.099722102 -0.0105876, + 0.0302257 -0.101188 -0.0122685, + 0.0328326 -0.099877603 -0.0107426, + 0.0328326 -0.101343 -0.0124355, + 0.035366699 -0.099967897 -0.0107532, + 0.035366699 -0.10144 -0.0124617, + 0.0378174 -0.100013 -0.0106275, + 0.0378174 -0.10149 -0.0123328, + 0.040174201 -0.100024 -0.010353, + 0.040174201 -0.101572 -0.0120227, + 0.0424264 -0.100079 -0.0099050105, + 0.0424264 -0.101738 -0.0115611, + 0.044564299 -0.100229 -0.0093142996, + 0.044564299 -0.101996 -0.0109629, + 0.0465803 -0.10048 -0.00859896, + 0.0465803 -0.102352 -0.0102424, + 0.048467699 -0.102812 -0.0094152903, + 0.0165099 -0.101906 -0.012613, + 0.0165099 -0.100464 -0.0109394, + 0.019305199 -0.101122 -0.0118239, + 0.019305199 -0.102542 -0.0135153, + 0.0220857 -0.101653 -0.0125763, + 0.0220857 -0.103056 -0.0142827, + 0.0248404 -0.102069 -0.0131889, + 0.0248404 -0.103456 -0.0149084, + 0.027557701 -0.102382 -0.0136579, + 0.027557701 -0.10376 -0.0153899, + 0.0302257 -0.102609 -0.013982, + 0.0302257 -0.103984 -0.0157292, + 0.0328326 -0.102766 -0.0141642, + 0.0328326 -0.104136 -0.015906701, + 0.035366699 -0.102863 -0.0141863, + 0.035366699 -0.104298 -0.015889499, + 0.0378174 -0.10298 -0.0140198, + 0.0378174 -0.104523 -0.015705099, + 0.040174201 -0.103171 -0.0136939, + 0.040174201 -0.10482 -0.0153665, + 0.0424264 -0.103445 -0.0132221, + 0.0424264 -0.105196 -0.0148837, + 0.044564299 -0.103806 -0.0126156, + 0.044564299 -0.105657 -0.0142684, + 0.0465803 -0.104262 -0.0118892, + 0.0465803 -0.106208 -0.0135357, + 0.048467699 -0.106853 -0.0127022, + 0.055787299 -0.111991 -0.0069835298, + 0.055787299 -0.109424 -0.0055519301, + 0.056809202 -0.113451 -0.0055651101, + 0.0546159 -0.110681 -0.0083222501, + 0.0546159 -0.108218 -0.00683732, + 0.0532961 -0.109517 -0.0095722796, + 0.0532961 -0.107161 -0.0080365604, + 0.051830001 -0.108496 -0.0107245, + 0.051830001 -0.106248 -0.0091402996, + 0.050219599 -0.10761 -0.0117697, + 0.050219599 -0.105472 -0.010143, + 0.0137106 -0.101138 -0.0115848, + 0.0137106 -0.102561 -0.013271, + 0.0165099 -0.103303 -0.0143184, + 0.019305199 -0.103916 -0.0152371, + 0.0220857 -0.10441 -0.016018599, + 0.0248404 -0.104797 -0.0166573, + 0.027557701 -0.105092 -0.017154001, + 0.0302257 -0.105307 -0.0174881, + 0.0328326 -0.105521 -0.017625, + 0.035366699 -0.105787 -0.017588001, + 0.0378174 -0.106116 -0.0173888, + 0.040174201 -0.106515 -0.017036701, + 0.0424264 -0.106991 -0.016542001, + 0.044564299 -0.107546 -0.0159171, + 0.0465803 -0.108188 -0.0151773, + 0.048467699 -0.108934 -0.0143258, + 0.050219599 -0.109799 -0.013351, + 0.051830001 -0.110792 -0.0122576, + 0.0532961 -0.11192 -0.0110549, + 0.0546159 -0.113187 -0.0097518601, + 0.055787299 -0.114598 -0.0083576497, + 0.056809202 -0.118899 -0.0081362398, + 0.0576833 -0.117865 -0.0053314599, + 0.0576833 -0.123566 -0.0076519502, + 0.058412101 -0.122647 -0.0048450101, + 0.058412101 -0.128581 -0.0069015399, + 0.058998398 -0.127781 -0.0041028201, + 0.058998398 -0.133922 -0.0058899699, + 0.059445001 -0.133241 -0.0031101999, + 0.059445001 -0.139566 -0.0046247002, + 0.059757002 -0.13900401 -0.0018756801, + 0.059757002 -0.14549001 -0.0031145399, + 0.0599402 -0.145046 -0.000402862, + 0.0599402 -0.15166999 -0.00136351, + 0.059999999 -0.151338 0.00132629, + 0.059999999 -0.158079 0.00064591598, + 0.0599402 -0.157857 0.0033349099, + 0.0599402 -0.164693 0.0029371199, + 0.059930101 -0.171496 0.00303161, + 0.059821099 -0.191495 0.0047830199, + 0.0081428103 -0.0784325 0.0072367699, + 0.0109179 -0.079817399 0.0063335402, + 0.0081428103 -0.082199603 0.0049623302, + 0.0053973799 -0.078788698 0.0071049398, + 0.0053973799 -0.074928701 0.0092087695, + 0.00268824 -0.075134903 0.0091480296, + 0.00268824 -0.071191698 0.0110617, + 0 -0.0712571 0.0110472, + 0 -0.0672471 0.0127569, + -0.00268824 -0.071191698 0.0110617, + -0.00268824 -0.075135797 0.0091478303, + -0.0053973799 -0.074930497 0.00920837, + -0.0053973799 -0.078791402 0.0071049999, + -0.0081428103 -0.078436501 0.0072368602, + 0.054602899 -0.171479 0.024971301, + 0.055455498 -0.17148 0.023042699, + 0.0546159 -0.163765 0.025092101, + 0.055579402 -0.19148 0.0227562, + 0.054265399 -0.171478 0.025734801, + 0.0532961 -0.163652 0.027809899, + 0.0546159 -0.15602501 0.0254949, + 0.055787299 -0.156253 0.022739099, + 0.055787299 -0.148615 0.023426101, + 0.056809202 -0.148958 0.0206437, + 0.056809202 -0.141441 0.0216121, + 0.0576833 -0.141899 0.018813999, + 0.0576833 -0.13452201 0.0200611, + 0.058412101 -0.135095 0.017257901, + 0.058412101 -0.127877 0.018781301, + 0.058998398 -0.128563 0.015983701, + 0.058998398 -0.121524 0.017781099, + 0.059445001 -0.122319 0.0149998, + 0.059445001 -0.115479 0.0170688, + 0.059757002 -0.116379 0.0143156, + 0.059757002 -0.109757 0.016651601, + 0.0599402 -0.110759 0.013933, + 0.0599402 -0.104373 0.0165252, + 0.059999999 -0.105482 0.013825, + 0.059999999 -0.0993523 0.016659901, + 0.0599402 -0.100578 0.0139563, + 0.0599402 -0.094724298 0.0170196, + 0.059757002 -0.096079104 0.0142901, + 0.059757002 -0.090520903 0.017564099, + 0.059445001 -0.092017002 0.0147915, + 0.059445001 -0.086696804 0.0180666, + 0.058998398 -0.0883395 0.0152652, + 0.058998398 -0.083177596 0.018382199, + 0.058412101 -0.084973902 0.0155812, + 0.058412101 -0.080025896 0.0185393, + 0.0576833 -0.081980802 0.0157665, + 0.0576833 -0.077266403 0.018594099, + 0.056809202 -0.0793809 0.0158778, + 0.056809202 -0.077064 0.0172494, + 0.055787299 -0.079247698 0.0145795, + 0.055787299 -0.076975502 0.015914701, + 0.0532961 -0.074870899 0.0145718, + 0.0532961 -0.072621197 0.0157224, + 0.0546159 -0.074726097 0.0158507, + 0.051830001 -0.075086802 0.0133615, + 0.051830001 -0.072881296 0.0144941, + 0.050219599 -0.075358503 0.0122353, + 0.050219599 -0.073205002 0.0133554, + 0.048467699 -0.075677 0.0112089, + 0.048467699 -0.0735991 0.0123173, + 0.0465803 -0.076046303 0.0102918, + 0.0465803 -0.0739979 0.011359, + 0.044564299 -0.076403402 0.0094656404, + 0.044564299 -0.074374102 0.0104885, + 0.0424264 -0.076721899 0.0087382002, + 0.0424264 -0.074720502 0.0097252, + 0.040174201 -0.076993302 0.0081264097, + 0.040174201 -0.075020202 0.0090856403, + 0.0378174 -0.077202298 0.0076433499, + 0.0378174 -0.075257301 0.0085845301, + 0.035366699 -0.077332899 0.0073012798, + 0.035366699 -0.075413503 0.0082330499, + 0.0328326 -0.077366203 0.00710891, + 0.0328326 -0.075467199 0.0080385702, + 0.0302257 -0.077281602 0.0070708101, + 0.0302257 -0.075396903 0.0080031697, + 0.027557701 -0.077061497 0.0071848398, + 0.027557701 -0.075183503 0.0081223696, + 0.0248404 -0.076688997 0.0074442299, + 0.0248404 -0.074810199 0.00838657, + 0.0220857 -0.076148301 0.0078378599, + 0.0220857 -0.074261203 0.0087819397, + 0.019305199 -0.075426303 0.0083502596, + 0.019305199 -0.073525101 0.0092913499, + 0.0165099 -0.074516401 0.0089623397, + 0.0165099 -0.072596803 0.0098959096, + 0.0137106 -0.073416203 0.0096544595, + 0.0137106 -0.071475402 0.0105717, + 0.0109179 -0.072126403 0.010403, + 0.0109179 -0.070161298 0.0112896, + 0.0109179 -0.074075401 0.0094601903, + 0.0137106 -0.075343102 0.008688, + 0.0109179 -0.077922799 0.0074254302, + 0.0081428103 -0.0745776 0.0093121901, + 0.0165099 -0.076422997 0.0079809995, + 0.019305199 -0.0773158 0.0073591699, + 0.0220857 -0.078025401 0.00684227, + 0.0248404 -0.078560099 0.0064481399, + 0.027557701 -0.078933403 0.0061897398, + 0.0302257 -0.079161197 0.0060755601, + 0.0328326 -0.079259597 0.0061101001, + 0.035366699 -0.079245299 0.0062930798, + 0.0378174 -0.079136699 0.0066186101, + 0.040174201 -0.078950502 0.0070766001, + 0.0424264 -0.078702301 0.0076562199, + 0.044564299 -0.078399703 0.0083439304, + 0.0465803 -0.078067601 0.0091329701, + 0.048467699 -0.0777665 0.0100395, + 0.050219599 -0.077495903 0.0110546, + 0.051830001 -0.077265099 0.0121645, + 0.0532961 -0.077090397 0.0133549, + 0.0546159 -0.076988801 0.0146106, + 0.055787299 -0.0746684 0.0171823, + 0.056809202 -0.074712098 0.0185492, + 0.0576833 -0.074868597 0.0199333, + 0.058412101 -0.075148799 0.0213145, + 0.058998398 -0.078075603 0.0213056, + 0.059445001 -0.081392698 0.021165701, + 0.059757002 -0.085071698 0.020838, + 0.0599402 -0.089044698 0.0203001, + 0.059999999 -0.0933799 0.0197281, + 0.0599402 -0.098126397 0.019363601, + 0.059757002 -0.103255 0.019246399, + 0.059445001 -0.108741 0.019406701, + 0.058998398 -0.114569 0.019851601, + 0.058412101 -0.120724 0.0205801, + 0.0576833 -0.12719101 0.021585699, + 0.056809202 -0.13395099 0.0228603, + 0.055787299 -0.140985 0.024395499, + 0.0546159 -0.148276 0.026182801, + 0.0532961 -0.155801 0.028213499, + 0.052944701 -0.17147601 0.0283654, + 0.052960001 -0.17147601 0.0283348, + 0.051830001 -0.16354001 0.0304785, + 0.050210599 -0.171472 0.032963499, + 0.0497806 -0.19147199 0.033647101, + 0.051496498 -0.17147399 0.030928001, + 0.049775898 -0.171472 0.033627801, + 0.048461299 -0.17147 0.035498701, + 0.048467699 -0.163325 0.035620902, + -0.0465803 -0.163219 0.0380987, + -0.046066999 -0.171468 0.038566999, + -0.044564299 -0.16312 0.040454999, + -0.0576833 -0.067480102 0.0234851, + -0.056809202 -0.0699123 0.020918, + -0.0576833 -0.0699718 0.022373701, + -0.058412101 -0.0676139 0.0249868, + -0.058412101 -0.070156701 0.0238395, + -0.058998398 -0.067883298 0.0264854, + -0.058998398 -0.070475399 0.0252956, + -0.059445001 -0.068295904 0.027960099, + -0.059445001 -0.070935801 0.0267205, + -0.059757002 -0.068859003 0.029388299, + -0.059757002 -0.074220099 0.026765, + -0.0599402 -0.072328202 0.029448399, + -0.0599402 -0.077886 0.0266266, + -0.059999999 -0.076156899 0.029323, + -0.059999999 -0.081877202 0.0262821, + -0.0599402 -0.080285899 0.028995801, + -0.0599402 -0.086115897 0.025726801, + -0.059757002 -0.084639601 0.028462701, + -0.059757002 -0.090690702 0.0251769, + -0.059445001 -0.089317799 0.027943, + -0.059445001 -0.095656298 0.024872599, + -0.058998398 -0.094390802 0.0276636, + -0.058998398 -0.100998 0.024822099, + -0.058412101 -0.099845201 0.027627001, + -0.058412101 -0.106703 0.025027899, + -0.0576833 -0.105666 0.027836701, + -0.0576833 -0.112756 0.0254921, + -0.056809202 -0.111839 0.028294999, + -0.056809202 -0.119143 0.026215401, + -0.055787299 -0.118346 0.0290017, + -0.055787299 -0.125843 0.027194001, + -0.0546159 -0.125167 0.029953299, + -0.0546159 -0.132835 0.0284227, + -0.0532961 -0.13227899 0.0311433, + -0.0532961 -0.1401 0.029895101, + -0.051830001 -0.139663 0.032565299, + -0.051830001 -0.147615 0.031601898, + -0.050219599 -0.147294 0.034209799, + -0.050219599 -0.15536299 0.033525702, + -0.048467699 -0.155154 0.036060002, + -0.051830001 -0.155579 0.0309186, + -0.0532961 -0.147944 0.0289327, + -0.0546159 -0.140545 0.0271754, + -0.055787299 -0.13339899 0.025664501, + -0.056809202 -0.126525 0.024409, + -0.0576833 -0.119944 0.0234142, + -0.058412101 -0.113674 0.0226852, + -0.058998398 -0.107737 0.0222256, + -0.059445001 -0.102143 0.0220348, + -0.059757002 -0.096908301 0.0221115, + -0.0599402 -0.092045501 0.0224474, + -0.059999999 -0.0875808 0.0230119, + -0.0599402 -0.0834684 0.0235685, + -0.059757002 -0.079628602 0.023909399, + -0.059445001 -0.076137401 0.0240457, + -0.058998398 -0.073035002 0.0240239, + -0.058412101 -0.072668798 0.0226142, + -0.0576833 -0.072435603 0.0211873, + -0.056809202 -0.072326399 0.019764399, + -0.055787299 -0.072331503 0.0183645, + 0.0532961 -0.070346102 0.0168058, + 0.0532961 -0.068059497 0.0178234, + 0.0546159 -0.070110202 0.018127, + 0.051830001 -0.070661999 0.0155636, + 0.051830001 -0.068465397 0.016566399, + 0.050219599 -0.0710686 0.0144118, + 0.050219599 -0.068909802 0.0153638, + 0.048467699 -0.071496397 0.0133278, + 0.048467699 -0.0693627 0.0142247, + 0.0465803 -0.071917303 0.0123202, + 0.0465803 -0.069820598 0.0131719, + 0.044564299 -0.072325997 0.0114095, + 0.044564299 -0.070268497 0.0122261, + 0.0424264 -0.072706297 0.0106149, + 0.0424264 -0.070689298 0.0114086, + 0.040174201 -0.073040299 0.0099551603, + 0.040174201 -0.071062803 0.0107375, + 0.0378174 -0.073309802 0.0094439797, + 0.0378174 -0.071367197 0.0102254, + 0.035366699 -0.073493503 0.0090913204, + 0.035366699 -0.0715793 0.0098797996, + 0.0328326 -0.073568299 0.0089019798, + 0.0328326 -0.071674198 0.0097030802, + 0.0302257 -0.073511101 0.0088756401, + 0.0302257 -0.071627997 0.0096915402, + 0.027557701 -0.073302701 0.0090047698, + 0.027557701 -0.071421303 0.0098343799, + 0.0248404 -0.072925799 0.0092768697, + 0.0248404 -0.071038097 0.0101172, + 0.0220857 -0.072366297 0.0096761296, + 0.0220857 -0.070465602 0.0105239, + 0.019305199 -0.071614303 0.0101854, + 0.019305199 -0.069695398 0.0110324, + 0.0165099 -0.070666 0.0107813, + 0.0165099 -0.068722501 0.0116078, + 0.0137106 -0.069519997 0.0114315, + 0.0137106 -0.067548499 0.0122396, + 0.0109179 -0.068180099 0.0121247, + 0.0109179 -0.0661847 0.0129083, + 0.0109179 -0.062159099 0.0143178, + 0.0137106 -0.063566998 0.0137002, + 0.0081428103 -0.062617801 0.0142901, + 0.0081428103 -0.062109899 0.0144562, + 0.0053973799 -0.062428899 0.0144401, + 0.0053973799 -0.061942901 0.0145496, + 0.00268824 -0.062129501 0.0145418, + 0.00268824 -0.061590001 0.0145218, + 0 -0.061651099 0.0145195, + 0 -0.061101001 0.0143417, + -0.00268824 -0.061590899 0.0145208, + -0.00268824 -0.062129699 0.0145409, + -0.0053973799 -0.0619433 0.0145478, + -0.0053973799 -0.062428899 0.0144392, + -0.0081428103 -0.062109798 0.0144549, + -0.0081428103 -0.062618397 0.0142894, + -0.0109179 -0.06216 0.0143168, + -0.055787299 -0.065173499 0.021530701, + -0.056809202 -0.065012001 0.0230061, + -0.055787299 -0.0627397 0.0224468, + -0.0546159 -0.065426297 0.020113699, + -0.0546159 -0.063086197 0.0210081, + -0.0532961 -0.065799601 0.0187626, + -0.0532961 -0.063527897 0.0195875, + -0.051830001 -0.066251002 0.017444599, + -0.051830001 -0.064011201 0.018200399, + -0.050219599 -0.066728503 0.016175101, + -0.050219599 -0.064533196 0.016876301, + -0.048467699 -0.067226902 0.014982, + -0.048467699 -0.065081 0.015641499, + -0.0465803 -0.0677329 0.0138894, + -0.0465803 -0.0656396 0.0145213, + -0.044564299 -0.068230301 0.01292, + -0.044564299 -0.0661899 0.013537, + -0.0424264 -0.068699099 0.0120929, + -0.0424264 -0.0667082 0.0127084, + -0.040174201 -0.069115497 0.0114245, + -0.040174201 -0.067167997 0.0120493, + -0.0378174 -0.069455601 0.0109247, + -0.0378174 -0.067542799 0.0115672, + -0.035366699 -0.069694199 0.0105978, + -0.035366699 -0.067805901 0.0112634, + -0.0328326 -0.069805399 0.0104431, + -0.0328326 -0.067930698 0.0111345, + -0.0302257 -0.069765002 0.0104541, + -0.0302257 -0.0678932 0.0111694, + -0.027557701 -0.069554202 0.0106171, + -0.027557701 -0.0676746 0.0113471, + -0.0248404 -0.069156997 0.0109102, + -0.0248404 -0.067262203 0.0116527, + -0.0220857 -0.068562701 0.0113173, + -0.0220857 -0.066647999 0.0120665, + -0.019305199 -0.067766003 0.0118192, + -0.019305199 -0.065821297 0.0125538, + -0.0165099 -0.066763103 0.0123825, + -0.0165099 -0.064789802 0.013106, + -0.0137106 -0.065562896 0.012996, + -0.0137106 -0.063566998 0.0136995, + -0.0109179 -0.064178899 0.0136374, + -0.0081428103 -0.066658303 0.0128404, + -0.0053973799 -0.062938802 0.0142702, + -0.00268824 -0.062616199 0.0144302, + 0 -0.062190499 0.0145389, + 0.00268824 -0.062616199 0.0144306, + 0.0053973799 -0.0629384 0.0142706, + 0.0081428103 -0.0666584 0.0128408, + 0.0081428103 -0.0706499 0.0111816, + 0.0053973799 -0.066989303 0.0127936, + 0.00268824 -0.063126497 0.0142593, + 0 -0.062677301 0.0144273, + -0.00268824 -0.063126698 0.014259, + -0.0053973799 -0.066989303 0.0127933, + -0.0081428103 -0.0706499 0.0111816, + -0.0109179 -0.068180002 0.0121247, + -0.0109179 -0.070161201 0.0112896, + -0.0109179 -0.074078903 0.0094593903, + -0.0137106 -0.071476601 0.0105663, + -0.0137106 -0.069519803 0.0114314, + -0.0165099 -0.070667498 0.0107748, + -0.0165099 -0.072602101 0.0098947203, + -0.019305199 -0.071620502 0.010184, + -0.019305199 -0.073533803 0.0092934603, + -0.0220857 -0.0723764 0.0096785398, + -0.0220857 -0.074272104 0.0087822396, + -0.0248404 -0.072938003 0.0092770802, + -0.0248404 -0.074822798 0.0083844801, + -0.027557701 -0.073316701 0.0090024797, + -0.027557701 -0.075197697 0.0081181796, + -0.0302257 -0.073526703 0.0088710496, + -0.0302257 -0.075412199 0.0079963403, + -0.0328326 -0.073585004 0.0088946, + -0.0328326 -0.075483099 0.0080285603, + -0.035366699 -0.073510602 0.0090805404, + -0.035366699 -0.075429298 0.0082195699, + -0.0378174 -0.073326699 0.0094295898, + -0.0378174 -0.075272299 0.0085677402, + -0.040174201 -0.073056199 0.0099373804, + -0.040174201 -0.075033203 0.0090663498, + -0.0424264 -0.072719902 0.0105946, + -0.0424264 -0.074730597 0.00970551, + -0.044564299 -0.072336704 0.0113889, + -0.044564299 -0.074380703 0.0104717, + -0.0465803 -0.071924202 0.0123026, + -0.0465803 -0.0739998 0.0113469, + -0.048467699 -0.071498498 0.0133152, + -0.048467699 -0.073597699 0.0123092, + -0.050219599 -0.071067102 0.0144034, + -0.050219599 -0.073220901 0.013345, + -0.051830001 -0.070678398 0.0155528, + -0.051830001 -0.072906099 0.0144789, + -0.0532961 -0.070371702 0.0167902, + -0.0532961 -0.072637103 0.015704701, + -0.0546159 -0.070126399 0.0181088, + -0.0546159 -0.0724397 0.017005499, + -0.055787299 -0.069967799 0.0194906, + -0.055787299 -0.067581102 0.020546099, + -0.0546159 -0.067790397 0.0191442, + -0.0532961 -0.068076402 0.017812399, + -0.051830001 -0.068463802 0.016557699, + -0.050219599 -0.068911903 0.0153507, + -0.048467699 -0.069369897 0.0142064, + -0.0465803 -0.069831803 0.0131503, + -0.044564299 -0.070282899 0.0122047, + -0.0424264 -0.070706204 0.0113898, + -0.040174201 -0.071080796 0.0107222, + -0.0378174 -0.071385503 0.0102139, + -0.035366699 -0.0715973 0.00987182, + -0.0328326 -0.071691103 0.0096980901, + -0.0302257 -0.071643397 0.0096889501, + -0.027557701 -0.071434803 0.00983469, + -0.0248404 -0.0710494 0.0101199, + -0.0220857 -0.070472904 0.0105223, + -0.019305199 -0.069697097 0.0110249, + -0.0165099 -0.068722397 0.0116077, + -0.0137106 -0.067548402 0.0122396, + -0.0109179 -0.066184603 0.0129076, + -0.0576833 -0.064964503 0.0245206, + -0.058412101 -0.065044403 0.026055999, + -0.058998398 -0.065261699 0.0275939, + -0.059445001 -0.065624297 0.0291145, + -0.059757002 -0.066139698 0.0305962, + -0.0599402 -0.066809699 0.0320209, + -0.059999999 -0.070450999 0.032111101, + -0.0599402 -0.074427798 0.032019299, + -0.059757002 -0.078682303 0.0317306, + -0.059445001 -0.083143599 0.0312353, + -0.058998398 -0.087930098 0.030738899, + -0.058412101 -0.0931172 0.0304722, + -0.0576833 -0.098689802 0.030438701, + -0.056809202 -0.104632 0.0306415, + -0.055787299 -0.110927 0.0310828, + -0.0546159 -0.117556 0.031762298, + -0.0532961 -0.124499 0.032675002, + -0.051830001 -0.131733 0.033814602, + -0.050219599 -0.13923401 0.035174299, + -0.048467699 -0.146981 0.0367449, + -0.0465803 -0.15495101 0.038510598, + -0.00267513 -0.162294 0.060210399, + -0.0053918599 -0.162302 0.060028002, + -0.0030883299 -0.171451 0.060051501, + -0.050219599 -0.043872301 0.0180058, + -0.048467699 -0.0458913 0.017167101, + -0.050219599 -0.0446858 0.0181226, + -0.051830001 -0.041756999 0.018985899, + -0.051830001 -0.0434127 0.0193073, + -0.0532961 -0.040389199 0.020312199, + -0.0532961 -0.042113502 0.0207086, + -0.0546159 -0.039017599 0.021856699, + -0.0546159 -0.040834401 0.022328099, + -0.055787299 -0.0376896 0.023618201, + -0.055787299 -0.0396179 0.024148401, + -0.056809202 -0.036447801 0.0255765, + -0.056809202 -0.0385032 0.026141301, + -0.0576833 -0.035330798 0.027700899, + -0.0576833 -0.037523098 0.028274, + -0.058412101 -0.034370501 0.0299554, + -0.058412101 -0.036704998 0.030507401, + -0.058998398 -0.0335932 0.032298502, + -0.058998398 -0.036067098 0.0327999, + -0.059445001 -0.033016101 0.034685802, + -0.059445001 -0.035621099 0.035106901, + -0.059757002 -0.032650001 0.037070099, + -0.059757002 -0.035370599 0.037385099, + -0.0599402 -0.032490801 0.039410401, + -0.0599402 -0.035307799 0.0395956, + -0.059999999 -0.032505602 0.0416844, + -0.059999999 -0.0354001 0.041723099, + -0.0599402 -0.032656301 0.0438825, + -0.0599402 -0.0355964 0.043758601, + -0.059757002 -0.032891098 0.0459975, + -0.059757002 -0.0359344 0.045723598, + -0.059445001 -0.033256602 0.048048899, + -0.059445001 -0.036455002 0.047719501, + -0.058998398 -0.033818401 0.0501238, + -0.058998398 -0.0370849 0.049747702, + -0.058412101 -0.034504201 0.052218899, + -0.058412101 -0.037845898 0.051784799, + -0.0576833 -0.035333801 0.054310501, + -0.0576833 -0.0387499 0.0538112, + -0.056809202 -0.036317602 0.056378599, + -0.056809202 -0.039804801 0.055807799, + -0.055787299 -0.037462801 0.058403499, + -0.055787299 -0.041016899 0.057754502, + -0.0546159 -0.038774598 0.0603646, + -0.0546159 -0.042390998 0.0596302, + -0.0532961 -0.040256899 0.062239401, + -0.0532961 -0.043930698 0.0614127, + -0.051830001 -0.0419126 0.064005397, + -0.051830001 -0.045635302 0.063085303, + -0.050219599 -0.043739501 0.065645099, + -0.050219599 -0.047522701 0.064632699, + -0.048467699 -0.045752998 0.067143001, + -0.048467699 -0.049592599 0.066029601, + -0.0465803 -0.047949798 0.068474397, + -0.0465803 -0.051832099 0.067254901, + -0.044564299 -0.0503162 0.069618799, + -0.044564299 -0.0542273 0.068288296, + -0.0424264 -0.052837498 0.070556402, + -0.0424264 -0.056763701 0.069110498, + -0.040174201 -0.055498201 0.0712687, + -0.040174201 -0.0594263 0.069703698, + -0.0378174 -0.0582815 0.071740799, + -0.0378174 -0.062197801 0.070054002, + -0.035366699 -0.0611693 0.071960002, + -0.035366699 -0.069150597 0.068569601, + -0.0328326 -0.068274297 0.070334502, + -0.0328326 -0.076464802 0.067186303, + -0.0302257 -0.0757301 0.068805397, + -0.0302257 -0.084108002 0.065908499, + -0.027557701 -0.083502501 0.067380399, + -0.027557701 -0.092047401 0.064742498, + -0.0248404 -0.091558397 0.066066101, + -0.0248404 -0.10025 0.063694596, + -0.0220857 -0.099865198 0.064868502, + -0.0220857 -0.108683 0.062769599, + -0.019305199 -0.108391 0.063792899, + -0.019305199 -0.117315 0.061970402, + -0.0165099 -0.117099 0.062845498, + -0.0165099 -0.126111 0.061302301, + -0.0137106 -0.12596101 0.062031701, + -0.0137106 -0.135038 0.060770702, + -0.0109179 -0.134942 0.061356898, + -0.0109179 -0.14406499 0.060379598, + -0.0081421202 -0.14401101 0.060825702, + -0.0081421202 -0.153164 0.0601307, + -0.0053918599 -0.153138 0.060442001, + -0.0026750399 -0.171451 0.060072798, + 5.2000001e-008 -0.171451 0.060134199, + -0.051042698 -0.0339665 0.016012101, + -0.050219599 -0.035296101 0.015931999, + -0.051830001 -0.034147698 0.016691901, + 0.0220857 -0.0573759 0.0146533, + 0.0220857 -0.0568421 0.0144398, + 0.023467001 -0.0568006 0.014671, + 0.020698 -0.057376999 0.0144276, + 0.0220857 -0.056375802 0.0140689, + 0.019305199 -0.057404 0.0140526, + 0.019305199 -0.057055399 0.0135805, + 0.0165099 -0.057931799 0.0135716, + 0.0165099 -0.057736099 0.0130566, + 0.0137106 -0.058464799 0.0130528, + 0.0147097 -0.058157299 0.0125463, + 0.0118392 -0.058808699 0.0125468, + 0.0109151 -0.058971301 0.012547, + 0.0107568 -0.059020299 0.007547, + 0.0211595 -0.171454 0.056265, + 0.0220857 -0.162469 0.056050099, + 0.020292999 -0.171453 0.0566006, + -0.034109399 -0.052265901 0.0149114, + -0.0328326 -0.053147402 0.0148584, + -0.035366699 -0.053187601 0.0147551, + -0.037815802 -0.046566602 0.0125371, + -0.0360066 -0.047970701 0.0125382, + -0.0378174 -0.046616402 0.0131005, + -0.035366699 -0.048505299 0.0130921, + -0.045588002 -0.040814001 0.0153755, + -0.044564299 -0.0420013 0.0153287, + -0.045588002 -0.041213602 0.0154892, + -0.0465803 -0.039996099 0.0155496, + -0.047540501 -0.0391674 0.0156992, + -0.0465803 -0.040414199 0.0156242, + -0.048467699 -0.039513599 0.016146099, + -0.044564299 -0.042833801 0.0154786, + -0.0465803 -0.042071499 0.0158858, + -0.048467699 -0.041120499 0.016472699, + -0.050219599 -0.038432799 0.0168551, + -0.050219599 -0.039989199 0.017253, + -0.051830001 -0.037180599 0.017764, + -0.051830001 -0.038681101 0.0182507, + -0.0532961 -0.035762001 0.0188962, + -0.0532961 -0.037221398 0.019405199, + -0.0546159 -0.034204502 0.0201841, + -0.0546159 -0.035706598 0.020769, + -0.055787299 -0.032611702 0.021681201, + -0.055787299 -0.0341882 0.022373101, + -0.056809202 -0.0310372 0.023420401, + -0.056809202 -0.032710999 0.0241952, + -0.0576833 -0.0295262 0.025376, + -0.0576833 -0.031323999 0.026229501, + -0.058412101 -0.028128101 0.027540401, + -0.058412101 -0.030068999 0.028450301, + -0.058998398 -0.0268848 0.0298848, + -0.058998398 -0.0289841 0.030820999, + -0.059445001 -0.025834501 0.032369301, + -0.059445001 -0.028100001 0.0332998, + -0.059757002 -0.025008 0.0349489, + -0.059757002 -0.027442001 0.035838999, + -0.0599402 -0.024423299 0.0375765, + -0.0599402 -0.0270191 0.0383927, + -0.059999999 -0.0240636 0.040219799, + -0.059999999 -0.026808999 0.040929701, + -0.0599402 -0.023899799 0.042851999, + -0.0599402 -0.0267756 0.0434299, + -0.059757002 -0.0238958 0.045455299, + -0.059757002 -0.026879599 0.045878202, + -0.059445001 -0.0240178 0.0480115, + -0.059445001 -0.0270888 0.048264101, + -0.058998398 -0.0242563 0.0504933, + -0.058998398 -0.0273785 0.050559901, + -0.058412101 -0.024589701 0.052868001, + -0.058412101 -0.027825801 0.052764799, + -0.0576833 -0.025095301 0.055135801, + -0.0576833 -0.028505201 0.054968901, + -0.056809202 -0.0258493 0.057390898, + -0.056809202 -0.029334299 0.0571694, + -0.055787299 -0.026764899 0.059629802, + -0.055787299 -0.0303303 0.059341099, + -0.0546159 -0.0278582 0.061826501, + -0.0546159 -0.031501502 0.061462499, + -0.0532961 -0.0291372 0.063958302, + -0.0532961 -0.0328537 0.063512102, + -0.051830001 -0.030606501 0.066002898, + -0.051830001 -0.034390699 0.065467, + -0.050219599 -0.032268502 0.067937098, + -0.050219599 -0.036114 0.067304499, + -0.048467699 -0.0341237 0.069737799, + -0.048467699 -0.038023699 0.069001399, + -0.0465803 -0.036169901 0.071382903, + -0.0465803 -0.040114701 0.070540302, + -0.044564299 -0.038401 0.072854601, + -0.044564299 -0.0423958 0.071905002, + -0.0424264 -0.040822901 0.074135996, + -0.0424264 -0.044860199 0.073072203, + -0.040174201 -0.043427099 0.075204998, + -0.040174201 -0.047492299 0.074022397, + -0.0378174 -0.0461956 0.076044701, + -0.0378174 -0.050274301 0.074739598, + -0.035366699 -0.0491096 0.0766403, + -0.035366699 -0.053187601 0.075209297, + -0.0328326 -0.052150499 0.076977901, + -0.0328326 -0.056214899 0.075418197, + -0.0302257 -0.0553004 0.077045299, + -0.0302257 -0.059337098 0.075355798, + -0.027557701 -0.058538198 0.0768364, + -0.027557701 -0.066735499 0.073433697, + -0.0248404 -0.066075303 0.074763, + -0.0248404 -0.074458897 0.071606301, + -0.0220857 -0.0739244 0.072783902, + -0.0220857 -0.082473397 0.069881298, + -0.019305199 -0.082051203 0.070906997, + -0.019305199 -0.090745702 0.068265498, + -0.0165099 -0.090421699 0.069141798, + -0.0165099 -0.099242203 0.066768199, + -0.0137106 -0.0990026 0.067498296, + -0.0137106 -0.10793 0.065398201, + -0.0109179 -0.107762 0.065984897, + -0.0109179 -0.116776 0.064161703, + -0.0081421202 -0.116666 0.064608499, + -0.0081421202 -0.12574799 0.063064799, + -0.0053918599 -0.12568399 0.063376904, + -0.0053918599 -0.13481601 0.0621152, + -0.00267513 -0.13478599 0.062297899, + -0.00267513 -0.14395 0.061319601, + 0 -0.143942 0.061378699, + 0 -0.153118 0.060683001, + 0.00267513 -0.143949 0.061318099, + 0.00267513 -0.13478599 0.0622968, + 0.0053918599 -0.13481501 0.062112998, + 0.0053918599 -0.12568299 0.063375004, + 0.0081421202 -0.125746 0.0630619, + 0.0081421202 -0.116663 0.064605199, + 0.0109179 -0.116772 0.0641573, + 0.0109179 -0.107757 0.0659796, + 0.0137106 -0.107924 0.065391399, + 0.0137106 -0.098997302 0.067490503, + 0.0165099 -0.0992359 0.066758797, + 0.0165099 -0.090415403 0.069132298, + 0.019305199 -0.090738401 0.068254396, + 0.019305199 -0.0820444 0.070896901, + 0.0220857 -0.082465596 0.069869898, + 0.0220857 -0.073918 0.072775401, + 0.0248404 -0.0744517 0.071596697, + 0.0248404 -0.066071197 0.074758597, + 0.027557701 -0.066730998 0.073428698, + 0.027557701 -0.058537699 0.0768378, + 0.0302257 -0.059336599 0.075357303, + 0.0302257 -0.0553004 0.077046297, + 0.0328326 -0.056214999 0.075419202, + 0.0328326 -0.052150398 0.076980203, + 0.035366699 -0.0531874 0.075211801, + 0.035366699 -0.049109001 0.076644599, + 0.0378174 -0.050273601 0.074744202, + 0.0378174 -0.046194401 0.076050997, + 0.040174201 -0.0474911 0.074029103, + 0.040174201 -0.043426 0.0752123, + 0.0424264 -0.0448591 0.073079899, + 0.0424264 -0.040823199 0.074142098, + 0.044564299 -0.042396002 0.071911402, + 0.044564299 -0.038403001 0.0728577, + 0.0465803 -0.040116802 0.070543602, + 0.0465803 -0.036171101 0.071386397, + 0.048467699 -0.038024899 0.069005102, + 0.048467699 -0.034124698 0.069743797, + 0.050219599 -0.036114998 0.067310601, + 0.050219599 -0.032269299 0.067946099, + 0.051830001 -0.0343915 0.065476298, + 0.051830001 -0.030606501 0.066015303, + 0.0532961 -0.032853801 0.063524798, + 0.0532961 -0.029135101 0.063974001, + 0.0546159 -0.0314993 0.0614786, + 0.0546159 -0.027851 0.061844502, + 0.055787299 -0.030322799 0.059359498, + 0.055787299 -0.0267483 0.059648301, + 0.056809202 -0.0293175 0.057188299, + 0.056809202 -0.025822099 0.057407599, + 0.0576833 -0.0284776 0.054985899, + 0.0576833 -0.025077101 0.055147801, + 0.058412101 -0.0278074 0.052776899, + 0.058412101 -0.0245915 0.052877702, + 0.058998398 -0.0273802 0.050569698, + 0.058998398 -0.024253899 0.0505086, + 0.059445001 -0.027086301 0.048279598, + 0.059445001 -0.024009099 0.048033901, + 0.059757002 -0.0268708 0.045900799, + 0.059757002 -0.023881501 0.045483001, + 0.0599402 -0.026761301 0.043457702, + 0.0599402 -0.0238805 0.0428808, + 0.059999999 -0.026789701 0.040958401, + 0.059999999 -0.0240399 0.040246401, + 0.0599402 -0.026995501 0.038419299, + 0.0599402 -0.024396401 0.037599299, + 0.059757002 -0.027415199 0.035861701, + 0.059757002 -0.024979001 0.034967098, + 0.059445001 -0.0280712 0.033317901, + 0.059445001 -0.0258043 0.032382801, + 0.058998398 -0.0289542 0.0308343, + 0.058998398 -0.026854301 0.029893801, + 0.058412101 -0.0300388 0.028459201, + 0.058412101 -0.028098401 0.0275454, + 0.0576833 -0.031294599 0.026234301, + 0.0576833 -0.029497899 0.0253754, + 0.056809202 -0.032683201 0.024194499, + 0.056809202 -0.031011401 0.0234142, + 0.055787299 -0.034162801 0.022367001, + 0.055787299 -0.0325936 0.021685399, + 0.0465803 -0.0395982 0.015439, + 0.0465803 -0.039996602 0.015557, + 0.045588002 -0.040810999 0.015391, + 0.047540501 -0.0387551 0.0156187, + 0.0465803 -0.040410701 0.015628099, + 0.048467699 -0.037894402 0.0157797, + 0.048467699 -0.039513901 0.016148601, + 0.0465803 -0.0420717 0.0158883, + 0.044564299 -0.042830501 0.0154824, + 0.048467699 -0.041120999 0.016475501, + 0.050219599 -0.038433298 0.016858, + 0.050219599 -0.039989602 0.017252799, + 0.051830001 -0.037181001 0.017763801, + 0.051830001 -0.0386815 0.018250899, + 0.0532961 -0.0357625 0.018896401, + 0.0532961 -0.037216701 0.019425999, + 0.0546159 -0.0341998 0.0202053, + 0.0546159 -0.035689 0.0207731, + 0.055787299 -0.035851698 0.023019901, + 0.056809202 -0.034486402 0.0249252, + 0.0576833 -0.033230901 0.027021199, + 0.058412101 -0.032124002 0.029276, + 0.058998398 -0.0311967 0.031650901, + 0.059445001 -0.030474501 0.034100801, + 0.059757002 -0.0299742 0.0365781, + 0.0599402 -0.0296988 0.039036099, + 0.059999999 -0.0296189 0.0414479, + 0.0599402 -0.0296946 0.043795899, + 0.059757002 -0.0298885 0.0460742, + 0.059445001 -0.030151401 0.048276301, + 0.058998398 -0.0305312 0.050411601, + 0.058412101 -0.031137099 0.052560698, + 0.0576833 -0.031900201 0.054715101, + 0.056809202 -0.0328178 0.0568511, + 0.055787299 -0.0338961 0.058948699, + 0.0546159 -0.035142701 0.0609884, + 0.0532961 -0.0365634 0.062948599, + 0.051830001 -0.0381625 0.064807601, + 0.050219599 -0.039941799 0.066542499, + 0.048467699 -0.041898999 0.068137102, + 0.0465803 -0.044041801 0.069577202, + 0.044564299 -0.0463688 0.070833497, + 0.0424264 -0.048866201 0.071884997, + 0.040174201 -0.051517598 0.072714202, + 0.0378174 -0.054304499 0.073306702, + 0.035366699 -0.057209801 0.073649101, + 0.0328326 -0.060214099 0.073731102, + 0.0302257 -0.0674638 0.071951203, + 0.027557701 -0.0750532 0.070268899, + 0.0248404 -0.082948498 0.068692498, + 0.0220857 -0.091116004 0.067228198, + 0.019305199 -0.099522099 0.065881602, + 0.0165099 -0.108133 0.064660199, + 0.0137106 -0.116916 0.063569501, + 0.0109179 -0.125838 0.062614299, + 0.0081421202 -0.134866 0.061799999, + 0.0053918599 -0.14397199 0.0611341, + 0.00267513 -0.15312301 0.060622301, + 0 -0.162292 0.0602693, + -0.00267513 -0.15312301 0.0606241, + -0.0053918599 -0.14397199 0.061137199, + -0.0081421202 -0.134868 0.061803401, + -0.0109179 -0.12584101 0.062618203, + -0.0137106 -0.116921 0.063575, + -0.0165099 -0.108139 0.064668298, + -0.019305199 -0.099529497 0.065892503, + -0.0220857 -0.0911244 0.067240901, + -0.0248404 -0.082957298 0.068705298, + -0.027557701 -0.075061202 0.070279501, + -0.0302257 -0.0674688 0.071956702, + -0.0328326 -0.060214698 0.073729403, + -0.035366699 -0.0572097 0.073647998, + -0.0378174 -0.054304801 0.073303998, + -0.040174201 -0.051518299 0.0727093, + -0.0424264 -0.048867401 0.071878001, + -0.044564299 -0.04637 0.070825398, + -0.0465803 -0.044041499 0.069570497, + -0.048467699 -0.041896801 0.068133697, + -0.050219599 -0.039940599 0.066538699, + -0.051830001 -0.038161501 0.064801201, + -0.0532961 -0.036562499 0.0629391, + -0.0546159 -0.0351425 0.060975298, + -0.055787299 -0.033898398 0.058932401, + -0.056809202 -0.032825399 0.0568325, + -0.0576833 -0.031917501 0.054695901, + -0.058412101 -0.031165 0.052543499, + -0.058998398 -0.030549901 0.0503993, + -0.059445001 -0.0301496 0.0482664, + -0.059757002 -0.029890999 0.046058699, + -0.0599402 -0.0297036 0.0437732, + -0.059999999 -0.0296332 0.041420098, + -0.0599402 -0.0297183 0.039007399, + -0.059757002 -0.029997701 0.036551598, + -0.059445001 -0.030501099 0.034078199, + -0.058998398 -0.031225299 0.0316329, + -0.058412101 -0.0321537 0.0292628, + -0.0576833 -0.033260699 0.0270124, + -0.056809202 -0.034515299 0.0249203, + -0.055787299 -0.035879102 0.0230204, + -0.0546159 -0.0373099 0.0213356, + -0.0532961 -0.0387595 0.0198693, + -0.0424264 -0.045146201 0.0153396, + -0.041313998 -0.045816801 0.015261, + -0.040174201 -0.047341101 0.0152075, + -0.0424264 -0.0468821 0.0153964, + -0.044564299 -0.044531301 0.0156356, + -0.044564299 -0.046219401 0.0157474, + -0.0465803 -0.043719798 0.016102999, + -0.0465803 -0.045359898 0.016276, + -0.048467699 -0.042719498 0.0167563, + -0.048467699 -0.044305898 0.0170069, + -0.050219599 -0.041533299 0.017619999, + -0.050219599 -0.043077901 0.0178934, + -0.051830001 -0.0401836 0.0186406, + -0.051830001 -0.0409595 0.0188103, + -0.0532961 -0.037978601 0.0196336, + -0.043510102 -0.043571301 0.0153723, + -0.0424264 -0.043840699 0.0150525, + -0.043510102 -0.043161999 0.0152831, + -0.044564299 -0.041557599 0.0151215, + -0.0424264 -0.043377299 0.0147346, + -0.041313998 -0.044939399 0.0150194, + -0.0424264 -0.044295002 0.0152386, + -0.044564299 -0.042405698 0.0154301, + -0.0465803 -0.039168499 0.0151936, + -0.044564299 -0.0411047 0.0147853, + -0.0424264 -0.042965699 0.0142795, + -0.040174201 -0.045114201 0.0142455, + -0.040174201 -0.044791002 0.0137024, + -0.0378174 -0.046811301 0.0136822, + -0.0390082 -0.0479412 0.0151558, + -0.040174201 -0.046894599 0.0152076, + -0.0390082 -0.047514599 0.0151119, + -0.0378174 -0.048525099 0.0150722, + -0.0378174 -0.048051599 0.0149256, + -0.036603201 -0.049024999 0.0148962, + -0.036603201 -0.048537198 0.0146195, + -0.035366699 -0.0494726 0.0145986, + -0.035366699 -0.0490366 0.0141837, + -0.0378174 -0.047140099 0.0142136, + -0.035366699 -0.048702501 0.0136633, + -0.0328326 -0.0504581 0.0136457, + -0.027557701 -0.053337801 0.0130707, + -0.0248404 -0.0546588 0.0130649, + -0.027557701 -0.0535408 0.0136148, + -0.0302257 -0.052071799 0.0136296, + -0.0302257 -0.051870398 0.0130771, + -0.032827701 -0.050200298 0.01254, + -0.0308851 -0.0514233 0.012541, + -0.0328326 -0.050258599 0.0130843, + -0.040174201 -0.045534302 0.0146865, + -0.040174201 -0.046007998 0.0149871, + -0.041313998 -0.0453986 0.0151952, + -0.0424264 -0.044708598 0.0153159, + -0.040174201 -0.046472099 0.0151529, + -0.0390082 -0.0470456 0.0149559, + -0.0378174 -0.047568399 0.0146411, + -0.0390082 -0.048392199 0.0151443, + -0.0378174 -0.048955899 0.0151055, + -0.036603201 -0.049502902 0.0150338, + -0.035366699 -0.0499648 0.0148679, + -0.034109399 -0.0503738 0.0145785, + -0.0328326 -0.0507969 0.014156, + -0.0302257 -0.052414998 0.0141304, + -0.031537499 -0.052070301 0.0145408, + -0.027557701 -0.0538879 0.0141072, + -0.0288986 -0.053622399 0.0145062, + -0.0248404 -0.054863099 0.0136016, + -0.0220857 -0.055831399 0.0130599, + -0.0228185 -0.05548 0.0125442, + -0.0220806 -0.055762399 0.0125444, + -0.0197125 -0.056661699 0.0075451201, + -0.0200695 -0.056532301 0.012545, + -0.0165099 -0.057729501 0.0130518, + -0.019305199 -0.056854401 0.0130555, + -0.017272299 -0.057448499 0.0125457, + -0.019305199 -0.057060599 0.0135796, + -0.0220857 -0.0560368 0.0135899, + -0.0220857 -0.056390401 0.0140678, + -0.0248404 -0.055213701 0.0140863, + -0.023467001 -0.0562842 0.0144471, + -0.00814154 -0.059422798 0.0125473, + -0.0077019902 -0.059475999 0.0125474, + -0.0081428103 -0.059493799 0.0130448, + -0.0086586103 -0.059360299 0.0125473, + -0.0109179 -0.059046399 0.0130465, + -0.0109179 -0.059253599 0.0135578, + -0.0137106 -0.058666401 0.0135636, + -0.0137106 -0.059026401 0.0140263, + -0.0165099 -0.058294501 0.0140378, + -0.0165099 -0.058768 0.0143921, + -0.019305199 -0.0578865 0.0144116, + -0.019305199 -0.058419298 0.0146141, + -0.0220857 -0.057383802 0.0146451, + -0.0220857 -0.057900999 0.0147046, + -0.023467001 -0.056809001 0.0146623, + -0.00268824 -0.059990302 0.0130433, + -0.00154448 -0.059950799 0.0125477, + 0 -0.0600507 0.0130434, + -0.0026881699 -0.0599255 0.0125477, + -0.0028003999 -0.059923001 0.0125477, + -0.0053973799 -0.0598066 0.0130437, + -0.0053973799 -0.060013201 0.0135503, + -0.0081428103 -0.059700798 0.0135534, + -0.0081428103 -0.0600628 0.01401, + -0.0109179 -0.059614699 0.0140171, + -0.0109179 -0.0600935 0.0143631, + -0.0137106 -0.059502698 0.014376, + -0.0137106 -0.060043499 0.0145659, + -0.0165099 -0.059305001 0.0145878, + -0.0165099 -0.059831701 0.0146293, + -0.019305199 -0.058941599 0.014664, + -0.019305199 -0.0594147 0.0145877, + -0.0220857 -0.058369901 0.0146394, + -0.0220857 -0.058863498 0.0145148, + -0.0248404 -0.057660799 0.014587, + -0.0248404 -0.059604701 0.0141024, + -0.027557701 -0.0582272 0.0142425, + -0.027557701 -0.060136698 0.0137677, + -0.0302257 -0.058581699 0.0139889, + -0.0302257 -0.060456902 0.0135296, + -0.0328326 -0.058721799 0.0138453, + -0.0328326 -0.060556401 0.0134134, + -0.035366699 -0.058639601 0.0138373, + -0.035366699 -0.060436498 0.0134134, + -0.0378174 -0.058341101 0.0139541, + -0.0378174 -0.060130499 0.0135706, + -0.040174201 -0.057865702 0.0142381, + -0.040174201 -0.0596609 0.0139063, + -0.0424264 -0.057238299 0.0147117, + -0.0424264 -0.059053 0.0144269, + -0.044564299 -0.056487199 0.0153785, + -0.044564299 -0.058339201 0.0151472, + -0.0465803 -0.055648901 0.0162508, + -0.0465803 -0.057553299 0.016067799, + -0.048467699 -0.054759402 0.017326601, + -0.048467699 -0.0567309 0.0171804, + -0.050219599 -0.053855099 0.0185942, + -0.050219599 -0.055904899 0.0184702, + -0.051830001 -0.052969299 0.0200359, + -0.051830001 -0.0551061 0.0199163, + -0.0532961 -0.052133501 0.021627201, + -0.0532961 -0.054360699 0.0214925, + -0.0546159 -0.0513734 0.023338901, + -0.0546159 -0.0536904 0.023167601, + -0.055787299 -0.0507094 0.0251371, + -0.055787299 -0.053109899 0.0249095, + -0.056809202 -0.050154399 0.026987899, + -0.056809202 -0.052628499 0.0266847, + -0.0576833 -0.0497148 0.028856499, + -0.0576833 -0.0522517 0.0284613, + -0.058412101 -0.049394399 0.0307099, + -0.058412101 -0.051972099 0.030206, + -0.058998398 -0.049183201 0.032513998, + -0.058998398 -0.051847499 0.0319052, + -0.059445001 -0.0491409 0.034255501, + -0.059445001 -0.0519276 0.033610001, + -0.059757002 -0.049319301 0.035988498, + -0.059757002 -0.052161001 0.035311501, + -0.0599402 -0.049657699 0.0377087, + -0.0599402 -0.0525616 0.036989901, + -0.059999999 -0.050149299 0.039415099, + -0.059999999 -0.053114899 0.038647801, + -0.0599402 -0.050776001 0.0411167, + -0.0599402 -0.053801201 0.040295299, + -0.059757002 -0.051519301 0.042824201, + -0.059757002 -0.054602001 0.041942999, + -0.059445001 -0.052367099 0.044544101, + -0.059445001 -0.055505201 0.043597199, + -0.058998398 -0.053325702 0.046261799, + -0.058998398 -0.056517601 0.045242701, + -0.058412101 -0.054405101 0.0479565, + -0.058412101 -0.057644799 0.046867602, + -0.0576833 -0.0556091 0.049616601, + -0.0576833 -0.0589213 0.048464399, + -0.056809202 -0.0569693 0.051233299, + -0.056809202 -0.060359199 0.0500075, + -0.055787299 -0.058495399 0.052781101, + -0.055787299 -0.061951 0.0514751, + -0.0546159 -0.060179099 0.0542382, + -0.0546159 -0.063689202 0.052846801, + -0.0532961 -0.062012602 0.055583201, + -0.0532961 -0.065564901 0.0541007, + -0.051830001 -0.063985601 0.0567941, + -0.051830001 -0.067568801 0.0552154, + -0.050219599 -0.066088401 0.0578495, + -0.050219599 -0.0696894 0.0561698, + -0.048467699 -0.068308502 0.058729101, + -0.048467699 -0.075703003 0.055371098, + -0.0465803 -0.074477501 0.057840001, + -0.0465803 -0.0821224 0.054715399, + -0.044564299 -0.081047498 0.057085399, + -0.044564299 -0.0889211 0.054204602, + -0.0424264 -0.0879912 0.0564663, + -0.0424264 -0.0960728 0.053839199, + -0.040174201 -0.095281199 0.055983901, + -0.040174201 -0.10355 0.0536195, + -0.0378174 -0.102888 0.055640399, + -0.0378174 -0.111325 0.053546101, + -0.035366699 -0.110783 0.055436999, + -0.035366699 -0.119365 0.053617802, + -0.0328326 -0.118934 0.0553721, + -0.0328326 -0.12763999 0.053831801, + -0.0302257 -0.12730899 0.055443801, + -0.0302257 -0.13611799 0.0541857, + -0.027557701 -0.135878 0.0556526, + -0.027557701 -0.14477 0.054678801, + -0.0248404 -0.14460699 0.055998601, + -0.0248404 -0.15356199 0.055306099, + -0.0220857 -0.153466 0.056476898, + -0.019305199 -0.153382 0.057498101, + -0.0220857 -0.144462 0.057169799, + -0.0248404 -0.13566101 0.0569731, + -0.027557701 -0.127009 0.056911401, + -0.0302257 -0.118539 0.056984801, + -0.0328326 -0.110281 0.057192199, + -0.035366699 -0.102269 0.0575324, + -0.0378174 -0.094534598 0.058006302, + -0.040174201 -0.0871085 0.058613099, + -0.0424264 -0.0800201 0.059350099, + -0.044564299 -0.073298797 0.0602144, + -0.0465803 -0.066973098 0.061204001, + -0.048467699 -0.064649299 0.060410101, + -0.050219599 -0.0624425 0.0594257, + -0.051830001 -0.060366198 0.058269899, + -0.0532961 -0.058431402 0.056963701, + -0.0546159 -0.056648798 0.055528998, + -0.055787299 -0.0550276 0.053987399, + -0.056809202 -0.053576399 0.0523615, + -0.0576833 -0.052287601 0.0506768, + -0.058412101 -0.0511324 0.0489433, + -0.058998398 -0.050108101 0.047173399, + -0.059445001 -0.049206901 0.045387201, + -0.059757002 -0.048418801 0.043605, + -0.0599402 -0.047736999 0.041840401, + -0.059999999 -0.047173601 0.040087301, + -0.0599402 -0.046745501 0.038335599, + -0.059757002 -0.046463199 0.036580801, + -0.059445001 -0.046412099 0.034807399, + -0.058998398 -0.0465439 0.032953199, + -0.058412101 -0.046796899 0.031031501, + -0.0576833 -0.0471831 0.029077601, + -0.056809202 -0.047700599 0.0271252, + -0.055787299 -0.048345 0.0252108, + -0.0546159 -0.049106002 0.0233698, + -0.0532961 -0.0499648 0.0216383, + -0.051830001 -0.0508967 0.020048499, + -0.050219599 -0.051870398 0.018628201, + -0.048467699 -0.052851301 0.017398501, + -0.0465803 -0.053802401 0.0163741, + -0.044564299 -0.0546862 0.0155601, + -0.0424264 -0.055464 0.014946, + -0.040174201 -0.056102902 0.0145317, + -0.0378174 -0.056574602 0.014294, + -0.035366699 -0.056834299 0.0141887, + -0.0328326 -0.056873702 0.0142318, + -0.0302257 -0.056697 0.0143982, + -0.027557701 -0.0563059 0.0146685, + -0.0248404 -0.057172101 0.0146986, + -0.0057364102 -0.059713598 0.0125476, + -0.0077038999 -0.059495799 0.0075473799, + -0.0109157 -0.0589744 0.012547, + -0.01156 -0.058864299 0.0125469, + -0.0137106 -0.058459301 0.0130489, + -0.0165099 -0.0579363 0.0135709, + -0.019305199 -0.0574167 0.0140516, + -0.0220857 -0.0568561 0.0144344, + -0.0248404 -0.0561965 0.0146807, + -0.0144335 -0.0582265 0.0125464, + -0.0137785 -0.058371902 0.0125465, + -0.016506299 -0.0576584 0.0125459, + -0.0193008 -0.056784101 0.0125452, + -0.019710001 -0.056650098 0.0125451, + -0.0262044 -0.0550276 0.014475, + -0.027557701 -0.055364098 0.0148039, + -0.0262044 -0.055546399 0.0147001, + -0.0248404 -0.056708202 0.0147513, + -0.027557701 -0.0558227 0.0147655, + -0.0288986 -0.054636199 0.0148324, + -0.027557701 -0.054858901 0.0147208, + -0.0248404 -0.055674601 0.0144606, + -0.0302257 -0.054800801 0.0147589, + -0.0328326 -0.0550161 0.0145691, + -0.035366699 -0.055015601 0.0144961, + -0.0378174 -0.054800801 0.0145585, + -0.040174201 -0.054368898 0.0147817, + -0.0424264 -0.0537294 0.0151442, + -0.044564299 -0.0529337 0.0156918, + -0.0465803 -0.052015699 0.016447701, + -0.048467699 -0.0510104 0.0174095, + -0.050219599 -0.0499583 0.0185853, + -0.051830001 -0.048898298 0.0199672, + -0.0532961 -0.0478689 0.021537, + -0.0546159 -0.046904702 0.0232704, + -0.055787299 -0.046036702 0.0251364, + -0.056809202 -0.045288201 0.0271003, + -0.0576833 -0.0446756 0.0291239, + -0.058412101 -0.044207402 0.031170299, + -0.058998398 -0.043885998 0.0332014, + -0.059445001 -0.043711402 0.0351822, + -0.059757002 -0.043670598 0.037076298, + -0.0599402 -0.043820899 0.0388753, + -0.059999999 -0.044191401 0.040664699, + -0.0599402 -0.044689599 0.042465799, + -0.059757002 -0.0453059 0.044284601, + -0.059445001 -0.04603 0.0461265, + -0.058998398 -0.046869401 0.047977801, + -0.058412101 -0.047834702 0.049819302, + -0.0576833 -0.0489337 0.051631302, + -0.056809202 -0.0501731 0.053393301, + -0.055787299 -0.051554501 0.055091899, + -0.0546159 -0.053103901 0.056716099, + -0.0532961 -0.054827198 0.058239602, + -0.051830001 -0.056715202 0.059639901, + -0.050219599 -0.058757499 0.0608951, + -0.048467699 -0.060942501 0.061983801, + -0.0465803 -0.063257597 0.062886402, + -0.044564299 -0.065688796 0.063584201, + -0.0424264 -0.072172299 0.0624834, + -0.040174201 -0.079044901 0.061499901, + -0.0378174 -0.086276002 0.0606374, + -0.035366699 -0.0938356 0.059899502, + -0.0328326 -0.101693 0.059288401, + -0.0302257 -0.109819 0.0588056, + -0.027557701 -0.118178 0.0584529, + -0.0248404 -0.126739 0.0582323, + -0.0220857 -0.135469 0.058145098, + -0.019305199 -0.144336 0.058191501, + -0.0165099 -0.153309 0.058371499, + -0.0137106 -0.153249 0.059099499, + -0.0165099 -0.144228 0.059065402, + -0.019305199 -0.13530099 0.0591674, + -0.0220857 -0.126499 0.059404802, + -0.0248404 -0.117854 0.059774499, + -0.027557701 -0.109398 0.060274102, + -0.0302257 -0.101165 0.060902599, + -0.0328326 -0.093186803 0.061656799, + -0.035366699 -0.085496597 0.062532596, + -0.0378174 -0.078125097 0.063527003, + -0.040174201 -0.071103103 0.064637102, + -0.0424264 -0.064461499 0.065858804, + -0.044564299 -0.061919399 0.065267697, + -0.0465803 -0.059491798 0.064457901, + -0.048467699 -0.057193801 0.063447103, + -0.050219599 -0.0550384 0.062254701, + -0.051830001 -0.053038798 0.060901102, + -0.0532961 -0.051206298 0.059407599, + -0.0546159 -0.049551301 0.057797, + -0.055787299 -0.048069902 0.056095202, + -0.056809202 -0.0467383 0.054315299, + -0.0576833 -0.0455558 0.052471701, + -0.058412101 -0.0445171 0.050585002, + -0.058998398 -0.043615501 0.048675101, + -0.059445001 -0.042842198 0.046761502, + -0.059757002 -0.042186201 0.044863001, + -0.0599402 -0.041637398 0.042993799, + -0.059999999 -0.041198801 0.041152202, + -0.0599402 -0.0409653 0.039315201, + -0.059757002 -0.040909201 0.037387501, + -0.059445001 -0.0409934 0.035357501, + -0.058998398 -0.0412388 0.033257999, + -0.058412101 -0.041646302 0.0311256, + -0.0576833 -0.042215101 0.0289998, + -0.056809202 -0.042938702 0.026919501, + -0.055787299 -0.0438025 0.0249249, + -0.0546159 -0.044785101 0.0230531, + -0.0532961 -0.045856498 0.0213376, + -0.051830001 -0.0469823 0.0198061, + -0.050219599 -0.048123199 0.0184801, + -0.048467699 -0.0492386 0.0173708, + -0.0465803 -0.050286099 0.016472001, + -0.044564299 -0.051228799 0.0157896, + -0.0424264 -0.0520298 0.0152989, + -0.040174201 -0.0526287 0.0149537, + -0.0378174 -0.053013802 0.0147808, + -0.0302257 -0.054323599 0.0148397, + -0.0302257 -0.053871199 0.0148624, + -0.0288986 -0.054134302 0.0147425, + -0.027557701 -0.054343399 0.0144902, + -0.0302257 -0.053373002 0.0147654, + -0.031537499 -0.053069498 0.0148939, + -0.0328326 -0.052677002 0.0149212, + -0.0328326 -0.0522312 0.0149267, + -0.031537499 -0.052574899 0.0147894, + -0.0302257 -0.0528646 0.0145231, + -0.0328326 -0.051740602 0.0148145, + -0.034109399 -0.0513569 0.014961, + -0.036603201 -0.0503968 0.0150237, + -0.035366699 -0.051348701 0.0149665, + -0.0378174 -0.051217601 0.0149555, + -0.035366699 -0.0508858 0.0150098, + -0.034109399 -0.0517992 0.0149647, + -0.040174201 -0.0508755 0.015085, + -0.0424264 -0.050325502 0.0153727, + -0.044564299 -0.049565699 0.015843799, + -0.0465803 -0.0486123 0.0164649, + -0.048467699 -0.047532901 0.0172836, + -0.050219599 -0.0463669 0.018325301, + -0.051830001 -0.0451531 0.0195815, + -0.0532961 -0.043936599 0.0210556, + -0.0546159 -0.042758498 0.0227334, + -0.055787299 -0.0416587 0.024590001, + -0.056809202 -0.040671099 0.026595, + -0.0576833 -0.039824199 0.028712099, + -0.058412101 -0.039137401 0.030902101, + -0.058998398 -0.0386241 0.033122599, + -0.059445001 -0.038288999 0.035332602, + -0.059757002 -0.038131699 0.037490699, + -0.0599402 -0.038144 0.039563701, + -0.059999999 -0.0382808 0.041536901, + -0.0599402 -0.0385768 0.043428998, + -0.059757002 -0.039063498 0.045340899, + -0.059445001 -0.0396493 0.0472923, + -0.058998398 -0.040352002 0.049265102, + -0.058412101 -0.041185498 0.051240101, + -0.0576833 -0.0421593 0.0531983, + -0.056809202 -0.0432803 0.055120099, + -0.055787299 -0.044554502 0.056985099, + -0.0546159 -0.045986101 0.058772098, + -0.0532961 -0.047575399 0.060465299, + -0.051830001 -0.049343102 0.062050398, + -0.050219599 -0.051291399 0.063501701, + -0.048467699 -0.053408399 0.064796597, + -0.0465803 -0.055681601 0.065915003, + -0.044564299 -0.0580968 0.066836998, + -0.0424264 -0.060640302 0.067543499, + -0.040174201 -0.063296497 0.068017803, + -0.0378174 -0.070094697 0.066668101, + -0.035366699 -0.0772641 0.0654248, + -0.0328326 -0.084773101 0.064291596, + -0.0302257 -0.092590503 0.063272104, + -0.027557701 -0.100684 0.062371999, + -0.0248404 -0.109019 0.0615962, + -0.0220857 -0.117566 0.060947299, + -0.019305199 -0.126289 0.060427599, + -0.0165099 -0.135158 0.0600417, + -0.0137106 -0.14413799 0.059793901, + -0.0109179 -0.153201 0.059684999, + -0.0109156 -0.171451 0.059121899, + -0.0092316195 -0.171451 0.059411202, + -0.0109179 -0.162333 0.059270799, + -0.0081421202 -0.162315 0.059716601, + -0.0137106 -0.162358 0.058685299, + -0.016506201 -0.171452 0.057806101, + -0.0152764 -0.171452 0.0581441, + -0.0165099 -0.162388 0.057957198, + -0.019305199 -0.162425 0.057083901, + -0.0220857 -0.162468 0.056062698, + -0.021159001 -0.171454 0.0562636, + -0.0248404 -0.162517 0.054891899, + -0.0228623 -0.171454 0.055610102, + -0.027557701 -0.153671 0.0539869, + -0.0302257 -0.14495 0.053212602, + -0.0328326 -0.136383 0.052574299, + -0.035366699 -0.12799799 0.052077901, + -0.0378174 -0.119828 0.0517275, + -0.040174201 -0.111902 0.051526099, + -0.0424264 -0.104252 0.051476199, + -0.044564299 -0.096906699 0.0515798, + -0.0465803 -0.089894101 0.051837899, + -0.048467699 -0.083240204 0.052251, + -0.050219599 -0.076970503 0.052818, + -0.051830001 -0.071110003 0.053537, + -0.0532961 -0.069083802 0.0525195, + -0.0546159 -0.067173302 0.051357701, + -0.055787299 -0.065389201 0.0500728, + -0.056809202 -0.063739501 0.048686299, + -0.0576833 -0.0622329 0.047219101, + -0.058412101 -0.060876299 0.045691598, + -0.058998398 -0.0596756 0.0441253, + -0.059445001 -0.058616702 0.042546101, + -0.059757002 -0.057661399 0.040961102, + -0.0599402 -0.056807399 0.039376199, + -0.059999999 -0.0560655 0.037785798, + -0.0599402 -0.055454001 0.036178902, + -0.059757002 -0.054992601 0.034545802, + -0.059445001 -0.0546978 0.0328824, + -0.058998398 -0.054563999 0.031205799, + -0.058412101 -0.054571301 0.02954, + -0.0576833 -0.0547674 0.0278925, + -0.056809202 -0.055104699 0.026216101, + -0.055787299 -0.0555267 0.024524501, + -0.0546159 -0.056038 0.022850299, + -0.0532961 -0.056630801 0.0212247, + -0.051830001 -0.057293899 0.0196796, + -0.050219599 -0.058010601 0.018244701, + -0.048467699 -0.058758602 0.016948201, + -0.0465803 -0.059512001 0.015813099, + -0.044564299 -0.06024 0.0148574, + -0.0424264 -0.060910001 0.0140925, + -0.040174201 -0.061488502 0.0135238, + -0.0378174 -0.0619452 0.0131469, + -0.035366699 -0.0622508 0.0129457, + -0.0328326 -0.062381499 0.0129116, + -0.0302257 -0.0623184 0.0130238, + -0.027557701 -0.062036399 0.0132423, + -0.0248404 -0.061536402 0.0135686, + -0.0220857 -0.0608273 0.013978, + -0.019305199 -0.0599126 0.0144518, + -0.0165099 -0.060308401 0.0145436, + -0.0137106 -0.060573898 0.0146004, + -0.0109179 -0.0606374 0.0145484, + -0.0081428103 -0.060543399 0.0143532, + -0.0053973799 -0.060375601 0.0140051, + -0.00268824 -0.0601964 0.0135485, + 0.023037801 -0.171454 0.055537399, + 0.0248404 -0.16251899 0.054877799, + 0.0248404 -0.15356299 0.0552889, + 0.0030847499 -0.059909102 0.0125477, + 0.0046291598 -0.059791502 0.0125476, + 0.00268824 -0.059991401 0.0130441, + 0.0053973799 -0.059808701 0.0130453, + 0.0053973799 -0.0600118 0.0135506, + 0.000142344 -0.059988201 0.0125478, + 0.00268824 -0.060195699 0.0135486, + 0.0053973799 -0.060371999 0.0140054, + 0.0081428103 -0.060057402 0.0140104, + 0.0081428103 -0.060538299 0.0143552, + 0.0109179 -0.0600866 0.0143657, + 0.0109179 -0.060633499 0.0145524, + 0.0137106 -0.0600386 0.0145709, + 0.0137106 -0.060573 0.0146051, + 0.0165099 -0.059830699 0.0146349, + 0.0165099 -0.060308602 0.0145462, + 0.019305199 -0.059414901 0.0145908, + 0.019305199 -0.059911098 0.0144534, + 0.0220857 -0.0588619 0.0145167, + 0.0220857 -0.060827401 0.0139792, + 0.0248404 -0.059604801 0.0141037, + 0.0248404 -0.0615367 0.01357, + 0.027557701 -0.060137 0.0137693, + 0.027557701 -0.0620366 0.0132422, + 0.0302257 -0.0604572 0.0135295, + 0.0302257 -0.062318601 0.0130239, + 0.0328326 -0.060556602 0.0134135, + 0.0328326 -0.0623786 0.0129244, + 0.035366699 -0.060433399 0.0134272, + 0.035366699 -0.0622393 0.0129483, + 0.0378174 -0.060118299 0.0135734, + 0.0378174 -0.061928 0.0131428, + 0.040174201 -0.059642602 0.013902, + 0.040174201 -0.061468799 0.0135233, + 0.0424264 -0.059032101 0.0144265, + 0.0424264 -0.060888398 0.0140961, + 0.044564299 -0.058316499 0.0151509, + 0.044564299 -0.060217001 0.0148642, + 0.0465803 -0.0575293 0.016075, + 0.0465803 -0.0594883 0.0158237, + 0.048467699 -0.056706298 0.0171913, + 0.048467699 -0.058735099 0.016962999, + 0.050219599 -0.055880599 0.0184855, + 0.050219599 -0.0579881 0.0182638, + 0.051830001 -0.055082802 0.0199361, + 0.051830001 -0.057273299 0.0197026, + 0.0532961 -0.054339699 0.0215161, + 0.0532961 -0.056613602 0.0212503, + 0.0546159 -0.053672802 0.0231937, + 0.0546159 -0.056024998 0.0228756, + 0.055787299 -0.0530966 0.0249354, + 0.055787299 -0.055518501 0.0245455, + 0.056809202 -0.052620102 0.0267062, + 0.056809202 -0.0551023 0.026230801, + 0.0576833 -0.052249201 0.0284763, + 0.0576833 -0.054769199 0.0279021, + 0.058412101 -0.051973801 0.030215699, + 0.058412101 -0.054552801 0.029552, + 0.058998398 -0.051828802 0.031917401, + 0.058998398 -0.054535799 0.0312231, + 0.059445001 -0.051899102 0.033627398, + 0.059445001 -0.054680198 0.0329022, + 0.059757002 -0.052143302 0.035331398, + 0.059757002 -0.0549847 0.0345654, + 0.0599402 -0.052553698 0.037009601, + 0.0599402 -0.055451602 0.0361965, + 0.059999999 -0.0531126 0.038665399, + 0.059999999 -0.056065701 0.0378001, + 0.0599402 -0.053801399 0.040309701, + 0.0599402 -0.056808401 0.039386898, + 0.059757002 -0.054602899 0.041953702, + 0.059757002 -0.057662699 0.040968399, + 0.059445001 -0.055506401 0.043604501, + 0.059445001 -0.058618199 0.042550601, + 0.058998398 -0.056519099 0.045247201, + 0.058998398 -0.059678301 0.044129401, + 0.058412101 -0.0576474 0.046871699, + 0.058412101 -0.0608766 0.045700099, + 0.0576833 -0.058921698 0.048472799, + 0.0576833 -0.062231299 0.047229599, + 0.056809202 -0.0603576 0.0500178, + 0.056809202 -0.063737698 0.048695799, + 0.055787299 -0.061949302 0.051484399, + 0.055787299 -0.065388002 0.050079599, + 0.0546159 -0.063688204 0.052853499, + 0.0546159 -0.067172997 0.051361699, + 0.0532961 -0.065564603 0.0541046, + 0.0532961 -0.069083899 0.052521199, + 0.051830001 -0.067568898 0.055217002, + 0.051830001 -0.071109198 0.0535396, + 0.050219599 -0.069688603 0.0561723, + 0.050219599 -0.0769623 0.052808899, + 0.048467699 -0.075695097 0.055362299, + 0.048467699 -0.083226196 0.052232299, + 0.0465803 -0.082108997 0.054697499, + 0.0465803 -0.089877501 0.0518139, + 0.044564299 -0.0889052 0.054181602, + 0.044564299 -0.096889697 0.051554099, + 0.0424264 -0.096056603 0.053814799, + 0.0424264 -0.104235 0.051452301, + 0.040174201 -0.103535 0.053596798, + 0.040174201 -0.111887 0.0515064, + 0.0378174 -0.11131 0.0535275, + 0.0378174 -0.119815 0.051712301, + 0.035366699 -0.119353 0.0536035, + 0.035366699 -0.127988 0.052065201, + 0.0328326 -0.12763 0.053819899, + 0.0328326 -0.13637599 0.052560799, + 0.0302257 -0.136112 0.054173298, + 0.0302257 -0.14494801 0.053195201, + 0.027557701 -0.144767 0.054662999, + 0.027557701 -0.15367199 0.0539678, + 0.025727101 -0.171455 0.054340899, + 0.027557701 -0.16257399 0.053557299, + 0.0302257 -0.15379401 0.052500401, + 0.0328326 -0.145146 0.051583201, + 0.035366699 -0.136663 0.050806701, + 0.0378174 -0.128373 0.050174899, + 0.040174201 -0.120309 0.049692199, + 0.0424264 -0.112499 0.0493633, + 0.044564299 -0.104974 0.0491932, + 0.0465803 -0.097761497 0.049188599, + 0.048467699 -0.0908885 0.0493518, + 0.050219599 -0.084381603 0.049683299, + 0.051830001 -0.078265801 0.050182201, + 0.0532961 -0.072563 0.050845198, + 0.0546159 -0.070626996 0.049775701, + 0.055787299 -0.068803601 0.0485809, + 0.056809202 -0.067103803 0.047279801, + 0.0576833 -0.065535702 0.045892201, + 0.058412101 -0.064107798 0.0444373, + 0.058998398 -0.062826797 0.0429339, + 0.059445001 -0.061696298 0.0414044, + 0.059757002 -0.060695 0.039882701, + 0.0599402 -0.059790399 0.038367201, + 0.059999999 -0.0589967 0.036839999, + 0.0599402 -0.058329999 0.035290599, + 0.059757002 -0.057808802 0.0337083, + 0.059445001 -0.057448398 0.0320885, + 0.058998398 -0.057244498 0.030446701, + 0.058412101 -0.0571892 0.028803499, + 0.0576833 -0.057283301 0.027180901, + 0.056809202 -0.0575605 0.025591901, + 0.055787299 -0.057940401 0.023997201, + 0.0546159 -0.058389999 0.0224049, + 0.0532961 -0.0589136 0.0208438, + 0.051830001 -0.0595011 0.019342, + 0.050219599 -0.060139801 0.0179305, + 0.048467699 -0.060812298 0.0166381, + 0.0465803 -0.061495699 0.0154906, + 0.044564299 -0.0621638 0.0145084, + 0.0424264 -0.062785603 0.0137071, + 0.040174201 -0.063329898 0.0130947, + 0.0378174 -0.063766502 0.0126716, + 0.035366699 -0.064067602 0.0124321, + 0.0328326 -0.064208202 0.012368, + 0.0302257 -0.064166799 0.0124621, + 0.027557701 -0.063922599 0.0126692, + 0.0248404 -0.063458502 0.0129835, + 0.0220857 -0.062779203 0.0133932, + 0.019305199 -0.061894 0.0138707, + 0.0165099 -0.0608087 0.0143993, + 0.0137106 -0.061053898 0.014509, + 0.0109179 -0.061170101 0.0145811, + 0.0081428103 -0.0610868 0.0145381, + 0.0053973799 -0.0608541 0.0143478, + 0.00268824 -0.060557 0.0140024, + 0 -0.060256001 0.013548, + -0.00268824 -0.0605588 0.0140023, + -0.0053973799 -0.060857501 0.0143465, + -0.0081428103 -0.061089799 0.0145351, + -0.0109179 -0.061170802 0.0145774, + -0.0137106 -0.061053801 0.0145068, + -0.0165099 -0.06081 0.0143978, + -0.019305199 -0.061893899 0.0138696, + -0.0220857 -0.062778898 0.0133919, + -0.0248404 -0.063458301 0.0129836, + -0.027557701 -0.063922398 0.0126691, + -0.0302257 -0.064169399 0.0124504, + -0.0328326 -0.064218797 0.0123656, + -0.035366699 -0.064083703 0.0124359, + -0.0378174 -0.063785002 0.012672, + -0.040174201 -0.063350402 0.0130913, + -0.0424264 -0.0628075 0.0137006, + -0.044564299 -0.062186401 0.0144984, + -0.0465803 -0.0615183 0.0154764, + -0.048467699 -0.060834002 0.0166196, + -0.050219599 -0.060159702 0.017908201, + -0.051830001 -0.059517801 0.0193171, + -0.0532961 -0.058926299 0.0208191, + -0.0546159 -0.058398001 0.022384301, + -0.055787299 -0.0579427 0.0239827, + -0.056809202 -0.057558801 0.025582399, + -0.0576833 -0.0573016 0.027169, + -0.058412101 -0.057217099 0.0287864, + -0.058998398 -0.057262 0.0304271, + -0.059445001 -0.0574563 0.032069001, + -0.059757002 -0.057811201 0.033690799, + -0.0599402 -0.058329798 0.035276301, + -0.059999999 -0.058995701 0.0368293, + -0.0599402 -0.059789199 0.038359798, + -0.059757002 -0.060693499 0.0398781, + -0.059445001 -0.061693601 0.041400202, + -0.058998398 -0.062826499 0.042925399, + -0.058412101 -0.064109497 0.044426601, + -0.0576833 -0.065537497 0.045882601, + -0.056809202 -0.067104898 0.047272801, + -0.055787299 -0.068803899 0.048576899, + -0.0546159 -0.0706269 0.049773902, + -0.0532961 -0.072563902 0.050842602, + -0.051830001 -0.078274302 0.050191499, + -0.050219599 -0.084396198 0.0497026, + -0.048467699 -0.0909058 0.049376801, + -0.0465803 -0.097779103 0.049215399, + -0.044564299 -0.104991 0.049218401, + -0.0424264 -0.112515 0.049384099, + -0.040174201 -0.120324 0.049708501, + -0.0378174 -0.12838399 0.0501884, + -0.035366699 -0.13666999 0.0508212, + -0.0328326 -0.14514901 0.051601999, + -0.0302257 -0.15379301 0.0525214, + -0.027557701 -0.162572 0.053572901, + -0.0255554 -0.171455 0.054422099, + -0.0275521 -0.17145599 0.053421501, + -0.026817599 -0.17145599 0.053789601, + -0.026825599 -0.191456 0.053821702, + -0.0322018 -0.191458 0.050779, + -0.030220101 -0.17145699 0.051956601, + -0.032192402 -0.17145801 0.050748099, + -0.032827299 -0.17145801 0.050347701, + -0.0302257 -0.162633 0.052107502, + -0.0328326 -0.1627 0.0504978, + -0.030750699 -0.17145699 0.0516573, + -0.0328326 -0.153926 0.0509114, + -0.035366699 -0.154071 0.049159899, + -0.035366699 -0.145366 0.049849901, + -0.0378174 -0.14559799 0.047962099, + -0.0378174 -0.136979 0.048932601, + -0.040174201 -0.13731 0.046915099, + -0.040174201 -0.12879799 0.048170201, + -0.0424264 -0.129236 0.046029899, + -0.0424264 -0.120849 0.0475673, + -0.044564299 -0.121401 0.045311701, + -0.044564299 -0.113161 0.0471274, + -0.0465803 -0.113837 0.044766098, + -0.0465803 -0.105765 0.046855599, + -0.048467699 -0.106569 0.044398699, + -0.048467699 -0.098686501 0.0467567, + -0.050219599 -0.099624597 0.0442142, + -0.050219599 -0.091951899 0.046831802, + -0.051830001 -0.093028098 0.044213802, + -0.051830001 -0.085585102 0.047081102, + -0.0532961 -0.086801998 0.044397902, + -0.0532961 -0.0796085 0.047503602, + -0.0546159 -0.080967501 0.044766001, + -0.0546159 -0.0740446 0.0480984, + -0.055787299 -0.075545698 0.045316398, + -0.055787299 -0.072191097 0.046990499, + -0.056809202 -0.073770098 0.044181, + -0.056809202 -0.070449799 0.045770101, + -0.0576833 -0.072104402 0.042948298, + -0.0576833 -0.0688297 0.044458002, + -0.058412101 -0.070557103 0.041639101, + -0.058412101 -0.067338102 0.043074701, + -0.058998398 -0.069134399 0.0402737, + -0.058998398 -0.0659815 0.041640799, + -0.059445001 -0.064764403 0.040176701, + -0.037815198 -0.171461 0.0467139, + -0.0372269 -0.171461 0.047171298, + -0.0378174 -0.162852 0.0468596, + -0.035366699 -0.162774 0.0487464, + -0.0378174 -0.154227 0.047272801, + -0.040174201 -0.154393 0.045257099, + -0.040174201 -0.14584699 0.045945399, + -0.0424264 -0.146111 0.043807, + -0.0424264 -0.137661 0.044775601, + -0.044564299 -0.13803101 0.0425217, + -0.044564299 -0.129697 0.043775, + -0.0465803 -0.130178 0.041415598, + -0.0465803 -0.12198 0.0429512, + -0.048467699 -0.122582 0.040496599, + -0.048467699 -0.11454 0.042310301, + -0.050219599 -0.115266 0.039771002, + -0.050219599 -0.1074 0.041857999, + -0.051830001 -0.108256 0.039244302, + -0.051830001 -0.100589 0.0415987, + -0.0532961 -0.101577 0.0389218, + -0.0532961 -0.0941296 0.041534401, + -0.0546159 -0.095251203 0.038805399, + -0.0546159 -0.088041298 0.041665301, + -0.055787299 -0.089297697 0.038894899, + -0.055787299 -0.082345098 0.041990601, + -0.056809202 -0.0837356 0.039189301, + -0.056809202 -0.077060901 0.042508401, + -0.0576833 -0.078584097 0.039685398, + -0.0576833 -0.0753574 0.0413565, + -0.058412101 -0.0769471 0.038527999, + -0.058412101 -0.0737615 0.040122401, + -0.058998398 -0.075414501 0.037303399, + -0.058998398 -0.0722804 0.038826801, + -0.059445001 -0.070919402 0.0374902, + -0.059445001 -0.077057198 0.034502, + -0.059757002 -0.072685301 0.034736499, + -0.059757002 -0.066681698 0.037457298, + -0.0599402 -0.068573602 0.034773801, + -0.0576833 -0.059876502 0.0263611, + -0.056809202 -0.060027901 0.024801601, + -0.0576833 -0.0624291 0.0254793, + -0.058412101 -0.059842601 0.027956201, + -0.058412101 -0.062452499 0.027046001, + -0.058998398 -0.0599465 0.0295654, + -0.058998398 -0.062614501 0.0286208, + -0.059445001 -0.060199998 0.031169301, + -0.059445001 -0.062924199 0.030184301, + -0.059757002 -0.060611699 0.032747202, + -0.059757002 -0.063389398 0.031715602, + -0.0599402 -0.061184 0.034282301, + -0.0599402 -0.064011902 0.0331975, + -0.059999999 -0.0619005 0.035778601, + -0.059999999 -0.064776197 0.034633201, + -0.0599402 -0.0627428 0.037245601, + -0.059757002 -0.063689999 0.038704298, + -0.0332404 -0.171459 0.050087199, + -0.035362698 -0.17146 0.048598502, + -0.028186901 -0.17145599 0.053103399, + -0.055787299 -0.060335301 0.0232847, + -0.0546159 -0.0607544 0.021770099, + -0.0532961 -0.061230302 0.020273199, + -0.051830001 -0.061762199 0.0188249, + -0.050219599 -0.062338699 0.0174533, + -0.048467699 -0.0629455 0.016186301, + -0.0465803 -0.063564301 0.0150482, + -0.044564299 -0.064172097 0.014061, + -0.0424264 -0.0647422 0.013242, + -0.040174201 -0.0652446 0.0126027, + -0.0378174 -0.065651603 0.0121473, + -0.035366699 -0.065935098 0.0118746, + -0.0328326 -0.066068597 0.011776, + -0.0302257 -0.066027798 0.0118325, + -0.027557701 -0.065797001 0.0120305, + -0.0248404 -0.065366298 0.0123499, + -0.0220857 -0.0647204 0.012754, + -0.019305199 -0.063862696 0.0132378, + -0.0165099 -0.062806301 0.0137769, + -0.0137106 -0.061558198 0.0143529, + -0.0109179 -0.061653201 0.0144773, + -0.0081428103 -0.061625499 0.0145599, + -0.0053973799 -0.0614057 0.014526, + -0.00268824 -0.0610415 0.0143427, + 0 -0.060617998 0.0140014, + 0.00268824 -0.061039802 0.0143433, + 0.0053973799 -0.0614038 0.014528, + 0.0081428103 -0.061625 0.0145627, + 0.0109179 -0.061653301 0.014479, + 0.0137106 -0.0615572 0.0143541, + 0.0165099 -0.062806301 0.0137777, + 0.019305199 -0.063862897 0.0132389, + 0.0220857 -0.064720601 0.0127539, + 0.0248404 -0.065366499 0.01235, + 0.027557701 -0.065794602 0.0120413, + 0.0302257 -0.066018 0.0118347, + 0.0328326 -0.066053703 0.0117724, + 0.035366699 -0.065917701 0.0118742, + 0.0378174 -0.065632299 0.0121505, + 0.040174201 -0.065223902 0.0126087, + 0.0424264 -0.064720601 0.0132515, + 0.044564299 -0.064150497 0.0140746, + 0.0465803 -0.063543402 0.0150659, + 0.048467699 -0.062926397 0.016207799, + 0.050219599 -0.062322602 0.017477401, + 0.051830001 -0.061749902 0.0188489, + 0.0532961 -0.061222501 0.0202934, + 0.0546159 -0.060752101 0.0217843, + 0.055787299 -0.060337 0.023294, + 0.056809202 -0.0600099 0.0248133, + 0.0576833 -0.059848901 0.026378101, + 0.058412101 -0.0598251 0.0279755, + 0.058998398 -0.059938598 0.029584801, + 0.059445001 -0.060197599 0.0311868, + 0.059757002 -0.0606119 0.0327616, + 0.0599402 -0.061184999 0.034293, + 0.059999999 -0.0619017 0.035785999, + 0.0599402 -0.062744297 0.037250102, + 0.059757002 -0.063692696 0.0387084, + 0.059445001 -0.064764798 0.040185299, + 0.058998398 -0.065979898 0.041651599, + 0.058412101 -0.067336299 0.043084402, + 0.0576833 -0.068828598 0.044465002, + 0.056809202 -0.070449501 0.045774199, + 0.055787299 -0.072191298 0.046992201, + 0.0546159 -0.074043699 0.048101101, + 0.0532961 -0.079599798 0.047494002, + 0.051830001 -0.085570201 0.047061101, + 0.050219599 -0.091934197 0.0468059, + 0.048467699 -0.098668002 0.046728801, + 0.0465803 -0.105747 0.046829399, + 0.044564299 -0.113145 0.047105499, + 0.0424264 -0.120834 0.047550201, + 0.040174201 -0.128786 0.0481558, + 0.0378174 -0.136971 0.0489171, + 0.035366699 -0.145363 0.049829502, + 0.0328326 -0.153927 0.050888699, + 0.0302257 -0.162635 0.052090298, + 0.028354499 -0.17145599 0.053013898, + 0.041876599 -0.19146401 0.043121599, + 0.040171102 -0.171463 0.044697199, + 0.037236601 -0.191461 0.0471997, + 0.058998398 -0.078533098 0.035707999, + 0.058998398 -0.081630401 0.034040801, + 0.059445001 -0.0770569 0.034506299, + 0.058412101 -0.080108598 0.0368612, + 0.058412101 -0.086523898 0.0335421, + 0.0576833 -0.085124098 0.0363626, + 0.0576833 -0.091823801 0.0332653, + 0.056809202 -0.090549298 0.036076799, + 0.056809202 -0.097515799 0.033216801, + 0.055787299 -0.096368499 0.0360098, + 0.055787299 -0.103582 0.033399299, + 0.0546159 -0.102563 0.036164001, + 0.0546159 -0.110003 0.033814002, + 0.0532961 -0.109111 0.036539201, + 0.0532961 -0.116758 0.034459099, + 0.051830001 -0.115994 0.037133299, + 0.051830001 -0.123826 0.035326399, + 0.050219599 -0.123186 0.0379382, + 0.050219599 -0.131184 0.0364068, + 0.048467699 -0.130666 0.038944598, + 0.048467699 -0.138809 0.037690599, + 0.0465803 -0.13840701 0.040144, + 0.0465803 -0.14667501 0.0391698, + 0.044564299 -0.146384 0.041528501, + 0.044564299 -0.15475801 0.040836301, + 0.0424264 -0.154571 0.043090001, + 0.0424264 -0.163029 0.042682599, + 0.040347401 -0.171463 0.044544701, + 0.0418665 -0.171464 0.043095, + 0.040174201 -0.16294 0.0448213, + 0.0378174 -0.162855 0.046838101, + 0.035366699 -0.16277599 0.048726302, + 0.037225999 -0.171461 0.047170199, + 0.0378174 -0.154228 0.047246601, + 0.058998398 -0.072279297 0.038833998, + 0.058998398 -0.075414203 0.037307601, + 0.059445001 -0.070917502 0.037500098, + 0.058412101 -0.073761202 0.040126599, + 0.058412101 -0.076947302 0.038529798, + 0.0576833 -0.075357601 0.0413584, + 0.0576833 -0.078583099 0.0396882, + 0.056809202 -0.077059999 0.042511199, + 0.056809202 -0.083726302 0.039179102, + 0.055787299 -0.082336001 0.041980602, + 0.055787299 -0.089281499 0.038873501, + 0.0546159 -0.088025503 0.041644301, + 0.0546159 -0.095231801 0.038777102, + 0.0532961 -0.094110601 0.041506801, + 0.0532961 -0.101557 0.038891099, + 0.051830001 -0.10057 0.041568801, + 0.051830001 -0.108236 0.039215099, + 0.050219599 -0.107381 0.041829601, + 0.050219599 -0.115247 0.0397464, + 0.048467699 -0.114521 0.042286601, + 0.048467699 -0.122565 0.040477101, + 0.0465803 -0.121964 0.042932399, + 0.0465803 -0.130165 0.041398901, + 0.044564299 -0.129684 0.0437591, + 0.044564299 -0.13802201 0.042503402, + 0.0424264 -0.13765299 0.044758201, + 0.0424264 -0.146108 0.0437827, + 0.040174201 -0.145844 0.045922302, + 0.040174201 -0.154394 0.045229301, + 0.038121 -0.171461 0.046470001, + 0.059757002 -0.072683401 0.034746502, + 0.059757002 -0.069680303 0.036144901, + 0.0599402 -0.0685739 0.034782499, + 0.0599402 -0.066811197 0.032025501, + 0.0599402 -0.072328597 0.0294571, + 0.059757002 -0.068860501 0.0293929, + 0.059757002 -0.066140898 0.030603601, + 0.059445001 -0.068297103 0.027967401, + 0.059445001 -0.065625302 0.029125201, + 0.058998398 -0.067884304 0.0264959, + 0.058998398 -0.065261804 0.027608, + 0.058412101 -0.067614101 0.025000799, + 0.058412101 -0.065042101 0.026073201, + 0.0576833 -0.0674778 0.023502, + 0.0576833 -0.064956799 0.0245395, + 0.056809202 -0.067465201 0.022017499, + 0.056809202 -0.064995103 0.023025, + 0.055787299 -0.065146796 0.0215471, + 0.055787299 -0.067564502 0.020564601, + 0.0546159 -0.065408997 0.020125, + 0.055787299 -0.0699604 0.0195089, + 0.056809202 -0.069909997 0.020934699, + 0.0576833 -0.069972001 0.022387501, + 0.058412101 -0.070157699 0.023849901, + 0.058998398 -0.070476599 0.025302799, + 0.059445001 -0.070937201 0.026725, + 0.059757002 -0.074220397 0.0267737, + 0.0599402 -0.077884197 0.0266366, + 0.059999999 -0.076155096 0.029332999, + 0.059999999 -0.081876896 0.0262865, + 0.0599402 -0.080285601 0.0290001, + 0.0599402 -0.086114898 0.0257298, + 0.059757002 -0.084638603 0.028465699, + 0.059757002 -0.090680897 0.0251662, + 0.059445001 -0.089308001 0.027932299, + 0.059445001 -0.095639102 0.0248498, + 0.058998398 -0.094373703 0.0276409, + 0.058998398 -0.100977 0.0247916, + 0.058412101 -0.099824503 0.0275969, + 0.058412101 -0.106681 0.0249942, + 0.0576833 -0.105644 0.027803499, + 0.0576833 -0.112734 0.025459601, + 0.056809202 -0.111818 0.0282628, + 0.056809202 -0.119122 0.026187601, + 0.055787299 -0.118325 0.0289743, + 0.055787299 -0.12582301 0.0271715, + 0.0546159 -0.125148 0.029931299, + 0.0546159 -0.132819 0.0284032, + 0.0532961 -0.132263 0.031124201, + 0.0532961 -0.14008901 0.0298732, + 0.051830001 -0.139652 0.032543998, + 0.051830001 -0.14761101 0.031571999, + 0.050219599 -0.14729001 0.034180898, + 0.050219599 -0.15536501 0.033490799, + 0.048467699 -0.155155 0.036026299, + 0.0465803 -0.163222 0.038072299, + 0.044564299 -0.163123 0.0404297, + 0.0460645 -0.171468 0.038564902, + 0.0465803 -0.154953 0.0384783, + 0.048467699 -0.14697701 0.036717001, + 0.050219599 -0.13922399 0.035153698, + 0.051830001 -0.13171799 0.033796102, + 0.0532961 -0.12448 0.032653399, + 0.0546159 -0.117536 0.031735402, + 0.055787299 -0.110906 0.0310513, + 0.056809202 -0.10461 0.030608799, + 0.0576833 -0.098669298 0.0304089, + 0.058412101 -0.093100302 0.030449601, + 0.058998398 -0.087920398 0.030728299, + 0.059445001 -0.083142601 0.031238301, + 0.059757002 -0.078681998 0.031734899, + 0.0599402 -0.074425898 0.032029301, + 0.059999999 -0.0704512 0.032119799, + 0.059999999 -0.067617603 0.0334085, + 0.042476799 -0.17146499 0.042512499, + 0.044503901 -0.17146599 0.040378299, + 0.0424252 -0.17146499 0.042561699, + 0.0378129 -0.171461 0.046711002, + 0.0358027 -0.17146 0.0482838, + 0.032825802 -0.17145801 0.050345398, + 0.0322018 -0.191458 0.050779, + 0.033398401 -0.171459 0.049981698, + 0.035360798 -0.17146 0.048595902, + 0.0378174 -0.048956402 0.0151115, + 0.0378174 -0.048522599 0.0150851, + 0.0390082 -0.0479417 0.0151619, + 0.0378174 -0.049408101 0.0150862, + 0.035366699 -0.050886199 0.0150154, + 0.040174201 -0.047338098 0.0152109, + 0.040174201 -0.049113501 0.0151716, + 0.0424264 -0.046882302 0.0153987, + 0.0424264 -0.048608501 0.01541, + 0.044564299 -0.0462198 0.01575, + 0.044564299 -0.047899298 0.0158139, + 0.0465803 -0.045360301 0.016275801, + 0.0465803 -0.046987601 0.0164141, + 0.048467699 -0.044306301 0.017007099, + 0.048467699 -0.045887198 0.017185999, + 0.050219599 -0.043073598 0.017913001, + 0.050219599 -0.044669501 0.0181264, + 0.051830001 -0.041740201 0.018989701, + 0.051830001 -0.043389302 0.019301601, + 0.0532961 -0.042087302 0.020708101, + 0.0030374301 -0.171451 0.0600596, + 0.00308863 -0.171451 0.060055699, + 0.00267513 -0.162295 0.060208701, + 0.0053918599 -0.162303 0.060024898, + 0.0053918599 -0.153138 0.060438201, + 0.0081421202 -0.153165 0.060125101, + 0.0081421202 -0.14401001 0.060821, + 0.0109179 -0.14406399 0.060373299, + 0.0109179 -0.13494 0.061352499, + 0.0137106 -0.13503499 0.060764998, + 0.0137106 -0.125957 0.062026799, + 0.0165099 -0.12610599 0.0612964, + 0.0165099 -0.117094 0.0628388, + 0.019305199 -0.117308 0.061962601, + 0.019305199 -0.108383 0.063783497, + 0.0220857 -0.108675 0.062758699, + 0.0220857 -0.099856801 0.064856, + 0.0248404 -0.100241 0.0636805, + 0.0248404 -0.091548897 0.066051804, + 0.027557701 -0.092036903 0.064726703, + 0.027557701 -0.083492696 0.067366198, + 0.0302257 -0.084097303 0.065892898, + 0.0302257 -0.075721398 0.068793803, + 0.0328326 -0.076455303 0.067173697, + 0.0328326 -0.068268903 0.070328496, + 0.035366699 -0.0691448 0.068563201, + 0.035366699 -0.061168801 0.071961798, + 0.0378174 -0.062197201 0.070055902, + 0.0378174 -0.0582816 0.071741998, + 0.040174201 -0.059426401 0.069705002, + 0.040174201 -0.055498 0.071271598, + 0.0424264 -0.056763399 0.069113597, + 0.0424264 -0.052836701 0.070561603, + 0.044564299 -0.054226499 0.068293698, + 0.044564299 -0.050314799 0.069626302, + 0.0465803 -0.051830601 0.067262597, + 0.0465803 -0.047948498 0.068482898, + 0.048467699 -0.049591199 0.0660384, + 0.048467699 -0.0457533 0.067149997, + 0.050219599 -0.047522899 0.06464, + 0.050219599 -0.0437418 0.065648697, + 0.051830001 -0.0456376 0.063088901, + 0.051830001 -0.041913699 0.064009398, + 0.0532961 -0.043931998 0.061416801, + 0.0532961 -0.040258002 0.062245999, + 0.0546159 -0.042392101 0.059636999, + 0.0546159 -0.038775299 0.060374301, + 0.055787299 -0.041017801 0.0577645, + 0.055787299 -0.037462901 0.058416899, + 0.056809202 -0.039804898 0.0558214, + 0.056809202 -0.0363153 0.056395199, + 0.0576833 -0.038747601 0.053828198, + 0.0576833 -0.035326201 0.054329298, + 0.058412101 -0.037838198 0.051803902, + 0.058412101 -0.034486901 0.0522383, + 0.058998398 -0.037067398 0.0497673, + 0.058998398 -0.033790201 0.0501412, + 0.059445001 -0.0364266 0.047736999, + 0.059445001 -0.033237699 0.0480613, + 0.059757002 -0.035915501 0.045736, + 0.059757002 -0.032892901 0.046007399, + 0.0599402 -0.0355982 0.043768499, + 0.0599402 -0.032653801 0.043898098, + 0.059999999 -0.0353976 0.0417387, + 0.059999999 -0.032496799 0.041707098, + 0.0599402 -0.035298899 0.039618202, + 0.0599402 -0.0324765 0.039438199, + 0.059757002 -0.035356399 0.037412699, + 0.059757002 -0.032630801 0.037098698, + 0.059445001 -0.035601798 0.0351354, + 0.059445001 -0.032992698 0.034712199, + 0.058998398 -0.0360438 0.0328261, + 0.058998398 -0.033566799 0.032320902, + 0.058412101 -0.036678798 0.0305296, + 0.058412101 -0.034342099 0.0299732, + 0.0576833 -0.0374952 0.0282916, + 0.0576833 -0.035301398 0.0277139, + 0.056809202 -0.038474299 0.026154101, + 0.056809202 -0.036418401 0.025585201, + 0.055787299 -0.0395891 0.0241568, + 0.055787299 -0.037661199 0.0236229, + 0.0546159 -0.040806599 0.0223327, + 0.0546159 -0.038990799 0.021856099, + 0.0532961 -0.0387422 0.019873301, + 0.051830001 -0.0401791 0.0186607, + 0.050219599 -0.041533701 0.0176202, + 0.048467699 -0.042719901 0.016756199, + 0.0465803 -0.043720301 0.0161057, + 0.044564299 -0.044531502 0.015637999, + 0.0424264 -0.045143001 0.0153432, + 0.041313998 -0.0458172 0.0152676, + 0.033437699 -0.049807198 0.0125397, + 0.032825399 -0.0501968 0.01254, + 0.033494599 -0.049773 0.0075396402, + 0.024833901 -0.054589801 0.0125435, + 0.0226037 -0.055571798 0.0075442502, + 0.025769901 -0.054172501 0.0125431, + 0.0230815 -0.055371098 0.0125441, + 0.0248404 -0.054668799 0.0130721, + 0.027557701 -0.053348899 0.0130787, + 0.027557701 -0.053533401 0.013616, + 0.0302257 -0.0520637 0.0136309, + 0.0302257 -0.052395001 0.0141319, + 0.027557701 -0.053869698 0.0141086, + 0.0248404 -0.054856502 0.0136027, + 0.0220857 -0.055840299 0.0130663, + 0.0225999 -0.0555581 0.0125442, + 0.0220796 -0.0557601 0.0125444, + 0.0203376 -0.056436501 0.0125449, + 0.019300001 -0.056781799 0.0125452, + 0.0167691 -0.0576014 0.0075458698, + 0.0175448 -0.057365902 0.0125457, + 0.019305199 -0.056862101 0.0130611, + 0.0220857 -0.056030899 0.0135908, + 0.0248404 -0.055197299 0.0140876, + 0.0220857 -0.057899602 0.0147121, + 0.019305199 -0.058940299 0.0146705, + 0.020698 -0.057913002 0.0146367, + 0.0220857 -0.058370199 0.0146429, + 0.0248404 -0.057172399 0.0147025, + 0.0248404 -0.057659 0.0145892, + 0.027557701 -0.056303799 0.0146708, + 0.027557701 -0.058227301 0.014244, + 0.0302257 -0.0566971 0.0143998, + 0.0302257 -0.058582101 0.0139906, + 0.0328326 -0.0568741 0.0142337, + 0.0328326 -0.058722101 0.0138452, + 0.035366699 -0.056834601 0.0141886, + 0.035366699 -0.058639899 0.0138374, + 0.0378174 -0.0565749 0.0142941, + 0.0378174 -0.0583378 0.0139689, + 0.040174201 -0.056099299 0.0145473, + 0.040174201 -0.0578527 0.0142411, + 0.0424264 -0.055450201 0.0149492, + 0.0424264 -0.057219099 0.014707, + 0.044564299 -0.054666001 0.0155551, + 0.044564299 -0.056465399 0.015378, + 0.0465803 -0.053779501 0.016373601, + 0.0465803 -0.0556252 0.016254799, + 0.048467699 -0.052826598 0.017402699, + 0.048467699 -0.054734401 0.017333999, + 0.050219599 -0.0518445 0.018635901, + 0.050219599 -0.053829599 0.0186055, + 0.051830001 -0.050870299 0.0200602, + 0.051830001 -0.052944198 0.020051699, + 0.0532961 -0.049938899 0.0216546, + 0.0532961 -0.052109599 0.0216475, + 0.0546159 -0.049081501 0.0233906, + 0.0546159 -0.051351901 0.0233631, + 0.055787299 -0.048323002 0.025235601, + 0.055787299 -0.0506914 0.0251639, + 0.056809202 -0.0476822 0.027152499, + 0.056809202 -0.050140802 0.0270143, + 0.0576833 -0.047169302 0.0291043, + 0.0576833 -0.049706299 0.0288783, + 0.058412101 -0.046788301 0.031053601, + 0.058412101 -0.049391899 0.030725099, + 0.058998398 -0.0465414 0.032968499, + 0.058998398 -0.049185 0.0325238, + 0.059445001 -0.046413898 0.034817301, + 0.059445001 -0.049121998 0.034267802, + 0.059757002 -0.046444301 0.036593199, + 0.059757002 -0.049290702 0.0360061, + 0.0599402 -0.046716802 0.038353302, + 0.0599402 -0.049639899 0.0377285, + 0.059999999 -0.047155801 0.040107202, + 0.059999999 -0.050141301 0.039434802, + 0.0599402 -0.047729 0.0418601, + 0.0599402 -0.050773598 0.041134302, + 0.059757002 -0.048416398 0.043622501, + 0.059757002 -0.051519498 0.0428386, + 0.059445001 -0.049207099 0.045401499, + 0.059445001 -0.052368 0.0445548, + 0.058998398 -0.0501091 0.047183901, + 0.058998398 -0.053326901 0.0462691, + 0.058412101 -0.051133499 0.048950501, + 0.058412101 -0.054406501 0.047961, + 0.0576833 -0.052289002 0.0506813, + 0.0576833 -0.0556117 0.049620599, + 0.056809202 -0.053578999 0.0523655, + 0.056809202 -0.056969602 0.051241498, + 0.055787299 -0.055027898 0.053995501, + 0.055787299 -0.0584938 0.052791201, + 0.0546159 -0.056647301 0.0555389, + 0.0546159 -0.060177501 0.054247301, + 0.0532961 -0.0584298 0.056972601, + 0.0532961 -0.0620116 0.055589698, + 0.051830001 -0.0603652 0.058276199, + 0.051830001 -0.0639854 0.056797799, + 0.050219599 -0.062442299 0.059429299, + 0.050219599 -0.066088498 0.057851098, + 0.048467699 -0.064649403 0.060411699, + 0.048467699 -0.068307698 0.0587315, + 0.0465803 -0.0669723 0.0612064, + 0.0465803 -0.074469797 0.0578316, + 0.044564299 -0.073291399 0.060206302, + 0.044564299 -0.081034496 0.057068098, + 0.0424264 -0.080007799 0.059333701, + 0.0424264 -0.087976098 0.056444399, + 0.040174201 -0.087094203 0.058592301, + 0.040174201 -0.095265903 0.0559608, + 0.0378174 -0.094520301 0.057984501, + 0.0378174 -0.102874 0.055619001, + 0.035366699 -0.102256 0.057512399, + 0.035366699 -0.11077 0.055419698, + 0.0328326 -0.110269 0.057176098, + 0.0328326 -0.118922 0.055358902, + 0.0302257 -0.118528 0.056972601, + 0.0302257 -0.12730099 0.055433001, + 0.027557701 -0.127001 0.056901399, + 0.027557701 -0.13587201 0.055641301, + 0.0248404 -0.135656 0.0569629, + 0.0248404 -0.144605 0.0559843, + 0.0220857 -0.14445999 0.057157099, + 0.0220857 -0.153466 0.056461599, + 0.019305199 -0.153382 0.057484601, + 0.019305199 -0.16242599 0.0570729, + 0.0165099 -0.162389 0.0579478, + 0.0174994 -0.171453 0.0575279, + 0.0109179 -0.162334 0.0592646, + 0.0117927 -0.171452 0.058966201, + 0.0137106 -0.162359 0.058677498, + 0.0137106 -0.153249 0.05909, + 0.0081421202 -0.16231599 0.059712, + 0.0092321504 -0.171451 0.059414402, + 0.0109179 -0.153201 0.0596774, + 0.0137106 -0.144137 0.059785999, + 0.0165099 -0.144226 0.059055898, + 0.0165099 -0.13515399 0.060034901, + 0.019305199 -0.135297 0.059159499, + 0.019305199 -0.126283 0.060420699, + 0.0220857 -0.12649199 0.0593969, + 0.0220857 -0.117558 0.060938399, + 0.0248404 -0.117845 0.0597644, + 0.0248404 -0.10901 0.061584, + 0.027557701 -0.109388 0.060260601, + 0.027557701 -0.100673 0.062356401, + 0.0302257 -0.101153 0.0608855, + 0.0302257 -0.092578903 0.063254699, + 0.0328326 -0.093174301 0.061637901, + 0.0328326 -0.0847615 0.064274698, + 0.035366699 -0.085484102 0.062514298, + 0.035366699 -0.077253804 0.065411098, + 0.0378174 -0.078114301 0.0635124, + 0.0378174 -0.070088401 0.066661298, + 0.040174201 -0.071096502 0.064629897, + 0.040174201 -0.063295901 0.068019897, + 0.0424264 -0.064460799 0.065860897, + 0.0424264 -0.060640398 0.0675449, + 0.044564299 -0.061919499 0.065269202, + 0.044564299 -0.058096599 0.066840202, + 0.0465803 -0.059491601 0.064461201, + 0.0465803 -0.0556807 0.065920703, + 0.048467699 -0.057193 0.063452996, + 0.048467699 -0.053406902 0.064804703, + 0.050219599 -0.055036802 0.062263101, + 0.050219599 -0.051289901 0.063510798, + 0.051830001 -0.053037401 0.060910601, + 0.051830001 -0.0493434 0.062057901, + 0.0532961 -0.0512066 0.0594154, + 0.0532961 -0.047577798 0.060469002, + 0.0546159 -0.0495538 0.0578008, + 0.0546159 -0.045987502 0.0587763, + 0.055787299 -0.048071299 0.056099501, + 0.055787299 -0.044555701 0.056992002, + 0.056809202 -0.0467395 0.054322299, + 0.056809202 -0.043281302 0.055130299, + 0.0576833 -0.045556799 0.052482001, + 0.0576833 -0.0421593 0.053212099, + 0.058412101 -0.044517301 0.050599001, + 0.058412101 -0.0411832 0.051257301, + 0.058998398 -0.043613002 0.048692401, + 0.058998398 -0.040344201 0.049284499, + 0.059445001 -0.042834401 0.046781, + 0.059445001 -0.039631501 0.047311999, + 0.059757002 -0.042168502 0.0448828, + 0.059757002 -0.039034899 0.045358501, + 0.0599402 -0.041608799 0.0430113, + 0.0599402 -0.038557801 0.0434414, + 0.059999999 -0.041179799 0.041164599, + 0.059999999 -0.038282599 0.041546799, + 0.0599402 -0.040967099 0.039325099, + 0.0599402 -0.0381415 0.039579298, + 0.059757002 -0.040906601 0.037403099, + 0.059757002 -0.038122799 0.0375132, + 0.059445001 -0.0409845 0.035379902, + 0.059445001 -0.038274899 0.035360102, + 0.058998398 -0.0412248 0.033285301, + 0.058998398 -0.038605101 0.0331508, + 0.058412101 -0.0416274 0.031153699, + 0.058412101 -0.039114401 0.0309281, + 0.0576833 -0.042192299 0.029025299, + 0.0576833 -0.0397982 0.028734, + 0.056809202 -0.042913198 0.0269411, + 0.056809202 -0.040643599 0.0266123, + 0.055787299 -0.043775398 0.024941999, + 0.055787299 -0.041630398 0.024602599, + 0.0546159 -0.0447574 0.023065399, + 0.0546159 -0.042730398 0.0227417, + 0.0532961 -0.045829002 0.0213458, + 0.0532961 -0.043909501 0.0210601, + 0.051830001 -0.046955999 0.0198105, + 0.051830001 -0.045127701 0.019580901, + 0.050219599 -0.048098601 0.018479601, + 0.050219599 -0.046344101 0.0183198, + 0.048467699 -0.049216598 0.0173655, + 0.048467699 -0.047517199 0.0172871, + 0.0465803 -0.050271001 0.016475501, + 0.0465803 -0.048608299 0.016483, + 0.044564299 -0.051224899 0.0158069, + 0.044564299 -0.049566001 0.015844001, + 0.0424264 -0.052030101 0.015299, + 0.0424264 -0.0503259 0.0153726, + 0.040174201 -0.052629098 0.0149535, + 0.040174201 -0.050875999 0.0150873, + 0.0378174 -0.053014301 0.014783, + 0.0378174 -0.051217798 0.0149574, + 0.035366699 -0.053187702 0.014757, + 0.035366699 -0.051346101 0.0149695, + 0.0328326 -0.053144898 0.0148611, + 0.0328326 -0.0526774 0.0149264, + 0.0302257 -0.054324001 0.0148444, + 0.031537499 -0.053067401 0.0149046, + 0.027557701 -0.055822998 0.0147698, + 0.0288986 -0.054634299 0.0148422, + 0.0302257 -0.054798499 0.0147615, + 0.0328326 -0.055016201 0.0145708, + 0.035366699 -0.055016 0.0144981, + 0.0378174 -0.0548012 0.0145584, + 0.040174201 -0.054369301 0.0147818, + 0.0424264 -0.053725701 0.0151607, + 0.044564299 -0.052919298 0.015695, + 0.0465803 -0.051994499 0.016442601, + 0.048467699 -0.050986599 0.017409001, + 0.050219599 -0.0499328 0.018589601, + 0.051830001 -0.048871499 0.0199751, + 0.0532961 -0.047841799 0.0215491, + 0.0546159 -0.0468782 0.023287, + 0.055787299 -0.046011701 0.0251575, + 0.056809202 -0.045265801 0.0271255, + 0.0576833 -0.0446571 0.0291516, + 0.058412101 -0.044193499 0.0311973, + 0.058998398 -0.0438773 0.0332237, + 0.059445001 -0.043708902 0.035197701, + 0.059757002 -0.043672401 0.0370862, + 0.0599402 -0.0438019 0.038887698, + 0.059999999 -0.044162702 0.040682301, + 0.0599402 -0.0446718 0.0424858, + 0.059757002 -0.045297898 0.0443042, + 0.059445001 -0.046027601 0.046143901, + 0.058998398 -0.046869598 0.047991902, + 0.058412101 -0.0478356 0.0498298, + 0.0576833 -0.048934899 0.051638398, + 0.056809202 -0.050174501 0.0533976, + 0.055787299 -0.051557101 0.055095799, + 0.0546159 -0.053104199 0.056724001, + 0.0532961 -0.054825801 0.058249298, + 0.051830001 -0.0567136 0.059648599, + 0.050219599 -0.058756601 0.060901199, + 0.048467699 -0.0609423 0.061987299, + 0.0465803 -0.063257702 0.0628879, + 0.044564299 -0.065688103 0.063586399, + 0.0424264 -0.072165303 0.0624757, + 0.040174201 -0.079033203 0.0614843, + 0.0378174 -0.086262599 0.060617901, + 0.035366699 -0.0938223 0.059879199, + 0.0328326 -0.101681 0.059269901, + 0.0302257 -0.109808 0.058790699, + 0.027557701 -0.118169 0.058441799, + 0.0248404 -0.12673201 0.0582234, + 0.0220857 -0.135464 0.058136001, + 0.019305199 -0.144334 0.058180399, + 0.0165099 -0.15331 0.058359999, + 0.015277 -0.171452 0.058146399, + 0.0262044 -0.056053199 0.0147857, + 0.0248404 -0.055658899 0.0144666, + 0.023467001 -0.0562694 0.0144528, + 0.0248404 -0.0561876 0.0146898, + 0.0262044 -0.055537 0.0147098, + 0.027557701 -0.055362299 0.0148133, + 0.027557701 -0.054848999 0.014731, + 0.0262044 -0.055011101 0.0144813, + 0.027557701 -0.054326098 0.0144969, + 0.0288986 -0.054124001 0.0147532, + 0.0302257 -0.053869199 0.0148727, + 0.0302257 -0.053362101 0.0147766, + 0.0288986 -0.0536041 0.0145132, + 0.0302257 -0.0528455 0.0145304, + 0.031537499 -0.0525636 0.0148011, + 0.0328326 -0.052229099 0.0149379, + 0.034109399 -0.051354699 0.0149727, + 0.0328326 -0.0517288 0.0148266, + 0.031537499 -0.052050401 0.0145484, + 0.0328326 -0.0507752 0.0141576, + 0.035366699 -0.049013302 0.0141855, + 0.0378174 -0.047115099 0.0142155, + 0.036603201 -0.048514102 0.0146283, + 0.035366699 -0.048693102 0.0136648, + 0.040174201 -0.045087699 0.0142476, + 0.0390082 -0.046542499 0.0146729, + 0.0378174 -0.046801101 0.0136839, + 0.035366699 -0.0485195 0.0131023, + 0.0328326 -0.050271802 0.0130938, + 0.033493701 -0.049767699 0.0125396, + 0.030218599 -0.051805999 0.0125413, + 0.0281986 -0.052953102 0.0075421701, + 0.030954201 -0.051387198 0.0125409, + 0.0283962 -0.052843399 0.0125421, + 0.0302257 -0.051882599 0.0130859, + 0.0328326 -0.050449301 0.0136471, + 0.034109399 -0.050352301 0.0145868, + 0.028196299 -0.052944601 0.0125422, + 0.0275509 -0.053271201 0.0125424, + -0.059692498 -0.0060553099 0.0125048, + -0.059744101 -0.0053848098 0.0125043, + -0.059682 -0.00616168 0.0075049102, + -0.058998398 -0.0109309 0.0132639, + -0.0587232 -0.0122597 0.0125098, + -0.058412101 -0.0137252 0.0132509, + -0.058998398 -0.0110715 0.0140405, + -0.059445001 -0.0082903402 0.0140684, + -0.059445001 -0.0085070599 0.0148236, + -0.059757002 -0.0060091098 0.0155714, + -0.0546159 0.0127807 0.049533501, + -0.055787299 0.0107478 0.0468385, + -0.0546159 0.0116027 0.050773598, + -0.0532961 0.0146871 0.052289899, + -0.0532961 0.0134315 0.053543501, + -0.051830001 0.0164496 0.055089999, + -0.051830001 0.0151149 0.056348599, + -0.050219599 0.0180513 0.057914801, + -0.050219599 0.016636699 0.0591694, + -0.048467699 0.019477099 0.060744099, + -0.048467699 0.0179836 0.061985999, + -0.0465803 0.0207147 0.063558199, + -0.0465803 0.0191443 0.0647787, + -0.044564299 0.021754 0.066336401, + -0.044564299 0.0201093 0.067526303, + -0.0424264 0.022585901 0.069057398, + -0.0424264 0.020870199 0.070207603, + -0.040174201 0.0232033 0.071699701, + -0.040174201 0.0214216 0.072802603, + -0.0378174 0.0236036 0.074244797, + -0.0378174 0.021761701 0.075293101, + -0.035366699 0.023786901 0.076674797, + -0.035366699 0.021891 0.077661097, + -0.0328326 0.0237536 0.078971401, + -0.0328326 0.021810699 0.079889096, + -0.0302257 0.023506399 0.081117898, + -0.0302257 0.021522401 0.081962302, + -0.027557701 0.0230508 0.083102003, + -0.027557701 0.021032 0.0838691, + -0.0248404 0.022393599 0.084912904, + -0.0248404 0.020346699 0.085599303, + -0.0220857 0.0215423 0.086540699, + -0.0220857 0.019477 0.087142996, + -0.019305199 0.020508699 0.087976404, + -0.019305199 0.0184473 0.088489696, + -0.0165099 0.01932 0.089212298, + -0.0165099 0.0172497 0.089640997, + -0.0137106 0.0179695 0.0902512, + -0.0137106 0.015781401 0.0906303, + -0.0109179 0.0163536 0.091127098, + -0.0109179 0.0118731 0.091787003, + -0.0081421202 0.0122981 0.092174299, + -0.0081421202 0.0077637001 0.092693999, + -0.0053918599 0.0080525 0.092970498, + -0.0053918599 0.00347784 0.093335703, + -0.00267513 0.00364236 0.093501396, + -0.00267513 -0.00096041098 0.093706504, + 0 -0.00090833602 0.093761899, + 0 -0.0055275899 0.093803801, + 0.00267513 -0.00096032 0.093707301, + 0.00267513 0.0036427299 0.093502201, + 0.0053918599 0.0034785401 0.093337499, + 0.0053918599 0.0080541195 0.092972301, + 0.0081421202 0.0077661402 0.0926966, + 0.0081421202 0.012302 0.092176698, + 0.0109179 0.0118783 0.091790304, + 0.0109179 0.0163571 0.091129303, + 0.0137106 0.0157857 0.090633102, + 0.0137106 0.017970299 0.090253398, + 0.0165099 0.017250599 0.089643702, + 0.0165099 0.019319501 0.0892151, + 0.019305199 0.018446701 0.0884929, + 0.019305199 0.0205085 0.0879803, + 0.0220857 0.019476701 0.087147497, + 0.0220857 0.0215433 0.086546503, + 0.0248404 0.0203477 0.0856058, + 0.0248404 0.022396 0.084920801, + 0.027557701 0.021034701 0.083877899, + 0.027557701 0.0230549 0.083112396, + 0.0302257 0.021526899 0.081973702, + 0.0302257 0.0235123 0.081130803, + 0.0328326 0.021817001 0.0799032, + 0.0328326 0.0237615 0.0789866, + 0.035366699 0.021899501 0.077677503, + 0.035366699 0.023796899 0.076691702, + 0.0378174 0.0217724 0.075311199, + 0.0378174 0.0236158 0.074262999, + 0.040174201 0.021434501 0.072821803, + 0.040174201 0.0232177 0.071718402, + 0.0424264 0.020885499 0.070227399, + 0.0424264 0.0226027 0.069076203, + 0.044564299 0.0201269 0.067546003, + 0.044564299 0.021772901 0.066354901, + 0.0465803 0.019164 0.064797997, + 0.0465803 0.020735599 0.063575901, + 0.048467699 0.0180053 0.062004499, + 0.048467699 0.019499799 0.0607608, + 0.050219599 0.0166602 0.0591866, + 0.050219599 0.018075701 0.057930101, + 0.051830001 0.0151401 0.056364398, + 0.051830001 0.016475501 0.055103701, + 0.0532961 0.0134581 0.053557701, + 0.0532961 0.0147142 0.052301899, + 0.0546159 0.0116304 0.050786, + 0.0546159 0.0128088 0.049543802, + 0.055787299 0.0096740602 0.048067398, + 0.055787299 0.0107765 0.0468469, + 0.055787299 0.0144795 0.0416811, + 0.0546159 0.0168043 0.044231199, + 0.055787299 0.0127711 0.044309799, + 0.0599402 -0.0029843601 0.0149133, + 0.0599402 -0.0028075001 0.0141259, + 0.059999999 -0.00028193899 0.014956, + 0.059999999 -0.00052374101 0.0157081, + 0.0599402 0.0021895 0.0157691, + 0.0599402 0.00165337 0.0170705, + 0.059757002 0.00441236 0.0171795, + 0.059757002 0.0039599799 0.018299101, + 0.055787299 0.015899001 0.0390031, + 0.0546159 0.0183565 0.041446399, + 0.056809202 0.012748 0.037955798, + 0.056809202 0.0139128 0.0353918, + 0.0576833 0.0107721 0.0344662, + 0.0576833 0.0117106 0.032061901, + 0.058412101 0.00860254 0.031259499, + 0.058412101 0.0093888799 0.028880799, + 0.058998398 0.00633338 0.028205199, + 0.058998398 0.0079687396 0.023460601, + 0.059445001 0.0050254902 0.0230418, + 0.059445001 0.0067788102 0.0184687, + 0.059757002 0.00492378 0.015830399, + 0.0599402 0.0024204601 0.0149987, + 0.059999999 -0.000113206 0.014153, + 0.059935998 -0.0026765901 0.0125021, + 0.0599324 -0.0028361699 0.0125023, + 0.0599204 -0.0030811401 0.0075024599, + 0.059748501 -0.0053852098 0.0125043, + 0.059914999 -0.0030767999 0.0125025, + 0.059757002 -0.0055227298 0.0140986, + 0.059757002 -0.0057078502 0.0148702, + 0.059445001 -0.0082743801 0.014071, + 0.0599402 -0.00323702 0.015647201, + 0.059999999 -0.00108433 0.0169625, + 0.0599402 0.00117841 0.018131699, + 0.059757002 0.0021136701 0.022627501, + 0.059445001 0.00329723 0.027533799, + 0.058998398 0.0055018901 0.0304588, + 0.058412101 0.0076269298 0.033539198, + 0.0576833 0.0095801102 0.036903001, + 0.056809202 0.0113116 0.0405064, + 0.056809202 0.0095967203 0.043007798, + 0.0576833 0.0081266603 0.039325401, + 0.058412101 0.0064076101 0.035848599, + 0.058998398 0.0044891699 0.032614499, + 0.059445001 0.0024208699 0.0296633, + 0.059757002 0.00029346501 0.026869601, + 0.0599402 -0.00075967598 0.0222187, + 0.059999999 -0.00158166 0.0179656, + 0.0599402 -0.0038220601 0.016854201, + 0.059757002 -0.0059714098 0.0155859, + 0.059445001 -0.0084678596 0.0148266, + 0.058998398 -0.0110557 0.0140431, + 0.0592747 -0.0092200805 0.0125073, + 0.053284999 -0.027540499 0.0125219, + 0.053653099 -0.026806001 0.0125213, + 0.0532961 -0.027602 0.0132026, + 0.056809202 -0.020744899 0.016185399, + 0.056809202 -0.0200097 0.0152704, + 0.0576833 -0.0178982 0.016298, + 0.0576833 -0.018533099 0.016945301, + 0.058412101 -0.0156589 0.017118299, + 0.058412101 -0.018152401 0.019743999, + 0.058998398 -0.0151904 0.020165401, + 0.058998398 -0.017557001 0.0229223, + 0.059445001 -0.0145207 0.0235937, + 0.059445001 -0.015660699 0.0249938, + 0.059757002 -0.0126125 0.025781101, + 0.059757002 -0.0138422 0.0272118, + 0.0599402 -0.0107982 0.0281089, + 0.0599402 -0.0121777 0.029672399, + 0.059999999 -0.0091309603 0.030684801, + 0.059999999 -0.0106851 0.032350399, + 0.0599402 -0.00762195 0.033486199, + 0.0599402 -0.0093747796 0.0352256, + 0.059757002 -0.0062816702 0.0364943, + 0.059757002 -0.0082509797 0.038274799, + 0.059445001 -0.0051206201 0.039685, + 0.059445001 -0.0073201 0.0414696, + 0.058998398 -0.00417051 0.043017998, + 0.058998398 -0.0066039301 0.044767398, + 0.058412101 -0.0034587299 0.0464449, + 0.058412101 -0.0061237598 0.048116699, + 0.0576833 -0.0030046201 0.049911998, + 0.0576833 -0.0058884001 0.051466301, + 0.056809202 -0.0028152501 0.053365901, + 0.056809202 -0.0058981301 0.054763, + 0.019305199 -0.012751 0.0906597, + 0.0220857 -0.0113294 0.089802802, + 0.019305199 -0.00821527 0.090827502, + 0.0165099 -0.0120395 0.091487601, + 0.0165099 -0.016597001 0.091169603, + 0.0137106 -0.016024601 0.091869399, + 0.0137106 -0.020592 0.091398098, + 0.0109179 -0.0201486 0.091967702, + 0.0109179 -0.024713499 0.091341302, + 0.0081421202 -0.0243886 0.091779701, + 0.0081421202 -0.0289384 0.090996601, + 0.0053918599 -0.028720301 0.091305502, + 0.0053918599 -0.033242401 0.090364002, + 0.00267513 -0.033119701 0.090546399, + 0.00267513 -0.037601698 0.089448102, + 0 -0.037563201 0.089507699, + 0 -0.0419931 0.088255301, + -0.00267513 -0.037601799 0.089447603, + -0.00267513 -0.033119701 0.0905459, + -0.0053918599 -0.033242598 0.090363003, + -0.0053918599 -0.028720301 0.091304801, + -0.0081421202 -0.028938301 0.090995498, + -0.0081421202 -0.0243882 0.091779299, + -0.0109179 -0.024713 0.091340601, + -0.0109179 -0.0201483 0.091966897, + -0.0137106 -0.0205917 0.091397099, + -0.0137106 -0.016024301 0.0918677, + -0.0165099 -0.016596699 0.091167599, + -0.0165099 -0.0120392 0.091484703, + -0.019305199 -0.0127507 0.090656303, + -0.019305199 -0.0082152104 0.090822898, + -0.0220857 -0.0090759303 0.089868598, + -0.0220857 -0.0045742001 0.089889601, + -0.0248404 -0.0055935201 0.088813297, + -0.0378174 6.8612797e-005 0.081024297, + -0.035366699 0.00186236 0.082659803, + -0.0378174 0.0042372602 0.080606602, + -0.040174201 0.00227051 0.078898802, + -0.040174201 0.0042942399 0.078659698, + -0.0424264 0.0021830699 0.076870397, + -0.0424264 0.0040851999 0.076601297, + -0.044564299 0.0018362 0.074739799, + -0.044564299 0.00371387 0.0744121, + -0.0465803 0.0013345 0.072490498, + -0.0465803 0.0032001201 0.0721028, + -0.048467699 0.000698674 0.070133902, + -0.048467699 0.00253442 0.069692098, + -0.050219599 -8.0006299e-005 0.067688502, + -0.050219599 0.0017186099 0.0671973, + -0.051830001 -0.00099882297 0.065171503, + -0.051830001 0.00075841398 0.064635597, + -0.0532961 -0.0020506999 0.062600397, + -0.0532961 -0.00033854501 0.062024198, + -0.0546159 -0.0032271901 0.0599925, + -0.0546159 -0.00156349 0.059381001, + -0.055787299 -0.0029072801 0.056724299, + 0.0302257 0.0072271102 0.085338399, + 0.0302257 0.0093684001 0.08506, + 0.027557701 0.00646473 0.086852401, + 0.0328326 0.0077980701 0.083696298, + 0.0328326 0.00988096 0.083398603, + 0.035366699 0.0081510702 0.0819325, + 0.035366699 0.0101168 0.081600599, + 0.0378174 0.0082320496 0.080040999, + 0.0378174 0.0101811 0.079643101, + 0.040174201 0.0081456397 0.0779998, + 0.040174201 0.0100884 0.077533603, + 0.0424264 0.0079063596 0.075816602, + 0.0424264 0.0098218601 0.075287499, + 0.044564299 0.0074984799 0.073507302, + 0.044564299 0.00937826 0.072919697, + 0.0465803 0.0069218501 0.071088903, + 0.0465803 0.0087608797 0.070446797, + 0.048467699 0.0061808601 0.068578102, + 0.048467699 0.00797466 0.067886002, + 0.050219599 0.00528104 0.065991797, + 0.050219599 0.0070253899 0.065254301, + 0.051830001 0.0042288899 0.063347198, + 0.051830001 0.0059191901 0.062571101, + 0.0532961 0.0030321099 0.060663499, + 0.0532961 0.0046641901 0.059855599, + 0.0546159 0.00169957 0.0579601, + 0.0546159 0.00326998 0.057127099, + 0.055787299 0.000241544 0.055255201, + 0.055787299 0.00174767 0.054403901, + 0.056809202 0.000109933 0.0517046, + 0.0576833 -0.016549399 0.0132548, + 0.0576833 -0.0166605 0.0139868, + 0.056809202 -0.019346001 0.0132416, + -0.019305199 0.0053264801 0.090359896, + -0.0165099 0.0061345799 0.091133699, + -0.019305199 0.0097911898 0.089889102, + -0.0220857 0.0066049499 0.0892483, + -0.055787299 0.00459179 0.052491199, + -0.056809202 0.00281437 0.049787998, + -0.055787299 0.0031829299 0.053466599, + -0.0546159 0.0062527298 0.055233501, + -0.0546159 0.0047743199 0.056201398, + -0.0532961 0.0077831601 0.057997301, + -0.0532961 0.00623621 0.058949899, + -0.051830001 0.0091698803 0.060763501, + -0.051830001 0.0075562699 0.0616927, + -0.050219599 0.010401 0.063511901, + -0.050219599 0.0087238997 0.064410798, + -0.048467699 0.0114666 0.066223398, + -0.048467699 0.00973015 0.067085102, + -0.0465803 0.0123595 0.0688788, + -0.0465803 0.0105684 0.069696203, + -0.044564299 0.0130739 0.071458504, + -0.044564299 0.0112333 0.0722249, + -0.0424264 0.0136048 0.073943101, + -0.0424264 0.0117194 0.074653298, + -0.040174201 0.0139481 0.076314799, + -0.040174201 0.0120233 0.076964296, + -0.0378174 0.0141033 0.078558497, + -0.0378174 0.0121445 0.079142801, + -0.035366699 0.014071 0.0806593, + -0.035366699 0.0120871 0.081174299, + -0.0328326 0.0138559 0.082602799, + -0.0328326 0.0118672 0.0830428, + -0.0302257 0.0134754 0.084373899, + -0.0302257 0.0114693 0.084741302, + -0.027557701 0.0129171 0.085968398, + -0.027557701 0.0107892 0.086295702, + -0.0248404 0.0120768 0.087413803, + -0.0248404 0.0077060899 0.087988101, + -0.0220857 0.00881969 0.089003399, + -0.0220857 0.0132199 0.088406198, + -0.0248404 0.0142204 0.087073199, + -0.027557701 0.0149392 0.085585698, + -0.0302257 0.0154817 0.083916001, + -0.0328326 0.0158592 0.082066901, + -0.035366699 0.0160504 0.080050804, + -0.0378174 0.0160497 0.077881701, + -0.040174201 0.0158558 0.075574197, + -0.0424264 0.0154682 0.073142797, + -0.044564299 0.0148882 0.070603803, + -0.0465803 0.0141191 0.0679764, + -0.048467699 0.0131663 0.065280497, + -0.050219599 0.0120364 0.062535502, + -0.051830001 0.0107375 0.059760801, + -0.0532961 0.0092808502 0.056976601, + -0.0546159 0.0076791602 0.054202899, + -0.055787299 0.00594613 0.0514584, + -0.0576833 -0.016675999 0.0139843, + -0.056809202 -0.0194775 0.0139562, + -0.0576833 -0.0169177 0.0146908, + -0.058412101 -0.0141038 0.0147352, + -0.058412101 -0.0143993 0.0153832, + -0.058998398 -0.0115807 0.0154464, + -0.058998398 -0.0122071 0.016503001, + -0.059445001 -0.0093809301 0.016614599, + -0.059445001 -0.0099466704 0.017457301, + -0.059757002 -0.0071278298 0.0176269, + -0.059757002 -0.0093346899 0.020995, + -0.0599402 -0.0064613498 0.021403899, + -0.0599402 -0.0085524498 0.024913101, + -0.059999999 -0.00561126 0.025563501, + -0.059999999 -0.00662508 0.027305299, + -0.0599402 -0.00364039 0.028076099, + -0.0599402 -0.00477676 0.0298848, + -0.059757002 -0.00173278 0.030781999, + -0.059757002 -0.0030410099 0.032724101, + -0.059445001 7.0618597e-005 0.033758201, + -0.059445001 -0.00143604 0.0357912, + -0.058998398 0.0017261 0.0369635, + -0.058998398 -8.9189198e-006 0.0390747, + -0.058412101 0.00317978 0.040382698, + -0.058412101 0.00119748 0.042536099, + -0.0576833 0.0043896101 0.043974102, + -0.0576833 0.0021468401 0.046125099, + -0.056809202 0.0053197402 0.0476849, + -0.055787299 0.0072418302 0.0503718, + -0.0546159 0.0090489602 0.0531133, + -0.0532961 0.0107246 0.055891499, + -0.051830001 0.0122541 0.0586881, + -0.050219599 0.0136243 0.0614838, + -0.048467699 0.014823 0.064258203, + -0.0465803 0.015840599 0.0669908, + -0.044564299 0.016669899 0.069662102, + -0.0424264 0.017304599 0.072252303, + -0.040174201 0.017741101 0.074741699, + -0.0378174 0.017978599 0.077112302, + -0.035366699 0.018017299 0.079348803, + -0.0328326 0.0178579 0.081436202, + -0.0302257 0.017503001 0.083360903, + -0.027557701 0.016961901 0.085111499, + -0.0248404 0.0162571 0.086676598, + -0.0220857 0.0153772 0.0880538, + -0.019305199 0.014217 0.089272, + -0.0165099 0.0106224 0.0906469, + -0.0137106 0.0068085399 0.091779202, + -0.0137106 0.0022704201 0.092120998, + -0.0109179 0.0027966499 0.092650302, + -0.0109179 -0.00178007 0.092840299, + -0.0081421202 -0.00139144 0.093250901, + -0.0081421202 -0.0059951101 0.093284801, + -0.0053918599 -0.0057322499 0.093576401, + -0.0053918599 -0.0103511 0.093450502, + -0.00267513 -0.0102021 0.093624301, + -0.00267513 -0.0148243 0.093335502, + 0 -0.0147773 0.093393102, + 0 -0.0193907 0.092940703, + 0.00267513 -0.0148243 0.0933358, + 0.00267513 -0.0102021 0.093624704, + 0.0053918599 -0.0103512 0.093451403, + 0.0053918599 -0.0057322402 0.093577698, + 0.0081421202 -0.0059951101 0.093286701, + 0.0081421202 -0.0013911 0.0932533, + 0.0109179 -0.00177964 0.0928436, + 0.0109179 0.00279809 0.0926539, + 0.0137106 0.0022722499 0.092125498, + 0.0137106 0.0068126 0.091783702, + 0.0165099 0.0061395098 0.091139197, + 0.0165099 0.0106303 0.090651698, + 0.055787299 0.0072696302 0.0503866, + 0.055787299 0.0059732101 0.051475398, + 0.056809202 0.0053485902 0.047697701, + 0.0546159 0.00907546 0.0531299, + 0.0546159 0.0077047399 0.054221701, + 0.0532961 0.0107496 0.055909801, + 0.0532961 0.00930476 0.056996901, + 0.051830001 0.0122773 0.058707699, + 0.051830001 0.0107595 0.0597822, + 0.050219599 0.0136455 0.061504599, + 0.050219599 0.0120562 0.062557802, + 0.048467699 0.0148421 0.064279698, + 0.048467699 0.0131838 0.065303102, + 0.0465803 0.015857499 0.067012601, + 0.0465803 0.0141341 0.0679987, + 0.044564299 0.016684201 0.0696835, + 0.044564299 0.0149007 0.070625201, + 0.0424264 0.0173166 0.072272703, + 0.0424264 0.0154784 0.073162504, + 0.040174201 0.0177506 0.074760303, + 0.040174201 0.015863599 0.0755914, + 0.0378174 0.017985901 0.0771285, + 0.0378174 0.016055301 0.077895999, + 0.035366699 0.0180225 0.079362102, + 0.035366699 0.0160539 0.080062099, + 0.0328326 0.0178612 0.0814467, + 0.0328326 0.015860699 0.082075499, + 0.0302257 0.017504301 0.083368704, + 0.0302257 0.0154813 0.0839222, + 0.027557701 0.016961601 0.085117102, + 0.027557701 0.0149385 0.085590199, + 0.0248404 0.016256399 0.0866808, + 0.0248404 0.0142218 0.0870772, + 0.0220857 0.0153786 0.088057399, + 0.0220857 0.0132269 0.088410802, + 0.019305199 0.0142231 0.089276001, + 0.019305199 0.0098004397 0.089894801, + 0.019305199 0.0053322199 0.090366296, + 0.0220857 0.0066138399 0.089255303, + 0.055787299 0.0046179299 0.052510299, + 0.055787299 0.0032079399 0.0534878, + 0.056809202 0.0028419399 0.049805298, + 0.0546159 0.0062772199 0.055254299, + 0.0546159 0.00479746 0.0562241, + 0.0532961 0.00780576 0.0580194, + 0.0532961 0.0062572602 0.058973499, + 0.051830001 0.0091903498 0.060786501, + 0.051830001 0.0075749699 0.061716899, + 0.050219599 0.0104191 0.063535303, + 0.050219599 0.0087400898 0.064434901, + 0.048467699 0.0114822 0.066246703, + 0.048467699 0.0097438097 0.067108303, + 0.0465803 0.0123727 0.068901204, + 0.0465803 0.0105795 0.069717698, + 0.044564299 0.0130845 0.071479201, + 0.044564299 0.0112419 0.072244003, + 0.0424264 0.013613 0.073961303, + 0.0424264 0.0117258 0.074669302, + 0.040174201 0.0139541 0.076329999, + 0.040174201 0.0120273 0.076977096, + 0.0378174 0.014107 0.0785705, + 0.0378174 0.0121461 0.079152703, + 0.035366699 0.0140725 0.080668502, + 0.035366699 0.0120866 0.081181601, + 0.0328326 0.0138555 0.082609601, + 0.0328326 0.0118663 0.083048202, + 0.0302257 0.0134744 0.084378898, + 0.0302257 0.0114711 0.0847461, + 0.027557701 0.0129188 0.085972801, + 0.027557701 0.0107979 0.086301401, + 0.0248404 0.0120847 0.087418899, + 0.0248404 0.00771796 0.087995403, + 0.0220857 0.0088302502 0.089009903, + 0.0576833 0.00217615 0.0461381, + 0.0576833 0.0044193701 0.043982901, + 0.058412101 0.00122764 0.042544998, + 0.058412101 0.0032094701 0.040387701, + 0.058998398 2.1084101e-005 0.0390797, + 0.058998398 0.00175509 0.0369629, + 0.059445001 -0.00140683 0.035790499, + 0.059445001 9.76214e-005 0.033751599, + 0.059757002 -0.00301386 0.0327176, + 0.059757002 -0.00171342 0.030786499, + 0.0599402 -0.00475732 0.0298893, + 0.0599402 -0.00363521 0.028099401, + 0.059999999 -0.0066198702 0.0273287, + 0.059999999 -0.0056117801 0.0255637, + 0.0599402 -0.0085529396 0.0249133, + 0.0599402 -0.0064620101 0.021407399, + 0.059757002 -0.0093353298 0.0209984, + 0.059757002 -0.0071233502 0.017632, + 0.059445001 -0.0099422103 0.0174623, + 0.059445001 -0.0093770102 0.0166348, + 0.058998398 -0.0122032 0.0165231, + 0.058998398 -0.0115435 0.0154607, + 0.058412101 -0.0143625 0.0153973, + 0.058412101 -0.0140653 0.0147382, + 0.0576833 -0.0168796 0.0146936, + 0.056809202 -0.0194622 0.0139587, + 0.055787299 -0.022127699 0.0132284, + 0.056127101 -0.0211474 0.0125168, + 0.0546159 -0.0248836 0.0132154, + 0.0554736 -0.0228507 0.0125182, + 0.055787299 -0.022249 0.0139306, + 0.056809202 -0.019689901 0.0146493, + 0.0576833 -0.017188 0.0153338, + 0.058412101 -0.0150472 0.016410699, + 0.058998398 -0.0127914 0.017290801, + 0.059445001 -0.0122471 0.0205842, + 0.059757002 -0.011517 0.0242579, + 0.0599402 -0.00960455 0.0265579, + 0.059999999 -0.0077777798 0.0289991, + 0.0599402 -0.00608422 0.031697299, + 0.059757002 -0.0045350399 0.034630701, + 0.059445001 -0.00314718 0.037780099, + 0.058998398 -0.0019565499 0.041110501, + 0.058412101 -0.00100093 0.044576202, + 0.0576833 -0.00030609299 0.0481264, + 0.0248404 0.0055165798 0.088229798, + 0.0220857 0.0043883501 0.089462601, + 0.019305199 0.00308623 0.0905433, + 0.0165099 0.00161838 0.091468297, + 0.0137106 -0.00228963 0.092305601, + 0.0109179 -0.0063713002 0.092870101, + 0.0081421202 -0.0106052 0.093156002, + 0.0053918599 -0.0149682 0.0931601, + 0.00267513 -0.0194361 0.092882603, + 0 -0.023984799 0.092324503, + -0.00267513 -0.019436 0.092882402, + -0.0053918599 -0.0149681 0.093159497, + -0.0081421202 -0.0106051 0.093154497, + -0.0109179 -0.0063712699 0.092867501, + -0.0137106 -0.0022901699 0.0923016, + -0.0165099 0.00161617 0.091462903, + -0.019305199 0.00083160802 0.090673901, + -0.0220857 0.0021513 0.089623101, + -0.0165099 -0.00292443 0.091631703, + -0.0137106 -0.0068650199 0.092319898, + -0.0109179 -0.0109687 0.0927312, + -0.0081421202 -0.0152132 0.0928597, + -0.0053918599 -0.019574501 0.092704304, + -0.00267513 -0.024028201 0.092265703, + 0 -0.028550699 0.091545798, + 0.00267513 -0.024028299 0.092265896, + 0.0053918599 -0.019574599 0.092704698, + 0.0081421202 -0.0152134 0.092860699, + 0.0109179 -0.0109689 0.0927331, + 0.0137106 -0.00686508 0.092323199, + 0.0165099 -0.0029237601 0.091636598, + 0.019305199 -0.00142298 0.0907773, + 0.035366699 0.0039910199 0.082458198, + 0.035366699 0.00187928 0.082670197, + 0.0378174 0.00424923 0.080614403, + 0.0328326 0.0035431201 0.084187701, + 0.0328326 0.0013983099 0.0843812, + 0.0302257 0.00290695 0.085791104, + 0.0302257 0.00073288498 0.0859624, + 0.027557701 0.0020872201 0.0872593, + 0.027557701 -0.000112554 0.087405197, + 0.0248404 0.00108919 0.0885842, + 0.0248404 -0.00113365 0.088702403, + 0.0220857 -8.2635102e-005 0.089758798, + 0.0220857 -0.002326 0.089847296, + 0.019305199 -0.00368426 0.0908342, + 0.0165099 -0.0074789999 0.091643199, + 0.0137106 -0.0114461 0.092177898, + 0.0109179 -0.0155641 0.092432, + 0.0081421202 -0.019810701 0.092401601, + 0.0053918599 -0.0241616 0.092086203, + 0.00267513 -0.028592501 0.091486797, + 0 -0.033079699 0.0906059, + -0.00267513 -0.028592501 0.091486402, + -0.0053918599 -0.0241614 0.092085801, + -0.0081421202 -0.0198105 0.092400998, + -0.0109179 -0.0155639 0.092430703, + -0.0137106 -0.0114458 0.092175402, + -0.0165099 -0.0074789701 0.091639198, + -0.019305199 -0.0036850199 0.090828501, + -0.0220857 -8.5569904e-005 0.089751497, + -0.0248404 0.00108408 0.0885759, + -0.0248404 0.0032989299 0.088418297, + -0.027557701 0.00207904 0.087250099, + -0.027557701 0.0042692199 0.087065697, + -0.0302257 0.0028947601 0.085781403, + -0.0302257 0.0050580399 0.085573703, + -0.0328326 0.0035274201 0.084178001, + -0.0328326 0.0077876798 0.083689399, + -0.035366699 0.0060785199 0.0822054, + -0.035366699 0.0081489496 0.081926897, + -0.0378174 0.00628511 0.080347203, + -0.0378174 0.00823317 0.080034703, + -0.040174201 0.0062200101 0.078368299, + -0.040174201 0.0081461603 0.0779915, + -0.0424264 0.0059877601 0.076248497, + -0.0424264 0.0079045501 0.0758055, + -0.044564299 0.0056056599 0.073996097, + -0.044564299 0.0074941101 0.073493101, + -0.0465803 0.0050627501 0.0716298, + -0.0465803 0.0069149402 0.071071297, + -0.048467699 0.0043602898 0.069166698, + -0.048467699 0.00617145 0.068557397, + -0.050219599 0.0035032299 0.066624202, + -0.050219599 0.0052690599 0.065968499, + -0.051830001 0.0024977301 0.064019203, + -0.051830001 0.0042143101 0.063322298, + -0.0532961 0.00135182 0.061369602, + -0.0532961 0.00301491 0.060637899, + -0.0546159 7.4055999e-005 0.0586945, + -0.0546159 0.00167987 0.057934601, + -0.055787299 -0.001326 0.056012299, + -0.055787299 0.000219522 0.055230498, + -0.056809202 -0.00283767 0.0533407, + -0.0328326 0.00138506 0.084370703, + -0.0302257 0.00072390499 0.085952498, + -0.027557701 -0.000118178 0.087396003, + -0.0248404 -0.00113695 0.0886942, + -0.0248404 -0.0033631399 0.0887734, + -0.027557701 -0.00232143 0.087503202, + -0.0302257 -0.00145372 0.086085401, + -0.0328326 -0.00076456601 0.084527001, + -0.035366699 -0.00025724599 0.082836099, + -0.035366699 -0.00238379 0.082976498, + -0.0328326 -0.00292073 0.084645897, + -0.0302257 -0.00363718 0.086180001, + -0.027557701 -0.0045296601 0.087571397, + 0.0220857 -0.0068236399 0.089905001, + 0.0378174 -0.00201123 0.0811949, + 0.0378174 -0.0041169501 0.081318699, + 0.040174201 -0.00182812 0.079289101, + 0.035366699 -0.00237328 0.082988299, + 0.035366699 -0.0045093298 0.083091699, + 0.0328326 -0.0029140001 0.084656797, + 0.0328326 -0.0050781202 0.084737599, + 0.0302257 -0.0036331799 0.086189903, + 0.0302257 -0.0058231 0.086245798, + 0.027557701 -0.0045274901 0.0875801, + 0.027557701 -0.0067407801 0.087608904, + 0.0248404 -0.0055925399 0.088820599, + 0.0248404 -0.0078266701 0.088820502, + 0.0220857 -0.0090759797 0.089873902, + 0.0248404 -0.0100627 0.088780597, + 0.027557701 -0.0089567099 0.087598599, + 0.0302257 -0.00801636 0.0862628, + 0.0328326 -0.00724624 0.08478, + 0.035366699 -0.0066500199 0.083157398, + 0.0378174 -0.00622808 0.081405498, + 0.040174201 -0.00597951 0.079535201, + 0.0424264 -0.00385872 0.0774372, + 0.0424264 0.00019842001 0.077096701, + 0.044564299 -0.0019980201 0.0751893, + 0.044564299 -3.8332299e-005 0.074992299, + 0.0465803 -0.00236549 0.073020197, + 0.0465803 -0.00051856402 0.072799601, + 0.048467699 -0.00296582 0.070774503, + 0.048467699 -0.0011403901 0.070502304, + 0.050219599 -0.0036989099 0.0684366, + 0.050219599 -0.0018858199 0.068111099, + 0.051830001 -0.00454664 0.066017203, + 0.051830001 -0.0027643801 0.065643899, + 0.0532961 -0.0055167298 0.063534997, + 0.0532961 -0.00377209 0.063118197, + 0.0546159 -0.0066044 0.061007202, + 0.0546159 -0.0049010902 0.060550898, + 0.055787299 -0.0078012398 0.0584502, + 0.055787299 -0.0061422898 0.057958499, + 0.055787299 -0.0045032199 0.057391699, + 0.0546159 -0.00321417 0.060017802, + 0.0532961 -0.0020403401 0.062623098, + 0.051830001 -0.00099114701 0.065191001, + 0.050219599 -7.5080599e-005 0.067704499, + 0.048467699 0.00070072903 0.070146501, + 0.0465803 0.00133389 0.072500102, + 0.044564299 0.0018348499 0.074747197, + 0.0424264 0.0021856099 0.076877102, + 0.040174201 0.00228324 0.078907102, + 0.0378174 8.6688699e-005 0.081035502, + 0.035366699 -0.000242985 0.082847401, + 0.0328326 -0.00075479102 0.084537998, + 0.0302257 -0.00144755 0.086095497, + 0.027557701 -0.0023177599 0.087512203, + 0.0248404 -0.00336118 0.0887812, + 0.0220857 -0.0045733401 0.089896098, + 0.040174201 0.0042966502 0.078666098, + 0.0424264 0.00408393 0.076608397, + 0.044564299 0.00371329 0.074421197, + 0.0465803 0.0032021201 0.0721149, + 0.048467699 0.00253916 0.069707602, + 0.050219599 0.00172608 0.067216299, + 0.051830001 0.000768503 0.064657703, + 0.0532961 -0.00032583001 0.062048901, + 0.0546159 -0.0015481201 0.0594071, + 0.055787299 -0.00288929 0.056751002, + 0.055787299 -0.00130587 0.056038398, + 0.0546159 9.1685797e-005 0.0587206, + 0.0532961 0.00136683 0.061395202, + 0.051830001 0.0025100801 0.064043202, + 0.050219599 0.0035129699 0.066645697, + 0.048467699 0.0043674698 0.069185004, + 0.0465803 0.0050673098 0.071644597, + 0.044564299 0.00560755 0.074007697, + 0.0424264 0.00598722 0.076257199, + 0.040174201 0.0062188199 0.078374997, + 0.0378174 0.0062873801 0.0803532, + 0.035366699 0.0060897302 0.082212701, + 0.0328326 0.0056771799 0.083958901, + 0.0302257 0.0050724898 0.085582599, + 0.027557701 0.0042803399 0.087074503, + 0.0248404 0.0033063199 0.088426501, + 0.0220857 0.0021558199 0.089630499, + 0.019305199 0.00083417603 0.090680301, + 0.055787299 -0.0224855 0.0146051, + 0.0546159 -0.0250101 0.0139029, + 0.054285601 -0.0255438 0.0125203, + 0.053669199 -0.026818 0.0075213602, + 0.051820099 -0.0302085 0.0125241, + 0.0529669 -0.028175401 0.0125224, + 0.051830001 -0.0302712 0.0131899, + 0.0532961 -0.0277337 0.0138756, + 0.0546159 -0.025255 0.0145613, + 0.055787299 -0.0228163 0.0152073, + 0.055787299 -0.0231998 0.015696799, + 0.0546159 -0.025597 0.0151448, + 0.0532961 -0.0279871 0.0145181, + 0.051830001 -0.0304079 0.0138487, + 0.050219599 -0.032879099 0.0131775, + 0.0506116 -0.032180801 0.0125256, + -0.051830001 -0.0302503 0.0131749, + -0.051374301 -0.0309832 0.0125247, + -0.050219599 -0.032858901 0.0131629, + -0.0576833 -0.019832101 0.0181484, + -0.058412101 -0.0181517 0.0197406, + -0.0576833 -0.0185374 0.0169404, + -0.056809202 -0.021407399 0.016767699, + -0.056809202 -0.020748699 0.016166, + -0.055787299 -0.0235803 0.016054399, + -0.055787299 -0.022851501 0.0151938, + -0.0546159 -0.0256315 0.0151315, + -0.0546159 -0.025291 0.0145585, + -0.0532961 -0.0280223 0.0145154, + -0.0532961 -0.027748 0.0138732, + -0.051830001 -0.030421801 0.0138464, + -0.0423088 -0.042532001 0.0125339, + -0.040746599 -0.044011202 0.012535, + -0.0424264 -0.042459399 0.0131193, + 0.0465803 -0.0122129 0.073566496, + 0.0465803 -0.0162064 0.073550701, + 0.048467699 -0.0144772 0.071398497, + 0.048467699 -0.0105645 0.071321703, + 0.050219599 -0.0129718 0.069126397, + 0.050219599 -0.0091577796 0.068971798, + 0.051830001 -0.0117001 0.0667639, + 0.051830001 -0.0098620104 0.066666998, + 0.0532961 -0.0124966 0.064434201, + 0.0532961 -0.0107639 0.064321101, + 0.055787299 -0.0145492 0.059675701, + 0.055787299 -0.012855 0.059479099, + 0.0546159 -0.011768 0.061921299, + 0.0546159 -0.0134774 0.062075499, + 0.0532961 -0.0143022 0.0645044, + 0.051830001 -0.0154481 0.066868097, + 0.050219599 -0.016818499 0.069156498, + 0.048467699 -0.0184054 0.071340099, + 0.0465803 -0.020208299 0.073395804, + 0.044564299 -0.0181577 0.075560004, + 0.044564299 -0.022227 0.075301498, + 0.0424264 -0.0203299 0.077403702, + 0.0424264 -0.0244595 0.077035002, + 0.040174201 -0.022719201 0.079060301, + 0.040174201 -0.026900901 0.078574501, + -0.048467699 -0.0355739 0.0137947, + -0.0465803 -0.038029902 0.0137702, + -0.048467699 -0.035870899 0.0143915, + -0.050219599 -0.033323899 0.0144316, + -0.052581199 -0.031257 0.016175, + -0.0532961 -0.029880401 0.0162578, + -0.052581199 -0.0305184 0.0157809, + -0.051830001 -0.03187 0.015727701, + -0.051830001 -0.031472102 0.0154263, + -0.0532961 -0.028767399 0.0155081, + -0.051830001 -0.031066 0.0150098, + -0.050219599 -0.033696599 0.014951, + -0.048467699 -0.036253899 0.0148938, + -0.0465803 -0.0383339 0.0143525, + -0.044564299 -0.040391698 0.0137465, + -0.044564299 -0.040205602 0.0131295, + -0.044344399 -0.040405899 0.0125322, + -0.046273202 -0.038182501 0.0125304, + -0.045055199 -0.039586499 0.0125315, + -0.0465803 -0.037847199 0.0131401, + -0.0484582 -0.0353484 0.0125282, + -0.0480907 -0.035867199 0.0125286, + -0.048467699 -0.035394698 0.0131514, + -0.050219599 -0.033034299 0.0138202, + -0.051830001 -0.0307038 0.0144731, + -0.0532961 -0.028373601 0.0150701, + -0.0546159 -0.0263856 0.015943799, + -0.0576833 -0.0224033 0.020452101, + -0.058412101 -0.020611901 0.022246299, + -0.0576833 -0.021120699 0.0193181, + -0.056809202 -0.024085499 0.0188963, + -0.056809202 -0.022749599 0.0178515, + -0.055787299 -0.025651701 0.0175563, + -0.055787299 -0.0242621 0.016595799, + -0.0546159 -0.0270904 0.016425701, + -0.0532961 -0.0291529 0.0158347, + -0.0546159 -0.0285269 0.0172638, + -0.055787299 -0.027034501 0.0184767, + -0.056809202 -0.025415 0.019904301, + -0.0576833 -0.0236747 0.021569099, + -0.058412101 -0.0218475 0.0233745, + -0.058998398 -0.018746899 0.0241751, + -0.058998398 -0.020064199 0.0253793, + -0.059445001 -0.016946301 0.026298201, + -0.059445001 -0.018386699 0.027624501, + -0.059757002 -0.0152753 0.028658601, + -0.059757002 -0.016864499 0.0300708, + -0.0599402 -0.0137776 0.0312154, + -0.0599402 -0.0155438 0.032702498, + -0.059999999 -0.0124746 0.0339614, + -0.059999999 -0.0144361 0.035493098, + -0.0599402 -0.0113709 0.036874, + -0.0599402 -0.0135413 0.038412701, + -0.059757002 -0.0104664 0.039924301, + -0.059757002 -0.0128502 0.0414332, + -0.059445001 -0.0097580804 0.043082401, + -0.059445001 -0.0123543 0.044523399, + -0.058998398 -0.0092619602 0.046303201, + -0.058998398 -0.0120597 0.047639899, + -0.058412101 -0.0089890799 0.049538098, + -0.058412101 -0.0119712 0.050734501, + -0.0576833 -0.0089416504 0.052736599, + -0.0576833 -0.0120829 0.053763699, + -0.056809202 -0.0091113402 0.055853799, + -0.056809202 -0.0123823 0.056685299, + -0.055787299 -0.0094839903 0.0588459, + -0.055787299 -0.0128574 0.0594646, + -0.0546159 -0.0100456 0.061677501, + 0.035366699 -0.025977099 0.082047701, + 0.035366699 -0.0281146 0.081735499, + 0.0378174 -0.025317499 0.080510199, + 0.0328326 -0.026789401 0.0834378, + 0.0328326 -0.031097701 0.082721598, + 0.0302257 -0.0299266 0.084302902, + 0.0302257 -0.034256201 0.0834556, + 0.027557701 -0.033232301 0.084907599, + 0.027557701 -0.037572999 0.083921097, + 0.0248404 -0.036688399 0.085237302, + 0.0248404 -0.041025899 0.084109597, + 0.0220857 -0.0402725 0.0852843, + 0.0220857 -0.044592399 0.084014498, + 0.019305199 -0.043962002 0.085043304, + 0.019305199 -0.0482499 0.083631597, + 0.0165099 -0.047732498 0.084513903, + 0.0165099 -0.051976599 0.082960397, + 0.0137106 -0.0515627 0.083696902, + 0.0137106 -0.055750001 0.082004197, + 0.0109179 -0.055430502 0.082596198, + 0.0109179 -0.063880801 0.079175398, + 0.0081421202 -0.063657701 0.079625599, + 0.0081421202 -0.072251998 0.0764568, + 0.0053918599 -0.072110102 0.0767712, + 0.0053918599 -0.080830202 0.073861502, + 0.00267513 -0.0807551 0.074046202, + 0.00267513 -0.089582801 0.071401097, + 0 -0.089561202 0.071461797, + 0 -0.098479003 0.069086596, + -0.00267513 -0.089583799 0.071402699, + -0.00267513 -0.080756098 0.074047498, + -0.0053918599 -0.080832101 0.073864304, + -0.0053918599 -0.072111703 0.076773196, + -0.0081421202 -0.0722543 0.076459996, + -0.0081421202 -0.063658997 0.079627, + -0.0109179 -0.063882597 0.079177298, + -0.0109179 -0.0554308 0.082595602, + -0.0137106 -0.055750199 0.082003497, + -0.0137106 -0.0515626 0.083696403, + -0.0165099 -0.051976599 0.082959898, + -0.0165099 -0.047732599 0.084512703, + -0.019305199 -0.0482499 0.083630197, + -0.019305199 -0.0439623 0.085041001, + -0.0220857 -0.044592801 0.084011801, + -0.0220857 -0.040273201 0.085280597, + -0.0248404 -0.0410267 0.084105402, + -0.0248404 -0.036688998 0.085232802, + -0.027557701 -0.037573799 0.083916098, + -0.027557701 -0.033232201 0.084903598, + -0.0302257 -0.034256101 0.083451197, + -0.0302257 -0.0299253 0.084300801, + -0.0328326 -0.0310962 0.082719401, + -0.0328326 -0.0267886 0.083435297, + -0.035366699 -0.028113799 0.081732802, + -0.035366699 -0.0238344 0.082317904, + -0.0378174 -0.0253167 0.080505498, + -0.0378174 -0.021077299 0.080963403, + -0.040174201 -0.0227185 0.079053096, + -0.040174201 -0.0185291 0.079389602, + -0.0424264 -0.0203298 0.077393502, + -0.0424264 -0.016199799 0.077615701, + -0.044564299 -0.0181596 0.075546898, + -0.044564299 -0.0140977 0.075661898, + -0.0465803 -0.016212599 0.073535398, + -0.0465803 -0.0122267 0.073550999, + -0.048467699 -0.0144916 0.071382403, + -0.048467699 -0.0105876 0.071307503, + -0.050219599 -0.0129957 0.069111697, + -0.050219599 -0.0091736903 0.0689613, + -0.051830001 -0.0117167 0.066753298, + -0.051830001 -0.0080980901 0.066517301, + -0.0532961 -0.0107623 0.064312197, + -0.0532961 -0.0090238899 0.064125501, + -0.0546159 -0.0117673 0.0619101, + -0.0546159 -0.0134757 0.062066499, + -0.0532961 -0.0143192 0.064493299, + -0.051830001 -0.0154729 0.066852801, + -0.050219599 -0.016833499 0.069139801, + -0.048467699 -0.0184118 0.071324199, + -0.0465803 -0.0202101 0.073382102, + -0.044564299 -0.0222269 0.075290799, + -0.0424264 -0.0244588 0.077027403, + -0.040174201 -0.0269001 0.078569502, + -0.0378174 -0.0295415 0.079898499, + -0.035366699 -0.032370199 0.080998898, + -0.0328326 -0.035380598 0.081855901, + -0.0302257 -0.038556602 0.082453497, + -0.027557701 -0.041875701 0.082781501, + -0.0248404 -0.045315798 0.082832001, + -0.0220857 -0.048854802 0.082598597, + -0.019305199 -0.052472901 0.082076602, + -0.0165099 -0.0561474 0.081267297, + -0.0137106 -0.064175896 0.078586899, + -0.0109179 -0.072458401 0.0760113, + -0.0081421202 -0.080961399 0.073551603, + -0.0053918599 -0.089652099 0.071219601, + -0.00267513 -0.098499201 0.069027498, + 0 -0.107472 0.066986099, + 0.00267513 -0.098498203 0.069026001, + 0.0053918599 -0.089649998 0.071216501, + 0.0081421202 -0.080958501 0.073547401, + 0.0109179 -0.072455302 0.076007098, + 0.0137106 -0.064173803 0.0785845, + 0.0165099 -0.056147099 0.081268102, + 0.019305199 -0.052473001 0.082077302, + 0.0220857 -0.048854701 0.082600102, + 0.0248404 -0.045315299 0.082835101, + 0.027557701 -0.0418749 0.082786098, + 0.0302257 -0.038555801 0.082459003, + 0.0328326 -0.035380799 0.081860699, + 0.035366699 -0.0323718 0.081001401, + 0.0378174 -0.0295424 0.079901397, + 0.0378174 -0.0231991 0.080758803, + 0.035366699 -0.023835201 0.082322203, + 0.0328326 -0.0246264 0.0837401, + 0.0302257 -0.025571199 0.085002601, + 0.027557701 -0.028860399 0.085742503, + 0.0248404 -0.032310799 0.086214602, + 0.0220857 -0.035903201 0.086405598, + 0.019305199 -0.0396153 0.086309001, + 0.0165099 -0.043422598 0.085923404, + 0.0137106 -0.047301002 0.085249603, + 0.0109179 -0.0512297 0.084289096, + 0.0081421202 -0.055187199 0.083047099, + 0.0053918599 -0.063501902 0.079940297, + 0.00267513 -0.072026901 0.076955996, + 0 -0.080730803 0.074106902, + -0.00267513 -0.072027698 0.076957002, + -0.0053918599 -0.063502803 0.079941198, + -0.0081421202 -0.0551874 0.083046697, + -0.0109179 -0.0512297 0.084288798, + -0.0137106 -0.047301099 0.085248597, + -0.0165099 -0.0434229 0.085921399, + -0.019305199 -0.039615899 0.086305797, + -0.0220857 -0.0359038 0.086401597, + -0.0248404 -0.032310601 0.086211003, + -0.027557701 -0.028859099 0.085740499, + -0.0302257 -0.0255704 0.085000299, + -0.0328326 -0.022458401 0.0840002, + -0.035366699 -0.0195409 0.082751803, + -0.0378174 -0.016830901 0.081271797, + -0.040174201 -0.0143396 0.079579398, + -0.0424264 -0.0120764 0.0776942, + -0.044564299 -0.0100487 0.0756367, + -0.0465803 -0.0082588801 0.073431, + -0.048467699 -0.0067017102 0.071107998, + -0.050219599 -0.0054949098 0.068671897, + -0.051830001 -0.00633022 0.066300802, + -0.0532961 -0.0072720801 0.063860402, + -0.0546159 -0.0083252396 0.061369698, + -0.0546159 -0.0066124802 0.060986601, + -0.0532961 -0.0055219298 0.063518003, + -0.051830001 -0.00454885 0.066003703, + -0.050219599 -0.0036982801 0.068426199, + -0.048467699 -0.00296437 0.070766397, + -0.0302257 -0.0124091 0.0861734, + -0.027557701 -0.0111742 0.087542303, + -0.0302257 -0.0102124 0.086233102, + -0.0328326 -0.0115914 0.084741302, + -0.0328326 -0.0094187902 0.084774502, + -0.035366699 -0.0109432 0.083165102, + -0.035366699 -0.00879726 0.083174199, + -0.0378174 -0.0083485702 0.081442602, + -0.0378174 -0.0125855 0.081431299, + -0.040174201 -0.0101578 0.079623401, + -0.040174201 -0.00599143 0.079521902, + -0.0424264 -0.0079672299 0.077629901, + -0.0424264 -0.00387902 0.077424698, + -0.044564299 -0.0060192998 0.0754731, + -0.044564299 -0.0020121201 0.075180002, + -0.0465803 -0.0043111001 0.0731837, + -0.0465803 -0.00236828 0.073012702, + -0.048467699 -0.0047883401 0.070961498, + -0.035366699 -0.0152412 0.083034098, + 0.0302257 -0.023384901 0.0852957, + 0.0302257 -0.0211943 0.085550301, + 0.027557701 -0.024462201 0.0864271, + 0.0328326 -0.022459099 0.084004201, + 0.0328326 -0.0202884 0.084230199, + 0.035366699 -0.021689599 0.082559101, + 0.035366699 -0.0195415 0.082758099, + 0.0378174 -0.021077899 0.080970101, + 0.0378174 -0.018954899 0.081144199, + 0.040174201 -0.018529201 0.079399198, + 0.040174201 -0.0164333 0.079513602, + 0.0424264 -0.016198101 0.077628098, + 0.0378174 -0.0168311 0.081280902, + 0.035366699 -0.017391801 0.0829193, + 0.0328326 -0.018115301 0.084417701, + 0.0302257 -0.0190005 0.085766204, + 0.027557701 -0.0200429 0.086957902, + 0.0248404 -0.023463801 0.087709501, + 0.0248404 -0.0279007 0.087038301, + 0.0220857 -0.0270488 0.088188604, + 0.0220857 -0.031492598 0.087374702, + 0.019305199 -0.030779 0.088386603, + 0.019305199 -0.035218298 0.087424703, + 0.0165099 -0.0346324 0.088296399, + 0.0165099 -0.039053101 0.087185502, + 0.0137106 -0.038584299 0.087916397, + 0.0137106 -0.0429729 0.086657099, + 0.0109179 -0.0426111 0.087247401, + 0.0109179 -0.046954099 0.085841201, + 0.0081421202 -0.0466897 0.086291902, + 0.0081421202 -0.050976101 0.0847404, + 0.0053918599 -0.0507989 0.085055701, + 0.0053918599 -0.055017099 0.083362199, + 0.00267513 -0.054917399 0.0835471, + 0.00267513 -0.063410498 0.080124997, + 0 -0.063380897 0.080185503, + 0 -0.072000101 0.077016503, + -0.00267513 -0.063410901 0.080125503, + -0.00267513 -0.054917499 0.083547004, + -0.0053918599 -0.055017199 0.083361901, + -0.0053918599 -0.0507989 0.0850555, + -0.0081421202 -0.050976101 0.084740102, + -0.0081421202 -0.0466897 0.086291403, + -0.0109179 -0.046954099 0.085840397, + -0.0109179 -0.042611301 0.087246001, + -0.0137106 -0.042973101 0.086655498, + -0.0137106 -0.038584702 0.087914102, + -0.0165099 -0.0390536 0.087182701, + -0.0165099 -0.034632798 0.088293403, + -0.019305199 -0.035218801 0.087421201, + -0.019305199 -0.0307789 0.088383801, + -0.0220857 -0.031492501 0.087371498, + -0.0220857 -0.0270478 0.088187002, + -0.0248404 -0.0278995 0.087036602, + -0.0248404 -0.023463201 0.087707601, + -0.027557701 -0.0244615 0.086424999, + -0.027557701 -0.0200423 0.086954497, + -0.0302257 -0.0211937 0.085546598, + -0.0302257 -0.0168039 0.085937798, + -0.0328326 -0.0181148 0.0844118, + -0.0328326 -0.0159404 0.084559999, + -0.035366699 -0.0173914 0.082911901, + 0.044564299 -0.0140918 0.075676598, + 0.044564299 -0.0100355 0.075651497, + 0.0465803 -0.0082365898 0.073444702, + 0.048467699 -0.0066863499 0.071117997, + 0.050219599 -0.0072878301 0.068848602, + 0.051830001 -0.00809965 0.066526003, + 0.0532961 -0.00902458 0.064136498, + 0.0546159 -0.0100433 0.061691701, + 0.055787299 -0.0111617 0.059209701, + 0.056809202 -0.012374 0.056706801, + 0.0424264 -0.043350499 0.0147449, + 0.044564299 -0.041076601 0.0147962, + 0.043510102 -0.042697601 0.0151027, + 0.0424264 -0.0429377 0.0142816, + 0.048467699 -0.036666699 0.0152866, + 0.050219599 -0.034097001 0.015365, + 0.049361002 -0.0358219 0.0155887, + 0.048467699 -0.036223199 0.0149055, + 0.040174201 -0.044615 0.0131212, + 0.040382501 -0.044364698 0.0125353, + 0.0424264 -0.042476501 0.0131316, + 0.0424264 -0.0426373 0.0137258, + 0.044564299 -0.040379699 0.0137485, + 0.044564299 -0.040672999 0.0143175, + 0.0465803 -0.0383032 0.0143549, + 0.0465803 -0.038697399 0.0148498, + 0.0465803 -0.039151799 0.0152109, + 0.047540501 -0.038361602 0.0154881, + 0.040174201 -0.044780198 0.0137042, + 0.0378174 -0.046631601 0.0131115, + 0.038430501 -0.046055399 0.0125367, + 0.035840798 -0.048107401 0.0125383, + 0.0353604 -0.048447199 0.0125386, + 0.038435601 -0.0460652 0.00753668, + 0.0381575 -0.046291798 0.0125369, + 0.037812401 -0.046562299 0.0125371, + 0.040170401 -0.0445484 0.0125355, + 0.0429691 -0.041869 0.0075333398, + 0.044563901 -0.040162198 0.012532, + 0.046453901 -0.0379625 0.0125302, + 0.044564299 -0.040223502 0.0131424, + 0.046577401 -0.037803601 0.0125301, + 0.0470348 -0.0372153 0.0125296, + 0.0465803 -0.037865799 0.0131537, + 0.0465803 -0.038017299 0.0137722, + 0.0532961 -0.0298764 0.016262401, + 0.0532961 -0.0291494 0.0158529, + 0.0546159 -0.027086301 0.0164304, + 0.0546159 -0.0285271 0.017266599, + 0.055787299 -0.0256519 0.017559201, + 0.055787299 -0.0270351 0.0184799, + 0.056809202 -0.025415501 0.019904001, + 0.056809202 -0.0240862 0.018899599, + 0.0576833 -0.023675101 0.0215693, + 0.055787299 -0.024258001 0.0166006, + 0.0546159 -0.0263821 0.0159624, + 0.0532961 -0.0287483 0.0155279, + 0.051830001 -0.031453598 0.0154455, + 0.051830001 -0.0310333 0.0150224, + 0.050219599 -0.033664901 0.0149632, + 0.050219599 -0.0332908 0.0144342, + 0.048467699 -0.035838999 0.0143939, + 0.048467699 -0.035560898 0.0137969, + 0.048467699 -0.0354142 0.0131654, + 0.048260398 -0.0356385 0.0125284, + 0.047047202 -0.037229002 0.0075296499, + 0.0445357 -0.040194999 0.012532, + 0.0429601 -0.041856501 0.0125333, + 0.0425102 -0.042330801 0.0125337, + 0.0424245 -0.042412799 0.0125338, + 0.051830001 -0.031866599 0.015745301, + 0.051830001 -0.0322343 0.0159427, + 0.050219599 -0.034521502 0.015640199, + 0.050219599 -0.0348997 0.015810199, + 0.051830001 -0.032615699 0.016097501, + 0.0532961 -0.0313632 0.016977999, + 0.0546159 -0.0299567 0.0180643, + 0.055787299 -0.0284111 0.019359101, + 0.056809202 -0.026733501 0.020893, + 0.0576833 -0.024950501 0.0225945, + 0.058412101 -0.0218425 0.0233972, + 0.058412101 -0.023182999 0.0244589, + 0.058998398 -0.0200451 0.0253837, + 0.058998398 -0.021505 0.0265729, + 0.059445001 -0.0183597 0.027618, + 0.059445001 -0.019963499 0.0289103, + 0.059757002 -0.0168352 0.030070201, + 0.059757002 -0.018606501 0.031438801, + 0.0599402 -0.0155133 0.032707602, + 0.0599402 -0.017470401 0.034121301, + 0.059999999 -0.0144051 0.035502199, + 0.059999999 -0.016562 0.036926299, + 0.0599402 -0.0135109 0.038426299, + 0.0599402 -0.0158724 0.039824098, + 0.059757002 -0.0128213 0.041451398, + 0.059757002 -0.0153867 0.042785201, + 0.059445001 -0.0123276 0.0445459, + 0.059445001 -0.0150874 0.045780201, + 0.058998398 -0.0120364 0.047666099, + 0.058998398 -0.0149746 0.0487656, + 0.058412101 -0.0119524 0.050762601, + 0.058412101 -0.0150447 0.051697802, + 0.0576833 -0.0120691 0.053790402, + 0.0576833 -0.0152876 0.054534901, + 0.056809202 -0.015692901 0.057245702, + 0.055787299 -0.016228201 0.059799001, + 0.0546159 -0.016952399 0.062203102, + 0.0532961 -0.0179825 0.0645568, + 0.051830001 -0.019227199 0.066850103, + 0.050219599 -0.020679399 0.069054097, + 0.048467699 -0.022340599 0.071145304, + 0.0465803 -0.0242121 0.073101699, + 0.044564299 -0.0262929 0.074901298, + 0.0424264 -0.028580001 0.076521903, + 0.040174201 -0.0310675 0.077942498, + 0.0378174 -0.033744399 0.079148099, + 0.035366699 -0.0366042 0.0801256, + 0.0328326 -0.0396352 0.080852903, + 0.0302257 -0.042817801 0.081315801, + 0.027557701 -0.046129599 0.081506297, + 0.0248404 -0.049548201 0.081417799, + 0.0220857 -0.0530532 0.081044801, + 0.019305199 -0.056623399 0.080385499, + 0.0165099 -0.064538002 0.077849798, + 0.0137106 -0.072722197 0.0754169, + 0.0109179 -0.081142299 0.073097996, + 0.0081421202 -0.089765102 0.070902601, + 0.0053918599 -0.098557703 0.068841502, + 0.00267513 -0.107489 0.066925503, + 0 -0.116529 0.065162897, + -0.00267513 -0.10749 0.0669268, + -0.0053918599 -0.098559797 0.068844602, + -0.0081421202 -0.089768201 0.070907302, + -0.0109179 -0.081146203 0.073103704, + -0.0137106 -0.072726198 0.075422198, + -0.0165099 -0.064540699 0.0778528, + -0.019305199 -0.056623802 0.0803845, + -0.0220857 -0.0530532 0.0810441, + -0.0248404 -0.049548302 0.081416003, + -0.027557701 -0.046130098 0.0815029, + -0.0302257 -0.042818699 0.081310801, + -0.0328326 -0.039636102 0.080846898, + -0.035366699 -0.036603998 0.080120496, + -0.0378174 -0.033742599 0.079145499, + -0.040174201 -0.0310665 0.077939399, + -0.0424264 -0.0285792 0.076516703, + -0.044564299 -0.026292199 0.074893303, + -0.0465803 -0.0242119 0.073090501, + -0.048467699 -0.022342499 0.071130998, + -0.050219599 -0.020686001 0.069037601, + -0.051830001 -0.0192426 0.066832803, + -0.0532961 -0.018007999 0.064541198, + -0.0546159 -0.016969699 0.062191699, + -0.055787299 -0.0162265 0.059789699, + -0.056809202 -0.0156953 0.057230901, + -0.0576833 -0.0152961 0.054513201, + -0.058412101 -0.0150587 0.0516707, + -0.058998398 -0.0149936 0.048737399, + -0.059445001 -0.0151108 0.045753799, + -0.059757002 -0.0154136 0.042762399, + -0.0599402 -0.0159015 0.0398058, + -0.059999999 -0.016592501 0.036912698, + -0.0599402 -0.0175013 0.0341121, + -0.059757002 -0.018636899 0.031433798, + -0.059445001 -0.0199927 0.0289109, + -0.058998398 -0.021531699 0.026579499, + -0.058412101 -0.0232019 0.024454501, + -0.0576833 -0.0249555 0.022572, + -0.056809202 -0.0267331 0.020892801, + -0.055787299 -0.0284106 0.0193593, + -0.0546159 -0.029956101 0.0180611, + -0.0532961 -0.031362999 0.0169753, + -0.051830001 -0.032619599 0.016093099, + -0.051042698 -0.0332059 0.015675001, + -0.050219599 -0.034115002 0.0153464, + -0.048467699 -0.0366841 0.0152687, + -0.049361002 -0.0358251 0.0155719, + -0.0465803 -0.038726699 0.0148385, + -0.044564299 -0.040702298 0.0143152, + -0.0424264 -0.042648699 0.0137239, + -0.040174201 -0.044598799 0.0131096, + -0.045067899 -0.039601501 0.00753154, + -0.046573199 -0.037800301 0.0125301, + -0.048901699 -0.0347577 0.0075276801, + -0.040756401 -0.044025499 0.0075350599, + -0.042423598 -0.042412098 0.0125338, + -0.0308876 -0.051431298 0.0075409599, + -0.033201002 -0.0499654 0.0125398, + -0.036012899 -0.047982801 0.0075382101, + -0.0254349 -0.054334499 0.00754327, + -0.028145101 -0.052977599 0.0125422, + -0.037937399 -0.0464723 0.012537, + -0.0401715 -0.044555798 0.0125355, + -0.0445593 -0.040158201 0.012532, + -0.049792401 -0.033465501 0.0125267, + -0.048886999 -0.034743302 0.0125277, + -0.058998398 -0.0175565 0.022922, + -0.059445001 -0.015665799 0.024970699, + -0.059757002 -0.0138616 0.0272073, + -0.0599402 -0.0122049 0.0296789, + -0.059999999 -0.0107146 0.032350998, + -0.0599402 -0.0094052702 0.0352205, + -0.059757002 -0.0082818102 0.038265601, + -0.059445001 -0.0073502902 0.041456301, + -0.058998398 -0.0066325502 0.044749402, + -0.058412101 -0.0061499602 0.0480945, + -0.0576833 -0.00591115 0.051440701, + -0.056809202 -0.0059164301 0.054735702, + -0.055787299 -0.0061555901 0.057932701, + -0.0546159 -0.0049116998 0.0605276, + -0.0532961 -0.0037799799 0.063098103, + -0.051830001 -0.00276945 0.065627404, + -0.050219599 -0.00188797 0.068098001, + -0.048467699 -0.00113976 0.070492297, + -0.0465803 -0.00051716599 0.072791897, + -0.044564299 -4.1022999e-005 0.074985303, + -0.0424264 0.000184955 0.077087902, + -0.040174201 -0.00184733 0.079277299, + -0.0378174 -0.00412816 0.0813061, + -0.027557701 -0.0089570703 0.087591201, + -0.0248404 -0.0100626 0.088774703, + -0.027557701 -0.00674188 0.087600797, + -0.0302257 -0.0080175595 0.086253896, + -0.0302257 -0.00582546 0.086236298, + -0.0328326 -0.0072488398 0.084769703, + -0.0328326 -0.0050824601 0.084726803, + -0.035366699 -0.0066547301 0.083145797, + -0.035366699 -0.0045165699 0.0830798, + -0.0378174 -0.0062358198 0.081392802, + -0.0248404 -0.0145361 0.088577703, + -0.0220857 -0.0135825 0.089687802, + -0.0220857 -0.0180858 0.089346804, + -0.019305199 -0.017283199 0.090328202, + -0.019305199 -0.0218042 0.089839198, + -0.0165099 -0.021143001 0.090688698, + -0.0165099 -0.0256691 0.090048999, + -0.0137106 -0.025139101 0.090764798, + -0.0137106 -0.0296595 0.089971997, + -0.0109179 -0.0292501 0.090552799, + -0.0109179 -0.033751201 0.089605696, + -0.0081421202 -0.033451799 0.090051502, + -0.0081421202 -0.037920401 0.088950403, + -0.0053918599 -0.037719499 0.0892637, + -0.0053918599 -0.042143099 0.088010304, + -0.00267513 -0.0420301 0.088194899, + -0.00267513 -0.046396598 0.0867915, + 0 -0.046361201 0.086851902, + 0 -0.050660901 0.085301101, + 0.00267513 -0.046396598 0.086791702, + 0.00267513 -0.0420301 0.088195197, + 0.0053918599 -0.042142998 0.088010997, + 0.0053918599 -0.037719399 0.089264601, + 0.0081421202 -0.037920099 0.088951699, + 0.0081421202 -0.033451501 0.090052903, + 0.0109179 -0.033750899 0.089607701, + 0.0109179 -0.029250201 0.090554401, + 0.0137106 -0.029659601 0.089974001, + 0.0137106 -0.025139799 0.0907657, + 0.0165099 -0.025669901 0.090050198, + 0.0165099 -0.021143399 0.090690002, + 0.019305199 -0.0218047 0.089840703, + 0.019305199 -0.0172836 0.090330601, + 0.0220857 -0.018086201 0.089349501, + 0.0220857 -0.0135829 0.089691803, + 0.0248404 -0.016772401 0.088423401, + 0.040174201 -0.0122441 0.079632297, + 0.040174201 -0.014338 0.0795912, + 0.0424264 -0.0120707 0.0777082, + 0.0378174 -0.012584 0.081442401, + 0.0378174 -0.0147071 0.0813803, + 0.035366699 -0.013091 0.083127901, + 0.035366699 -0.0152413 0.083042599, + 0.0328326 -0.0137657 0.084677704, + 0.0328326 -0.0159408 0.084566899, + 0.0302257 -0.014607 0.086081401, + 0.0302257 -0.016804401 0.0859432, + 0.027557701 -0.0156109 0.0873321, + 0.027557701 -0.0178279 0.087164603, + 0.0248404 -0.019006301 0.088225, + 0.0220857 -0.022577699 0.088847801, + 0.019305199 -0.026305599 0.089191899, + 0.0165099 -0.0301685 0.089252301, + 0.0137106 -0.034143802 0.089023203, + 0.0109179 -0.0382073 0.088504098, + 0.0081421202 -0.0423356 0.087696798, + 0.0053918599 -0.046505 0.086606897, + 0.00267513 -0.050694801 0.085240699, + 0 -0.054884799 0.083607398, + -0.00267513 -0.050694801 0.085240602, + -0.0053918599 -0.046505101 0.086606503, + -0.0081421202 -0.042335801 0.0876958, + -0.0109179 -0.038207602 0.088502303, + -0.0137106 -0.0341441 0.089020699, + -0.0165099 -0.030168399 0.089249797, + -0.019305199 -0.026304699 0.089190602, + -0.0220857 -0.0225772 0.088846102, + -0.0248404 -0.0190058 0.0882219, + -0.027557701 -0.0156104 0.0873271, + -0.0302257 -0.0146066 0.086075097, + -0.0328326 -0.0137656 0.084669799, + -0.035366699 -0.0130915 0.083118401, + 0.0424264 -0.0100109 0.077694103, + 0.040174201 -0.0101525 0.079636604, + 0.0378174 -0.0104624 0.081467398, + 0.035366699 -0.0109418 0.083175503, + 0.0328326 -0.0115909 0.084750101, + 0.0302257 -0.0124092 0.086180702, + 0.027557701 -0.0133927 0.087460198, + 0.0248404 -0.0145365 0.088582203, + 0.0248404 -0.0122997 0.088701203, + 0.027557701 -0.0111743 0.087548897, + 0.0302257 -0.010212 0.086241201, + 0.0328326 -0.0094175003 0.084784098, + 0.035366699 -0.0087944698 0.0831853, + 0.0378174 -0.0083435504 0.081455097, + 0.040174201 -0.0080640204 0.079604201, + 0.0424264 -0.0079546496 0.077643998, + 0.044564299 -0.0059980201 0.075486198, + 0.0465803 -0.0042963298 0.073193401, + 0.048467699 -0.0047854399 0.070969298, + 0.050219599 -0.00549642 0.068680197, + 0.051830001 -0.0063308901 0.066311501, + 0.0532961 -0.00726985 0.063874297, + 0.0546159 -0.0083198901 0.061387099, + 0.055787299 -0.0094757099 0.058867, + 0.056809202 -0.0090977997 0.0558801, + 0.0576833 -0.0089230398 0.0527642, + 0.058412101 -0.0089660203 0.049564, + 0.058998398 -0.0092355097 0.046325698, + 0.059445001 -0.0097292596 0.043100599, + 0.059757002 -0.0104361 0.039937802, + 0.0599402 -0.0113399 0.036883101, + 0.059999999 -0.0124441 0.033966601, + 0.0599402 -0.0137482 0.0312148, + 0.059757002 -0.0152482 0.0286521, + 0.059445001 -0.016927101 0.026302701, + 0.058998398 -0.018741701 0.024197999, + 0.058412101 -0.0206124 0.022246599, + 0.0576833 -0.021121399 0.019321401, + 0.056809202 -0.021403201 0.016772401, + 0.055787299 -0.0235766 0.0160734, + 0.0546159 -0.025993001 0.0156117, + 0.0532961 -0.028340001 0.0150831, + 0.051830001 -0.0306697 0.0144756, + 0.050219599 -0.033020802 0.0138224, + 0.0499507 -0.0332288 0.0125265, + -0.0576833 -0.0030304899 0.04989, + -0.058412101 -0.0034870701 0.046427101, + -0.058998398 -0.0042004902 0.0430048, + -0.059445001 -0.0051513002 0.039675899, + -0.059757002 -0.0063120602 0.0364892, + -0.0599402 -0.00765137 0.033486798, + -0.059999999 -0.0091581997 0.0306914, + -0.0599402 -0.0108176 0.0281044, + -0.059757002 -0.0126176 0.0257579, + -0.059445001 -0.0145202 0.0235934, + -0.058998398 -0.0151898 0.020161999, + -0.058412101 -0.015663199 0.0171133, + -0.0576833 -0.017902 0.016278399, + -0.056809202 -0.0200455 0.0152567, + -0.055787299 -0.0225222 0.0146022, + -0.0546159 -0.025024701 0.0139005, + -0.0532961 -0.0275806 0.0131871, + -0.0528326 -0.028426399 0.0125226, + -0.052201699 -0.0295325 0.0125235, + -0.0522171 -0.0295453 0.0075235302, + -0.051817201 -0.0302068 0.0125241, + -0.050207902 -0.032813501 0.0125261, + -0.053282399 -0.027539199 0.0125219, + -0.054979 -0.024019601 0.0075191301, + -0.054163702 -0.0258011 0.0125205, + -0.054601099 -0.0248222 0.0125198, + -0.054964401 -0.024009099 0.0125191, + -0.0546159 -0.0248616 0.0131996, + -0.055364501 -0.023113601 0.0125184, + -0.055787299 -0.022264 0.0139282, + -0.056809202 -0.0197274 0.0146464, + -0.0576833 -0.017224399 0.0153198, + -0.058412101 -0.0150512 0.0163908, + -0.058998398 -0.0127958 0.0172858, + -0.059445001 -0.0122465 0.0205808, + -0.059757002 -0.0115165 0.024257701, + -0.0599402 -0.0096097598 0.0265346, + -0.059999999 -0.0077972198 0.028994599, + -0.0599402 -0.0061114701 0.031703901, + -0.059757002 -0.0045643998 0.034631301, + -0.059445001 -0.00317744 0.037774999, + -0.058998398 -0.00198701 0.0411015, + -0.058412101 -0.00103064 0.044562999, + -0.0576833 -0.00033409201 0.048108801, + -0.056809202 8.44639e-005 0.051683001, + -0.055787299 0.00172404 0.054380801, + -0.0546159 0.0032484101 0.0571029, + -0.0532961 0.0046449401 0.0598308, + -0.051830001 0.0059024398 0.062546201, + -0.050219599 0.0070112399 0.065230198, + -0.048467699 0.0079631004 0.067863598, + -0.0465803 0.0087518198 0.070427001, + -0.044564299 0.0093716597 0.072902903, + -0.0424264 0.0098176897 0.075273901, + -0.040174201 0.0100867 0.077523202, + -0.0378174 0.0101815 0.0796353, + -0.035366699 0.0101179 0.081594698, + -0.0328326 0.0098789698 0.083393402, + -0.0302257 0.0093588103 0.085053697, + -0.027557701 0.0064515499 0.086844198, + -0.0248404 0.00550659 0.0882219, + -0.0220857 0.0043818201 0.089455202, + -0.055787299 -0.022105301 0.0132123, + -0.055771399 -0.022067901 0.0125176, + -0.056432001 -0.020370601 0.0125162, + -0.056809202 -0.019323099 0.0132251, + -0.0576833 -0.0165262 0.0132381, + -0.057145901 -0.0182312 0.0125145, + -0.058412101 -0.0138705 0.0140124, + -0.058998398 -0.0112965 0.0147795, + -0.059445001 -0.00878001 0.0155092, + -0.059757002 -0.0065849698 0.016724899, + -0.0599402 -0.0043462701 0.0177943, + -0.059999999 -0.00361019 0.0218096, + -0.0599402 -0.0026701 0.026213801, + -0.059757002 -0.00063247501 0.0288529, + -0.059445001 0.00135199 0.0316911, + -0.058998398 0.0032158301 0.034803301, + -0.058412101 0.0049084001 0.0381434, + -0.0576833 0.0063760998 0.041693699, + -0.056809202 0.0075771199 0.0454101, + -0.055787299 0.0084758298 0.049236398, + -0.0546159 0.0103579 0.051968601, + -0.0532961 0.0121097 0.054745801, + -0.051830001 0.0137148 0.057549398, + -0.050219599 0.0151594 0.060360301, + -0.048467699 0.0164304 0.063158698, + -0.0465803 0.0175178 0.065924197, + -0.044564299 0.0184124 0.068635702, + -0.0424264 0.019107601 0.0712732, + -0.040174201 0.019598501 0.073817201, + -0.0378174 0.0198844 0.076249503, + -0.035366699 0.0199659 0.078552298, + -0.0328326 0.019843601 0.0807105, + -0.0302257 0.0195194 0.0827097, + -0.027557701 0.0189995 0.084538899, + -0.0248404 0.018294301 0.086187698, + -0.0220857 0.017426901 0.087645002, + -0.019305199 0.016386401 0.088909298, + -0.0165099 0.01507 0.090012603, + -0.0137106 0.0113155 0.091278702, + -0.0109179 0.0073506301 0.092298299, + -0.0081421202 0.0031976099 0.093053699, + -0.0053918599 -0.00111985 0.093537897, + -0.00267513 -0.0055779698 0.093747698, + 0 -0.0101534 0.093681097, + 0.00267513 -0.0055780001 0.093748398, + 0.0053918599 -0.0011196299 0.093539499, + 0.0081421202 0.00319868 0.093056403, + 0.0109179 0.0073538702 0.092302002, + 0.0137106 0.0113221 0.091282703, + 0.0165099 0.0150753 0.090016, + 0.019305199 0.0163876 0.088912398, + 0.0220857 0.0174262 0.087648697, + 0.0248404 0.018293999 0.086192802, + 0.027557701 0.019000599 0.084546, + 0.0302257 0.019522401 0.082719401, + 0.0328326 0.019848499 0.080722898, + 0.035366699 0.0199729 0.078567497, + 0.0378174 0.0198934 0.076266997, + 0.040174201 0.0196098 0.073836498, + 0.0424264 0.0191213 0.0712936, + 0.044564299 0.018428501 0.0686564, + 0.0465803 0.0175361 0.065944798, + 0.048467699 0.016450999 0.0631788, + 0.050219599 0.0151819 0.060379401, + 0.051830001 0.0137391 0.057567202, + 0.0532961 0.0121355 0.054761998, + 0.0546159 0.0103851 0.051982999, + 0.055787299 0.0085041597 0.049249001, + 0.056809202 0.0076064202 0.045418799, + 0.0576833 0.00640547 0.041698601, + 0.058412101 0.00493709 0.0381428, + 0.058998398 0.00324262 0.0347968, + 0.059445001 0.00137125 0.0316955, + 0.059757002 -0.0006273 0.0288761, + 0.0599402 -0.0026705801 0.026214, + 0.059999999 -0.0036108301 0.021813, + 0.0599402 -0.0043417802 0.0177994, + 0.059757002 -0.0065810601 0.0167452, + 0.059445001 -0.0087425197 0.0155236, + 0.058998398 -0.0112577 0.0147826, + 0.058412101 -0.0138548 0.0140149, + 0.058412101 -0.0137486 0.013268, + 0.058866698 -0.0115948 0.0125092, + 0.058398601 -0.013696 0.0125109, + 0.058021698 -0.0152727 0.0075121601, + 0.058226701 -0.0144679 0.0125115, + 0.058007602 -0.0152648 0.0125122, + 0.057669599 -0.0164946 0.0125131, + -0.056809202 0.0095678195 0.0430029, + -0.0576833 0.0080983099 0.039326102, + -0.058412101 0.0063810698 0.035854999, + -0.058998398 0.0044700601 0.0326101, + -0.059445001 0.0024157299 0.029640101, + -0.059757002 0.00029395401 0.026869301, + -0.0599402 -0.00075900799 0.022215201, + -0.059999999 -0.00158619 0.0179605, + -0.0599402 -0.00382597 0.0168339, + -0.058157299 -0.014744 0.0125117, + -0.0573637 -0.017578499 0.012514, + -0.0576673 -0.0164939 0.0125131, + -0.057158101 -0.018239301 0.0075145299, + -0.056793101 -0.0192883 0.0125154, + -0.058731299 -0.0122655 0.0075097699, + -0.058396202 -0.0136953 0.0125109, + -0.058811001 -0.0118741 0.0125095, + -0.058982499 -0.0109035 0.0125087, + -0.059323099 -0.0089755096 0.0125072, + -0.0594301 -0.0081293797 0.0125065, + -0.0546159 0.017591201 0.042845398, + -0.0546159 0.0158881 0.0455954, + -0.0532961 0.019878 0.045439299, + -0.055787299 0.0144521 0.041681699, + -0.0546159 0.013889 0.0482536, + -0.0532961 0.018027199 0.0482735, + -0.055787299 0.0127427 0.044305202, + -0.056809202 0.0112837 0.040507, + -0.056809202 0.0127221 0.037962001, + -0.0576833 0.0095539102 0.036909301, + -0.0576833 0.0107534 0.034461901, + -0.058412101 0.00760801 0.033535, + -0.058412101 0.0085974801 0.031236701, + -0.058998398 0.0054968102 0.030435801, + -0.058998398 0.0063338899 0.028205, + -0.059445001 0.0032977201 0.0275336, + -0.059445001 0.0050261701 0.0230384, + -0.059757002 0.00211434 0.022624001, + -0.059757002 0.00395549 0.018293999, + -0.0599402 0.00117393 0.018126599, + -0.0599402 0.00164945 0.0170501, + -0.059999999 -0.00108828 0.016942, + -0.059999999 -0.00056159502 0.015693599, + -0.0599402 -0.0032748401 0.0156327, + -0.0599402 -0.0028235901 0.0141233, + -0.059757002 -0.00553875 0.014096, + -0.059757002 -0.0054073599 0.0132896, + -0.059679601 -0.0061574001 0.0125049, + -0.059445001 -0.0081543103 0.0132768, + -0.059757002 0.0044084499 0.017159101, + -0.059445001 0.0067743598 0.0184636, + -0.059757002 0.00488608 0.015815901, + -0.0599402 0.0021516799 0.0157545, + -0.0599402 0.0025649699 0.0141774, + -0.059999999 -0.00012932099 0.0141503, + -0.059999999 -7.0921701e-006 0.0133147, + -0.0599402 -0.00269674 0.0133022, + -0.059999 -0.00033305801 0.0125003, + -0.059931099 -0.0026764099 0.0125021, + -0.059999999 7.5646799e-006 0.0074999998, + -0.059918199 -0.0031204999 0.0125025, + -0.058998398 0.0079693701 0.023457199, + -0.058412101 0.0093893697 0.0288806, + -0.0576833 0.0117056 0.032039501, + -0.056809202 0.0138944 0.035387602, + -0.055787299 0.0158737 0.039009199, + 0.050219599 0.0291108 0.0398711, + 0.050219599 0.028633701 0.041459799, + 0.051830001 0.026182 0.039007999, + 0.048467699 0.031957898 0.0407103, + 0.048467699 0.032341801 0.039074302, + 0.0465803 0.0350799 0.039830402, + 0.0465803 0.035367299 0.038169, + 0.044564299 0.037983801 0.038844399, + 0.044564299 0.038342599 0.035283402, + 0.0424264 0.0408068 0.035828199, + 0.0424264 0.0413871 0.028215, + 0.040174201 0.043654501 0.028537501, + 0.040174201 0.0441733 0.020718399, + 0.0378174 0.046243101 0.0208429, + 0.040174201 0.044449002 0.016715201, + 0.0424264 0.042291999 0.0166671, + 0.0424264 0.042406101 0.0145794, + 0.044564299 0.0401491 0.0145568, + 0.042958502 0.041878 0.0124667, + 0.0465803 0.0377874 0.0145331, + 0.048467699 0.035331499 0.0145085, + 0.047033701 0.037237499 0.0124704, + 0.0465803 0.037641399 0.016563199, + 0.050219599 0.032791801 0.0144831, + 0.0498452 0.033409901 0.0124734, + 0.048467699 0.035168398 0.016507899, + 0.0465803 0.037246302 0.0203017, + 0.044564299 0.039666001 0.020447301, + 0.044564299 0.038998298 0.0278752, + 0.0424264 0.0419783 0.020586399, + 0.044564299 0.0400194 0.0166163, + 0.046333499 0.038132399 0.0124696, + 0.0465803 0.035764098 0.034713101, + 0.048467699 0.032646399 0.037466701, + 0.050219599 0.029510399 0.038292199, + 0.059445001 0.0079036197 0.0150853, + 0.059445001 0.0080478098 0.0142349, + 0.058998398 0.0104954 0.015955299, + 0.059757002 0.0052962699 0.0142073, + 0.059702002 0.0059841401 0.0124952, + 0.059431199 0.0081526199 0.0124935, + 0.059337199 0.0089049097 0.0124929, + 0.059285302 0.0092409896 0.0074926401, + 0.056793701 0.019311599 0.0124846, + 0.056809202 0.019234899 0.0143471, + 0.057391401 0.017511001 0.0124861, + 0.056464098 0.020304499 0.0124838, + 0.056143001 0.0211727 0.0074831401, + 0.0576679 0.0165172 0.0124869, + 0.058021698 0.0152879 0.0074878298, + 0.055400901 0.023049301 0.0124817, + 0.055771999 0.022091201 0.0124824, + 0.054601699 0.0248456 0.0124802, + 0.0546159 0.0247823 0.0144028, + 0.054204401 0.025738601 0.0124795, + 0.053669199 0.026833201 0.0074786399, + 0.0528774 0.028365999 0.0124774, + 0.0532832 0.0275626 0.0124781, + 0.051817998 0.030230399 0.0124759, + 0.051830001 0.030179201 0.0144569, + 0.051423199 0.030925101 0.0124754, + 0.050626501 0.0322094 0.0074743498, + 0.048459399 0.035372298 0.0124718, + 0.047047202 0.037244201 0.0074703498, + 0.048147298 0.0358142 0.0124715, + 0.0424252 0.0424367 0.0124662, + 0.0429691 0.041884098 0.0074666501, + 0.042376 0.042488299 0.0124662, + 0.0402418 0.044515401 0.0124646, + 0.040174201 0.0445484 0.0146008, + 0.038010798 0.046435501 0.012463, + 0.038435601 0.046080299 0.0074633099, + 0.037814599 0.046588201 0.0124629, + 0.0378174 0.046568699 0.0146211, + 0.0356883 0.048243701 0.0124616, + 0.033491299 0.049787398 0.0124604, + 0.035362199 0.048472799 0.0124614, + 0.033494599 0.049788099 0.0074603599, + 0.035366699 0.0484601 0.01464, + 0.0328326 0.0501546 0.016842499, + 0.0332799 0.049936 0.0124602, + 0.0328269 0.050222099 0.01246, + 0.0307914 0.051507998 0.012459, + 0.0302257 0.0516329 0.021167001, + 0.028228801 0.052956201 0.0124578, + 0.030219801 0.051831 0.0124587, + 0.0281986 0.0529682 0.0074578198, + 0.035366699 0.0483873 0.016803101, + 0.0328326 0.049979601 0.021067601, + 0.0328326 0.049652699 0.029390801, + 0.035366699 0.047794599 0.0291264, + 0.035366699 0.047416601 0.037289899, + 0.0378174 0.045351502 0.036833201, + 0.035366699 0.047322601 0.039331201, + 0.0328326 0.0493333 0.037713699, + 0.0302257 0.0513607 0.029633701, + 0.027557701 0.053137999 0.021257401, + 0.028198199 0.052971501 0.0124578, + 0.0275518 0.053296 0.0124576, + 0.0255982 0.054276899 0.0124568, + 0.0226037 0.055586901 0.0074557401, + 0.0167691 0.057616498 0.0074541201, + 0.0193005 0.0568063 0.0124548, + -0.040171701 0.044572901 0.0124645, + -0.040174201 0.044537701 0.0145991, + -0.038084399 0.0463751 0.0124631, + -0.040312301 0.044451501 0.0124646, + -0.040756401 0.044040602 0.0074649299, + -0.045056298 0.039610699 0.0124685, + -0.044562198 0.040183902 0.012468, + -0.045067899 0.0396166 0.0074684601, + -0.046393901 0.038058899 0.0124697, + -0.0465803 0.037774902 0.0145311, + -0.0546159 0.0201139 0.037220702, + -0.055787299 0.017018599 0.0363084, + -0.0546159 0.018996 0.040046599, + -0.059746899 0.0054081799 0.0124957, + -0.059682 0.0061768098 0.0074950801, + -0.059927799 0.00295392 0.0124977, + -0.0597114 0.0058894102 0.0124953, + -0.059757002 0.0053930799 0.01334, + -0.059934001 0.0026996301 0.0124979, + -0.059999999 1.15461e-005 0.0125, + -0.0599402 0.0026825599 0.0133273, + -0.059757002 0.00528024 0.0142046, + -0.059445001 0.0080318796 0.0142323, + -0.059445001 0.0076571498 0.0158781, + -0.058998398 0.0104582 0.0159411, + -0.058998398 0.0096236104 0.0186351, + -0.058412101 0.012491 0.0188077, + -0.058412101 0.0109313 0.0238786, + -0.0576833 0.0139003 0.024301, + -0.0576833 0.0124521 0.029557901, + -0.056809202 0.0155105 0.030234201, + -0.056809202 0.0148091 0.032841101, + -0.055787299 0.0178963 0.0336386, + -0.048467699 0.035318501 0.0145064, + -0.048887499 0.0347667 0.0124723, + -0.050219599 0.0327783 0.0144809, + -0.048204001 0.035737801 0.0124715, + -0.0465803 0.037611999 0.016551999, + -0.044564299 0.039991301 0.016605601, + -0.044564299 0.0396626 0.020443499, + -0.0424264 0.0419752 0.020582801, + -0.044564299 0.038998801 0.0278726, + -0.0465803 0.0372428 0.020297799, + -0.048467699 0.035137899 0.0164961, + -0.052201401 0.0295555 0.0124765, + -0.051819 0.030231001 0.0124759, + -0.0522171 0.029560501 0.0074764602, + -0.051830001 0.030232901 0.013457, + -0.051472198 0.0308435 0.0124754, + -0.050209999 0.032838002 0.0124739, + -0.052922402 0.0282821 0.0124775, + -0.053284001 0.027563101 0.0124781, + -0.054245099 0.0256526 0.0124796, + -0.0532961 0.027563799 0.0134444, + -0.0546159 0.0215664 0.031573299, + -0.055787299 0.018552501 0.0309068, + -0.0546159 0.020954801 0.0344286, + -0.055787299 0.019814 0.0251425, + -0.056809202 0.016865101 0.024723001, + -0.056809202 0.018235199 0.0191535, + -0.0576833 0.0153652 0.018980701, + -0.0576833 0.0161027 0.0160679, + -0.058412101 0.013277 0.0160043, + -0.058412101 0.0136123 0.0142883, + -0.058998398 0.0108133 0.0142602, + -0.058998398 0.0109163 0.0133658, + -0.059445001 0.0081399204 0.0133528, + -0.059432399 0.0081528099 0.0124935, + -0.0596756 0.00618 0.0124951, + -0.059351299 0.0088107605 0.012493, + -0.058984298 0.0109269 0.0124913, + -0.058848299 0.0117109 0.0124907, + -0.058731299 0.0122807 0.00749022, + -0.055772699 0.0220915 0.0124824, + -0.056496199 0.0202149 0.0124839, + -0.055787299 0.022089399 0.0134184, + -0.051830001 0.028447401 0.026371101, + -0.051830001 0.0274585 0.032876201, + -0.050219599 0.0312123 0.026764501, + -0.051830001 0.0294479 0.0198285, + -0.0532961 0.0267085 0.0196635, + -0.0532961 0.0272546 0.016318699, + -0.0546159 0.0245116 0.016256999, + -0.0546159 0.0247676 0.0144004, + -0.055787299 0.022006501 0.0143726, + -0.056809202 0.019307701 0.0134053, + -0.056794401 0.019311899 0.0124846, + -0.0571438 0.018253701 0.0124855, + -0.057158101 0.0182545 0.0074854698, + -0.054979 0.0240348 0.0074808602, + -0.055437401 0.0229614 0.0124817, + -0.0546159 0.0248453 0.0134314, + -0.0532961 0.027491201 0.0144277, + -0.051830001 0.029947899 0.016379301, + -0.050219599 0.032124501 0.0199896, + -0.048467699 0.0339 0.027147001, + -0.050219599 0.030310599 0.033507001, + -0.051830001 0.027212501 0.034491401, + -0.0532961 0.0245394 0.032230798, + -0.058412101 0.0137104 0.013379, + -0.0576833 0.016511099 0.0133922, + -0.058203701 0.0145829 0.0124884, + -0.0576833 0.016418001 0.0143165, + -0.056809202 0.0192197 0.0143446, + -0.056809202 0.0189243 0.0161313, + -0.055787299 0.0217309 0.016194399, + -0.055787299 0.0210901 0.019325299, + -0.0546159 0.0239185 0.019495601, + -0.0546159 0.022735801 0.0255583, + -0.0532961 0.0256177 0.025968401, + -0.057419099 0.017419901 0.0124861, + -0.057668701 0.016517401 0.0124869, + -0.058397699 0.0137188 0.0124891, + -0.058720101 0.0122821 0.0124902, + -0.0532961 0.0239718 0.035207901, + -0.051830001 0.0269341 0.035973199, + -0.050219599 0.030086299 0.035182402, + -0.048467699 0.033083301 0.034120101, + -0.0465803 0.036499199 0.027516801, + -0.048467699 0.034726501 0.0201464, + -0.050219599 0.032579601 0.0164386, + -0.051830001 0.0301654 0.0144546, + -0.0546025 0.0248459 0.0124802, + -0.054963201 0.024031701 0.0124809, + -0.0465803 0.0357645 0.034713, + -0.048467699 0.032880001 0.0358539, + -0.050219599 0.0298285 0.036720999, + -0.051830001 0.026587 0.037471101, + -0.0532961 0.023167299 0.038120601, + -0.048901699 0.034772899 0.0074723102, + -0.0498982 0.033330798 0.0124735, + -0.048460599 0.0353733 0.0124718, + -0.0465759 0.037825499 0.0124699, + -0.042443302 0.042420998 0.0124662, + -0.036012899 0.047997899 0.0074617802, + -0.037813399 0.0465867 0.0124629, + -0.035366699 0.0484506 0.0146385, + -0.036008701 0.047996499 0.0124618, + -0.0378174 0.046558499 0.0146194, + -0.035366699 0.0483649 0.016794501, + -0.0328326 0.050133899 0.016834499, + -0.0328326 0.049977101 0.021064799, + -0.0302257 0.0517601 0.0168713, + -0.0328326 0.050206799 0.0146562, + -0.033358999 0.049883101 0.0124603, + -0.035361301 0.048471499 0.0124614, + -0.035764702 0.048187099 0.0124616, + -0.0378174 0.046459101 0.0167515, + -0.035366699 0.0481782 0.020956401, + -0.035366699 0.047795001 0.029124301, + -0.0378174 0.045793202 0.028839501, + -0.0378174 0.0453519 0.0368331, + -0.040174201 0.0431461 0.0363454, + -0.040174201 0.043019101 0.0382917, + -0.0424264 0.0406623 0.037725002, + -0.0424264 0.040480699 0.039473198, + -0.044564299 0.037980001 0.038827099, + -0.044564299 0.037703902 0.0405434, + -0.0465803 0.035070401 0.0398155, + -0.0465803 0.034696098 0.041518301, + -0.048467699 0.031942099 0.040706702, + -0.048467699 0.0314744 0.042360101, + -0.0465803 0.034241501 0.043227099, + -0.0465803 0.033705398 0.044933598, + -0.044564299 0.0373444 0.042298801, + -0.0424264 0.0402207 0.041239001, + -0.040174201 0.042854398 0.040086601, + -0.0378174 0.045241602 0.038826101, + -0.035366699 0.047416899 0.037289798, + -0.0328326 0.049653001 0.029388901, + -0.0302257 0.051630698 0.021164401, + -0.027557701 0.053240702 0.0169049, + -0.0302257 0.051821101 0.0146724, + -0.0308873 0.051449999 0.012459, + -0.0302191 0.051830001 0.0124587, + -0.0308876 0.051446401 0.0074590398, + -0.030873001 0.0514591 0.012459, + -0.0283127 0.0529113 0.0124579, + -0.0328261 0.050220899 0.01246, + -0.0254349 0.054349601 0.0074567199, + -0.0275514 0.053295098 0.0124576, + -0.025684301 0.0542362 0.0124568, + -0.027557701 0.0532909 0.0146873, + -0.0248404 0.054573599 0.016935, + -0.027557701 0.053135999 0.0212551, + -0.0302257 0.051360998 0.0296319, + -0.0328326 0.049333598 0.037713598, + -0.035366699 0.047322199 0.039326299, + -0.0378174 0.045092899 0.040665101, + -0.040174201 0.0426098 0.041899301, + -0.0424264 0.039875299 0.043044701, + -0.044564299 0.036902498 0.044060901, + 0.019305199 0.056641702 0.030384701, + 0.0220857 0.055695701 0.021411199, + 0.020158799 0.056523599 0.012455, + 0.040174201 0.041371599 0.047469899, + 0.0424264 0.038949199 0.046664599, + 0.040174201 0.041875701 0.045611098, + 0.0378174 0.044151202 0.046324499, + 0.0378174 0.044555601 0.0444232, + 0.035366699 0.046675801 0.045048099, + 0.0248404 0.054315399 0.030053999, + 0.0220857 0.055557899 0.030230699, + 0.0248404 0.054143298 0.038777299, + 0.027557701 0.052699301 0.038458001, + 0.027557701 0.052645199 0.040610101, + 0.0302257 0.051029101 0.040221799, + 0.0302257 0.050924499 0.0421836, + 0.0328326 0.049136501 0.041722301, + 0.0328326 0.048936401 0.043656599, + 0.035366699 0.046978999 0.043116301, + 0.0378174 0.0448705 0.042534102, + 0.040174201 0.042290699 0.043755598, + 0.0424264 0.0394627 0.0448546, + 0.044564299 0.036397099 0.045816202, + 0.0424264 0.0383467 0.0484729, + -0.0137813 0.058403399 0.0074534998, + -0.0197125 0.056676898 0.0074548698, + -0.0165058 0.057679798 0.0124541, + -0.0193002 0.056805499 0.0124548, + -0.019709 0.0566702 0.0124549, + -0.019305199 0.056812901 0.0147228, + -0.017454101 0.0574167 0.0124543, + -0.0165099 0.057672098 0.0170056, + -0.019305199 0.056789 0.0169855, + -0.019305199 0.056743301 0.021472501, + -0.0220857 0.055693999 0.021409299, + -0.0220857 0.0555581 0.030229401, + -0.0248404 0.054315601 0.0300525, + -0.0248404 0.0541435 0.038777199, + -0.027557701 0.052699499 0.0384579, + -0.027557701 0.052645002 0.040606301, + -0.0302257 0.051028799 0.040217701, + -0.0302257 0.050921801 0.042171799, + -0.0328326 0.049133699 0.041709598, + -0.0328326 0.048929699 0.043646201, + -0.035366699 0.046971802 0.043104999, + -0.035366699 0.046664398 0.045045499, + -0.0378174 0.0445433 0.044420298, + -0.0378174 0.044135898 0.0463273, + -0.040174201 0.0418594 0.045614101, + -0.040174201 0.041353401 0.047474299, + -0.0424264 0.038929999 0.0466692, + -0.0424264 0.038326401 0.048475999, + -0.044564299 0.036376901 0.045821, + -0.0424264 0.039445501 0.044857699, + -0.040174201 0.042277601 0.0437527, + -0.0378174 0.044862699 0.042521998, + -0.035366699 0.047188502 0.041206699, + -0.0328326 0.049253501 0.039790701, + -0.0302257 0.051095501 0.0381032, + -0.027557701 0.052916002 0.029853299, + -0.0248404 0.054491099 0.021336701, + -0.0220857 0.0557568 0.016961999, + -0.024834299 0.054613601 0.0124565, + -0.0254324 0.054347999 0.0124567, + -0.0248404 0.054613899 0.0147006, + -0.022994 0.055430599 0.0124559, + -0.0220799 0.055783801 0.0124556, + -0.0202484 0.056491598 0.012455, + -0.0220857 0.055788402 0.0147124, + -0.0146178 0.0582036 0.0124537, + -0.0109153 0.058995299 0.012453, + -0.0077038999 0.059510902 0.0074526099, + -0.0053910702 0.059758 0.0124524, + -0.0059254402 0.059718199 0.0124525, + -0.0053918599 0.059770498 0.021655301, + -0.00154487 0.059987601 0.0074522402, + -0.0029901101 0.0599369 0.0124523, + 0.0081421202 0.059426799 0.039945599, + 0.0053918599 0.059768301 0.040021099, + 0.0081421202 0.059423499 0.042238101, + 0.0109179 0.058931202 0.042119902, + 0.0109179 0.0588824 0.044235099, + 0.0137106 0.0582317 0.044067498, + 0.0137106 0.0580885 0.046182599, + 0.0165099 0.057274301 0.045958001, + 0.0165099 0.057027198 0.048099101, + 0.019305199 0.056045499 0.047809798, + 0.019305199 0.055695001 0.0499443, + 0.0220857 0.054542001 0.049582701, + 0.0220857 0.054087199 0.051697601, + 0.0248404 0.052760102 0.051256299, + 0.0248404 0.052200399 0.0533434, + 0.027557701 0.050700601 0.0528161, + 0.027557701 0.050035302 0.054866798, + 0.0302257 0.048365399 0.054247402, + 0.027557701 0.049267702 0.056905702, + 0.0248404 0.0515384 0.0554244, + 0.0220857 0.053531501 0.053811599, + 0.019305199 0.055244699 0.052082699, + 0.0165099 0.056681201 0.0502537, + 0.0137106 0.057845701 0.048340399, + 0.0109179 0.058743201 0.0463631, + 0.0081421202 0.059378099 0.044362601, + 0.0053918599 0.0597676 0.042320501, + 0.00267513 0.059968699 0.040065501, + -0.00267513 0.055976201 0.0620359, + 0 0.0560451 0.0620641, + -0.00267513 0.0568415 0.059864599, + 0 0.055072401 0.064209402, + 0.00267513 0.055977602 0.062036101, + 0 0.056910399 0.059891298, + 0 0.057667401 0.0576992, + 0.00267513 0.056842901 0.0598647, + 0.0053918599 0.055769101 0.061950501, + 0.00267513 0.055004898 0.064180098, + 0 0.053993199 0.066318698, + -0.00267513 0.055003501 0.0641798, + -0.0053918599 0.0557664 0.061950099, + 0.00267513 0.058789499 0.0532628, + 0 0.058856599 0.053285498, + 0.00267513 0.058248099 0.055471402, + 0.0053918599 0.0580405 0.0553982, + 0.0053918599 0.0573918 0.057596501, + 0.0081421202 0.057036899 0.0574646, + 0.0081421202 0.0562791 0.0596442, + 0.0109179 0.0557702 0.059445299, + 0.0081421202 0.055413499 0.061804499, + 0.0053918599 0.056634501 0.059783202, + 0.00267513 0.057599802 0.057673801, + 0 0.058315501 0.055495501, + -0.00267513 0.058246799 0.055471599, + -0.00267513 0.057598501 0.057673998, + -0.0053918599 0.0573892 0.057596501, + -0.0053918599 0.0566318 0.0597829, + -0.0081421202 0.056274999 0.059643898, + 0.0053918599 0.054796498 0.064090297, + 0.00267513 0.053925801 0.066288203, + 0 0.052808899 0.068384103, + -0.00267513 0.0539244 0.066287801, + -0.0053918599 0.054793701 0.064089701, + -0.0081421202 0.055409402 0.061803799, + -0.0109179 0.055764701 0.059444901, + -0.0081421202 0.057032902 0.0574647, + -0.0053918599 0.058037899 0.055398598, + -0.00267513 0.0587883 0.053263102, + 0 0.0592933 0.051073998, + 0.00267513 0.059226301 0.051052801, + 0.0053918599 0.0585826 0.0531937, + 0.0081421202 0.0576864 0.055273399, + 0.0109179 0.056528602 0.057275899, + 0.0137106 0.055101998 0.059184201, + 0.0109179 0.054904401 0.0615955, + 0.0081421202 0.054441001 0.063937299, + 0.0053918599 0.053717598 0.066194199, + 0.00267513 0.052741501 0.0683522, + 0 0.051522899 0.070397899, + -0.00267513 0.052740101 0.068351701, + -0.0053918599 0.053714801 0.066193402, + -0.0081421202 0.054436799 0.063936301, + -0.0109179 0.054898798 0.061594501, + -0.0137106 0.055095099 0.059183698, + -0.0109179 0.056523301 0.0572761, + -0.0081421202 0.057682499 0.055273999, + -0.0053918599 0.058580101 0.053194299, + -0.00267513 0.059225202 0.051052999, + 0 0.059627499 0.048865601, + 0.00267513 0.059560802 0.048845999, + 0.0053918599 0.059020098 0.050987799, + 0.0081421202 0.058229499 0.053075999, + 0.0109179 0.057179399 0.055094901, + 0.0137106 0.055861399 0.0570282, + 0.0165099 0.054271001 0.058859698, + 0.0137106 0.054235701 0.061321001, + 0.0109179 0.053931899 0.063718103, + 0.0081421202 0.0533625 0.066034198, + 0.0053918599 0.052533802 0.068254299, + 0.00267513 0.051455598 0.0703649, + 0 0.050138898 0.072352901, + -0.00267513 0.051454201 0.070364296, + -0.0053918599 0.052531101 0.068253301, + -0.0081421202 0.053358302 0.066032901, + -0.0109179 0.0539263 0.063716799, + -0.0137106 0.054228701 0.061319798, + -0.0165099 0.054262701 0.058859002, + -0.0137106 0.0558546 0.057028402, + -0.0109179 0.057174101 0.055095699, + -0.0081421202 0.058225799 0.053077001, + -0.0053918599 0.0590179 0.050988201, + -0.00267513 0.0595599 0.048845802, + 0 0.059861299 0.0466705, + 0.00267513 0.059794798 0.0466525, + 0.0053918599 0.059355501 0.0487854, + 0.0081421202 0.058668301 0.050877299, + 0.0109179 0.057723898 0.052907702, + 0.0137106 0.0565136 0.054860599, + 0.0165099 0.055031601 0.056720302, + 0.019305199 0.0532743 0.058470398, + 0.0165099 0.053404301 0.060979798, + 0.0137106 0.0532635 0.063430302, + 0.0109179 0.052854002 0.065805003, + 0.0081421202 0.052179299 0.068087302, + 0.0053918599 0.051248498 0.070262901, + 0.00267513 0.050071999 0.072318599, + 0 0.048661198 0.074241802, + -0.00267513 0.050070599 0.072317801, + -0.0053918599 0.051245701 0.070261702, + -0.0081421202 0.052175101 0.068085797, + -0.0109179 0.052848302 0.065803297, + -0.0137106 0.053256501 0.0634287, + -0.0165099 0.053395901 0.060978401, + -0.019305199 0.053264599 0.058469601, + -0.0165099 0.055023499 0.056720499, + -0.0137106 0.056506999 0.054861601, + -0.0109179 0.057718899 0.052908901, + -0.0081421202 0.058665 0.050877899, + -0.0053918599 0.059353702 0.048785001, + -0.00267513 0.059794199 0.046651699, + 0 0.059994102 0.044520099, + 0.00267513 0.059927698 0.044503599, + 0.0053918599 0.059590399 0.046596501, + 0.0081421202 0.059005301 0.048682101, + 0.0109179 0.058164701 0.050719202, + 0.0137106 0.057060201 0.052686799, + 0.0165099 0.055685598 0.0545693, + 0.019305199 0.054036301 0.056350999, + 0.0220857 0.052108899 0.058015302, + 0.019305199 0.0524069 0.060570501, + 0.0165099 0.052432202 0.063072599, + 0.0137106 0.052186299 0.065504096, + 0.0109179 0.051671699 0.067848198, + 0.0081421202 0.050894901 0.070089102, + 0.0053918599 0.049865499 0.0722128, + 0.00267513 0.048594501 0.074206203, + 0 0.047093902 0.076057397, + -0.00267513 0.048593201 0.074205399, + -0.0053918599 0.049862798 0.072211303, + -0.0081421202 0.0508908 0.070087299, + -0.0109179 0.0516661 0.067846201, + -0.0137106 0.052179199 0.065502003, + -0.0165099 0.052423701 0.063070603, + -0.019305199 0.052397098 0.060568899, + -0.0220857 0.052097902 0.0580143, + -0.019305199 0.054026801 0.0563512, + -0.0165099 0.055677701 0.0545705, + -0.0137106 0.057054002 0.0526882, + -0.0109179 0.058160301 0.050719999, + -0.0081421202 0.059002601 0.048681501, + -0.0053918599 0.0595893 0.046594702, + -0.00267513 0.059927501 0.0445025, + 0 0.0600354 0.042384598, + 0.00267513 0.059969399 0.042369001, + 0.0053918599 0.059724499 0.044451602, + 0.0081421202 0.059241898 0.0465005, + 0.0109179 0.0585039 0.0485343, + 0.0137106 0.057503499 0.050511599, + 0.0165099 0.056234699 0.052412, + 0.019305199 0.054692499 0.054219998, + 0.0220857 0.052872501 0.055919301, + 0.0248404 0.050772998 0.057493601, + 0.0220857 0.051240999 0.060092099, + 0.019305199 0.051435299 0.062643498, + 0.0165099 0.051355898 0.065129898, + 0.0137106 0.051005401 0.067534201, + 0.0109179 0.050388701 0.0698402, + 0.0081421202 0.049513299 0.072032303, + 0.0053918599 0.048388898 0.074096598, + 0.00267513 0.047027402 0.0760208, + 0 0.045442998 0.077794299, + -0.00267513 0.047026198 0.076019801, + -0.0053918599 0.048386302 0.074095003, + -0.0081421202 0.049509201 0.072030097, + -0.0109179 0.050383199 0.069837697, + -0.0137106 0.0509983 0.067531697, + -0.0165099 0.051347401 0.065127298, + -0.019305199 0.051425301 0.062641203, + -0.0220857 0.051229801 0.060090199, + -0.0248404 0.0507605 0.057492498, + -0.0220857 0.052861702 0.055919498, + -0.019305199 0.054683302 0.054221399, + -0.0165099 0.0562272 0.052413799, + -0.0137106 0.0574979 0.050512701, + -0.0109179 0.058500402 0.048533499, + -0.0081421202 0.0592403 0.0464979, + -0.0053918599 0.0597241 0.044449501, + -0.00267513 0.059969399 0.042368598, + 0 0.0600341 0.040079899, + 0.0248404 0.049904201 0.059543598, + 0.0220857 0.050269499 0.062141798, + 0.019305199 0.050359901 0.064681098, + 0.0165099 0.050176602 0.067143902, + 0.0137106 0.049724098 0.069513403, + 0.0109179 0.049008802 0.071773797, + 0.0081421202 0.048038099 0.073909603, + 0.0053918599 0.046822801 0.075907402, + 0.00267513 0.045376901 0.077756397, + 0 0.043714799 0.079447001, + -0.00267513 0.045375701 0.077755399, + -0.0053918599 0.046820302 0.075905502, + -0.0081421202 0.048034199 0.0739071, + -0.0109179 0.0490034 0.071770899, + -0.0137106 0.049717199 0.069510303, + -0.0165099 0.050168101 0.067140803, + -0.019305199 0.050349999 0.064678103, + -0.0220857 0.050258201 0.062139101, + -0.0248404 0.049891599 0.059541501, + -0.027557701 0.0492539 0.056904498, + -0.0248404 0.0515262 0.055424701, + -0.0220857 0.053520899 0.0538132, + -0.019305199 0.055236001 0.0520848, + -0.0165099 0.056674499 0.0502549, + -0.0137106 0.0578412 0.0483394, + -0.0109179 0.058741 0.046359599, + -0.0081421202 0.059377398 0.044359401, + -0.0053918599 0.0597675 0.042319801, + -0.00267513 0.059968699 0.040065501, + 0 0.060026001 0.030865701, + 0.00267513 0.0599626 0.030856799, + 0.0053918599 0.059768301 0.030829201, + 0.0046292599 0.059815101 0.0124524, + 0.0081406701 0.059444599 0.0124527, + 0.0058307201 0.059727501 0.0124524, + 0.0081421202 0.059437301 0.0307822, + 0.0109179 0.058938202 0.039837599, + 0.0137106 0.058285002 0.041964799, + 0.0165099 0.0574225 0.043859102, + 0.019305199 0.056297999 0.0456887, + 0.0220857 0.0548978 0.047471501, + 0.0248404 0.053220101 0.049168002, + 0.027557701 0.051265001 0.0507592, + 0.0302257 0.049034499 0.052230299, + 0.0328326 0.0465311 0.0535671, + 0.0302257 0.0475954 0.056252699, + 0.027557701 0.048397999 0.058925599, + 0.0248404 0.0489331 0.061566699, + 0.0220857 0.049195498 0.064156301, + 0.019305199 0.049182501 0.066675603, + 0.0165099 0.048897501 0.0691071, + 0.0137106 0.0483464 0.071434401, + 0.0109179 0.047535699 0.073641799, + 0.0081421202 0.046473801 0.075714, + 0.0053918599 0.045173399 0.077639498, + 0.00267513 0.0436491 0.079407997, + 0 0.0419157 0.081010103, + -0.00267513 0.0436479 0.079406902, + -0.0053918599 0.045171 0.077637501, + -0.0081421202 0.046470001 0.075711198, + -0.0109179 0.047530401 0.073638402, + -0.0137106 0.048339602 0.071430802, + -0.0165099 0.048889101 0.069103301, + -0.019305199 0.049172599 0.066671997, + -0.0220857 0.049184099 0.064153001, + -0.0248404 0.0489203 0.0615637, + -0.027557701 0.048384 0.0589233, + -0.0302257 0.047580302 0.056251399, + -0.0302257 0.048350599 0.0542477, + -0.0328326 0.046514999 0.053567398, + -0.0302257 0.04902 0.0522325, + -0.027557701 0.050687399 0.052818201, + -0.027557701 0.051252499 0.050762199, + -0.0248404 0.0527489 0.0512591, + -0.0248404 0.053210001 0.049169902, + -0.0220857 0.054533001 0.049584299, + -0.0220857 0.054890599 0.047469798, + -0.019305199 0.0560393 0.047808301, + -0.019305199 0.056294002 0.045682501, + -0.0165099 0.057271 0.045952801, + -0.0165099 0.057421099 0.043852702, + -0.0137106 0.058230501 0.044062201, + -0.0137106 0.058284901 0.041962899, + -0.0109179 0.058931101 0.0421184, + -0.0109179 0.058938298 0.039837599, + -0.0081421202 0.0594269 0.039945599, + -0.0081421202 0.059437402 0.030781699, + -0.0053918599 0.059768401 0.030828901, + -0.00267513 0.0599587 0.0216667, + -0.0026749601 0.059944902 0.0124523, + -4.7590001e-005 0.060011499 0.0124522, + -0.00154442 0.059973601 0.0124522, + 0 0.060020201 0.0216705, + -0.00267513 0.0599626 0.030856701, + -0.0053918599 0.059768401 0.040021099, + -0.0081421202 0.059423398 0.042236999, + -0.0109179 0.058881499 0.0442308, + -0.0137106 0.058085699 0.0461783, + -0.0165099 0.0570218 0.048097901, + -0.019305199 0.0556872 0.049945801, + -0.0220857 0.054077201 0.051700201, + -0.0248404 0.0521884 0.0533453, + -0.027557701 0.050021801 0.0548671, + 0.0026750199 0.059946802 0.0124523, + -2.7e-008 0.0600104 0.0124522, + 0.0046305298 0.059828501 0.0074523599, + 0.00289505 0.059941601 0.0124523, + 0.0053912001 0.059759598 0.0124524, + 0.0107568 0.059035402 0.0074529899, + 0.035366699 0.0452132 0.050886799, + 0.0378174 0.043067999 0.050132599, + 0.035366699 0.045794599 0.0489402, + 0.0328326 0.0477795 0.049600199, + 0.0328326 0.048258699 0.047612298, + 0.0302257 0.050076202 0.0481821, + 0.0302257 0.050452799 0.046161301, + 0.027557701 0.052099701 0.046646699, + 0.027557701 0.052373402 0.044605501, + 0.0248404 0.0538477 0.0450125, + 0.0248404 0.054017201 0.042981301, + 0.0220857 0.0553177 0.043316599, + 0.0220857 0.055391502 0.041269802, + 0.019305199 0.056518 0.041540399, + 0.019305199 0.056543 0.039308, + 0.0165099 0.057499401 0.039519399, + 0.0137106 0.058341801 0.0306265, + 0.0165099 0.0575688 0.0305166, + 0.0145255 0.058226701 0.0124536, + 0.0167659 0.057608899 0.0124541, + 0.017363001 0.057444301 0.0124543, + 0.0220857 0.055424899 0.039060801, + 0.0248404 0.0541001 0.0409596, + 0.027557701 0.052552 0.0426034, + 0.0302257 0.0507356 0.0441534, + 0.0328326 0.048643801 0.045628201, + 0.035366699 0.046281401 0.046992399, + 0.0378174 0.043655999 0.048229299, + 0.040174201 0.040776599 0.049327001, + 0.0378174 0.0423855 0.052029502, + -0.0081421202 0.0594499 0.021635899, + -0.0088465102 0.059355699 0.0124527, + -0.0109179 0.0590013 0.017036, + -0.0117463 0.058850501 0.0124531, + -0.0137106 0.058408801 0.017022399, + -0.0137106 0.058389299 0.0215718, + -0.0165099 0.057640899 0.0215267, + -0.0165099 0.0575689 0.030515701, + -0.019305199 0.056641899 0.0303836, + -0.019305199 0.056543101 0.0393079, + -0.0220857 0.0554251 0.039060701, + -0.0220857 0.0553913 0.041266799, + -0.0248404 0.054099798 0.040956199, + -0.0248404 0.0540151 0.0429716, + -0.027557701 0.052549701 0.042592701, + -0.027557701 0.052367698 0.044596702, + -0.0302257 0.050729401 0.044143699, + -0.0302257 0.050443001 0.046158999, + -0.0328326 0.048633099 0.045625702, + -0.0328326 0.0482453 0.047614701, + -0.035366699 0.046266999 0.046994999, + -0.035366699 0.045778502 0.048944101, + -0.0378174 0.043638799 0.048233401, + -0.0378174 0.043049902 0.0501354, + -0.040174201 0.040757399 0.0493301, + -0.0378174 0.0423669 0.0520299, + -0.035366699 0.045196202 0.050889298, + -0.0328326 0.047764599 0.049603801, + -0.0302257 0.050063901 0.048184399, + -0.027557701 0.0520906 0.046644598, + -0.0248404 0.0538426 0.045004498, + -0.0220857 0.0553158 0.043308001, + -0.019305199 0.056517798 0.041537698, + -0.0165099 0.057499502 0.039519299, + -0.0137106 0.058341999 0.030625699, + -0.0109179 0.058991302 0.021608099, + -0.0109179 0.058963802 0.0307143, + -0.0137106 0.0582969 0.039695699, + -0.0165099 0.057481401 0.041769501, + -0.019305199 0.056450501 0.043601599, + -0.0220857 0.055151898 0.0453666, + -0.0248404 0.053574 0.047081798, + -0.027557701 0.051719502 0.048703, + -0.0302257 0.049590301 0.0502101, + -0.0328326 0.047188599 0.051589198, + -0.035366699 0.044518199 0.052827299, + -0.035366699 0.0437424 0.054753698, + -0.0328326 0.045742001 0.055534098, + -0.0328326 0.044870201 0.057482202, + -0.0302257 0.0467095 0.058236498, + -0.0302257 0.045738999 0.0601952, + -0.027557701 0.0474132 0.060915399, + -0.027557701 0.046342202 0.062872902, + -0.0248404 0.047847699 0.063551001, + -0.0248404 0.046675 0.065495797, + -0.0220857 0.0480089 0.066124, + -0.0220857 0.046735801 0.068044797, + -0.019305199 0.0478963 0.068615302, + -0.019305199 0.046525098 0.070501097, + -0.0165099 0.047514498 0.071007997, + -0.0165099 0.0460479 0.0728475, + -0.0137106 0.046869598 0.073285803, + -0.0137106 0.045311201 0.075068504, + -0.0109179 0.045968801 0.075433202, + -0.0109179 0.044324301 0.077149801, + -0.0081421202 0.0448227 0.0774367, + -0.0081421202 0.043098502 0.079078503, + -0.0053918599 0.0434446 0.079285301, + -0.0053918599 0.041647501 0.080843903, + -0.00267513 0.041849501 0.080968902, + -0.00267513 0.0399867 0.082436599, + 0 0.0400525 0.082478903, + 0 0.0381325 0.083850399, + 0.00267513 0.039987601 0.082437903, + 0.00267513 0.0418505 0.080970101, + 0.0053918599 0.041649699 0.080846302, + 0.0053918599 0.043446802 0.079287499, + 0.0081421202 0.043102 0.0790819, + 0.0081421202 0.044826299 0.0774398, + 0.0109179 0.0443292 0.077153899, + 0.0109179 0.045974001 0.075437002, + 0.0137106 0.045317698 0.075073197, + 0.0137106 0.0468762 0.073289998, + 0.0165099 0.046055902 0.072852597, + 0.0165099 0.047522798 0.0710124, + 0.019305199 0.046534698 0.0705062, + 0.019305199 0.047906101 0.068619698, + 0.0220857 0.046746999 0.068049803, + 0.0220857 0.0480203 0.066128097, + 0.0248404 0.0466878 0.065500498, + 0.0248404 0.047860499 0.063554801, + 0.027557701 0.046356399 0.062877104, + 0.027557701 0.0474273 0.0609187, + 0.0302257 0.0457545 0.060198799, + 0.0302257 0.046724901 0.058239099, + 0.0328326 0.044886898 0.057484999, + 0.0328326 0.045758501 0.055535499, + 0.035366699 0.043760099 0.0547552, + 0.035366699 0.0445356 0.0528269, + 0.0328326 0.047204301 0.051586799, + 0.0302257 0.049604099 0.050206799, + 0.027557701 0.0517307 0.048700999, + 0.0248404 0.053582001 0.047083601, + 0.0220857 0.055156399 0.045373701, + 0.019305199 0.056452099 0.043609101, + 0.0165099 0.057481602 0.041771799, + 0.0137106 0.0582968 0.039695799, + 0.0109179 0.058963601 0.030714899, + 0.0116529 0.058869001 0.0124531, + 0.0107542 0.0590242 0.012453, + 0.0109155 0.058996301 0.012453, + 0.00875236 0.059369698 0.0124527, + -0.0077017802 0.0594978 0.0124526, + -0.0081404904 0.059443399 0.0124527, + -0.0137072 0.0584087 0.0124535, + -0.013778 0.0583928 0.0124535, + -0.040174201 0.0400692 0.051178198, + -0.0378174 0.041588102 0.0539129, + -0.035366699 0.0428693 0.056661699, + -0.0328326 0.043900199 0.059404202, + -0.0302257 0.0446698 0.062119499, + -0.027557701 0.0451723 0.064788103, + -0.0248404 0.0454056 0.067390896, + -0.0220857 0.045368701 0.069908403, + -0.019305199 0.045062799 0.072322004, + -0.0165099 0.044493701 0.074615203, + -0.0137106 0.043670502 0.076773196, + -0.0109179 0.0426034 0.078782797, + -0.0081421202 0.041303899 0.0806311, + -0.0053918599 0.039786302 0.082308203, + -0.00267513 0.0380673 0.083806999, + 0 0.036163799 0.0851219, + 0.00267513 0.038068201 0.083808199, + 0.0053918599 0.039788298 0.082310699, + 0.0081421202 0.041307099 0.080634698, + 0.0109179 0.042608 0.078787401, + 0.0137106 0.0436766 0.076778501, + 0.0165099 0.044501401 0.074620903, + 0.019305199 0.045072202 0.072327897, + 0.0220857 0.045379698 0.069914304, + 0.0248404 0.045418199 0.067396499, + 0.027557701 0.045186501 0.064793304, + 0.0302257 0.044685401 0.0621242, + 0.0328326 0.043917 0.059408002, + 0.035366699 0.0428872 0.056664702, + 0.0378174 0.041607 0.053914499, + 0.040174201 0.040089 0.0511778, + 0.0248404 0.054492999 0.021338901, + 0.027557701 0.0529157 0.029854899, + 0.0302257 0.051095299 0.038103301, + 0.0328326 0.0492539 0.039795201, + 0.035366699 0.047191501 0.041220501, + 0.0378174 0.0450962 0.040679801, + 0.040174201 0.042617999 0.041912101, + 0.0424264 0.039889 0.043047901, + 0.044564299 0.0369206 0.0440576, + 0.0465803 0.033726599 0.044928499, + 0.044564299 0.0357867 0.047573, + 0.0424264 0.037653401 0.050274499, + 0.040174201 0.039307199 0.053016499, + 0.0378174 0.040732998 0.055780798, + 0.035366699 0.041917901 0.058547799, + 0.0328326 0.042849801 0.061297201, + 0.0302257 0.0435187 0.064007796, + 0.027557701 0.043920901 0.0666603, + 0.0248404 0.044055399 0.069235697, + 0.0220857 0.043921899 0.071714498, + 0.019305199 0.0435226 0.074078299, + 0.0165099 0.042865101 0.076311603, + 0.0137106 0.041959502 0.0784005, + 0.0109179 0.040816601 0.080331802, + 0.0081421202 0.039448299 0.082093596, + 0.0053918599 0.0378704 0.083678, + 0.00267513 0.036100101 0.085078798, + 0 0.034154098 0.086290903, + -0.00267513 0.036099199 0.085077502, + -0.0053918599 0.037868701 0.083675399, + -0.0081421202 0.0394454 0.082089797, + -0.0109179 0.040812299 0.080326997, + -0.0137106 0.041953702 0.0783948, + -0.0165099 0.042857699 0.0763053, + -0.019305199 0.043513499 0.074071601, + -0.0220857 0.0439112 0.071707897, + -0.0248404 0.044043001 0.069229104, + -0.027557701 0.043906901 0.066654198, + -0.0302257 0.043503199 0.064002201, + -0.0328326 0.0428329 0.061292101, + -0.035366699 0.0418997 0.058543701, + -0.0378174 0.040713701 0.055777598, + -0.040174201 0.039287001 0.0530148, + -0.0424264 0.037632599 0.050275002, + -0.044564299 0.035765398 0.0475762, + 0.0137074 0.058409601 0.0124535, + 0.016505999 0.057680599 0.0124541, + 0.0220802 0.055784602 0.0124556, + 0.0226011 0.0555843 0.0124557, + 0.0229061 0.055466998 0.0124558, + 0.0248347 0.054614399 0.0124565, + 0.040174201 0.0428578 0.040102299, + 0.0424264 0.040229499 0.041252501, + 0.044564299 0.037358802 0.042302102, + 0.0465803 0.0342604 0.043223601, + 0.048467699 0.0314942 0.042356499, + 0.0465803 0.034711201 0.041521799, + 0.044564299 0.037713099 0.040557601, + 0.0424264 0.040484399 0.039489701, + 0.040174201 0.043145798 0.0363455, + 0.0378174 0.045792799 0.0288416, + 0.035366699 0.048180901 0.0209594, + 0.0378174 0.046483099 0.016760699, + 0.0384284 0.046076 0.0124633, + 0.040173098 0.044574499 0.0124645, + 0.044560701 0.040182602 0.012468, + 0.044408198 0.040358901 0.0124679, + 0.0599204 0.0030962699 0.0074975402, + 0.059745401 0.0054080202 0.0124957, + 0.059919201 0.00310016 0.0124975, + 0.059923101 0.0030489999 0.0124976, + 0.0599402 0.0025810599 0.0141799, + 0.059757002 0.0051438198 0.0150417, + 0.059445001 0.00769467 0.0158925, + 0.058998398 0.0096280398 0.018640099, + 0.058412101 0.0124954 0.018812699, + 0.058412101 0.0109307 0.023882, + 0.0576833 0.0138997 0.024304399, + 0.0576833 0.0124516 0.0295581, + 0.056809202 0.01551 0.0302344, + 0.056809202 0.0148141 0.0328632, + 0.055787299 0.0179011 0.0336603, + 0.055787299 0.0170366 0.036312498, + 0.0546159 0.020131599 0.037224699, + 0.0532961 0.022679299 0.039593399, + 0.0546159 0.0190208 0.040040601, + 0.0546159 0.0209595 0.034449801, + 0.0532961 0.0236167 0.0366644, + 0.0546159 0.021565899 0.0315735, + 0.0532961 0.024538999 0.032230999, + 0.0546159 0.022735201 0.0255614, + 0.055787299 0.0198134 0.0251457, + 0.055787299 0.0210943 0.019330099, + 0.056809202 0.018239601 0.0191583, + 0.056809202 0.0189602 0.016145101, + 0.0576833 0.016139099 0.016081899, + 0.0576833 0.0164335 0.014319, + 0.058412101 0.013628 0.0142909, + 0.0580099 0.0152885 0.0124878, + 0.058998398 0.0108291 0.0142628, + 0.058829699 0.0118043 0.0124906, + 0.058412101 0.013314 0.016018501, + 0.0576833 0.0153695 0.018985599, + 0.056809202 0.016864499 0.024726201, + 0.055787299 0.018552 0.030906999, + 0.0592779 0.0092436904 0.0124926, + 0.0589833 0.0109267 0.0124913, + 0.0581805 0.0146752 0.0124883, + 0.058396801 0.0137186 0.0124891, + 0.055787299 0.0217661 0.016208, + 0.0546159 0.0239226 0.0195003, + 0.0532961 0.0256171 0.0259715, + 0.051830001 0.028446799 0.0263741, + 0.0532961 0.0267125 0.0196681, + 0.0546159 0.0245462 0.0162702, + 0.055787299 0.0220215 0.0143751, + 0.056128498 0.021171 0.0124831, + 0.0532961 0.027288301 0.0163316, + 0.051830001 0.029451801 0.0198329, + 0.050219599 0.0312117 0.026767399, + 0.051830001 0.027458001 0.032876398, + 0.0532961 0.023976499 0.035228699, + 0.051830001 0.0269386 0.035993401, + 0.050219599 0.030310201 0.033507202, + 0.048467699 0.033899501 0.0271498, + 0.050219599 0.032128301 0.019993899, + 0.051830001 0.0299807 0.016391801, + 0.0532961 0.0275055 0.0144301, + 0.050219599 0.032611299 0.016450699, + 0.048467699 0.034730099 0.020150499, + 0.0465803 0.036498699 0.0275195, + 0.048467699 0.033082802 0.034120299, + 0.050219599 0.029833 0.0367405, + 0.051830001 0.026597699 0.037487701, + 0.050611299 0.0322036 0.0124744, + 0.0502089 0.032837301 0.0124739, + 0.046574499 0.0378244 0.0124699, + 0.048467699 0.030949401 0.044005401, + 0.0465803 0.033107799 0.046631299, + 0.044564299 0.035087701 0.049323101, + 0.0424264 0.0368683 0.0520644, + 0.040174201 0.038431801 0.054836702, + 0.0378174 0.039764199 0.057621099, + 0.035366699 0.040852901 0.060397401, + 0.0328326 0.041686598 0.0631449, + 0.0302257 0.042257499 0.065842703, + 0.027557701 0.042563301 0.068471201, + 0.0248404 0.042603299 0.071011297, + 0.0220857 0.042378101 0.0734438, + 0.019305199 0.041891702 0.075751498, + 0.0165099 0.041153099 0.077919401, + 0.0137106 0.0401727 0.079934001, + 0.0109179 0.0389615 0.081782602, + 0.0081421202 0.037533201 0.083455399, + 0.0053918599 0.035903901 0.084945403, + 0.00267513 0.034090899 0.0862469, + 0 0.032111 0.087355703, + -0.00267513 0.034090199 0.086245701, + -0.0053918599 0.0359024 0.084942803, + -0.0081421202 0.037530601 0.083451502, + -0.0109179 0.0389576 0.081777602, + -0.0137106 0.040167298 0.079928003, + -0.0165099 0.0411461 0.077912703, + -0.019305199 0.0418831 0.0757441, + -0.0220857 0.0423677 0.073436201, + -0.0248404 0.042591199 0.071003698, + -0.027557701 0.042549599 0.068463899, + -0.0302257 0.042242199 0.065835901, + -0.0328326 0.0416697 0.063138701, + -0.035366699 0.040834598 0.060392, + -0.0378174 0.039744802 0.057616599, + -0.040174201 0.038411401 0.0548333, + -0.0424264 0.0368471 0.0520625, + -0.044564299 0.0350658 0.049323499, + -0.0465803 0.033085499 0.046634801, + -0.048467699 0.030927399 0.044010699, + -0.050219599 0.0286132 0.041463502, + -0.044564299 0.040137202 0.0145548, + -0.0424264 0.042394701 0.0145775, + -0.044472098 0.0402884 0.0124679, + -0.0424264 0.042265199 0.016656799, + -0.040174201 0.044423599 0.0167055, + -0.040174201 0.044170301 0.020715, + -0.0378174 0.0462403 0.0208397, + -0.040174201 0.0436549 0.0285351, + -0.0424264 0.041387599 0.028212599, + -0.0424264 0.040807098 0.035828099, + -0.044564299 0.038343001 0.0352832, + -0.044564299 0.038179599 0.037128098, + -0.0465803 0.035581499 0.036503501, + -0.0465803 0.035363302 0.038151, + -0.048467699 0.032642201 0.0374479, + -0.048467699 0.032331899 0.039058801, + -0.050219599 0.029500101 0.038276099, + -0.050219599 0.0290945 0.039867401, + -0.051830001 0.0261652 0.039004099, + -0.040748298 0.044036102 0.0124649, + -0.051830001 0.025669999 0.040541299, + -0.050219599 0.028054999 0.043056399, + -0.048467699 0.030299 0.045655701, + -0.0465803 0.032379899 0.0483278, + -0.044564299 0.034276601 0.051059201, + -0.0424264 0.035969902 0.053831998, + -0.040174201 0.0374429 0.056626301, + -0.0378174 0.038681898 0.059422299, + -0.035366699 0.039675198 0.062199399, + -0.0328326 0.0404137 0.064936899, + -0.0302257 0.040890701 0.0676139, + -0.027557701 0.041104201 0.070210598, + -0.0248404 0.041054301 0.072707899, + -0.0220857 0.040743802 0.075088203, + -0.019305199 0.0401778 0.077334397, + -0.0165099 0.039365299 0.079432003, + -0.0137106 0.038317502 0.081367902, + -0.0109179 0.037046801 0.0831315, + -0.0081421202 0.035567202 0.084713802, + -0.0053918599 0.033895198 0.086107999, + -0.00267513 0.032047801 0.087309398, + 0 0.0300407 0.088316098, + 0.00267513 0.0320483 0.087310597, + 0.0053918599 0.033896498 0.086110599, + 0.0081421202 0.0355695 0.084717698, + 0.0109179 0.037050299 0.0831367, + 0.0137106 0.0383224 0.081374303, + 0.0165099 0.0393718 0.079439402, + 0.019305199 0.040185899 0.077342398, + 0.0220857 0.0407537 0.0750966, + 0.0248404 0.041065902 0.0727164, + 0.027557701 0.041117501 0.070219003, + 0.0302257 0.0409058 0.067621797, + 0.0328326 0.040430401 0.064944401, + 0.035366699 0.0396934 0.062206101, + 0.0378174 0.0387014 0.0594281, + 0.040174201 0.037463602 0.056631099, + 0.0424264 0.035991501 0.053835601, + 0.044564299 0.034298901 0.051061202, + 0.0465803 0.032402799 0.048327401, + 0.048467699 0.0303222 0.0456522, + 0.050219599 0.0280778 0.0430509, + 0.051830001 0.025691099 0.040537398, + 0.0532961 0.023184501 0.038124401, + 0.051830001 0.0251236 0.042068999, + 0.050219599 0.0274415 0.044639699, + 0.048467699 0.0296109 0.047292002, + 0.0465803 0.031610101 0.0500114, + 0.044564299 0.033420499 0.0527809, + 0.0424264 0.035023902 0.055581301, + 0.040174201 0.036403298 0.058392599, + 0.0378174 0.037546001 0.061194699, + 0.035366699 0.038442601 0.063967101, + 0.0328326 0.039085001 0.066688903, + 0.0302257 0.039466999 0.069338702, + 0.027557701 0.039587598 0.071896903, + 0.0248404 0.039448999 0.074345797, + 0.0220857 0.039055198 0.076667704, + 0.019305199 0.038411401 0.078845903, + 0.0165099 0.037527598 0.0808663, + 0.0137106 0.0364164 0.082718201, + 0.0109179 0.0350908 0.084391601, + 0.0081421202 0.0335651 0.085877903, + 0.0053918599 0.031855699 0.087171502, + 0.00267513 0.029978599 0.088270202, + 0 0.0279493 0.089173198, + -0.00267513 0.029978201 0.088269196, + -0.0053918599 0.0318547 0.0871692, + -0.0081421202 0.0335632 0.085874103, + -0.0109179 0.035087701 0.084386297, + -0.0137106 0.036412001 0.0827116, + -0.0165099 0.037521701 0.080858603, + -0.019305199 0.038403701 0.078837298, + -0.0220857 0.039045699 0.076658502, + -0.0248404 0.039437901 0.074336298, + -0.027557701 0.039574601 0.071887501, + -0.0302257 0.039452299 0.0693295, + -0.0328326 0.039068598 0.0666802, + -0.035366699 0.0384246 0.063959204, + -0.0378174 0.0375266 0.061187599, + -0.040174201 0.036382601 0.058386501, + -0.0424264 0.035002101 0.055576202, + -0.044564299 0.033397801 0.0527771, + -0.0465803 0.0315868 0.0500095, + -0.048467699 0.029587099 0.047292601, + -0.050219599 0.0274175 0.044643302, + -0.051830001 0.0251 0.042074598, + -0.0532961 0.0226577 0.039597299, + -0.0532961 0.022075901 0.041069798, + -0.051830001 0.0244534 0.0436018, + -0.050219599 0.026698999 0.046222001, + -0.048467699 0.028790001 0.0489178, + -0.0465803 0.030706501 0.051673301, + -0.044564299 0.032430701 0.054469999, + -0.0424264 0.033944301 0.0572882, + -0.040174201 0.035231698 0.060106799, + -0.0378174 0.036281899 0.062905803, + -0.035366699 0.037086502 0.065664597, + -0.0328326 0.037637901 0.068361796, + -0.0302257 0.037930999 0.070976101, + -0.027557701 0.037966698 0.073489398, + -0.0248404 0.037748098 0.075883903, + -0.0220857 0.037279699 0.078142203, + -0.019305199 0.036567401 0.080248103, + -0.0165099 0.0356226 0.082189798, + -0.0137106 0.034458499 0.083956704, + -0.0109179 0.033087999 0.085539602, + -0.0081421202 0.031525798 0.086930498, + -0.0053918599 0.029787101 0.088126302, + -0.00267513 0.027887501 0.089125402, + 0 0.0258427 0.089927502, + 0.00267513 0.027887801 0.089126296, + 0.0053918599 0.0297879 0.088128299, + 0.0081421202 0.0315274 0.086934, + 0.0109179 0.033090599 0.085544698, + 0.0137106 0.034462299 0.083963297, + 0.0165099 0.035628099 0.082197599, + 0.019305199 0.036574401 0.0802572, + 0.0220857 0.037288301 0.078152001, + 0.0248404 0.0377586 0.075894199, + 0.027557701 0.037978999 0.073499903, + 0.0302257 0.0379452 0.070986502, + 0.0328326 0.0376538 0.068371698, + 0.035366699 0.0371041 0.065673903, + 0.0378174 0.036301099 0.062914297, + 0.040174201 0.035252299 0.060114302, + 0.0424264 0.033966199 0.0572947, + 0.044564299 0.0324536 0.054475401, + 0.0465803 0.0307303 0.051677201, + 0.048467699 0.0288142 0.048919901, + 0.050219599 0.0267237 0.046221301, + 0.051830001 0.0244783 0.043598, + 0.0532961 0.0221001 0.041064002, + 0.0532961 0.021445399 0.042532001, + 0.051830001 0.0237536 0.045120001, + 0.050219599 0.025923001 0.047791101, + 0.048467699 0.0279327 0.050529599, + 0.0465803 0.029764 0.053318098, + 0.044564299 0.031398699 0.0561378, + 0.0424264 0.0328198 0.0589687, + 0.040174201 0.034013402 0.061789699, + 0.0378174 0.03497 0.064580403, + 0.035366699 0.0356814 0.067319699, + 0.0328326 0.036141101 0.069986403, + 0.0302257 0.036346 0.072560102, + 0.027557701 0.036297999 0.075022601, + 0.0248404 0.036001001 0.077356599, + 0.0220857 0.035459898 0.079544798, + 0.019305199 0.034682602 0.081573203, + 0.0165099 0.0336807 0.083430603, + 0.0137106 0.032467902 0.085107103, + 0.0109179 0.031057499 0.086594, + 0.0081421202 0.029462799 0.087886401, + 0.0053918599 0.027698999 0.088982001, + 0.00267513 0.0257817 0.0898799, + 0 0.02373 0.090579599, + -0.00267513 0.0257816 0.0898792, + -0.0053918599 0.027698399 0.088980302, + -0.0081421202 0.0294616 0.087883301, + -0.0109179 0.0310554 0.086589299, + -0.0137106 0.032464601 0.085100703, + -0.0165099 0.033675998 0.083422698, + -0.019305199 0.034676298 0.081564002, + -0.0220857 0.0354519 0.079534501, + -0.0248404 0.035991199 0.077345498, + -0.027557701 0.036286298 0.075011201, + -0.0302257 0.036332499 0.072548598, + -0.0328326 0.036125701 0.069975197, + -0.035366699 0.035664201 0.067309, + -0.0378174 0.034951098 0.064570397, + -0.040174201 0.033992998 0.061780699, + -0.0424264 0.032798 0.058960699, + -0.044564299 0.031375699 0.056131002, + -0.0465803 0.029740101 0.053312499, + -0.048467699 0.027907999 0.050525401, + -0.050219599 0.0258979 0.047788899, + -0.051830001 0.023728199 0.045120601, + -0.0532961 0.0214199 0.042536002, + -0.0532961 0.015873499 0.050990202, + -0.051830001 0.0177157 0.053778801, + -0.050219599 0.0193986 0.0566011, + -0.048467699 0.020905901 0.059437402, + -0.0465803 0.022223899 0.062267099, + -0.044564299 0.023341199 0.0650701, + -0.0424264 0.0242482 0.067825198, + -0.040174201 0.024936801 0.070510902, + -0.0378174 0.025403401 0.0731069, + -0.035366699 0.025646601 0.075595103, + -0.0328326 0.025666701 0.077957302, + -0.0302257 0.025465799 0.080175899, + -0.027557701 0.025050201 0.0822367, + -0.0248404 0.024426701 0.084127903, + -0.0220857 0.023602299 0.085839301, + -0.019305199 0.0225855 0.087361902, + -0.0165099 0.021391099 0.088689297, + -0.0137106 0.020047899 0.089814998, + -0.0109179 0.0185485 0.090742096, + -0.0081421202 0.0167896 0.091505699, + -0.0053918599 0.0125952 0.092445098, + -0.00267513 0.0082221497 0.093133099, + 0 0.00369621 0.093555801, + 0.00267513 0.0082229497 0.093133897, + 0.0053918599 0.0125978 0.0924467, + 0.0081421202 0.016792201 0.091507301, + 0.0109179 0.0185491 0.090743899, + 0.0137106 0.020047501 0.0898173, + 0.0165099 0.0213909 0.088692702, + 0.019305199 0.022586299 0.087366901, + 0.0220857 0.023604499 0.085846402, + 0.0248404 0.024430299 0.084137298, + 0.027557701 0.0250556 0.082248501, + 0.0302257 0.025473099 0.080189899, + 0.0328326 0.0256759 0.077973098, + 0.035366699 0.025658 0.075612098, + 0.0378174 0.025417 0.073124602, + 0.040174201 0.024952799 0.070528701, + 0.0424264 0.0242662 0.067842796, + 0.044564299 0.0233612 0.065086998, + 0.0465803 0.0222457 0.062283099, + 0.048467699 0.0209294 0.059452001, + 0.050219599 0.0194236 0.056614298, + 0.051830001 0.017742099 0.053790499, + 0.0532961 0.015900901 0.0510002, + 0.0546159 0.0139172 0.0482619, + 0.0546159 0.0149533 0.046945401, + 0.0532961 0.0170152 0.049657699, + 0.051830001 0.0189369 0.05243, + 0.050219599 0.020700499 0.0552448, + 0.048467699 0.022289401 0.058082901, + 0.0465803 0.023689101 0.060924001, + 0.044564299 0.0248864 0.063747004, + 0.0424264 0.0258704 0.066531204, + 0.040174201 0.0266327 0.069255002, + 0.0378174 0.0271689 0.071898296, + 0.035366699 0.027475899 0.0744408, + 0.0328326 0.027553501 0.076864302, + 0.0302257 0.0274032 0.079150803, + 0.027557701 0.027031099 0.081285402, + 0.0248404 0.0264448 0.083254501, + 0.0220857 0.0256512 0.085046999, + 0.019305199 0.024658499 0.086653799, + 0.0165099 0.023478299 0.088068701, + 0.0137106 0.022126799 0.089286603, + 0.0109179 0.0206329 0.090301499, + 0.0081421202 0.018990099 0.091117397, + 0.0053918599 0.017096199 0.091771297, + 0.00267513 0.0127711 0.092605002, + 0 0.0082777999 0.093186401, + -0.00267513 0.0127698 0.092604302, + -0.0053918599 0.0170945 0.091770202, + -0.0081421202 0.0189896 0.091116101, + -0.0109179 0.0206332 0.090299703, + -0.0137106 0.022127001 0.089283802, + -0.0165099 0.023477601 0.088064402, + -0.019305199 0.024656599 0.0866476, + -0.0220857 0.025647899 0.085038602, + -0.0248404 0.02644 0.083243802, + -0.027557701 0.027024601 0.081272602, + -0.0302257 0.027394701 0.079136297, + -0.0328326 0.0275429 0.076848499, + -0.035366699 0.0274632 0.074424297, + -0.0378174 0.027153799 0.071881503, + -0.040174201 0.0266157 0.069238402, + -0.0424264 0.025851401 0.066514999, + -0.044564299 0.0248654 0.0637317, + -0.0465803 0.023666499 0.0609098, + -0.048467699 0.0222652 0.05807, + -0.050219599 0.020675 0.055233601, + -0.051830001 0.018910199 0.0524204, + -0.0532961 0.0169877 0.049649499, + -0.051830001 0.0200302 0.051020201, + -0.050219599 0.0218776 0.053817801, + -0.048467699 0.023551701 0.0566478, + -0.0465803 0.0250376 0.059490599, + -0.044564299 0.026321299 0.062325701, + -0.0424264 0.027389999 0.065131404, + -0.040174201 0.0282341 0.067886598, + -0.0378174 0.0288484 0.070571199, + -0.035366699 0.029229499 0.073164701, + -0.0328326 0.029375101 0.075647302, + -0.0302257 0.0292861 0.078000702, + -0.027557701 0.0289679 0.080209799, + -0.0248404 0.0284278 0.082259998, + -0.0220857 0.0276735 0.084137902, + -0.019305199 0.0267132 0.085833199, + -0.0165099 0.025558401 0.087339103, + -0.0137106 0.0242217 0.088650197, + -0.0109179 0.022718901 0.089761898, + -0.0081421202 0.021079199 0.090668902, + -0.0053918599 0.019297799 0.091377497, + -0.00267513 0.017273501 0.091925599, + 0 0.0128274 0.092656396, + 0.00267513 0.0172744 0.091926202, + 0.0053918599 0.019298101 0.091378398, + 0.0081421202 0.0210789 0.090670303, + 0.0109179 0.0227187 0.0897642, + 0.0137106 0.024222299 0.088653803, + 0.0165099 0.0255602 0.087344401, + 0.019305199 0.026716201 0.085840501, + 0.0220857 0.027677899 0.084147297, + 0.0248404 0.028433699 0.082271501, + 0.027557701 0.028975699 0.080223002, + 0.0302257 0.0292958 0.078015298, + 0.0328326 0.0293869 0.075662598, + 0.035366699 0.029243501 0.0731804, + 0.0378174 0.0288644 0.070586801, + 0.040174201 0.028252101 0.067901902, + 0.0424264 0.027409799 0.065145999, + 0.044564299 0.0263429 0.062339202, + 0.0465803 0.0250609 0.059503, + 0.048467699 0.023576301 0.0566586, + 0.050219599 0.021903399 0.0538272, + 0.051830001 0.020057 0.051027998, + 0.0532961 0.018054601 0.0482798, + 0.0546159 0.0159159 0.0455999, + 0.0532961 0.019018 0.0468725, + 0.051830001 0.0210997 0.049589999, + 0.050219599 0.023029 0.052367099, + 0.048467699 0.024786901 0.055185299, + 0.0465803 0.026357399 0.0580258, + 0.044564299 0.027726 0.060868502, + 0.0424264 0.028879 0.063691802, + 0.040174201 0.0298051 0.066473901, + 0.0378174 0.030498 0.069194503, + 0.035366699 0.030953599 0.071833603, + 0.0328326 0.0311691 0.074370503, + 0.0302257 0.0311436 0.076785602, + 0.027557701 0.0308821 0.079062998, + 0.0248404 0.030391101 0.081188001, + 0.0220857 0.0296786 0.083146602, + 0.019305199 0.0287534 0.084926099, + 0.0165099 0.027627099 0.0865191, + 0.0137106 0.0263119 0.087920099, + 0.0109179 0.0248206 0.089124396, + 0.0081421202 0.0231697 0.090127997, + 0.0053918599 0.0213906 0.090928003, + 0.00267513 0.0194789 0.091531403, + 0 0.0173322 0.091976501, + -0.00267513 0.019478699 0.091530897, + -0.0053918599 0.021390701 0.090927102, + -0.0081421202 0.0231697 0.090126403, + -0.0109179 0.024820101 0.089121602, + -0.0137106 0.0263106 0.087915704, + -0.0165099 0.0276246 0.086512797, + -0.019305199 0.028749701 0.084917799, + -0.0220857 0.029673399 0.083136402, + -0.0248404 0.030384099 0.081176102, + -0.027557701 0.030873099 0.079049699, + -0.0302257 0.0311327 0.076771498, + -0.0328326 0.0311561 0.0743559, + -0.035366699 0.0309387 0.071818903, + -0.0378174 0.0304811 0.069180198, + -0.040174201 0.0297863 0.066460103, + -0.0424264 0.028858401 0.063678898, + -0.044564299 0.027703799 0.060856801, + -0.0465803 0.026333701 0.058015302, + -0.048467699 0.024762001 0.055176198, + -0.050219599 0.023003099 0.052359398, + -0.051830001 0.021073001 0.0495838, + -0.0532961 0.0189909 0.046868, + -0.051830001 0.0220374 0.0481176, + -0.050219599 0.0240491 0.050864201, + -0.048467699 0.0258931 0.053661302, + -0.0465803 0.027551601 0.05649, + -0.044564299 0.0290091 0.059330501, + -0.0424264 0.0302517 0.062162299, + -0.040174201 0.0312667 0.064963497, + -0.0378174 0.032046098 0.067713097, + -0.035366699 0.032584701 0.070391104, + -0.0328326 0.032878902 0.072977103, + -0.0302257 0.0329272 0.075451002, + -0.027557701 0.0327328 0.077795103, + -0.0248404 0.032301798 0.079994202, + -0.0220857 0.0316412 0.082033999, + -0.019305199 0.030759901 0.083901003, + -0.0165099 0.029670199 0.085585102, + -0.0137106 0.0283846 0.087079696, + -0.0109179 0.0269155 0.088379599, + -0.0081421202 0.0252761 0.089480601, + -0.0053918599 0.0234848 0.090380996, + -0.00267513 0.021573599 0.091078803, + 0 0.019537801 0.0915813, + 0.00267513 0.021573501 0.091079101, + 0.0053918599 0.0234848 0.090382099, + 0.0081421202 0.0252764 0.089482799, + 0.0109179 0.0269165 0.088383101, + 0.0137106 0.0283866 0.087084897, + 0.0165099 0.0296735 0.085592203, + 0.019305199 0.0307645 0.083909899, + 0.0220857 0.031647399 0.082044601, + 0.0248404 0.0323098 0.0800061, + 0.027557701 0.032742798 0.077807903, + 0.0302257 0.032939099 0.075464398, + 0.0328326 0.032892801 0.072990701, + 0.035366699 0.0326006 0.070404597, + 0.0378174 0.032063801 0.067726098, + 0.040174201 0.031286199 0.064975701, + 0.0424264 0.0302728 0.062173501, + 0.044564299 0.0290318 0.0593406, + 0.0465803 0.027575601 0.056498699, + 0.048467699 0.0259181 0.0536687, + 0.050219599 0.024074901 0.050870098, + 0.051830001 0.022063799 0.048121899, + 0.0532961 0.019904699 0.045441601, + 0.0546159 0.017618001 0.042844899, + 0.0532961 0.020713899 0.043992799, + 0.051830001 0.022948699 0.046629898, + 0.050219599 0.0250398 0.0493428, + 0.048467699 0.026967101 0.052114598, + 0.0465803 0.028712001 0.054927502, + 0.044564299 0.030257201 0.057761699, + 0.0424264 0.031587601 0.060597099, + 0.040174201 0.032690302 0.063412301, + 0.0378174 0.033556301 0.066186398, + 0.035366699 0.034178399 0.068898298, + 0.0328326 0.034552202 0.071527697, + 0.0302257 0.0346753 0.074054301, + 0.027557701 0.034550499 0.076460198, + 0.0248404 0.034182299 0.078728102, + 0.0220857 0.033577099 0.080843203, + 0.019305199 0.032743301 0.082791701, + 0.0165099 0.031693399 0.084562801, + 0.0137106 0.030440601 0.086147502, + 0.0109179 0.028997401 0.0875398, + 0.0081421202 0.027377101 0.088735603, + 0.0053918599 0.025594899 0.089732997, + 0.00267513 0.0236696 0.0905312, + 0 0.021633301 0.091128401, + -0.00267513 0.023669699 0.090530701, + -0.0053918599 0.0255946 0.089731596, + -0.0081421202 0.0273763 0.088733003, + -0.0109179 0.028995899 0.087535702, + -0.0137106 0.0304379 0.086141698, + -0.0165099 0.031689402 0.084555097, + -0.019305199 0.0327379 0.082782403, + -0.0220857 0.033569999 0.080832601, + -0.0248404 0.034173299 0.078716502, + -0.027557701 0.034539599 0.076447897, + -0.0302257 0.034662601 0.074041799, + -0.0328326 0.034537401 0.071515203, + -0.035366699 0.034161899 0.068886198, + -0.0378174 0.033537898 0.066174902, + -0.040174201 0.0326703 0.063401602, + -0.0424264 0.031565901 0.060587499, + -0.044564299 0.030234201 0.057753298, + -0.0465803 0.0286879 0.054920301, + -0.048467699 0.026942199 0.052108899, + -0.050219599 0.0250143 0.049338501, + -0.051830001 0.0229227 0.0466277, + -0.0532961 0.020687699 0.043993399, + 0.059999902 0.000106517 0.0124999, + 0.059932198 0.00269957 0.0124979, + 0.0599977 1.16071e-005 0.0125, + 0.059720598 -0.0057720202 0.0125046, + 0.059285302 -0.0092258602 0.0075073498, + 0.059433699 -0.0081299003 0.0125065, + 0.059365101 -0.0086939204 0.0125069, + 0.058985401 -0.010904 0.0125087, + 0.057446498 -0.017306101 0.0125138, + 0.056143001 -0.021157499 0.0075168498, + 0.056795198 -0.019289 0.0125154, + 0.056527998 -0.0201026 0.012516, + 0.055773601 -0.0220688 0.0125176, + 0.054603402 -0.024823301 0.0125198, + 0.050626501 -0.032194201 0.0075256401, + 0.051520798 -0.030739101 0.0125245, + 0.050211199 -0.032815699 0.0125261, + 0.048462 -0.035351101 0.0125282, + 0.040174201 -0.045508999 0.0146961, + 0.041313998 -0.044924501 0.0150347, + 0.040174201 -0.0459936 0.015002, + 0.041313998 -0.045395799 0.0152093, + 0.0424264 -0.0442921 0.015253, + 0.0424264 -0.044709101 0.0153227, + 0.043510102 -0.0435718 0.0153792, + 0.040174201 -0.046469402 0.0151666, + 0.0390082 -0.047031701 0.0149704, + 0.0378174 -0.047544599 0.0146503, + 0.0378174 -0.048037998 0.0149396, + 0.0390082 -0.047511999 0.0151252, + 0.040174201 -0.046895001 0.0152139, + 0.036603201 -0.0490118 0.0149097, + 0.035366699 -0.049450301 0.0146072, + 0.035366699 -0.049952101 0.014881, + 0.036603201 -0.049500499 0.0150463, + 0.035366699 -0.050444901 0.0150088, + 0.034109399 -0.050858099 0.0148533, + 0.0328326 -0.051219299 0.0145672, + 0.0059725801 -0.171451 0.0598385, + 0.0088933604 -0.171451 0.059473701, + 0.0081404103 -0.171451 0.059567802, + 0.00923343 -0.191451 0.0594378, + 0.0109152 -0.171451 0.059119798, + 0.0152803 -0.191452 0.0581742, + 0.0146637 -0.171452 0.058316998, + 0.0137071 -0.171452 0.0585333, + 0.0165057 -0.171452 0.057804398, + 0.021165101 -0.19145399 0.056295499, + 0.026825599 -0.191456 0.053821702, + 0.0248341 -0.171455 0.054738201, + 0.030218899 -0.17145699 0.0519545, + 0.030913601 -0.17145699 0.051559702, + 0.0275511 -0.17145599 0.053419702, + 0.022079799 -0.171454 0.055908501, + 0.019300099 -0.171453 0.056930199, + 0.0165099 -0.0592991 0.0145939, + 0.0137106 -0.059494101 0.0143793, + 0.0109179 -0.059607498 0.0140176, + 0.0081428103 -0.0596986 0.0135537, + 0.0060197199 -0.0596857 0.0125475, + 0.0081428103 -0.059496999 0.0130472, + 0.0109179 -0.059250601 0.0135583, + 0.0137106 -0.059017301 0.014027, + 0.0165099 -0.058757599 0.0143961, + 0.019305199 -0.058412399 0.0146213, + 0.019305199 -0.0578744 0.0144163, + 0.0165099 -0.058283601 0.0140386, + 0.0137106 -0.058662701 0.0135642, + 0.0109179 -0.059050798 0.0130496, + 0.0089402199 -0.059318598 0.0125472, + 0.0107539 -0.058999602 0.012547, + 0.0248404 -0.056706499 0.0147598, + 0.0167653 -0.0575835 0.0125459, + 0.016505601 -0.057656001 0.0125459, + 0.013707 -0.058384899 0.0125465, + 0.0046305298 -0.059813399 0.00754763, + 0.002688 -0.0599197 0.0125477, + -0.00154487 -0.059972499 0.0075477599, + 0.0081410101 -0.059418999 0.0125473, + 0.0053964402 -0.0597331 0.0125476, + 7.3000002e-008 -0.059985101 0.0125478, + -0.0053968299 -0.059737802 0.0125476, + -0.0137813 -0.0583883 0.0075464998, + -0.0137077 -0.0583876 0.0125465, + -0.0248351 -0.0545923 0.0125435, + -0.025434 -0.054328699 0.0125433, + -0.0255125 -0.054294098 0.0125432, + -0.0275524 -0.053273998 0.0125424, + -0.030220401 -0.051809099 0.0125413, + -0.030710001 -0.051533502 0.012541, + -0.035363302 -0.0484511 0.0125386, + -0.035611998 -0.048276901 0.0125384, + -0.047540501 -0.038364701 0.0154719, + -0.049361002 -0.036607102 0.0158532, + -0.048467699 -0.037898 0.0157755, + -0.050219599 -0.036868598 0.016415199, + -0.048467699 -0.037490301 0.015673799, + -0.047540501 -0.038754601 0.0156111, + -0.0465803 -0.039601199 0.0154232, + -0.051830001 -0.0356679 0.0172485, + -0.0532961 -0.034306102 0.018286901, + -0.0546159 -0.032788999 0.0195536, + -0.055787299 -0.0311461 0.020973699, + -0.056809202 -0.029487699 0.022601901, + -0.0576833 -0.027869301 0.0244732, + -0.058412101 -0.0263367 0.026558699, + -0.058998398 -0.0249396 0.0288484, + -0.059445001 -0.0237207 0.031310301, + -0.059757002 -0.0227185 0.0339012, + -0.0599402 -0.0219568 0.0365762, + -0.059999999 -0.021427801 0.039300699, + -0.0599402 -0.021107901 0.0420467, + -0.059757002 -0.020967901 0.0447894, + -0.059445001 -0.0209774 0.047507901, + -0.058998398 -0.021125199 0.050167799, + -0.058412101 -0.021405799 0.0527367, + -0.0576833 -0.021794399 0.0551816, + -0.056809202 -0.0223688 0.057503399, + -0.055787299 -0.0232074 0.059799898, + -0.0546159 -0.024219301 0.062067401, + -0.0532961 -0.025419701 0.0642782, + -0.051830001 -0.026815699 0.066408902, + -0.050219599 -0.0284106 0.0684366, + -0.048467699 -0.0302056 0.070338197, + -0.0465803 -0.032198999 0.072091103, + -0.044564299 -0.034387201 0.073673099, + -0.0424264 -0.036763199 0.075066298, + -0.040174201 -0.039329998 0.076253697, + -0.0378174 -0.042075701 0.077216201, + -0.035366699 -0.044981498 0.077937998, + -0.0328326 -0.048028599 0.078404598, + -0.0302257 -0.051197302 0.078603603, + -0.027557701 -0.054467801 0.078526802, + -0.0248404 -0.057819001 0.078169398, + -0.0220857 -0.0654893 0.075943097, + -0.019305199 -0.073458001 0.073811099, + -0.0165099 -0.081689999 0.071784198, + -0.0137106 -0.090151399 0.069872402, + -0.0109179 -0.098809697 0.068085298, + -0.0081421202 -0.107633 0.066431798, + -0.0053918599 -0.116589 0.064920597, + -0.00267513 -0.12564699 0.0635598, + 0 -0.134776 0.062357198, + 0.00267513 -0.125646 0.063558899, + 0.0053918599 -0.116587 0.064918503, + 0.0081421202 -0.10763 0.066427797, + 0.0109179 -0.098805502 0.068079203, + 0.0137106 -0.090146199 0.069864497, + 0.0165099 -0.081684098 0.071775697, + 0.019305199 -0.073452398 0.073803701, + 0.0220857 -0.065485701 0.075939097, + 0.0248404 -0.057818599 0.078170598, + 0.027557701 -0.054467902 0.078527696, + 0.0302257 -0.0511971 0.078605801, + 0.0328326 -0.048028 0.078408703, + 0.035366699 -0.044980399 0.077943802, + 0.0378174 -0.042074598 0.077223003, + 0.040174201 -0.039330199 0.076259501, + 0.0424264 -0.036765099 0.075069301, + 0.044564299 -0.0343883 0.073676497, + 0.0465803 -0.032199901 0.072096802, + 0.048467699 -0.030206401 0.070346899, + 0.050219599 -0.0284108 0.068448603, + 0.051830001 -0.0268136 0.066424102, + 0.0532961 -0.025412699 0.064295799, + 0.0546159 -0.024203099 0.062085599, + 0.055787299 -0.023180701 0.059816401, + 0.056809202 -0.022350799 0.0575152, + 0.0576833 -0.0217961 0.0551912, + 0.058412101 -0.0214034 0.052751899, + 0.058998398 -0.0211164 0.050190099, + 0.059445001 -0.020963199 0.047535501, + 0.059757002 -0.020948701 0.0448181, + 0.0599402 -0.021084299 0.042073298, + 0.059999999 -0.021400901 0.039323501, + 0.0599402 -0.0219278 0.036594499, + 0.059757002 -0.0226881 0.0339147, + 0.059445001 -0.02369 0.031319398, + 0.058998398 -0.024909601 0.028853299, + 0.058412101 -0.026308 0.026558099, + 0.0576833 -0.027843 0.0244669, + 0.056809202 -0.0294693 0.0226062, + 0.055787299 -0.031141199 0.020995401, + 0.0546159 -0.032789402 0.019553799, + 0.0532961 -0.034306601 0.018286699, + 0.051830001 -0.035668399 0.017251501, + 0.050219599 -0.036868799 0.0164178, + 0.050219599 -0.035292398 0.0159363, + 0.049361002 -0.0362054 0.015745301, + 0.051830001 -0.0341479 0.0166946, + 0.0532961 -0.032838698 0.017654199, + 0.0546159 -0.031378899 0.0188193, + 0.055787299 -0.029775601 0.0202203, + 0.056809202 -0.0280542 0.021792799, + 0.0576833 -0.0263285 0.023531901, + 0.058412101 -0.0246702 0.0255212, + 0.058998398 -0.0231256 0.027737901, + 0.059445001 -0.0217411 0.030153001, + 0.059757002 -0.0205596 0.0327297, + 0.0599402 -0.019613201 0.0354263, + 0.059999999 -0.0189001 0.0382093, + 0.0599402 -0.0184054 0.041047599, + 0.059757002 -0.018105701 0.0439144, + 0.059445001 -0.0179777 0.046781301, + 0.058998398 -0.0180133 0.049610101, + 0.058412101 -0.018205401 0.052359901, + 0.0576833 -0.018546101 0.055000499, + 0.056809202 -0.019004701 0.057501201, + 0.055787299 -0.019639 0.059870102, + 0.0546159 -0.0205639 0.0622028, + 0.0532961 -0.021692401 0.064489603, + 0.051830001 -0.0230186 0.0667025, + 0.050219599 -0.024545399 0.0688181, + 0.048467699 -0.026276199 0.070814103, + 0.0465803 -0.028211299 0.072668597, + 0.044564299 -0.030348901 0.074359499, + 0.0424264 -0.032684602 0.075865, + 0.040174201 -0.035210501 0.077168502, + 0.0378174 -0.0379223 0.078256302, + 0.035366699 -0.040809501 0.079105496, + 0.0328326 -0.0438536 0.079700798, + 0.0302257 -0.047034301 0.080030099, + 0.027557701 -0.050329302 0.080085598, + 0.0248404 -0.053718399 0.079861201, + 0.0220857 -0.0571802 0.079353601, + 0.019305199 -0.0649748 0.076968998, + 0.0165099 -0.073054202 0.074683398, + 0.0137106 -0.081383802 0.072508499, + 0.0109179 -0.089929797 0.070453599, + 0.0081421202 -0.098659597 0.068527803, + 0.0053918599 -0.107541 0.066741303, + 0.00267513 -0.116543 0.065102398, + 0 -0.125634 0.063619196, + -0.00267513 -0.116544 0.065103501, + -0.0053918599 -0.107543 0.066744, + -0.0081421202 -0.098662697 0.0685324, + -0.0109179 -0.089933902 0.070459902, + -0.0137106 -0.0813886 0.072515599, + -0.0165099 -0.073059 0.074689701, + -0.019305199 -0.064978004 0.076972403, + -0.0220857 -0.057180598 0.079352498, + -0.0248404 -0.053718299 0.079860397, + -0.027557701 -0.050329398 0.080083601, + -0.0302257 -0.0470348 0.080026403, + -0.0328326 -0.043854602 0.079695299, + -0.035366699 -0.040810499 0.079099096, + -0.0378174 -0.037922099 0.078250803, + -0.040174201 -0.035208602 0.0771657, + -0.0424264 -0.032683499 0.075861797, + -0.044564299 -0.030347999 0.074354, + -0.0465803 -0.0282107 0.072660297, + -0.048467699 -0.0262761 0.070802502, + -0.050219599 -0.024547501 0.0688034, + -0.051830001 -0.0230255 0.066685498, + -0.0532961 -0.0217082 0.0644719, + -0.0546159 -0.02059 0.062186699, + -0.055787299 -0.0196566 0.059858501, + -0.056809202 -0.019003 0.057491701, + -0.0576833 -0.0185485 0.054985501, + -0.058412101 -0.018214099 0.0523379, + -0.058998398 -0.018027401 0.049582802, + -0.059445001 -0.017996799 0.046752799, + -0.059757002 -0.018129401 0.043887999, + -0.0599402 -0.018432301 0.0410248, + -0.059999999 -0.0189292 0.038191002, + -0.0599402 -0.0196437 0.0354128, + -0.059757002 -0.0205904 0.032720499, + -0.059445001 -0.021771399 0.030147901, + -0.058998398 -0.0231546 0.0277385, + -0.058412101 -0.024696801 0.0255276, + -0.0576833 -0.026347199 0.023527499, + -0.056809202 -0.028059101 0.0217708, + -0.055787299 -0.0297751 0.020220101, + -0.0546159 -0.0313785 0.0188195, + -0.0532961 -0.032838199 0.0176511, + -0.049361002 -0.0362048 0.0157375, + -0.048467699 -0.037105601 0.0155215, + -0.050219599 -0.034899201 0.0158023, + -0.050219599 -0.034524798 0.0156231, + 0.048467699 -0.037102301 0.0155379, + 0.048467699 -0.0374908 0.0156815, + 0.044564299 -0.041541699 0.015138, + 0.044564299 -0.041998401 0.0153439, + 0.045588002 -0.041214202 0.0154964, + 0.044564299 -0.042406298 0.0154372, + 0.043510102 -0.043159202 0.0152979, + 0.0424264 -0.0438256 0.0150682, + 9.4966999e-005 -0.171451 0.0601364, + -0.0465803 -0.046987198 0.016414, + -0.044564299 -0.0478989 0.015814099, + -0.0424264 -0.048608098 0.0154076, + -0.040174201 -0.0491134 0.0151695, + -0.0378174 -0.049410999 0.015083, + -0.036603201 -0.049937699 0.0150569, + -0.035366699 -0.050447199 0.0149968, + -0.034109399 -0.050870299 0.0148407, + -0.0328326 -0.051240001 0.0145592, + -0.0057835602 -0.171451 0.0598571, + -0.0081407595 -0.171451 0.059570301, + -0.00923343 -0.191451 0.0594378, + -0.00870548 -0.171451 0.0595016, + -0.0165099 -0.167217 -0.057416301, + -0.019305199 -0.16718 -0.056541301, + -0.0165099 -0.16503499 -0.0572544, + -0.0137106 -0.16508099 -0.0579843, + -0.0137106 -0.16290601 -0.057756599, + -0.0109179 -0.162955 -0.058343999, + -0.0109179 -0.160787 -0.058049198, + -0.0081428103 -0.160833 -0.058496799, + -0.0081428103 -0.158672 -0.058134001, + -0.0053973799 -0.15871 -0.058447, + -0.0053973799 -0.15655699 -0.058014899, + -0.00268824 -0.156583 -0.058198702, + -0.00268824 -0.15443701 -0.057696301, + 0 -0.15444601 -0.0577568, + 0 -0.15231 -0.0571835, + 0.00268824 -0.15443601 -0.0576974, + 0.00268824 -0.156583 -0.058200099, + 0.0053973799 -0.156556 -0.0580175, + 0.0053973799 -0.15871 -0.058450099, + 0.0081428103 -0.15867101 -0.058138698, + 0.0081428103 -0.160832 -0.0585021, + 0.0109179 -0.160787 -0.058056299, + 0.0109179 -0.162955 -0.058351502, + 0.0137106 -0.16290601 -0.057766099, + 0.0137106 -0.16508199 -0.057993598, + 0.0165099 -0.16503599 -0.057265501, + 0.0165099 -0.167218 -0.0574257, + 0.019305199 -0.167181 -0.056552298, + 0.019305199 -0.16937 -0.056645501, + 0.0165099 -0.169388 -0.057519101, + 0.018242201 -0.171544 -0.057007201, + 0.019300301 -0.171544 -0.056657799, + 0.0202034 -0.171543 -0.0563596, + 0.0220857 -0.169348 -0.055624198, + -0.044033099 -0.191531 -0.040603898, + -0.042423699 -0.17153201 -0.042287, + -0.039609101 -0.191534 -0.0449154, + -0.040174201 -0.16910701 -0.044390101, + -0.0404175 -0.171534 -0.0442078, + -0.0424264 -0.16906101 -0.042251799, + -0.035366699 -0.16919 -0.048294399, + -0.035878699 -0.171537 -0.047954101, + -0.0378174 -0.169149 -0.0464065, + -0.035366699 -0.166831 -0.0481948, + -0.0328326 -0.166904 -0.0499475, + -0.0328326 -0.16457 -0.049784102, + -0.0302257 -0.16467001 -0.051395599, + -0.0302257 -0.16236199 -0.0511669, + -0.027557701 -0.16248301 -0.052634299, + -0.027557701 -0.160199 -0.052339099, + -0.0248404 -0.160335 -0.0536603, + -0.0248404 -0.158077 -0.053297199, + -0.0220857 -0.158222 -0.0544701, + -0.0220857 -0.15598699 -0.054037999, + -0.019305199 -0.15613399 -0.055061299, + -0.019305199 -0.153926 -0.054558899, + -0.0165099 -0.15406901 -0.055434398, + -0.0165099 -0.151885 -0.054861199, + -0.0137106 -0.15201899 -0.055591401, + -0.0137106 -0.14986099 -0.0549477, + -0.0109179 -0.14998101 -0.055535201, + -0.0109179 -0.147848 -0.054821901, + -0.0081428103 -0.147947 -0.0552697, + -0.0081428103 -0.145842 -0.054487798, + -0.0053973799 -0.145918 -0.054800902, + -0.0053973799 -0.143839 -0.0539511, + -0.00268824 -0.143889 -0.0541352, + -0.00268824 -0.141838 -0.053218301, + 0 -0.141855 -0.053278901, + 0 -0.139833 -0.052295499, + 0.00268824 -0.141837 -0.053219602, + 0.00268824 -0.143888 -0.054136399, + 0.0053973799 -0.143838 -0.053953499, + 0.0053973799 -0.145916 -0.054803099, + 0.0081428103 -0.14584 -0.054491099, + 0.0081428103 -0.147945 -0.055272698, + 0.0109179 -0.147844 -0.054825999, + 0.0109179 -0.149977 -0.055539101, + 0.0137106 -0.149856 -0.054952599, + 0.0137106 -0.152016 -0.055596501, + 0.0165099 -0.15188099 -0.054867301, + 0.0165099 -0.154066 -0.055441201, + 0.019305199 -0.15392201 -0.054566801, + 0.019305199 -0.156131 -0.055070698, + 0.0220857 -0.155984 -0.054048698, + 0.0220857 -0.15821999 -0.054482799, + 0.0248404 -0.158075 -0.053311501, + 0.0248404 -0.160335 -0.053676501, + 0.027557701 -0.160199 -0.052356999, + 0.027557701 -0.16248301 -0.052653398, + 0.0302257 -0.16236199 -0.051187899, + 0.0302257 -0.164672 -0.051415998, + 0.0328326 -0.164572 -0.049806301, + 0.0328326 -0.166906 -0.049966201, + 0.035366699 -0.166833 -0.048214901, + 0.035366699 -0.169192 -0.048306901, + 0.0378174 -0.16915201 -0.0464199, + 0.035726301 -0.171537 -0.048067398, + 0.037813999 -0.171535 -0.046439301, + 0.034765299 -0.19153699 -0.048749201, + 0.033319298 -0.171538 -0.049761601, + 0.0328326 -0.169229 -0.050058398, + 0.034755301 -0.171537 -0.0487509, + 0.0353618 -0.171537 -0.048324, + 0.0302257 -0.16697399 -0.051576, + 0.027557701 -0.164764 -0.052881401, + 0.0248404 -0.16259199 -0.053972598, + 0.0220857 -0.160455 -0.054847501, + 0.019305199 -0.158346 -0.055504501, + 0.0165099 -0.156257 -0.0559448, + 0.0137106 -0.154185 -0.056170199, + 0.0109179 -0.152124 -0.056182802, + 0.0081428103 -0.150069 -0.0559857, + 0.0053973799 -0.14801601 -0.055584799, + 0.00268824 -0.145962 -0.054986, + 0 -0.143904 -0.054195698, + -0.00268824 -0.145963 -0.054985002, + -0.0053973799 -0.148018 -0.055582799, + -0.0081428103 -0.150071 -0.055982798, + -0.0109179 -0.152126 -0.056178801, + -0.0137106 -0.15418801 -0.0561646, + -0.0165099 -0.15626 -0.055936798, + -0.019305199 -0.15834799 -0.0554934, + -0.0220857 -0.160456 -0.054833099, + -0.0248404 -0.16259199 -0.053955398, + -0.027557701 -0.16476201 -0.052862801, + -0.0302257 -0.166972 -0.0515588, + -0.0328326 -0.169227 -0.050046802, + -0.034754898 -0.171537 -0.048750401, + -0.033477101 -0.171538 -0.049655799, + -0.032825101 -0.171538 -0.050071299, + -0.034765299 -0.19153699 -0.048749201, + -0.029552899 -0.19154 -0.052064601, + -0.0302184 -0.17154001 -0.051680598, + -0.030994801 -0.17153899 -0.051237699, + -0.035360001 -0.171537 -0.048321601, + -0.037811901 -0.171535 -0.0464366, + -0.038194101 -0.171535 -0.046136599, + -0.0395981 -0.171534 -0.0449186, + -0.0378174 -0.166751 -0.046306599, + -0.035366699 -0.164461 -0.048031099, + -0.0328326 -0.162229 -0.049555201, + -0.0302257 -0.16004901 -0.050871599, + -0.027557701 -0.157915 -0.051975898, + -0.0248404 -0.15582 -0.052864999, + -0.0220857 -0.153758 -0.053535599, + -0.019305199 -0.151724 -0.053985499, + -0.0165099 -0.149712 -0.054217301, + -0.0137106 -0.147717 -0.0542343, + -0.0109179 -0.145733 -0.054039899, + -0.0081428103 -0.143757 -0.053637799, + -0.0053973799 -0.14178599 -0.053034, + -0.00268824 -0.139815 -0.052234899, + 0 -0.137843 -0.051246502, + 0.00268824 -0.139814 -0.0522363, + 0.0053973799 -0.141784 -0.053036701, + 0.0081428103 -0.14375401 -0.053641401, + 0.0109179 -0.14572901 -0.054044299, + 0.0137106 -0.14771201 -0.0542394, + 0.0165099 -0.149707 -0.054223198, + 0.019305199 -0.151719 -0.0539927, + 0.0220857 -0.153754 -0.0535446, + 0.0248404 -0.155817 -0.052877001, + 0.027557701 -0.157912 -0.051991802, + 0.0302257 -0.16004799 -0.050891299, + 0.0328326 -0.16223 -0.049577899, + 0.035366699 -0.164463 -0.0480549, + 0.0378174 -0.16675401 -0.046328101, + 0.040174201 -0.169109 -0.044404302, + 0.039599199 -0.171534 -0.044919699, + 0.040172402 -0.171534 -0.044425599, + 0.0402769 -0.171534 -0.044335499, + 0.0424264 -0.169063 -0.042266801, + 0.040174201 -0.16666999 -0.0443126, + 0.0378174 -0.164345 -0.046168, + 0.035366699 -0.162085 -0.047826499, + 0.0328326 -0.15988199 -0.049281001, + 0.0302257 -0.157731 -0.050525598, + 0.027557701 -0.155627 -0.051557001, + 0.0248404 -0.153561 -0.052372601, + 0.0220857 -0.151531 -0.052970201, + 0.019305199 -0.149528 -0.0533484, + 0.0165099 -0.147548 -0.053509898, + 0.0137106 -0.145585 -0.053457599, + 0.0109179 -0.143635 -0.053194501, + 0.0081428103 -0.14169399 -0.0527246, + 0.0053973799 -0.13975801 -0.052053399, + 0.00268824 -0.137823 -0.051187299, + 0 -0.135888 -0.0501328, + -0.00268824 -0.137824 -0.051185802, + -0.0053973799 -0.13976 -0.052050501, + -0.0081428103 -0.141697 -0.052720599, + -0.0109179 -0.143639 -0.053189699, + -0.0137106 -0.14559001 -0.053452, + -0.0165099 -0.147553 -0.0535037, + -0.019305199 -0.149534 -0.0533415, + -0.0220857 -0.151537 -0.052961901, + -0.0248404 -0.153567 -0.052362401, + -0.027557701 -0.15563001 -0.051543601, + -0.0302257 -0.15773401 -0.050508201, + -0.0328326 -0.15988301 -0.049259599, + -0.035366699 -0.162084 -0.047801901, + -0.0378174 -0.164343 -0.0461425, + -0.040174201 -0.166667 -0.044289801, + -0.042543601 -0.17153201 -0.042172201, + -0.044022799 -0.17153101 -0.04061, + -0.044564299 -0.169012 -0.039999101, + -0.0424264 -0.166577 -0.042151202, + -0.040174201 -0.16421799 -0.0441254, + -0.0378174 -0.161928 -0.045913201, + -0.035366699 -0.159702 -0.047506101, + -0.0328326 -0.157535 -0.0488961, + -0.0302257 -0.15542001 -0.050075799, + -0.027557701 -0.15335099 -0.051040899, + -0.0248404 -0.15132099 -0.051788699, + -0.0220857 -0.149325 -0.052317798, + -0.019305199 -0.147356 -0.052627798, + -0.0165099 -0.145411 -0.052721299, + -0.0137106 -0.143483 -0.052601699, + -0.0109179 -0.141569 -0.052272301, + -0.0081428103 -0.13966499 -0.051736899, + -0.0053973799 -0.13776501 -0.051001299, + -0.00268824 -0.135867 -0.050071999, + 0.00268824 -0.135866 -0.050073601, + 0.0053973799 -0.13776299 -0.051004399, + 0.0081428103 -0.139662 -0.051741298, + 0.0109179 -0.141565 -0.052277699, + 0.0137106 -0.14347801 -0.052607901, + 0.0165099 -0.14540499 -0.052728001, + 0.019305199 -0.14735 -0.052634999, + 0.0220857 -0.14931799 -0.052325699, + 0.0248404 -0.151315 -0.0517979, + 0.027557701 -0.153345 -0.051052202, + 0.0302257 -0.155415 -0.050090399, + 0.0328326 -0.15753201 -0.048914999, + 0.035366699 -0.159701 -0.047529198, + 0.0378174 -0.161929 -0.045939401, + 0.040174201 -0.16422001 -0.044152401, + 0.0424264 -0.166581 -0.0421753, + 0.044564299 -0.16901501 -0.0400148, + 0.044024602 -0.17153101 -0.040611699, + 0.044440001 -0.17152999 -0.040175699, + 0.044033099 -0.191531 -0.040603898, + 0.044561401 -0.17152999 -0.040035099, + 0.0463636 -0.171529 -0.0379478, + 0.0465803 -0.168965 -0.037658501, + 0.044564299 -0.166486 -0.0399234, + 0.0424264 -0.164087 -0.042015001, + 0.040174201 -0.161762 -0.043923602, + 0.0378174 -0.15950701 -0.045641799, + 0.035366699 -0.157316 -0.0471627, + 0.0328326 -0.155184 -0.048479401, + 0.0302257 -0.15310401 -0.049585301, + 0.027557701 -0.151072 -0.050477099, + 0.0248404 -0.149078 -0.051153202, + 0.0220857 -0.147121 -0.051612101, + 0.019305199 -0.145191 -0.051852901, + 0.0165099 -0.14328501 -0.051878098, + 0.0137106 -0.141397 -0.051690798, + 0.0109179 -0.139523 -0.051294301, + 0.0081428103 -0.13766 -0.050692201, + 0.0053973799 -0.135802 -0.049890701, + 0.00268824 -0.133947 -0.0488974, + 0 -0.13396899 -0.048956499, + 0 -0.132091 -0.047720101, + -0.00268824 -0.133948 -0.048895799, + -0.0053973799 -0.135804 -0.049887601, + -0.0081428103 -0.13766301 -0.0506876, + -0.0109179 -0.13952699 -0.0512885, + -0.0137106 -0.141403 -0.0516841, + -0.0165099 -0.143291 -0.051870801, + -0.019305199 -0.145198 -0.0518451, + -0.0220857 -0.147128 -0.051603898, + -0.0248404 -0.149086 -0.051144298, + -0.027557701 -0.151079 -0.050466899, + -0.0302257 -0.153111 -0.0495729, + -0.0328326 -0.15518899 -0.0484634, + -0.035366699 -0.15731899 -0.047142401, + -0.0378174 -0.159508 -0.0456172, + -0.040174201 -0.161761 -0.0438958, + -0.0424264 -0.164084 -0.041986499, + -0.044564299 -0.166483 -0.039898101, + -0.0465803 -0.168962 -0.037642099, + -0.046578299 -0.171528 -0.037679199, + -0.047982302 -0.171527 -0.035870001, + -0.0464839 -0.171529 -0.0378008, + -0.044567399 -0.17152999 -0.040034901, + -0.040169802 -0.171534 -0.044422701, + -0.027550699 -0.17154101 -0.0531458, + -0.0240272 -0.191542 -0.054826502, + -0.028437899 -0.17154001 -0.052696001, + -0.027557701 -0.169294 -0.053124201, + -0.0258127 -0.17154101 -0.054027099, + -0.0248338 -0.171542 -0.0544645, + -0.0240207 -0.171542 -0.054827798, + -0.0248404 -0.169322 -0.054444499, + -0.0231252 -0.171542 -0.055227902, + -0.0248404 -0.167089 -0.054346301, + -0.0220857 -0.167138 -0.055518601, + -0.0220857 -0.16491801 -0.055356201, + -0.019305199 -0.16497999 -0.056379098, + -0.019305199 -0.162773 -0.0561512, + -0.0165099 -0.162846 -0.057026502, + -0.0165099 -0.160652 -0.056731701, + -0.0137106 -0.160726 -0.057461798, + -0.0137106 -0.158545 -0.057099, + -0.0109179 -0.15861601 -0.057686299, + -0.0109179 -0.15644801 -0.057254199, + -0.0081428103 -0.15651201 -0.057701901, + -0.0081428103 -0.154357 -0.057199501, + -0.0053973799 -0.15440699 -0.057512499, + -0.0053973799 -0.152266 -0.056939401, + -0.00268824 -0.152299 -0.057123099, + -0.00268824 -0.150171 -0.0564797, + 0 -0.15018301 -0.056540102, + 0 -0.148072 -0.0558271, + 0.00268824 -0.15017 -0.056480601, + 0.00268824 -0.152298 -0.057124101, + 0.0053973799 -0.152265 -0.056941401, + 0.0053973799 -0.154406 -0.057514701, + 0.0081428103 -0.154355 -0.057202902, + 0.0081428103 -0.15651099 -0.057705801, + 0.0109179 -0.15644699 -0.0572595, + 0.0109179 -0.15861601 -0.057692599, + 0.0137106 -0.158544 -0.0571068, + 0.0137106 -0.160726 -0.057470702, + 0.0165099 -0.160651 -0.056742501, + 0.0165099 -0.162846 -0.057037901, + 0.019305199 -0.162774 -0.0561646, + 0.019305199 -0.16498201 -0.0563922, + 0.0220857 -0.164919 -0.055371098, + 0.0220857 -0.16713899 -0.055531099, + 0.0248404 -0.16709 -0.054360501, + 0.0248404 -0.169323 -0.054453202, + 0.027557701 -0.169295 -0.053133901, + 0.0256411 -0.171542 -0.0541085, + 0.027551601 -0.17154101 -0.053147402, + 0.0240272 -0.191542 -0.054826502, + 0.024020201 -0.171542 -0.054826599, + 0.0229499 -0.171542 -0.055300798, + 0.024834501 -0.171542 -0.054465901, + -0.0220857 -0.169347 -0.055616401, + -0.022079499 -0.171543 -0.0556348, + -0.020382199 -0.171543 -0.056295399, + -0.019305199 -0.169369 -0.0566388, + -0.0165099 -0.169387 -0.0575133, + -0.018242801 -0.171544 -0.057009298, + -0.0137106 -0.167248 -0.058145899, + -0.0109179 -0.165117 -0.058571499, + -0.0081428103 -0.162991 -0.0587916, + -0.0053973799 -0.160864 -0.058809999, + -0.00268824 -0.158733 -0.058630999, + 0 -0.156591 -0.058259301, + 0.00268824 -0.158732 -0.058632601, + 0.0053973799 -0.160864 -0.058813501, + 0.0081428103 -0.162991 -0.058797199, + 0.0109179 -0.16511799 -0.058578901, + 0.0137106 -0.16724899 -0.0581537, + 0.0109179 -0.167273 -0.0587392, + 0.0081428103 -0.16514499 -0.059024598, + 0.0053973799 -0.163018 -0.059108499, + 0.00268824 -0.16088299 -0.058995798, + 0 -0.15874 -0.058691598, + -0.00268824 -0.16088299 -0.058994099, + -0.0053973799 -0.163018 -0.0591047, + -0.0081428103 -0.16514499 -0.0590191, + -0.0109179 -0.167272 -0.058733001, + -0.0137106 -0.169403 -0.058242701, + -0.0147556 -0.171545 -0.0580207, + -0.0165055 -0.171544 -0.057530701, + -0.0182469 -0.191544 -0.057005599, + -0.0175901 -0.171544 -0.057227101, + -0.0192999 -0.171544 -0.056656498, + -0.0116065 -0.171451 0.0590032, + -0.0152803 -0.191452 0.0581742, + -0.0137075 -0.171452 0.058535099, + -0.0144795 -0.171452 0.058363199, + -0.051830001 -0.16606601 -0.029947, + -0.051830001 -0.160576 -0.0295492, + -0.050219599 -0.163486 -0.032388501, + -0.0532961 -0.16595399 -0.027278399, + -0.0529892 -0.17152099 -0.0280085, + -0.051820699 -0.17152201 -0.0300838, + -0.051545098 -0.171523 -0.0305734, + -0.051438902 -0.191523 -0.0307351, + -0.053285599 -0.17151999 -0.027415801, + -0.054305699 -0.171519 -0.025375901, + -0.054342099 -0.19151901 -0.0252824, + -0.017317699 -0.171453 0.057583001, + -0.021165101 -0.19145399 0.056295499, + -0.019300601 -0.171453 0.056931701, + -0.0201142 -0.171453 0.0566645, + -0.022080399 -0.171454 0.055910099, + -0.024834899 -0.171455 0.0547399, + -0.037236601 -0.191461 0.0471997, + -0.035650201 -0.17146 0.0483969, + -0.040173799 -0.171463 0.044700399, + -0.037974101 -0.171461 0.046590399, + -0.040174201 -0.162937 0.044844199, + -0.0424264 -0.15457 0.043119401, + -0.044564299 -0.14638799 0.041554101, + -0.0465803 -0.13841701 0.0401632, + -0.048467699 -0.13067999 0.038961999, + -0.050219599 -0.123204 0.037958398, + -0.051830001 -0.116013 0.037158798, + -0.0532961 -0.109131 0.036569301, + -0.0546159 -0.102584 0.036195401, + -0.055787299 -0.096388303 0.0360387, + -0.056809202 -0.090565696 0.0360987, + -0.0576833 -0.085133597 0.036373001, + -0.058412101 -0.080109604 0.036858201, + -0.058998398 -0.078533001 0.035706099, + -0.058998398 -0.0816314 0.034037899, + -0.058412101 -0.086533502 0.033552598, + -0.0576833 -0.091840498 0.033287499, + -0.056809202 -0.097536102 0.033246201, + -0.055787299 -0.103603 0.0334314, + -0.0546159 -0.110023 0.033844799, + -0.0532961 -0.116778 0.034485199, + -0.051830001 -0.123844 0.035347302, + -0.050219599 -0.131199 0.0364247, + -0.048467699 -0.13881899 0.037710499, + -0.0465803 -0.146679 0.039196499, + -0.044564299 -0.15475599 0.040867299, + -0.0424264 -0.16302501 0.042706799, + -0.041868102 -0.171464 0.043096598, + -0.042342398 -0.171464 0.042646699, + -0.042424399 -0.17146499 0.042560998, + -0.044376299 -0.17146599 0.040518999, + 0.0165099 -0.064790003 0.0131069, + 0.019305199 -0.065821499 0.0125537, + 0.0220857 -0.0666482 0.0120665, + 0.0248404 -0.067259997 0.0116624, + 0.027557701 -0.067665704 0.0113491, + 0.0302257 -0.067879498 0.0111661, + 0.0328326 -0.067914598 0.0111341, + 0.035366699 -0.067787901 0.0112665, + 0.0378174 -0.067523301 0.011573, + 0.040174201 -0.067147598 0.0120584, + 0.0424264 -0.066687599 0.0127213, + 0.044564299 -0.066169903 0.013554, + 0.0465803 -0.065621197 0.0145419, + 0.048467699 -0.065065399 0.015664799, + 0.050219599 -0.064521298 0.0168995, + 0.051830001 -0.064003602 0.01822, + 0.0532961 -0.063525602 0.019601399, + 0.0546159 -0.063087799 0.021017199, + 0.055787299 -0.062721997 0.0224583, + 0.056809202 -0.062504798 0.0239562, + 0.0576833 -0.062412001 0.0254985, + 0.058412101 -0.062444702 0.027065201, + 0.058998398 -0.062612101 0.0286381, + 0.059445001 -0.0629244 0.0301986, + 0.059757002 -0.063390397 0.031726301, + 0.0599402 -0.064013101 0.033204801, + 0.059999999 -0.064777702 0.034637801, + 0.0599402 -0.065662801 0.0360482, + 0.059757002 -0.066682003 0.0374659, + 0.059445001 -0.067840099 0.038883399, + 0.058998398 -0.069132499 0.040283501, + 0.058412101 -0.070556097 0.041646201, + 0.0576833 -0.072104096 0.0429525, + 0.056809202 -0.073770098 0.0441829, + 0.055787299 -0.075544797 0.0453192, + 0.0546159 -0.080958501 0.0447561, + 0.0532961 -0.086786598 0.044377401, + 0.051830001 -0.0930098 0.044187099, + 0.050219599 -0.099605598 0.044185199, + 0.048467699 -0.10655 0.0443714, + 0.0465803 -0.11382 0.044743098, + 0.044564299 -0.121386 0.0452937, + 0.0424264 -0.129223 0.0460147, + 0.040174201 -0.137302 0.0468986, + 0.0378174 -0.145595 0.047940299, + 0.035366699 -0.154072 0.049135402, + 0.0328326 -0.16270199 0.050479099, + 0.0321921 -0.17145801 0.050747801, + 0.0532961 -0.065801203 0.018771499, + 0.051830001 -0.066248901 0.0174581, + 0.050219599 -0.066721 0.0161941, + 0.048467699 -0.067215301 0.0150045, + 0.0465803 -0.067717798 0.0139118, + 0.044564299 -0.068212703 0.0129398, + 0.0424264 -0.0686801 0.0121091, + 0.040174201 -0.069095999 0.0114368, + 0.0378174 -0.069436401 0.0109332, + 0.035366699 -0.069675997 0.0106033, + 0.0328326 -0.069788702 0.0104459, + 0.0302257 -0.0697501 0.0104537, + 0.027557701 -0.0695417 0.0106141, + 0.0248404 -0.069149002 0.010912, + 0.0220857 -0.068560801 0.0113259, + 0.019305199 -0.067766197 0.0118193, + 0.0165099 -0.066763297 0.0123824, + 0.0137106 -0.065563098 0.0129968, + 0.055787299 -0.072329298 0.018380901, + 0.056809202 -0.072326504 0.019778, + 0.0576833 -0.072436497 0.0211976, + 0.058412101 -0.072669901 0.0226213, + 0.058998398 -0.073036402 0.0240284, + 0.059445001 -0.076137699 0.0240543, + 0.059757002 -0.079626702 0.0239194, + 0.0599402 -0.083468102 0.023572801, + 0.059999999 -0.087579802 0.023014899, + 0.0599402 -0.092035703 0.0224366, + 0.059757002 -0.096891001 0.0220885, + 0.059445001 -0.102122 0.0220041, + 0.058998398 -0.107714 0.022191601, + 0.058412101 -0.113652 0.022652199, + 0.0576833 -0.119922 0.0233858, + 0.056809202 -0.126505 0.024386, + 0.055787299 -0.13338199 0.0256446, + 0.0546159 -0.140534 0.027153, + 0.0532961 -0.14793999 0.028902, + 0.051830001 -0.15558 0.030882699, + 0.050219599 -0.163431 0.033085998, + 0.0499245 -0.171472 0.033416498, + 0.0053973799 -0.070991397 0.011106, + 0.00268824 -0.067183599 0.0127659, + 0 -0.063188002 0.0142554, + -0.00268824 -0.067183599 0.0127658, + -0.0053973799 -0.070991397 0.011106, + -0.0081428103 -0.0745802 0.0093115903, + -0.054601401 -0.171479 0.0249705, + -0.055579402 -0.19148 0.0227562, + -0.054184102 -0.171478 0.025906499, + -0.055569701 -0.17148 0.022736499, + -0.055771701 -0.171481 0.022216201, + -0.056448001 -0.171482 0.020474199, + -0.056793399 -0.171483 0.0194366, + -0.055787299 -0.163877 0.022368601, + -0.0109179 -0.0779282 0.0074255499, + -0.0109179 -0.076013103 0.0084685301, + -0.0137106 -0.077260897 0.0076732198, + -0.0137106 -0.079154298 0.0066070398, + -0.0165099 -0.078322798 0.0069482801, + -0.0165099 -0.080197297 0.0058654002, + -0.019305199 -0.079201303 0.0063141999, + -0.019305199 -0.081060797 0.0052193501, + -0.0220857 -0.079901598 0.0057892199, + -0.0220857 -0.081751198 0.00468574, + -0.0248404 -0.080432497 0.00538899, + -0.0248404 -0.0822777 0.0042783301, + -0.027557701 -0.080807701 0.00512427, + -0.027557701 -0.082653902 0.0040058699, + -0.0302257 -0.081042603 0.0050016502, + -0.0302257 -0.082894497 0.0038729401, + -0.0328326 -0.081152201 0.00502392, + -0.0328326 -0.083013602 0.00388145, + -0.035366699 -0.081151702 0.0051906202, + -0.035366699 -0.083024897 0.0040293401, + -0.0378174 -0.081057802 0.0054954002, + -0.0378174 -0.082943901 0.0043090498, + -0.040174201 -0.080886103 0.0059281802, + -0.040174201 -0.082782298 0.0047087101, + -0.0424264 -0.080647498 0.0064753499, + -0.0424264 -0.082577102 0.0052201301, + -0.044564299 -0.080380701 0.0071274899, + -0.044564299 -0.0823562 0.0058607799, + -0.0465803 -0.080117598 0.0079023102, + -0.0465803 -0.0821165 0.0066278302, + -0.048467699 -0.079852201 0.0087959897, + -0.048467699 -0.081885099 0.0075098798, + -0.050219599 -0.079611197 0.0097959004, + -0.050219599 -0.081682198 0.0084951501, + -0.051830001 -0.079414003 0.0108891, + -0.051830001 -0.081524603 0.0095705204, + -0.0532961 -0.079277299 0.012061, + -0.0532961 -0.081428997 0.0107205, + -0.0546159 -0.079216897 0.0132949, + -0.0546159 -0.081410103 0.0119277, + -0.055787299 -0.079246603 0.0145727, + -0.055787299 -0.081482701 0.0131716, + -0.056809202 -0.079379499 0.015873499, + -0.056809202 -0.083932601 0.0129894, + -0.0576833 -0.081980497 0.0157582, + -0.0576833 -0.086776301 0.0127637, + -0.058412101 -0.084975697 0.0155715, + -0.058412101 -0.089992799 0.012442, + -0.058998398 -0.088339798 0.015261, + -0.058998398 -0.0935302 0.011986, + -0.059445001 -0.092018001 0.0147885, + -0.059445001 -0.097461797 0.0115347, + -0.059757002 -0.096088797 0.0143009, + -0.059757002 -0.10183 0.0112546, + -0.0599402 -0.100595 0.0139794, + -0.0599402 -0.106614 0.0111558, + -0.059999999 -0.105504 0.013856, + -0.059999999 -0.111776 0.0112699, + -0.0599402 -0.110782 0.0139675, + -0.0599402 -0.117291 0.0116327, + -0.059757002 -0.116402 0.0143493, + -0.059757002 -0.123129 0.0122776, + -0.059445001 -0.122341 0.015029, + -0.059445001 -0.129265 0.0132276, + -0.058998398 -0.128584 0.0160075, + -0.058998398 -0.135684 0.0144824, + -0.058412101 -0.135113 0.0172788, + -0.058412101 -0.14237 0.016035801, + -0.0576833 -0.141911 0.0188377, + -0.0576833 -0.149307 0.0178797, + -0.056809202 -0.148963 0.020676401, + -0.056809202 -0.156482 0.0199969, + -0.055787299 -0.156251 0.0227778, + -0.0546159 -0.163761 0.025123199, + -0.055382699 -0.17148 0.023218101, + -0.0532961 -0.16364799 0.027840201, + -0.0546159 -0.15602399 0.025532801, + -0.055787299 -0.14861999 0.023458101, + -0.056809202 -0.141453 0.0216354, + -0.0576833 -0.13453899 0.020081701, + -0.058412101 -0.12789799 0.0188048, + -0.058998398 -0.121546 0.017810101, + -0.059445001 -0.115502 0.017102299, + -0.059757002 -0.109779 0.016686101, + -0.0599402 -0.104394 0.016556101, + -0.059999999 -0.099369697 0.016682999, + -0.0599402 -0.094734102 0.017030399, + -0.059757002 -0.090521902 0.0175611, + -0.059445001 -0.086697102 0.018062299, + -0.058998398 -0.083179399 0.0183724, + -0.058412101 -0.080025598 0.018530799, + -0.0576833 -0.077265002 0.0185897, + -0.056809202 -0.077062801 0.0172424, + -0.055787299 -0.076974504 0.0159047, + -0.0546159 -0.0769886 0.0145975, + -0.0532961 -0.077092499 0.0133393, + -0.051830001 -0.077272102 0.0121475, + -0.050219599 -0.077510796 0.0110379, + -0.048467699 -0.077789702 0.0100252, + -0.0465803 -0.078082398 0.0091233803, + -0.044564299 -0.078398399 0.0083365301, + -0.0424264 -0.078704 0.0076451902, + -0.040174201 -0.0789565 0.0070614298, + -0.0378174 -0.0791457 0.0066010901, + -0.035366699 -0.079256698 0.0062761102, + -0.0328326 -0.079272598 0.0060955398, + -0.0302257 -0.079174697 0.0060640601, + -0.027557701 -0.078946702 0.00618135, + -0.0248404 -0.078572698 0.0064425301, + -0.0220857 -0.0780368 0.0068389, + -0.019305199 -0.077325597 0.0073575401, + -0.0165099 -0.076431103 0.00798117, + -0.0137106 -0.075349301 0.0086895004, + 0.0137106 -0.079147398 0.0066081998, + 0.0137106 -0.081020601 0.0054932898, + 0.0165099 -0.080188699 0.0058679199, + 0.0165099 -0.082043797 0.0047356701, + 0.019305199 -0.081050999 0.0052237101, + 0.019305199 -0.082892098 0.0040782099, + 0.0220857 -0.081740499 0.0046924599, + 0.0220857 -0.083572499 0.0035359301, + 0.0248404 -0.082266599 0.0042877798, + 0.0248404 -0.084094703 0.00312055, + 0.027557701 -0.082643099 0.0040180902, + 0.027557701 -0.084471799 0.0028384, + 0.0302257 -0.082884803 0.0038874401, + 0.0302257 -0.084717996 0.0026920901, + 0.0328326 -0.083005801 0.0038966599, + 0.0328326 -0.084845997 0.0026809699, + 0.035366699 -0.083019704 0.0040426902, + 0.035366699 -0.084868804 0.00280245, + 0.0378174 -0.0829423 0.0043188799, + 0.0378174 -0.084796697 0.00304904, + 0.040174201 -0.082783498 0.00471539, + 0.040174201 -0.084649198 0.0034179699, + 0.0424264 -0.082563698 0.0052289199, + 0.0424264 -0.084475197 0.0039222599, + 0.044564299 -0.082334898 0.0058738701, + 0.044564299 -0.084280699 0.0045576999, + 0.0465803 -0.082102701 0.0066433102, + 0.0465803 -0.084077999 0.0053145201, + 0.048467699 -0.081878699 0.0075257998, + 0.048467699 -0.083885103 0.0061822198, + 0.050219599 -0.081680201 0.0085099395, + 0.050219599 -0.083720498 0.0071492, + 0.051830001 -0.081524797 0.0095830197, + 0.051830001 -0.083601698 0.00820217, + 0.0532961 -0.081429899 0.0107301, + 0.0532961 -0.083545402 0.0093252296, + 0.0546159 -0.081411198 0.0119344, + 0.0546159 -0.083567902 0.0104989, + 0.056809202 -0.16399799 0.019556001, + 0.055787299 -0.163881 0.0223369, + 0.056512099 -0.171482 0.0202954, + 0.056809202 -0.15648299 0.0199575, + 0.0576833 -0.15671401 0.0171612, + 0.0576833 -0.14930201 0.017846599, + 0.058412101 -0.149647 0.0150454, + 0.058412101 -0.14235801 0.016011899, + 0.058998398 -0.14281601 0.0132163, + 0.058998398 -0.135666 0.0144613, + 0.059445001 -0.136234 0.0116825, + 0.059445001 -0.129244 0.0132037, + 0.059757002 -0.12991799 0.0104535, + 0.059757002 -0.123106 0.0122482, + 0.0599402 -0.123882 0.0095330495, + 0.0599402 -0.117268 0.0115989, + 0.059999999 -0.118149 0.0089031802, + 0.059999999 -0.111754 0.0112354, + 0.0599402 -0.112749 0.0085377796, + 0.0599402 -0.106593 0.0111249, + 0.059757002 -0.10771 0.0084037697, + 0.059757002 -0.101813 0.0112316, + 0.059445001 -0.103066 0.0084704701, + 0.059445001 -0.097452 0.011524, + 0.058998398 -0.0988397 0.0087281102, + 0.058998398 -0.093529202 0.011989, + 0.058412101 -0.095050998 0.0091685904, + 0.058412101 -0.089992501 0.0124462, + 0.0576833 -0.091649599 0.00962028, + 0.0576833 -0.086774498 0.0127733, + 0.056809202 -0.088572502 0.0099696303, + 0.056809202 -0.083932899 0.0129976, + 0.055787299 -0.085874602 0.0102436, + 0.055787299 -0.081484102 0.0131759, + 0.0546159 -0.079217799 0.0133047, + 0.0532961 -0.079277501 0.0120737, + 0.051830001 -0.079411797 0.0109043, + 0.050219599 -0.079604603 0.0098123904, + 0.048467699 -0.079837903 0.0088120801, + 0.0465803 -0.080095299 0.0079159997, + 0.044564299 -0.0803665 0.0071367202, + 0.0424264 -0.080648802 0.0064824, + 0.040174201 -0.080884397 0.0059386301, + 0.0378174 -0.081052102 0.0055096699, + 0.035366699 -0.081143297 0.0052069998, + 0.0328326 -0.081141599 0.00503967, + 0.0302257 -0.081030697 0.0050150598, + 0.027557701 -0.0807954 0.0051347502, + 0.0248404 -0.080420397 0.0053965598, + 0.0220857 -0.0798904 0.0057942001, + 0.019305199 -0.079191297 0.0063171401, + 0.0165099 -0.078314401 0.0069496701, + 0.0137106 -0.077254198 0.0076730801, + 0.0555728 -0.17148 0.0227377, + 0.055773102 -0.171481 0.022216801, + 0.0567948 -0.171483 0.019437101, + 0.057432801 -0.17148501 0.0174996, + 0.057608999 -0.191485 0.0169216, + 0.052960701 -0.191476 0.0283511, + 0.0532845 -0.17147601 0.027688401, + 0.0518195 -0.17147399 0.030356299, + 0.048232201 -0.17147 0.035824802, + 0.0460728 -0.191468 0.038588099, + 0.046576701 -0.171468 0.037951101, + 0.046423901 -0.171468 0.0381473, + 0.044562999 -0.17146599 0.040309601, + 0.059027899 -0.19148999 0.0109093, + 0.058398101 -0.171487 0.013844, + 0.059432998 -0.171492 0.0082778595, + 0.050219599 -0.095307 -0.0019905199, + 0.050219599 -0.093379602 -0.00040171301, + 0.051830001 -0.095596701 -0.00098401005, + 0.048467699 -0.095149301 -0.00291194, + 0.048467699 -0.0933358 -0.00132105, + 0.0465803 -0.0951178 -0.00372762, + 0.0465803 -0.093384102 -0.0021118501, + 0.044564299 -0.095166802 -0.0044020801, + 0.044564299 -0.093454301 -0.00278937, + 0.0424264 -0.095223203 -0.0049520601, + 0.0424264 -0.093533598 -0.0033581001, + 0.040174201 -0.095273897 -0.00538381, + 0.040174201 -0.093602203 -0.00380373, + 0.0378174 -0.095300302 -0.0056860298, + 0.0378174 -0.093642101 -0.0041181198, + 0.035366699 -0.095284402 -0.0058519002, + 0.035366699 -0.093635902 -0.0042957901, + 0.0328326 -0.095208101 -0.00587674, + 0.0328326 -0.093564898 -0.0043326798, + 0.0302257 -0.0950533 -0.0057580201, + 0.0302257 -0.093412198 -0.0042266599, + 0.027557701 -0.094805703 -0.0054972302, + 0.027557701 -0.093167901 -0.0039789202, + 0.0248404 -0.094455503 -0.0050970102, + 0.0248404 -0.092820697 -0.00359294, + 0.0220857 -0.0939904 -0.0045612999, + 0.0220857 -0.092340097 -0.0030789301, + 0.019305199 -0.093383104 -0.0039001401, + 0.019305199 -0.091715701 -0.0024417001, + 0.0165099 -0.092626996 -0.0031214, + 0.0165099 -0.090941697 -0.00168706, + 0.0137106 -0.091716804 -0.00223263, + 0.0137106 -0.090010598 -0.000823426, + 0.0109179 -0.0906455 -0.0012433, + 0.0109179 -0.088915698 0.000139033, + -0.0109179 -0.098735802 -0.0088125402, + -0.0109179 -0.101683 -0.0121075, + -0.0137106 -0.099676199 -0.0099357404, + -0.0081428103 -0.099170901 -0.0091905203, + 0.0081428103 -0.096073702 -0.0060188598, + 0.0109179 -0.097196802 -0.0072159902, + 0.0081428103 -0.099168301 -0.0091888402, + 0.0053973799 -0.096392304 -0.0062699099, + 0.0053973799 -0.093147397 -0.00324002, + 0.00268824 -0.093342401 -0.0033775701, + 0.00268824 -0.089952901 -0.00050287199, + 0 -0.090019204 -0.00054411899, + 0 -0.0864904 0.0021585601, + -0.00268824 -0.089953899 -0.00050407101, + -0.00268824 -0.093342997 -0.0033788199, + -0.0053973799 -0.093148701 -0.0032425199, + -0.0053973799 -0.096392497 -0.0062713102, + -0.0081428103 -0.096074 -0.00602098, + -0.0109179 -0.0956183 -0.0056625898, + -0.0137106 -0.095020004 -0.0051920698, + -0.0109179 -0.093999803 -0.0041484199, + -0.056809202 -0.110802 -0.0041631502, + -0.0576833 -0.112318 -0.0027278301, + -0.056809202 -0.108173 -0.0027338001, + -0.055787299 -0.109441 -0.00553045, + -0.055787299 -0.106915 -0.0040483898, + -0.0546159 -0.108231 -0.0068213702, + -0.0546159 -0.105812 -0.0052890698, + -0.0532961 -0.10717 -0.0080269398, + -0.0532961 -0.104859 -0.0064469501, + -0.051830001 -0.106252 -0.00913807, + -0.051830001 -0.104051 -0.0075128102, + -0.050219599 -0.105472 -0.0101455, + -0.050219599 -0.101312 -0.0068607, + -0.048467699 -0.102812 -0.0094187697, + -0.048467699 -0.100841 -0.0077803298, + -0.0465803 -0.102353 -0.010248, + -0.0465803 -0.100481 -0.0086067095, + -0.044564299 -0.101997 -0.0109703, + -0.044564299 -0.10023 -0.0093224104, + -0.0424264 -0.10174 -0.0115688, + -0.0424264 -0.100079 -0.00991116, + -0.040174201 -0.101572 -0.0120285, + -0.040174201 -0.098486602 -0.0086714104, + -0.0378174 -0.100012 -0.0106304, + -0.0378174 -0.098484799 -0.0089454902, + -0.035366699 -0.099967197 -0.0107576, + -0.035366699 -0.098450899 -0.0090888599, + -0.0328326 -0.099877097 -0.0107485, + -0.0328326 -0.098365597 -0.0090918401, + -0.0302257 -0.099721998 -0.0105949, + -0.0302257 -0.098211303 -0.0089495396, + -0.027557701 -0.099486798 -0.0102956, + -0.027557701 -0.097972803 -0.0086621996, + -0.0248404 -0.099156998 -0.0098524, + -0.0248404 -0.097635798 -0.00823214, + -0.0220857 -0.098717801 -0.0092681795, + -0.0220857 -0.097184397 -0.0076628602, + -0.019305199 -0.098154597 -0.0085477699, + -0.019305199 -0.096601799 -0.00695924, + -0.0165099 -0.0974539 -0.00769928, + -0.0165099 -0.095883101 -0.0061314101, + -0.0137106 -0.096611001 -0.00673356, + -0.0081428103 -0.092817202 -0.0030098399, + -0.0053973799 -0.089753099 -0.000380201, + -0.00268824 -0.086423799 0.00219408, + 0 -0.082834601 0.0046765902, + 0.00268824 -0.086422503 0.0021948901, + 0.0053973799 -0.089750998 -0.000377802, + 0.0081428103 -0.092815302 -0.0030060699, + 0.0109179 -0.093998201 -0.0041442998, + 0.055787299 -0.106902 -0.0040646698, + 0.055787299 -0.104424 -0.0025235801, + 0.056809202 -0.108157 -0.0027556701, + 0.0546159 -0.105803 -0.0052989302, + 0.0546159 -0.103434 -0.0037084899, + 0.0532961 -0.104854 -0.00644925, + 0.0532961 -0.102596 -0.0048157498, + 0.051830001 -0.10405 -0.0075102099, + 0.051830001 -0.0997684 -0.0042254701, + 0.050219599 -0.101312 -0.0068570902, + 0.050219599 -0.097273499 -0.00359885, + 0.048467699 -0.098903596 -0.0061407601, + 0.048467699 -0.097005799 -0.0045185201, + 0.0465803 -0.0986486 -0.0069632698, + 0.0465803 -0.096860699 -0.0053395, + 0.044564299 -0.098506398 -0.0076740002, + 0.044564299 -0.096831501 -0.0060419301, + 0.0424264 -0.098469302 -0.0082536303, + 0.0424264 -0.096870497 -0.0065907901, + 0.040174201 -0.098487496 -0.0086683501, + 0.040174201 -0.096902199 -0.0070049302, + 0.0378174 -0.098485596 -0.0089408504, + 0.0378174 -0.096914999 -0.0072940998, + 0.035366699 -0.098451503 -0.0090825204, + 0.035366699 -0.096890099 -0.0074482299, + 0.0328326 -0.098365702 -0.0090839704, + 0.0328326 -0.096808799 -0.0074612601, + 0.0302257 -0.098210096 -0.0089406697, + 0.0302257 -0.096653402 -0.00733004, + 0.027557701 -0.097969197 -0.0086531397, + 0.027557701 -0.096408501 -0.0070556798, + 0.0248404 -0.0976284 -0.0082238801, + 0.0248404 -0.096060202 -0.0066410499, + 0.0220857 -0.097173803 -0.00765636, + 0.0220857 -0.095598496 -0.0060894601, + 0.019305199 -0.096595697 -0.0069552399, + 0.019305199 -0.095010698 -0.00540605, + 0.0165099 -0.0958836 -0.0061286702, + 0.0165099 -0.0942754 -0.0046026399, + 0.0137106 -0.0950194 -0.0051885, + 0.0137106 -0.093387097 -0.00368828, + 0.0109179 -0.092340298 -0.00267154, + 0.0532961 -0.098189101 -0.00153216, + 0.0546159 -0.101116 -0.0020715301, + 0.055787299 -0.101995 -0.00092999201, + 0.056809202 -0.103034 0.000277735, + 0.0576833 -0.106881 5.5528399e-005, + 0.0576833 -0.112297 -0.0027576301, + 0.058412101 -0.111141 5.3980501e-005, + 0.058412101 -0.116828 -0.00252253, + 0.058998398 -0.115794 0.00027973601, + 0.058998398 -0.121731 -0.0020447201, + 0.059445001 -0.120821 0.00073790801, + 0.059445001 -0.126985 -0.00132176, + 0.059757002 -0.12619799 0.00142966, + 0.059757002 -0.132567 -0.00036006901, + 0.0599402 -0.13190199 0.0023537299, + 0.0599402 -0.13845 0.00083702599, + 0.059999999 -0.13789999 0.0035288199, + 0.059999999 -0.14460599 0.0022879201, + 0.0599402 -0.144164 0.0049787201, + 0.0599402 -0.151007 0.00401612, + 0.059757002 -0.150673 0.0067269001, + 0.059757002 -0.15763301 0.0060448502, + 0.059445001 -0.157405 0.0087911403, + 0.059445001 -0.164465 0.0083921598, + 0.058998398 -0.164349 0.0111675, + 0.059358198 -0.171491 0.0088889599, + 0.0590127 -0.17149 0.0108908, + 0.058984801 -0.17149 0.0110521, + 0.059716001 -0.17149401 0.0059672799, + 0.0137106 -0.096611403 -0.0067312801, + 0.0109179 -0.095617801 -0.0056597502, + 0.0137106 -0.098159999 -0.0083134901, + 0.0109179 -0.098732203 -0.0088102799, + 0.0109179 -0.10168 -0.0121039, + 0.0109179 -0.104448 -0.015527, + 0.0081428103 -0.102093 -0.0124995, + 0.0053973799 -0.099473201 -0.0094534401, + 0.00268824 -0.096579298 -0.0064173802, + 0 -0.093406402 -0.0034229101, + -0.00268824 -0.096579403 -0.0064180801, + -0.0053973799 -0.099474899 -0.0094545502, + -0.0081428103 -0.102095 -0.0125022, + -0.0109179 -0.104448 -0.0155302, + -0.0137106 -0.102563 -0.0132755, + -0.0137106 -0.103938 -0.0149922, + -0.0165099 -0.103304 -0.0143232, + -0.0165099 -0.104652 -0.016057299, + -0.019305199 -0.103916 -0.0152417, + -0.019305199 -0.105241 -0.016990401, + -0.0220857 -0.104409 -0.0160226, + -0.0220857 -0.105716 -0.017784899, + -0.0248404 -0.104796 -0.016660299, + -0.0248404 -0.10609 -0.018438401, + -0.027557701 -0.105092 -0.0171561, + -0.027557701 -0.10767 -0.0206766, + -0.0302257 -0.106646 -0.019224601, + -0.0302257 -0.108043 -0.0209479, + -0.0328326 -0.106963 -0.0193417, + -0.0328326 -0.108458 -0.021044901, + -0.035366699 -0.107332 -0.019287899, + -0.035366699 -0.108924 -0.020972, + -0.0378174 -0.10776 -0.019071599, + -0.0378174 -0.109449 -0.020738101, + -0.040174201 -0.108256 -0.018703001, + -0.040174201 -0.11004 -0.020354301, + -0.0424264 -0.108826 -0.0181941, + -0.0424264 -0.1107 -0.019834099, + -0.044564299 -0.109472 -0.017559599, + -0.044564299 -0.111449 -0.019172801, + -0.0465803 -0.110218 -0.0167956, + -0.0465803 -0.1123 -0.018364601, + -0.048467699 -0.111075 -0.0158953, + -0.048467699 -0.113261 -0.0174178, + -0.050219599 -0.11205 -0.0148668, + -0.050219599 -0.11434 -0.0163403, + -0.051830001 -0.113151 -0.013718, + -0.051830001 -0.115543 -0.0151398, + -0.0532961 -0.114385 -0.012458, + -0.0532961 -0.116876 -0.0138257, + -0.0546159 -0.115755 -0.0110961, + -0.0546159 -0.118343 -0.0124073, + -0.055787299 -0.117266 -0.0096414704, + -0.055787299 -0.119949 -0.010894, + -0.056809202 -0.118921 -0.0081035197, + -0.056809202 -0.124505 -0.0104227, + -0.0576833 -0.123589 -0.0076194, + -0.059999999 -0.158077 0.00068754499, + -0.0599402 -0.157855 0.00337649, + -0.059999999 -0.151343 0.00136076, + -0.0599402 -0.151675 -0.0013290599, + -0.0599402 -0.145059 -0.00037825201, + -0.059757002 -0.145503 -0.00309, + -0.059757002 -0.13902199 -0.00185428, + -0.059445001 -0.13958301 -0.0046034101, + -0.059445001 -0.133261 -0.00308621, + -0.058998398 -0.13394199 -0.0058661602, + -0.058998398 -0.127803 -0.0040738401, + -0.058412101 -0.128603 -0.0068728598, + -0.058412101 -0.12267 -0.0048120501, + -0.044564299 -0.107546 -0.015918501, + -0.0424264 -0.106991 -0.016545, + -0.040174201 -0.106516 -0.017041599, + -0.0378174 -0.106117 -0.0173951, + -0.035366699 -0.105788 -0.0175945, + -0.0328326 -0.105521 -0.0176297, + -0.0302257 -0.103983 -0.0157315, + -0.027557701 -0.10376 -0.0153932, + -0.0248404 -0.103456 -0.0149129, + -0.0220857 -0.103055 -0.014288, + -0.019305199 -0.102543 -0.0135209, + -0.0165099 -0.101908 -0.0126184, + -0.0137106 -0.101142 -0.0115893, + -0.0165099 -0.100469 -0.0109449, + -0.019305199 -0.101125 -0.0118303, + -0.0220857 -0.101654 -0.0125828, + -0.0248404 -0.102069 -0.0131948, + -0.027557701 -0.102381 -0.0136628, + -0.0302257 -0.102608 -0.0139857, + -0.0328326 -0.102765 -0.0141668, + -0.035366699 -0.104298 -0.015894599, + -0.0378174 -0.104524 -0.015712, + -0.040174201 -0.104821 -0.0153732, + -0.0424264 -0.105197 -0.0148889, + -0.044564299 -0.105658 -0.0142716, + -0.0465803 -0.106208 -0.0135372, + -0.0465803 -0.104263 -0.0118926, + -0.044564299 -0.103807 -0.012621, + -0.0424264 -0.103446 -0.0132291, + -0.040174201 -0.103172 -0.0137011, + -0.0378174 -0.10298 -0.0140253, + -0.035366699 -0.101439 -0.0124644, + -0.0328326 -0.101343 -0.0124396, + -0.0302257 -0.101188 -0.012274, + -0.027557701 -0.100957 -0.0119631, + -0.0248404 -0.100635 -0.0115073, + -0.0220857 -0.100208 -0.0109088, + -0.019305199 -0.099661604 -0.0101719, + -0.0165099 -0.098984398 -0.0093046697, + -0.0137106 -0.098164402 -0.0083163297, + -0.058412101 -0.11685 -0.00248888, + -0.058998398 -0.121754 -0.00201143, + -0.059445001 -0.12700699 -0.00129256, + -0.059757002 -0.132588 -0.00033594199, + -0.0599402 -0.138468 0.00085849001, + -0.059999999 -0.144618 0.0023125601, + -0.0599402 -0.151012 0.0040505598, + -0.059757002 -0.15763099 0.0060863001, + -0.059757002 -0.164575 0.0056804498, + -0.0596973 -0.17149401 0.0061562802, + -0.059920698 -0.171496 0.00322131, + -0.059803098 -0.17149501 0.0047657201, + -0.0599402 -0.16468801 0.0029712, + -0.059999999 -0.164801 0.000282819, + -0.0599402 -0.158299 -0.0020014499, + -0.059757002 -0.152009 -0.0040398501, + -0.059445001 -0.145952 -0.0058381101, + -0.058998398 -0.14015099 -0.0073822201, + -0.058412101 -0.134627 -0.0086638201, + -0.0576833 -0.12940399 -0.0096785901, + -0.055787299 -0.12541699 -0.0132111, + -0.0599402 -0.164913 -0.0024055899, + -0.059962399 -0.1715 -0.00140792, + -0.059937101 -0.1715 -0.0025516101, + -0.059934601 -0.171501 -0.0026638401, + -0.059757002 -0.16502699 -0.00511494, + -0.059445001 -0.165142 -0.0078606298, + -0.059725199 -0.17150301 -0.0055998499, + -0.058998398 -0.15898 -0.0102336, + -0.058412101 -0.153034 -0.0123582, + -0.0576833 -0.147324 -0.0142136, + -0.056809202 -0.141867 -0.015781101, + -0.0546159 -0.129042 -0.0170343, + -0.0532961 -0.127211 -0.018699, + -0.051830001 -0.125508 -0.020251, + -0.050219599 -0.123926 -0.021679901, + -0.048467699 -0.122462 -0.0229767, + -0.0465803 -0.121109 -0.0241329, + -0.044564299 -0.119862 -0.0251402, + -0.0424264 -0.118714 -0.025990799, + -0.040174201 -0.117657 -0.0266771, + -0.0378174 -0.116681 -0.027194301, + -0.035366699 -0.115781 -0.027538201, + -0.0328326 -0.114947 -0.0277042, + -0.0302257 -0.114165 -0.027695701, + -0.027557701 -0.113424 -0.027517, + -0.0248404 -0.112718 -0.0271625, + -0.0220857 -0.11204 -0.026628399, + -0.019305199 -0.11138 -0.0259136, + -0.0165099 -0.110733 -0.025021199, + -0.0137106 -0.108962 -0.022127099, + -0.0165099 -0.10841 -0.021418899, + -0.019305199 -0.110123 -0.024155701, + -0.0220857 -0.110695 -0.024894601, + -0.0248404 -0.111286 -0.0254537, + -0.027557701 -0.111904 -0.025833599, + -0.0302257 -0.112557 -0.026037199, + -0.0328326 -0.113251 -0.026068499, + -0.035366699 -0.113992 -0.025935, + -0.0378174 -0.114795 -0.025634401, + -0.040174201 -0.115673 -0.0251629, + -0.0424264 -0.116635 -0.0245248, + -0.044564299 -0.117687 -0.0237251, + -0.0465803 -0.11884 -0.0227711, + -0.048467699 -0.120098 -0.0216708, + -0.050219599 -0.12147 -0.0204321, + -0.051830001 -0.122961 -0.019063501, + -0.0532961 -0.124576 -0.0175742, + -0.0546159 -0.12632 -0.015973801, + -0.055787299 -0.128196 -0.0142723, + -0.0546159 -0.123628 -0.0148481, + -0.0532961 -0.121973 -0.016385799, + -0.051830001 -0.120451 -0.0178145, + -0.050219599 -0.119053 -0.019124901, + -0.048467699 -0.117776 -0.0203076, + -0.0465803 -0.116613 -0.0213544, + -0.044564299 -0.115558 -0.022257499, + -0.0424264 -0.114605 -0.0230086, + -0.040174201 -0.113742 -0.023600901, + -0.0378174 -0.112964 -0.0240291, + -0.035366699 -0.112256 -0.0242984, + -0.0328326 -0.111604 -0.0244116, + -0.0302257 -0.111 -0.024357401, + -0.027557701 -0.110437 -0.024130199, + -0.0248404 -0.10991 -0.023726299, + -0.0220857 -0.10941 -0.023143699, + -0.019305199 -0.10775 -0.0205696, + -0.0165099 -0.107205 -0.019605, + -0.0137106 -0.106546 -0.018508701, + -0.0137106 -0.105266 -0.0167374, + -0.0165099 -0.105953 -0.0178183, + -0.019305199 -0.106518 -0.0187659, + -0.0220857 -0.106976 -0.0195767, + -0.0248404 -0.108592 -0.021983599, + -0.027557701 -0.109025 -0.0224101, + -0.0302257 -0.109494 -0.0226599, + -0.0328326 -0.110006 -0.022736, + -0.035366699 -0.110566 -0.0226433, + -0.0378174 -0.111184 -0.022391399, + -0.040174201 -0.111865 -0.021993, + -0.0424264 -0.112626 -0.021444499, + -0.044564299 -0.113478 -0.0207392, + -0.0465803 -0.114432 -0.019885, + -0.048467699 -0.115495 -0.018889301, + -0.050219599 -0.116676 -0.017760299, + -0.051830001 -0.117977 -0.016505999, + -0.0532961 -0.119406 -0.0151356, + -0.0546159 -0.120968 -0.0136586, + -0.055787299 -0.122667 -0.0120845, + 0.0137106 -0.105266 -0.016734101, + 0.0248404 -0.107333 -0.020223901, + 0.0248404 -0.108592 -0.021980001, + 0.0220857 -0.106977 -0.019575, + 0.027557701 -0.10767 -0.020672601, + 0.027557701 -0.109024 -0.022405, + 0.0302257 -0.108042 -0.020942399, + 0.0302257 -0.109493 -0.0226549, + 0.0328326 -0.108457 -0.0210394, + 0.0328326 -0.110005 -0.022732001, + 0.035366699 -0.108924 -0.0209677, + 0.035366699 -0.110566 -0.0226407, + 0.0378174 -0.109449 -0.0207354, + 0.0378174 -0.111184 -0.0223902, + 0.040174201 -0.11004 -0.020353001, + 0.040174201 -0.111864 -0.021991, + 0.0424264 -0.110699 -0.019832, + 0.0424264 -0.112622 -0.021446301, + 0.044564299 -0.111445 -0.019174701, + 0.044564299 -0.113471 -0.0207473, + 0.0465803 -0.112292 -0.018373, + 0.0465803 -0.114421 -0.0198985, + 0.048467699 -0.11325 -0.017432, + 0.048467699 -0.115481 -0.018907901, + 0.050219599 -0.114325 -0.016359599, + 0.050219599 -0.116659 -0.017783299, + 0.051830001 -0.115527 -0.0151637, + 0.051830001 -0.117959 -0.016532799, + 0.0532961 -0.116857 -0.0138533, + 0.0532961 -0.119387 -0.0151652, + 0.0546159 -0.118323 -0.0124377, + 0.0546159 -0.120948 -0.0136901, + 0.0546159 -0.123607 -0.0148797, + 0.055787299 -0.125395 -0.0132427, + 0.0532961 -0.121954 -0.016416499, + 0.051830001 -0.120431 -0.0178433, + 0.050219599 -0.119035 -0.019150799, + 0.048467699 -0.11776 -0.0203299, + 0.0465803 -0.116599 -0.0213724, + 0.044564299 -0.115548 -0.022270501, + 0.0424264 -0.114598 -0.023016401, + 0.040174201 -0.113739 -0.023602599, + 0.0378174 -0.112963 -0.0240272, + 0.035366699 -0.112256 -0.0242972, + 0.0328326 -0.111604 -0.024409199, + 0.0302257 -0.110999 -0.0243538, + 0.027557701 -0.110437 -0.0241256, + 0.0248404 -0.109909 -0.023721799, + 0.0220857 -0.10941 -0.023140499, + 0.019305199 -0.10775 -0.020568101, + 0.019305199 -0.106519 -0.018763499, + 0.0165099 -0.107206 -0.0196029, + 0.0165099 -0.105954 -0.0178154, + 0.0137106 -0.106546 -0.0185063, + 0.056809202 -0.13018399 -0.0125081, + 0.0576833 -0.135295 -0.0114915, + 0.058412101 -0.140705 -0.0101997, + 0.058998398 -0.146395 -0.0086401096, + 0.059445001 -0.152343 -0.0068211299, + 0.059757002 -0.158525 -0.0047528399, + 0.0599402 -0.16491801 -0.00243967, + 0.0599254 -0.171501 -0.00285355, + 0.059999999 -0.164805 0.00024871199, + 0.059962101 -0.1715 -0.00140785, + 0.0599402 -0.158301 -0.00204303, + 0.059757002 -0.152004 -0.00407418, + 0.059445001 -0.14594001 -0.0058625201, + 0.058998398 -0.14013299 -0.00740335, + 0.058412101 -0.134607 -0.0086874096, + 0.0576833 -0.129383 -0.00970692, + 0.056809202 -0.124483 -0.0104547, + 0.055787299 -0.119928 -0.0109261, + 0.0546159 -0.115735 -0.0111243, + 0.0532961 -0.114367 -0.0124825, + 0.051830001 -0.113136 -0.013738, + 0.050219599 -0.112038 -0.0148814, + 0.048467699 -0.111067 -0.015904101, + 0.0465803 -0.110214 -0.0167976, + 0.044564299 -0.109471 -0.017557301, + 0.0424264 -0.108826 -0.0181928, + 0.040174201 -0.108256 -0.0187001, + 0.0378174 -0.10776 -0.019067001, + 0.035366699 -0.107331 -0.019282, + 0.0328326 -0.106962 -0.0193357, + 0.0302257 -0.106646 -0.019220199, + 0.027557701 -0.106374 -0.0189279, + 0.0248404 -0.106091 -0.018436501, + 0.0220857 -0.105717 -0.0177821, + 0.019305199 -0.105242 -0.016987, + 0.0165099 -0.104652 -0.016053399, + 0.0137106 -0.103937 -0.0149882, + 0.059935 -0.171496 0.0028246699, + 0.059980098 -0.19149999 -0.00139239, + 0.0599989 -0.171498 0.00013653201, + 0.059999999 -0.171498 8.8971698e-005, + 0.0599331 -0.1715 -0.00255149, + 0.059746101 -0.17150301 -0.00526, + 0.0030887299 -0.191451 0.060072899, + 0.00267493 -0.171451 0.060068998, + 0.0122731 -0.19154499 -0.0585788, + 0.0145714 -0.171545 -0.058067098, + 0.0182469 -0.191544 -0.057005599, + 0.0053966301 -0.171546 -0.0596103, + 0.00294237 -0.171546 -0.0597912, + 0.0053973799 -0.169433 -0.059590999, + 0.00616926 -0.19154599 -0.059529498, + 0.0058778701 -0.171546 -0.059574801, + 0.0109154 -0.171545 -0.058847699, + 0.0087992204 -0.171546 -0.0592147, + 0.0116994 -0.171545 -0.0587117, + 0.0109179 -0.169416 -0.058833301, + 0.0081412597 -0.171546 -0.0592958, + 0.0061684698 -0.171546 -0.059539001, + 0.0081428103 -0.16942599 -0.059279401, + 0.0081428103 -0.167292 -0.059185099, + 0.0053973799 -0.16730499 -0.059496399, + 0.0053973799 -0.16516501 -0.059335802, + 0.00268824 -0.165177 -0.059518099, + 0.00268824 -0.16303299 -0.0592907, + 0 -0.163038 -0.0593496, + 0 -0.160889 -0.059054799, + -0.00268824 -0.16303299 -0.0592889, + -0.00268824 -0.165176 -0.0595163, + -0.0053973799 -0.16516501 -0.059332199, + -0.0053973799 -0.16730399 -0.0594933, + -0.0081428103 -0.167291 -0.059180401, + -0.0081428103 -0.16942599 -0.059276499, + -0.0109179 -0.169416 -0.058829401, + -0.0089870598 -0.171546 -0.0591865, + -0.010915 -0.171545 -0.0588459, + -0.0118856 -0.171545 -0.058674399, + -0.0122731 -0.19154499 -0.0585788, + -0.00616926 -0.19154599 -0.059529498, + -0.00814093 -0.171546 -0.059293501, + -0.0061689499 -0.171546 -0.059542999, + -0.0060668602 -0.171546 -0.059555899, + -0.0053973799 -0.169432 -0.059589099, + -0.00268824 -0.167312 -0.059677299, + 0 -0.16518 -0.059576999, + 0.00268824 -0.167312 -0.0596788, + 0 -0.19154599 -0.0598475, + -0.0026879699 -0.171546 -0.0597945, + -0.0031320599 -0.171546 -0.0597816, + -0.00268824 -0.16943599 -0.0597727, + -0.000344617 -0.171546 -0.059862401, + 0 -0.16943701 -0.059833001, + 0 -0.16731501 -0.059737802, + 0.00268824 -0.16943599 -0.059773698, + 0.0026880901 -0.171546 -0.059797499, + 0 -0.171546 -0.0598634, + -0.0053963801 -0.171546 -0.059607401, + -0.0030887299 -0.191451 0.060072899, + -0.0028477299 -0.171451 0.060068902, + -0.0053912699 -0.171451 0.059885401, + -0.0137069 -0.171545 -0.058259599, + -0.0122713 -0.171545 -0.058586601, + 0.016505901 -0.171544 -0.057532098, + 0.017408401 -0.171544 -0.0572825, + 0.022080099 -0.171543 -0.0556361, + 0.029552899 -0.19154 -0.052064601, + 0.0282706 -0.17154001 -0.052785799, + 0.0302257 -0.169264 -0.051668301, + 0.027557701 -0.167035 -0.053041399, + 0.0248404 -0.164846 -0.0542005, + 0.0220857 -0.162689 -0.055143502, + 0.019305199 -0.160561 -0.055868998, + 0.0165099 -0.158453 -0.056378301, + 0.0137106 -0.156363 -0.056673501, + 0.0109179 -0.154282 -0.0567565, + 0.0081428103 -0.152207 -0.056629401, + 0.0053973799 -0.150133 -0.056297801, + 0.00268824 -0.148058 -0.0557677, + 0 -0.14597701 -0.0550454, + -0.00268824 -0.148059 -0.055766702, + -0.0053973799 -0.150134 -0.056295902, + -0.0081428103 -0.152209 -0.056626402, + -0.0109179 -0.154284 -0.056752, + -0.0137106 -0.15636501 -0.056666899, + -0.0165099 -0.158455 -0.056368802, + -0.019305199 -0.160561 -0.055856399, + -0.0220857 -0.162689 -0.055128101, + -0.0248404 -0.16484401 -0.054183699, + -0.027557701 -0.167033 -0.0530257, + -0.0302257 -0.16926301 -0.051657598, + -0.0295441 -0.17154001 -0.052065101, + 0.030832 -0.17153899 -0.051335599, + 0.0302194 -0.17154001 -0.051682401, + 0.029544 -0.17154001 -0.052064799, + 0.032826498 -0.171538 -0.0500734, + 0.039609101 -0.191534 -0.0449154, + 0.038047399 -0.171535 -0.046257298, + 0.042409498 -0.17153201 -0.042306699, + 0.0465752 -0.171528 -0.0376768, + 0.047984999 -0.171527 -0.035872102, + -0.050211899 -0.171524 -0.032691099, + -0.051434901 -0.171523 -0.0307485, + -0.048467699 -0.161 -0.034692802, + -0.0465803 -0.15860599 -0.036847699, + -0.044564299 -0.156297 -0.0388414, + -0.0424264 -0.154071 -0.040661901, + -0.040174201 -0.151921 -0.042298101, + -0.0378174 -0.14984199 -0.043741699, + -0.035366699 -0.147829 -0.0449862, + -0.0328326 -0.14587601 -0.046025701, + -0.0302257 -0.143978 -0.0468552, + -0.027557701 -0.14212599 -0.047472499, + -0.0248404 -0.14031699 -0.047876701, + -0.0220857 -0.13854399 -0.048066501, + -0.019305199 -0.136801 -0.0480414, + -0.0165099 -0.135083 -0.047804002, + -0.0137106 -0.133385 -0.047359198, + -0.0109179 -0.13170201 -0.046711501, + -0.0081428103 -0.13002799 -0.045866299, + -0.0053973799 -0.12836 -0.044830799, + -0.00268824 -0.12669501 -0.043612901, + 0 -0.125029 -0.042220101, + 0.00268824 -0.12669399 -0.043613899, + 0.0053973799 -0.12835801 -0.044833299, + 0.0081428103 -0.130025 -0.045870598, + 0.0109179 -0.131698 -0.046717599, + 0.0137106 -0.133379 -0.0473671, + 0.0165099 -0.135077 -0.047813699, + 0.019305199 -0.136793 -0.0480523, + 0.0220857 -0.13853499 -0.048078299, + 0.0248404 -0.14030799 -0.047888901, + 0.027557701 -0.142116 -0.0474848, + 0.0302257 -0.143967 -0.0468674, + 0.0328326 -0.14586601 -0.046038002, + 0.035366699 -0.147819 -0.044998799, + 0.0378174 -0.149832 -0.043755598, + 0.040174201 -0.151912 -0.0423146, + 0.0424264 -0.154064 -0.040682498, + 0.044564299 -0.156293 -0.038867, + 0.0465803 -0.15860499 -0.036878102, + 0.048467699 -0.161002 -0.034726501, + 0.048467699 -0.158352 -0.034426998, + 0.0465803 -0.156003 -0.036509499, + 0.044564299 -0.15374 -0.0384291, + 0.0424264 -0.15156101 -0.0401752, + 0.040174201 -0.149461 -0.041737702, + 0.0378174 -0.147433 -0.043109301, + 0.035366699 -0.14547201 -0.0442838, + 0.0328326 -0.143571 -0.0452547, + 0.0302257 -0.141725 -0.046016499, + 0.027557701 -0.139929 -0.0465669, + 0.0248404 -0.138175 -0.046904702, + 0.0220857 -0.136457 -0.0470284, + 0.019305199 -0.134771 -0.0469376, + 0.0165099 -0.13311 -0.046636499, + 0.0137106 -0.131467 -0.0461298, + 0.0109179 -0.129841 -0.045422599, + 0.0081428103 -0.128223 -0.0445203, + 0.0053973799 -0.12661 -0.043430299, + 0.00268824 -0.125 -0.042160399, + 0 -0.123389 -0.0407185, + -0.00268824 -0.125001 -0.042159598, + -0.0053973799 -0.12661199 -0.043428201, + -0.0081428103 -0.128225 -0.044516601, + -0.0109179 -0.12984499 -0.045417, + -0.0137106 -0.131473 -0.046122201, + -0.0165099 -0.13311601 -0.046627, + -0.019305199 -0.13477799 -0.046926498, + -0.0220857 -0.136466 -0.047015902, + -0.0248404 -0.138184 -0.046891399, + -0.027557701 -0.139939 -0.046553399, + -0.0302257 -0.141736 -0.046002898, + -0.0328326 -0.143582 -0.045241401, + -0.035366699 -0.145483 -0.044270702, + -0.0378174 -0.14744399 -0.043095801, + -0.040174201 -0.149471 -0.041722901, + -0.0424264 -0.15157001 -0.040157799, + -0.044564299 -0.15374701 -0.038407501, + -0.0465803 -0.15600701 -0.036482699, + -0.048467699 -0.158353 -0.0343954, + -0.050219599 -0.16079099 -0.032157399, + -0.050219599 -0.15809201 -0.031859599, + -0.048467699 -0.155705 -0.034030002, + -0.0465803 -0.153409 -0.036048502, + -0.044564299 -0.15120199 -0.037903, + -0.0424264 -0.149078 -0.0395822, + -0.040174201 -0.14703199 -0.041076601, + -0.0378174 -0.145059 -0.042379901, + -0.035366699 -0.143153 -0.043485899, + -0.0328326 -0.14130899 -0.044388901, + -0.0302257 -0.13951901 -0.0450834, + -0.027557701 -0.137779 -0.045567699, + -0.0248404 -0.13608199 -0.045840401, + -0.0220857 -0.134422 -0.045900598, + -0.019305199 -0.13279299 -0.045749102, + -0.0165099 -0.131189 -0.045389801, + -0.0137106 -0.129603 -0.044827498, + -0.0109179 -0.128032 -0.0440671, + -0.0081428103 -0.12647 -0.043113802, + -0.0053973799 -0.124914 -0.041974802, + -0.00268824 -0.123359 -0.040658001, + 0 -0.121804 -0.039170999, + 0.00268824 -0.123359 -0.0406585, + 0.0053973799 -0.124912 -0.0419764, + 0.0081428103 -0.126468 -0.043116901, + 0.0109179 -0.128029 -0.044072099, + 0.0137106 -0.12959801 -0.044834498, + 0.0165099 -0.131182 -0.045398898, + 0.019305199 -0.13278501 -0.045760199, + 0.0220857 -0.134414 -0.045913398, + 0.0248404 -0.13607199 -0.045854401, + 0.027557701 -0.137769 -0.045582298, + 0.0302257 -0.13950799 -0.0450982, + 0.0328326 -0.141297 -0.044403501, + 0.035366699 -0.143141 -0.0435002, + 0.0378174 -0.145046 -0.042394001, + 0.040174201 -0.14702 -0.041090999, + 0.0424264 -0.149067 -0.039597798, + 0.044564299 -0.15119299 -0.037921201, + 0.0465803 -0.153402 -0.036071099, + 0.048467699 -0.155701 -0.0340579, + 0.0532961 -0.165959 -0.027308701, + 0.053283598 -0.17151999 -0.027414801, + 0.0542247 -0.171519 -0.0255477, + 0.054336499 -0.171519 -0.0252958, + 0.054602101 -0.171518 -0.024697701, + 0.0546159 -0.16584501 -0.024591601, + 0.0532961 -0.160357 -0.026916901, + 0.050219599 -0.152686 -0.0310832, + 0.051830001 -0.149561 -0.027964801, + 0.0532961 -0.154737 -0.0262456, + 0.0546159 -0.16013201 -0.0241994, + 0.055787299 -0.16573 -0.0218371, + 0.055772301 -0.171516 -0.021943299, + 0.056480099 -0.171514 -0.020111799, + 0.0566587 -0.171514 -0.0195724, + 0.056793999 -0.171514 -0.019163599, + 0.050219599 -0.14729799 -0.029994501, + 0.050219599 -0.144618 -0.0293456, + 0.048467699 -0.145137 -0.0318828, + 0.048467699 -0.14252201 -0.0311653, + 0.0465803 -0.14307299 -0.0336194, + 0.0465803 -0.140526 -0.032833699, + 0.044564299 -0.141103 -0.035194099, + 0.044564299 -0.138624 -0.034340899, + 0.0424264 -0.13922299 -0.036597099, + 0.0424264 -0.136812 -0.0356769, + 0.040174201 -0.13742501 -0.037818901, + 0.040174201 -0.135084 -0.036832199, + 0.0378174 -0.135703 -0.038852699, + 0.0378174 -0.133434 -0.037800301, + 0.035366699 -0.13405401 -0.039692201, + 0.035366699 -0.13185599 -0.0385749, + 0.0328326 -0.132469 -0.040331502, + 0.0328326 -0.130345 -0.039151501, + 0.0302257 -0.130941 -0.040766802, + 0.0302257 -0.12888899 -0.0395265, + 0.027557701 -0.129463 -0.040997598, + 0.027557701 -0.12748399 -0.039699402, + 0.0248404 -0.128029 -0.041024301, + 0.0248404 -0.126123 -0.039670698, + 0.0220857 -0.126632 -0.040847398, + 0.0220857 -0.124798 -0.0394408, + 0.019305199 -0.125264 -0.0404681, + 0.019305199 -0.123502 -0.039011199, + 0.0165099 -0.12392 -0.039890599, + 0.0165099 -0.122229 -0.038385801, + 0.0137106 -0.122594 -0.039119899, + 0.0137106 -0.120974 -0.037569702, + 0.0109179 -0.121281 -0.038160902, + 0.0109179 -0.11973 -0.036568802, + 0.0081428103 -0.119973 -0.037019901, + 0.0081428103 -0.11849 -0.035389502, + 0.0081428103 -0.117064 -0.033722799, + 0.0109179 -0.118236 -0.034938101, + 0.0137106 -0.11941 -0.0359767, + 0.0165099 -0.120593 -0.036834601, + 0.019305199 -0.121791 -0.037505299, + 0.0220857 -0.123013 -0.037983, + 0.0248404 -0.124263 -0.038263299, + 0.027557701 -0.125549 -0.038344901, + 0.0302257 -0.12687901 -0.038227499, + 0.0328326 -0.128259 -0.037910499, + 0.035366699 -0.129695 -0.0373942, + 0.0378174 -0.131198 -0.0366823, + 0.040174201 -0.132772 -0.035779301, + 0.0424264 -0.134426 -0.034689698, + 0.044564299 -0.13616601 -0.033420201, + 0.0465803 -0.137996 -0.03198, + 0.048467699 -0.139924 -0.0303792, + 0.050219599 -0.14195099 -0.028627601, + 0.051830001 -0.144085 -0.0267355, + 0.050219599 -0.139302 -0.027841, + 0.048467699 -0.137344 -0.0295249, + 0.0465803 -0.13549 -0.031058701, + 0.044564299 -0.133734 -0.0324324, + 0.0424264 -0.13207 -0.033636, + 0.040174201 -0.130493 -0.034660701, + 0.0378174 -0.128997 -0.035501, + 0.035366699 -0.127572 -0.0361524, + 0.0328326 -0.126214 -0.0366106, + 0.0302257 -0.124912 -0.036872, + 0.027557701 -0.123661 -0.036936399, + 0.0248404 -0.122453 -0.0368043, + 0.0220857 -0.12128 -0.036476001, + 0.019305199 -0.120136 -0.0359529, + 0.0165099 -0.119014 -0.035240501, + 0.0137106 -0.117903 -0.034345701, + 0.0109179 -0.1168 -0.033271801, + 0.0081428103 -0.115698 -0.032023299, + 0.0053973799 -0.114593 -0.030607801, + 0.00268824 -0.11231 -0.027255399, + 0 -0.110163 -0.0236696, + -0.00268824 -0.11231 -0.0272558, + -0.0053973799 -0.114593 -0.030608701, + -0.0081428103 -0.117064 -0.033723399, + -0.0109179 -0.118236 -0.034938499, + -0.0137106 -0.11941 -0.0359773, + -0.0165099 -0.120595 -0.036833901, + -0.019305199 -0.121795 -0.037501901, + -0.0220857 -0.123018 -0.0379766, + -0.0248404 -0.12427 -0.038253698, + -0.027557701 -0.125558 -0.038332202, + -0.0302257 -0.12688901 -0.038211901, + -0.0328326 -0.128271 -0.037892301, + -0.035366699 -0.12970901 -0.0373739, + -0.0378174 -0.131212 -0.036660399, + -0.040174201 -0.132788 -0.035756599, + -0.0424264 -0.134442 -0.034667101, + -0.044564299 -0.136182 -0.0333983, + -0.0465803 -0.13801301 -0.031959299, + -0.048467699 -0.13994101 -0.0303596, + -0.050219599 -0.141968 -0.0286089, + -0.051830001 -0.1441 -0.026717, + -0.0532961 -0.146339 -0.0246945, + -0.0109179 -0.1168 -0.033272602, + -0.0137106 -0.116452 -0.032680999, + -0.0109179 -0.115423 -0.0315747, + -0.0137106 -0.117903 -0.034346201, + -0.0165099 -0.117489 -0.0336098, + -0.0165099 -0.119014 -0.035241298, + -0.019305199 -0.118537 -0.034358598, + -0.019305199 -0.120138 -0.035952099, + -0.0220857 -0.119604 -0.0349214, + -0.0220857 -0.121284 -0.036472, + -0.0248404 -0.120699 -0.035291601, + -0.0248404 -0.122459 -0.036796998, + -0.027557701 -0.121828 -0.035468198, + -0.027557701 -0.123669 -0.0369258, + -0.0302257 -0.123001 -0.035450801, + -0.0302257 -0.124922 -0.0368581, + -0.0328326 -0.124224 -0.035239, + -0.0328326 -0.12622599 -0.036593601, + -0.035366699 -0.12550201 -0.034833301, + -0.035366699 -0.12758499 -0.036132701, + -0.0378174 -0.126848 -0.034237299, + -0.0378174 -0.12901101 -0.035479199, + -0.040174201 -0.12826499 -0.033455499, + -0.040174201 -0.130509 -0.0346375, + -0.0424264 -0.12976301 -0.032492299, + -0.0424264 -0.13208701 -0.033612099, + -0.044564299 -0.131348 -0.031353001, + -0.044564299 -0.133751 -0.032408699, + -0.0465803 -0.133027 -0.030045601, + -0.0465803 -0.135507 -0.0310359, + -0.048467699 -0.13480601 -0.0285793, + -0.048467699 -0.137362 -0.029503301, + -0.050219599 -0.13668799 -0.026963901, + -0.050219599 -0.139319 -0.027820701, + -0.051830001 -0.13868 -0.025209, + -0.051830001 -0.14138199 -0.0259977, + -0.0532961 -0.140782 -0.0233254, + -0.0532961 -0.143555 -0.0240451, + -0.0081428103 -0.114392 -0.0302958, + -0.0053973799 -0.112182 -0.0270746, + -0.00268824 -0.110118 -0.023611501, + 0 -0.107839 -0.020011799, + 0.00268824 -0.110118 -0.0236113, + 0.0053973799 -0.112182 -0.027073801, + 0.0081428103 -0.114392 -0.0302945, + 0.0109179 -0.115423 -0.0315734, + 0.0137106 -0.116452 -0.032680001, + 0.0165099 -0.117489 -0.033609301, + 0.019305199 -0.118537 -0.0343577, + 0.0220857 -0.119602 -0.034922399, + 0.0248404 -0.120695 -0.035296001, + 0.027557701 -0.121822 -0.0354762, + 0.0302257 -0.122992 -0.035462402, + 0.0328326 -0.124213 -0.035254098, + 0.035366699 -0.12548999 -0.034851599, + 0.0378174 -0.12683401 -0.034258299, + 0.040174201 -0.12825 -0.033478599, + 0.0424264 -0.129747 -0.0325169, + 0.044564299 -0.131331 -0.031378102, + 0.0465803 -0.133009 -0.0300704, + 0.048467699 -0.13478699 -0.028603099, + 0.050219599 -0.13666999 -0.0269862, + 0.051830001 -0.138662 -0.025229899, + -0.059434399 -0.171505 -0.0080049802, + -0.0594876 -0.17150401 -0.0075654299, + -0.059503399 -0.191504 -0.0075514098, + -0.0583992 -0.171509 -0.0135711, + -0.056795701 -0.171514 -0.019164201, + -0.0554916 -0.171517 -0.022681899, + -0.0546159 -0.165841 -0.024560601, + -0.0532961 -0.160355 -0.026879899, + -0.051830001 -0.15782399 -0.029251, + 0 -0.117393 -0.034283299, + 0.00268824 -0.118771 -0.035889901, + 0 -0.120275 -0.037580598, + -0.00268824 -0.120243 -0.037520301, + -0.00268824 -0.121773 -0.039110601, + -0.0053973799 -0.121677 -0.0389258, + -0.0053973799 -0.123268 -0.040473301, + -0.0081428103 -0.123112 -0.0401586, + -0.0081428103 -0.124765 -0.041660301, + -0.0109179 -0.124551 -0.041210301, + -0.0109179 -0.126266 -0.042664099, + -0.0137106 -0.126 -0.042073999, + -0.0137106 -0.12777799 -0.043477301, + -0.0165099 -0.127461 -0.042744, + -0.0165099 -0.12930299 -0.0440947, + -0.019305199 -0.128942 -0.043215901, + -0.019305199 -0.13084701 -0.0445114, + -0.0220857 -0.130447 -0.043484699, + -0.0220857 -0.132415 -0.044722799, + -0.0248404 -0.131982 -0.043546502, + -0.0248404 -0.134014 -0.044724699, + -0.027557701 -0.133554 -0.043400101, + -0.027557701 -0.13564999 -0.044516198, + -0.0302257 -0.135169 -0.043045301, + -0.0302257 -0.13733 -0.044097301, + -0.0328326 -0.13683499 -0.042482201, + -0.0328326 -0.13905799 -0.043468799, + -0.035366699 -0.138557 -0.0417124, + -0.035366699 -0.140843 -0.042633001, + -0.0378174 -0.140342 -0.040741298, + -0.0378174 -0.142691 -0.0415948, + -0.040174201 -0.142196 -0.039574798, + -0.040174201 -0.14460599 -0.040360399, + -0.0424264 -0.144125 -0.0382188, + -0.0424264 -0.146594 -0.038935602, + -0.044564299 -0.146135 -0.036679901, + -0.044564299 -0.148663 -0.037326898, + -0.0465803 -0.148229 -0.034967199, + -0.0465803 -0.15081599 -0.035543598, + -0.048467699 -0.150414 -0.0330901, + -0.048467699 -0.15305699 -0.033595402, + -0.050219599 -0.152693 -0.0310589, + -0.050219599 -0.15539201 -0.031493898, + -0.051830001 -0.15507001 -0.028884999, + 0.0053973799 -0.120143 -0.037335102, + 0.0081428103 -0.121514 -0.038611401, + 0.0109179 -0.122887 -0.039710298, + 0.0137106 -0.124269 -0.0406239, + 0.0165099 -0.125663 -0.041346598, + 0.019305199 -0.127076 -0.041873801, + 0.0220857 -0.12851299 -0.0422002, + 0.0248404 -0.12998 -0.042321801, + 0.027557701 -0.131484 -0.0422372, + 0.0302257 -0.133031 -0.041946199, + 0.0328326 -0.134628 -0.041448198, + 0.035366699 -0.13628399 -0.0407441, + 0.0378174 -0.13800199 -0.039838798, + 0.040174201 -0.139791 -0.038738701, + 0.0424264 -0.14165699 -0.0374499, + 0.044564299 -0.143604 -0.035979401, + 0.0465803 -0.145639 -0.034336399, + 0.048467699 -0.147765 -0.032531202, + 0.050219599 -0.149988 -0.030573901, + 0.048467699 -0.15040401 -0.03311, + 0.0465803 -0.14821699 -0.034984399, + 0.044564299 -0.146121 -0.036695998, + 0.0424264 -0.14411099 -0.038234599, + 0.040174201 -0.14218201 -0.039590999, + 0.0378174 -0.140328 -0.0407582, + 0.035366699 -0.13854399 -0.0417298, + 0.0328326 -0.136822 -0.042499699, + 0.0302257 -0.135158 -0.0430624, + 0.027557701 -0.133543 -0.043416101, + 0.0248404 -0.131972 -0.043560799, + 0.0220857 -0.130439 -0.043497, + 0.019305199 -0.12893599 -0.043225899, + 0.0165099 -0.12745599 -0.042751599, + 0.0137106 -0.12599599 -0.042079199, + 0.0109179 -0.124549 -0.041213501, + 0.0081428103 -0.12311 -0.04016, + 0.0053973799 -0.121676 -0.038926002, + 0.00268824 -0.120243 -0.0375202, + 0.00268824 -0.121773 -0.039110702, + 0.0053973799 -0.123267 -0.040474199, + 0.0081428103 -0.124763 -0.0416627, + 0.0109179 -0.12626299 -0.042668302, + 0.0137106 -0.127773 -0.0434836, + 0.0165099 -0.129297 -0.044103201, + 0.019305199 -0.13083901 -0.044522099, + 0.0220857 -0.13240699 -0.044735599, + 0.0248404 -0.134004 -0.044739101, + 0.027557701 -0.135639 -0.0445318, + 0.0302257 -0.137318 -0.044113401, + 0.0328326 -0.139046 -0.0434849, + 0.035366699 -0.14083 -0.042648699, + 0.0378174 -0.14267799 -0.041610099, + 0.040174201 -0.144593 -0.0403753, + 0.0424264 -0.14658201 -0.038950801, + 0.044564299 -0.148651 -0.037343401, + 0.0465803 -0.15080599 -0.035562702, + 0.048467699 -0.15305001 -0.033618901, + 0.050219599 -0.155388 -0.031522799, + -0.054340299 -0.171519 -0.0252974, + -0.054603901 -0.171518 -0.0246985, + -0.041876599 -0.19146401 0.043121599, + -0.0402066 -0.171463 0.044672199, + -0.059821099 -0.191495 0.0047830199, + -0.059931301 -0.171496 0.00282456, + -0.059980098 -0.19149999 -0.00139239, + -0.0460728 -0.191468 0.038588099, + -0.04456 -0.17146599 0.0403069, + -0.046303399 -0.171468 0.038293999, + -0.0465739 -0.171468 0.037948899, + -0.048119001 -0.17147 0.0359773, + -0.048467699 -0.163321 0.035648402, + -0.050219599 -0.163427 0.0331145, + -0.0497793 -0.171472 0.0336302, + -0.0518176 -0.17147399 0.0303552, + -0.052960701 -0.191476 0.0283511, + -0.051398799 -0.17147399 0.0310908, + -0.052855 -0.17147601 0.028532799, + -0.051830001 -0.163536 0.030508, + -0.0532961 -0.155799 0.0282504, + -0.0546159 -0.14827999 0.026214199, + -0.055787299 -0.14099699 0.024418401, + -0.056809202 -0.133967 0.022880601, + -0.0576833 -0.127211 0.021609001, + -0.058412101 -0.120746 0.0206089, + -0.058998398 -0.114591 0.019885, + -0.059445001 -0.108763 0.019440999, + -0.059757002 -0.103276 0.019277301, + -0.0599402 -0.098143801 0.0193868, + -0.059999999 -0.093389802 0.019739, + -0.0599402 -0.089045703 0.020297, + -0.059757002 -0.085072003 0.020833701, + -0.059445001 -0.081394501 0.021155801, + -0.058998398 -0.078075297 0.021297, + -0.058412101 -0.075147502 0.02131, + -0.0576833 -0.074867502 0.0199263, + -0.056809202 -0.074711099 0.018539, + -0.055787299 -0.0746684 0.0171689, + -0.0546159 -0.074728303 0.0158347, + -0.0532961 -0.074877903 0.0145542, + -0.051830001 -0.075102203 0.0133443, + -0.050219599 -0.075382501 0.0122205, + -0.048467699 -0.075692303 0.0111988, + -0.0465803 -0.076044902 0.0102841, + -0.044564299 -0.076405302 0.0094540399, + -0.0424264 -0.076728202 0.0087221004, + -0.040174201 -0.077002898 0.0081078196, + -0.0378174 -0.077214599 0.0076252101, + -0.035366699 -0.077346899 0.0072856001, + -0.0328326 -0.077380903 0.00709642, + -0.0302257 -0.077296197 0.0070616002, + -0.027557701 -0.077075496 0.00717862, + -0.0248404 -0.076701798 0.0074404399, + -0.0220857 -0.076159596 0.0078359898, + -0.019305199 -0.075435802 0.0083504701, + -0.0165099 -0.074523903 0.0089641502, + -0.0137106 -0.073420703 0.0096534695, + -0.052956201 -0.17147601 0.0283329, + -0.053282801 -0.17147601 0.027687499, + -0.0484588 -0.17147 0.035496902, + -0.059027899 -0.19148999 0.0109093, + -0.059430599 -0.171492 0.0082775597, + -0.057608999 -0.191485 0.0169216, + -0.0583965 -0.171487 0.0138436, + -0.057377499 -0.17148399 0.017681399, + -0.056809202 -0.163993 0.019588299, + -0.0576833 -0.156712 0.0172012, + -0.058412101 -0.149652 0.0150789, + -0.058998398 -0.142828 0.0132405, + -0.059445001 -0.136252 0.0117038, + -0.059757002 -0.12993801 0.0104776, + -0.0599402 -0.123905 0.0095625697, + -0.059999999 -0.118172 0.0089370003, + -0.0599402 -0.112772 0.0085723, + -0.059757002 -0.107732 0.00843459, + -0.059445001 -0.103083 0.0084932903, + -0.058998398 -0.098849401 0.0087387199, + -0.058412101 -0.095051996 0.0091656903, + -0.0576833 -0.091649897 0.0096160797, + -0.056809202 -0.088574201 0.0099601299, + -0.055787299 -0.085874297 0.0102355, + -0.0546159 -0.083566599 0.0104947, + -0.0532961 -0.083544299 0.0093187299, + -0.051830001 -0.083600901 0.0081929704, + -0.050219599 -0.083720401 0.0071371598, + -0.048467699 -0.083887003 0.0061679902, + -0.0465803 -0.084084198 0.0052992199, + -0.044564299 -0.084293902 0.00454289, + -0.0424264 -0.0844955 0.00390979, + -0.040174201 -0.084661901 0.00340966, + -0.0378174 -0.084795497 0.0030427601, + -0.035366699 -0.084870301 0.0027932599, + -0.0328326 -0.0848509 0.00266858, + -0.0302257 -0.084725201 0.0026781, + -0.027557701 -0.084480703 0.0028251801, + -0.0248404 -0.084104501 0.0031095401, + -0.0220857 -0.083582401 0.00352753, + -0.019305199 -0.082901403 0.0040723202, + -0.0165099 -0.082052201 0.0047319401, + -0.0137106 -0.081027597 0.0054911999, + -0.0109179 -0.079822898 0.0063326098, + -0.0081428103 -0.082203798 0.0049610799, + -0.0081428103 -0.085867196 0.00249073, + -0.0081428103 -0.089410603 -0.000168713, + -0.0109179 -0.087158002 0.00147016, + -0.0053973799 -0.086218096 0.0023036799, + 0.0081428103 -0.0858633 0.0024931999, + 0.0109179 -0.087153196 0.00147432, + 0.0081428103 -0.089407399 -0.000165096, + 0.0053973799 -0.086215504 0.00230532, + 0.0053973799 -0.082556203 0.0048018, + 0.00268824 -0.082765698 0.0047075199, + 0.00268824 -0.078997999 0.0070275799, + 0 -0.079066798 0.0070023201, + 0 -0.075202599 0.00912809, + -0.00268824 -0.078999303 0.0070276102, + -0.00268824 -0.082767099 0.0047071101, + -0.0053973799 -0.0825589 0.00480098, + -0.0109179 -0.083543397 0.0039987899, + 0.0109179 -0.083537802 0.00400125, + 0.051830001 -0.0895973 0.00372744, + 0.051830001 -0.087641403 0.0052656499, + 0.0532961 -0.089695901 0.0048233401, + 0.050219599 -0.089613497 0.00273233, + 0.050219599 -0.0876882 0.0042602299, + 0.048467699 -0.0896786 0.00182686, + 0.048467699 -0.087786801 0.00333105, + 0.0465803 -0.089781702 0.00100899, + 0.0465803 -0.087919302 0.00249532, + 0.044564299 -0.089904398 0.00029503001, + 0.044564299 -0.088068098 0.00176641, + 0.0424264 -0.090027802 -0.00030240201, + 0.0424264 -0.088214204 0.00115572, + 0.040174201 -0.090132698 -0.00077338901, + 0.040174201 -0.088338003 0.00067251298, + 0.0378174 -0.090201303 -0.00111172, + 0.0378174 -0.088422798 0.00032271, + 0.035366699 -0.090216599 -0.0013128601, + 0.035366699 -0.088457197 0.000111378, + 0.0328326 -0.090166301 -0.0013727, + 0.0328326 -0.0884308 4.09565e-005, + 0.0302257 -0.090038903 -0.00129016, + 0.0302257 -0.088300802 0.000100923, + 0.027557701 -0.089797199 -0.0010771001, + 0.027557701 -0.088053197 0.00028953599, + 0.0248404 -0.089429103 -0.00073643902, + 0.0248404 -0.0876799 0.000608109, + 0.0220857 -0.088925503 -0.00026830999, + 0.0220857 -0.087168701 0.00105562, + 0.019305199 -0.088275 0.000324213, + 0.019305199 -0.086507201 0.00162872, + 0.0165099 -0.087468803 0.00103404, + 0.0165099 -0.085686497 0.00231884, + 0.0137106 -0.086499304 0.00185083, + 0.0137106 -0.084698699 0.00311446, + 0.0109179 -0.0853597 0.0027619, + 0.0137106 -0.088270701 0.00053805899, + 0.0165099 -0.089221403 -0.00030153399, + 0.019305199 -0.0900122 -0.00103292, + 0.0220857 -0.090650298 -0.0016471701, + 0.0248404 -0.091144301 -0.00213758, + 0.027557701 -0.091502801 -0.00250201, + 0.0302257 -0.091737501 -0.00273693, + 0.0328326 -0.091881603 -0.00283105, + 0.035366699 -0.091945603 -0.0027821299, + 0.0378174 -0.091942102 -0.00259261, + 0.040174201 -0.091887899 -0.0022662, + 0.0424264 -0.091801502 -0.0018077299, + 0.044564299 -0.091700204 -0.0012240401, + 0.0465803 -0.091603398 -0.00052636699, + 0.048467699 -0.091530301 0.00026969501, + 0.050219599 -0.091493003 0.00116749, + 0.051830001 -0.091559 0.00218055, + 0.0532961 -0.093880601 0.00169213, + 0.0546159 -0.092132799 0.0044176499, + 0.0546159 -0.096580699 0.00121088, + 0.055787299 -0.094950102 0.0039916802, + 0.055787299 -0.099614799 0.000710472, + 0.056809202 -0.098099597 0.0035184899, + 0.056809202 -0.100543 0.0018744899, + 0.0576833 -0.101636 0.003094, + 0.058412101 -0.164231 0.0139606, + 0.0576833 -0.164114 0.016760301, + 0.058215201 -0.171487 0.0146621, + 0.058412101 -0.15694501 0.0143608, + 0.058998398 -0.157176 0.0115671, + 0.058998398 -0.149992 0.0122508, + 0.059445001 -0.150334 0.0094740102, + 0.059445001 -0.14327 0.0104386, + 0.059757002 -0.14372 0.0076904702, + 0.059757002 -0.136795 0.0089334296, + 0.0599402 -0.13734899 0.0062206299, + 0.0599402 -0.130582 0.0077395402, + 0.059999999 -0.13124201 0.0050466298, + 0.059999999 -0.124652 0.0068388898, + 0.0599402 -0.125422 0.00414473, + 0.0599402 -0.119032 0.0062074899, + 0.059757002 -0.119921 0.0034908699, + 0.059757002 -0.113752 0.0058192499, + 0.059445001 -0.114768 0.00306433, + 0.059445001 -0.108843 0.0056461901, + 0.058998398 -0.109989 0.00285893, + 0.058998398 -0.104331 0.0056795101, + 0.058412101 -0.105605 0.00287086, + 0.058412101 -0.100237 0.0059143999, + 0.0576833 -0.096576497 0.0063414802, + 0.056809202 -0.093304202 0.00679849, + 0.055787299 -0.090360902 0.0071807201, + 0.0546159 -0.087798201 0.0075149098, + 0.0532961 -0.085623302 0.0078583499, + 0.051830001 -0.085640803 0.0067634201, + 0.050219599 -0.085723899 0.0057321801, + 0.048467699 -0.085855097 0.00478331, + 0.0465803 -0.086017497 0.0039311801, + 0.044564299 -0.086193003 0.0031880001, + 0.0424264 -0.086362198 0.0025645201, + 0.040174201 -0.086506903 0.0020697301, + 0.0378174 -0.086616002 0.00171019, + 0.035366699 -0.086681299 0.00148902, + 0.0328326 -0.086656898 0.00139485, + 0.0302257 -0.086524799 0.00142919, + 0.027557701 -0.086276799 0.0015954101, + 0.0248404 -0.0859005 0.00189398, + 0.0220857 -0.085383199 0.00232381, + 0.019305199 -0.084711798 0.00288, + 0.0165099 -0.083877198 0.0035527099, + 0.0137106 -0.082871802 0.0043286602, + 0.0109179 -0.081689604 0.0051919501, + 0.057597399 -0.17148501 0.016902501, + 0.057669099 -0.17148501 0.0166426, + 0.058857501 -0.171489 0.0117895, + -0.0109179 -0.090649001 -0.00124854, + -0.050219599 -0.099276997 -0.00522858, + -0.051830001 -0.099768601 -0.0042292001, + -0.050219599 -0.097275101 -0.00360721, + -0.048467699 -0.098904997 -0.0061488301, + -0.048467699 -0.097007103 -0.0045273402, + -0.0465803 -0.098649897 -0.0069717499, + -0.0465803 -0.096860401 -0.0053462498, + -0.044564299 -0.0985061 -0.0076804501, + -0.044564299 -0.0951657 -0.0044054799, + -0.0424264 -0.096869402 -0.0065940302, + -0.0424264 -0.095222302 -0.0049572699, + -0.040174201 -0.096901402 -0.0070098699, + -0.040174201 -0.095273197 -0.0053910101, + -0.0378174 -0.0969145 -0.0073008798, + -0.0378174 -0.095300198 -0.0056950902, + -0.035366699 -0.096890002 -0.0074567101, + -0.035366699 -0.095285803 -0.00586229, + -0.0328326 -0.096810102 -0.0074709002, + -0.0328326 -0.095212497 -0.0058875298, + -0.0302257 -0.096657403 -0.0073399702, + -0.0302257 -0.095062301 -0.0057680602, + -0.027557701 -0.096416697 -0.0070648398, + -0.027557701 -0.094818898 -0.0055053299, + -0.0248404 -0.0960721 -0.00664835, + -0.0248404 -0.094463401 -0.0051021399, + -0.0220857 -0.0956055 -0.0060940301, + -0.0220857 -0.0939897 -0.0045649698, + -0.019305199 -0.095010102 -0.0054092598, + -0.019305199 -0.093383901 -0.0039051501, + -0.0165099 -0.0942761 -0.0046069301, + -0.0165099 -0.0926295 -0.0031276401, + -0.0137106 -0.093389101 -0.00369346, + -0.0137106 -0.09172 -0.00223898, + -0.0109179 -0.092342898 -0.0026765999, + -0.0532961 -0.102597 -0.0048184199, + -0.0546159 -0.103439 -0.00370614, + -0.055787299 -0.104433 -0.0025135099, + -0.056809202 -0.105585 -0.00124949, + -0.0576833 -0.106898 7.7741897e-005, + -0.058412101 -0.111162 8.4167303e-005, + -0.058998398 -0.115817 0.000313734, + -0.059445001 -0.120844 0.00077144703, + -0.059757002 -0.126221 0.0014590099, + -0.0599402 -0.131923 0.0023779401, + -0.059999999 -0.137918 0.0035503099, + -0.0599402 -0.144177 0.0050033298, + -0.059757002 -0.15067799 0.0067612301, + -0.059445001 -0.15740301 0.0088323401, + -0.0532961 -0.0938823 0.00168326, + -0.051830001 -0.095598303 -0.00099263305, + -0.0532961 -0.098189399 -0.0015360001, + -0.0546159 -0.0965809 0.0012069501, + -0.0546159 -0.101117 -0.00207427, + -0.055787299 -0.099615797 0.00070767303, + -0.055787299 -0.102 -0.00092759001, + -0.056809202 -0.100548 0.00187695, + -0.056809202 -0.103043 0.00028799201, + -0.0576833 -0.101646 0.0031044199, + -0.0576833 -0.10425 0.00156431, + -0.058412101 -0.105622 0.0028933501, + -0.058412101 -0.100246 0.0059249499, + -0.058998398 -0.104348 0.0057022301, + -0.058998398 -0.11001 0.0028894199, + -0.059445001 -0.108865 0.0056769, + -0.059445001 -0.11479 0.0030985801, + -0.059757002 -0.113775 0.00585368, + -0.059757002 -0.119944 0.0035245901, + -0.0599402 -0.119054 0.0062413001, + -0.0599402 -0.12544499 0.0041741799, + -0.059999999 -0.124675 0.0068683699, + -0.059999999 -0.131263 0.0050708498, + -0.0599402 -0.130603 0.0077637401, + -0.0599402 -0.137367 0.0062421099, + -0.059757002 -0.136813 0.0089548398, + -0.059757002 -0.14373299 0.0077150101, + -0.059445001 -0.14328299 0.010463, + -0.059445001 -0.15033901 0.0095082195, + -0.058998398 -0.149997 0.0122847, + -0.058998398 -0.15717401 0.0116081, + -0.058412101 -0.15694401 0.0144013, + -0.058412101 -0.16422699 0.0139938, + -0.058168899 -0.171487 0.0148463, + -0.0576833 -0.16411 0.0167931, + -0.0588204 -0.171489 0.0119758, + -0.050219599 -0.095308401 -0.0019996599, + -0.048467699 -0.095149003 -0.0029189601, + -0.0465803 -0.093382902 -0.0021154101, + -0.044564299 -0.0934534 -0.0027948399, + -0.0424264 -0.093532898 -0.0033656999, + -0.040174201 -0.093602099 -0.0038133599, + -0.0378174 -0.093643703 -0.0041292198, + -0.035366699 -0.093640603 -0.0043074102, + -0.0328326 -0.093574703 -0.00434358, + -0.0302257 -0.093426697 -0.0042355401, + -0.027557701 -0.093176603 -0.0039846301, + -0.0248404 -0.092819899 -0.00359707, + -0.0220857 -0.092340998 -0.0030846701, + -0.019305199 -0.091718599 -0.00244899, + -0.0165099 -0.090945601 -0.00169471, + -0.0137106 -0.090015098 -0.00083000201, + -0.0109179 -0.088920102 0.000134196, + -0.0137106 -0.088276103 0.00053197303, + -0.0165099 -0.0892267 -0.00030945, + -0.019305199 -0.090016797 -0.00104186, + -0.0220857 -0.090653598 -0.00165551, + -0.0248404 -0.091145404 -0.0021440401, + -0.027557701 -0.091502003 -0.00250659, + -0.0302257 -0.091747001 -0.0027431799, + -0.0328326 -0.091897301 -0.0028407001, + -0.035366699 -0.091956198 -0.0027938799, + -0.0378174 -0.091947101 -0.0026050401, + -0.040174201 -0.091889501 -0.0022779901, + -0.0424264 -0.091801398 -0.00181789, + -0.044564299 -0.091699503 -0.00123202, + -0.0465803 -0.0916024 -0.00053208799, + -0.048467699 -0.091529101 0.00026598401, + -0.050219599 -0.093379296 -0.00040899299, + -0.051830001 -0.093561001 0.000600592, + -0.051830001 -0.091558702 0.0021730401, + -0.050219599 -0.089612201 0.0027284999, + -0.048467699 -0.089677602 0.00182091, + -0.0465803 -0.089780897 0.00100065, + -0.044564299 -0.089904301 0.00028435001, + -0.0424264 -0.0900295 -0.00031486101, + -0.040174201 -0.0901381 -0.00078658399, + -0.0378174 -0.090212502 -0.00112428, + -0.035366699 -0.090233497 -0.00132325, + -0.0328326 -0.090176702 -0.00137949, + -0.0302257 -0.090038002 -0.00129519, + -0.027557701 -0.089798398 -0.0010842599, + -0.0248404 -0.089432701 -0.00074581598, + -0.0220857 -0.088930897 -0.00027854499, + -0.019305199 -0.088281199 0.00031494701, + -0.0165099 -0.0874753 0.00102672, + -0.0137106 -0.086505502 0.00184561, + -0.0109179 -0.085364901 0.00275858, + -0.0137106 -0.084705502 0.00311028, + -0.0165099 -0.085693903 0.0023125701, + -0.019305199 -0.086514801 0.0016201501, + -0.0220857 -0.087175801 0.00104503, + -0.0248404 -0.087686002 0.00059660297, + -0.027557701 -0.088057302 0.00027912899, + -0.0302257 -0.088302098 9.30639e-005, + -0.0328326 -0.088429801 3.5495701e-005, + -0.035366699 -0.088468499 0.000104057, + -0.0378174 -0.088440903 0.00031159501, + -0.040174201 -0.088349998 0.000659162, + -0.0424264 -0.088219799 0.0011417801, + -0.044564299 -0.088069797 0.00175333, + -0.0465803 -0.087919198 0.00248415, + -0.048467699 -0.087785996 0.0033223699, + -0.050219599 -0.087687202 0.0042540599, + -0.051830001 -0.087640204 0.0052617001, + -0.0532961 -0.089695603 0.0048156199, + -0.0546159 -0.092134498 0.00440857, + -0.055787299 -0.0949504 0.0039876699, + -0.056809202 -0.098100603 0.00351564, + -0.0576833 -0.099087402 0.0046964199, + -0.0576833 -0.096577398 0.00633858, + -0.056809202 -0.0933045 0.0067944, + -0.055787299 -0.090362601 0.0071714302, + -0.0546159 -0.087797999 0.0075070001, + -0.0532961 -0.085621998 0.0078542801, + -0.051830001 -0.0856397 0.0067570498, + -0.050219599 -0.085723102 0.00572319, + -0.048467699 -0.085855 0.0047716899, + -0.0465803 -0.0860193 0.0039174999, + -0.044564299 -0.086198904 0.0031733599, + -0.0424264 -0.086374797 0.0025504199, + -0.040174201 -0.086526103 0.00205792, + -0.0378174 -0.086627901 0.00170237, + -0.035366699 -0.086680301 0.00148314, + -0.0328326 -0.086658299 0.00138633, + -0.0302257 -0.0865293 0.0014177799, + -0.027557701 -0.086283401 0.00158265, + -0.0248404 -0.085908502 0.00188207, + -0.0220857 -0.085391901 0.0023140199, + -0.019305199 -0.084720403 0.00287265, + -0.0165099 -0.0838852 0.0035476901, + -0.0137106 -0.082878701 0.0043255701, + -0.0109179 -0.081695303 0.0051902798, + -0.0575951 -0.17148501 0.016901899, + -0.057667602 -0.17148501 0.0166422, + -0.058982901 -0.17149 0.0110517, + -0.059744701 -0.17149401 0.005533, + -0.059999801 -0.171498 0.00027890201, + -0.059996702 -0.171498 0.00013663201, + -0.059749398 -0.17150301 -0.0052602701, + 0.053653602 0.0268292 0.0124786, + 0.0268177 -0.17145599 0.0537901, + 0.0053910101 -0.171451 0.059882302, + 0.011126 -0.0487388 0.0075388099, + 0.016514 -0.047186598 0.0075375801, + 0.0216942 -0.045040801 0.0075358702, + 0.0266016 -0.0423286 0.00753371, + 0.0311745 -0.039083999 0.00753112, + 0.0353553 -0.0353477 0.00752815, + 0.039091598 -0.0311669 0.00752482, + 0.042336199 -0.026594 0.00752118, + 0.045048401 -0.021686601 0.0075172698, + 0.047194201 -0.016506299 0.0075131501, + 0.0487464 -0.0111184 0.00750886, + 0.049685601 -0.0055906698 0.0075044502, + 0.050000001 7.5646799e-006 0.0074999998, + 0.049685601 0.0056058001 0.0074955402, + 0.0487464 0.0111336 0.0074911402, + 0.047194201 0.0165215 0.00748685, + 0.045048401 0.0217018 0.0074827201, + 0.042336199 0.026609199 0.0074788099, + 0.039091598 0.031182099 0.0074751698, + 0.0353553 0.035362899 0.0074718399, + 0.0311745 0.039099101 0.0074688699, + 0.0266016 0.042343799 0.0074662799, + 0.0216942 0.045056 0.0074641299, + 0.016514 0.047201701 0.00746242, + 0.011126 0.048753899 0.00746118, + 0.00559822 0.0496931 0.0074604298, + 0 0.0500075 0.0074601802, + -0.00559822 0.0496931 0.0074604298, + -0.011126 0.048753899 0.00746118, + -0.016514 0.047201701 0.00746242, + -0.0216942 0.045056 0.0074641299, + -0.0266016 0.042343799 0.0074662799, + -0.0311745 0.039099101 0.0074688699, + -0.0353553 0.035362899 0.0074718399, + -0.039091598 0.031182099 0.0074751698, + -0.042336199 0.026609199 0.0074788099, + -0.045048401 0.0217018 0.0074827201, + -0.047194201 0.0165215 0.00748685, + -0.0487464 0.0111336 0.0074911402, + -0.049685601 0.0056058001 0.0074955402, + -0.050000001 7.5646799e-006 0.0074999998, + -0.049685601 -0.0055906698 0.0075044502, + -0.0487464 -0.0111184 0.00750886, + -0.047194201 -0.016506299 0.0075131501, + -0.045048401 -0.021686601 0.0075172698, + -0.042336199 -0.026594 0.00752118, + -0.039091598 -0.0311669 0.00752482, + -0.0353553 -0.0353477 0.00752815, + -0.0311745 -0.039083999 0.00753112, + -0.0266016 -0.0423286 0.00753371, + -0.0216942 -0.045040801 0.0075358702, + -0.016514 -0.047186598 0.0075375801, + -0.011126 -0.0487388 0.0075388099, + -0.00559822 -0.049678002 0.0075395601, + 0 -0.049992401 0.0075398101, + 0.00559822 -0.049678002 0.0075395601 ] + + } + normal + Normal { + vector [ -0.98486513 -0.0057662507 0.17322701, + -0.98728687 -0.0014080199 0.15894198, + -0.84375131 0.00033863712 0.53673416, + -0.9601441 -0.0034589805 -0.27948403, + -0.044446189 0.7390008 -0.6722368, + -0.050594583 0.71511078 -0.69717777, + -0.069329202 0.71430498 -0.696392, + -0.077281103 0.68883401 -0.720788, + -0.099514112 0.68747008 -0.71936208, + -0.10923901 0.66033208 -0.74298608, + -0.13510205 0.65821725 -0.74060625, + -0.14639993 0.62965173 -0.76295865, + -0.175826 0.62659401 -0.75925303, + -0.18838297 0.59700596 -0.77980489, + -0.221793 0.59275001 -0.77424502, + -0.23538603 0.56214404 -0.79283512, + -0.27175301 0.556629 -0.78505701, + -0.28600401 0.52530801 -0.80140698, + -0.32517102 0.51841605 -0.79089111, + -0.33983296 0.48634395 -0.8049739, + -0.38153493 0.47800195 -0.7911669, + -0.39609194 0.44574395 -0.80275989, + -0.43959895 0.43602693 -0.7852599, + -0.45356289 0.4041709 -0.79430884, + -0.49790195 0.39329094 -0.77292687, + -0.51095915 0.36207408 -0.77963018, + -0.55515224 0.35034117 -0.75436538, + -0.5669027 0.32043085 -0.75891066, + -0.61049592 0.30807498 -0.72964692, + -0.62069124 0.28002807 -0.73234326, + -0.66319698 0.26730901 -0.69908202, + -0.67174125 0.24148008 -0.70032221, + -0.71194679 0.22891192 -0.66387576, + -0.71897024 0.20518407 -0.66406423, + -0.756437 0.193088 -0.62491602, + -0.7620157 0.17165194 -0.62439376, + -0.79673785 0.16019195 -0.58270687, + -0.80108321 0.14082003 -0.58175212, + -0.8329379 0.13018899 -0.53783393, + -0.83616179 0.11313997 -0.5366869, + -0.8646419 0.10363199 -0.49158394, + -0.86696601 0.088679701 -0.49041399, + -0.89152074 0.080603577 -0.44575089, + -0.8954733 0.072463021 -0.43917716, + -0.91544658 0.065515473 -0.39707083, + -0.91740012 0.045156803 -0.39539605, + -0.93684989 0.039683595 -0.34747297, + -0.95311815 0.033736903 -0.30071202, + -0.93640321 0.039124813 -0.3487381, + -0.93489587 0.056742191 -0.35035697, + -0.91461378 0.064640686 -0.3991279, + -0.91173977 0.086672977 -0.40151992, + -0.91065568 0.085650668 -0.40419084, + -0.93204033 0.075117432 -0.35448313, + -0.93425721 0.056015115 -0.35217309, + -0.951666 0.048245002 -0.30332199, + -0.95278174 0.033270493 -0.30182794, + -0.96681666 0.027990991 -0.25393292, + -0.98568809 0.0019067603 -0.16856901, + -0.98570651 0.0019042491 -0.16846092, + -0.97859126 0.0067361714 -0.20570305, + -0.97846878 0.013418797 -0.20595795, + -0.96729851 0.016490592 -0.25310388, + -0.9762311 0.0029699905 -0.21671203, + -0.96763152 0.0082392162 -0.25223288, + -0.96744198 0.0167369 -0.25253901, + -0.95380026 0.019868005 -0.29978406, + -0.95427877 0.0096322279 -0.29876295, + -0.95400375 0.020173695 -0.29911494, + -0.93777287 0.023366999 -0.34646198, + -0.9338994 0.0064338134 -0.35747817, + -0.95026821 0.0052135312 -0.31138906, + -0.93842614 0.010962901 -0.34530604, + -0.93804389 0.023731995 -0.34570298, + -0.9191736 0.026973886 -0.39292783, + -0.91797626 0.04581831 -0.39398009, + -0.89595073 0.051307488 -0.44117987, + -0.89415377 0.068728387 -0.44245389, + -0.86942458 0.075835966 -0.48821077, + -0.86750114 0.090118505 -0.48920405, + -0.8396101 0.098407611 -0.53420109, + -0.83685815 0.11496303 -0.5352121, + -0.80568618 0.12439703 -0.57913309, + -0.80196089 0.14307098 -0.57999092, + -0.76791114 0.15341301 -0.62191409, + -0.76303685 0.17424396 -0.62242585, + -0.72634542 0.18529111 -0.66188341, + -0.72019017 0.20825605 -0.66178221, + -0.68075705 0.21988402 -0.69872808, + -0.67317206 0.24506202 -0.69769907, + -0.63130409 0.25701004 -0.73171103, + -0.62231004 0.28403902 -0.72941905, + -0.57909131 0.29582915 -0.75969636, + -0.5686571 0.32471609 -0.75577021, + -0.52461076 0.33607185 -0.78220165, + -0.51283693 0.36656198 -0.77629286, + -0.46852487 0.37722191 -0.79886681, + -0.455639 0.40896201 -0.79066002, + -0.41168022 0.41868421 -0.80945837, + -0.39829794 0.45058995 -0.79895389, + -0.35578704 0.45909405 -0.81403214, + -0.34214011 0.49111718 -0.80108929, + -0.301893 0.498274 -0.81276298, + -0.2884171 0.52995616 -0.7974723, + -0.2506569 0.53580683 -0.80627668, + -0.23786491 0.5665428 -0.78895468, + -0.20279998 0.57116294 -0.79538989, + -0.19088708 0.60106325 -0.7760703, + -0.15961394 0.60447276 -0.78047168, + -0.14889009 0.63331634 -0.75943547, + -0.120738 0.63576901 -0.76237798, + -0.11145101 0.66328204 -0.74002403, + -0.087082408 0.66490406 -0.74183506, + -0.079314001 0.69128197 -0.71821898, + -0.058550425 0.69227737 -0.71925235, + -0.052503712 0.71718121 -0.69490618, + -0.035300408 0.7177242 -0.69543219, + -0.031334601 0.73936898 -0.672571, + -0.014950496 0.75139982 -0.6596778, + -0.014729604 0.7514022 -0.65968019, + -0.0097830202 0.791628 -0.61092502, + -0.002061299 0.79166365 -0.61095369, + -0.00043170512 0.82772416 -0.56113511, + 0.00053589407 0.8277241 -0.56113505, + 0.0021736394 0.79168868 -0.61092079, + 0.0098244101 0.79165298 -0.610892, + 0.013568505 0.76155329 -0.64796025, + 0.84927589 0.063760094 -0.52408493, + 0.218952 0.0058585699 -0.97571802, + 0.96729976 0.016186496 -0.25311893, + 0.96679562 0.028253391 -0.25398391, + 0.9527421 0.033585504 -0.30191803, + 0.95161235 0.048673119 -0.30342212, + 0.93417579 0.056515183 -0.3523089, + 0.93199414 0.075242706 -0.35457802, + 0.90675473 0.10884498 -0.40736791, + 0.91060024 0.085790925 -0.40428609, + 0.911708 0.086831801 -0.40155801, + 0.91453272 0.065211579 -0.39922085, + 0.9348231 0.057248209 -0.35046902, + 0.93635076 0.039487988 -0.34883791, + 0.95307863 0.03405039 -0.30080187, + 0.95379514 0.019504203 -0.29982403, + 0.96744126 0.016429704 -0.25256205, + 0.96764112 0.0072000711 -0.25222802, + 0.97569788 0.0015037598 -0.21911497, + 0.97554713 0.0015241102 -0.21978503, + 0.97554791 0.00057334395 -0.21978597, + 0.97569889 0.00057387695 -0.21911497, + 0.97554612 0.00057585904 -0.21979403, + 0.97554535 0.0015161206 -0.21979308, + 0.97859746 0.0059899529 -0.2056971, + 0.97846991 0.013171298 -0.20596898, + 0.9872545 0.0047520725 -0.15907907, + 0.98718137 0.010015504 -0.15928806, + 0.97837549 0.012979593 -0.2064289, + 0.97804552 0.022649689 -0.2071569, + 0.96655446 0.027874513 -0.25494212, + 0.96575898 0.040388599 -0.25627801, + 0.95113033 0.048071019 -0.30502513, + 0.94951385 0.063998491 -0.30712798, + 0.93114674 0.074385785 -0.3569769, + 0.92817986 0.094371088 -0.35996696, + 0.9053607 0.10768797 -0.41076186, + 0.90024269 0.13261996 -0.41469884, + 0.86885202 0.18266501 -0.460141, + 0.8278138 0.20699196 -0.52141988, + 0.82033998 0.22834501 -0.52430999, + 0.78396171 0.24788392 -0.5691728, + 0.77406412 0.27227902 -0.57156706, + 0.73374999 0.29219601 -0.61337799, + 0.72112477 0.31948087 -0.61474478, + 0.67791176 0.33900389 -0.65231276, + 0.66243201 0.36880001 -0.65205097, + 0.61711806 0.38738406 -0.68490803, + 0.59876192 0.41930893 -0.68239594, + 0.55213183 0.43649685 -0.71036679, + 0.53099102 0.470184 -0.704965, + 0.48456699 0.485374 -0.727741, + 0.46127388 0.51988888 -0.71898681, + 0.4164362 0.53272521 -0.73673934, + 0.39143506 0.56762904 -0.72427607, + 0.34943098 0.57796496 -0.73746496, + 0.3237029 0.61227286 -0.72134483, + 0.28547505 0.62018514 -0.73066717, + 0.26027298 0.65279591 -0.71141791, + 0.2259061 0.65861928 -0.71776533, + 0.20352195 0.68723685 -0.69734085, + 0.17385499 0.69123894 -0.70140094, + 0.15352498 0.71743196 -0.67950094, + 0.12743801 0.72011906 -0.68204707, + 0.107861 0.74591899 -0.65724498, + 0.085920967 0.74752176 -0.65865678, + 0.067871191 0.77225989 -0.63167095, + 0.050246771 0.77306652 -0.63233167, + 0.03378889 0.79699069 -0.60304576, + 0.021165792 0.79726768 -0.60325474, + 0.0069938824 0.81963032 -0.57285017, + -0.025421306 0.84545517 -0.53344113, + -0.016303806 0.84561628 -0.53354216, + -0.0014338304 0.81964916 -0.57286412, + 0.002833141 0.82500929 -0.56511217, + 0.014413504 0.8034482 -0.59520012, + 0.025276197 0.80327487 -0.59507191, + 0.038985308 0.78037119 -0.62410015, + 0.054205112 0.77981716 -0.62365609, + 0.070053168 0.75538862 -0.65152168, + 0.089282289 0.75422388 -0.65051895, + 0.10672799 0.72887397 -0.67627794, + 0.13031803 0.7268092 -0.6743632, + 0.14862406 0.70122623 -0.69727522, + 0.17636596 0.69798684 -0.69405282, + 0.19676192 0.67006278 -0.71575177, + 0.2281101 0.66540432 -0.71077633, + 0.25123385 0.63382864 -0.7315346, + 0.2874859 0.62718779 -0.72386974, + 0.31167594 0.59360886 -0.74194783, + 0.35124287 0.58492279 -0.73109078, + 0.3752639 0.55050987 -0.74573183, + 0.41810185 0.5395118 -0.73083377, + 0.44097415 0.50517619 -0.74184823, + 0.48612106 0.49187705 -0.72231805, + 0.50727493 0.45814595 -0.72991395, + 0.55362308 0.44272006 -0.70533705, + 0.57268685 0.40997291 -0.70989585, + 0.61849308 0.39297706 -0.68046707, + 0.63490701 0.362176 -0.68243802, + 0.67920399 0.344062 -0.64830798, + 0.69296598 0.31542599 -0.64830899, + 0.73494518 0.29668206 -0.60978311, + 0.74610198 0.27055201 -0.60838598, + 0.78501886 0.25171396 -0.56602591, + 0.79374516 0.22835106 -0.56375915, + 0.8286981 0.21012303 -0.51875603, + 0.8351891 0.18993503 -0.51612407, + 0.86609513 0.17263801 -0.46912205, + 0.8724857 0.14883894 -0.46541983, + 0.87904233 0.15340605 -0.45138815, + 0.8416732 0.17375605 -0.51126814, + 0.83605117 0.19283704 -0.51364613, + 0.80231488 0.20979597 -0.55881697, + 0.79476011 0.23181103 -0.56091005, + 0.7570979 0.24952397 -0.60377192, + 0.74724919 0.27455306 -0.6051771, + 0.70656675 0.29236087 -0.64442879, + 0.69426036 0.32008114 -0.64463228, + 0.65112275 0.33753589 -0.67978579, + 0.63634276 0.36749589 -0.67824376, + 0.59126997 0.38420194 -0.70907593, + 0.574224 0.41576901 -0.70526803, + 0.52822393 0.43121094 -0.73146194, + 0.50891691 0.46434993 -0.72483295, + 0.46364579 0.47794577 -0.74605662, + 0.44273689 0.51168787 -0.73631483, + 0.39913291 0.5232389 -0.75293684, + 0.37713382 0.55707574 -0.73988962, + 0.33624592 0.56646788 -0.75236481, + 0.31367296 0.60007393 -0.73588091, + 0.27569595 0.60747689 -0.74495882, + 0.25338703 0.64008605 -0.72531706, + 0.22001192 0.64546776 -0.73141378, + 0.199085 0.67601597 -0.70948398, + 0.16983296 0.67980385 -0.71345884, + 0.15131409 0.7072804 -0.69054943, + 0.12646504 0.70977426 -0.69298422, + 0.10996602 0.73520005 -0.66887105, + 0.088431098 0.73678797 -0.67031598, + 0.073489033 0.76119131 -0.64435023, + 0.056034598 0.76205599 -0.645082, + 0.042650595 0.78572887 -0.61709893, + 0.029706892 0.78609782 -0.61738789, + 0.018362192 0.80844671 -0.58828276, + 0.014634197 0.80849582 -0.5883199, + 0.021882806 0.79095715 -0.61148012, + 0.033321407 0.79070717 -0.61128712, + 0.0443132 0.76779199 -0.63916498, + 0.059541684 0.76718384 -0.63865781, + 0.072322488 0.74324483 -0.66509885, + 0.091580547 0.74206436 -0.66404331, + 0.10592498 0.7172538 -0.68871385, + 0.12932397 0.71525484 -0.6867938, + 0.14554693 0.68872565 -0.71026266, + 0.17253406 0.68569922 -0.70714122, + 0.19137797 0.65590197 -0.73018295, + 0.22246006 0.65150815 -0.72529221, + 0.24274294 0.6198619 -0.74622184, + 0.27798194 0.6137889 -0.73891079, + 0.29905888 0.5807898 -0.75713068, + 0.3383221 0.57275414 -0.7466532, + 0.35913908 0.53953409 -0.76152617, + 0.40107891 0.52956688 -0.74745882, + 0.421426 0.49597201 -0.75921798, + 0.465446 0.484056 -0.74097902, + 0.48456824 0.45088521 -0.74959737, + 0.52993017 0.43711615 -0.72670722, + 0.54731882 0.40496784 -0.73242277, + 0.59284788 0.38967291 -0.70475984, + 0.60830873 0.35877088 -0.70798576, + 0.65257704 0.34250802 -0.67589307, + 0.66577423 0.31355911 -0.67707121, + 0.70789796 0.29681796 -0.64092094, + 0.7187978 0.27017093 -0.64057583, + 0.75826585 0.25335497 -0.60070294, + 0.76687253 0.22955887 -0.59934062, + 0.80331272 0.21301892 -0.55615783, + 0.80988789 0.19211297 -0.55423295, + 0.84250188 0.17642799 -0.50898296, + 0.84736788 0.15834698 -0.50684696, + 0.87616056 0.14373893 -0.46008879, + 0.88097429 0.12214004 -0.45712814, + 0.85858691 0.13471799 -0.49465093, + 0.88268977 0.12349497 -0.45343989, + 0.88748258 0.097399652 -0.45043078, + 0.8658728 0.10762598 -0.48854989, + 0.88882267 0.098587364 -0.44752085, + 0.89235878 0.074047484 -0.44521087, + 0.91534811 0.066063508 -0.39720705, + 0.91732711 0.045569602 -0.39551806, + 0.93679774 0.040045287 -0.34757191, + 0.93776524 0.022944206 -0.3465111, + 0.95399767 0.019808793 -0.29915887, + 0.95428914 0.0083306106 -0.29876903, + 0.96358752 -0.0054751672 -0.26733688, + 0.96359766 0.0023844391 -0.26734591, + 0.96359938 0.0023843108 -0.26734009, + 0.96360177 -0.0015751896 -0.26733693, + 0.96014446 -0.0033655616 -0.27948412, + 0.88267559 -0.0043434883 -0.46996278, + 0.86981845 -0.00041111177 -0.4933717, + 0.86982512 -0.00041164106 -0.49336007, + 0.86979687 0.0077623092 -0.49334893, + 0.86979002 0.0077625602 -0.493361, + 0.81730288 0.0012550598 -0.57620692, + 0.81730402 -0.00087633799 -0.57620603, + 0.81731111 -0.00087685313 -0.57619607, + 0.81731039 0.0012549706 -0.57619631, + 0.82496685 0.013870996 -0.56501091, + -0.81910884 -0.0011682998 -0.57363689, + -0.81906319 -0.0011651902 -0.5737021, + -0.81904513 0.0062643308 -0.57369506, + -0.81909043 0.0062633627 -0.57363027, + -0.82482386 0.016467499 -0.56514996, + 0.79056281 0.037186991 -0.61125088, + 0.7894398 0.054081988 -0.6114409, + 0.75626785 0.057644486 -0.65171784, + 0.75455511 0.07624881 -0.65179205, + 0.71875077 0.080783769 -0.69055879, + 0.71633595 0.10120498 -0.69037694, + 0.67804629 0.10661105 -0.72724634, + 0.67484277 0.12888396 -0.72661978, + 0.63465071 0.13496894 -0.76092166, + 0.63058919 0.15908705 -0.75963718, + 0.58879304 0.16568102 -0.79112113, + 0.58382487 0.19165996 -0.7889328, + 0.54043204 0.19862503 -0.8176071, + 0.53465283 0.22600593 -0.81428969, + 0.489907 0.233147 -0.84002, + 0.48338905 0.26178604 -0.8353461, + 0.43855122 0.26875412 -0.85758042, + 0.43140894 0.29858997 -0.85131091, + 0.38681108 0.30521005 -0.87018615, + 0.37928885 0.33575687 -0.86221069, + 0.33517608 0.34188208 -0.87793726, + 0.32748398 0.37294897 -0.8681379, + 0.28438604 0.37841704 -0.88086611, + 0.27678898 0.40974793 -0.86919188, + 0.23549403 0.41441506 -0.8790921, + 0.22824411 0.4457612 -0.86556441, + 0.18920895 0.44957587 -0.87297285, + 0.18259795 0.48050189 -0.85777384, + 0.14592107 0.48348719 -0.86310327, + 0.14023705 0.51347917 -0.84656531, + 0.10614298 0.51567388 -0.8501848, + 0.10154404 0.54471117 -0.83245331, + 0.070691392 0.54617196 -0.83468491, + 0.067352109 0.57386005 -0.8161791, + 0.039132915 0.57472515 -0.81741029, + 0.0370907 0.601215 -0.798226, + 0.011650799 0.60158896 -0.7987209, + 0.010959798 0.62689483 -0.77902681, + -0.011538097 0.62689078 -0.77902168, + -0.012230098 0.60152692 -0.79875886, + -0.037730284 0.60114378 -0.79824972, + -0.039772484 0.57465082 -0.81743169, + -0.068008319 0.5737741 -0.81618518, + -0.071347818 0.54608011 -0.8346892, + -0.10238998 0.54459786 -0.83242381, + -0.10694101 0.51579207 -0.85001314, + -0.14085598 0.51359391 -0.84639287, + -0.14655803 0.48350513 -0.86298519, + -0.18322301 0.48050806 -0.85763711, + -0.18980895 0.44969189 -0.87278283, + -0.22879508 0.44586915 -0.8653633, + -0.23605503 0.41446906 -0.87891614, + -0.27713397 0.40981594 -0.86904991, + -0.28468686 0.37869483 -0.88064957, + -0.32786104 0.37320602 -0.86788511, + -0.33552998 0.34222096 -0.87766987, + -0.37959492 0.33609092 -0.86194581, + -0.38710892 0.30556893 -0.86992782, + -0.43163291 0.29894495 -0.85107285, + -0.43880701 0.26896 -0.85738498, + -0.48365277 0.26197988 -0.8351326, + -0.49021405 0.23312803 -0.83984613, + -0.53490019 0.22599107 -0.81413132, + -0.54076213 0.19819905 -0.81749219, + -0.58411211 0.19124804 -0.78882021, + -0.58914894 0.16484898 -0.79102987, + -0.63093793 0.15828098 -0.75951588, + -0.63501418 0.13399804 -0.76079017, + -0.6752072 0.12795003 -0.72644615, + -0.67838693 0.10573999 -0.72705597, + -0.71667194 0.10037199 -0.69014996, + -0.71903181 0.080332175 -0.69031882, + -0.75478983 0.075822987 -0.65156984, + -0.75643802 0.0578954 -0.65149802, + -0.78957999 0.054317798 -0.61123902, + -0.79064769 0.038371686 -0.61106777, + -0.82141781 0.035742994 -0.56920588, + -0.8220129 0.022022597 -0.56904292, + -0.79165828 0.023627309 -0.61050725, + -0.79096317 0.039023809 -0.61061811, + -0.7581073 0.041591916 -0.65080225, + -0.75691414 0.058862407 -0.65085804, + -0.72150785 0.062365286 -0.68959183, + -0.71969867 0.081666663 -0.68946666, + -0.68174094 0.086054996 -0.72651494, + -0.67921394 0.10737199 -0.72604394, + -0.63937968 0.11248495 -0.76061863, + -0.63602597 0.13597098 -0.7595939, + -0.59455526 0.14167805 -0.79147428, + -0.59034395 0.16714099 -0.78965688, + -0.54721093 0.17332098 -0.8188529, + -0.54211617 0.20075108 -0.81597131, + -0.49752519 0.20723608 -0.84233129, + -0.49171188 0.23588593 -0.83819884, + -0.44681299 0.242351 -0.86117601, + -0.44044501 0.27188399 -0.85562098, + -0.39556095 0.27814096 -0.8753109, + -0.38877416 0.30843711 -0.86817127, + -0.34428787 0.31430587 -0.8846907, + -0.33730498 0.34514698 -0.87584186, + -0.29344106 0.3504931 -0.88940823, + -0.28650615 0.38154519 -0.87882739, + -0.24449691 0.38615385 -0.88944173, + -0.237873 0.41715801 -0.87715203, + -0.19767907 0.42101014 -0.88525331, + -0.19151992 0.4520708 -0.87117857, + -0.15366597 0.45512688 -0.87706679, + -0.14827304 0.48573411 -0.86143917, + -0.11264802 0.48803705 -0.8655231, + -0.10830402 0.51744008 -0.84883809, + -0.075594507 0.51901305 -0.85141712, + -0.072396912 0.54725909 -0.83382618, + -0.042531397 0.54820192 -0.83526391, + -0.040557984 0.57546979 -0.81681669, + -0.013329102 0.57589203 -0.81741714, + -0.012666699 0.60195196 -0.79843187, + 0.012028898 0.60195696 -0.79843789, + 0.012690303 0.57592613 -0.8174032, + 0.03988982 0.57551432 -0.81681842, + 0.041863188 0.54824889 -0.83526683, + 0.071710661 0.54731679 -0.83384758, + 0.074912339 0.51903921 -0.85146141, + 0.10763402 0.51747805 -0.84890014, + 0.11199001 0.48800406 -0.86562711, + 0.14763197 0.48571187 -0.86156183, + 0.15303901 0.45503506 -0.87722415, + 0.19094296 0.45198688 -0.8713488, + 0.19712608 0.42081514 -0.88546932, + 0.23722997 0.41698393 -0.87740886, + 0.24388503 0.38589707 -0.8897211, + 0.2862049 0.38126585 -0.87904668, + 0.29313993 0.3501749 -0.88963276, + 0.33697093 0.34484392 -0.87608975, + 0.34397188 0.31393689 -0.88494468, + 0.38847592 0.30807894 -0.86843181, + 0.39523315 0.2779291 -0.87552631, + 0.44018689 0.27167293 -0.85582083, + 0.44650587 0.24239895 -0.86132181, + 0.49142307 0.23593603 -0.83835411, + 0.49719518 0.20754008 -0.84245127, + 0.54172719 0.20106107 -0.81615329, + 0.54676503 0.17406 -0.81899399, + 0.58992893 0.16785799 -0.78981489, + 0.59412575 0.14260796 -0.79162973, + 0.63562793 0.13686799 -0.75976586, + 0.63899696 0.11337698 -0.76080787, + 0.67886722 0.10822704 -0.72624123, + 0.68145204 0.086499505 -0.72673309, + 0.7194072 0.082094125 -0.68972015, + 0.72128719 0.062095314 -0.68984717, + 0.75674164 0.058605969 -0.65108168, + 0.75799215 0.040356304 -0.65101403, + 0.79088914 0.037862603 -0.61078703, + 0.79161817 0.021201706 -0.6106481, + 0.82199073 0.019761093 -0.56915784, + 0.82136589 0.034637798 -0.56934893, + 0.82426268 0.040977087 -0.56472284, + 0.84939867 0.038194086 -0.52636784, + 0.85040081 0.013625497 -0.5259589, + 0.84352469 0.015667494 -0.53686184, + 0.84363383 -0.00040260391 -0.53691888, + 0.84458399 -0.000401417 -0.53542298, + 0.8445462 0.0090504121 -0.53540611, + 0.84456915 0.009049641 -0.53537005, + 0.84460688 -0.00039644694 -0.53538692, + 0.82967269 -0.0044084587 -0.55823284, + 0.926314 -0.0042038802 -0.37672901, + 0.98379302 -0.00337071 -0.179276, + 0.98514599 -0.0044956398 -0.17166001, + 0.98515499 0.00069902599 -0.171666, + 0.98516226 0.00069826818 -0.17162405, + 0.98516077 -0.0020997296 -0.17162095, + 0.99237537 0.00075980031 -0.12325004, + 0.99237567 7.566507e-005 -0.12324996, + 0.99239498 7.2922303e-005 -0.123094, + 0.99239463 0.00076340168 -0.12309495, + 0.99239022 0.00076337415 -0.12313103, + 0.99239051 7.100356e-005 -0.12312994, + 0.99358255 0.0034571884 -0.11305594, + 0.9935475 0.0070007034 -0.11320105, + 0.98712498 0.0098730801 -0.159646, + 0.98693025 0.017224304 -0.16022505, + 0.97788525 0.022354206 -0.20794405, + 0.97736478 0.032375291 -0.20906895, + 0.96541226 0.039899509 -0.25765705, + 0.96427548 0.053100627 -0.25952512, + 0.94886488 0.063279793 -0.30927497, + 0.94666225 0.080287822 -0.31206506, + 0.9270829 0.093400992 -0.36303398, + 0.92312258 0.11505995 -0.36688682, + 0.89849079 0.13136397 -0.41887692, + 0.89169568 0.15882695 -0.42385486, + 0.86139327 0.17823306 -0.47564119, + 0.8529017 0.20479693 -0.48022583, + 0.8194111 0.22485603 -0.52726203, + 0.81081879 0.24743994 -0.5304209, + 0.77301562 0.26819187 -0.57490867, + 0.76178366 0.29372886 -0.5774157, + 0.71995115 0.3146731 -0.61858809, + 0.70573705 0.34306702 -0.61987108, + 0.66115892 0.36329296 -0.65641993, + 0.64373207 0.39434305 -0.65582204, + 0.59743011 0.41324008 -0.68724817, + 0.57681084 0.44647884 -0.68406576, + 0.529603 0.46362299 -0.710334, + 0.50625885 0.49813783 -0.70396078, + 0.45980695 0.51294595 -0.72488892, + 0.43417194 0.54822195 -0.71480596, + 0.389862 0.56041998 -0.73071003, + 0.36274478 0.59559864 -0.71671361, + 0.32201213 0.60508823 -0.72813225, + 0.29487905 0.63876218 -0.7106542, + 0.25841993 0.64577985 -0.71846181, + 0.23416294 0.67512685 -0.69955081, + 0.201395 0.680206 -0.70481199, + 0.17956005 0.70646816 -0.68458819, + 0.15087 0.70991999 -0.68793303, + 0.12945703 0.73592716 -0.6645692, + 0.10461298 0.73809981 -0.6665318, + 0.083856799 0.76387 -0.63989902, + 0.064298682 0.76498383 -0.64083183, + 0.045321979 0.78950864 -0.61206371, + 0.029716689 0.78997171 -0.61242276, + 0.012629001 0.81339413 -0.58157605, + 0.0027692397 0.81345588 -0.58161992, + -0.015432105 0.84035927 -0.54181015, + -0.028167091 0.84012568 -0.54165983, + -0.027050281 0.83824939 -0.54461557, + -0.022000089 0.83835357 -0.54468274, + -0.017818591 0.83621657 -0.54810977, + -0.02585119 0.8360697 -0.54801381, + -0.01722909 0.81179255 -0.58369166, + -0.019185493 0.8117637 -0.58367074, + -0.012683903 0.78445417 -0.62005711, + -0.012077798 0.78445989 -0.62006193, + -0.0079767527 0.7541253 -0.65668225, + -0.0040366193 0.75414288 -0.65669793, + -0.0026217701 0.72090006 -0.69303405, + 0.0025530208 0.72090024 -0.69303423, + 0.0039509395 0.75415289 -0.65668696, + 0.0078932187 0.75413591 -0.65667093, + 0.011985103 0.78456318 -0.61993313, + 0.013173693 0.7845515 -0.61992365, + 0.019631898 0.81167889 -0.58377391, + 0.0173073 0.81171298 -0.58380002, + 0.017844802 0.83614713 -0.54821503, + 0.025924604 0.83599913 -0.54811805, + 0.003917099 0.81675184 -0.57697588, + -0.00017422595 0.81675768 -0.57698083, + 0.015172392 0.84998655 -0.52658576, + 0.02100189 0.84989661 -0.52653074, + 0.017201407 0.83964241 -0.54286724, + 0.019321889 0.8396095 -0.54284668, + 0.012980998 0.81443983 -0.58010286, + 0.011892695 0.81445068 -0.58011085, + 0.0078961411 0.78624213 -0.61786807, + 0.0037494705 0.78626114 -0.61788309, + 0.00237409 0.754798 -0.65595299, + -0.0024354397 0.75479788 -0.65595293, + -0.0038306015 0.78615928 -0.61801225, + -0.007989781 0.78613913 -0.61799806, + -0.012012898 0.8143869 -0.58019793, + -0.012881695 0.81437868 -0.58019084, + -0.019229989 0.83956051 -0.54292572, + -0.017426603 0.83958811 -0.54294407, + -0.021234006 0.8498472 -0.52660114, + -0.01507479 0.84994251 -0.52665973, + -0.0034209595 0.82500786 -0.56511092, + -0.0071318392 0.82088286 -0.57105196, + -0.0010312705 0.82090342 -0.57106632, + -0.0126224 0.85334003 -0.52120203, + -0.015535897 0.8533048 -0.52118087, + -0.012598698 0.84214187 -0.53910893, + -0.011778698 0.84214985 -0.53911495, + -0.0078451894 0.81600189 -0.57799596, + -0.00391735 0.81602103 -0.57800901, + -0.002539519 0.7866587 -0.61738276, + 0.0027228799 0.78665888 -0.61738193, + 0.0040878914 0.8159973 -0.5780412, + 0.0079487618 0.81597817 -0.57802814, + 0.011873202 0.84211516 -0.53916711, + 0.012916093 0.84210449 -0.53915972, + 0.015847804 0.85323417 -0.52128714, + 0.012672497 0.8532728 -0.52131087, + 0.00111839 0.82091802 -0.57104498, + -0.0095078181 0.82088184 -0.57101887, + -0.022097994 0.79085082 -0.61160988, + -0.033307798 0.79060501 -0.61141998, + -0.044210013 0.76787019 -0.6390782, + -0.059454106 0.7672621 -0.63857204, + -0.07224118 0.74331278 -0.66503179, + -0.091782503 0.74211401 -0.66395998, + -0.106106 0.71732497 -0.68861198, + -0.12924302 0.71534604 -0.68671405, + -0.14612001 0.68772304 -0.71111608, + -0.1732209 0.68467557 -0.7079646, + -0.19227298 0.65447897 -0.73122394, + -0.22377187 0.65001059 -0.72623158, + -0.24392492 0.61846775 -0.74699277, + -0.27930307 0.61235112 -0.73960519, + -0.30013502 0.57964504 -0.75758213, + -0.339479 0.57157302 -0.747033, + -0.36030498 0.53825295 -0.76188189, + -0.40228283 0.52825975 -0.74773663, + -0.42226201 0.49519601 -0.75926, + -0.46632013 0.48325512 -0.74095219, + -0.48538595 0.45011693 -0.74952996, + -0.53055894 0.43639493 -0.72668195, + -0.5478189 0.4044469 -0.73233682, + -0.59346491 0.38910395 -0.70455492, + -0.60869974 0.3586129 -0.70772976, + -0.65291685 0.34235391 -0.67564285, + -0.66598785 0.31366092 -0.67681384, + -0.70807517 0.29691505 -0.64068019, + -0.71885121 0.2705681 -0.64034826, + -0.75828212 0.25374004 -0.60052007, + -0.76687789 0.22998098 -0.59917194, + -0.80327117 0.21343304 -0.55605912, + -0.8098368 0.19258195 -0.55414486, + -0.8424648 0.17685595 -0.50889587, + -0.84731472 0.15884894 -0.50677884, + -0.87611145 0.14419791 -0.46003872, + -0.87963378 0.12861498 -0.45793289, + -0.90381521 0.11571003 -0.41198209, + -0.90145212 0.12715201 -0.41378307, + -0.87542909 0.14197502 -0.46202505, + -0.87138009 0.15825102 -0.46438506, + -0.84163839 0.17419589 -0.51117563, + -0.83601171 0.19327992 -0.51354384, + -0.80229086 0.21026596 -0.55867493, + -0.7947579 0.23220797 -0.56074893, + -0.75712401 0.249938 -0.60356802, + -0.74740374 0.2746419 -0.60494578, + -0.70674396 0.29245898 -0.64418995, + -0.69456756 0.31990683 -0.64438766, + -0.65145797 0.33736396 -0.67954993, + -0.63689393 0.36692598 -0.67803496, + -0.59188193 0.38361895 -0.70888096, + -0.57488179 0.41515684 -0.70509279, + -0.52888787 0.4306089 -0.73133683, + -0.50985998 0.46333599 -0.724819, + -0.46447405 0.47697905 -0.74616003, + -0.44383284 0.51035684 -0.73657876, + -0.40032595 0.52189696 -0.75323486, + -0.3783499 0.55579388 -0.74023283, + -0.33738503 0.56522304 -0.75279111, + -0.31507799 0.59853202 -0.73653603, + -0.27699593 0.60597688 -0.7456978, + -0.25501487 0.63822168 -0.72638863, + -0.22121499 0.64369297 -0.73261398, + -0.19972596 0.67513984 -0.71013784, + -0.17058693 0.67892271 -0.71411765, + -0.15145491 0.7073496 -0.69044757, + -0.126384 0.70986599 -0.69290501, + -0.11006907 0.7350114 -0.66906142, + -0.08849518 0.73660284 -0.67051083, + -0.073408313 0.76124918 -0.64429116, + -0.055935416 0.76211315 -0.64502317, + -0.042666927 0.78558946 -0.61727536, + -0.029666511 0.7859593 -0.61756623, + -0.021028493 0.80310172 -0.59547079, + -0.02506149 0.80302668 -0.59541577, + -0.038842902 0.77999502 -0.62457901, + -0.054097988 0.77944082 -0.62413585, + -0.069826506 0.75519115 -0.65177506, + -0.089390725 0.75400817 -0.65075415, + -0.10682302 0.72866321 -0.67649019, + -0.13045397 0.72659379 -0.67456883, + -0.14868002 0.70111203 -0.69737804, + -0.17617606 0.69790322 -0.69418526, + -0.19731396 0.66894495 -0.71664494, + -0.22905193 0.66421878 -0.71158177, + -0.25277898 0.63171792 -0.73282695, + -0.28895196 0.62507093 -0.72511595, + -0.31295186 0.5916487 -0.74297565, + -0.352873 0.58286601 -0.73194802, + -0.376423 0.54902101 -0.74624503, + -0.4195469 0.53793091 -0.73117083, + -0.44210315 0.50396615 -0.74199921, + -0.48724011 0.49065211 -0.72239721, + -0.50821489 0.4571209 -0.7299028, + -0.55457783 0.44167584 -0.70524174, + -0.57334793 0.40936494 -0.70971292, + -0.61911595 0.39236993 -0.68025094, + -0.63546503 0.36163601 -0.68220502, + -0.67960203 0.34358099 -0.64814597, + -0.69324815 0.31515908 -0.64813715, + -0.73516667 0.29643786 -0.6096347, + -0.74622464 0.27052888 -0.60824573, + -0.78511268 0.2516959 -0.56590384, + -0.79371816 0.22866206 -0.56367111, + -0.82867569 0.21040893 -0.5186758, + -0.83513659 0.19033392 -0.51606178, + -0.86603385 0.17301299 -0.46909693, + -0.8706882 0.15591803 -0.46646711, + -0.90384239 0.13563806 -0.40579718, + -0.99342662 0.011926095 -0.11384796, + -0.98684454 0.016843893 -0.16079192, + -0.98654288 0.024392197 -0.16167298, + -0.97716022 0.031702209 -0.21012604, + -0.97640353 0.042492382 -0.2117319, + -0.96383613 0.052437406 -0.26128602, + -0.96226209 0.066777706 -0.26380402, + -0.94583189 0.079668991 -0.31472996, + -0.92169952 0.11439206 -0.3706542, + -0.94286734 0.098250635 -0.31835213, + -0.51554388 0.52546591 -0.67683083, + -0.5673821 0.50497913 -0.65044117, + -0.59722108 0.46771505 -0.65159005, + -0.64905792 0.44360894 -0.61800891, + -0.67353785 0.40885893 -0.6157769, + -0.72262794 0.38235494 -0.57585895, + -0.7417388 0.35108492 -0.57145691, + -0.78638327 0.32336712 -0.5263412, + -0.80074465 0.29589486 -0.52082074, + -0.84041631 0.26770708 -0.47120419, + -0.85056484 0.24460694 -0.46551788, + -0.88464975 0.21687695 -0.41274592, + -0.89156491 0.19777396 -0.40742794, + -0.92587799 0.16499101 -0.339894, + 0.99735421 -0.0025313806 0.072650716, + -0.028333601 0.72377801 -0.68945098, + -0.033015583 0.73168057 -0.68084759, + -0.027093695 0.73181093 -0.68096894, + -0.032167189 0.73902577 -0.67290878, + -0.0238121 0.73919898 -0.67306602, + -0.028798496 0.74528396 -0.66612494, + -0.0175984 0.74547702 -0.66629899, + -0.021812895 0.74997282 -0.66110879, + -0.0079250867 0.75012761 -0.6612457, + -0.011551304 0.75356132 -0.65727621, + 0.0058836308 0.75359911 -0.65730804, + 0.0030629712 0.7560063 -0.65455723, + 0.024182612 0.75578839 -0.65436929, + 0.022240512 0.75730437 -0.65268332, + 0.0473447 0.75664198 -0.65211302, + 0.049778592 0.75486887 -0.65398395, + 0.079467937 0.75341535 -0.65272528, + 0.11414094 0.72845858 -0.67551458, + 0.151605 0.72477502 -0.67209899, + 0.19327909 0.69330734 -0.69423938, + 0.23789904 0.68634504 -0.68726605, + 0.27594104 0.65564007 -0.70284605, + 0.325746 0.64491898 -0.69135302, + 0.35920888 0.61582476 -0.70123374, + 0.44015816 0.59250724 -0.67468226, + -0.028339203 0.75719911 -0.65256906, + -0.033407088 0.76536173 -0.64273274, + -0.027587393 0.7654978 -0.64284682, + -0.032520313 0.7721833 -0.63456726, + -0.024671091 0.77235669 -0.63470978, + -0.029462384 0.77792454 -0.62766665, + -0.018611902 0.77812713 -0.62783104, + -0.022891607 0.78247333 -0.62226325, + -0.0092405789 0.78264487 -0.62239993, + -0.012616798 0.78568989 -0.61849195, + 0.0041398988 0.78574568 -0.61853576, + 0.0037883299 0.78603297 -0.618173, + 0.0246893 0.78579903 -0.617989, + 0.053186107 0.76358014 -0.64351904, + 0.07998962 0.76221216 -0.64236617, + 0.11765206 0.73235738 -0.67067927, + 0.15163094 0.72895175 -0.66756076, + 0.187135 0.699691 -0.689502, + 0.22742595 0.69360983 -0.6835078, + 0.26121193 0.66438484 -0.70025784, + 0.30666104 0.65511805 -0.69049203, + 0.33719009 0.62714916 -0.7021302, + 0.38661924 0.61436135 -0.68781239, + 0.41347006 0.58806103 -0.69514507, + 0.48703894 0.56407595 -0.66679192, + 0.88572812 0.22609103 -0.40542406, + 0.83913809 0.26491603 -0.47504407, + 0.8270492 0.29022107 -0.48141611, + 0.78483999 0.31994301 -0.53071898, + 0.76784384 0.3498069 -0.53670388, + 0.72040892 0.37869895 -0.58103192, + 0.69779098 0.41260001 -0.58553302, + 0.64653593 0.43943095 -0.62361193, + 0.6186161 0.47571412 -0.62530816, + 0.56532007 0.49943507 -0.65648907, + 0.53652894 0.53252792 -0.65463793, + 0.46969312 0.55710614 -0.68485117, + 0.4408448 0.5860827 -0.67982572, + 0.3875539 0.60192591 -0.69820285, + 0.35752892 0.62966681 -0.68970484, + 0.30780989 0.64149678 -0.70266277, + 0.27397403 0.67064005 -0.68933308, + 0.22862098 0.67885393 -0.69777495, + 0.19124791 0.70912063 -0.67865473, + 0.152594 0.71399498 -0.68331999, + 0.11235899 0.74491495 -0.65762997, + 0.08045119 0.74723095 -0.65967697, + 0.049125407 0.77052909 -0.63550907, + 0.023973804 0.7712391 -0.63609403, + 0.022983795 0.7719968 -0.63521081, + 0.0021463702 0.77219909 -0.63537705, + 0.0049372599 0.76987302 -0.63817799, + -0.012239807 0.7698245 -0.63813835, + -0.0086614387 0.76651585 -0.64216691, + -0.022420395 0.76635182 -0.64202982, + -0.0181091 0.76186299 -0.64748502, + -0.029087592 0.76166582 -0.64731681, + -0.024459895 0.75615281 -0.65393782, + -0.032367788 0.7559827 -0.65379077, + -0.027323095 0.74897581 -0.6620338, + -0.03326311 0.74884123 -0.66191423, + -0.0280861 0.74029797 -0.67169201, + -0.023255905 0.74038917 -0.67177618, + -0.031725194 0.7571218 -0.65250283, + -0.027030487 0.76388866 -0.64478171, + -0.031971198 0.77334887 -0.63317394, + -0.028508108 0.77343017 -0.63324016, + -0.033538107 0.78133017 -0.62321609, + -0.027702393 0.78146982 -0.62332785, + -0.032633085 0.78798366 -0.61483067, + -0.0250898 0.78815597 -0.61496401, + -0.029668396 0.79333889 -0.60805696, + -0.01916619 0.79354262 -0.60821271, + -0.023427898 0.79775691 -0.60252392, + -0.0095738405 0.79793912 -0.60266209, + -0.010820399 0.79903889 -0.60118192, + 0.0057043466 0.7990725 -0.60120761, + 0.030981196 0.77811688 -0.62735492, + 0.053952727 0.77735734 -0.62674129, + 0.088199079 0.74895483 -0.65672481, + 0.11776201 0.74665308 -0.65470707, + 0.15154798 0.71794593 -0.67940193, + 0.18682989 0.71354657 -0.6752376, + 0.21966296 0.68465596 -0.69497794, + 0.26072484 0.67752355 -0.6877386, + 0.29141003 0.64925903 -0.70252603, + 0.33670709 0.63908619 -0.69151819, + 0.364227 0.61233401 -0.701702, + 0.41312879 0.59876573 -0.68615168, + 0.43680006 0.57425106 -0.69241709, + 0.48718125 0.55748826 -0.67220628, + 0.51382005 0.52766204 -0.67643309, + 0.56543934 0.50729829 -0.6503284, + 0.59496802 0.47061399 -0.651564, + 0.64690399 0.44650301 -0.61818302, + 0.67186368 0.41126478 -0.61600369, + 0.72095639 0.38478217 -0.57633728, + 0.74059123 0.35281712 -0.57187819, + 0.78547382 0.32495692 -0.52671987, + 0.79997987 0.29730996 -0.52118993, + 0.83977997 0.26901799 -0.47159201, + 0.85013688 0.24551797 -0.46581995, + 0.88431102 0.21769901 -0.413039, + 0.89372313 0.19146803 -0.40570804, + 0.92289823 0.16433504 -0.34821409, + 0.92978698 0.138776 -0.34093601, + 0.95148343 0.11600494 -0.28499481, + 0.95517486 0.096947484 -0.27971798, + 0.97102666 0.078257971 -0.22579393, + 0.97283167 0.06468688 -0.22229293, + 0.98415375 0.049544189 -0.17025496, + 0.98494679 0.04025089 -0.16810596, + 0.99255478 0.028361492 -0.11845097, + 0.99284822 0.022398006 -0.11726403, + 0.99748886 0.013287598 -0.069566794, + 0.99756402 0.0100122 -0.069035403, + 0.99973851 0.0032820383 -0.022630088, + 0.99974412 0.0022716802 -0.022505801, + 0.99974614 -0.0022630002 0.022419801, + 0.99974954 -0.0012999194 0.022340288, + 0.9977029 -0.0039349995 0.067626789, + 0.99771464 -0.0018782692 0.067541681, + 0.9973501 -0.00047047104 0.072750509, + 0.99734986 0.00093512988 0.072749391, + 0.99735725 0.00093505025 0.072648115, + -0.020683898 0.51675093 -0.85588586, + -0.025946187 0.51668775 -0.8557806, + -0.019927293 0.47847381 -0.87787569, + -0.016746296 0.47850189 -0.87792677, + -0.013068405 0.43656814 -0.89957631, + -0.0057883905 0.43659806 -0.89963812, + -0.0045986078 0.39217183 -0.91988057, + 0.0045986078 0.39217183 -0.91988057, + 0.005787197 0.43655381 -0.89965957, + 0.012986093 0.43652472 -0.89959848, + 0.016637506 0.47833619 -0.87801927, + 0.019663999 0.47830993 -0.87797087, + 0.914581 -0.0078766001 0.40432599, + 0.91461128 -0.00012562705 0.40433416, + 0.91462421 -0.00012185803 0.4043051, + 0.91459328 -0.0078761829 0.40429816, + 0.8994627 -0.0044657788 0.43697485, + 0.89893889 -0.022768198 0.43748194, + 0.91950715 -0.020429403 0.39254206, + 0.91867512 -0.035385102 0.39342606, + 0.93697786 -0.031297997 0.34798396, + 0.93593311 -0.045000505 0.34929103, + 0.95193774 -0.03913739 0.30378094, + 0.95079935 -0.05164222 0.30547312, + 0.96467286 -0.043914795 0.25976497, + 0.96354246 -0.055259626 0.26178712, + 0.975429 -0.045502599 0.215564, + 0.97440064 -0.055626381 0.21782793, + 0.98439187 -0.043544795 0.17051798, + 0.98355341 -0.052288368 0.1728829, + 0.9914791 -0.037711903 0.12468801, + 0.9909001 -0.044778805 0.12693301, + 0.99664348 -0.027234713 0.077201441, + 0.99636263 -0.032050189 0.078957468, + 0.99958891 -0.010783799 0.026566597, + 0.99954665 -0.012637495 0.027327091, + 0.99952489 0.012936798 -0.027974296, + 0.99946475 0.015167097 -0.028984392, + 0.99480498 0.0471984 -0.090196103, + 0.99399567 0.05553478 -0.094279364, + 0.98216265 0.095434159 -0.16201495, + 0.98098052 0.10175795 -0.16529493, + 0.95966613 0.14738701 -0.23941202, + 0.96086103 0.14320099 -0.237149, + 0.92878288 0.19158097 -0.31726798, + 0.92991263 0.18872093 -0.31566888, + 0.88381577 0.24006194 -0.40154693, + 0.88318723 0.24124905 -0.4022181, + 0.81773698 0.296065 -0.49361101, + 0.82171214 0.29031602 -0.49041405, + 0.75731611 0.33267102 -0.56196308, + 0.76015913 0.32916704 -0.56018507, + 0.63071007 0.35335803 -0.69090009, + 0.55543888 0.37864792 -0.74034685, + 0.55329114 0.38053709 -0.74098617, + 0.47854912 0.4011271 -0.7810812, + 0.47144419 0.40694314 -0.78239232, + 0.39958808 0.4230001 -0.8132652, + 0.38481995 0.43442294 -0.81436491, + 0.31903088 0.44607285 -0.83620471, + 0.33257911 0.43575716 -0.83636528, + 0.27103707 0.44476411 -0.85365319, + 0.28874406 0.4309361 -0.85493916, + 0.23042104 0.43799606 -0.86894512, + 0.24121606 0.42923909 -0.87038416, + 0.1869709 0.4344998 -0.8810516, + 0.19347893 0.42896885 -0.88235569, + 0.14402898 0.43267092 -0.88997275, + 0.14599305 0.43090516 -0.89050931, + 0.10190204 0.43330416 -0.89546829, + 0.10067502 0.43448409 -0.89503527, + 0.062440716 0.4358511 -0.89785022, + 0.059498809 0.43892205 -0.8965531, + 0.02737879 0.43953586 -0.89780772, + 0.024131894 0.44327089 -0.89606279, + -0.0017297094 0.44339886 -0.89632273, + -0.004249231 0.44664112 -0.89470321, + -0.02417269 0.44651484 -0.89444971, + -0.025310896 0.44817993 -0.89358491, + -0.039696295 0.44796994 -0.8931669, + -0.039170399 0.44707999 -0.89363599, + -0.048572291 0.44689494 -0.89326686, + -0.046697214 0.44314814 -0.89523131, + -0.051764581 0.44303685 -0.89500773, + -0.04919121 0.43683809 -0.89819425, + -0.050393011 0.4368121 -0.89814025, + -0.047039192 0.42681894 -0.90311289, + -0.040774297 0.41088495 -0.91077489, + -0.044955887 0.42685986 -0.90319967, + -0.032188904 0.46726707 -0.88353014, + -0.037435509 0.46718213 -0.88336825, + -0.030787989 0.43528184 -0.8997677, + -0.040133417 0.43513715 -0.89946932, + -0.043597478 0.44791079 -0.89301461, + -0.044760976 0.44788778 -0.8929686, + -0.047963988 0.45712188 -0.88810974, + -0.045674611 0.45717111 -0.88820523, + -0.048582278 0.4639608 -0.88452256, + -0.042541083 0.4640888 -0.88476658, + -0.044603497 0.46809295 -0.88255286, + -0.034243587 0.46828482 -0.88291371, + -0.035058405 0.46962807 -0.88216811, + -0.019840002 0.46982405 -0.88253713, + -0.019478204 0.46930712 -0.88282025, + 0.00098483427 0.46939611 -0.88298726, + 0.0021323897 0.46795094 -0.88375187, + 0.028084099 0.46776801 -0.88340503, + 0.029311804 0.46638307 -0.8840971, + 0.060908906 0.46571705 -0.88283509, + 0.061141469 0.46547878 -0.88294458, + 0.098147556 0.46409979 -0.8803286, + 0.096171066 0.46596381 -0.87956172, + 0.13824797 0.46363789 -0.87517273, + 0.13272803 0.46849111 -0.87344116, + 0.17946102 0.46499905 -0.86693114, + 0.17048892 0.47242075 -0.8647266, + 0.22153901 0.467527 -0.85576802, + 0.20653796 0.47929987 -0.85300285, + 0.26110303 0.47286907 -0.8415581, + 0.24945997 0.48164493 -0.84011185, + 0.30841404 0.47312406 -0.82524812, + 0.32297608 0.46217611 -0.82588118, + 0.38918909 0.44984612 -0.80384719, + 0.39696091 0.44379389 -0.80341083, + 0.46868017 0.42712814 -0.77324027, + 0.47174588 0.4246169 -0.77275884, + 0.54652274 0.40328783 -0.73394263, + 0.54770803 0.40224907 -0.73362905, + 0.62322086 0.3759869 -0.68573284, + 0.62343311 0.3757821 -0.6856522, + 0.69655019 0.3448461 -0.62920517, + 0.69719636 0.34520817 -0.6282903, + 0.76634568 0.30935687 -0.56303883, + 0.76424652 0.31195483 -0.56445664, + 0.82726872 0.27174991 -0.49170983, + 0.824323 0.276041 -0.49426001, + 0.87886029 0.23262408 -0.41652215, + 0.87498212 0.23945002 -0.42079705, + 0.92614537 0.18653706 -0.32780913, + 0.92530626 0.18853004 -0.32903609, + 0.95983034 0.13949105 -0.24345009, + 0.95857209 0.14370002 -0.24594703, + 0.9808929 0.098144881 -0.16797799, + 0.98005438 0.10234704 -0.17034806, + 0.99338621 0.059133817 -0.098422721, + 0.99374962 0.055833183 -0.09666606, + 0.99936175 0.017866597 -0.030933093, + 0.9994455 0.015216207 -0.029619414, + 0.99947512 -0.014804602 0.028818004, + 0.99953222 -0.012651203 0.027843008, + 0.99589199 -0.0374582 0.082438603, + 0.99626225 -0.032017007 0.080227725, + 0.98993313 -0.052460507 0.13145502, + 0.99068397 -0.044641599 0.128656, + 0.98213273 -0.061690785 0.17779095, + 0.98322612 -0.052037306 0.17481002, + 0.97263485 -0.066288196 0.22268197, + 0.97397465 -0.055274483 0.21981393, + 0.96156722 -0.066958614 0.26628006, + 0.96304554 -0.054837074 0.26369688, + 0.94875246 -0.06434153 0.30940115, + 0.95027012 -0.051190309 0.30719104, + 0.93395478 -0.058745585 0.35252991, + 0.93541223 -0.04455971 0.35074008, + 0.91694415 -0.050288707 0.39583406, + 0.91822863 -0.03501479 0.39449984, + 0.89764029 -0.038964614 0.43900314, + 0.89863098 -0.022519199 0.43812701, + 0.89438128 -0.0084213726 0.44722614, + 0.87633973 -0.0051659388 0.48166588, + 0.87573373 -0.024782294 0.48215789, + 0.84542942 7.8989338e-005 0.53408724, + 0.81821001 0.000744919 0.57491899, + 0.81817073 -0.0092618959 0.57490081, + -0.75959182 -0.010342197 0.65031785, + -0.84009409 0.22097003 -0.49539307, + -0.89044142 0.18538909 -0.4156262, + -0.88862628 0.18863107 -0.41804516, + -0.92942464 0.15177093 -0.33635589, + -0.92764688 0.15578899 -0.33941296, + -0.95905924 0.11813903 -0.25738806, + -0.95765388 0.12237798 -0.26061997, + -0.97989035 0.084810726 -0.18061607, + -0.97859323 0.090456821 -0.18485904, + -0.99333447 0.050663922 -0.10353705, + -0.99296379 0.05360819 -0.10558898, + -0.99932063 0.016684795 -0.032862891, + -0.99927467 0.017874494 -0.033624791, + -0.99934334 -0.017007606 0.031994112, + -0.99929237 -0.018395908 0.032807011, + -0.99399602 -0.053514302 0.095436797, + -0.99424225 -0.051134109 0.094169021, + -0.98491251 -0.082579464 0.15207893, + -0.98665887 -0.070973694 0.14651598, + -0.97501224 -0.096847825 0.19992904, + -0.97738075 -0.083555281 0.19428195, + -0.96386564 -0.10524596 0.24471691, + -0.96668911 -0.090717204 0.23933803, + -0.95170766 -0.10881096 0.28707591, + -0.954817 -0.093313403 0.28216499, + -0.93837023 -0.10852202 0.3281531, + -0.94161385 -0.092202894 0.32382396, + -0.92358935 -0.10498804 0.36872813, + -0.92681086 -0.08803349 0.36506397, + -0.90706223 -0.098692425 0.4092651, + -0.91015089 -0.081090994 0.40626293, + -0.88877058 -0.089718357 0.44948578, + -0.89162421 -0.071362115 0.44711712, + -0.8684358 -0.078143276 0.48960489, + -0.87092215 -0.059103008 0.48785406, + -0.84554529 -0.064212523 0.53002816, + -0.8197481 -0.048383508 0.57067704, + -0.8475219 -0.044838496 0.52886295, + -0.84822714 -0.045275204 0.52769405, + -0.8735503 -0.041608114 0.48495218, + -0.87180072 -0.059646379 0.48621583, + -0.89480668 -0.054361083 0.44313186, + -0.89264774 -0.071983583 0.44496989, + -0.91363961 -0.064920269 0.40130782, + -0.91122621 -0.081718326 0.4037191, + -0.9304229 -0.072707593 0.35920298, + -0.92788899 -0.088620402 0.36217201, + -0.94519675 -0.077602684 0.3171449, + -0.94264477 -0.09270148 0.32066691, + -0.95821774 -0.079438277 0.27478793, + -0.95576513 -0.093684807 0.27881202, + -0.96969265 -0.07782197 0.23160291, + -0.96749562 -0.090921268 0.23597792, + -0.979819 -0.071865797 0.18652099, + -0.97801661 -0.083577871 0.19104493, + -0.98836964 -0.060950179 0.13932195, + -0.98709035 -0.070825525 0.14365405, + -0.99512774 -0.043598689 0.088430978, + -0.99445802 -0.050882298 0.0920012, + -0.99935699 -0.0173527 0.031375799, + -0.99932486 -0.018273799 0.031872198, + -0.99926865 0.019019593 -0.033172689, + -0.9993155 0.01777309 -0.032442983, + -0.99305046 0.056544725 -0.10321605, + -0.99342126 0.053468112 -0.10126902, + -0.9793005 0.094506547 -0.17899509, + -0.98012626 0.090716824 -0.17641704, + -0.9550131 0.13561802 -0.26373804, + -0.95741034 0.12847404 -0.25857309, + -0.92482036 0.16926506 -0.34067112, + -0.92694288 0.16448599 -0.33722597, + -0.88491768 0.20418093 -0.41860586, + -0.88712156 0.20024791 -0.4158318, + -0.83555388 0.23837297 -0.49500296, + -0.83740115 0.23566206 -0.49317613, + -0.77688986 0.27146897 -0.56810796, + 0.6440478 0.31102395 -0.6989038, + 0.56598032 0.33518815 -0.75320333, + 0.55370486 0.34583491 -0.75750184, + 0.47907007 0.36455104 -0.79849511, + 0.49649394 0.35024998 -0.79424089, + 0.42356908 0.36551109 -0.8288492, + 0.44663695 0.34670696 -0.8248089, + 0.37598583 0.35907283 -0.85422558, + 0.39152494 0.34631398 -0.85251087, + 0.32377389 0.35608688 -0.87656868, + 0.33382314 0.34771419 -0.87616044, + 0.26950094 0.35522592 -0.89508873, + 0.27295303 0.35227704 -0.89520812, + 0.21325393 0.35775888 -0.90913773, + 0.2112111 0.35956919 -0.90890044, + 0.15762594 0.36326888 -0.91825366, + 0.15159506 0.36889011 -0.91702735, + 0.10494903 0.37114212 -0.92262638, + 0.096986786 0.37906393 -0.9202739, + 0.057738625 0.38022417 -0.9230904, + 0.049574982 0.38904786 -0.91988266, + 0.0178646 0.389465 -0.92086798, + 0.011105096 0.39754686 -0.91751462, + -0.013355498 0.39753494 -0.91748989, + -0.017722704 0.40341109 -0.91484725, + -0.035649691 0.4032169 -0.91440976, + -0.037699081 0.40636981 -0.91293061, + -0.049751077 0.40615582 -0.91244859, + -0.050136693 0.40684593 -0.91211987, + -0.05701628 0.40669584 -0.91178268, + -0.055363815 0.4031851 -0.91344225, + -0.057924673 0.40312582 -0.91330957, + -0.05314029 0.3908039 -0.91893876, + -0.05344598 0.39079785 -0.91892362, + -0.049699891 0.37880296 -0.92414188, + -0.047653306 0.37884107 -0.92423409, + -0.044333015 0.36518613 -0.92987835, + -0.042083599 0.330167 -0.94298398, + -0.045146387 0.33012292 -0.94285774, + -0.041841101 0.31053701 -0.94963998, + -0.030545885 0.31066486 -0.95002854, + -0.019837897 0.21978398 -0.97534686, + -0.012313797 0.21981095 -0.97546476, + 0.0054383087 -0.036910791 -0.99930376, + 0.0017128403 -0.036911402 -0.99931711, + 0.0078240409 -0.30762002 -0.95147711, + -0.0073674563 -0.30762085 -0.95148051, + -0.0013343701 -0.037142105 -0.99930912, + -0.0051200897 -0.037141494 -0.9992969, + 0.012513602 0.21826603 -0.9758091, + 0.019806901 0.21824002 -0.97569412, + 0.030530289 0.30925888 -0.95048761, + 0.041673914 0.30913612 -0.95010436, + -0.79161167 0.2152409 -0.5718587, + -0.72612756 0.24220085 -0.64348865, + -0.72135144 0.24726714 -0.64692438, + -0.64997196 0.27132696 -0.70987195, + -0.66795123 0.25401008 -0.69951421, + -0.59480411 0.27437407 -0.75559717, + -0.62041104 0.25076002 -0.74310803, + -0.54621303 0.26782402 -0.79367614, + -0.5649159 0.25104293 -0.7860328, + -0.49006495 0.26520196 -0.83036387, + -0.50292194 0.25390896 -0.8261959, + -0.42876005 0.26539102 -0.86355811, + -0.43470892 0.26022893 -0.86215383, + -0.36256713 0.26929909 -0.8922013, + -0.3619771 0.26981106 -0.89228624, + -0.29336405 0.27670205 -0.91508126, + -0.28618315 0.28301814 -0.91542339, + -0.22313592 0.28792492 -0.93129462, + -0.211419 0.298558 -0.93067998, + -0.15593301 0.30172703 -0.94055611, + -0.14183103 0.31518209 -0.93837327, + -0.095025256 0.31695986 -0.94366652, + -0.080962598 0.331341 -0.94003099, + -0.042949602 0.33212504 -0.94225711, + -0.030668288 0.34585488 -0.93778664, + -0.0014156399 0.34601796 -0.93822688, + 0.0073694088 0.35696697 -0.93408787, + 0.028859107 0.35682809 -0.93372422, + 0.032409009 0.3618491 -0.93167323, + 0.047575109 0.36163002 -0.9311071, + 0.049267583 0.36438888 -0.92994267, + 0.058793508 0.36420003 -0.92946315, + 0.058558185 0.3637509 -0.92965376, + 0.063551612 0.3636401 -0.92936921, + 0.058788631 0.35278618 -0.93385541, + 0.061598178 0.35272688 -0.93369663, + 0.058326475 0.34366685 -0.93727857, + 0.058085579 0.34367189 -0.93729162, + 0.054671891 0.33193997 -0.94171488, + 0.051787693 0.33199096 -0.9418599, + 0.04874092 0.31857011 -0.94664538, + 0.043277685 0.31865087 -0.94688362, + 0.031284809 0.33744809 -0.94082421, + 0.032808211 0.33743113 -0.94077837, + 0.030076085 0.31449184 -0.94878352, + 0.018579202 0.31458002 -0.94904912, + 0.012083603 0.22188406 -0.97499824, + 0.0043115313 0.22189808 -0.97506034, + -0.0015392096 -0.035993494 -0.99935079, + 0.0018764904 -0.035993509 -0.99935025, + -0.0040214118 0.2227671 -0.97486347, + -0.011963895 0.2227529 -0.97480154, + -0.018478002 0.31564003 -0.94869912, + -0.030122312 0.31555113 -0.94843036, + -0.032732304 0.33744204 -0.94077712, + -0.034700811 0.33742011 -0.94071436, + -0.039711315 0.36525711 -0.93005937, + -0.027789991 0.38369486 -0.92304164, + -0.030401511 0.38366616 -0.92297137, + -0.025152296 0.34243196 -0.93920588, + -0.019843701 0.34247303 -0.93931812, + -0.018122802 0.31820402 -0.94784909, + -0.0060872589 0.31825098 -0.9479869, + -0.0039009715 0.22348608 -0.97469938, + 0.004045479 0.22348595 -0.97469878, + 0.0062214001 0.317974 -0.94807899, + 0.018115297 0.3179279 -0.94794178, + 0.019854192 0.34248188 -0.93931466, + 0.02519981 0.34244111 -0.93920135, + 0.030437611 0.38357913 -0.92300636, + 0.027714191 0.38360885 -0.92307967, + 0.035260983 0.4229908 -0.9054476, + 0.03924071 0.42292809 -0.90531325, + 0.032516506 0.38821006 -0.92099714, + 0.04238528 0.38806581 -0.92065656, + 0.046376489 0.40389091 -0.91363078, + 0.048694506 0.40384606 -0.91353011, + 0.051825389 0.41351593 -0.90902078, + 0.051131908 0.41353106 -0.90905315, + 0.054276109 0.42136806 -0.90526414, + 0.0500376 0.42146099 -0.90546501, + 0.052645892 0.42683893 -0.90279388, + 0.044562284 0.42700684 -0.90314972, + 0.044898402 0.42759207 -0.90285611, + 0.0316751 0.427809 -0.90331399, + 0.029975707 0.42526108 -0.90457422, + 0.011092898 0.4254249 -0.90492576, + 0.0075934702 0.42082301 -0.90711099, + -0.017614806 0.42077014 -0.90699631, + -0.022538593 0.41499686 -0.90954369, + -0.054479774 0.41448578 -0.9084236, + -0.059961077 0.40866485 -0.91071272, + -0.098743588 0.40739995 -0.90789586, + -0.10339702 0.40284708 -0.90940821, + -0.14883 0.400507 -0.90412599, + -0.15095201 0.39856306 -0.9046331, + -0.202553 0.39482599 -0.89614999, + -0.20102403 0.39615405 -0.89590812, + -0.25823393 0.39069292 -0.88355774, + -0.25162202 0.39621106 -0.88300812, + -0.31315708 0.38879108 -0.86647218, + -0.30071995 0.39886791 -0.86629784, + -0.36578912 0.38924316 -0.84539229, + -0.34511498 0.40562293 -0.84638387, + -0.41315794 0.39356494 -0.8212229, + -0.39949295 0.40430194 -0.8227669, + -0.47114375 0.38900781 -0.79164165, + -0.48147112 0.38061208 -0.7895062, + -0.55629307 0.36086404 -0.74854207, + -0.55935317 0.35818613 -0.74754721, + -0.63440937 0.33401722 -0.69710642, + -0.63645476 0.33205488 -0.69617873, + -0.70935762 0.30343986 -0.63618869, + -0.70979506 0.30296904 -0.63592505, + -0.77781737 0.27031612 -0.5673883, + -0.78219068 0.2519879 -0.56980681, + -0.71545702 0.28257099 -0.638964, + -0.71467203 0.283416 -0.63946801, + -0.64234406 0.31054604 -0.70068204, + -0.640311 0.31249201 -0.70167702, + -0.56563789 0.33549291 -0.75332481, + -0.55669004 0.34327403 -0.75647813, + -0.48207012 0.36203909 -0.79783219, + -0.4979609 0.34894991 -0.79389483, + -0.42500815 0.36423713 -0.8286733, + -0.44828689 0.3452169 -0.82453883, + -0.37761095 0.35760397 -0.8541249, + -0.39249691 0.34535792 -0.8524518, + -0.32464108 0.3551521 -0.87662727, + -0.33314398 0.34806398 -0.87627989, + -0.26884007 0.35556111 -0.8951543, + -0.2712341 0.35351813 -0.89524132, + -0.21166797 0.35896498 -0.90903288, + -0.20931897 0.36104298 -0.90875387, + -0.15592305 0.36470711 -0.91797435, + -0.14980599 0.370399 -0.916713, + -0.10339203 0.37262011 -0.92220634, + -0.095545739 0.38041914 -0.91986537, + -0.056488708 0.38155606 -0.92261809, + -0.048590288 0.3900899 -0.91949373, + -0.017058408 0.39049417 -0.92044741, + -0.010502304 0.39833415 -0.91718036, + 0.013828502 0.39831805 -0.91714311, + 0.018328499 0.40437195 -0.91441089, + 0.03604481 0.40417716 -0.91397029, + 0.038016085 0.40721086 -0.9125427, + 0.04994091 0.40699708 -0.91206324, + 0.0486915 0.40475699 -0.91312701, + 0.055950414 0.40460309 -0.91277921, + 0.053786188 0.39999491 -0.91493773, + 0.056979999 0.39992499 -0.91477501, + 0.054317791 0.39306295 -0.91790587, + 0.054142326 0.39306718 -0.91791439, + 0.049703889 0.37885892 -0.92411876, + 0.047666993 0.37889594 -0.92421091, + 0.044264596 0.36490497 -0.9299919, + 0.039760988 0.36497292 -0.93016875, + 0.035571981 0.34170285 -0.93913454, + 0.0463285 0.341553 -0.93871999, + 0.04962039 0.3555719 -0.93333077, + 0.052108817 0.35552713 -0.93321234, + 0.055607483 0.36714089 -0.92850167, + 0.055380017 0.36714607 -0.92851323, + 0.060076907 0.37969005 -0.92316109, + 0.057839692 0.37974095 -0.92328286, + 0.059575014 0.38355809 -0.92159325, + 0.053472508 0.38369107 -0.92191213, + 0.054076787 0.3848089 -0.92141074, + 0.043164611 0.3850131 -0.92190123, + 0.042380895 0.38377193 -0.92245489, + 0.026055794 0.38398692 -0.92297077, + 0.021086305 0.37714007 -0.92591625, + -0.0019502488 0.37722278 -0.92612046, + -0.0099817198 0.36742401 -0.93000001, + -0.040620487 0.36713892 -0.92927879, + -0.050787989 0.35596591 -0.93311775, + -0.089575581 0.3549929 -0.93056774, + -0.10062602 0.34384808 -0.93361825, + -0.14750803 0.3418211 -0.92811626, + -0.15757409 0.3323262 -0.92990851, + -0.21227802 0.32886103 -0.92021114, + -0.21928793 0.32256788 -0.92079467, + -0.28086093 0.31730691 -0.90577775, + -0.28273609 0.31567913 -0.90576327, + -0.34936181 0.30836985 -0.8847906, + -0.34544411 0.31171012 -0.8851583, + -0.41563609 0.30210805 -0.8578912, + -0.404955 0.31116301 -0.859761, + -0.47758025 0.29899716 -0.82614642, + -0.46042413 0.31359309 -0.83046317, + -0.53466499 0.29853201 -0.79057699, + -0.50957227 0.32008916 -0.79867333, + -0.58427078 0.30190888 -0.75331169, + -0.56681991 0.31728792 -0.76029181, + -0.64131224 0.29550412 -0.70809323, + -0.64825416 0.28891206 -0.70448315, + -0.71993357 0.26334584 -0.64214063, + -0.72087038 0.26234213 -0.64150029, + -0.78720909 0.23342903 -0.57080007, + -0.77567989 0.24740997 -0.58061093, + -0.84963715 0.20673504 -0.48515713, + -0.84522372 0.20341893 -0.49418381, + -0.89351189 0.17092298 -0.41523695, + -0.8919667 0.17367893 -0.41740984, + -0.93165487 0.13958198 -0.33546397, + -0.93014097 0.143005 -0.33821201, + -0.96051598 0.108353 -0.25625899, + -0.95931262 0.11199496 -0.25918391, + -0.98069054 0.077572361 -0.17952292, + -0.97993386 0.080909796 -0.18216299, + -0.99329513 0.046927206 -0.10565302, + -0.99281675 0.05055169 -0.10844098, + -0.99931961 0.015583495 -0.033429191, + -0.99927378 0.016729096 -0.034235794, + -0.99935442 -0.015772391 0.032277983, + -0.99930489 -0.017096698 0.033126097, + -0.99420738 -0.04929322 0.095508836, + -0.99371564 -0.05383338 0.098138161, + -0.98378533 -0.086256728 0.15724605, + -0.98434752 -0.082923062 0.15551093, + -0.97100914 -0.11247302 0.21092904, + -0.97420663 -0.096987359 0.20375192, + -0.95917761 -0.12154896 0.25535092, + -0.96285725 -0.10516502 0.24868906, + -0.94659364 -0.12558095 0.29696789, + -0.95055211 -0.10852601 0.29098603, + -0.93302077 -0.12573896 0.33713791, + -0.93710637 -0.10806504 0.33189413, + -0.91818202 -0.122652 0.37669399, + -0.92225623 -0.10440102 0.37221509, + -0.90181142 -0.11670205 0.4160732, + -0.90572 -0.098026298 0.412386, + -0.88384622 -0.10817903 0.45509711, + -0.88747925 -0.089030325 0.45216611, + -0.86396486 -0.097280487 0.49406594, + -0.86724383 -0.077480689 0.49181789, + -0.84171629 -0.084022433 0.53334218, + -0.84452158 -0.063630067 0.53172779, + -0.8167643 -0.068555124 0.5728842, + -0.81895614 -0.047930308 0.57185107, + -0.78916371 -0.051298283 0.61203676, + -0.7906763 -0.030462811 0.61147624, + -0.758775 -0.032409102 0.65054601, + -0.066942275 -0.014282895 0.99765462, + -0.53761584 -0.11978096 -0.83463871, + -0.61940324 -0.11152504 -0.77711129, + -0.65757006 -0.14357102 -0.73958707, + -0.72927797 -0.13038799 -0.67167896, + -0.748905 -0.148497 -0.64582503, + -0.8084082 -0.13190302 -0.5736531, + -0.81971884 -0.14386196 -0.55440485, + -0.86705512 -0.12513602 -0.48224106, + -0.8710832 -0.13019603 -0.47356412, + -0.90819949 -0.11094993 -0.40356377, + -0.90816802 -0.110902 -0.40364799, + -0.93699223 -0.092554219 -0.33686709, + -0.93534374 -0.089456975 -0.34224191, + -0.95765209 -0.072813809 -0.27856904, + -0.95553935 -0.067855723 -0.28695008, + -0.97273409 -0.053371307 -0.22569902, + -0.97082037 -0.04764092 -0.23502809, + -0.98384565 -0.035564188 -0.17545094, + -0.98239589 -0.029809697 -0.18441698, + -0.9917385 -0.020468991 -0.12663195, + -0.99086076 -0.015512196 -0.13399397, + -0.99695724 -0.0089643719 -0.077434018, + -0.99658149 -0.0054212129 -0.082438238, + -0.99965262 -0.0017294394 -0.026298791, + -0.99960464 -0.00037592885 -0.028113291, + -0.9996295 0.00036397917 0.027219612, + -0.9995715 -0.0012330695 0.029247288, + -0.99629748 -0.0036214716 0.085897535, + -0.99577838 -0.0082270857 0.09141995, + -0.98889321 -0.013321503 0.14803003, + -0.98849189 -0.015495198 0.15047799, + -0.97855467 -0.021099493 0.20490393, + -0.97786045 -0.02393561 0.2078851, + -0.96507186 -0.029966697 0.26026598, + -0.96375823 -0.034370106 0.26455405, + -0.94844788 -0.040831797 0.31429198, + -0.94641948 -0.046703123 0.31954515, + -0.92868012 -0.053636309 0.36698303, + -0.92580324 -0.061064214 0.37304109, + -0.90570211 -0.068480611 0.41834706, + -0.90182412 -0.077628709 0.42507306, + -0.87949568 -0.085498169 0.46816382, + -0.87446117 -0.096540019 0.47539213, + -0.85029799 -0.10474 0.51577401, + -0.84402168 -0.11773296 0.5232268, + -0.81819683 -0.12621297 0.56091386, + -0.81105018 -0.14036302 0.56788713, + -0.7834571 -0.14911401 0.60329103, + -0.77622581 -0.16299395 0.60902089, + -0.74682707 -0.17193002 0.64240909, + -0.73837966 -0.1878069 0.64770669, + -0.70769984 -0.19675395 0.67856383, + -0.69807595 -0.21458197 0.68311393, + -0.66621226 -0.22349508 0.71148527, + -0.65547681 -0.24321894 0.71497881, + -0.62231201 -0.252092 0.74106503, + -0.61053199 -0.27369499 0.74319702, + -0.57622433 -0.28243816 0.76693833, + -0.56357908 -0.30573303 0.76740211, + -0.52888995 -0.31410697 0.7884239, + -0.51555216 -0.33896613 0.78696132, + -0.48077375 -0.34687182 0.80531764, + -0.48310706 -0.34232903 0.80586511, + -0.4513602 -0.34889117 0.82130939, + -0.46554288 -0.31752792 0.82610279, + -0.43172416 -0.32362112 0.84195232, + -0.44354612 -0.29289305 0.8470422, + -0.40826014 -0.29832211 0.86274427, + -0.41805193 -0.26796198 0.86800289, + -0.38121685 -0.27269992 0.88335073, + -0.38923693 -0.24247497 0.88865089, + -0.35060504 -0.24652503 0.90349412, + -0.35704288 -0.21629493 0.9087007, + -0.31650901 -0.219653 0.92280799, + -0.3215099 -0.18945995 0.92775875, + -0.279645 -0.192101 0.94068903, + -0.28340292 -0.16186693 0.94524163, + -0.24052612 -0.16383207 0.95671648, + -0.24319997 -0.13346699 0.96074986, + -0.19906305 -0.13484403 0.97066522, + -0.20082805 -0.10432902 0.97405523, + -0.15577106 -0.10520004 0.98217535, + -0.15678802 -0.074781805 0.98479712, + -0.11146297 -0.075246282 0.99091578, + -0.11194398 -0.044850595 0.99270189, + -0.066800572 -0.045033477 0.99674952, + -0.0229441 -0.0150131 0.99962401, + -0.57850504 -0.31276402 -0.75333309, + 0.16433795 -0.3663899 -0.91583377, + 0.14961793 -0.36725783 -0.9180066, + 0.23961508 -0.60433424 -0.75984532, + 0.22124103 -0.58593506 -0.77957213, + 0.28818199 -0.77029401 -0.56885701, + 0.2462749 -0.77964473 -0.57576281, + 0.28225592 -0.89679372 -0.34072387, + 0.25101289 -0.96379155 -0.089990452, + 0.236889 -0.90819597 -0.345056, + 0.17328905 -0.98486227 0.0041620508, + 0.36111709 -0.014918503 0.93240124, + 0.0386522 0.115656 -0.99253702, + -0.61151969 -0.78800863 -0.071316063, + -0.60954297 -0.79057086 -0.058780193, + -0.33987215 -0.25741211 -0.90455842, + -0.3668029 -0.25462794 -0.89477378, + -0.35589099 -0.219442 -0.90839797, + -0.29181987 -0.16809994 -0.94158566, + -0.26558602 -0.16943802 -0.94908112, + -0.25421995 -0.15437198 -0.95474678, + -0.25024894 -0.15096897 -0.95633876, + -0.32827297 -0.14728898 -0.93302888, + -0.37548009 -0.18464205 -0.90825224, + -0.46101278 -0.17678592 -0.8696056, + -0.5090968 -0.21320993 -0.8338837, + -0.59454405 -0.19917703 -0.77900314, + -0.64314634 -0.23625414 -0.7283864, + -0.71852207 -0.21458302 -0.66157407, + -0.73107004 -0.22472003 -0.64423406, + -0.79489291 -0.19983597 -0.57289696, + -0.8096239 -0.21298197 -0.54694396, + -0.85986698 -0.185247 -0.475723, + -0.87123102 -0.197281 -0.449485, + -0.90876573 -0.16771495 -0.38212091, + -0.91212839 -0.17217109 -0.37199318, + -0.9400481 -0.14324802 -0.30949903, + -0.94108689 -0.14501798 -0.30549198, + -0.96163833 -0.11763904 -0.24781609, + -0.96131653 -0.11691495 -0.24940188, + -0.9763965 -0.091676652 -0.19556391, + -0.97563279 -0.089363381 -0.20038696, + -0.98656386 -0.066541493 -0.14921099, + -0.98587447 -0.063634031 -0.15492707, + -0.99339086 -0.043609597 -0.10617398, + -0.99293453 -0.040752281 -0.11144595, + -0.99765176 -0.023521895 -0.064325586, + -0.99745512 -0.021387102 -0.068013906, + -0.99974149 -0.0068200934 -0.021688912, + -0.9997161 -0.0059653712 -0.023070702, + -0.99973345 0.005779543 0.022352012, + -0.99970424 0.0047917608 0.023846006, + -0.99743533 0.014100605 0.070170723, + -0.99712187 0.010638599 0.075064689, + -0.99238563 0.017283695 0.12195095, + -0.99137914 0.010738701 0.13058402, + -0.98383921 0.014675104 0.17845204, + -0.98149562 0.0040829987 0.19144093, + -0.97066653 0.0051266579 0.24037488, + -0.96679324 -0.0081476523 0.25543007, + -0.95262778 -0.0096963979 0.30398393, + -0.95071876 -0.015155897 0.30968395, + -0.93421614 -0.017436402 0.35628104, + -0.93205577 -0.022984494 0.3615849, + -0.91336626 -0.025828106 0.40631908, + -0.91014576 -0.033444591 0.41293591, + -0.88929009 -0.036920305 0.45585105, + -0.88506424 -0.04627401 0.46316311, + -0.86240214 -0.050325606 0.50371605, + -0.85713184 -0.061405286 0.51142389, + -0.8327468 -0.066001683 0.54970586, + -0.82632858 -0.078965865 0.55762476, + -0.80012786 -0.084103391 0.59390396, + -0.79253018 -0.098994523 0.60174412, + -0.7645399 -0.10463499 0.63602692, + -0.75574511 -0.12150501 0.64349508, + -0.72663426 -0.12747204 0.67509526, + -0.71706796 -0.14560099 0.68162596, + -0.68686742 -0.15182209 0.71074843, + -0.67716205 -0.17017701 0.71588504, + -0.64548594 -0.17663799 0.74306595, + -0.63485318 -0.19685905 0.7471332, + -0.60183328 -0.20348111 0.77226436, + -0.59042102 -0.22544301 0.77497, + -0.55674207 -0.23203203 0.79762113, + -0.54472685 -0.25557992 0.79871869, + -0.51060998 -0.262041 0.81890899, + -0.49813306 -0.28711504 0.8181861, + -0.46346313 -0.29341105 0.83612919, + -0.45075011 -0.31981009 0.83339417, + -0.41569999 -0.32584801 0.84912699, + -0.40299806 -0.35335502 0.84423512, + -0.36844811 -0.35893312 0.8575623, + -0.3695991 -0.35624608 0.8581872, + -0.33763492 -0.36087891 0.86934984, + -0.34885088 -0.33024588 0.87706369, + -0.3148151 -0.3344661 0.88827026, + -0.3239359 -0.30416295 0.89585179, + -0.28776491 -0.30789989 0.90685672, + -0.29505888 -0.27774891 0.91421872, + -0.25730905 -0.28090307 0.92460024, + -0.26301703 -0.25071403 0.93164611, + -0.22379403 -0.25327304 0.94115311, + -0.22811393 -0.22294395 0.94776577, + -0.18733501 -0.22492804 0.95619714, + -0.19042791 -0.1946139 0.96221751, + -0.14823593 -0.19605091 0.96932453, + -0.15030299 -0.16565998 0.97466189, + -0.10732107 -0.1665951 0.98016757, + -0.108552 -0.136057 0.98473603, + -0.064988628 -0.13657705 0.98849547, + -0.065578617 -0.10592602 0.99220926, + -0.021639999 -0.10612898 0.9941169, + -0.021793295 -0.075577088 0.99690175, + 0.022381894 -0.075576082 0.99688876, + 0.0222381 -0.106182 0.99409801, + 0.066016488 -0.10597698 0.99217474, + 0.065436713 -0.13660403 0.98846221, + 0.108954 -0.13608301 0.98468798, + 0.10773604 -0.16652806 0.98013335, + 0.15074302 -0.16558805 0.97460622, + 0.14868902 -0.19592303 0.96928114, + 0.19100609 -0.19447809 0.96213049, + 0.1879169 -0.2248279 0.95610654, + 0.22871096 -0.22283797 0.94764686, + 0.22439189 -0.25321788 0.9410255, + 0.26360205 -0.25065306 0.93149722, + 0.25787404 -0.28098103 0.92441911, + 0.29554114 -0.27782613 0.91403943, + 0.28820303 -0.30817804 0.90662313, + 0.32423887 -0.30444688 0.89564568, + 0.31503299 -0.335031 0.88797998, + 0.34884408 -0.3308301 0.87684625, + 0.33756301 -0.361617 0.86907101, + 0.36924192 -0.35701892 0.85801983, + 0.36844298 -0.35888198 0.85758591, + 0.40301186 -0.35330188 0.84425068, + 0.41557294 -0.32610896 0.84908891, + 0.45060411 -0.3200731 0.83337218, + 0.46328813 -0.29374406 0.83610916, + 0.49787617 -0.28746009 0.81822127, + 0.51038003 -0.26234499 0.818955, + 0.54448199 -0.255885 0.79878801, + 0.55658603 -0.232173 0.79768902, + 0.59026569 -0.2255829 0.77504766, + 0.60186911 -0.20325404 0.77229619, + 0.63492399 -0.196631 0.74713302, + 0.64571792 -0.17608799 0.74299496, + 0.67741597 -0.16963698 0.71577293, + 0.68682724 -0.15183106 0.71078521, + 0.71703094 -0.14560999 0.68166292, + 0.72638208 -0.12789801 0.67528605, + 0.75551403 -0.121914 0.64368898, + 0.7642619 -0.10515098 0.63627595, + 0.79223287 -0.099495187 0.60205293, + 0.79983371 -0.084619768 0.59422678, + 0.82604915 -0.07945662 0.55796909, + 0.83249956 -0.066445373 0.55002677, + 0.8568933 -0.061824322 0.51177317, + 0.86226702 -0.0505399 0.50392598, + 0.88494331 -0.046473015 0.46337417, + 0.88929874 -0.036835793 0.45584089, + 0.9101541 -0.033367705 0.41292405, + 0.91348714 -0.025478704 0.40606907, + 0.93216556 -0.022670988 0.36132181, + 0.93439221 -0.016941004 0.3558431, + 0.95086914 -0.014722502 0.30924302, + 0.95268273 -0.0095267985 0.30381694, + 0.96683437 -0.0080047827 0.25527909, + 0.97054774 0.0047066091 0.24086294, + 0.98141402 0.0037491799 0.191866, + 0.98375487 0.014285098 0.17894799, + 0.9913311 0.010455201 0.13097101, + 0.99235487 0.017082598 0.12222899, + 0.99710989 0.010515699 0.075241789, + 0.99743187 0.014063098 0.07022699, + 0.99970376 0.0047790492 0.023865195, + 0.99973363 0.0057857782 0.022342592, + 0.99971622 -0.0059716315 -0.023060305, + 0.99974197 -0.0068347501 -0.0216648, + 0.99745965 -0.021431193 -0.067932576, + 0.99765736 -0.023582209 -0.064216524, + 0.99295276 -0.040853489 -0.11124697, + 0.99340802 -0.043714002 -0.10597, + 0.98591465 -0.063778877 -0.15461095, + 0.98660189 -0.066686392 -0.14889498, + 0.97570187 -0.08955849 -0.19996297, + 0.97646827 -0.091887824 -0.19510604, + 0.96144211 -0.11717401 -0.24879603, + 0.96182352 -0.11803594 -0.24690688, + 0.94137979 -0.14549997 -0.30435795, + 0.94040489 -0.14382999 -0.30814198, + 0.9126581 -0.17287502 -0.37036404, + 0.90810353 -0.1668431 -0.38407224, + 0.36598396 -0.26411498 -0.89235586, + 0.39393187 -0.26085591 -0.8813467, + 0.2716451 -0.16294307 -0.94850338, + 0.35336918 -0.21013111 -0.91157842, + 0.3506391 -0.20799008 -0.9131223, + 0.24906611 -0.14990108 -0.95681548, + 0.32697189 -0.14627095 -0.93364567, + 0.37563214 -0.18477006 -0.90816331, + 0.46120995 -0.17689998 -0.86947787, + 0.50743413 -0.21190305 -0.83522916, + 0.59298509 -0.19801505 -0.78048617, + 0.64331532 -0.23638612 -0.72819436, + 0.71865773 -0.21469992 -0.66138875, + 0.73842496 -0.23076896 -0.63361996, + 0.80080891 -0.20495997 -0.56275797, + 0.80691451 -0.21043389 -0.55191165, + 0.85781789 -0.18310298 -0.48023093, + 0.87030846 -0.19623189 -0.45172572, + 0.86687732 -0.17974406 -0.46499017, + 0.90966356 -0.14975493 -0.38740882, + 0.91243929 -0.15367106 -0.37926215, + 0.94016439 -0.12795104 -0.31578413, + 0.94027764 -0.12815395 -0.31536388, + 0.96104175 -0.10405798 -0.25606793, + 0.96013403 -0.10195 -0.260286, + 0.97563189 -0.08002159 -0.20430097, + 0.97454876 -0.076702788 -0.21064496, + 0.98594779 -0.057158284 -0.15697095, + 0.98504364 -0.053370681 -0.16383094, + 0.99299449 -0.03660002 -0.11235005, + 0.99242538 -0.033115711 -0.11830205, + 0.99748063 -0.019122493 -0.068312876, + 0.99723321 -0.016534904 -0.072474517, + 0.9997189 -0.0052740597 -0.023116898, + 0.99968725 -0.0042636008 -0.024645006, + 0.99970651 0.0041299784 0.02387259, + 0.99966913 0.0029458404 0.025555205, + 0.99713385 0.0086640595 0.07516069, + 0.99674052 0.0046279877 0.080540963, + 0.9913919 0.0075108591 0.13071199, + 0.99011421 -0.00014911203 0.14026403, + 0.98151624 -0.00020345204 0.19137904, + 0.97913122 -0.010184003 0.20297405, + 0.96701354 -0.012764393 0.25440487, + 0.96579909 -0.016796801 0.25874704, + 0.95125002 -0.0199793 0.30777299, + 0.94960326 -0.024721107 0.31247807, + 0.93276435 -0.028430309 0.35936412, + 0.93014234 -0.035201412 0.36550811, + 0.91101468 -0.039531887 0.41047484, + 0.90744269 -0.047984783 0.41742685, + 0.88611311 -0.052929007 0.46043706, + 0.88157743 -0.062943228 0.46782422, + 0.85840368 -0.068401679 0.50839382, + 0.85278499 -0.080152698 0.51607502, + 0.82793701 -0.0860705 0.55417699, + 0.82117188 -0.099641584 0.56191492, + 0.79451412 -0.10602602 0.59791803, + 0.7865417 -0.12151895 0.60546279, + 0.75820398 -0.128304 0.63926899, + 0.74957275 -0.14471996 0.64590776, + 0.72007775 -0.15170994 0.67710578, + 0.71142006 -0.16801201 0.68238807, + 0.68065178 -0.17514594 0.71136278, + 0.67047125 -0.19426507 0.71605122, + 0.63830221 -0.20155704 0.74293017, + 0.62713081 -0.22258694 0.74643284, + 0.59371388 -0.22994894 0.77112085, + 0.5818612 -0.25246409 0.77311027, + 0.54788774 -0.25968587 0.79522467, + 0.53544211 -0.28370607 0.79549515, + 0.50112283 -0.29069391 0.81509072, + 0.48829705 -0.31602702 0.81344509, + 0.45357579 -0.32274184 0.83072656, + 0.44064012 -0.34910208 0.82702118, + 0.40564683 -0.35545883 0.84208059, + 0.40673086 -0.35310289 0.84254873, + 0.37502107 -0.35830903 0.8549701, + 0.3873851 -0.32724109 0.86188519, + 0.3538008 -0.33199778 0.87441546, + 0.36399317 -0.30124414 0.88134044, + 0.32845092 -0.30548695 0.89375478, + 0.3366999 -0.27501693 0.90055478, + 0.29897997 -0.27870998 0.91265088, + 0.30553597 -0.24831897 0.91923088, + 0.26630107 -0.25137207 0.93053526, + 0.2713711 -0.22096308 0.93676734, + 0.23070607 -0.22338507 0.94703424, + 0.2344631 -0.19304708 0.95276433, + 0.19241403 -0.19487204 0.96177012, + 0.19504796 -0.16457295 0.96688777, + 0.151677 -0.16585401 0.97441602, + 0.15339206 -0.13544205 0.97883934, + 0.10950094 -0.13623995 0.98460555, + 0.11048596 -0.10564797 0.98824662, + 0.066321202 -0.106065 0.992145, + 0.066769622 -0.07545343 0.99491137, + 0.022475293 -0.075602971 0.99688464, + 0.022574907 -0.045035515 0.99873036, + -0.021903006 -0.045036212 0.99874526, + -0.021804808 -0.075580433 0.99690133, + -0.066216692 -0.07543239 0.99494988, + -0.065782167 -0.10598395 0.99218953, + -0.11002396 -0.10556896 0.98830664, + -0.10902904 -0.13619405 0.98466438, + -0.15300307 -0.13539805 0.97890633, + -0.15127203 -0.16593504 0.97446525, + -0.19461897 -0.16465698 0.96695989, + -0.19196901 -0.19504499 0.961824, + -0.23402703 -0.19322203 0.9528361, + -0.23027395 -0.22353594 0.94710374, + -0.27077103 -0.22112803 0.93690211, + -0.26571 -0.251432 0.93068802, + -0.30496505 -0.24838306 0.91940325, + -0.29843488 -0.27861691 0.91285771, + -0.3362439 -0.27492294 0.90075374, + -0.32804909 -0.30518007 0.89400727, + -0.36375004 -0.30092704 0.88154912, + -0.3536599 -0.33137992 0.8747068, + -0.38745207 -0.32660303 0.86209714, + -0.37517017 -0.35749018 0.85524744, + -0.40716591 -0.35224491 0.8426978, + -0.40565407 -0.35553002 0.8420471, + -0.44062701 -0.34917599 0.82699698, + -0.45372412 -0.32248309 0.83074617, + -0.48847705 -0.31576404 0.81343913, + -0.50135219 -0.2903221 0.81508231, + -0.53568184 -0.28333592 0.79546571, + -0.54810184 -0.25934991 0.7951867, + -0.58209991 -0.25212598 0.77304089, + -0.59385306 -0.22979003 0.77106112, + -0.62728792 -0.22242597 0.74634892, + -0.63824403 -0.20180003 0.74291408, + -0.67039698 -0.19450399 0.71605599, + -0.68041396 -0.17570299 0.71145296, + -0.71114093 -0.16856399 0.68254292, + -0.72010702 -0.15169001 0.67707902, + -0.74959594 -0.14470199 0.64588493, + -0.7584309 -0.12788899 0.63908297, + -0.78679198 -0.121113 0.60521901, + -0.7948063 -0.10551903 0.59761924, + -0.82143998 -0.0991605 0.56160802, + -0.82820868 -0.08556097 0.55384982, + -0.8530609 -0.079666495 0.51569396, + -0.85863811 -0.067982905 0.50805408, + -0.8817693 -0.062558122 0.46751419, + -0.88622409 -0.052712306 0.46024805, + -0.907547 -0.0477846 0.41722301, + -0.91099727 -0.039617416 0.41050515, + -0.93012524 -0.035278209 0.36554408, + -0.93264741 -0.028771713 0.35964018, + -0.94950461 -0.025020791 0.31275389, + -0.95110601 -0.0204194 0.308189, + -0.9656899 -0.017168999 0.25912997, + -0.96698225 -0.012886803 0.25451806, + -0.97910833 -0.010282304 0.20307907, + -0.98159701 0.000145873 0.190964, + -0.99015933 0.00010690104 0.13994505, + -0.9914391 0.007811971 0.13033602, + -0.99675989 0.0048124394 0.080291189, + -0.99714565 0.0087905973 0.074987873, + -0.99967051 0.0029886186 0.025494287, + -0.99970686 0.0041425894 0.023854697, + -0.99968755 -0.0042765983 -0.024626389, + -0.99971867 -0.0052669081 -0.023128593, + -0.99723065 -0.016513094 -0.07251408, + -0.99747574 -0.019072097 -0.068398587, + -0.99240887 -0.033031695 -0.11846299, + -0.99297535 -0.036489613 -0.11255503, + -0.98500162 -0.053211082 -0.16413493, + -0.98590475 -0.056982987 -0.15730496, + -0.97446722 -0.076472215 -0.21110605, + -0.97555715 -0.079801507 -0.20474403, + -0.96000123 -0.10168202 -0.26088005, + -0.96090537 -0.10377404 -0.25669408, + -0.94006824 -0.12780303 -0.3161301, + -0.93983978 -0.12739398 -0.31697291, + -0.91195971 -0.15300094 -0.38068384, + -0.90907079 -0.14894497 -0.3891089, + -0.87182128 -0.17510706 -0.45745516, + -0.86488813 -0.16724502 -0.47328407, + -0.8163588 -0.19242695 -0.54454589, + -0.089667074 -0.032117993 -0.99545377, + -0.09015099 -0.032617997 -0.99539387, + -0.14621601 -0.032399401 -0.98872203, + -0.18124704 -0.065014318 -0.98128623, + -0.249797 -0.064013503 -0.96618003, + -0.29216194 -0.10032897 -0.95109177, + -0.37125397 -0.097408585 -0.92340785, + -0.42507207 -0.14121501 -0.89407611, + -0.50979418 -0.13421604 -0.84976232, + -0.52723086 -0.14811897 -0.83671284, + -0.61017627 -0.13810304 -0.78013629, + -0.64196795 -0.16382599 -0.74902493, + -0.70103616 -0.15237203 -0.69665718, + -0.74740106 -0.19191302 -0.63605106, + -0.79728532 -0.17435905 -0.5778712, + -0.79725879 -0.17431895 -0.5779199, + -0.7346378 -0.19592595 -0.64955384, + -0.71142679 -0.17651996 -0.68022984, + -0.63591093 -0.19385198 -0.74701995, + -0.62014878 -0.18136793 -0.76323068, + -0.53675699 -0.195067 -0.82087803, + -0.48280883 -0.15292095 -0.86227071, + -0.39763591 -0.16022296 -0.90344578, + -0.35041797 -0.12236299 -0.92856586, + -0.27183488 -0.12572794 -0.95409554, + -0.22963311 -0.089608647 -0.96914345, + -0.16217692 -0.090849958 -0.98257053, + -0.16344796 -0.09204448 -0.98224878, + -0.39800009 -0.34702209 -0.84921819, + -0.53343481 -0.47842282 -0.69753778, + -0.50376606 -0.48860306 -0.71238106, + -0.37291098 -0.35169896 -0.85862988, + -0.39831999 -0.347673 -0.84880197, + -0.25419608 -0.20603707 -0.94495136, + -0.27770594 -0.20465496 -0.93861377, + -0.17622794 -0.11091396 -0.97808063, + -0.18536301 -0.11072502 -0.97641212, + -0.32110688 -0.23015492 -0.91865063, + -0.29576203 -0.23215203 -0.92662311, + -0.45092911 -0.37771708 -0.80869818, + -0.46981606 -0.37357202 -0.79982311, + -0.46854281 -0.37118587 -0.80167872, + -0.59227675 -0.48026583 -0.64695674, + -0.5465399 -0.49915987 -0.67240882, + -0.62675881 -0.5779689 -0.52261388, + -0.58306295 -0.60260493 -0.54488993, + -0.63753301 -0.662094 -0.393933, + -0.59540069 -0.69045866 -0.41080979, + -0.63200104 -0.73479909 -0.24626203, + -0.59061098 -0.76512998 -0.25642699, + -0.13475594 -0.10127696 -0.98568952, + -0.11904501 -0.10148201 -0.98768914, + -0.27226695 -0.28472993 -0.91912979, + -0.25188297 -0.28636798 -0.92441785, + -0.38458177 -0.45557174 -0.80283952, + -0.36174679 -0.46010473 -0.81082851, + -0.470889 -0.60820597 -0.63902199, + -0.47024989 -0.59738886 -0.64960885, + -0.5495742 -0.70302624 -0.45135614, + -0.50604099 -0.72580099 -0.465978, + -0.41507486 -0.85242271 -0.31794387, + -0.45982495 -0.8320179 -0.31033397, + -0.45965478 -0.83440161 -0.30412385, + -0.50411206 -0.8114211 -0.29574803, + -0.53033477 -0.84245461 -0.094948754, + -0.52499402 -0.84883499 -0.062132198, + -0.5039981 -0.81385916 -0.28917006, + -0.5479852 -0.78821331 -0.2800571, + -0.54791987 -0.79070783 -0.27306595, + -0.59063673 -0.76273566 -0.26340589, + -0.55103493 -0.70966393 -0.43901893, + -0.59388125 -0.68421125 -0.42327315, + -0.53404301 -0.612082 -0.58322698, + -0.57791007 -0.59082907 -0.56297505, + -0.46383411 -0.46748713 -0.7525382, + -0.46577278 -0.47424975 -0.74708962, + -0.33999789 -0.33613887 -0.87830073, + -0.36421087 -0.33288288 -0.8697927, + -0.2155001 -0.17944609 -0.95987445, + -0.23705903 -0.17852601 -0.95495111, + -0.107965 -0.053649899 -0.992706, + -0.10251202 -0.053680912 -0.99328226, + -0.19959795 -0.15239497 -0.96795475, + -0.18008794 -0.15298094 -0.97168165, + -0.33178598 -0.31733698 -0.8883779, + -0.30875596 -0.31995597 -0.89571089, + -0.44690895 -0.47943494 -0.7552579, + -0.4092561 -0.45657212 -0.78996921, + -0.52896982 -0.59950578 -0.60065275, + -0.49929905 -0.61207205 -0.61324406, + -0.38732791 -0.4676939 -0.79450583, + -0.41074592 -0.46252289 -0.78572279, + -0.27933601 -0.30320299 -0.91106498, + -0.30103213 -0.30112511 -0.90482229, + -0.14805499 -0.12704599 -0.98078489, + -0.16557404 -0.12668903 -0.97802621, + -0.046444595 0.00032256698 -0.99892086, + -0.044149697 0.00032260397 -0.99902487, + -0.031275406 0.025349906 -0.99918926, + -0.020605301 0.025356904 -0.99946612, + -0.10704906 -0.076499134 -0.99130648, + -0.093105875 -0.076606981 -0.99270475, + -0.24542002 -0.26814103 -0.93159515, + -0.22624694 -0.26942796 -0.93606675, + -0.35924289 -0.44794786 -0.81871068, + -0.33710486 -0.45189479 -0.82592458, + -0.4513078 -0.61522168 -0.6463927, + -0.42343292 -0.5988639 -0.67975479, + -0.50475585 -0.71911383 -0.47759488, + -0.46070519 -0.73934925 -0.49103317, + -0.37814915 -0.59812021 -0.70658022, + -0.45962995 -0.73262495 -0.50199693, + -0.41589892 -0.75019681 -0.51403588, + -0.33515596 -0.59558094 -0.73003691, + -0.41507486 -0.74358875 -0.52420282, + -0.37182197 -0.7587229 -0.53487194, + -0.4152981 -0.8501792 -0.32360908, + -0.3701759 -0.86819482 -0.33046591, + -0.3908129 -0.91780174 -0.070036985, + -0.35742411 -0.93394136 -0.0013078605, + -0.35447398 -0.9263339 -0.12748998, + -0.35457113 -0.92629737 -0.12748605, + -0.35752192 -0.93390375 -0.0013610696, + -0.29791602 -0.95128411 -0.07940121, + -0.28013405 -0.89333326 -0.35139808, + -0.32529899 -0.87998003 -0.34614399, + -0.28575391 -0.77033371 -0.57002681, + -0.32813087 -0.7593447 -0.56189483, + -0.25600684 -0.58726865 -0.76783854, + -0.11894899 -0.98289585 -0.14059499, + -0.11879405 -0.98291433 -0.14059705, + -0.15843804 -0.98235822 -0.099346824, + -0.14800496 -0.91658074 -0.3714489, + -0.19201402 -0.90954214 -0.36859703, + -0.16495205 -0.7784853 -0.60560024, + -0.2044569 -0.77262366 -0.60104072, + -0.15792105 -0.59163314 -0.79058915, + -0.19093002 -0.58812904 -0.78590709, + -0.11774303 -0.3528761 -0.92823225, + -0.14132001 -0.35178199 -0.92535299, + -0.059850808 -0.11409701 -0.99166512, + -0.053558808 -0.11413801 -0.99202013, + -0.022262799 -0.99120986 -0.13041198, + -0.021926206 -0.99131823 -0.12964404, + -0.0220678 -0.99131501 -0.12964401, + -0.06718903 -0.99057847 -0.11933106, + -0.062726386 -0.92412877 -0.37689692, + -0.105211 -0.92081302 -0.375545, + -0.089524254 -0.78050464 -0.6187067, + -0.12707798 -0.77729785 -0.61616492, + -0.096180581 -0.58295888 -0.8067888, + -0.12662698 -0.58095992 -0.80402189, + -0.074257895 -0.33042097 -0.9409079, + -0.094376162 -0.32985687 -0.93930167, + -0.02852531 -0.07855773 -0.99650139, + -0.037369292 -0.078534774 -0.99621075, + 0.038434297 0.15916298 -0.9865039, + 0.041472796 0.15914398 -0.98638386, + 0.073758803 0.2441 -0.966941, + 0.081164904 0.24395902 -0.9663831, + 0.079913802 0.241142 -0.96719402, + 0.072417863 0.24128088 -0.96774954, + 0.072098598 0.240668 -0.96792603, + 0.060080417 0.24086106 -0.96869826, + 0.058018021 0.23745909 -0.96966338, + 0.040680818 0.23766312 -0.97049546, + 0.034622092 0.22898194 -0.97281474, + 0.010490997 0.22910695 -0.97334474, + 0.010860196 0.22956991 -0.97323161, + -0.018406203 0.22954406 -0.97312427, + -0.036512498 0.20940597 -0.97714686, + -0.07535021 0.20895003 -0.9750191, + -0.10330603 0.18076305 -0.97808623, + -0.154287 0.17955901 -0.971573, + -0.18336706 0.15238807 -0.97116137, + -0.24587491 0.15025695 -0.95758462, + -0.28109413 0.11894606 -0.95228046, + -0.353443 0.115944 -0.92824298, + -0.38512081 0.088264354 -0.91863561, + -0.46295795 0.084774889 -0.88231689, + -0.48568276 0.064658269 -0.87174058, + -0.56421804 0.061070208 -0.82336414, + -0.57699096 0.049305592 -0.81526089, + -0.65221369 0.045761079 -0.75665265, + -0.65586215 0.04218531 -0.75370115, + -0.72474962 0.03850428 -0.68793565, + -0.72164518 0.041799311 -0.69100016, + -0.78324085 0.037539694 -0.62058395, + -0.77548516 0.04656731 -0.62964618, + -0.83017039 0.041120019 -0.55599123, + -0.82018518 0.053998113 -0.56954414, + -0.8684687 0.046791285 -0.49353081, + -0.85753256 0.062582768 -0.51060873, + -0.89965874 0.053113688 -0.43335092, + -0.88904613 0.070468009 -0.45236206, + -0.92558497 0.058265202 -0.37402901, + -0.91551614 0.07718581 -0.39480707, + -0.94708955 0.06158457 -0.31500584, + -0.94089735 0.075445428 -0.33018211, + -0.96675187 0.056962293 -0.24929097, + -0.9663915 0.058020473 -0.25044188, + -0.98409635 0.040091414 -0.17305206, + -0.98374754 0.041608382 -0.17466991, + -0.99457598 0.024102701 -0.101182, + -0.99441034 0.025369609 -0.10249203, + -0.99943274 0.0080919284 -0.032690991, + -0.99941242 0.008585575 -0.033181582, + -0.99945134 -0.0082974229 0.03206791, + -0.99942964 -0.0088498574 0.032590687, + -0.99509376 -0.025926894 0.095479079, + -0.99488527 -0.027763808 0.097121522, + -0.98659998 -0.044845 0.156874, + -0.98599535 -0.04817652 0.15966307, + -0.97403365 -0.065401778 0.21675092, + -0.97279924 -0.070453614 0.22067606, + -0.9573549 -0.087870091 0.27522796, + -0.95551223 -0.093972825 0.27958107, + -0.93713367 -0.11118396 0.33078489, + -0.93537414 -0.11619201 0.33402804, + -0.91435379 -0.13303196 0.3824389, + -0.9117319 -0.13968998 0.38630494, + -0.88810831 -0.15630206 0.43224216, + -0.88432574 -0.16504596 0.43672392, + -0.8581816 -0.18147591 0.48019877, + -0.85314286 -0.19223997 0.48496494, + -0.82489699 -0.20830899 0.52550203, + -0.81839073 -0.22131793 0.53033483, + -0.78814131 -0.2370441 0.56801718, + -0.78009486 -0.25225297 0.57255596, + -0.747769 -0.267694 0.60760301, + -0.73803002 -0.285245 0.61151201, + -0.70379674 -0.30030888 0.64380479, + -0.70859176 -0.29175988 0.64247477, + -0.67807525 -0.30390513 0.66922021, + -0.69447774 -0.2722199 0.66603076, + -0.66334873 -0.2831139 0.69268674, + -0.67737406 -0.25276303 0.69085103, + -0.6449948 -0.26257294 0.71766084, + -0.65705228 -0.2330461 0.71691835, + -0.62324005 -0.24176003 0.74372303, + -0.63358182 -0.21270895 0.74386084, + -0.59860605 -0.22023302 0.77017415, + -0.60740322 -0.19139607 0.77099228, + -0.57105494 -0.19778597 0.79672891, + -0.57838005 -0.16918302 0.79803109, + -0.54026204 -0.17451902 0.82320112, + -0.54623419 -0.14595006 0.82481933, + -0.50612503 -0.15027602 0.84926713, + -0.51085597 -0.121542 0.85103101, + -0.46937183 -0.12484196 0.87413073, + -0.47292799 -0.095923796 0.87586403, + -0.42999378 -0.098289557 0.89746559, + -0.43245307 -0.069511205 0.89897311, + -0.38807586 -0.071050778 0.91888463, + -0.34190008 -0.072102718 0.93696624, + -0.38715693 -0.070742793 0.91929591, + -0.38487408 -0.099959426 0.91754025, + -0.42865992 -0.097846977 0.89815176, + -0.4253059 -0.12717597 0.89606977, + -0.46746087 -0.12421897 0.87524277, + -0.46295005 -0.15339701 0.8730101, + -0.50368607 -0.14950301 0.85085213, + -0.49792701 -0.178499 0.84864998, + -0.53725517 -0.17360106 0.8253603, + -0.53011692 -0.20261496 0.82336086, + -0.56748921 -0.19675007 0.7995283, + -0.55883908 -0.22597703 0.79789311, + -0.59449375 -0.21911693 0.77366972, + -0.58424187 -0.24854393 0.7725848, + -0.61862791 -0.24061294 0.7479338, + -0.60659599 -0.27046901 0.74758798, + -0.63988119 -0.26144207 0.7226342, + -0.62580782 -0.29205194 0.72323585, + -0.65771806 -0.28205004 0.69846606, + -0.64118993 -0.31390098 0.70024395, + -0.6718868 -0.30296794 0.67585385, + -0.66740704 -0.31087303 0.67670208, + -0.70183074 -0.29736787 0.64730674, + -0.71256465 -0.27841687 0.6439997, + -0.74586403 -0.26432604 0.61140704, + -0.75500584 -0.24758095 0.60718191, + -0.78636086 -0.23325297 0.57203996, + -0.79397231 -0.21867907 0.56726319, + -0.82331151 -0.20415989 0.52960068, + -0.82942313 -0.19182703 0.52465206, + -0.85683787 -0.17704898 0.48423395, + -0.8616302 -0.16675505 0.47936013, + -0.88703376 -0.15169796 0.4360719, + -0.89056587 -0.14352098 0.43161795, + -0.91354769 -0.12833695 0.38595384, + -0.91607171 -0.12194396 0.38202384, + -0.93657124 -0.10657603 0.3338801, + -0.93918663 -0.099134065 0.32878688, + -0.95700061 -0.08374127 0.27773592, + -0.95892847 -0.077321336 0.27290612, + -0.97383976 -0.061943684 0.21862996, + -0.97496438 -0.057317823 0.21484707, + -0.98651087 -0.042195495 0.15816398, + -0.98706222 -0.039151911 0.15548404, + -0.99506563 -0.02422769 0.096215665, + -0.99525797 -0.022533201 0.094624601, + -0.9994489 -0.007689679 0.032291595, + -0.99946898 -0.0071791802 0.0317844, + -0.99943167 0.0074272272 -0.032882489, + -0.99945015 0.0069786711 -0.032414604, + -0.99458265 0.021878192 -0.10161997, + -0.99471927 0.020841705 -0.10049503, + -0.98417813 0.035980504 -0.17349002, + -0.98444813 0.034820404 -0.17219001, + -0.96713197 0.050399501 -0.24923, + -0.97080314 0.039375104 -0.23662403, + -0.94792014 0.052281909 -0.31418803, + -0.95447546 0.036644917 -0.29603016, + -0.92690802 0.0461041 -0.372446, + -0.93447465 0.03097209 -0.35467988, + -0.90172511 0.037607905 -0.43067107, + -0.91015702 0.023134399 -0.41361701, + -0.87160611 0.027375404 -0.48944205, + -0.88000703 0.0148014 -0.47473001, + -0.83485919 0.017154204 -0.55019611, + -0.84229028 0.0073436326 -0.53897417, + -0.79010397 0.0083510904 -0.61291599, + -0.79456514 0.0031001805 -0.60717106, + -0.73454219 0.0034646608 -0.67855418, + -0.73390096 0.0041453796 -0.67924392, + -0.66560417 0.0045545609 -0.74629116, + -0.65699881 0.012920598 -0.75378084, + -0.58140379 0.013944095 -0.8134957, + -0.56251508 0.031122504 -0.82620114, + -0.48315713 0.032957409 -0.87491316, + -0.452865 0.059418101 -0.889597, + -0.3746101 0.061790716 -0.92512125, + -0.33688885 0.094445258 -0.93679559, + -0.26522794 0.096716374 -0.95932275, + -0.23073809 0.12737805 -0.96464235, + -0.16951798 0.12901498 -0.97704589, + -0.13364205 0.16281205 -0.97756433, + -0.085419975 0.16368395 -0.98280776, + -0.061112378 0.18859492 -0.98015165, + -0.023766397 0.18889397 -0.9817099, + -0.021924006 0.19100004 -0.98134524, + 0.0092819082 0.19103795 -0.98153877, + 0.019836506 0.20467904 -0.97862822, + 0.042870704 0.20453003 -0.97792113, + 0.047918908 0.21197703 -0.97609913, + 0.064561203 0.211778 -0.97518301, + 0.06705863 0.21602011 -0.97408348, + 0.078421026 0.21584107 -0.97327435, + 0.08149717 0.22191292 -0.97165465, + 0.075625487 0.22201595 -0.97210574, + 0.038583007 0.13769303 -0.98972327, + 0.037093502 0.137701 -0.989779, + -0.050064009 -0.095005013 -0.9942171, + -0.03947458 -0.095049955 -0.99468952, + -0.11653806 -0.34008616 -0.9331454, + -0.094852298 -0.34087601 -0.93531102, + -0.15795298 -0.58434892 -0.79598188, + -0.12630795 -0.58703876 -0.79964471, + -0.16535099 -0.7753579 -0.60949093, + -0.12663205 -0.77985132 -0.61302227, + -0.14819904 -0.91601527 -0.37276408, + -0.10509104 -0.92111439 -0.37483913, + -0.11222301 -0.98451209 -0.13469201, + -0.11935297 -0.98743874 -0.10353497, + -0.12000702 -0.99276513 0.0039736005, + -0.12015503 -0.99274725 0.0039735911, + -0.119999 -0.99276602 0.0039875, + -0.16852292 -0.98568255 -0.0054698973, + -0.16681498 -0.97579986 -0.14137699, + -0.16673002 -0.9758141 -0.14137901, + -0.20493603 -0.97446209 -0.091787905, + -0.19172397 -0.91052788 -0.36630696, + -0.23607901 -0.90151501 -0.362681, + -0.20412596 -0.77666885 -0.59591788, + -0.244497 -0.76929402 -0.59026098, + -0.19131291 -0.5969677 -0.77912062, + -0.22589993 -0.59247988 -0.77326381, + -0.14355201 -0.36704701 -0.91905898, + -0.16367006 -0.36588711 -0.91615433, + -0.17862798 -0.37330797 -0.91034788, + -0.16340208 -0.37431017 -0.9127934, + -0.25465408 -0.59811324 -0.75987631, + -0.22680187 -0.60238564 -0.76530552, + -0.28572491 -0.76498473 -0.57719982, + -0.24431796 -0.77407187 -0.58405596, + -0.28046501 -0.89173198 -0.35518101, + -0.23575106 -0.90283322 -0.35960209, + -0.21457796 -0.96673876 -0.13918497, + -0.25144696 -0.9641369 -0.084937893, + -0.26183689 -0.95545954 -0.13615593, + -0.26178887 -0.95547253 -0.13615695, + -0.26420513 -0.96419746 -0.022783911, + -0.31126085 -0.9503215 0.0023617588, + -0.30848911 -0.94196433 -0.13243005, + -0.30843315 -0.94198245 -0.13243206, + -0.31120497 -0.95033985 0.0023566799, + -0.31138888 -0.95027965 0.0023566291, + -0.30862284 -0.94194353 -0.13226594, + -0.34443 -0.93582797 -0.074793696, + -0.32498688 -0.88183969 -0.34167588, + -0.37044981 -0.86611259 -0.33558285, + -0.32841396 -0.76528591 -0.55360794, + -0.37126404 -0.75231713 -0.54422605, + -0.29458901 -0.59191501 -0.75023597, + -0.096440434 -0.15648706 -0.98296034, + 0.022008901 0.08350721 -0.9962641, + 0.024141004 0.083503105 -0.99621511, + -0.10845298 -0.16134596 -0.98092073, + -0.097053356 -0.16153793 -0.98208255, + -0.21133192 -0.38904786 -0.89664972, + -0.19468592 -0.39042184 -0.89981568, + -0.29370204 -0.60267204 -0.74197406, + -0.27629703 -0.60593504 -0.74599105, + -0.17856905 -0.38220009 -0.90666223, + -0.194515 -0.381024 -0.90387201, + -0.079057232 -0.13627705 -0.98751134, + -0.073973969 -0.13633096 -0.98789763, + -0.073659606 -0.13144502 -0.98858315, + 0.03196789 0.11266496 -0.99311864, + 0.031527691 0.11266597 -0.99313265, + 0.073336266 0.19609591 -0.97783852, + 0.077471986 0.19603495 -0.97753179, + 0.071977064 0.18643291 -0.97982752, + 0.056005485 0.18662396 -0.98083377, + 0.050610408 0.17844102 -0.98264813, + 0.028370401 0.178598 -0.983513, + 0.019368198 0.16664998 -0.9858259, + -0.010511303 0.16667207 -0.98595637, + -0.026851695 0.14747797 -0.98870075, + -0.066461377 0.14720494 -0.98687065, + -0.071086764 0.14234893 -0.98726052, + -0.11795203 0.14171404 -0.98285526, + -0.14887998 0.11226597 -0.98246175, + -0.20759195 0.11105797 -0.97189075, + -0.25087607 0.072543517 -0.96529722, + -0.32173812 0.070955426 -0.94416636, + -0.3596471 0.038392909 -0.93229824, + -0.43801394 0.036988895 -0.89820689, + -0.47494093 0.0052749496 -0.8800019, + -0.55519402 0.0049854601 -0.83170599, + -0.58125889 -0.018262396 -0.81351382, + -0.6575228 -0.016909396 -0.75324482, + -0.67134321 -0.030124007 -0.74053419, + -0.73944384 -0.027362993 -0.67266184, + -0.74408478 -0.032242388 -0.66730678, + -0.80293584 -0.028766593 -0.59537089, + -0.80143011 -0.026993403 -0.59747905, + -0.8516283 -0.02365621 -0.5236122, + -0.84676111 -0.017145703 -0.53169703, + -0.88928598 -0.0147407 -0.45711401, + -0.88284898 -0.0048516402 -0.469632, + -0.91846037 -0.0040857312 -0.39549214, + -0.91192585 0.0075764488 -0.41028494, + -0.94157398 0.0062185102 -0.33674899, + -0.93554688 0.018909998 -0.35269597, + -0.96002823 0.014985603 -0.27950206, + -0.95509362 0.027547991 -0.29502088, + -0.97491264 0.020694492 -0.22162393, + -0.97114211 0.032789104 -0.23623703, + -0.98637223 0.022619305 -0.16296704, + -0.98456424 0.030576207 -0.17233205, + -0.99484688 0.017712198 -0.099829383, + -0.99472713 0.018610202 -0.10085402, + -0.99946475 0.0059364587 -0.032171294, + -0.99944925 0.0063080415 -0.032578409, + -0.99948525 -0.0060987715 0.031497706, + -0.9994669 -0.0065632393 0.031982195, + -0.99541026 -0.019238103 0.093746021, + -0.99523222 -0.020803906 0.09529002, + -0.98749036 -0.033632711 0.15405107, + -0.98697925 -0.036455806 0.15666205, + -0.97581124 -0.04954851 0.21292605, + -0.97478187 -0.053794291 0.21657898, + -0.96035975 -0.067197986 0.27054295, + -0.95859414 -0.073110506 0.27523103, + -0.94136226 -0.086619921 0.32608908, + -0.93864489 -0.094398282 0.33171496, + -0.91874987 -0.10807198 0.37976193, + -0.91527909 -0.11687002 0.38549405, + -0.89288068 -0.13064395 0.43092486, + -0.8894971 -0.13847001 0.43545505, + -0.86478621 -0.15216704 0.47852913, + -0.86027414 -0.16189002 0.48344606, + -0.83361381 -0.17538996 0.52376187, + -0.82779181 -0.18721895 0.52887589, + -0.79930001 -0.200532 0.566486, + -0.79211468 -0.21443492 0.57146484, + -0.76162201 -0.227662 0.60671401, + -0.75296885 -0.24373494 0.61125386, + -0.72056675 -0.2568199 0.64407074, + -0.71042997 -0.27502596 0.64780396, + -0.67686898 -0.28766301 0.67756802, + -0.66526568 -0.30796286 0.68013269, + -0.63071072 -0.32009384 0.70692563, + -0.63481694 -0.31284797 0.70649391, + -0.60361093 -0.32281598 0.72900194, + -0.62003988 -0.29091293 0.72864282, + -0.58744693 -0.30006897 0.75157487, + -0.60138077 -0.26929292 0.75221169, + -0.56771791 -0.27746993 0.77505285, + -0.57956606 -0.24737804 0.77647114, + -0.54469019 -0.25457609 0.79906428, + -0.55471814 -0.22486606 0.80107617, + -0.51814592 -0.23114997 0.82346487, + -0.52654493 -0.20159297 0.8258999, + -0.488051 -0.20696899 0.84792101, + -0.49491605 -0.17759801 0.8505981, + -0.45502114 -0.18200006 0.8716833, + -0.46050811 -0.15264003 0.87443316, + -0.41926116 -0.15611506 0.8943423, + -0.42349085 -0.12659895 0.89701068, + -0.38055894 -0.12923399 0.9156819, + -0.38365316 -0.09956494 0.91809434, + -0.33907908 -0.10142802 0.93527424, + -0.34114715 -0.071857035 0.93725944, + -0.29572016 -0.073023938 0.95247948, + -0.24955308 -0.073779933 0.96554637, + -0.29501513 -0.072799422 0.95271534, + -0.29318103 -0.10266201 0.9505291, + -0.33792716 -0.10106404 0.9357304, + -0.33512211 -0.13103405 0.93301839, + -0.37886882 -0.12870795 0.91645658, + -0.37496409 -0.15852804 0.91338426, + -0.41699579 -0.15542692 0.89552057, + -0.41186684 -0.18508895 0.89224869, + -0.45218286 -0.18116494 0.87333268, + -0.44568378 -0.21082589 0.87001055, + -0.48463717 -0.20600407 0.85011131, + -0.47661093 -0.23580196 0.84689987, + -0.51409906 -0.23006603 0.82630014, + -0.50441927 -0.25998613 0.8233884, + -0.54005307 -0.25341502 0.80257314, + -0.52853721 -0.28365314 0.80011839, + -0.56248307 -0.27626902 0.7792871, + -0.54886287 -0.30711794 0.77744985, + -0.58161205 -0.29887202 0.75657314, + -0.56549329 -0.33073214 0.75553536, + -0.59712714 -0.32166708 0.73482621, + -0.59345001 -0.32822299 0.73490602, + -0.62840182 -0.3172189 0.71026981, + -0.64069223 -0.29569113 0.70857626, + -0.67453873 -0.28430784 0.68129772, + -0.68553704 -0.26472303 0.67820406, + -0.71829182 -0.25297993 0.64811879, + -0.72792292 -0.23542698 0.64397395, + -0.75948828 -0.22336207 0.61097223, + -0.76770115 -0.20793103 0.60613507, + -0.79737788 -0.19581898 0.57082695, + -0.80422914 -0.18245402 0.56562006, + -0.8319571 -0.17033401 0.52804708, + -0.83747786 -0.15906498 0.52280897, + -0.86342686 -0.14684099 0.48262995, + -0.86775088 -0.13751498 0.47759596, + -0.89181721 -0.12517403 0.43473408, + -0.89619428 -0.11502705 0.42849115, + -0.91797978 -0.10283197 0.3830649, + -0.92154163 -0.09374547 0.37679285, + -0.94084877 -0.081805676 0.32880291, + -0.94334489 -0.074618593 0.32331496, + -0.96004498 -0.062932201 0.27267799, + -0.96167588 -0.057453293 0.26810196, + -0.97563988 -0.045968197 0.21450797, + -0.976596 -0.042022001 0.21093699, + -0.98741353 -0.030900786 0.15511192, + -0.98788714 -0.028288504 0.15257402, + -0.99538678 -0.017490696 0.094335474, + -0.99554998 -0.016062301 0.0928564, + -0.99948347 -0.005478153 0.031669315, + -0.99949878 -0.0050898585 0.031243892, + -0.99946409 0.0052636503 -0.032310702, + -0.99947864 0.0049161883 -0.031910889, + -0.99486578 0.015409696 -0.10002298, + -0.99548751 0.010627096 -0.094295852, + -0.9864729 0.018357798 -0.16289298, + -0.98828566 0.0098188166 -0.15229894, + -0.97514486 0.014255098 -0.22110897, + -0.97799766 0.0044667288 -0.20856793, + -0.96050179 0.0059582088 -0.27820995, + -0.96443522 -0.0046168608 -0.26427907, + -0.9424479 -0.0058401395 -0.33430198, + -0.94714421 -0.016154803 -0.3204011, + -0.92000097 -0.019735601 -0.39141899, + -0.925111 -0.0291271 -0.37857801, + -0.89191121 -0.034689806 -0.45087811, + -0.89644212 -0.041760605 -0.44118905, + -0.85598987 -0.048717994 -0.51469195, + -0.8586399 -0.052271493 -0.50990695, + -0.80994886 -0.059809793 -0.58344293, + -0.80843037 -0.058039024 -0.58572328, + -0.75024486 -0.065194793 -0.65793794, + -0.74154323 -0.056222517 -0.66854525, + -0.67315668 -0.06197077 -0.73689866, + -0.65315878 -0.043321684 -0.75598073, + -0.5758701 -0.046772812 -0.81620216, + -0.5431928 -0.018339993 -0.83940768, + -0.46212313 -0.019371204 -0.88660425, + -0.4241311 0.012733603 -0.90551126, + -0.34580782 0.013193393 -0.93821251, + -0.29711503 0.054708809 -0.95327312, + -0.22819503 0.055784408 -0.9720161, + -0.19100505 0.089007922 -0.97754526, + -0.13333896 0.089867674 -0.98698765, + -0.12538403 0.097595923 -0.98729622, + -0.075975738 0.098087944 -0.99227345, + -0.052561089 0.12325797 -0.99098176, + -0.014462095 0.12341595 -0.99224967, + -0.00046010618 0.14025505 -0.99011534, + 0.028540807 0.14019702 -0.98971224, + 0.037857186 0.15288495 -0.98751867, + 0.059217777 0.15272693 -0.98649263, + 0.068004221 0.16641305 -0.98370838, + 0.066149428 0.16643308 -0.98383147, + 0.010644501 0.068328008 -0.9976061, + 0.00636777 0.050198 -0.99871898, + -0.12293703 -0.17496604 -0.97686923, + -0.11053897 -0.17522195 -0.97830379, + -0.22918893 -0.3974739 -0.88853079, + -0.21176092 -0.39908084 -0.89212769, + -0.31674111 -0.61039925 -0.72600824, + -0.33469486 -0.60641873 -0.72127366, + -0.22988807 -0.4078961 -0.88361323, + -0.24809404 -0.40601707 -0.87954509, + -0.12555806 -0.18958409 -0.97380346, + -0.13897096 -0.18924193 -0.97204661, + 0.0067259278 0.050197981 -0.99871665, + -0.011667294 0.030990785 -0.99945152, + 0.052436888 0.13200797 -0.98986077, + 0.05005978 0.13202396 -0.98998165, + 0.011621702 0.012435202 -0.99985522, + -0.017296901 0.012434202 -0.99977314, + -0.15665302 -0.20418903 -0.9663161, + -0.14218293 -0.2046409 -0.96845549, + -0.268038 -0.41449001 -0.86968601, + -0.24906611 -0.4166742 -0.87427044, + -0.35947099 -0.613841 -0.70283699, + -0.37809119 -0.6089803 -0.69727337, + -0.26931894 -0.42561492 -0.8638978, + -0.28920597 -0.42305893 -0.85870886, + -0.160423 -0.220033 -0.96221101, + -0.17604904 -0.21943806 -0.95961124, + 0.0082616173 0.070710778 -0.99746263, + 0.025644995 0.093161575 -0.99532074, + 0.031917695 0.093144692 -0.99514091, + -0.041890603 -0.0082534812 -0.99908811, + -0.032505486 -0.0082563665 -0.99943751, + 0.0088109756 0.11332795 -0.99351853, + 0.039123282 0.11324495 -0.99279654, + 0.039780505 0.11413901 -0.99266809, + 0.010570899 0.11422299 -0.9933989, + -0.0035974013 0.096789934 -0.99529839, + -0.040618218 0.096710742 -0.99448347, + -0.060840592 0.074546196 -0.9953599, + -0.10848399 0.074243695 -0.99132186, + -0.14024505 0.042799514 -0.98919135, + -0.20062298 0.042347796 -0.97875285, + -0.21223895 0.031815294 -0.97669977, + -0.28077799 0.0312474 -0.95926398, + -0.32233202 -0.0040330403 -0.94661814, + -0.39979714 -0.0039051315 -0.91659528, + -0.45001614 -0.045623314 -0.89185429, + -0.53174978 -0.043267079 -0.84579557, + -0.56605792 -0.07237839 -0.82118189, + -0.64461499 -0.067123003 -0.76155502, + -0.67044294 -0.090444691 -0.73642796, + -0.73967576 -0.082033873 -0.66794479, + -0.75322247 -0.095595062 -0.65078241, + -0.81124818 -0.084976323 -0.57849413, + -0.81576389 -0.090132795 -0.57131892, + -0.86347359 -0.078602366 -0.49823177, + -0.86300433 -0.077978827 -0.49914217, + -0.90187597 -0.066679798 -0.42681801, + -0.89893061 -0.062062468 -0.43367279, + -0.93023312 -0.051987007 -0.36326802, + -0.92648113 -0.044960402 -0.37364602, + -0.95159036 -0.036720514 -0.30516812, + -0.94786775 -0.028274992 -0.31740692, + -0.96788448 -0.022306411 -0.25040412, + -0.96479303 -0.0136098 -0.262658, + -0.98043513 -0.0101858 -0.19657902, + -0.97815764 -0.0019100093 -0.20785592, + -0.98972303 -0.00131397 -0.142992, + -0.98834378 0.0056518684 -0.15213397, + -0.99611413 0.0032696605 -0.088011511, + -0.99550301 0.0083100302 -0.094364598, + -0.99954313 0.0026513801 -0.030107804, + -0.999479 0.0042184698 -0.0319997, + -0.99951261 -0.0040801484 0.030950289, + -0.99949723 -0.0044645811 0.031392708, + -0.99566615 -0.013094402 0.092073508, + -0.99552852 -0.014290494 0.093374453, + -0.98825276 -0.023120595 0.15106897, + -0.98781633 -0.025519209 0.15351807, + -0.97732663 -0.034720387 0.20887093, + -0.97643566 -0.038393587 0.21236593, + -0.9628911 -0.048015207 0.26558504, + -0.96137726 -0.053106513 0.27006206, + -0.94516999 -0.0630133 0.32044199, + -0.94285476 -0.069701985 0.32583192, + -0.92410511 -0.079938509 0.37368402, + -0.92080587 -0.088405095 0.37986994, + -0.89962101 -0.098979399 0.42530599, + -0.8951599 -0.10938998 0.43211395, + -0.87169832 -0.12026104 0.47505718, + -0.86638832 -0.13175105 0.48167717, + -0.8411122 -0.14269704 0.5216971, + -0.83580983 -0.15354897 0.52710986, + -0.80878729 -0.16448006 0.56463218, + -0.80226433 -0.17728008 0.57003832, + -0.7733379 -0.18827596 0.60539293, + -0.76548511 -0.20316803 0.61053705, + -0.7346788 -0.21420695 0.64370984, + -0.72551703 -0.23111403 0.64823705, + -0.69349498 -0.241947 0.67862099, + -0.68302 -0.26089001 0.682217, + -0.64989394 -0.27147198 0.70988792, + -0.63817096 -0.29238296 0.71221495, + -0.60384113 -0.30271706 0.73738617, + -0.59101522 -0.32543212 0.73810226, + -0.55574638 -0.33539322 0.76069546, + -0.5589819 -0.32950991 0.76089585, + -0.52741611 -0.33762708 0.77964115, + -0.5430398 -0.30588487 0.78201169, + -0.51019305 -0.31329903 0.80096614, + -0.52334422 -0.28244415 0.80395037, + -0.48878106 -0.28916702 0.82308912, + -0.49983588 -0.25883594 0.82653981, + -0.46341106 -0.26482004 0.84564811, + -0.47263011 -0.23474006 0.84942216, + -0.43479407 -0.23987202 0.86799514, + -0.44236493 -0.20989697 0.8719269, + -0.40303615 -0.21419108 0.88976628, + -0.40911201 -0.184287 0.89368099, + -0.36809099 -0.187782 0.91062999, + -0.37281209 -0.15788405 0.91437626, + -0.3300311 -0.16061704 0.93020523, + -0.33356404 -0.13055901 0.9336431, + -0.28969291 -0.13255195 0.94789666, + -0.29217598 -0.10235199 0.95087188, + -0.24736209 -0.10369604 0.96335834, + -0.24895009 -0.073592126 0.96571636, + -0.20337392 -0.074396372 0.97627062, + -0.16929007 -0.016128106 0.98543435, + -0.15845996 -0.014096996 0.98726475, + -0.15811898 -0.044741996 0.98640591, + -0.20424007 -0.044356816 0.97791535, + -0.20460998 -0.044471998 0.97783285, + -0.25058991 -0.043983486 0.96709365, + -0.26497397 -0.016178098 0.96411985, + -0.25154603 -0.014275902 0.96774012, + -0.25102091 -0.044121087 0.96697563, + -0.29693297 -0.043524697 0.95390588, + -0.29741785 -0.043683376 0.95374751, + -0.34326288 -0.042973787 0.93825567, + -0.34451091 -0.014536897 0.93866974, + -0.3438381 -0.043167312 0.93803626, + -0.38956186 -0.042338487 0.92002666, + -0.3909241 -0.012563803 0.92033726, + -0.39015001 -0.042542499 0.91976798, + -0.43500879 -0.041603383 0.89946461, + -0.43340299 -0.069839202 0.89849001, + -0.47695011 -0.068113312 0.87628722, + -0.47435406 -0.096410312 0.8750391, + -0.51657605 -0.093771718 0.85109115, + -0.51285315 -0.12221003 0.84973317, + -0.55368274 -0.11854494 0.82424659, + -0.54880184 -0.14678393 0.82296473, + -0.58755577 -0.14208396 0.79661173, + -0.58145779 -0.17014293 0.79558671, + -0.61838108 -0.16435002 0.7685011, + -0.61097795 -0.19245097 0.76789886, + -0.6464172 -0.18548304 0.7400952, + -0.63759369 -0.2138069 0.74010867, + -0.67185456 -0.20556588 0.71158558, + -0.66155773 -0.23416291 0.71239674, + -0.69423878 -0.22474892 0.68375474, + -0.68232608 -0.25383404 0.68556505, + -0.71367085 -0.24322094 0.65689981, + -0.69989079 -0.27318895 0.65993983, + -0.73053837 -0.26118812 0.63094729, + -0.71450824 -0.29255912 0.63552123, + -0.74480516 -0.27903306 0.60614014, + -0.73979378 -0.28816491 0.60800177, + -0.7731517 -0.2716279 0.57310981, + -0.78177214 -0.25558102 0.56878006, + -0.81300002 -0.238653 0.53110802, + -0.81990916 -0.22499906 0.52642614, + -0.84907186 -0.20762096 0.48576793, + -0.85445416 -0.19621405 0.48104912, + -0.88141078 -0.17839596 0.4373669, + -0.88539529 -0.16922006 0.43294314, + -0.90971029 -0.15116505 0.38675115, + -0.91254878 -0.14395396 0.38279492, + -0.9341231 -0.12564501 0.33410704, + -0.93594825 -0.12042503 0.33090609, + -0.95476365 -0.10169296 0.27943692, + -0.95588112 -0.097985514 0.27693003, + -0.97184336 -0.07859683 0.22213307, + -0.97300678 -0.073858887 0.21863796, + -0.98542464 -0.054443881 0.16116494, + -0.98609114 -0.050789807 0.15825501, + -0.99468642 -0.03146008 0.098025844, + -0.9949159 -0.029442597 0.096308984, + -0.99940854 -0.010053695 0.032886386, + -0.99943227 -0.009448912 0.032341309, + -0.99939185 0.0097787492 -0.033470295, + -0.99941391 0.0092421686 -0.032962497, + -0.99422324 0.028976908 -0.10334703, + -0.99440575 0.027574293 -0.10196498, + -0.98324138 0.04759182 -0.17598706, + -0.98366767 0.045723684 -0.17408994, + -0.96549022 0.066158712 -0.25189605, + -0.96608633 0.064386524 -0.25006309, + -0.93972725 0.085258521 -0.33112508, + -0.939982 0.084699102 -0.33054501, + -0.90466022 0.10577602 -0.41279709, + -0.913836 0.089552999 -0.39608601, + -0.87248939 0.10775805 -0.47660324, + -0.88660657 0.086004756 -0.45445779, + -0.84024286 0.10082199 -0.53275394, + -0.8539983 0.081843428 -0.51379818, + -0.80202281 0.093959078 -0.58985686, + -0.81515998 0.077565096 -0.57401901, + -0.75754535 0.087413847 -0.64690328, + -0.76846886 0.074964091 -0.63548094, + -0.70484281 0.083103277 -0.7044788, + -0.71207124 0.075507931 -0.69803524, + -0.64229572 0.082428262 -0.76201165, + -0.64320117 0.081541523 -0.76134318, + -0.56813598 0.087637 -0.81825501, + -0.56108278 0.094169654 -0.82238561, + -0.48332518 0.099594437 -0.86975729, + -0.46714801 0.114032 -0.87679499, + -0.3899999 0.11875697 -0.91312474, + -0.36554208 0.14028104 -0.92016321, + -0.29299811 0.14409605 -0.94519234, + -0.26279807 0.17100905 -0.94957525, + -0.19894807 0.17369606 -0.96449435, + -0.16851996 0.20194496 -0.96478975, + -0.11601303 0.20349105 -0.97217923, + -0.093007773 0.22636592 -0.96959162, + -0.0515467 0.22705001 -0.97251803, + -0.030906508 0.24953605 -0.96787226, + -0.00014970894 0.24965592 -0.96833462, + 0.012541702 0.26510802 -0.96413714, + 0.035069693 0.26496595 -0.96361977, + 0.032986388 0.26207492 -0.96448362, + 0.051241409 0.26187304 -0.96374112, + 0.053926218 0.2661671 -0.96241736, + 0.066547118 0.26596406 -0.96168321, + 0.066429116 0.26574406 -0.96175224, + 0.074494891 0.26559296 -0.96120286, + 0.073277026 0.26293308 -0.96202737, + 0.077402197 0.26284999 -0.96172702, + 0.077277638 0.26252612 -0.96182549, + 0.068809874 0.26268992 -0.96242362, + 0.041019786 0.17680594 -0.98339063, + 0.036730394 0.17683595 -0.98355478, + -0.027516587 -0.064927869 -0.99751055, + -0.020072507 -0.064939424 -0.99768734, + -0.074321315 -0.3216151 -0.94394922, + -0.055557307 -0.32200903 -0.94510514, + -0.096642599 -0.578381 -0.810022, + -0.067522116 -0.57977611 -0.81197315, + -0.089870676 -0.77895385 -0.62060785, + -0.05321769 -0.78101081 -0.62224591, + -0.062735707 -0.92410815 -0.37694606, + -0.020778099 -0.92573202 -0.37760901, + 0.39137509 -0.011027703 0.92016524, + 0.39057082 -0.042211581 0.9196046, + 0.075506471 -0.99169463 -0.10411796, + 0.066712528 -0.98830348 -0.13713406, + 0.062621459 -0.92602646 -0.37222779, + 0.021926088 -0.99266654 -0.11887994, + 0.020533405 -0.92670625 -0.3752251, + 0.063064322 -0.92505634 -0.37455812, + 0.053587165 -0.7828365 -0.61991566, + 0.090604052 -0.78073847 -0.61825436, + 0.068103686 -0.58129787 -0.81083584, + 0.097431377 -0.57987887 -0.80885583, + 0.056064215 -0.32259208 -0.94487625, + 0.074895486 -0.32219291 -0.94370675, + 0.0202318 -0.063904099 -0.997751, + 0.0275659 -0.063892797 -0.997576, + -0.037898686 0.18236794 -0.98249966, + -0.042627417 0.18233305 -0.98231238, + -0.06978149 0.26621696 -0.96138388, + -0.078534238 0.26604411 -0.96075648, + -0.077348486 0.26295793 -0.96170175, + -0.073290832 0.26303908 -0.96199733, + -0.074427828 0.26552308 -0.96122736, + -0.066320188 0.26567495 -0.96177876, + -0.066909373 0.26677087 -0.96143454, + -0.05442021 0.26697305 -0.96216625, + -0.05117958 0.2617909 -0.96376663, + -0.032926615 0.26199111 -0.96450847, + -0.030892096 0.25916496 -0.96533889, + -0.0073847137 0.25928211 -0.96577346, + -0.0049817082 0.25635591 -0.96656966, + 0.024671804 0.25628203 -0.96628714, + 0.047768906 0.23119903 -0.97173309, + 0.08857429 0.23055397 -0.96901989, + 0.11766603 0.20166405 -0.97236127, + 0.17046502 0.20010203 -0.96483213, + 0.20105907 0.17167006 -0.96441936, + 0.26510394 0.16897796 -0.94929779, + 0.29468685 0.14258392 -0.94489652, + 0.36736304 0.13877602 -0.91966611, + 0.39198795 0.11707199 -0.9124909, + 0.46906587 0.11238897 -0.87598276, + 0.48542288 0.097758979 -0.86879683, + 0.5631181 0.092402622 -0.82119417, + 0.5700497 0.085964955 -0.81710058, + 0.64497018 0.07995902 -0.76001316, + 0.64381725 0.081091732 -0.76087028, + 0.71335316 0.074269414 -0.69685817, + 0.70578092 0.082245491 -0.70363992, + 0.7692402 0.074180417 -0.6346392, + 0.75758213 0.087482311 -0.64685106, + 0.81519169 0.077624969 -0.57396585, + 0.80115771 0.095112562 -0.59084678, + 0.85333472 0.082860567 -0.51473683, + 0.83919317 0.10230003 -0.53412509, + 0.88583356 0.087282859 -0.4557198, + 0.87179118 0.10883402 -0.47763512, + 0.9133417 0.090463974 -0.39701784, + 0.90431225 0.10637902 -0.41340408, + 0.93976277 0.08518558 -0.33104292, + 0.9399389 0.084798694 -0.33064198, + 0.96620363 0.064039581 -0.24969891, + 0.96570766 0.065518774 -0.2512289, + 0.98376775 0.045283888 -0.17363895, + 0.98328888 0.047388893 -0.17577599, + 0.99442124 0.027457608 -0.10184602, + 0.99422026 0.029002508 -0.10336802, + 0.99941355 0.0092505654 -0.032969985, + 0.99939024 0.0098188324 -0.033507809, + 0.99943078 -0.0094865784 0.032373991, + 0.99940652 -0.010105396 0.032931685, + 0.99489897 -0.029592801 0.096438102, + 0.99466962 -0.031604789 0.098150462, + 0.98604989 -0.051017791 0.15843898, + 0.98538864 -0.05463608 0.16131994, + 0.97294587 -0.074111491 0.21882397, + 0.97184402 -0.078594297 0.222131, + 0.95588064 -0.097984262 0.27693191, + 0.95488602 -0.101287 0.27916601, + 0.93610674 -0.11995797 0.3306269, + 0.93418175 -0.12547196 0.33400792, + 0.91261023 -0.14376903 0.38271809, + 0.90964621 -0.15130003 0.38684908, + 0.88532072 -0.16936494 0.43303886, + 0.88123488 -0.17876698 0.43756995, + 0.85427082 -0.19659795 0.48121789, + 0.84887099 -0.20803 0.485944, + 0.81968373 -0.22543192 0.52659184, + 0.81280082 -0.23901995 0.53124785, + 0.78156066 -0.25596088 0.56889969, + 0.77319402 -0.27153 0.57309902, + 0.73983604 -0.28806403 0.60799807, + 0.74403501 -0.280424 0.606444, + 0.71384603 -0.29392299 0.63563597, + 0.73005879 -0.26227191 0.63105273, + 0.69953996 -0.27424997 0.65987194, + 0.71355903 -0.24380203 0.65680605, + 0.68227774 -0.25441492 0.68539774, + 0.69434798 -0.224952 0.683577, + 0.66174918 -0.23435706 0.71215516, + 0.67214316 -0.20547205 0.71134019, + 0.6379478 -0.21370195 0.73983383, + 0.64682317 -0.18514904 0.73982418, + 0.61129689 -0.19213195 0.76772481, + 0.61870706 -0.16397402 0.76831913, + 0.58177507 -0.16976202 0.79543614, + 0.58782178 -0.14187495 0.7964527, + 0.54904002 -0.146576 0.82284302, + 0.5538668 -0.11864395 0.82410872, + 0.51313311 -0.12230703 0.84955019, + 0.51681 -0.094189398 0.85090297, + 0.47468677 -0.096835956 0.87481159, + 0.47731104 -0.068389706 0.87606913, + 0.43389285 -0.070119776 0.89823169, + 0.43553421 -0.04127622 0.89922541, + 0.43689907 -0.010687001 0.89944714, + 0.43604395 -0.041458998 0.89896989, + 0.48011705 -0.040412202 0.8762731, + 0.47837925 -0.06877093 0.87545639, + 0.52108216 -0.06684082 0.85088527, + 0.51835316 -0.09473294 0.84990329, + 0.55968088 -0.091801777 0.8236078, + 0.5558902 -0.11934204 0.82264429, + 0.59523392 -0.11536498 0.79522789, + 0.59032905 -0.14271301 0.79444611, + 0.62782592 -0.13761999 0.76609087, + 0.62173486 -0.16494295 0.76566285, + 0.65766191 -0.15864399 0.73641896, + 0.65027994 -0.18619098 0.73652494, + 0.68482298 -0.178596 0.70648497, + 0.67604375 -0.20655192 0.70731974, + 0.70890582 -0.19770496 0.67702681, + 0.69870317 -0.22602606 0.67876816, + 0.73010033 -0.2158931 0.64833927, + 0.71834004 -0.24480604 0.65119708, + 0.74883008 -0.23321803 0.62037307, + 0.73526818 -0.26313606 0.62461209, + 0.76527917 -0.24990606 0.59320712, + 0.74970198 -0.28106901 0.59912199, + 0.77907127 -0.2662721 0.56758016, + 0.7747491 -0.27440703 0.56961805, + 0.80704516 -0.25627407 0.53197914, + 0.81424385 -0.24225497 0.52755994, + 0.8444339 -0.22353297 0.48678994, + 0.850142 -0.211568 0.48218, + 0.87799633 -0.19232808 0.43832916, + 0.88228989 -0.18251298 0.43388194, + 0.90738612 -0.16296801 0.38741705, + 0.91046757 -0.15516092 0.38337183, + 0.93267179 -0.13533197 0.33437791, + 0.93476921 -0.12931703 0.33088309, + 0.95403886 -0.10908799 0.27912298, + 0.95526576 -0.10498198 0.27648893, + 0.97152537 -0.084105328 0.22150607, + 0.97206259 -0.08190845 0.21996713, + 0.9849081 -0.060397107 0.16219802, + 0.98549253 -0.057210475 0.15978593, + 0.99445087 -0.035462495 0.099045083, + 0.99470311 -0.033259302 0.097260617, + 0.99938333 -0.011362104 0.033226412, + 0.9994095 -0.010696605 0.032655116, + 0.99936712 0.011073301 -0.033805404, + 0.99939197 0.0104675 -0.033259399, + 0.99400622 0.032820009 -0.10428102, + 0.99421901 0.0311807 -0.102744, + 0.98268491 0.053806793 -0.17729999, + 0.98321986 0.051446993 -0.17501998, + 0.96456325 0.074411117 -0.25314206, + 0.96541947 0.071835838 -0.25060913, + 0.93858099 0.095080398 -0.33170101, + 0.93914676 0.093819976 -0.3304559, + 0.90337688 0.11712599 -0.41254294, + 0.90240169 0.11881596 -0.41419086, + 0.8565681 0.14229302 -0.49602807, + 0.86881942 0.12453706 -0.47921124, + 0.81700385 0.14503796 -0.55809391, + 0.83517468 0.12143195 -0.53641182, + 0.77867609 0.13853002 -0.61194205, + 0.79570287 0.11823399 -0.59403497, + 0.73457897 0.13245198 -0.66546994, + 0.75034797 0.11504 -0.65095598, + 0.68452543 0.12686308 -0.71786541, + 0.69632083 0.11469097 -0.70850784, + 0.62557107 0.12466802 -0.77014214, + 0.63175815 0.11865003 -0.76603121, + 0.55675888 0.12714598 -0.82088584, + 0.55529988 0.12849997 -0.82166284, + 0.47838089 0.13568397 -0.86760682, + 0.46840587 0.14463197 -0.87159485, + 0.39220494 0.15058398 -0.90746886, + 0.37396881 0.16671793 -0.91233361, + 0.30167601 0.17138501 -0.93787998, + 0.27751592 0.19296493 -0.94114262, + 0.21282603 0.19625303 -0.95717812, + 0.18670101 0.22042903 -0.95736814, + 0.13222705 0.22240408 -0.96594638, + 0.10736602 0.24684402 -0.96308911, + 0.064016178 0.24776991 -0.96670163, + 0.041846085 0.27144891 -0.96154267, + 0.009270031 0.27167603 -0.96234411, + -0.0069751493 0.29092696 -0.95671988, + -0.029892389 0.29080391 -0.95631564, + -0.029821711 0.29071009 -0.95634633, + -0.047599781 0.2905089 -0.95568764, + -0.047503181 0.29035991 -0.95573765, + -0.060915709 0.29014802 -0.95504111, + -0.061571922 0.29132909 -0.95463938, + -0.07008402 0.29116508 -0.95410234, + -0.068074189 0.28691298 -0.95553488, + -0.0727304 0.28681901 -0.95521998, + -0.070524581 0.28125292 -0.95703864, + -0.071784034 0.28122813 -0.95695245, + -0.071758896 0.28115097 -0.95697689, + -0.062168822 0.28133309 -0.95759434, + -0.039116398 0.19585297 -0.97985286, + -0.033453614 0.19589309 -0.9800545, + 0.020016897 -0.053449694 -0.99836987, + 0.013855302 -0.053455308 -0.99847412, + 0.05645512 -0.31585813 -0.94712538, + 0.038935196 -0.31612298 -0.94791889, + 0.068652309 -0.57763803 -0.8134011, + 0.040394396 -0.57853192 -0.81465888, + 0.054026082 -0.7812317 -0.62189877, + 0.017697601 -0.782251 -0.62271202, + 0.020863691 -0.92606056 -0.37679783, + -0.020608008 -0.92606539 -0.37680015, + -0.017450092 -0.78133267 -0.62387073, + -0.053401906 -0.78033614 -0.62307608, + -0.039886482 -0.57758069 -0.81535858, + -0.067982122 -0.57670319 -0.81412029, + -0.038450785 -0.3157059 -0.94807762, + -0.055933699 -0.31544501 -0.947294, + -0.013619 -0.054333001 -0.99843001, + -0.019843001 -0.054327399 -0.998326, + 0.0328172 0.191376 -0.980968, + 0.038049694 0.19134095 -0.98078579, + 0.061585624 0.27863207 -0.95842135, + 0.070892118 0.27845907 -0.95782822, + 0.071793437 0.28121513 -0.95695549, + 0.070554219 0.28124008 -0.95704037, + 0.072793193 0.28688997 -0.95519388, + 0.068142101 0.28698301 -0.95550901, + 0.069792777 0.2904759 -0.95433366, + 0.061189078 0.29064092 -0.95487362, + 0.060966294 0.29023996 -0.95500988, + 0.047563087 0.29045194 -0.95570678, + 0.050844118 0.29552713 -0.95398039, + 0.033938192 0.29573894 -0.95466578, + 0.025764214 0.28474715 -0.95825648, + 0.0017967302 0.28484103 -0.9585731, + -0.012443498 0.26791596 -0.96336186, + -0.045653701 0.26765701 -0.96243203, + -0.0626809 0.24945 -0.96635699, + -0.105788 0.248538 -0.96282798, + -0.13047804 0.22428508 -0.96574938, + -0.18464698 0.22232997 -0.95732689, + -0.21129499 0.19769301 -0.95722097, + -0.27584904 0.19441102 -0.94133514, + -0.29983193 0.17301595 -0.93817174, + -0.37196511 0.16834706 -0.9128533, + -0.39002109 0.15240303 -0.90810627, + -0.4662528 0.14641793 -0.87245059, + -0.47622889 0.13749097 -0.86850584, + -0.55327117 0.13024904 -0.82275528, + -0.55496591 0.12868199 -0.8218599, + -0.63010907 0.12011702 -0.76716012, + -0.62438625 0.12567005 -0.7709403, + -0.69528615 0.11563403 -0.7093702, + -0.68440193 0.12685299 -0.71798491, + -0.75026017 0.11502903 -0.65105915, + -0.73560375 0.13123396 -0.66457874, + -0.7965579 0.11712099 -0.59310895, + -0.78000027 0.13692604 -0.61061525, + -0.8362202 0.11999303 -0.53510511, + -0.81794089 0.14382999 -0.55703294, + -0.86951786 0.12347998 -0.47821695, + -0.85721356 0.14136793 -0.49517676, + -0.9028421 0.11803702 -0.41345307, + -0.90306109 0.11765701 -0.41308305, + -0.9389509 0.094246387 -0.33089098, + -0.93816376 0.095993578 -0.33261693, + -0.96518654 0.07252726 -0.25130588, + -0.96444511 0.07474871 -0.25349203, + -0.98316699 0.051676799 -0.175249, + -0.98269165 0.05377198 -0.17727295, + -0.99422109 0.031160804 -0.10273001, + -0.99402225 0.032694306 -0.10416802, + -0.99939352 0.010427495 -0.033223387, + -0.99936938 0.011018803 -0.033756312, + -0.9994114 -0.010644794 0.032610781, + -0.99938536 -0.011311204 0.03318271, + -0.99471974 -0.033112593 0.097139478, + -0.99446523 -0.035340607 0.098944023, + -0.98552835 -0.057017718 0.15963405, + -0.98490763 -0.060404778 0.16219795, + -0.97206163 -0.081918873 0.21996692, + -0.97144586 -0.084434889 0.22172897, + -0.95514613 -0.10538702 0.27674803, + -0.95398802 -0.109256 0.27923101, + -0.93471438 -0.12949905 0.33096713, + -0.93272913 -0.13519101 0.33427504, + -0.9105286 -0.15501292 0.38328683, + -0.90752286 -0.16263399 0.38723695, + -0.88246286 -0.18214199 0.43368593, + -0.87818927 -0.19192305 0.43812013, + -0.85033786 -0.21115197 0.48201695, + -0.84460109 -0.22318803 0.48665807, + -0.81443882 -0.24188495 0.52742887, + -0.80701917 -0.25634107 0.53198612, + -0.77469987 -0.27448797 0.56964594, + -0.7797963 -0.2648811 0.56723517, + -0.75037783 -0.27967995 0.59892589, + -0.76577085 -0.24880397 0.59303594, + -0.73566663 -0.26204687 0.62460071, + -0.74898517 -0.23262106 0.62041014, + -0.71840775 -0.24421892 0.65134275, + -0.73000783 -0.21568996 0.64851081, + -0.69857693 -0.22581898 0.67896694, + -0.70867294 -0.19780996 0.67723995, + -0.6757955 -0.20665585 0.7075265, + -0.68450719 -0.17893904 0.7067042, + -0.64994222 -0.18654206 0.73673421, + -0.65734082 -0.15898596 0.73663181, + -0.62135762 -0.16530189 0.76589155, + -0.62749803 -0.13784501 0.7663191, + -0.59008592 -0.14292899 0.79458791, + -0.59505713 -0.11526203 0.79537517, + -0.55568284 -0.11923596 0.82279968, + -0.55951512 -0.091363624 0.82376915, + -0.51804221 -0.094288737 0.8501423, + -0.52075905 -0.066534504 0.85110712, + -0.47791982 -0.068459481 0.87573171, + -0.47961706 -0.040772904 0.87653011, + -0.43562779 -0.04182528 0.8991546, + -0.43645984 -0.012369895 0.89963871, + -0.44798201 -0.0155087 0.89390802, + -0.44794807 -0.015505502 0.89392513, + -0.44800684 0.0016108694 0.89402872, + -0.44804084 0.0016108494 0.89401168, + -0.49254289 -0.0024418193 0.8702848, + -0.53342986 0.0015543896 0.84584284, + -0.52513307 -0.012167602 0.85093313, + -0.52422816 -0.040098116 0.85063332, + -0.56663913 -0.038797908 0.82305217, + -0.56483102 -0.065198198 0.82262701, + -0.60529101 -0.062890902 0.79351598, + -0.60248077 -0.089311272 0.79312068, + -0.64091003 -0.085896596 0.76279497, + -0.63702101 -0.112439 0.76260197, + -0.67376095 -0.10778698 0.73104596, + -0.6688332 -0.13403803 0.73122919, + -0.70396394 -0.12805699 0.69859594, + -0.69799918 -0.15409203 0.69932318, + -0.73115098 -0.14680099 0.66623402, + -0.72410822 -0.17284606 0.66767621, + -0.755584 -0.164166 0.63414699, + -0.74743378 -0.19039492 0.63646877, + -0.77764672 -0.18018194 0.60232878, + -0.76838511 -0.20664203 0.60570908, + -0.79771984 -0.19470896 0.5707289, + -0.78727603 -0.221655 0.57538301, + -0.81557041 -0.2080161 0.53997624, + -0.8038168 -0.23579194 0.54615086, + -0.8314051 -0.22025102 0.51015204, + -0.81806511 -0.24944703 0.51821405, + -0.84560782 -0.23152494 0.48098189, + -0.84074116 -0.24177006 0.48446012, + -0.87066299 -0.219641 0.44011801, + -0.87561876 -0.20852296 0.4356719, + -0.90243328 -0.18599907 0.38861114, + -0.90590233 -0.17730007 0.38458514, + -0.92950535 -0.15440805 0.33493012, + -0.93179739 -0.14784905 0.33150312, + -0.95214963 -0.12449095 0.27912891, + -0.95352262 -0.11986995 0.27645192, + -0.97141087 -0.094442382 0.21781097, + -0.61373925 -0.013511505 0.78939331, + -0.60973489 -0.013124498 0.7924968, + -0.60884804 -0.037962303 0.79237813, + -0.64806318 -0.036445308 0.76071417, + -0.64625776 -0.061267879 0.7606557, + -0.68376428 -0.058585126 0.72734737, + -0.6810112 -0.083400622 0.72750819, + -0.71669996 -0.079426691 0.69284391, + -0.71297801 -0.104272 0.69339001, + -0.74646503 -0.098953798 0.65802598, + -0.74185783 -0.12345997 0.6590938, + -0.7732842 -0.11674003 0.62322015, + -0.76782912 -0.14093801 0.62496006, + -0.79770517 -0.13266502 0.58827412, + -0.79141968 -0.15676793 0.59082878, + -0.81995332 -0.14680606 0.55328518, + -0.81283885 -0.17099398 0.55682492, + -0.83991009 -0.15932101 0.51881409, + -0.83202499 -0.183621 0.523467, + -0.85792798 -0.17006101 0.484808, + -0.84928441 -0.19465908 0.49073824, + -0.8744911 -0.17884402 0.45086607, + -0.8650474 -0.2040661 0.45831221, + -0.88988876 -0.18555295 0.4167349, + -0.87956327 -0.21184207 0.42601815, + -0.90411127 -0.19025305 0.38260508, + -0.90013623 -0.20033005 0.38681108, + -0.92548001 -0.17420299 0.33636299, + -0.92818522 -0.16655605 0.33276308, + -0.94985801 -0.139953 0.279612, + -0.95147365 -0.13452895 0.2767669, + -0.97048151 -0.10543295 0.2169089, + -0.97056347 -0.10542705 0.2165451, + -0.98362625 -0.078888722 0.16203704, + -0.98497021 -0.071298413 0.15732205, + -0.99398845 -0.045194123 0.099722244, + -0.85234618 0.17075604 -0.49431613, + -0.89905912 0.14295402 -0.41383207, + -0.89795411 0.14490801 -0.41554806, + -0.93560624 0.11624703 -0.33335808, + -0.93444735 0.11885504 -0.33568111, + -0.96303189 0.089912094 -0.25393996, + -0.96210152 0.092725955 -0.25644189, + -0.98203689 0.064161696 -0.17744498, + -0.98145515 0.066739008 -0.17969902, + -0.99380612 0.038689803 -0.10417502, + -0.99356091 0.040581096 -0.10578199, + -0.99934673 0.012943897 -0.033740893, + -0.99931663 0.013678195 -0.034340788, + -0.99936289 -0.013206098 0.033155795, + -0.99931234 -0.014472306 0.034140211, + -0.99445415 -0.041047204 0.096830316, + -0.99431598 -0.040963199 0.098273903, + -0.98485726 -0.066701613 0.16002205, + -0.98403978 -0.071185082 0.16308996, + -0.97169662 -0.094500564 0.21650693, + -0.970034 -0.101521 0.220743, + -0.95255899 -0.12717099 0.276512, + -0.95107126 -0.13217904 0.27927107, + -0.93009025 -0.15714605 0.3320201, + -0.92762113 -0.16417702 0.33550704, + -0.90319312 -0.18866403 0.38554907, + -0.89941776 -0.19804196 0.3896499, + -0.8715778 -0.22213094 0.43704692, + -0.87607175 -0.21186395 0.43314192, + -0.84971285 -0.23166494 0.47362387, + -0.86165512 -0.20373903 0.46480206, + -0.83530712 -0.22071603 0.50353408, + -0.84599668 -0.19407293 0.49661383, + -0.81927019 -0.20871304 0.53407413, + -0.82887781 -0.18285495 0.5287019, + -0.80124885 -0.19556996 0.56546688, + -0.80987573 -0.17011894 0.56139183, + -0.78094929 -0.18113706 0.59775221, + -0.78864014 -0.15583502 0.59477907, + -0.758587 -0.165141 0.63029701, + -0.7652989 -0.14001198 0.62826294, + -0.73387384 -0.14775798 0.66302085, + -0.73962402 -0.122592 0.66176099, + -0.70634019 -0.12894003 0.6960302, + -0.7111392 -0.10352702 0.69538718, + -0.67573178 -0.10854796 0.72911179, + -0.67956531 -0.082799934 0.72892737, + -0.64241999 -0.0864949 0.76145601, + -0.64522278 -0.060832176 0.76156873, + -0.60635072 -0.063316673 0.79267263, + -0.60816622 -0.037673716 0.79291528, + -0.56734288 -0.03908189 0.82255381, + -0.56826484 -0.012105695 0.82275671, + -0.57419699 -0.0142007 0.81859398, + -0.5742591 -0.0015064303 0.81867218, + -0.53340483 0.0015555294 0.84585869, + -0.53334087 -0.014810396 0.84577084, + -0.53336596 -0.014810198 0.84575486, + -0.53336412 -0.014810003 0.84575617, + -0.53342807 0.0015543902 0.84584409, + -0.49129981 -0.0026063491 0.8709867, + -0.49123982 -0.015202294 0.87089169, + -0.49121606 -0.015202502 0.8709051, + -0.49127612 -0.0021599405 0.87100118, + -0.44800207 0.0016126502 0.89403111, + -0.44794285 -0.015508994 0.89392769, + -0.48114994 -0.012239198 0.87655288, + -0.48027393 -0.041017197 0.87615889, + -0.52356482 -0.039841983 0.85105371, + -0.52180117 -0.066919625 0.8504383, + -0.5637728 -0.064790875 0.8233847, + -0.56098908 -0.091901705 0.8227061, + -0.60095799 -0.088733003 0.79434001, + -0.59706986 -0.11597997 0.79376084, + -0.63499922 -0.11168904 0.76439631, + -0.63000607 -0.13871002 0.7641021, + -0.66640997 -0.13317199 0.73359597, + -0.66031671 -0.15996492 0.73375267, + -0.695144 -0.153124 0.70237303, + -0.68787074 -0.17997295 0.70316678, + -0.72091097 -0.17183799 0.67138594, + -0.71241862 -0.1988579 0.67298973, + -0.74387419 -0.18938404 0.64092517, + -0.73411703 -0.21670103 0.64351606, + -0.76455301 -0.20570301 0.610856, + -0.75344086 -0.23353197 0.61464596, + -0.7831738 -0.22084694 0.58126187, + -0.77054048 -0.24953783 0.58651358, + -0.7994439 -0.23518898 0.55278891, + -0.78494614 -0.26536304 0.55985904, + -0.813416 -0.249138 0.52562797, + -0.80836099 -0.25913 0.52858698, + -0.83961201 -0.23910099 0.48773199, + -0.84580386 -0.22627696 0.48312995, + -0.87464112 -0.20561104 0.43900707, + -0.87920988 -0.19524497 0.43459094, + -0.90510929 -0.17424005 0.38783714, + -0.90833628 -0.16609406 0.38384616, + -0.93120211 -0.14475401 0.33452803, + -0.9333269 -0.13865998 0.33117098, + -0.95311612 -0.11686902 0.27912602, + -0.95438677 -0.11260197 0.27652594, + -0.97103447 -0.090111941 0.2212961, + -0.97167414 -0.087473206 0.21954003, + -0.98474109 -0.064414404 0.16166602, + -0.98501652 -0.06290257 0.16057892, + -0.99426854 -0.038994581 0.099546053, + -0.99450153 -0.036963783 0.097981453, + -0.99935937 -0.012632305 0.033485111, + -0.99938852 -0.011893095 0.032881085, + -0.99934453 0.012313395 -0.034042787, + -0.99937135 0.011659403 -0.03348171, + -0.99380338 0.036554415 -0.10497004, + -0.99402255 0.034861285 -0.10345895, + -0.982099 0.0601486 -0.17850401, + -0.98262334 0.057829421 -0.17637207, + -0.96331537 0.083614632 -0.25501409, + -0.96415037 0.08109843 -0.2526601, + -0.93637186 0.10727599 -0.33421496, + -0.93738365 0.10501196 -0.33209088, + -0.90065825 0.13101003 -0.4143081, + -0.90146989 0.12958498 -0.41298893, + -0.85525817 0.15514003 -0.49443412, + -0.85406858 0.15683992 -0.49595177, + -0.79811317 0.18167004 -0.57446611, + -0.81324279 0.16299595 -0.55863088, + -0.75204098 0.184617 -0.63273299, + -0.77400202 0.15971 -0.61271, + -0.70942295 0.17776999 -0.68199492, + -0.72792792 0.15810099 -0.66717696, + -0.65959316 0.17331305 -0.73136818, + -0.67477506 0.15809701 -0.72089106, + -0.6026631 0.17094405 -0.77947116, + -0.61255676 0.16151494 -0.7737487, + -0.53737009 0.17232901 -0.82555211, + -0.54092097 0.169076 -0.82390398, + -0.46468389 0.17800196 -0.86740083, + -0.46038917 0.18183206 -0.86889529, + -0.38531485 0.18901493 -0.9032197, + -0.37335488 0.19956693 -0.90596873, + -0.30198705 0.20507905 -0.93099225, + -0.28390405 0.22118805 -0.93299222, + -0.21927197 0.22506598 -0.94934988, + -0.19774409 0.24488212 -0.94917345, + -0.14248599 0.24726596 -0.9584139, + -0.12050101 0.26865602 -0.95566911, + -0.075587295 0.26985398 -0.95992988, + -0.056724984 0.28968793 -0.95543873, + -0.021932889 0.29008484 -0.9567495, + -0.010242799 0.30367097 -0.95272189, + 0.0158781 0.30364799 -0.95265198, + 0.024870196 0.31542096 -0.94862586, + 0.043097712 0.31522408 -0.94803822, + 0.04768962 0.32209811 -0.94550437, + 0.060023271 0.32188386 -0.94487453, + 0.055915475 0.31473985 -0.94752949, + 0.065190323 0.31456313 -0.94699538, + 0.063688621 0.31148812 -0.94811338, + 0.068834469 0.31138185 -0.94778854, + 0.066181704 0.30490303 -0.95008111, + 0.068012007 0.30486503 -0.94996411, + 0.06514252 0.29636613 -0.95285034, + 0.063936986 0.29638895 -0.95292479, + 0.062535487 0.29124695 -0.95460176, + 0.052452218 0.29141608 -0.95515734, + 0.033248495 0.20310196 -0.97859287, + 0.02709979 0.20313993 -0.97877467, + -0.013865796 -0.046096791 -0.99884075, + -0.0086328564 -0.046099376 -0.99889952, + -0.038952097 -0.31101996 -0.94960487, + -0.022451801 -0.31117904 -0.95008612, + -0.040240087 -0.5758028 -0.8165977, + -0.012979198 -0.57622093 -0.81719089, + -0.017429095 -0.7813977 -0.62378979, + 0.0179752 -0.78139001 -0.62378401, + 0.013405995 -0.5767048 -0.81684268, + 0.04084279 -0.57627487 -0.81623483, + 0.022913288 -0.31150386 -0.94996852, + 0.039448582 -0.31134287 -0.94947851, + 0.0089477105 -0.045526404 -0.99892312, + 0.014099296 -0.045523789 -0.99886376, + -0.027384896 0.20669597 -0.97802186, + -0.033844102 0.20665602 -0.97782815, + -0.05278511 0.29372907 -0.95443022, + -0.063092783 0.29355195 -0.95385873, + -0.063901603 0.296518 -0.952887, + -0.065073393 0.29649496 -0.95281488, + -0.067895211 0.30485305 -0.94997627, + -0.066096611 0.30489007 -0.95009124, + -0.06901142 0.31200913 -0.94756937, + -0.063993603 0.312114 -0.947887, + -0.065146774 0.31447488 -0.94702762, + -0.055864885 0.31465191 -0.94756174, + -0.057491716 0.31748408 -0.94651926, + -0.044449277 0.31769484 -0.94715053, + -0.046423104 0.32064804 -0.94606012, + -0.029067803 0.32085803 -0.94668114, + -0.018517697 0.30708197 -0.95150286, + 0.0070331618 0.30712807 -0.95164222, + 0.022947907 0.28865409 -0.95715839, + 0.057978291 0.28824496 -0.95579988, + 0.077028841 0.26820111 -0.96027845, + 0.12216905 0.2669861 -0.95592535, + 0.14376095 0.24596392 -0.95855862, + 0.19922404 0.24356306 -0.94920325, + 0.22099698 0.22350398 -0.94931889, + 0.28574494 0.21961494 -0.93280178, + 0.30411413 0.20322508 -0.93070638, + 0.37560314 0.19771008 -0.90544629, + 0.3874909 0.18719895 -0.90266675, + 0.46261713 0.18002805 -0.86808717, + 0.4666748 0.17640191 -0.86665857, + 0.54281098 0.167512 -0.82297999, + 0.53877813 0.17121305 -0.82486618, + 0.61384588 0.16043796 -0.77295083, + 0.60289794 0.17088298 -0.7793029, + 0.67496395 0.15803899 -0.72072697, + 0.65848732 0.17453709 -0.73207337, + 0.72692716 0.15925905 -0.66799217, + 0.70781666 0.17950691 -0.68320769, + 0.77267665 0.16131292 -0.6139617, + 0.75085086 0.18597798 -0.63374692, + 0.81229413 0.16423301 -0.55964804, + 0.79707539 0.18295386 -0.57549858, + 0.85327411 0.15798402 -0.49695507, + 0.85567969 0.15455094 -0.49388883, + 0.90176022 0.12908603 -0.41251108, + 0.90136689 0.12977798 -0.41315293, + 0.93783367 0.10401396 -0.33113289, + 0.93661338 0.10675403 -0.33370513, + 0.96428162 0.080707267 -0.2522839, + 0.9633109 0.08363539 -0.25502396, + 0.98261952 0.057846773 -0.17638791, + 0.98205203 0.060353801 -0.178693, + 0.99400687 0.034980796 -0.10356998, + 0.99377936 0.036733717 -0.10513504, + 0.99936914 0.011715 -0.033529304, + 0.99934226 0.012368402 -0.034090109, + 0.99938655 -0.011945094 0.032923486, + 0.99935752 -0.012677995 0.033522286, + 0.99448735 -0.037092116 0.09807694, + 0.99426901 -0.038993798 0.099541999, + 0.98501778 -0.062901482 0.16057196, + 0.98478955 -0.064154074 0.16147393, + 0.97175187 -0.087140292 0.21932797, + 0.97106624 -0.089971423 0.22121406, + 0.95443475 -0.11242897 0.27643093, + 0.95307398 -0.117 0.27921501, + 0.93327099 -0.13880999 0.33126599, + 0.93108773 -0.14506596 0.3347109, + 0.90820313 -0.16643402 0.38401407, + 0.90495825 -0.17461705 0.3880201, + 0.87902302 -0.19566099 0.434782, + 0.8744812 -0.20595305 0.43916512, + 0.84564084 -0.22662795 0.48325089, + 0.83965302 -0.239026 0.48769799, + 0.80838484 -0.25906393 0.52858287, + 0.81270987 -0.25053096 0.52605796, + 0.78429699 -0.266747 0.56011099, + 0.79896909 -0.23629902 0.55300206, + 0.77013689 -0.25064397 0.58657193, + 0.78301716 -0.22144306 0.58124614, + 0.75332868 -0.23413292 0.61455476, + 0.7646023 -0.20591708 0.61072224, + 0.73422784 -0.21690795 0.64331985, + 0.7440908 -0.18927796 0.64070481, + 0.71264601 -0.198753 0.67277998, + 0.72120166 -0.17148992 0.67116272, + 0.68814844 -0.1796201 0.70298541, + 0.6954174 -0.15275209 0.70218343, + 0.66054517 -0.15959305 0.73362815, + 0.666601 -0.132937 0.73346502, + 0.6302588 -0.13845997 0.76393884, + 0.63517725 -0.11180504 0.76423132, + 0.59728771 -0.11609795 0.79357964, + 0.60112226 -0.089210629 0.79416227, + 0.56128788 -0.092387974 0.82244784, + 0.56409502 -0.065107197 0.82313901, + 0.52217883 -0.067245975 0.85018069, + 0.52398878 -0.03946038 0.85081059, + 0.48069194 -0.040626295 0.87594789, + 0.48159581 -0.010402396 0.87633169, + 0.66015816 -0.0028809106 0.75112116, + 0.969212 -0.116706 0.216813, + 0.94885767 -0.14963694 0.27798891, + 0.95111877 -0.14190897 0.27428994, + 0.93119889 -0.16749698 0.32374898, + 0.93803376 -0.14541897 0.3145569, + 0.91755545 -0.1668459 0.36090779, + 0.92429578 -0.14495496 0.35307992, + 0.90302289 -0.16315298 0.39740494, + 0.9095121 -0.14145702 0.39086807, + 0.88722891 -0.15699299 0.43379495, + 0.89339077 -0.13532098 0.42841691, + 0.87012881 -0.14843597 0.46993887, + 0.87588298 -0.12665699 0.46560401, + 0.8514061 -0.13767801 0.50611508, + 0.85660613 -0.11598402 0.50276607, + 0.83050019 -0.12521003 0.54276311, + 0.835109 -0.103447 0.54026997, + 0.80712819 -0.11102303 0.5798431, + 0.81110036 -0.089018948 0.57809329, + 0.78143227 -0.094967037 0.61672121, + 0.78472829 -0.072535619 0.61558121, + 0.7532019 -0.076976396 0.65326995, + 0.75576431 -0.053943418 0.65261823, + 0.72194976 -0.05699968 0.68959373, + 0.72371697 -0.0331975 0.68929797, + 0.69035405 -0.0094404612 0.72341007, + 0.68833697 -0.010227299 0.72531897, + 0.68743503 -0.034936603 0.72540504, + 0.61006624 -0.011345903 0.79226929, + 0.6091423 -0.037511617 0.79217339, + 0.97042978 -0.10566998 0.21702495, + 0.95138198 -0.134839 0.27693099, + 0.94978052 -0.14020894 0.27974689, + 0.92808914 -0.16684401 0.33288702, + 0.92550063 -0.17415693 0.33632988, + 0.90015769 -0.20028393 0.38678485, + 0.90363055 -0.19149691 0.38311982, + 0.87904799 -0.213146 0.426431, + 0.88952112 -0.18657401 0.41706407, + 0.86467516 -0.20512904 0.45854011, + 0.87431985 -0.17942598 0.45096695, + 0.84912968 -0.19526093 0.49076682, + 0.85792011 -0.17026602 0.48475006, + 0.83206517 -0.18381804 0.52333415, + 0.84003448 -0.1592401 0.5186373, + 0.81297886 -0.17091098 0.55664593, + 0.8201521 -0.14648402 0.55307609, + 0.7916128 -0.15643695 0.59065789, + 0.79790282 -0.13228397 0.58809191, + 0.76804119 -0.14053904 0.62478912, + 0.77344584 -0.11650797 0.62306291, + 0.74201816 -0.12322003 0.6589582, + 0.74655563 -0.099076755 0.65790468, + 0.71312219 -0.10439602 0.69322318, + 0.71678704 -0.079927906 0.69269603, + 0.68115371 -0.08392226 0.72731465, + 0.68393195 -0.058941994 0.72716093, + 0.64652604 -0.061636206 0.76039809, + 0.64838904 -0.036009803 0.7604571, + 0.64995372 -0.0095697856 0.75991362, + 0.64900202 -0.036282301 0.75992101, + 0.68684906 -0.034661405 0.72597307, + 0.68502194 -0.059424091 0.72609496, + 0.72093821 -0.056526516 0.69069016, + 0.71825618 -0.080569126 0.69109815, + 0.7518453 -0.076349631 0.65490425, + 0.74834365 -0.099837758 0.65575469, + 0.77979183 -0.094228178 0.61890686, + 0.775509 -0.117352 0.62033403, + 0.80525231 -0.11021303 0.58259916, + 0.80021518 -0.13317204 0.5847401, + 0.82843328 -0.12437304 0.54610419, + 0.82265383 -0.14735897 0.54911387, + 0.84919786 -0.13686998 0.51002896, + 0.8426978 -0.16004795 0.51404786, + 0.86781245 -0.14771192 0.47442874, + 0.86070442 -0.17094007 0.47954923, + 0.88485879 -0.15641996 0.43881389, + 0.87717277 -0.17989495 0.44520289, + 0.90065044 -0.16279908 0.40289617, + 0.892416 -0.186759 0.41074899, + 0.91522413 -0.16678101 0.36680904, + 0.90653533 -0.19131407 0.37628815, + 0.92893976 -0.16779296 0.3300249, + 0.92603213 -0.17618401 0.33380204, + 0.94848466 -0.14788695 0.2801899, + 0.95017314 -0.14225101 0.27737302, + 0.96870786 -0.11326499 0.22085297, + 0.97050714 -0.10566401 0.21668203, + 0.98359138 -0.079075031 0.16215806, + 0.98448926 -0.074062817 0.15904604, + 0.99425751 -0.045175079 0.097011253, + 0.99283147 0.050442021 -0.10835705, + 0.99327475 0.047084689 -0.10577498, + 0.97987276 0.081180677 -0.18237096, + 0.98061675 0.077906884 -0.17978096, + 0.95915735 0.11247404 -0.25955108, + 0.96036625 0.10882502 -0.25662005, + 0.929865 0.14363401 -0.33870399, + 0.93147641 0.13999806 -0.33578616, + 0.8917079 0.17417298 -0.41775694, + 0.8935774 0.17084007 -0.4151302, + 0.84437084 0.20389296 -0.49544489, + 0.84617633 0.20125008 -0.49344116, + 0.72097296 0.26087296 -0.64198393, + 0.78894114 0.23132303 -0.56926405, + 0.78797382 0.23252194 -0.57011485, + 0.7837379 0.25043896 -0.56836194, + 0.7822488 0.25228894 -0.56959391, + 0.84167027 0.21868607 -0.49372819, + 0.83973086 0.22152697 -0.49575993, + 0.89018869 0.18586694 -0.41595384, + 0.88819778 0.18941495 -0.41860092, + 0.92914563 0.15241595 -0.33683488, + 0.92736602 0.156426 -0.33988699, + 0.95890266 0.11862396 -0.25774792, + 0.95752186 0.12277898 -0.26091596, + 0.97982925 0.085087322 -0.18081704, + 0.97864074 0.090259977 -0.18470396, + 0.99334747 0.050559822 -0.10346305, + 0.99296486 0.053601392 -0.10558198, + 0.99932063 0.016683195 -0.032861888, + 0.999273 0.0179173 -0.033652298, + 0.99934191 -0.017047498 0.032018695, + 0.99929178 -0.018411096 0.032817092, + 0.99399185 -0.053553794 0.095457882, + 0.99420065 -0.051540282 0.094385266, + 0.98481297 -0.083209097 0.15238, + 0.98659098 -0.071447298 0.146743, + 0.97489899 -0.097465403 0.20018101, + 0.97732538 -0.083891928 0.19441508, + 0.96379524 -0.10564302 0.24482305, + 0.96667123 -0.090865023 0.23935406, + 0.95168579 -0.10898398 0.28708294, + 0.95484012 -0.093265206 0.28210303, + 0.93841076 -0.10845798 0.32805791, + 0.94168186 -0.091974795 0.32369098, + 0.92365664 -0.10474296 0.36862889, + 0.92687923 -0.08775752 0.36495709, + 0.90716201 -0.098376803 0.40911999, + 0.91022074 -0.080902979 0.4061439, + 0.88883024 -0.089521125 0.44940713, + 0.89163512 -0.071470305 0.44707805, + 0.86846715 -0.07825692 0.48953113, + 0.87091231 -0.059566922 0.48781517, + 0.84557289 -0.064708695 0.52992392, + 0.84757131 -0.045188516 0.52875417, + 0.8198359 -0.048757691 0.57051891, + 0.82128221 -0.028273307 0.56982112, + 0.79138017 -0.030295307 0.61057311, + 0.75978798 -0.0086847804 0.65011299, + 0.75894701 -0.031932499 0.65036899, + 0.7908808 -0.030011093 0.61123389, + 0.78931302 -0.051681999 0.611812, + 0.81902611 -0.048295408 0.57172006, + 0.81681091 -0.069077596 0.57275492, + 0.84453416 -0.064120017 0.53164911, + 0.84177786 -0.084149495 0.53322494, + 0.86728483 -0.077600583 0.49172688, + 0.86406714 -0.097057112 0.49393106, + 0.88754177 -0.088833675 0.45208189, + 0.88393915 -0.10784802 0.45499507, + 0.90582502 -0.097711101 0.41223001, + 0.90191579 -0.11642997 0.41592291, + 0.92233598 -0.104159 0.37208501, + 0.91822886 -0.12257399 0.37660494, + 0.93713987 -0.10799898 0.33182096, + 0.93299401 -0.12593199 0.33713999, + 0.95052564 -0.10869896 0.29100791, + 0.94649565 -0.12603895 0.29708588, + 0.96277714 -0.10556702 0.24882904, + 0.95900822 -0.12229903 0.25562906, + 0.97408485 -0.097615384 0.20403397, + 0.97083235 -0.11330204 0.21129908, + 0.98424011 -0.083566807 0.15584601, + 0.98377454 -0.086319052 0.15727893, + 0.99371123 -0.053874012 0.09816172, + 0.99419546 -0.049406521 0.095574446, + 0.99930334 -0.017138405 0.033153512, + 0.99935454 -0.015770592 0.032277286, + 0.99927378 0.016726997 -0.034234993, + 0.99932086 0.015551598 -0.033407297, + 0.99929589 0.015531898 -0.034153495, + 0.99934125 -0.015023404 0.033035409, + 0.99931109 -0.015799701 0.033582002, + 0.9943549 -0.045170795 0.096010081, + 0.99386662 -0.04961748 0.09882886, + 0.9844349 -0.078855492 0.15706599, + 0.98304766 -0.086741872 0.16153394, + 0.969069 -0.116755 0.217425, + 0.96977699 -0.113692 0.215886, + 0.95274925 -0.14154103 0.26876605, + 0.95773488 -0.12240799 0.26030797, + 0.93982875 -0.14538397 0.30916893, + 0.94506055 -0.12588593 0.30168384, + 0.92619026 -0.14520203 0.3479771, + 0.93144286 -0.12555498 0.34154096, + 0.91147679 -0.14193197 0.38608992, + 0.91663378 -0.12203197 0.38064492, + 0.89535725 -0.13595903 0.42408809, + 0.90030342 -0.11576705 0.4195852, + 0.8778109 -0.12740198 0.46175393, + 0.8823809 -0.10712998 0.45817795, + 0.85845 -0.116775 0.49942699, + 0.8625716 -0.096319556 0.49668175, + 0.83681411 -0.10423002 0.53747404, + 0.84042656 -0.083455563 0.53546077, + 0.81262368 -0.089748673 0.57583684, + 0.81566489 -0.068475395 0.57445794, + 0.78602201 -0.073171198 0.61385298, + 0.7884239 -0.051209893 0.61299694, + 0.75672871 -0.054423083 0.65145975, + 0.75840819 -0.031645708 0.65101117, + 0.72427893 -0.033477496 0.68869394, + 0.72514981 -0.0095504383 0.68852484, + 0.72502899 -0.0094883395 0.68865299, + 0.72506499 -0.000788017 0.68867999, + 0.69010603 0.0013277602 0.72370708, + 0.69006485 -0.010468697 0.72367179, + 0.69042873 -0.010463797 0.72332478, + 0.69047093 0.0013080199 0.72335893, + 0.69038808 0.0013080802 0.72343808, + 0.65420592 -0.0037970794 0.75630689, + 0.65416622 -0.011241804 0.75626731, + 0.65405095 -0.011243199 0.75636691, + 0.65409625 -0.0013293305 0.7564103, + 0.61611992 0.0014897498 0.78765088, + 0.61607099 -0.0119491 0.78759998, + 0.61616468 -0.011948095 0.78752667, + 0.61621308 0.0014852702 0.78757811, + 0.61620975 0.0014852694 0.78758073, + 0.61617988 -0.0091915885 0.78755182, + 0.53616184 0.0015689294 0.84411371, + 0.57684106 -0.0019515502 0.81685412, + 0.576792 -0.0126551 0.81679302, + 0.57684302 -0.0126545 0.81675702, + 0.57689101 -0.00291832 0.81681597, + 0.57941306 -0.0025570602 0.8150301, + 0.093484826 -0.060359821 -0.99378937, + -0.0047935699 0.0557895 -0.99843103, + -0.0052858777 0.055789374 -0.99842852, + 0.026445905 0.030060407 -0.99919826, + 0.033428285 0.022110488 -0.99919653, + 0.078658961 0.022054289 -0.99665755, + 0.10670099 -0.0064931992 -0.99426991, + 0.16407305 -0.0064419913 -0.98642725, + 0.19745795 -0.037292294 -0.97960174, + 0.26681507 -0.036662206 -0.96305025, + 0.31759313 -0.080295533 -0.94482136, + 0.39761201 -0.077698 -0.914258, + 0.4268159 -0.10171898 -0.89859974, + 0.51004285 -0.09674786 -0.85469073, + 0.52946693 -0.11241899 -0.84084886, + 0.6113041 -0.10487402 -0.7844162, + 0.65409893 -0.14053698 -0.74323893, + 0.7422632 -0.12450203 -0.65844119, + 0.075917818 -0.013232603 0.99702626, + 0.067487404 -0.013623402 0.99762714, + 0.067331769 -0.044951178 0.99671751, + 0.11256999 -0.044766996 0.99263489, + 0.11207402 -0.075321309 0.99084109, + 0.15734008 -0.074854836 0.98470348, + 0.15631701 -0.10538101 0.98206913, + 0.201288 -0.104509 0.97394103, + 0.19953798 -0.13489999 0.9705599, + 0.24356188 -0.13352194 0.9606505, + 0.2409111 -0.16373406 0.95663637, + 0.28386194 -0.16176295 0.94512177, + 0.28013694 -0.19188996 0.94058573, + 0.321989 -0.189247 0.92763603, + 0.31698608 -0.21944706 0.92269325, + 0.35757798 -0.21608198 0.9085409, + 0.35111782 -0.24644189 0.90331757, + 0.38973692 -0.24238694 0.88845575, + 0.38167006 -0.27281603 0.88311911, + 0.41845408 -0.26807505 0.86777419, + 0.40857914 -0.29870611 0.86246032, + 0.44369915 -0.29329112 0.84682429, + 0.43174601 -0.32434899 0.84166098, + 0.46534094 -0.31828597 0.82592487, + 0.45104313 -0.34986508 0.82106918, + 0.482577 -0.343339 0.80575299, + 0.48079899 -0.34679899 0.80533397, + 0.51557118 -0.33889511 0.78697932, + 0.52871495 -0.31440398 0.78842288, + 0.5633812 -0.30603212 0.76742828, + 0.57598615 -0.28282607 0.76697415, + 0.61027908 -0.27408203 0.74326205, + 0.62207103 -0.25247499 0.74113703, + 0.65523994 -0.24359497 0.71506792, + 0.66609025 -0.22367108 0.71154422, + 0.69793463 -0.2147619 0.68320173, + 0.70778275 -0.19651793 0.67854577, + 0.73846304 -0.18757802 0.64767808, + 0.74709803 -0.171335 0.64225298, + 0.77652216 -0.16241005 0.6087991, + 0.78343111 -0.14914101 0.60331804, + 0.81102228 -0.14039105 0.56792021, + 0.81797159 -0.12664095 0.56114578, + 0.84380198 -0.118142 0.523489, + 0.85005844 -0.10520694 0.5160737, + 0.87423116 -0.096981622 0.47572511, + 0.8792479 -0.085995294 0.46853793, + 0.90161443 -0.078084335 0.4254342, + 0.90553975 -0.068840884 0.41863891, + 0.92565227 -0.061395217 0.37336108, + 0.9286049 -0.053781692 0.36715198, + 0.94636422 -0.04682941 0.31969008, + 0.94847363 -0.040724885 0.31422788, + 0.96378177 -0.034277491 0.26447994, + 0.96515673 -0.029661292 0.25998595, + 0.97792011 -0.023688404 0.20763204, + 0.97862411 -0.020805102 0.20460203, + 0.9885329 -0.015276498 0.15023099, + 0.98889941 -0.013287691 0.14799091, + 0.99578089 -0.0082060993 0.091394693, + 0.99627924 -0.003791421 0.086101323, + 0.99956924 -0.0012911303 0.029320907, + 0.99962711 0.00029753803 0.027303904, + 0.99960214 -0.00030734504 -0.028203905, + 0.99965113 -0.0016816902 -0.026361704, + 0.99656552 -0.0052718776 -0.082640462, + 0.9969539 -0.0089251092 -0.077481389, + 0.99084938 -0.015445406 -0.13408604, + 0.99174863 -0.020523893 -0.12654395, + 0.98242003 -0.0298873 -0.184276, + 0.98388833 -0.035726711 -0.17517807, + 0.97090352 -0.047853976 -0.23464088, + 0.9728291 -0.053636208 -0.22522603, + 0.95569813 -0.06819021 -0.28634104, + 0.95781636 -0.073177531 -0.27790809, + 0.9355976 -0.089904055 -0.34142986, + 0.93724036 -0.092999928 -0.33605313, + 0.90854573 -0.11143097 -0.40265092, + 0.9085834 -0.11148805 -0.40255019, + 0.87161982 -0.13083297 -0.47239989, + 0.86788458 -0.12612595 -0.48048776, + 0.82080591 -0.14502598 -0.55248994, + 0.81607491 -0.13994898 -0.56074595, + 0.73371708 -0.16452901 -0.65923405, + 0.71110576 -0.14500396 -0.68796974, + 0.636383 -0.159087 -0.75479001, + 0.62081409 -0.14645602 -0.77015615, + 0.53872794 -0.15738899 -0.82764786, + 0.50996989 -0.13435598 -0.84963483, + 0.42529491 -0.14136297 -0.89394677, + 0.36938897 -0.095874988 -0.92431587, + 0.29034603 -0.098727517 -0.95181513, + 0.24996094 -0.064116389 -0.96613073, + 0.18140501 -0.06511981 -0.98125011, + 0.14540392 -0.031603884 -0.98886752, + 0.08946418 -0.031815294 -0.99548179, + 0.082753927 -0.024883609 -0.99625933, + 0.53683203 -0.84368914 0.00033511102, + 0.40719393 -0.9133389 -0.0022486697, + 0.40720585 -0.91333371 -0.0022552893, + 0.40315181 -0.90435058 -0.14006694, + 0.40313992 -0.90435576 -0.14006697, + 0.43582115 -0.89685231 -0.075603828, + 0.41806009 -0.85919917 -0.29496205, + 0.46332201 -0.83817399 -0.287745, + 0.41983092 -0.75707781 -0.50057489, + 0.41897005 -0.74988407 -0.51199406, + 0.37530276 -0.76549453 -0.52265269, + 0.41841906 -0.85626012 -0.30289304, + 0.37270096 -0.87482989 -0.30946198, + 0.39024591 -0.91723377 -0.079939179, + 0.35804501 -0.922243 -0.14584801, + 0.36195388 -0.93219167 0.002826069, + 0.36192292 -0.93220377 0.0028260793, + 0.35801297 -0.92224985 -0.14588298, + 0.35804904 -0.92223614 -0.14588201, + 0.36196011 -0.93218935 0.0028304309, + 0.315685 -0.948632 -0.0209824, + 0.32852098 -0.94442689 -0.011485299, + 0.31575292 -0.94883174 -0.0042991191, + 0.31218812 -0.93823534 -0.14917506, + 0.31219113 -0.93823433 -0.14917506, + 0.34387082 -0.93530661 -0.083392665, + 0.32701102 -0.88821214 -0.32271203, + 0.37312704 -0.87200814 -0.31682503, + 0.33141398 -0.77188289 -0.54255092, + 0.37472108 -0.75850916 -0.53314912, + 0.054964386 -0.10719298 -0.99271774, + -0.03965579 0.14543498 -0.98857278, + -0.041826412 0.14542203 -0.98848522, + -0.07729277 0.22612193 -0.97102761, + -0.083561607 0.22600703 -0.9705351, + -0.078484811 0.21599004 -0.97323614, + -0.067109779 0.21616992 -0.97404665, + -0.064476512 0.21169704 -0.97520626, + -0.047789209 0.21189603 -0.97612309, + -0.043485899 0.20555 -0.97768003, + -0.020628892 0.20569992 -0.97839767, + -0.0092007117 0.19093205 -0.98156023, + 0.022016594 0.19089395 -0.98136377, + 0.030374596 0.18132599 -0.98295391, + 0.068887427 0.18097909 -0.98107147, + 0.078128368 0.17150994 -0.98207963, + 0.125204 0.170682 -0.97733903, + 0.16451694 0.13380395 -0.97725666, + 0.22513489 0.13216893 -0.96532154, + 0.26766598 0.094413288 -0.95887488, + 0.33951291 0.092168279 -0.93607473, + 0.37718105 0.059503108 -0.92422611, + 0.45549184 0.05719658 -0.88840067, + 0.48489511 0.031463306 -0.87400615, + 0.56417716 0.02970341 -0.82511932, + 0.5831129 0.012447897 -0.81229579, + 0.65853918 0.011530903 -0.75245816, + 0.66721869 0.0030699386 -0.74485564, + 0.73527795 0.0027934099 -0.67775995, + 0.73582983 0.0022055595 -0.67716283, + 0.79559702 0.0019731901 -0.60582298, + 0.79099488 0.0074075689 -0.61177796, + 0.84298611 0.0065129912 -0.53789604, + 0.83533591 0.016638298 -0.54948795, + 0.88034588 0.014355998 -0.47411495, + 0.87156957 0.027503688 -0.48949975, + 0.91011697 0.023244601 -0.413699, + 0.90124559 0.038444482 -0.4315998, + 0.93415844 0.031661715 -0.35545117, + 0.92639321 0.047127713 -0.37359709, + 0.95415175 0.037461493 -0.29696995, + 0.94761622 0.05298451 -0.31498608, + 0.97063637 0.039903115 -0.2372191, + 0.96706074 0.050612688 -0.24946295, + 0.98441553 0.034966886 -0.1723469, + 0.9842391 0.035724502 -0.17319702, + 0.99473876 0.020695195 -0.10033198, + 0.99461037 0.021671508 -0.10139304, + 0.99945277 0.0069136983 -0.032346793, + 0.99943286 0.0073980489 -0.032852095, + 0.99947011 -0.0071513909 0.031756803, + 0.99944854 -0.0077003362 0.032302186, + 0.9952541 -0.022564901 0.094658017, + 0.99505365 -0.024328291 0.09631376, + 0.98703289 -0.039311398 0.15562999, + 0.98646885 -0.042419195 0.15836598, + 0.9748891 -0.057617906 0.21510804, + 0.97376579 -0.062227786 0.21887894, + 0.95882475 -0.077663988 0.27317294, + 0.95690835 -0.08403483 0.2779651, + 0.93906534 -0.09947294 0.32903111, + 0.93656522 -0.10658202 0.33389509, + 0.9160707 -0.12194595 0.38202584, + 0.9137429 -0.12784699 0.38565394, + 0.89078468 -0.14299296 0.43134186, + 0.8871156 -0.15149592 0.43597579, + 0.8617152 -0.16654305 0.47928113, + 0.85675502 -0.17719799 0.484326, + 0.82932758 -0.19198591 0.52474475, + 0.82309484 -0.20455295 0.52978587, + 0.79374069 -0.21908693 0.56742984, + 0.786111 -0.23367999 0.572209, + 0.7547608 -0.24801394 0.60730988, + 0.74565178 -0.26468492 0.61151075, + 0.71236515 -0.27877605 0.6440652, + 0.70187396 -0.29729396 0.64729393, + 0.6674493 -0.31079715 0.67669529, + 0.67114395 -0.30428597 0.67599994, + 0.64056998 -0.315193 0.70023102, + 0.65726995 -0.28307799 0.69847196, + 0.62552679 -0.29304889 0.72307575, + 0.63982576 -0.26197892 0.72248876, + 0.60663575 -0.27099892 0.74736375, + 0.61881173 -0.24078688 0.74772567, + 0.58449799 -0.248712 0.77233702, + 0.59484005 -0.21900202 0.77343613, + 0.55925214 -0.22585505 0.79763818, + 0.56794286 -0.19644596 0.79928082, + 0.53051698 -0.202319 0.82317603, + 0.53764606 -0.17328501 0.82517213, + 0.49828181 -0.17818494 0.8485077, + 0.50400871 -0.14928891 0.85069847, + 0.46321201 -0.15318701 0.872908, + 0.46767518 -0.12431104 0.87511528, + 0.4256281 -0.12726504 0.89590424, + 0.42894599 -0.098206401 0.89797598, + 0.38529581 -0.10032295 0.91732359, + 0.38759387 -0.070976578 0.91909367, + 0.34245089 -0.072339676 0.93674666, + 0.34383681 -0.042710681 0.93805754, + 0.29856396 -0.011615499 0.95431888, + 0.29792204 -0.043418411 0.95360225, + 0.20560497 -0.012293098 0.97855788, + 0.20515007 -0.044279713 0.97772837, + 0.15902202 -0.013176702 0.98718715, + 0.15867496 -0.044581987 0.98632377, + 0.20488304 -0.044196211 0.97778821, + 0.204006 -0.074548997 0.97612703, + 0.24948403 -0.073742405 0.96556711, + 0.24789897 -0.10394099 0.96319389, + 0.29249901 -0.102598 0.950746, + 0.29002914 -0.13261206 0.9477855, + 0.33389613 -0.13061604 0.93351638, + 0.3303951 -0.16047604 0.93010026, + 0.37322199 -0.157739 0.91423398, + 0.36852804 -0.18754002 0.91050309, + 0.40956491 -0.18404296 0.89352375, + 0.40350693 -0.21391697 0.88961887, + 0.44287685 -0.20961593 0.87173468, + 0.43526614 -0.23979309 0.86778033, + 0.473077 -0.234658 0.84919602, + 0.46379489 -0.26496595 0.84539181, + 0.50017184 -0.2589789 0.82629168, + 0.48901206 -0.28960702 0.82279712, + 0.52339596 -0.28290397 0.80375487, + 0.51006597 -0.31415701 0.80071098, + 0.54272223 -0.30677015 0.78188539, + 0.52696306 -0.33873904 0.77946514, + 0.55834311 -0.33065709 0.76086718, + 0.5557822 -0.33530912 0.76070631, + 0.59104103 -0.32535201 0.73811698, + 0.60364687 -0.30303195 0.73741585, + 0.63797385 -0.29269594 0.71226281, + 0.64964467 -0.27189389 0.70995462, + 0.68274218 -0.26131606 0.68233216, + 0.69324607 -0.24233703 0.67873603, + 0.72526783 -0.23149794 0.64837885, + 0.73455679 -0.21436696 0.64379585, + 0.76534653 -0.20333289 0.61065567, + 0.77341753 -0.18802688 0.60536861, + 0.80235767 -0.17703594 0.56998283, + 0.80905718 -0.16387604 0.56442112, + 0.83608699 -0.15296499 0.52683997, + 0.84108984 -0.14271997 0.52172691, + 0.8663711 -0.13177001 0.48170307, + 0.87150502 -0.12067 0.475308, + 0.89498788 -0.10976999 0.43237394, + 0.89942014 -0.099440716 0.42562306, + 0.92063373 -0.08882568 0.38018891, + 0.92393339 -0.080373228 0.37401512, + 0.94270903 -0.070091501 0.32617, + 0.94505388 -0.06332849 0.32072198, + 0.96129423 -0.053373512 0.27030507, + 0.96285689 -0.048124794 0.26568896, + 0.97641188 -0.038482998 0.21245897, + 0.97735137 -0.034609612 0.20877407, + 0.98783052 -0.025436686 0.15343992, + 0.98829126 -0.022900505 0.15085103, + 0.99554455 -0.014152193 0.093223758, + 0.99568164 -0.012958095 0.09192507, + 0.99949914 -0.0044176304 0.031338703, + 0.99951249 -0.004083382 0.030954115, + 0.99947888 0.0042218496 -0.032003697, + 0.99954063 0.002714969 -0.030184589, + 0.99547738 0.0085103726 -0.094616637, + 0.99608862 0.0034914389 -0.088290773, + 0.98826355 0.0060360571 -0.15263893, + 0.98967326 -0.0010504503 -0.14333802, + 0.97805148 -0.0015269407 -0.20835811, + 0.98041534 -0.010097004 -0.19668208, + 0.96475625 -0.013491303 -0.26279905, + 0.96794248 -0.022457911 -0.25016612, + 0.94797897 -0.028463 -0.317058, + 0.95176065 -0.037062585 -0.30459487, + 0.92673457 -0.045381878 -0.37296581, + 0.93052942 -0.052508827 -0.36243317, + 0.89935875 -0.062687986 -0.4326939, + 0.90233374 -0.067367986 -0.4257409, + 0.86365002 -0.078786001 -0.497897, + 0.86409456 -0.079378366 -0.49703076, + 0.81659281 -0.091030478 -0.56999087, + 0.81211787 -0.085906193 -0.57713497, + 0.75431383 -0.096656881 -0.64935982, + 0.74131966 -0.08361046 -0.66592371, + 0.67238569 -0.092212453 -0.73443466, + 0.64694029 -0.069165632 -0.75939733, + 0.56859714 -0.074614719 -0.81922519, + 0.52673596 -0.039149296 -0.84912688, + 0.44488794 -0.041247398 -0.89463586, + 0.3899301 0.0041406211 -0.92083526, + 0.31298003 0.0042706407 -0.94975013, + 0.29285896 0.021366198 -0.95591688, + 0.22329086 0.021781787 -0.9745084, + 0.20079203 0.042234104 -0.97872311, + 0.14040299 0.042684995 -0.98917389, + 0.10708396 0.075665168 -0.99136662, + 0.059588708 0.07596761 -0.99532813, + 0.040826481 0.096528657 -0.99449253, + 0.0037487515 0.096608534 -0.99531537, + -0.010907101 0.11464102 -0.99334711, + -0.03886972 0.11456205 -0.99265546, + -0.055658113 0.13798504 -0.98886925, + 0.003497211 0.044207811 -0.99901623, + -0.056052018 0.13798204 -0.98884737, + -0.017098203 0.08003822 -0.99664521, + -0.068900995 0.17155099 -0.98276287, + -0.071262822 0.17152306 -0.98259938, + -0.059386823 0.15303107 -0.98643535, + -0.038004182 0.15319093 -0.9874655, + -0.028407691 0.14012195 -0.98972666, + 0.00061040308 0.14017801 -0.99012613, + 0.013496798 0.12468297 -0.99210477, + 0.05133171 0.12453003 -0.99088722, + 0.076092929 0.097916834 -0.99228138, + 0.12555605 0.097424537 -0.98729134, + 0.14294893 0.080492161 -0.98645151, + 0.20188807 0.079652831 -0.97616434, + 0.21910293 0.064268284 -0.97358274, + 0.28715286 0.063094571 -0.95580453, + 0.34037092 0.017960696 -0.94011974, + 0.41848293 0.017348198 -0.90805888, + 0.46483099 -0.0217588 -0.88513201, + 0.54583299 -0.020591401 -0.837641, + 0.57819587 -0.048825789 -0.81443584, + 0.65525174 -0.045205984 -0.75405669, + 0.67451376 -0.063216679 -0.73555076, + 0.74271607 -0.057337806 -0.66714704, + 0.751396 -0.066312902 -0.65651101, + 0.80933917 -0.059025913 -0.58436811, + 0.81086868 -0.060815077 -0.5820598, + 0.85934412 -0.053142808 -0.50862908, + 0.85663891 -0.049504194 -0.51353592, + 0.89690787 -0.042432595 -0.44017693, + 0.89232957 -0.035265781 -0.45000479, + 0.92539078 -0.029611792 -0.3778559, + 0.92018676 -0.020027794 -0.39096692, + 0.94726962 -0.016393295 -0.32001787, + 0.94239813 -0.0056886002 -0.33444503, + 0.96440214 -0.0044972203 -0.26440203, + 0.96030813 0.006485261 -0.27886602, + 0.97789139 0.0048617818 -0.20905708, + 0.97497112 0.014838802 -0.22183603, + 0.98820567 0.010220196 -0.15279093, + 0.98639452 0.018713791 -0.16332692, + 0.99546188 0.010832499 -0.094541982, + 0.99486148 0.015440907 -0.10006104, + 0.99947822 0.0049260715 -0.031922206, + 0.99946612 0.0052156406 -0.032255404, + 0.99950063 -0.0050438982 0.031193189, + 0.99948555 -0.0054235971 0.031609185, + 0.9955669 -0.015905999 0.09270139, + 0.99539298 -0.017431799 0.094281599, + 0.98790354 -0.028193187 0.15248492, + 0.98740125 -0.030963408 0.15517803, + 0.97657424 -0.042105909 0.21102105, + 0.97558451 -0.046185877 0.2147129, + 0.96159488 -0.057720494 0.26833498, + 0.959939 -0.063272998 0.27297199, + 0.94320136 -0.075017527 0.32364112, + 0.94070464 -0.082191467 0.32911888, + 0.92137134 -0.094174534 0.37710214, + 0.91782838 -0.10319804 0.38332915, + 0.89602631 -0.11542205 0.42873615, + 0.8918131 -0.12518202 0.43474007, + 0.86773384 -0.13752997 0.47762287, + 0.86367518 -0.14629003 0.48235312, + 0.8377499 -0.15848199 0.52254993, + 0.8320598 -0.17010896 0.52795786, + 0.80432415 -0.18222405 0.56555915, + 0.79726917 -0.19598705 0.57092112, + 0.76756972 -0.20811093 0.60623974, + 0.75923532 -0.22375907 0.61114126, + 0.72768599 -0.235825 0.64409602, + 0.71803385 -0.25340194 0.64823979, + 0.68526804 -0.26515502 0.67830706, + 0.67431474 -0.2846449 0.68137878, + 0.64050919 -0.29601806 0.70860517, + 0.62844104 -0.31715202 0.71026504, + 0.59348488 -0.32815591 0.73490781, + 0.59644604 -0.32288304 0.73484606, + 0.56501669 -0.33190486 0.75537765, + 0.58128011 -0.29981005 0.75645715, + 0.54869819 -0.30803213 0.77720428, + 0.56251568 -0.27675587 0.77909064, + 0.52867699 -0.284132 0.79985601, + 0.54031801 -0.25356001 0.80234897, + 0.5047558 -0.2601299 0.82313669, + 0.51451087 -0.22995093 0.82607579, + 0.47697723 -0.23569912 0.84672242, + 0.48504919 -0.20572308 0.84994429, + 0.44616693 -0.21053697 0.86983287, + 0.45265612 -0.18086705 0.87314916, + 0.41218692 -0.18480496 0.89215976, + 0.41729394 -0.15525198 0.89541191, + 0.37527007 -0.15835202 0.91328913, + 0.37914193 -0.12878399 0.9163329, + 0.33551198 -0.13110799 0.93286788, + 0.33829084 -0.10135496 0.93556756, + 0.29365888 -0.10295596 0.95034963, + 0.29550293 -0.072972588 0.95255077, + 0.25016704 -0.07395491 0.96537411, + 0.25122702 -0.043791004 0.96693712, + 0.25207907 -0.013086903 0.96761823, + 0.25154307 -0.043891616 0.96685034, + 0.29754701 -0.043295801 0.95372498, + 0.29632512 -0.073233932 0.95227534, + 0.34160909 -0.072065018 0.93707526, + 0.33952999 -0.101746 0.935076, + 0.38393208 -0.099882126 0.91794324, + 0.38085991 -0.12931897 0.91554475, + 0.42378601 -0.126679 0.89686, + 0.41959986 -0.15595295 0.89421171, + 0.46090713 -0.15247203 0.8742522, + 0.45546505 -0.18169501 0.8715151, + 0.49532217 -0.17729805 0.85042429, + 0.48846531 -0.20669012 0.84775048, + 0.52699494 -0.20130996 0.82568187, + 0.51855999 -0.23103701 0.82323599, + 0.55513698 -0.22474501 0.80081999, + 0.54502231 -0.25473714 0.79878646, + 0.5798139 -0.24754494 0.77623284, + 0.5678342 -0.27797309 0.77478731, + 0.60136294 -0.26981196 0.75203991, + 0.5872187 -0.30102286 0.75137162, + 0.61964804 -0.29189304 0.72858405, + 0.60305899 -0.32404801 0.728912, + 0.63407105 -0.31412703 0.70659608, + 0.63073421 -0.32000908 0.70694315, + 0.66530198 -0.30787501 0.68013698, + 0.67665821 -0.28801209 0.67763025, + 0.7102198 -0.27537093 0.64788783, + 0.72031707 -0.25725102 0.64417803, + 0.75271583 -0.24415994 0.6113959, + 0.76138288 -0.22807796 0.60685796, + 0.79187882 -0.21484196 0.57163888, + 0.79919267 -0.20070091 0.56657767, + 0.82769561 -0.18737891 0.52896976, + 0.83371013 -0.17515801 0.52368605, + 0.86036086 -0.16167098 0.48336494, + 0.86502671 -0.15160795 0.47827181, + 0.88972121 -0.13794403 0.43516409, + 0.89287591 -0.13063999 0.43093595, + 0.91527522 -0.11686703 0.3855041, + 0.91860074 -0.10844298 0.38001692, + 0.93852174 -0.094731681 0.33196792, + 0.94122022 -0.08702112 0.32639208, + 0.95848978 -0.073453486 0.27550295, + 0.9602555 -0.067552269 0.27082488, + 0.97470576 -0.054088891 0.21684796, + 0.97575688 -0.049761694 0.21312498, + 0.98694915 -0.036614105 0.15681502, + 0.98747921 -0.033689607 0.15411003, + 0.99522775 -0.020839494 0.095328279, + 0.99541736 -0.019172808 0.093684629, + 0.99946791 -0.0065399893 0.031956594, + 0.99948752 -0.0060402774 0.031435184, + 0.99945176 0.0062474688 -0.032513492, + 0.99946666 0.0058883778 -0.03212009, + 0.99474764 0.018456992 -0.10067996, + 0.99483967 0.017766295 -0.099891663, + 0.98454189 0.030669795 -0.17244299, + 0.98629349 0.022980388 -0.16339193, + 0.97097576 0.033311293 -0.23684694, + 0.974738 0.021296199 -0.222334, + 0.95477176 0.028350793 -0.29598495, + 0.9598341 0.015517702 -0.28013903, + 0.93523264 0.019580992 -0.35349187, + 0.94153267 0.0063422276 -0.33686188, + 0.91187024 0.0077268719 -0.41040608, + 0.91866964 -0.0044177086 -0.39500186, + 0.88315231 -0.0052459617 -0.46905717, + 0.88974768 -0.015403095 -0.45619285, + 0.84739912 -0.017917302 -0.53065407, + 0.85234398 -0.0245525 -0.52240503, + 0.80237466 -0.028018987 -0.59616268, + 0.8039428 -0.029871793 -0.59395587, + 0.74535275 -0.033486389 -0.66582876, + 0.74069619 -0.028574808 -0.67123216, + 0.67279005 -0.031466704 -0.73916405, + 0.65896869 -0.018220691 -0.75194967, + 0.5828619 -0.019683894 -0.81233281, + 0.55764711 0.0028582907 -0.83007318, + 0.47751081 0.0030254489 -0.87862068, + 0.4407542 0.034662616 -0.89695841, + 0.36230478 0.035992179 -0.93136448, + 0.31594697 0.07575319 -0.94574785, + 0.24550205 0.077399418 -0.96630126, + 0.19816096 0.11932797 -0.97287875, + 0.140614 0.120534 -0.98269999, + 0.12727603 0.13323402 -0.98287827, + 0.079113007 0.13390602 -0.98783112, + 0.066565596 0.14710198 -0.98687887, + 0.026944287 0.14737593 -0.9887135, + 0.0095637357 0.16778892 -0.98577654, + -0.020166703 0.16776301 -0.98562109, + -0.02823391 0.17846906 -0.98354036, + -0.050487392 0.17831199 -0.98267788, + -0.056144185 0.18689196 -0.98077476, + -0.072034724 0.18670106 -0.97977233, + -0.08012598 0.20083496 -0.97634274, + -0.075609915 0.20090604 -0.97668827, + -0.030645508 0.11119303 -0.99332625, + 0.278422 -0.609541 -0.74225402, + 0.17921294 -0.38264886 -0.90634573, + 0.19519188 -0.38146377 -0.90354049, + 0.083606996 -0.14499998 -0.98589289, + 0.094000913 -0.14486502 -0.98497611, + -0.027751587 0.094050959 -0.99518055, + -0.029597497 0.094045885 -0.99512786, + 0.10664193 -0.15741591 -0.9817574, + 0.095483474 -0.15759495 -0.98287678, + 0.21201 -0.38945901 -0.89631099, + 0.19530907 -0.39084414 -0.89949727, + 0.29586396 -0.60622293 -0.73821294, + 0.29678804 -0.59561908 -0.74642807, + 0.31913498 -0.61408591 -0.72183895, + 0.21237205 -0.3993071 -0.89188123, + 0.22975494 -0.39769691 -0.88828474, + 0.10858096 -0.17079994 -0.97930467, + 0.12080096 -0.17055795 -0.97791463, + -0.012920304 0.062179223 -0.99798137, + -0.013766002 0.062178608 -0.9979701, + 0.13638704 -0.18445304 -0.97333223, + 0.12326898 -0.18477298 -0.97501987, + 0.24858503 -0.40598106 -0.87942314, + 0.23037305 -0.40786508 -0.88350123, + 0.33719814 -0.61002028 -0.71705836, + 0.33770484 -0.59948373 -0.72565466, + 0.36207309 -0.61757714 -0.69821316, + 0.24948394 -0.4166269 -0.87417382, + 0.268462 -0.41443801 -0.86957997, + 0.13939595 -0.19930792 -0.96997166, + 0.15363398 -0.19888397 -0.96790588, + 0.0090681454 0.025738187 -0.99962753, + 0.0096224146 0.025738113 -0.99962246, + 0.17269102 -0.21388602 -0.96147311, + 0.15723999 -0.21444698 -0.96399587, + 0.28949809 -0.42284414 -0.85871631, + 0.26964498 -0.42539793 -0.86390287, + 0.38076583 -0.61262268 -0.69261163, + 0.3808929 -0.60189688 -0.70188379, + 0.46394107 -0.73894608 -0.48858705, + 0.47329083 -0.60086477 -0.64417177, + 0.55444902 -0.70893502 -0.43588701, + 0.52119732 -0.59620535 -0.61064935, + 0.59878987 -0.68962383 -0.40727091, + 0.55588275 -0.71576065 -0.42270678, + 0.59482801 -0.76807803 -0.237141, + 0.56755 -0.82042801 -0.069173001, + 0.5518322 -0.79684031 -0.24602209, + 0.49476293 -0.86902785 -0.00051527895, + 0.49471 -0.86905801 -0.00048675499, + 0.49062493 -0.86198187 -0.12757099, + 0.49067813 -0.86195219 -0.12756702, + 0.5245102 -0.84851128 -0.070125923, + 0.50770187 -0.82036179 -0.26314494, + 0.55200922 -0.79399037 -0.25468612, + 0.51069379 -0.73239964 -0.45031378, + 0.42635885 -0.60253274 -0.67466474, + 0.50938791 -0.72529781 -0.46310589, + 0.46504694 -0.74615794 -0.47642395, + 0.50792819 -0.81745732 -0.27161109, + 0.46303278 -0.84112656 -0.27947587, + 0.48053017 -0.87398428 -0.072403923, + 0.44758487 -0.88421679 -0.13352297, + 0.45167178 -0.89218259 0.0017214292, + 0.45152014 -0.8922593 0.0017214906, + 0.44742012 -0.88426524 -0.13375503, + 0.44743812 -0.88425624 -0.13375403, + 0.45153812 -0.89225024 0.0017243205, + 0.42386207 -0.90560311 -0.014971701, + -0.99705201 -0.076727398 -0.00046187101, + -0.97867239 -0.20537308 0.0047339117, + -0.97804767 -0.20504892 -0.037117586, + -0.98699147 -0.15820208 -0.028637514, + -0.98640776 -0.15794095 -0.045325588, + -0.99291635 -0.11420604 -0.03277481, + -0.94333977 0.24057794 0.22854394, + -0.92773724 0.27059707 0.25706205, + -0.9266119 0.26567298 0.26609796, + -0.91043222 0.29226705 0.29273406, + -0.90891302 0.28607401 0.303379, + -0.8906281 0.31197003 0.33084202, + -0.88862276 0.30430993 0.34313992, + -0.86803013 0.32943904 0.37147504, + -0.86548632 0.32027712 0.38517016, + -0.84276986 0.34415197 0.41388193, + -0.83960772 0.33331987 0.42890185, + -0.81460541 0.35591474 0.45797667, + -0.81071728 0.34315312 0.47432417, + -0.78311354 0.3645128 0.50384873, + -0.77839732 0.34956512 0.52144217, + -0.74803704 0.36954704 0.55124909, + -0.74252582 0.3525269 0.5695439, + -0.70978808 0.37073603 0.59896207, + -0.70347321 0.35153311 0.61769724, + -0.66844529 0.36787519 0.64641231, + -0.66128397 0.34620997 0.66546392, + -0.62370896 0.36075798 0.69342697, + -0.61574012 0.33651409 0.71247619, + -0.57566899 0.34921199 0.739362, + -0.56706303 0.32255104 0.75789213, + -0.52533299 0.33321199 0.78293997, + -0.51625592 0.30420998 0.80058485, + -0.47315612 0.31292909 0.82352817, + -0.46380806 0.28167504 0.83996511, + -0.41939691 0.28862694 0.86069781, + -0.41004601 0.255362 0.87558699, + -0.36465281 0.26070389 0.8939026, + -0.3556259 0.22585094 0.90692979, + -0.31019884 0.22972789 0.92249757, + -0.30169511 0.19329508 0.93360436, + -0.25669792 0.19594893 0.94641966, + -0.2504389 0.16524594 0.95392567, + -0.20576903 0.16703302 0.96424013, + -0.20163497 0.14271298 0.96900791, + -0.15834606 0.14386705 0.97684634, + -0.15420707 0.11248804 0.98161435, + -0.11116701 0.11314402 0.98734009, + -0.10796102 0.07910122 0.99100322, + -0.065502286 0.079395376 0.99468875, + -0.063524619 0.044418715 0.99699134, + -0.021533607 0.044498216 0.99877733, + -0.0208642 0.00908521 0.99974102, + 0.020567505 0.0090852622 0.99974722, + 0.021235999 0.044495896 0.99878389, + 0.063151106 0.044417102 0.99701512, + 0.065124683 0.079381675 0.99471474, + 0.10761794 0.079088561 0.99104154, + 0.11081995 0.11317495 0.9873755, + 0.15385106 0.11252104 0.98166639, + 0.15801105 0.14416103 0.97685724, + 0.20144592 0.14300196 0.96900463, + 0.20561296 0.16755596 0.96418273, + 0.25037807 0.16576104 0.95385224, + 0.25654787 0.19603992 0.94644153, + 0.30159998 0.19338296 0.93361688, + 0.31001282 0.22940487 0.92264044, + 0.35537499 0.22554199 0.90710503, + 0.36432803 0.26007202 0.8942191, + 0.40967801 0.25475499 0.87593597, + 0.41903007 0.28797704 0.86109412, + 0.46336389 0.28106093 0.84041584, + 0.47270724 0.31225315 0.82404244, + 0.51577896 0.30357298 0.80113387, + 0.52488518 0.33261913 0.78349233, + 0.56658512 0.3220011 0.75848317, + 0.57524115 0.34876409 0.73990619, + 0.61531913 0.33609807 0.71303618, + 0.62335473 0.36050689 0.69387579, + 0.66093475 0.34598488 0.66592777, + 0.66814196 0.36775696 0.64679295, + 0.70320505 0.35142303 0.61806506, + 0.70957279 0.3707689 0.59919685, + 0.74231595 0.35257298 0.56978893, + 0.74785304 0.36966303 0.55142105, + 0.77825916 0.34966108 0.52158409, + 0.78299153 0.36465478 0.50393569, + 0.81061834 0.34328315 0.47439924, + 0.81452513 0.35610604 0.45797107, + 0.83953899 0.33349901 0.42889699, + 0.84271187 0.34436998 0.41381893, + 0.8654539 0.32046098 0.38508993, + 0.86799932 0.32963711 0.37137112, + 0.88859868 0.30449089 0.34304187, + 0.89061022 0.31218305 0.3306891, + 0.90890324 0.28626207 0.30323106, + 0.91042525 0.29247707 0.29254606, + 0.92661399 0.26585099 0.26591301, + 0.92773664 0.27077192 0.2568799, + 0.94207889 0.24331696 0.23083398, + 0.9428941 0.24718203 0.22327504, + 0.94361466 0.27757692 0.18039495, + 0.99974477 -0.022043994 -0.0049518184, + 0.99973273 -0.022010094 -0.0070763682, + 0.99973601 0.021876 0.0070332401, + 0.99972123 0.021831706 0.0089937216, + 0.99751252 0.065175273 0.026849488, + 0.99752462 0.065196075 0.02634369, + 0.94288588 0.29432696 0.15600598, + 0.95459467 0.26321891 0.13951595, + 0.95529687 0.26917398 0.12228298, + 0.96552688 0.23699497 0.10766298, + 0.96592677 0.24109994 0.09410838, + 0.97483736 0.20765908 0.081055328, + 0.97507513 0.21066204 0.069642209, + 0.98272437 0.17572206 0.058091924, + 0.982678 0.17520601 0.060389299, + 0.98849809 0.14297901 0.049281806, + 0.98833388 0.14220898 0.054522794, + 0.99335426 0.10746902 0.04120351, + 0.99327701 0.107331 0.043368701, + 0.99324054 0.10853795 0.04114398, + 0.99748546 0.066269733 0.025121212, + 0.99759489 0.066393994 0.019904498, + 0.99973577 0.022018194 0.0066009285, + 0.99974614 0.022049502 0.0046330406, + 0.999744 -0.0221423 -0.0046525602, + 0.99974525 -0.022145206 -0.0043711509, + 0.99973565 -0.022563493 -0.0044048284, + 0.99974465 -0.022561193 -0.0012942696, + 0.99734211 -0.071945108 -0.011522501, + 0.99740833 -0.071939826 0.0011392303, + 0.99739563 -0.072116077 0.0011393595, + 0.99738985 -0.072119392 -0.0035184396, + 0.99772513 -0.067274511 -0.0043273303, + 0.99762821 -0.067159615 -0.015086204, + 0.99330223 -0.11235803 -0.026954006, + 0.99763387 -0.066854492 -0.016038198, + 0.99750614 -0.066736311 -0.022974903, + 0.99973261 -0.021864492 -0.0075271572, + 0.99971449 -0.021814188 -0.0097491657, + 0.99972373 0.021458395 0.0095901582, + 0.99972361 0.021457892 0.009603966, + 0.99754041 0.06397716 0.028634483, + 0.997572 0.064058103 0.027324099, + 0.99402326 0.10041502 0.042832211, + 0.99412823 0.10099202 0.038856208, + 0.98961574 0.13415197 0.051614389, + 0.98965621 0.13459103 0.04965781, + 0.98348701 0.169791 0.062645003, + 0.9832775 0.16742708 0.071648434, + 0.9758569 0.20079698 0.085928991, + 0.97551525 0.19756004 0.096644223, + 0.96682239 0.22946508 0.11225104, + 0.96621555 0.2245709 0.12647294, + 0.95616353 0.25515187 0.14369692, + 0.95515567 0.24827892 0.16135395, + 0.95525336 0.23253308 0.18281005, + 0.95659512 0.24036004 0.16478102, + 0.96656066 0.21150692 0.14500095, + 0.96739364 0.21718493 0.13030796, + 0.97595102 0.18692601 0.112153, + 0.97643948 0.19082609 0.10075404, + 0.9836911 0.15905702 0.08398021, + 0.98395276 0.16149595 0.075868085, + 0.98995399 0.12797201 0.0601191, + 0.99011064 0.12973295 0.053388983, + 0.9947421 0.094705515 0.038974304, + 0.99471366 0.094366863 0.040491585, + 0.99786901 0.059962198 0.025729001, + 0.99782223 0.059598815 0.028262008, + 0.99972838 0.021059008 0.0099862441, + 0.99972445 0.021032309 0.010427805, + 0.99971426 -0.021416705 -0.010618303, + 0.99971652 -0.02142599 -0.010384696, + 0.99729866 -0.066099279 -0.032036889, + 0.99750215 -0.066284008 -0.024412403, + 0.99290389 -0.11159199 -0.041099295, + 0.99331415 -0.11183502 -0.028635703, + 0.9873035 -0.15841192 -0.011719895, + 0.98660791 -0.15801199 -0.040459696, + 0.89264458 -0.44739878 -0.054955374, + 0.934228 -0.27803001 -0.22342201, + 0.92393398 -0.273112 -0.26787299, + 0.94810277 -0.22700194 -0.22264594, + 0.94940948 -0.2277181 -0.2162551, + 0.97228163 -0.16954294 -0.16100794, + 0.9740265 -0.17181192 -0.14748892, + 0.98698634 -0.12201405 -0.10474104, + 0.9873265 -0.12306794 -0.10020296, + 0.99410576 -0.084071875 -0.068452485, + 0.99395579 -0.083254576 -0.071557686, + 0.99800134 -0.047924519 -0.041191414, + 0.9979775 -0.047668021 -0.042056918, + 0.99979526 -0.015174604 -0.013388303, + 0.99979013 -0.014979202 -0.013976102, + 0.99980336 0.014501706 0.013530605, + 0.99979651 0.014209193 0.014318894, + 0.99823487 0.041832697 0.042155597, + 0.99815965 0.040668786 0.044982184, + 0.99511653 0.066197671 0.073218763, + 0.99486703 0.063758299 0.078578599, + 0.99032313 0.087442808 0.10776801, + 0.98975343 0.083345547 0.11593793, + 0.98360598 0.105261 0.146422, + 0.98249787 0.098988086 0.15779498, + 0.97470403 0.11877 0.18933, + 0.97279435 0.10991704 0.20393507, + 0.96315211 0.12760802 0.23675802, + 0.96004546 0.11551605 0.25489011, + 0.31067395 -0.035138194 0.94986677, + 0.27548599 -0.035537001 0.960648, + 0.26762098 -0.067058891 0.9611879, + 0.22888903 -0.06774991 0.9710921, + 0.221981 -0.100073 0.96990198, + 0.18340296 -0.10089198 0.97784674, + 0.17759395 -0.13377796 0.97496867, + 0.13920796 -0.13461596 0.98107064, + 0.13457404 -0.16809806 0.97654134, + 0.096791066 -0.16884494 0.98087865, + 0.093396991 -0.20293997 0.97472686, + 0.056437384 -0.20350595 0.97744578, + 0.054383889 -0.23765995 0.96982479, + 0.018240491 -0.23797289 0.97110051, + 0.017551105 -0.2720241 0.96213037, + -0.017719194 -0.2720229 0.96212763, + -0.018411696 -0.23796694 0.97109878, + -0.054545667 -0.23765285 0.9698174, + -0.056599684 -0.20355695 0.97742575, + -0.093540967 -0.20298992 0.97470266, + -0.096928619 -0.16896005 0.98084521, + -0.13463502 -0.16821301 0.97651315, + -0.139286 -0.134599 0.981062, + -0.17766401 -0.13376202 0.97495812, + -0.18349595 -0.10074098 0.97784477, + -0.22211097 -0.099921688 0.96988785, + -0.229027 -0.067556702 0.97107297, + -0.2678279 -0.066865876 0.96114361, + -0.27570492 -0.035281688 0.96059465, + -0.31476802 -0.034838505 0.94852912, + -0.32340303 -0.0044183806 0.94625109, + -0.36251909 -0.0043516811 0.93196625, + -0.59330302 0.080260701 0.80096799, + -0.62668699 0.077697396 0.775388, + -0.63292783 0.090842277 0.76886284, + -0.66854376 0.087259173 0.73853576, + -0.67624056 0.10319894 0.72941661, + -0.71044058 0.098586738 0.69681758, + -0.72037023 0.11924504 0.68326223, + -0.75230283 0.11326697 0.6490078, + -0.76109588 0.13197199 0.63507193, + -0.79057485 0.12459097 0.59955686, + -0.7980392 0.14098904 0.5858801, + -0.82522702 0.132144 0.54912502, + -0.83143401 0.14636099 0.53600001, + -0.85631102 0.13604499 0.49822, + -0.86134428 0.14819206 0.48592716, + -0.88356942 0.13660505 0.4479332, + -0.88758332 0.14691806 0.43659014, + -0.90724921 0.13414402 0.39862809, + -0.91036612 0.14276302 0.38839707, + -0.92971265 0.12705895 0.34567389, + 0.46545106 0.11411601 0.87768614, + 0.51221603 0.11073501 0.85168815, + 0.51642907 0.12118302 0.8477121, + 0.55621499 0.117604 0.82267499, + 0.56463194 0.13743898 0.81381887, + 0.60283887 0.13286297 0.78672284, + 0.61372614 0.15790504 0.7735672, + 0.65024495 0.15194598 0.74437493, + 0.66043472 0.17522691 0.73015165, + 0.69529378 0.16772294 0.69888175, + 0.70454782 0.18895295 0.68403882, + 0.73748004 0.17982301 0.65098906, + 0.74563503 0.19880803 0.63600606, + 0.77600282 0.18817796 0.60200387, + 0.78305614 0.20500903 0.58719206, + 0.8108288 0.19292195 0.55257386, + 0.81680429 0.20767607 0.53823918, + 0.84222412 0.19407403 0.50298506, + 0.84719086 0.20689197 0.48934993, + 0.87030029 0.19179508 0.45364314, + 0.8742519 0.20255996 0.44119495, + 0.89479429 0.18629105 0.40575716, + 0.89789569 0.19529192 0.39451784, + 0.91602677 0.17794995 0.3594839, + 0.91840714 0.18538302 0.34951603, + 0.93440223 0.16691405 0.31469408, + 0.93618226 0.17296705 0.30601507, + 0.95136374 0.15158997 0.26819295, + 0.95354927 -0.29782507 -0.04521041, + -0.29228505 0.10027903 0.95105922, + -0.32982191 0.098990574 0.93883878, + -0.95353585 0.17149799 0.24770497, + -0.93906534 0.19566707 0.28261408, + -0.93764025 0.19039704 0.29082605, + -0.9223429 0.21162997 0.32325897, + -0.92040002 0.20501401 0.33291599, + -0.903063 0.225218 0.365724, + -0.90047622 0.21702604 0.37688509, + -0.88082427 0.23625706 0.41028208, + -0.87754422 0.22650807 0.4226231, + -0.85540581 0.24467695 0.4565239, + -0.85133046 0.23320086 0.46995074, + -0.8269223 0.24995309 0.5037092, + -0.82192087 0.23648497 0.51818997, + -0.79515213 0.25176704 0.55167603, + -0.78912169 0.23610091 0.56704783, + -0.75971287 0.24994797 0.60030192, + -0.7526533 0.23210108 0.61615121, + -0.7205658 0.24442793 0.64887583, + -0.71248984 0.22435895 0.66484684, + -0.6782822 0.23494905 0.69622719, + -0.66916007 0.21244404 0.71210408, + -0.63301319 0.22131306 0.7418322, + -0.62300086 0.19653496 0.75712883, + -0.58483493 0.20380397 0.78513187, + -0.57410896 0.17687598 0.79944587, + -0.53413808 0.18262501 0.82543612, + -0.52286208 0.15355702 0.83847213, + -0.48203993 0.15783198 0.86181587, + -0.47317082 0.13393095 0.8707307, + -0.43179405 0.13712402 0.89148813, + -0.42513114 0.11791504 0.89741832, + -0.38573885 0.12019096 0.91474569, + -0.37995985 0.10165096 0.91940063, + -0.33455789 0.10355996 0.93666762, + -0.34091991 0.12643097 0.93155175, + -0.38155818 0.12431306 0.91594744, + -0.38794315 0.14463404 0.91026431, + -0.43038315 0.14164604 0.89146328, + -0.43905213 0.16707106 0.88279128, + -0.48078594 0.16304998 0.86154491, + -0.49185377 0.19372891 0.84885156, + -0.53296691 0.18826897 0.82492489, + -0.54368681 0.21688193 0.81078172, + -0.58373702 0.20981599 0.784365, + -0.59394908 0.23639002 0.76898915, + -0.63200581 0.22771095 0.74075383, + -0.6414367 0.25193989 0.72462761, + -0.67738718 0.24157906 0.69482815, + -0.6858812 0.26336405 0.6783852, + -0.71978116 0.25123605 0.6471442, + -0.72734696 0.27080998 0.63057792, + -0.75902712 0.25691602 0.59822404, + -0.76557797 0.27418199 0.58199197, + -0.79456419 0.25877106 0.54927713, + -0.8000893 0.2737481 0.53377819, + -0.82642317 0.25694105 0.50100511, + -0.83100897 0.26983699 0.48642799, + -0.85498816 0.25159207 0.45353812, + -0.85875016 0.26266506 0.43994913, + -0.88048214 0.24302404 0.40705106, + -0.88350213 0.25241503 0.39460206, + -0.90278876 0.23175494 0.3623009, + -0.90510869 0.23944591 0.35134587, + -0.92212898 0.217878 0.31969899, + -0.92388135 0.22411707 0.3101851, + -0.93890637 0.20156607 0.2789731, + -0.94019651 0.20655189 0.27086288, + -0.95334899 0.18304799 0.24004, + -0.95001179 -0.29539993 -0.10107598, + -0.96487635 -0.24855709 -0.085047632, + -0.96230602 -0.24745201 -0.112848, + -0.97533566 -0.20082892 -0.091585971, + -0.97268599 -0.19967601 -0.11837, + -0.98426837 -0.15198205 -0.090096027, + -0.98324138 -0.15136506 -0.10161204, + -0.99189025 -0.10552502 -0.070839211, + -0.99199349 -0.10563405 -0.06921313, + -0.99757802 -0.0581806 -0.038120698, + -0.99766755 -0.058638468 -0.034941584, + -0.99978149 -0.01796061 -0.010702404, + -0.99978286 -0.018009298 -0.010482299, + -0.99979699 0.0174137 0.0101355, + -0.99979287 0.017234698 0.010828199, + -0.9982065 0.050689977 0.031847283, + -0.99817222 0.050123211 0.033763207, + -0.99515635 0.081532732 0.054920819, + -0.99502337 0.08005473 0.059328523, + -0.99062526 0.10975303 0.08133772, + -0.99032611 0.10720202 0.088101506, + -0.9845261 0.13538502 0.11126202, + -0.98394036 0.13132605 0.12089205, + -0.9767769 0.15763699 0.14511198, + -0.97572976 0.15157297 0.15804096, + -0.96708155 0.17613791 0.18365391, + -0.96537286 0.16772498 0.19980897, + -0.95506763 0.19055893 0.22700892, + -0.95509279 0.19039096 0.22704394, + -0.94114864 0.21717593 0.25898591, + -0.93997574 0.21242796 0.26705796, + -0.92518187 0.23625997 0.29701796, + -0.92359543 0.23033911 0.30645615, + -0.90684402 0.25322899 0.33691099, + -0.90475124 0.24595906 0.34774908, + -0.88578576 0.26799095 0.37889892, + -0.88306791 0.25912797 0.39120793, + -0.8616938 0.28021294 0.42304191, + -0.85823268 0.26953891 0.43678984, + -0.83462697 0.28926 0.46875, + -0.83040029 0.2768231 0.48353317, + -0.80446386 0.29512498 0.51549894, + -0.7993868 0.28073993 0.5311929, + -0.77079886 0.29768497 0.56325191, + -0.76477683 0.28111193 0.57973486, + -0.73347884 0.29656494 0.6116029, + -0.72644657 0.27759683 0.62866163, + -0.69285196 0.29127198 0.65963393, + -0.68487394 0.26997596 0.67680192, + -0.64918399 0.281822 0.706496, + -0.64034104 0.25821403 0.72338706, + -0.60237575 0.26834092 0.75175571, + -0.59275377 0.24235891 0.7680527, + -0.55264521 0.2507951 0.79478627, + -0.54240692 0.22248697 0.81011987, + -0.50108278 0.2291829 0.83450061, + -0.49052799 0.198916 0.84841901, + -0.44832411 0.20403905 0.87027216, + -0.43765685 0.17187095 0.8825627, + -0.39477307 0.17562501 0.90183711, + -0.38645694 0.14869699 0.9102419, + -0.34297892 0.15144297 0.92705476, + -0.33698902 0.13002402 0.93248713, + -0.29569986 0.13192494 0.94612753, + -0.28872284 0.10326394 0.95182753, + -0.2472759 0.10450796 0.96329266, + -0.24071789 0.07289996 0.96785355, + -0.19907196 0.073605284 0.97721678, + -0.19345105 0.04070501 0.98026526, + -0.151821 0.041007798 0.98755699, + -0.147321 0.0072752 0.98906201, + -0.10612104 0.007313923 0.99432635, + -0.10283105 -0.027108112 0.99432945, + -0.062325709 -0.027199704 0.99768513, + -0.060311507 -0.062227607 0.99623811, + -0.020378293 -0.062327977 0.99784762, + -0.019699091 -0.097581655 0.99503255, + 0.019588394 -0.097581878 0.99503475, + 0.020266891 -0.06235107 0.99784851, + 0.060126685 -0.062251084 0.99624777, + 0.062138472 -0.027284887 0.99769455, + 0.10260702 -0.027193505 0.99435025, + 0.10589502 0.0072065117 0.99435127, + 0.14702399 0.0071685091 0.98910689, + 0.151527 0.040915299 0.98760599, + 0.19312793 0.040613987 0.98033261, + 0.19875591 0.073572859 0.97728354, + 0.24036606 0.072869718 0.96794325, + 0.24694106 0.10459402 0.96336925, + 0.95510989 0.19052097 0.22686297, + 0.941158 0.21734799 0.25880799, + 0.9399839 0.21258897 0.26690096, + 0.92518735 0.23644608 0.29685313, + 0.92359489 0.23049697 0.30633897, + 0.90683377 0.25341594 0.33679792, + 0.90473598 0.246124 0.34767199, + 0.88575727 0.26818106 0.37883109, + 0.88302547 0.25926986 0.39120975, + 0.86164069 0.28036892 0.42304686, + 0.85815799 0.26962599 0.436883, + 0.83454001 0.289352 0.46884799, + 0.83027387 0.27680597 0.48375994, + 0.80431366 0.29510686 0.51574373, + 0.79920012 0.28063503 0.53152907, + 0.77059513 0.29756504 0.56359404, + 0.76450688 0.28083697 0.58022392, + 0.73317021 0.29627311 0.61211425, + 0.72606897 0.277156 0.62929201, + 0.69247282 0.29078895 0.66024482, + 0.68442607 0.26935202 0.67750305, + 0.64872503 0.28115204 0.70718408, + 0.63984674 0.2574999 0.72407877, + 0.60191202 0.26757199 0.75240099, + 0.59227508 0.24160303 0.76866013, + 0.55217409 0.24999607 0.79536515, + 0.54195672 0.22179587 0.81061053, + 0.50069219 0.22845207 0.83493531, + 0.49022219 0.19846907 0.84870028, + 0.44810012 0.20356604 0.87049818, + 0.43761387 0.17195895 0.88256675, + 0.39468899 0.175717 0.90185601, + 0.38658708 0.14947502 0.91005921, + 0.34297588 0.15224394 0.92692465, + 0.33689696 0.13047099 0.93245786, + 0.29547101 0.132384 0.94613498, + 0.28841606 0.10335002 0.95191121, + 0.29199201 0.100357 0.951141, + 0.32951301 0.099070102 0.93893898, + 0.95355237 0.17161407 0.24756108, + 0.93907475 0.19581796 0.28247795, + 0.93764597 0.190529 0.290721, + 0.9223401 0.21178903 0.32316303, + 0.92038238 0.20512107 0.33289912, + 0.90304011 0.22533603 0.36570802, + 0.90043873 0.21709692 0.37693384, + 0.88076824 0.23634405 0.41035208, + 0.87745988 0.22651596 0.42279395, + 0.85530901 0.244683 0.45670199, + 0.8511827 0.2330749 0.47028083, + 0.82675928 0.24981108 0.50404716, + 0.82169211 0.23618802 0.51868808, + 0.7949053 0.25143909 0.55218118, + 0.78880221 0.23562007 0.5676921, + 0.75936365 0.24942788 0.60095972, + 0.75223017 0.23143706 0.61691713, + 0.72013992 0.24370597 0.64961994, + 0.7120114 0.22355914 0.66562843, + 0.6777848 0.23409495 0.69699883, + 0.6686697 0.21166089 0.71279764, + 0.63253874 0.22047593 0.74248576, + 0.62253201 0.19576401 0.75771397, + 0.58441186 0.20298496 0.78565884, + 0.57378513 0.17634705 0.79979515, + 0.5338279 0.18207195 0.82575881, + 0.52281284 0.15368894 0.83847868, + 0.48198095 0.15796798 0.86182386, + 0.47341201 0.13486101 0.87045598, + 0.43192494 0.13808699 0.89127588, + 0.42512894 0.11846498 0.89734685, + 0.38563415 0.12075704 0.91471529, + 0.37973014 0.10178903 0.91948038, + 0.33431408 0.10370002 0.93673927, + 0.34076592 0.12693398 0.93153977, + 0.3815349 0.12480097 0.91589075, + 0.38803184 0.14551096 0.91008669, + 0.430554 0.142498 0.89124501, + 0.43898311 0.16723704 0.88279426, + 0.48072389 0.16321196 0.86154884, + 0.49155983 0.19322893 0.8491357, + 0.53264219 0.18779208 0.82524329, + 0.54326022 0.21609211 0.81127834, + 0.58330172 0.20906289 0.78488964, + 0.59349072 0.23552687 0.76960766, + 0.63152784 0.22689794 0.74141079, + 0.64096522 0.25108808 0.72534025, + 0.67688298 0.24078999 0.695593, + 0.68543971 0.26268387 0.67909467, + 0.71934599 0.250606 0.64787197, + 0.72697699 0.270302 0.63122201, + 0.75867486 0.25644898 0.59887093, + 0.76530886 0.27390096 0.58247793, + 0.79431129 0.25851709 0.54976219, + 0.79990345 0.27365115 0.53410631, + 0.8262549 0.25685596 0.50132596, + 0.830881 0.26985401 0.486637, + 0.85489011 0.25159904 0.45371905, + 0.85867786 0.26274398 0.44004294, + 0.88042486 0.24309397 0.40713295, + 0.88346326 0.25254607 0.3946051, + 0.90276289 0.23186697 0.36229396, + 0.90509731 0.23960608 0.35126612, + 0.92212391 0.21801797 0.31961796, + 0.92388326 0.22428806 0.31005606, + 0.93891323 0.20171104 0.27884507, + 0.94020754 0.20672089 0.27069589, + 0.95335978 0.18319196 0.23988694, + 0.9550795 0.19072191 0.2268219, + 0.96538788 0.16785498 0.19962697, + 0.96709275 0.17626895 0.18346895, + 0.97574013 0.15168001 0.15787502, + 0.97678661 0.15775494 0.14491795, + 0.98395014 0.13141201 0.12071902, + 0.98453873 0.13550597 0.11100297, + 0.99033552 0.10728995 0.087888658, + 0.9906354 0.10986293 0.081064954, + 0.99502963 0.080127172 0.059123777, + 0.99515635 0.081540532 0.05490962, + 0.99817222 0.050127011 0.033755708, + 0.99820745 0.050708622 0.031789716, + 0.99979299 0.017240399 0.0108082, + 0.99979788 0.017456798 0.0099704992, + 0.99978399 -0.0180481 -0.0103082, + 0.99978137 -0.017959006 -0.010710604, + 0.9976669 -0.058634091 -0.034968898, + 0.9975751 -0.058165807 -0.038218603, + 0.9919821 -0.10561901 -0.069398411, + 0.99181437 -0.10544304 -0.072014421, + 0.98307914 -0.15126802 -0.10331202, + 0.98391575 -0.15175997 -0.094226979, + 0.97206742 -0.19939388 -0.12380192, + 0.97543025 -0.20084004 -0.090549521, + 0.96245003 -0.24747001 -0.111573, + 0.9654789 -0.24879996 -0.077129893, + 0.95085979 -0.29573694 -0.091680877, + 0.95364922 -0.29704407 -0.048145313, + 0.93837351 -0.34459817 -0.026596813, + 0.93728912 -0.34406304 -0.055766106, + 0.92029661 -0.39113382 -0.008282816, + 0.91833621 -0.39002109 -0.067396715, + 0.93741035 -0.34314111 -0.059295822, + 0.93327588 -0.34108996 -0.11248899, + 0.95080686 -0.29419798 -0.097024985, + 0.94601035 -0.29201713 -0.14067905, + 0.96215165 -0.24550991 -0.11827496, + 0.95605999 -0.242907 -0.164151, + 0.97187102 -0.195135 -0.131868, + 0.969666 -0.194015 -0.148681, + 0.98264599 -0.147231 -0.112827, + 0.98304188 -0.14752798 -0.10892299, + 0.99281442 -0.096268043 -0.071076557, + 0.99314147 -0.097162947 -0.065034829, + 0.997908 -0.053726301 -0.035960998, + 0.99794078 -0.05403899 -0.034555592, + 0.99979174 -0.017191997 -0.010993497, + 0.99978638 -0.016989606 -0.011776905, + 0.99980003 0.016436201 0.0113933, + 0.99979621 0.016273905 0.011943803, + 0.99823451 0.047883376 0.035142686, + 0.99818712 0.047110707 0.037459403, + 0.99519241 0.076658756 0.060954064, + 0.99503136 0.074938528 0.065551125, + 0.99063522 0.10276702 0.089893319, + 0.99026066 0.099743761 0.097133964, + 0.98441637 0.12598504 0.12268805, + 0.98367822 0.12120803 0.13298804, + 0.97639412 0.14549902 0.15963902, + 0.97511065 0.13861196 0.17304894, + 0.96624702 0.161054 0.201068, + 0.96414089 0.15148899 0.21790697, + 0.95348811 0.17206001 0.24749903, + 0.95139652 0.16367193 0.26087588, + 0.93774486 0.18458799 0.29421398, + 0.93614966 0.17892994 0.30266789, + 0.92052424 0.19882004 0.33631209, + 0.9183439 0.19171497 0.34625098, + 0.9006294 0.2105121 0.38019916, + 0.89779431 0.20192307 0.39139816, + 0.87770873 0.21970195 0.42586192, + 0.87410229 0.20944907 0.43826514, + 0.85149872 0.22609892 0.47310582, + 0.84698361 0.21393989 0.48667076, + 0.8220818 0.22913094 0.52122986, + 0.81653059 0.2148359 0.53583878, + 0.7892769 0.22850597 0.56993592, + 0.78270316 0.21217005 0.58511513, + 0.7527979 0.22439297 0.61882395, + 0.74518299 0.205953 0.63426, + 0.71268624 0.21664608 0.66719025, + 0.70398957 0.19591889 0.68265259, + 0.66946107 0.20492204 0.71402305, + 0.65976775 0.18194894 0.72910976, + 0.62343276 0.18930992 0.75861269, + 0.61296314 0.16437005 0.77282518, + 0.57476985 0.17023696 0.80041182, + 0.56374872 0.14354692 0.81337661, + 0.52389312 0.14803703 0.83882117, + 0.5153141 0.12652403 0.84761018, + 0.47468495 0.12994199 0.87051088, + 0.46772778 0.11148395 0.87681359, + 0.42939106 0.11391102 0.89590609, + 0.4232212 0.095950142 0.90093142, + 0.38120115 0.09790574 0.91929334, + 0.37744695 0.085917793 0.92203689, + 0.33461803 0.08743231 0.93828911, + 0.33090311 0.074133433 0.94074833, + 0.28589907 0.075280018 0.95529824, + 0.28024092 0.069690481 0.95739663, + 0.24354294 0.070413582 0.96733075, + 0.23685694 0.038313191 0.97078878, + 0.1958281 0.038671918 0.9798755, + 0.19016109 0.005677063 0.98173648, + 0.149177 0.0057178698 0.98879403, + 0.14464502 -0.028047305 0.98908609, + 0.10417602 -0.028191207 0.99415922, + 0.10086302 -0.06262961 0.99292713, + 0.061088778 -0.062832981 0.99615264, + 0.059071392 -0.097633183 0.99346787, + 0.019938298 -0.097784482 0.99500787, + 0.019254802 -0.13290201 0.99094212, + -0.019336091 -0.13290194 0.99094051, + -0.020019 -0.097767003 0.99500799, + -0.059187185 -0.097615078 0.99346274, + -0.06120627 -0.062768571 0.99614954, + -0.10108198 -0.062564492 0.9929089, + -0.10439695 -0.028103987 0.99413854, + -0.14490199 -0.027960297 0.98905087, + -0.14943895 0.0058479384 0.98875362, + -0.19045496 0.0058060987 0.98167878, + -0.19611895 0.038784992 0.97981274, + -0.23718108 0.038424514 0.97070533, + -0.24385805 0.070470713 0.96724725, + -0.28481299 0.0696548 0.95604903, + -0.32521302 0.065895505 0.94334209, + -0.28836593 0.066723384 0.95519274, + -0.28075004 0.035638005 0.95911914, + -0.240301 0.036043402 0.970029, + -0.2335691 0.0038989619 0.97233248, + -0.19308791 0.0039344081 0.98117352, + -0.18737805 -0.029117508 0.98185623, + -0.14694192 -0.029320784 0.9887104, + -0.14236805 -0.063179724 0.98779535, + -0.10255498 -0.063493393 0.99269891, + -0.099225014 -0.097862415 0.99024111, + -0.06011077 -0.098169953 0.99335253, + -0.058083486 -0.13287997 0.98942876, + -0.019642994 -0.13307898 0.99091077, + -0.018956991 -0.16810092 0.98558754, + 0.0188777 -0.168101 0.98558903, + 0.0195645 -0.133081 0.99091202, + 0.058011476 -0.13288195 0.98943263, + 0.060036194 -0.098212786 0.99335289, + 0.099075764 -0.097906061 0.99025166, + 0.102401 -0.063599497 0.99270803, + 0.14221103 -0.063285612 0.98781127, + 0.14678 -0.0294712 0.98873001, + 0.18711402 -0.029267604 0.98190212, + 0.19282497 0.0037836796 0.98122591, + 0.23324403 0.0037496805 0.9724111, + 0.23998395 0.035928693 0.97011179, + 0.27615306 0.035571106 0.96045524, + 0.59384227 0.080360733 0.80055827, + 0.55165905 0.083306007 0.82989913, + 0.54815888 0.075154886 0.83299083, + 0.5085628 0.077369973 0.85754168, + 0.50470412 0.067820713 0.86062419, + 0.46444818 0.06957332 0.88286328, + 0.46037781 0.058768179 0.88577569, + 0.41954795 0.060092792 0.90574187, + 0.41546515 0.04832942 0.9083243, + 0.37395203 0.049277209 0.9261381, + 0.36996117 0.03661662 0.92832541, + 0.3278299 0.037234992 0.94400275, + 0.32404688 0.02379759 0.94574165, + 0.28189003 0.024134804 0.9591431, + 0.27625999 0.0013979001 0.96108198, + 0.23635094 0.0014132897 0.97166675, + 0.22955306 -0.030845808 0.97280723, + 0.18974698 -0.031116296 0.98133987, + 0.18398301 -0.064254411 0.98082709, + 0.14433296 -0.06468568 0.98741263, + 0.13974501 -0.098400414 0.98528612, + 0.10062002 -0.098871216 0.99000013, + 0.097285025 -0.13300502 0.98632926, + 0.058891315 -0.13340603 0.98931026, + 0.05685392 -0.16798706 0.98414838, + 0.019101098 -0.16822898 0.98556286, + 0.018410601 -0.20316701 0.978971, + -0.018555705 -0.20316705 0.97896826, + -0.019246496 -0.16826595 0.98555374, + -0.056932174 -0.16802393 0.98413754, + -0.058970898 -0.13340899 0.98930502, + -0.097360052 -0.13300695 0.98632151, + -0.10070302 -0.098785713 0.99000013, + -0.13986298 -0.098314583 0.98527789, + -0.144457 -0.064557299 0.98740298, + -0.18421191 -0.064125068 0.98079252, + -0.18998195 -0.030944992 0.98129976, + -0.22981709 -0.030675411 0.97275037, + -0.23661812 0.0016053508 0.97160149, + -0.27656287 0.0015878192 0.96099454, + -0.2842491 0.032797411 0.95818937, + -0.32429004 0.032359704 0.94540411, + -0.33042011 0.054081619 0.94228333, + -0.37278509 0.053169712 0.92639321, + -0.37673706 0.065732107 0.92398512, + -0.41842616 0.064449824 0.90596128, + -0.422434 0.076021597 0.90319997, + -0.46336505 0.074325204 0.88304514, + -0.46719587 0.084509879 0.88010573, + -0.50754011 0.082356825 0.85768318, + -0.51373303 0.097753897 0.85236299, + -0.55006516 0.095152937 0.8296833, + -0.55678874 0.11071495 0.8232426, + -0.59495425 0.10712904 0.7965883, + -0.60353494 0.12631299 0.78726786, + -0.64023805 0.12169302 0.75847614, + -0.65111208 0.14568701 0.74486804, + -0.68626517 0.13961503 0.71382618, + -0.69619977 0.16161893 0.69941777, + -0.72956073 0.15397994 0.66635674, + -0.73828596 0.17357199 0.65177196, + -0.76914233 0.16445908 0.61755431, + -0.77669716 0.18183404 0.60305715, + -0.80499989 0.17126898 0.56801593, + -0.8113609 0.18639499 0.55403095, + -0.8373161 0.17433402 0.51817906, + -0.84260553 0.18746389 0.50484967, + -0.86624169 0.17392094 0.46837682, + -0.8705256 0.18513492 0.45597178, + -0.8915571 0.17038201 0.41963807, + -0.89490587 0.17971699 0.40846694, + -0.91349059 0.16385193 0.37240782, + -0.91605574 0.17154296 0.3625119, + -0.93245423 0.15453503 0.32657009, + -0.93437743 0.16081007 0.31792915, + -0.94870138 0.14270605 0.28213608, + -0.94840354 0.13018595 0.28910586, + -0.93234235 0.14846206 0.32969213, + -0.93024099 0.141872 0.33841401, + -0.91338485 0.15739399 0.37543994, + -0.91056275 0.14926697 0.3854799, + -0.8914659 0.16360898 0.42251694, + -0.88777924 0.15374303 0.43383309, + -0.86617583 0.16692695 0.47103587, + -0.86152542 0.15524207 0.48339823, + -0.83728999 0.16718 0.52057302, + -0.83158302 0.153574 0.533746, + -0.80503112 0.16403502 0.57010305, + -0.79813784 0.14828297 0.58394188, + -0.76924717 0.15726104 0.61929613, + -0.7611261 0.13929902 0.63346905, + -0.72975618 0.14683902 0.66775316, + -0.7203328 0.12647296 0.68200082, + -0.68654698 0.13257299 0.71489698, + -0.67608422 0.11025104 0.72852921, + -0.64064878 0.11489195 0.75918972, + -0.63244504 0.097314619 0.76846814, + -0.59568173 0.10090996 0.79685664, + -0.58916801 0.086594 0.80335701, + -0.55435389 0.089194976 0.82748783, + -0.54825026 0.074924834 0.83295143, + -0.50868869 0.077131756 0.85748845, + -0.50491285 0.067795582 0.86050379, + -0.46466383 0.069548279 0.8827517, + -0.46062511 0.058826916 0.88564324, + -0.41982687 0.060153078 0.90560871, + -0.4157488 0.048401378 0.90819061, + -0.3742449 0.04935139 0.92601573, + -0.36908808 0.033032406 0.92880726, + -0.41304392 0.032368291 0.91013575, + -0.41714215 0.044149116 0.90776831, + -0.45783606 0.043187004 0.88798714, + -0.46193221 0.054039627 0.88526744, + -0.50208092 0.052693292 0.8632139, + -0.50607204 0.062549509 0.86022013, + -0.54556787 0.060778085 0.83585984, + -0.54921716 0.069263823 0.83280432, + -0.58736992 0.067078993 0.80653387, + -0.58906168 0.053234674 0.80633265, + -0.5465309 0.055168185 0.83561981, + -0.54267699 0.046216901 0.838669, + -0.50322199 0.0475494 0.86284798, + -0.49915496 0.037523597 0.86569989, + -0.45912987 0.038469993 0.88753575, + -0.45498616 0.027515309 0.8900733, + -0.41444206 0.028120104 0.90964115, + -0.41032115 0.016302105 0.91179532, + -0.36919689 0.016613295 0.92920262, + -0.36453983 0.028630387 0.93074757, + -0.32811296 0.029043796 0.94419187, + -0.31958708 -0.0011700202 0.94755626, + -0.28003502 -0.0011853701 0.95998913, + -0.27225912 -0.032575916 0.96167248, + -0.232851 -0.032924201 0.971955, + -0.22597803 -0.065332204 0.97193915, + -0.18675494 -0.065887079 0.98019463, + -0.18095393 -0.099004462 0.97849566, + -0.14190696 -0.09964776 0.98485166, + -0.13728903 -0.13331103 0.98151922, + -0.098847613 -0.13392702 0.98604912, + -0.095483884 -0.16807498 0.98113889, + -0.057842813 -0.16856304 0.98399222, + -0.055789206 -0.20308203 0.97757113, + -0.018899003 -0.20336205 0.97892123, + -0.018207997 -0.23785195 0.97113079, + 0.018028097 -0.23785298 0.97113389, + 0.018717999 -0.20334198 0.97892886, + 0.055681016 -0.20306304 0.97758126, + 0.057735778 -0.16850995 0.98400766, + 0.095444903 -0.16802099 0.981152, + 0.098803803 -0.133945 0.98605102, + 0.13721304 -0.13333003 0.98152721, + 0.14181991 -0.099753737 0.98485339, + 0.18079695 -0.099111676 0.97851378, + 0.18658891 -0.066059873 0.98021454, + 0.22581108 -0.065504119 0.97196639, + 0.23267291 -0.03315749 0.97198963, + 0.27200788 -0.032807685 0.96173555, + 0.27978793 -0.0014178896 0.96006078, + 0.31553108 -0.0014014303 0.94891423, + 0.62598181 0.045761287 0.77849382, + 0.58529514 0.047579311 0.80942321, + 0.58156008 0.039333403 0.81255209, + 0.54342192 0.040588498 0.83847791, + 0.539451 0.031383902 0.84143198, + 0.50002509 0.032278206 0.8654092, + 0.49590212 0.022136705 0.86809617, + 0.45598912 0.022687607 0.88969624, + 0.4517808 0.011592695 0.8920536, + 0.41140205 0.011843801 0.91137713, + 0.40724295 -4.9349994e-005 0.91331989, + 0.36630788 -5.0278581e-005 0.93049365, + 0.36223203 -0.012870802 0.93199915, + 0.32076308 -0.013078903 0.94706923, + 0.31598186 -0.029880784 0.94829452, + 0.35959819 -0.029387714 0.93264443, + 0.36368009 -0.016587304 0.93137622, + 0.40442306 -0.016285403 0.9144271, + 0.4086411 -0.004257021 0.91268522, + 0.44885293 -0.0041679796 0.89359587, + 0.45307401 0.0069303699 0.89144599, + 0.49289599 0.00676412 0.87006199, + 0.49706006 0.016977603 0.86755013, + 0.53639901 0.016512901 0.84380299, + 0.54042011 0.025814205 0.84099919, + 0.5785172 0.02502491 0.81528628, + 0.58231288 0.033389192 0.81227881, + 0.61920822 0.032249913 0.78456432, + 0.62573922 0.046162415 0.7786653, + 0.65815067 0.044555977 0.75156665, + 0.66681403 0.062329501 0.74261302, + 0.69808704 0.059886307 0.71350408, + 0.70369881 0.071050286 0.70693684, + 0.73649603 0.067644708 0.67305106, + 0.74243033 0.079441935 0.6651963, + 0.77318132 0.07520403 0.62971026, + 0.78146601 0.092006803 0.617127, + 0.81007701 0.086458802 0.57991397, + 0.81734431 0.10179204 0.56708616, + 0.84370089 0.094841883 0.52836895, + 0.84967428 0.10810604 0.5161072, + 0.87332588 0.099870488 0.47678894, + 0.87811071 0.11117496 0.46536183, + 0.89913768 0.10169696 0.42568684, + 0.90288597 0.111229 0.415241, + 0.92150891 0.10048498 0.37513193, + 0.92436701 0.108417 0.36577499, + 0.94457489 0.10729399 0.31026798, + 0.92735535 0.12229104 0.35363412, + 0.92472988 0.11470199 0.36292997, + 0.9067449 0.12707399 0.40207693, + 0.90329099 0.117927 0.412503, + 0.88294929 0.12904304 0.45138514, + 0.87854278 0.11820897 0.46280587, + 0.85561484 0.12809397 0.50151289, + 0.85011399 0.115385 0.51380199, + 0.82450014 0.12398802 0.55211109, + 0.81777209 0.10922401 0.56508309, + 0.78988081 0.11638197 0.60211587, + 0.78188086 0.099527389 0.61543196, + 0.75176114 0.10527501 0.65097809, + 0.74277395 0.08690089 0.66387892, + 0.71031499 0.091358103 0.69792998, + 0.70372319 0.078032717 0.70617616, + 0.66923475 0.081610471 0.73855579, + 0.66317123 0.069239825 0.74525821, + 0.63081604 0.071780406 0.77260512, + 0.62490726 0.059172623 0.77845329, + 0.58804888 0.061304286 0.80649883, + 0.58454007 0.053545609 0.80959612, + 0.54637796 0.055272993 0.83571291, + 0.5424549 0.046160787 0.83881581, + 0.50296575 0.047491577 0.86300057, + 0.49887693 0.037412696 0.86586487, + 0.45884699 0.0383556 0.88768703, + 0.45469314 0.027378809 0.89022732, + 0.41414291 0.027980192 0.90978175, + 0.40999693 0.016092198 0.91194487, + 0.36889511 0.016398806 0.92932636, + 0.36486301 0.0036770499 0.931054, + 0.32074898 0.0037406494 0.94715691, + 0.32549709 0.020524906 0.94532025, + 0.36743209 0.020188505 0.92983127, + 0.37142292 0.032814793 0.92788374, + 0.41275501 0.032191999 0.91027302, + 0.41687486 0.044035085 0.9078967, + 0.45754793 0.043076895 0.88814086, + 0.4616788 0.054022275 0.88540059, + 0.50181013 0.052678213 0.86337221, + 0.5058499 0.062659487 0.8603428, + 0.54540712 0.060883515 0.83595717, + 0.54912484 0.069534376 0.83284271, + 0.58729011 0.067340918 0.80657017, + 0.59342992 0.08099629 0.80079991, + 0.6269238 0.078399375 0.7751258, + 0.63335592 0.091971695 0.76837587, + 0.66901082 0.088333875 0.73798484, + 0.6762076 0.10325294 0.72943956, + 0.71041673 0.098637462 0.69683474, + 0.72004503 0.11865301 0.68370807, + 0.75196183 0.11271497 0.64949882, + 0.76062 0.131092 0.63582402, + 0.79012269 0.12377296 0.60032177, + 0.79756314 0.14006701 0.58674908, + 0.82478356 0.13129294 0.54999477, + 0.83100867 0.14550495 0.53689182, + 0.85592312 0.13526201 0.49909905, + 0.8610152 0.14751004 0.4867171, + 0.88326222 0.13599503 0.44872412, + 0.887344 0.146448 0.43723401, + 0.90704477 0.13372096 0.39923492, + 0.91022927 0.14250603 0.38881209, + 0.92762876 0.12853298 0.3506909, + 0.92998677 0.13562897 0.34165692, + 0.94518214 0.12048302 0.30350402, + 0.94827962 0.13103296 0.28912991, + 0.94839811 0.13013701 0.28914604, + 0.93230325 0.14844103 0.32981208, + 0.93017459 0.14177093 0.33863884, + 0.91330129 0.15728205 0.37569016, + 0.91042721 0.14901903 0.38589609, + 0.89130324 0.16333504 0.42296609, + 0.88754326 0.15329804 0.4344731, + 0.86591786 0.16642898 0.47168595, + 0.861202 0.154615 0.484175, + 0.836927 0.166494 0.52137601, + 0.83116382 0.15280198 0.53461987, + 0.80457884 0.16319495 0.57098186, + 0.79766589 0.14744999 0.58479697, + 0.7687729 0.15635498 0.62011397, + 0.76065314 0.13844901 0.63422304, + 0.72928119 0.14592503 0.66847217, + 0.72001094 0.12593098 0.68244094, + 0.68621379 0.13199995 0.71532273, + 0.67605603 0.110346 0.72854102, + 0.6406092 0.11499103 0.7592082, + 0.63288504 0.098426513 0.76796412, + 0.5960539 0.10207498 0.79642981, + 0.592246 0.093645103 0.80029702, + 0.55403012 0.096752726 0.82685518, + 0.55069214 0.088980623 0.82995218, + 0.51105583 0.091628373 0.85464972, + 0.50740892 0.082594194 0.8577379, + 0.46702418 0.084754527 0.88017333, + 0.46313018 0.074396133 0.88316232, + 0.42216405 0.07609421 0.90332013, + 0.41812721 0.064434826 0.90610039, + 0.37645805 0.065714806 0.9241001, + 0.37248918 0.053095225 0.92651641, + 0.33012116 0.054005027 0.94239247, + 0.32635313 0.040582716 0.94437635, + 0.28180802 0.041193303 0.9585861, + 0.28597715 0.058182627 0.95646846, + 0.32865304 0.057345506 0.94270813, + 0.332398 0.070720702 0.94048399, + 0.3750079 0.069512084 0.92441177, + 0.37893113 0.082016729 0.92178333, + 0.4207609 0.080398977 0.90360177, + 0.42463216 0.091600128 0.9007203, + 0.46572605 0.089532405 0.88038814, + 0.46944818 0.099442936 0.87734228, + 0.5099048 0.096882865 0.85475773, + 0.51336211 0.10544603 0.85166919, + 0.55308491 0.10236898 0.82681185, + 0.55714285 0.11182597 0.82285285, + 0.59534776 0.10819697 0.79614973, + 0.60348797 0.12641199 0.78728789, + 0.64020377 0.12178796 0.75848973, + 0.65077585 0.14509697 0.74527681, + 0.68593419 0.13905703 0.71425319, + 0.69572723 0.16070506 0.70009822, + 0.72908705 0.15312402 0.66707206, + 0.73780692 0.17265698 0.65255696, + 0.76866966 0.16360992 0.61836773, + 0.77623314 0.18095301 0.60391909, + 0.8045519 0.17045799 0.56889397, + 0.81098115 0.18569905 0.55482012, + 0.8369568 0.17369996 0.51897186, + 0.8423149 0.18696299 0.50551993, + 0.86598682 0.17346196 0.46901789, + 0.87034428 0.18484306 0.45643616, + 0.89139587 0.17012098 0.42008594, + 0.89480239 0.17960209 0.40874422, + 0.91340631 0.16374806 0.37266013, + 0.91600776 0.17153895 0.3626349, + 0.93241435 0.15453306 0.32668513, + 0.93436521 0.16089705 0.3179211, + 0.94869548 0.14277907 0.28211915, + 0.95126837 0.15227906 0.26814109, + 0.96239865 0.13414395 0.23620792, + 0.96494347 0.14483307 0.21887811, + 0.9741379 0.12468999 0.18843497, + 0.97571826 0.13256402 0.17435804, + 0.98320651 0.11045295 0.14527592, + 0.98410845 0.11590605 0.13452306, + 0.99006897 0.091763496 0.106503, + 0.99053621 0.09532132 0.098752119, + 0.99497998 0.069501698 0.072003201, + 0.99518025 0.071549714 0.067059211, + 0.99818313 0.043962605 0.041203402, + 0.99824363 0.044925187 0.038617086, + 0.99979746 0.015263308 0.013120106, + 0.99980265 0.015490995 0.012435395, + 0.99978936 -0.016006906 -0.012849605, + 0.99979275 -0.016134497 -0.012416997, + 0.99795121 -0.050703913 -0.039021209, + 0.99800438 -0.051262919 -0.036869016, + 0.99396223 -0.089077219 -0.064065516, + 0.99383622 -0.088454023 -0.066824615, + 0.98557538 -0.13503404 -0.10201504, + 0.98475212 -0.13356501 -0.11146201, + 0.96932 -0.188721 -0.15749, + 0.96854788 -0.18824796 -0.16271998, + 0.9505499 -0.23495997 -0.20309797, + 0.95555812 -0.23735704 -0.17484401, + 0.93524939 -0.28501016 -0.20994711, + 0.94548953 -0.28955084 -0.14902993, + 0.92596233 -0.33575311 -0.17281106, + 0.93315434 -0.33923313 -0.11892805, + 0.91260713 -0.38581505 -0.13525902, + 0.91847563 -0.38894284 -0.07159508, + 0.896842 -0.43504199 -0.080080703, + 0.89898258 -0.43627679 -0.038638882, + 0.89402974 -0.44800687 0.00071987783, + 0.89402431 -0.44800115 0.0039525814, + 0.89400727 -0.44803512 0.003952601, + 0.86944985 -0.49047393 -0.059094392, + 0.8709358 -0.49127287 -0.011038597, + 0.89405525 -0.44793913 0.0039701308, + 0.89269257 -0.4473038 -0.054947574, + 0.87637687 -0.48127395 -0.018409397, + 0.87281984 -0.47896287 -0.09370248, + 0.89699131 -0.43382415 -0.084871531, + 0.88899279 -0.42919692 -0.15962996, + 0.91238922 -0.3836481 -0.14268903, + 0.90207469 -0.37825486 -0.20780893, + 0.92513663 -0.33272788 -0.18279594, + 0.90890622 -0.3250531 -0.26120907, + 0.9093613 -0.32747212 -0.25656208, + 0.88506842 -0.36640117 -0.28706115, + 0.90084302 -0.37456399 -0.21950801, + 0.87444514 -0.41854706 -0.24528404, + 0.8886413 -0.42662415 -0.16825105, + 0.86239856 -0.47092977 -0.18572491, + 0.8729738 -0.47759789 -0.099081181, + 0.84985983 -0.52455086 -0.05083989, + 0.84607899 -0.52194399 -0.108281, + -0.85091555 -0.5252853 -0.0042660525, + -0.95368034 -0.20522907 -0.21994308, + -0.92218363 -0.26385292 -0.28276992, + -0.92076814 -0.26310503 -0.28803104, + -0.88976711 -0.30782303 -0.33698604, + -0.90930277 -0.31755692 -0.26893494, + -0.87920678 -0.36357692 -0.30790794, + -0.90021777 -0.37434492 -0.22242694, + -0.87367189 -0.41825494 -0.24851596, + -0.88651514 -0.42551506 -0.18173602, + -0.85987616 -0.46947613 -0.20051205, + -0.87084347 -0.47627971 -0.12161092, + -0.8436479 -0.52020693 -0.13282698, + -0.68674493 -0.72531694 -0.047924694, + 0.75289112 -0.0026067202 0.65814006, + 0.76072532 0.012724205 0.64894927, + 0.78797489 0.012070098 0.61558896, + 0.79436511 0.024607604 0.60694206, + 0.8202219 0.023173798 0.57157594, + 0.82362717 0.029874507 0.56634414, + 0.85028231 0.027725009 0.5255962, + 0.85333699 0.033953201 0.520253, + 0.90878624 0.048111312 0.41447908, + 0.90463614 0.038304202 0.42446005, + 0.88280314 0.042219102 0.46784207, + 0.87771767 0.031206088 0.47816083, + 0.87581903 0.0187585 0.48227501, + 0.8493309 0.020516098 0.52746195, + 0.84648579 0.014793696 0.53220588, + 0.82220685 0.015815599 0.56896895, + 0.8165161 0.0045117904 0.57730508, + 0.79037011 0.0047877105 0.61261106, + 0.78322172 -0.0092378864 0.62167376, + 0.75568414 -0.0097310506 0.65486407, + 0.74750406 -0.025695303 0.66376007, + 0.71860701 -0.026900601 0.69489598, + 0.70952106 -0.044669304 0.70326704, + 0.67907017 -0.046532411 0.73259717, + 0.66916478 -0.066085078 0.74016976, + 0.63728875 -0.068531677 0.76757169, + 0.62663698 -0.089922301 0.77410603, + -0.760382 -0.58147001 -0.28933001, + -0.79527581 -0.54276788 -0.27007294, + -0.71016395 -0.33142698 -0.62114692, + -0.67283052 -0.34826177 -0.65269655, + -0.75260121 -0.39763209 -0.52486211, + -0.74790317 -0.38912109 -0.53779709, + -0.80558109 -0.42414105 -0.41369507, + -0.76687533 -0.45944017 -0.44812614, + -0.80324268 -0.48395783 -0.34725487, + -0.76679027 -0.52153218 -0.37421513, + -0.76305431 -0.51397115 -0.39189515, + -0.72421896 -0.54835296 -0.41810995, + -0.75917262 -0.5769847 -0.30123985, + -0.72214895 -0.61319494 -0.32014498, + -0.72512084 -0.68766582 -0.036269993, + -0.71084976 -0.67337275 -0.20312993, + -0.74741381 -0.63604879 -0.19187096, + -0.7552101 -0.65517807 -0.019986402, + -0.7593497 -0.64888376 -0.048350282, + -0.74741793 -0.63806891 -0.18502599, + -0.78168488 -0.59899795 -0.17369598, + -0.81474161 -0.57718068 -0.055302974, + -0.7924009 -0.60976195 -0.017062599, + -0.78167391 -0.60081792 -0.16734299, + -0.81380886 -0.55982393 -0.15592399, + -0.7962808 -0.54669988 -0.25895193, + -0.8288359 -0.50563794 -0.23950197, + -0.80629665 -0.49034077 -0.33083487, + -0.83954519 -0.45036712 -0.30386406, + -0.8123877 -0.43365484 -0.38983285, + -0.8423146 -0.40083483 -0.36032981, + -0.96094686 -0.18330298 -0.20731898, + -0.93372273 -0.23713094 -0.26819894, + -0.92689711 -0.23121403 -0.29563802, + -0.8923496 -0.27805188 -0.35552683, + -0.87996298 -0.27010399 -0.39078, + -0.83073628 -0.31651512 -0.45792514, + -0.82904369 -0.31559187 -0.46161482, + -0.781259 -0.35228899 -0.515293, + -0.81729412 -0.37245703 -0.43966606, + -0.79082215 -0.39561406 -0.46700105, + -0.71590519 -0.35101208 -0.60354811, + -0.76091373 -0.32620487 -0.56089282, + -0.76159865 -0.32659885 -0.55973274, + -0.82369632 -0.28576809 -0.48975617, + -0.84310985 -0.29796094 -0.44764388, + -0.88893902 -0.253791 -0.381284, + -0.90049458 -0.26274088 -0.34652081, + -0.9324609 -0.21827497 -0.28787598, + -0.93958336 -0.22592607 -0.2571781, + -0.96093225 -0.18267305 -0.20794204, + -0.96193451 -0.18426691 -0.20181091, + -0.97692847 -0.14400408 -0.15771407, + -0.97694474 -0.14403997 -0.15757996, + -0.98735762 -0.10694296 -0.11699595, + -0.98741186 -0.10713998 -0.11635698, + -0.99413574 -0.073250286 -0.079551481, + -0.99401861 -0.072546281 -0.08163397, + -0.99801886 -0.041793197 -0.047028393, + -0.99796009 -0.041119203 -0.048836708, + -0.99979323 -0.013098403 -0.015556804, + -0.99978465 -0.012770696 -0.016355194, + -0.999798 0.0123689 0.0158408, + -0.99978745 0.011926506 0.016822308, + -0.99815488 0.035118096 0.049533892, + -0.99804014 0.033468805 0.052875008, + -0.99479926 0.05447631 0.086063124, + -0.99442565 0.051169682 0.092191868, + -0.98949587 0.070154995 0.12639698, + -0.98865134 0.064764924 0.13555105, + -0.98186445 0.081732035 0.17106207, + -0.98023576 0.073665783 0.18360595, + -0.97148597 0.088285998 0.220047, + -0.96870899 0.077135503 0.235909, + -0.95772767 0.089404173 0.27343091, + -0.95326048 0.07444194 0.29283616, + -0.93970847 0.084254339 0.33143514, + -0.93293822 0.064948715 0.35413009, + -0.9165076 0.072160862 0.39345482, + 0.55066311 -0.12063703 0.82596415, + 0.50757498 -0.124522 0.85256201, + 0.49969989 -0.14203697 0.85447383, + 0.46462005 -0.14520301 0.87352413, + 0.45362005 -0.17115201 0.87460613, + 0.41820106 -0.17444701 0.89144611, + 0.40705785 -0.20241593 0.8906917, + 0.37154713 -0.20574208 0.9053303, + 0.36081699 -0.23468199 0.90262699, + 0.32519698 -0.23795597 0.91521788, + 0.3150861 -0.26763806 0.91054422, + 0.27945513 -0.27076712 0.92118943, + 0.27011997 -0.30108798 0.91453886, + 0.23513703 -0.30394503 0.9232161, + 0.2267119 -0.33479184 0.91461259, + 0.19256397 -0.33730897 0.92148888, + 0.18524301 -0.36828604 0.91107112, + 0.15186007 -0.37042516 0.91636443, + 0.15176997 -0.37088892 0.91619176, + 0.11933304 -0.37255311 0.92030638, + 0.12343193 -0.3432928 0.93108249, + 0.08904323 -0.34456411 0.93453038, + 0.091708705 -0.31519303 0.9445861, + 0.055664591 -0.31603596 0.94711286, + 0.057108417 -0.28656808 0.95635635, + 0.019451797 -0.28698093 0.95773876, + 0.01988131 -0.25732112 0.96612149, + -0.019206604 -0.25732407 0.96613425, + -0.018771602 -0.28695503 0.9577601, + -0.056487627 -0.28654715 0.9563995, + -0.055042092 -0.31595898 0.94717491, + -0.091262527 -0.31511813 0.94465435, + -0.088603891 -0.34437996 0.93463987, + -0.12323203 -0.34310508 0.93117821, + -0.11914498 -0.37226596 0.92044687, + -0.15186003 -0.37058908 0.91629821, + -0.15188891 -0.3704378 0.91635448, + -0.18522398 -0.36830097 0.91106886, + -0.192579 -0.33717999 0.92153299, + -0.22682308 -0.33465713 0.91463429, + -0.23525392 -0.30377987 0.92324066, + -0.2702781 -0.30092013 0.91454732, + -0.27962098 -0.27057397 0.92119586, + -0.31528896 -0.26744097 0.91053188, + -0.32536212 -0.2378711 0.91518128, + -0.36097196 -0.23459797 0.90258688, + -0.37161803 -0.20589203 0.90526712, + -0.40710309 -0.20256504 0.89063722, + -0.41814509 -0.17486104 0.89139122, + -0.45347494 -0.17156799 0.87459987, + -0.46467081 -0.14516295 0.87350368, + -0.49976718 -0.14199604 0.85444129, + -0.51119381 -0.11642296 0.85154372, + -0.54545981 -0.11353397 0.83041167, + -0.55679685 -0.08920607 0.82584471, + -0.59017825 -0.086695731 0.80260432, + -0.60112393 -0.063976794 0.79659086, + -0.63381398 -0.061921801 0.77100301, + -0.64410621 -0.041097917 0.76383132, + -0.67587698 -0.039597798 0.73594999, + -0.68543184 -0.020618694 0.72784483, + -0.71567762 -0.01977749 0.69815063, + -0.72436816 -0.0027025908 0.68940818, + -0.75299603 -0.00257954 0.65802002, + -0.76067889 0.012451898 0.64900893, + -0.78790951 0.011812492 0.61567765, + -0.79407513 0.023891104 0.60735005, + -0.81990433 0.022502808 0.5720582, + -0.82699811 0.036584903 0.56101304, + -0.85080791 0.034194995 0.52436292, + -0.86055315 0.054385006 0.50644904, + -0.88399923 0.049914312 0.46481612, + -0.88903069 0.061290178 0.45372686, + -0.90990227 0.055530619 0.41108915, + -0.90774977 0.038236994 0.41776592, + -0.88306689 0.042770095 0.46729395, + -0.87460703 0.024659 0.48420501, + -0.85233891 0.026599696 0.52231294, + -0.84619129 0.014124105 0.53269219, + -0.821913 0.0150977 0.56941301, + -0.81643569 0.0042363685 0.57742083, + -0.7903012 0.0044952207 0.61270213, + -0.78330773 -0.0092234667 0.62156576, + -0.75577885 -0.0097159278 0.65475482, + -0.74772108 -0.025448404 0.66352504, + -0.718835 -0.026643001 0.69467002, + -0.7098372 -0.044256411 0.7029742, + -0.67936999 -0.046105701 0.732346, + -0.6695022 -0.065606616 0.73990721, + -0.63760984 -0.068039782 0.76734883, + -0.62693381 -0.089497775 0.77391481, + -0.59422505 -0.092395708 0.7989741, + -0.58299106 -0.11553501 0.80422211, + -0.54968983 -0.11878996 0.82687968, + -0.53821284 -0.14320995 0.8305527, + -0.50406826 -0.14675307 0.85110444, + -0.49272323 -0.17192408 0.85303342, + -0.45761299 -0.175671 0.87162501, + -0.44623712 -0.20224105 0.87176317, + -0.41095784 -0.20602393 0.88806969, + -0.39976916 -0.23377208 0.88630432, + -0.36449888 -0.2374929 0.9004097, + -0.35370392 -0.26621693 0.89667279, + -0.31840709 -0.26980305 0.90874821, + -0.30816799 -0.29941401 0.90298599, + -0.27292091 -0.30278289 0.91314667, + -0.26343614 -0.3330822 0.90534955, + -0.22900894 -0.3361029 0.91355878, + -0.22048107 -0.36677513 0.90380532, + -0.18697599 -0.36939698 0.91026688, + -0.18703493 -0.36914587 0.9103567, + -0.15455092 -0.37126184 0.91557556, + -0.159853 -0.34187499 0.92605001, + -0.12517095 -0.34360385 0.93073559, + -0.12892397 -0.31417391 0.94057077, + -0.092551805 -0.31545904 0.94441509, + -0.094977103 -0.28591701 0.95353597, + -0.057217386 -0.28674495 0.95629674, + -0.058527894 -0.25699496 0.96463889, + -0.019436793 -0.25738791 0.96611261, + -0.019828198 -0.22740696 0.97359788, + 0.020457292 -0.22740392 0.97358567, + 0.020073008 -0.25737408 0.96610337, + 0.059161969 -0.25697488 0.96460551, + 0.057856884 -0.28676993 0.95625079, + 0.095556997 -0.28593701 0.95347202, + 0.093130179 -0.31556791 0.94432175, + 0.12936305 -0.31428212 0.94047433, + 0.12559605 -0.34385011 0.93058735, + 0.16001098 -0.34212896 0.92592889, + 0.15469107 -0.37161818 0.91540742, + 0.18693194 -0.36951587 0.91022772, + 0.18696696 -0.36936492 0.91028178, + 0.22041394 -0.36674792 0.90383273, + 0.22889797 -0.33623797 0.91353691, + 0.26337597 -0.33321297 0.90531886, + 0.27283496 -0.30300096 0.91309988, + 0.30797997 -0.29964098 0.9029749, + 0.31822589 -0.27001491 0.90874869, + 0.3535111 -0.26643106 0.89668524, + 0.36435404 -0.23758502 0.90044409, + 0.39959517 -0.23386811 0.88635743, + 0.41088992 -0.20585695 0.88813978, + 0.44620314 -0.20207408 0.87181932, + 0.45770407 -0.17520401 0.87167114, + 0.49285707 -0.17146201 0.8530491, + 0.50398213 -0.14677203 0.85115218, + 0.53815407 -0.14322601 0.8305881, + 0.54947281 -0.11915296 0.82697171, + 0.58274668 -0.11589295 0.80434763, + 0.59395427 -0.092828631 0.79912531, + 0.59458393 -0.093719393 0.79855287, + 0.55307174 -0.097111158 0.82745457, + 0.54880512 -0.10626102 0.82916915, + 0.51113707 -0.10925402 0.85252714, + 0.50663388 -0.11936897 0.85385782, + 0.46814781 -0.12234396 0.87513971, + 0.46033511 -0.14082003 0.87650526, + 0.42490116 -0.14359404 0.89377832, + 0.41419095 -0.17073698 0.8940329, + 0.37841991 -0.17363395 0.90920275, + 0.3678109 -0.20259096 0.90756375, + 0.33187288 -0.20551592 0.92066467, + 0.32184485 -0.23535489 0.91707361, + 0.28576398 -0.23821597 0.92821985, + 0.27652907 -0.26866007 0.92268825, + 0.24101891 -0.2713199 0.93182367, + 0.23269591 -0.30229789 0.92437464, + 0.19787908 -0.30468413 0.93167138, + 0.19059588 -0.33605579 0.92235547, + 0.15648392 -0.33811286 0.92800456, + 0.15039608 -0.36953917 0.9169634, + 0.11708495 -0.37121981 0.92113358, + 0.11697499 -0.37195498 0.92085087, + 0.084563427 -0.37318411 0.92389536, + 0.087459996 -0.34415099 0.93483198, + 0.053162709 -0.34498602 0.93710113, + 0.054746326 -0.31579015 0.94724846, + 0.018648803 -0.31620908 0.94850624, + 0.0191247 -0.286892 0.95777202, + -0.018553207 -0.2868951 0.95778233, + -0.018071402 -0.31617704 0.94852811, + -0.054307792 -0.31576198 0.94728291, + -0.052724589 -0.34486392 0.93717074, + -0.087252967 -0.34402788 0.93489665, + -0.084362909 -0.37298003 0.92399609, + -0.11707298 -0.37174097 0.9209249, + -0.117146 -0.371259 0.92110997, + -0.15046692 -0.36957681 0.91693658, + -0.15657896 -0.33802691 0.92801976, + -0.19067796 -0.33596992 0.92236978, + -0.19797596 -0.30453396 0.93169987, + -0.23283209 -0.30214512 0.92439038, + -0.24115796 -0.27115098 0.9318369, + -0.27672502 -0.26848602 0.92268014, + -0.28592986 -0.23813888 0.92818856, + -0.32201704 -0.23527703 0.91703314, + -0.33197385 -0.20565389 0.92059755, + -0.36786789 -0.20272993 0.90750968, + -0.37840107 -0.17399201 0.90914214, + -0.41407284 -0.17109694 0.89401871, + -0.42493808 -0.14356703 0.89376521, + -0.46039599 -0.14079 0.87647802, + -0.47162282 -0.11408097 0.87438971, + -0.50689721 -0.11151905 0.85476243, + -0.51820791 -0.085991375 0.8509208, + -0.5525862 -0.083799727 0.82923228, + -0.56366891 -0.059834287 0.82383084, + -0.59709686 -0.058107983 0.80006182, + -0.60770077 -0.035954189 0.79335171, + -0.64031708 -0.034774605 0.76732314, + -0.65030372 -0.014463494 0.75953662, + -0.68196404 -0.013924802 0.73125309, + -0.69120383 0.0045024692 0.72264582, + -0.72125506 0.0043156105 0.69265604, + -0.72956675 0.020683793 0.68359679, + -0.75794232 0.019728508 0.65202326, + -0.76474947 0.03303542 0.64348036, + -0.79172599 0.0313203 0.61007297, + -0.79975766 0.047084976 0.59847373, + -0.82513952 0.044308774 0.56318867, + -0.8361659 0.066673793 0.54440892, + -0.86141729 0.061741021 0.5041312, + -0.86724901 0.074493997 0.49226999, + -0.88979572 0.068282276 0.45122185, + -0.89426523 0.07881292 0.44054312, + -0.91675913 0.070342809 0.39319807, + -0.918235 0.086460002 0.38648301, + -0.89895159 0.095631652 0.4274818, + -0.89489567 0.085682668 0.43797284, + -0.87316197 0.093584202 0.47836199, + -0.86793882 0.081685379 0.48990789, + -0.84353614 0.088329904 0.52975905, + -0.83691829 0.074169733 0.54227918, + -0.80980301 0.079505399 0.58129001, + -0.44745293 -0.024276895 0.89397788, + -0.48705983 -0.023708491 0.8730467, + -0.49130988 -0.013334298 0.87088281, + -0.53049111 -0.012977703 0.84759116, + -0.53457218 -0.0035786012 0.8451153, + -0.57749087 -0.003456959 0.8163898, + -0.57657814 -0.0021639005 0.81703919, + -0.61001396 -0.0020986097 0.7923879, + -0.62006706 0.019111602 0.78431612, + -0.65256172 0.018458391 0.75751066, + -0.66189104 0.037568703 0.74865806, + -0.69323802 0.036120702 0.71980298, + -0.70118296 0.052009791 0.71108192, + -0.73084408 0.049789608 0.68072605, + -0.73576093 0.059393093 0.67463195, + -0.76691329 0.05628062 0.63927823, + -0.7726298 0.067540586 0.63125384, + -0.8019529 0.063554294 0.59399694, + -0.80012399 0.045768801 0.598086, + -0.76644289 0.049009994 0.64043993, + -0.76203901 0.0404751 0.64626497, + -0.73389 0.042458899 0.67794001, + -0.72648436 0.027879514 0.68661731, + -0.69663501 0.029106401 0.71683502, + -0.68776619 0.011371302 0.72584319, + -0.65628475 0.011818895 0.7544207, + -0.6465708 -0.0080210278 0.76281184, + -0.61400193 -0.0082991393 0.78926086, + -0.60370308 -0.029934105 0.79664713, + -0.5702647 -0.030844685 0.82088161, + 0.42374384 -0.10455296 0.8997277, + 0.47043517 -0.10185704 0.87653631, + 0.47491288 -0.091120176 0.87530273, + 0.51364005 -0.088839509 0.85339409, + 0.51802915 -0.078899927 0.85171628, + 0.55583411 -0.076679617 0.82774919, + 0.55998188 -0.067716584 0.82573283, + 0.6013869 -0.065301582 0.79628479, + 0.64392215 -0.04171171 0.76395315, + 0.60405588 -0.043448187 0.79575682, + 0.6002571 -0.051378909 0.79815519, + 0.56334811 -0.053075612 0.8245132, + 0.55923778 -0.061986569 0.82668656, + 0.52139103 -0.063804507 0.85092914, + 0.51707906 -0.073604509 0.85276711, + 0.47822583 -0.075522073 0.87498373, + 0.47377688 -0.08623258 0.87641275, + 0.43476909 -0.088181019 0.89621425, + 0.42710185 -0.10782396 0.89775169, + 0.39095306 -0.10975701 0.9138431, + 0.38068095 -0.13830599 0.91430485, + 0.34419709 -0.14042903 0.92833626, + 0.33454984 -0.16976592 0.92696059, + 0.297622 -0.171983 0.93906498, + 0.28851604 -0.20277403 0.9357571, + 0.25199103 -0.20494503 0.94577914, + 0.24378698 -0.23635997 0.94058585, + 0.2077529 -0.23839588 0.94868654, + 0.20059896 -0.27019095 0.94167775, + 0.16511901 -0.27201101 0.94802201, + 0.15910895 -0.30410993 0.93925577, + 0.12416406 -0.30565014 0.94401348, + 0.11939704 -0.33791012 0.93357438, + 0.085535578 -0.3390969 0.93685478, + 0.082087405 -0.37129802 0.92487812, + 0.049396317 -0.37210011 0.92687738, + 0.04932173 -0.37326822 0.92641151, + 0.016825097 -0.37367091 0.92740875, + 0.017391797 -0.3450239 0.93843275, + -0.017166192 -0.34502482 0.93843651, + -0.016598597 -0.37360391 0.92743975, + -0.049390391 -0.3731989 0.92643577, + -0.049459994 -0.37210998 0.92686987, + -0.082119323 -0.37130809 0.92487127, + -0.085573137 -0.33905816 0.93686539, + -0.11950398 -0.33786798 0.93357587, + -0.12428206 -0.30554014 0.9440335, + -0.15919393 -0.30400088 0.93927664, + -0.16520801 -0.27188003 0.94804412, + -0.200782 -0.27005401 0.94167799, + -0.20791893 -0.23834191 0.94866365, + -0.24395105 -0.23630506 0.94055724, + -0.25211412 -0.2050551 0.94572246, + -0.2886059 -0.20288293 0.93570566, + -0.29765987 -0.17227393 0.93899965, + -0.33449098 -0.17005998 0.92692786, + -0.34424296 -0.14040498 0.92832285, + -0.38075086 -0.13827996 0.9142797, + -0.39110816 -0.10948504 0.9138093, + -0.42728895 -0.10755499 0.89769489, + -0.43805811 -0.079794519 0.89539826, + -0.47406194 -0.078156389 0.87701589, + -0.48179212 -0.059574313 0.87425816, + -0.52073079 -0.058040377 0.85174572, + -0.52500474 -0.048284478 0.84972858, + -0.56293917 -0.046888817 0.8251673, + -0.56476468 -0.061293371 0.8229726, + -0.52168113 -0.063364714 0.85078418, + -0.51391101 -0.080934398 0.85401702, + -0.47839218 -0.082849927 0.87422931, + -0.46728095 -0.10950699 0.87730086, + -0.43156508 -0.11173403 0.89513522, + -0.42069307 -0.13952802 0.89640909, + -0.3848801 -0.14195202 0.91198522, + -0.37448487 -0.17059994 0.91140372, + -0.33827502 -0.17314202 0.92498213, + -0.32841489 -0.20282492 0.92249966, + -0.29192698 -0.20538197 0.93412888, + -0.28280991 -0.23584192 0.92972964, + -0.24675891 -0.23827592 0.93932664, + -0.23853494 -0.26934594 0.93303478, + -0.20308304 -0.27157307 0.94074726, + -0.195867 -0.30316699 0.93259102, + -0.16098799 -0.30512297 0.93860686, + -0.15492006 -0.33700612 0.92866933, + -0.12078101 -0.33862802 0.93313611, + -0.11597607 -0.37057221 0.92153454, + -0.082984604 -0.37180302 0.92459512, + -0.082899109 -0.37260202 0.92428112, + -0.050222188 -0.37341791 0.92630279, + -0.051939983 -0.34465688 0.93729067, + -0.017334098 -0.34506997 0.9384169, + -0.017859003 -0.31612003 0.94855112, + 0.018307991 -0.31611684 0.94854355, + 0.017786905 -0.34513012 0.93838638, + 0.05213882 -0.34471512 0.93725836, + 0.050419599 -0.373557 0.92623597, + 0.082863525 -0.37274608 0.92422622, + 0.082964711 -0.37180004 0.9245981, + 0.115977 -0.37056801 0.92153603, + 0.12076598 -0.33872497 0.93310291, + 0.15484805 -0.33710811 0.92864436, + 0.16091307 -0.30523813 0.93858236, + 0.19572495 -0.30328694 0.93258178, + 0.202931 -0.27172899 0.94073498, + 0.238379 -0.26950401 0.933029, + 0.24662402 -0.23835103 0.93934309, + 0.28264499 -0.23592 0.92975998, + 0.29182005 -0.20526004 0.93418926, + 0.32833588 -0.20270292 0.92255467, + 0.33826891 -0.17279695 0.92504877, + 0.3745231 -0.17025705 0.91145223, + 0.38479006 -0.14195901 0.91202211, + 0.4206312 -0.13953306 0.89643741, + 0.42828107 -0.12009201 0.89563012, + 0.46701181 -0.11751395 0.87640768, + 0.47155806 -0.10665801 0.87536114, + 0.51018798 -0.104024 0.85374898, + 0.51458907 -0.094097413 0.85225815, + 0.55233395 -0.091483891 0.82858789, + 0.55657405 -0.082355611 0.82670611, + 0.59344512 -0.07978572 0.80091017, + 0.60079879 -0.064441174 0.79679871, + 0.63346571 -0.062375169 0.77125263, + 0.64379495 -0.041498996 0.76407188, + 0.67555004 -0.039986804 0.73622906, + 0.68517292 -0.020889599 0.72808093, + 0.71544182 -0.020037495 0.69838482, + 0.72425497 -0.0027310299 0.68952692, + 0.72112584 0.004291439 0.69279081, + 0.72958362 0.020949591 0.68357068, + 0.7579813 0.019981207 0.65197027, + 0.76503789 0.033792995 0.64309794, + 0.792027 0.032035202 0.60964501, + 0.79601401 0.039789699 0.60396898, + 0.82446414 0.037202004 0.56469005, + 0.82821798 0.044694901 0.55862099, + 0.85436618 0.041446213 0.5180161, + 0.86026329 0.053804919 0.50700319, + 0.88374275 0.049385689 0.46535987, + 0.88867325 0.060501516 0.45453212, + 0.90958923 0.054823715 0.41187608, + 0.91330731 0.063975424 0.40221515, + 0.93358737 0.05629072 0.35390112, + 0.51968622 -0.47256222 -0.71176636, + 0.62948626 -0.58019519 -0.51683718, + 0.60448164 -0.39093375 -0.69409859, + 0.70349121 -0.46315917 -0.53905821, + 0.68728274 -0.72350675 -0.064656675, + 0.6761542 -0.71116519 -0.19250904, + 0.71478766 -0.67504668 -0.18273091, + 0.68625307 -0.64651108 -0.33328703, + 0.72523296 -0.61197096 -0.31548196, + 0.68142217 -0.57248312 -0.45599011, + 0.72208136 -0.54113024 -0.4310182, + 0.65921992 -0.49003893 -0.57034296, + 0.53176087 -0.3808229 -0.75644183, + 0.64787024 -0.47388417 -0.59640425, + 0.60255486 -0.49648288 -0.62484586, + 0.67682624 -0.56280315 -0.47450918, + 0.63440579 -0.59098089 -0.49826789, + 0.68486172 -0.64101672 -0.34649983, + 0.64390028 -0.67307031 -0.36382517, + 0.67626923 -0.70873123 -0.20089808, + 0.63608181 -0.74237281 -0.21043396, + 0.64881098 -0.757936 -0.0676568, + 0.57747191 -0.81640989 0.00098652288, + 0.60013688 -0.79975283 -0.015201896, + 0.61690301 -0.78703803 -0.00135914, + 0.61682898 -0.78709602 -0.00137409, + 0.61371505 -0.7832011 -0.099749416, + 0.61378896 -0.78314388 -0.099743389, + 0.65342993 -0.75464988 -0.059438091, + 0.6546098 -0.7559638 0.0021463595, + 0.65470308 -0.7558831 0.0021463102, + 0.65202701 -0.75286603 -0.089741498, + 0.65200871 -0.75288165 -0.089743055, + 0.65468484 -0.75589883 0.0021575796, + 0.67919731 -0.73380435 -0.014905808, + 0.75681782 -0.65031481 -0.065706886, + 0.78777838 -0.6125443 -0.064766832, + 0.78787684 -0.61241889 -0.064754687, + 0.75906867 -0.64882773 -0.053266473, + 0.7509529 -0.64139396 -0.15710999, + 0.75414473 -0.32229087 -0.57218385, + 0.76052731 -0.32594913 -0.56156516, + 0.8228761 -0.28524503 -0.49143705, + 0.84312588 -0.29795596 -0.44761693, + 0.93858898 -0.208013 -0.27528399, + 0.90021676 -0.26251593 -0.3474119, + 0.88894522 -0.25379205 -0.3812691, + 0.88971776 -0.25867793 -0.37614891, + 0.82996809 -0.31607804 -0.45961705, + 0.82455099 -0.31313601 -0.47123399, + 0.7758081 -0.34921104 -0.52552205, + 0.81064302 -0.368617 -0.45495, + 0.76962173 -0.40195686 -0.49609783, + 0.80325681 -0.42250791 -0.41983992, + 0.76426619 -0.45745611 -0.4545671, + 0.80471027 -0.48472017 -0.34276512, + 0.76844311 -0.52248305 -0.36946803, + 0.79889584 -0.54524589 -0.25391394, + 0.76433772 -0.58454078 -0.27221292, + 0.78501713 -0.60168606 -0.14738402, + 0.78487998 -0.60357702 -0.14020801, + 0.79116482 -0.60880786 -0.058405586, + 0.78887272 -0.61320078 -0.040798184, + 0.78954268 -0.61368477 0.0036370286, + 0.78945714 -0.61379504 0.0036371204, + 0.78955489 -0.61366892 0.0036608896, + 0.75846809 -0.65168607 -0.0056040906, + 0.75104117 -0.66010219 -0.014226303, + 0.7581352 -0.65181118 -0.019320704, + 0.75661886 -0.65054393 -0.065729789, + 0.72401202 -0.686634 -0.065881997, + 0.72561175 -0.68809777 0.0030240589, + 0.72552216 -0.68819219 0.0030241406, + 0.69133085 -0.72253084 -0.0032850392, + 0.69097394 -0.72287196 -0.0033611394, + 0.68879503 -0.72065204 -0.078879304, + 0.68915278 -0.72031379 -0.078844368, + 0.72392607 -0.68673307 -0.06579221, + 0.72398508 -0.68668103 -0.065686308, + 0.71467024 -0.67732024 -0.17459606, + 0.75107831 -0.63931423 -0.16479906, + 0.72649342 -0.61694938 -0.30262318, + 0.76324785 -0.5800789 -0.28453693, + 0.72620898 -0.54967701 -0.41288701, + 0.76488113 -0.51505405 -0.38688007, + 0.71355116 -0.47706011 -0.51308709, + 0.75581765 -0.44585878 -0.47953075, + 0.70880795 -0.41443995 -0.57081592, + 0.75412232 -0.38584614 -0.53143418, + 0.69755936 -0.35164818 -0.62430328, + 0.6898098 -0.3424049 -0.63790381, + 0.64192379 -0.36263689 -0.67559475, + 0.68938524 -0.39410916 -0.60780424, + 0.65821415 -0.40958008 -0.6316632, + 0.55978787 -0.33968291 -0.75581282, + 0.60179621 -0.3273901 -0.72846222, + 0.57276005 -0.30830303 -0.75953615, + 0.6279943 -0.29269314 -0.72107834, + 0.67370725 -0.32048011 -0.66589123, + 0.74857402 -0.287545 -0.59745699, + 0.77791315 -0.30615506 -0.54874414, + 0.83625698 -0.26716101 -0.478852, + 0.8540681 -0.28006804 -0.43832606, + 0.89686477 -0.23814894 -0.37271792, + 0.90935874 -0.24967894 -0.33275691, + 0.93852675 -0.20718296 -0.27612093, + 0.94155526 -0.21104905 -0.26254907, + 0.96214509 -0.17075102 -0.21241704, + 0.96175301 -0.17005999 -0.214734, + 0.97678179 -0.13300797 -0.16794695, + 0.9772079 -0.13407798 -0.16458398, + 0.98748934 -0.099593334 -0.12225404, + 0.987405 -0.099268198 -0.123196, + 0.99412662 -0.067902781 -0.084270068, + 0.99397987 -0.06698779 -0.086698391, + 0.99800402 -0.038611401 -0.049972501, + 0.99792546 -0.037697919 -0.052188225, + 0.99978954 -0.012012694 -0.016630093, + 0.99977863 -0.011593997 -0.017559394, + 0.99979222 0.011232203 0.017011404, + 0.99977922 0.010704303 0.018084504, + 0.99808311 0.031523302 0.053257108, + 0.99794221 0.029576808 0.056890715, + 0.99453962 0.048138481 0.092593871, + 0.99408698 0.0443337 0.099123903, + 0.98886186 0.060766593 0.13586599, + 0.98782325 0.05452821 0.14571203, + 0.98055553 0.068779074 0.18379392, + 0.97857052 0.05960397 0.19709691, + 0.96912289 0.071375594 0.23602197, + 0.9656741 0.058538206 0.25307503, + 0.95372713 0.067759007 0.29293904, + 0.94826478 0.050886691 0.31337592, + 0.93345386 0.057493191 0.35405996, + 0.92801875 0.04295389 0.37004891, + 0.92603725 0.027650708 0.37641808, + 0.90366811 0.031372402 0.42708305, + 0.89691126 0.016222803 0.44191313, + 0.87598926 0.017694604 0.48200613, + 0.87090373 0.0070016976 0.49140382, + 0.8481397 0.0075476272 0.52971882, + 0.84316611 -0.0025589503 0.53764707, + 0.81856471 -0.0027339191 0.57440782, + 0.81215483 -0.015472597 0.58323687, + 0.78567016 -0.016406303 0.61842811, + 0.77819085 -0.031045396 0.62725997, + 0.75034183 -0.032677893 0.66024184, + 0.74188185 -0.049123488 0.66872883, + 0.71273422 -0.051387619 0.69954926, + 0.70335215 -0.069640316 0.7074222, + 0.672732 -0.0724857 0.73632699, + 0.66249603 -0.092565209 0.74332404, + 0.6304962 -0.095917523 0.77024317, + 0.61954808 -0.11773501 0.77607912, + 0.58683306 -0.12144802 0.80054814, + 0.57563818 -0.14430104 0.80487132, + 0.54234594 -0.14826198 0.82696986, + 0.53124809 -0.17168105 0.8296392, + 0.49695525 -0.1758481 0.84977239, + 0.48526487 -0.20154895 0.85082084, + 0.45011994 -0.20583597 0.86892086, + 0.43841881 -0.2328479 0.86808461, + 0.4032729 -0.23707294 0.88383675, + 0.39185295 -0.26501396 0.88103288, + 0.35683504 -0.26908702 0.89457309, + 0.34583411 -0.29791611 0.88974428, + 0.31086901 -0.30177701 0.901272, + 0.30047402 -0.33133602 0.89438909, + 0.265811 -0.33489099 0.90398699, + 0.25625807 -0.3648591 0.89510322, + 0.22236504 -0.36801302 0.90284014, + 0.22241703 -0.36782703 0.90290314, + 0.19042103 -0.37037402 0.90915513, + 0.19695804 -0.34065402 0.91932714, + 0.16276301 -0.34282604 0.9251911, + 0.16764405 -0.3130511 0.93482333, + 0.13132498 -0.3147949 0.94003075, + 0.13475105 -0.28500408 0.94900733, + 0.096826285 -0.28627697 0.95324188, + 0.099019952 -0.25635788 0.96149653, + 0.059850093 -0.25716296 0.96451288, + 0.061015677 -0.22706793 0.97196567, + 0.020600306 -0.22744405 0.97357327, + 0.020940505 -0.19731104 0.98011726, + -0.020388808 -0.19731407 0.98012835, + -0.020040294 -0.22746594 0.97357976, + -0.060351521 -0.22709708 0.97200036, + -0.059178777 -0.25717291 0.96455163, + -0.098372944 -0.25637513 0.96155846, + -0.096177198 -0.286239 0.95331901, + -0.13415197 -0.28497195 0.94910175, + -0.13073395 -0.31464687 0.94016266, + -0.16721299 -0.31290299 0.93494999, + -0.16235505 -0.34250909 0.92538023, + -0.19678308 -0.34032813 0.91948533, + -0.19026895 -0.36994192 0.90936273, + -0.22259192 -0.36737087 0.90304571, + -0.22240993 -0.3680259 0.90282375, + -0.25623992 -0.36487788 0.89510071, + -0.26584592 -0.33474287 0.90403169, + -0.30061507 -0.3311781 0.89440024, + -0.311037 -0.30153501 0.90129501, + -0.34600678 -0.29767582 0.88975745, + -0.3570019 -0.26885295 0.89457679, + -0.39204895 -0.26477697 0.88101691, + -0.40341792 -0.23695295 0.88380277, + -0.43859199 -0.23272499 0.86803001, + -0.45016414 -0.20601207 0.86885631, + -0.48525387 -0.20172696 0.85078484, + -0.49682093 -0.17630598 0.84975588, + -0.53105927 -0.17213809 0.82966542, + -0.54239088 -0.14823197 0.82694584, + -0.57570308 -0.14426701 0.80483115, + -0.58706105 -0.12107102 0.80043811, + -0.61977476 -0.11736695 0.77595371, + -0.63076276 -0.095450766 0.77008271, + -0.66280693 -0.092106692 0.74310392, + -0.67305392 -0.07198479 0.73608196, + -0.70369291 -0.069153495 0.70713097, + -0.71303564 -0.050955974 0.69927365, + -0.74219018 -0.048707511 0.66841716, + -0.75055188 -0.032436796 0.66001493, + -0.778391 -0.0308154 0.62702298, + -0.78574717 -0.016408104 0.61833012, + -0.81222713 -0.015474302 0.58313608, + -0.81848073 -0.0030482388 0.57452583, + -0.84306115 -0.0028534406 0.53781015, + -0.84785599 0.0068752901 0.530182, + -0.87063003 0.0063788202 0.49189699, + -0.87583029 0.017293606 0.48230919, + -0.89675814 0.015856702 0.44223705, + -0.90748143 0.040358718 0.4181492, + -0.92543942 0.036400918 0.37714317, + -0.93371475 0.058178984 0.35325891, + -0.9484809 0.051486693 0.31262296, + -0.95386821 0.068195112 0.29237807, + -0.96579051 0.058904272 0.25254488, + -0.96916527 0.071501017 0.23581006, + -0.97859967 0.059708979 0.19691992, + -0.98055488 0.068753392 0.18380699, + -0.98782223 0.054508612 0.14572603, + -0.98885286 0.060693491 0.13596399, + -0.99408197 0.0442813 0.099197902, + -0.99453312 0.048067007 0.092700809, + -0.99793947 0.029535314 0.056960925, + -0.99808055 0.031478986 0.053332575, + -0.99977887 0.010690399 0.018111998, + -0.99979186 0.011217899 0.017039698, + -0.99977821 -0.011580002 -0.017589804, + -0.99978924 -0.011998303 -0.016661903, + -0.99792165 -0.037655987 -0.052292481, + -0.99799854 -0.03854768 -0.050129879, + -0.99396235 -0.066883922 -0.08698003, + -0.99410611 -0.06777551 -0.084614106, + -0.9873575 -0.099095345 -0.12371506, + -0.98751777 -0.099712275 -0.12192697, + -0.97726274 -0.13422997 -0.16413395, + -0.97688389 -0.13327199 -0.16714199, + -0.96192878 -0.17038596 -0.21368596, + -0.96144485 -0.16954099 -0.21651697, + -0.94043714 -0.20959704 -0.26767004, + -0.93850011 -0.20714903 -0.27623704, + -0.90932322 -0.24963206 -0.33288908, + -0.89719588 -0.23842697 -0.37174198, + -0.8545292 -0.28041306 -0.43720508, + -0.83622581 -0.26713893 -0.47891888, + -0.77785528 -0.30613911 -0.54883516, + -0.74970096 -0.28826997 -0.59569192, + -0.68609983 -0.31690192 -0.65485883, + -0.67997724 -0.33568913 -0.65187722, + -0.66599 -0.32685599 -0.67053902, + -0.62640929 -0.34154916 -0.70068234, + -0.73312426 -0.41068715 -0.54209316, + -0.68394017 -0.39827409 -0.61123115, + -0.75829285 -0.44773394 -0.47384194, + -0.71621704 -0.47930205 -0.50725007, + -0.61417389 -0.39822292 -0.68132883, + -0.70601296 -0.46530795 -0.53388596, + -0.66184896 -0.49253395 -0.56512493, + -0.71995598 -0.53976297 -0.43625599, + -0.67917204 -0.57084006 -0.46137506, + -0.72080576 -0.60831279 -0.33225688, + -0.68163574 -0.64214873 -0.35073888, + -0.71083558 -0.67121559 -0.21019588, + -0.67214799 -0.706581 -0.22126999, + -0.68780226 -0.72381526 -0.05495102, + -0.78404909 -0.62057304 -0.012496202, + -0.71608198 -0.69788402 -0.013583, + -0.55817193 -0.82958889 -0.015042698, + -0.46991017 -0.88258332 -0.015201606, + -0.64052868 -0.76779562 -0.014594894, + -0.65108794 -0.75898987 -0.0043369895, + -0.64991003 -0.7576611 -0.059722606, + -0.68643326 -0.72492021 -0.057445422, + -0.68758905 -0.72609204 0.0034215504, + -0.68755203 -0.72612709 0.0034215804, + -0.72218198 -0.691477 -0.017685501, + -0.72101396 -0.69039196 -0.059143193, + -0.72102523 -0.69038022 -0.059142321, + -0.72229362 -0.69155365 -0.0067422269, + -0.75534081 -0.65532082 0.0038674991, + -0.75404531 -0.65424526 -0.058128621, + -0.75411099 -0.65416998 -0.058123, + -0.75540715 -0.65524417 0.003882691, + -0.755364 -0.655294 0.0038827299, + -0.78653109 -0.61738306 -0.014393002, + -0.78534168 -0.61648375 -0.056446582, + -0.78531218 -0.61652112 -0.056449115, + -0.78654981 -0.61745489 -0.0094350977, + -0.816006 -0.57802898 0.0040889601, + -0.81593418 -0.57813513 0.0033558507, + -0.8159318 -0.57813388 0.0040612691, + -0.81589782 -0.57818186 0.0040613092, + -0.81463313 -0.57733303 -0.055312607, + -0.82216412 -0.56782109 -0.040315602, + -0.81377912 -0.56153208 -0.14981802, + -0.84369588 -0.51867795 -0.13838498, + -0.82964784 -0.50910789 -0.22911493, + -0.85926211 -0.46647507 -0.20992804, + -0.84197116 -0.45577711 -0.28870705, + -0.87184888 -0.41375095 -0.26208696, + -0.84098113 -0.39651906 -0.36813504, + -0.87633687 -0.35301298 -0.32774296, + -0.84239233 -0.33512512 -0.42197916, + -0.88172674 -0.29339194 -0.3694309, + -0.88347876 -0.29431695 -0.36447591, + -0.92082256 -0.24500687 -0.30340984, + -0.92821109 -0.25006104 -0.27548802, + -0.95359886 -0.20235898 -0.22293498, + -0.95734078 -0.20619196 -0.20244396, + -0.97645098 -0.153944 -0.151145, + -0.97690648 -0.15491408 -0.14715807, + -0.98735636 -0.11492804 -0.10917404, + -0.98724985 -0.11456899 -0.11050598, + -0.99406654 -0.078290164 -0.075513765, + -0.99403602 -0.078116298 -0.076093398, + -0.99802601 -0.044986099 -0.043821201, + -0.99797666 -0.044431984 -0.045479584, + -0.99979502 -0.0141492 -0.0144828, + -0.99978834 -0.013890404 -0.015180806, + -0.99980152 0.013449494 0.014698992, + -0.99979311 0.013093702 0.015566102, + -0.99820501 0.038551699 0.045831099, + -0.99811113 0.037150804 0.048928507, + -0.99498779 0.060470086 0.07964088, + -0.99468315 0.057636708 0.08534281, + -0.98997837 0.079036728 0.11703005, + -0.98927861 0.074296869 0.12572895, + -0.98285574 0.093799978 0.15873295, + -0.98151988 0.086730592 0.17057699, + -0.97331166 0.10401096 0.20456293, + -0.97099334 0.094012737 0.21984908, + -0.96075875 0.10906298 0.25504494, + -0.95706922 0.095742121 0.27359107, + -0.94451755 0.10849195 0.31002584, + -0.93887186 0.091084391 0.33199897, + -0.92369503 0.101366 0.36947599, + -0.92394423 0.099660121 0.36931708, + -0.90316123 0.11184603 0.4144761, + -0.8994621 0.10240401 0.42483106, + -0.87847924 0.11196103 0.46447712, + -0.87371027 0.10065003 0.47592017, + -0.85009319 0.10896502 0.51523614, + -0.8441087 0.095631361 0.52757484, + -0.81778812 0.10265002 0.56629103, + -0.81039882 0.087021075 0.57937986, + -0.78181118 0.092611425 0.61659914, + -0.77318788 0.075105496 0.62971395, + -0.74244285 0.079337277 0.66519481, + -0.73601234 0.066568628 0.67368728, + -0.70322984 0.069911286 0.70751685, + -0.69781822 0.059165023 0.71382725, + -0.66660124 0.061572023 0.74286723, + -0.65820122 0.044357516 0.75153428, + -0.62579805 0.045956604 0.77863014, + -0.40069494 -0.0039847894 0.9162029, + -0.44917393 -0.0038857795 0.8934359, + -0.45337901 0.0071744001 0.891289, + -0.49319676 0.0070021367 0.86988956, + -0.49734676 0.017185992 0.86738157, + -0.5366801 0.016715204 0.84362018, + -0.54067385 0.025955794 0.84083182, + -0.57876211 0.025161706 0.81510818, + -0.5825001 0.033399407 0.81214416, + -0.61936677 0.032259889 0.78443873, + -0.62046307 0.018472102 0.7840181, + -0.57951468 0.019195791 0.81473559, + -0.57571417 0.010837804 0.81757927, + -0.53764397 0.011175999 0.84309787, + -0.53361708 0.0018806902 0.84572411, + -0.49433783 0.0019330293 0.8692677, + -0.49016589 -0.008279738 0.87158984, + -0.45045415 -0.0084808525 0.89275932, + -0.44617411 -0.019706605 0.89472926, + -0.40612501 -0.0201221 0.91359597, + -0.39897406 -0.040349305 0.9160741, + -0.36122099 -0.041032199 0.93157703, + -0.3517051 -0.070686318 0.93343824, + -0.31349885 -0.071703963 0.94687754, + -0.30465403 -0.10242301 0.94694012, + -0.26667494 -0.10364098 0.95819777, + -0.25868604 -0.13517901 0.95645612, + -0.22111003 -0.13647902 0.96565211, + -0.21410011 -0.16874208 0.96212649, + -0.17668906 -0.17003006 0.96946937, + -0.17077599 -0.202888 0.96419501, + -0.13373204 -0.20406404 0.96978027, + -0.12903903 -0.23724206 0.96284223, + -0.092714176 -0.23821194 0.96677774, + -0.089314058 -0.27151689 0.9582805, + -0.053956691 -0.27220997 0.96072388, + -0.051890619 -0.30557713 0.95075238, + -0.0174639 -0.305942 0.95188999, + -0.016766192 -0.33924785 0.94054753, + 0.016696507 -0.33924916 0.94054848, + 0.017392999 -0.30596197 0.95188487, + 0.051759887 -0.30559793 0.95075274, + 0.053822074 -0.27225187 0.96071953, + 0.089190096 -0.27155998 0.95827991, + 0.092588954 -0.23823288 0.96678454, + 0.12882903 -0.23726706 0.96286422, + 0.13353199 -0.20400196 0.96982086, + 0.17065302 -0.20282502 0.96423012, + 0.17659001 -0.16982602 0.96952313, + 0.21404296 -0.16853896 0.96217477, + 0.22100502 -0.13649301 0.9656741, + 0.25861511 -0.13519207 0.95647347, + 0.26656196 -0.10382998 0.95820874, + 0.30450696 -0.10261199 0.94696689, + 0.31332985 -0.071979366 0.94691253, + 0.34815091 -0.071054287 0.93474174, + 0.65013069 -0.014884492 0.75967664, + 0.61046404 -0.015515602 0.79189211, + 0.60678214 -0.023244405 0.79452819, + 0.56988317 -0.02402981 0.8213743, + 0.56590211 -0.032713208 0.82382315, + 0.52794302 -0.033697501 0.848611, + 0.52373409 -0.043327812 0.85077918, + 0.48471111 -0.044487011 0.87354219, + 0.48036084 -0.055032481 0.87534273, + 0.44107494 -0.056312494 0.89570189, + 0.43666878 -0.067750171 0.89706761, + 0.39709714 -0.069117419 0.91517031, + 0.39274201 -0.081368104 0.91604197, + 0.35282996 -0.082787089 0.93201786, + 0.34588003 -0.10416202 0.93247914, + 0.30824196 -0.10560799 0.94542789, + 0.29937887 -0.13613395 0.94437265, + 0.26197997 -0.13769399 0.9551999, + 0.25400192 -0.16891494 0.95233965, + 0.21684605 -0.17048804 0.96120322, + 0.20975304 -0.20281103 0.95648915, + 0.17290808 -0.2043011 0.96351647, + 0.16695204 -0.23701505 0.95705324, + 0.13054402 -0.23833203 0.9623701, + 0.12583497 -0.27120095 0.95426178, + 0.090362675 -0.27225494 0.95797276, + 0.086946145 -0.30526015 0.94829148, + 0.052462213 -0.30599907 0.95058525, + 0.050388418 -0.33898813 0.93944037, + 0.016916597 -0.33936998 0.94050086, + 0.016220098 -0.37210998 0.92804688, + -0.016254505 -0.37211013 0.92804635, + -0.016951801 -0.33935103 0.94050711, + -0.05044828 -0.33896688 0.93944466, + -0.052526508 -0.30593902 0.9506011, + -0.087043494 -0.30519998 0.94830185, + -0.090461694 -0.27219698 0.95797986, + -0.12601103 -0.27113906 0.95425624, + -0.13071901 -0.23828501 0.962358, + -0.16712499 -0.23696697 0.95703489, + -0.17305902 -0.20438203 0.96347213, + -0.20986603 -0.20289204 0.95644712, + -0.21693005 -0.17070805 0.96114522, + -0.2539809 -0.16913794 0.95230561, + -0.26202404 -0.13766304 0.95519227, + -0.29944906 -0.13610102 0.94435525, + -0.30836207 -0.10539802 0.94541222, + -0.3460688 -0.10395194 0.93243247, + -0.35569689 -0.07417047 0.93165362, + -0.39303017 -0.072974034 0.91662544, + -0.40316081 -0.044355679 0.91405356, + -0.44005194 -0.043523997 0.89691687, + -0.43683305 -0.040218603 0.89864314, + -0.483895 -0.039126899 0.87425101, + -0.48818889 -0.028674792 0.87226683, + -0.5273028 -0.02791699 0.84921873, + -0.53144497 -0.018405598 0.84689289, + -0.56944996 -0.017860997 0.82183188, + -0.57124901 -0.032198001 0.82014501, + -0.52825582 -0.033308487 0.84843171, + -0.52405417 -0.042931017 0.85060227, + -0.485028 -0.044080898 0.87338698, + -0.48066407 -0.054667506 0.87519914, + -0.44132215 -0.055941917 0.8956033, + -0.43375894 -0.075479195 0.8978619, + -0.39720881 -0.076878063 0.91450256, + -0.38693491 -0.10568298 0.91603076, + -0.35005996 -0.10735799 0.93055487, + -0.34034801 -0.137154 0.93024302, + -0.30313703 -0.13899902 0.9427551, + -0.29417604 -0.16959402 0.94058412, + -0.25718793 -0.17147696 0.95102578, + -0.24907994 -0.20288396 0.94699377, + -0.21251504 -0.20470105 0.95547622, + -0.20541693 -0.23666291 0.94962865, + -0.16924295 -0.23833095 0.95632374, + -0.16327792 -0.27065587 0.9487285, + -0.12757203 -0.27209607 0.95377624, + -0.12283602 -0.30466604 0.9445051, + -0.088065393 -0.30579796 0.94801486, + -0.084624805 -0.33850902 0.93715012, + -0.051010974 -0.33928484 0.93929952, + -0.04892832 -0.37181312 0.92701733, + -0.016436206 -0.37220913 0.92800337, + -0.016407596 -0.37355292 0.92746377, + 0.016384495 -0.3735539 0.92746377, + 0.016412908 -0.37221518 0.9280014, + 0.048894119 -0.37182012 0.92701638, + 0.050974682 -0.33931789 0.93928963, + 0.084578097 -0.338543 0.93714201, + 0.088014208 -0.30588603 0.94799113, + 0.12268697 -0.30475795 0.94449478, + 0.12742496 -0.27217391 0.95377362, + 0.16311005 -0.27073705 0.94873422, + 0.16907698 -0.23838396 0.9563399, + 0.20525308 -0.23671809 0.94965035, + 0.21238296 -0.20460695 0.95552576, + 0.24898006 -0.20279005 0.94704026, + 0.25713289 -0.17119993 0.95109051, + 0.29415989 -0.16931894 0.94063866, + 0.30303699 -0.139008 0.94278598, + 0.34028196 -0.13716199 0.9302659, + 0.34991813 -0.10760804 0.93057936, + 0.38675505 -0.10593201 0.91607809, + 0.39411995 -0.085408494 0.91508186, + 0.43349993 -0.083744593 0.89725387, + 0.43794715 -0.072243325 0.89609331, + 0.47709399 -0.070624299 0.87601, + 0.48149887 -0.059982587 0.87439179, + 0.52043277 -0.058439676 0.85190058, + 0.52469301 -0.048724402 0.84989601, + 0.56260413 -0.04731831 0.82537121, + 0.5666492 -0.038520515 0.82305831, + 0.60354108 -0.037275705 0.79646009, + 0.60729486 -0.029415892 0.79393184, + 0.64340395 -0.028344097 0.76500189, + 0.65005177 -0.014747694 0.75974673, + 0.68169898 -0.0141993 0.73149502, + 0.69106793 0.0044771796 0.72277594, + 0.69082499 0.0049649398 0.723005, + 0.65292972 0.0052011278 0.75740063, + 0.64960998 -0.00157709 0.76026601, + 0.61359006 -0.0016380002 0.78962314, + 0.60994792 -0.009302659 0.79238689, + 0.57305884 -0.0096204765 0.81945771, + 0.56913596 -0.018202098 0.82204187, + 0.53112495 -0.018756699 0.84708589, + 0.5269829 -0.028263893 0.84940583, + 0.48789206 -0.029029803 0.87242115, + 0.48357576 -0.039526183 0.87440956, + 0.44414622 -0.040458817 0.89504039, + 0.43979606 -0.051791109 0.89660311, + 0.40005085 -0.052851982 0.91496772, + 0.39572418 -0.065068029 0.9160614, + 0.35299113 -0.066290826 0.93327534, + 0.3583599 -0.049603891 0.93226475, + 0.39866015 -0.048728019 0.91580331, + 0.40294784 -0.036579084 0.91449171, + 0.44284487 -0.035834692 0.89588177, + 0.44714305 -0.024601104 0.89412409, + 0.48675382 -0.02402569 0.8732087, + 0.49100411 -0.013656002 0.87105018, + 0.53016394 -0.013291298 0.8477909, + 0.5342651 -0.0038530009 0.84530818, + 0.57230699 -0.00373777 0.82003099, + 0.57617188 0.0047384589 0.8173148, + 0.61307412 0.0045801611 0.79001218, + 0.61668587 0.012197398 0.7871148, + 0.65265781 0.011739397 0.7575618, + 0.65591204 0.018396601 0.7546131, + 0.69080216 0.017621703 0.72282916, + 0.69662791 0.029351296 0.71683192, + 0.72649908 0.028113104 0.68659204, + 0.73415595 0.043205295 0.67760491, + 0.76235712 0.041180305 0.64584506, + 0.76690781 0.050020888 0.63980484, + 0.79668885 0.047108293 0.60255092, + 0.80119967 0.05601358 0.59576976, + 0.82913768 0.05232998 0.55658984, + 0.83584589 0.066093296 0.54497093, + 0.86113709 0.061206307 0.50467503, + 0.86685681 0.073678888 0.49308288, + 0.889449 0.067542501 0.452016, + 0.89390713 0.07800971 0.44141206, + 0.91398925 0.070611112 0.3995471, + 0.91737759 0.079292163 0.39003983, + 0.93500537 0.070649423 0.34752512, + 0.93953621 0.083787926 0.33204108, + 0.95311463 0.074039973 0.29341188, + 0.95767313 0.08926741 0.27366704, + 0.96866411 0.077023104 0.23613003, + 0.9714815 0.088324659 0.2200509, + 0.98023474 0.073694088 0.18359995, + 0.98187453 0.081819162 0.17096193, + 0.9886601 0.064827509 0.13545701, + 0.98950636 0.070238225 0.12626904, + 0.99443209 0.051226109 0.092090607, + 0.99480575 0.054540288 0.085946977, + 0.99804264 0.033507288 0.05280238, + 0.99815714 0.035156902 0.049460907, + 0.99978763 0.011938196 0.016795294, + 0.99979836 0.012381305 0.015812205, + 0.99978501 -0.0127826 -0.0163248, + 0.99979365 -0.013117195 -0.015509894, + 0.99796522 -0.041174412 -0.048685111, + 0.99802476 -0.041860688 -0.046843488, + 0.99403763 -0.072655581 -0.081303872, + 0.99412674 -0.073191285 -0.079718977, + 0.98739153 -0.10705695 -0.11660495, + 0.98732263 -0.10680896 -0.11741295, + 0.97687811 -0.14386602 -0.15815102, + 0.97727466 -0.14480396 -0.15480994, + 0.96253037 -0.18524206 -0.19804208, + 0.96098536 -0.18275505 -0.20762408, + 0.93349642 -0.23692612 -0.26916611, + 0.92771924 -0.23190206 -0.29250407, + 0.88155049 -0.29328883 -0.3699328, + 0.87890911 -0.29190403 -0.37724105, + 0.83878613 -0.33319503 -0.43060306, + 0.85845882 -0.3433719 -0.3809779, + 0.82226312 -0.38101405 -0.42274305, + 0.84513414 -0.39383307 -0.36144704, + 0.81003213 -0.43202007 -0.39649305, + 0.840716 -0.450901 -0.299808, + 0.80763435 -0.49104425 -0.32650015, + 0.83195531 -0.50760621 -0.22402307, + 0.79978883 -0.54917687 -0.24236894, + 0.81676519 -0.56200612 -0.13055202, + 0.82226187 -0.56806391 -0.034479298, + 0.8166157 -0.5637368 -0.12385295, + 0.84623402 -0.52039999 -0.114332, + 0.83264929 -0.5110302 -0.21340908, + 0.86188489 -0.46793994 -0.19541398, + 0.8430047 -0.45620286 -0.2849949, + 0.87271112 -0.41407806 -0.25867903, + 0.85024899 -0.40143001 -0.34048599, + 0.88134998 -0.36031201 -0.30561, + 0.86664116 -0.35270408 -0.3528921, + 0.89761513 -0.31159502 -0.31176203, + 0.88751978 -0.30668095 -0.34388292, + 0.91912144 -0.26222312 -0.29403216, + 0.92111474 -0.26326695 -0.28677195, + 0.95400202 -0.202747 -0.22084799, + 0.95730901 -0.20615 -0.202637, + 0.97643399 -0.15391099 -0.151288, + 0.97720367 -0.15556493 -0.14447296, + 0.98751014 -0.11544801 -0.10721701, + 0.98722947 -0.11449105 -0.11076906, + 0.99405777 -0.078232579 -0.075689286, + 0.99402988 -0.078074291 -0.07621669, + 0.99802411 -0.044961203 -0.043891404, + 0.99798214 -0.044490203 -0.045301404, + 0.9997955 -0.014169306 -0.014427607, + 0.99978876 -0.013906796 -0.015135496, + 0.99980187 0.013467198 0.014657198, + 0.99979347 0.013105807 0.015537907, + 0.99820721 0.038590107 0.045751311, + 0.99811333 0.037184715 0.048858218, + 0.99499297 0.060529299 0.079531603, + 0.99468935 0.057697721 0.085229933, + 0.98998815 0.079127707 0.11688601, + 0.98928821 0.074377514 0.12560603, + 0.98286879 0.093908481 0.15858796, + 0.98152912 0.086809605 0.17048402, + 0.97332335 0.10410903 0.20445807, + 0.97098851 0.094034955 0.2198609, + 0.96075213 0.10908902 0.25505903, + 0.95701301 0.095600098 0.273837, + 0.94444448 0.10833094 0.31030482, + 0.94066077 0.096437275 0.3253569, + 0.93967611 0.082611911 0.33194003, + 0.92104489 0.094057284 0.37792793, + 0.9179436 0.085789062 0.38732383, + 0.89861774 0.094876178 0.42835093, + 0.894548 0.084929898 0.438829, + 0.87276816 0.092751123 0.47924212, + 0.86755484 0.080916576 0.49071488, + 0.84311986 0.08748699 0.53056091, + 0.83660072 0.073575467 0.54284984, + 0.80947018 0.078860424 0.58184111, + 0.80195487 0.063604996 0.59398896, + 0.77261412 0.067596905 0.63126707, + 0.76739115 0.057297308 0.63861406, + 0.73623282 0.060474087 0.67402083, + 0.73113525 0.05049742 0.68036121, + 0.70143163 0.052755274 0.71078163, + 0.69323099 0.0363364 0.71979898, + 0.66183996 0.037794895 0.74869192, + 0.655635 0.0250012 0.754664, + 0.61972827 0.02598591 0.78438628, + 0.61616713 0.018457703 0.78739917, + 0.57926929 0.019102609 0.81491244, + 0.57541996 0.010642399 0.8177889, + 0.53736585 0.010974097 0.84327781, + 0.53330785 0.0016098995 0.84591973, + 0.49404806 0.0016546502 0.8694331, + 0.48985794 -0.0085961791 0.87175989, + 0.45014384 -0.0088047571 0.89291269, + 0.44586307 -0.020028802 0.89487714, + 0.40581393 -0.020450698 0.91372687, + 0.40157685 -0.032493889 0.91524869, + 0.36104509 -0.033087209 0.93196124, + 0.35692701 -0.045959398 0.93300098, + 0.31589115 -0.046680823 0.9476465, + 0.30951685 -0.068858273 0.94839752, + 0.27105007 -0.069703415 0.96003824, + 0.26312602 -0.10122801 0.95943612, + 0.22499304 -0.10223501 0.9689821, + 0.21806096 -0.13441198 0.96663475, + 0.1801111 -0.13547406 0.97427249, + 0.17426609 -0.16828308 0.97021246, + 0.13645901 -0.16929902 0.97607213, + 0.13176505 -0.2028911 0.97029549, + 0.094741598 -0.20375501 0.97442698, + 0.091345802 -0.237488 0.96708602, + 0.055177882 -0.23812191 0.96966666, + 0.053122081 -0.27184892 0.96087265, + 0.017845903 -0.27219003 0.96207809, + 0.017153399 -0.30582896 0.95193189, + -0.017259305 -0.30582812 0.95193034, + -0.017953498 -0.27215496 0.9620859, + -0.053266909 -0.27181202 0.96087509, + -0.055322673 -0.23810488 0.96966255, + -0.091477208 -0.23747003 0.96707809, + -0.09486942 -0.20379505 0.97440624, + -0.13192697 -0.20292796 0.97026575, + -0.13660394 -0.16946793 0.97602254, + -0.1743129 -0.16845292 0.97017455, + -0.18018894 -0.13546295 0.97425961, + -0.21816808 -0.13440004 0.96661234, + -0.22512689 -0.10208695 0.96896654, + -0.26329604 -0.10108002 0.95940512, + -0.27123293 -0.069492288 0.96000177, + -0.30976495 -0.068647482 0.94833177, + -0.31852901 -0.037979499 0.94715202, + -0.35717604 -0.037423603 0.93328714, + -0.36654696 -0.0080232192 0.93036491, + -0.40469083 -0.0078857066 0.91441959, + -0.41171315 0.012092405 0.91123331, + -0.45208794 0.011835798 0.89189488, + -0.45626912 0.022861606 0.88954824, + -0.49619982 0.022305792 0.86792171, + -0.50029886 0.032389492 0.86524683, + -0.53971481 0.031491589 0.8412587, + -0.54364485 0.040603586 0.83833271, + -0.58175194 0.039348196 0.81241387, + -0.58843291 0.054177988 0.80672884, + -0.62185186 0.052475289 0.78137481, + -0.63061285 0.071034387 0.77283984, + -0.66292673 0.068525374 0.74554175, + -0.66878217 0.080447622 0.73909318, + -0.70324308 0.076929808 0.70677507, + -0.7103442 0.091268323 0.69791216, + -0.74278092 0.086818092 0.66388196, + -0.7521081 0.10590401 0.65047508, + -0.78222084 0.10011297 0.61490488, + -0.79033762 0.11725394 0.60134673, + -0.81820911 0.11002801 0.56429404, + -0.82494819 0.12486603 0.55124313, + -0.85052484 0.11618997 0.51293987, + -0.85600841 0.12890491 0.50063264, + -0.87890321 0.11894103 0.46193311, + -0.88326257 0.12970094 0.4505828, + -0.90355986 0.11852098 0.41174293, + -0.90695375 0.12753697 0.40145892, + -0.92490786 0.11511198 0.36234596, + -0.9294734 0.12861706 0.34574118, + -0.94362038 0.11541705 0.31025711, + -0.94829702 0.13099299 0.28909099, + -0.96005464 0.11548596 0.25486892, + -0.96314275 0.12750196 0.23685294, + -0.97278315 0.10983402 0.20403303, + -0.97468799 0.118651 0.189487, + -0.98248535 0.098893136 0.15793306, + -0.98359346 0.10515305 0.14658408, + -0.98974389 0.083267294 0.11607599, + -0.9903149 0.087364189 0.10790698, + -0.99486214 0.06370461 0.078684308, + -0.99511176 0.066137984 0.073337883, + -0.9981575 0.040635683 0.045059279, + -0.99823213 0.041783903 0.042270802, + -0.99979621 0.014193804 0.014359304, + -0.99980289 0.014482498 0.013581198, + -0.99978966 -0.014961095 -0.014029996, + -0.99979538 -0.015179305 -0.013373905, + -0.99797875 -0.047681689 -0.042010687, + -0.99800253 -0.047938578 -0.041143883, + -0.99395978 -0.083278574 -0.071475089, + -0.99404824 -0.083755225 -0.069664918, + -0.98719335 -0.12264805 -0.10201403, + -0.98699349 -0.12203606 -0.10464706, + -0.974042 -0.17184 -0.14735401, + -0.97232938 -0.16960905 -0.16065006, + -0.94950902 -0.227782 -0.21574999, + -0.94897974 -0.22748993 -0.21837096, + -0.92522442 -0.27372012 -0.26274911, + -0.93581635 -0.27883109 -0.21564108, + -0.91105378 -0.32613492 -0.25222394, + -0.92470801 -0.332609 -0.185166, + -0.90152574 -0.3780849 -0.21048295, + -0.91072589 -0.38285193 -0.15492798, + -0.88695931 -0.42812216 -0.17324705, + -0.89527243 -0.43283021 -0.10557105, + -0.87078142 -0.47766724 -0.11650705, + -0.87652314 -0.48135805 0.0013204201, + -0.86751831 -0.49485818 -0.050273418, + -0.8686288 -0.49544787 0.003941929, + -0.86868984 -0.49534088 0.0039418391, + -0.86758602 -0.494755 -0.050120302, + -0.86749816 -0.49490812 -0.05012881, + -0.86860198 -0.49549499 0.0039144498, + -0.84324515 -0.53738606 -0.012403202, + -0.84325629 -0.5373922 -0.011338804, + -0.84371501 -0.536663 -0.0117421, + -0.89442891 -0.44706994 -0.011198899, + -0.89188474 -0.45218089 -0.008605388, + -0.89094311 -0.45173305 -0.046450604, + -0.89092076 -0.45177689 -0.046452887, + -0.891783 -0.452191 -0.015698399, + -0.91299742 -0.40795022 0.0035181316, + -0.91214222 -0.40756708 -0.04342391, + -0.91301179 -0.40791792 0.003520919, + -0.91300374 -0.40793592 0.003520929, + -0.91213298 -0.407585 -0.0434504, + -0.91212672 -0.40759885 -0.043450985, + -0.89959931 -0.43668616 0.0051360517, + -0.89520079 -0.4340609 -0.10102798, + -0.91711915 -0.38823605 -0.090362206, + -0.91102231 -0.38507614 -0.14749506, + -0.93190688 -0.33870196 -0.12973298, + -0.92559111 -0.33568004 -0.17492901, + -0.94521576 -0.28949594 -0.15086196, + -0.93678176 -0.28573895 -0.20197296, + -0.95661312 -0.23792502 -0.16817601, + -0.95125353 -0.23532487 -0.19934592, + -0.96899563 -0.18852693 -0.15970294, + -0.96937448 -0.18876009 -0.15710807, + -0.9847759 -0.13360599 -0.11120199, + -0.98558289 -0.13504799 -0.10192399, + -0.99383914 -0.088464804 -0.066766806, + -0.99391186 -0.08882039 -0.065192789, + -0.997989 -0.051100101 -0.037506599, + -0.99795121 -0.050708212 -0.039015409, + -0.99979275 -0.016135296 -0.012414797, + -0.99978936 -0.016009506 -0.012841205, + -0.99980277 0.015493697 0.012427397, + -0.99979711 0.015247202 0.013168902, + -0.99824065 0.044872586 0.038756184, + -0.99818045 0.043920424 0.041314717, + -0.99517387 0.071474396 0.067233689, + -0.99497521 0.069451213 0.072117716, + -0.99052888 0.095243484 0.098900385, + -0.99006122 0.091692023 0.10663702, + -0.98409754 0.11580895 0.13468593, + -0.98319411 0.11036001 0.14543101, + -0.97570378 0.13244297 0.17453095, + -0.97412276 0.12457997 0.18858595, + -0.96492922 0.14469303 0.21903306, + -0.9623909 0.13404298 0.23629697, + -0.95126265 0.15215795 0.2682299, + -0.95135099 0.15151601 0.26828, + -0.93618476 0.17285796 0.30606893, + -0.93441665 0.16684794 0.31468588, + -0.91843402 0.18530101 0.349489, + -0.9160763 0.17793706 0.35936412, + -0.89795488 0.19527997 0.39438894, + -0.89489812 0.18640001 0.40547806, + -0.874376 0.20268001 0.44089401, + -0.87048072 0.19204992 0.45318884, + -0.84740043 0.2071701 0.48886925, + -0.84251332 0.19452707 0.50232518, + -0.81710929 0.20818007 0.53758121, + -0.81120682 0.19356395 0.55179387, + -0.78344887 0.20571098 0.58642197, + -0.77646512 0.18899903 0.60115004, + -0.74610603 0.199696 0.63517499, + -0.73795897 0.18067898 0.65020895, + -0.70505697 0.18986297 0.68326193, + -0.69577283 0.16851196 0.69821483, + -0.66088593 0.17607199 0.72953993, + -0.65058309 0.15249002 0.74396807, + -0.61405373 0.15847993 0.77318966, + -0.60288125 0.13276304 0.78670728, + -0.56468409 0.13733603 0.81380016, + -0.55584592 0.11652499 0.82307786, + -0.51615375 0.12005894 0.84803957, + -0.50934988 0.10330198 0.8543368, + -0.47203976 0.10582495 0.8752026, + -0.46588218 0.089366831 0.88032228, + -0.42485484 0.091428474 0.90063268, + -0.42102605 0.080357105 0.90348214, + -0.37917277 0.081976347 0.92168748, + -0.37527683 0.069565572 0.92429858, + -0.33029491 0.070838884 0.94121575, + -0.33491808 0.087344125 0.93819022, + -0.3777101 0.085831024 0.92193723, + -0.38144115 0.097731836 0.91921234, + -0.42344886 0.095778562 0.90084273, + -0.42946994 0.11328299 0.89594787, + -0.467684 0.110876 0.87691402, + -0.47448283 0.12888795 0.87077773, + -0.5150069 0.12550896 0.84794784, + -0.52394575 0.14790493 0.83881158, + -0.56380111 0.14341803 0.81336319, + -0.57509291 0.17078498 0.80006289, + -0.61329597 0.164891 0.77244997, + -0.62388992 0.19016898 0.75802189, + -0.66022003 0.182761 0.72849703, + -0.66993719 0.20584305 0.7133112, + -0.70450103 0.19677202 0.68187904, + -0.71316397 0.21747699 0.66640902, + -0.74565876 0.20671992 0.63345075, + -0.75322211 0.22508503 0.61805606, + -0.7830959 0.21281198 0.58435595, + -0.78959614 0.22900803 0.56929207, + -0.81683588 0.21528997 0.53519094, + -0.8223111 0.22942403 0.52073908, + -0.84719342 0.21420211 0.48619023, + -0.85164589 0.22621398 0.47278595, + -0.87422812 0.20955403 0.43796405, + -0.87779123 0.21969606 0.42569509, + -0.89785522 0.20192404 0.39125809, + -0.90066475 0.21043895 0.38015592, + -0.91837287 0.19164898 0.34621096, + -0.92053926 0.19871004 0.33633608, + -0.93615437 0.17884105 0.30270612, + -0.93773675 0.18444896 0.29432693, + -0.95138878 0.16355096 0.26097995, + -0.95347601 0.171914 0.247647, + -0.96412575 0.15137197 0.21805495, + -0.96623135 0.16091606 0.20125407, + -0.97509724 0.13849802 0.17321604, + -0.97638321 0.14538303 0.15981105, + -0.98366737 0.12112404 0.13314505, + -0.98440599 0.125891 0.122867, + -0.99025363 0.099672563 0.097278364, + -0.99062574 0.10266398 0.090115078, + -0.99502522 0.074871518 0.065720215, + -0.99518585 0.076576091 0.061165292, + -0.99818414 0.047065608 0.037593704, + -0.99823463 0.047885481 0.035135288, + -0.99979633 0.016274605 0.011941205, + -0.99979991 0.016433598 0.011402399, + -0.99978626 -0.016987404 -0.011786803, + -0.99979055 -0.017144293 -0.011179394, + -0.99792713 -0.053906608 -0.035151403, + -0.99790865 -0.053732682 -0.035932288, + -0.99314433 -0.097169638 -0.06497962, + -0.99282449 -0.096292652 -0.070902362, + -0.98306888 -0.14755198 -0.10864598, + -0.98284733 -0.14738306 -0.11085804, + -0.97002465 -0.19420293 -0.14607294, + -0.97251624 -0.19549005 -0.12647504, + -0.95707023 -0.24336506 -0.15744905, + -0.96198535 -0.24547809 -0.11968604, + -0.94577122 -0.29197806 -0.14235803, + -0.94991475 -0.29383495 -0.10640997, + -0.93208843 -0.34058514 -0.12334106, + -0.93639064 -0.34263888 -0.075967468, + -0.91704261 -0.38933486 -0.086320467, + -0.92029464 -0.39115086 0.0076606474, + -0.93114525 -0.36236009 -0.04078931, + -0.9319129 -0.36262998 -0.0061436989, + -0.9318859 -0.36269996 -0.0061121793, + -0.93111789 -0.36242998 -0.040792298, + -0.938622 -0.3448 0.0100889, + -0.93631786 -0.34357396 -0.072565295, + -0.95291579 -0.29668993 -0.062663183, + -0.95446438 -0.29826412 -0.0060326322, + -0.95284837 -0.29751113 -0.059726223, + -0.96677262 -0.25063691 -0.050316181, + -0.96491933 -0.24985109 -0.080655128, + -0.97698075 -0.20301196 -0.065534882, + -0.97550374 -0.20237796 -0.086230278, + -0.98557913 -0.15567301 -0.066330306, + -0.98430073 -0.15506697 -0.084299177, + -0.99235779 -0.10840998 -0.058935385, + -0.99200433 -0.10812904 -0.065081023, + -0.99725962 -0.06338618 -0.038151287, + -0.99729252 -0.063446969 -0.037177481, + -0.99974835 -0.019354507 -0.011341004, + -0.9997561 -0.019490102 -0.010389501, + -0.99978763 0.018184094 0.0096933162, + -0.99978876 0.018227596 0.0094969785, + -0.99817288 0.053584792 0.027918896, + -0.99813765 0.052987583 0.030222889, + -0.99506855 0.086159855 0.049143579, + -0.99497622 0.085088626 0.052747313, + -0.99054086 0.11662699 0.072298191, + -0.99029714 0.11440202 0.078891009, + -0.9844861 0.14444701 0.099611014, + -0.98401898 0.14095201 0.108808, + -0.97689497 0.169177 0.130596, + -0.97606987 0.16396798 0.14283599, + -0.96754289 0.19054697 0.16598998, + -0.96615952 0.1830949 0.18169191, + -0.95607424 0.20806605 0.20647204, + -0.95470423 0.20148204 0.21896306, + -0.94190377 0.22743393 0.24716593, + -0.94086677 0.22302394 0.25500995, + -0.92626524 0.24810305 0.28368607, + -0.92482513 0.24245404 0.29311204, + -0.90830302 0.26662299 0.32233199, + -0.9064061 0.25969803 0.33314404, + -0.88771057 0.28305686 0.36310983, + -0.88526213 0.27467003 0.37532306, + -0.8641901 0.29715404 0.40604806, + -0.86107582 0.28706795 0.41969091, + -0.83782214 0.30822104 0.45061505, + -0.83391798 0.296168 0.46568799, + -0.80833483 0.31593591 0.49676889, + -0.80365616 0.30205205 0.51273912, + -0.77542502 0.32049999 0.54405499, + -0.7698878 0.30456793 0.56081289, + -0.73892003 0.32156503 0.59210908, + -0.732458 0.30336401 0.60948801, + -0.69918609 0.31857103 0.64004004, + -0.69173825 0.29783812 0.65786827, + -0.65625602 0.31119701 0.68737501, + -0.6479668 0.28816593 0.70505279, + -0.61013687 0.29975295 0.7334038, + -0.60107476 0.2743319 0.75063372, + -0.56094193 0.28416997 0.77755487, + -0.55126286 0.25641394 0.79395282, + -0.509776 0.26439801 0.81867099, + -0.49965519 0.23435009 0.83392131, + -0.45709616 0.24062508 0.85624927, + -0.44687912 0.20877005 0.86989319, + -0.40344799 0.213532 0.88973802, + -0.39332515 0.17984407 0.90163827, + -0.34925798 0.18329199 0.91892487, + -0.34148011 0.15499906 0.92702037, + -0.29753205 0.15744305 0.94164026, + -0.29206195 0.13501997 0.94682074, + -0.25019211 0.13668506 0.95849949, + -0.24405488 0.10703395 0.96383655, + -0.20190893 0.10809696 0.97342062, + -0.19637392 0.075569369 0.97761261, + -0.15415807 0.076148838 0.98510748, + -0.14968607 0.042460918 0.98782146, + -0.10785998 0.042694196 0.99324888, + -0.10459097 0.0082946178 0.99448079, + -0.063389808 0.0083235912 0.99795413, + -0.061392423 -0.026631609 0.99775833, + -0.020758292 -0.026676191 0.99942863, + -0.02007989 -0.062154371 0.99786454, + 0.019929091 -0.062154569 0.99786752, + 0.020606102 -0.026739104 0.99943012, + 0.061168529 -0.026694713 0.99777049, + 0.063165493 0.0082589993 0.99796885, + 0.104298 0.00823039 0.99451202, + 0.107565 0.042622998 0.99328399, + 0.14935802 0.042390805 0.98787409, + 0.15382907 0.07610184 0.9851625, + 0.19607505 0.075523518 0.97767621, + 0.20161897 0.10814998 0.97347486, + 0.24375889 0.10708695 0.96390551, + 0.24995209 0.13706805 0.95850736, + 0.29193297 0.13539499 0.94680691, + 0.29748106 0.15817204 0.94153422, + 0.34151888 0.15571094 0.92688662, + 0.34913683 0.18343891 0.91894156, + 0.39322594 0.17998698 0.90165287, + 0.40319508 0.21315004 0.88994426, + 0.44662395 0.20839997 0.8701129, + 0.45674995 0.23993698 0.85662687, + 0.49924219 0.23369908 0.8343513, + 0.50932205 0.26357704 0.8192181, + 0.55078876 0.25563589 0.79453266, + 0.56049103 0.28340501 0.77815902, + 0.60060108 0.27361304 0.75127512, + 0.60968709 0.29905105 0.73406416, + 0.64750695 0.28751197 0.70574194, + 0.65587419 0.31071305 0.68795818, + 0.69135302 0.297396 0.65847301, + 0.69886684 0.31827092 0.6405378, + 0.73214507 0.30309603 0.60999703, + 0.73867506 0.32145903 0.59247208, + 0.76967973 0.30446589 0.56115383, + 0.7752583 0.32049912 0.54429317, + 0.80350101 0.30205899 0.51297802, + 0.80822599 0.31606799 0.49686199, + 0.83382529 0.29629213 0.46577519, + 0.83773702 0.308366 0.450674, + 0.8610239 0.28718397 0.41971794, + 0.86415201 0.29732201 0.40600601, + 0.88523322 0.27482206 0.37528008, + 0.88769001 0.283243 0.363015, + 0.9063943 0.25986108 0.33304912, + 0.90829957 0.26682687 0.32217285, + 0.92482775 0.24262995 0.29295793, + 0.92626661 0.24828288 0.28352386, + 0.94087422 0.22317407 0.25485107, + 0.94191152 0.2275929 0.24698988, + 0.95471627 0.20161004 0.21879306, + 0.95608562 0.20820493 0.20627892, + 0.96617103 0.18321 0.18151499, + 0.96755278 0.19067496 0.16578496, + 0.97608012 0.16406801 0.14265102, + 0.97690874 0.16932096 0.13030598, + 0.98403102 0.14106099 0.108558, + 0.98449862 0.14458196 0.09929046, + 0.99030721 0.11449603 0.078628421, + 0.99054164 0.11664695 0.072254978, + 0.99497676 0.085102081 0.05271519, + 0.99507135 0.086203627 0.049010418, + 0.99813902 0.053010501 0.030138699, + 0.99817902 0.0537007 0.027475299, + 0.99978954 0.018261291 0.009343205, + 0.99978763 0.018182294 0.009700086, + 0.99975598 -0.019489201 -0.0103973, + 0.99974811 -0.019350503 -0.011371301, + 0.99728912 -0.063440308 -0.037280805, + 0.99723923 -0.063349113 -0.038742006, + 0.99194264 -0.10807896 -0.066097081, + 0.9921965 -0.10827595 -0.061825369, + 0.98396277 -0.15490097 -0.088448077, + 0.98562688 -0.15567899 -0.065602392, + 0.97558552 -0.2023849 -0.085283764, + 0.97735661 -0.20316693 -0.059136678, + 0.96549046 -0.25006112 -0.072786041, + 0.96727121 -0.25087106 -0.038082808, + 0.97766322 -0.20993204 -0.010158502, + 0.97555125 -0.21735604 -0.032498308, + 0.97605926 -0.21744704 -0.0050076316, + 0.97607523 -0.21737504 -0.0050313915, + 0.97556746 -0.2172841 -0.032493714, + 0.96410334 -0.2650601 0.015746906, + 0.96421552 -0.26510087 0.0031375587, + 0.96424079 -0.26500893 0.0031374793, + 0.96356523 -0.26485506 -0.037335306, + 0.96770513 -0.25175604 -0.012869602, + 0.96719378 -0.25151494 -0.035726294, + 0.97840363 -0.20464893 -0.02906929, + 0.97734737 -0.20416008 -0.055774018, + 0.98662263 -0.15725794 -0.042960986, + 0.98569322 -0.15681104 -0.061799314, + 0.99288213 -0.11080702 -0.043669004, + 0.99218953 -0.11040594 -0.058055375, + 0.99731022 -0.064874917 -0.034113608, + 0.99726087 -0.064811289 -0.035639696, + 0.99971378 -0.020965094 -0.011528697, + 0.99971837 -0.020992707 -0.011071804, + 0.99975687 0.019504698 0.010286999, + 0.99976325 0.019632505 0.0093899518, + 0.99808609 0.055788107 0.026682703, + 0.99809963 0.056006182 0.02570029, + 0.99496925 0.091051623 0.041782111, + 0.99487376 0.089847974 0.046405189, + 0.99035364 0.12311196 0.063585579, + 0.9901799 0.12139098 0.069339991, + 0.984303 0.153248 0.087536901, + 0.9839431 0.15026401 0.096316218, + 0.97679049 0.18033209 0.11558905, + 0.9761411 0.17577401 0.12748401, + 0.96764022 0.20426604 0.14814803, + 0.96655726 0.19776905 0.16326204, + 0.95658267 0.22476892 0.18554895, + 0.95549387 0.21892197 0.19774897, + 0.95606762 0.20831692 0.20624892, + 0.94248247 0.23753011 0.23517312, + 0.94156611 0.23342302 0.24283104, + 0.92711389 0.25972298 0.27019197, + 0.92583686 0.25443298 0.27944598, + 0.90950227 0.27986506 0.30737805, + 0.90778202 0.27323201 0.318239, + 0.88929731 0.29791212 0.34698513, + 0.88707542 0.28988314 0.35925618, + 0.86626011 0.31372604 0.38880506, + 0.86343968 0.30410188 0.40248486, + 0.84045488 0.32666498 0.43234894, + 0.8369261 0.31520602 0.44743705, + 0.81164187 0.33642197 0.47755393, + 0.80731171 0.32293487 0.49392381, + 0.77938616 0.34286508 0.52440512, + 0.7742359 0.32734796 0.54166591, + 0.74355495 0.34585398 0.57228595, + 0.73754936 0.32818216 0.59018427, + 0.70454305 0.34488404 0.62022108, + 0.69763696 0.32483798 0.63857895, + 0.66236681 0.33967692 0.66774982, + 0.65454602 0.317063 0.686324, + 0.6168291 0.33009508 0.71453416, + 0.60826176 0.30513689 0.73274076, + 0.5681631 0.3163541 0.75967818, + 0.55899566 0.28910384 0.77713752, + 0.5173918 0.29837087 0.80204773, + 0.50777888 0.26883593 0.81846684, + 0.46500888 0.27626893 0.84109581, + 0.45520386 0.24467792 0.85610873, + 0.4112958 0.25047988 0.8764106, + 0.40167114 0.21741207 0.8896023, + 0.35692781 0.2217689 0.90742558, + 0.34766307 0.18715404 0.91875124, + 0.30302989 0.19021992 0.93380362, + 0.29606205 0.16114604 0.94147724, + 0.25170487 0.16327693 0.95393151, + 0.24679892 0.13957396 0.95896262, + 0.20414211 0.14099507 0.9687345, + 0.19891797 0.11013599 0.97380787, + 0.15603794 0.11100596 0.98149365, + 0.15163207 0.077610336 0.98538548, + 0.109218 0.078048497 0.99094898, + 0.10596997 0.043653283 0.99341065, + 0.064138092 0.043809995 0.99697888, + 0.062154409 0.0088778809 0.99802715, + 0.020895302 0.0088931508 0.99974209, + 0.020221999 -0.026514696 0.99944389, + -0.02048159 -0.026514586 0.99943852, + -0.021155009 0.0089147845 0.99973649, + -0.062449064 0.0088993646 0.99800843, + -0.064435475 0.043858286 0.99695766, + -0.10630202 0.043700602 0.9933731, + -0.10955097 0.078066982 0.99091077, + -0.15200607 0.077627137 0.98532647, + -0.15641208 0.11095905 0.98143947, + -0.19920105 0.11009003 0.97375524, + -0.2043909 0.14066093 0.96873051, + -0.24697202 0.13924402 0.95896614, + -0.25182688 0.16265492 0.95400554, + -0.29605302 0.16053702 0.94158411, + -0.30314213 0.19009708 0.93379235, + -0.34777281 0.18703191 0.91873461, + -0.35716009 0.22212406 0.90724725, + -0.401939 0.21775299 0.88939798, + -0.41164485 0.2511369 0.8760587, + -0.45556805 0.24531002 0.85573411, + -0.46540007 0.27703604 0.84062713, + -0.50826281 0.26955491 0.81792969, + -0.51785088 0.29906493 0.80149281, + -0.5594762 0.2897571 0.77654833, + -0.56861889 0.31698492 0.75907379, + -0.60873967 0.30571985 0.73210067, + -0.61724311 0.33053908 0.7139712, + -0.65494221 0.31747511 0.68575525, + -0.6627028 0.33995491 0.66727483, + -0.69796693 0.32508597 0.63809192, + -0.704813 0.34498501 0.61985803, + -0.73779982 0.32826892 0.58982289, + -0.74375975 0.34582388 0.57203782, + -0.77440912 0.32732204 0.54143405, + -0.77952516 0.3427451 0.52427709, + -0.80742121 0.3228291 0.49381411, + -0.81173921 0.3362821 0.47748712, + -0.83701319 0.31507108 0.44736913, + -0.84052229 0.32646611 0.43236816, + -0.86347997 0.30393299 0.40252599, + -0.86629111 0.31351802 0.38890406, + -0.88710022 0.28969207 0.3593491, + -0.88932079 0.29770693 0.34710091, + -0.90778512 0.27306703 0.31837204, + -0.90950722 0.27969605 0.30751705, + -0.92583615 0.25428703 0.27958104, + -0.927109 0.25954801 0.27037701, + -0.94156098 0.23326799 0.243, + -0.94324613 0.24107203 0.22841004, + -0.95484042 0.21568286 0.20435388, + -0.95657748 0.2246201 0.18575609, + -0.96654689 0.19765697 0.16345899, + -0.96762633 0.20410408 0.14846206, + -0.97612727 0.17564805 0.12776303, + -0.97677636 0.18017606 0.11595105, + -0.98393053 0.15014693 0.096625656, + -0.98430198 0.153209 0.087616302, + -0.99017811 0.12136701 0.069406904, + -0.99034786 0.12304098 0.063812494, + -0.99487001 0.089802898 0.0465746, + -0.99495709 0.090878606 0.042443603, + -0.9980939 0.055914994 0.026114296, + -0.99808621 0.055792715 0.026665505, + -0.99976325 0.019633505 0.0093836216, + -0.99975711 0.019508902 0.010258501, + -0.99971867 -0.020994792 -0.011039896, + -0.99971545 -0.020975409 -0.011363205, + -0.99727774 -0.064834088 -0.035123192, + -0.9973619 -0.064946294 -0.032421496, + -0.99234426 -0.11049903 -0.055161614, + -0.99286264 -0.11080496 -0.044113185, + -0.98565251 -0.15681693 -0.062431071, + -0.98641151 -0.15716892 -0.047856178, + -0.97699124 -0.20403105 -0.062125314, + -0.97809035 -0.20449208 -0.039016213, + -0.96671778 -0.25131193 -0.047949091, + -0.96767288 -0.25184298 0.013575498, + -0.96297574 -0.26955894 -0.003974149, + -0.96295202 -0.26964399 -0.0039420901, + -0.96242189 -0.26951897 -0.033219896, + -0.96244586 -0.26943398 -0.033216696, + -0.94778323 -0.3162331 0.041275911, + -0.94857836 -0.31653011 0.0028260709, + -0.94856298 -0.316576 0.0028261, + -0.94790775 -0.31638992 -0.036989693, + -0.94793791 -0.31629997 -0.036985897, + -0.94859254 -0.31648687 0.0028470387, + -0.93561465 -0.35272589 -0.014479394, + -0.96691376 -0.25464895 -0.015222397, + -0.97501922 -0.22211306 0.0018295805, + -0.97457975 -0.22203794 -0.029888693, + -0.97458464 -0.22201693 -0.029887989, + -0.97502398 -0.222092 0.00183605, + -0.97505498 -0.221956 0.0018359401, + -0.9744581 -0.22179303 0.035203505, + -0.98438615 -0.17393002 -0.027062204, + -0.98438185 -0.17395398 -0.027062995, + -0.98474377 -0.17399795 -0.0020736395, + -0.98474813 -0.17397402 -0.0020804603, + -0.99209887 -0.12545699 0.00060948596, + -0.98796326 -0.15389203 -0.015682304, + -0.92887723 0.3148891 0.19501804, + -0.94179225 0.28582007 0.17701505, + -0.92923909 0.29529303 0.22207403, + -0.94204634 0.26812309 0.20164007, + -0.94363737 0.27730808 0.18069007, + -0.95514375 0.24811894 0.16167095, + -0.95615399 0.254958 0.144104, + -0.96620053 0.2244249 0.12684594, + -0.96682048 0.22938611 0.11242905, + -0.97551203 0.19749901 0.096801199, + -0.97584742 0.20064788 0.086383551, + -0.98326766 0.16731894 0.072035074, + -0.98346937 0.16953306 0.063613325, + -0.98964077 0.13441497 0.050436489, + -0.98961645 0.13415806 0.051585425, + -0.99412888 0.10099398 0.038833298, + -0.99402714 0.10043202 0.042703804, + -0.99757397 0.064063497 0.0272399, + -0.99754936 0.063999921 0.02827131, + -0.99972475 0.021462295 0.0094806878, + -0.99972826 0.021478806 0.0090614818, + -0.99971938 -0.021827007 -0.0092083933, + -0.99973911 -0.021887202 -0.0065431311, + -0.99754411 -0.067106307 -0.020061202, + -0.99355751 -0.11289494 0.0099079954, + -0.99345338 -0.11275204 -0.018372007, + -0.997679 -0.067206703 -0.0109509, + -0.99322289 0.10950799 0.038940795, + -0.99752098 0.066302903 0.0235771, + -0.99763787 0.066449195 0.017413298, + -0.99973834 0.022130707 0.0057994518, + -0.99974924 0.022156706 0.0032410107, + -0.99974799 -0.022212399 -0.00324915, + -0.99972266 -0.022262793 0.0076834871, + -0.99957687 -0.029031597 -0.0018089098, + -0.99957889 -0.028965397 -0.0017733597, + -0.99950689 -0.028971497 -0.012107398, + -0.99950498 -0.0290378 -0.0121091, + -0.99768686 -0.06746839 0.0083065089, + -0.99767309 -0.067380905 -0.010410001, + -0.99974865 -0.022154992 -0.0034228389, + -0.99973601 -0.022126799 -0.0061978898, + -0.99974149 0.021896111 0.0061332528, + -0.99972552 0.021843189 0.008467366, + -0.99754912 0.065239407 0.025289604, + -0.99753213 0.065209106 0.026026905, + -0.99329615 0.10736202 0.042851202, + -0.99335903 0.107476 0.041070301, + -0.98833936 0.14223604 0.05435342, + -0.98849851 0.14298493 0.049254376, + -0.98267853 0.1752139 0.06035617, + -0.98270649 0.17552109 0.05899493, + -0.97506148 0.21037011 0.070708536, + -0.97482622 0.20751205 0.081564523, + -0.96591961 0.2409009 0.094688766, + -0.96552509 0.23690502 0.10787702, + -0.95530152 0.26905188 0.12251594, + -0.95458603 0.26303801 0.139916, + -0.94295764 0.29391888 0.15634094, + 0.88451731 0.44679216 0.13418604, + 0.86117911 0.48682007 0.14620802, + 0.86083084 0.49543387 0.11625697, + 0.83271116 0.53906512 0.12649503, + 0.83167112 0.54714304 0.094645016, + 0.80057317 0.59046614 0.10213903, + 0.79817384 0.59939289 0.060387883, + 0.76082528 0.64568824 0.065052122, + 0.7598092 0.6482662 0.049407013, + 0.712264 0.69988197 0.053340901, + 0.71202195 0.70061696 0.046483897, + 0.660541 0.749143 0.049703501, + 0.66053385 0.74902183 0.05158719, + 0.69138503 0.72077906 0.049642008, + 0.69158608 0.72121704 0.039429802, + 0.72601604 0.68759006 0.010986101, + 0.72568065 0.6870057 0.037559383, + 0.79290164 0.60923368 0.011886694, + 0.7923528 0.6084919 0.043756589, + 0.82305986 0.56755793 0.021222997, + 0.82248217 0.56691015 0.046217613, + 0.79449087 0.60526794 0.049344692, + 0.79399151 0.60456163 0.063895665, + 0.76853585 0.63626295 0.067246296, + 0.76871914 0.63701808 0.057261508, + 0.73471779 0.67564875 0.060734078, + 0.73469383 0.67552984 0.062324684, + 0.76208764 0.64473569 0.059483469, + 0.76247281 0.64535379 0.04640729, + 0.76055038 0.6490413 0.017568408, + 0.760149 0.64846498 0.040824801, + 0.72815806 0.68405503 0.043065403, + 0.72787267 0.68352669 0.054706175, + 0.69853097 0.71329898 0.057089001, + 0.69854796 0.71342397 0.055291593, + 0.74778593 0.66195494 0.051302593, + 0.74799681 0.66111779 0.058515284, + 0.79238665 0.60764372 0.053782273, + 0.7932831 0.60487807 0.069459207, + 0.82764328 0.55759019 0.06402912, + 0.82957917 0.54862612 0.10396102, + 0.85808885 0.50452286 0.095604375, + 0.85880011 0.49665606 0.12567902, + 0.88437539 0.45251322 0.11450806, + 0.98660213 0.16084902 0.027272904, + 0.99347347 0.11245905 0.019068209, + 0.99355966 0.11252796 0.013293396, + 0.99229246 0.12391806 -0.00040594421, + 0.992284 0.123985 -0.00040185999, + 0.99228233 0.12398405 -0.0019659507, + 0.99229074 0.12391597 -0.0019807196, + 0.94906479 0.3150399 0.0050788084, + 0.9490605 0.31505314 0.0050793625, + 0.94905686 0.31504297 -0.0062483293, + 0.9490611 0.31503004 -0.006253541, + 0.96340376 0.26804495 0.0022653195, + 0.95252663 0.30407888 -0.015133695, + 0.93249136 0.36118111 0.0028368009, + 0.91352522 0.4064281 -0.016966803, + 0.91362971 0.40649286 0.0066514076, + 0.91363287 0.40648594 0.0066511389, + 0.91362214 0.40646905 -0.008814781, + 0.91625661 0.40042081 -0.011709195, + 0.89259225 0.45085412 0.0031309007, + 0.86936301 0.49398199 -0.0137742, + 0.86941344 0.49402824 0.0075076139, + 0.86938339 0.49408123 0.0075091738, + 0.86935514 0.49405107 -0.011626901, + 0.87022328 0.49250019 -0.012447305, + 0.81673568 0.57682383 -0.014732894, + 0.81496501 0.57935798 -0.0132845, + 0.72370404 0.69010603 0.0024564003, + 0.68866992 0.72505093 -0.0059228889, + 0.68863696 0.72502893 0.010591199, + 0.61418927 0.78914928 -0.0038768414, + 0.61417806 0.78914213 0.0063258708, + 0.61432207 0.78903013 0.0063246707, + 0.61433327 0.78903735 -0.003847532, + 0.5749197 0.81820959 0.00049695378, + 0.57491511 0.81820518 0.0036071609, + 0.56529164 0.8247385 0.01586549, + 0.57496887 0.81797981 0.017886296, + 0.57506704 0.81810611 0.00049703603, + 0.53408706 0.8454271 -0.0020583803, + 0.53398895 0.84548891 -0.0020767497, + 0.53394514 0.84542918 0.012329803, + 0.534042 0.84536803 0.0123288, + 0.5199458 0.85392773 0.021535693, + 0.49200812 0.87059015 -0.00087851525, + 0.49190694 0.87042987 0.019474398, + 0.49186876 0.87045157 0.019474991, + 0.49196911 0.8706122 -0.00085804425, + 0.51472813 0.85719317 -0.016575504, + 0.60013908 0.79973012 -0.016277602, + 0.57485801 0.81825298 0.00053123001, + 0.57485408 0.81824809 0.0036075304, + 0.61097503 0.791565 0.01159, + 0.61087185 0.79128182 0.026623594, + 0.5721119 0.8197118 0.027580192, + 0.57206589 0.8195048 0.033949394, + 0.53619307 0.84337211 0.034938104, + 0.53617716 0.84345531 0.033124711, + 0.59316313 0.80446219 0.031593308, + 0.59343004 0.8040241 0.037229605, + 0.64780706 0.76098913 0.035236802, + 0.64779001 0.76101297 0.0350332, + 0.60672998 0.79406703 0.036554798, + 0.60620987 0.79471982 0.030495392, + 0.54983687 0.83465785 0.032027893, + 0.54958296 0.83500791 0.026840895, + 0.49188411 0.87021118 0.027972508, + 0.49176505 0.87050915 0.019519001, + 0.4471758 0.89430958 0.015626693, + 0.44723594 0.89441586 -0.00055082195, + 0.44865173 0.89370644 -0.00055024266, + 0.44859079 0.89359856 0.015743092, + 0.44865274 0.89356744 0.01574249, + 0.44871289 0.89367574 -0.00054025691, + 0.42386121 0.90557539 -0.016583208, + 0.32851985 0.94440353 -0.013286693, + -0.65347308 0.75685912 0.011715601, + -0.65348923 0.7568453 0.011715304, + -0.65353495 0.75688487 -0.0041511897, + -0.6535188 0.75689882 -0.0041544889, + -0.75742972 0.65291178 0.0025300591, + -0.7574451 0.65289408 0.0025300703, + -0.75726479 0.65275484 0.021475095, + -0.93953824 0.31843108 0.12597503, + -0.99729335 0.073508032 -0.0016444806, + -0.99728888 0.073567092 -0.0016353398, + -0.99723464 0.073555872 -0.010614696, + -0.99723899 0.0734969 -0.0106158, + -0.9996745 0.024539988 -0.0069709267, + -0.99967891 0.024362896 -0.0069746091, + -0.99770051 0.067399867 0.0071324366, + -0.99768788 0.067391194 0.0087955091, + -0.99354249 0.11250705 0.014683708, + -0.99333662 0.11237296 0.025586192, + -0.98702335 0.15657006 0.03564921, + -0.98653841 0.15620591 0.048389971, + -0.97862524 0.19644204 0.060854416, + -0.97864562 0.19647193 0.060428377, + -0.97103864 0.22836493 0.070237778, + -0.97127253 0.2294229 0.063203871, + -0.96310562 0.25945792 0.071478479, + -0.96312553 0.25981489 0.069895171, + -0.95228177 0.29474095 0.07929118, + -0.9520995 0.29049385 0.095497854, + -0.93993211 0.32428804 0.10660701, + -0.82316881 0.56757289 0.015940497, + -0.7928651 0.60897207 0.022758102, + -0.79224432 0.60823125 0.049027417, + -0.76250386 0.64489192 0.051982492, + -0.76240748 0.64473635 0.055225935, + -0.73480296 0.67580593 0.057887092, + -0.73476994 0.67562497 0.060367193, + -0.76873887 0.63702494 0.056918193, + -0.76864219 0.63659418 0.062746413, + -0.79429215 0.60460609 0.059593514, + -0.7944563 0.60483724 0.054873418, + -0.82235116 0.56665313 0.05140911, + -0.87022746 0.49263969 0.0032166583, + -0.84847319 0.52887112 0.019715006, + -0.84494358 0.53472376 0.011863294, + -0.84495711 0.53471404 -0.011337001, + -0.87018818 0.49270913 0.0032042607, + -0.87014771 0.49267483 -0.010702396, + -0.87018669 0.49260584 -0.010702697, + -0.87014914 0.49267107 -0.010762201, + -0.87019056 0.49270475 0.0032166084, + -0.89327526 0.44936311 -0.011497503, + -0.93493789 0.34694096 0.074317396, + -0.93493986 0.34660298 0.075853296, + -0.94560766 0.31778789 0.069547474, + -0.94538224 0.31652609 0.077869512, + -0.95541036 0.28673208 0.070539825, + -0.9553051 0.28657904 0.072558209, + -0.96674126 0.24793306 0.062773615, + -0.96743286 0.24843197 0.048531294, + -0.97805774 0.20446895 0.039943088, + -0.97853339 0.20473307 0.02359801, + -0.98715687 0.15870298 0.018292397, + -0.99240822 0.12232903 -0.012715803, + -0.99240965 0.12231696 -0.012715995, + -0.98719037 0.15871707 0.016252706, + -0.98519379 0.17088695 -0.013816096, + -0.98520052 0.17084792 -0.013816593, + -0.98528689 0.17087099 -0.0035920094, + -0.98528022 0.17091005 -0.003581201, + -0.93297291 0.35968497 -0.013723898, + -0.86628383 0.49387789 0.075079381, + -0.8662824 0.49381423 0.07551384, + -0.88120401 0.46730399 0.0714598, + -0.88101089 0.46691296 0.07623639, + -0.89949685 0.43121696 0.070408195, + -0.90004009 0.43172505 0.059510309, + -0.91944087 0.38954493 0.053695992, + -0.92016912 0.39005405 0.033864602, + -0.93829012 0.34455302 0.029914305, + -0.93849689 0.34467396 0.020577699, + -0.94947588 0.31353596 -0.013810799, + -0.94948936 0.31349513 -0.013811205, + -0.94957262 0.31353489 0.002761069, + -0.94955909 0.31357604 0.0027514102, + -0.93291837 0.35966113 -0.017527405, + -0.93565822 0.35272208 -0.011439803, + -0.9330551 0.35963702 -0.0083401408, + -0.93300098 0.35961199 -0.0137246, + -0.92015886 0.39101794 0.020311799, + -0.91991466 0.39086285 0.031354688, + -0.89949888 0.43552393 0.034937296, + -0.89879102 0.434986 0.054423898, + -0.87730789 0.47621495 0.059582394, + -0.87686533 0.47576219 0.068974525, + -0.85647798 0.51084298 0.074060403, + -0.85666031 0.51126719 0.068840124, + -0.8402307 0.5373798 0.072356075, + -0.84022886 0.53744692 0.071876891, + -0.87499416 0.47986111 0.064175613, + -0.87527698 0.47810799 0.072822101, + -0.89746475 0.43605691 0.066417187, + -0.8974613 0.43608314 0.066293523, + -0.96759665 0.25169292 0.020185793, + -0.967489 0.25164101 0.0253345, + -0.9542765 0.29742184 0.029943686, + -0.95360762 0.29702088 0.04910228, + -0.93856591 0.34047896 0.056286592, + -0.93787414 0.33992904 0.069573708, + -0.922773 0.377518 0.077266999, + -0.92294723 0.3778041 0.073705211, + -0.91055822 0.4057321 0.079153821, + -0.91069669 0.40708485 0.070095778, + -0.88969499 0.44993401 0.077473901, + -0.88969111 0.44988006 0.077832006, + -0.90323001 0.42287499 0.073159799, + -0.90303957 0.42252979 0.077383362, + -0.91983289 0.38589194 0.070673496, + -0.92046237 0.38643315 0.058468822, + -0.93777001 0.34334901 0.051950201, + -0.93848687 0.34381098 0.032194395, + -0.95413023 0.29808807 0.027913107, + -0.95445812 0.29829603 0.0054090503, + -0.94889712 0.31333503 0.037621904, + -0.94957399 0.31353101 0.0027610699, + -0.96380377 0.26654893 -0.0058219787, + -0.96373177 0.26652294 -0.013663197, + -0.96373361 0.26651591 -0.013663296, + -0.9638055 0.26654312 -0.0058244229, + -0.96691978 0.25462595 -0.015220596, + -0.97570914 0.21906003 0.0020901302, + -0.97562265 0.21902692 -0.013697595, + -0.97564536 0.21892607 -0.013698905, + -0.97573179 0.21895894 0.0021207395, + -0.97572386 0.21899398 0.0021207097, + -0.97523713 0.21890803 0.031493604, + -0.978652 0.205318 0.0092105102, + -0.97846574 0.20521896 0.022135094, + -0.96759135 0.25106508 0.027080009, + -0.96700412 0.25073004 0.045140304, + -0.95420951 0.29440615 0.053003527, + -0.95349425 0.29386905 0.067006618, + -0.94023538 0.33200413 0.075702131, + -0.9403801 0.33222604 0.07287731, + -0.9291051 0.36122704 0.079239011, + -0.92929542 0.36255017 0.070479237, + -0.91746336 0.39051014 0.075914532, + -0.91750813 0.38889506 0.083304606, + -0.92052025 0.38378409 0.073160313, + -0.90123326 0.4256691 0.08114472, + -0.90142858 0.4254868 0.079921365, + -0.87786824 0.47067112 0.088408619, + -0.87705344 0.47614571 0.063737065, + -0.85022599 0.52176398 0.069843799, + -0.84986442 0.52342325 0.061308231, + -0.8118701 0.57987404 0.067920208, + -0.811876 0.57980299 0.068453804, + -0.8295511 0.55457908 0.065475807, + -0.82939088 0.55413693 0.071013391, + -0.85174215 0.51971108 0.066601709, + -0.85208315 0.52009708 0.058765307, + -0.87581015 0.47960407 0.054190107, + -0.87646788 0.48015293 0.035457596, + -0.89918178 0.43638691 0.032225594, + -0.8994481 0.43657407 0.019908102, + -0.91421741 0.40502816 -0.012602706, + -0.91422856 0.40500283 -0.012602895, + -0.9142133 0.40503615 -0.012636905, + -0.91427726 0.4050771 0.0031337508, + -0.91429186 0.40504393 0.0031337696, + -0.91428077 0.4050689 0.0031288592, + -0.89324403 0.44934499 -0.0142902, + -0.89442527 0.44704914 -0.012268905, + -0.89332944 0.4492642 -0.011150805, + -0.8933261 0.44926205 -0.011498, + -0.87636322 0.48128211 0.018847505, + -0.87608159 0.48106277 0.032554187, + -0.85092598 0.52408701 0.035465799, + -0.85033798 0.52354598 0.0531509, + -0.82433802 0.56320298 0.057176899, + -0.82409167 0.56289279 0.063439779, + -0.80009389 0.59610093 0.067182496, + -0.8002249 0.59654397 0.061443493, + -0.78121632 0.62097526 0.063960023, + -0.7812053 0.62104625 0.063403822, + -0.82232744 0.56607229 0.057791427, + -0.82276118 0.56451911 0.066197813, + -0.8521502 0.51973611 0.060946416, + -0.85323811 0.51435304 0.086173207, + -0.8796351 0.46911106 0.078593507, + -0.8803221 0.46213207 0.10708401, + -0.90175575 0.4210889 0.097573876, + -0.90523589 0.40956995 0.11313899, + -0.92079157 0.37597382 0.10385895, + -0.92374474 0.3667379 0.11044897, + -0.9375211 0.33314803 0.10033301, + -0.937594 0.33811301 0.081222698, + -0.95017678 0.30308893 0.072809182, + -0.95016664 0.30273187 0.074409373, + -0.95956564 0.2733489 0.067187279, + -0.95932525 0.27217507 0.074938312, + -0.96812576 0.24147893 0.066486686, + -0.96806449 0.24139112 0.067687526, + -0.97772664 0.20208792 0.05666668, + -0.97834152 0.20252791 0.04278088, + -0.98685449 0.15812208 0.033400916, + -0.98719674 0.15831695 0.019448197, + -0.99352276 0.11278497 0.013854897, + -0.99357253 0.11281095 0.0093449457, + -0.99232852 0.12227094 0.018274391, + -0.99249536 0.12227704 0.0011925604, + -0.99248636 0.12235004 0.0011925105, + -0.99248791 0.12233698 0.0011975499, + -0.98796654 0.15386693 -0.015718192, + -0.84370971 0.53663981 -0.013100895, + -0.84497881 0.53461087 -0.014217597, + -0.84499484 0.53464288 0.011860698, + -0.81741917 0.57538712 0.027489807, + -0.81773371 0.57558882 0.0030265888, + -0.81778157 0.57552069 0.0030266386, + -0.81771618 0.57548213 0.012669703, + -0.81762558 0.5756107 0.012673395, + -0.81769085 0.57564986 0.0030031693, + -0.78853279 0.61493188 -0.0086488277, + -0.78848213 0.61491108 0.013429902, + -0.78851497 0.614869 0.0134288, + -0.78847682 0.61481386 -0.017558597, + -0.78404152 0.62054664 -0.014168192, + -0.71607322 0.69785225 -0.015533705, + -0.64052492 0.76776689 -0.016176699, + -0.61542386 0.78819585 0.00084865384, + -0.61110574 0.79140371 0.015163395, + -0.61095387 0.79104179 0.031438693, + -0.5724529 0.81929082 0.032561392, + -0.57246989 0.81936282 0.030376792, + -0.5293352 0.8478303 0.031432111, + -0.52935201 0.84792799 0.028364301, + -0.56952703 0.82151312 0.027480803, + -0.56961787 0.82176483 0.015430696, + -0.57620615 0.81730115 -0.0023208605, + -0.57619613 0.81730819 -0.0023228906, + -0.57618201 0.81729603 0.0064413399, + -0.57619202 0.81728899 0.00644125, + -0.61549199 0.787956 0.0171763, + -0.61558902 0.78806698 0.00074033602, + -0.61561096 0.78804988 0.00074034987, + -0.61558187 0.78801984 0.0091559282, + -0.61539596 0.78816485 0.0091581689, + -0.65091777 0.75897872 0.016038995, + -0.65068978 0.75851971 0.035364188, + -0.61385399 0.78856301 0.036764901, + -0.61386901 0.78861499 0.035373401, + -0.57950395 0.81415087 0.036518797, + -0.5795151 0.81406617 0.038192008, + -0.63472009 0.77189314 0.036213502, + -0.63500321 0.7713353 0.042576917, + -0.68718618 0.7253772 0.040040113, + -0.68776375 0.72439277 0.04728708, + -0.72758335 0.68456233 0.044687022, + -0.72958523 0.68022925 0.070665821, + -0.76681787 0.63842893 0.066323295, + -0.76897019 0.63116819 0.10154602, + -0.80293489 0.58849895 0.094681785, + -0.80426139 0.58041531 0.12760006, + -0.83498818 0.5374341 0.11815003, + -0.83559531 0.52860719 0.14951606, + -0.83810383 0.52042788 0.16351396, + -0.83786571 0.52753383 0.14031796, + -0.80751586 0.57002592 0.15161999, + -0.8066079 0.57906795 0.11859199, + -0.7730338 0.62146586 0.12727498, + -0.77136582 0.6296038 0.092702478, + -0.73450398 0.67136598 0.098851599, + -0.7320022 0.67845321 0.062242515, + -0.69245702 0.71844202 0.065911204, + -0.69031405 0.72240406 0.039985705, + -0.64836079 0.76016968 0.042075984, + -0.64778924 0.76100427 0.035238013, + -0.59340996 0.80403888 0.037230697, + -0.59313011 0.80449718 0.031320609, + -0.53624594 0.84342289 0.032836094, + -0.53615987 0.84373283 0.025446594, + -0.48530406 0.8739481 0.026357904, + -0.48530975 0.87400657 0.024227088, + -0.52643687 0.84988785 0.023558494, + -0.52648592 0.85005391 0.014863398, + -0.49337205 0.86981809 -0.00076561613, + -0.49335995 0.86982489 -0.00076777587, + -0.49335799 0.86982399 0.0020409999, + -0.49337006 0.86981714 0.0020409303, + -0.53681493 0.84348488 0.019052098, + -0.53691882 0.84363371 -0.00057203177, + -0.53542292 0.84458387 -0.00057280192, + -0.53541815 0.84457833 0.0038571814, + -0.53538024 0.84460241 0.0038574419, + -0.53538501 0.84460801 -0.00055231299, + -0.55817014 0.82956219 -0.016514704, + -0.46990982 0.8825587 -0.016577994, + -0.45016605 0.89294213 -0.0022305301, + -0.45010021 0.89297539 -0.0021953608, + -0.45010006 0.89297813 0.00042034805, + -0.45016715 0.89294428 0.00042009415, + -0.48253807 0.87575811 0.014308902, + -0.48251581 0.87566268 0.019834792, + -0.44049093 0.89752686 0.020330098, + -0.4404912 0.89749742 0.021587912, + -0.49183875 0.87043458 0.02093699, + -0.49193224 0.87019241 0.027712412, + -0.54957205 0.83502311 0.026592404, + -0.54983813 0.83465719 0.032020807, + -0.60620886 0.79472083 0.030488692, + -0.60675913 0.79402816 0.036914408, + -0.650967 0.75828701 0.035252798, + -0.6532017 0.75471961 0.061039869, + -0.69495499 0.71671301 0.057966001, + -0.69776499 0.70989001 0.095813297, + -0.7370078 0.66981083 0.09040378, + -0.73900878 0.66169477 0.12659396, + -0.77549183 0.62011087 0.11863797, + -0.77670503 0.61094701 0.153209, + -0.8099277 0.56891382 0.14266795, + -0.81039488 0.55894494 0.17561498, + 0.35266092 0.93569076 0.010627598, + 0.74935794 0.63907892 0.17332299, + 0.71098596 0.67868894 0.18406598, + 0.70968801 0.68910098 0.14657, + 0.66866094 0.72729796 0.15469399, + 0.41203278 0.91099161 0.01797829, + 0.47077799 0.88208002 0.0174077, + 0.47116882 0.88176471 0.022159992, + 0.52026397 0.85373586 0.021455599, + 0.52239275 0.85149461 0.045416079, + 0.57032216 0.82025528 0.043749914, + 0.57369912 0.81471616 0.084302925, + 0.6200161 0.78042215 0.080754325, + 0.62284297 0.77288187 0.12132698, + 0.66658002 0.73641503 0.115603, + 0.66388518 0.73765719 0.12295703, + 0.70514524 0.69941324 0.11658204, + 0.7069788 0.69017982 0.15437897, + 0.74560606 0.65031707 0.14546202, + 0.74664384 0.63996279 0.18157795, + 0.7824977 0.59900874 0.16995794, + 0.78279752 0.59037262 0.19669288, + 0.749874 0.627662 0.209116, + -0.279466 0.96006298 -0.0133356, + -0.31420401 0.94934797 -0.0037928501, + -0.31429797 0.94931686 -0.0037929595, + -0.30034807 0.95378923 0.0087814517, + -0.30130306 0.95347524 0.010070203, + -0.30130205 0.95347923 0.0097162714, + -0.35326281 0.93547559 0.0095327953, + -0.35333911 0.93538433 0.014410205, + -0.4118498 0.9111436 0.014036694, + -0.41203406 0.91099113 0.017975302, + -0.47077683 0.88208067 0.017404795, + -0.47118416 0.8817513 0.022365008, + -0.52030689 0.85370481 0.021653594, + -0.52251983 0.85135072 0.046636984, + -0.57046515 0.8200922 0.044924609, + -0.57384795 0.81445289 0.085820094, + -0.62024468 0.78008962 0.082199059, + -0.62302071 0.77256763 0.12241094, + -0.66680402 0.73605102 0.116625, + -0.66883975 0.72700179 0.15531194, + -0.70985699 0.68880302 0.14715099, + -0.7111302 0.67840821 0.18454304, + -0.74948901 0.63880402 0.173769, + -0.74998784 0.6273728 0.20957495, + -0.78289717 0.59009713 0.19712305, + -0.78261113 0.59873503 0.17040001, + -0.74676019 0.63969117 0.18205604, + -0.74574506 0.65002704 0.14604501, + -0.70712209 0.68989307 0.15500301, + -0.70533264 0.69905162 0.11761194, + -0.66406727 0.73731035 0.12404906, + -0.66149974 0.74510676 0.085052967, + -0.61755276 0.78145468 0.089202069, + -0.61428708 0.78755009 0.049156606, + -0.56786799 0.82152098 0.051276799, + -0.56560093 0.82426888 0.026006795, + -0.51769298 0.85514098 0.026980899, + -0.5172292 0.85557628 0.021521507, + -0.45909512 0.88810623 0.022339806, + -0.45887813 0.88831925 0.017883005, + -0.40050992 0.91610676 0.018442396, + -0.40042293 0.9162389 0.012950098, + -0.34809488 0.93736565 0.013248695, + -0.34808403 0.93741113 0.0099005606, + -0.40585691 0.91393578 -0.0012206997, + -0.40576115 0.91397828 -0.0012204505, + -0.36041892 0.93278176 -0.0040341089, + -0.36047411 0.93276036 -0.0040638014, + -0.36047488 0.93276465 -0.0028261691, + -0.36041996 0.93278587 -0.0028260797, + -0.39221907 0.91979313 0.012033902, + -0.39221781 0.91978157 0.012924094, + -0.34575212 0.93823338 0.013183405, + -0.34575409 0.93826222 0.010868003, + -0.314325 0.94930798 -0.0037688101, + -0.31432596 0.94931388 0.0014956797, + -0.31420499 0.94935399 0.00149565, + -0.31429896 0.94932288 0.0015041898, + -0.26728609 0.96337038 -0.021811908, + -0.26734406 0.96360022 0.0013840804, + -0.26733798 0.96360189 0.0013840899, + -0.26733398 0.96358389 -0.006216439, + -0.17926492 0.98370552 -0.013693693, + -0.074272208 0.99723715 -0.0013531301, + -0.074264795 0.99712688 -0.014922398, + -0.077161416 0.99692625 -0.013572503, + -0.074302405 0.9971711 -0.011362001, + -0.074306563 0.99723452 -0.0013531293, + 0.12324799 0.9923749 0.0014159299, + 0.174687 0.98462301 0.0014048601, + 0.1755219 0.98421341 0.022713287, + 0.22815397 0.9733659 0.022462899, + 0.23018298 0.9709239 0.065745592, + 0.28347915 0.95678747 0.064788327, + 0.28570291 0.95199966 0.10986596, + 0.33935091 0.93445778 0.10784098, + 0.34149608 0.92746222 0.15229703, + 0.39522991 0.90644276 0.14884497, + 0.39714983 0.89724159 0.19294991, + 0.45053595 0.87280488 0.18769397, + 0.45205799 0.86154401 0.23105299, + 0.5039019 0.83427984 0.22374094, + 0.50487924 0.8210634 0.26636812, + 0.55488575 0.79132563 0.25672087, + 0.5552119 0.77837783 0.29303193, + 0.50815111 0.80604118 0.30344707, + 0.50773412 0.82097816 0.26115307, + 0.45572415 0.8482393 0.2698251, + 0.45470014 0.86137831 0.22644007, + 0.40107006 0.88594609 0.23290002, + 0.39958614 0.89702427 0.18888707, + 0.34540692 0.91831475 0.19336995, + 0.34362796 0.9272269 0.14889598, + 0.28941706 0.94509524 0.15176603, + 0.28751794 0.95176977 0.10708698, + 0.23356511 0.96624446 0.10871606, + 0.23168907 0.97071522 0.063500017, + 0.17829606 0.98187834 0.064230226, + 0.17669806 0.98404038 0.021032207, + 0.124732 0.99196398 0.021201501, + 0.12414304 0.99226433 0.00028811712, + 0.073583402 0.997289 0.00028957601, + -0.027817607 0.92860126 0.37003508, + -0.027798695 0.91040289 0.41278794, + 0.027290912 0.91041541 0.4127942, + 0.027303591 0.92869663 0.36983389, + -0.02762411 0.92868835 0.36983112, + -0.027605604 0.94487214 0.32627404, + 0.027099499 0.94488502 0.32627901, + 0.0271248 0.92862499 0.37002701, + 0.082668997 0.92578697 0.36889601, + 0.08262001 0.90754712 0.41174304, + 0.027491214 0.91031641 0.41299921, + 0.027438616 0.88991153 0.45530728, + -0.027954491 0.88989872 0.45530084, + -0.028012987 0.91029656 0.4130078, + -0.083080694 0.90750587 0.41174093, + -0.083135396 0.92574489 0.36889696, + 0.026383709 0.97090334 0.23801409, + 0.080360621 0.96810025 0.23732705, + 0.080642402 0.95598298 0.282123, + 0.13606697 0.95018679 0.28041193, + 0.13635406 0.93572342 0.32531413, + 0.19298796 0.92678887 0.32220796, + 0.19311491 0.91078657 0.36493081, + 0.13744093 0.91945058 0.36840281, + 0.13733996 0.93598878 0.3241339, + 0.08141274 0.9418065 0.32614815, + 0.081237227 0.95613837 0.28142509, + 0.026704704 0.95896709 0.28225702, + 0.026606906 0.97096026 0.23775706, + -0.027060613 0.97094846 0.23775412, + -0.027149197 0.95895189 0.28226596, + -0.081700765 0.9560985 0.28142586, + -0.081871219 0.94174325 0.3262161, + -0.13780798 0.93589985 0.32419196, + -0.13790095 0.91982561 0.36729288, + -0.082533091 0.9255299 0.36957097, + -0.082475096 0.94192988 0.32552397, + -0.027387587 0.94479555 0.32651386, + -0.027333695 0.95900786 0.28205797, + 0.026878295 0.9590199 0.28206098, + 0.026940703 0.94482911 0.32645404, + 0.082003005 0.94198912 0.32547203, + 0.082065694 0.92557186 0.36956996, + 0.13842602 0.91976315 0.36725202, + 0.13833997 0.90161777 0.40981391, + 0.083218068 0.90721369 0.41235685, + 0.083053477 0.88707274 0.45409688, + 0.0276289 0.88980901 0.45549601, + 0.027534992 0.86716068 0.49726683, + -0.028062107 0.86714816 0.49725911, + -0.028161591 0.88978672 0.45550686, + -0.083557889 0.88702691 0.45409393, + -0.083727993 0.90714389 0.41240695, + -0.13883296 0.90152472 0.40985185, + -0.13892606 0.9192344 0.36838517, + -0.19356903 0.91068012 0.36495602, + -0.19344808 0.92667139 0.32227013, + -0.13680995 0.93563157 0.32538685, + -0.136531 0.95011199 0.28044, + -0.081076667 0.95593566 0.28215891, + -0.080804177 0.96805274 0.23736994, + -0.026791597 0.97087985 0.23806398, + -0.026669813 0.98071247 0.19362809, + 0.026252709 0.98072338 0.19363007, + 0.026107991 0.98069364 0.19379993, + 0.079413973 0.97792965 0.19325392, + 0.079794891 0.96798086 0.23800397, + 0.13462698 0.96223688 0.23659196, + 0.13509105 0.94997233 0.28160807, + 0.19127293 0.94105965 0.27896491, + 0.19165708 0.92648333 0.32387713, + 0.24865206 0.91433525 0.31963009, + 0.24879187 0.89844257 0.36180583, + 0.19449295 0.90989578 0.36641791, + 0.19436008 0.89252329 0.40697214, + 0.13932903 0.90099925 0.4108381, + 0.13905002 0.88117713 0.45187607, + 0.083667397 0.886702 0.45470801, + 0.083379865 0.86435258 0.49592575, + 0.027742404 0.86703914 0.49746707, + 0.02760721 0.84249127 0.53800219, + -0.028148808 0.84247917 0.53799313, + -0.028289191 0.86701471 0.49747881, + -0.083895281 0.86430383 0.49592388, + -0.084188037 0.88664544 0.4547222, + -0.13955399 0.88109702 0.451877, + -0.13983704 0.90089631 0.41089115, + -0.19486503 0.89239413 0.40701407, + -0.195004 0.909751 0.36650601, + -0.24922697 0.89828891 0.36188796, + -0.24909499 0.91417402 0.31974599, + -0.19206508 0.92635334 0.32400712, + -0.19168991 0.94095254 0.27903989, + -0.13551103 0.94988823 0.28169006, + -0.13505603 0.96216524 0.23663905, + -0.08023078 0.96793175 0.23805694, + -0.079859503 0.97788799 0.19328099, + -0.026495796 0.98067689 0.19383197, + -0.026344404 0.98839611 0.14959702, + 0.025950106 0.98840624 0.14959903, + 0.025749905 0.98837525 0.14983803, + 0.078364737 0.98566246 0.14942707, + 0.078835167 0.97783667 0.19395992, + 0.13305892 0.97216743 0.19283588, + 0.13368604 0.96207821 0.23776805, + 0.18927602 0.95324409 0.23558503, + 0.18990704 0.94081521 0.28071705, + 0.24644712 0.92869741 0.27710113, + 0.24691197 0.91400087 0.32192698, + 0.30350903 0.8987121 0.31654203, + 0.30364195 0.88297975 0.3579779, + 0.25054595 0.89717579 0.36373392, + 0.25036004 0.8801831 0.40323406, + 0.19576102 0.89154613 0.40844005, + 0.19536997 0.87213486 0.44856593, + 0.140045 0.88050801 0.45287201, + 0.139566 0.85854101 0.49338499, + 0.083977096 0.8639639 0.49650195, + 0.083566919 0.83973718 0.53652412, + 0.027817808 0.84235919 0.53819811, + 0.027638707 0.81588018 0.57756013, + -0.028195197 0.81586689 0.57755196, + -0.028379304 0.84233409 0.53820807, + -0.08406195 0.83969051 0.53651971, + -0.084476367 0.8639257 0.49648383, + -0.14008102 0.8584761 0.49335206, + -0.14056401 0.8804161 0.45289007, + -0.19583891 0.87202561 0.4485738, + -0.19623609 0.89143741 0.4084492, + -0.2508001 0.88005728 0.40323514, + -0.25099307 0.89701223 0.36382908, + -0.304066 0.88279903 0.358064, + -0.30393907 0.89853722 0.3166261, + -0.24737412 0.91384339 0.32201916, + -0.24691808 0.92856133 0.27713808, + -0.19034591 0.94071251 0.28076389, + -0.18972391 0.95313251 0.23567589, + -0.13407296 0.96199965 0.23786791, + -0.13345604 0.97209322 0.19293605, + -0.079216599 0.97778499 0.194065, + -0.07875213 0.98562336 0.14948206, + -0.026093706 0.98835725 0.14989702, + -0.025910605 0.99404424 0.10585202, + 0.025568396 0.99405289 0.10585398, + 0.025430191 0.99403864 0.10602096, + 0.077292658 0.9913854 0.10573894, + 0.077843674 0.98560566 0.15007295, + 0.13135396 0.98003966 0.14922594, + 0.13213305 0.97205937 0.19401407, + 0.18711101 0.96333802 0.192274, + 0.18797404 0.9530791 0.23728903, + 0.24400197 0.94104689 0.23429397, + 0.24478206 0.92846423 0.27934906, + 0.30094305 0.91320425 0.27475706, + 0.30146199 0.89839202 0.31939399, + 0.35735407 0.88001025 0.31285807, + 0.35746381 0.86447859 0.35340682, + 0.30569914 0.88132644 0.36029419, + 0.30545017 0.86476755 0.39859423, + 0.25209004 0.87884015 0.40508106, + 0.25158405 0.85990417 0.44415113, + 0.19672804 0.87111914 0.44994405, + 0.19606297 0.84960389 0.48962495, + 0.14056903 0.85781717 0.49435812, + 0.13989204 0.83403128 0.53368717, + 0.084158979 0.83932585 0.53707486, + 0.083625272 0.81321073 0.57592982, + 0.027827309 0.81575328 0.57773018, + 0.027606303 0.7873171 0.61593008, + -0.02817939 0.7873047 0.61591977, + -0.028405193 0.8157258 0.57774091, + -0.084167868 0.8131597 0.57592285, + -0.084705897 0.83924198 0.53711998, + -0.14043306 0.83392245 0.53371525, + -0.14111708 0.85772842 0.49435624, + -0.19657205 0.84949416 0.48961112, + -0.19724192 0.87097555 0.4499968, + -0.25202999 0.85974997 0.444197, + -0.25254303 0.87870413 0.40509406, + -0.30586585 0.86461759 0.39860082, + -0.30612203 0.88114411 0.36038104, + -0.35785082 0.8642866 0.35348481, + -0.35775003 0.87979913 0.31299904, + -0.30184087 0.89820969 0.31954888, + -0.30132988 0.91303569 0.2748929, + -0.245171 0.92831802 0.27949399, + -0.24440201 0.94090903 0.234431, + -0.18838093 0.95296264 0.23743391, + -0.18752892 0.96323162 0.19239992, + -0.13250402 0.97198212 0.19414803, + -0.13173206 0.97997147 0.14934108, + -0.078179389 0.98556089 0.15019199, + -0.077627227 0.99134839 0.10584204, + -0.02568499 0.99402064 0.10612796, + -0.025465604 0.99777514 0.061613806, + 0.02522371 0.99778134 0.061614223, + 0.025115391 0.99777561 0.061749477, + 0.076126017 0.99519426 0.061589815, + 0.0767617 0.991355 0.106409, + 0.12950803 0.98591524 0.10582502, + 0.13042803 0.97998023 0.15042403, + 0.18474196 0.97140974 0.14910898, + 0.18581694 0.96324265 0.19399893, + 0.24127306 0.95135427 0.19160505, + 0.24234594 0.94090474 0.23657294, + 0.29805699 0.925735 0.232759, + 0.29895607 0.91300124 0.27758607, + 0.35447687 0.89462972 0.27199993, + 0.35502192 0.87972474 0.31629691, + 0.41019499 0.85821301 0.30856201, + 0.41025707 0.84291309 0.34811902, + 0.35983011 0.86236727 0.35615313, + 0.3595092 0.84630847 0.39308423, + 0.30750304 0.86300111 0.40083805, + 0.30687904 0.84459114 0.43873805, + 0.25331998 0.8584649 0.44594494, + 0.25247398 0.83749586 0.48462093, + 0.19745199 0.84849602 0.49098599, + 0.19651604 0.82524115 0.52948904, + 0.14090198 0.83325589 0.53463197, + 0.14002201 0.80764014 0.57281005, + 0.084209323 0.81277817 0.57645512, + 0.083545335 0.78471535 0.61420029, + 0.0278216 0.78716397 0.61611599, + 0.027553987 0.75668162 0.65320271, + -0.028115984 0.75666952 0.65319258, + -0.028387308 0.78715616 0.61610013, + -0.084098294 0.78468388 0.61416495, + -0.084763937 0.81271839 0.57645828, + -0.14051703 0.80756116 0.5728001, + -0.1414009 0.83317852 0.5346207, + -0.197006 0.82514101 0.52946299, + -0.19794704 0.84839618 0.49095911, + -0.252931 0.83737999 0.48458299, + -0.25377986 0.85829747 0.44600573, + -0.30734393 0.8443988 0.43878287, + -0.30797294 0.8628028 0.40090391, + -0.35990009 0.84611219 0.39314908, + -0.3602289 0.86216283 0.35624492, + -0.4106051 0.84270716 0.34820709, + -0.41055015 0.85799032 0.30870911, + -0.35540792 0.87951279 0.31645292, + -0.35487282 0.8944276 0.27214789, + -0.29932693 0.91283077 0.27774695, + -0.29843903 0.92556912 0.23292904, + -0.242716 0.94076401 0.236753, + -0.24165297 0.95121789 0.19180296, + -0.18617405 0.96313226 0.19420505, + -0.18510605 0.97131437 0.14927906, + -0.13075902 0.97990912 0.15060002, + -0.12984002 0.9858461 0.10606202, + -0.076986574 0.99131167 0.10664997, + -0.076335035 0.99516749 0.06176313, + -0.025217306 0.99776226 0.061924115, + -0.024979604 0.99950111 0.019329201, + 0.024895806 0.99950325 0.019329203, + 0.024740506 0.99950325 0.019525304, + 0.074959926 0.99699634 0.019476308, + 0.075643606 0.99519211 0.062215608, + 0.12758501 0.98989511 0.061884508, + 0.12865095 0.98590565 0.10695297, + 0.18222706 0.97752136 0.10604404, + 0.18350092 0.97138554 0.15078993, + 0.23828012 0.95970249 0.14897607, + 0.23963097 0.95130289 0.19390696, + 0.29481611 0.93630135 0.19084908, + 0.29607007 0.92564225 0.23564605, + 0.35121709 0.90735322 0.23099107, + 0.35219812 0.89447832 0.2754361, + 0.40708995 0.87293887 0.26880398, + 0.40762606 0.85798115 0.31258503, + 0.46169713 0.83344716 0.30364707, + 0.46169189 0.81843984 0.3420479, + 0.41282779 0.8403706 0.35121283, + 0.41242424 0.82487446 0.38663724, + 0.361797 0.84412903 0.39566299, + 0.36105809 0.82629019 0.43229809, + 0.30891815 0.84272242 0.4408952, + 0.30790088 0.82240772 0.47837481, + 0.25414908 0.83601928 0.48629218, + 0.25296906 0.8133682 0.5238691, + 0.19787605 0.82408917 0.53077513, + 0.19666597 0.79907387 0.56815791, + 0.14099398 0.80684888 0.57368594, + 0.13990402 0.77928913 0.61084807, + 0.084154576 0.7842378 0.6147269, + 0.083358809 0.7542001 0.65133208, + 0.027737891 0.75654268 0.65335578, + 0.027427288 0.72454864 0.68867767, + -0.028009608 0.72453725 0.68866622, + -0.028321199 0.75651401 0.653364, + -0.08390858 0.75414884 0.65132082, + -0.084708571 0.78420568 0.61469173, + -0.14044395 0.77923369 0.61079478, + -0.14153592 0.80673063 0.57371873, + -0.19718893 0.79893368 0.56817383, + -0.19840209 0.82395744 0.53078324, + -0.25346187 0.81321758 0.52386475, + -0.254648 0.83586401 0.48629799, + -0.30834812 0.82224232 0.47837117, + -0.30936897 0.84254086 0.44092593, + -0.3614811 0.82609415 0.43231907, + -0.36222404 0.84389609 0.39576906, + -0.4128001 0.8246392 0.38673809, + -0.41320914 0.8401283 0.35134411, + -0.4620502 0.81818742 0.34216815, + -0.46206501 0.83318502 0.30380699, + -0.40796095 0.8577559 0.31276596, + -0.407435 0.872715 0.26900801, + -0.35254812 0.89427328 0.27565408, + -0.35157898 0.90716588 0.23117597, + -0.29643485 0.9254756 0.23584189, + -0.29519504 0.93614113 0.19104902, + -0.24000292 0.95116663 0.19411492, + -0.23866406 0.95956624 0.14923903, + -0.18378896 0.97128874 0.15106197, + -0.18251905 0.97742522 0.10642702, + -0.12886605 0.98583537 0.10734203, + -0.12778807 0.98984945 0.062196732, + -0.075743482 0.99516475 0.062530681, + -0.075041518 0.99698824 0.019577205, + -0.024744105 0.99950111 0.019626603, + -0.024627989 0.99969655 -0.00053625577, + 0.024627989 0.99969655 -0.00053625577, + 0.024442406 0.99970126 -0.00031924609, + 0.074085295 0.99725187 -0.00031846296, + 0.074433506 0.99702209 0.020166002, + 0.12556703 0.99188226 0.020062106, + 0.12671196 0.98993278 0.063065387, + 0.1794849 0.98177052 0.062545367, + 0.18096894 0.97756565 0.10777596, + 0.23508406 0.96612126 0.10651402, + 0.23668788 0.95974153 0.15124492, + 0.29130995 0.94496673 0.14891697, + 0.29289585 0.9363206 0.19368991, + 0.34759399 0.91820502 0.189942, + 0.34898382 0.90733361 0.23442689, + 0.40352494 0.88587791 0.22888397, + 0.40454915 0.87285727 0.27287409, + 0.45844483 0.84823871 0.26517791, + 0.45893878 0.83328056 0.30825084, + 0.51108682 0.80613971 0.29820988, + 0.51099485 0.79144579 0.3354069, + 0.46447989 0.81538481 0.34555191, + 0.46398783 0.80048168 0.37939987, + 0.41501293 0.82214588 0.38966694, + 0.41415995 0.80497891 0.42482993, + 0.36338198 0.82393688 0.43483493, + 0.36220703 0.8043431 0.47099707, + 0.30991086 0.82045257 0.48042977, + 0.30850199 0.79849899 0.51693898, + 0.25468987 0.81176162 0.52552474, + 0.25317097 0.7874499 0.56198496, + 0.19803791 0.79784662 0.56940472, + 0.19653909 0.77094138 0.60582328, + 0.14090209 0.77843249 0.61171037, + 0.13959302 0.74897408 0.64772809, + 0.083952308 0.75370914 0.65182406, + 0.083031923 0.72214717 0.68673819, + 0.027649293 0.72437185 0.68885481, + 0.027299199 0.69088399 0.72245002, + -0.027881008 0.69087321 0.72243816, + -0.028233493 0.7243588 0.6888448, + -0.083600104 0.72211105 0.68670708, + -0.084523097 0.75364101 0.651829, + -0.14014502 0.74888307 0.64771408, + -0.1414571 0.77836245 0.61167133, + -0.19703293 0.77085572 0.60577178, + -0.19853397 0.7977289 0.56939691, + -0.2536509 0.78731269 0.56196082, + -0.25517493 0.81161684 0.52551287, + -0.30896094 0.79833782 0.51691389, + -0.31037202 0.82027113 0.48044205, + -0.362611 0.80415702 0.47100401, + -0.3637909 0.82375181 0.4348439, + -0.414518 0.80479199 0.424835, + -0.41537377 0.82192254 0.38975376, + -0.46432489 0.80024981 0.3794769, + -0.46482295 0.81514388 0.34565896, + -0.51128119 0.79121631 0.33551213, + -0.51138198 0.80587101 0.29843, + -0.45926511 0.8330152 0.30848205, + -0.458783 0.84799898 0.26536, + -0.40490282 0.87263256 0.27306789, + -0.40389299 0.88565201 0.229109, + -0.34930983 0.90714556 0.23466888, + -0.34793296 0.9180249 0.19019197, + -0.29323396 0.93616086 0.19394997, + -0.29165906 0.94481021 0.14922702, + -0.23703088 0.95960653 0.15156393, + -0.23543508 0.96598834 0.10694404, + -0.18121994 0.97747064 0.10821496, + -0.17972492 0.98170155 0.062936269, + -0.12685305 0.98988938 0.063461326, + -0.12568699 0.99186391 0.020215798, + -0.074474491 0.99701589 0.020320797, + -0.074121617 0.99724925 -0.00031838109, + -0.024442406 0.99970126 -0.0003191641, + -0.024439296 0.9997009 -0.0008825449, + 0.024439296 0.9997009 -0.0008825449, + 0.023693699 0.99971902 -0.00066560699, + 0.073567897 0.99729002 -0.00066398998, + 0.071341984 0.99745178 -0.00041668891, + 0.071346179 0.99745166 -1.9550594e-006, + 0.12320995 0.99238062 -1.9451493e-006, + 0.12156098 0.99258387 0.00038594296, + 0.11947796 0.99283665 0.00065260177, + 0.11948603 0.99283522 0.0011383602, + 0.17339495 0.98485178 0.0011292098, + 0.17346489 0.98483539 0.0030132781, + 0.2255961 0.97421646 0.0029807915, + 0.22667298 0.97365791 0.024692096, + 0.27928096 0.95990086 0.024343297, + 0.28169805 0.95711923 0.067594215, + 0.33470404 0.93998212 0.066383906, + 0.337228 0.93482202 0.111288, + 0.39055207 0.9141261 0.10882401, + 0.39288199 0.90679997 0.152832, + 0.44594207 0.88261414 0.14875501, + 0.44794807 0.87313312 0.19230503, + 0.49956781 0.8459987 0.18632793, + 0.50107825 0.83454943 0.2290151, + 0.55102336 0.80473948 0.22083414, + 0.55191201 0.79149503 0.26254299, + 0.60001498 0.75930601 0.25186601, + 0.60022414 0.74667817 0.28671005, + 0.55826485 0.77452683 0.29740295, + 0.55804497 0.7621659 0.32815996, + 0.51389885 0.7879197 0.33924988, + 0.51331496 0.77368486 0.37137496, + 0.46670017 0.79731828 0.38272014, + 0.46573901 0.78088403 0.416302, + 0.41665399 0.80218798 0.427661, + 0.41533214 0.7833513 0.46245018, + 0.36448404 0.80190015 0.47340006, + 0.36287418 0.78075933 0.50866222, + 0.31048504 0.79646111 0.51889205, + 0.30868298 0.77294087 0.55432594, + 0.25485596 0.78579187 0.56354195, + 0.25298092 0.75968868 0.59906077, + 0.19784707 0.76970929 0.60696322, + 0.19605204 0.74094015 0.64231718, + 0.1405571 0.74810243 0.64852637, + 0.13904601 0.71712708 0.68293107, + 0.083633393 0.72162491 0.68721396, + 0.082589954 0.68862444 0.72039944, + 0.027490992 0.69072384 0.72259581, + 0.0270971 0.65563798 0.75458902, + -0.027703209 0.65562725 0.75457633, + -0.028099297 0.69069093 0.72260392, + -0.083151996 0.68857092 0.72038597, + -0.08419843 0.72159123 0.68718022, + -0.13959803 0.71707219 0.68287617, + -0.14111108 0.74801034 0.6485123, + -0.19660898 0.74082392 0.64228094, + -0.19840592 0.76956171 0.60696775, + -0.25347304 0.75952911 0.59905505, + -0.25535196 0.78563589 0.56353492, + -0.30917898 0.77276188 0.55429894, + -0.31098297 0.7962569 0.51890695, + -0.36328691 0.78055781 0.50867689, + -0.36490181 0.80169666 0.47342277, + -0.4157322 0.78313237 0.4624612, + -0.41705886 0.80194569 0.42772084, + -0.46610111 0.78063917 0.41635609, + -0.46706781 0.79704672 0.38283685, + -0.51362294 0.77342486 0.37149096, + -0.51421386 0.78765082 0.33939692, + -0.55830526 0.76191235 0.32830614, + -0.55853313 0.77423918 0.29764807, + -0.60046077 0.74639773 0.2869449, + -0.60026389 0.75902385 0.25212294, + -0.5521692 0.7912243 0.2628181, + -0.55129701 0.80446798 0.22114, + -0.50137293 0.83428389 0.22933698, + -0.49987799 0.84574699 0.186639, + -0.44822189 0.8729198 0.19263496, + -0.44623905 0.88238311 0.14923401, + -0.39318994 0.90658289 0.15332699, + -0.39087915 0.91390532 0.10950103, + -0.33750492 0.93463874 0.11198597, + -0.33498502 0.93982512 0.067184605, + -0.28182793 0.95702279 0.068413988, + -0.27938795 0.95985574 0.024885094, + -0.226702 0.97363698 0.025242301, + -0.225601 0.97421497 0.0030679901, + -0.17347005 0.98483425 0.0031014306, + -0.17339592 0.98485154 0.0011286894, + -0.11948603 0.99283522 0.0011378402, + -0.11947095 0.99283767 0.00022670091, + -0.069113784 0.99760878 0.00022779194, + -0.069112889 0.9976089 9.0520789e-006, + -0.025374696 0.99967688 -0.0014909498, + -0.025374604 0.99967414 0.0028057103, + -0.025311405 0.99967927 -0.0008064232, + -0.025311191 0.99967563 0.002804629, + -0.025379296 0.9996739 0.0028046297, + -0.025379494 0.99967676 -0.0014909497, + -0.022983102 0.99973512 -0.0011967901, + -0.022984194 0.99973577 -0.00042632292, + -0.071305737 0.99745446 -0.00042535021, + -0.071310014 0.99745423 -2.3954508e-006, + -0.12320995 0.99238062 -2.3831092e-006, + -0.12324994 0.99237454 0.0015061992, + -0.17469005 0.98462236 0.0014944306, + -0.175539 0.98420101 0.023117401, + -0.22828098 0.97332686 0.022861999, + -0.23033297 0.97084087 0.066443592, + -0.283694 0.95667702 0.065474302, + -0.28592193 0.95185179 0.11057497, + -0.339636 0.93427402 0.108533, + -0.34176201 0.92729002 0.152748, + -0.39558005 0.90621912 0.14927602, + -0.39748186 0.89703071 0.19324593, + -0.45083693 0.87258786 0.18797997, + -0.45234695 0.86129189 0.23142697, + -0.50417691 0.83401787 0.22409797, + -0.50513709 0.82081914 0.26663202, + -0.5551579 0.7910558 0.25696394, + -0.55547214 0.77810615 0.29326007, + -0.5084362 0.80577129 0.30368611, + -0.50803101 0.82073402 0.261343, + -0.45605299 0.84799898 0.27002501, + -0.45504496 0.86112386 0.22671497, + -0.40139705 0.88572115 0.23319203, + -0.39992881 0.89681256 0.1891669, + -0.34571612 0.91813636 0.19366507, + -0.34395397 0.92704791 0.14925799, + -0.28972098 0.94494188 0.15213999, + -0.28783506 0.95161027 0.10765202, + -0.2338119 0.96611953 0.10929295, + -0.23192991 0.97062063 0.064062677, + -0.17840809 0.98182046 0.064801931, + -0.17678699 0.98401791 0.021330899, + -0.12474497 0.99195576 0.021502994, + -0.12414697 0.99226373 0.00037571791, + -0.07354717 0.99729162 0.00037761385, + -0.073530287 0.99729276 -0.00066399283, + -0.023693699 0.99971902 -0.00066560903, + -0.023693804 0.99971914 -0.00063306605, + 0.023693804 0.99971914 -0.00063306605, + 0.024459185 0.99970043 -0.00085607247, + 0.023769496 0.99971688 -0.0010563399, + 0.023092294 0.99973273 -0.0010563597, + 0.023090901 0.99966502 -0.0116897, + 0.023767991 0.99964666 -0.011898795, + 0.025752805 0.99957621 -0.013574403, + 0.023621803 0.9996171 -0.014408902, + 0.023623988 0.99972051 -0.00085608556, + 0.072750114 0.99735022 -0.00026636507, + 0.072749674 0.99734664 0.0026948291, + 0.072647505 0.99735409 0.0026948203, + 0.072647862 0.99735755 -0.00047112376, + 0.072841838 0.99734348 -0.00047112323, + 0.072841302 0.99734002 0.00266515, + 0.12155694 0.99254251 -0.0091251554, + 0.12837601 0.99162698 -0.0139824, + 0.67975283 0.7027688 0.20988595, + 0.63640606 0.73909605 0.22073603, + 0.63523418 0.75081116 0.18099804, + 0.5890761 0.78557318 0.18937804, + 0.58719027 0.79574937 0.14829208, + 0.53914791 0.82795686 0.15429498, + 0.53664595 0.83631891 0.11216898, + 0.48705077 0.86562258 0.11609995, + 0.48403081 0.87202072 0.072759978, + 0.43315309 0.89819926 0.074944414, + 0.42991686 0.90228271 0.032519288, + 0.37807807 0.9251731 0.033344403, + 0.37634891 0.92641973 0.010384697, + 0.32441184 0.94585651 0.010602595, + 0.26638287 0.96384954 0.0058418773, + 0.2664381 0.96382338 0.0074330429, + 0.32419804 0.94596112 0.0072952812, + 0.26574692 0.96402466 0.0059076077, + 0.3151471 0.94900626 0.0083443318, + 0.31523189 0.94895667 0.010495496, + 0.3738519 0.92743164 0.010257396, + 0.37412411 0.92727238 0.014038204, + 0.42568007 0.90477014 0.013697502, + 0.42757991 0.90321875 0.037032492, + 0.47817788 0.87752575 0.035979092, + 0.48154107 0.87295711 0.077873506, + 0.53092384 0.84406769 0.075296268, + 0.53396016 0.8372463 0.11792004, + 0.58196688 0.80526483 0.11341597, + 0.58438778 0.79660672 0.15462394, + 0.63063592 0.76185989 0.14787799, + 0.63236725 0.75155032 0.18784007, + 0.67583382 0.71505785 0.17871995, + 0.67681295 0.70335895 0.21727997, + 0.71742505 0.66560006 0.20561603, + 0.71767282 0.65525681 0.23576294, + 0.68016201 0.68977201 0.248182, + -0.16346601 0.98654598 0.0024175099, + -0.2075661 0.97820646 0.0053427424, + -0.20756197 0.97821289 0.0041884095, + -0.25835201 0.96604198 0.0041362899, + -0.25840095 0.96600676 0.007731508, + -0.31508592 0.94903278 0.0075956583, + -0.31520215 0.9489665 0.010505305, + -0.37382391 0.92744279 0.010266997, + -0.37410888 0.92727566 0.014224395, + -0.42572385 0.90474671 0.013878895, + -0.42768085 0.90313268 0.037953787, + -0.47831887 0.87741178 0.036872793, + -0.48170999 0.87273902 0.079259597, + -0.53116679 0.8437947 0.076630972, + -0.53416198 0.83697301 0.118942, + -0.58222705 0.80493909 0.11438902, + -0.58460814 0.7963202 0.15526603, + -0.63084584 0.76156682 0.14849097, + -0.63255125 0.75127733 0.18831207, + -0.67601502 0.71477598 0.179162, + -0.67697418 0.70308119 0.21767604, + -0.71757543 0.66532344 0.20598611, + -0.71780998 0.65497297 0.23613399, + -0.68031007 0.68948406 0.24857603, + -0.67991877 0.70249379 0.21026893, + -0.63661098 0.73879999 0.221136, + -0.63545597 0.75052989 0.18138498, + -0.58930212 0.78530419 0.18979004, + -0.58744168 0.79545367 0.14888193, + -0.53936213 0.82770115 0.15491703, + -0.53689694 0.8360309 0.11310998, + -0.48728111 0.86536115 0.11707803, + -0.48429212 0.8717742 0.073965319, + -0.43331385 0.89801669 0.076191768, + -0.43005306 0.90218711 0.033359103, + -0.37814215 0.92511535 0.034206912, + -0.37636116 0.92641336 0.010521304, + -0.32442096 0.94585186 0.010741999, + -0.32419804 0.94596112 0.007294571, + -0.26647106 0.96381426 0.0074322317, + -0.26638794 0.96385276 0.0050341086, + -0.21079308 0.97751737 0.0051054819, + -0.21075797 0.9775359 0.0021292197, + -0.16303305 0.98661834 0.0021489908, + -0.16304095 0.98661476 0.0029849892, + -0.21740808 0.97607636 0.0029531112, + -0.2174629 0.97605652 0.0048513175, + -0.27424711 0.96164745 0.0047797025, + -0.27441388 0.96158051 0.0077386862, + -0.32644996 0.94518387 0.0076067289, + -0.32802108 0.94416922 0.030769007, + -0.38040307 0.92433012 0.030122403, + -0.38345695 0.92064691 0.07328099, + -0.43581805 0.89719713 0.071414508, + -0.43872914 0.89119732 0.11525705, + -0.48993987 0.86455584 0.11181297, + -0.49242413 0.85654217 0.15444703, + -0.54214305 0.82695013 0.14911202, + -0.54410285 0.81698769 0.19100593, + -0.59217823 0.7846483 0.18344507, + -0.59348971 0.77296865 0.22425289, + -0.63959783 0.73826784 0.21418495, + -0.64017969 0.72512162 0.25370988, + -0.68336117 0.68911719 0.24111205, + -0.68328118 0.67730016 0.27274805, + -0.64632004 0.70782906 0.28504103, + -0.64589494 0.69682497 0.31185699, + -0.60619289 0.72593385 0.32488492, + -0.60542202 0.71316999 0.35334501, + -0.56349987 0.74024081 0.3667579, + -0.56234008 0.72542506 0.39690307, + -0.51816583 0.75031668 0.41052285, + -0.51659393 0.73323596 0.44214895, + -0.46995994 0.75589287 0.45581093, + -0.46801588 0.73661882 0.48821488, + -0.41884905 0.75690413 0.50165904, + -0.41658586 0.73527277 0.53463084, + -0.36570489 0.75277072 0.5473538, + -0.36318997 0.72851592 0.58082491, + -0.31089097 0.74316096 0.59250194, + -0.30824593 0.71623385 0.6260938, + -0.2545529 0.72809374 0.63646078, + -0.25196904 0.69882405 0.66944504, + -0.19719197 0.70794392 0.67818195, + -0.194846 0.67637002 0.71032298, + -0.13986903 0.68280816 0.71708417, + -0.13794601 0.64890504 0.74826008, + -0.083196193 0.65289694 0.75286388, + -0.081892699 0.616813 0.78283799, + -0.027632516 0.61865538 0.78517646, + -0.027155086 0.58102071 0.81343555, + 0.026563291 0.58102983 0.81344873, + 0.027041914 0.6186713 0.78518438, + 0.081279978 0.6168499 0.7828728, + 0.082582265 0.65297973 0.75285965, + 0.13732602 0.64901006 0.74828309, + 0.13924605 0.68291223 0.71710622, + 0.19429795 0.67648882 0.71035981, + 0.19663788 0.70802361 0.67825961, + 0.25146192 0.69891876 0.66953677, + 0.25405005 0.72826117 0.6364702, + 0.30774787 0.71642178 0.62612379, + 0.31039113 0.74335927 0.59251523, + 0.36275402 0.72871709 0.58084506, + 0.36526498 0.75296891 0.54737496, + 0.41619095 0.73547596 0.53465897, + 0.41845301 0.75712901 0.50164998, + 0.46764818 0.73685223 0.48821518, + 0.46959105 0.75615412 0.45575806, + 0.51627797 0.73348993 0.44209695, + 0.51784474 0.75058264 0.41044179, + 0.56205809 0.72568518 0.3968271, + 0.56321192 0.74050695 0.36666298, + 0.60518622 0.71341723 0.35325012, + 0.60595196 0.72621691 0.32470196, + 0.64570206 0.69708407 0.31167704, + 0.64611977 0.70812178 0.2847679, + 0.68310905 0.67757905 0.27248603, + 0.68317801 0.68940502 0.240808, + 0.63996518 0.72542316 0.25338906, + 0.63936776 0.73856574 0.21384493, + 0.593288 0.77323103 0.223882, + 0.59195703 0.78491509 0.18301702, + 0.54386383 0.81725168 0.19055693, + 0.54188013 0.82721919 0.14857402, + 0.49214783 0.85680169 0.15388794, + 0.48963195 0.8648389 0.11096898, + 0.43848988 0.89142776 0.11438097, + 0.43555814 0.89740729 0.070350625, + 0.38327882 0.9208076 0.072184965, + 0.38025308 0.92441422 0.029428007, + 0.32797292 0.94420874 0.030058093, + 0.32644102 0.94518811 0.0074721407, + 0.27440596 0.96158385 0.0076017589, + 0.27424595 0.96164775 0.0047692088, + 0.21746407 0.97605634 0.004840672, + 0.21743095 0.97606874 0.003697919, + 0.17044201 0.98536509 0.0022998003, + 0.17011705 0.98542124 0.0023105806, + 0.17011707 0.98542237 0.0017452306, + 0.170443 0.98536599 0.00174508, + 0.17007704 0.98542923 0.0017485705, + 0.17007606 0.98542833 0.0022997509, + 0.12152497 0.99243176 -0.017633196, + 0.12154203 0.99258626 0.00038595108, + 0.16828799 0.98573589 0.0019675097, + 0.16830599 0.98573101 0.0027376299, + 0.22397693 0.97459066 0.0027066891, + 0.22408794 0.97455579 0.0050650085, + 0.2761949 0.96108866 0.004995028, + 0.27750805 0.96033925 0.027163006, + 0.32996792 0.94361478 0.026689995, + 0.33271608 0.94044721 0.069706917, + 0.38551185 0.92017865 0.068204574, + 0.38827705 0.91461813 0.11275902, + 0.44095385 0.89078569 0.10982096, + 0.44341195 0.88310289 0.15334599, + 0.49482876 0.85617858 0.14866993, + 0.49685413 0.8464402 0.19150704, + 0.54668278 0.8166976 0.18477792, + 0.54813087 0.80510283 0.22663194, + 0.59623295 0.77277786 0.21753298, + 0.5969919 0.75955284 0.25822493, + 0.64299816 0.72510916 0.24651606, + 0.64307415 0.71286815 0.27977607, + 0.60327595 0.74240392 0.29136696, + 0.60295773 0.73068666 0.32021686, + 0.56098288 0.75821382 0.33227992, + 0.56030595 0.74466091 0.36268097, + 0.51615077 0.77002466 0.37503383, + 0.51508582 0.7543577 0.40697786, + 0.46842501 0.77756101 0.419496, + 0.46697095 0.75958186 0.45273995, + 0.41780379 0.78042465 0.4651638, + 0.41601506 0.76017213 0.49906906, + 0.36510208 0.77823716 0.51092809, + 0.36305317 0.75560236 0.54521322, + 0.31065115 0.77081233 0.55618721, + 0.30843589 0.74557978 0.59074378, + 0.25465986 0.75795251 0.60054666, + 0.25241694 0.73003185 0.63508981, + 0.19738795 0.73961884 0.64342982, + 0.195316 0.70939201 0.67721099, + 0.140029 0.716196 0.683707, + 0.13831694 0.68383169 0.71640962, + 0.083195239 0.68807435 0.72085536, + 0.082022674 0.65351081 0.75245982, + 0.027282303 0.65547603 0.75472313, + 0.026843296 0.61885196 0.7850489, + -0.027427793 0.6188429 0.78503585, + -0.027867116 0.65548444 0.75469446, + -0.082561232 0.65350026 0.75241029, + -0.083733089 0.68804193 0.72082394, + -0.1388929 0.68377459 0.71635258, + -0.14060496 0.71611774 0.68367076, + -0.19589397 0.70928895 0.67715192, + -0.19796596 0.73948091 0.64341092, + -0.25290096 0.72988695 0.63506395, + -0.2551471 0.75779629 0.60053724, + -0.30892095 0.7454018 0.59071487, + -0.31113896 0.77063888 0.55615497, + -0.363478 0.75542498 0.54517603, + -0.36552802 0.77801812 0.51095706, + -0.41641986 0.75994068 0.49908382, + -0.41821501 0.78018999 0.465188, + -0.46731704 0.75935411 0.45276505, + -0.46877611 0.77732617 0.41953909, + -0.51537985 0.7541337 0.40702084, + -0.51644826 0.76977336 0.37514019, + -0.56059605 0.74439704 0.36277404, + -0.56127715 0.75790828 0.33248013, + -0.6032089 0.73039484 0.32040992, + -0.60353631 0.74208337 0.29164416, + -0.64327878 0.71257675 0.28004792, + -0.64321607 0.72481108 0.24682403, + -0.5972051 0.7592712 0.25856006, + -0.59646189 0.77251381 0.21784295, + -0.54839593 0.80483091 0.22695597, + -0.54696697 0.81642491 0.18514198, + -0.49712175 0.84619558 0.19189291, + -0.49511987 0.85591584 0.14921297, + -0.44365507 0.88288212 0.15391402, + -0.44122478 0.89054859 0.11065195, + -0.38849387 0.91441971 0.11361796, + -0.3857429 0.92000675 0.069209687, + -0.33285889 0.94031966 0.070737779, + -0.33007985 0.94355851 0.027284987, + -0.27757913 0.96030146 0.027769113, + -0.276234 0.96107697 0.0050836201, + -0.22409303 0.97455412 0.0051549105, + -0.22397693 0.97459066 0.0027170491, + -0.16827196 0.98573679 0.0027481292, + -0.16823906 0.98574537 0.0013489504, + -0.11576595 0.99327564 0.0013592496, + -0.11576403 0.99327624 0.0010750302, + -0.12313005 0.99239033 -0.00072888623, + -0.12312902 0.99238712 0.0026554402, + -0.12305996 0.99239564 0.0026554291, + -0.12306099 0.99239886 -0.00072551292, + -0.12326998 0.99237287 -0.00072553195, + -0.12326897 0.99236977 0.0026368194, + -0.17161892 0.98512554 -0.008636686, + -0.17162393 0.98516154 -0.0013762893, + -0.17165892 0.98515552 -0.0013762993, + -0.17163308 0.9849925 -0.01822081, + -0.21979395 0.97554374 0.0022267096, + -0.21979503 0.97554612 -0.00017146801, + -0.219115 0.97569901 -0.00017096401, + -0.21911395 0.97569674 0.0022164795, + -0.21978404 0.97554612 0.0022166003, + -0.21978508 0.97554839 -0.00016055605, + -0.25451213 0.96704346 0.0071170931, + -0.25451094 0.96704674 0.0066950386, + -0.30582589 0.95206463 0.0065913177, + -0.30588886 0.95200551 0.010833494, + -0.36366981 0.93146759 0.010599895, + -0.36381903 0.93136412 0.014023002, + -0.42294484 0.90605271 0.013641795, + -0.42329586 0.9058097 0.018150594, + -0.47368211 0.88051921 0.017643904, + -0.47578606 0.87855011 0.042158704, + -0.52511275 0.85005456 0.04079118, + -0.52853703 0.84489709 0.082447909, + -0.57654715 0.81320119 0.079354919, + -0.57947302 0.80599898 0.120734, + -0.62576729 0.77140337 0.11555205, + -0.62800384 0.76253283 0.15541796, + -0.67161906 0.72597104 0.14796601, + -0.67312592 0.71559495 0.18661599, + -0.71393704 0.67754906 0.17669502, + -0.71467179 0.66595578 0.21388592, + -0.75279909 0.62672007 0.20128503, + -0.7528618 0.61679989 0.22968894, + -0.72075784 0.64960682 0.24190694, + -0.72051823 0.64079225 0.26502609, + -0.68623394 0.67215997 0.27799997, + -0.68571615 0.66186619 0.30286404, + -0.64884031 0.69192433 0.31661814, + -0.64798969 0.67996371 0.34315985, + -0.60831589 0.7085728 0.35759792, + -0.6070779 0.69461381 0.38596392, + -0.56517416 0.72112525 0.40069515, + -0.56351221 0.70499122 0.43062913, + -0.51931787 0.72928983 0.44547188, + -0.51725686 0.71104485 0.47629887, + -0.47057506 0.73308605 0.49106407, + -0.46813789 0.71249682 0.52268088, + -0.41898507 0.73212004 0.53707707, + -0.41622579 0.70895362 0.56933367, + -0.36536303 0.72579807 0.58286107, + -0.36237597 0.69994897 0.61543095, + -0.31015703 0.71395808 0.62774706, + -0.30711505 0.68569517 0.65992618, + -0.25361398 0.69695896 0.67076695, + -0.25069112 0.66635329 0.70223033, + -0.1961479 0.6749627 0.71130264, + -0.19352102 0.64192104 0.74194807, + -0.13887103 0.64795017 0.74891615, + -0.136738 0.61255097 0.77851403, + -0.082458541 0.61625332 0.78321934, + -0.081043325 0.57916611 0.81117117, + -0.027324004 0.58086103 0.81354409, + -0.026810788 0.54236877 0.83971256, + 0.0262527 0.542377 0.83972502, + 0.026764309 0.58083916 0.81357831, + 0.080454223 0.57916415 0.8112312, + 0.081867598 0.61626899 0.78326899, + 0.13618499 0.61258394 0.7785849, + 0.13831805 0.64798623 0.74898726, + 0.192968 0.64197898 0.74204201, + 0.19560114 0.67508149 0.71134055, + 0.25014508 0.66649425 0.70229125, + 0.25306809 0.69709826 0.67082822, + 0.30663899 0.68584102 0.65999597, + 0.30968207 0.71412116 0.62779617, + 0.36192408 0.70012718 0.61549413, + 0.36491197 0.72602195 0.58286494, + 0.4158062 0.70918733 0.56934929, + 0.41856301 0.73236299 0.53707498, + 0.46777579 0.71273464 0.52268076, + 0.47020823 0.73332137 0.49106425, + 0.51693183 0.71127778 0.47630382, + 0.51899177 0.72956365 0.44540378, + 0.56321585 0.70526481 0.4305689, + 0.56487405 0.72141808 0.40059105, + 0.6068421 0.69488019 0.38585508, + 0.60807371 0.70883566 0.35748881, + 0.64779615 0.68020415 0.34304908, + 0.64864224 0.69219923 0.31642312, + 0.68554497 0.66212893 0.30267698, + 0.68605715 0.6724562 0.27772006, + 0.72036701 0.64107299 0.26475799, + 0.72059864 0.6499427 0.24147888, + 0.7527408 0.61710089 0.22927694, + 0.75266373 0.62700975 0.20088792, + 0.71454406 0.66623104 0.21345504, + 0.71378881 0.67783082 0.17621295, + 0.67297679 0.71586883 0.18610196, + 0.67144293 0.72626692 0.14731199, + 0.62783778 0.76281071 0.15472394, + 0.62555784 0.77172881 0.11450797, + 0.57928014 0.80630118 0.11963703, + 0.57631469 0.81349456 0.078024261, + 0.5283218 0.84516573 0.08106187, + 0.5249117 0.85022748 0.039760977, + 0.47571906 0.87863714 0.041089606, + 0.47368383 0.88052273 0.017416194, + 0.42327791 0.90582275 0.017916497, + 0.42294484 0.90605271 0.013643796, + 0.36381698 0.93136489 0.014024998, + 0.36383992 0.93134779 0.014549197, + 0.41185793 0.91113687 0.014233498, + 0.40045515 0.91612631 0.018664908, + 0.45891419 0.88829631 0.018098006, + 0.45911899 0.88809401 0.0223336, + 0.51722687 0.85557783 0.021515895, + 0.51767105 0.85516214 0.026729004, + 0.56555206 0.82431012 0.025764704, + 0.56773907 0.82168615 0.050043207, + 0.61412287 0.78775084 0.04797639, + 0.61738092 0.78176886 0.087625891, + 0.6612618 0.7454868 0.083559178, + 0.6586712 0.74691719 0.090922825, + 0.70015901 0.70875502 0.086277202, + 0.70252317 0.70070815 0.12437603, + 0.74143177 0.66070074 0.11727495, + 0.742984 0.651425 0.153689, + 0.77913052 0.61011165 0.14394191, + 0.77989483 0.59989589 0.17857495, + 0.81279516 0.55833709 0.16620405, + 0.81290799 0.55013102 0.191145, + 0.78549784 0.58458287 0.20311595, + 0.78537101 0.57773 0.222307, + 0.75553131 0.61141026 0.23526609, + 0.75519884 0.60323989 0.25646895, + 0.72318602 0.63559502 0.270224, + 0.72259277 0.62602478 0.29317689, + 0.68837082 0.65689284 0.30763194, + 0.68745768 0.64570969 0.33235684, + 0.65062499 0.67520601 0.34753999, + 0.64933205 0.66215503 0.37405702, + 0.60964489 0.6901648 0.3898789, + 0.60791975 0.67499578 0.41810784, + 0.5659579 0.7008698 0.4341349, + 0.56380802 0.683635 0.46342599, + 0.51957911 0.70723915 0.47942713, + 0.51701808 0.68777007 0.50957304, + 0.47028676 0.70909363 0.52537274, + 0.46733311 0.68707019 0.5563581, + 0.41815785 0.70594978 0.5716458, + 0.41488579 0.68125373 0.60312772, + 0.36404082 0.69735867 0.61738569, + 0.36060882 0.67021471 0.64867067, + 0.30851412 0.68351024 0.66153824, + 0.30507481 0.65394461 0.69230461, + 0.25178403 0.66455704 0.70354009, + 0.24850309 0.63247222 0.73363823, + 0.19426997 0.64051497 0.74296695, + 0.191349 0.60598499 0.77211899, + 0.13713795 0.61156076 0.77922171, + 0.13482004 0.57517618 0.80684328, + 0.081034631 0.57856721 0.81159931, + 0.079514295 0.54063994 0.83748788, + 0.026464906 0.54216814 0.83985317, + 0.025914406 0.50264013 0.86410719, + -0.026483495 0.5026319 0.86409479, + -0.02703391 0.54214919 0.83984733, + -0.080102205 0.54060405 0.83745509, + -0.081621878 0.5785709 0.8115378, + -0.135381 0.57516402 0.80675799, + -0.13769598 0.61152196 0.77915388, + -0.19190304 0.60592812 0.77202618, + -0.19482502 0.64045405 0.74287409, + -0.24903095 0.63239384 0.73352683, + -0.25231004 0.66443908 0.70346308, + -0.30557215 0.65381128 0.69221133, + -0.30900902 0.68333906 0.66148406, + -0.3610948 0.67002457 0.64859664, + -0.3645249 0.69713581 0.61735189, + -0.41528192 0.6810388 0.60309786, + -0.41855806 0.70573908 0.57161307, + -0.46770719 0.68685126 0.55631417, + -0.47066101 0.70883399 0.525388, + -0.51734596 0.68751395 0.50958592, + -0.51991278 0.70698863 0.47943476, + -0.56407189 0.68340582 0.46344289, + -0.56622493 0.70063794 0.43416095, + -0.60816312 0.67476416 0.4181281, + -0.60988694 0.68988097 0.39000294, + -0.64955598 0.66187203 0.37416899, + -0.65085405 0.67489707 0.34771103, + -0.68765444 0.64541537 0.3325212, + -0.68857193 0.65656495 0.30788198, + -0.72275221 0.62572622 0.29342112, + -0.72335303 0.63527298 0.27053401, + -0.75529981 0.6029799 0.25678295, + -0.75563967 0.61112177 0.23566692, + -0.78546399 0.57745802 0.22268499, + -0.78560013 0.58428907 0.20356503, + -0.8129878 0.54986489 0.19157095, + -0.81288815 0.55806905 0.16664901, + -0.7799899 0.59962791 0.17905898, + -0.77924937 0.60981631 0.14454907, + -0.74308634 0.65115231 0.15434808, + -0.74157596 0.66034997 0.11833499, + -0.70265818 0.70037121 0.12550603, + -0.70035201 0.70837402 0.087825097, + -0.65884972 0.74655867 0.092559054, + -0.65577883 0.75305182 0.053544387, + -0.61167723 0.78911531 0.056108717, + -0.60940194 0.79227185 0.030570196, + -0.56294495 0.82587987 0.031866997, + -0.5624308 0.82643872 0.025897091, + -0.50503212 0.86267716 0.027032806, + -0.50478721 0.86296129 0.022086008, + -0.44670278 0.89438957 0.022890288, + -0.44660985 0.89457172 0.016765594, + -0.39474601 0.91862899 0.017216399, + -0.39474508 0.91864121 0.016578203, + -0.4377622 0.89894444 0.016222807, + -0.43777013 0.89898825 0.013324203, + -0.40565884 0.9140237 -0.0012832995, + -0.40565914 0.91402429 0.00049874815, + -0.40585718 0.91393644 0.00049882825, + -0.40576106 0.91397911 0.00048504505, + -0.37668917 0.92619544 -0.016351307, + 0.22966994 0.97317177 -0.013726196, + 0.21821196 0.97587889 -0.0066264891, + 0.21821408 0.97589433 0.0036041413, + 0.2181821 0.97590148 0.0036041816, + 0.21813895 0.97568774 -0.021187395, + 0.26581612 0.96402246 0.0016319508, + 0.265811 0.96400702 0.0059104702, + 0.26593894 0.96397173 0.0059102187, + 0.26594496 0.96398687 0.0016391698, + 0.26575202 0.9640401 0.0016391203, + 0.3127681 0.94981927 -0.0044349912, + 0.31275609 0.94979423 0.0086386018, + 0.3128261 0.94977123 0.0086383717, + 0.3127481 0.94950837 -0.024953809, + 0.35897791 0.93334574 0.00068354281, + 0.35896087 0.93330866 0.0090518976, + 0.35889292 0.93333477 0.0090522077, + 0.35890996 0.9333719 0.00067533297, + 0.35895488 0.93335462 0.00067534577, + 0.35893819 0.93331742 0.0090550343, + 0.4003709 0.91625679 0.013286198, + 0.40429983 0.91454458 0.012242994, + 0.40433314 0.9146083 -0.0025186508, + 0.40430409 0.91462123 -0.0025034908, + 0.40427116 0.91455728 0.012243205, + 0.44657579 0.89459658 0.016338093, + 0.44667912 0.89439523 0.023131305, + 0.504798 0.86294901 0.022318101, + 0.50503093 0.86267787 0.027027896, + 0.56245178 0.8264246 0.025891988, + 0.56293792 0.82589787 0.031521898, + 0.60936725 0.79231131 0.03024001, + 0.61156189 0.78929883 0.054767586, + 0.65559793 0.75329888 0.052269693, + 0.65638417 0.75277019 0.049968813, + 0.6939888 0.71840483 0.04768759, + 0.69762623 0.71025121 0.094132036, + 0.73681635 0.6702323 0.088828146, + 0.73887998 0.66203803 0.12554701, + 0.7753588 0.62046289 0.11766297, + 0.77660912 0.61122906 0.15256901, + 0.8098371 0.56919104 0.14207602, + 0.81032485 0.55920589 0.17510696, + 0.83803213 0.52069008 0.16304602, + 0.83778089 0.52780795 0.13979198, + 0.8074342 0.57029414 0.15104502, + 0.80649418 0.5794121 0.11768103, + 0.77292418 0.6218031 0.12629002, + 0.77119291 0.63004893 0.091103889, + 0.73436517 0.67176819 0.09713652, + 0.73109674 0.68027776 0.052151881, + 0.68835485 0.72325182 0.055446487, + 0.68717098 0.72539097 0.040050998, + 0.63500404 0.77133411 0.042587705, + 0.63473392 0.77186787 0.036509395, + 0.57947314 0.81408119 0.038506109, + 0.57948315 0.81398129 0.040419016, + 0.61351687 0.78870982 0.039164089, + 0.61359912 0.78898519 0.031600706, + 0.65067983 0.75874382 0.030389393, + 0.65084481 0.75913185 0.010948597, + 0.65237194 0.75780886 0.011682899, + 0.65241891 0.75785691 0.0015944497, + 0.65230119 0.75795817 0.0015943703, + 0.65227276 0.75793171 0.0089245569, + 0.65213674 0.75804871 0.0089260573, + 0.65216517 0.75807518 0.0016771203, + 0.67920083 0.73378479 -0.015687795, + 0.75619382 0.65409684 -0.018115597, + 0.75105029 0.66008723 -0.014440405, + 0.99457622 0.10278302 -0.015929503, + 0.99717462 0.075118467 0.00016995794, + 0.99717301 0.075116903 -0.00185374, + 0.99717474 0.075094186 -0.0018552395, + 0.99717635 0.075096034 0.00018044306, + 0.99711013 0.075969808 0.00017974702, + 0.99704921 0.075973816 0.010996102, + 0.99770278 0.067233682 0.0082912985, + 0.99766463 0.067191079 0.012275595, + 0.99349838 0.11199304 0.020460807, + 0.99330467 0.11183796 0.028950788, + 0.98685485 0.15645199 0.040500097, + 0.98644203 0.15616301 0.050450899, + 0.97849888 0.19626397 0.063405991, + 0.97863549 0.19645809 0.060637329, + 0.97103 0.228329 0.0704742, + 0.97127163 0.22941791 0.063236676, + 0.96310502 0.25944999 0.0715148, + 0.96313787 0.26005098 0.068840295, + 0.95227921 0.29506505 0.078109413, + 0.95210755 0.29071084 0.094754554, + 0.92607933 0.35100311 0.13847004, + 0.93953598 0.31855801 0.12567, + 0.93992877 0.3245649 0.10578997, + 0.92358714 0.36738604 0.10961001, + 0.93752366 0.33339888 0.099470764, + 0.93748862 0.34052989 0.071794376, + 0.91750854 0.38916123 0.08204715, + 0.91746789 0.39049393 0.075941391, + 0.92929423 0.36254808 0.070506819, + 0.9290961 0.36118203 0.079549104, + 0.94036174 0.33221391 0.073168889, + 0.94003421 0.3317261 0.079332225, + 0.95328176 0.29379794 0.070261784, + 0.95435274 0.29460195 0.049198888, + 0.9677971 0.25125304 0.015513401, + 0.96712863 0.2508139 0.041886285, + 0.97860926 0.20479704 0.019548405, + 0.97815514 0.20452502 0.037175305, + 0.96755534 0.24858609 0.045184016, + 0.96656334 0.24787009 0.065694526, + 0.95512265 0.28632492 0.075886473, + 0.95539588 0.28671396 0.070807993, + 0.94537312 0.31648204 0.078159511, + 0.94560689 0.31778398 0.069577396, + 0.93494034 0.34659511 0.075885527, + 0.93492812 0.34531802 0.081639208, + 0.95018226 0.30333307 0.071713313, + 0.95016623 0.30272505 0.074442916, + 0.95956337 0.27334908 0.067218922, + 0.959315 0.27213901 0.075200297, + 0.96811122 0.24147105 0.066726014, + 0.96790433 0.24118209 0.070657022, + 0.97758991 0.20202696 0.059185792, + 0.97843933 0.20263508 0.039945114, + 0.98692077 0.15816195 0.031178292, + 0.98727673 0.15839095 0.014030396, + 0.98474002 0.17238601 0.023879699, + 0.9850229 0.17241798 0.0013647799, + 0.98502254 0.17241991 0.0013647693, + 0.9850229 0.17241998 0.0011105998, + 0.98502612 0.17240201 0.0011095802, + 0.98502576 0.17240195 0.0013709996, + 0.97873867 0.20451193 -0.015670795, + 0.97536951 0.22054189 -0.003955388, + 0.97536415 0.22056603 -0.0039475504, + 0.97536689 0.22057097 0.0028163197, + 0.97537214 0.22054803 0.0028150803, + 0.96292323 0.26788107 0.031914707, + 0.96341777 0.26799494 0.0022376396, + 0.96337461 0.26814991 0.0022375192, + 0.96336848 0.26814911 0.004158562, + 0.9633975 0.26804513 0.004153532, + 0.95442474 0.29756895 0.022938995, + 0.95375526 0.29713506 0.045407612, + 0.93872601 0.340709 0.0520663, + 0.93763638 0.33983913 0.073126033, + 0.92256325 0.37721208 0.08116772, + 0.9229269 0.37779295 0.074015595, + 0.91055214 0.40568206 0.079479709, + 0.91069657 0.40708178 0.070114873, + 0.88969368 0.44993284 0.077495471, + 0.88968575 0.44983187 0.078170374, + 0.90320927 0.42286316 0.073483728, + 0.90283114 0.42220107 0.081500508, + 0.91956991 0.38580394 0.074474394, + 0.92062575 0.38670892 0.053892989, + 0.93794036 0.34347713 0.047868118, + 0.938676 0.34399101 0.0236148, + 0.93248612 0.36115903 0.0058131902, + 0.93249923 0.36116108 0.0028210906, + 0.93246287 0.36125496 0.0028210199, + 0.93245 0.36125299 0.0057644299, + 0.93247879 0.3611789 0.0057614585, + 0.92038041 0.39028516 0.02403021, + 0.9196189 0.38970894 0.049274594, + 0.90019768 0.43204185 0.05462718, + 0.89921814 0.43112707 0.074406609, + 0.88081121 0.46657011 0.080523625, + 0.88118201 0.46729401 0.071795203, + 0.86628002 0.493765 0.075862303, + 0.86628282 0.49387589 0.075103983, + 0.89745623 0.43609008 0.066316515, + 0.89775461 0.4329398 0.08123906, + 0.92048573 0.3840729 0.072069488, + 0.92079866 0.37834084 0.094805263, + 0.90178579 0.41922191 0.10504898, + 0.9011426 0.42762581 0.071261659, + 0.87545413 0.47672707 0.079444304, + 0.87500125 0.47984713 0.064185418, + 0.84023684 0.53743291 0.071888283, + 0.84023958 0.53731775 0.072711863, + 0.85663986 0.51125497 0.069185093, + 0.85629684 0.51048988 0.078458577, + 0.87656826 0.47569212 0.073110312, + 0.87744099 0.47658601 0.054435201, + 0.89896888 0.43518293 0.049706094, + 0.89971697 0.43580201 0.0242058, + 0.89257157 0.45084679 0.0072994367, + 0.87668413 0.48047906 0.023765303, + 0.87597531 0.47983617 0.049239218, + 0.85219502 0.520491 0.0534111, + 0.85144287 0.51964194 0.07083299, + 0.82922 0.553801 0.075489402, + 0.82951981 0.55458587 0.065813683, + 0.8118788 0.57975787 0.068800986, + 0.81186932 0.57987219 0.067945525, + 0.84985715 0.52343214 0.061332215, + 0.8504653 0.52039319 0.076809332, + 0.87925285 0.47124994 0.069555789, + 0.88029331 0.46254617 0.10552104, + 0.90343279 0.41799092 0.095356077, + 0.903602 0.41320401 0.112986, + 0.88250071 0.45365685 0.12404796, + 0.88209414 0.46121407 0.095872417, + 0.85612887 0.50594693 0.10517099, + 0.85465097 0.51484501 0.067129299, + 0.82309502 0.56313699 0.073425896, + 0.82233709 0.56605709 0.057802808, + 0.78120416 0.62104613 0.063417912, + 0.78122109 0.62093306 0.064310506, + 0.80020398 0.59653699 0.061783802, + 0.79995912 0.59575707 0.071686104, + 0.8237769 0.56285393 0.067726992, + 0.82440013 0.56364006 0.051715106, + 0.8505069 0.52376395 0.048056394, + 0.85115832 0.52441919 0.022671407, + 0.84414017 0.53606814 0.0076339017, + 0.84416187 0.53607893 0.0031790696, + 0.84417659 0.53605574 0.0031790885, + 0.84415483 0.5360449 0.0076434482, + 0.84408742 0.53615123 0.0076462235, + 0.84410918 0.53616214 0.0031601707, + 0.81681103 0.57680303 -0.0108668, + 0.81682402 0.576828 0.0082495902, + 0.8167879 0.57687896 0.0082507692, + 0.78737968 0.61606973 0.022164693, + 0.78757715 0.61620909 0.0029418408, + 0.78757489 0.61621195 0.0029418296, + 0.78754532 0.61619323 0.0088540632, + 0.78752202 0.61622298 0.00885465, + 0.78755212 0.61624104 0.0029362305, + 0.75640398 0.65405297 -0.0082287705, + 0.75639111 0.65405506 0.0091976812, + 0.75627601 0.65418798 0.0092000104, + 0.7233482 0.69031417 0.015289403, + 0.72343618 0.69038719 0.0023783306, + 0.72335708 0.69047004 0.0023782603, + 0.72332257 0.69044358 0.0095944041, + 0.72367078 0.69007874 0.0095888963, + 0.68922096 0.72445595 0.011747899, + 0.68898082 0.72397983 0.034039892, + 0.65334606 0.7562241 0.035556003, + 0.65321225 0.75587028 0.044430215, + 0.62093025 0.78251529 0.045996316, + 0.62092811 0.78262818 0.044062011, + 0.67428583 0.73730284 0.04151009, + 0.67454815 0.73666918 0.047993813, + 0.72455692 0.68775696 0.044807196, + 0.72567081 0.6853888 0.060365386, + 0.7659995 0.64036238 0.056399733, + 0.76884699 0.63159502 0.099810101, + 0.80280381 0.5889349 0.093068779, + 0.80418903 0.58073199 0.12661099, + 0.83489412 0.53777808 0.11724602, + 0.8355307 0.52886581 0.14896093, + 0.86328387 0.48581594 0.13683498, + 0.86335212 0.47912607 0.15830801, + 0.84038609 0.51462507 0.17003602, + 0.8402921 0.50954103 0.18514101, + 0.81537789 0.54412395 0.19770697, + 0.81515199 0.537925 0.214858, + 0.78792971 0.57183784 0.22840393, + 0.78751385 0.56437796 0.24758697, + 0.75783652 0.59748065 0.26210785, + 0.75717467 0.58866471 0.28312585, + 0.72530496 0.62039995 0.29838997, + 0.72434026 0.61006325 0.32117611, + 0.69019824 0.64030623 0.33709711, + 0.68886304 0.62818706 0.36173004, + 0.65207475 0.65701276 0.37832886, + 0.65031129 0.64288032 0.40472218, + 0.61062801 0.67017198 0.421904, + 0.60842425 0.65402925 0.44951716, + 0.56646514 0.67914319 0.46677813, + 0.56381583 0.66082579 0.49539983, + 0.51959091 0.68364096 0.51250392, + 0.51649511 0.66283119 0.54211414, + 0.46978718 0.68333626 0.5588842, + 0.46629587 0.65990382 0.58914787, + 0.41717505 0.67795408 0.60526305, + 0.41342109 0.65204316 0.63554919, + 0.36271408 0.66734016 0.65045816, + 0.3588419 0.63901085 0.6803658, + 0.30691105 0.65156621 0.69373417, + 0.303058 0.62063301 0.723167, + 0.25004804 0.63057208 0.73474807, + 0.24640404 0.59705007 0.7634241, + 0.19261193 0.60450876 0.77296168, + 0.18944097 0.56901896 0.80020589, + 0.13574199 0.57414901 0.80742002, + 0.13324994 0.53692275 0.83304161, + 0.080103293 0.54001194 0.83783686, + 0.078470223 0.50106412 0.8618452, + 0.026107004 0.50244308 0.86421615, + 0.025517903 0.46198407 0.8865211, + -0.026037503 0.46197805 0.88650912, + -0.026627909 0.5024842 0.86417627, + -0.079012305 0.50109106 0.86178011, + -0.080643229 0.5400272 0.83777529, + -0.13380997 0.53691989 0.83295381, + -0.13630104 0.57413715 0.8073343, + -0.189973 0.56899202 0.80009902, + -0.19314392 0.60447574 0.77285469, + -0.24693485 0.59699762 0.7632935, + -0.25057694 0.63049179 0.73463684, + -0.30356088 0.62053776 0.72303778, + -0.30740982 0.65142858 0.69364256, + -0.35930988 0.63885975 0.68026078, + -0.36317989 0.66717374 0.65036875, + -0.41383922 0.65187228 0.63545227, + -0.41758585 0.67771477 0.60524774, + -0.46667606 0.65965807 0.58912206, + -0.47017118 0.68309826 0.5588522, + -0.51681697 0.66260397 0.54208499, + -0.51991314 0.68338919 0.5125131, + -0.56409812 0.66058016 0.49540612, + -0.56674689 0.6788758 0.46682489, + -0.60869592 0.65375394 0.44954994, + -0.61090213 0.6698792 0.4219721, + -0.65052927 0.64261323 0.40479615, + -0.65229696 0.65672594 0.37844393, + -0.68903399 0.62792999 0.36185101, + -0.69037402 0.64004499 0.33723301, + -0.72447801 0.609828 0.32131201, + -0.72544515 0.62013113 0.29860806, + -0.75728518 0.58842009 0.28333905, + -0.75794989 0.59718192 0.26246098, + -0.78761691 0.56408894 0.24791797, + -0.78803891 0.57151395 0.22883697, + -0.81522429 0.5376482 0.21527608, + -0.81545901 0.54383999 0.198153, + -0.84034312 0.50930107 0.18556902, + -0.84044421 0.51438713 0.17046805, + -0.86339498 0.47891501 0.158712, + -0.86333811 0.48557606 0.13734402, + -0.72605592 0.68740696 0.017738698, + -0.72563124 0.68675226 0.042785514, + -0.69172579 0.72076279 0.044904385, + -0.69171381 0.72073483 0.045533691, + -0.66058475 0.74925774 0.047335681, + -0.66058081 0.74912983 0.049370188, + -0.71199483 0.70066482 0.046176188, + -0.71224898 0.69989699 0.053344, + -0.75979799 0.64827901 0.049409799, + -0.76033473 0.64699775 0.057314079, + -0.79510897 0.604101 0.053514201, + -0.7967093 0.59913123 0.079348333, + -0.82825851 0.55549562 0.073569156, + -0.82965982 0.54818988 0.10560498, + -0.85818321 0.50407511 0.097107425, + -0.85884881 0.49636489 0.12649398, + -0.88442159 0.4522348 0.11524795, + -0.88455027 0.44658014 0.13467404, + -0.86121559 0.48659477 0.14674193, + -0.8608911 0.49512705 0.11711401, + -0.83277619 0.53874409 0.12743104, + -0.83178788 0.54669595 0.096190087, + -0.80067468 0.59003574 0.10381597, + -0.79889733 0.59736127 0.070162125, + -0.76449811 0.64022505 0.075196505, + -0.76267833 0.64490223 0.049225118, + -0.725124 0.68662101 0.0524095, + -0.72455657 0.68775761 0.044802476, + -0.67455095 0.73666692 0.047988694, + -0.67427629 0.73732835 0.041210819, + -0.62094873 0.78262973 0.043742783, + -0.62094414 0.78273416 0.041900512, + -0.65355873 0.75579363 0.040458381, + -0.65355206 0.75577313 0.040948205, + -0.68899584 0.7237038 0.039210688, + -0.68932593 0.72429192 0.015198698, + -0.68970907 0.72392309 0.015388402, + -0.68979478 0.72400278 0.0017719694, + -0.68983579 0.72396374 0.0017719994, + -0.68975902 0.72389299 0.0145446, + -0.72443795 0.68918991 0.014389498, + -0.72450691 0.68923897 -0.006271759, + -0.75735891 0.65299392 0.0025135498, + -0.75728434 0.65293831 0.013861206, + -0.75735515 0.65285617 0.013859204, + -0.760647 0.64897799 0.0156143, + -0.7600823 0.64818925 0.046105314, + -0.72823465 0.68360072 0.048624076, + -0.72818822 0.68351525 0.050485719, + -0.69858718 0.7135812 0.052706413, + -0.69857001 0.71342897 0.0549464, + -0.74777776 0.66198874 0.050984681, + -0.74799865 0.66111672 0.058504876, + -0.7923857 0.60764575 0.053772982, + -0.79288 0.60621703 0.0619854, + -0.82483584 0.56243986 0.057509184, + -0.82618898 0.55723 0.083105899, + -0.85515797 0.51269698 0.076464102, + -0.85619015 0.50550908 0.10676701, + -0.88215911 0.46078607 0.097321711, + -0.8825289 0.45340094 0.12478098, + -0.90531278 0.40951991 0.11270397, + -0.90528786 0.40433794 0.13024898, + -0.8864401 0.44055006 0.14191401, + -0.88633972 0.43697685 0.15314394, + -0.865457 0.47278899 0.165695, + -0.86527389 0.46828493 0.17891398, + -0.8425563 0.50313717 0.19222908, + -0.84224814 0.49760005 0.20739403, + -0.81755781 0.53152788 0.22153394, + -0.81707519 0.52482611 0.23863307, + -0.7900542 0.55805814 0.25374305, + -0.78934312 0.55007207 0.27268702, + -0.75982529 0.58248317 0.28875408, + -0.758825 0.57304198 0.30952799, + -0.72708392 0.60405993 0.32628298, + -0.72572505 0.59290308 0.34898302, + -0.69166791 0.62240297 0.36634696, + -0.68988699 0.60933501 0.390854, + -0.65316975 0.63735974 0.40882984, + -0.65094292 0.62235093 0.43468693, + -0.61133122 0.64878923 0.45315215, + -0.60863811 0.63167518 0.48015213, + -0.56670296 0.65593594 0.49859393, + -0.56352615 0.63643825 0.5266732, + -0.51931983 0.65838075 0.54483181, + -0.51567197 0.63626093 0.57380694, + -0.46906093 0.65585095 0.59147394, + -0.465069 0.63133103 0.62058997, + -0.41608679 0.64848268 0.63744968, + -0.41186208 0.62149215 0.66642118, + -0.36136097 0.63593692 0.68191093, + -0.35701904 0.60625505 0.71062803, + -0.30543181 0.61801362 0.72441059, + -0.30115703 0.58573508 0.75247514, + -0.24851088 0.59498268 0.76435465, + -0.24455789 0.56058276 0.79116267, + -0.19122805 0.56746912 0.80088121, + -0.18781798 0.53115892 0.82619286, + -0.13473403 0.53585213 0.83349216, + -0.13205591 0.49763966 0.85727239, + -0.079599634 0.50044322 0.86210239, + -0.077855542 0.46053326 0.88422155, + -0.026227705 0.46177712 0.88660824, + -0.025608104 0.42070705 0.90683514, + 0.025123809 0.42071214 0.90684628, + 0.02574419 0.46174383 0.88663971, + 0.077300481 0.46051487 0.88427979, + 0.079047441 0.50042731 0.86216253, + 0.13151397 0.49763787 0.85735685, + 0.13419099 0.53583497 0.83359087, + 0.18727398 0.53115791 0.82631689, + 0.19068795 0.5675059 0.80098385, + 0.24399203 0.56064105 0.79129612, + 0.24794994 0.59507388 0.76446581, + 0.30060598 0.58584493 0.75260991, + 0.30488813 0.61816627 0.72450924, + 0.35655296 0.60640997 0.71072996, + 0.36089492 0.63608783 0.68201685, + 0.41142586 0.62165374 0.66653979, + 0.4156549 0.64867979 0.6375308, + 0.46470326 0.63152236 0.62066936, + 0.46869919 0.65607226 0.59151524, + 0.51533705 0.63648707 0.57385707, + 0.51898605 0.65863305 0.54484504, + 0.56323385 0.63668483 0.52668786, + 0.56641012 0.65620619 0.49857113, + 0.60835892 0.63195193 0.48014194, + 0.6110521 0.64908618 0.45310313, + 0.65072596 0.62261891 0.43462795, + 0.65295082 0.63763583 0.40874892, + 0.68971223 0.60958725 0.39076915, + 0.69149196 0.62267894 0.36620998, + 0.72556382 0.59317386 0.34885791, + 0.72692084 0.60436088 0.32608891, + 0.75870001 0.57331097 0.30933601, + 0.75969583 0.58278185 0.28849193, + 0.78924584 0.55033785 0.27243194, + 0.78995311 0.55835706 0.25340003, + 0.81700253 0.52508968 0.23830186, + 0.8174811 0.53183407 0.22108203, + 0.8421948 0.49786988 0.20696296, + 0.84249586 0.50341797 0.19175798, + 0.86523443 0.46852821 0.17846809, + 0.86541086 0.47301894 0.16527899, + 0.88631469 0.43716484 0.15275194, + 0.88641024 0.44075412 0.14146703, + 0.90527213 0.40450707 0.12983301, + 0.90531921 0.40726009 0.12056703, + 0.92372537 0.36729813 0.10873704, + 0.9235909 0.36254197 0.12467199, + 0.9068709 0.39850393 0.13703899, + 0.90672088 0.39546093 0.14651899, + 0.88808721 0.43104109 0.15970205, + 0.88785714 0.42714405 0.17104901, + 0.86717314 0.46231607 0.18513401, + 0.86682415 0.45743611 0.19841404, + 0.84427029 0.49165916 0.21325807, + 0.8437528 0.48562589 0.22857994, + 0.81921172 0.51888484 0.2442349, + 0.81848013 0.51166105 0.26133004, + 0.79156387 0.54421294 0.27795497, + 0.79055762 0.53561777 0.29687086, + 0.76111019 0.56731009 0.31443709, + 0.75975585 0.5570789 0.33531192, + 0.72804374 0.58734179 0.35352787, + 0.72627592 0.57529193 0.37624794, + 0.69223779 0.60396987 0.3950029, + 0.69002604 0.59008408 0.41912407, + 0.65327507 0.61726207 0.43842807, + 0.65058523 0.60135925 0.46379519, + 0.61089689 0.62691784 0.48350689, + 0.60768926 0.60869926 0.51009721, + 0.56572914 0.63201219 0.5296331, + 0.56199008 0.61120504 0.55731106, + 0.51777989 0.63216782 0.57642686, + 0.51362401 0.60903603 0.60437202, + 0.46702304 0.62765509 0.62284708, + 0.46252611 0.60204214 0.65085715, + 0.41359916 0.61823922 0.66836822, + 0.40886378 0.58994472 0.69627267, + 0.35853708 0.60346812 0.7122342, + 0.35370803 0.57240605 0.73975807, + 0.30241495 0.58331186 0.75385183, + 0.29776901 0.55010903 0.78020102, + 0.245524 0.55861002 0.79225802, + 0.24126694 0.52336186 0.81724083, + 0.18849392 0.52962583 0.82702273, + 0.18482801 0.49232906 0.85055912, + 0.13242503 0.49654812 0.85784817, + 0.12955897 0.45733789 0.87980479, + 0.07790681 0.45982406 0.8845861, + 0.076065816 0.4193891 0.90461421, + 0.025344295 0.42047095 0.9069519, + 0.024693409 0.37908015 0.92503434, + -0.025095595 0.3790769 0.92502475, + -0.025747191 0.42055485 0.90690172, + -0.076510333 0.41946116 0.90454328, + -0.078353323 0.45996511 0.88447326, + -0.13004501 0.45746505 0.8796671, + -0.13290602 0.49662206 0.8577311, + -0.18539105 0.49238119 0.85040629, + -0.18904905 0.52961314 0.82690418, + -0.24181803 0.52333206 0.81709713, + -0.24607302 0.55857408 0.79211313, + -0.29828504 0.55005908 0.78003913, + -0.30292803 0.58325207 0.75369209, + -0.35420904 0.57233006 0.73957705, + -0.35902196 0.60328394 0.71214592, + -0.40933475 0.58974564 0.69616461, + -0.41406822 0.61802232 0.66827828, + -0.46292412 0.60183012 0.65077019, + -0.46741611 0.62741315 0.62279612, + -0.51396918 0.60879827 0.60431826, + -0.51812625 0.6319173 0.57639033, + -0.56230694 0.61095291 0.55726796, + -0.56604284 0.63171977 0.52964681, + -0.60795903 0.60841805 0.51011103, + -0.61117238 0.62664133 0.48351729, + -0.65078819 0.60111815 0.46382311, + -0.6534813 0.61700827 0.4384782, + -0.69019705 0.58984709 0.41917607, + -0.69241077 0.60371274 0.39509284, + -0.72642106 0.57505107 0.37633607, + -0.72819197 0.58709103 0.35363901, + -0.7598753 0.55684918 0.33542311, + -0.76122862 0.56704569 0.31462684, + -0.79065597 0.53537202 0.297052, + -0.79166311 0.54392904 0.27822804, + -0.81854701 0.51141697 0.26159799, + -0.81928283 0.51861089 0.24457794, + -0.84379989 0.48538795 0.22891097, + -0.84432191 0.49137595 0.21370597, + -0.86685812 0.45718807 0.19883703, + -0.86721283 0.46205488 0.18559995, + -0.88788772 0.42690685 0.17148194, + -0.88812369 0.43080387 0.16013893, + -0.90673625 0.39527309 0.14693102, + -0.90689009 0.39832306 0.13743801, + -0.92360586 0.36237898 0.12503499, + -0.92609948 0.35082379 0.13878891, + -0.92613065 0.35081187 0.13861096, + -0.90821987 0.38921395 0.15378298, + -0.90795922 0.38589808 0.16337904, + -0.88954097 0.42070401 0.178115, + -0.88916427 0.41647714 0.18956207, + -0.86867881 0.45086989 0.20521596, + -0.86814499 0.445602 0.218548, + -0.84576583 0.47903988 0.23494893, + -0.84503043 0.47264323 0.2500641, + -0.82063472 0.50511384 0.26724291, + -0.81964183 0.49742189 0.28418094, + -0.79285681 0.5291419 0.30230293, + -0.79153019 0.51989913 0.32122409, + -0.76217568 0.55072981 0.34027189, + -0.76044381 0.53973991 0.3611179, + -0.72879517 0.56910211 0.38076308, + -0.72662818 0.55637515 0.40306109, + -0.69261807 0.58413106 0.42316806, + -0.68996465 0.56946069 0.4468368, + -0.65323997 0.59566492 0.46739793, + -0.65004641 0.57876337 0.49241531, + -0.61041564 0.60327762 0.5132727, + -0.60665596 0.58390594 0.53946495, + -0.56473708 0.60616606 0.56003106, + -0.56049401 0.58449298 0.586698, + -0.51633304 0.60441607 0.60669708, + -0.51165986 0.58028787 0.63361681, + -0.46520311 0.59785914 0.65280217, + -0.46017995 0.57109892 0.67976493, + -0.41144714 0.58628523 0.69784021, + -0.40618891 0.55671185 0.72462583, + -0.35618702 0.56927705 0.74098206, + -0.35096309 0.53746915 0.7667802, + -0.30001813 0.54753816 0.7811473, + -0.295019 0.51354098 0.80575401, + -0.24328606 0.5213151 0.81795019, + -0.23871803 0.48515907 0.84121013, + -0.18658391 0.49082875 0.85104257, + -0.18265991 0.4525758 0.87281758, + -0.13094205 0.45635715 0.88010931, + -0.12792103 0.41663808 0.90002722, + -0.077037789 0.41884094 0.90478587, + -0.075106084 0.3779299 0.92278278, + -0.025270494 0.3788799 0.92510074, + -0.024589991 0.33703589 0.94117063, + 0.024235494 0.3370389 0.94117874, + 0.024915794 0.3788299 0.92513078, + 0.07471057 0.37788886 0.92283165, + 0.076639101 0.418713 0.90487897, + 0.12743205 0.41652414 0.90014929, + 0.13045396 0.45623186 0.8802467, + 0.18213904 0.45246813 0.8729822, + 0.18606506 0.49072117 0.85121828, + 0.23821403 0.48506507 0.84140712, + 0.242792 0.52126801 0.81812698, + 0.29449287 0.51351684 0.80596173, + 0.29950407 0.5475871 0.7813102, + 0.3504349 0.53753889 0.76697284, + 0.35566711 0.5693872 0.74114722, + 0.40577608 0.55681312 0.72477919, + 0.41103795 0.58638793 0.69799495, + 0.45978311 0.57121611 0.67993516, + 0.46482006 0.59804904 0.65290105, + 0.51130801 0.58048201 0.63372302, + 0.51598895 0.60465795 0.60674894, + 0.56016499 0.584741 0.58676499, + 0.56441104 0.60644203 0.56006104, + 0.60640097 0.58415693 0.53947991, + 0.61015993 0.60353696 0.51327193, + 0.64983916 0.57900214 0.49240813, + 0.65303296 0.59592396 0.46735695, + 0.68978107 0.56971204 0.44680005, + 0.69243497 0.58440393 0.42309093, + 0.72647494 0.55663097 0.40298393, + 0.72864091 0.56937593 0.38064894, + 0.7603147 0.53999585 0.36100689, + 0.76204413 0.55100006 0.34012902, + 0.79143131 0.52013916 0.32107911, + 0.79275566 0.52940577 0.30210584, + 0.81956911 0.49765307 0.28398603, + 0.82056189 0.50538892 0.26694596, + 0.8449809 0.47288394 0.24977598, + 0.84571409 0.47930905 0.23458603, + 0.86810881 0.44583988 0.21820596, + 0.86864185 0.45115095 0.20475397, + 0.88913798 0.416729 0.18913101, + 0.88950968 0.42096385 0.17765693, + 0.90794957 0.38610381 0.16294593, + 0.90820527 0.38941014 0.15337206, + 0.92611867 0.35098988 0.13823995, + 0.92566991 0.34552497 0.15410298, + 0.90932989 0.37999594 0.16947599, + 0.90896028 0.37639314 0.17921905, + 0.89068514 0.41046605 0.19544204, + 0.89016467 0.40587986 0.20704693, + 0.86980373 0.43951586 0.22420393, + 0.86909181 0.4338659 0.23757094, + 0.8468166 0.46652478 0.25545287, + 0.84585685 0.45963287 0.27067295, + 0.8215369 0.49129593 0.28931898, + 0.82026082 0.48296487 0.30645895, + 0.79351783 0.51383287 0.32604492, + 0.79185462 0.50386977 0.34508184, + 0.76250213 0.53380007 0.36557904, + 0.76041198 0.52218503 0.38613001, + 0.72873974 0.5506078 0.40714785, + 0.72616464 0.53714275 0.42914179, + 0.69209784 0.56392688 0.45054087, + 0.68897092 0.54832494 0.47398195, + 0.65218872 0.57349271 0.49573776, + 0.6484707 0.55553573 0.52044779, + 0.60875696 0.57897395 0.54240596, + 0.60448927 0.5587132 0.56783116, + 0.56252515 0.57987118 0.58933425, + 0.55775803 0.55723208 0.61514103, + 0.51359779 0.57604772 0.63591373, + 0.50837111 0.55077612 0.6619702, + 0.46196511 0.5672521 0.68177217, + 0.45636806 0.53917706 0.70782506, + 0.40785575 0.55326867 0.72632456, + 0.40213916 0.52283716 0.75161529, + 0.35238603 0.53441608 0.76826012, + 0.34674698 0.50175494 0.79246986, + 0.29620495 0.51093787 0.8069728, + 0.2908251 0.47599018 0.82997233, + 0.23967089 0.48299375 0.8421846, + 0.23476508 0.44580615 0.86379528, + 0.18334392 0.45084879 0.87356758, + 0.17920202 0.41207206 0.89335513, + 0.12832302 0.41538906 0.90054715, + 0.12515797 0.37531692 0.91840774, + 0.07526309 0.37721893 0.92306089, + 0.073244981 0.3359859 0.93901473, + 0.024450706 0.33679008 0.94126225, + 0.023742694 0.29484293 0.95525074, + -0.024004195 0.29484093 0.95524478, + -0.024711797 0.33689496 0.9412179, + -0.073562361 0.33608484 0.93895453, + -0.075581573 0.37735385 0.92297965, + -0.12558404 0.37544009 0.91829926, + -0.12875201 0.41557705 0.90039915, + -0.17966996 0.4122459 0.89318079, + -0.18380904 0.45103213 0.87337518, + -0.23527886 0.44596872 0.86357147, + -0.24017406 0.48308811 0.84198719, + -0.29134101 0.47606599 0.82974797, + -0.29671502 0.51098406 0.80675614, + -0.34723699 0.50178701 0.79223502, + -0.35286787 0.53441781 0.76803768, + -0.40258694 0.52282792 0.75138187, + -0.40828091 0.55314386 0.72618079, + -0.45681587 0.53902787 0.70764983, + -0.46240282 0.56705582 0.68163878, + -0.50874007 0.55058807 0.66184306, + -0.51396006 0.57582808 0.63582003, + -0.55807364 0.55701667 0.61504966, + -0.56284004 0.57964504 0.58925605, + -0.60476214 0.5584951 0.5677551, + -0.60901904 0.57869905 0.54240507, + -0.64869392 0.55527395 0.52044892, + -0.65241176 0.5732078 0.49577382, + -0.68916994 0.54804796 0.47401294, + -0.69229692 0.56362891 0.45060793, + -0.72632062 0.53687179 0.4292168, + -0.72889817 0.55032915 0.40724108, + -0.76052487 0.52194291 0.38623494, + -0.76262128 0.53356117 0.36567912, + -0.79195184 0.50364989 0.34517992, + -0.79361516 0.51358712 0.32619509, + -0.82033086 0.48274994 0.30660996, + -0.82160771 0.49105781 0.2895219, + -0.84591669 0.45941082 0.27086291, + -0.8468731 0.46624407 0.25577804, + -0.86912769 0.43362284 0.23788291, + -0.86984199 0.439248 0.22458, + -0.89018142 0.40565917 0.2074071, + -0.89070439 0.41021922 0.19587208, + -0.9089669 0.37618494 0.17962198, + -0.90933889 0.37977093 0.16993198, + -0.92567301 0.34533 0.154521, + -0.9278329 0.33336198 0.16731998, + -0.94095451 0.30256087 0.15185992, + -0.94173086 0.30968896 0.13128498, + -0.95357662 0.27726492 0.11753996, + -0.95399511 0.28216904 0.10136101, + -0.96448678 0.24857894 0.089295477, + -0.96471924 0.25212005 0.075843714, + -0.97391498 0.21729399 0.065367401, + -0.97388846 0.2169531 0.066878729, + -0.98087525 0.18600105 0.057337016, + -0.98066938 0.18508406 0.063494921, + -0.98707521 0.15158603 0.05200281, + -0.98708552 0.15160093 0.051762573, + -0.99310189 0.11096498 0.037887797, + -0.9934209 0.11124098 0.027211396, + -0.99760813 0.06714461 0.016424801, + -0.99769467 0.06722188 0.0092979958, + -0.99974853 0.022213088 0.0030724786, + -0.99975288 0.022225197 0.00050844793, + -0.99999577 -0.0029003292 -6.6350884e-005, + -0.99999577 -0.0029002794 2.3094397e-006, + -0.99969876 0.024546094 -1.9545594e-005, + -0.99970311 0.024369104 7.5871205e-005, + -0.99854845 0.051458728 -0.015911408, + -0.99854785 -0.051483892 -0.015865197, + -0.9970569 -0.07666409 -0.00047176893, + -0.99688375 -0.076665185 -0.018577896, + -0.99687886 -0.076728493 -0.018579498, + -0.99187237 -0.12532805 0.021957507, + -0.99210924 -0.12537503 0.00058345712, + -0.99209064 -0.12552196 0.00058357377, + -0.99182034 -0.12550704 -0.023245808, + -0.99182862 -0.12544195 -0.023243792, + -0.98721611 -0.15884602 0.013128602, + -0.98696375 -0.15861796 -0.027256895, + -0.99346888 -0.11245499 -0.019324299, + -0.99303663 -0.11223996 -0.035782687, + -0.99757111 -0.066364504 -0.021157302, + -0.99734849 -0.066143431 -0.030349515, + -0.99972153 -0.021448091 -0.0098413052, + -0.99971563 -0.021422993 -0.010472996, + -0.99972576 0.021040494 0.010285997, + -0.99972862 0.021060392 0.009956466, + -0.99782389 0.059610393 0.028181197, + -0.99786925 0.059964515 0.025713105, + -0.99471426 0.094371222 0.040466912, + -0.99473089 0.094565682 0.039594695, + -0.99009466 0.12950796 0.054224983, + -0.98994738 0.12789305 0.060395923, + -0.98394549 0.16138007 0.076209739, + -0.98368949 0.15900907 0.084089935, + -0.97643775 0.19076596 0.10088398, + -0.97593665 0.18679094 0.11250196, + -0.96738124 0.21700504 0.13070004, + -0.96654677 0.21136196 0.14530496, + -0.95658511 0.24017303 0.16511202, + -0.95524752 0.23240089 0.18300791, + -0.94375122 0.25978005 0.20456804, + -0.94242185 0.25282398 0.21890897, + -0.92816877 0.28134993 0.24360794, + -0.92717034 0.2767041 0.25256708, + -0.91109711 0.30443904 0.27788302, + -0.90975767 0.29863387 0.2883729, + -0.89161032 0.32572711 0.31453612, + -0.88984221 0.31854609 0.32666409, + -0.86943388 0.34492296 0.35371298, + -0.86713499 0.33613399 0.36754701, + -0.84461689 0.36130497 0.39507094, + -0.84176081 0.35094291 0.4102169, + -0.81699413 0.37486202 0.43817705, + -0.81348819 0.36270109 0.45462611, + -0.78613514 0.38544807 0.48313707, + -0.78188699 0.37124801 0.50082701, + -0.75177318 0.39268708 0.5297491, + -0.74669993 0.37620193 0.54855394, + -0.71419966 0.39587283 0.57723773, + -0.70835125 0.37721515 0.59661323, + -0.67352283 0.3950139 0.62476486, + -0.66692007 0.37411204 0.64440507, + -0.62948281 0.39012092 0.67197984, + -0.62210923 0.36669412 0.69174826, + -0.58209181 0.38083485 0.71842474, + -0.574018 0.35477501 0.73799598, + -0.53220618 0.36680713 0.7630263, + -0.52364677 0.33836785 0.78185767, + -0.48030293 0.34836298 0.80495489, + -0.47145417 0.31766111 0.82269228, + -0.42667708 0.32577109 0.84369415, + -0.41773707 0.29283002 0.86008513, + -0.37180787 0.29919189 0.87877369, + -0.36307693 0.26434794 0.89347374, + -0.3168999 0.2690849 0.90948772, + -0.30871797 0.23289996 0.92219889, + -0.26281703 0.23625302 0.9354741, + -0.25534385 0.19860888 0.94623148, + -0.20981905 0.20084605 0.95688921, + -0.20452 0.169138 0.96413898, + -0.15940194 0.17058094 0.97236466, + -0.15608306 0.14544904 0.97697634, + -0.11256602 0.14631902 0.98281211, + -0.109549 0.114203 0.98739898, + -0.066471174 0.11464096 0.99118066, + -0.064519122 0.080003031 0.99470437, + -0.021861801 0.080150798 0.99654299, + -0.021193493 0.044698086 0.99877566, + 0.020891301 0.044698402 0.9987821, + 0.021555208 0.080142431 0.99655038, + 0.064130306 0.079996005 0.99473011, + 0.066074982 0.11466197 0.99120474, + 0.10921305 0.11422605 0.98743349, + 0.11223495 0.14653693 0.98281753, + 0.15585798 0.14566599 0.97697985, + 0.15919299 0.17097899 0.97232902, + 0.2044431 0.16953008 0.96408647, + 0.209686 0.200919 0.95690298, + 0.25520492 0.19868192 0.94625366, + 0.26261294 0.23597795 0.93560076, + 0.30850601 0.23263399 0.922337, + 0.31663308 0.26854506 0.90974021, + 0.36270109 0.26383406 0.89377826, + 0.37141913 0.29859111 0.87914228, + 0.41734207 0.29225004 0.86047411, + 0.4262782 0.32512915 0.84414339, + 0.47097811 0.3170611 0.82319617, + 0.47985017 0.34779513 0.80547029, + 0.52317989 0.33783391 0.78240085, + 0.53178406 0.36637703 0.7635271, + 0.57357216 0.35438213 0.73853123, + 0.58170289 0.38058692 0.71887082, + 0.62174892 0.36646396 0.69219393, + 0.62916577 0.39000386 0.67234474, + 0.66660976 0.37401587 0.64478177, + 0.67326015 0.3950451 0.62502819, + 0.70813608 0.37723807 0.59685403, + 0.71400696 0.39595494 0.57741994, + 0.74651825 0.37628916 0.54874116, + 0.75161791 0.39285594 0.52984393, + 0.78176016 0.3714031 0.5009101, + 0.78602684 0.3856689 0.48313689, + 0.81340283 0.36290291 0.45461789, + 0.81691486 0.37509093 0.43812895, + 0.84169984 0.3511509 0.41016391, + 0.84456527 0.36155111 0.39495614, + 0.86709768 0.33635488 0.36743289, + 0.8693971 0.34515902 0.35357302, + 0.88982153 0.31875017 0.32652122, + 0.89158797 0.325937 0.31438199, + 0.90975112 0.29880702 0.28821403, + 0.91109198 0.30462599 0.277695, + 0.92716736 0.27687109 0.25239509, + 0.92816538 0.28152409 0.24342009, + 0.94242924 0.25295907 0.21872105, + 0.94375777 0.25992894 0.20434795, + 0.94379377 0.25974894 0.20441096, + 0.92840725 0.29199106 0.22978505, + 0.92752659 0.28759184 0.23871589, + 0.91151386 0.31645596 0.26267496, + 0.91033369 0.31097189 0.27310991, + 0.89226979 0.33924291 0.29794094, + 0.89071232 0.33247212 0.30999011, + 0.87043017 0.36006409 0.3357161, + 0.86840719 0.35179609 0.3494401, + 0.84603888 0.37823793 0.37570494, + 0.84345913 0.36826503 0.39109805, + 0.81886184 0.39349091 0.4178879, + 0.81569469 0.38182384 0.43457186, + 0.78852165 0.40593183 0.46200979, + 0.78469145 0.39237124 0.4799003, + 0.754758 0.415232 0.50786102, + 0.75016868 0.39948285 0.5269348, + 0.71787322 0.42058316 0.5547682, + 0.71246099 0.40240899 0.574862, + 0.67776394 0.42165893 0.60236192, + 0.67162526 0.40127715 0.62281322, + 0.63431495 0.41870794 0.64986795, + 0.62746108 0.39593405 0.67046905, + 0.58746308 0.41149607 0.69682008, + 0.57994211 0.38617408 0.71731216, + 0.53807104 0.39956206 0.74217904, + 0.52998424 0.37160018 0.76225334, + 0.48647895 0.38285494 0.78534091, + 0.47806188 0.35254091 0.80446982, + 0.43300408 0.36179909 0.82559615, + 0.4245168 0.32940584 0.84337258, + 0.37807307 0.33681202 0.86233312, + 0.36972591 0.30235693 0.87856877, + 0.32295799 0.307978 0.89490098, + 0.31503788 0.2718119 0.90932369, + 0.268347 0.27589199 0.92297, + 0.26118797 0.23870097 0.93530887, + 0.2147159 0.24151789 0.94634354, + 0.20845801 0.20309 0.95671302, + 0.16244498 0.20489398 0.9652099, + 0.158235 0.17244799 0.97222602, + 0.11310998 0.17352799 0.9783119, + 0.11067495 0.14756493 0.98284054, + 0.066928968 0.14814393 0.98669851, + 0.065093905 0.11527002 0.99119914, + 0.021877 0.115488 0.99306798, + 0.021224495 0.080336981 0.99654174, + -0.021546599 0.080336392 0.99653488, + -0.022208298 0.11547699 0.9930619, + -0.065477721 0.11525705 0.99117535, + -0.0673199 0.148003 0.98669302, + -0.11088697 0.14742497 0.98283774, + -0.11331595 0.17323191 0.97834051, + -0.15837505 0.17215405 0.97225535, + -0.16261199 0.20480397 0.9652009, + -0.20860003 0.20300002 0.9567011, + -0.21490495 0.24174494 0.94624275, + -0.26142192 0.23891991 0.93518764, + -0.26862001 0.27634501 0.922755, + -0.31535488 0.27224991 0.90908271, + -0.32329616 0.30854815 0.89458239, + -0.37014213 0.30290011 0.87820631, + -0.3784861 0.33738407 0.86192816, + -0.42495701 0.32995 0.84293801, + -0.43343115 0.36234313 0.82513332, + -0.47853923 0.35304618 0.80396438, + -0.48691183 0.38324186 0.78488368, + -0.53043276 0.37195581 0.76176763, + -0.53847474 0.39979881 0.74175864, + -0.58034396 0.38638595 0.71687293, + -0.58781993 0.41159093 0.69646293, + -0.62778896 0.39601895 0.67011195, + -0.63459992 0.41866693 0.64961594, + -0.67189574 0.40122685 0.62255377, + -0.67801106 0.42154706 0.60216206, + -0.71266079 0.40230986 0.57468385, + -0.71804607 0.42039907 0.55468404, + -0.75033027 0.39929914 0.5268442, + -0.75490868 0.41501185 0.50781679, + -0.78479713 0.39218205 0.47988206, + -0.78861982 0.40570891 0.46203789, + -0.81577301 0.38161999 0.43460399, + -0.8189342 0.39325908 0.4179641, + -0.84350884 0.3680599 0.39118391, + -0.84608918 0.37803108 0.3758001, + -0.86843884 0.35161692 0.3495419, + -0.8704561 0.35985103 0.33587703, + -0.89073688 0.33227098 0.31013498, + -0.89229411 0.33902702 0.29811403, + -0.91034102 0.310794 0.27328801, + -0.91152412 0.31627703 0.26285502, + -0.92753088 0.28743696 0.23888597, + -0.92903399 0.295223 0.223023, + -0.91172576 0.32778192 0.24761894, + -0.91068888 0.32258996 0.25803396, + -0.892703 0.351915 0.28149101, + -0.89133477 0.34552091 0.29349193, + -0.87114269 0.37424189 0.31788889, + -0.86937171 0.36647588 0.33149388, + -0.84713787 0.39407495 0.35645798, + -0.84488201 0.38473499 0.37169001, + -0.82045281 0.41117391 0.39723191, + -0.81760859 0.39998582 0.41415879, + -0.79062814 0.42535806 0.44042906, + -0.78718197 0.41238099 0.45857, + -0.75747788 0.43654695 0.48544195, + -0.75336319 0.4215731 0.5046981, + -0.72126716 0.44404411 0.53160012, + -0.71640599 0.42678401 0.55192202, + -0.6819225 0.44742367 0.57861358, + -0.67628884 0.4277029 0.5997529, + -0.63912582 0.44655287 0.62618583, + -0.63281482 0.4245179 0.64755684, + -0.59289199 0.441502 0.67346501, + -0.58598125 0.41711414 0.69472426, + -0.54408085 0.43189192 0.71933681, + -0.53661895 0.40491495 0.74032694, + -0.49296519 0.41749814 0.76333529, + -0.48508319 0.38787714 0.78373832, + -0.43966699 0.398386 0.80497301, + -0.4316439 0.3665089 0.82422984, + -0.38470784 0.37503985 0.8434127, + -0.37677699 0.34105 0.86123401, + -0.32932699 0.347644 0.87788802, + -0.32172087 0.31166488 0.89406973, + -0.27417699 0.31655198 0.9080869, + -0.26718199 0.27898499 0.922378, + -0.21972799 0.28243399 0.93378299, + -0.21365005 0.24390607 0.94597226, + -0.16656592 0.24618287 0.95480353, + -0.16154996 0.20650496 0.96501678, + -0.11559401 0.20785204 0.97130615, + -0.11250102 0.17437701 0.97823113, + -0.067707382 0.17508896 0.98222178, + -0.066221721 0.14868806 0.98666435, + -0.022478005 0.14897703 0.98858523, + -0.021848906 0.11568903 0.99304521, + 0.021535499 0.11568999 0.99305189, + 0.022150092 0.14900994 0.98858762, + 0.066000901 0.14872199 0.98667401, + 0.067488506 0.17528401 0.98220211, + 0.11236697 0.17457196 0.97821176, + 0.11544401 0.20788403 0.97131711, + 0.16141894 0.20653793 0.96503162, + 0.16640602 0.24596304 0.95488811, + 0.21345297 0.24369197 0.94607186, + 0.21950497 0.28202197 0.9339599, + 0.2668789 0.27858791 0.92258567, + 0.27386209 0.31605712 0.90835428, + 0.32133415 0.31119215 0.89437342, + 0.328942 0.34714201 0.87823099, + 0.37631792 0.34057692 0.8616218, + 0.38426509 0.3745971 0.84381115, + 0.43115905 0.36609802 0.82466614, + 0.43921316 0.39804715 0.80538827, + 0.48462006 0.38756505 0.78417909, + 0.49253711 0.41727909 0.76373118, + 0.53620023 0.40471718 0.74073833, + 0.54369819 0.43179315 0.71968526, + 0.58561689 0.41703191 0.69508082, + 0.59257299 0.441558 0.67370898, + 0.63252091 0.42457893 0.64780396, + 0.63884884 0.44665888 0.62639284, + 0.67604083 0.42780891 0.59995687, + 0.68170184 0.44761989 0.57872188, + 0.71623224 0.42696014 0.55201119, + 0.72110003 0.44424707 0.53165704, + 0.75321519 0.42176908 0.50475514, + 0.75734586 0.43680394 0.48541695, + 0.78707689 0.41261595 0.45853895, + 0.79052532 0.42561015 0.44037014, + 0.81753385 0.40021092 0.4140889, + 0.82037681 0.41140291 0.39715192, + 0.84482914 0.38493606 0.37160203, + 0.84709281 0.3943229 0.35629091, + 0.86934072 0.36669689 0.3313309, + 0.87110716 0.37446108 0.3177281, + 0.89131021 0.34571609 0.29333705, + 0.89267778 0.35211891 0.28131595, + 0.91067672 0.32276189 0.25786191, + 0.91171432 0.32796913 0.24741308, + 0.9276951 0.29804304 0.22483803, + 0.9284479 0.30210397 0.21614297, + 0.94265276 0.27145293 0.19421396, + 0.94365454 0.27758387 0.18017592, + 0.92829663 0.31189689 0.20244892, + 0.92765987 0.30814597 0.21093397, + 0.91167569 0.33907789 0.23210691, + 0.91079414 0.33424702 0.24234903, + 0.89281458 0.36465782 0.26439887, + 0.89162469 0.35858488 0.27644593, + 0.87146968 0.38842186 0.29944789, + 0.86992383 0.38105091 0.31310192, + 0.84775215 0.40979809 0.33672208, + 0.84578329 0.40097615 0.35195011, + 0.8214395 0.42861074 0.37620476, + 0.81894988 0.41805294 0.39313194, + 0.7920748 0.44468588 0.41817692, + 0.78898531 0.43221015 0.43668815, + 0.759408 0.45767701 0.462419, + 0.75570214 0.44328406 0.48209307, + 0.72372681 0.46708989 0.50798291, + 0.7193532 0.45058912 0.52867812, + 0.68496972 0.47259676 0.55449873, + 0.67987704 0.45372805 0.57610607, + 0.64278984 0.47397089 0.60180789, + 0.63695592 0.45250294 0.62412196, + 0.59707308 0.47086707 0.64945203, + 0.59064186 0.44704887 0.67178082, + 0.54869324 0.46316519 0.69599837, + 0.54174787 0.43690392 0.71806979, + 0.49793112 0.45077011 0.7408582, + 0.49058989 0.42199191 0.76239383, + 0.44491506 0.43370306 0.7835511, + 0.43731493 0.40229294 0.80431086, + 0.39001292 0.41191092 0.82354081, + 0.38246191 0.3783229 0.84296781, + 0.33449385 0.38586882 0.85977858, + 0.32724988 0.35038087 0.87757671, + 0.27903593 0.35606992 0.89182574, + 0.27232313 0.31879416 0.9078604, + 0.22409403 0.32288903 0.91952413, + 0.21818204 0.28421807 0.93360424, + 0.17015894 0.28698692 0.94270062, + 0.16533205 0.24764407 0.95464021, + 0.118302 0.249336 0.961164, + 0.11467005 0.20901811 0.97116548, + 0.068916678 0.20990592 0.97528964, + 0.067036599 0.175871 0.98212802, + 0.022333793 0.17622393 0.98409665, + 0.021833612 0.14919707 0.98856646, + -0.022106089 0.14919592 0.9885605, + -0.022612611 0.17612308 0.98410845, + -0.067182921 0.17576906 0.98213637, + -0.069066688 0.20986596 0.97528774, + -0.11482698 0.20897597 0.97115588, + -0.118468 0.24945 0.96111399, + -0.16556399 0.24775197 0.9545719, + -0.17040505 0.28726605 0.94257122, + -0.21849105 0.28448606 0.93345022, + -0.224416 0.323275 0.91930997, + -0.27270898 0.31916296 0.90761489, + -0.27943194 0.35651791 0.89152277, + -0.32767397 0.35080996 0.87724686, + -0.33490813 0.38628516 0.85943031, + -0.38293201 0.37871099 0.84258002, + -0.39045805 0.41222006 0.82317513, + -0.437796 0.40257099 0.80391002, + -0.44536901 0.433902 0.78318298, + -0.49103576 0.42217079 0.76200765, + -0.49834889 0.45086288 0.74052083, + -0.54214001 0.436984 0.71772498, + -0.54904491 0.46311587 0.69575381, + -0.59096205 0.44699505 0.67153507, + -0.59737915 0.47077513 0.64923716, + -0.63723171 0.45240879 0.6239087, + -0.64303803 0.47378007 0.60169303, + -0.68009877 0.45354185 0.5759908, + -0.68517917 0.47236413 0.55443811, + -0.71952808 0.45037207 0.52862507, + -0.72389281 0.46683589 0.50797987, + -0.75583118 0.44305411 0.48210213, + -0.7595349 0.45742694 0.46245795, + -0.78908634 0.43198121 0.4367322, + -0.7921713 0.44443014 0.41826615, + -0.81903243 0.4178122 0.39321619, + -0.82151914 0.42834207 0.37633705, + -0.84582698 0.400754 0.35209799, + -0.84780014 0.40957806 0.33686903, + -0.8699584 0.38085419 0.31324515, + -0.87150586 0.38821495 0.29961097, + -0.89165014 0.35840103 0.27660203, + -0.89283973 0.36445689 0.26459092, + -0.91080612 0.33407804 0.24253704, + -0.91168529 0.33888012 0.23235808, + -0.92766356 0.30797485 0.2111679, + -0.9287799 0.31487596 0.19550197, + -0.91141671 0.34958288 0.21705192, + -0.91068143 0.34514219 0.22701611, + -0.89269972 0.37650785 0.24764691, + -0.89169788 0.37088597 0.25945798, + -0.87156773 0.40173185 0.2810359, + -0.87023157 0.39474881 0.29473785, + -0.84810811 0.42454106 0.31698203, + -0.84639573 0.41617584 0.33228287, + -0.82213467 0.44488585 0.35520589, + -0.81998229 0.43498716 0.37204212, + -0.79321998 0.46276 0.39579701, + -0.79052389 0.45100093 0.41433093, + -0.76108509 0.47767505 0.43883505, + -0.75778085 0.46389288 0.45888087, + -0.7259562 0.48894012 0.48365811, + -0.72204 0.47315601 0.50475901, + -0.68780226 0.49644017 0.52959919, + -0.68324304 0.47847506 0.55158007, + -0.64630693 0.50002396 0.57642293, + -0.64105892 0.47955993 0.59922093, + -0.60126686 0.49927789 0.62385887, + -0.59536594 0.47621194 0.64711791, + -0.55342317 0.49366418 0.67083424, + -0.54701489 0.46819088 0.69395381, + -0.50312698 0.48334101 0.71641099, + -0.49634799 0.45549399 0.73902899, + -0.45046422 0.46843821 0.76003134, + -0.44343105 0.43805805 0.78196812, + -0.39572209 0.44884112 0.80121517, + -0.38861606 0.41588807 0.82220113, + -0.340096 0.42445901 0.83914798, + -0.33321679 0.38941577 0.85867447, + -0.28433505 0.3959721 0.87313217, + -0.27793291 0.35910287 0.89095372, + -0.22880693 0.36391488 0.9028917, + -0.22311589 0.32536885 0.91888756, + -0.17406301 0.32868704 0.92826015, + -0.16933593 0.28887984 0.94227052, + -0.12120596 0.29095292 0.94902867, + -0.11768098 0.25057897 0.96091688, + -0.070828326 0.25169909 0.96521038, + -0.068610094 0.21048297 0.97518688, + -0.023057012 0.2109241 0.97723049, + -0.022421489 0.1763529 0.98407155, + 0.022225998 0.17635399 0.9840759, + 0.022861501 0.21099803 0.9772191, + 0.068434089 0.21055897 0.97518289, + 0.070644811 0.25160202 0.96524912, + 0.11750097 0.25048393 0.96096379, + 0.12101303 0.29067606 0.94913822, + 0.16908398 0.28861198 0.94239789, + 0.17380498 0.32835796 0.92842489, + 0.22274986 0.32505479 0.91908747, + 0.22843695 0.3635439 0.90313476, + 0.2774789 0.35875389 0.89123571, + 0.28388703 0.39563406 0.87343115, + 0.33274913 0.38909715 0.85900033, + 0.33964416 0.42418122 0.8394714, + 0.38814199 0.41563299 0.82255399, + 0.39526606 0.44863605 0.8015551, + 0.44296816 0.43787614 0.7823323, + 0.45003411 0.46837312 0.76032621, + 0.49590695 0.45545194 0.73935091, + 0.50271612 0.48340213 0.71665817, + 0.54665595 0.46824995 0.69419694, + 0.55308414 0.49379012 0.67102116, + 0.59504175 0.47634682 0.64731675, + 0.60096192 0.49948493 0.62398696, + 0.64080781 0.47975188 0.59933591, + 0.64605993 0.50022894 0.57652193, + 0.68304503 0.478661 0.55166399, + 0.68761694 0.49667794 0.52961695, + 0.72187716 0.47338411 0.50477815, + 0.72579992 0.48920095 0.48362893, + 0.75765264 0.46413478 0.45884779, + 0.76096088 0.47794795 0.43875295, + 0.7904247 0.45125285 0.41424584, + 0.79311889 0.46301794 0.39569795, + 0.81990802 0.43521601 0.37193799, + 0.82206011 0.44513205 0.35507002, + 0.84634489 0.41638994 0.33214396, + 0.84805667 0.42476386 0.31682089, + 0.87019283 0.39494991 0.29458293, + 0.87152946 0.40194976 0.28084281, + 0.89167076 0.37107992 0.25927395, + 0.89267325 0.3767271 0.24740906, + 0.91067213 0.34532002 0.22678304, + 0.91140878 0.34979191 0.21674795, + 0.9274351 0.31790003 0.19698703, + 0.92796934 0.32138813 0.18863407, + 0.94225574 0.28882095 0.16951896, + 0.94298422 0.29432207 0.15542004, + 0.92746526 0.33064109 0.17459905, + 0.92702544 0.32738614 0.18287209, + 0.91092741 0.36018419 0.20119309, + 0.91031772 0.35600388 0.21114692, + 0.89226377 0.38834691 0.23032995, + 0.89143622 0.38310409 0.24201806, + 0.8712607 0.41495484 0.26213992, + 0.87014973 0.40844786 0.2756989, + 0.84800917 0.43927613 0.29650807, + 0.84654361 0.4313198 0.31197286, + 0.82228798 0.461099 0.33351201, + 0.82042813 0.45166805 0.35056204, + 0.79369479 0.48055488 0.37298191, + 0.7913748 0.46948588 0.39154691, + 0.7619791 0.49734005 0.41477805, + 0.75910699 0.48432499 0.434955, + 0.72735125 0.51058817 0.45854118, + 0.723858 0.49540499 0.480212, + 0.68968177 0.51993585 0.50398982, + 0.68559402 0.50268501 0.52656299, + 0.64869708 0.52551603 0.55047709, + 0.64398599 0.505952 0.57384199, + 0.60418105 0.52698904 0.59770209, + 0.598849 0.50489599 0.62165898, + 0.55689907 0.52363205 0.64472705, + 0.55097824 0.49880123 0.66904432, + 0.50695312 0.51521009 0.69105518, + 0.50064081 0.48799282 0.71499777, + 0.45455801 0.50212097 0.73569798, + 0.44801107 0.47253406 0.75894511, + 0.39996591 0.48442787 0.77804685, + 0.393332 0.45234001 0.80042398, + 0.34439003 0.46189907 0.81734014, + 0.33786902 0.42735207 0.83857912, + 0.28837806 0.4347631 0.85312319, + 0.28228009 0.39831915 0.87273127, + 0.23244694 0.4038319 0.88480973, + 0.22701903 0.36576304 0.90259612, + 0.17717502 0.36962703 0.91213214, + 0.17263201 0.33008003 0.92803311, + 0.12358303 0.33254209 0.93495625, + 0.12014206 0.29188314 0.94887847, + 0.072252363 0.29324386 0.95330352, + 0.070114583 0.25230294 0.96510476, + 0.023454696 0.25285497 0.96721989, + 0.022707701 0.211191 0.97718102, + -0.022844601 0.21119003 0.9771781, + -0.023589389 0.25290087 0.96720451, + -0.070339352 0.25234485 0.9650774, + -0.072481811 0.29340002 0.95323813, + -0.120426 0.292034 0.94879597, + -0.12386803 0.33275908 0.93484122, + -0.17297406 0.33028811 0.92789537, + -0.17751996 0.36990392 0.91195273, + -0.22746105 0.3660211 0.90238023, + -0.23288989 0.40411583 0.88456357, + -0.28277186 0.39858282 0.8724516, + -0.28886497 0.43503493 0.85281986, + -0.33833385 0.42760879 0.83826059, + -0.3448351 0.46208513 0.81704718, + -0.393812 0.452499 0.800098, + -0.40042105 0.48448506 0.77777714, + -0.44845399 0.47257501 0.75865799, + -0.45498306 0.50210208 0.73544806, + -0.50104004 0.48796207 0.71473908, + -0.50733209 0.51511204 0.69085008, + -0.5513078 0.49870482 0.66884476, + -0.55720574 0.52344775 0.64461172, + -0.59915304 0.50470006 0.62152505, + -0.60447693 0.52675992 0.59760493, + -0.64424092 0.50573295 0.57374895, + -0.64893603 0.52522403 0.55047405, + -0.6857962 0.50241011 0.52656209, + -0.68988705 0.51966709 0.50398606, + -0.72401094 0.49516794 0.48022595, + -0.72750205 0.51033205 0.45858705, + -0.75922179 0.48409489 0.43501091, + -0.76209712 0.49710405 0.41484407, + -0.79146802 0.469271 0.39161599, + -0.79378819 0.48032212 0.37308308, + -0.82049614 0.45146307 0.35066703, + -0.82235771 0.46087983 0.33364287, + -0.84659082 0.43113092 0.31210595, + -0.84805518 0.43906012 0.29669607, + -0.87018716 0.40824908 0.27587506, + -0.87129784 0.41473091 0.26237094, + -0.89146227 0.3829051 0.24223706, + -0.89228886 0.38811594 0.23062196, + -0.91032571 0.35581589 0.21142893, + -0.91093278 0.3599489 0.20158896, + -0.92702538 0.32718113 0.18323906, + -0.92780685 0.33336398 0.16745998, + -0.91024643 0.37000719 0.18586609, + -0.90975571 0.36612788 0.19569093, + -0.89162278 0.3993189 0.21343195, + -0.89095509 0.39447206 0.22492403, + -0.87071282 0.42722291 0.24359794, + -0.86981088 0.42121395 0.25691998, + -0.84764588 0.45295295 0.27627897, + -0.84644049 0.44555727 0.29157719, + -0.82219088 0.47628993 0.31168896, + -0.82061714 0.46737507 0.32885903, + -0.79392487 0.49725693 0.34988397, + -0.79193372 0.48675382 0.36866188, + -0.76260185 0.51565993 0.39055493, + -0.76013827 0.50342315 0.41079816, + -0.72847217 0.53078413 0.4331241, + -0.72545278 0.51649684 0.45491686, + -0.69138902 0.54216999 0.47752801, + -0.68776196 0.52563596 0.50068992, + -0.65095896 0.54965794 0.52357292, + -0.64675444 0.53093559 0.54755455, + -0.60705191 0.55318588 0.57050288, + -0.60228109 0.53211313 0.59507412, + -0.56034589 0.55209291 0.61741889, + -0.55502409 0.52840704 0.64244407, + -0.51098508 0.54603803 0.66388005, + -0.50519109 0.51965004 0.68901807, + -0.45895213 0.53497612 0.70934016, + -0.45289999 0.50621903 0.73391002, + -0.40461177 0.5192377 0.75278252, + -0.39846492 0.48808989 0.77652681, + -0.34910589 0.49867982 0.79337472, + -0.34305099 0.46515799 0.81605399, + -0.29300007 0.47347611 0.8306452, + -0.2872479 0.43764985 0.85202771, + -0.23666909 0.44392514 0.86424428, + -0.23149493 0.40623292 0.88395977, + -0.18078801 0.41069606 0.89366913, + -0.17644 0.371447 0.91153502, + -0.12642294 0.37433884 0.91863358, + -0.12310696 0.33378589 0.93457562, + -0.074096411 0.3354201 0.93915021, + -0.072002865 0.29401284 0.95308554, + -0.02412881 0.29469311 0.95528734, + -0.023408297 0.25312296 0.96715087, + 0.023235895 0.25312394 0.96715474, + 0.023958391 0.29458588 0.95532465, + 0.071730815 0.29391205 0.95313722, + 0.073822588 0.3352659 0.93922675, + 0.12276898 0.33364096 0.93467188, + 0.126081 0.374107 0.91877502, + 0.17605498 0.37122497 0.91169989, + 0.18039991 0.41041079 0.89387858, + 0.23104 0.405967 0.88420099, + 0.23621795 0.44366989 0.86449879, + 0.28673398 0.43741995 0.85231888, + 0.29250905 0.47336212 0.8308832, + 0.34255308 0.46506312 0.8163172, + 0.34862292 0.49863887 0.79361284, + 0.39799094 0.48806593 0.7767849, + 0.40415406 0.51926708 0.75300813, + 0.45245999 0.50626302 0.73415101, + 0.45852911 0.53508312 0.70953315, + 0.504803 0.51976198 0.68921798, + 0.51061583 0.54623181 0.66400474, + 0.5547142 0.52859116 0.64256024, + 0.56004006 0.55229205 0.61751807, + 0.60199207 0.53231704 0.59518409, + 0.60677093 0.55343193 0.57056296, + 0.64653915 0.53115511 0.5475961, + 0.65074706 0.54990005 0.52358204, + 0.68756121 0.5258792 0.50071019, + 0.69119298 0.54244798 0.477496, + 0.72529882 0.51674891 0.45487589, + 0.72831964 0.53105575 0.4330478, + 0.76001185 0.50367594 0.41072193, + 0.76247728 0.51594716 0.39041916, + 0.79182488 0.48702693 0.36853498, + 0.79381269 0.49753883 0.34973788, + 0.82053632 0.46762219 0.32870913, + 0.82210946 0.47655728 0.31149518, + 0.84638721 0.44578612 0.29138207, + 0.84758842 0.45318121 0.27608112, + 0.86977899 0.42140099 0.25672099, + 0.87068313 0.42745805 0.24329104, + 0.89092731 0.39469415 0.22464408, + 0.89159822 0.39959809 0.21301204, + 0.90974456 0.36636582 0.19529691, + 0.91023421 0.37027109 0.18540004, + 0.92643911 0.33660603 0.16854401, + 0.92678314 0.33959404 0.16046502, + 0.94128186 0.30525896 0.14424099, + 0.94172525 0.30982405 0.13100603, + 0.95357615 0.27737504 0.11728501, + 0.95399725 0.28241205 0.10066102, + 0.96449763 0.24876191 0.088666968, + 0.96472663 0.25243092 0.074707672, + 0.97393113 0.21751803 0.064375311, + 0.9738875 0.2169459 0.066914469, + 0.98087466 0.18599394 0.057367578, + 0.98066235 0.18505105 0.063698925, + 0.98706722 0.15157802 0.052176412, + 0.98699486 0.15146498 0.053846393, + 0.99304521 0.11093203 0.03943691, + 0.99331939 0.11115193 0.031011581, + 0.99759138 0.066813521 0.018641107, + 0.99767298 0.066906102 0.0131248, + 0.99974537 0.022145908 0.0043443013, + 0.99975026 0.022160506 0.0028855507, + 0.99965525 0.026096705 -0.0029155207, + 0.99965674 0.026036495 -0.0029197694, + 0.99966091 0.026038697 -0.00029376097, + 0.99965936 0.026098909 -0.00028897912, + 0.99928826 -0.023198506 -0.029746408, + 0.99972624 -0.023187406 -0.0031420006, + 0.99973178 -0.022948094 -0.0031239393, + 0.99973589 -0.022946699 -0.0012630599, + 0.99988055 -1.2309195e-005 -0.015458393, + 0.99457926 -0.10280802 -0.015579304, + 0.99740821 -0.071942411 0.0011380102, + 0.99734187 -0.071947694 -0.011522699, + 0.993626 -0.112613 -0.00507815, + 0.99251014 -0.12078101 -0.018321402, + 0.99267387 -0.12078799 -0.0029871895, + 0.99267989 -0.12073798 -0.0029982096, + 0.99251634 -0.12073105 -0.018317007, + 0.98554665 -0.16933294 -0.0049238582, + 0.9855569 -0.16932899 0.0022853597, + 0.98555964 -0.16931294 0.0022853492, + 0.98524851 -0.16928193 -0.025081089, + 0.98524237 -0.16931707 -0.025084609, + 0.98555374 -0.16934796 0.0022731796, + 0.97874433 -0.20453808 -0.014962906, + 0.95253462 -0.30410388 -0.014089495, + 0.96421945 -0.26508713 0.0031167914, + 0.96354336 -0.26493409 -0.037340716, + 0.95446521 -0.29832205 -0.0003386201, + 0.94918579 -0.31180093 -0.042736288, + 0.95003653 -0.31205285 -0.0073118769, + 0.95004791 -0.31201798 -0.0073262393, + 0.94919711 -0.31176704 -0.042733904, + 0.93356788 -0.35820797 0.011753698, + 0.93362379 -0.35823593 0.0036911492, + 0.93364024 -0.3581931 0.003691121, + 0.93257499 -0.35782599 -0.047586601, + 0.93256611 -0.35784903 -0.047588408, + 0.93363112 -0.35821703 0.0036861706, + 0.91483301 -0.40358299 -0.0141886, + 0.91370797 -0.403117 -0.0513262, + 0.9137277 -0.40307286 -0.051322781, + 0.9149003 -0.40355715 -0.0099496637, + 0.91625232 -0.40043816 -0.011447104, + 0.8702181 -0.49251705 -0.012146102, + 0.87091315 -0.49127007 -0.012807302, + 0.86944711 -0.49047905 -0.059094906, + 0.84570313 -0.53335303 -0.017913101, + 0.8458401 -0.53342205 0.0039481707, + 0.84583884 -0.5334239 0.0039481693, + 0.84415752 -0.5324167 -0.06269446, + 0.84417391 -0.53239095 -0.062692292, + 0.84585518 -0.53339809 0.0039526909, + 0.81864202 -0.57424599 -0.0081757, + 0.81696761 -0.57311571 -0.064047873, + 0.8169598 -0.57312685 -0.064048886, + 0.8185544 -0.57420731 -0.015965207, + 0.8149581 -0.57937407 -0.013006002, + 0.51472777 -0.85721856 -0.015220293, + 0.53675812 -0.84373617 0.0003213631, + 0.53281814 -0.83763719 -0.12028603, + 0.5328908 -0.83759171 -0.12028096, + 0.57549798 -0.81591201 -0.055584401, + 0.57641006 -0.81716013 0.00096707011, + 0.57750815 -0.81638432 0.00096644834, + 0.57393581 -0.81142372 -0.11040496, + 0.57389987 -0.81144881 -0.11040697, + 0.60911709 -0.79037815 -0.065412618, + 0.594684 -0.77084899 -0.228348, + 0.63620579 -0.73974484 -0.21913394, + 0.60028404 -0.69609904 -0.39383405, + 0.64241201 -0.667005 -0.37737399, + 0.58581513 -0.6051591 -0.53907609, + 0.46289501 -0.46593899 -0.75407499, + 0.58074689 -0.59334987 -0.55737686, + 0.55067587 -0.60838985 -0.57150489, + 0.44004387 -0.47934687 -0.75933385, + 0.46475205 -0.47265506 -0.74873406, + 0.33258688 -0.32759789 -0.8843447, + 0.35646087 -0.32455489 -0.87612772, + 0.19837607 -0.16164106 -0.96670538, + 0.21904607 -0.16091307 -0.96235436, + 0.10095295 -0.046828676 -0.99378854, + 0.095933452 -0.046851978 -0.99428451, + 0.18256405 -0.13483703 -0.97390425, + 0.16399007 -0.13528505 -0.97714138, + 0.32464591 -0.30914894 -0.89388579, + 0.30190396 -0.31159997 -0.9009769, + 0.4369958 -0.46737379 -0.76850265, + 0.41297886 -0.47323382 -0.77813768, + 0.52198517 -0.60680825 -0.59942925, + 0.5022012 -0.61520022 -0.60771924, + 0.38676792 -0.46638587 -0.79554683, + 0.41014194 -0.46124995 -0.7867859, + 0.27318707 -0.29524806 -0.91553122, + 0.29452199 -0.293309 -0.90951997, + 0.13292103 -0.10957303 -0.98505121, + 0.14961602 -0.10931101 -0.98268312, + 0.040527888 0.006868578 -0.99915475, + 0.038453691 0.006869148 -0.99923676, + 0.11988306 -0.084336534 -0.98919946, + 0.105062 -0.084478997 -0.99087101, + 0.26644799 -0.27732399 -0.92309099, + 0.246445 -0.278851 -0.92817402, + 0.38415 -0.45435899 -0.80373299, + 0.36132199 -0.45887199 -0.81171602, + 0.47382799 -0.611485 -0.63369799, + 0.45420778 -0.61862171 -0.64109468, + 0.33694184 -0.45097879 -0.82649159, + 0.35899112 -0.44705814 -0.81930733, + 0.221442 -0.26249999 -0.939179, + 0.24033706 -0.26129407 -0.93486023, + 0.080478691 -0.060428493 -0.99492288, + 0.07252714 -0.042501319 -0.9964605, + 0.041837201 -0.0150575 -0.99901098, + 0.21588589 -0.24509688 -0.94515651, + 0.19818403 -0.24603602 -0.9487831, + 0.33487508 -0.43924311 -0.8336212, + 0.31349012 -0.44265914 -0.8401053, + 0.42658892 -0.61317688 -0.6648578, + 0.40714508 -0.61922312 -0.67141318, + 0.29097304 -0.43408906 -0.85258514, + 0.31171203 -0.43111506 -0.84674412, + 0.17691799 -0.23007697 -0.95695591, + 0.19333901 -0.22935399 -0.95394802, + 0.039563183 -0.015058893 -0.99910355, + 0.032661911 0.0034930513 -0.99946034, + -0.035245705 0.099311113 -0.99443209, + -0.0311622 0.099325001 -0.99456698, + -0.0086439028 0.071022324 -0.99743736, + 0.02724221 0.07099852 -0.99710435, + 0.048082393 0.047718294 -0.9977029, + 0.094592348 0.047559522 -0.99437946, + 0.12042298 0.021632697 -0.99248689, + 0.1787409 0.02144039 -0.98366255, + 0.22123908 -0.017566806 -0.97506136, + 0.29243505 -0.017225804 -0.95613027, + 0.31924301 -0.040245101 -0.94681799, + 0.39764115 -0.038965516 -0.91671336, + 0.4186739 -0.056220386 -0.90639478, + 0.50090891 -0.053580791 -0.86383986, + 0.55223012 -0.095661722 -0.8281852, + 0.63229203 -0.088896111 -0.76961315, + 0.66609395 -0.11834698 -0.73641896, + 0.7362982 -0.10736502 -0.66808516, + 0.7540881 -0.12455702 -0.64485407, + 0.81227732 -0.11061703 -0.5726862, + 0.81989831 -0.11906604 -0.55999118, + 0.8669318 -0.10365798 -0.48752889, + 0.86852288 -0.10573398 -0.48423994, + 0.90613639 -0.090233043 -0.41324919, + 0.90472078 -0.088023581 -0.41681191, + 0.93444097 -0.073583297 -0.34843299, + 0.93175489 -0.068499289 -0.35656798, + 0.95518976 -0.055841785 -0.29067895, + 0.952353 -0.049240299 -0.30099699, + 0.97071087 -0.038787197 -0.23709898, + 0.96820486 -0.031464096 -0.24817197, + 0.98236591 -0.023516396 -0.18548399, + 0.98051554 -0.016457593 -0.19575091, + 0.99084479 -0.011310497 -0.13453098, + 0.98970187 -0.0051969797 -0.14304999, + 0.99656999 -0.0030044799 -0.082699999, + 0.99609214 0.0012096001 -0.088311709, + 0.99960309 0.00038586505 -0.028171604, + 0.99954075 0.0020110996 -0.030235093, + 0.99957013 -0.0019459903 0.029256204, + 0.99951202 -0.0034308999 0.031048801, + 0.99579126 -0.010066103 0.091095723, + 0.99566233 -0.011178404 0.09236633, + 0.98859298 -0.0180953 0.14952099, + 0.98822337 -0.020117607 0.15169007, + 0.97806388 -0.027386297 0.20649697, + 0.97719836 -0.030949811 0.21006107, + 0.96405274 -0.038730994 0.26287293, + 0.96257091 -0.043711197 0.26748198, + 0.94681185 -0.051897291 0.31757498, + 0.9445855 -0.058332827 0.32304114, + 0.92633063 -0.066941574 0.37071589, + 0.92322677 -0.074925289 0.3768799, + 0.90257168 -0.083950073 0.42227584, + 0.89842379 -0.093674481 0.42902192, + 0.87551951 -0.10307206 0.47206128, + 0.87016988 -0.11470999 0.47921395, + 0.84545785 -0.12432198 0.51936996, + 0.83940589 -0.13675098 0.52601993, + 0.81304353 -0.14648791 0.56347263, + 0.80707711 -0.15825002 0.56884408, + 0.77883768 -0.16810794 0.60427779, + 0.77114815 -0.18280701 0.60984606, + 0.74104118 -0.19280104 0.64318419, + 0.73204118 -0.20958005 0.64822221, + 0.70070994 -0.21948197 0.67884696, + 0.69057405 -0.23804103 0.68296707, + 0.6581322 -0.24779706 0.71095616, + 0.64690977 -0.26811892 0.71387678, + 0.61318201 -0.277744 0.73950398, + 0.60095197 -0.29979196 0.74093294, + 0.56620514 -0.30916205 0.76408815, + 0.55323595 -0.33260596 0.76374286, + 0.51819313 -0.3414861 0.78413218, + 0.52035302 -0.33744299 0.78445202, + 0.48909113 -0.34466809 0.80124515, + 0.50418508 -0.31288102 0.80492413, + 0.47112983 -0.31957188 0.82213771, + 0.48383623 -0.28838614 0.82627839, + 0.44871399 -0.29448801 0.84376103, + 0.4592838 -0.26382887 0.84820557, + 0.42274806 -0.26916203 0.86535311, + 0.4314599 -0.23877995 0.8699578, + 0.39335209 -0.24334706 0.88659823, + 0.40042016 -0.21305807 0.8912183, + 0.36047113 -0.21688108 0.9072063, + 0.366025 -0.18682 0.91166002, + 0.32429001 -0.18990301 0.9267, + 0.32851684 -0.15992293 0.93086058, + 0.28559703 -0.16226901 0.94451213, + 0.2886799 -0.13220796 0.94825363, + 0.24478903 -0.13388501 0.96028811, + 0.24690303 -0.10363901 0.96348214, + 0.20207496 -0.10474398 0.97375274, + 0.20339188 -0.074361354 0.97626942, + 0.15781493 -0.074997269 0.98461664, + 0.15849407 -0.044526722 0.98635548, + 0.11271197 -0.04480939 0.99261677, + 0.112966 -0.0130633 0.99351299, + 0.12401196 0.00032385089 0.99228066, + 0.12390795 0.00031812288 0.99229366, + 0.12389199 -0.015676599 0.99217188, + 0.123995 -0.0156764 0.99215901, + 0.172399 -0.0115081 0.98496002, + 0.17241204 0.0011598702 0.98502421, + 0.17239501 -0.015687 0.98490298, + 0.17239694 -0.015686994 0.98490262, + 0.20454793 -0.0030969689 0.97885162, + 0.2205459 -0.00016827592 0.97537655, + 0.22055893 -0.00016722294 0.97537363, + 0.22053006 -0.015546003 0.97525626, + 0.22051705 -0.015546104 0.97525924, + 0.26797804 -0.010100401 0.96337211, + 0.26799297 0.0013799199 0.96341985, + 0.26814911 0.0013798807 0.96337646, + 0.26811391 -0.015363694 0.96326464, + 0.26803491 -0.015363994 0.96328664, + 0.26806894 0.0013851597 0.96339875, + 0.30412185 -0.0029631886 0.95262855, + 0.400455 -0.00211811 0.91631401, + 0.49254301 -0.00232098 0.87028497, + 0.49408889 -0.0021162296 0.86940885, + 0.49403894 -0.013759998 0.86933088, + 0.49398601 -0.0137604 0.86936098, + 0.49403501 -0.0026531599 0.86943799, + 0.45085412 0.0015832403 0.89259624, + 0.45080388 -0.014154197 0.89251077, + 0.40649006 -0.0013953202 0.91365415, + 0.40644309 -0.014556804 0.91356021, + 0.40645006 -0.014556802 0.91355711, + 0.40649399 -0.0034338201 0.913647, + 0.36121303 0.0015201102 0.93248212, + 0.36116901 -0.0149253 0.93238097, + 0.36117697 -0.014925298 0.93237787, + 0.36122099 0.00151969 0.93247902, + 0.36116108 0.0015197103 0.93250221, + 0.31505296 -0.00074365886 0.94907385, + 0.31502414 -0.00074661232 0.94908345, + 0.31498513 -0.015170005 0.94897538, + 0.31501302 -0.015169902 0.94896615, + 0.34504613 -0.011337103 0.93851733, + 0.34432292 -0.042873889 0.93787175, + 0.39010081 -0.042048283 0.91981161, + 0.38857785 -0.071306176 0.91865265, + 0.43285584 -0.069762081 0.89875972, + 0.4303889 -0.09868478 0.89723277, + 0.47316182 -0.096315861 0.87569469, + 0.46963701 -0.124949 0.87397301, + 0.5111469 -0.12164297 0.85084182, + 0.50648206 -0.15007302 0.8490901, + 0.54651827 -0.14575608 0.82466543, + 0.54057986 -0.17418195 0.82306385, + 0.57880604 -0.16883402 0.79779613, + 0.57149321 -0.19747707 0.79649132, + 0.60779303 -0.19109704 0.77075911, + 0.59895301 -0.220119 0.76993698, + 0.63390505 -0.21259503 0.74361807, + 0.62346512 -0.24194206 0.7434752, + 0.65720993 -0.23323298 0.71671295, + 0.64500326 -0.26312208 0.71745223, + 0.67725474 -0.2533319 0.69075978, + 0.66299397 -0.28415298 0.69260097, + 0.69402409 -0.27326903 0.66607404, + 0.67744124 -0.30523011 0.66925925, + 0.70782185 -0.29311895 0.64270484, + 0.70383221 -0.30022311 0.64380622, + 0.73808038 -0.28515515 0.61149329, + 0.74756616 -0.26806507 0.60768914, + 0.77987719 -0.25262606 0.5726881, + 0.78789902 -0.237478 0.56817198, + 0.81815702 -0.22174001 0.53051901, + 0.82468468 -0.20870292 0.52567881, + 0.85295248 -0.19261289 0.48515171, + 0.85809988 -0.18162599 0.48028794, + 0.88424909 -0.16518901 0.43682507, + 0.88818479 -0.15609197 0.43216091, + 0.91179526 -0.13950104 0.38622409, + 0.91454071 -0.13251996 0.38216984, + 0.93553627 -0.11572503 0.33373609, + 0.93712842 -0.11118805 0.33079815, + 0.95551097 -0.093973897 0.279585, + 0.95726401 -0.0881733 0.27544701, + 0.97273767 -0.070701979 0.22086793, + 0.97396123 -0.065703712 0.21698505, + 0.98595363 -0.048403382 0.15985194, + 0.9865585 -0.045078821 0.15706807, + 0.9948681 -0.027912203 0.097254112, + 0.99508214 -0.026030604 0.095571816, + 0.99942821 -0.0088861017 0.032625508, + 0.99945086 -0.0083064493 0.032076795, + 0.99941212 0.0085950308 -0.033191305, + 0.99943411 0.0080584306 -0.032658003, + 0.99442422 0.025263306 -0.10238302, + 0.99460548 0.023873812 -0.10094605, + 0.98384124 0.041207112 -0.17423704, + 0.98415411 0.039842304 -0.17278102, + 0.96651649 0.057658527 -0.25004312, + 0.96665555 0.057249673 -0.24959888, + 0.94072789 0.075823791 -0.33057797, + 0.94678211 0.062308606 -0.31578702, + 0.91502625 0.078089118 -0.39576408, + 0.92506689 0.059301592 -0.37514594, + 0.88828111 0.07171391 -0.45366707, + 0.89917576 0.053968888 -0.4342469, + 0.85687357 0.06358137 -0.51159078, + 0.86845499 0.046885401 -0.49354601, + 0.82018101 0.0541046 -0.56954002, + 0.830706 0.040516101 -0.55523503, + 0.77617389 0.045887597 -0.62884694, + 0.78421611 0.036503606 -0.61941308, + 0.72282416 0.040653709 -0.68983519, + 0.72615594 0.037106995 -0.68652797, + 0.65752208 0.040664103 -0.7523371, + 0.65394884 0.044175588 -0.75524783, + 0.57891303 0.047612008 -0.8139981, + 0.56602091 0.059515085 -0.82223982, + 0.48753706 0.063031711 -0.8708241, + 0.46475813 0.08323092 -0.88151723, + 0.38694909 0.086677223 -0.91801822, + 0.35600802 0.11375701 -0.92753309, + 0.28345698 0.11673999 -0.95185286, + 0.24825189 0.14808592 -0.95730954, + 0.18544494 0.15021995 -0.97110462, + 0.149198 0.184047 -0.97152799, + 0.098937355 0.1852169 -0.97770452, + 0.067963876 0.21633093 -0.97395164, + 0.030322095 0.21673296 -0.97575986, + 0.024801509 0.22287108 -0.97453237, + -0.0055686701 0.222937 -0.97481698, + -0.010410897 0.22901694 -0.97336674, + -0.034560498 0.22889297 -0.97283787, + -0.041299418 0.23854712 -0.97025245, + -0.058507722 0.23834209 -0.96941733, + -0.059991661 0.24078985 -0.96872139, + -0.071991019 0.24059808 -0.96795136, + -0.072450466 0.24147987 -0.9676975, + -0.079914533 0.24134108 -0.96714437, + -0.082767479 0.24776293 -0.96527874, + -0.075064361 0.24791388 -0.96586955, + -0.043739095 0.16550899 -0.9852379, + -0.040177222 0.16553311 -0.9853856, + 0.037177004 -0.076892309 -0.99634612, + 0.028511601 -0.076914199 -0.99663001, + 0.095018625 -0.33045608 -0.93902624, + 0.074822515 -0.33102709 -0.94065022, + 0.12759902 -0.58295709 -0.80242109, + 0.096913047 -0.58499432 -0.80522639, + 0.12801903 -0.77992117 -0.61264509, + 0.090054691 -0.78319585 -0.61521894, + 0.10568403 -0.92265135 -0.37087113, + 0.11226998 -0.98823786 -0.10383399, + 0.10515195 -0.92397457 -0.36771482, + 0.14892094 -0.91876465 -0.36564189, + 0.12743895 -0.78323567 -0.60852373, + 0.16660005 -0.77863818 -0.6049521, + 0.12725598 -0.58939385 -0.79775983, + 0.15912202 -0.58665407 -0.79405111, + 0.095482953 -0.34156185 -0.9349966, + 0.11723895 -0.34076288 -0.93281066, + 0.039173316 -0.092752129 -0.99491835, + 0.044249617 -0.09273243 -0.99470735, + 0.13673897 -0.3528049 -0.92565179, + 0.11842994 -0.35364383 -0.92785257, + 0.19235897 -0.59095097 -0.78343791, + 0.15907802 -0.59452903 -0.78818113, + 0.20604303 -0.77679515 -0.59509307, + 0.1660669 -0.7828055 -0.59969765, + 0.19301993 -0.91327071 -0.35871989, + 0.14832003 -0.92047924 -0.36155108, + 0.15806101 -0.98250514 -0.098491319, + 0.17111394 -0.97299165 -0.15494294, + 0.17322604 -0.98487324 0.0041743508, + 0.17292 -0.984927 0.0041743899, + 0.17081393 -0.97305864 -0.15485294, + 0.17117895 -0.97299576 -0.15484497, + 0.20454796 -0.97430074 -0.094329774, + 0.19243604 -0.91519326 -0.3541041, + 0.23747408 -0.9059453 -0.35052711, + 0.20564397 -0.78161991 -0.58888096, + 0.24649291 -0.77404672 -0.58317482, + 0.19274396 -0.60016191 -0.77630883, + 0.21937697 -0.59673196 -0.77187085, + 0.13610397 -0.36012891 -0.92292076, + 0.150104 -0.359393 -0.92103499, + 0.054979809 -0.11143102 -0.99225014, + 0.059133913 -0.11140503 -0.99201423, + 0.072696209 -0.12834102 -0.98906213, + -0.0356104 0.12183 -0.99191201, + -0.039454289 0.12181197 -0.99176878, + 0.08255662 -0.13308503 -0.98766023, + 0.072985612 -0.13318503 -0.98840022, + 0.17931791 -0.37381881 -0.91000259, + 0.16402805 -0.37483108 -0.91246724, + 0.25658897 -0.60162795 -0.7564429, + 0.25797206 -0.59088814 -0.76439619, + 0.33111691 -0.76522082 -0.55208588, + 0.28820392 -0.77655768 -0.56026483, + 0.32750398 -0.88553387 -0.32950097, + 0.28171092 -0.89926368 -0.33460987, + 0.29743084 -0.95081955 -0.086469352, + 0.2657381 -0.95205635 -0.15156506, + 0.26887503 -0.96316814 0.0036490306, + 0.26887903 -0.96316713 0.0036490306, + 0.26574287 -0.95205551 -0.15156193, + 0.26572111 -0.95206147 -0.15156308, + 0.26885706 -0.96317321 0.003647801, + 0.22131993 -0.97504866 -0.017250195, + 0.218702 -0.96362197 -0.15363, + 0.21862103 -0.96364009 -0.15363201, + 0.2212681 -0.97519046 -0.006634023, + 0.22967106 -0.97319627 -0.011846303, + 0.025753001 -0.999605 -0.0112503, + 0.12837699 -0.99165386 -0.011915698, + 0.12462997 -0.99210578 -0.013911896, + 0.123152 -0.98045403 -0.153439, + 0.12325097 -0.98044175 -0.15343797, + 0.12473702 -0.99214613 -0.0093213813, + 0.075832091 -0.9971109 0.0043933797, + 0.07496687 -0.98585767 -0.14988194, + 0.075026132 -0.98585337 -0.14988106, + 0.075892039 -0.99710649 0.0043841419, + 0.075924993 -0.99710387 0.0043841396, + 0.026708404 -0.99958414 -0.010878801, + 0.026432896 -0.98937887 -0.14293599, + 0.026619803 -0.9893741 -0.14293501, + 0.026896788 -0.99956352 -0.012218994, + -0.021793593 -0.99975365 0.0042105485, + -0.021603107 -0.99112236 -0.13118604, + -0.022008488 -0.99111354 -0.13118494, + -0.022202602 -0.99974412 0.0043369606, + -0.022115 -0.99974602 0.0043369601, + -0.022257799 -0.99974298 0.0043042898, + -0.071145095 -0.9974339 -0.0079945587, + -0.070468321 -0.98804837 -0.13709405, + -0.070406474 -0.98805267 -0.13709396, + -0.071076088 -0.99735075 -0.015479797, + -0.077160828 -0.99693835 -0.012652405, + -0.17926393 -0.98372066 -0.012574395, + -0.16840802 -0.98553413 -0.019008001, + -0.21668404 -0.97623622 0.0033226807, + -0.2145509 -0.96674055 -0.13921393, + -0.21437804 -0.96677822 -0.13921903, + -0.216509 -0.97627503 0.00332011, + -0.21671008 -0.97623038 0.0033200812, + -0.2643241 -0.96442837 -0.0032727011, + -0.27947891 -0.96007466 -0.012169096, + -0.376674 -0.92622298 -0.0150927, + -0.40288907 -0.9152481 0.0011364401, + -0.39994609 -0.90866023 -0.11991603, + -0.39990294 -0.90867889 -0.11991799, + -0.40284482 -0.91526759 0.0011302395, + -0.40335208 -0.91504425 0.0011300802, + -0.40043992 -0.90853477 -0.11921597, + -0.43640193 -0.89739388 -0.065097094, + -0.44442812 -0.88881421 -0.11177203, + -0.44726595 -0.89440089 0.00028179298, + -0.447272 -0.89439797 0.00027851199, + -0.44443411 -0.88881123 -0.11177203, + -0.48112911 -0.8745082 -0.061239313, + -0.48793307 -0.8666721 -0.10392702, + -0.49062487 -0.87137079 -0.00037517291, + -0.49053282 -0.87142271 -0.00039151186, + -0.48784113 -0.86672318 -0.10393202, + -0.531955 -0.84526002 -0.050590001, + -0.53265494 -0.84633088 0.0016176398, + -0.53277588 -0.84625483 0.0016175796, + -0.53258187 -0.84637684 0.0017226496, + -0.53014112 -0.84257519 -0.094959922, + -0.56815118 -0.82090729 -0.057579324, + -0.57160914 -0.81627917 -0.083375119, + -0.5736357 -0.81910759 -0.0021938491, + -0.57370031 -0.81906241 -0.002181231, + -0.57167405 -0.81623411 -0.083371006, + -0.61213475 -0.78889573 -0.054170482, + -0.61305422 -0.79003632 0.0026814109, + -0.61310714 -0.78999519 0.0026813806, + -0.61282307 -0.79021513 0.0028462003, + -0.61123604 -0.78822714 -0.071334705, + -0.64944476 -0.7583757 -0.055567183, + -0.63200098 -0.73717302 -0.239062, + -0.67213529 -0.70431834 -0.2284071, + -0.63908195 -0.66803795 -0.38118193, + -0.68015683 -0.63670784 -0.3633039, + -0.63182795 -0.58883792 -0.50404692, + -0.67436194 -0.56095195 -0.48017594, + -0.60482001 -0.498851 -0.620758, + -0.65011424 -0.47597119 -0.59228623, + -0.54151601 -0.388843 -0.74536002, + -0.46733981 -0.2728079 -0.84093368, + -0.39831781 -0.2220939 -0.88995355, + -0.36798391 -0.22514094 -0.90216374, + -0.46287078 -0.29807186 -0.83480757, + -0.43325585 -0.30306289 -0.84878868, + -0.5440529 -0.3933309 -0.74114585, + -0.52411598 -0.39923599 -0.75227201, + -0.38578606 -0.28107402 -0.87873012, + -0.41410086 -0.2773079 -0.8669607, + -0.31559289 -0.19809993 -0.92798567, + -0.34395102 -0.19603103 -0.91829711, + -0.36034617 -0.20855311 -0.90920639, + -0.43802121 -0.20098409 -0.87620944, + -0.48636889 -0.23657894 -0.84111583, + -0.57348216 -0.22181307 -0.78861731, + -0.61749905 -0.25372404 -0.74452609, + -0.69627708 -0.23153202 -0.67940503, + -0.73560375 -0.26150492 -0.62490177, + -0.79908013 -0.23209403 -0.55462009, + -0.80804282 -0.23971593 -0.53814787, + -0.859038 -0.208298 -0.46761701, + -0.86726761 -0.21642789 -0.44833678, + -0.90599376 -0.18401796 -0.38119891, + -0.91208369 -0.19151393 -0.36252689, + -0.94010288 -0.15923099 -0.30141696, + -0.94142222 -0.16135505 -0.29612306, + -0.96191353 -0.13079195 -0.24003288, + -0.96206337 -0.13111505 -0.23925509, + -0.97688514 -0.10273202 -0.18746102, + -0.97645164 -0.10144896 -0.19039492, + -0.9870311 -0.075487711 -0.14167301, + -0.98651409 -0.073312305 -0.14634001, + -0.9936955 -0.050216824 -0.10023805, + -0.993339 -0.0479494 -0.104778, + -0.99778736 -0.027666708 -0.060456522, + -0.99762726 -0.025873605 -0.063800514, + -0.99975902 -0.00824943 -0.020341899, + -0.99973851 -0.0075292764 -0.021592289, + -0.99975455 0.0072952965 0.02092129, + -0.99973035 0.0064357421 0.022311108, + -0.99766135 0.018943608 0.065673023, + -0.99740762 0.015958894 0.07016588, + -0.99313378 0.025944794 0.11407097, + -0.99231386 0.020222198 0.12208299, + -0.9855665 0.027664613 0.16701308, + -0.98370898 0.018587301 0.17880499, + -0.97410601 0.023376999 0.22487999, + -0.97047347 0.0099413246 0.24100313, + -0.95774388 0.011854198 0.28737798, + -0.95231098 -0.0042306599 0.30509999, + -0.93626302 -0.0048708199 0.351266, + -0.93364298 -0.0115751 0.35801801, + -0.91530687 -0.013014798 0.40254694, + -0.91254085 -0.019528799 0.40851894, + -0.89213526 -0.021571705 0.45125312, + -0.88816601 -0.0303555 0.45851901, + -0.86595589 -0.033037398 0.49902794, + -0.86093712 -0.043607004 0.50683904, + -0.83699989 -0.046906594 0.54518896, + -0.83091128 -0.059250921 0.55324119, + -0.80512571 -0.063158877 0.58973175, + -0.79789752 -0.077404857 0.59780264, + -0.77030611 -0.081884004 0.63239509, + -0.76191473 -0.098100759 0.64020479, + -0.73312807 -0.10301001 0.67224407, + -0.72362274 -0.12117296 0.67947578, + -0.69369906 -0.12645102 0.70907807, + -0.68351793 -0.14584999 0.71521395, + -0.65229559 -0.15145092 0.7426796, + -0.64196599 -0.171259 0.74736202, + -0.60933292 -0.17710699 0.77288187, + -0.59822696 -0.19870697 0.77629888, + -0.56486291 -0.20462295 0.79941183, + -0.55315703 -0.22786203 0.80130911, + -0.51926619 -0.23375309 0.82202327, + -0.5071519 -0.25846195 0.82218879, + -0.47257489 -0.26429093 0.84072781, + -0.46021807 -0.29039103 0.83897114, + -0.4251588 -0.29605386 0.8553316, + -0.4127759 -0.32337692 0.85149485, + -0.37800193 -0.32869196 0.86549187, + -0.36586502 -0.35693002 0.85950214, + -0.33161604 -0.36181802 0.87127411, + -0.33245286 -0.35969383 0.87183458, + -0.30031997 -0.36378196 0.88174289, + -0.31041104 -0.33341002 0.8902151, + -0.2759859 -0.33711287 0.90010369, + -0.28407985 -0.30697885 0.90832961, + -0.24793696 -0.31017298 0.91777986, + -0.25429603 -0.28012204 0.92567015, + -0.21656908 -0.28276908 0.93441933, + -0.221426 -0.25264001 0.94188303, + -0.18204398 -0.25474298 0.94971889, + -0.18559301 -0.22445004 0.95664912, + -0.14456193 -0.22601889 0.96333653, + -0.14698093 -0.19569992 0.96958655, + -0.10507096 -0.19675392 0.97480667, + -0.10654701 -0.16637601 0.9802891, + -0.063944273 -0.16698593 0.9838835, + -0.064674132 -0.13648707 0.98852849, + -0.021437999 -0.13674098 0.99037486, + -0.021636002 -0.10612801 0.99411714, + 0.022044005 -0.10612702 0.99410826, + 0.021844406 -0.13674603 0.99036527, + 0.065036021 -0.13649005 0.98850435, + 0.064305708 -0.16694401 0.98386711, + 0.10703304 -0.16632806 0.98024434, + 0.10556795 -0.19667192 0.97476953, + 0.14757197 -0.19561096 0.96951479, + 0.14517103 -0.22593705 0.96326423, + 0.18621804 -0.22436206 0.95654821, + 0.18267198 -0.25469598 0.94961089, + 0.22203608 -0.25258809 0.94175333, + 0.21716696 -0.28284094 0.93425876, + 0.25482196 -0.28018996 0.92550486, + 0.24842909 -0.31042013 0.91756338, + 0.28441504 -0.30723202 0.90813911, + 0.27625793 -0.33760491 0.89983577, + 0.31040993 -0.33392391 0.89002275, + 0.30026689 -0.36443889 0.88148969, + 0.33214113 -0.36037913 0.87167031, + 0.33159 -0.36177701 0.871301, + 0.36586988 -0.35688487 0.85951871, + 0.3778919 -0.32891592 0.86545479, + 0.41261178 -0.32360786 0.85148656, + 0.42496321 -0.29636714 0.85532039, + 0.46001711 -0.29070306 0.83897316, + 0.47239777 -0.26456687 0.84074056, + 0.50690126 -0.25874811 0.82225341, + 0.51909882 -0.23387691 0.82209373, + 0.55298692 -0.22798698 0.80139089, + 0.56486213 -0.20441304 0.79946619, + 0.59827596 -0.19849297 0.77631587, + 0.60953766 -0.1765779 0.77284151, + 0.64222115 -0.17073305 0.74726319, + 0.6522612 -0.15147403 0.74270517, + 0.68348283 -0.14587297 0.7152428, + 0.69346625 -0.12686305 0.70923221, + 0.72335815 -0.12157803 0.67968518, + 0.73282605 -0.10350701 0.67249703, + 0.76161909 -0.098579712 0.64048308, + 0.77000153 -0.082401849 0.63269866, + 0.79759318 -0.077901617 0.59814411, + 0.80486369 -0.063592076 0.59004277, + 0.83065081 -0.059663083 0.55358785, + 0.8368333 -0.047142819 0.54542416, + 0.86079514 -0.043827005 0.50706106, + 0.86594588 -0.032982796 0.49904895, + 0.88816828 -0.030304112 0.45851818, + 0.89225847 -0.021246588 0.45102474, + 0.91265726 -0.019232605 0.4082731, + 0.91552413 -0.012466802 0.40207005, + 0.93382663 -0.011086596 0.35755387, + 0.93634111 -0.0046424805 0.35106102, + 0.95237774 -0.004031959 0.30489394, + 0.95758402 0.0113652 0.28793001, + 0.97035325 0.0095326221 0.24150306, + 0.97397935 0.022889307 0.22547807, + 0.98362386 0.018202698 0.17931199, + 0.98551226 0.027389508 0.16737804, + 0.99228287 0.020023998 0.12236699, + 0.99312478 0.025883794 0.11416297, + 0.9974041 0.015922002 0.070225708, + 0.99766248 0.01896031 0.065652333, + 0.99973053 0.0064410469 0.022302888, + 0.99975491 0.0073089991 0.020899598, + 0.99973887 -0.0075432393 -0.021569299, + 0.9997595 -0.0082678236 -0.02031111, + 0.9976325 -0.025927788 -0.063695468, + 0.99779236 -0.02772351 -0.060346924, + 0.99335521 -0.048044711 -0.10458102, + 0.99371064 -0.050313182 -0.10003896, + 0.98654926 -0.073446013 -0.14603503, + 0.98706609 -0.075627707 -0.14135401, + 0.97651821 -0.10163102 -0.18995604, + 0.97698224 -0.10301203 -0.18680005, + 0.96223211 -0.13145901 -0.23838603, + 0.96211565 -0.13120596 -0.23899491, + 0.9417429 -0.16185799 -0.29482597, + 0.9397561 -0.15866202 -0.30279502, + 0.91157198 -0.190824 -0.36417401, + 0.9048779 -0.18264599 -0.38449493, + 0.86571616 -0.21476905 -0.45211712, + 0.8628794 -0.21195111 -0.45882019, + 0.81312102 -0.24411 -0.52843601, + 0.79918182 -0.23217194 -0.55444086, + 0.735717 -0.26160401 -0.62472701, + 0.6950568 -0.23063494 -0.68095779, + 0.6161111 -0.25267506 -0.74603117, + 0.57362592 -0.22188698 -0.7884919, + 0.48653707 -0.23666203 -0.84099513, + 0.43647984 -0.19981793 -0.87724471, + 0.46957517 -0.2654821 -0.84203231, + 0.46087894 -0.25922096 -0.8487609, + 0.5496338 -0.24401592 -0.79897368, + 0.59615189 -0.27613395 -0.75389183, + 0.67773718 -0.25289607 -0.6904462, + 0.71271718 -0.27760106 -0.64418316, + 0.78049135 -0.24741112 -0.5741263, + 0.81024486 -0.27070096 -0.51983094, + 0.86101556 -0.23490013 -0.45108128, + 0.8700369 -0.24334697 -0.42873994, + 0.90819073 -0.20660692 -0.36400989, + 0.90906745 -0.20761389 -0.36123779, + 0.93811035 -0.17257705 -0.30027711, + 0.94130945 -0.17731509 -0.28722116, + 0.96189123 -0.14363603 -0.23266706, + 0.96256053 -0.14499892 -0.2290249, + 0.97721225 -0.11354503 -0.17934304, + 0.97702086 -0.11299598 -0.18072699, + 0.98735666 -0.084034771 -0.13440596, + 0.98699778 -0.082542278 -0.13792098, + 0.99392545 -0.056517128 -0.094435245, + 0.99364799 -0.054737799 -0.098323099, + 0.99789113 -0.031573005 -0.056713209, + 0.99776411 -0.030113304 -0.059666809, + 0.99977291 -0.0096006487 -0.019022899, + 0.9997561 -0.0089873513 -0.020172201, + 0.99977112 0.0087084109 0.019546103, + 0.99975145 0.0079730442 0.02082311, + 0.99784255 0.023475688 0.061310969, + 0.99763125 0.020837905 0.065557413, + 0.99372077 0.033893391 0.10663098, + 0.99304253 0.028840788 0.11416995, + 0.98691809 0.039486505 0.15631202, + 0.98536062 0.031325888 0.16757993, + 0.97669065 0.039441787 0.21099693, + 0.97374237 0.027693709 0.22596207, + 0.96232802 0.033075299 0.26987201, + 0.95726067 0.016941193 0.28872991, + 0.94269389 0.019543799 0.33308598, + 0.93586975 0.0014703596 0.3523429, + 0.91804022 0.0016545603 0.39648408, + 0.91473532 -0.0061233821 0.40400714, + 0.8947081 -0.0067689507 0.44660005, + 0.89116168 -0.014603795 0.45345086, + 0.8693732 -0.015906503 0.49390012, + 0.86451286 -0.026151497 0.50192994, + 0.84100211 -0.028150704 0.54029906, + 0.83503872 -0.040263884 0.54871583, + 0.8096531 -0.042950902 0.58533508, + 0.80267733 -0.056741428 0.59370828, + 0.77546889 -0.060068391 0.62852192, + 0.76741987 -0.075694293 0.63666093, + 0.73893762 -0.079546466 0.66906172, + 0.72985208 -0.097014718 0.67668605, + 0.70019174 -0.10132197 0.70672876, + 0.69011992 -0.12065098 0.71356696, + 0.65914679 -0.12537296 0.74148977, + 0.64863497 -0.14567798 0.74702793, + 0.61634928 -0.15072708 0.77291334, + 0.6058107 -0.17140992 0.77692467, + 0.5727151 -0.17661305 0.80050319, + 0.56112719 -0.19988108 0.80323333, + 0.52740175 -0.20516789 0.82447159, + 0.51542211 -0.22992706 0.8255142, + 0.48098695 -0.23523697 0.84457988, + 0.46888211 -0.26118305 0.84376121, + 0.43378484 -0.26643392 0.86072272, + 0.42170593 -0.29352698 0.85790789, + 0.3868351 -0.29851705 0.87249416, + 0.37498504 -0.32659602 0.86759514, + 0.34047711 -0.33125412 0.8799693, + 0.32913086 -0.35996181 0.87298357, + 0.29495084 -0.36424282 0.8833636, + 0.29529512 -0.36327913 0.8836453, + 0.26311204 -0.36683902 0.89230114, + 0.27207309 -0.33658811 0.90149027, + 0.23795392 -0.3397359 0.90992171, + 0.24503595 -0.30956495 0.91876376, + 0.20911796 -0.31223896 0.9267019, + 0.2145371 -0.28215516 0.93507344, + 0.17675099 -0.28433296 0.94229186, + 0.18073891 -0.25417787 0.9501195, + 0.141102 -0.25584799 0.95636398, + 0.14385405 -0.22557607 0.96354634, + 0.10309702 -0.22673206 0.96848524, + 0.10479898 -0.19645695 0.97489578, + 0.063044794 -0.19715098 0.9783439, + 0.063914463 -0.16683289 0.9839114, + 0.021460505 -0.16713604 0.98570025, + 0.021702899 -0.13670598 0.99037391, + -0.021318402 -0.13670701 0.99038213, + -0.021066099 -0.16715799 0.98570502, + -0.063492067 -0.16685793 0.98393452, + -0.06261199 -0.19721997 0.97835785, + -0.10426998 -0.19652997 0.97493786, + -0.10256005 -0.2268081 0.96852446, + -0.14324999 -0.22565897 0.96361691, + -0.14049304 -0.25588706 0.95644325, + -0.18011095 -0.2542229 0.95022666, + -0.17612991 -0.28427485 0.94242555, + -0.213999 -0.282098 0.93521398, + -0.208602 -0.31202599 0.92689002, + -0.24467103 -0.30934802 0.91893411, + -0.23763897 -0.33930197 0.91016591, + -0.27198595 -0.33613992 0.90168375, + -0.26307005 -0.36625308 0.89255422, + -0.29554102 -0.36266804 0.8838141, + -0.29496685 -0.36427581 0.88334459, + -0.3291449 -0.35999489 0.87296468, + -0.34058309 -0.3310501 0.88000524, + -0.37511817 -0.32638916 0.8676154, + -0.3869971 -0.29823405 0.8725192, + -0.42192891 -0.29323593 0.85789782, + -0.43399405 -0.26616302 0.86070114, + -0.46907276 -0.26091689 0.8437376, + -0.48111382 -0.23509991 0.84454572, + -0.51557499 -0.22978599 0.82545799, + -0.52739906 -0.20535003 0.82442814, + -0.56110114 -0.20006305 0.80320621, + -0.57252812 -0.17712805 0.80052316, + -0.60558623 -0.17191906 0.77698731, + -0.61639601 -0.150712 0.772879, + -0.64867705 -0.14566402 0.74699408, + -0.65938675 -0.12496796 0.74134475, + -0.69036424 -0.12025604 0.71339726, + -0.70047426 -0.10083604 0.70651823, + -0.73016715 -0.096539423 0.67641419, + -0.73926115 -0.079032123 0.66876519, + -0.76773709 -0.07519991 0.63633704, + -0.77574283 -0.059636984 0.62822485, + -0.80295116 -0.056328915 0.59337711, + -0.80983919 -0.042696211 0.58509612, + -0.83521241 -0.040023517 0.54846925, + -0.84102881 -0.028201593 0.54025489, + -0.86453331 -0.026199209 0.50189215, + -0.86925972 -0.016242795 0.49408883, + -0.89104861 -0.014913793 0.45366278, + -0.89446712 -0.0073750308 0.44707307, + -0.91450971 -0.0066728778 0.40450886, + -0.91793603 0.00137661 0.39672601, + -0.93577713 0.0012234601 0.35259002, + -0.94289249 0.02008621 0.33249116, + -0.95742285 0.017408399 0.28816396, + -0.96249801 0.033631299 0.269196, + -0.97387123 0.028153408 0.22534905, + -0.97677326 0.039767113 0.21055305, + -0.98541623 0.031579908 0.16720505, + -0.98693585 0.039564896 0.15617998, + -0.99305212 0.028897803 0.11407202, + -0.99371922 0.033870306 0.10665302, + -0.99763036 0.020824907 0.065574922, + -0.99783999 0.023438901 0.061367098, + -0.99975109 0.0079611512 0.020843701, + -0.99977064 0.0086928476 0.019573092, + -0.99975562 -0.0089719472 -0.020201592, + -0.99977255 -0.0095841056 -0.01905439, + -0.99775922 -0.030064408 -0.059771813, + -0.99788666 -0.03152319 -0.05681958, + -0.99363363 -0.054655083 -0.098514162, + -0.99391139 -0.05643072 -0.094634734, + -0.98696488 -0.082424596 -0.13822599, + -0.98730963 -0.08385177 -0.13486496, + -0.97693187 -0.11275698 -0.18135598, + -0.97710454 -0.11324995 -0.18011391, + -0.96237755 -0.14463192 -0.23002389, + -0.96206051 -0.14398593 -0.23174889, + -0.94157225 -0.17774804 -0.28609005, + -0.93866122 -0.17340705 -0.29806906, + -0.90988678 -0.20861596 -0.35858792, + -0.90586388 -0.20403098 -0.37118998, + -0.86676383 -0.24022993 -0.43704692, + -0.86096144 -0.23484112 -0.45121521, + -0.81015712 -0.27064103 -0.51999909, + -0.7813502 -0.24807206 -0.57267112, + -0.71377963 -0.27839187 -0.64266372, + -0.6776368 -0.25285193 -0.69056082, + -0.59603423 -0.27608109 -0.7540043, + -0.55112779 -0.24506691 -0.79762173, + -0.47257313 -0.25883305 -0.84242517, + -0.45432988 -0.24605694 -0.85617781, + -0.42247185 -0.25034991 -0.87111568, + -0.5119918 -0.31614789 -0.79869568, + -0.48161319 -0.32255012 -0.81486827, + -0.59703374 -0.41253984 -0.68801278, + -0.61775804 -0.40439007 -0.67442107, + -0.5299179 -0.3390519 -0.77732283, + -0.56064296 -0.33105898 -0.75899887, + -0.47791088 -0.27288294 -0.83494681, + -0.51087314 -0.26705807 -0.81712216, + -0.58380008 -0.35047203 -0.73235708, + -0.57757199 -0.35238999 -0.73636401, + -0.66771501 -0.41661 -0.61692202, + -0.68837404 -0.40594307 -0.60112506, + -0.57719982 -0.33082789 -0.74658775, + -0.6185239 -0.31833491 -0.71839482, + -0.58429796 -0.29608998 -0.75559688, + -0.65763676 -0.2748549 -0.70140475, + -0.69507074 -0.29942489 -0.65362173, + -0.76608318 -0.26768905 -0.5843451, + -0.7929762 -0.28665406 -0.53760409, + -0.8478108 -0.24950694 -0.46793488, + -0.86720985 -0.26567498 -0.42114595, + -0.90634614 -0.22544204 -0.35736904, + -0.90981656 -0.22911389 -0.34603581, + -0.9387601 -0.19022603 -0.28730404, + -0.94040251 -0.19248492 -0.28034389, + -0.96134377 -0.15585697 -0.22699495, + -0.96253997 -0.158117 -0.220263, + -0.97722936 -0.12373804 -0.17237106, + -0.97715223 -0.12352903 -0.17295705, + -0.98744524 -0.09180782 -0.12854303, + -0.98723137 -0.09094923 -0.13077705, + -0.99404162 -0.062234979 -0.089488067, + -0.99384052 -0.060960371 -0.092546254, + -0.99795663 -0.035147388 -0.05335848, + -0.99785513 -0.033970803 -0.055957008, + -0.99978238 -0.010827004 -0.017834306, + -0.99976873 -0.010319897 -0.018865095, + -0.99978298 0.0099984501 0.018277301, + -0.99976689 0.009370449 0.019454198, + -0.99797654 0.027591787 0.057283875, + -0.99780589 0.025348896 0.061162692, + -0.99418086 0.041244198 0.099515587, + -0.9936285 0.036866881 0.10650495, + -0.98800778 0.050507188 0.14590997, + -0.98676676 0.043526091 0.15619497, + -0.97889334 0.054861117 0.19687107, + -0.97650713 0.044577803 0.21082403, + -0.96620852 0.053323675 0.25218588, + -0.96212101 0.039177101 0.269793, + -0.94903755 0.045290276 0.31189185, + -0.94240248 0.026294613 0.33344615, + -0.92613697 0.029651901 0.37602001, + -0.91724223 0.0079801418 0.3982501, + -0.8976993 0.0088271424 0.44052014, + -0.89340687 -0.00062214694 0.44924793, + -0.8719818 -0.00067794981 0.48953789, + -0.8678782 -0.0092968717 0.49669012, + -0.8447656 -0.010014796 0.53504276, + -0.8392821 -0.021166801 0.54328406, + -0.81430799 -0.022597101 0.57999301, + -0.80770588 -0.035697397 0.58850396, + -0.78086799 -0.037823301 0.62355, + -0.77321315 -0.052768108 0.63194704, + -0.74505305 -0.055502407 0.66469204, + -0.73634076 -0.072376579 0.67272878, + -0.70692116 -0.075658612 0.7032342, + -0.6971938 -0.094485678 0.71062881, + -0.66637409 -0.098273017 0.73911303, + -0.65576607 -0.11894701 0.74553508, + -0.62364197 -0.12316099 0.77194691, + -0.61253273 -0.14513496 0.77700669, + -0.57976598 -0.14960299 0.80093098, + -0.56861597 -0.172188 0.80438, + -0.53510702 -0.17682999 0.82607001, + -0.5235278 -0.20102993 0.82795268, + -0.4891881 -0.20578805 0.84755319, + -0.47740093 -0.23139597 0.8476699, + -0.44231114 -0.23618309 0.86520427, + -0.4305228 -0.26303589 0.86340159, + -0.39546475 -0.26767084 0.87861246, + -0.38385692 -0.29565293 0.87478185, + -0.3490479 -0.30004194 0.88777274, + -0.33782884 -0.32896286 0.88184756, + -0.30321994 -0.3330569 0.89282179, + -0.29263085 -0.36262983 0.88479757, + -0.25842005 -0.3663491 0.89387226, + -0.25877512 -0.36523217 0.89422643, + -0.22640306 -0.36829409 0.90172124, + -0.23412301 -0.33843499 0.91139901, + -0.1998219 -0.34108886 0.91854757, + -0.20577504 -0.31130406 0.92776424, + -0.16954999 -0.31350598 0.93432689, + -0.17396298 -0.28370398 0.9429999, + -0.13586102 -0.28542605 0.94872224, + -0.13894802 -0.25547007 0.95678025, + -0.099537298 -0.25669199 0.96135402, + -0.10150002 -0.22651707 0.96870422, + -0.060971878 -0.22726792 0.97192162, + -0.062001314 -0.19704905 0.97843122, + -0.020649102 -0.19738702 0.98010814, + -0.020943791 -0.16712293 0.98571354, + 0.021411095 -0.16712196 0.98570377, + 0.021125594 -0.19736296 0.98010278, + 0.062575169 -0.1970199 0.97840053, + 0.061554492 -0.22721697 0.97189689, + 0.10210601 -0.22645903 0.9686541, + 0.10014798 -0.25666493 0.96129775, + 0.13957796 -0.25543591 0.95669764, + 0.136489 -0.28546599 0.94862002, + 0.17449994 -0.28374091 0.94288963, + 0.17007194 -0.31367689 0.93417466, + 0.206139 -0.31147799 0.927625, + 0.20015092 -0.34145287 0.91834062, + 0.23420601 -0.33881101 0.91123801, + 0.22645102 -0.36880302 0.90150112, + 0.25857806 -0.3657611 0.89406723, + 0.25840494 -0.3663069 0.89389378, + 0.29260594 -0.36259091 0.88482177, + 0.30311602 -0.33324203 0.89278811, + 0.33769992 -0.32915092 0.88182676, + 0.34889618 -0.30029914 0.88774544, + 0.38366586 -0.29591289 0.87477767, + 0.39528394 -0.26791698 0.8786189, + 0.430291 -0.263289 0.86343998, + 0.442139 -0.236305 0.86525899, + 0.47725406 -0.23151504 0.84772015, + 0.48918331 -0.20559612 0.84760249, + 0.52352804 -0.20084202 0.8279981, + 0.53525215 -0.17632806 0.8260833, + 0.56881982 -0.17168795 0.80434269, + 0.57970417 -0.14963706 0.8009693, + 0.61249495 -0.14516498 0.77703089, + 0.62342972 -0.12354694 0.77205664, + 0.655509 -0.119329 0.7457, + 0.66607797 -0.098752603 0.73931599, + 0.69689894 -0.094951086 0.71085596, + 0.70660394 -0.076187089 0.70349592, + 0.73601204 -0.072888106 0.67303306, + 0.74476582 -0.055955186 0.66497582, + 0.77293485 -0.053201493 0.63225096, + 0.78068697 -0.0380807 0.623761, + 0.80750853 -0.035943877 0.58875966, + 0.81424642 -0.022580311 0.58008027, + 0.83925015 -0.021149902 0.54333407, + 0.84487957 -0.0096959854 0.53486878, + 0.86798614 -0.009000591 0.49650705, + 0.872244 -4.3462202e-005 0.48907101, + 0.8936609 -3.9877697e-005 0.44874293, + 0.8978349 0.0091662994 0.44023693, + 0.91736186 0.0082861995 0.39796793, + 0.92589635 0.029062711 0.37665814, + 0.94220078 0.025775595 0.3340559, + 0.94882512 0.044669405 0.31262702, + 0.96194786 0.038648196 0.27048597, + 0.96609437 0.05293832 0.25270408, + 0.97642362 0.044259585 0.21127692, + 0.97886527 0.054754514 0.19704005, + 0.98674822 0.04344321 0.15633504, + 0.98800933 0.050531518 0.14589106, + 0.99362963 0.036883485 0.10648796, + 0.99418634 0.041298915 0.099437937, + 0.99780834 0.025380408 0.061109822, + 0.99797952 0.027634688 0.057211474, + 0.99976724 0.0093843322 0.019428203, + 0.99978334 0.010013604 0.018248908, + 0.99976921 -0.010335003 -0.018834604, + 0.99978274 -0.010842497 -0.017802795, + 0.99785936 -0.034016512 -0.055853419, + 0.99796075 -0.035195094 -0.053250488, + 0.99385375 -0.061039183 -0.092352778, + 0.9940604 -0.062355261 -0.08919435, + 0.98727489 -0.091114394 -0.13033198, + 0.98749685 -0.092010491 -0.12799999, + 0.97725034 -0.12379204 -0.17221306, + 0.97715455 -0.12353294 -0.17294091, + 0.96241337 -0.15786105 -0.22099908, + 0.96108967 -0.15537494 -0.22839692, + 0.94000876 -0.19188696 -0.28206894, + 0.94007897 -0.191984 -0.28176901, + 0.91178375 -0.23123793 -0.33938092, + 0.90638477 -0.22547194 -0.35725191, + 0.86725414 -0.26572204 -0.42102507, + 0.84725899 -0.249075 -0.469163, + 0.79225379 -0.28612393 -0.53894991, + 0.76616538 -0.26773512 -0.5842163, + 0.69516093 -0.29948598 -0.65349793, + 0.65627557 -0.27397385 -0.7030226, + 0.57169414 -0.29791906 -0.76446718, + 0.51670116 -0.26178008 -0.81516331, + 0.47302288 -0.26938894 -0.8388558, + 0.54194689 -0.3177349 -0.77803481, + 0.51104391 -0.32497191 -0.7957558, + 0.60790604 -0.39683107 -0.68773204, + 0.58716398 -0.40455699 -0.70112199, + 0.46211305 -0.30729803 -0.83187711, + 0.49238312 -0.30160105 -0.81645316, + 0.37920105 -0.21884303 -0.89906311, + 0.36195502 -0.22047003 -0.90574914, + 0.44277373 -0.28246284 -0.85097945, + 0.41351905 -0.28682902 -0.8641361, + 0.53398192 -0.38477495 -0.75286889, + 0.51404822 -0.39035717 -0.76379037, + 0.45931894 -0.36273196 -0.81083387, + 0.59022599 -0.47805199 -0.65046102, + 0.56022364 -0.49054971 -0.66746557, + 0.43365216 -0.37041813 -0.82142329, + 0.46046883 -0.36490789 -0.80920368, + 0.32010013 -0.23964009 -0.9165743, + 0.3465009 -0.23727894 -0.90754378, + 0.25874108 -0.16354406 -0.95200133, + 0.247021 -0.14815 -0.957618, + 0.17815396 -0.10435198 -0.97845376, + 0.30120704 -0.21244504 -0.92959213, + 0.27669501 -0.214094 -0.93680501, + 0.42465115 -0.35254312 -0.83389729, + 0.39862183 -0.35712183 -0.84472758, + 0.52191383 -0.47983482 -0.70524079, + 0.50212687 -0.48647088 -0.71499282, + 0.36482811 -0.34289113 -0.86563629, + 0.3899641 -0.33911908 -0.85611117, + 0.23597895 -0.18795596 -0.95340776, + 0.25866994 -0.18683596 -0.94772476, + 0.16943595 -0.10451498 -0.97998375, + 0.15623999 -0.085184589 -0.98403889, + 0.16123904 -0.089879222 -0.98281425, + 0.22856504 -0.088660009 -0.96948314, + 0.27198109 -0.12581505 -0.95404238, + 0.35056689 -0.12244596 -0.92849863, + 0.3958891 -0.15877405 -0.90446824, + 0.48102313 -0.15158303 -0.86350417, + 0.53693497 -0.195242 -0.82072002, + 0.62034291 -0.18151996 -0.76303685, + 0.64553124 -0.20157607 -0.73665226, + 0.71976721 -0.18322706 -0.66959924, + 0.73040277 -0.19215192 -0.65543073, + 0.793778 -0.171106 -0.58364302, + 0.80747414 -0.18384002 -0.56052506, + 0.87174088 -0.15269598 -0.46556595, + 0.8729822 -0.15421103 -0.46273211, + 0.90974361 -0.13126294 -0.39387381, + 0.91109169 -0.13325696 -0.39006984, + 0.9391281 -0.11106802 -0.32511902, + 0.93837023 -0.10966403 -0.32777309, + 0.95972067 -0.089143567 -0.2664389, + 0.95826524 -0.085718624 -0.27272707, + 0.9744491 -0.067346506 -0.21427403, + 0.97296888 -0.062829591 -0.22222497, + 0.98505354 -0.046862576 -0.16575092, + 0.98390698 -0.042158 -0.173637, + 0.99245465 -0.028929189 -0.11915096, + 0.9917345 -0.02467539 -0.12591194, + 0.99724966 -0.014253295 -0.072731279, + 0.99694264 -0.011194796 -0.077330768, + 0.99968934 -0.0035710712 -0.02466801, + 0.99964952 -0.0023747389 -0.026367787, + 0.99967134 0.0022996708 0.02553441, + 0.9996255 0.00094511651 0.027350187, + 0.99676001 0.0027778 0.080385201, + 0.99626625 -0.0019192805 0.086312421, + 0.99015838 -0.0031112612 0.13991705, + 0.9888615 -0.010345195 0.14847893, + 0.97922277 -0.014094897 0.20229696, + 0.97849399 -0.017056299 0.205569, + 0.96603566 -0.021366993 0.25752392, + 0.96490014 -0.025161404 0.26140904, + 0.95001203 -0.029913099 0.31077701, + 0.94804615 -0.035598304 0.31613502, + 0.93076891 -0.040910497 0.36331198, + 0.92795599 -0.048174899 0.36956301, + 0.90833426 -0.054063611 0.41473609, + 0.90461421 -0.062849917 0.42157209, + 0.88278174 -0.069271885 0.46464789, + 0.8780036 -0.07978446 0.47195777, + 0.85434669 -0.086627074 0.51243281, + 0.84845471 -0.098888062 0.51994783, + 0.82310915 -0.10610303 0.55788314, + 0.8159759 -0.12031499 0.56542695, + 0.7888822 -0.12790303 0.60108709, + 0.78106499 -0.142986 0.60785902, + 0.75227827 -0.15086105 0.64134121, + 0.74446064 -0.16565092 0.64679068, + 0.71435994 -0.17361699 0.67789894, + 0.70489681 -0.19131896 0.68302083, + 0.67361879 -0.19934796 0.71168685, + 0.66304374 -0.21900593 0.71582776, + 0.63038981 -0.22710994 0.7423138, + 0.61895877 -0.24835891 0.74512279, + 0.58513272 -0.25642687 0.76932764, + 0.57292515 -0.27927908 0.7705583, + 0.5386101 -0.28709906 0.7921322, + 0.525801 -0.311409 0.79155397, + 0.49126893 -0.31887797 0.81053787, + 0.47813606 -0.34433803 0.80797112, + 0.44331712 -0.35142508 0.8246032, + 0.44473186 -0.34853289 0.82506871, + 0.41282079 -0.35442683 0.83902359, + 0.42619908 -0.32308909 0.84496617, + 0.39267108 -0.32846409 0.85902315, + 0.40378207 -0.29754704 0.86511612, + 0.36851782 -0.30234987 0.87907857, + 0.3776159 -0.27178395 0.88517779, + 0.3404651 -0.27597907 0.89884323, + 0.34780481 -0.24556188 0.90483761, + 0.30859303 -0.24913102 0.91798913, + 0.31437913 -0.21873207 0.92375433, + 0.27374098 -0.22161298 0.93592387, + 0.27813193 -0.19132395 0.94129574, + 0.236233 -0.193545 0.95222598, + 0.23942906 -0.16330704 0.95708126, + 0.19628502 -0.16492702 0.96657711, + 0.19847596 -0.13458897 0.97082078, + 0.15420803 -0.13567904 0.97867823, + 0.15558393 -0.10516496 0.98220867, + 0.11101596 -0.10580296 0.98817062, + 0.11175 -0.075225502 0.99088502, + 0.067030109 -0.075529404 0.99488813, + 0.067324705 -0.044949003 0.99671811, + 0.022589395 -0.045039687 0.99872977, + 0.022633597 -0.014272398 0.9996419, + -0.02318099 -0.014747192 0.99962252, + -0.022034686 -0.014747592 0.99964839, + -0.021991502 -0.045061905 0.9987421, + -0.066594407 -0.044972703 0.99676609, + -0.066302225 -0.075457431 0.99494237, + -0.11115403 -0.075155228 0.99095738, + -0.11041203 -0.10568302 0.98825121, + -0.15524293 -0.10504396 0.98227566, + -0.15386492 -0.13564794 0.97873652, + -0.19809701 -0.134562 0.97090203, + -0.19588795 -0.16501996 0.96664178, + -0.23903488 -0.16340193 0.95716351, + -0.23582987 -0.19372891 0.95228851, + -0.27757895 -0.19151695 0.94141978, + -0.27317205 -0.22178607 0.93604922, + -0.31380311 -0.21890907 0.92390835, + -0.30803001 -0.249198 0.91816002, + -0.34725004 -0.24563403 0.90503114, + -0.33994514 -0.27587011 0.89907342, + -0.377184 -0.27167299 0.885396, + -0.3681519 -0.30200395 0.87935078, + -0.40357885 -0.29718989 0.86533368, + -0.39258307 -0.32779202 0.8593201, + -0.42632878 -0.32239285 0.84516656, + -0.41305178 -0.35352683 0.83928961, + -0.44522411 -0.34759209 0.8252002, + -0.44331193 -0.35150498 0.82457191, + -0.47811812 -0.34441909 0.80794716, + -0.49143276 -0.31860086 0.81054765, + -0.5259949 -0.31112793 0.79153579, + -0.53884393 -0.28672698 0.79210788, + -0.57317972 -0.27890688 0.77050364, + -0.58536375 -0.25608492 0.76926571, + -0.61923075 -0.2480109 0.74501276, + -0.6305508 -0.22695693 0.7422238, + -0.66318703 -0.218859 0.71574003, + -0.67355168 -0.1995929 0.71168166, + -0.70481294 -0.19155997 0.68303996, + -0.71410185 -0.17419796 0.67802185, + -0.74417216 -0.16622205 0.64697617, + -0.75230211 -0.15084901 0.64131606, + -0.78109819 -0.14297003 0.60782009, + -0.78912264 -0.12747794 0.60086173, + -0.81620914 -0.11990701 0.56517708, + -0.8233723 -0.10561503 0.55758721, + -0.84869689 -0.098427087 0.51963997, + -0.85461003 -0.086102903 0.51208198, + -0.87825429 -0.079291932 0.47157419, + -0.8829717 -0.06889578 0.46434283, + -0.90478212 -0.062503807 0.42126307, + -0.90843332 -0.053870019 0.41454414, + -0.92803389 -0.048002191 0.36938998, + -0.93074387 -0.041000698 0.36336598, + -0.94802511 -0.035677403 0.31618902, + -0.94990736 -0.030241711 0.31106511, + -0.96482015 -0.025440203 0.26167703, + -0.96593112 -0.021736601 0.25788504, + -0.97842133 -0.017354006 0.20589007, + -0.97920662 -0.014168495 0.20236993, + -0.98885125 -0.010399903 0.14854303, + -0.99020326 -0.0028485407 0.13960503, + -0.99628466 -0.0017568694 0.086103372, + -0.99677914 0.0029679304 0.08014141, + -0.99962777 0.0010096797 0.027263794, + -0.99967265 0.002343969 0.02547509, + -0.99965113 -0.0024201702 -0.026303304, + -0.99968976 -0.003583109 -0.024650794, + -0.99694622 -0.011232803 -0.077278912, + -0.99724686 -0.014227498 -0.072775491, + -0.99172574 -0.024630895 -0.12598997, + -0.99243712 -0.028826904 -0.11932202, + -0.98386753 -0.04201138 -0.17389591, + -0.98500848 -0.046680722 -0.16607007, + -0.97288114 -0.062592208 -0.22267602, + -0.97436088 -0.067093894 -0.21475397, + -0.95811427 -0.085402921 -0.27335605, + -0.95957613 -0.088831507 -0.26706302, + -0.93814474 -0.10928198 -0.32854491, + -0.93889964 -0.11067496 -0.32591188, + -0.9107433 -0.13279104 -0.39104116, + -0.90921539 -0.13054006 -0.39533117, + -0.87223858 -0.15335193 -0.4644168, + -0.86603284 -0.14591797 -0.47822088, + -0.81810498 -0.16783001 -0.55003399, + -0.80568999 -0.155339 -0.57160598, + -0.74524194 -0.17486499 -0.64345694, + -0.71679795 -0.14989498 -0.68097895, + -0.65922576 -0.16164695 -0.73436475, + -0.59901714 -0.11220903 -0.79283518, + -0.53636408 -0.11826901 -0.83565915, + -0.497796 -0.087223299 -0.86289698, + -0.41444391 -0.091525778 -0.90546077, + -0.39737481 -0.07753966 -0.91437459, + -0.31740192 -0.080128275 -0.94489974, + -0.26867509 -0.038243715 -0.96247137, + -0.19910704 -0.038908504 -0.97920513, + -0.16392194 -0.0063864575 -0.98645264, + -0.10655797 -0.0064371675 -0.99428564, + -0.079251871 0.021361992 -0.99662566, + -0.034819704 0.021416502 -0.9991641, + -0.034100909 0.020252706 -0.99921322, + -0.0092753191 0.049240094 -0.99874389, + -0.00017436598 0.049242094 -0.99878687, + -0.082503974 -0.05274969 -0.99519378, + -0.070165902 -0.052799799 -0.99613702, + -0.22049201 -0.251766 -0.94233602, + -0.20250203 -0.25277102 -0.94609714, + -0.33491296 -0.44000894 -0.83320189, + -0.3135339 -0.44343087 -0.8396818, + -0.42374706 -0.60966909 -0.66988206, + -0.40431583 -0.61561871 -0.67641872, + -0.2908181 -0.43468115 -0.85233629, + -0.31163406 -0.43169308 -0.84647816, + -0.18048806 -0.23603308 -0.95483637, + -0.197303 -0.235258 -0.95169598, + -0.049897183 -0.029700588 -0.99831265, + -0.060718071 -0.029682785 -0.99771351, + 0.017247794 0.071983576 -0.99725664, + 0.009724929 0.071990989 -0.9973579, + 0.0084520895 0.070430391 -0.99748087, + -0.0276924 0.070405997 -0.99713397, + -0.047888812 0.047842912 -0.99770623, + -0.094424635 0.047683917 -0.99438936, + -0.12181803 0.020184705 -0.99234724, + -0.18036391 0.020002691 -0.98339653, + -0.22103 -0.017333601 -0.97511297, + -0.29221305 -0.016997404 -0.95620221, + -0.30715597 -0.029788297 -0.95119286, + -0.38488305 -0.028890103 -0.92251313, + -0.42766213 -0.063942619 -0.90167427, + -0.50986212 -0.060852613 -0.85810119, + -0.55664897 -0.099464782 -0.82477188, + -0.63638377 -0.092355669 -0.76582372, + -0.66391182 -0.11637697 -0.73869979, + -0.73442209 -0.10562102 -0.67042404, + -0.75258613 -0.12311202 -0.64688307, + -0.8110823 -0.10936004 -0.57461816, + -0.81910384 -0.11822297 -0.56133085, + -0.86633933 -0.10293303 -0.48873419, + -0.86795789 -0.10503799 -0.48540294, + -0.90572226 -0.089647919 -0.4142831, + -0.9043079 -0.087446794 -0.41782793, + -0.93416423 -0.073099613 -0.3492761, + -0.93148446 -0.068043463 -0.35736078, + -0.95501709 -0.055468306 -0.29131702, + -0.95219666 -0.048923083 -0.30154288, + -0.97062021 -0.038534407 -0.23751105, + -0.96815377 -0.031340592 -0.24838693, + -0.98233867 -0.023423392 -0.18563995, + -0.98053735 -0.016552206 -0.19563407, + -0.99085534 -0.011375303 -0.13444805, + -0.98975176 -0.0054575684 -0.14269397, + -0.99658579 -0.0031554692 -0.082502879, + -0.99611777 0.00099141675 -0.088025376, + -0.99960554 0.00031629886 -0.028083187, + -0.99954337 0.0019492607 -0.030156512, + -0.99957234 -0.0018864108 0.029184312, + -0.9995119 -0.0034331495 0.031051496, + -0.99579042 -0.010072694 0.091103546, + -0.99564612 -0.011316301 0.092524208, + -0.98855376 -0.018315697 0.14975297, + -0.98818702 -0.020317901 0.15189999, + -0.97800052 -0.027655886 0.2067609, + -0.9771769 -0.031041896 0.21014696, + -0.96402478 -0.038842991 0.26295894, + -0.96260864 -0.043602884 0.26736391, + -0.94686276 -0.051770188 0.31744391, + -0.94470364 -0.058019176 0.32275188, + -0.92647624 -0.066587612 0.37041607, + -0.92340225 -0.074507013 0.37653309, + -0.90277791 -0.083489291 0.42192593, + -0.89862901 -0.093234003 0.42868799, + -0.87574178 -0.10259898 0.47175187, + -0.87036699 -0.114312 0.47895101, + -0.84567171 -0.12389895 0.51912284, + -0.83942997 -0.13672601 0.52598798, + -0.8130697 -0.14646193 0.56344181, + -0.80679172 -0.15883094 0.56908685, + -0.77855402 -0.168708 0.60447598, + -0.77105433 -0.18303207 0.60989726, + -0.74096197 -0.19302897 0.64320695, + -0.73216748 -0.20942485 0.64812952, + -0.70085907 -0.21931803 0.67874604, + -0.69084096 -0.23767397 0.68282497, + -0.658373 -0.24743301 0.71086001, + -0.64717895 -0.26771897 0.71378297, + -0.61342388 -0.27734593 0.73945284, + -0.6011529 -0.29948294 0.74089479, + -0.56639111 -0.30885306 0.76407516, + -0.55320394 -0.33269596 0.76372689, + -0.51818895 -0.34157097 0.78409791, + -0.52097189 -0.3363589 0.7845068, + -0.48946106 -0.34363002 0.80146509, + -0.50444007 -0.31204703 0.8050881, + -0.47113594 -0.31877398 0.8224439, + -0.48368418 -0.28796509 0.8265143, + -0.44847113 -0.29406905 0.84403616, + -0.45894617 -0.26369408 0.84843028, + -0.42228806 -0.26903504 0.8656171, + -0.43095291 -0.23884994 0.87018985, + -0.39278507 -0.24341802 0.88683009, + -0.39983085 -0.21330093 0.89142472, + -0.35999483 -0.21710989 0.90734059, + -0.36555892 -0.18705496 0.91179878, + -0.32387084 -0.19013192 0.9267996, + -0.32812089 -0.16005394 0.93097764, + -0.28522184 -0.16239692 0.9446035, + -0.28833395 -0.13214397 0.94836777, + -0.24439394 -0.13381997 0.96039778, + -0.24652503 -0.10344201 0.9636001, + -0.20154998 -0.10454599 0.97388285, + -0.20286199 -0.0742402 0.97638899, + -0.15710005 -0.074875213 0.98474026, + -0.15778306 -0.044639416 0.98646438, + -0.11217595 -0.044920277 0.9926725, + -0.11242799 -0.013736598 0.9935649, + -0.12076201 -0.015904002 0.99255413, + -0.12077906 1.8469209e-005 0.99267948, + -0.12076095 1.7465794e-005 0.99268162, + -0.12074404 -0.015904006 0.99255633, + -0.16932207 -0.012742107 0.98547846, + -0.16933706 0.0013225104 0.98555738, + -0.16931404 0.0013225103 0.98556125, + -0.2971321 0.070632525 -0.95222038, + -0.25055712 0.071613841 -0.96544945, + -0.24947201 0.100853 -0.96311599, + -0.20304993 0.10197696 -0.97384363, + -0.20182499 0.13194001 -0.97049397, + -0.15567292 0.13306995 -0.97880453, + -0.15444693 0.16359593 -0.97436255, + -0.10948998 0.16458699 -0.98026687, + -0.10841902 0.19562005 -0.97466826, + -0.06451232 0.19637008 -0.97840536, + -0.063754879 0.22753893 -0.97167963, + -0.021137998 0.22795197 -0.97344285, + -0.020857194 0.25911695 -0.96562076, + 0.02036551 0.25912011 -0.96563047, + 0.0206545 0.227983 -0.97344601, + 0.063241802 0.22757401 -0.97170502, + 0.064005211 0.19650704 -0.97841114, + 0.10778298 0.19576398 -0.97470987, + 0.10885798 0.16486299 -0.98029089, + 0.15387607 0.16387306 -0.97440636, + 0.15509394 0.13325995 -0.97887063, + 0.20114991 0.13213494 -0.97060752, + 0.20238596 0.10185397 -0.97399473, + 0.24889709 0.10073303 -0.96327734, + 0.24999888 0.070876062 -0.96564853, + 0.29666007 0.069905318 -0.95242125, + 0.29749301 0.040654801 -0.95385802, + 0.29779002 0.041080803 -0.95374709, + 0.298188 0.0129743 -0.95441902, + 0.3135561 0.0046520317 -0.94955838, + 0.31353989 0.0046520983 -0.94956362, + 0.3446171 0.018941803 -0.93855226, + 0.34425783 0.039979883 -0.93802351, + -0.69793826 -0.0041052615 -0.71614623, + -0.68829715 0.014542404 -0.72528321, + -0.60997188 0.018212195 -0.7922138, + -0.60957301 0.033446901 -0.79202402, + -0.56782812 0.034730308 -0.82241416, + -0.56678104 0.057547808 -0.82185614, + -0.52322811 0.059526313 -0.85011119, + -0.52161193 0.084109291 -0.84902686, + -0.47708312 0.086640522 -0.87457716, + -0.47490701 0.112784 -0.87277901, + -0.42963707 0.11572801 -0.89555514, + -0.42691615 0.14355305 -0.89282429, + -0.38095516 0.14677507 -0.91286927, + -0.37779906 0.17580801 -0.90904313, + -0.33144292 0.17914796 -0.92631078, + -0.3279449 0.20953695 -0.92116576, + -0.28212893 0.21279295 -0.93547976, + -0.27849704 0.24389303 -0.92895412, + -0.23353803 0.24691802 -0.94047409, + -0.22998406 0.27822807 -0.93257523, + -0.18605305 0.28090009 -0.94153035, + -0.18280296 0.31185994 -0.93237674, + -0.14027996 0.3140679 -0.93897974, + -0.13749495 0.34481588 -0.92854565, + -0.096797578 0.34648791 -0.93304676, + -0.094637558 0.37673381 -0.92147458, + -0.055969708 0.37783906 -0.92417812, + -0.054570712 0.40758508 -0.91153526, + -0.017983194 0.40812784 -0.91274768, + -0.017491095 0.43733487 -0.89912868, + 0.016894702 0.43733907 -0.89913809, + 0.017391605 0.40809613 -0.91277331, + 0.05416939 0.40755892 -0.91157079, + 0.055557508 0.37792906 -0.92416614, + 0.094268352 0.37682882 -0.92147356, + 0.096437901 0.34638301 -0.93312299, + 0.13690102 0.34472802 -0.92866611, + 0.13970003 0.31401709 -0.93908322, + 0.18238194 0.31180787 -0.93247664, + 0.18564795 0.28076094 -0.94165176, + 0.2295921 0.27809513 -0.93271142, + 0.23311706 0.24712107 -0.94052523, + 0.27805892 0.24410091 -0.92903066, + 0.281663 0.21333399 -0.93549699, + 0.32749814 0.2100741 -0.92120242, + 0.3309769 0.17989896 -0.92633176, + 0.37726405 0.17655702 -0.90912014, + 0.3804369 0.14742997 -0.91297978, + 0.42639592 0.14419897 -0.89296877, + 0.4291378 0.11622195 -0.89573056, + 0.47438481 0.11327196 -0.87299973, + 0.476625 0.086365603 -0.87485403, + 0.52120578 0.08384306 -0.84930259, + 0.52287591 0.058271684 -0.85041481, + 0.56653684 0.056332182 -0.82210869, + 0.56762183 0.032090988 -0.82266372, + 0.6094749 0.030902792 -0.79220283, + 0.60990286 0.012611497 -0.7923758, + 0.61494809 0.0055426816 -0.78854817, + 0.61495811 -0.0026677707 -0.7885552, + 0.57548106 0.016224802 -0.81765413, + 0.57556319 0.00021721507 -0.81775731, + 0.57558382 0.00021722693 -0.81774271, + 0.5756501 0.00021427606 -0.81769615, + 0.57564199 0.0047720401 -0.81768799, + 0.57557619 0.004772522 -0.8177343, + 0.56848019 0.007555183 -0.82266229, + 0.56794369 0.032623883 -0.8224206, + 0.52446991 0.033748098 -0.85075986, + 0.52337688 0.059092786 -0.85004979, + 0.47892907 0.060878806 -0.87574011, + 0.47728094 0.087426096 -0.8743909, + 0.43206105 0.089723609 -0.8973701, + 0.42989916 0.11743405 -0.89520729, + 0.38394892 0.12009697 -0.91551077, + 0.38135895 0.14886598 -0.91236186, + 0.33485496 0.15173799 -0.92997187, + 0.3319439 0.18136495 -0.92569977, + 0.2857849 0.18424794 -0.94041467, + 0.28267205 0.21481605 -0.93485326, + 0.23726809 0.21755408 -0.94677037, + 0.23414902 0.24858002 -0.93988413, + 0.18953907 0.25105208 -0.94923538, + 0.186619 0.28207499 -0.94106698, + 0.14312193 0.28416285 -0.94803351, + 0.14056899 0.31513798 -0.93857789, + 0.099112198 0.31673101 -0.94332302, + 0.097128764 0.34722689 -0.93273765, + 0.057220291 0.34830597 -0.93563288, + 0.055921327 0.37835118 -0.92397141, + 0.018143302 0.37888205 -0.9252671, + 0.017687999 0.40842393 -0.9126209, + -0.018247604 0.4084211 -0.91261125, + -0.018696401 0.37895307 -0.92522711, + -0.056466907 0.37841505 -0.92391211, + -0.057759676 0.34837589 -0.93557364, + -0.097459413 0.34729704 -0.93267709, + -0.099449836 0.31675813 -0.94327837, + -0.14111999 0.31515098 -0.93849087, + -0.14364107 0.28434515 -0.94790047, + -0.18705404 0.28225306 -0.94092727, + -0.19000401 0.25082299 -0.94920301, + -0.23455206 0.24835105 -0.93984425, + -0.23769906 0.21704005 -0.94678026, + -0.28315485 0.2142999 -0.9348256, + -0.28627795 0.18360296 -0.94039077, + -0.33248091 0.18072195 -0.92563277, + -0.33538684 0.15108493 -0.92988658, + -0.38188007 0.14821903 -0.91224927, + -0.38445592 0.11967097 -0.91535378, + -0.43044195 0.11700998 -0.89500189, + -0.43255216 0.089974128 -0.89710832, + -0.47771794 0.087669395 -0.87412786, + -0.47931689 0.062075686 -0.87544376, + -0.52367288 0.060256284 -0.8497858, + -0.52472806 0.036336504 -0.85049415, + -0.56806833 0.035129014 -0.82223141, + -0.56861615 0.011595304 -0.82252127, + -0.53741693 -0.0036133695 -0.84330887, + -0.53669089 -0.003714439 -0.8437708, + -0.49550119 0.00018832408 -0.86860728, + -0.53741688 -0.0038795192 -0.84330779, + -0.57797593 0.023199799 -0.8157239, + -0.57813984 0.00025051591 -0.8159377, + -0.57818896 0.00025054297 -0.81590289, + -0.57816809 0.0078155221 -0.81588018, + -0.57808912 0.0078164022 -0.81593621, + -0.57810885 0.0002540969 -0.81595969, + -0.61745566 -0.0031033882 -0.78659952, + -0.61743212 0.0084998515 -0.78657818, + -0.61741489 0.0085000582 -0.78659183, + -0.65518701 0.018009299 -0.755252, + -0.64995605 0.011210401 -0.75988913, + -0.64945781 0.031646091 -0.7597388, + -0.6093111 0.033000208 -0.7922442, + -0.60828787 0.054693986 -0.79182982, + -0.56633389 0.056792885 -0.82221681, + -0.56472796 0.080283396 -0.82136285, + -0.5209679 0.083036378 -0.84952784, + -0.51875705 0.10827901 -0.84803712, + -0.47413296 0.11151299 -0.8733629, + -0.47132081 0.13852195 -0.87101573, + -0.42601192 0.14209697 -0.89348876, + -0.42267984 0.17042494 -0.89011073, + -0.37677085 0.17419194 -0.90978068, + -0.37297791 0.20398396 -0.90513974, + -0.32679212 0.20777908 -0.92197335, + -0.32270989 0.23858692 -0.91593373, + -0.27733597 0.24218497 -0.92974788, + -0.27322695 0.27322695 -0.92233074, + -0.2287619 0.27650288 -0.93338859, + -0.224806 0.307567 -0.92458898, + -0.18171391 0.31039086 -0.9330796, + -0.17811996 0.34130991 -0.92291975, + -0.13655099 0.34360701 -0.929133, + -0.13351306 0.37415618 -0.9177044, + -0.093922362 0.37586686 -0.92190164, + -0.091577306 0.40601805 -0.9092651, + -0.054175094 0.40713295 -0.91176087, + -0.052678619 0.43661815 -0.8981033, + -0.017330097 0.4371599 -0.89921677, + -0.016802292 0.4662838 -0.88447559, + 0.016169794 0.46628883 -0.88448471, + 0.016701296 0.4371289 -0.89924377, + 0.052055594 0.43659693 -0.89814991, + 0.053567883 0.40687084 -0.91191369, + 0.090911344 0.40576819 -0.90944344, + 0.093271427 0.37562016 -0.92206836, + 0.13291803 0.3739171 -0.91788822, + 0.135957 0.34351799 -0.92925298, + 0.17769408 0.34121916 -0.92303544, + 0.18129 0.31033701 -0.93317997, + 0.22450189 0.30751085 -0.9246816, + 0.22844894 0.27648395 -0.93347079, + 0.27280596 0.27322197 -0.92245686, + 0.2768949 0.24239092 -0.92982566, + 0.32236198 0.23878796 -0.91600388, + 0.32639298 0.20838997 -0.92197686, + 0.37253398 0.20459397 -0.90518486, + 0.37630299 0.17504799 -0.90981001, + 0.42209685 0.17127794 -0.89022368, + 0.4254739 0.14271396 -0.89364678, + 0.47075981 0.13913296 -0.87122172, + 0.47359988 0.11198397 -0.87359184, + 0.51834226 0.10873405 -0.84823239, + 0.52060509 0.08284311 -0.84976912, + 0.56439131 0.080098234 -0.82161242, + 0.56605989 0.055527885 -0.82249182, + 0.60808271 0.053474072 -0.79207063, + 0.60914075 0.030333688 -0.79248172, + 0.64937925 0.029086811 -0.75990832, + 0.64986718 0.0074595618 -0.7600112, + 0.65289778 0.0061906176 -0.75742072, + 0.65297997 0.0061899391 -0.75734991, + 0.68827194 0.0085901394 -0.72540194, + 0.68784225 0.027257109 -0.72534823, + 0.64908195 0.028566096 -0.7601819, + 0.648063 0.050494201 -0.759911, + 0.60761279 0.052658681 -0.79248571, + 0.60598701 0.076048702 -0.79183102, + 0.56373 0.078962997 -0.82217598, + 0.5614658 0.10380896 -0.82096273, + 0.5175209 0.10734298 -0.84891081, + 0.51462394 0.13364199 -0.84693688, + 0.46983281 0.13759096 -0.87196672, + 0.46633187 0.16532995 -0.86902285, + 0.42102006 0.16952302 -0.89106911, + 0.41701895 0.19836697 -0.88698685, + 0.37130511 0.20264708 -0.90612727, + 0.366889 0.232694 -0.90069199, + 0.32112288 0.23688892 -0.91693163, + 0.31651998 0.26754197 -0.91007489, + 0.271597 0.27144101 -0.92333901, + 0.267019 0.30236501 -0.91502798, + 0.22331093 0.30583388 -0.92552567, + 0.21897601 0.336676 -0.91580498, + 0.17651106 0.33963212 -0.92384738, + 0.17259499 0.37026799 -0.91275001, + 0.13190003 0.37262508 -0.91856027, + 0.12855798 0.40329394 -0.90599489, + 0.090277031 0.40500814 -0.90984529, + 0.087746255 0.43498227 -0.89615351, + 0.051602092 0.43608493 -0.89842486, + 0.049989589 0.46558189 -0.88359177, + 0.015998397 0.46610489 -0.88458478, + 0.015435806 0.49492916 -0.86879629, + -0.016105592 0.49492475 -0.86878657, + -0.016665494 0.46613681 -0.8845557, + -0.050647888 0.46560389 -0.88354278, + -0.052255791 0.43614092 -0.89835978, + -0.088315926 0.43503216 -0.89607328, + -0.090836793 0.40513095 -0.9097349, + -0.12906994 0.40340981 -0.90587056, + -0.13240702 0.37275109 -0.91843623, + -0.1730819 0.37038681 -0.91260958, + -0.17698795 0.33979088 -0.92369765, + -0.21928906 0.33683908 -0.91567022, + -0.22363903 0.30592304 -0.92541713, + -0.26740396 0.30244297 -0.91488987, + -0.2719911 0.27140608 -0.92323333, + -0.31690192 0.26750195 -0.90995377, + -0.32151103 0.23674802 -0.91683209, + -0.36739087 0.23253791 -0.90052772, + -0.37183392 0.20217095 -0.90601677, + -0.41751984 0.19789493 -0.88685668, + -0.421565 0.16860799 -0.89098501, + -0.46682781 0.16443294 -0.8689267, + -0.4703021 0.13682503 -0.87183416, + -0.515113 0.132889 -0.84675801, + -0.5179652 0.10693604 -0.84869128, + -0.5618999 0.10341198 -0.82071584, + -0.56410491 0.079211891 -0.82189488, + -0.60631496 0.076287992 -0.79155689, + -0.60787606 0.053977709 -0.79219514, + -0.64823717 0.051762011 -0.75967717, + -0.64921701 0.031224901 -0.75996202, + -0.68790138 0.029796315 -0.72519237, + -0.72607285 0.012300097 -0.68750781, + -0.72517663 0.011078794 -0.68847364, + -0.72475702 0.0278864 -0.68844002, + -0.68767381 0.029384492 -0.72542483, + -0.68675077 0.04866958 -0.72526175, + -0.64781505 0.051006809 -0.76008815, + -0.64631474 0.07214658 -0.75965267, + -0.60571688 0.075229883 -0.79211581, + -0.60356975 0.098288462 -0.79122871, + -0.56111586 0.10203898 -0.82142383, + -0.55827409 0.12697802 -0.81988215, + -0.51417172 0.13126792 -0.84758252, + -0.51063806 0.15799302 -0.84515512, + -0.46574795 0.16260898 -0.86984891, + -0.46155283 0.19104692 -0.86629671, + -0.4162572 0.19581409 -0.88791144, + -0.41153309 0.22552006 -0.88305223, + -0.36597711 0.23027809 -0.90168327, + -0.36090603 0.26079902 -0.89539415, + -0.3155109 0.26536295 -0.91106278, + -0.31035593 0.29609594 -0.90333074, + -0.2659249 0.30026188 -0.91603869, + -0.26083687 0.33126786 -0.90676659, + -0.21790993 0.33490089 -0.91670966, + -0.21315089 0.36569083 -0.90600055, + -0.17183593 0.36872482 -0.91351759, + -0.16754596 0.39951491 -0.90128577, + -0.12788405 0.40191615 -0.90670228, + -0.12429597 0.43221191 -0.89316475, + -0.087380655 0.4339228 -0.89670259, + -0.084648728 0.46383119 -0.88187027, + -0.050032619 0.46491918 -0.88393831, + -0.048316911 0.49406013 -0.86808419, + -0.015774803 0.49457613 -0.8689912, + 0.015075305 0.49455017 -0.86901832, + 0.0476261 0.49404499 -0.86813098, + 0.049345318 0.46486518 -0.88400531, + 0.084006794 0.46378693 -0.88195491, + 0.086748555 0.4337998 -0.89682359, + 0.12371194 0.43209678 -0.89330161, + 0.12731305 0.40172514 -0.90686733, + 0.16700296 0.3993319 -0.90146774, + 0.17129694 0.36853689 -0.91369468, + 0.21272208 0.36550513 -0.90617627, + 0.21750295 0.33460391 -0.91691476, + 0.26047894 0.3309769 -0.90697575, + 0.26553708 0.30017912 -0.91617829, + 0.30998501 0.29602 -0.90348297, + 0.31512815 0.26540011 -0.91118443, + 0.36062199 0.26083201 -0.89549899, + 0.36563203 0.23068602 -0.90171909, + 0.41117299 0.225927 -0.88311601, + 0.415865 0.196467 -0.88795102, + 0.46109611 0.19169804 -0.86639619, + 0.46526799 0.163536 -0.869932, + 0.51015711 0.15890105 -0.84527516, + 0.51371521 0.13207905 -0.84773332, + 0.55780393 0.12777099 -0.82007891, + 0.56069613 0.10246602 -0.82165718, + 0.60318309 0.098701321 -0.7914722, + 0.60539168 0.074994966 -0.79238665, + 0.64605284 0.071919985 -0.75989681, + 0.64761883 0.049699288 -0.76034182, + 0.68660885 0.04742039 -0.72547883, + 0.68756592 0.026757196 -0.72562891, + 0.72473198 0.0253904 -0.68856299, + 0.72512984 0.0078122183 -0.68856782, + 0.72400296 3.7848295e-005 -0.68979692, + 0.72397482 0.0083469478 -0.68977582, + 0.75688368 0.0044020084 -0.65353477, + 0.75689316 -0.0014075304 -0.65353715, + 0.75690651 -0.0014083391 -0.6535216, + 0.75689811 0.0044018705 -0.65351808, + 0.75972402 0.0091703804 -0.650181, + 0.75939661 0.023494288 -0.6502037, + 0.72446603 0.0248912 -0.68886101, + 0.72357309 0.044248104 -0.68882805, + 0.68618184 0.04663159 -0.72593385, + 0.68470603 0.067584507 -0.72567904, + 0.64545518 0.070828013 -0.76050717, + 0.64332592 0.093350992 -0.75987989, + 0.60241914 0.09732452 -0.79222417, + 0.59957922 0.12154304 -0.79103231, + 0.55688703 0.12614001 -0.82095414, + 0.55333221 0.15189408 -0.8189944, + 0.50904495 0.15695898 -0.84630787, + 0.50478989 0.18427795 -0.84334379, + 0.45984712 0.18956204 -0.86752915, + 0.45493314 0.21838808 -0.86333227, + 0.40983114 0.22369407 -0.88430732, + 0.4044849 0.25332093 -0.87876076, + 0.35917699 0.25850701 -0.89675301, + 0.35352108 0.28892207 -0.88968927, + 0.30854699 0.29379699 -0.90469998, + 0.30284184 0.32450986 -0.89609158, + 0.25905502 0.32887602 -0.9081471, + 0.25347203 0.35985902 -0.89791614, + 0.21136689 0.36360383 -0.90725756, + 0.20616205 0.3944751 -0.89548123, + 0.16567099 0.39756495 -0.90249389, + 0.16102405 0.42825809 -0.88919425, + 0.12255404 0.43065014 -0.89415932, + 0.11867999 0.46091095 -0.87947488, + 0.082984999 0.46259001 -0.88268, + 0.080055393 0.49229193 -0.86674088, + 0.046975687 0.49333188 -0.86857182, + 0.045155905 0.52207708 -0.85170209, + 0.013876297 0.54983687 -0.8351568, + -0.014576701 0.54983205 -0.8351481, + -0.045818724 0.52206123 -0.8516764, + -0.04763712 0.49331519 -0.86854529, + -0.080702521 0.49226511 -0.86669618, + -0.08362332 0.46263111 -0.88259822, + -0.11927298 0.46094295 -0.8793779, + -0.12313299 0.43075994 -0.89402688, + -0.16170296 0.42834991 -0.88902676, + -0.16630407 0.39786714 -0.90224427, + -0.20657603 0.39478305 -0.89525014, + -0.21179695 0.36379191 -0.90708178, + -0.25388193 0.36003992 -0.89772779, + -0.25943592 0.32919788 -0.90792173, + -0.30317083 0.32482681 -0.89586544, + -0.308916 0.29387099 -0.90455002, + -0.35387397 0.28898996 -0.8895269, + -0.35952297 0.25857097 -0.8965959, + -0.40481207 0.25338003 -0.87859315, + -0.41022316 0.22333908 -0.8842153, + -0.45533493 0.21803397 -0.8632099, + -0.46028799 0.18888099 -0.86744398, + -0.50522888 0.18360895 -0.84322685, + -0.50951415 0.15602507 -0.84619832, + -0.55377203 0.15098502 -0.81886512, + -0.55730879 0.12525895 -0.82080269, + -0.59999096 0.12068798 -0.79085088, + -0.60277611 0.096854925 -0.79201019, + -0.64367115 0.092896722 -0.7596432, + -0.64573175 0.071079575 -0.76024872, + -0.68494296 0.06782449 -0.72543293, + -0.68635792 0.047943592 -0.72568196, + -0.72369874 0.045494586 -0.68861479, + -0.72455025 0.02749891 -0.68867326, + -0.7594198 0.025958095 -0.65008283, + -0.78998917 0.0082619116 -0.61306512, + -0.78987682 0.0082640983 -0.6132099, + -0.75977421 0.011676203 -0.65008217, + -0.75899512 -0.0017538102 -0.65109408, + -0.7589519 0.010189899 -0.65106696, + -0.72605205 0.010668101 -0.68755704, + -0.72609806 0.00016333001 -0.68759108, + -0.72613215 0.00016335904 -0.68755519, + -0.69157016 -0.0051348815 -0.72229117, + -0.69154209 0.0095427707 -0.72227305, + -0.69153082 0.0095429579 -0.72228384, + -0.69156516 -0.0023984304 -0.72231019, + -0.6553272 0.00023495605 -0.75534517, + -0.65529698 0.00897869 -0.75531799, + -0.65522093 0.0089797191 -0.75538391, + -0.65525109 0.00023871603 -0.75541115, + -0.65529984 0.00023874994 -0.75536883, + -0.61743605 -0.0043479004 -0.78660911, + -0.62061214 -0.0038722109 -0.78410816, + -0.44708911 -0.003598891 -0.89448225, + -0.45218989 -0.0029494793 -0.89191675, + -0.45217714 0.0071689929 -0.89189929, + -0.45224294 0.0071684592 -0.89186591, + -0.45225307 -0.0047276006 -0.89187711, + -0.40795499 7.1316201e-005 -0.91300201, + -0.40791085 0.0070337178 -0.91299468, + -0.40792316 7.2010029e-005 -0.91301632, + -0.40794116 7.2016526e-005 -0.91300827, + -0.40792885 0.0070257075 -0.9129867, + -0.40794316 0.0070256223 -0.91298032, + -0.43673107 0.022204703 -0.8993181, + -0.43635201 0.039537702 -0.89890701, + -0.39066699 0.040449802 -0.91964298, + -0.38969994 0.067199491 -0.91848689, + -0.34310088 0.068538979 -0.93679464, + -0.34174284 0.096542753 -0.93482161, + -0.29506904 0.098153815 -0.95042109, + -0.29338902 0.12731901 -0.9474771, + -0.24705487 0.12905094 -0.96036953, + -0.24520104 0.15908901 -0.95633012, + -0.19918993 0.16080894 -0.96667665, + -0.19730103 0.19158103 -0.9614411, + -0.15188502 0.19315504 -0.9693411, + -0.15011497 0.22442494 -0.96285975, + -0.10625698 0.22571197 -0.96838188, + -0.10480598 0.25709596 -0.96068591, + -0.062244177 0.25801891 -0.96413267, + -0.06127283 0.28893015 -0.95538747, + -0.020201391 0.28941485 -0.95699054, + -0.019846398 0.31986296 -0.94725591, + 0.019409301 0.319866 -0.94726402, + 0.019771991 0.28945786 -0.95698655, + 0.060920384 0.28897694 -0.95539576, + 0.061887369 0.25810888 -0.96413153, + 0.10429402 0.25719503 -0.96071512, + 0.10575201 0.22583704 -0.96840811, + 0.14963202 0.22455303 -0.96290511, + 0.15138808 0.1935131 -0.96934748, + 0.19671592 0.19194393 -0.96148866, + 0.19861192 0.16122992 -0.96672553, + 0.24451102 0.15951301 -0.9564361, + 0.24638803 0.12927201 -0.96051115, + 0.29279903 0.12753801 -0.94763011, + 0.29448894 0.097999781 -0.95061678, + 0.34118608 0.096394025 -0.93504024, + 0.34258816 0.067545831 -0.9370544, + 0.38926092 0.066225782 -0.91874379, + 0.3902559 0.038197294 -0.91991377, + 0.43614006 0.037333302 -0.89910412, + 0.43653786 0.017803894 -0.89950973, + 0.44939479 0.004153878 -0.8933236, + 0.44939715 -0.0041947616 -0.89332229, + 0.40507686 0.00013605396 -0.91428268, + 0.40500191 0.00013602697 -0.91431576, + 0.40510994 0.00013080398 -0.9142679, + 0.40510491 0.0041686893 -0.91426075, + 0.40499681 0.004169248 -0.91430861, + 0.40507218 0.0041360818 -0.91427541, + 0.39099881 0.018387591 -0.92020756, + 0.3906149 0.038736794 -0.91973877, + 0.34393996 0.039512698 -0.93815988, + 0.34301803 0.068180904 -0.93685114, + 0.29625788 0.069326177 -0.95258862, + 0.29500285 0.098743357 -0.9503805, + 0.24844894 0.10010198 -0.96345878, + 0.24696609 0.13008904 -0.96025234, + 0.200699 0.13151599 -0.97078502, + 0.19914 0.161953 -0.96649599, + 0.15344898 0.16330598 -0.9745689, + 0.15196399 0.19427399 -0.96910501, + 0.10751302 0.19541803 -0.97480911, + 0.10626196 0.22648193 -0.96820164, + 0.063033216 0.22731906 -0.97177821, + 0.062163707 0.25844404 -0.96402413, + 0.020173308 0.2588931 -0.96569538, + 0.019842798 0.28954098 -0.9569599, + -0.020307101 0.28953803 -0.95695114, + -0.020629691 0.25884888 -0.96569753, + -0.062555626 0.2583971 -0.96401137, + -0.063431531 0.22714311 -0.97179347, + -0.10672201 0.22630203 -0.96819311, + -0.10798195 0.19506191 -0.97482854, + -0.15246001 0.19391502 -0.9690991, + -0.15395702 0.16294505 -0.97454923, + -0.19975697 0.16158698 -0.96642989, + -0.20131201 0.131236 -0.97069597, + -0.24758995 0.12980796 -0.96012974, + -0.24905303 0.10026202 -0.9632861, + -0.29558304 0.098897912 -0.95018411, + -0.29682288 0.07018698 -0.95234966, + -0.34343213 0.069029026 -0.93663734, + -0.34433213 0.041500013 -0.93793035, + -0.39082509 0.040687412 -0.91956526, + -0.39119107 0.022432001 -0.92003614, + -0.36262304 0.0068059908 -0.93191111, + -0.36263219 -0.0023502212 -0.93192941, + -0.3627021 -0.0023423405 -0.93190223, + -0.36269209 0.0068055815 -0.93188423, + -0.34486297 0.022641398 -0.93837988, + -0.34451798 0.041772597 -0.93784988, + -0.29794484 0.042475682 -0.95363754, + -0.29845798 0.016798098 -0.95427489, + -0.29807103 0.042656403 -0.9535901, + -0.25155598 0.043250695 -0.96687585, + -0.25084305 0.072016813 -0.96534526, + -0.20432892 0.072825879 -0.97618961, + -0.20342095 0.10248598 -0.97371274, + -0.157084 0.103375 -0.98215997, + -0.15612194 0.13366696 -0.97865164, + -0.11079403 0.13449302 -0.98470122, + -0.10992295 0.16514492 -0.98012453, + -0.065407574 0.16579594 -0.98398864, + -0.064759187 0.19667496 -0.97832775, + -0.021502398 0.19704397 -0.98015887, + -0.021257099 0.22809497 -0.97340685, + 0.020750508 0.22809708 -0.97341734, + 0.020991001 0.19722202 -0.98013413, + 0.064288117 0.19685705 -0.97832227, + 0.064922296 0.16597898 -0.98398989, + 0.10922495 0.16533493 -0.98017055, + 0.11010806 0.13457806 -0.98476648, + 0.15546602 0.13375501 -0.97874409, + 0.15643096 0.10329398 -0.98227274, + 0.20278992 0.10240895 -0.97385252, + 0.20371193 0.072164275 -0.97636765, + 0.25034502 0.071362808 -0.96552312, + 0.25107312 0.041654717 -0.96707147, + 0.25137609 0.042081013 -0.96697438, + 0.20464303 0.042556904 -0.97791111, + 0.20403507 0.072607726 -0.97626734, + 0.157438 0.073243 -0.98480898, + 0.15671699 0.10367598 -0.98218685, + 0.11106002 0.10432301 -0.98832309, + 0.11035696 0.13489896 -0.98469466, + 0.065562323 0.13543704 -0.98861438, + 0.065032333 0.16611607 -0.9839595, + 0.021135891 0.16643092 -0.98582655, + 0.020919302 0.19713503 -0.98015314, + -0.021575889 0.19713192 -0.98013949, + -0.021784095 0.16645895 -0.98580778, + -0.065682814 0.16614005 -0.98391223, + -0.066218585 0.13529697 -0.98858976, + -0.11099803 0.13475603 -0.98464227, + -0.111699 0.104361 -0.98824698, + -0.15733492 0.10370995 -0.98208451, + -0.15805808 0.073781639 -0.98466951, + -0.20455895 0.073140785 -0.97611779, + -0.20515689 0.043911677 -0.97774351, + -0.25167787 0.043421779 -0.96683651, + -0.25195992 0.022649392 -0.96747261, + -0.26955813 -0.0018140208 -0.96298248, + -0.26964292 -0.0018059993 -0.96295863, + -0.26963398 0.007210149 -0.96293586, + -0.26954892 0.0072105071 -0.96295965, + -0.31635699 0.032628201 -0.94807899, + -0.31653285 -0.00011183095 -0.94858152, + -0.31657904 -0.00011181901 -0.94856614, + -0.31657016 0.0069759833 -0.94854349, + -0.31648108 0.0069764419 -0.94857323, + -0.31648996 -0.00010659098 -0.94859588, + -0.3527509 -0.004435529 -0.93570673, + -0.204548 -0.0030034401 0.97885197, + -0.16932702 0.0013214301 0.98555911, + -0.16930301 -0.016128102 0.98543215, + -0.20505692 -0.013229296 0.97866064, + -0.21743396 -0.016188296 0.97594076, + -0.217465 -0.00051527499 0.97606802, + -0.21734802 -0.00052501407 0.97609413, + -0.21731603 -0.016188702 0.97596711, + -0.26508304 -0.011731802 0.96415424, + -0.26510391 0.0014994094 0.96421862, + -0.265012 0.00149943 0.96424401, + -0.85207599 0.037818301 -0.52205002, + -0.87528759 0.034941483 -0.48233876, + -0.87608111 0.014914602 -0.48193306, + -0.87142289 -0.00066195591 -0.49053195, + -0.87136787 0.010818099 -0.49051094, + -0.8713156 0.010820494 -0.49060377, + -0.87137002 -0.00065793499 -0.49062601, + -0.89436901 -0.00835294 -0.44725201, + -0.8943556 0.0093587451 -0.4472588, + -0.89435869 0.0093585765 -0.44725284, + -0.89437199 -0.0083542597 -0.44724599, + -0.88268274 -0.00059124688 -0.46996889, + -0.30412197 -0.0028246997 0.95262891, + -0.26509106 0.0014942203 0.96422225, + -0.26505303 -0.016177703 0.9640981, + -0.29804698 -0.012839599 0.95446485, + -0.312011 -0.016163999 0.94994098, + -0.31205511 -0.0011336204 0.95006335, + -0.31202084 -0.0011371895 0.95007449, + -0.31197584 -0.016164092 0.94995254, + -0.35821509 -0.011260003 0.93357122, + -0.3582409 0.0015949097 0.93362778, + -0.35819811 0.0015949205 0.93364435, + -0.35814792 -0.016058195 0.93352675, + -0.35817096 -0.016058099 0.93351787, + -0.35822204 0.0015936802 0.93363512, + -0.40361184 -0.0028993292 0.91492569, + -0.40355906 -0.015803803 0.91481709, + -0.40351483 -0.015803993 0.91483659, + -0.40356916 -0.0018393107 0.91494727, + -0.40045491 -0.0022120595 0.91631377, + -0.57941282 -0.0027181192 0.81502968, + -0.57413399 -0.0034731899 0.81875402, + -0.5740748 -0.014202096 0.81867969, + -0.61366802 -0.011735 0.78947699, + -0.61371469 0.0014157793 0.78952664, + -0.61380011 0.0014157303 0.78946018, + -0.65163469 -0.012813994 0.75842464, + -0.65169269 -0.00092681253 0.75848264, + -0.6136741 0.0014217703 0.78955817, + -0.61361313 -0.013513103 0.78949118, + -0.64962715 -0.011940603 0.76015919, + -0.64871997 -0.036737397 0.76013988, + -0.68654895 -0.035098895 0.72623593, + -0.68478197 -0.059035692 0.72635293, + -0.72076362 -0.056154273 0.69090265, + -0.71810097 -0.080039591 0.69132096, + -0.75177413 -0.075839706 0.65504503, + -0.74821794 -0.099700786 0.65591896, + -0.7797097 -0.094093464 0.61903077, + -0.7753529 -0.11758499 0.62048495, + -0.805107 -0.110435 0.58275801, + -0.80002385 -0.13355298 0.58491492, + -0.82825917 -0.12473303 0.54628611, + -0.82247883 -0.14768697 0.54928786, + -0.84903711 -0.13718101 0.51021308, + -0.84259403 -0.160134 0.51419097, + -0.86771113 -0.14779902 0.47458705, + -0.86068898 -0.17073201 0.479651, + -0.88487643 -0.15621008 0.4388532, + -0.87731898 -0.179315 0.445149, + -0.90079927 -0.16224906 0.40278515, + -0.89274311 -0.18574701 0.41049707, + -0.91553432 -0.16582505 0.36646813, + -0.90697187 -0.19008997 0.37585595, + -0.92934185 -0.16663499 0.32947898, + -0.92601711 -0.17624801 0.33381003, + -0.94846624 -0.14795204 0.28021806, + -0.95024925 -0.14199702 0.27724206, + -0.96876067 -0.11305296 0.22072993, + -0.96927863 -0.11660396 0.21656993, + -0.948838 -0.149693 0.27802601, + -0.95140654 -0.14089693 0.27381289, + -0.93156087 -0.16635899 0.32329398, + -0.93828613 -0.14454702 0.31420603, + -0.91783875 -0.16590096 0.36062291, + -0.92443067 -0.14443696 0.35293889, + -0.90315157 -0.16260593 0.39733681, + -0.90952742 -0.14126907 0.39090016, + -0.88724613 -0.15678501 0.43383506, + -0.89332914 -0.13538902 0.42852405, + -0.87002897 -0.148524 0.47009599, + -0.87573725 -0.12695403 0.46579713, + -0.85125411 -0.13798901 0.50628608, + -0.85645545 -0.11633393 0.50294173, + -0.83035117 -0.12557803 0.54290611, + -0.83499712 -0.10366601 0.54040104, + -0.80700791 -0.11125498 0.57996595, + -0.81104887 -0.088899195 0.57818395, + -0.78136665 -0.094840258 0.61682367, + -0.78471118 -0.072039418 0.61566114, + -0.75311309 -0.076459207 0.65343308, + -0.75565082 -0.053574789 0.65277982, + -0.72174925 -0.056616019 0.68983525, + -0.72345066 -0.033645984 0.68955564, + -0.68720108 -0.035404902 0.72560406, + -0.68806791 -0.012006298 0.72554696, + -0.68814176 -0.012014295 0.72547674, + -0.72247499 -0.0121127 0.69129097, + -0.72281677 -0.012106596 0.69093376, + -0.72493738 -0.011044705 0.68872637, + -0.72408122 -0.03395981 0.68887824, + -0.75819963 -0.032103784 0.65123171, + -0.75658214 -0.054038808 0.65166205, + -0.78831464 -0.050846774 0.6131677, + -0.78593814 -0.072643705 0.61402303, + -0.81565702 -0.0679712 0.57452899, + -0.8125661 -0.089627005 0.57593703, + -0.84039015 -0.083339907 0.53553605, + -0.836716 -0.104455 0.53758299, + -0.86245668 -0.096537963 0.49683881, + -0.8582989 -0.11712299 0.49960494, + -0.88225585 -0.10744999 0.45834395, + -0.87768269 -0.12770195 0.46191481, + -0.90019774 -0.11604197 0.41973591, + -0.89529711 -0.13602701 0.42419305, + -0.91657025 -0.12210403 0.38077509, + -0.91147923 -0.14174204 0.38615409, + -0.93147373 -0.12536097 0.34152791, + -0.92631298 -0.14468899 0.347864, + -0.94516754 -0.12542194 0.30154186, + -0.94005603 -0.14452399 0.30888101, + -0.95792037 -0.12164505 0.25998309, + -0.95301539 -0.14054805 0.26834309, + -0.96997225 -0.11284603 0.21545205, + -0.969091 -0.116667 0.217374, + -0.98305923 -0.086678021 0.16149804, + -0.98446554 -0.078676365 0.15696393, + -0.99388009 -0.049499307 0.098753914, + -0.99435425 -0.045176812 0.096013822, + -0.99931097 -0.015801899 0.0335836, + -0.99936014 -0.014527001 0.032685902, + -0.99926734 0.015544405 -0.034975011, + -0.99931926 0.014301703 -0.034008909, + -0.99328679 0.044842288 -0.10663298, + -0.99356645 0.042694017 -0.10489506, + -0.98074055 0.073630661 -0.18090491, + -0.98139924 0.070716918 -0.17847905, + -0.96077877 0.10215198 -0.25781593, + -0.96182865 0.098971061 -0.25512791, + -0.93238664 0.13072996 -0.33699387, + -0.93369979 0.12776497 -0.33448592, + -0.89506114 0.15912502 -0.41658705, + -0.89637828 0.15678406 -0.41463816, + -0.848221 0.187326 -0.49540901, + -0.85665143 0.17485109 -0.48536125, + -0.78533912 0.20981804 -0.58242506, + -0.79325134 0.20037208 -0.57498127, + -0.72815722 0.22555207 -0.64723521, + -0.74530923 0.20708407 -0.63374323, + -0.67674476 0.22866993 -0.69980478, + -0.70128405 0.20385604 -0.68311304, + -0.63052225 0.22195508 -0.74375921, + -0.64974177 0.20338693 -0.73244077, + -0.57648098 0.21862499 -0.78732002, + -0.59099805 0.20514803 -0.78015113, + -0.51583183 0.21786693 -0.8285237, + -0.52395403 0.21055603 -0.82531112, + -0.44861495 0.22093298 -0.86598688, + -0.44989988 0.21979894 -0.86560881, + -0.37619215 0.22803408 -0.89804232, + -0.36994481 0.23351389 -0.89922857, + -0.29975003 0.23978902 -0.9233911, + -0.28725901 0.250866 -0.92441797, + -0.22319807 0.25529808 -0.94074738, + -0.20656104 0.27052006 -0.94029325, + -0.15086991 0.27331886 -0.95001841, + -0.13289905 0.2906391 -0.94755834, + -0.086708598 0.29213601 -0.952438, + -0.069665588 0.30980393 -0.94824475, + -0.03303811 0.31038913 -0.95003533, + -0.019610608 0.32567513 -0.94527835, + 0.007969643 0.32572711 -0.94543034, + 0.015160498 0.33490497 -0.94212991, + 0.035295717 0.33473414 -0.94165146, + 0.040126685 0.34175888 -0.93893063, + 0.053678919 0.34154212 -0.93833238, + 0.055506501 0.344614 -0.93710202, + 0.063911423 0.34444013 -0.93663037, + 0.059318677 0.33536288 -0.94021964, + 0.065060973 0.33524284 -0.93988252, + 0.062428776 0.32902688 -0.94225466, + 0.064702809 0.32897902 -0.94211811, + 0.061501514 0.31980509 -0.94548523, + 0.060774829 0.31981915 -0.94552749, + 0.057673685 0.30879995 -0.94937676, + 0.054277588 0.30885893 -0.94955778, + 0.05265459 0.30147594 -0.95201874, + 0.041928999 0.30162901 -0.95250303, + 0.026958097 0.21184297 -0.97693187, + 0.020239994 0.21187696 -0.97708678, + -0.0090792086 -0.040562388 -0.99913573, + -0.0046735499 -0.040563598 -0.99916601, + -0.022890102 -0.30837303 -0.95099014, + -0.0071994672 -0.30844587 -0.95121467, + -0.013065903 -0.57586813 -0.81743819, + 0.013612702 -0.57586408 -0.81743211, + 0.0076117474 -0.30866387 -0.95114064, + 0.0233691 -0.30858701 -0.95090902, + 0.0050238185 -0.040082689 -0.99918377, + 0.0093894638 -0.040081415 -0.99915236, + -0.020198593 0.21450692 -0.97651362, + -0.0272553 0.214471 -0.97635001, + -0.042083114 0.30336612 -0.95194435, + -0.05297808 0.30320787 -0.95145065, + -0.054236989 0.30893394 -0.94953579, + -0.057660572 0.30887386 -0.94935352, + -0.060721178 0.31974888 -0.94555461, + -0.061409377 0.31973588 -0.94551462, + -0.064813927 0.32949114 -0.94193149, + -0.062644467 0.32953584 -0.9420625, + -0.065042809 0.33520004 -0.93989915, + -0.059263006 0.33532104 -0.94023812, + -0.061963886 0.34066191 -0.93814176, + -0.052915499 0.34084001 -0.938631, + -0.05624 0.34642601 -0.93638998, + -0.043543804 0.34664503 -0.93698514, + -0.037443284 0.33779487 -0.94047463, + -0.01784279 0.33797884 -0.94098455, + -0.0072409129 0.32446411 -0.94587034, + 0.020567808 0.32440311 -0.94569534, + 0.034216892 0.30885994 -0.95049179, + 0.07105349 0.30825996 -0.94864488, + 0.087740369 0.29095292 -0.95270562, + 0.13412397 0.28943995 -0.94775277, + 0.15236701 0.27184603 -0.95020211, + 0.2082631 0.26902613 -0.94034648, + 0.22511303 0.25359002 -0.9407531, + 0.28937805 0.24913506 -0.92422521, + 0.30193099 0.237982 -0.92314798, + 0.37217781 0.2316989 -0.89877659, + 0.37822315 0.22638507 -0.89760631, + 0.45198795 0.21814597 -0.86493886, + 0.45022005 0.21970902 -0.8654651, + 0.52547818 0.20934707 -0.82464927, + 0.51616287 0.21774395 -0.82834983, + 0.59130788 0.20501995 -0.77994984, + 0.57532811 0.21984605 -0.7878232, + 0.64866382 0.20456496 -0.73306781, + 0.62875623 0.22374508 -0.74471724, + 0.699687 0.20557401 -0.68423498, + 0.6753462 0.23010406 -0.7006852, + 0.74411923 0.20843408 -0.63469821, + 0.72665179 0.22717692 -0.64835775, + 0.79200786 0.20188197 -0.57616591, + 0.79648584 0.19645196 -0.57185388, + 0.85283428 0.16965505 -0.49385318, + 0.85301298 0.169397 -0.493633, + 0.89982778 0.14159697 -0.41262591, + 0.89837301 0.144181 -0.414895, + 0.93587512 0.11565501 -0.33280903, + 0.93444711 0.11887102 -0.33567604, + 0.9630335 0.089922555 -0.25392988, + 0.96200562 0.093029372 -0.2566919, + 0.98199087 0.064373493 -0.17762299, + 0.98138279 0.067061387 -0.17997396, + 0.99378234 0.038876314 -0.10433304, + 0.99353665 0.040765684 -0.10593896, + 0.99934453 0.013001094 -0.033786286, + 0.99931467 0.013724695 -0.03437759, + 0.9993611 -0.013251602 0.033192404, + 0.9993369 -0.013865299 0.033669498, + 0.99430764 -0.040571384 0.09852086, + 0.99424547 -0.041117217 0.098920844, + 0.98490465 -0.066438481 0.15983994, + 0.98459399 -0.068166301 0.16102199, + 0.97130686 -0.092715792 0.21901298, + 0.97053611 -0.095919415 0.22104102, + 0.95348078 -0.12000297 0.27653894, + 0.95206678 -0.12475897 0.27929193, + 0.93168473 -0.14815997 0.33168092, + 0.92938036 -0.15474506 0.33512112, + 0.90575159 -0.17767091 0.38476881, + 0.90230298 -0.186307 0.38876599, + 0.87546003 -0.20886099 0.43582901, + 0.8706879 -0.21956398 0.44010693, + 0.84077489 -0.24168298 0.48444495, + 0.84495085 -0.23290896 0.48146793, + 0.8174473 -0.25083208 0.51852018, + 0.83096498 -0.22133701 0.51039898, + 0.80339783 -0.23689994 0.54628789, + 0.81539088 -0.20861296 0.54001695, + 0.78715169 -0.22225192 0.57532281, + 0.79774499 -0.194934 0.57061702, + 0.76846355 -0.20686215 0.60553443, + 0.77783215 -0.18008605 0.60211813, + 0.74765497 -0.190291 0.63624001, + 0.75586581 -0.16382295 0.63389981, + 0.72438991 -0.17249699 0.66746092, + 0.731426 -0.14642 0.66601598, + 0.69823402 -0.15370899 0.69917297, + 0.70415401 -0.12784 0.69844401, + 0.66904801 -0.133812 0.73107398, + 0.67390573 -0.10789395 0.73089665, + 0.63719177 -0.11255097 0.76244271, + 0.64103109 -0.086376607 0.76263911, + 0.60268891 -0.089804575 0.79290682, + 0.60552406 -0.063219108 0.79331213, + 0.56520182 -0.065532781 0.82234567, + 0.56705981 -0.038405687 0.82278073, + 0.52459806 -0.039696105 0.85042411, + 0.52553618 -0.010184304 0.85071027, + 0.53602707 -0.013300202 0.84409612, + 0.53607917 0.0015736906 0.84416628, + 0.53605598 0.0015737 0.844181, + 0.53600389 -0.013298097 0.84411085, + 0.53611016 -0.013297104 0.84404331, + 0.56862813 -0.0099743325 0.8225342, + 0.56766903 -0.038651805 0.82234913, + 0.60853785 -0.037255794 0.79264981, + 0.60666901 -0.063678898 0.7924, + 0.64545006 -0.061183508 0.76134813, + 0.64262217 -0.087006025 0.76122719, + 0.67964983 -0.083298579 0.72879183, + 0.67586893 -0.10865299 0.72896892, + 0.71123093 -0.10362998 0.69527793, + 0.70649576 -0.12871096 0.69591475, + 0.73981398 -0.122363 0.66159099, + 0.73411304 -0.14736702 0.66284305, + 0.76555789 -0.13962698 0.62803292, + 0.75885582 -0.16479495 0.63006383, + 0.78886169 -0.15551195 0.59456974, + 0.781111 -0.181034 0.59757203, + 0.80999583 -0.17002895 0.56124586, + 0.80126309 -0.19579104 0.56537008, + 0.82891029 -0.18305106 0.52858317, + 0.8191461 -0.20931503 0.53402907, + 0.84581786 -0.19467697 0.49668193, + 0.83491486 -0.22179598 0.50370991, + 0.86122513 -0.20480803 0.46512905, + 0.84911287 -0.23303597 0.47402695, + 0.87550122 -0.21318504 0.4336471, + 0.87160611 -0.22206703 0.43702307, + 0.8994379 -0.19798598 0.38963193, + 0.90306586 -0.18897897 0.38569295, + 0.92752165 -0.16445693 0.33564487, + 0.92996991 -0.15749198 0.33219296, + 0.95097762 -0.13248396 0.2794449, + 0.95247775 -0.12744197 0.27666694, + 0.96997923 -0.10174502 0.22088106, + 0.97078633 -0.098377839 0.21885107, + 0.98435867 -0.072231881 0.16068794, + 0.98471802 -0.070216902 0.159374, + 0.99419498 -0.043379799 0.098461002, + 0.99428689 -0.042559795 0.097888984, + 0.99933702 -0.0145163 0.033388101, + 0.99934065 -0.014423494 0.033319388, + 0.99929303 0.0149351 -0.0345014, + 0.99931735 0.014348205 -0.034045011, + 0.99326646 0.044993524 -0.10675905, + 0.99354225 0.042879712 -0.10504902, + 0.98066723 0.073951215 -0.18117104, + 0.98132652 0.07104066 -0.1787499, + 0.96063054 0.10261095 -0.25818589, + 0.96173453 0.099274255 -0.25536489, + 0.93220621 0.13113903 -0.3373341, + 0.93371314 0.12774101 -0.33445802, + 0.89510524 0.15907905 -0.41651008, + 0.89684111 0.15598801 -0.41393706, + 0.84888202 0.186396 -0.494627, + 0.85028201 0.184351 -0.49298599, + 0.79321414 0.21328802 -0.57036805, + 0.79202902 0.214748 -0.57146603, + 0.72663891 0.24166997 -0.64311093, + 0.71957195 0.24915397 -0.64818096, + 0.64792502 0.273296 -0.71098697, + 0.66656709 0.25540504 -0.70032609, + 0.59329104 0.27580604 -0.7562651, + 0.618689 0.25245601 -0.74396902, + 0.54441094 0.26954597 -0.79433089, + 0.56381613 0.25217706 -0.78645921, + 0.48891506 0.26635402 -0.8306731, + 0.50334901 0.25368401 -0.82600498, + 0.42925707 0.26516303 -0.86338115, + 0.43641114 0.25894809 -0.86167932, + 0.3642219 0.26803195 -0.89190876, + 0.36407197 0.26816198 -0.89193088, + 0.29538003 0.27507502 -0.91492313, + 0.28839508 0.28123009 -0.91528028, + 0.22515407 0.2861681 -0.93135035, + 0.21332397 0.29692098 -0.93076891, + 0.15769005 0.30011407 -0.94077921, + 0.14327498 0.31388098 -0.93858987, + 0.096218035 0.31568113 -0.94397438, + 0.08194571 0.33028302 -0.94031811, + 0.043822695 0.33107898 -0.94258487, + 0.031793013 0.34453118 -0.93823647, + 0.0022707507 0.3447051 -0.93870836, + -0.0066797277 0.35586187 -0.93451464, + -0.028347796 0.35572696 -0.93415987, + -0.034614217 0.36458018 -0.9305284, + -0.049300712 0.36435509 -0.92995423, + -0.05196159 0.36868292 -0.92810178, + -0.060702924 0.36850113 -0.92764336, + -0.056514286 0.3605099 -0.93104178, + -0.0621568 0.36038899 -0.93072897, + -0.058785621 0.35270211 -0.93388736, + -0.061567992 0.35264397 -0.93372989, + -0.058476277 0.34408289 -0.93711662, + -0.058173709 0.34408903 -0.93713313, + -0.054617982 0.33186987 -0.94174266, + -0.044054497 0.33204296 -0.94223487, + -0.049654912 0.3559151 -0.93319821, + -0.052232418 0.35586813 -0.93307537, + -0.055608019 0.36707613 -0.92852736, + -0.055342413 0.36708108 -0.92854124, + -0.059054386 0.37699991 -0.92432874, + -0.056282986 0.37706092 -0.92447674, + -0.060946815 0.38731408 -0.91993123, + -0.055544391 0.38743594 -0.92022187, + -0.055426285 0.38721791 -0.92032075, + -0.044964716 0.38742214 -0.92080534, + -0.042054195 0.38282093 -0.92286485, + -0.025566597 0.38303494 -0.9233799, + -0.020464092 0.37600484 -0.92639166, + 0.0027719906 0.37608209 -0.92658222, + 0.010612103 0.36651608 -0.93035126, + 0.04145309 0.3662219 -0.92960376, + 0.051805373 0.35484281 -0.93348956, + 0.090725072 0.35385489 -0.93088967, + 0.102097 0.34237701 -0.933999, + 0.149235 0.34032199 -0.92839098, + 0.15937595 0.33074591 -0.93016475, + 0.21427596 0.32724592 -0.92032379, + 0.22116593 0.32105088 -0.92087567, + 0.28289798 0.31575596 -0.9056859, + 0.28440005 0.3144491 -0.90567023, + 0.35107702 0.30711502 -0.88454813, + 0.34604889 0.31140688 -0.88502872, + 0.41622385 0.30179688 -0.85771573, + 0.403896 0.312242 -0.85986799, + 0.47648695 0.30008298 -0.82638389, + 0.45869201 0.31518999 -0.83081698, + 0.53293598 0.300136 -0.79113698, + 0.50806206 0.32144904 -0.79908913, + 0.58279186 0.30327395 -0.75390881, + 0.56420213 0.3195971 -0.76127118, + 0.63892096 0.29777896 -0.70930094, + 0.63383019 0.30253005 -0.71185321, + 0.72904623 0.26771608 -0.62993622, + 0.71678883 0.28116494 -0.63809085, + 0.71065634 0.30246815 -0.63520128, + 0.778032 0.270089 -0.56720197, + 0.7764191 0.27209103 -0.56845409, + 0.83704382 0.23622194 -0.4935149, + 0.83496171 0.23927091 -0.49556881, + 0.8866899 0.20103396 -0.41637295, + 0.88446432 0.20499608 -0.41916513, + 0.92665726 0.16514805 -0.33768708, + 0.92459124 0.16979104 -0.34103107, + 0.95727724 0.12888104 -0.25886306, + 0.95511174 0.13533297 -0.26352695, + 0.98016751 0.090529956 -0.17628391, + 0.97930437 0.09449444 -0.17898005, + 0.99342221 0.05346271 -0.10126302, + 0.99303389 0.056680992 -0.10329998, + 0.99931413 0.017813902 -0.032465603, + 0.99926811 0.019034302 -0.033180203, + 0.99932438 -0.018288407 0.03188001, + 0.99935222 -0.017494004 0.031451907, + 0.99441999 -0.051278401 0.092192002, + 0.99510175 -0.043897588 0.088574477, + 0.9870289 -0.07128989 0.14384599, + 0.98834062 -0.061198279 0.13941896, + 0.97796589 -0.083909892 0.19115897, + 0.97980201 -0.071998797 0.18655901, + 0.96748322 -0.091068722 0.23597206, + 0.96971178 -0.077776887 0.23153794, + 0.95578736 -0.09363693 0.27875209, + 0.95826113 -0.079253308 0.27469003, + 0.94271547 -0.092477143 0.32052416, + 0.94526714 -0.077345811 0.31699803, + 0.92795312 -0.088344507 0.36207503, + 0.93046576 -0.072539583 0.35912591, + 0.91128814 -0.081526406 0.40361807, + 0.91365623 -0.065020017 0.40125409, + 0.89266622 -0.072095118 0.44491512, + 0.89478791 -0.054806791 0.44311494, + 0.87182009 -0.060126007 0.48612207, + 0.87358987 -0.041944098 0.48485193, + 0.84829789 -0.045637798 0.52754897, + 0.84959799 -0.0264339 0.52676803, + 0.82174879 -0.028559893 0.56913388, + 0.82248503 -0.0070627802 0.56874299, + 0.81808698 -0.0063944999 0.575059, + 0.818106 0.00074503699 0.57506698, + 0.84549081 7.4331983e-005 0.53398991, + 0.84545285 -0.0090871081 0.53397286, + 0.84539127 -0.0090885432 0.53407019, + 0.8506887 -0.0059843375 0.52563584, + 0.8500123 -0.02671041 0.5260852, + 0.8753677 -0.024514491 0.48283583, + 0.87421715 -0.042367913 0.48368311, + 0.89709073 -0.038555693 0.44016087, + 0.89556068 -0.055329081 0.44148585, + 0.9162969 -0.049802992 0.39739093, + 0.91450876 -0.065589689 0.39921391, + 0.93326801 -0.058231499 0.35442901, + 0.93133235 -0.073101833 0.35675812, + 0.9480741 -0.063843705 0.31157604, + 0.94609588 -0.077851892 0.31439096, + 0.96094209 -0.066521704 0.26863602, + 0.95902288 -0.079668693 0.27189696, + 0.97210366 -0.065952979 0.22508793, + 0.97036564 -0.078062773 0.22868493, + 0.98172277 -0.061482184 0.18011196, + 0.9803111 -0.072131507 0.18381302, + 0.98966402 -0.052385502 0.133495, + 0.98868024 -0.061179616 0.13699803, + 0.99576497 -0.037488099 0.083945699, + 0.99526685 -0.043773796 0.086761996, + 0.99945635 -0.014851905 0.029437112, + 0.99937737 -0.017396506 0.030698411, + 0.99933565 0.017968494 -0.031707488, + 0.99930239 0.018903408 -0.032211311, + 0.99305999 0.059526201 -0.101432, + 0.99342936 0.05636622 -0.099604338, + 0.97975248 0.098606348 -0.17424709, + 0.98063987 0.094328485 -0.17160298, + 0.95710886 0.13956499 -0.25389796, + 0.95827162 0.13588895 -0.25149491, + 0.92072266 0.18549794 -0.34330788, + 0.92389691 0.17843099 -0.33849198, + 0.88033623 0.22119506 -0.4196201, + 0.88297021 0.21652104 -0.4165121, + 0.82990968 0.2573269 -0.49500781, + 0.83229589 0.25383797 -0.49279794, + 0.7704888 0.29190093 -0.56669289, + 0.77223271 0.28973791 -0.56542784, + 0.70325291 0.32421398 -0.63270897, + 0.71823525 0.30774513 -0.62404424, + 0.62113523 0.34662312 -0.70288223, + 0.63728106 0.33132604 -0.69577008, + 0.56238997 0.35550696 -0.74654692, + 0.5564869 0.36068591 -0.74848384, + 0.48175099 0.380418 -0.78942901, + 0.46776319 0.39175916 -0.79228932, + 0.39614895 0.40697694 -0.82306486, + 0.41179314 0.39472815 -0.82135028, + 0.34379011 0.40675616 -0.84637928, + 0.36427203 0.39056206 -0.84543914, + 0.29934594 0.4001449 -0.86618483, + 0.31238088 0.38960084 -0.86638868, + 0.25089207 0.39700708 -0.88285822, + 0.25897303 0.39026606 -0.88353014, + 0.20175508 0.39574113 -0.8959263, + 0.20417392 0.39363584 -0.89630568, + 0.15242197 0.39740792 -0.90489477, + 0.15052906 0.39914414 -0.90444732, + 0.10489695 0.40151682 -0.90982461, + 0.10027696 0.40604284 -0.90833569, + 0.061294571 0.40733278 -0.91122061, + 0.055701982 0.41327584 -0.90890068, + 0.0235266 0.41380399 -0.91006202, + 0.01839569 0.41982079 -0.90742058, + -0.006963673 0.41988119 -0.90755242, + -0.010640697 0.42471686 -0.90526372, + -0.029658407 0.4245531 -0.90491724, + -0.031282384 0.42698878 -0.90371561, + -0.044597976 0.4267728 -0.90325856, + -0.044350412 0.4263421 -0.90347421, + -0.052635282 0.42616984 -0.90311068, + -0.051217008 0.42325005 -0.90456414, + -0.055070028 0.42316321 -0.90437841, + -0.05228921 0.41624409 -0.90774822, + -0.052394606 0.41624206 -0.9077431, + -0.047789913 0.40203309 -0.91437721, + -0.045869511 0.40207008 -0.91445923, + -0.042338904 0.38806707 -0.92065811, + -0.032502588 0.38820985 -0.92099762, + -0.036898293 0.41094792 -0.91091174, + -0.024649309 0.42962414 -0.90267128, + -0.02859821 0.42957914 -0.90257633, + -0.022971092 0.38845184 -0.92118263, + -0.018416096 0.38848791 -0.92126977, + -0.015151593 0.34539083 -0.93833655, + -0.0065583489 0.34542397 -0.93842387, + -0.0059411325 0.31902912 -0.94772637, + 0.0060230708 0.31902802 -0.94772613, + 0.006636709 0.34539798 -0.93843287, + 0.015219 0.34536499 -0.93834502, + 0.018479707 0.38842914 -0.92129338, + 0.022963092 0.38839287 -0.92120767, + 0.028581696 0.42945895 -0.90263391, + 0.029507296 0.42944694 -0.90260988, + -0.91334075 -0.0004197479 0.4071959, + -0.93220723 0.0008091412 0.36192408, + -0.94879812 -0.0051690205 0.31584102, + -0.9322111 0.00080884009 0.36191404, + -0.93216985 -0.0091675492 0.36190498, + -0.9321661 -0.0091677411 0.36191502, + 0.027869096 0.47808594 -0.87787086, + 0.036371998 0.47795501 -0.87763101, + 0.039935786 0.49027982 -0.8706497, + 0.039494511 0.49028811 -0.87066519, + 0.042988822 0.49976525 -0.86509341, + 0.039176501 0.49984401 -0.86522901, + 0.0423862 0.50692397 -0.86094803, + 0.034887295 0.50707096 -0.86119789, + 0.037559692 0.51199186 -0.85816884, + 0.026014503 0.51218003 -0.85848415, + 0.028130796 0.51550293 -0.85642588, + 0.012255803 0.51566911 -0.85670018, + 0.014022204 0.51808012 -0.85521716, + -0.0063110008 0.51812106 -0.85528409, + -0.0043909289 0.52043688 -0.85388881, + -0.029157603 0.52022207 -0.85353315, + -0.026671804 0.52290905 -0.85197109, + -0.055868115 0.52227813 -0.85094321, + -0.051877007 0.52619004 -0.84878314, + -0.08518973 0.52498519 -0.84683728, + -0.078762822 0.53076512 -0.84385115, + -0.11587998 0.52883291 -0.84077787, + -0.10495204 0.53792918 -0.83643132, + -0.14545991 0.5351637 -0.83213055, + -0.13929103 0.53997213 -0.83007717, + -0.18442504 0.53593409 -0.82387018, + -0.19279808 0.52964717 -0.82601631, + -0.24537791 0.5232718 -0.81607372, + -0.24884088 0.52069879 -0.8166706, + -0.30792406 0.51148713 -0.80222416, + -0.3128531 0.50779712 -0.80266118, + -0.37839419 0.49488223 -0.78224635, + -0.38300592 0.49132589 -0.78224385, + -0.45412794 0.47387394 -0.75446087, + -0.45749301 0.471145 -0.75413698, + -0.53214318 0.44859514 -0.71804327, + -0.53382015 0.44713315 -0.71771026, + -0.60974509 0.41910705 -0.67272604, + -0.60942292 0.41941494 -0.67282593, + -0.68457103 0.38561201 -0.61860001, + -0.68207699 0.38828501 -0.61968201, + -0.75395584 0.34880492 -0.55667388, + -0.74952966 0.35422781 -0.55922079, + -0.82873398 0.29947099 -0.472776, + -0.83272785 0.29324794 -0.46964887, + -0.89070421 0.24076205 -0.38559008, + -0.89088011 0.24040402 -0.38540706, + -0.93276215 0.19079003 -0.30586603, + -0.93154711 0.19404003 -0.30752003, + -0.9615261 0.14659601 -0.23233002, + -0.96444327 0.13559203 -0.22685707, + -0.98299277 0.09421768 -0.15763296, + -0.98530966 0.080040567 -0.15085894, + -0.9950161 0.046734706 -0.088084109, + -0.99558061 0.039888587 -0.085018769, + -0.99954122 0.012865003 -0.027420407, + -0.9995845 0.010988605 -0.026650613, + -0.99960053 -0.010773594 0.026128987, + -0.999632 -0.0091597401 0.025535, + -0.99672151 -0.027319012 0.076158337, + -0.99693513 -0.023026701 0.07476791, + -0.99164051 -0.03797818 0.12331594, + -0.99208164 -0.031625289 0.12154795, + -0.98464203 -0.043961398 0.16896001, + -0.98528898 -0.035888199 0.16708601, + -0.97575814 -0.045958802 0.21397203, + -0.97655565 -0.036342688 0.21217492, + -0.96506411 -0.044235304 0.25825304, + -0.96592414 -0.033249203 0.25668103, + -0.95235199 -0.039181098 0.30247399, + -0.95315522 -0.027226906 0.30125406, + -0.93732762 -0.03136459 0.34703487, + -0.93797189 -0.018580198 0.34621298, + -0.91972679 -0.021037195 0.39199492, + -0.92015642 -0.0052238423 0.39151618, + -0.932154 -0.0091659296 0.36194599, + -0.93219566 0.00080916472 0.36195388, + -0.91333491 -0.00042138994 0.40720895, + -0.91328889 -0.0097760586 0.40719494, + -0.91329426 -0.0097758723 0.40718308, + -0.89938068 -0.0059579578 0.43712586, + -0.89887321 -0.023167806 0.43759611, + -0.91945136 -0.020788407 0.39265415, + -0.91865724 -0.035078607 0.39349508, + -0.93696803 -0.031026 0.34803501, + -0.93593657 -0.044610679 0.34933183, + -0.95195401 -0.0387928 0.303774, + -0.95079511 -0.051553808 0.30550104, + -0.96466899 -0.043840099 0.259792, + -0.96351635 -0.055391219 0.2618551, + -0.97541386 -0.045608897 0.21560997, + -0.97437602 -0.055811599 0.21789099, + -0.98437667 -0.043690186 0.17056894, + -0.98353809 -0.052419007 0.17293102, + -0.99147046 -0.037807819 0.12472806, + -0.99089766 -0.044792086 0.12694696, + -0.99664223 -0.027244706 0.077214912, + -0.99636525 -0.031991906 0.078948021, + -0.99958915 -0.010764301 0.026563503, + -0.99954778 -0.012585697 0.027311394, + -0.9995265 0.012877894 -0.027945787, + -0.99946779 0.015061696 -0.028934393, + -0.9948355 0.046866421 -0.090033442, + -0.99404162 0.055084083 -0.094058864, + -0.98230726 0.094640821 -0.16160305, + -0.98099566 0.10167896 -0.16525394, + -0.95969564 0.14727694 -0.23936091, + -0.96094722 0.14288902 -0.23698805, + -0.92894834 0.19115607 -0.31704012, + -0.92990738 0.18872507 -0.31568211, + -0.88379622 0.24007706 -0.40158108, + -0.88294071 0.2416909 -0.40249386, + -0.81736386 0.29658797 -0.49391493, + -0.82225269 0.28951392 -0.48998183, + -0.75798184 0.3318139 -0.5615719, + -0.7609899 0.32809797 -0.55968392, + -0.69022483 0.36594293 -0.62423986, + -0.69151378 0.36455387 -0.62362576, + -0.61698991 0.39715895 -0.67940295, + -0.61654878 0.39758384 -0.67955476, + -0.54075807 0.42478305 -0.72604406, + -0.53835297 0.42688593 -0.72659796, + -0.46363187 0.44882387 -0.76393884, + -0.45968801 0.45203301 -0.76442999, + -0.3882249 0.46907687 -0.79325181, + -0.38333091 0.47286487 -0.79338282, + -0.31742692 0.4854959 -0.81457585, + -0.31336591 0.48855388 -0.81431985, + -0.25385505 0.49761412 -0.82942015, + -0.24398306 0.50497913 -0.82793015, + -0.19180401 0.51104802 -0.837879, + -0.19924302 0.50538206 -0.83957809, + -0.15172593 0.5097518 -0.84683669, + -0.16446196 0.49952388 -0.85054582, + -0.12057606 0.50272423 -0.85599643, + -0.12785095 0.49648783 -0.85857671, + -0.088123828 0.49864817 -0.86231327, + -0.092146799 0.494939 -0.86402798, + -0.05688468 0.49624881 -0.86631471, + -0.058707178 0.49442282 -0.86723667, + -0.028227707 0.49507913 -0.86838919, + -0.029045189 0.49417582 -0.8688767, + -0.003579658 0.4943817 -0.86923748, + -0.0039797993 0.49388894 -0.8695159, + 0.016509695 0.49382481 -0.86940467, + 0.015790001 0.49281999 -0.86998802, + 0.031405617 0.49263823 -0.86966741, + 0.029949296 0.49029493 -0.87104189, + 0.040955011 0.49010411 -0.87070119, + 0.038641278 0.48572969 -0.87325448, + 0.045419917 0.48559117 -0.87300527, + 0.042424705 0.47879505 -0.87690109, + 0.04546351 0.47873011 -0.87678427, + 0.041985698 0.46900693 -0.88219589, + 0.041671187 0.46901283 -0.88220769, + 0.03791932 0.45561221 -0.88937044, + 0.034942891 0.45566189 -0.88946676, + 0.022890098 0.47367194 -0.88040388, + 0.027329994 0.47361889 -0.88030577, + 0.021497006 0.43391109 -0.90069926, + 0.017346699 0.43394595 -0.90077186, + 0.013869897 0.39122692 -0.92018974, + 0.0061794287 0.3912569 -0.92026079, + 0.0050587882 0.34633389 -0.93809766, + -0.0050238487 0.34633392 -0.93809777, + -0.0061456524 0.39127713 -0.92025238, + -0.013871504 0.39124709 -0.92018121, + -0.017353896 0.43403292 -0.90072978, + -0.021571092 0.43399784 -0.90065569, + -0.027442399 0.473874 -0.88016498, + -0.027189605 0.47387713 -0.88017124, + -0.03278292 0.49906629 -0.86594355, + -0.034569316 0.49903625 -0.8658914, + -0.038168181 0.51108277 -0.85868359, + -0.036968179 0.51110572 -0.85872245, + -0.040555313 0.5205422 -0.85287231, + -0.035978407 0.5206331 -0.85302216, + -0.039352685 0.52786881 -0.84841371, + -0.031207208 0.52802014 -0.8486582, + -0.034263197 0.53350294 -0.84510386, + -0.022263398 0.53368396 -0.84539086, + -0.02507611 0.53799617 -0.8425743, + -0.0090806875 0.5381428 -0.84280473, + -0.012016503 0.54206109 -0.84025317, + 0.0079619121 0.54208314 -0.84028721, + 0.0044702208 0.54620409 -0.83764017, + 0.028299799 0.545991 -0.837313, + 0.023501391 0.55105984 -0.8341347, + 0.05103479 0.5504939 -0.83327782, + 0.044778068 0.55647558 -0.82965642, + 0.075779714 0.55543309 -0.82810116, + 0.066254809 0.56375408 -0.82328111, + 0.100235 0.56215101 -0.82093799, + 0.092391297 0.56848103 -0.81749201, + 0.13035293 0.56605166 -0.81399852, + 0.139862 0.55877298 -0.817442, + 0.18538606 0.55453718 -0.81124628, + 0.19160688 0.54988968 -0.81296253, + 0.24402091 0.54333383 -0.80326968, + 0.24742398 0.54081392 -0.80392885, + 0.30625302 0.53134906 -0.78985912, + 0.30919394 0.52915388 -0.79018682, + 0.37434089 0.51596284 -0.77048773, + 0.37704217 0.51388925 -0.77055633, + 0.4478159 0.49609587 -0.74387485, + 0.44981405 0.49448305 -0.74374306, + 0.52430868 0.47145474 -0.70910561, + 0.52501714 0.47084111 -0.7089892, + 0.60117811 0.44208613 -0.6656912, + 0.59987068 0.44332778 -0.66604471, + 0.93858415 -0.0031730004 0.34503603, + 0.93822026 -0.018461304 0.3455461, + 0.95395589 -0.016002199 0.29951996, + 0.95343125 -0.027773608 0.30032906, + 0.96680337 -0.023529408 0.25443608, + 0.96620065 -0.033881988 0.25555491, + 0.97740489 -0.027781596 0.20954198, + 0.97682089 -0.036720797 0.21088497, + 0.98599327 -0.028611308 0.16431305, + 0.98550612 -0.036073305 0.16576001, + 0.99256325 -0.025885306 0.11894603, + 0.99222726 -0.031702608 0.12033303, + 0.99716514 -0.019169401 0.072761305, + 0.99700123 -0.023072705 0.073866017, + 0.99966526 -0.0077144718 0.024697406, + 0.99964088 -0.0091818888 0.025176497, + 0.99962866 0.009336316 -0.025599891, + 0.99959552 0.011018694 -0.026219187, + 0.9961279 0.034060996 -0.081048995, + 0.99570566 0.040032785 -0.083472371, + 0.98741663 0.068385281 -0.14258996, + 0.9857325 0.080427565 -0.14786093, + 0.97035176 0.11548897 -0.21231996, + 0.96552235 0.13621704 -0.22183707, + 0.93943709 0.17933601 -0.29205602, + 0.93451875 0.19353396 -0.29869595, + 0.89599699 0.241466 -0.37267101, + 0.89628679 0.24083994 -0.37237892, + 0.84439373 0.29093692 -0.44983885, + 0.84216291 0.29470897 -0.45156193, + 0.77299166 0.34673584 -0.53127974, + 0.76446617 0.3580471 -0.53609115, + 0.67401206 0.41028607 -0.61430705, + 0.67574871 0.4084388 -0.6136297, + 0.68172002 0.387629 -0.62048501, + 0.60829097 0.42053199 -0.67315298, + 0.60872006 0.42012206 -0.67302108, + 0.53270596 0.44814193 -0.71790892, + 0.53164214 0.44906911 -0.71811819, + 0.45701975 0.47159672 -0.75414151, + 0.45483094 0.47337294 -0.75435185, + 0.38375807 0.49083707 -0.7821821, + 0.38097095 0.49299094 -0.78218991, + 0.31532496 0.50599992 -0.80282891, + 0.31161398 0.50879097 -0.8025139, + 0.25225896 0.51813596 -0.81725186, + 0.24499606 0.52354515 -0.81601316, + 0.19245204 0.52990711 -0.82593018, + 0.18074402 0.53867006 -0.82290113, + 0.136041 0.54259801 -0.82890302, + 0.14478202 0.53580505 -0.8318361, + 0.10437704 0.53855217 -0.83610231, + 0.11528496 0.52948284 -0.8404507, + 0.078273833 0.53140116 -0.84349632, + 0.085027166 0.52533174 -0.84663856, + 0.051785119 0.5265342 -0.84857529, + 0.056543019 0.52187115 -0.85114831, + 0.027262909 0.52251315 -0.85219532, + 0.030156193 0.51938391 -0.85400879, + 0.0052359803 0.51961404 -0.85438514, + 0.0072201402 0.51722002 -0.85582203, + -0.0132711 0.51718801 -0.85576898, + -0.011542297 0.51482791 -0.85721582, + -0.027593492 0.51466584 -0.85694671, + -0.025569696 0.51148796 -0.8589099, + -0.037251718 0.51130027 -0.85859442, + -0.034666795 0.50654393 -0.86151689, + -0.042269815 0.50639617 -0.86126429, + -0.039138604 0.49949706 -0.86543113, + -0.043053698 0.49941593 -0.86529189, + -0.039530601 0.48987499 -0.87089598, + -0.040050581 0.48986375 -0.87087858, + -0.033951014 0.46875525 -0.88267541, + -0.042090174 0.46861073 -0.88240147, + -0.045533706 0.47822705 -0.87705511, + -0.042370886 0.47829282 -0.87717772, + -0.045402303 0.48516506 -0.87324309, + -0.038527094 0.48530489 -0.87349582, + -0.040746395 0.48949793 -0.87105191, + -0.029622797 0.48968893 -0.87139386, + -0.030967316 0.49185124 -0.87012839, + -0.015179706 0.49203119 -0.87044531, + -0.015796209 0.49289131 -0.86994755, + 0.0048531089 0.49294689 -0.87004584, + 0.0044919997 0.49339294 -0.86979491, + 0.030128097 0.49317393 -0.86940891, + 0.029224196 0.49417195 -0.86887288, + 0.059882108 0.49349606 -0.86768413, + 0.057539687 0.49584487 -0.86650282, + 0.092863105 0.49452206 -0.8641901, + 0.08791057 0.49908781 -0.86208069, + 0.12755096 0.49693483 -0.85836267, + 0.1199 0.50348699 -0.85564297, + 0.163688 0.500305 -0.850236, + 0.15097402 0.51050204 -0.84651911, + 0.19833504 0.50616205 -0.8393231, + 0.188354 0.51374 -0.83701497, + 0.24014895 0.50779486 -0.8273288, + 0.25363806 0.49776313 -0.8293972, + 0.31318399 0.488702 -0.81430101, + 0.32097799 0.48281801 -0.814776, + 0.38701886 0.47006583 -0.79325569, + 0.39065483 0.46723878 -0.79314363, + 0.46211672 0.45012474 -0.76409155, + 0.46424222 0.4483912 -0.76382238, + 0.53896493 0.42642993 -0.72641194, + 0.54020303 0.42534706 -0.72612709, + 0.61603886 0.3981449 -0.67968881, + 0.61595625 0.39822415 -0.67971724, + 0.69057393 0.36560997 -0.62404895, + 0.68921262 0.36707282 -0.62469471, + 0.68310207 0.38823506 -0.61858308, + 0.75329417 0.3496201 -0.5570581, + 0.74998778 0.35366988 -0.55895984, + 0.8290661 0.29897103 -0.47251007, + 0.83274287 0.29323697 -0.46962893, + 0.89071399 0.240753 -0.385573, + 0.89063722 0.24090905 -0.38565308, + 0.93261087 0.19119696 -0.30607298, + 0.93149358 0.19418292 -0.30759186, + 0.96149677 0.14670397 -0.23238294, + 0.96415091 0.13672298 -0.22741997, + 0.98285776 0.09499298 -0.15800895, + 0.98522067 0.080610469 -0.15113594, + 0.99498755 0.047060076 -0.088232853, + 0.99556655 0.04006378 -0.085100159, + 0.99953961 0.012922895 -0.027449891, + 0.99958378 0.011009097 -0.026663994, + 0.99960011 -0.010792701 0.026140004, + 0.99963188 -0.0091579892 0.025537696, + 0.99672222 -0.027308706 0.076152317, + 0.99693787 -0.022972697 0.074747592, + 0.99165022 -0.037884608 0.12326703, + 0.99209136 -0.031514511 0.12149704, + 0.98465526 -0.043815311 0.16892104, + 0.98529625 -0.035804007 0.16706105, + 0.97577065 -0.045850486 0.21393792, + 0.97655445 -0.036399517 0.21217111, + 0.96506274 -0.04430389 0.25824594, + 0.96590686 -0.033546895 0.25670698, + 0.95233899 -0.039527301 0.30247, + 0.95315254 -0.027471887 0.30123985, + 0.93734413 -0.031641904 0.34696501, + 0.93801677 -0.018252097 0.34610891, + 0.91977012 -0.020667503 0.39191306, + 0.920214 -0.00382879 0.391397, + 0.9333269 -0.0074146092 0.35895097, + 0.93335462 0.00064046774 0.35895488, + 0.9333719 0.00064043293 0.35890996, + 0.93334466 -0.0074174772 0.35890487, + 0.93331814 -0.0074185207 0.35897404, + 0.93334585 0.00064253493 0.35897797, + 0.94978851 -0.0058019771 0.31283885, + 0.94978225 -0.0067982813 0.31283808, + 0.94980526 -0.0067972112 0.3127681, + 0.94982839 -0.00067061925 0.31277111, + 0.94448322 -0.0028722908 0.32854709, + 0.90569514 -0.0036284404 0.42391405, + 0.89367586 0.00040014295 0.44871294, + 0.89364189 -0.0082968595 0.44870394, + 0.89367312 -0.0082959505 0.44864205, + 0.89370656 0.00039760378 0.44865179, + 0.89441586 0.00039647295 0.44723594, + 0.87059069 0.00034545688 0.49200782, + 0.87055486 -0.0087289494 0.49199393, + 0.87057739 -0.0087283636 0.49195424, + 0.87061316 0.00035076108 0.49196813, + 0.85730779 -0.0035637692 0.51479191, + 0.79983455 -0.0034327079 0.60021067, + 0.81825286 0.00075344788 0.57485795, + 0.81821412 -0.0092610111 0.57483906, + 0.79218131 -0.0076217428 0.61023825, + 0.78900599 -0.0093684997 0.61431402, + 0.78904384 -0.00031562592 0.61433691, + 0.78896284 -0.00031026592 0.61444086, + 0.78892499 -0.0093700001 0.61441803, + 0.75791538 -0.0084370235 0.65229827, + 0.75794572 0.0010689097 0.65231675, + 0.75795829 0.0010689003 0.65230227, + 0.75792021 -0.009504512 0.65227818, + 0.75803763 -0.0095024956 0.65214169, + 0.75807619 0.0010895003 0.65216517, + 0.73387492 -0.0032353795 0.67927694, + 0.97325885 -0.0030551895 0.22969097, + 0.99171662 -0.0031930588 0.12840496, + 0.51241195 0.54621094 -0.66263694, + 0.42024684 0.57716781 -0.70019275, + 0.38011 0.60997099 -0.69530702, + 0.3183859 0.62515181 -0.71261179, + 0.27768582 0.65497756 -0.70277661, + 0.22244203 0.66470903 -0.71321905, + 0.21562003 0.66943407 -0.71089107, + 0.16684394 0.67595077 -0.71781176, + 0.16570799 0.67673796 -0.71733296, + 0.12303806 0.68101132 -0.72186238, + 0.121971 0.68176901 -0.72132802, + 0.085205689 0.68439996 -0.72411096, + 0.084973581 0.6845718 -0.72397584, + 0.053550467 0.68607157 -0.72556061, + 0.054391406 0.68541008 -0.72612303, + 0.027780604 0.68616104 -0.72691905, + 0.029772397 0.68447095 -0.72843194, + 0.0074741808 0.68475604 -0.72873408, + 0.010224301 0.68220007 -0.73109406, + -0.0081513496 0.68221301 -0.73110801, + -0.0058441428 0.67983329 -0.73334336, + -0.020387584 0.67970353 -0.73320347, + -0.018018289 0.67695856 -0.73580056, + -0.028779807 0.67678815 -0.73561519, + -0.022221398 0.66808194 -0.74375594, + -0.030945504 0.66792709 -0.74358308, + -0.024652494 0.65815485 -0.75247884, + -0.031596504 0.65802705 -0.75233114, + -0.02611999 0.64790076 -0.76127672, + -0.031031212 0.64780927 -0.76117033, + -0.0260546 0.63658899 -0.77076298, + -0.024475206 0.62409115 -0.78096819, + -0.0288487 0.63654 -0.77070397, + 0.017130401 0.74522406 -0.66659409, + 0.026043287 0.74508166 -0.66646469, + -0.011753094 0.71552265 -0.69849062, + -0.01916049 0.71544063 -0.69841063, + -0.012362299 0.68242192 -0.73085392, + -0.012013799 0.68242496 -0.73085696, + -0.0078363102 0.646797 -0.762622, + -0.0042345487 0.64681077 -0.76263869, + -0.0027998702 0.60804707 -0.79389614, + 0.0029278009 0.60804623 -0.79389632, + 0.0043359087 0.64686078 -0.76259571, + 0.0080277771 0.64684677 -0.76257771, + 0.012174698 0.68241584 -0.7308628, + 0.012527395 0.68241274 -0.73085976, + 0.019253291 0.71513164 -0.69872463, + 0.01695439 0.71516156 -0.6987536, + 0.023338297 0.68299097 -0.73005396, + -0.91519928 0.19248807 -0.35406011, + -0.87547523 0.23082305 -0.42457509, + -0.86607742 0.25296611 -0.43118221, + -0.82739216 0.28419405 -0.48441312, + -0.81346112 0.31121403 -0.49135205, + -0.76870853 0.3422378 -0.54033369, + -0.74939084 0.3736679 -0.54661286, + -0.69958824 0.40325016 -0.58988625, + -0.67379779 0.43902186 -0.59435374, + -0.62039495 0.46597993 -0.63085091, + -0.59300977 0.49901581 -0.63191974, + -0.52404493 0.52783191 -0.66840893, + -0.49889177 0.55396378 -0.66650671, + -0.4425098 0.57320273 -0.68965465, + -0.41392514 0.60025626 -0.68436724, + -0.35978803 0.61524004 -0.70145005, + -0.32588291 0.64474285 -0.6914528, + -0.27577105 0.65552717 -0.70301819, + -0.23762497 0.68630493 -0.68740094, + -0.1933111 0.69321537 -0.69432235, + -0.14658399 0.72832394 -0.66937095, + -0.085651755 0.73357141 -0.67419344, + -0.07844732 0.73866516 -0.66949219, + -0.048304912 0.74008417 -0.6707772, + -0.049515493 0.73918492 -0.67167991, + -0.023888109 0.73988223 -0.67231226, + -0.025647797 0.73847592 -0.67379194, + -0.0042419625 0.73871243 -0.67400742, + -0.0066839275 0.73657978 -0.67631775, + 0.010935696 0.73655176 -0.67629278, + 0.007668871 0.73338705 -0.67976809, + 0.021846807 0.73323321 -0.67962623, + 0.017898604 0.72892821 -0.68435615, + 0.028921688 0.72873974 -0.68417978, + 0.024252005 0.72291416 -0.69051218, + 0.032478407 0.72274518 -0.69035119, + 0.02703421 0.71482825 -0.69877726, + 0.0328977 0.71470302 -0.698654, + 0.0279634 0.70618099 -0.707479, + 0.031435505 0.70610803 -0.70740604, + 0.026434794 0.6955958 -0.71794683, + 0.028077507 0.69556415 -0.71791518, + 0.017114505 0.71066421 -0.70332325, + 0.025859695 0.71053082 -0.7031908, + 0.017870402 0.68306804 -0.73013604, + 0.011951997 0.67882282 -0.73420483, + 0.019734791 0.67873973 -0.73411363, + 0.013018705 0.64446121 -0.76452631, + 0.012810092 0.64446265 -0.76452851, + 0.0086812489 0.60723096 -0.79447788, + 0.0045532286 0.60724878 -0.79449868, + 0.0031778605 0.56723905 -0.82354712, + -0.00320541 0.56723899 -0.82354701, + -0.0046057999 0.60715902 -0.79456699, + -0.0085680373 0.60714376 -0.79454571, + -0.012723405 0.64436024 -0.76461631, + -0.012787005 0.64436024 -0.7646153, + -0.019548701 0.67876208 -0.73409808, + -0.011770393 0.67884457 -0.7341876, + 0.8665607 0.26362392 -0.42376286, + 0.81180698 0.30844599 -0.49581301, + 0.79508519 0.3381291 -0.50349611, + 0.74725682 0.3704859 -0.55167687, + 0.724778 0.403918 -0.558164, + 0.67199498 0.43415299 -0.59994501, + 0.64964718 0.46271712 -0.60320109, + 0.58066869 0.49552575 -0.6459707, + 0.55660188 0.52166587 -0.6465748, + 0.47851393 0.55136693 -0.68338794, + 0.44600412 0.58156013 -0.68034416, + 0.38649809 0.59927315 -0.70106417, + 0.35006002 0.62977308 -0.69342905, + 0.29468489 0.64245778 -0.70739573, + 0.25129899 0.67549598 -0.69322002, + 0.20204598 0.68349892 -0.70143193, + 0.1626149 0.71125156 -0.6838696, + 0.12089702 0.71555907 -0.68801105, + 0.11587802 0.71901804 -0.68526304, + 0.080119908 0.72156805 -0.68769205, + 0.080479577 0.72131079 -0.6879198, + 0.04989988 0.72275674 -0.68929875, + 0.050749902 0.72211301 -0.68991101, + 0.024867794 0.72282183 -0.69058681, + 0.026698597 0.72132891 -0.69207793, + 0.0050186301 0.721578 -0.69231498, + 0.0078801075 0.71902478 -0.69493973, + -0.0099893995 0.71901095 -0.69492692, + -0.0062028589 0.71525997 -0.69883096, + -0.020674298 0.71512091 -0.69869494, + -0.016352491 0.71029758 -0.70371157, + -0.027764 0.71011901 -0.70353401, + -0.02375529 0.70500565 -0.70880365, + -0.032127611 0.70484126 -0.70863724, + -0.028002704 0.69872606 -0.71484107, + -0.033385485 0.69861066 -0.71472263, + -0.027404293 0.68806982 -0.7251268, + -0.031104188 0.68799478 -0.72504878, + -0.025743697 0.67646694 -0.73602295, + -0.027853001 0.67642897 -0.73598099, + -0.023249298 0.66393495 -0.74742895, + -0.02355689 0.66392976 -0.74742377, + -0.01813611 0.64431828 -0.76454234, + -0.023679109 0.64424425 -0.76445329, + -0.0281805 0.65675199 -0.75357997, + -0.025714995 0.6567958 -0.7536298, + -0.030836411 0.66807222 -0.74345726, + -0.026410306 0.66815621 -0.74355221, + -0.032293305 0.67877805 -0.73363304, + -0.026214492 0.67889875 -0.73376375, + -0.032544106 0.68849015 -0.7245152, + -0.02465079 0.68864578 -0.72467875, + -0.028060604 0.69307607 -0.72031808, + -0.016770402 0.69325209 -0.72050005, + -0.020054806 0.69699121 -0.7167992, + -0.005382047 0.69712162 -0.71693265, + -0.0090179555 0.70080143 -0.71329939, + 0.0091297934 0.70080024 -0.71329921, + 0.006163253 0.70350337 -0.71066535, + 0.028132692 0.70323783 -0.71039784, + 0.026255 0.70480001 -0.70892, + 0.052491099 0.70407099 -0.70818698, + 0.051686607 0.70469207 -0.70762807, + 0.082692005 0.70321804 -0.70614904, + 0.082825109 0.70312107 -0.70623004, + 0.11910199 0.70052391 -0.70361996, + 0.119564 0.70020002 -0.70386398, + 0.16163802 0.69598603 -0.69962609, + 0.16770498 0.69182795 -0.70231694, + 0.21604304 0.68519419 -0.69558215, + 0.25671303 0.65622306 -0.70955604, + 0.31217289 0.64504576 -0.69746977, + 0.35460287 0.61183578 -0.70704573, + 0.41538706 0.59523404 -0.68785906, + 0.44941521 0.56555831 -0.69149834, + 0.51303798 0.54342699 -0.66443902, + 0.54102504 0.51601207 -0.66409606, + 0.6197347 0.48153275 -0.61972171, + 0.638457 0.45983601 -0.61719, + 0.70615333 0.42303321 -0.56779432, + 0.72466892 0.39747193 -0.56291294, + 0.77565199 0.36405501 -0.51558501, + 0.79473621 0.33291909 -0.50750309, + 0.83964187 0.29791597 -0.45414495, + 0.85733718 0.26228905 -0.44291911, + 0.89653569 0.22571293 -0.38115284, + 0.90903658 0.19210491 -0.36979482, + 0.93744314 0.16049002 -0.30893904, + 0.94395751 0.13620993 -0.30065086, + 0.96400511 0.10972302 -0.24218804, + 0.96719766 0.092612773 -0.23654091, + 0.98101687 0.070700489 -0.18057498, + 0.98242837 0.059144624 -0.17702106, + 0.99137527 0.041529812 -0.12430003, + 0.99189645 0.034373514 -0.12231106, + 0.99717623 0.020317506 -0.072296314, + 0.99731237 0.016532706 -0.071377821, + 0.99971366 0.0053996979 -0.023312593, + 0.99972445 0.0042712218 -0.023082212, + 0.9997285 -0.0042398381 0.022912689, + 0.99973625 -0.0031992407 0.022742305, + 0.99759686 -0.0096516088 0.068609595, + 0.99764597 -0.0066883801 0.068247698, + 0.99344265 -0.011151196 0.11378596, + 0.99352849 -0.0064093131 0.11340305, + 0.98719966 -0.0089996569 0.15923494, + 0.98729199 -0.00096049003 0.158914, + 0.98536736 0.00090683333 0.17044206, + 0.98535633 -0.0046317517 0.17044505, + 0.98541898 -0.00461757 0.170083, + 0.98543 0.00090654398 0.17007899, + 0.99258351 -0.0041198083 0.12149494, + 0.99258524 -0.003671441 0.12149503, + 0.99257553 -0.003672698 0.12157394, + 0.99258047 -0.001982701 0.12157406, + 0.99734312 0.00092772511 0.072842009, + 0.99734014 -0.0025345401 0.072844408, + 0.99360234 -0.00065225025 0.11293404, + 0.99355412 -0.0064895009 0.11317302, + 0.99769354 -0.0038859481 0.067768671, + 0.99766213 -0.0067632408 0.068004608, + 0.99974436 -0.0022378308 0.022501407, + 0.99973887 -0.0032312896 0.022623599, + 0.99973589 0.0032492494 -0.022749398, + 0.9997279 0.0043088896 -0.022922497, + 0.99745637 0.013168205 -0.070052624, + 0.99735433 0.016659906 -0.070759021, + 0.99243701 0.028132901 -0.119488, + 0.99204552 0.034602687 -0.12102994, + 0.98385763 0.049192183 -0.17205894, + 0.98280036 0.059477724 -0.17483106, + 0.97040313 0.077778004 -0.22862303, + 0.96798891 0.093041591 -0.23311096, + 0.95030552 0.11540395 -0.28913885, + 0.94543844 0.13670292 -0.29573381, + 0.92083412 0.16362101 -0.35396704, + 0.91164011 0.19265103 -0.36304003, + 0.87816656 0.22422889 -0.42254579, + 0.86541414 0.25450704 -0.43160707, + 0.82649183 0.28594396 -0.48491988, + 0.81229872 0.31333488 -0.49192682, + 0.76734489 0.34449098 -0.54083997, + 0.74760097 0.376432 -0.547167, + 0.69745576 0.40617585 -0.59040374, + 0.67206305 0.44119307 -0.59471005, + 0.61854994 0.46815395 -0.63105291, + 0.592686 0.499266 -0.63202602, + 0.52392399 0.52798599 -0.66838199, + 0.4948197 0.55808663 -0.66610259, + 0.41929314 0.58304119 -0.69588524, + 0.38334894 0.61518592 -0.68890494, + 0.32844415 0.62911928 -0.70450938, + 0.29078683 0.65983558 -0.69286358, + 0.24100298 0.66930896 -0.70281094, + 0.19772005 0.7018832 -0.68430018, + 0.15467301 0.70740104 -0.68968105, + 0.11727306 0.73383534 -0.6691283, + 0.081580803 0.73646998 -0.67153299, + 0.077994309 0.73899406 -0.66918206, + 0.04798729 0.74039781 -0.67045385, + 0.049092099 0.73957902 -0.67127699, + 0.023555705 0.7402662 -0.67190117, + 0.025398891 0.73879474 -0.67345178, + 0.0040421621 0.73902738 -0.67366332, + 0.0067985584 0.73662084 -0.6762718, + -0.010811097 0.7365948 -0.67624784, + -0.0071323798 0.73303002 -0.68015897, + -0.021376099 0.73288101 -0.68002099, + -0.016941303 0.72804117 -0.68532419, + -0.028193083 0.72785658 -0.68514961, + -0.023381712 0.72184736 -0.69165736, + -0.031876788 0.72167778 -0.69149476, + -0.027400708 0.71517217 -0.69841117, + -0.033185106 0.71504718 -0.6982882, + -0.028690305 0.70730108 -0.70633006, + -0.031831089 0.70723277 -0.70626378, + -0.026325304 0.69567204 -0.71787703, + -0.0279429 0.69564199 -0.71784502, + -0.023194293 0.68305373 -0.72999978, + -0.017749 0.68313003 -0.73008102, + -0.023150308 0.70177925 -0.71201825, + -0.023523103 0.70177305 -0.71201205, + -0.028382296 0.71435392 -0.69920892, + -0.02727101 0.71437621 -0.69923025, + -0.031814698 0.72370195 -0.68937892, + -0.021471899 0.73935091 -0.67297792, + -0.031760495 0.73914796 -0.67279392, + -0.024167595 0.72005993 -0.69349092, + -0.0185326 0.720146 -0.69357502, + -0.0260894 0.74488997 -0.666677, + -0.0207402 0.74498302 -0.66676098, + -0.028497096 0.7638579 -0.64475495, + -0.017460596 0.77749884 -0.62864184, + -0.026185496 0.7773509 -0.62852192, + -0.017229199 0.749282 -0.662027, + -0.019409293 0.74925178 -0.66200078, + -0.01278319 0.71854448 -0.69536352, + -0.011750208 0.71855354 -0.69537246, + -0.0075756311 0.68454409 -0.72893208, + -0.0039860685 0.68455774 -0.72894776, + -0.0025502699 0.647605 -0.76197201, + 0.0027589803 0.64760405 -0.76197213, + 0.0041707694 0.68454796 -0.72895592, + 0.0077376389 0.68453395 -0.72893995, + 0.011878205 0.71835124 -0.69557923, + 0.012651902 0.71834403 -0.69557303, + 0.019340003 0.74942118 -0.66181117, + 0.017223699 0.74944997 -0.66183692, + 0.026203694 0.77764779 -0.6281538, + 0.017695002 0.77779412 -0.62827003, + 0.021903606 0.7802372 -0.6251002, + 0.027467282 0.78012955 -0.62501466, + 0.032223497 0.78900987 -0.61353493, + 0.028914396 0.78908986 -0.61359692, + 0.033762682 0.7965095 -0.60368264, + 0.028144417 0.7966485 -0.60378736, + 0.033013005 0.8029111 -0.59518409, + 0.025132691 0.8030957 -0.59531975, + 0.029687304 0.8081181 -0.58827204, + 0.019206602 0.80832511 -0.58842307, + 0.017537298 0.80670285 -0.59069693, + -0.011806895 0.80677068 -0.59074676, + -0.044564102 0.77596003 -0.629206, + -0.066029087 0.77503681 -0.62845683, + -0.094657563 0.74809676 -0.65680379, + -0.12248903 0.74581218 -0.65479815, + -0.15161106 0.71821225 -0.67910624, + -0.18428694 0.71416676 -0.67528075, + -0.21331711 0.68610728 -0.69552338, + -0.25104111 0.67978227 -0.68911135, + -0.27831796 0.65257597 -0.70475793, + -0.31987396 0.64372396 -0.69519794, + -0.34450999 0.61817098 -0.70652503, + -0.38917923 0.60656738 -0.69326442, + -0.41866109 0.57425213 -0.70353216, + -0.46648481 0.55932081 -0.68523878, + -0.49801606 0.52184409 -0.69257408, + -0.54753798 0.50355798 -0.66830498, + -0.57494217 0.46759719 -0.67141223, + -0.62463105 0.44629505 -0.64082503, + -0.64789683 0.4121519 -0.64059383, + -0.69620597 0.38840601 -0.60368699, + -0.71492308 0.35724303 -0.60105103, + -0.7598471 0.33215502 -0.55884308, + -0.77421415 0.30461004 -0.55480206, + -0.81453985 0.27919093 -0.50850487, + -0.82521909 0.25526404 -0.50383908, + -0.86070281 0.23008794 -0.45414788, + -0.8683008 0.20982595 -0.44947389, + -0.89865869 0.18554994 -0.39747185, + -0.90565068 0.16264294 -0.39159185, + -0.93144339 0.13957606 -0.33605316, + -0.99974614 -0.0022413903 0.022418402, + -0.99974424 0.0022498404 -0.022502905, + -0.99973875 0.0032518094 -0.022626095, + -0.9975661 0.0099192914 -0.069018506, + -0.99748951 0.013263093 -0.069560967, + -0.99285173 0.022354394 -0.11724197, + -0.99255335 0.028425109 -0.11844804, + -0.98494112 0.040344704 -0.16811702, + -0.98414034 0.049711719 -0.17028406, + -0.97280937 0.064905122 -0.22232707, + -0.97100598 0.078442402 -0.22581901, + -0.95514423 0.097174026 -0.27974406, + -0.95149535 0.11600304 -0.2849561, + -0.92980886 0.13876998 -0.34087896, + -0.92459542 0.15835908 -0.34647617, + -0.89808601 0.182831 -0.40001801, + -0.89212656 0.20065191 -0.40478283, + -0.86001211 0.22662804 -0.45718607, + -0.85122287 0.24827597 -0.46236193, + -0.81377387 0.27494597 -0.51203191, + -0.80145431 0.30046013 -0.51710218, + -0.75905567 0.32707188 -0.56290179, + -0.74242204 0.35654804 -0.56717104, + -0.69545025 0.38243514 -0.60835224, + -0.67412275 0.41524485 -0.61084378, + -0.62395287 0.43933088 -0.64627481, + -0.59764725 0.47497219 -0.64592522, + -0.54699314 0.49593011 -0.67442715, + -0.51579106 0.53370506 -0.67016304, + -0.46606818 0.55116916 -0.69209325, + -0.43685806 0.58336508 -0.68471909, + -0.38882014 0.59749222 -0.70130026, + -0.36468482 0.62234068 -0.69260162, + -0.31943396 0.63335395 -0.70485795, + -0.29172605 0.66048217 -0.69185215, + -0.25041211 0.6685183 -0.70026934, + -0.22027206 0.69680119 -0.68260419, + -0.18332189 0.70224059 -0.68793261, + -0.15217806 0.73049927 -0.66574222, + -0.12101605 0.73367524 -0.66863722, + -0.08918529 0.76194388 -0.64147294, + -0.063975908 0.76342613 -0.64271903, + -0.02791171 0.79496932 -0.60600722, + 0.006899152 0.79526019 -0.60622913, + 0.0096967248 0.79774153 -0.60292166, + 0.023002006 0.7975682 -0.60279012, + 0.018908396 0.7935158 -0.60825586, + 0.029463993 0.79331285 -0.60810089, + 0.02472309 0.78793973 -0.61525577, + 0.032903593 0.78775382 -0.61511087, + 0.028173093 0.78150481 -0.62326288, + 0.033744205 0.7813701 -0.62315506, + 0.028759403 0.77353811 -0.63309705, + 0.032233398 0.77345598 -0.63303, + 0.027461195 0.76431686 -0.64425594, + 0.028625792 0.76429182 -0.64423484, + 0.022012306 0.74822116 -0.66308415, + 0.0270954 0.748128 -0.663001, + 0.032005012 0.75776929 -0.65173721, + 0.02868709 0.7578457 -0.65180278, + 0.033539716 0.76566434 -0.64236528, + 0.028013587 0.76579463 -0.64247471, + 0.032888904 0.77240109 -0.63428307, + 0.024719905 0.77258319 -0.6344322, + 0.029105011 0.77768332 -0.62798226, + 0.018749399 0.77787602 -0.62813801, + 0.022783989 0.78197461 -0.62289369, + 0.0090795411 0.7821461 -0.62302905, + 0.012738605 0.78544831 -0.61879623, + -0.0043649706 0.7855041 -0.61884105, + -0.0082249083 0.7823348 -0.62280387, + -0.0486986 0.78143299 -0.62208599, + -0.088034526 0.74901515 -0.6566782, + -0.11758901 0.74671805 -0.65466404, + -0.15159799 0.71781796 -0.67952591, + -0.18688904 0.71341616 -0.67535919, + -0.22004603 0.68422109 -0.69528508, + -0.26116708 0.67706925 -0.68801826, + -0.29168686 0.6489327 -0.70271266, + -0.33729202 0.63867909 -0.69160908, + -0.36468089 0.61202276 -0.70173776, + -0.41336879 0.5985027 -0.68623668, + -0.43677992 0.57424986 -0.69243079, + -0.48690987 0.55757886 -0.67232782, + -0.486774 0.56397098 -0.66707402, + -0.41371891 0.58777988 -0.69523484, + -0.3872481 0.61373115 -0.68802118, + -0.33779001 0.62654299 -0.70238298, + -0.30716503 0.65463305 -0.69072807, + -0.261659 0.66392303 -0.70052898, + -0.22752306 0.69347119 -0.68361616, + -0.18719399 0.69955993 -0.68961895, + -0.15143201 0.72903407 -0.66751605, + -0.11746199 0.73243392 -0.67062896, + -0.074825302 0.76603502 -0.63842899, + -0.0283066 0.76788002 -0.63996798, + -0.023026902 0.77194512 -0.63527209, + -0.0024069406 0.77214718 -0.63543916, + -0.0052649006 0.76976311 -0.63830805, + 0.011978205 0.76971835 -0.63827127, + 0.0084180189 0.76642388 -0.64227992, + 0.022496406 0.76625717 -0.64214015, + 0.018237999 0.76182085 -0.64753091, + 0.029241711 0.76162231 -0.64736122, + 0.024894411 0.75644338 -0.65358531, + 0.032794204 0.75627112 -0.65343606, + 0.027956491 0.74955475 -0.66135174, + 0.033650797 0.74942297 -0.66123593, + 0.028586404 0.74106807 -0.67082107, + 0.031911004 0.74099308 -0.67075408, + 0.026789887 0.73069364 -0.68217969, + 0.028291516 0.73066342 -0.68215144, + 0.021566793 0.71354073 -0.70028174, + 0.026736297 0.71345192 -0.70019394, + 0.031577703 0.72341007 -0.68969607, + 0.0279989 0.72348702 -0.68976998, + 0.033414502 0.73263597 -0.67979997, + 0.027746303 0.73276305 -0.67991805, + 0.032701604 0.73980504 -0.67202604, + 0.024585694 0.73997682 -0.6721828, + 0.029210286 0.74561661 -0.66573471, + 0.018082498 0.74581295 -0.66590995, + 0.021935906 0.74992317 -0.66116118, + 0.0080618905 0.7500791 -0.66129905, + 0.0113596 0.75320399 -0.65768898, + -0.0060660602 0.75323898 -0.65771902, + -0.0033543715 0.75555533 -0.65507632, + -0.024500186 0.75533253 -0.65488356, + -0.022289602 0.7570591 -0.65296608, + -0.047647923 0.75638735 -0.65238631, + -0.053922199 0.751791 -0.65719301, + -0.10733107 0.74853742 -0.65434843, + -0.15237497 0.7141118 -0.68324685, + -0.19128293 0.70920777 -0.67855376, + -0.2287049 0.67889172 -0.69771063, + -0.27376902 0.67073208 -0.68932503, + -0.30832285 0.64095569 -0.70293164, + -0.35810301 0.62909698 -0.68992698, + -0.38819015 0.60126221 -0.69842124, + -0.441284 0.58546603 -0.68007201, + -0.46956882 0.55704784 -0.68498379, + -0.53665787 0.53238088 -0.65465182, + -0.56725109 0.49713105 -0.65657204, + -0.62047201 0.473398 -0.62522697, + -0.64868253 0.43654069 -0.62341261, + -0.69993204 0.40966806 -0.58503604, + -0.72207308 0.37627605 -0.58054006, + -0.76921201 0.347545 -0.53621399, + -0.78574866 0.31835586 -0.53032875, + -0.82797217 0.28861907 -0.48079211, + -0.8397963 0.2637541 -0.47452718, + -0.8760249 0.23429596 -0.42152795, + -0.88408726 0.21372004 -0.41558808, + -0.91403711 0.18550701 -0.36072603, + -0.92097664 0.16327494 -0.35375589, + -0.94551426 0.13644002 -0.29561305, + -0.95031786 0.11540298 -0.28909898, + -0.96799511 0.093043007 -0.23308504, + -0.97038138 0.077963829 -0.22865207, + -0.98278725 0.059620615 -0.17485605, + -0.98384362 0.04936038 -0.17209095, + -0.99204051 0.034716986 -0.12103894, + -0.99243522 0.028196407 -0.11948803, + -0.99735326 0.016699104 -0.070765413, + -0.99745715 0.013143502 -0.070046104, + -0.99972802 0.00430123 -0.0229226, + -0.99973613 0.0032188105 -0.022745403, + -0.99973899 -0.00320109 0.022620199, + -0.99974447 -0.0022164311 0.022499111, + -0.99766266 -0.0066990578 0.068002477, + -0.99360067 -0.0008057307 0.11294696, + -0.99355191 -0.0066149193 0.11318499, + -0.99769253 -0.0039611883 0.067778073, + -0.99711353 -6.6780769e-005 0.075925462, + -0.99771255 -0.0022840588 0.067561172, + -0.99770224 -0.0040113311 0.067632616, + -0.99974948 -0.0013251706 0.022342911, + -0.99975049 -0.0013418695 0.02229449, + -0.99974948 0.0013448508 -0.022344012, + -0.99974602 0.00227571 -0.022420799, + -0.99764234 0.0069301021 -0.068277225, + -0.99759012 0.010023701 -0.068655007, + -0.99316275 0.016864996 -0.11551297, + -0.99294353 0.022569388 -0.11642095, + -0.98578 0.031981301 -0.16497, + -0.98517567 0.040690783 -0.16665295, + -0.97467321 0.053045113 -0.21725205, + -0.97330689 0.065399989 -0.21999197, + -0.95884174 0.08091148 -0.27216893, + -0.95608467 0.097825766 -0.27628291, + -0.93661511 0.11694101 -0.33026803, + -0.91471314 0.13718902 -0.38010406, + -0.93789989 0.11777198 -0.32630298, + -0.94181722 0.097407624 -0.32170209, + -0.95957911 0.08155971 -0.26936203, + -0.96166599 0.066143602 -0.26612699, + -0.97506666 0.05352588 -0.21535993, + -0.97609651 0.04204848 -0.21323089, + -0.98596245 0.032303415 -0.16381307, + -0.98640686 0.024114596 -0.16254199, + -0.99322975 0.017047796 -0.11490897, + -0.99337935 0.011780005 -0.11427504, + -0.99765903 0.0070122899 -0.068025, + -0.99769109 0.0041420204 -0.067789711, + -0.99975049 0.0013622193 -0.022294588, + -0.99975276 9.3634077e-007 -0.022237895, + -0.99975538 1.951479e-005 -0.022115286, + -0.99975234 2.2665907e-005 -0.022257308, + -0.99771512 0.0017996102 -0.067538708, + -0.99770111 0.0041971304 -0.067637905, + -0.99351835 0.0070401723 -0.11345404, + -0.99358237 0.0035861013 -0.11305404, + -0.99354666 0.0071367975 -0.11319897, + -0.98712403 0.0100648 -0.15964, + -0.98693889 0.017060699 -0.16018899, + -0.97789991 0.022142097 -0.20789798, + -0.97738624 0.032077607 -0.20901504, + -0.96544987 0.039529696 -0.25757298, + -0.964293 0.0530065 -0.25947899, + -0.94888824 0.063168816 -0.30922607, + -0.94664949 0.080452837 -0.31206116, + -0.92706299 0.093594298 -0.36303499, + -0.92306697 0.115419 -0.366914, + -0.89845431 0.13175204 -0.41883314, + -0.89330298 0.152831 -0.42267299, + -0.86530256 0.17044292 -0.47138175, + -0.85990888 0.18859898 -0.47432795, + -0.82779503 0.207288 -0.52133203, + -0.82038289 0.22845697 -0.52419394, + -0.78408486 0.24796897 -0.56896591, + -0.77428353 0.27214485 -0.57133365, + -0.73400062 0.29205984 -0.61314273, + -0.72150606 0.31909603 -0.61449707, + -0.67833221 0.33861211 -0.65207922, + -0.66310304 0.36798203 -0.65183103, + -0.61770022 0.38660714 -0.68482226, + -0.59951192 0.41829795 -0.68235797, + -0.55307978 0.43542078 -0.71028966, + -0.53225386 0.46870288 -0.70499885, + -0.48564377 0.48396775 -0.72795963, + -0.46255195 0.51827896 -0.71932793, + -0.41786721 0.53109026 -0.73710936, + -0.39321205 0.56564307 -0.72486705, + -0.35109198 0.57603592 -0.73818493, + -0.32543501 0.610385 -0.72216499, + -0.28702787 0.61836272 -0.73160267, + -0.26133984 0.65171057 -0.71202159, + -0.22689307 0.65756625 -0.71841925, + -0.20365089 0.6873247 -0.69721663, + -0.17374098 0.69135994 -0.70130992, + -0.15369694 0.71718776 -0.67971975, + -0.12756701 0.71988207 -0.68227303, + -0.108022 0.745655 -0.65751803, + -0.086012609 0.74726504 -0.65893608, + -0.067748427 0.77230638 -0.63162732, + -0.050383281 0.77310169 -0.63227779, + -0.034003109 0.7969352 -0.60310709, + -0.021088699 0.79721886 -0.60332197, + -0.0068214815 0.8197372 -0.57269913, + 0.0015536298 0.81975585 -0.57271093, + 0.016396195 0.84567469 -0.53344685, + 0.025488395 0.84551382 -0.53334486, + 0.022000492 0.83827168 -0.5448088, + 0.027323203 0.83816111 -0.54473805, + 0.028469687 0.84008658 -0.54170477, + 0.0158072 0.84032202 -0.541857, + -0.0024456899 0.81334686 -0.58177394, + -0.012900097 0.81328183 -0.58172691, + -0.029927507 0.78991616 -0.6124841, + -0.044967286 0.78947067 -0.61213875, + -0.064064607 0.76479214 -0.64108407, + -0.084266372 0.7636407 -0.64011878, + -0.10486404 0.73804224 -0.66655624, + -0.129443 0.73588997 -0.66461301, + -0.15103807 0.70965326 -0.68817127, + -0.17977194 0.70619273 -0.68481678, + -0.20146105 0.68009615 -0.70489919, + -0.23421006 0.67502016 -0.69963819, + -0.2594291 0.64446527 -0.71927822, + -0.29605806 0.63739717 -0.71138918, + -0.32369491 0.60298288 -0.72913182, + -0.36476383 0.59338373 -0.71752566, + -0.39162377 0.55838364 -0.73132658, + -0.435837 0.54618597 -0.71535099, + -0.46108413 0.51132613 -0.72522217, + -0.50774872 0.4964307 -0.70409358, + -0.53086191 0.46213794 -0.71036196, + -0.57802498 0.44499299 -0.68400902, + -0.59821093 0.41236094 -0.68709695, + -0.64448398 0.39346501 -0.65561098, + -0.66183084 0.36248592 -0.65618885, + -0.70625293 0.34232497 -0.61969393, + -0.72031081 0.31420192 -0.61840886, + -0.76208711 0.29328504 -0.57724106, + -0.77321202 0.267968 -0.57474899, + -0.8110339 0.24719997 -0.53020394, + -0.81946713 0.22501503 -0.52710706, + -0.8529399 0.20494696 -0.48009393, + -0.85914129 0.18577206 -0.47682819, + -0.88835102 0.166687 -0.42784101, + -0.89269632 0.15059206 -0.42475316, + -0.9177016 0.13275194 -0.37443382, + -0.91954213 0.14020102 -0.36713204, + -0.88771671 0.16424593 -0.43009585, + -0.88270086 0.18131098 -0.43354994, + -0.85215569 0.20189592 -0.48277181, + -0.84507418 0.22205506 -0.48635513, + -0.81011331 0.24349609 -0.5333162, + -0.800403 0.26706201 -0.53668702, + -0.76107419 0.28898206 -0.58073711, + -0.74849176 0.31546089 -0.58330482, + -0.70514798 0.33730301 -0.62369299, + -0.68922019 0.36680609 -0.62484312, + -0.64328706 0.38759905 -0.66026407, + -0.62398428 0.41953421 -0.65926832, + -0.57679719 0.43856716 -0.68917626, + -0.55424988 0.47238088 -0.68531984, + -0.50645804 0.48935807 -0.70995003, + -0.48081076 0.52466077 -0.70253265, + -0.43451715 0.53892517 -0.72163326, + -0.40679577 0.57446766 -0.71028459, + -0.36333698 0.58587396 -0.72438794, + -0.33403316 0.62133229 -0.70877934, + -0.29450899 0.62995899 -0.71862102, + -0.26791406 0.66083419 -0.70108515, + -0.23233491 0.66713977 -0.70777476, + -0.20919989 0.69345963 -0.68945563, + -0.17745495 0.69789582 -0.69386685, + -0.15392105 0.72458524 -0.67177725, + -0.12662205 0.72742224 -0.67440623, + -0.10377794 0.75356454 -0.64913064, + -0.080885909 0.75517315 -0.65051603, + -0.058845524 0.78095728 -0.62180626, + -0.041216914 0.78164828 -0.62235624, + -0.021283405 0.80591017 -0.59165514, + -0.0087455967 0.80606169 -0.59176677, + 0.012947001 0.83389515 -0.55177104, + 0.029441297 0.83360291 -0.55157894, + 0.028669596 0.83250988 -0.55326796, + 0.031993195 0.83242589 -0.55321193, + 0.027345303 0.8244471 -0.56527805, + 0.028585004 0.82441813 -0.56525904, + 0.022097699 0.81023097 -0.58569402, + 0.027356103 0.81012613 -0.58561707, + 0.032057695 0.81843787 -0.57369995, + 0.028829092 0.81851882 -0.57375586, + 0.033593118 0.82541347 -0.56352836, + 0.028481787 0.8255446 -0.56361771, + 0.028603204 0.82569313 -0.56339407, + 0.0079134321 0.82600516 -0.5636071, + -0.017280893 0.79736966 -0.60324371, + -0.032476094 0.79706782 -0.6030159, + -0.055371985 0.77188283 -0.63334882, + -0.07633131 0.77081311 -0.63247204, + -0.100901 0.74436402 -0.66010702, + -0.126289 0.74219197 -0.65818101, + -0.151538 0.71524203 -0.68225002, + -0.18232496 0.71146983 -0.67865181, + -0.20734701 0.68463898 -0.69876802, + -0.24239103 0.67897707 -0.69299108, + -0.26646402 0.65273309 -0.70918006, + -0.30473503 0.64500809 -0.70078605, + -0.33277488 0.61343777 -0.71620876, + -0.375101 0.60301602 -0.70403898, + -0.40563285 0.56672585 -0.71713579, + -0.45152599 0.55322301 -0.70004898, + -0.47969916 0.51727617 -0.70874125, + -0.52776295 0.50074494 -0.68609095, + -0.55314207 0.46547407 -0.69091809, + -0.60114789 0.44650489 -0.66276282, + -0.62287503 0.41320407 -0.66429603, + -0.67020392 0.39200094 -0.63020796, + -0.6881426 0.36123678 -0.62925965, + -0.733042 0.33863801 -0.58989298, + -0.74745804 0.31058803 -0.58723205, + -0.78854489 0.28752398 -0.54362392, + -0.79947788 0.26301298 -0.54005492, + -0.83613032 0.24017309 -0.49315616, + -0.84428209 0.21876803 -0.48921207, + -0.87627059 0.19669092 -0.4398438, + -0.88203788 0.17862798 -0.43600595, + -0.90940732 0.15767406 -0.38486016, + -0.91114801 0.16533899 -0.377455, + -0.87559915 0.19381003 -0.44245207, + -0.86897588 0.21293597 -0.44669795, + -0.835325 0.236561 -0.49625701, + -0.82600689 0.25915098 -0.50055295, + -0.78766412 0.28326404 -0.54712605, + -0.77508032 0.30935612 -0.55095315, + -0.73208827 0.33351612 -0.59398127, + -0.71580625 0.36282811 -0.59663826, + -0.66922867 0.38608381 -0.63487971, + -0.64875096 0.41858995 -0.63553494, + -0.60020792 0.43995595 -0.66797394, + -0.57571608 0.47471106 -0.66573304, + -0.52684319 0.49347118 -0.69204223, + -0.49872181 0.52964681 -0.68611276, + -0.45062721 0.54550421 -0.70665437, + -0.41931686 0.58247882 -0.69634175, + -0.37416679 0.59500366 -0.71131557, + -0.34521109 0.62698817 -0.69836617, + -0.30366501 0.63651103 -0.70897198, + -0.2792159 0.66235977 -0.69521075, + -0.24098806 0.66946518 -0.70266718, + -0.214531 0.696652 -0.684582, + -0.18051901 0.70154005 -0.68938708, + -0.15325703 0.72904718 -0.66708517, + -0.12396502 0.73207206 -0.66985303, + -0.096917212 0.7592001 -0.64360106, + -0.073394991 0.7607339 -0.64490092, + -0.047513306 0.78689814 -0.61525106, + -0.028954696 0.78745788 -0.61568797, + -0.00010346001 0.81704211 -0.57657808, + 0.024497297 0.8167969 -0.57640493, + 0.025282595 0.8176468 -0.57516485, + 0.033141594 0.81745881 -0.57503289, + 0.028306397 0.81141186 -0.58378893, + 0.033663105 0.81127709 -0.58369207, + 0.028853612 0.80411428 -0.59377426, + 0.031977788 0.80403769 -0.59371775, + 0.027352592 0.79562783 -0.60516787, + 0.028549897 0.79560089 -0.60514796, + 0.017937694 0.8079567 -0.58896875, + 0.026083604 0.80781114 -0.58886409, + 0.0173622 0.78180599 -0.62327999, + 0.019491099 0.78177488 -0.62325597, + 0.012864698 0.7524209 -0.65855694, + 0.0118278 0.75243098 -0.65856498, + 0.007705729 0.72025192 -0.69366992, + 0.0040222383 0.72026765 -0.69368464, + 0.0026142406 0.68525016 -0.72830319, + -0.0024500398 0.68525094 -0.72830296, + -0.0038722286 0.72036177 -0.69358778, + -0.0078182593 0.72034496 -0.69357193, + -0.011943296 0.75240469 -0.65859276, + -0.012619597 0.75239885 -0.6585868, + -0.019219099 0.78158391 -0.62350392, + -0.017119195 0.78161371 -0.62352777, + -0.025949387 0.80791765 -0.58872372, + -0.017825402 0.80806112 -0.58882904, + -0.032389808 0.81220216 -0.58247614, + 0.0046702307 0.8126201 -0.58277506, + 0.029015293 0.7874878 -0.6156469, + 0.04757189 0.78692681 -0.61520988, + 0.073397487 0.76082683 -0.64479083, + 0.096936181 0.75929183 -0.64348984, + 0.12377796 0.73238474 -0.66954577, + 0.15327401 0.72933906 -0.66676205, + 0.18048094 0.70189577 -0.68903476, + 0.21414299 0.69705999 -0.68428802, + 0.24065594 0.66983885 -0.70242482, + 0.27886397 0.66274494 -0.69498491, + 0.30364305 0.63655818 -0.70893919, + 0.34518704 0.62703705 -0.69833404, + 0.37261179 0.59679765 -0.71062857, + 0.41767001 0.584328 -0.69578201, + 0.44856799 0.54799497 -0.70603698, + 0.49641582 0.53225881 -0.68576378, + 0.52498293 0.49569595 -0.69186592, + 0.57399201 0.47691301 -0.66564798, + 0.59878576 0.44187185 -0.66798574, + 0.64727592 0.42054695 -0.63574696, + 0.66813302 0.38757199 -0.63512701, + 0.71488494 0.36423597 -0.59688497, + 0.73145074 0.33449388 -0.59421676, + 0.77446687 0.31032097 -0.55127293, + 0.78720313 0.28398204 -0.54741704, + 0.82566649 0.25979015 -0.50078332, + 0.83514285 0.23684993 -0.49642587, + 0.88480574 0.19028896 -0.42533392, + 0.84415615 0.21893203 -0.48935607, + 0.83594888 0.24046397 -0.49332196, + 0.79926389 0.26332396 -0.54021996, + 0.78809816 0.28831807 -0.54385114, + 0.74692881 0.31143495 -0.58745688, + 0.73240799 0.339627 -0.59011197, + 0.68736792 0.36229497 -0.62949795, + 0.66910774 0.39350885 -0.63043278, + 0.62182999 0.414682 -0.66435403, + 0.59972471 0.4484458 -0.66274172, + 0.55154592 0.46746495 -0.69084996, + 0.52589619 0.50295317 -0.68590921, + 0.47801393 0.51939392 -0.70833093, + 0.44946 0.55566901 -0.69944102, + 0.40346181 0.56916469 -0.71642864, + 0.37351802 0.60460109 -0.70352107, + 0.33152393 0.61491489 -0.71552181, + 0.30470803 0.64506108 -0.70074904, + 0.266413 0.65279102 -0.70914602, + 0.24206091 0.67932874 -0.69276178, + 0.20709093 0.68497175 -0.69851774, + 0.18225302 0.71159106 -0.67854404, + 0.15152702 0.71535504 -0.68213403, + 0.12610191 0.74247849 -0.65789354, + 0.10046201 0.74466705 -0.65983206, + 0.076270498 0.77068698 -0.63263297, + 0.055629659 0.77174145 -0.63349855, + 0.032540806 0.79713619 -0.60292214, + 0.017308399 0.79743999 -0.60315001, + -0.0078293122 0.82600319 -0.56361109, + -0.02826399 0.82569867 -0.56340283, + -0.028419893 0.82588983 -0.56311488, + -0.033768393 0.82575184 -0.5630219, + -0.028848989 0.81863868 -0.57358384, + -0.031731099 0.81856698 -0.57353401, + -0.027040403 0.81027412 -0.58542705, + -0.022056101 0.81037301 -0.58549899, + -0.028531304 0.82452214 -0.56511009, + -0.027028605 0.82455617 -0.56513411, + -0.031689484 0.83255857 -0.55302978, + -0.028996792 0.83262682 -0.5530749, + -0.029544186 0.83340156 -0.55187774, + -0.0130069 0.83369499 -0.55207199, + 0.0084723989 0.80615491 -0.59164393, + 0.021312509 0.80600035 -0.59153128, + 0.041466787 0.7814728 -0.62255991, + 0.059090894 0.78077888 -0.62200695, + 0.08057607 0.75565571 -0.64999378, + 0.10339998 0.75405788 -0.64861792, + 0.12663805 0.72748435 -0.67433631, + 0.15390597 0.7246508 -0.67170984, + 0.17724495 0.69819474 -0.69361979, + 0.20894289 0.69376862 -0.68922263, + 0.23228697 0.66722196 -0.70771295, + 0.26786196 0.66091692 -0.70102692, + 0.29334 0.631383 -0.71784902, + 0.33278078 0.62279463 -0.70808458, + 0.36136702 0.58833504 -0.72337806, + 0.40463799 0.57701099 -0.70945501, + 0.43285805 0.54098606 -0.72108805, + 0.47911993 0.52675593 -0.70211995, + 0.50500619 0.49125919 -0.70967126, + 0.55264586 0.47435489 -0.68525183, + 0.57559121 0.44007516 -0.68922323, + 0.62293422 0.42099014 -0.65933323, + 0.64255917 0.38860407 -0.66038215, + 0.68844044 0.36783922 -0.62509537, + 0.70461184 0.33795691 -0.62394488, + 0.74792618 0.3161391 -0.58366311, + 0.76073003 0.289253 -0.58105302, + 0.80016989 0.26728597 -0.53692293, + 0.80989432 0.24371609 -0.53354818, + 0.84494913 0.22222403 -0.48649505, + 0.85212898 0.201791 -0.48286301, + 0.8826521 0.18123701 -0.43368006, + 0.88953859 0.15753293 -0.42884079, + 0.91648126 0.13795303 -0.37554109, + 0.92175156 0.11402795 -0.37063682, + 0.94289535 0.097945534 -0.31836313, + 0.94583648 0.079495735 -0.31476015, + 0.96226555 0.066632472 -0.26382789, + 0.96381462 0.05252808 -0.26134691, + 0.97639453 0.042561781 -0.2117599, + 0.97713691 0.031999696 -0.21018897, + 0.98653036 0.024619808 -0.16171506, + 0.98683625 0.017009404 -0.16082604, + 0.99342364 0.012042295 -0.11386196, + 0.99351966 0.0069063175 -0.11344996, + 0.99771386 0.0020039098 -0.067549594, + 0.99770153 0.0041174679 -0.067636967, + 0.99975288 -0.00015861899 -0.022231398, + 0.99975061 0.0013363195 -0.022294292, + 0.99769163 0.0040631085 -0.067786381, + 0.9976579 0.007079869 -0.068033695, + 0.99337554 0.011894194 -0.11429594, + 0.99322379 0.017207997 -0.11493597, + 0.98639375 0.024342295 -0.16258796, + 0.9859575 0.032357216 -0.16383207, + 0.97608745 0.042119417 -0.2132591, + 0.97507423 0.053413112 -0.21535404, + 0.96167666 0.066005081 -0.26612291, + 0.95960778 0.081308678 -0.26933593, + 0.94185722 0.09710902 -0.32167509, + 0.93793809 0.11750901 -0.32628804, + 0.91476214 0.13688701 -0.38009506, + 0.90773714 0.16368702 -0.38629007, + 0.87783188 0.18687499 -0.44100896, + 0.86879867 0.21322292 -0.44690585, + 0.87073511 0.22254004 -0.43851605, + 0.82486486 0.25583798 -0.50412792, + 0.81400418 0.28011006 -0.50885713, + 0.77360302 0.30557799 -0.55512202, + 0.75895512 0.33356702 -0.55921406, + 0.71400565 0.35866681 -0.60129368, + 0.694929 0.39031199 -0.60392898, + 0.64643151 0.41413769 -0.6407935, + 0.62284392 0.44858894 -0.64096296, + 0.57322496 0.46983394 -0.67131895, + 0.54522395 0.50639397 -0.66805393, + 0.49573183 0.52462882 -0.69210875, + 0.46475282 0.56128085 -0.68481278, + 0.41702294 0.57614893 -0.70295393, + 0.38921407 0.60657406 -0.69323903, + 0.34448981 0.61819172 -0.70651662, + 0.31944501 0.64415801 -0.69499302, + 0.27796412 0.65298527 -0.70451838, + 0.25059596 0.68025595 -0.68880594, + 0.21292892 0.68656379 -0.69519174, + 0.18423101 0.71428204 -0.67517406, + 0.15158997 0.71832383 -0.67899281, + 0.12247495 0.74590874 -0.65469074, + 0.094677076 0.74819082 -0.65669382, + 0.066120982 0.77505583 -0.62842381, + 0.044632699 0.77598202 -0.62917399, + 0.016560506 0.80255729 -0.59634525, + 0.0011805494 0.80266666 -0.59642673, + -0.017796896 0.82120484 -0.57035589, + -0.028366007 0.82100415 -0.57021713, + -0.025391715 0.81781048 -0.57492733, + -0.033190012 0.81762332 -0.5747962, + -0.028345 0.81156802 -0.58357, + -0.0336615 0.81143397 -0.58347398, + -0.028708013 0.80406034 -0.59385431, + -0.031819519 0.80398446 -0.59379834, + -0.02716771 0.79552829 -0.60530722, + -0.02861689 0.7954967 -0.60528177, + -0.021947999 0.78010386 -0.62526494, + -0.027218914 0.78000236 -0.6251843, + -0.032012884 0.78894866 -0.61362469, + -0.028718892 0.78902781 -0.61368591, + -0.033598017 0.79649246 -0.60371435, + -0.02800009 0.79662973 -0.60381877, + -0.033035781 0.80310452 -0.59492165, + -0.025258388 0.80328667 -0.59505671, + -0.0297985 0.80829 -0.58802998, + -0.019638101 0.80849302 -0.58817798, + -0.021643801 0.81042898 -0.585437, + -0.0079309586 0.8105939 -0.58555496, + 0.013754805 0.79121131 -0.61138827, + 0.032879993 0.79085881 -0.61111486, + 0.064073212 0.7634002 -0.64274019, + 0.089336656 0.76191366 -0.64148772, + 0.121004 0.73379499 -0.66850799, + 0.152128 0.73062199 -0.66561902, + 0.18325789 0.70238656 -0.68780059, + 0.219891 0.69699901 -0.68252498, + 0.24995098 0.66881996 -0.70014596, + 0.29146084 0.66075569 -0.69170266, + 0.31900108 0.63381219 -0.70464218, + 0.36423498 0.62281293 -0.69241393, + 0.38886005 0.59747106 -0.70129603, + 0.43687093 0.58335096 -0.68472296, + 0.464342 0.55312997 -0.69168901, + 0.51405376 0.53570676 -0.66990072, + 0.54468876 0.49879575 -0.67417872, + 0.5953849 0.47786087 -0.6458838, + 0.62218469 0.44174379 -0.64633471, + 0.67244118 0.41763908 -0.61106509, + 0.69417918 0.38435009 -0.6085971, + 0.74128604 0.35839304 -0.56749403, + 0.75818062 0.32856986 -0.5632087, + 0.80068785 0.30188093 -0.5174619, + 0.81325287 0.27594197 -0.51232392, + 0.85079509 0.24919103 -0.46265706, + 0.8627432 0.21950406 -0.45551312, + 0.89638627 0.19242905 -0.39932808, + 0.90559685 0.16264598 -0.39171493, + 0.93140787 0.13957499 -0.33615196, + 0.93664211 0.11666802 -0.33028802, + 0.95610499 0.0975952 -0.27629399, + 0.95886463 0.080652967 -0.27216491, + 0.97332853 0.065182872 -0.2199609, + 0.97468114 0.052932009 -0.21724403, + 0.98518312 0.040600102 -0.16663101, + 0.98577654 0.032038786 -0.16497892, + 0.99294013 0.022612803 -0.11644101, + 0.99315578 0.017023396 -0.11554997, + 0.99758822 0.010116703 -0.068669118, + 0.99764115 0.0069973511 -0.06828811, + 0.99974591 0.0022976499 -0.022422997, + 0.99974954 0.0013193594 -0.022342289, + 0.99975061 -0.0013164296 0.022292592, + 0.99975109 -0.0011324601 0.022285001, + 0.9997189 -0.0011555098 0.023681697, + 0.99971378 -0.0033747694 0.023683395, + 0.99966365 -0.0031729687 0.025741192, + 0.99972963 -0.0027052991 0.023095893, + 0.99971378 -0.0027565493 0.023766495, + 0.99971747 -0.0005624133 0.023764912, + 0.99973321 -0.00055117614 0.023094205, + 0.99967939 0.00060410268 -0.025311986, + 0.99967927 0.00088002323 -0.025312105, + 0.99967825 0.00087999325 -0.025349606, + 0.99967849 -0.00064755528 -0.025348412, + 0.99967486 -0.00064515695 -0.025489297, + 0.99967474 0.00087181677 -0.025490494, + 0.99723238 -0.002700951 -0.074299231, + 0.99723577 -0.00040414892 -0.074301288, + 0.99723625 -0.00040426408 -0.074294612, + 0.99723011 -0.0035895405 -0.074291706, + 0.99701309 -0.0032577605 -0.077164806, + 0.10280801 -0.0031701506 0.99469614, + 0.075925313 0.00085408217 0.99711323, + 0.025920695 0.00072750682 0.99966377, + 0.025917394 -0.015252196 0.99954778, + 0.02611289 -0.015252095 0.99954265, + 0.02611619 0.00073155074 0.99965864, + -0.023183202 -0.0066481209 0.99970913, + 0.25466493 -0.0045248591 -0.96701878, + 0.073505826 0.0090908529 -0.99725336, + 0.073509388 -0.0011905398 -0.99729377, + 0.073566861 -0.0011882994 -0.99728954, + 0.073563404 0.0090907905 -0.99724913, + 0.17087506 -0.0016485606 -0.98529136, + 0.17091393 -0.0016458494 -0.98528463, + 0.17091008 0.0064645833 -0.98526549, + 0.17087105 0.0064646713 -0.98527223, + 0.12234592 0.0075939451 -0.9924584, + 0.12233006 0.0075939735 -0.99246049, + 0.15862001 0.018992202 -0.98715711, + 0.15841696 0.043587789 -0.98640978, + 0.11234593 0.043865774 -0.9927004, + 0.11199695 0.074359164 -0.99092251, + 0.066615224 0.074663728 -0.99498135, + 0.0662935 0.105228 -0.99223602, + 0.021583 0.105435 -0.994192, + 0.021444499 0.13591801 -0.99048799, + -0.022107592 0.13591595 -0.99047363, + -0.022248307 0.10548203 -0.99417233, + -0.066987984 0.10527097 -0.99218476, + -0.067298472 0.074926764 -0.99491554, + -0.11256297 0.074619688 -0.99083877, + -0.11290903 0.044677313 -0.99260038, + -0.15875605 0.044394612 -0.98631924, + -0.15895206 0.021403208 -0.98705435, + -0.17396696 0.0073968382 -0.98472375, + -0.17399108 0.0073967939 -0.98471946, + -0.17399704 -0.0013371804 -0.98474526, + -0.17397308 -0.0013388906 -0.9847495, + -0.15389693 -0.0047384175 -0.98807549, + -0.12545699 -0.00066253095 -0.99209887, + -0.12545294 0.0078493962 -0.99206853, + -0.12551706 0.0078492733 -0.99206048, + -0.12552196 -0.00066901575 -0.99209064, + -0.12537503 -0.00066903018 -0.99210924, + -0.12533601 0.0241252 -0.99182099, + -0.11306303 0.019611506 -0.99339426, + -0.11291603 0.04468631 -0.99259925, + -0.067557693 0.044871196 -0.99670589, + -0.067344896 0.074986003 -0.99490798, + -0.022395793 0.075137772 -0.99692166, + -0.022287905 0.10553102 -0.99416625, + 0.021661598 0.10553198 -0.9941799, + 0.021756792 0.075033873 -0.99694365, + 0.066788107 0.074884206 -0.9949531, + 0.066991009 0.044311605 -0.99676913, + 0.112547 0.0441291 -0.99266601, + 0.11271195 0.016690692 -0.99348754, + 0.12224504 0.020198908 -0.99229437, + 0.12227194 -0.00046782577 -0.99249655, + 0.12234998 -0.00046781794 -0.99248689, + 0.12233497 -0.00046626589 -0.99248874, + 0.15389697 -0.004686119 -0.98807573, + 0.051477287 -0.0047632488 -0.99866277, + -0.029028507 0.010331702 -0.99952525, + -0.029030293 -0.0012539696 -0.99957776, + -0.028964089 -0.0012450696 -0.99957967, + -0.028962303 0.010331801 -0.9995271, + -0.022414295 0.017607396 -0.99959373, + -0.022384593 0.044810385 -0.99874467, + 0.022013498 0.044810798 -0.99875289, + 0.022047305 0.011284503 -0.99969321, + 0.024504894 0.014418496 -0.99959576, + -0.0028998293 0.014422797 -0.99989176, + -0.0029001713 -0.0007962794 -0.99999547, + 0.024507809 -0.00079604331 -0.99969935, + 0.024775594 -0.00083206181 -0.99969274, + 0.02477381 0.011283504 -0.99962938, + 0.067257114 0.016383404 -0.99760121, + 0.067166716 0.044536911 -0.99674726, + 0.021868307 0.044627115 -0.99876434, + 0.021793807 0.075080633 -0.99693936, + -0.022349501 0.075079605 -0.99692714, + -0.022424489 0.044860978 -0.99874151, + -0.067478783 0.044769987 -0.99671578, + -0.067575291 0.018431298 -0.99754387, + -0.076703385 0.0086024785 -0.99701679, + -0.076579332 0.0086026331 -0.99702638, + -0.076582693 -0.00092539191 -0.99706286, + -0.076706812 -0.00092055922 -0.99705327, + -0.051477287 -0.0047722389 -0.99866277, + 0 -0.0030687412 0.99999535, + -0.022946889 0.00047594577 0.99973655, + -0.022570102 0.00046815106 0.99974513, + -0.022567289 -0.015013193 0.99963254, + -0.072118118 -0.014043104 0.99729723, + -0.072126001 0.00106484 0.99739498, + -0.07193806 0.0010648496 0.99740851, + -0.071928486 -0.015539196 0.99728876, + -0.071947135 -0.015539207 0.99728745, + -0.071956716 0.0010627002 0.99740726, + -0.10280804 -0.0031235912 0.99469638, + -0.25466505 -0.0046267407 -0.96701825, + -0.2221151 -0.00036321417 -0.97502047, + -0.22210696 0.0073047089 -0.9749949, + -0.22208592 0.0073047774 -0.97499967, + -0.22209311 -0.00036159519 -0.97502548, + -0.22195707 -0.00036161911 -0.97505635, + -0.221853 0.029888 -0.97462201, + -0.20546605 0.019029804 -0.97847927, + -0.20518896 0.04395609 -0.97773474, + -0.15871699 0.044342496 -0.98632789, + -0.15824607 0.074033037 -0.98462045, + -0.11247299 0.074501991 -0.9908579, + -0.11195693 0.10469494 -0.98818243, + -0.066870272 0.10512195 -0.99220854, + -0.066450231 0.13558806 -0.98853445, + -0.022057505 0.13585503 -0.99048322, + -0.021882305 0.16657904 -0.98578525, + 0.02125879 0.16658093 -0.98579854, + 0.021430692 0.13590096 -0.99049062, + 0.065723397 0.135639 -0.98857599, + 0.066142619 0.10503703 -0.99226636, + 0.11128303 0.10461304 -0.98826736, + 0.11180194 0.074104764 -0.99096352, + 0.15773402 0.073638804 -0.98473209, + 0.15821098 0.043312095 -0.9864549, + 0.20491704 0.04293371 -0.97783726, + 0.20519893 0.015559695 -0.97859663, + 0.21892197 0.024651097 -0.97543091, + 0.2189931 -0.0002031801 -0.97572649, + 0.2189569 -0.0002031859 -0.97573453, + 0.21905795 -0.00021080195 -0.97571176, + 0.21905403 0.0058582607 -0.97569513, + 0.25166804 0.019652702 -0.96761411, + 0.26654708 0.0053102518 -0.96380734, + 0.26655108 -0.0021705306 -0.96381837, + 0.26655811 -0.0021699208 -0.96381646, + 0.26655293 0.0053102183 -0.96380562, + 0.31341386 0.026438586 -0.94924855, + 0.31353012 -3.4475711e-006 -0.94957834, + 0.31356102 -3.4396005e-006 -0.94956809, + 0.31354389 -2.4736391e-006 -0.94957364, + 0.3597081 -0.0050520012 -0.93305123, + 0.359707 0.00416394 -0.933056, + 0.35968691 0.0041640289 -0.93306375, + 0.35968998 -0.0027542498 -0.93306786, + 0.35275203 -0.0035367205 -0.93571013, + 0.44708893 -0.0036906695 -0.8944819, + 0.44929701 -0.0034097901 -0.89337599, + 0.44929412 0.004154461 -0.89337426, + 0.48123711 0.016921803 -0.87642723, + 0.480827 0.035856102 -0.876082, + 0.43579707 0.036806002 -0.89929211, + 0.43474907 0.064049408 -0.89827114, + 0.3888 0.065526702 -0.918989, + 0.38728991 0.093655579 -0.91718876, + 0.34059215 0.095509842 -0.93534744, + 0.33869997 0.12457599 -0.93261087, + 0.29216987 0.12662496 -0.94794667, + 0.290023 0.156469 -0.94414198, + 0.24383706 0.15856205 -0.95676625, + 0.24155691 0.18904793 -0.95179367, + 0.196052 0.191036 -0.96180499, + 0.19381095 0.22200795 -0.95558876, + 0.14903702 0.22377203 -0.96317911, + 0.14700201 0.25509903 -0.95567513, + 0.10374796 0.25650892 -0.96095765, + 0.10210695 0.28754586 -0.95230854, + 0.060544793 0.28852597 -0.95555586, + 0.059467569 0.31918284 -0.94582552, + 0.019256491 0.31968984 -0.94732654, + 0.018865705 0.34958908 -0.93671322, + -0.019344991 0.34958583 -0.93670458, + -0.019728007 0.31972712 -0.94730437, + -0.059813671 0.31921586 -0.9457925, + -0.060897283 0.28847894 -0.95554775, + -0.10255496 0.28749192 -0.95227665, + -0.10419502 0.25632906 -0.96095723, + -0.14738202 0.25491703 -0.95566511, + -0.14942408 0.2235171 -0.96317846, + -0.194332 0.221745 -0.95554399, + -0.19657591 0.1905899 -0.96178651, + -0.24219792 0.18859492 -0.95172065, + -0.24447106 0.15805605 -0.95668823, + -0.29056504 0.15596901 -0.94405812, + -0.29270497 0.12632298 -0.94782186, + -0.33935311 0.12427004 -0.93241435, + -0.34120196 0.095737986 -0.93510187, + -0.387784 0.093880199 -0.91695702, + -0.38926715 0.066542722 -0.91871834, + -0.4350878 0.065044567 -0.89803559, + -0.4361099 0.03916489 -0.89904076, + -0.48101681 0.038155984 -0.87588072, + -0.48140377 0.021605488 -0.87623256, + -0.49540606 0.0071511809 -0.86863214, + -0.49542099 0.000195163 -0.868653, + -0.49534705 0.00019513002 -0.86869514, + -0.49533206 0.0071808808 -0.8686741, + -0.49548611 0.0071795019 -0.86858618, + -0.52535206 0.020580001 -0.85063612, + -0.52495211 0.036698107 -0.85034019, + -0.48079482 0.037806284 -0.87601769, + -0.47975013 0.062768117 -0.87515724, + -0.43468991 0.064425983 -0.89827275, + -0.4331412 0.090903245 -0.89673042, + -0.38720191 0.092987679 -0.91729379, + -0.38519916 0.12082005 -0.91489029, + -0.33863199 0.123188 -0.93282002, + -0.3362571 0.15239602 -0.92935824, + -0.28981498 0.15487398 -0.94446886, + -0.28720599 0.184964 -0.93984097, + -0.24134688 0.18739091 -0.95217454, + -0.2386409 0.21837293 -0.94623667, + -0.19350603 0.22061902 -0.95597214, + -0.19090295 0.25204495 -0.94869876, + -0.14667299 0.25398999 -0.95602101, + -0.14436997 0.28529295 -0.94750476, + -0.10200694 0.28680882 -0.95254141, + -0.10019498 0.3176789 -0.94288975, + -0.059398092 0.31872296 -0.9459849, + -0.058217008 0.34891304 -0.93534511, + -0.019217703 0.34944108 -0.93676126, + -0.018802702 0.37907207 -0.92517614, + 0.018316703 0.37907609 -0.92518425, + 0.018738499 0.34944397 -0.9367699, + 0.057745598 0.34892201 -0.93537098, + 0.05894047 0.31855685 -0.94606954, + 0.099751234 0.31752011 -0.94299036, + 0.10155798 0.28686094 -0.95257378, + 0.14403203 0.28534606 -0.94754022, + 0.14631999 0.25420898 -0.9560169, + 0.19043605 0.25227207 -0.94873226, + 0.19304092 0.22095892 -0.95598763, + 0.23809206 0.21871805 -0.94629526, + 0.24078993 0.18796295 -0.95220274, + 0.28666404 0.18553402 -0.93989414, + 0.28927994 0.15538597 -0.94454879, + 0.33563191 0.15290996 -0.92949975, + 0.33802986 0.12357194 -0.93298757, + 0.38466209 0.12119803 -0.91506624, + 0.3867079 0.09276478 -0.91752476, + 0.4326739 0.090687476 -0.89697778, + 0.43426794 0.063299894 -0.89855689, + 0.47942394 0.061669592 -0.87541389, + 0.48050395 0.035347298 -0.87627989, + 0.52481717 0.034308311 -0.85052329, + 0.52524078 0.015545192 -0.8508116, + 0.49264312 0.0040225908 -0.87022215, + 0.49268913 0.0040223007 -0.87019616, + 0.49269995 0.0040178997 -0.87018991, + 0.49270517 0.00020931807 -0.87019628, + 0.49269381 0.00020931293 -0.87020272, + 0.49264783 0.00021134093 -0.87022871, + 0.53475285 -0.0034008089 -0.8450017, + 0.53474903 0.0040988503 -0.8450011, + 0.53466696 0.0040993993 -0.8450529, + 0.53466994 -0.0041211797 -0.84505087, + 0.53668988 -0.0038405191 -0.8437708, + 0.62061214 -0.004043201 -0.78410721, + 0.61491174 -0.0048957481 -0.78858072, + 0.61490488 0.0055430187 -0.78858185, + 0.6528492 0.011332802 -0.75740319, + 0.65289521 0.00015935105 -0.75744832, + 0.65291184 0.00015936195 -0.75743383, + 0.65299517 0.00015531004 -0.75736219, + 0.68925399 -0.00200768 -0.72451699, + 0.68923503 0.0069997408 -0.72450405, + 0.72394735 0.0062013529 -0.68982738, + 0.72396392 3.7814898e-005 -0.68983793, + 0.69793761 -0.0043151472 -0.71614558, + 0.76786715 -0.0044018603 -0.64059407, + 0.78819531 -0.00012098204 -0.61542523, + 0.78819114 0.0028401203 -0.61542404, + 0.78804511 0.0028417502 -0.61561108, + 0.78804964 -0.00014823693 -0.61561167, + 0.78806669 -0.00014821894 -0.61558974, + 0.78801614 0.010849501 -0.61555904, + 0.79210937 0.0087623838 -0.61031628, + 0.79181999 0.0216118 -0.61037201, + 0.75915885 0.023032494 -0.65049779, + 0.758349 0.041065399 -0.650554, + 0.72318667 0.043509878 -0.68928063, + 0.72181684 0.063130282 -0.68919879, + 0.68414623 0.066529222 -0.72630423, + 0.68213105 0.08780551 -0.72593904, + 0.64260322 0.092004433 -0.76065528, + 0.63986677 0.11503196 -0.75982767, + 0.59868407 0.11989602 -0.79196113, + 0.59519005 0.14460501 -0.79046714, + 0.55229509 0.15001501 -0.82004011, + 0.54802704 0.17638901 -0.81765109, + 0.50360996 0.18218198 -0.84450388, + 0.49861181 0.21009792 -0.84097868, + 0.45356405 0.21601303 -0.86464912, + 0.44797021 0.24497512 -0.85983139, + 0.40297085 0.25077391 -0.88018572, + 0.39691091 0.28078395 -0.87385482, + 0.35193202 0.28634202 -0.89115214, + 0.34567383 0.31671885 -0.88328856, + 0.30113405 0.32185808 -0.89762223, + 0.29481101 0.35278001 -0.88805002, + 0.25173989 0.35729882 -0.89942461, + 0.24560393 0.38843891 -0.88814074, + 0.20456304 0.39223906 -0.89682913, + 0.19888307 0.42326516 -0.88390732, + 0.15958305 0.4263581 -0.89036626, + 0.15456396 0.45703188 -0.87591773, + 0.11744998 0.45938894 -0.88043588, + 0.11328803 0.48959312 -0.86456019, + 0.079127498 0.49122 -0.86743402, + 0.076050192 0.52033693 -0.85056788, + 0.044464711 0.52133113 -0.8521952, + 0.042587914 0.54901719 -0.83472532, + 0.013509698 0.54946595 -0.8354069, + 0.012871598 0.57610697 -0.8172729, + -0.013539798 0.5761019 -0.81726581, + -0.014178902 0.54942906 -0.83542013, + -0.043254904 0.54897004 -0.8347221, + -0.045128677 0.52131778 -0.85216856, + -0.076733164 0.52031076 -0.85052258, + -0.079805821 0.49123013 -0.86736619, + -0.11391903 0.48959318 -0.86447728, + -0.11806902 0.45945606 -0.88031811, + -0.15516397 0.45708889 -0.87578177, + -0.16019005 0.42635608 -0.89025825, + -0.19929799 0.423269 -0.88381201, + -0.2049399 0.39249381 -0.8966316, + -0.24619406 0.38866308 -0.88787925, + -0.25228688 0.35768282 -0.8991186, + -0.29515797 0.35317197 -0.88777888, + -0.30148593 0.32220992 -0.89737779, + -0.34597582 0.31706384 -0.88304657, + -0.35228497 0.28641298 -0.8909899, + -0.397158 0.28086001 -0.87371802, + -0.40324295 0.25073597 -0.88007188, + -0.44827685 0.24492891 -0.85968471, + -0.45393115 0.21559708 -0.86456031, + -0.498887 0.209699 -0.84091502, + -0.50396097 0.18135299 -0.84447289, + -0.54842985 0.17557295 -0.81755668, + -0.55270797 0.14905499 -0.81993687, + -0.59561515 0.14367104 -0.79031718, + -0.59908694 0.11902399 -0.79178786, + -0.64027303 0.11418601 -0.7596131, + -0.64295226 0.091556832 -0.7604143, + -0.68242615 0.087378621 -0.72571319, + -0.6843822 0.066766113 -0.72606015, + -0.72201383 0.063355483 -0.68897182, + -0.72332102 0.044771001 -0.68905902, + -0.7584421 0.042257104 -0.65036905, + -0.75921899 0.025565499 -0.65033299, + -0.7918371 0.023990303 -0.61026108, + -0.79214531 0.011401704 -0.61022621, + -0.78997284 0.012527697 -0.61301386, + -0.79003966 2.4914987e-005 -0.61305571, + -0.79002011 2.4895104e-005 -0.61308104, + -0.7899068 3.7248492e-006 -0.61322689, + -0.76786691 -0.0043120794 -0.64059496, + -0.82967281 -0.0043707993 -0.5582329, + -0.84637946 -0.0001615971 -0.53258032, + -0.8463099 0.012384998 -0.53254694, + -0.846187 0.0123903 -0.53274202, + -0.8462562 -0.00018830904 -0.53277612, + -0.84633189 -0.00018821398 -0.53265595, + -0.84620398 0.016962901 -0.53258902, + -0.85041809 0.015671501 -0.52587408, + -0.84975916 0.032472506 -0.52617013, + -0.82114702 0.035154801 -0.56963301, + -0.82020873 0.049764581 -0.5698958, + -0.78915972 0.053428981 -0.61185974, + -0.78767866 0.070025772 -0.61209369, + -0.75421786 0.074633494 -0.65236896, + -0.75206685 0.093319878 -0.65244681, + -0.71593016 0.098853923 -0.69113821, + -0.71297991 0.11967099 -0.69089693, + -0.67426115 0.12603803 -0.72765815, + -0.67038357 0.14909391 -0.72688156, + -0.62982774 0.15606993 -0.7608937, + -0.62496185 0.18124595 -0.75932384, + -0.5827961 0.18866804 -0.7904132, + -0.57700568 0.21540989 -0.78782165, + -0.53339189 0.22309095 -0.8159188, + -0.52673519 0.25123608 -0.81205332, + -0.48203799 0.258957 -0.83700699, + -0.47461212 0.28837407 -0.83161515, + -0.42990109 0.29580507 -0.85304415, + -0.42196101 0.32594699 -0.84599501, + -0.37775484 0.33288288 -0.86399668, + -0.36944199 0.36377001 -0.855093, + -0.32598099 0.37008101 -0.86992902, + -0.31754303 0.40143007 -0.85908109, + -0.27532983 0.40697876 -0.87095445, + -0.26708007 0.43841612 -0.85817218, + -0.22690697 0.44307595 -0.86729288, + -0.21912906 0.47427613 -0.85266918, + -0.18142794 0.47802281 -0.8594057, + -0.17440605 0.50860614 -0.8431502, + -0.139226 0.51149201 -0.84793401, + -0.13330694 0.54067576 -0.83060157, + -0.10085604 0.54276317 -0.8338083, + -0.096078813 0.57104903 -0.81527412, + -0.066786282 0.57242191 -0.81723481, + -0.063299581 0.59953988 -0.79783779, + -0.036940202 0.60033506 -0.79889512, + -0.034811005 0.62630808 -0.7787981, + -0.0112841 0.62664902 -0.77921999, + -0.010573401 0.65131706 -0.75873214, + 0.010048099 0.65132093 -0.7587359, + 0.0107589 0.62670302 -0.77918398, + 0.034199595 0.62637293 -0.77877289, + 0.03632639 0.60043275 -0.7988497, + 0.062638804 0.59965008 -0.7978071, + 0.06612882 0.57250619 -0.81722927, + 0.095396899 0.571145 -0.81528699, + 0.10014503 0.54303616 -0.83371627, + 0.13257399 0.54096293 -0.8305319, + 0.13858102 0.51134515 -0.8481282, + 0.17377599 0.50847095 -0.84336185, + 0.18077694 0.47797981 -0.85956669, + 0.21836397 0.47425893 -0.85287488, + 0.22622597 0.44277394 -0.86762488, + 0.26646096 0.43812388 -0.85851383, + 0.2747561 0.40654916 -0.87133628, + 0.31716108 0.40099308 -0.8594262, + 0.32556704 0.36976102 -0.87022012, + 0.36910698 0.36345196 -0.85537291, + 0.37743405 0.33252403 -0.8642751, + 0.42168784 0.32559487 -0.84626669, + 0.429645 0.29539001 -0.85331702, + 0.47446081 0.28795791 -0.8318457, + 0.48180813 0.25882807 -0.83717918, + 0.52659196 0.25110096 -0.81218791, + 0.53319097 0.22319797 -0.81602091, + 0.57675815 0.21552604 -0.7879712, + 0.58250004 0.18906303 -0.79053712, + 0.62464887 0.18163696 -0.75948781, + 0.62945783 0.15683796 -0.76104182, + 0.67002916 0.14983404 -0.72705621, + 0.67389303 0.12697001 -0.72783709, + 0.71263397 0.12056199 -0.69109893, + 0.71560705 0.099714518 -0.69134909, + 0.7517873 0.094132841 -0.65265226, + 0.75399065 0.075076766 -0.65258068, + 0.78748333 0.070442535 -0.6122973, + 0.78902018 0.053194713 -0.61206013, + 0.81965297 0.049600899 -0.57070899, + 0.81836879 0.064531982 -0.57105887, + 0.78694803 0.069284797 -0.61311698, + 0.78496915 0.086892426 -0.61341113, + 0.75106519 0.09259972 -0.6537022, + 0.74833626 0.11211403 -0.65377623, + 0.71175581 0.11872497 -0.69232082, + 0.70814317 0.14028603 -0.69199216, + 0.66898471 0.14767893 -0.72845763, + 0.66440582 0.17121495 -0.72749585, + 0.62341392 0.17912298 -0.76109791, + 0.61783278 0.20449792 -0.75925171, + 0.57535601 0.212715 -0.78975803, + 0.56881368 0.23963988 -0.78678066, + 0.52500182 0.24798392 -0.81417269, + 0.517537 0.27642101 -0.80978203, + 0.47273794 0.28467196 -0.83395487, + 0.46451899 0.31426999 -0.827923, + 0.41979015 0.32209811 -0.84854531, + 0.41095409 0.35273308 -0.84065217, + 0.36709583 0.35990083 -0.85773659, + 0.35790682 0.39124683 -0.84783757, + 0.31516597 0.39764893 -0.86171091, + 0.30591801 0.42937699 -0.84973502, + 0.26444691 0.43494385 -0.86075068, + 0.25542003 0.46678707 -0.84668213, + 0.21640597 0.47136095 -0.85497791, + 0.20810707 0.50228316 -0.83928728, + 0.17189693 0.50588185 -0.84530169, + 0.16451998 0.53588295 -0.82810789, + 0.13074398 0.53862292 -0.8323409, + 0.12446801 0.56755906 -0.81387013, + 0.093984157 0.56947571 -0.81661761, + 0.08898858 0.59725189 -0.7971018, + 0.061577208 0.59849304 -0.79875809, + 0.0579766 0.62486899 -0.77857399, + 0.033403181 0.62557262 -0.77945054, + 0.031203311 0.65084022 -0.75857329, + 0.009839599 0.65112597 -0.75890589, + 0.0091036288 0.67525196 -0.73753095, + -0.009573428 0.6752488 -0.73752785, + -0.010308397 0.65106982 -0.75894785, + -0.031755213 0.65077627 -0.7586053, + -0.033958707 0.62545216 -0.77952319, + -0.058330186 0.62474787 -0.7786448, + -0.061975393 0.59809697 -0.79902387, + -0.08964505 0.59683633 -0.7973395, + -0.09459462 0.56929511 -0.81667316, + -0.12533301 0.56735003 -0.81388313, + -0.13158301 0.53847098 -0.83230698, + -0.16500293 0.53574878 -0.8280986, + -0.17237401 0.50580406 -0.84525114, + -0.20871796 0.50218087 -0.8391968, + -0.21703297 0.47117794 -0.85491991, + -0.25606298 0.46659094 -0.84659588, + -0.26498389 0.4351058 -0.86050355, + -0.30626503 0.42955306 -0.8495211, + -0.3154799 0.3979699 -0.86144781, + -0.3582719 0.39154691 -0.84754485, + -0.36744508 0.36024809 -0.85744119, + -0.41125709 0.35307309 -0.84036118, + -0.42007893 0.32248098 -0.84825689, + -0.46466488 0.3146629 -0.82769179, + -0.47288787 0.28508195 -0.8337298, + -0.5176819 0.27681494 -0.80955482, + -0.52519095 0.24820597 -0.8139829, + -0.56901008 0.23984803 -0.78657514, + -0.57561809 0.21262603 -0.78959113, + -0.61802006 0.20442103 -0.75912011, + -0.62368596 0.17864299 -0.76098788, + -0.66465497 0.17075299 -0.72737694, + -0.66929483 0.14684197 -0.72834182, + -0.70844007 0.13948502 -0.69185007, + -0.71206594 0.11775298 -0.69216794, + -0.74863875 0.11118996 -0.65358776, + -0.75134033 0.091774344 -0.65350229, + -0.78520787 0.086116493 -0.61321497, + -0.78713864 0.068855569 -0.6129207, + -0.81853414 0.064131305 -0.57086706, + -0.81983185 0.048929788 -0.57050991, + -0.84832817 0.045244113 -0.52753413, + -0.84727317 0.058238216 -0.52795511, + -0.81806099 0.063059703 -0.57166398, + -0.81636018 0.078937523 -0.57212311, + -0.78458798 0.084742799 -0.61419898, + -0.78216112 0.10274202 -0.61454707, + -0.74784917 0.10946803 -0.65478116, + -0.744528 0.129786 -0.654854, + -0.70746905 0.13739702 -0.69326007, + -0.70312017 0.16000505 -0.69283515, + -0.66352224 0.16835105 -0.72896922, + -0.65812093 0.19288097 -0.72778696, + -0.61670178 0.20166293 -0.76092768, + -0.61026502 0.227791 -0.75874102, + -0.56750399 0.236754 -0.788598, + -0.5600329 0.26447195 -0.78512281, + -0.51600385 0.27344692 -0.8117677, + -0.50760704 0.30248004 -0.80674714, + -0.46288395 0.31119698 -0.82999688, + -0.453686 0.34145501 -0.82315099, + -0.40939006 0.34957704 -0.84273112, + -0.39966407 0.38058406 -0.83392113, + -0.35625592 0.38794392 -0.85004783, + -0.34620517 0.4195922 -0.83909744, + -0.30419698 0.42605495 -0.85202187, + -0.29420304 0.45779407 -0.83896911, + -0.25397891 0.46328682 -0.84903473, + -0.24440788 0.49469978 -0.83398861, + -0.20667295 0.49915689 -0.8415038, + -0.19792102 0.52960306 -0.82483214, + -0.16304494 0.5330618 -0.83021772, + -0.15535405 0.56232017 -0.8121953, + -0.12338498 0.56488192 -0.8158949, + -0.11686899 0.59311694 -0.7965889, + -0.087980144 0.59489328 -0.79897535, + -0.082755476 0.62220287 -0.7784698, + -0.0570076 0.62332898 -0.77987897, + -0.053233091 0.64929795 -0.7586689, + -0.030875919 0.64991033 -0.7593835, + -0.028604707 0.67453218 -0.73769116, + -0.0090597551 0.67478073 -0.73796266, + -0.0082906643 0.69850051 -0.71556145, + 0.0081577739 0.69850135 -0.71556234, + 0.0089133345 0.67507827 -0.73769236, + 0.02810709 0.67483777 -0.73743075, + 0.030397596 0.65004694 -0.75928587, + 0.052938871 0.64943564 -0.75857151, + 0.056701593 0.62350196 -0.77976286, + 0.082138494 0.62239695 -0.77837986, + 0.087323822 0.59530813 -0.79873818, + 0.11617298 0.59354496 -0.79637188, + 0.12269504 0.56531018 -0.81570232, + 0.15462892 0.56276363 -0.8120265, + 0.16244602 0.53304005 -0.83034915, + 0.19712709 0.52961522 -0.82501441, + 0.20592304 0.49905506 -0.84174812, + 0.24382094 0.49459288 -0.83422381, + 0.25331399 0.463447 -0.84914601, + 0.29360712 0.45795816 -0.83908832, + 0.30375889 0.42572784 -0.85234171, + 0.34584498 0.41926795 -0.83940786, + 0.3558909 0.38764092 -0.85033882, + 0.3993237 0.38029173 -0.83421743, + 0.40907392 0.3492099 -0.84303683, + 0.45344514 0.34108913 -0.82343531, + 0.4626818 0.31069785 -0.83029658, + 0.50744784 0.30199289 -0.80702972, + 0.51583189 0.27299893 -0.81202781, + 0.55980384 0.26405692 -0.78542572, + 0.56725502 0.236441 -0.78887099, + 0.61011696 0.22747497 -0.75895488, + 0.61647773 0.2016689 -0.76110762, + 0.65793508 0.19288403 -0.72795403, + 0.66325378 0.16877393 -0.72911578, + 0.70291418 0.16040304 -0.69295216, + 0.70718783 0.13823797 -0.69337982, + 0.74425119 0.13058802 -0.65500915, + 0.74756062 0.11042695 -0.65494972, + 0.78189713 0.10364702 -0.61473107, + 0.78435302 0.085529797 -0.61439002, + 0.81615919 0.079671621 -0.57230812, + 0.81790215 0.063477211 -0.57184505, + 0.8471393 0.058624323 -0.52812719, + 0.8487829 0.037570596 -0.52740496, + 0.87525898 0.034366801 -0.48243201, + 0.87608677 0.012750497 -0.48198488, + 0.8929559 0.0065858592 -0.45009595, + 0.89292312 0.006587211 -0.45016107, + 0.8929441 -0.00073833612 -0.45016706, + 0.89297789 -0.00072948093 -0.45009995, + 0.91402441 -1.6375307e-005 -0.40565917, + 0.91393667 -1.6532895e-005 -0.40585685, + 0.91397923 -1.9893505e-005 -0.40576109, + 0.91396397 0.0053644702 -0.40575999, + 0.91392177 0.0053663687 -0.40585491, + 0.91400987 0.0053374893 -0.40565693, + 0.89923978 0.011687997 -0.43729991, + 0.89856678 0.030610792 -0.43776789, + 0.87473339 0.033803314 -0.48342425, + 0.87283015 0.058938514 -0.48445213, + 0.8447119 0.09099789 -0.52742893, + 0.86896116 0.084139325 -0.48767513, + 0.87196487 0.058072291 -0.48611194, + 0.89656669 0.052537482 -0.43978184, + 0.89813572 0.03011819 -0.43868586, + 0.91950297 0.0269239 -0.39216, + 0.92003286 0.010522799 -0.39169994, + 0.93275911 0.0041978303 -0.36047602, + 0.93278027 0.004196771 -0.36042109, + 0.93278956 -0.0011098394 -0.36041981, + 0.93276823 -0.0011173103 -0.36047509, + 0.94931477 0.00031260791 -0.31432691, + 0.94935477 0.00031270392 -0.31420591, + 0.94932365 0.00031475889 -0.31429988, + 0.94931787 0.0032487495 -0.31430098, + 0.94934899 0.00324696 -0.31420699, + 0.94930887 0.0032585596 -0.31432799, + 0.93844336 0.0094034234 -0.34530511, + 0.93804097 0.023316801 -0.34573901, + 0.91916162 0.026503392 -0.39298785, + 0.91791111 0.046237104 -0.39408305, + 0.89585412 0.051779509 -0.44132105, + 0.89338058 0.07504686 -0.44298878, + 0.86774713 0.083015211 -0.49002406, + 0.86454487 0.10393398 -0.49169093, + 0.83602297 0.113477 -0.53683197, + 0.83284682 0.13024297 -0.5379619, + 0.80098897 0.140873 -0.58186901, + 0.796709 0.159942 -0.58281499, + 0.76198 0.17138401 -0.624511, + 0.75642312 0.19275703 -0.62503505, + 0.71895492 0.20483097 -0.66418993, + 0.71196425 0.22847608 -0.66400725, + 0.67173982 0.24102594 -0.70047981, + 0.66317892 0.26692998 -0.69924396, + 0.620628 0.279643 -0.732544, + 0.61046195 0.30763498 -0.72986096, + 0.56672496 0.32000998 -0.7592209, + 0.55498266 0.3499068 -0.75469154, + 0.51061285 0.36166289 -0.78004771, + 0.49745607 0.39309606 -0.77331311, + 0.45321307 0.40393206 -0.79463011, + 0.43898973 0.43635872 -0.78541654, + 0.39546791 0.44606587 -0.80288881, + 0.38090423 0.47830731 -0.79128647, + 0.33918691 0.48663789 -0.80506885, + 0.32445404 0.51883006 -0.79091412, + 0.28528693 0.52570885 -0.80139983, + 0.27086896 0.55735296 -0.78484887, + 0.23457193 0.56284386 -0.79257983, + 0.22093694 0.59349787 -0.77391684, + 0.18780905 0.59770709 -0.77940619, + 0.17522594 0.62733376 -0.75878072, + 0.14547402 0.63041407 -0.76250613, + 0.134247 0.658732 -0.74030399, + 0.108689 0.66081101 -0.74264097, + 0.098874614 0.68815404 -0.71879607, + 0.076811709 0.68949908 -0.72020209, + 0.068978988 0.71454084 -0.69618481, + 0.050563902 0.71533 -0.69695503, + 0.044480987 0.73895878 -0.67228079, + 0.029530188 0.73936874 -0.67265278, + 0.02525581 0.76138037 -0.64781332, + 0.023573488 0.75977665 -0.64975673, + 0.036310513 0.75948632 -0.64950925, + 0.042483401 0.73683 -0.67474198, + 0.058705732 0.7362234 -0.67418742, + 0.066765986 0.71191084 -0.69908881, + 0.086407207 0.71083504 -0.69803107, + 0.096338682 0.68479794 -0.72233695, + 0.11998004 0.68302822 -0.72047025, + 0.131762 0.65508097 -0.743981, + 0.15930198 0.65240294 -0.74094093, + 0.17258792 0.6230427 -0.76290965, + 0.20388804 0.61924809 -0.75826216, + 0.21832807 0.58882022 -0.77821827, + 0.25308397 0.58373296 -0.77149487, + 0.26834294 0.5524019 -0.78920484, + 0.30642101 0.54584903 -0.77984297, + 0.32210401 0.51385099 -0.79511398, + 0.36286217 0.50578421 -0.78263235, + 0.3786571 0.47322112 -0.79541218, + 0.42159379 0.46363279 -0.77929664, + 0.43687415 0.43129814 -0.78938133, + 0.48115513 0.4203251 -0.76929617, + 0.49557477 0.38842782 -0.77687162, + 0.53991389 0.3764219 -0.75286084, + 0.55317205 0.34530202 -0.75813413, + 0.5972811 0.33243909 -0.72989017, + 0.60879207 0.30332404 -0.73305309, + 0.651981 0.289906 -0.700625, + 0.66168392 0.26303896 -0.70212895, + 0.7026062 0.24963605 -0.66635317, + 0.71062237 0.22496811 -0.6666373, + 0.74893492 0.21188097 -0.62785596, + 0.7552861 0.18977603 -0.62731808, + 0.79083031 0.17722006 -0.58581626, + 0.79576784 0.15745096 -0.58477587, + 0.82840669 0.14562796 -0.54086483, + 0.83210111 0.12824202 -0.53959405, + 0.86016113 0.11793002 -0.49620107, + 0.85746348 0.13141993 -0.49747869, + 0.82759011 0.14337002 -0.54271507, + 0.82329285 0.16153999 -0.54414493, + 0.78985089 0.17454098 -0.58793795, + 0.78419185 0.19506496 -0.5890609, + 0.74777395 0.20871897 -0.63029397, + 0.74044508 0.23194203 -0.63082808, + 0.70127577 0.24601191 -0.66909677, + 0.69218707 0.27160302 -0.66866207, + 0.65048105 0.28583002 -0.70368707, + 0.639449 0.31389001 -0.70183903, + 0.59561908 0.32794803 -0.73327208, + 0.58268499 0.35809699 -0.72955102, + 0.5380348 0.37141588 -0.75668269, + 0.5234943 0.40294924 -0.75072348, + 0.47914094 0.41510695 -0.77337587, + 0.46339005 0.44741905 -0.76490915, + 0.41946092 0.45833489 -0.78356981, + 0.40288693 0.49096793 -0.77241987, + 0.36054087 0.50035185 -0.7871837, + 0.34363514 0.53284723 -0.77329737, + 0.30398285 0.54054976 -0.78447467, + 0.28708497 0.57276595 -0.76780289, + 0.25063905 0.57885009 -0.77595919, + 0.23441792 0.61004674 -0.75689572, + 0.20136903 0.61467808 -0.76264113, + 0.18609296 0.64487582 -0.7412858, + 0.15674701 0.64822805 -0.74513805, + 0.14285608 0.67706531 -0.72192436, + 0.117468 0.67934501 -0.724356, + 0.10532594 0.7064386 -0.69989359, + 0.084149748 0.7078706 -0.70131159, + 0.07424064 0.73238033 -0.67683631, + 0.056171317 0.73324716 -0.67763817, + 0.04798371 0.75656116 -0.65216017, + 0.033933494 0.75699681 -0.65253681, + 0.027574308 0.77906215 -0.62634015, + 0.019595698 0.7792089 -0.62645793, + 0.0026407097 0.79070085 -0.61219692, + 0.0073682088 0.7906819 -0.61218292, + 0.0023397203 0.82745314 -0.56153005, + -0.00021297595 0.82745582 -0.56153089, + -0.0017080903 0.85741419 -0.51462412, + 0.0017843002 0.85741413 -0.51462406, + 0.00029650202 0.82746309 -0.56152004, + -0.0022557296 0.82746083 -0.56151891, + -0.0072834357 0.79063952 -0.61223865, + -0.017150203 0.79054409 -0.61216503, + -0.023541609 0.7597003 -0.64984721, + -0.036285717 0.75941038 -0.64959931, + -0.042429812 0.73685217 -0.67472118, + -0.058674823 0.73624521 -0.67416626, + -0.06690108 0.71141773 -0.69957775, + -0.086878091 0.71031994 -0.69849694, + -0.096895352 0.68400371 -0.72301465, + -0.120659 0.68221599 -0.72112602, + -0.132416 0.65426803 -0.74457997, + -0.159877 0.65158898 -0.74153298, + -0.17314704 0.62223113 -0.7634452, + -0.20478095 0.6183849 -0.75872582, + -0.219161 0.58802801 -0.77858299, + -0.25399706 0.58291513 -0.77181315, + -0.2692059 0.5516358 -0.78944671, + -0.30711004 0.54510105 -0.7800951, + -0.32272089 0.51322085 -0.79527068, + -0.36368001 0.50510401 -0.78269202, + -0.37928092 0.47289687 -0.79530782, + -0.42235422 0.4632622 -0.77910537, + -0.43753287 0.4310869 -0.78913182, + -0.4815217 0.42017177 -0.7691505, + -0.49591005 0.38834307 -0.77670014, + -0.54032087 0.37630591 -0.75262684, + -0.55334181 0.34573287 -0.75781369, + -0.59741223 0.33285713 -0.72959226, + -0.60887223 0.30388212 -0.73275524, + -0.65202898 0.290445 -0.70035702, + -0.66175008 0.26354402 -0.70187706, + -0.70262992 0.25012696 -0.66614395, + -0.71063876 0.22549193 -0.66644275, + -0.74893606 0.21237902 -0.62768608, + -0.75532198 0.190162 -0.62715799, + -0.79083699 0.17759 -0.58569503, + -0.79580212 0.15771501 -0.58465809, + -0.82840914 0.14588101 -0.54079306, + -0.83217841 0.12814806 -0.53949726, + -0.86130017 0.11742203 -0.49434212, + -0.8640359 0.10196499 -0.49299595, + -0.8898176 0.092421852 -0.44685879, + -0.89096498 0.0958101 -0.443849, + -0.036809415 0.7760793 -0.62956023, + -0.045262087 0.75332081 -0.65609384, + -0.061259493 0.7526769 -0.65553397, + -0.071460389 0.72885484 -0.68092883, + -0.090591356 0.72771865 -0.67986673, + -0.10299101 0.70164007 -0.70504904, + -0.12632403 0.69974017 -0.7031402, + -0.14080603 0.6714462 -0.72755319, + -0.16821496 0.66853881 -0.72440284, + -0.18420106 0.63883722 -0.74696523, + -0.21550608 0.63468623 -0.74211222, + -0.23268503 0.60367906 -0.76251513, + -0.26786092 0.59803379 -0.75538468, + -0.28558797 0.56635594 -0.77309787, + -0.32422614 0.55904323 -0.76311737, + -0.34230304 0.52653104 -0.77819914, + -0.38359094 0.51751596 -0.76487589, + -0.40142307 0.48476306 -0.77708709, + -0.44500795 0.47398293 -0.75980788, + -0.46196878 0.44160178 -0.76913762, + -0.50631595 0.42937893 -0.74784893, + -0.5221709 0.39746892 -0.75455683, + -0.56703967 0.38388377 -0.72876561, + -0.58126128 0.35324419 -0.73304439, + -0.62560695 0.33866698 -0.70279497, + -0.63795805 0.30975202 -0.70502704, + -0.68051922 0.29473212 -0.67084026, + -0.69080502 0.26815999 -0.67147499, + -0.73092991 0.25310698 -0.63378096, + -0.73925996 0.22897796 -0.63329595, + -0.7765125 0.21424887 -0.59255862, + -0.78308189 0.19259797 -0.59134495, + -0.81744117 0.17838204 -0.5476951, + -0.82241273 0.15937795 -0.5461098, + -0.85309851 0.14617109 -0.50085628, + -0.85677713 0.12956601 -0.49914506, + -0.88387209 0.11751702 -0.45272505, + -0.88613522 0.10525303 -0.45131612, + -0.86066979 0.11563997 -0.49585789, + -0.85748959 0.13163593 -0.49737677, + -0.82759184 0.14361797 -0.54264688, + -0.8232767 0.16184793 -0.54407781, + -0.78984302 0.174869 -0.58785099, + -0.78412789 0.19556896 -0.58897895, + -0.74777943 0.20922913 -0.63011837, + -0.74046415 0.23240006 -0.63063717, + -0.70129722 0.24649809 -0.66889524, + -0.69219226 0.2721231 -0.66844523, + -0.65052909 0.28636304 -0.70342606, + -0.63954628 0.31429014 -0.70157135, + -0.59574991 0.32836097 -0.73298097, + -0.58297986 0.3581329 -0.72929782, + -0.53848588 0.3714219 -0.7563588, + -0.524059 0.40275601 -0.75043303, + -0.47952101 0.41497901 -0.77320898, + -0.46394011 0.44695812 -0.76484519, + -0.42017195 0.45784393 -0.78347588, + -0.40362385 0.49046981 -0.77235168, + -0.36142918 0.49983725 -0.78710335, + -0.34463492 0.53218585 -0.7733078, + -0.30474415 0.53995126 -0.78459138, + -0.28804183 0.57184964 -0.7681275, + -0.2515181 0.57796121 -0.77633733, + -0.23535097 0.60911691 -0.75735486, + -0.20223904 0.61377007 -0.76314211, + -0.18699294 0.64396977 -0.74184674, + -0.15730007 0.64737231 -0.74576533, + -0.14355098 0.6759578 -0.7228238, + -0.11796596 0.67826277 -0.72528875, + -0.10571904 0.70563626 -0.70064324, + -0.084412105 0.70708108 -0.70207608, + -0.0741833 0.73240399 -0.676817, + -0.056140207 0.73326904 -0.67761707, + -0.047988877 0.75648266 -0.65225071, + -0.033908408 0.75692016 -0.65262717, + -0.028344192 0.77629369 -0.62973374, + -0.0095994994 0.78855288 -0.61489195, + -0.0122636 0.78852999 -0.61487401, + -0.003659321 0.82609016 -0.56352609, + 0.0013834593 0.82609457 -0.56352973, + 0.0060598888 0.85692179 -0.5154109, + 0.0032286495 0.85693288 -0.51541793, + 0.002562579 0.84404969 -0.53625882, + -0.0025226793 0.84404981 -0.53625888, + -0.0031896494 0.8569209 -0.51543796, + -0.0059814737 0.85690951 -0.5154323, + -0.0012987696 0.82608783 -0.56353986, + 0.0037432015 0.82608229 -0.56353718, + 0.010304404 0.79778033 -0.60286027, + 0.018569704 0.79768521 -0.60278809, + 0.025035797 0.77645189 -0.62967896, + 0.0368197 0.776169 -0.62944901, + 0.045273084 0.75341773 -0.65598178, + 0.061215706 0.75277615 -0.65542406, + 0.071487166 0.72879064 -0.68099469, + 0.090646878 0.72765183 -0.67993081, + 0.10262398 0.70248282 -0.70426279, + 0.12582304 0.70059919 -0.70237416, + 0.14015996 0.6726408 -0.72657382, + 0.16744795 0.6697548 -0.7234568, + 0.183466 0.64005399 -0.746104, + 0.21462592 0.63593274 -0.74129975, + 0.23187409 0.60486221 -0.76182431, + 0.26671502 0.59928405 -0.75479913, + 0.28464797 0.56731296 -0.77274287, + 0.32321092 0.56003088 -0.76282382, + 0.341389 0.527403 -0.77801001, + 0.38282216 0.5183692 -0.76468331, + 0.40076092 0.48545989 -0.77699381, + 0.44419494 0.47472894 -0.7598179, + 0.46138281 0.44196486 -0.76928073, + 0.50574774 0.4297508 -0.74801964, + 0.52165097 0.39778295 -0.75475091, + 0.56664288 0.38417092 -0.72892284, + 0.58098906 0.35327303 -0.73324609, + 0.62539417 0.33868808 -0.7029742, + 0.63788801 0.309432 -0.70523101, + 0.68039757 0.29444984 -0.67108756, + 0.69078624 0.26760608 -0.67171526, + 0.73086792 0.25260198 -0.63405395, + 0.73921198 0.22843499 -0.63354802, + 0.77660787 0.21368296 -0.59263796, + 0.78314734 0.19210009 -0.59142029, + 0.81747115 0.17793101 -0.54779708, + 0.82241368 0.15902694 -0.54621083, + 0.85168719 0.14649203 -0.50315911, + 0.84816313 0.16081302 -0.50473607, + 0.81656289 0.17523898 -0.55001491, + 0.81085688 0.19510096 -0.55176693, + 0.77551913 0.21046104 -0.59521109, + 0.76801389 0.23310196 -0.59650493, + 0.72962719 0.24890307 -0.63693917, + 0.72009301 0.27424499 -0.63738197, + 0.67897284 0.29016694 -0.67438781, + 0.66720879 0.31813988 -0.67351276, + 0.62378603 0.33382502 -0.70671904, + 0.60988694 0.36385396 -0.70402294, + 0.56487894 0.37885994 -0.73305994, + 0.5490272 0.41045615 -0.72807622, + 0.5038721 0.4241941 -0.75244421, + 0.48642612 0.45675012 -0.74482816, + 0.44215506 0.46888706 -0.76462013, + 0.4234359 0.50208086 -0.75406682, + 0.38065809 0.51249415 -0.7697072, + 0.36127496 0.54564494 -0.75614285, + 0.32090482 0.55421865 -0.7680245, + 0.30139402 0.58693308 -0.75144613, + 0.26428092 0.59367079 -0.76007271, + 0.24514505 0.62558818 -0.74063718, + 0.21206497 0.63060194 -0.74657196, + 0.19389801 0.661264 -0.72466099, + 0.164804 0.66483903 -0.72858, + 0.14819999 0.69372493 -0.70482796, + 0.12311703 0.69613415 -0.70727617, + 0.108903 0.722206 -0.68305099, + 0.087953821 0.72371221 -0.68447417, + 0.07565327 0.74811476 -0.65924275, + 0.058289476 0.74898964 -0.66001272, + 0.047761213 0.77222121 -0.63355619, + 0.033755809 0.77266318 -0.63391817, + 0.025127104 0.79461914 -0.60658807, + 0.015682904 0.79477221 -0.60670513, + 0.006196551 0.82392913 -0.56665903, + -0.0016532602 0.82394314 -0.56667006, + -0.0096833883 0.85552084 -0.5176779, + -0.009909384 0.85551929 -0.51767617, + -0.0080195889 0.84351486 -0.53704596, + -0.0040287804 0.84353513 -0.53705907, + -0.0026821997 0.81647187 -0.57737893, + 0.0027894115 0.8164714 -0.57737929, + 0.0041274694 0.84351486 -0.53708994, + 0.008075797 0.84349471 -0.53707683, + 0.0099695539 0.8555373 -0.51764518, + 0.0097634811 0.85553914 -0.51764607, + 0.0017372805 0.82395118 -0.56665814, + -0.0060924585 0.82393682 -0.5666489, + -0.015600803 0.79468918 -0.60681611, + -0.025358504 0.79453009 -0.60669506, + -0.03390421 0.77275431 -0.63379925, + -0.047671381 0.77231967 -0.63344276, + -0.058304925 0.74885136 -0.66016829, + -0.075436696 0.74799001 -0.65940899, + -0.087752931 0.72356623 -0.68465424, + -0.108948 0.722045 -0.68321401, + -0.12356895 0.69519174 -0.70812374, + -0.14879102 0.69276303 -0.70564908, + -0.16554201 0.66356099 -0.729577, + -0.194838 0.659949 -0.72560698, + -0.21293907 0.62933326 -0.74739325, + -0.24635091 0.62425476 -0.74136174, + -0.26540902 0.59237808 -0.76068813, + -0.30241284 0.58564472 -0.75204164, + -0.3218351 0.55301315 -0.7685042, + -0.36244583 0.54437375 -0.75649863, + -0.38147295 0.51175892 -0.76979285, + -0.42427507 0.50132507 -0.75409812, + -0.44296211 0.46812612 -0.76461917, + -0.48724219 0.45597416 -0.74477023, + -0.50444287 0.42382491 -0.7522698, + -0.54957086 0.41008192 -0.72787684, + -0.56530988 0.37867591 -0.73282284, + -0.61026973 0.36367083 -0.70378566, + -0.62403405 0.33391201 -0.70645905, + -0.66741705 0.31822303 -0.67326707, + -0.6790942 0.29044706 -0.67414516, + -0.72011399 0.27454299 -0.63722998, + -0.72963601 0.24925099 -0.63679302, + -0.76799279 0.23343994 -0.5963999, + -0.77542889 0.21103597 -0.59512496, + -0.81082034 0.1956161 -0.55163825, + -0.81654173 0.17571694 -0.5498938, + -0.84809691 0.16127498 -0.50469995, + -0.85234886 0.14392598 -0.50277895, + -0.88025826 0.13058503 -0.45617211, + -0.88329309 0.11574002 -0.45431006, + -0.90771312 0.10358602 -0.40660405, + -0.90850031 0.10618503 -0.40416816, + -0.92816633 0.09456864 -0.35995013, + -0.93118298 0.074248001 -0.356911, + -0.94953251 0.063884571 -0.30709386, + -0.95117778 0.047630988 -0.30494595, + -0.96579379 0.040017787 -0.25620493, + -0.96657836 0.02761481 -0.2548801, + -0.97806013 0.022439202 -0.20711103, + -0.97837454 0.013227694 -0.20641789, + -0.98718053 0.010207196 -0.15928093, + -0.98725152 0.0052097277 -0.15908292, + -0.99279678 0.0010637097 -0.11980597, + -0.9927544 0.0010717295 -0.12015592, + -0.99277222 0.0010787002 -0.12000903, + -0.99277252 0.00070021168 -0.12000894, + -0.99275476 0.00070009485 -0.12015597, + -0.99279714 0.00070818805 -0.11980601, + -0.98568887 -0.0017050197 -0.16856599, + -0.98379266 -0.0034828188 -0.17927594, + -0.98569661 -0.0050809183 -0.16845293, + -0.97624213 0.00046378205 -0.21668203, + -0.97623736 0.0029668813 -0.21668407, + -0.97627574 0.0029628193 -0.21651095, + -0.97628033 0.00046327917 -0.21651007, + -0.97623575 0.00046311889 -0.21671095, + -0.96444523 -0.0012190603 -0.26428005, + -0.96443689 0.0040763696 -0.26428196, + -0.96440452 0.0040791882 -0.26439989, + -0.96439701 -0.0060791401 -0.26438901, + -0.95032448 0.00015811507 -0.31126115, + -0.95031023 0.0051962612 -0.31126106, + -0.95032865 0.0051948782 -0.31120488, + -0.95034277 0.00015689195 -0.31120494, + -0.95028222 0.00015674304 -0.31139007, + -0.93392015 -0.00080536009 -0.35748103, + -0.93389821 -0.00081317715 -0.3575381, + -0.93387765 0.0064352378 -0.35753489, + -0.92002302 0.01231 -0.391671, + -0.9195196 0.027400287 -0.39208782, + -0.89816588 0.030649897 -0.43858695, + -0.89666909 0.052074607 -0.43962806, + -0.87519878 0.056904685 -0.48040488, + -0.0073565361 0.75284064 -0.6581617, + -0.0058045494 0.75284791 -0.65816891, + -0.0069712289 0.72080392 -0.69310397, + -0.021966701 0.72064704 -0.69295406, + -0.024394806 0.69719017 -0.7164712, + -0.042669702 0.69676208 -0.71603209, + -0.046733417 0.67186123 -0.73920125, + -0.068107694 0.67103493 -0.73829097, + -0.073768817 0.64481318 -0.76077217, + -0.099004686 0.64339793 -0.75910288, + -0.10615095 0.61600971 -0.78055364, + -0.13432795 0.61389476 -0.77787471, + -0.14282493 0.5854457 -0.79803163, + -0.17442004 0.58244312 -0.79393816, + -0.18417694 0.55270785 -0.8127687, + -0.21902393 0.54867381 -0.80683672, + -0.22966693 0.51825088 -0.8238138, + -0.26761416 0.51306331 -0.81556648, + -0.27902192 0.48168981 -0.83073568, + -0.3191759 0.47537488 -0.81984484, + -0.33093387 0.44355285 -0.83291268, + -0.37286893 0.43613991 -0.81899381, + -0.38468406 0.40403706 -0.82992309, + -0.42835507 0.39552906 -0.81244612, + -0.4395428 0.36440983 -0.8209796, + -0.48408794 0.35499597 -0.79977286, + -0.49459311 0.3245711 -0.80624521, + -0.53883481 0.31459489 -0.7814647, + -0.54826808 0.28564304 -0.78600913, + -0.59164798 0.275361 -0.75771302, + -0.59991604 0.24798903 -0.7606591, + -0.64223319 0.23758806 -0.72875816, + -0.64927328 0.21198511 -0.73041534, + -0.69000864 0.20174091 -0.69511765, + -0.69582278 0.17803794 -0.69579679, + -0.73395795 0.16836599 -0.65799594, + -0.73861718 0.14664303 -0.65798217, + -0.77402014 0.13773201 -0.61799908, + -0.77762514 0.11804602 -0.61754704, + -0.8103748 0.11000797 -0.57549191, + -0.81301415 0.092656925 -0.57482409, + -0.8430714 0.085584536 -0.53094822, + -0.84491891 0.070485793 -0.53022993, + -0.87133271 0.064660981 -0.48641381, + -0.86990315 0.077094704 -0.48716006, + -0.84251529 0.084198929 -0.53205121, + -0.84023857 0.10001095 -0.53291374, + -0.8096543 0.10825404 -0.57683718, + -0.80647564 0.12636694 -0.57760572, + -0.77311116 0.13555902 -0.61961514, + -0.76889116 0.15582404 -0.62010109, + -0.73287737 0.16581208 -0.65984631, + -0.72750467 0.18811391 -0.65981072, + -0.68874174 0.19878092 -0.69722378, + -0.6821 0.223125 -0.69638699, + -0.64078718 0.23424906 -0.73110819, + -0.63279682 0.26057595 -0.72915584, + -0.59003991 0.27170095 -0.76028383, + -0.58075482 0.29974389 -0.75688672, + -0.53704292 0.31059796 -0.78429186, + -0.5264678 0.34035489 -0.77909571, + -0.48211995 0.35072798 -0.80283886, + -0.470514 0.381666 -0.79558003, + -0.426305 0.39126301 -0.815584, + -0.41384494 0.42331395 -0.8059389, + -0.3707138 0.43186975 -0.82222855, + -0.35807988 0.46373183 -0.8103897, + -0.31686884 0.47107175 -0.82321656, + -0.30427796 0.50279194 -0.80908287, + -0.26522696 0.50891596 -0.8189379, + -0.25309113 0.54008126 -0.80265635, + -0.21672797 0.54498792 -0.80994886, + -0.20539297 0.57534492 -0.79170185, + -0.17215501 0.57910204 -0.79687113, + -0.1620421 0.60805035 -0.7771855, + -0.13203593 0.61079967 -0.78069854, + -0.123097 0.63893598 -0.75934702, + -0.096896984 0.64080292 -0.76156586, + -0.08942537 0.66775876 -0.73898679, + -0.066265635 0.66897142 -0.74032843, + -0.060448691 0.69436991 -0.71707493, + -0.040991973 0.69505757 -0.71778458, + -0.036804795 0.71922195 -0.69380492, + -0.020780908 0.71955425 -0.69412524, + -0.017133703 0.75240219 -0.65848118, + -0.0049556405 0.7525031 -0.65857005, + -0.0033565483 0.79215962 -0.61030471, + 0.0034024001 0.79215997 -0.610304, + 0.0046035093 0.76276189 -0.64666295, + 0.014861302 0.76268613 -0.64659804, + 0.017365294 0.74114275 -0.67112279, + 0.031097285 0.74089664 -0.67089868, + 0.035319891 0.71789885 -0.69525081, + 0.052435093 0.71735793 -0.69472891, + 0.058339715 0.69305819 -0.71851718, + 0.078950696 0.69207293 -0.71749693, + 0.086772628 0.66553521 -0.74130523, + 0.11102601 0.66392404 -0.73951209, + 0.12032098 0.63640392 -0.7619139, + 0.14791697 0.63400984 -0.75904679, + 0.15866196 0.60517991 -0.78011781, + 0.19030297 0.60174292 -0.77568686, + 0.20224197 0.57179195 -0.79507989, + 0.23703803 0.56721705 -0.78871912, + 0.24996603 0.53619206 -0.80623513, + 0.28770208 0.5303582 -0.7974633, + 0.30124104 0.49855906 -0.81283009, + 0.34149602 0.49141407 -0.80118209, + 0.35514897 0.45941094 -0.81413186, + 0.39767492 0.45091689 -0.79907984, + 0.41122708 0.41863108 -0.80971617, + 0.45536 0.40888199 -0.79086202, + 0.46830705 0.37697905 -0.7991091, + 0.51257306 0.36634603 -0.77656913, + 0.5244118 0.33568788 -0.78249973, + 0.56849772 0.32434186 -0.75605065, + 0.57896501 0.29536 -0.75997502, + 0.62221795 0.28358296 -0.72967494, + 0.63126725 0.25637609 -0.73196524, + 0.67311406 0.24446604 -0.69796407, + 0.68064421 0.21947907 -0.69896525, + 0.72015584 0.20785396 -0.66194582, + 0.72627193 0.18503399 -0.66203594, + 0.76300919 0.17399204 -0.6225301, + 0.76781601 0.15344299 -0.622024, + 0.80186033 0.14310607 -0.58012128, + 0.80552173 0.12478796 -0.57927781, + 0.83673012 0.11532202 -0.53533506, + 0.83914798 0.100885 -0.53446501, + 0.80944633 0.10891605 -0.57700431, + 0.80630612 0.12674302 -0.57776004, + 0.77294517 0.13595203 -0.61973614, + 0.76879734 0.15585208 -0.62021029, + 0.73277175 0.16583894 -0.65995675, + 0.72745466 0.18791391 -0.65992272, + 0.68860304 0.19859003 -0.69741505, + 0.68200576 0.22276393 -0.69659477, + 0.64072526 0.23385909 -0.73128724, + 0.63279408 0.26002204 -0.72935605, + 0.58995688 0.27114195 -0.76054782, + 0.58063787 0.29929793 -0.7571528, + 0.536865 0.31014499 -0.78459299, + 0.52626806 0.33996904 -0.7793991, + 0.48195699 0.350315 -0.80311698, + 0.47029695 0.38142094 -0.7958259, + 0.4258242 0.39105818 -0.81593341, + 0.41333693 0.42314395 -0.8062889, + 0.37029117 0.43166521 -0.8225264, + 0.35744202 0.46405205 -0.8104881, + 0.31635019 0.47135928 -0.82325149, + 0.30370197 0.50321895 -0.80903387, + 0.26450488 0.50935477 -0.81889856, + 0.25238696 0.54044092 -0.80263591, + 0.21586592 0.54535383 -0.80993271, + 0.20457298 0.57554895 -0.79176587, + 0.17135501 0.57928705 -0.79690909, + 0.16105694 0.60870874 -0.77687472, + 0.13155694 0.61139971 -0.78030962, + 0.122628 0.63950002 -0.75894803, + 0.096306957 0.64136738 -0.7611655, + 0.08888571 0.66810703 -0.73873705, + 0.066060424 0.66929722 -0.74005222, + 0.060158279 0.69506174 -0.71642876, + 0.041076373 0.69573557 -0.71712255, + 0.036960002 0.71953106 -0.69347608, + 0.020771703 0.71986705 -0.69380105, + 0.018336404 0.7420162 -0.67013121, + 0.0062289322 0.74212623 -0.67023122, + 0.0069962093 0.72084796 -0.69305795, + 0.021670707 0.72069526 -0.69291323, + 0.024094896 0.69735694 -0.71631896, + 0.042259105 0.69693607 -0.71588707, + 0.046315577 0.67211968 -0.73899263, + 0.067842282 0.67129183 -0.73808181, + 0.073449798 0.64530599 -0.76038498, + 0.098376215 0.64391506 -0.75874615, + 0.10552198 0.61656195 -0.78020287, + 0.13381502 0.61444706 -0.77752709, + 0.14232701 0.58594906 -0.79775113, + 0.17384695 0.58296084 -0.79368371, + 0.18355501 0.55337697 -0.81245399, + 0.21835998 0.54935694 -0.80655187, + 0.22916791 0.51846385 -0.82381868, + 0.26679295 0.5133329 -0.81566584, + 0.27826893 0.48182487 -0.83090985, + 0.318573 0.475503 -0.820005, + 0.33039698 0.44351894 -0.83314389, + 0.37252283 0.43608478 -0.81918061, + 0.38434783 0.40394083 -0.83012557, + 0.427937 0.39546201 -0.81269902, + 0.43928799 0.36388901 -0.821347, + 0.48388094 0.35448697 -0.80012387, + 0.49437013 0.32410309 -0.80657017, + 0.53865498 0.31413901 -0.78177202, + 0.54811388 0.28509694 -0.78631485, + 0.59157312 0.27481905 -0.75796819, + 0.59980792 0.24754797 -0.76088786, + 0.64215583 0.23716295 -0.72896481, + 0.64915198 0.21172 -0.7306, + 0.68985015 0.20150304 -0.69534415, + 0.69560397 0.17808698 -0.69600296, + 0.73385292 0.16838999 -0.65810692, + 0.73843724 0.14703706 -0.65809625, + 0.7738483 0.13810804 -0.61813027, + 0.77739668 0.11877996 -0.61769378, + 0.81017911 0.11069302 -0.57563609, + 0.81279713 0.093558304 -0.57498509, + 0.84288961 0.086417757 -0.53110176, + 0.84460831 0.072514124 -0.53045118, + 0.81559682 0.078370079 -0.57328886, + 0.81342679 0.095048778 -0.5738489, + 0.78117788 0.10201699 -0.61591697, + 0.77820712 0.12066201 -0.61630708, + 0.74332702 0.128525 -0.65646499, + 0.73940325 0.14925106 -0.65651125, + 0.70178896 0.15792398 -0.69465995, + 0.69678593 0.18076499 -0.69412792, + 0.65664119 0.19007005 -0.72986019, + 0.65052497 0.214792 -0.72847903, + 0.60867709 0.22438803 -0.7610271, + 0.60138494 0.25102898 -0.75849891, + 0.55820608 0.26068804 -0.7876851, + 0.54984009 0.28883505 -0.78374118, + 0.505665 0.29833099 -0.80950701, + 0.49624819 0.32806513 -0.8038103, + 0.45147413 0.33717209 -0.82612717, + 0.44127995 0.36793897 -0.81846988, + 0.39722207 0.37628505 -0.83703309, + 0.38643205 0.40798905 -0.82717311, + 0.34371096 0.41540194 -0.84220189, + 0.33264697 0.44765294 -0.83003187, + 0.29134291 0.45409384 -0.84197271, + 0.28058296 0.48581094 -0.82780486, + 0.24165194 0.49114287 -0.83688885, + 0.23150498 0.52219695 -0.82080185, + 0.1950011 0.52647525 -0.82752544, + 0.18573509 0.55659425 -0.80975634, + 0.15247796 0.55982786 -0.81445885, + 0.14436898 0.58872086 -0.79533982, + 0.11419597 0.59106189 -0.79850185, + 0.10736198 0.61885089 -0.77813685, + 0.080432981 0.6204319 -0.78012484, + 0.075011007 0.64707905 -0.75872409, + 0.051617119 0.64804226 -0.7598533, + 0.047688693 0.67354095 -0.73760992, + 0.027296597 0.67405695 -0.73817492, + 0.024935504 0.69815004 -0.71551704, + 0.0079813246 0.69834441 -0.71571743, + 0.0072069126 0.72102922 -0.69286722, + -0.0072324458 0.72102958 -0.69286656, + -0.0080108009 0.69825208 -0.71580708, + -0.025308011 0.69805038 -0.71560138, + -0.027692292 0.67365181 -0.7385298, + -0.047963288 0.67313582 -0.73796183, + -0.051862594 0.64785296 -0.7599979, + -0.075579397 0.64687097 -0.75884497, + -0.081005365 0.62018669 -0.78026062, + -0.10821505 0.6185773 -0.77823633, + -0.11502997 0.5908069 -0.79857081, + -0.14504799 0.58846593 -0.79540485, + -0.15320297 0.55938387 -0.81462783, + -0.18649904 0.55613512 -0.80989617, + -0.19567603 0.52628505 -0.82748711, + -0.23202007 0.52201509 -0.82077217, + -0.24213491 0.49108082 -0.83678567, + -0.28134999 0.48569599 -0.82761198, + -0.29204696 0.45411593 -0.84171689, + -0.33318388 0.44768584 -0.8297987, + -0.34411687 0.41580984 -0.84183472, + -0.38691205 0.40836507 -0.82676309, + -0.39765993 0.37676293 -0.8366099, + -0.44152206 0.36843503 -0.81811613, + -0.45174295 0.33759397 -0.82580787, + -0.49644807 0.32848102 -0.8035171, + -0.50583702 0.29884201 -0.80921102, + -0.5499711 0.28933406 -0.78346521, + -0.5583899 0.26101094 -0.78744781, + -0.60144424 0.2513631 -0.75834131, + -0.60877705 0.22459503 -0.76088613, + -0.6506142 0.21498905 -0.72834116, + -0.65679777 0.18999892 -0.72973776, + -0.69698799 0.18068001 -0.69394702, + -0.70203274 0.15760595 -0.69448578, + -0.73962098 0.148947 -0.656335, + -0.74361902 0.127753 -0.65628499, + -0.77843899 0.119941 -0.61615503, + -0.78143013 0.10108201 -0.61575109, + -0.81365317 0.094174422 -0.57367212, + -0.81579489 0.077626795 -0.57310796, + -0.84541351 0.071690343 -0.52927929, + -0.84687287 0.057285294 -0.52870095, + -0.87345088 0.052450594 -0.48407894, + -0.8747741 0.034391705 -0.48330906, + -0.89859813 0.031143704 -0.43766606, + -0.89923722 0.013664103 -0.43724808, + -0.91501403 0.0079331798 -0.40334401, + -0.9150449 -0.00022082197 -0.40335193, + -0.91526777 -0.00022042094 -0.40284592, + -0.91523713 0.0078566512 -0.40283906, + -0.91521823 0.007857752 -0.4028821, + -0.91524887 -0.00021890397 -0.40288895, + -0.92631376 -0.0042558792 -0.37672892, + -0.66015768 -0.0030902587 0.75112063, + -0.65191585 -0.0043570292 0.75827885, + -0.65186495 -0.012810598 0.75822687, + -0.68804681 -0.012014598 0.7255668, + -0.68810201 0.00119683 0.725613, + -0.68819594 0.0011967599 0.72552395, + -0.72253263 -0.0004146038 0.69133663, + -0.72287381 -0.00043397889 0.69097984, + -0.99966425 -0.0029878807 0.025741106, + -0.73387474 -0.0033320589 0.67927676, + -0.75590116 0.00091023423 0.6546852, + -0.75584209 -0.012002301 0.65464407, + -0.7558257 -0.012002695 0.65466279, + -0.75588489 0.00090743089 0.65470392, + -0.75596619 0.00090735621 0.65461016, + -0.75592548 -0.0098718852 0.65458339, + -0.7869789 -0.011807499 0.61686695, + -0.78703833 -5.2319119e-006 0.61690426, + -0.78709573 -9.0400763e-006 0.61683077, + -0.78703612 -0.011806302 0.61679405, + -0.79200703 -0.0092461202 0.61044198, + -0.79123199 -0.030778799 0.61074102, + -0.82113332 -0.028726311 0.57001317, + -0.82234102 -0.00853715 0.56893098, + -0.82162344 -0.029026613 0.56929129, + -0.84947711 -0.026867203 0.52694106, + -0.86902684 9.1977781e-005 0.49476489, + -0.86905813 9.9242017e-005 0.49471006, + -0.86900258 -0.010884695 0.49468777, + -0.86897182 -0.010885597 0.49474189, + -0.85055882 -0.007603528 0.5258249, + -0.84990382 -0.027151695 0.52623791, + -0.87527227 -0.02492011 0.48298818, + -0.87417167 -0.042028487 0.48379481, + -0.89707178 -0.038243592 0.44022688, + -0.89556015 -0.054872908 0.44154406, + -0.91630721 -0.04938931 0.3974191, + -0.91448557 -0.065486774 0.39928383, + -0.93327039 -0.058131725 0.35443917, + -0.93130022 -0.073275812 0.3568061, + -0.94803977 -0.064001784 0.31164795, + -0.94604313 -0.07811711 0.31448403, + -0.96090311 -0.066749305 0.26871902, + -0.95898664 -0.079855368 0.27196991, + -0.97207701 -0.066110298 0.22515699, + -0.97035313 -0.078110211 0.22872204, + -0.98171949 -0.061512228 0.1801201, + -0.98033035 -0.072000623 0.18376206, + -0.98967248 -0.052294627 0.13346806, + -0.98870754 -0.060934972 0.13690995, + -0.99577624 -0.037333108 0.083880723, + -0.99529076 -0.043480787 0.086635478, + -0.99945927 -0.014749303 0.029387908, + -0.99938166 -0.017258994 0.030631788, + -0.99934089 0.017818999 -0.031625897, + -0.99930286 0.018888798 -0.032202195, + -0.99306524 0.059482016 -0.10140702, + -0.99344426 0.056236014 -0.09952902, + -0.97980112 0.098373018 -0.17410502, + -0.98063737 0.094337739 -0.17161205, + -0.95710546 0.13957606 -0.25390512, + -0.95818621 0.13616003 -0.25167406, + -0.92055076 0.18587495 -0.3435649, + -0.92412764 0.17790894 -0.33813688, + -0.88068324 0.22057106 -0.41922009, + -0.88343209 0.21568303 -0.41596705, + -0.83056718 0.25635505 -0.49440911, + -0.83289117 0.25294906 -0.49224913, + -0.77124888 0.29092798 -0.56615895, + -0.77269191 0.28913498 -0.56510895, + -0.70376498 0.323594 -0.63245702, + -0.70383066 0.32352185 -0.63242072, + -0.63041598 0.353531 -0.69107997, + -0.62868196 0.35519698 -0.69180495, + -0.553325 0.38045701 -0.74100202, + -0.55006909 0.38330808 -0.74195617, + -0.47521076 0.40384883 -0.78171664, + -0.47132194 0.40702394 -0.78242385, + -0.39950305 0.42307106 -0.81327009, + -0.38850677 0.43159974 -0.81411552, + -0.32248002 0.44337007 -0.83631915, + -0.33384201 0.43468899 -0.83641797, + -0.272212 0.44373101 -0.85381699, + -0.29000309 0.42981315 -0.85507828, + -0.23159306 0.4369041 -0.86918318, + -0.24185807 0.42856508 -0.87053818, + -0.18744999 0.43384793 -0.88127089, + -0.19270504 0.42938006 -0.88232511, + -0.14333104 0.4330641 -0.88989425, + -0.14451003 0.43200508 -0.89021826, + -0.10057504 0.43437314 -0.8951003, + -0.099189401 0.43570599 -0.89460701, + -0.061137464 0.43704674 -0.89735848, + -0.058187384 0.44012389 -0.89604974, + -0.026298495 0.44071889 -0.89725977, + -0.023164293 0.44432184 -0.89556772, + 0.0025258902 0.44444007 -0.89580512, + 0.0048672808 0.44745311 -0.89429426, + 0.024622999 0.44732201 -0.89403403, + 0.025622409 0.44878516 -0.89327228, + 0.039910905 0.44857407 -0.89285409, + 0.03946761 0.44782412 -0.89325023, + 0.048685506 0.44764104 -0.89288712, + 0.046722285 0.44371584 -0.89494872, + 0.051712811 0.44360712 -0.89472824, + 0.048275724 0.43531621 -0.89898241, + 0.049818911 0.43528309 -0.89891422, + 0.046228684 0.42456886 -0.90421468, + 0.037233982 0.42472878 -0.90455461, + 0.043164399 0.44667801 -0.89365298, + 0.044031605 0.44666106 -0.89361912, + 0.047824591 0.45760995 -0.8878659, + 0.045642484 0.45765686 -0.88795668, + 0.048602622 0.46457621 -0.88419843, + 0.042681098 0.46470195 -0.88443786, + 0.04469841 0.46862212 -0.88226724, + 0.034458824 0.46881226 -0.88262552, + 0.035378806 0.47033012 -0.88178122, + 0.020286698 0.47052795 -0.8821519, + 0.020082893 0.47023681 -0.8823117, + -0.00019975402 0.47033107 -0.8824901, + -0.0012521701 0.46900606 -0.88319415, + -0.027019609 0.46883518 -0.88287228, + -0.028220214 0.4674812 -0.88355243, + -0.059616607 0.46683607 -0.88233215, + -0.059969485 0.46647388 -0.88249975, + -0.096813284 0.46511993 -0.87993789, + -0.095482185 0.46637493 -0.87941891, + -0.13750997 0.46406487 -0.87506276, + -0.13309099 0.46794993 -0.87367588, + -0.17986399 0.46444994 -0.8671419, + -0.17136702 0.47148806 -0.86506212, + -0.22260703 0.46655905 -0.85601914, + -0.20752203 0.47841606 -0.8532601, + -0.26219207 0.47195411 -0.84173316, + -0.25302693 0.47888488 -0.84062284, + -0.31219798 0.47025195 -0.82546687, + -0.323006 0.462102 -0.82591099, + -0.38928792 0.44975787 -0.8038488, + -0.39344394 0.44652995 -0.80362487, + -0.46514487 0.42996091 -0.77380484, + -0.46948701 0.42642099 -0.77314103, + -0.54425788 0.4051609 -0.73459381, + -0.54720271 0.40258375 -0.73382258, + -0.62282568 0.37630281 -0.68591869, + -0.62396222 0.37521014 -0.68548423, + -0.69791198 0.343871 -0.62822902, + -0.69726682 0.34456691 -0.62856382, + -0.76711512 0.30837002 -0.56253207, + -0.7650587 0.31092089 -0.56392682, + -0.82793415 0.27078104 -0.49112406, + -0.82485032 0.27528408 -0.49380219, + -0.87921202 0.231987 -0.41613501, + -0.87470913 0.23991403 -0.42110005, + -0.92599088 0.18689598 -0.32804096, + -0.92529839 0.18853909 -0.32905316, + -0.95982635 0.13949804 -0.24346209, + -0.95866847 0.14337307 -0.24576212, + -0.98093677 0.097921677 -0.16785195, + -0.98007113 0.10226502 -0.17030102, + -0.99339062 0.059091277 -0.098403566, + -0.99379897 0.055371501 -0.096423797, + -0.99936664 0.017720794 -0.030859089, + -0.99944866 0.015108595 -0.029564388, + -0.99947786 -0.014703898 0.028772496, + -0.99953353 -0.012598295 0.027818987, + -0.99590278 -0.037305593 0.08237648, + -0.99626613 -0.031958103 0.080203705, + -0.98994088 -0.052370593 0.13143198, + -0.99068153 -0.044654977 0.12866995, + -0.98212337 -0.061717421 0.17783307, + -0.98320687 -0.052166391 0.17487998, + -0.97260952 -0.066444568 0.2227459, + -0.97394812 -0.055459909 0.21988504, + -0.96152747 -0.067183733 0.26636711, + -0.96302027 -0.054970216 0.26376206, + -0.94871676 -0.064497888 0.30947796, + -0.95026463 -0.051099982 0.30722287, + -0.93394965 -0.058641177 0.35256088, + -0.9354319 -0.044181697 0.35073498, + -0.91694415 -0.049869508 0.39588705, + -0.91821611 -0.034711402 0.39455605, + -0.89759344 -0.038632717 0.43912822, + -0.89854378 -0.022901794 0.43828589, + -0.87565625 -0.025200406 0.48227713, + -0.87624198 -0.00674965 0.48182401, + -0.89213371 -0.010314397 0.45165384, + -0.8921839 0.00061240897 0.45167193, + -0.89226079 0.0006122858 0.45151988, + -0.89220989 -0.010327199 0.45150295, + -0.89220124 -0.010327603 0.45152012, + -0.89225173 0.00061301177 0.45153785, + -0.90569532 -0.0035861114 0.42391413, + -0.85730779 -0.0035662791 0.51479191, + -0.84373617 0.00033978908 0.53675812, + -0.84367782 -0.011354798 0.53672987, + -0.8436929 -0.011354399 0.53670591, + -0.81645221 -0.0076743118 0.57736212, + -0.81647891 0.00053884793 0.57737494, + -0.81638485 0.00053895294 0.57750791, + -0.81632572 -0.011620896 0.57747483, + -0.81635112 -0.011620201 0.57743907, + -0.81641018 0.00054393912 0.57747209, + -0.79983413 -0.0034821904 0.60021108, + -0.9917171 -0.0030721605 0.12840502, + -0.97325909 -0.0029726205 0.22969103, + -0.94448388 -0.0027979198 0.32854596, + -0.94883925 -0.0010122502 0.31575808, + -0.94880462 -0.008398097 0.31575188, + -0.94877625 -0.0083997715 0.31583709, + -0.93853891 -0.0044393195 0.34514496, + -0.93818766 -0.018801592 0.34561589, + -0.95392764 -0.016297894 0.2995939, + -0.95342809 -0.027523104 0.30036202, + -0.96680588 -0.023315698 0.25444597, + -0.96621102 -0.033578198 0.25555599, + -0.9774155 -0.027530087 0.2095259, + -0.97682035 -0.036662616 0.21089807, + -0.98599422 -0.028564608 0.16431504, + -0.98549837 -0.036156513 0.16578805, + -0.99256015 -0.025943603 0.11895902, + -0.99222052 -0.031816684 0.12035794, + -0.9971621 -0.019240601 0.072784111, + -0.99699867 -0.023126392 0.073883772, + -0.9996649 -0.0077323392 0.024703296, + -0.99964088 -0.0091833789 0.025176996, + -0.99962854 0.0093393056 -0.025604486, + -0.99959576 0.010998297 -0.026215794, + -0.99613166 0.03399539 -0.08103177, + -0.99571741 0.039860677 -0.083414048, + -0.98746026 0.068067513 -0.14244004, + -0.985816 0.079868302 -0.147607, + -0.97053289 0.11467499 -0.21193297, + -0.96579653 0.13511094 -0.2213189, + -0.93992114 0.17788501 -0.29138502, + -0.93456489 0.19339597 -0.29864097, + -0.8960824 0.24128112 -0.37258518, + -0.89651078 0.24035494 -0.37215292, + -0.8447302 0.29036105 -0.44957912, + -0.84215879 0.29471195 -0.45156789, + -0.77297109 0.34674904 -0.53130108, + -0.76404691 0.35858098 -0.53633195, + -0.67342895 0.41087794 -0.61455095, + -0.67653674 0.40757185 -0.61333776, + -0.6007567 0.4424518 -0.6658287, + -0.60232514 0.44096011 -0.66540116, + -0.52616602 0.469758 -0.70885599, + -0.52545178 0.47037777 -0.70897466, + -0.45098007 0.49343807 -0.74373108, + -0.44827101 0.495626 -0.74391401, + -0.37750599 0.51342899 -0.77063602, + -0.373503 0.51650202 -0.77053303, + -0.30837801 0.529661 -0.79016602, + -0.30365202 0.53317904 -0.78963012, + -0.24500585 0.54254568 -0.8035025, + -0.24050106 0.54586613 -0.80261415, + -0.1884 0.55230099 -0.81207699, + -0.18587501 0.55418503 -0.81137514, + -0.14030196 0.55843484 -0.81759769, + -0.13378698 0.56343788 -0.81525379, + -0.095400818 0.56595606 -0.81889713, + -0.100749 0.56162798 -0.82123297, + -0.066657692 0.56324494 -0.82359689, + -0.076204017 0.55489612 -0.82842219, + -0.045094602 0.55594802 -0.82999301, + -0.0510897 0.55021298 -0.83345997, + -0.023512805 0.55078012 -0.83431917, + -0.027694508 0.54636019 -0.83709228, + -0.003926022 0.54656523 -0.83740741, + -0.0071090967 0.54280978 -0.83982557, + 0.0127306 0.54277903 -0.83977902, + 0.0098411161 0.53892285 -0.84229767, + 0.025670003 0.53877103 -0.8420611, + 0.022818398 0.53439796 -0.84492487, + 0.034646794 0.53421587 -0.84463781, + 0.03153079 0.52862179 -0.84827173, + 0.039560802 0.52847105 -0.84802914, + 0.036117099 0.521079 -0.85274398, + 0.04055912 0.52099025 -0.85259843, + 0.036919504 0.51140207 -0.8585481, + 0.038069203 0.51138008 -0.85851109, + 0.034489885 0.49937776 -0.86569756, + 0.032598507 0.49941012 -0.86575216, + 0.020577993 0.51695579 -0.85576469, + 0.025723286 0.5168947 -0.85566247, + 0.0149324 0.600214 -0.79970002, + 0.022215907 0.60013223 -0.79959232, + -0.014821006 0.59997523 -0.79988128, + -0.022216694 0.59989285 -0.79977185, + -0.015755802 0.56349808 -0.82596713, + -0.014826504 0.56350714 -0.82597816, + -0.010909298 0.52431285 -0.85145581, + -0.005422438 0.52433681 -0.85149372, + -0.0041064797 0.48198494 -0.87616986, + 0.0038639782 0.48198575 -0.87617058, + 0.0051616998 0.52439898 -0.851457, + 0.010791404 0.52437615 -0.85141832, + 0.014693802 0.56364703 -0.82588512, + 0.015761605 0.56363714 -0.82587218, + 0.017622001 0.55899906 -0.8289811, + 0.023964096 0.55892491 -0.82887191, + 0.017734794 0.5216378 -0.8529827, + 0.015675198 0.52165592 -0.85301191, + 0.011885403 0.48106712 -0.87660325, + 0.0055006319 0.48109317 -0.8766523, + 0.004250661 0.4374181 -0.89924824, + -0.0043307412 0.43741715 -0.8992483, + -0.0055992794 0.48117095 -0.87660891, + -0.012152198 0.48114294 -0.87655789, + -0.015941598 0.52150893 -0.8530969, + -0.017861703 0.52149212 -0.85306919, + -0.024101397 0.55870092 -0.82901889, + -0.017680101 0.55877608 -0.82913011, + 0.53251505 0.52325106 -0.66530907, + 0.432356 0.55742699 -0.70876199, + 0.42608204 0.56239206 -0.70863909, + 0.356639 0.58076602 -0.73179197, + 0.35533112 0.58174419 -0.73165125, + 0.29187918 0.59525937 -0.74864739, + 0.2893489 0.59709477 -0.74816775, + 0.23231503 0.60671103 -0.76021814, + 0.22969794 0.60858786 -0.75951284, + 0.17904806 0.61520225 -0.76776832, + 0.176962 0.61671102 -0.76704103, + 0.13259096 0.62106687 -0.77246082, + 0.13144305 0.6219213 -0.77196938, + 0.093128271 0.62463778 -0.77534169, + 0.092550397 0.62508798 -0.77504802, + 0.0598698 0.62665701 -0.77699202, + 0.058076184 0.62813884 -0.77593082, + 0.030817188 0.62890178 -0.77687371, + 0.028124597 0.63129592 -0.77503186, + 0.0063319709 0.63153309 -0.77532309, + 0.013212398 0.62480396 -0.78066987, + -0.0057480671 0.62484872 -0.78072464, + 0.0015851103 0.61680412 -0.78711516, + -0.015127704 0.61673415 -0.78702617, + -0.0092373323 0.60940909 -0.79280216, + -0.023319893 0.60926878 -0.79262072, + -0.018041208 0.60172927 -0.79849637, + -0.029360296 0.60156792 -0.79828191, + -0.024583001 0.59359699 -0.80438697, + -0.033060804 0.59345204 -0.8041901, + -0.028568393 0.58452487 -0.81087279, + -0.034139391 0.58442289 -0.81073081, + -0.029929092 0.5742029 -0.81816584, + -0.032615609 0.5741542 -0.81809729, + -0.028732304 0.56222206 -0.82648712, + -0.022008089 0.56231874 -0.82662761, + -0.027173504 0.58299106 -0.81202412, + -0.027029287 0.58299267 -0.81202763, + -0.031078288 0.59511179 -0.8030417, + -0.028196108 0.59516311 -0.80311018, + -0.03269051 0.60580122 -0.79494429, + -0.027155694 0.6059019 -0.79507583, + -0.032010894 0.61531788 -0.78762883, + -0.023878297 0.61545795 -0.78780788, + -0.029220104 0.62416106 -0.78074914, + -0.018585108 0.62431926 -0.78094828, + -0.024414504 0.63244903 -0.77421713, + -0.011396001 0.63259608 -0.77439815, + -0.018338298 0.64101791 -0.76730686, + -0.0032123807 0.64112216 -0.76743215, + -0.0099955024 0.64837319 -0.76125717, + 0.0076009198 0.64838701 -0.76127303, + 0.0082902405 0.64772505 -0.76182914, + 0.030821597 0.64743996 -0.76149291, + 0.031067114 0.64722431 -0.76166636, + 0.058412109 0.64643109 -0.76073313, + 0.057863809 0.64687806 -0.76039511, + 0.090119004 0.64532703 -0.7585721, + 0.090245873 0.64522976 -0.75863969, + 0.128039 0.64254099 -0.75547802, + 0.12926804 0.64164019 -0.7560342, + 0.17306606 0.63730526 -0.75092632, + 0.17510594 0.63584977 -0.75168669, + 0.22515804 0.62924504 -0.74387807, + 0.22752392 0.62756777 -0.74457479, + 0.28392804 0.61794806 -0.73316103, + 0.285505 0.616817 -0.73350102, + 0.348369 0.60328901 -0.71741301, + 0.35538799 0.59806699 -0.71834201, + 0.42420909 0.57941312 -0.6959362, + 0.46090007 0.54950005 -0.69686508, + 0.5322001 0.52421612 -0.66480118, + 0.56341231 0.49496523 -0.66149527, + 0.6520822 0.45421013 -0.60702711, + 0.6692403 0.43455121 -0.60272932, + 0.7434212 0.3911441 -0.54252315, + 0.75198591 0.37924793 -0.53915495, + 0.8126452 0.3352811 -0.47664911, + 0.82359791 0.31662497 -0.47056895, + 0.88030672 0.26483691 -0.39360085, + 0.96772778 -0.0018995395 0.25199094, + 0.96751398 -0.013865 0.252437, + 0.97842866 -0.011329496 0.20627393, + 0.97816163 -0.019692393 0.20691092, + 0.98690009 -0.015285602 0.16060701, + 0.98664314 -0.022039302 0.16139902, + 0.99320114 -0.015750103 0.11534102, + 0.99301225 -0.020848406 0.11615503, + 0.99747336 -0.012550805 0.069925219, + 0.99737948 -0.015844407 0.070591837, + 0.99971014 -0.0052728807 0.023492305, + 0.99969625 -0.0064683212 0.023785105, + 0.9996891 0.0065429211 -0.024059303, + 0.99967015 0.0078899506 -0.024444005, + 0.99687564 0.024262391 -0.075167671, + 0.99663526 0.028943608 -0.076683715, + 0.99025601 0.049175899 -0.13028701, + 0.98933953 0.058174375 -0.13350295, + 0.97807187 0.083197691 -0.19092797, + 0.97556853 0.098012954 -0.19661991, + 0.95745313 0.12874801 -0.25827804, + 0.95157689 0.15161099 -0.26742396, + 0.92418265 0.18837292 -0.33226788, + 0.91174603 0.221874 -0.34567499, + 0.87144297 0.26494801 -0.412783, + 0.8595497 0.28851891 -0.42181885, + 0.80519581 0.33478791 -0.48946589, + 0.80067348 0.34187922 -0.49197629, + 0.73181003 0.38890505 -0.55964905, + 0.72075105 0.40300906 -0.56400508, + 0.63564199 0.448816 -0.628111, + 0.61310405 0.47206405 -0.63345003, + 0.51160997 0.51342303 -0.68895, + 0.50857913 0.51601809 -0.68925518, + 0.43446508 0.5397951 -0.7210142, + 0.433855 0.54027897 -0.72101903, + 0.36391997 0.55853695 -0.74538493, + 0.36164802 0.56025404 -0.74520206, + 0.29759789 0.57370085 -0.76308769, + 0.29477605 0.57576913 -0.76262516, + 0.23713006 0.58535612 -0.77532417, + 0.23445305 0.58729714 -0.77467018, + 0.18319102 0.59391207 -0.78339612, + 0.18114701 0.59541005 -0.7827341, + 0.13620299 0.59978491 -0.78848386, + 0.13445103 0.60110611 -0.7877782, + 0.095734246 0.6038273 -0.79134536, + 0.09240631 0.60645103 -0.78973311, + 0.059720691 0.60796994 -0.79171085, + 0.054872572 0.61201572 -0.78893965, + 0.028341314 0.61269331 -0.78981239, + 0.03536519 0.60633475 -0.79442269, + 0.011981297 0.60667086 -0.79486281, + 0.0198057 0.598813 -0.80064398, + -0.0010408199 0.59893095 -0.80079991, + 0.0048632976 0.59228671 -0.80571264, + -0.013101898 0.59224296 -0.80565286, + -0.0079602273 0.58569175 -0.81049472, + -0.022961395 0.58555585 -0.81030685, + -0.018456703 0.57896811 -0.8151412, + -0.030270996 0.57880092 -0.8149069, + -0.026045803 0.57158107 -0.82013214, + -0.034646116 0.57143128 -0.81991839, + -0.030582985 0.56315571 -0.82578456, + -0.035986088 0.5630548 -0.82563573, + -0.032040097 0.55322593 -0.83241487, + -0.034352005 0.55318308 -0.83235115, + -0.030595392 0.54131991 -0.84025985, + -0.029953515 0.54133022 -0.84027642, + -0.025018591 0.52044481 -0.85352868, + -0.032577202 0.52033103 -0.85334301, + -0.036213998 0.53214896 -0.84587586, + -0.034421399 0.53218198 -0.84592998, + -0.038166516 0.54176319 -0.83966428, + -0.033083893 0.54186088 -0.83981681, + -0.036772091 0.54956585 -0.8346408, + -0.028299609 0.54971719 -0.83487129, + -0.031892795 0.55600792 -0.83056486, + -0.019857397 0.55618095 -0.8308239, + -0.023548588 0.56170774 -0.82700056, + -0.0079156999 0.56184602 -0.82720399, + -0.011964601 0.56712604 -0.82354414, + 0.0071745217 0.5671531 -0.82358116, + 0.0021937802 0.57289606 -0.81962514, + 0.024628 0.57272297 -0.81937897, + 0.018606698 0.57892996 -0.81516486, + 0.044249795 0.57846391 -0.81450689, + 0.035723493 0.58639687 -0.80923581, + 0.064084522 0.58556521 -0.8080883, + 0.056781586 0.59176689 -0.80410683, + 0.088632196 0.59038997 -0.80223686, + 0.095833175 0.58467185 -0.8055898, + 0.13459601 0.58203101 -0.80194998, + 0.13943003 0.57834715 -0.80378717, + 0.18488505 0.57398319 -0.79772228, + 0.18761107 0.57196319 -0.7985363, + 0.23947085 0.56535965 -0.78931755, + 0.24214891 0.56339681 -0.7899037, + 0.30039203 0.55386007 -0.77653313, + 0.30330718 0.55170435 -0.7769345, + 0.36789897 0.53837293 -0.75815886, + 0.37053117 0.53636622 -0.75829935, + 0.44088694 0.51831692 -0.73277992, + 0.44254893 0.51698494 -0.73271894, + 0.51686311 0.49353412 -0.69948316, + 0.5165168 0.49383181 -0.69952875, + 0.59293491 0.46440387 -0.65784281, + 0.59341609 0.46395013 -0.65772921, + 0.69137257 0.41645476 -0.59039766, + 0.70635706 0.39911705 -0.58460706, + 0.7850073 0.34929112 -0.51162416, + 0.79097915 0.34062704 -0.50825703, + 0.8520633 0.2914111 -0.43481916, + 0.85362059 0.28858685 -0.4336468, + 0.90041459 0.24101788 -0.36216581, + 0.90843725 0.22219506 -0.35407808, + 0.9416821 0.17886502 -0.28503004, + 0.94990277 0.15170597 -0.27325794, + 0.9713695 0.11531595 -0.20770989, + 0.97480488 0.097965285 -0.20039497, + 0.98780787 0.068372294 -0.13985999, + 0.9890371 0.058075309 -0.13576801, + 0.99623388 0.034100197 -0.079719193, + 0.99655074 0.028858092 -0.077806085, + 0.99963766 0.0093608759 -0.025238492, + 0.99966288 0.0078558894 -0.024746496, + 0.99967223 -0.007746872 0.024403106, + 0.99969065 -0.0064314376 0.024027491, + 0.99721575 -0.019281596 0.072035082, + 0.99733979 -0.015731197 0.071174487, + 0.99267274 -0.026077595 0.11798597, + 0.99292737 -0.020668607 0.11691105, + 0.98615879 -0.028864993 0.16327195, + 0.98652023 -0.021820806 0.16217804, + 0.97760665 -0.028061491 0.20856093, + 0.97802186 -0.019474298 0.20759097, + 0.96700966 -0.023792891 0.2536259, + 0.96739697 -0.0137003 0.25289401, + 0.9541201 -0.016197301 0.29898602, + 0.95440453 -0.0024967089 0.29850584, + 0.96402186 -0.0061087892 0.26575297, + 0.96404111 0.0008133091 0.26575202, + 0.96398813 0.00081346213 0.26594403, + 0.96396887 -0.0061044591 0.26594496, + 0.96400452 -0.0061024772 0.26581588, + 0.96402347 0.00081156142 0.26581612, + 0.97589475 -0.0049298485 0.21818596, + 0.97589254 -0.0053896271 0.21818489, + 0.97588545 -0.0053901128 0.2182171, + 0.97589946 -0.0012886206 0.2182171, + 0.98542351 0.0009092784 0.17011708, + 0.98541254 -0.0046265875 0.17011993, + 0.97865838 -0.0014123805 0.20548907, + 0.97851002 -0.0114702 0.20588, + 0.98715001 -0.0088889403 0.159549, + 0.9869855 -0.015456907 0.16006507, + 0.99339825 -0.011026403 0.11418603, + 0.99326438 -0.015906205 0.11477304, + 0.99757373 -0.009556978 0.068959385, + 0.99750423 -0.012658403 0.069462717, + 0.9997251 -0.0042037903 0.023068301, + 0.99971449 -0.0053109778 0.023294289, + 0.99970925 0.0053606015 -0.023512006, + 0.99969488 0.006581529 -0.023810396, + 0.99712354 0.020193091 -0.073053963, + 0.99694264 0.024375191 -0.074237272, + 0.991189 0.041320302 -0.125845, + 0.99049515 0.049347408 -0.12839101, + 0.9805479 0.070418291 -0.18321298, + 0.97868079 0.083393581 -0.18769495, + 0.96301633 0.10940204 -0.24623309, + 0.95874637 0.12890804 -0.2533541, + 0.93554914 0.16016802 -0.31479204, + 0.92664587 0.18843397 -0.32529998, + 0.89317697 0.22541 -0.38913399, + 0.87963891 0.25666296 -0.40044895, + 0.83928388 0.29338497 -0.45774195, + 0.82382011 0.32166103 -0.46674907, + 0.77548599 0.35826901 -0.51986998, + 0.76086313 0.38045207 -0.52568406, + 0.69596303 0.421004 -0.58171397, + 0.68251592 0.43790793 -0.58515692, + 0.605124 0.47701001 -0.63740599, + 0.58141088 0.5018869 -0.64036781, + 0.49171212 0.53713912 -0.6853472, + 0.45421594 0.56970793 -0.68492395, + 0.386776 0.58971202 -0.708974, + 0.34736517 0.61991328 -0.70359439, + 0.28510299 0.63364202 -0.71917599, + 0.27788696 0.63877791 -0.71745497, + 0.22217208 0.64834923 -0.72820526, + 0.22063994 0.64941984 -0.7277168, + 0.17120194 0.65599877 -0.73508877, + 0.16935907 0.6572963 -0.73435634, + 0.12611598 0.66160494 -0.73917097, + 0.124919 0.66246903 -0.73860002, + 0.087649778 0.66512984 -0.74156582, + 0.087400258 0.66531771 -0.74142665, + 0.055576492 0.66684192 -0.74312395, + 0.056548685 0.66606182 -0.7437498, + 0.029514203 0.66683906 -0.74461704, + 0.031220604 0.66536504 -0.74586505, + 0.0086414833 0.66566432 -0.74620134, + 0.0097543392 0.66461092 -0.74712592, + -0.0085177589 0.66461897 -0.74713391, + -0.0075009349 0.66355342 -0.7480914, + -0.021472702 0.66342008 -0.74793905, + -0.014782404 0.65550619 -0.75504518, + -0.026515609 0.65534723 -0.75486231, + -0.019891502 0.64633304 -0.7627961, + -0.029664697 0.64617693 -0.76261085, + -0.023963111 0.6371063 -0.77040339, + -0.031565811 0.63697225 -0.77024031, + -0.026318794 0.62703681 -0.77854484, + -0.031627588 0.62694079 -0.77842468, + -0.026907699 0.61603898 -0.787256, + -0.029796597 0.61598796 -0.78719187, + -0.025572991 0.60366374 -0.79682869, + -0.019623499 0.60374498 -0.79693598, + -0.024977716 0.62408334 -0.78095847, + -0.012740999 0.64026695 -0.76804686, + -0.020639 0.64018202 -0.767946, + -0.013955996 0.6044699 -0.79650581, + -0.013713704 0.60447222 -0.79650831, + -0.0096692611 0.56628609 -0.82415211, + -0.005036992 0.56630516 -0.82418031, + -0.0036769181 0.52525878 -0.85093457, + 0.0035335105 0.52525908 -0.8509351, + 0.0048705284 0.56637579 -0.82413268, + 0.009662101 0.56635606 -0.82410413, + 0.013689496 0.60463274 -0.79638672, + 0.014096905 0.60462922 -0.79638231, + 0.0207546 0.64034498 -0.76780701, + 0.012995393 0.64042872 -0.76790762, + -0.55911988 0.52181387 -0.64427882, + -0.47639206 0.55337507 -0.68324709, + -0.44626895 0.58130091 -0.68039197, + -0.38669214 0.59904021 -0.70115626, + -0.34984583 0.62988472 -0.69343567, + -0.29448614 0.64255828 -0.70738733, + -0.24733186 0.67832756 -0.69188058, + -0.17056999 0.68981892 -0.70360196, + -0.16225594 0.69553578 -0.69993079, + -0.12006994 0.69977665 -0.70419866, + -0.11975208 0.69999945 -0.70403147, + -0.083371066 0.70261866 -0.70666564, + -0.083120793 0.70280093 -0.70651394, + -0.052054413 0.7042852 -0.7080062, + -0.052451111 0.70397919 -0.70828116, + -0.026186004 0.70470804 -0.70901406, + -0.027420796 0.70368093 -0.70998693, + -0.0055614887 0.70393485 -0.71024281, + -0.0077997046 0.7018984 -0.71223444, + 0.010117697 0.70188373 -0.71221977, + 0.0067453631 0.69847739 -0.71560037, + 0.021115908 0.69833738 -0.71545738, + 0.016310498 0.69286597 -0.72088194, + 0.0276848 0.69269198 -0.72070199, + 0.023429494 0.68714982 -0.72613782, + 0.031694911 0.68699324 -0.72597224, + 0.026279604 0.67877704 -0.73387408, + 0.03239109 0.67865479 -0.73374277, + 0.02653311 0.66807222 -0.74362326, + 0.030961914 0.66798729 -0.74352837, + 0.025869001 0.65676099 -0.75365502, + 0.0283757 0.65671599 -0.75360399, + 0.023947304 0.64439106 -0.76432115, + 0.018368792 0.64446676 -0.76441169, + 0.023732105 0.6639142 -0.74743217, + 0.023432005 0.66391915 -0.74743718, + 0.028005393 0.67634779 -0.73604983, + 0.025873195 0.67638695 -0.73609191, + 0.031221388 0.68789679 -0.72513676, + 0.027497103 0.68797207 -0.72521603, + 0.032781206 0.69729519 -0.71603417, + 0.0270462 0.69741499 -0.71615702, + 0.031796105 0.70447206 -0.70901906, + 0.023343898 0.70463693 -0.70918393, + 0.028584296 0.71132195 -0.70228493, + 0.017454989 0.71150458 -0.70246458, + 0.021591689 0.71611363 -0.69764966, + 0.0073327492 0.71626097 -0.69779396, + 0.010506596 0.71940279 -0.69451374, + -0.007257822 0.71942317 -0.69453418, + -0.0049151583 0.72151273 -0.69238377, + -0.026613494 0.72126579 -0.69214684, + -0.025129404 0.72247607 -0.69093907, + -0.05110018 0.72176075 -0.69025373, + -0.050337087 0.7223388 -0.68970484, + -0.081003696 0.72087896 -0.68831092, + -0.080591455 0.72117358 -0.68805057, + -0.11636905 0.71861136 -0.6856063, + -0.12442094 0.71303862 -0.68999666, + -0.19308691 0.70509964 -0.68231368, + -0.24067503 0.66945505 -0.70278406, + -0.29060602 0.65996206 -0.69281906, + -0.32857314 0.62899029 -0.70456433, + -0.38352695 0.61503893 -0.68893695, + -0.41601405 0.58607209 -0.69530708, + -0.47411093 0.56745094 -0.67321491, + -0.50029415 0.54174513 -0.67543918, + -0.55953109 0.51856613 -0.64654016, + -0.58092111 0.49525011 -0.6459552, + -0.64984274 0.46246082 -0.60318679, + -0.6737178 0.4318639 -0.59966487, + -0.72634482 0.4016749 -0.55774587, + -0.74904108 0.36773103 -0.55110008, + -0.79663014 0.33550802 -0.50280708, + -0.81296611 0.30634004 -0.49521905, + -0.85449719 0.27327305 -0.44176513, + -0.865569 0.249211 -0.434378, + -0.8999806 0.21693389 -0.37811983, + -0.90938121 0.19123904 -0.36939609, + -0.93765134 0.15979806 -0.30866611, + -0.94403726 0.13594402 -0.30052105, + -0.9640671 0.10949201 -0.24204603, + -0.96721101 0.092618398 -0.23648401, + -0.98101765 0.070717879 -0.18056394, + -0.98241448 0.059288628 -0.17705008, + -0.9913705 0.041625682 -0.12430494, + -0.99189079 0.034488194 -0.12232397, + -0.99717379 0.020387394 -0.072311185, + -0.99731112 0.016571902 -0.071385309, + -0.99971354 0.0054124771 -0.02331489, + -0.99972451 0.0042638681 -0.023080489, + -0.99972862 -0.0042324085 0.022910092, + -0.99973643 -0.0031694681 0.022736387, + -0.99759835 -0.0095630838 0.068601623, + -0.99764675 -0.0066248085 0.068242587, + -0.99344379 -0.011046197 0.11378697, + -0.99352539 -0.0065321522 0.11342303, + -0.98719567 -0.0091713667 0.15924995, + -0.60568577 0.47637582 -0.63734674, + -0.68298924 0.43729615 -0.58506227, + -0.69613326 0.42075816 -0.58168817, + -0.76102114 0.38020906 -0.52563107, + -0.77683872 0.35614887 -0.51930684, + -0.82494783 0.3196739 -0.46612188, + -0.84055227 0.2909801 -0.45694914, + -0.88069355 0.25443187 -0.39955384, + -0.89073527 0.23136809 -0.39122814, + -0.92988479 0.18724896 -0.31662592, + -0.92461425 0.18708804 -0.3317931, + -0.95187223 0.15054102 -0.26697707, + -0.95759702 0.12818 -0.25802699, + -0.97565776 0.097564675 -0.19639996, + -0.9781059 0.083038092 -0.19082297, + -0.98935527 0.058065016 -0.13343403, + -0.99025875 0.04918189 -0.13026397, + -0.99663502 0.028952399 -0.076683797, + -0.99687314 0.024318803 -0.07518331, + -0.99966979 0.0079082483 -0.024448894, + -0.99968886 0.006565779 -0.024065496, + -0.9996959 -0.0064908192 0.023790795, + -0.99971002 -0.00528542 0.0234956, + -0.99737823 -0.015881903 0.070600815, + -0.99747378 -0.012527697 0.069921985, + -0.99301314 -0.020810902 0.11615402, + -0.99320549 -0.015605507 0.11532305, + -0.98664874 -0.021839395 0.16139196, + -0.98690236 -0.015141706 0.16060705, + -0.97816211 -0.019508502 0.20692603, + -0.96770722 -0.0028199807 0.25206107, + -0.96749902 -0.0141263 0.25248, + -0.97841603 -0.0115437 0.206322, + -0.97864538 -0.0020949689 0.20554487, + -0.97849989 -0.011687899 0.20591597, + -0.98714447 -0.0090574948 0.15957408, + -0.98698765 -0.015313694 0.16006494, + -0.99340022 -0.010923703 0.11417903, + -0.99326813 -0.015761001 0.11476102, + -0.99757546 -0.0094690546 0.068946928, + -0.99750465 -0.012635295 0.069460675, + -0.9997251 -0.0041959905 0.023066903, + -0.99971449 -0.0053235725 0.023297111, + -0.99970913 0.0053733406 -0.023514904, + -0.99969453 0.0066043269 -0.023815889, + -0.99712086 0.020263199 -0.073071294, + -0.99694037 0.02443121 -0.074250527, + -0.99118227 0.04141511 -0.12586702, + -0.99049586 0.049351592 -0.12838398, + -0.98054421 0.070433415 -0.18322705, + -0.97870255 0.083232559 -0.18765292, + -0.96307153 0.10916594 -0.24612188, + -0.95888233 0.12834704 -0.25312409, + -0.93576688 0.15946798 -0.31449997, + -0.92906964 0.18106894 -0.32255787, + -0.89954811 0.21382603 -0.38090906, + -0.8911373 0.23480609 -0.38825315, + -0.85405087 0.26919696 -0.44511795, + -0.84091169 0.29549587 -0.45337585, + -0.79627681 0.33031091 -0.50679189, + -0.77701288 0.36191696 -0.51504093, + -0.72622621 0.39524615 -0.56247318, + -0.70632601 0.422791 -0.56775999, + -0.63866878 0.45957983 -0.61716175, + -0.62027109 0.48092005 -0.61966103, + -0.54156089 0.51542288 -0.6641168, + -0.51328796 0.54314196 -0.66447896, + -0.44968185 0.56527483 -0.69155675, + -0.41515177 0.59539163 -0.6878646, + -0.35435709 0.61198711 -0.70703816, + -0.30906904 0.64732504 -0.69674003, + -0.22440594 0.6632908 -0.71392381, + -0.21630605 0.66891515 -0.71117115, + -0.16748308 0.6754573 -0.71812737, + -0.16647999 0.67615396 -0.71770495, + -0.12370697 0.6804558 -0.7222718, + -0.12252296 0.68129873 -0.72167873, + -0.085654996 0.68394798 -0.72448498, + -0.084947124 0.68447316 -0.72407216, + -0.053530965 0.68597156 -0.72565657, + -0.053648572 0.68587869 -0.72573566, + -0.027091887 0.68661571 -0.72651565, + -0.0282067 0.68567199 -0.727364, + -0.0061738677 0.68593174 -0.72763973, + -0.0085706431 0.68370926 -0.72970426, + 0.0094816592 0.68370295 -0.72969896, + 0.0053177886 0.6794098 -0.73373979, + 0.019975308 0.67928326 -0.73360425, + 0.0165239 0.67527503 -0.73738098, + 0.027657287 0.67510873 -0.73719966, + 0.022252195 0.66792279 -0.7438978, + 0.031015201 0.66776699 -0.74372399, + 0.0247548 0.65803999 -0.75257599, + 0.031724408 0.65791118 -0.75242716, + 0.026282895 0.64783996 -0.76132286, + 0.031197218 0.64774835 -0.76121545, + 0.026352491 0.63681078 -0.77056968, + 0.02906769 0.63676274 -0.77051169, + 0.024731694 0.62439787 -0.78071481, + 0.02513301 0.62439126 -0.7807073, + 0.019785695 0.60402489 -0.79671985, + 0.025808405 0.6039421 -0.79661018, + 0.030042589 0.61631978 -0.78692269, + 0.027252495 0.61636889 -0.78698581, + 0.03192322 0.62716937 -0.77822846, + 0.026644006 0.62726617 -0.77834916, + 0.031727597 0.63690293 -0.77029085, + 0.024119699 0.63703799 -0.770455, + 0.029766204 0.64602804 -0.7627331, + 0.019936893 0.64618576 -0.76291972, + 0.02653669 0.65517175 -0.7550137, + 0.014763207 0.65533131 -0.75519735, + 0.020058801 0.66160506 -0.74958408, + 0.0057206065 0.66172761 -0.7497226, + 0.0080442056 0.6641686 -0.74753958, + -0.010322398 0.66415483 -0.74752384, + -0.0070137917 0.66728318 -0.74477118, + -0.02924842 0.66701448 -0.74447054, + -0.027981 0.66810697 -0.74353898, + -0.054767575 0.66736573 -0.74271363, + -0.05486358 0.66728878 -0.74277574, + -0.086579174 0.66578579 -0.74110276, + -0.087654807 0.66497505 -0.74170405, + -0.12498603 0.66231018 -0.73873121, + -0.12669501 0.661075 -0.739546, + -0.17004505 0.65674019 -0.7346952, + -0.17199704 0.65536416 -0.73546916, + -0.22150497 0.64875293 -0.72804892, + -0.22287913 0.64779037 -0.72848642, + -0.27870005 0.6381762 -0.71767515, + -0.28599304 0.63297707 -0.71940804, + -0.37804699 0.61154503 -0.69504899, + -0.41998485 0.57734281 -0.70020574, + -0.48558894 0.55613095 -0.67447895, + -0.5166862 0.5274142 -0.67444026, + -0.58255488 0.50068891 -0.64026582, + -0.58224112 0.50214911 -0.63940716, + -0.49041507 0.53826404 -0.68539405, + -0.45327801 0.57045197 -0.68492597, + -0.35506192 0.59827286 -0.71833181, + -0.34923384 0.60261172 -0.71756166, + -0.28633597 0.61617696 -0.73371494, + -0.28494403 0.61717606 -0.73341703, + -0.22841406 0.62684721 -0.74490917, + -0.22594993 0.62859577 -0.74418676, + -0.17582405 0.6352312 -0.75204217, + -0.17320496 0.63710183 -0.7510668, + -0.12936904 0.64144319 -0.75618416, + -0.12717402 0.64305109 -0.75519013, + -0.089458451 0.64571565 -0.7583195, + -0.088118032 0.64674121 -0.75760227, + -0.056121025 0.64824331 -0.75936234, + -0.056107014 0.64825517 -0.75935316, + -0.029121183 0.64900267 -0.76022851, + -0.031400211 0.64700222 -0.7618413, + -0.0088020386 0.64729595 -0.7621879, + -0.0097347852 0.64639872 -0.76293766, + 0.0083001135 0.64640731 -0.76294738, + 0.0031413704 0.64088309 -0.76763213, + 0.018315397 0.64077783 -0.76750779, + 0.011378899 0.63235897 -0.77459186, + 0.024469294 0.63221085 -0.77440983, + 0.018752499 0.62423193 -0.78101391, + 0.029375397 0.62407392 -0.78081286, + 0.024248006 0.61571312 -0.78759718, + 0.032325812 0.61557221 -0.78741729, + 0.027564196 0.60632795 -0.79473686, + 0.032986294 0.60622895 -0.79460585, + 0.0284961 0.595586 -0.80278599, + 0.031226093 0.59553689 -0.80272084, + 0.027153691 0.58332384 -0.8117857, + 0.02723269 0.58332282 -0.81178373, + 0.022079701 0.56264901 -0.826401, + 0.028785616 0.56255233 -0.82626045, + 0.032691009 0.57457715 -0.8177973, + 0.030165203 0.57462305 -0.81786209, + 0.034404192 0.58492589 -0.8103568, + 0.028950199 0.58502698 -0.81049699, + 0.033439409 0.59395611 -0.80380219, + 0.025075812 0.59410131 -0.80399936, + 0.029718315 0.6018523 -0.79805434, + 0.018455297 0.60201585 -0.79827082, + 0.023472404 0.60918707 -0.79267913, + 0.0093628401 0.60932797 -0.79286301, + 0.015093798 0.61646092 -0.78724086, + -0.001650641 0.61653036 -0.78732949, + 0.005661028 0.62455577 -0.78095973, + -0.013356606 0.62451029 -0.78090239, + -0.0083734123 0.62939417 -0.7770412, + -0.030609207 0.62912017 -0.77670521, + -0.031326097 0.62848091 -0.7771939, + -0.0586759 0.62770599 -0.776236, + -0.057593577 0.62860078 -0.77559268, + -0.089924075 0.62709379 -0.77373582, + -0.091172501 0.62612498 -0.77437401, + -0.12919697 0.6234749 -0.7710948, + -0.13177305 0.62156332 -0.77220136, + -0.17604999 0.61723691 -0.76682788, + -0.17923102 0.61493808 -0.76793712, + -0.22991906 0.6083141 -0.75966519, + -0.23314001 0.60600197 -0.76053101, + -0.29030204 0.59633803 -0.74840206, + -0.292916 0.59443802 -0.74889499, + -0.35644302 0.58087105 -0.73180407, + -0.3575131 0.58006912 -0.73191816, + -0.42702809 0.5616411 -0.70866519, + -0.43080315 0.55865419 -0.70874125, + -0.53236598 0.52403003 -0.66481501, + -0.56341136 0.4949303 -0.66152239, + -0.65207767 0.45417979 -0.60705471, + -0.66974807 0.43392006 -0.60262007, + -0.74387306 0.39052305 -0.54235107, + -0.75215966 0.37900183 -0.53908575, + -0.81277311 0.33506203 -0.47658506, + -0.82472068 0.31465587 -0.46992281, + -0.86831069 0.2759769 -0.41215685, + -0.88034356 0.25059289 -0.40273881, + -0.91519475 0.21291195 -0.34217992, + -0.91583669 0.21984193 -0.33602488, + -0.86805558 0.27180588 -0.41545278, + -0.8596409 0.28832898 -0.42176294, + -0.80532891 0.33456698 -0.48939794, + -0.80105186 0.34127897 -0.49177694, + -0.73228294 0.38826194 -0.55947691, + -0.72073793 0.40299493 -0.56403196, + -0.63562995 0.44879693 -0.62813693, + -0.61251074 0.47262883 -0.63360274, + -0.5109129 0.51398689 -0.6890468, + -0.50954509 0.51515806 -0.68918508, + -0.43543491 0.5389719 -0.72104484, + -0.43499601 0.53932202 -0.721048, + -0.36504602 0.55762506 -0.74551708, + -0.36267382 0.55942076 -0.74532962, + -0.29857183 0.57290965 -0.76330155, + -0.29510596 0.57545197 -0.76273686, + -0.23738697 0.58505893 -0.7754699, + -0.23352009 0.58786225 -0.77452332, + -0.18233098 0.59444195 -0.7831949, + -0.17874309 0.59706432 -0.78202635, + -0.13402405 0.60136229 -0.78765535, + -0.13149302 0.60326403 -0.78662711, + -0.0931499 0.60590202 -0.79006702, + -0.093007691 0.60601395 -0.78999788, + -0.060237415 0.6075471 -0.79199618, + -0.057688825 0.60968029 -0.79054534, + -0.030723808 0.61040914 -0.7914902, + -0.035602808 0.60598212 -0.79468119, + -0.012151195 0.60632169 -0.79512662, + -0.019957801 0.59847605 -0.80089211, + 0.00095156924 0.59859514 -0.8010512, + -0.0047865082 0.59213477 -0.8058247, + 0.013225992 0.59208965 -0.80576354, + 0.0084476583 0.58599889 -0.81026781, + 0.023368999 0.585859 -0.810076, + 0.019056799 0.57954997 -0.8147139, + 0.030742297 0.57938093 -0.81447691, + 0.0265209 0.57216299 -0.81971103, + 0.035001591 0.57201385 -0.81949681, + 0.0309078 0.56366801 -0.825423, + 0.036181901 0.563568 -0.82527697, + 0.032187294 0.55360389 -0.83215785, + 0.034383088 0.55356383 -0.8320967, + 0.030607199 0.54161698 -0.84006798, + 0.029857608 0.54162914 -0.84008718, + 0.024913499 0.52065098 -0.85340601, + 0.032524586 0.52053678 -0.85321957, + 0.036200296 0.53250092 -0.8456549, + 0.034464788 0.53253382 -0.8457067, + 0.038261283 0.54226077 -0.8393386, + 0.033326495 0.54235697 -0.8394869, + 0.037065417 0.55017519 -0.83422631, + 0.028706184 0.55032563 -0.8344565, + 0.032341216 0.55669326 -0.83008844, + 0.020463198 0.55686796 -0.83034891, + 0.024133403 0.56236607 -0.82653612, + 0.0086350208 0.56250906 -0.82674611, + 0.012439298 0.56747186 -0.82329881, + -0.0066201324 0.5675022 -0.8233453, + -0.0021312104 0.57268012 -0.81977618, + -0.024614591 0.5725078 -0.81952971, + -0.018793892 0.57851285 -0.81545669, + -0.044515897 0.57804191 -0.81479186, + -0.035997096 0.58597392 -0.8095299, + -0.064439394 0.58513594 -0.80837089, + -0.059476707 0.58936006 -0.80567813, + -0.091790333 0.58791322 -0.80369931, + -0.096329935 0.58429724 -0.80580229, + -0.13515508 0.58164036 -0.80213946, + -0.13652098 0.58060092 -0.80266088, + -0.18160191 0.5763427 -0.79677463, + -0.18529402 0.57361805 -0.79789013, + -0.23694594 0.56710291 -0.78882885, + -0.24128608 0.56393015 -0.78978729, + -0.29948884 0.55442679 -0.77647763, + -0.30368713 0.55132216 -0.77705729, + -0.36831498 0.53797293 -0.75824088, + -0.37158212 0.5354802 -0.75841129, + -0.44201413 0.5173741 -0.73276716, + -0.44368386 0.51603281 -0.73270375, + -0.51798701 0.492542 -0.69935101, + -0.51747286 0.49298587 -0.69941884, + -0.59382308 0.46354407 -0.65764809, + -0.59277505 0.46453407 -0.65789509, + -0.69084299 0.41702801 -0.59061301, + -0.7063368 0.3991119 -0.5846349, + -0.78498584 0.3492929 -0.51165587, + -0.79138291 0.34000498 -0.50804496, + -0.85236371 0.2908549 -0.43460286, + -0.85371983 0.28839394 -0.43357992, + -0.90049726 0.24083605 -0.36208108, + -0.90915322 0.22046506 -0.35332108, + -0.94215125 0.17744105 -0.28436905, + -0.95022452 0.15061793 -0.27274087, + -0.97153747 0.11451605 -0.20736711, + -0.97489142 0.097510144 -0.20019588, + -0.98784786 0.068059295 -0.13972999, + -0.98905051 0.057963274 -0.13571794, + -0.99623823 0.034035906 -0.079693019, + -0.99655038 0.028867083 -0.077806853, + -0.99963754 0.0093640657 -0.025239488, + -0.99966264 0.007874297 -0.02475249, + -0.99967188 -0.0077646589 0.024407797, + -0.99969035 -0.0064541022 0.02403361, + -0.99721241 -0.019351589 0.072061256, + -0.99733812 -0.015767401 0.071191311, + -0.99266952 -0.026134986 0.11800094, + -0.9929285 -0.020631291 0.11690695, + -0.98615789 -0.028816096 0.16328599, + -0.98652655 -0.021621188 0.16216592, + -0.97761399 -0.0278069 0.208561, + -0.97802401 -0.0192918 0.207598, + -0.96700591 -0.023572396 0.25366098, + -0.96737635 -0.013953905 0.2529591, + -0.95409489 -0.016496398 0.29904997, + -0.95437253 -0.0036089083 0.29859686, + -0.96314573 -0.0075529781 0.26887393, + -0.96317464 0.00093462266 0.26887491, + -0.96317351 0.00093462755 0.26887888, + -0.96314466 -0.0075528971 0.26887792, + -0.96315074 -0.007552458 0.26885593, + -0.96317965 0.00093429763 0.26885691, + -0.97518301 -0.00433107 0.221358, + -0.97517025 -0.0066757514 0.22135606, + -0.97517776 -0.0066750785 0.22132294, + -0.97519886 -0.0016840597 0.22132397, + -0.98488849 0.00098321843 0.17318709, + -0.98487163 -0.005758428 0.17318994, + -0.98491853 -0.0057529374 0.17292291, + -0.98493546 0.00098522648 0.17292009, + -0.984882 0.00098546804 0.173224, + -0.99219465 -0.0035763488 0.12464695, + -0.99219024 -0.0046622911 0.12464703, + -0.99217767 -0.0046643582 0.12474696, + -0.99218577 -0.0024237696 0.12474597, + -0.99712014 0.00096518412 0.075831905, + -0.99711466 -0.0033884188 0.075834773, + -0.99711013 -0.0033897005 0.075894706, + -0.99711555 0.00096292055 0.075891562, + -0.99711311 0.00096294814 0.075924709, + -0.99963897 -0.0028926299 0.026712401, + -0.99964148 -0.0018820909 0.026711613, + -0.99974948 -0.0017874908 0.022313211, + -0.99963814 -4.5343902e-005 0.026899103, + -0.99963289 -0.0032325694 0.026901497, + -0.99976212 0.0008362821 -0.021794602, + -0.99976248 -1.6864407e-005 -0.021793911, + -0.99975353 -7.9351266e-006 -0.022202689, + -0.99975312 0.00086754712 -0.022203403, + -0.99975502 0.00086761598 -0.022115899, + -0.99975187 0.00085937389 -0.022257999, + -0.99746335 -0.0022539108 -0.071146019, + -0.99746567 0.00042616186 -0.071148179, + -0.99747014 0.00042475807 -0.071085908, + -0.99746197 -0.00412559 -0.071081698, + -0.9970125 -0.0034232817 -0.077164739, + -0.84207714 -0.53667408 -0.053731006, + 0.89261347 0.45081174 0.0031386581, + 0.450762 -0.0141545 0.89253199, + 0.4508118 0.0015851893 0.89261758, + -0.015182205 0.52255017 -0.85247332, + 0.014481494 0.52255481 -0.85248268, + 0 -0.99999964 0.00079628272, + 0.89259273 0.45080486 0.0072980574, + 0.17241998 0.0011597698 0.9850229, + -0.53740287 0.0072184582 -0.8432948, + 0.075101063 0.0008541306 0.99717551, + 0.075090967 -0.015539794 0.99705565, + 0 -0.00079628272 -0.99999964 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 2, 1, -1, + 4, 5, 6, -1, 7, 8, 9, -1, + 10, 11, 12, -1, 11, 10, 13, -1, + 13, 14, 11, -1, 14, 13, 15, -1, + 15, 16, 14, -1, 16, 15, 17, -1, + 17, 18, 16, -1, 18, 17, 19, -1, + 19, 20, 18, -1, 20, 19, 21, -1, + 21, 22, 20, -1, 22, 21, 23, -1, + 23, 24, 22, -1, 24, 23, 25, -1, + 25, 26, 24, -1, 26, 25, 27, -1, + 27, 28, 26, -1, 28, 27, 29, -1, + 29, 30, 28, -1, 30, 29, 31, -1, + 31, 32, 30, -1, 32, 31, 33, -1, + 33, 34, 32, -1, 34, 33, 35, -1, + 35, 36, 34, -1, 36, 35, 37, -1, + 37, 38, 36, -1, 38, 37, 39, -1, + 39, 40, 38, -1, 40, 39, 41, -1, + 41, 42, 40, -1, 42, 41, 43, -1, + 43, 44, 42, -1, 44, 43, 45, -1, + 45, 46, 44, -1, 46, 45, 47, -1, + 47, 48, 46, -1, 48, 47, 49, -1, + 48, 49, 50, -1, 51, 50, 49, -1, + 51, 52, 50, -1, 52, 51, 53, -1, + 53, 54, 52, -1, 54, 55, 56, -1, + 56, 52, 54, -1, 52, 56, 57, -1, + 57, 50, 52, -1, 50, 57, 58, -1, + 59, 58, 57, -1, 57, 60, 59, -1, + 60, 57, 56, -1, 56, 61, 60, -1, + 61, 56, 55, -1, 55, 62, 61, -1, + 63, 64, 65, -1, 63, 65, 66, -1, + 65, 67, 66, -1, 67, 65, 62, -1, + 62, 55, 67, -1, 68, 67, 69, -1, + 67, 70, 69, -1, 70, 67, 55, -1, + 55, 54, 70, -1, 70, 71, 72, -1, + 71, 70, 54, -1, 54, 53, 71, -1, + 73, 74, 75, -1, 76, 71, 74, -1, + 71, 75, 74, -1, 75, 71, 53, -1, + 53, 77, 75, -1, 77, 53, 51, -1, + 51, 78, 77, -1, 78, 51, 49, -1, + 49, 79, 78, -1, 79, 49, 47, -1, + 47, 80, 79, -1, 80, 47, 45, -1, + 45, 81, 80, -1, 81, 45, 43, -1, + 43, 82, 81, -1, 82, 43, 41, -1, + 41, 83, 82, -1, 83, 41, 39, -1, + 39, 84, 83, -1, 84, 39, 37, -1, + 37, 85, 84, -1, 85, 37, 35, -1, + 35, 86, 85, -1, 86, 35, 33, -1, + 33, 87, 86, -1, 87, 33, 31, -1, + 31, 88, 87, -1, 88, 31, 29, -1, + 29, 89, 88, -1, 89, 29, 27, -1, + 27, 90, 89, -1, 90, 27, 25, -1, + 25, 91, 90, -1, 91, 25, 23, -1, + 23, 92, 91, -1, 92, 23, 21, -1, + 21, 93, 92, -1, 93, 21, 19, -1, + 19, 94, 93, -1, 94, 19, 17, -1, + 17, 95, 94, -1, 95, 17, 15, -1, + 15, 96, 95, -1, 96, 15, 13, -1, + 13, 97, 96, -1, 97, 13, 10, -1, + 10, 98, 97, -1, 10, 12, 98, -1, + 99, 98, 12, -1, 99, 100, 98, -1, + 100, 99, 101, -1, 101, 102, 100, -1, + 102, 101, 103, -1, 102, 103, 104, -1, + 104, 105, 102, -1, 105, 104, 106, -1, + 106, 107, 105, -1, 108, 109, 110, -1, + 111, 112, 113, -1, 114, 115, 116, -1, + 116, 117, 114, -1, 117, 116, 118, -1, + 118, 119, 117, -1, 119, 118, 120, -1, + 120, 121, 119, -1, 122, 123, 121, -1, + 121, 120, 122, -1, 124, 122, 120, -1, + 120, 125, 124, -1, 125, 120, 118, -1, + 118, 126, 125, -1, 126, 118, 116, -1, + 116, 127, 126, -1, 127, 116, 115, -1, + 115, 128, 127, -1, 129, 130, 115, -1, + 130, 128, 115, -1, 130, 131, 128, -1, + 130, 129, 131, -1, 132, 131, 129, -1, + 129, 115, 132, -1, 133, 132, 115, -1, + 115, 114, 133, -1, 134, 135, 133, -1, + 133, 136, 134, -1, 136, 133, 114, -1, + 114, 137, 136, -1, 137, 114, 117, -1, + 117, 138, 137, -1, 138, 117, 119, -1, + 119, 139, 138, -1, 139, 119, 121, -1, + 121, 140, 139, -1, 140, 121, 123, -1, + 123, 141, 140, -1, 142, 143, 141, -1, + 143, 142, 144, -1, 144, 145, 143, -1, + 145, 144, 146, -1, 146, 147, 145, -1, + 147, 146, 148, -1, 148, 149, 147, -1, + 149, 148, 150, -1, 150, 151, 149, -1, + 151, 150, 152, -1, 152, 153, 151, -1, + 153, 152, 154, -1, 154, 155, 153, -1, + 155, 154, 156, -1, 156, 157, 155, -1, + 157, 156, 158, -1, 158, 159, 157, -1, + 159, 158, 160, -1, 160, 161, 159, -1, + 161, 160, 162, -1, 162, 163, 161, -1, + 163, 162, 164, -1, 164, 165, 163, -1, + 165, 164, 166, -1, 166, 167, 165, -1, + 167, 166, 168, -1, 168, 169, 167, -1, + 169, 168, 170, -1, 170, 171, 169, -1, + 171, 170, 172, -1, 172, 173, 171, -1, + 173, 172, 174, -1, 174, 175, 173, -1, + 176, 177, 178, -1, 177, 176, 175, -1, + 175, 174, 177, -1, 179, 177, 174, -1, + 174, 180, 179, -1, 180, 174, 172, -1, + 172, 181, 180, -1, 181, 172, 170, -1, + 170, 182, 181, -1, 182, 170, 168, -1, + 168, 183, 182, -1, 183, 168, 166, -1, + 166, 184, 183, -1, 184, 166, 164, -1, + 164, 185, 184, -1, 185, 164, 162, -1, + 162, 186, 185, -1, 186, 162, 160, -1, + 160, 187, 186, -1, 187, 160, 158, -1, + 158, 188, 187, -1, 188, 158, 156, -1, + 156, 189, 188, -1, 189, 156, 154, -1, + 154, 190, 189, -1, 190, 154, 152, -1, + 152, 191, 190, -1, 191, 152, 150, -1, + 150, 192, 191, -1, 192, 150, 148, -1, + 148, 193, 192, -1, 193, 148, 146, -1, + 146, 194, 193, -1, 194, 146, 144, -1, + 144, 195, 194, -1, 195, 144, 142, -1, + 142, 196, 195, -1, 196, 142, 141, -1, + 141, 123, 196, -1, 197, 196, 123, -1, + 196, 197, 198, -1, 198, 195, 196, -1, + 195, 198, 199, -1, 199, 194, 195, -1, + 194, 199, 200, -1, 200, 193, 194, -1, + 193, 200, 201, -1, 201, 192, 193, -1, + 192, 201, 202, -1, 202, 191, 192, -1, + 191, 202, 203, -1, 203, 190, 191, -1, + 190, 203, 204, -1, 204, 189, 190, -1, + 189, 204, 205, -1, 205, 188, 189, -1, + 188, 205, 206, -1, 206, 187, 188, -1, + 187, 206, 207, -1, 207, 186, 187, -1, + 186, 207, 208, -1, 208, 185, 186, -1, + 185, 208, 209, -1, 209, 184, 185, -1, + 184, 209, 210, -1, 210, 183, 184, -1, + 183, 210, 211, -1, 211, 182, 183, -1, + 182, 211, 212, -1, 212, 181, 182, -1, + 181, 212, 213, -1, 213, 180, 181, -1, + 180, 213, 214, -1, 214, 179, 180, -1, + 214, 215, 179, -1, 214, 216, 215, -1, + 216, 214, 213, -1, 213, 217, 216, -1, + 217, 213, 212, -1, 212, 218, 217, -1, + 218, 212, 211, -1, 211, 219, 218, -1, + 219, 211, 210, -1, 210, 220, 219, -1, + 220, 210, 209, -1, 209, 221, 220, -1, + 221, 209, 208, -1, 208, 222, 221, -1, + 222, 208, 207, -1, 207, 223, 222, -1, + 223, 207, 206, -1, 206, 224, 223, -1, + 224, 206, 205, -1, 205, 225, 224, -1, + 225, 205, 204, -1, 204, 226, 225, -1, + 226, 204, 203, -1, 203, 227, 226, -1, + 227, 203, 202, -1, 202, 228, 227, -1, + 228, 202, 201, -1, 201, 229, 228, -1, + 229, 201, 200, -1, 200, 230, 229, -1, + 230, 200, 199, -1, 199, 231, 230, -1, + 231, 199, 198, -1, 198, 232, 231, -1, + 232, 198, 197, -1, 197, 233, 232, -1, + 233, 197, 123, -1, 123, 122, 233, -1, + 234, 235, 233, -1, 234, 233, 122, -1, + 122, 124, 234, -1, 236, 237, 234, -1, + 236, 234, 124, -1, 124, 238, 236, -1, + 238, 124, 125, -1, 125, 239, 238, -1, + 239, 125, 126, -1, 126, 240, 239, -1, + 240, 126, 127, -1, 127, 241, 240, -1, + 241, 242, 243, -1, 242, 241, 127, -1, + 242, 127, 128, -1, 242, 128, 131, -1, + 131, 243, 242, -1, 244, 245, 246, -1, + 247, 244, 248, -1, 247, 245, 244, -1, + 247, 249, 245, -1, 247, 248, 249, -1, + 250, 251, 252, -1, 250, 253, 251, -1, + 250, 254, 253, -1, 250, 252, 254, -1, + 255, 254, 252, -1, 256, 257, 258, -1, + 256, 259, 257, -1, 256, 260, 259, -1, + 256, 258, 260, -1, 261, 260, 258, -1, + 262, 263, 264, -1, 264, 265, 262, -1, + 265, 264, 266, -1, 266, 267, 265, -1, + 267, 266, 268, -1, 268, 269, 267, -1, + 269, 268, 270, -1, 270, 271, 269, -1, + 271, 270, 272, -1, 272, 273, 271, -1, + 273, 272, 274, -1, 274, 275, 273, -1, + 275, 274, 276, -1, 276, 277, 275, -1, + 277, 276, 278, -1, 278, 279, 277, -1, + 279, 278, 280, -1, 280, 281, 279, -1, + 281, 280, 282, -1, 282, 283, 281, -1, + 283, 282, 284, -1, 284, 285, 283, -1, + 285, 284, 286, -1, 286, 287, 285, -1, + 287, 286, 288, -1, 288, 289, 287, -1, + 289, 288, 290, -1, 290, 291, 289, -1, + 291, 290, 292, -1, 292, 293, 291, -1, + 293, 292, 294, -1, 294, 295, 293, -1, + 295, 294, 296, -1, 296, 297, 295, -1, + 297, 296, 298, -1, 298, 299, 297, -1, + 299, 298, 300, -1, 300, 301, 299, -1, + 300, 302, 301, -1, 302, 300, 303, -1, + 303, 304, 302, -1, 304, 303, 305, -1, + 305, 306, 304, -1, 306, 305, 307, -1, + 307, 308, 306, -1, 308, 307, 309, -1, + 309, 310, 308, -1, 310, 309, 311, -1, + 311, 312, 310, -1, 312, 311, 313, -1, + 313, 314, 312, -1, 314, 313, 315, -1, + 315, 316, 314, -1, 316, 315, 317, -1, + 317, 318, 316, -1, 318, 317, 319, -1, + 319, 320, 318, -1, 320, 319, 321, -1, + 321, 322, 320, -1, 322, 321, 323, -1, + 323, 324, 322, -1, 324, 323, 325, -1, + 325, 326, 324, -1, 326, 325, 327, -1, + 327, 328, 326, -1, 328, 327, 329, -1, + 329, 330, 328, -1, 330, 329, 331, -1, + 331, 332, 330, -1, 332, 331, 333, -1, + 333, 334, 332, -1, 334, 333, 335, -1, + 335, 336, 334, -1, 336, 335, 337, -1, + 337, 338, 336, -1, 338, 337, 339, -1, + 339, 261, 338, -1, 339, 260, 261, -1, + 339, 340, 260, -1, 340, 339, 337, -1, + 337, 341, 340, -1, 341, 337, 335, -1, + 335, 342, 341, -1, 342, 335, 333, -1, + 333, 343, 342, -1, 343, 333, 331, -1, + 331, 344, 343, -1, 344, 331, 329, -1, + 329, 345, 344, -1, 345, 329, 327, -1, + 327, 346, 345, -1, 346, 327, 325, -1, + 325, 347, 346, -1, 347, 325, 323, -1, + 323, 348, 347, -1, 348, 323, 321, -1, + 321, 349, 348, -1, 349, 321, 319, -1, + 319, 350, 349, -1, 350, 319, 317, -1, + 317, 351, 350, -1, 351, 317, 315, -1, + 315, 352, 351, -1, 352, 315, 313, -1, + 313, 353, 352, -1, 353, 313, 311, -1, + 311, 354, 353, -1, 354, 311, 309, -1, + 309, 355, 354, -1, 355, 309, 307, -1, + 307, 356, 355, -1, 356, 307, 305, -1, + 305, 357, 356, -1, 357, 305, 303, -1, + 303, 358, 357, -1, 358, 303, 300, -1, + 358, 300, 298, -1, 298, 359, 358, -1, + 359, 298, 296, -1, 296, 360, 359, -1, + 360, 296, 294, -1, 294, 361, 360, -1, + 361, 294, 292, -1, 292, 362, 361, -1, + 362, 292, 290, -1, 290, 363, 362, -1, + 363, 290, 288, -1, 288, 364, 363, -1, + 364, 288, 286, -1, 286, 365, 364, -1, + 365, 286, 284, -1, 284, 366, 365, -1, + 366, 284, 282, -1, 282, 367, 366, -1, + 367, 282, 280, -1, 280, 368, 367, -1, + 368, 280, 278, -1, 278, 369, 368, -1, + 369, 278, 276, -1, 276, 370, 369, -1, + 370, 276, 274, -1, 274, 371, 370, -1, + 371, 274, 272, -1, 272, 372, 371, -1, + 372, 272, 270, -1, 270, 373, 372, -1, + 373, 270, 268, -1, 268, 374, 373, -1, + 374, 268, 266, -1, 266, 375, 374, -1, + 375, 266, 264, -1, 264, 376, 375, -1, + 376, 264, 263, -1, 263, 252, 376, -1, + 263, 255, 252, -1, 263, 262, 255, -1, + 255, 262, 377, -1, 255, 377, 249, -1, + 249, 378, 255, -1, 378, 249, 248, -1, + 378, 248, 244, -1, 378, 244, 379, -1, + 379, 255, 378, -1, 379, 254, 255, -1, + 254, 379, 244, -1, 244, 253, 254, -1, + 246, 380, 243, -1, 131, 381, 382, -1, + 381, 131, 132, -1, 381, 132, 133, -1, + 381, 133, 135, -1, 135, 382, 381, -1, + 135, 383, 382, -1, 383, 135, 134, -1, + 383, 134, 384, -1, 384, 382, 383, -1, + 384, 385, 382, -1, 384, 134, 385, -1, + 386, 385, 134, -1, 134, 387, 386, -1, + 387, 134, 136, -1, 136, 388, 387, -1, + 388, 136, 137, -1, 137, 389, 388, -1, + 389, 137, 138, -1, 138, 390, 389, -1, + 390, 138, 139, -1, 139, 391, 390, -1, + 391, 139, 140, -1, 140, 392, 391, -1, + 392, 140, 141, -1, 141, 393, 392, -1, + 393, 141, 143, -1, 143, 394, 393, -1, + 394, 143, 145, -1, 145, 395, 394, -1, + 395, 145, 147, -1, 147, 396, 395, -1, + 396, 147, 149, -1, 149, 397, 396, -1, + 397, 149, 151, -1, 151, 398, 397, -1, + 398, 151, 153, -1, 153, 399, 398, -1, + 399, 153, 155, -1, 155, 400, 399, -1, + 400, 155, 157, -1, 157, 401, 400, -1, + 401, 157, 159, -1, 159, 402, 401, -1, + 402, 159, 161, -1, 161, 403, 402, -1, + 403, 161, 163, -1, 163, 404, 403, -1, + 404, 163, 165, -1, 165, 405, 404, -1, + 405, 165, 167, -1, 167, 406, 405, -1, + 406, 167, 169, -1, 169, 407, 406, -1, + 407, 169, 171, -1, 171, 408, 407, -1, + 408, 171, 173, -1, 173, 409, 408, -1, + 409, 173, 175, -1, 175, 410, 409, -1, + 410, 175, 176, -1, 176, 411, 410, -1, + 176, 178, 411, -1, 412, 411, 178, -1, + 412, 178, 413, -1, 413, 414, 412, -1, + 414, 413, 415, -1, 415, 416, 414, -1, + 416, 415, 417, -1, 417, 418, 416, -1, + 418, 417, 419, -1, 419, 420, 418, -1, + 419, 421, 420, -1, 421, 419, 422, -1, + 422, 423, 421, -1, 423, 422, 424, -1, + 424, 425, 423, -1, 425, 424, 426, -1, + 426, 427, 425, -1, 427, 428, 429, -1, + 427, 426, 428, -1, 430, 431, 432, -1, + 430, 433, 431, -1, 433, 430, 428, -1, + 428, 434, 433, -1, 434, 428, 426, -1, + 426, 435, 434, -1, 435, 426, 424, -1, + 424, 436, 435, -1, 436, 424, 422, -1, + 422, 437, 436, -1, 437, 422, 419, -1, + 437, 419, 417, -1, 417, 438, 437, -1, + 438, 417, 415, -1, 415, 439, 438, -1, + 439, 415, 413, -1, 413, 440, 439, -1, + 440, 413, 178, -1, 178, 441, 440, -1, + 441, 178, 177, -1, 177, 179, 441, -1, + 441, 179, 215, -1, 441, 215, 442, -1, + 442, 440, 441, -1, 440, 442, 443, -1, + 443, 439, 440, -1, 439, 443, 444, -1, + 444, 438, 439, -1, 438, 444, 445, -1, + 445, 437, 438, -1, 445, 436, 437, -1, + 436, 445, 446, -1, 446, 435, 436, -1, + 435, 446, 447, -1, 447, 434, 435, -1, + 434, 447, 448, -1, 448, 433, 434, -1, + 433, 448, 449, -1, 449, 431, 433, -1, + 431, 449, 450, -1, 450, 451, 431, -1, + 451, 450, 452, -1, 452, 453, 451, -1, + 453, 452, 454, -1, 454, 455, 453, -1, + 455, 454, 456, -1, 456, 457, 455, -1, + 457, 456, 458, -1, 458, 459, 457, -1, + 459, 458, 460, -1, 460, 461, 459, -1, + 461, 460, 462, -1, 462, 463, 461, -1, + 463, 462, 464, -1, 464, 465, 463, -1, + 465, 464, 466, -1, 466, 467, 465, -1, + 467, 466, 468, -1, 468, 469, 467, -1, + 469, 468, 470, -1, 470, 471, 469, -1, + 471, 470, 472, -1, 472, 473, 471, -1, + 473, 472, 474, -1, 474, 475, 473, -1, + 475, 474, 476, -1, 476, 477, 475, -1, + 477, 476, 478, -1, 478, 479, 477, -1, + 479, 478, 480, -1, 480, 481, 479, -1, + 481, 480, 482, -1, 482, 483, 481, -1, + 483, 482, 484, -1, 484, 485, 483, -1, + 485, 484, 486, -1, 485, 486, 487, -1, + 485, 487, 488, -1, 488, 483, 485, -1, + 483, 488, 489, -1, 489, 481, 483, -1, + 481, 489, 490, -1, 490, 479, 481, -1, + 479, 490, 491, -1, 491, 477, 479, -1, + 477, 491, 492, -1, 492, 475, 477, -1, + 475, 492, 493, -1, 493, 473, 475, -1, + 473, 493, 494, -1, 494, 471, 473, -1, + 471, 494, 495, -1, 495, 469, 471, -1, + 469, 495, 496, -1, 496, 467, 469, -1, + 467, 496, 497, -1, 497, 465, 467, -1, + 465, 497, 498, -1, 498, 463, 465, -1, + 463, 498, 499, -1, 499, 461, 463, -1, + 461, 499, 500, -1, 500, 459, 461, -1, + 459, 500, 501, -1, 501, 457, 459, -1, + 457, 501, 502, -1, 502, 455, 457, -1, + 455, 502, 503, -1, 503, 453, 455, -1, + 453, 503, 504, -1, 504, 451, 453, -1, + 451, 504, 505, -1, 505, 431, 451, -1, + 505, 432, 431, -1, 505, 506, 432, -1, + 506, 505, 504, -1, 504, 507, 506, -1, + 507, 504, 503, -1, 503, 508, 507, -1, + 508, 503, 502, -1, 502, 509, 508, -1, + 509, 502, 501, -1, 501, 510, 509, -1, + 510, 501, 500, -1, 500, 511, 510, -1, + 511, 500, 499, -1, 499, 512, 511, -1, + 512, 499, 498, -1, 498, 513, 512, -1, + 513, 498, 497, -1, 497, 514, 513, -1, + 514, 497, 496, -1, 496, 515, 514, -1, + 515, 496, 495, -1, 495, 516, 515, -1, + 516, 495, 494, -1, 494, 517, 516, -1, + 517, 494, 493, -1, 493, 518, 517, -1, + 518, 493, 492, -1, 492, 519, 518, -1, + 519, 492, 491, -1, 491, 520, 519, -1, + 520, 491, 490, -1, 490, 521, 520, -1, + 521, 490, 489, -1, 489, 522, 521, -1, + 522, 489, 488, -1, 488, 487, 522, -1, + 523, 524, 525, -1, 525, 526, 523, -1, + 526, 525, 527, -1, 527, 528, 526, -1, + 528, 527, 529, -1, 529, 530, 528, -1, + 530, 529, 531, -1, 531, 532, 530, -1, + 533, 534, 532, -1, 532, 531, 533, -1, + 535, 536, 537, -1, 537, 538, 535, -1, + 538, 537, 539, -1, 539, 540, 538, -1, + 540, 539, 541, -1, 541, 542, 540, -1, + 542, 541, 543, -1, 543, 544, 542, -1, + 544, 543, 545, -1, 545, 546, 544, -1, + 546, 545, 547, -1, 547, 548, 546, -1, + 548, 547, 549, -1, 549, 550, 548, -1, + 551, 552, 553, -1, 554, 555, 556, -1, + 556, 557, 554, -1, 557, 556, 558, -1, + 558, 559, 557, -1, 559, 558, 560, -1, + 560, 561, 559, -1, 561, 560, 562, -1, + 562, 563, 561, -1, 563, 562, 564, -1, + 564, 565, 563, -1, 565, 564, 566, -1, + 566, 567, 565, -1, 567, 566, 568, -1, + 568, 569, 567, -1, 569, 568, 570, -1, + 570, 571, 569, -1, 571, 570, 572, -1, + 572, 573, 571, -1, 573, 572, 574, -1, + 574, 575, 573, -1, 575, 574, 576, -1, + 576, 577, 575, -1, 577, 576, 578, -1, + 578, 579, 577, -1, 579, 578, 580, -1, + 581, 582, 583, -1, 583, 584, 581, -1, + 584, 583, 585, -1, 585, 586, 584, -1, + 586, 585, 587, -1, 587, 588, 586, -1, + 588, 587, 589, -1, 589, 590, 588, -1, + 590, 589, 591, -1, 591, 592, 590, -1, + 592, 591, 593, -1, 593, 594, 592, -1, + 594, 593, 595, -1, 595, 596, 594, -1, + 596, 595, 597, -1, 597, 598, 596, -1, + 598, 597, 599, -1, 599, 600, 598, -1, + 600, 599, 601, -1, 601, 602, 600, -1, + 602, 601, 603, -1, 603, 604, 602, -1, + 604, 603, 605, -1, 605, 606, 604, -1, + 606, 605, 607, -1, 608, 609, 610, -1, + 609, 608, 611, -1, 611, 612, 609, -1, + 612, 611, 613, -1, 613, 614, 612, -1, + 614, 613, 615, -1, 615, 616, 614, -1, + 616, 615, 617, -1, 617, 618, 616, -1, + 618, 617, 607, -1, 607, 580, 618, -1, + 580, 607, 605, -1, 605, 579, 580, -1, + 579, 605, 603, -1, 603, 577, 579, -1, + 577, 603, 601, -1, 601, 575, 577, -1, + 575, 601, 599, -1, 599, 573, 575, -1, + 573, 599, 597, -1, 597, 571, 573, -1, + 571, 597, 595, -1, 595, 569, 571, -1, + 569, 595, 593, -1, 593, 567, 569, -1, + 567, 593, 591, -1, 591, 565, 567, -1, + 565, 591, 589, -1, 589, 563, 565, -1, + 563, 589, 587, -1, 587, 561, 563, -1, + 561, 587, 585, -1, 585, 559, 561, -1, + 559, 585, 583, -1, 583, 557, 559, -1, + 557, 583, 582, -1, 582, 554, 557, -1, + 582, 619, 554, -1, 582, 581, 619, -1, + 620, 619, 581, -1, 581, 621, 620, -1, + 621, 581, 584, -1, 584, 622, 621, -1, + 622, 584, 586, -1, 586, 623, 622, -1, + 623, 586, 588, -1, 588, 624, 623, -1, + 624, 588, 590, -1, 590, 625, 624, -1, + 625, 590, 592, -1, 592, 626, 625, -1, + 626, 592, 594, -1, 594, 627, 626, -1, + 627, 594, 596, -1, 596, 628, 627, -1, + 628, 596, 598, -1, 598, 629, 628, -1, + 629, 598, 600, -1, 600, 630, 629, -1, + 630, 600, 602, -1, 602, 631, 630, -1, + 631, 602, 604, -1, 604, 632, 631, -1, + 632, 604, 606, -1, 606, 633, 632, -1, + 633, 606, 607, -1, 607, 634, 633, -1, + 634, 607, 617, -1, 617, 635, 634, -1, + 635, 617, 615, -1, 615, 636, 635, -1, + 636, 615, 613, -1, 613, 637, 636, -1, + 637, 613, 611, -1, 611, 638, 637, -1, + 638, 611, 608, -1, 608, 639, 638, -1, + 639, 608, 610, -1, 610, 640, 639, -1, + 640, 610, 641, -1, 641, 642, 640, -1, + 642, 641, 643, -1, 643, 644, 642, -1, + 644, 643, 645, -1, 645, 646, 644, -1, + 646, 645, 647, -1, 647, 648, 646, -1, + 648, 647, 649, -1, 649, 650, 648, -1, + 650, 649, 651, -1, 651, 652, 650, -1, + 652, 651, 653, -1, 653, 654, 652, -1, + 654, 653, 655, -1, 655, 656, 654, -1, + 656, 655, 553, -1, 553, 552, 656, -1, + 657, 656, 552, -1, 552, 658, 657, -1, + 552, 551, 658, -1, 659, 660, 661, -1, + 659, 661, 662, -1, 662, 663, 659, -1, + 663, 662, 664, -1, 664, 665, 663, -1, + 665, 664, 666, -1, 666, 667, 665, -1, + 666, 668, 667, -1, 668, 666, 669, -1, + 669, 670, 668, -1, 670, 669, 671, -1, + 671, 672, 670, -1, 673, 674, 675, -1, + 673, 676, 674, -1, 673, 677, 676, -1, + 673, 675, 677, -1, 675, 678, 677, -1, + 675, 679, 678, -1, 679, 675, 680, -1, + 680, 681, 679, -1, 681, 680, 682, -1, + 682, 683, 681, -1, 683, 682, 684, -1, + 684, 685, 683, -1, 685, 684, 686, -1, + 686, 687, 685, -1, 687, 686, 688, -1, + 688, 689, 687, -1, 689, 688, 690, -1, + 690, 691, 689, -1, 691, 690, 692, -1, + 692, 693, 691, -1, 693, 692, 694, -1, + 694, 695, 693, -1, 695, 694, 696, -1, + 696, 697, 695, -1, 697, 696, 698, -1, + 698, 699, 697, -1, 699, 698, 700, -1, + 700, 701, 699, -1, 701, 700, 702, -1, + 702, 703, 701, -1, 703, 702, 704, -1, + 704, 705, 703, -1, 705, 704, 706, -1, + 706, 707, 705, -1, 707, 706, 708, -1, + 708, 709, 707, -1, 709, 708, 710, -1, + 710, 711, 709, -1, 711, 710, 712, -1, + 712, 713, 711, -1, 714, 715, 716, -1, + 715, 714, 717, -1, 717, 718, 715, -1, + 718, 717, 719, -1, 719, 720, 718, -1, + 720, 719, 721, -1, 721, 722, 720, -1, + 722, 721, 723, -1, 723, 724, 722, -1, + 724, 723, 725, -1, 725, 726, 724, -1, + 726, 725, 727, -1, 727, 728, 726, -1, + 728, 727, 729, -1, 729, 730, 728, -1, + 730, 729, 731, -1, 731, 732, 730, -1, + 732, 731, 733, -1, 733, 734, 732, -1, + 734, 733, 735, -1, 735, 736, 734, -1, + 736, 735, 737, -1, 737, 738, 736, -1, + 738, 737, 739, -1, 739, 740, 738, -1, + 740, 739, 741, -1, 741, 742, 740, -1, + 742, 741, 743, -1, 743, 744, 742, -1, + 744, 743, 745, -1, 745, 746, 744, -1, + 746, 745, 747, -1, 747, 748, 746, -1, + 748, 747, 749, -1, 749, 750, 748, -1, + 751, 752, 750, -1, 750, 749, 751, -1, + 753, 754, 755, -1, 753, 755, 756, -1, + 753, 756, 751, -1, 753, 751, 749, -1, + 749, 754, 753, -1, 754, 749, 747, -1, + 747, 757, 754, -1, 757, 747, 745, -1, + 745, 758, 757, -1, 758, 745, 743, -1, + 743, 759, 758, -1, 759, 743, 741, -1, + 741, 760, 759, -1, 760, 741, 739, -1, + 739, 761, 760, -1, 761, 739, 737, -1, + 737, 762, 761, -1, 762, 737, 735, -1, + 735, 763, 762, -1, 763, 735, 733, -1, + 733, 764, 763, -1, 764, 733, 731, -1, + 731, 765, 764, -1, 765, 731, 729, -1, + 729, 766, 765, -1, 766, 729, 727, -1, + 727, 767, 766, -1, 767, 727, 725, -1, + 725, 768, 767, -1, 768, 725, 723, -1, + 723, 769, 768, -1, 769, 723, 721, -1, + 721, 770, 769, -1, 770, 721, 719, -1, + 719, 771, 770, -1, 771, 719, 717, -1, + 717, 772, 771, -1, 772, 717, 714, -1, + 714, 773, 772, -1, 773, 714, 716, -1, + 716, 774, 773, -1, 774, 716, 713, -1, + 775, 713, 716, -1, 713, 775, 776, -1, + 776, 711, 713, -1, 711, 776, 777, -1, + 777, 709, 711, -1, 709, 777, 778, -1, + 778, 707, 709, -1, 707, 778, 779, -1, + 779, 705, 707, -1, 705, 779, 780, -1, + 780, 703, 705, -1, 703, 780, 781, -1, + 781, 701, 703, -1, 701, 781, 782, -1, + 782, 699, 701, -1, 699, 782, 783, -1, + 783, 697, 699, -1, 697, 783, 784, -1, + 784, 695, 697, -1, 695, 784, 785, -1, + 785, 693, 695, -1, 693, 785, 786, -1, + 786, 691, 693, -1, 691, 786, 787, -1, + 787, 689, 691, -1, 689, 787, 788, -1, + 788, 687, 689, -1, 687, 788, 789, -1, + 789, 685, 687, -1, 685, 789, 790, -1, + 790, 683, 685, -1, 683, 790, 791, -1, + 791, 681, 683, -1, 681, 791, 792, -1, + 792, 679, 681, -1, 679, 792, 793, -1, + 793, 678, 679, -1, 794, 795, 678, -1, + 678, 796, 794, -1, 678, 793, 796, -1, + 797, 798, 799, -1, 800, 801, 798, -1, + 801, 800, 802, -1, 803, 804, 805, -1, + 806, 807, 808, -1, 808, 809, 806, -1, + 809, 808, 810, -1, 810, 811, 809, -1, + 811, 810, 812, -1, 812, 813, 811, -1, + 813, 812, 814, -1, 814, 815, 813, -1, + 815, 814, 816, -1, 816, 817, 815, -1, + 817, 816, 818, -1, 818, 819, 817, -1, + 819, 818, 820, -1, 820, 821, 819, -1, + 821, 820, 822, -1, 822, 823, 821, -1, + 823, 822, 824, -1, 824, 825, 823, -1, + 825, 824, 826, -1, 826, 827, 825, -1, + 827, 826, 828, -1, 828, 829, 827, -1, + 829, 828, 830, -1, 830, 831, 829, -1, + 831, 830, 832, -1, 832, 833, 831, -1, + 833, 832, 834, -1, 834, 835, 833, -1, + 835, 834, 836, -1, 836, 837, 835, -1, + 837, 836, 838, -1, 838, 839, 837, -1, + 839, 838, 840, -1, 840, 841, 839, -1, + 841, 840, 842, -1, 842, 843, 841, -1, + 844, 845, 843, -1, 843, 842, 844, -1, + 846, 844, 842, -1, 842, 847, 846, -1, + 847, 842, 840, -1, 840, 848, 847, -1, + 848, 840, 838, -1, 838, 849, 848, -1, + 849, 838, 836, -1, 836, 850, 849, -1, + 850, 836, 834, -1, 834, 851, 850, -1, + 851, 834, 832, -1, 832, 852, 851, -1, + 852, 832, 830, -1, 830, 853, 852, -1, + 853, 830, 828, -1, 828, 854, 853, -1, + 854, 828, 826, -1, 826, 855, 854, -1, + 855, 826, 824, -1, 824, 856, 855, -1, + 856, 824, 822, -1, 822, 857, 856, -1, + 857, 822, 820, -1, 820, 858, 857, -1, + 858, 820, 818, -1, 818, 859, 858, -1, + 859, 818, 816, -1, 816, 860, 859, -1, + 860, 816, 814, -1, 814, 861, 860, -1, + 861, 814, 812, -1, 812, 862, 861, -1, + 862, 812, 810, -1, 810, 863, 862, -1, + 863, 810, 808, -1, 808, 864, 863, -1, + 864, 808, 807, -1, 807, 865, 864, -1, + 866, 867, 868, -1, 867, 866, 869, -1, + 869, 870, 867, -1, 870, 869, 871, -1, + 871, 872, 870, -1, 872, 871, 873, -1, + 873, 874, 872, -1, 874, 873, 875, -1, + 875, 876, 874, -1, 876, 875, 877, -1, + 877, 878, 876, -1, 878, 877, 879, -1, + 879, 880, 878, -1, 880, 879, 881, -1, + 881, 882, 880, -1, 882, 881, 883, -1, + 883, 884, 882, -1, 884, 883, 885, -1, + 885, 886, 884, -1, 886, 885, 887, -1, + 887, 888, 886, -1, 888, 887, 889, -1, + 889, 890, 888, -1, 890, 889, 891, -1, + 891, 892, 890, -1, 892, 891, 893, -1, + 893, 894, 892, -1, 894, 893, 895, -1, + 895, 896, 894, -1, 896, 895, 897, -1, + 897, 898, 896, -1, 898, 897, 899, -1, + 899, 900, 898, -1, 900, 899, 901, -1, + 901, 902, 900, -1, 902, 901, 903, -1, + 903, 904, 902, -1, 905, 906, 904, -1, + 905, 904, 907, -1, 907, 908, 905, -1, + 908, 907, 909, -1, 909, 910, 908, -1, + 910, 909, 911, -1, 911, 912, 910, -1, + 912, 911, 913, -1, 913, 914, 912, -1, + 913, 915, 914, -1, 915, 913, 916, -1, + 916, 917, 915, -1, 917, 916, 918, -1, + 918, 919, 917, -1, 919, 918, 920, -1, + 920, 921, 919, -1, 922, 923, 924, -1, + 924, 925, 922, -1, 925, 924, 926, -1, + 926, 927, 925, -1, 927, 926, 928, -1, + 928, 929, 927, -1, 929, 928, 930, -1, + 930, 931, 929, -1, 931, 930, 932, -1, + 932, 933, 931, -1, 933, 932, 934, -1, + 934, 935, 933, -1, 935, 934, 936, -1, + 936, 937, 935, -1, 937, 936, 938, -1, + 938, 939, 937, -1, 939, 938, 940, -1, + 940, 941, 939, -1, 941, 940, 942, -1, + 942, 943, 941, -1, 943, 942, 944, -1, + 944, 945, 943, -1, 945, 944, 946, -1, + 946, 947, 945, -1, 947, 946, 948, -1, + 948, 949, 947, -1, 949, 948, 950, -1, + 950, 951, 949, -1, 951, 950, 952, -1, + 952, 953, 951, -1, 953, 952, 954, -1, + 954, 955, 953, -1, 955, 954, 956, -1, + 956, 957, 955, -1, 957, 956, 958, -1, + 958, 959, 957, -1, 959, 958, 960, -1, + 960, 961, 959, -1, 961, 960, 962, -1, + 962, 963, 961, -1, 963, 962, 921, -1, + 921, 920, 963, -1, 920, 964, 963, -1, + 920, 965, 964, -1, 965, 920, 918, -1, + 918, 966, 965, -1, 966, 918, 916, -1, + 916, 967, 966, -1, 967, 916, 913, -1, + 967, 913, 911, -1, 911, 968, 967, -1, + 968, 911, 909, -1, 909, 969, 968, -1, + 969, 909, 907, -1, 907, 970, 969, -1, + 970, 907, 904, -1, 904, 903, 970, -1, + 970, 903, 971, -1, 970, 971, 972, -1, + 972, 969, 970, -1, 969, 972, 973, -1, + 973, 968, 969, -1, 968, 973, 974, -1, + 974, 967, 968, -1, 974, 966, 967, -1, + 966, 974, 975, -1, 975, 965, 966, -1, + 965, 975, 976, -1, 976, 964, 965, -1, + 964, 976, 977, -1, 964, 977, 978, -1, + 979, 980, 981, -1, 979, 977, 980, -1, + 979, 978, 977, -1, 979, 982, 978, -1, + 982, 979, 981, -1, 981, 983, 982, -1, + 983, 981, 984, -1, 984, 985, 983, -1, + 985, 984, 986, -1, 986, 987, 985, -1, + 987, 986, 988, -1, 988, 989, 987, -1, + 989, 988, 990, -1, 990, 991, 989, -1, + 991, 990, 992, -1, 992, 993, 991, -1, + 993, 992, 994, -1, 994, 995, 993, -1, + 995, 994, 996, -1, 996, 997, 995, -1, + 997, 996, 998, -1, 998, 999, 997, -1, + 999, 998, 1000, -1, 1000, 1001, 999, -1, + 1001, 1000, 1002, -1, 1002, 1003, 1001, -1, + 1003, 1002, 1004, -1, 1004, 1005, 1003, -1, + 1005, 1004, 1006, -1, 1006, 1007, 1005, -1, + 1007, 1006, 1008, -1, 1008, 1009, 1007, -1, + 1009, 1008, 1010, -1, 1010, 1011, 1009, -1, + 1011, 1010, 1012, -1, 1012, 1013, 1011, -1, + 1013, 1012, 1014, -1, 1014, 1015, 1013, -1, + 1015, 1014, 1016, -1, 1016, 1017, 1015, -1, + 1017, 1016, 1018, -1, 1018, 1019, 1017, -1, + 1019, 1018, 865, -1, 865, 807, 1019, -1, + 1019, 807, 1020, -1, 1020, 1017, 1019, -1, + 1017, 1020, 1021, -1, 1021, 1015, 1017, -1, + 1015, 1021, 1022, -1, 1022, 1013, 1015, -1, + 1013, 1022, 1023, -1, 1023, 1011, 1013, -1, + 1011, 1023, 1024, -1, 1024, 1009, 1011, -1, + 1009, 1024, 1025, -1, 1025, 1007, 1009, -1, + 1007, 1025, 1026, -1, 1026, 1005, 1007, -1, + 1005, 1026, 1027, -1, 1027, 1003, 1005, -1, + 1003, 1027, 1028, -1, 1028, 1001, 1003, -1, + 1001, 1028, 1029, -1, 1029, 999, 1001, -1, + 999, 1029, 1030, -1, 1030, 997, 999, -1, + 997, 1030, 1031, -1, 1031, 995, 997, -1, + 995, 1031, 1032, -1, 1032, 993, 995, -1, + 993, 1032, 1033, -1, 1033, 991, 993, -1, + 991, 1033, 1034, -1, 1034, 989, 991, -1, + 989, 1034, 1035, -1, 1035, 987, 989, -1, + 987, 1035, 1036, -1, 1036, 985, 987, -1, + 985, 1036, 1037, -1, 1037, 983, 985, -1, + 983, 1037, 1038, -1, 1038, 982, 983, -1, + 982, 1038, 1039, -1, 1039, 978, 982, -1, + 978, 1039, 1040, -1, 1040, 964, 978, -1, + 1040, 963, 964, -1, 1040, 961, 963, -1, + 961, 1040, 1039, -1, 1039, 959, 961, -1, + 959, 1039, 1038, -1, 1038, 957, 959, -1, + 957, 1038, 1037, -1, 1037, 955, 957, -1, + 955, 1037, 1036, -1, 1036, 953, 955, -1, + 953, 1036, 1035, -1, 1035, 951, 953, -1, + 951, 1035, 1034, -1, 1034, 949, 951, -1, + 949, 1034, 1033, -1, 1033, 947, 949, -1, + 947, 1033, 1032, -1, 1032, 945, 947, -1, + 945, 1032, 1031, -1, 1031, 943, 945, -1, + 943, 1031, 1030, -1, 1030, 941, 943, -1, + 941, 1030, 1029, -1, 1029, 939, 941, -1, + 939, 1029, 1028, -1, 1028, 937, 939, -1, + 937, 1028, 1027, -1, 1027, 935, 937, -1, + 935, 1027, 1026, -1, 1026, 933, 935, -1, + 933, 1026, 1025, -1, 1025, 931, 933, -1, + 931, 1025, 1024, -1, 1024, 929, 931, -1, + 929, 1024, 1023, -1, 1023, 927, 929, -1, + 927, 1023, 1022, -1, 1022, 925, 927, -1, + 925, 1022, 1021, -1, 1021, 922, 925, -1, + 922, 1021, 1020, -1, 1020, 923, 922, -1, + 923, 1020, 807, -1, 807, 806, 923, -1, + 1041, 923, 806, -1, 806, 1042, 1041, -1, + 1042, 806, 809, -1, 809, 1043, 1042, -1, + 1043, 809, 811, -1, 811, 1044, 1043, -1, + 1044, 811, 813, -1, 813, 1045, 1044, -1, + 1045, 813, 815, -1, 815, 1046, 1045, -1, + 1046, 815, 817, -1, 817, 1047, 1046, -1, + 1047, 817, 819, -1, 819, 1048, 1047, -1, + 1048, 819, 821, -1, 821, 1049, 1048, -1, + 1049, 821, 823, -1, 823, 1050, 1049, -1, + 1050, 823, 825, -1, 825, 1051, 1050, -1, + 1051, 825, 827, -1, 827, 1052, 1051, -1, + 1052, 827, 829, -1, 829, 1053, 1052, -1, + 1053, 829, 831, -1, 831, 1054, 1053, -1, + 1054, 831, 833, -1, 833, 1055, 1054, -1, + 1055, 833, 835, -1, 835, 1056, 1055, -1, + 1056, 835, 837, -1, 837, 1057, 1056, -1, + 1057, 837, 839, -1, 839, 1058, 1057, -1, + 1058, 839, 841, -1, 841, 1059, 1058, -1, + 1059, 841, 843, -1, 843, 1060, 1059, -1, + 1060, 843, 845, -1, 845, 1061, 1060, -1, + 1061, 845, 803, -1, 803, 805, 1061, -1, + 1062, 1063, 1064, -1, 1065, 1066, 1067, -1, + 1067, 1068, 1065, -1, 1068, 1067, 1069, -1, + 1069, 1070, 1068, -1, 1070, 1069, 1071, -1, + 1071, 1072, 1070, -1, 1072, 1071, 1073, -1, + 1073, 1074, 1072, -1, 1074, 1073, 1075, -1, + 1075, 1076, 1074, -1, 1076, 1075, 1077, -1, + 1077, 1078, 1076, -1, 1078, 1077, 1079, -1, + 1079, 1080, 1078, -1, 1080, 1079, 1081, -1, + 1081, 1082, 1080, -1, 1082, 1081, 1083, -1, + 1083, 1084, 1082, -1, 1084, 1083, 1085, -1, + 1085, 1086, 1084, -1, 1086, 1085, 1087, -1, + 1087, 1088, 1086, -1, 1088, 1087, 1089, -1, + 1089, 1090, 1088, -1, 1090, 1089, 1091, -1, + 1091, 1092, 1090, -1, 1092, 1091, 1093, -1, + 1093, 1094, 1092, -1, 1094, 1093, 1095, -1, + 1095, 1096, 1094, -1, 1096, 1095, 1097, -1, + 1097, 1098, 1096, -1, 1098, 1097, 1099, -1, + 1099, 1100, 1098, -1, 1100, 1099, 1101, -1, + 1101, 1102, 1100, -1, 1102, 1101, 1103, -1, + 1103, 1104, 1102, -1, 1104, 1103, 1105, -1, + 1105, 1106, 1104, -1, 1106, 1105, 1107, -1, + 1107, 1108, 1106, -1, 1108, 1107, 1109, -1, + 1109, 1110, 1108, -1, 1110, 1109, 1111, -1, + 1111, 1112, 1110, -1, 1112, 1111, 1113, -1, + 1113, 1114, 1112, -1, 1114, 1113, 1115, -1, + 1115, 1116, 1114, -1, 1116, 1115, 1117, -1, + 1117, 1118, 1116, -1, 1118, 1117, 1119, -1, + 1119, 1120, 1118, -1, 1120, 1119, 1121, -1, + 1121, 1122, 1120, -1, 1122, 1121, 1123, -1, + 1123, 1124, 1122, -1, 1124, 1123, 1125, -1, + 1125, 1126, 1124, -1, 1126, 1125, 1127, -1, + 1127, 1128, 1126, -1, 1128, 1127, 1129, -1, + 1129, 1130, 1128, -1, 1130, 1129, 1131, -1, + 1131, 1132, 1130, -1, 1132, 1131, 1133, -1, + 1133, 1134, 1132, -1, 1134, 1133, 1135, -1, + 1135, 1136, 1134, -1, 1136, 1135, 1137, -1, + 1137, 1138, 1136, -1, 1138, 1137, 1139, -1, + 1139, 1140, 1138, -1, 1140, 1139, 1141, -1, + 1141, 1142, 1140, -1, 1142, 1141, 1143, -1, + 1143, 1144, 1142, -1, 1144, 1143, 1145, -1, + 1145, 1146, 1144, -1, 1146, 1145, 1147, -1, + 1147, 1148, 1146, -1, 1148, 1147, 1149, -1, + 1149, 1150, 1148, -1, 1150, 1149, 1063, -1, + 1063, 1062, 1150, -1, 1151, 1152, 1062, -1, + 1153, 1154, 1155, -1, 1156, 1157, 1158, -1, + 1157, 1156, 1159, -1, 1157, 1159, 1160, -1, + 1161, 1160, 1159, -1, 1161, 1162, 1160, -1, + 1162, 1161, 1163, -1, 1163, 1164, 1162, -1, + 1165, 1166, 1164, -1, 1164, 1163, 1165, -1, + 1167, 1168, 1169, -1, 1170, 1171, 1172, -1, + 1173, 1174, 1175, -1, 1176, 1177, 1178, -1, + 1179, 1178, 1177, -1, 1180, 1181, 1182, -1, + 1182, 1183, 1180, -1, 1184, 1185, 1186, -1, + 1185, 1184, 1183, -1, 1183, 1182, 1185, -1, + 1185, 1182, 1187, -1, 1185, 1187, 1188, -1, + 1188, 1186, 1185, -1, 1186, 1188, 1189, -1, + 1189, 1190, 1186, -1, 1190, 1189, 1191, -1, + 1191, 1192, 1190, -1, 1192, 1191, 1193, -1, + 1193, 1194, 1192, -1, 1194, 1193, 1195, -1, + 1195, 1196, 1194, -1, 1196, 1195, 1197, -1, + 1197, 1198, 1196, -1, 1198, 1197, 1199, -1, + 1199, 1200, 1198, -1, 1200, 1199, 1201, -1, + 1201, 1202, 1200, -1, 1202, 1201, 1203, -1, + 1203, 1204, 1202, -1, 1204, 1203, 1205, -1, + 1205, 1206, 1204, -1, 1206, 1205, 1207, -1, + 1207, 1208, 1206, -1, 1208, 1207, 1209, -1, + 1209, 1210, 1208, -1, 1210, 1209, 1211, -1, + 1211, 1212, 1210, -1, 1212, 1211, 1213, -1, + 1213, 1214, 1212, -1, 1214, 1213, 1215, -1, + 1215, 1216, 1214, -1, 1216, 1215, 1217, -1, + 1217, 1218, 1216, -1, 1218, 1217, 1219, -1, + 1219, 1220, 1218, -1, 1220, 1219, 1221, -1, + 1221, 1222, 1220, -1, 1222, 1221, 1223, -1, + 1223, 1224, 1222, -1, 1224, 1223, 1225, -1, + 1225, 1226, 1224, -1, 1226, 1225, 1227, -1, + 1227, 1228, 1226, -1, 1228, 1227, 1229, -1, + 1229, 1230, 1228, -1, 1230, 1229, 1231, -1, + 1231, 1232, 1230, -1, 1232, 1231, 1233, -1, + 1233, 1234, 1232, -1, 1234, 1233, 1235, -1, + 1235, 1236, 1234, -1, 1236, 1235, 1237, -1, + 1237, 1238, 1236, -1, 1238, 1237, 1239, -1, + 1239, 1240, 1238, -1, 1240, 1239, 1241, -1, + 1241, 1242, 1240, -1, 1242, 1241, 1243, -1, + 1243, 1244, 1242, -1, 1244, 1243, 1245, -1, + 1245, 1246, 1244, -1, 1246, 1245, 1247, -1, + 1247, 1248, 1246, -1, 1248, 1247, 1249, -1, + 1249, 1250, 1248, -1, 1250, 1249, 1251, -1, + 1251, 1252, 1250, -1, 1252, 1251, 1253, -1, + 1253, 1254, 1252, -1, 1254, 1253, 1255, -1, + 1255, 1256, 1254, -1, 1256, 1255, 1257, -1, + 1257, 1258, 1256, -1, 1258, 1257, 1259, -1, + 1259, 1260, 1258, -1, 1260, 1259, 1261, -1, + 1261, 1262, 1260, -1, 1262, 1261, 1263, -1, + 1263, 1264, 1262, -1, 1264, 1263, 1265, -1, + 1265, 1266, 1264, -1, 1266, 1265, 1267, -1, + 1267, 1268, 1266, -1, 1268, 1267, 1269, -1, + 1269, 1270, 1268, -1, 1270, 1269, 1271, -1, + 1271, 1272, 1270, -1, 1272, 1271, 1273, -1, + 1273, 1274, 1272, -1, 1274, 1273, 1275, -1, + 1275, 1276, 1274, -1, 1276, 1275, 1277, -1, + 1277, 1278, 1276, -1, 1278, 1277, 1279, -1, + 1278, 1279, 1280, -1, 1280, 1281, 1278, -1, + 1281, 1280, 1282, -1, 1282, 1283, 1281, -1, + 1283, 1282, 1284, -1, 1284, 1285, 1283, -1, + 1285, 1284, 1286, -1, 1286, 1287, 1285, -1, + 1287, 1286, 1288, -1, 1288, 1289, 1287, -1, + 1289, 1288, 1290, -1, 1290, 1291, 1289, -1, + 1291, 1290, 1292, -1, 1292, 1293, 1291, -1, + 1293, 1292, 1294, -1, 1294, 1295, 1293, -1, + 1295, 1294, 1296, -1, 1296, 1297, 1295, -1, + 1297, 1296, 1298, -1, 1298, 1299, 1297, -1, + 1299, 1298, 1300, -1, 1300, 1301, 1299, -1, + 1301, 1300, 1302, -1, 1302, 1303, 1301, -1, + 1303, 1302, 1304, -1, 1304, 1305, 1303, -1, + 1305, 1304, 1306, -1, 1306, 1307, 1305, -1, + 1307, 1306, 1308, -1, 1308, 1309, 1307, -1, + 1309, 1308, 1310, -1, 1310, 1311, 1309, -1, + 1311, 1310, 1312, -1, 1312, 1313, 1311, -1, + 1313, 1312, 1314, -1, 1314, 1315, 1313, -1, + 1315, 1314, 1316, -1, 1316, 1317, 1315, -1, + 1317, 1316, 1318, -1, 1318, 1319, 1317, -1, + 1319, 1318, 1320, -1, 1320, 1321, 1319, -1, + 1321, 1320, 1322, -1, 1322, 1323, 1321, -1, + 1323, 1322, 1324, -1, 1324, 1325, 1323, -1, + 1325, 1324, 1326, -1, 1326, 1327, 1325, -1, + 1327, 1326, 1328, -1, 1328, 1329, 1327, -1, + 1329, 1328, 1330, -1, 1330, 1331, 1329, -1, + 1331, 1330, 1332, -1, 1332, 1333, 1331, -1, + 1333, 1332, 1334, -1, 1334, 1335, 1333, -1, + 1335, 1334, 1336, -1, 1336, 1337, 1335, -1, + 1337, 1336, 1338, -1, 1338, 1339, 1337, -1, + 1339, 1338, 1340, -1, 1340, 1341, 1339, -1, + 1341, 1340, 1342, -1, 1342, 1343, 1341, -1, + 1343, 1342, 1344, -1, 1344, 1345, 1343, -1, + 1345, 1344, 1346, -1, 1346, 1347, 1345, -1, + 1347, 1346, 1348, -1, 1348, 1349, 1347, -1, + 1349, 1348, 1350, -1, 1350, 1351, 1349, -1, + 1351, 1350, 1352, -1, 1352, 1353, 1351, -1, + 1353, 1352, 1354, -1, 1354, 1355, 1353, -1, + 1355, 1354, 1356, -1, 1356, 1357, 1355, -1, + 1357, 1356, 1358, -1, 1358, 1359, 1357, -1, + 1360, 1361, 1362, -1, 1361, 1360, 1363, -1, + 1361, 1363, 1364, -1, 1365, 1364, 1363, -1, + 1365, 1366, 1364, -1, 1364, 1367, 1368, -1, + 1367, 1364, 1366, -1, 1366, 1369, 1367, -1, + 1369, 1366, 1370, -1, 1370, 1371, 1369, -1, + 1371, 1370, 1372, -1, 1372, 1373, 1371, -1, + 1373, 1372, 1374, -1, 1374, 1375, 1373, -1, + 1375, 1374, 1376, -1, 1376, 1377, 1375, -1, + 1377, 1376, 1359, -1, 1359, 1358, 1377, -1, + 1358, 1378, 1377, -1, 1378, 1358, 1356, -1, + 1356, 1379, 1378, -1, 1379, 1356, 1354, -1, + 1354, 1380, 1379, -1, 1380, 1354, 1352, -1, + 1352, 1381, 1380, -1, 1381, 1352, 1350, -1, + 1350, 1382, 1381, -1, 1382, 1350, 1348, -1, + 1348, 1383, 1382, -1, 1383, 1348, 1346, -1, + 1346, 1384, 1383, -1, 1384, 1346, 1344, -1, + 1344, 1385, 1384, -1, 1385, 1344, 1342, -1, + 1342, 1386, 1385, -1, 1386, 1342, 1340, -1, + 1340, 1387, 1386, -1, 1387, 1340, 1338, -1, + 1338, 1388, 1387, -1, 1388, 1338, 1336, -1, + 1336, 1389, 1388, -1, 1389, 1336, 1334, -1, + 1334, 1390, 1389, -1, 1390, 1334, 1332, -1, + 1332, 1391, 1390, -1, 1391, 1332, 1330, -1, + 1330, 1392, 1391, -1, 1392, 1330, 1328, -1, + 1328, 1393, 1392, -1, 1393, 1328, 1326, -1, + 1326, 1394, 1393, -1, 1394, 1326, 1324, -1, + 1324, 1395, 1394, -1, 1395, 1324, 1322, -1, + 1322, 1396, 1395, -1, 1396, 1322, 1320, -1, + 1320, 1397, 1396, -1, 1397, 1320, 1318, -1, + 1318, 1398, 1397, -1, 1398, 1318, 1316, -1, + 1316, 1399, 1398, -1, 1399, 1316, 1314, -1, + 1314, 1400, 1399, -1, 1400, 1314, 1312, -1, + 1312, 1401, 1400, -1, 1401, 1312, 1310, -1, + 1310, 1402, 1401, -1, 1402, 1310, 1308, -1, + 1308, 1403, 1402, -1, 1403, 1308, 1306, -1, + 1306, 1404, 1403, -1, 1404, 1306, 1304, -1, + 1304, 1405, 1404, -1, 1405, 1304, 1302, -1, + 1302, 1406, 1405, -1, 1406, 1302, 1300, -1, + 1300, 1407, 1406, -1, 1407, 1300, 1298, -1, + 1298, 1408, 1407, -1, 1408, 1298, 1296, -1, + 1296, 1409, 1408, -1, 1409, 1296, 1294, -1, + 1294, 1410, 1409, -1, 1410, 1294, 1292, -1, + 1292, 1411, 1410, -1, 1411, 1292, 1290, -1, + 1290, 1412, 1411, -1, 1412, 1290, 1288, -1, + 1288, 1413, 1412, -1, 1413, 1288, 1286, -1, + 1286, 1414, 1413, -1, 1414, 1286, 1284, -1, + 1284, 1415, 1414, -1, 1415, 1284, 1282, -1, + 1282, 1416, 1415, -1, 1416, 1282, 1280, -1, + 1280, 1417, 1416, -1, 1417, 1280, 1279, -1, + 1279, 1418, 1417, -1, 1279, 1419, 1418, -1, + 1419, 1279, 1277, -1, 1277, 1420, 1419, -1, + 1420, 1277, 1275, -1, 1275, 1421, 1420, -1, + 1421, 1275, 1273, -1, 1273, 1422, 1421, -1, + 1422, 1273, 1271, -1, 1271, 1423, 1422, -1, + 1423, 1271, 1269, -1, 1269, 1424, 1423, -1, + 1424, 1269, 1267, -1, 1267, 1425, 1424, -1, + 1425, 1267, 1265, -1, 1265, 1426, 1425, -1, + 1426, 1265, 1263, -1, 1263, 1427, 1426, -1, + 1427, 1263, 1261, -1, 1261, 1428, 1427, -1, + 1428, 1261, 1259, -1, 1259, 1429, 1428, -1, + 1429, 1259, 1257, -1, 1257, 1430, 1429, -1, + 1430, 1257, 1255, -1, 1255, 1431, 1430, -1, + 1431, 1255, 1253, -1, 1253, 1432, 1431, -1, + 1432, 1253, 1251, -1, 1251, 1433, 1432, -1, + 1433, 1251, 1249, -1, 1249, 1434, 1433, -1, + 1434, 1249, 1247, -1, 1247, 1435, 1434, -1, + 1435, 1247, 1245, -1, 1245, 1436, 1435, -1, + 1436, 1245, 1243, -1, 1243, 1437, 1436, -1, + 1437, 1243, 1241, -1, 1241, 1438, 1437, -1, + 1438, 1241, 1239, -1, 1239, 1439, 1438, -1, + 1439, 1239, 1237, -1, 1237, 1440, 1439, -1, + 1440, 1237, 1235, -1, 1235, 1441, 1440, -1, + 1441, 1235, 1233, -1, 1233, 1442, 1441, -1, + 1442, 1233, 1231, -1, 1231, 1443, 1442, -1, + 1443, 1231, 1229, -1, 1229, 1444, 1443, -1, + 1444, 1229, 1227, -1, 1227, 1445, 1444, -1, + 1445, 1227, 1225, -1, 1225, 1446, 1445, -1, + 1446, 1225, 1223, -1, 1223, 1447, 1446, -1, + 1447, 1223, 1221, -1, 1221, 1448, 1447, -1, + 1448, 1221, 1219, -1, 1219, 1449, 1448, -1, + 1449, 1219, 1217, -1, 1217, 1450, 1449, -1, + 1450, 1217, 1215, -1, 1215, 1451, 1450, -1, + 1451, 1215, 1213, -1, 1213, 1452, 1451, -1, + 1452, 1213, 1211, -1, 1211, 1453, 1452, -1, + 1453, 1211, 1209, -1, 1209, 1454, 1453, -1, + 1454, 1209, 1207, -1, 1207, 1455, 1454, -1, + 1455, 1207, 1205, -1, 1205, 1456, 1455, -1, + 1456, 1205, 1203, -1, 1203, 1457, 1456, -1, + 1457, 1203, 1201, -1, 1201, 1458, 1457, -1, + 1458, 1201, 1199, -1, 1199, 1459, 1458, -1, + 1459, 1199, 1197, -1, 1197, 1460, 1459, -1, + 1461, 1462, 1463, -1, 1461, 1463, 1464, -1, + 1464, 1465, 1461, -1, 1465, 1464, 1466, -1, + 1466, 1467, 1465, -1, 1467, 1466, 1468, -1, + 1468, 1469, 1467, -1, 1469, 1468, 1470, -1, + 1470, 1471, 1469, -1, 1471, 1470, 1472, -1, + 1472, 1473, 1471, -1, 1473, 1472, 1474, -1, + 1474, 1475, 1473, -1, 1475, 1474, 1460, -1, + 1460, 1197, 1475, -1, 1475, 1197, 1195, -1, + 1195, 1473, 1475, -1, 1473, 1195, 1193, -1, + 1193, 1471, 1473, -1, 1471, 1193, 1191, -1, + 1191, 1469, 1471, -1, 1469, 1191, 1189, -1, + 1189, 1467, 1469, -1, 1467, 1189, 1188, -1, + 1188, 1465, 1467, -1, 1465, 1188, 1187, -1, + 1187, 1461, 1465, -1, 1187, 1476, 1461, -1, + 1477, 1478, 1479, -1, 1477, 1479, 1480, -1, + 1477, 1480, 1481, -1, 1477, 1481, 1482, -1, + 1482, 1478, 1477, -1, 1478, 1482, 1476, -1, + 1476, 1483, 1478, -1, 1483, 1476, 1187, -1, + 1483, 1187, 1182, -1, 1483, 1182, 1181, -1, + 1181, 1478, 1483, -1, 1181, 1479, 1478, -1, + 1181, 1180, 1479, -1, 1479, 1180, 1484, -1, + 1479, 1484, 1485, -1, 1485, 1480, 1479, -1, + 1480, 1485, 1486, -1, 1486, 1487, 1480, -1, + 1487, 1486, 1488, -1, 1488, 1489, 1487, -1, + 1489, 1488, 1178, -1, 1178, 1179, 1489, -1, + 1490, 1491, 1492, -1, 1492, 1493, 1490, -1, + 1493, 1492, 1494, -1, 1494, 1495, 1493, -1, + 1495, 1494, 1496, -1, 1496, 1497, 1495, -1, + 1497, 1496, 1498, -1, 1498, 1496, 1499, -1, + 1498, 1499, 1500, -1, 1500, 1501, 1498, -1, + 1502, 1503, 1504, -1, 1504, 1505, 1502, -1, + 1506, 1502, 1505, -1, 1505, 1501, 1506, -1, + 1507, 1508, 1509, -1, 1506, 1509, 1508, -1, + 1509, 1506, 1501, -1, 1501, 1500, 1509, -1, + 1179, 1509, 1500, -1, 1500, 1489, 1179, -1, + 1489, 1500, 1499, -1, 1499, 1487, 1489, -1, + 1487, 1499, 1510, -1, 1510, 1480, 1487, -1, + 1510, 1481, 1480, -1, 1511, 1481, 1510, -1, + 1481, 1511, 1512, -1, 1512, 1482, 1481, -1, + 1482, 1512, 1513, -1, 1513, 1476, 1482, -1, + 1513, 1461, 1476, -1, 1513, 1462, 1461, -1, + 1462, 1513, 1512, -1, 1512, 1514, 1462, -1, + 1514, 1512, 1511, -1, 1511, 1515, 1514, -1, + 1511, 1510, 1515, -1, 1516, 1515, 1510, -1, + 1516, 1510, 1499, -1, 1516, 1499, 1496, -1, + 1516, 1496, 1494, -1, 1494, 1515, 1516, -1, + 1515, 1494, 1492, -1, 1492, 1514, 1515, -1, + 1514, 1492, 1491, -1, 1491, 1462, 1514, -1, + 1491, 1463, 1462, -1, 1491, 1490, 1463, -1, + 1517, 1463, 1490, -1, 1490, 1518, 1517, -1, + 1518, 1490, 1493, -1, 1493, 1519, 1518, -1, + 1519, 1493, 1495, -1, 1495, 1520, 1519, -1, + 1520, 1495, 1497, -1, 1497, 1521, 1520, -1, + 1497, 1498, 1521, -1, 1522, 1521, 1498, -1, + 1522, 1498, 1501, -1, 1501, 1505, 1522, -1, + 1523, 1524, 1522, -1, 1523, 1522, 1505, -1, + 1505, 1504, 1523, -1, 1525, 1526, 1523, -1, + 1525, 1523, 1504, -1, 1504, 1527, 1525, -1, + 1527, 1504, 1503, -1, 1503, 1528, 1527, -1, + 1528, 1503, 1529, -1, 1530, 1529, 1531, -1, + 1530, 1528, 1529, -1, 1530, 1532, 1528, -1, + 1532, 1530, 1531, -1, 1533, 1534, 1535, -1, + 1534, 1533, 1536, -1, 1536, 1537, 1534, -1, + 1537, 1536, 1538, -1, 1538, 1539, 1537, -1, + 1538, 1540, 1539, -1, 1541, 1542, 1543, -1, + 1541, 1543, 1544, -1, 1543, 1545, 1544, -1, + 1545, 1543, 1546, -1, 1546, 1547, 1545, -1, + 1547, 1546, 1548, -1, 1548, 1549, 1547, -1, + 1549, 1548, 1550, -1, 1550, 1551, 1549, -1, + 1551, 1550, 1552, -1, 1552, 1553, 1551, -1, + 1553, 1554, 1555, -1, 1553, 1552, 1554, -1, + 1556, 1557, 1558, -1, 1559, 1557, 1556, -1, + 1559, 1556, 1560, -1, 1556, 1561, 1560, -1, + 1561, 1556, 1562, -1, 1562, 1563, 1561, -1, + 1563, 1562, 1564, -1, 1564, 1565, 1563, -1, + 1565, 1564, 1566, -1, 1566, 1567, 1565, -1, + 1567, 1566, 1568, -1, 1568, 1569, 1567, -1, + 1569, 1568, 1570, -1, 1570, 1571, 1569, -1, + 1571, 1570, 1572, -1, 1572, 1573, 1571, -1, + 1573, 1572, 1574, -1, 1574, 1575, 1573, -1, + 1575, 1574, 1576, -1, 1576, 1577, 1575, -1, + 1577, 1576, 1578, -1, 1578, 1579, 1577, -1, + 1579, 1578, 1580, -1, 1580, 1581, 1579, -1, + 1581, 1580, 1582, -1, 1582, 1583, 1581, -1, + 1583, 1582, 1584, -1, 1584, 1585, 1583, -1, + 1585, 1584, 1586, -1, 1586, 1587, 1585, -1, + 1587, 1586, 1588, -1, 1588, 1589, 1587, -1, + 1589, 1588, 1590, -1, 1590, 1591, 1589, -1, + 1591, 1590, 1592, -1, 1592, 1593, 1591, -1, + 1593, 1592, 1594, -1, 1594, 1595, 1593, -1, + 1595, 1594, 1596, -1, 1596, 1597, 1595, -1, + 1597, 1596, 1598, -1, 1598, 1599, 1597, -1, + 1599, 1598, 1600, -1, 1600, 1601, 1599, -1, + 1601, 1600, 1602, -1, 1602, 1603, 1601, -1, + 1603, 1602, 1604, -1, 1604, 1605, 1603, -1, + 1605, 1604, 1606, -1, 1606, 1607, 1605, -1, + 1607, 1606, 1608, -1, 1608, 1609, 1607, -1, + 1609, 1608, 1610, -1, 1610, 1611, 1609, -1, + 1611, 1610, 1612, -1, 1612, 1613, 1611, -1, + 1613, 1612, 1614, -1, 1614, 1615, 1613, -1, + 1615, 1614, 1616, -1, 1616, 1617, 1615, -1, + 1617, 1616, 1618, -1, 1618, 1619, 1617, -1, + 1619, 1618, 1620, -1, 1620, 1621, 1619, -1, + 1621, 1620, 1622, -1, 1622, 1623, 1621, -1, + 1623, 1622, 1624, -1, 1624, 1625, 1623, -1, + 1625, 1624, 1626, -1, 1626, 1627, 1625, -1, + 1627, 1626, 1628, -1, 1628, 1629, 1627, -1, + 1629, 1628, 1630, -1, 1630, 1631, 1629, -1, + 1631, 1630, 1632, -1, 1632, 1633, 1631, -1, + 1633, 1632, 1634, -1, 1634, 1635, 1633, -1, + 1635, 1634, 1636, -1, 1636, 1637, 1635, -1, + 1637, 1636, 1638, -1, 1638, 1639, 1637, -1, + 1639, 1638, 1640, -1, 1640, 1641, 1639, -1, + 1641, 1640, 1642, -1, 1642, 1643, 1641, -1, + 1643, 1642, 1644, -1, 1644, 1645, 1643, -1, + 1645, 1644, 1646, -1, 1646, 1647, 1645, -1, + 1647, 1646, 1648, -1, 1648, 1649, 1647, -1, + 1649, 1648, 1650, -1, 1650, 1651, 1649, -1, + 1651, 1650, 1652, -1, 1652, 1653, 1651, -1, + 1653, 1652, 1654, -1, 1654, 1655, 1653, -1, + 1655, 1654, 1656, -1, 1656, 1657, 1655, -1, + 1657, 1656, 1658, -1, 1658, 1659, 1657, -1, + 1659, 1658, 1660, -1, 1660, 1661, 1659, -1, + 1661, 1660, 1662, -1, 1662, 1663, 1661, -1, + 1663, 1662, 1664, -1, 1664, 1665, 1663, -1, + 1665, 1664, 1666, -1, 1666, 1667, 1665, -1, + 1667, 1666, 1668, -1, 1668, 1669, 1667, -1, + 1669, 1670, 1671, -1, 1671, 1667, 1669, -1, + 1667, 1671, 1672, -1, 1672, 1665, 1667, -1, + 1665, 1672, 1673, -1, 1673, 1663, 1665, -1, + 1663, 1673, 1674, -1, 1674, 1661, 1663, -1, + 1661, 1674, 1675, -1, 1675, 1659, 1661, -1, + 1659, 1675, 1676, -1, 1676, 1657, 1659, -1, + 1657, 1676, 1677, -1, 1677, 1655, 1657, -1, + 1655, 1677, 1678, -1, 1678, 1653, 1655, -1, + 1653, 1678, 1679, -1, 1679, 1651, 1653, -1, + 1651, 1679, 1680, -1, 1680, 1649, 1651, -1, + 1649, 1680, 1681, -1, 1681, 1647, 1649, -1, + 1647, 1681, 1682, -1, 1682, 1645, 1647, -1, + 1645, 1682, 1683, -1, 1683, 1643, 1645, -1, + 1643, 1683, 1684, -1, 1684, 1641, 1643, -1, + 1641, 1684, 1685, -1, 1685, 1639, 1641, -1, + 1639, 1685, 1686, -1, 1686, 1637, 1639, -1, + 1637, 1686, 1687, -1, 1687, 1635, 1637, -1, + 1635, 1687, 1688, -1, 1688, 1633, 1635, -1, + 1633, 1688, 1689, -1, 1689, 1631, 1633, -1, + 1631, 1689, 1690, -1, 1690, 1629, 1631, -1, + 1629, 1690, 1691, -1, 1691, 1627, 1629, -1, + 1627, 1691, 1692, -1, 1692, 1625, 1627, -1, + 1625, 1692, 1693, -1, 1693, 1623, 1625, -1, + 1623, 1693, 1694, -1, 1694, 1621, 1623, -1, + 1621, 1694, 1695, -1, 1695, 1619, 1621, -1, + 1619, 1695, 1696, -1, 1696, 1617, 1619, -1, + 1617, 1696, 1697, -1, 1697, 1615, 1617, -1, + 1615, 1697, 1698, -1, 1698, 1613, 1615, -1, + 1613, 1698, 1699, -1, 1699, 1611, 1613, -1, + 1611, 1699, 1700, -1, 1700, 1609, 1611, -1, + 1609, 1700, 1701, -1, 1701, 1607, 1609, -1, + 1607, 1701, 1702, -1, 1702, 1605, 1607, -1, + 1605, 1702, 1703, -1, 1703, 1603, 1605, -1, + 1603, 1703, 1704, -1, 1704, 1601, 1603, -1, + 1601, 1704, 1705, -1, 1705, 1599, 1601, -1, + 1599, 1705, 1706, -1, 1706, 1597, 1599, -1, + 1597, 1706, 1707, -1, 1707, 1595, 1597, -1, + 1595, 1707, 1708, -1, 1708, 1593, 1595, -1, + 1593, 1708, 1709, -1, 1709, 1591, 1593, -1, + 1591, 1709, 1710, -1, 1710, 1589, 1591, -1, + 1589, 1710, 1711, -1, 1711, 1587, 1589, -1, + 1587, 1711, 1712, -1, 1712, 1585, 1587, -1, + 1585, 1712, 1713, -1, 1713, 1583, 1585, -1, + 1583, 1713, 1714, -1, 1714, 1581, 1583, -1, + 1581, 1714, 1715, -1, 1715, 1579, 1581, -1, + 1579, 1715, 1716, -1, 1716, 1577, 1579, -1, + 1577, 1716, 1717, -1, 1717, 1575, 1577, -1, + 1575, 1717, 1718, -1, 1718, 1573, 1575, -1, + 1573, 1718, 1554, -1, 1554, 1571, 1573, -1, + 1571, 1554, 1552, -1, 1552, 1569, 1571, -1, + 1569, 1552, 1550, -1, 1550, 1567, 1569, -1, + 1567, 1550, 1548, -1, 1548, 1565, 1567, -1, + 1565, 1548, 1546, -1, 1546, 1563, 1565, -1, + 1563, 1546, 1543, -1, 1543, 1561, 1563, -1, + 1543, 1542, 1561, -1, 1719, 1561, 1542, -1, + 1542, 1720, 1719, -1, 1542, 1541, 1720, -1, + 1541, 1544, 1720, -1, 1544, 1721, 1720, -1, + 1721, 1544, 1545, -1, 1721, 1545, 1722, -1, + 1545, 1723, 1722, -1, 1723, 1545, 1547, -1, + 1547, 1724, 1723, -1, 1724, 1547, 1549, -1, + 1549, 1725, 1724, -1, 1725, 1549, 1551, -1, + 1551, 1726, 1725, -1, 1726, 1551, 1553, -1, + 1553, 1555, 1726, -1, 1555, 1727, 1540, -1, + 1540, 1726, 1555, -1, 1726, 1540, 1538, -1, + 1538, 1725, 1726, -1, 1725, 1538, 1536, -1, + 1536, 1724, 1725, -1, 1724, 1536, 1533, -1, + 1533, 1723, 1724, -1, 1728, 1729, 1723, -1, + 1723, 1533, 1728, -1, 1730, 1728, 1533, -1, + 1730, 1533, 1535, -1, 1535, 1531, 1730, -1, + 1535, 1731, 1531, -1, 1731, 1535, 1534, -1, + 1731, 1534, 1732, -1, 1732, 1531, 1731, -1, + 1732, 1532, 1531, -1, 1532, 1732, 1534, -1, + 1534, 1528, 1532, -1, 1528, 1534, 1537, -1, + 1537, 1527, 1528, -1, 1527, 1537, 1539, -1, + 1539, 1525, 1527, -1, 1539, 1733, 1525, -1, + 1734, 1735, 1736, -1, 1734, 1736, 1737, -1, + 1734, 1737, 1738, -1, 1734, 1738, 1739, -1, + 1739, 1735, 1734, -1, 1735, 1739, 1733, -1, + 1733, 1740, 1735, -1, 1740, 1733, 1539, -1, + 1740, 1539, 1540, -1, 1740, 1540, 1727, -1, + 1727, 1735, 1740, -1, 1727, 1736, 1735, -1, + 1727, 1555, 1736, -1, 1736, 1555, 1554, -1, + 1736, 1554, 1718, -1, 1718, 1737, 1736, -1, + 1737, 1718, 1717, -1, 1717, 1741, 1737, -1, + 1741, 1717, 1716, -1, 1716, 1742, 1741, -1, + 1742, 1716, 1715, -1, 1715, 1743, 1742, -1, + 1743, 1715, 1714, -1, 1714, 1744, 1743, -1, + 1744, 1714, 1713, -1, 1713, 1745, 1744, -1, + 1745, 1713, 1712, -1, 1712, 1746, 1745, -1, + 1746, 1712, 1711, -1, 1711, 1747, 1746, -1, + 1747, 1711, 1710, -1, 1710, 1748, 1747, -1, + 1748, 1710, 1709, -1, 1709, 1749, 1748, -1, + 1749, 1709, 1708, -1, 1708, 1750, 1749, -1, + 1750, 1708, 1707, -1, 1707, 1751, 1750, -1, + 1751, 1707, 1706, -1, 1706, 1752, 1751, -1, + 1752, 1706, 1705, -1, 1705, 1753, 1752, -1, + 1753, 1705, 1704, -1, 1704, 1754, 1753, -1, + 1754, 1704, 1703, -1, 1703, 1755, 1754, -1, + 1755, 1703, 1702, -1, 1702, 1756, 1755, -1, + 1756, 1702, 1701, -1, 1701, 1757, 1756, -1, + 1757, 1701, 1700, -1, 1700, 1758, 1757, -1, + 1758, 1700, 1699, -1, 1699, 1759, 1758, -1, + 1759, 1699, 1698, -1, 1698, 1760, 1759, -1, + 1760, 1698, 1697, -1, 1697, 1761, 1760, -1, + 1761, 1697, 1696, -1, 1696, 1762, 1761, -1, + 1762, 1696, 1695, -1, 1695, 1763, 1762, -1, + 1763, 1695, 1694, -1, 1694, 1764, 1763, -1, + 1764, 1694, 1693, -1, 1693, 1765, 1764, -1, + 1765, 1693, 1692, -1, 1692, 1766, 1765, -1, + 1766, 1692, 1691, -1, 1691, 1767, 1766, -1, + 1767, 1691, 1690, -1, 1690, 1768, 1767, -1, + 1768, 1690, 1689, -1, 1689, 1769, 1768, -1, + 1769, 1689, 1688, -1, 1688, 1770, 1769, -1, + 1770, 1688, 1687, -1, 1687, 1771, 1770, -1, + 1771, 1687, 1686, -1, 1686, 1772, 1771, -1, + 1772, 1686, 1685, -1, 1685, 1773, 1772, -1, + 1773, 1685, 1684, -1, 1684, 1774, 1773, -1, + 1774, 1684, 1683, -1, 1683, 1775, 1774, -1, + 1775, 1683, 1682, -1, 1682, 1776, 1775, -1, + 1776, 1682, 1681, -1, 1681, 1777, 1776, -1, + 1777, 1681, 1680, -1, 1680, 1778, 1777, -1, + 1778, 1680, 1679, -1, 1679, 1779, 1778, -1, + 1779, 1679, 1678, -1, 1678, 1780, 1779, -1, + 1780, 1678, 1677, -1, 1677, 1781, 1780, -1, + 1781, 1677, 1676, -1, 1676, 1782, 1781, -1, + 1782, 1676, 1675, -1, 1675, 1783, 1782, -1, + 1783, 1675, 1674, -1, 1674, 1784, 1783, -1, + 1784, 1674, 1673, -1, 1673, 1785, 1784, -1, + 1785, 1673, 1672, -1, 1672, 1786, 1785, -1, + 1786, 1672, 1671, -1, 1671, 1787, 1786, -1, + 1787, 1671, 1670, -1, 1670, 1788, 1787, -1, + 1788, 1789, 1790, -1, 1790, 1787, 1788, -1, + 1787, 1790, 1791, -1, 1791, 1786, 1787, -1, + 1786, 1791, 1792, -1, 1792, 1785, 1786, -1, + 1785, 1792, 1793, -1, 1793, 1784, 1785, -1, + 1784, 1793, 1794, -1, 1794, 1783, 1784, -1, + 1783, 1794, 1795, -1, 1795, 1782, 1783, -1, + 1782, 1795, 1796, -1, 1796, 1781, 1782, -1, + 1781, 1796, 1797, -1, 1797, 1780, 1781, -1, + 1780, 1797, 1798, -1, 1798, 1779, 1780, -1, + 1779, 1798, 1799, -1, 1799, 1778, 1779, -1, + 1778, 1799, 1800, -1, 1800, 1777, 1778, -1, + 1777, 1800, 1801, -1, 1801, 1776, 1777, -1, + 1776, 1801, 1802, -1, 1802, 1775, 1776, -1, + 1775, 1802, 1803, -1, 1803, 1774, 1775, -1, + 1774, 1803, 1804, -1, 1804, 1773, 1774, -1, + 1773, 1804, 1805, -1, 1805, 1772, 1773, -1, + 1772, 1805, 1806, -1, 1806, 1771, 1772, -1, + 1771, 1806, 1807, -1, 1807, 1770, 1771, -1, + 1770, 1807, 1808, -1, 1808, 1769, 1770, -1, + 1769, 1808, 1809, -1, 1809, 1768, 1769, -1, + 1768, 1809, 1810, -1, 1810, 1767, 1768, -1, + 1767, 1810, 1811, -1, 1811, 1766, 1767, -1, + 1766, 1811, 1812, -1, 1812, 1765, 1766, -1, + 1765, 1812, 1813, -1, 1813, 1764, 1765, -1, + 1764, 1813, 1814, -1, 1814, 1763, 1764, -1, + 1763, 1814, 1815, -1, 1815, 1762, 1763, -1, + 1762, 1815, 1816, -1, 1816, 1761, 1762, -1, + 1761, 1816, 1817, -1, 1817, 1760, 1761, -1, + 1760, 1817, 1818, -1, 1818, 1759, 1760, -1, + 1759, 1818, 1819, -1, 1819, 1758, 1759, -1, + 1758, 1819, 1820, -1, 1820, 1757, 1758, -1, + 1757, 1820, 1821, -1, 1821, 1756, 1757, -1, + 1756, 1821, 1822, -1, 1822, 1755, 1756, -1, + 1755, 1822, 1823, -1, 1823, 1754, 1755, -1, + 1754, 1823, 1824, -1, 1824, 1753, 1754, -1, + 1753, 1824, 1825, -1, 1825, 1752, 1753, -1, + 1752, 1825, 1826, -1, 1826, 1751, 1752, -1, + 1751, 1826, 1827, -1, 1827, 1750, 1751, -1, + 1750, 1827, 1828, -1, 1828, 1749, 1750, -1, + 1749, 1828, 1829, -1, 1829, 1748, 1749, -1, + 1748, 1829, 1830, -1, 1830, 1747, 1748, -1, + 1747, 1830, 1831, -1, 1831, 1746, 1747, -1, + 1746, 1831, 1832, -1, 1832, 1745, 1746, -1, + 1745, 1832, 1833, -1, 1833, 1744, 1745, -1, + 1744, 1833, 1834, -1, 1834, 1743, 1744, -1, + 1743, 1834, 1175, -1, 1175, 1742, 1743, -1, + 1742, 1175, 1174, -1, 1174, 1741, 1742, -1, + 1741, 1174, 1835, -1, 1835, 1737, 1741, -1, + 1835, 1738, 1737, -1, 1836, 1738, 1835, -1, + 1738, 1836, 1837, -1, 1837, 1739, 1738, -1, + 1739, 1837, 1838, -1, 1838, 1733, 1739, -1, + 1838, 1525, 1733, -1, 1838, 1526, 1525, -1, + 1526, 1838, 1837, -1, 1837, 1839, 1526, -1, + 1839, 1837, 1836, -1, 1836, 1840, 1839, -1, + 1836, 1835, 1840, -1, 1841, 1840, 1835, -1, + 1841, 1835, 1174, -1, 1174, 1173, 1841, -1, + 1841, 1173, 1842, -1, 1842, 1840, 1841, -1, + 1840, 1842, 1843, -1, 1843, 1839, 1840, -1, + 1839, 1843, 1844, -1, 1844, 1526, 1839, -1, + 1844, 1523, 1526, -1, 1844, 1524, 1523, -1, + 1524, 1844, 1843, -1, 1843, 1845, 1524, -1, + 1845, 1843, 1842, -1, 1842, 1846, 1845, -1, + 1847, 1848, 1849, -1, 1848, 1847, 1850, -1, + 1850, 1851, 1848, -1, 1851, 1850, 1846, -1, + 1846, 1842, 1851, -1, 1851, 1842, 1173, -1, + 1173, 1848, 1851, -1, 1848, 1173, 1175, -1, + 1175, 1849, 1848, -1, 1849, 1175, 1834, -1, + 1834, 1852, 1849, -1, 1852, 1834, 1833, -1, + 1833, 1853, 1852, -1, 1853, 1833, 1832, -1, + 1832, 1854, 1853, -1, 1854, 1832, 1831, -1, + 1831, 1855, 1854, -1, 1855, 1831, 1830, -1, + 1830, 1856, 1855, -1, 1856, 1830, 1829, -1, + 1829, 1857, 1856, -1, 1857, 1829, 1828, -1, + 1828, 1858, 1857, -1, 1858, 1828, 1827, -1, + 1827, 1859, 1858, -1, 1859, 1827, 1826, -1, + 1826, 1860, 1859, -1, 1860, 1826, 1825, -1, + 1825, 1861, 1860, -1, 1861, 1825, 1824, -1, + 1824, 1862, 1861, -1, 1862, 1824, 1823, -1, + 1823, 1863, 1862, -1, 1863, 1823, 1822, -1, + 1822, 1864, 1863, -1, 1864, 1822, 1821, -1, + 1821, 1865, 1864, -1, 1865, 1821, 1820, -1, + 1820, 1866, 1865, -1, 1866, 1820, 1819, -1, + 1819, 1867, 1866, -1, 1867, 1819, 1818, -1, + 1818, 1868, 1867, -1, 1868, 1818, 1817, -1, + 1817, 1869, 1868, -1, 1869, 1817, 1816, -1, + 1816, 1870, 1869, -1, 1870, 1816, 1815, -1, + 1815, 1871, 1870, -1, 1871, 1815, 1814, -1, + 1814, 1872, 1871, -1, 1872, 1814, 1813, -1, + 1813, 1873, 1872, -1, 1873, 1813, 1812, -1, + 1812, 1874, 1873, -1, 1874, 1812, 1811, -1, + 1811, 1875, 1874, -1, 1875, 1811, 1810, -1, + 1810, 1876, 1875, -1, 1876, 1810, 1809, -1, + 1809, 1877, 1876, -1, 1877, 1809, 1808, -1, + 1808, 1878, 1877, -1, 1878, 1808, 1807, -1, + 1807, 1879, 1878, -1, 1879, 1807, 1806, -1, + 1806, 1880, 1879, -1, 1880, 1806, 1805, -1, + 1805, 1881, 1880, -1, 1881, 1805, 1804, -1, + 1804, 1882, 1881, -1, 1882, 1804, 1803, -1, + 1803, 1883, 1882, -1, 1883, 1803, 1802, -1, + 1802, 1884, 1883, -1, 1884, 1802, 1801, -1, + 1801, 1885, 1884, -1, 1885, 1801, 1800, -1, + 1800, 1886, 1885, -1, 1886, 1800, 1799, -1, + 1799, 1887, 1886, -1, 1887, 1799, 1798, -1, + 1798, 1888, 1887, -1, 1888, 1798, 1797, -1, + 1797, 1889, 1888, -1, 1889, 1797, 1796, -1, + 1796, 1890, 1889, -1, 1890, 1796, 1795, -1, + 1795, 1891, 1890, -1, 1891, 1795, 1794, -1, + 1794, 1892, 1891, -1, 1892, 1794, 1793, -1, + 1793, 1893, 1892, -1, 1893, 1793, 1792, -1, + 1792, 1894, 1893, -1, 1894, 1792, 1791, -1, + 1791, 1895, 1894, -1, 1895, 1791, 1790, -1, + 1790, 1896, 1895, -1, 1896, 1790, 1789, -1, + 1789, 1897, 1896, -1, 1898, 1899, 1900, -1, + 1901, 1900, 1899, -1, 1900, 1901, 1897, -1, + 1897, 1789, 1900, -1, 1902, 1900, 1789, -1, + 1789, 1788, 1902, -1, 1903, 1904, 1905, -1, + 1905, 1904, 1902, -1, 1905, 1902, 1788, -1, + 1788, 1670, 1905, -1, 1906, 1905, 1670, -1, + 1670, 1669, 1906, -1, 1907, 1908, 1906, -1, + 1907, 1906, 1669, -1, 1669, 1668, 1907, -1, + 1907, 1909, 1910, -1, 1909, 1907, 1668, -1, + 1668, 1911, 1909, -1, 1911, 1668, 1666, -1, + 1666, 1912, 1911, -1, 1912, 1666, 1664, -1, + 1664, 1913, 1912, -1, 1913, 1664, 1662, -1, + 1662, 1914, 1913, -1, 1914, 1662, 1660, -1, + 1660, 1915, 1914, -1, 1915, 1660, 1658, -1, + 1658, 1916, 1915, -1, 1916, 1658, 1656, -1, + 1656, 1917, 1916, -1, 1917, 1656, 1654, -1, + 1654, 1918, 1917, -1, 1918, 1654, 1652, -1, + 1652, 1919, 1918, -1, 1919, 1652, 1650, -1, + 1650, 1920, 1919, -1, 1920, 1650, 1648, -1, + 1648, 1921, 1920, -1, 1921, 1648, 1646, -1, + 1646, 1922, 1921, -1, 1922, 1646, 1644, -1, + 1644, 1923, 1922, -1, 1923, 1644, 1642, -1, + 1642, 1924, 1923, -1, 1924, 1642, 1640, -1, + 1640, 1925, 1924, -1, 1925, 1640, 1638, -1, + 1638, 1926, 1925, -1, 1926, 1638, 1636, -1, + 1636, 1927, 1926, -1, 1927, 1636, 1634, -1, + 1634, 1928, 1927, -1, 1928, 1634, 1632, -1, + 1632, 1929, 1928, -1, 1929, 1632, 1630, -1, + 1630, 1930, 1929, -1, 1930, 1630, 1628, -1, + 1628, 1931, 1930, -1, 1931, 1628, 1626, -1, + 1626, 1932, 1931, -1, 1932, 1626, 1624, -1, + 1624, 1933, 1932, -1, 1933, 1624, 1622, -1, + 1622, 1934, 1933, -1, 1934, 1622, 1620, -1, + 1620, 1935, 1934, -1, 1935, 1620, 1618, -1, + 1618, 1936, 1935, -1, 1936, 1618, 1616, -1, + 1616, 1937, 1936, -1, 1937, 1616, 1614, -1, + 1614, 1938, 1937, -1, 1938, 1614, 1612, -1, + 1612, 1939, 1938, -1, 1939, 1612, 1610, -1, + 1610, 1940, 1939, -1, 1940, 1610, 1608, -1, + 1608, 1941, 1940, -1, 1941, 1608, 1606, -1, + 1606, 1942, 1941, -1, 1942, 1606, 1604, -1, + 1604, 1943, 1942, -1, 1943, 1604, 1602, -1, + 1602, 1944, 1943, -1, 1944, 1602, 1600, -1, + 1600, 1945, 1944, -1, 1945, 1600, 1598, -1, + 1598, 1946, 1945, -1, 1946, 1598, 1596, -1, + 1596, 1947, 1946, -1, 1947, 1596, 1594, -1, + 1594, 1948, 1947, -1, 1948, 1594, 1592, -1, + 1592, 1949, 1948, -1, 1949, 1592, 1590, -1, + 1590, 1950, 1949, -1, 1950, 1590, 1588, -1, + 1588, 1951, 1950, -1, 1951, 1588, 1586, -1, + 1586, 1952, 1951, -1, 1952, 1586, 1584, -1, + 1584, 1953, 1952, -1, 1953, 1584, 1582, -1, + 1582, 1954, 1953, -1, 1954, 1582, 1580, -1, + 1580, 1955, 1954, -1, 1955, 1580, 1578, -1, + 1578, 1956, 1955, -1, 1956, 1578, 1576, -1, + 1576, 1957, 1956, -1, 1957, 1576, 1574, -1, + 1574, 1958, 1957, -1, 1958, 1574, 1572, -1, + 1572, 1959, 1958, -1, 1959, 1572, 1570, -1, + 1570, 1960, 1959, -1, 1960, 1570, 1568, -1, + 1568, 1961, 1960, -1, 1961, 1568, 1566, -1, + 1566, 1962, 1961, -1, 1962, 1566, 1564, -1, + 1564, 1963, 1962, -1, 1963, 1564, 1562, -1, + 1562, 1964, 1963, -1, 1964, 1562, 1556, -1, + 1556, 1558, 1964, -1, 1171, 1965, 1966, -1, + 1966, 1967, 1171, -1, 1968, 1969, 1970, -1, + 1971, 1970, 1969, -1, 1971, 1972, 1970, -1, + 1558, 1973, 1970, -1, 1970, 1974, 1558, -1, + 1974, 1970, 1972, -1, 1972, 1975, 1974, -1, + 1975, 1972, 1976, -1, 1976, 1977, 1975, -1, + 1977, 1976, 1978, -1, 1978, 1979, 1977, -1, + 1979, 1978, 1980, -1, 1980, 1981, 1979, -1, + 1981, 1980, 1982, -1, 1982, 1983, 1981, -1, + 1983, 1982, 1984, -1, 1984, 1985, 1983, -1, + 1985, 1984, 1986, -1, 1986, 1987, 1985, -1, + 1987, 1986, 1988, -1, 1988, 1989, 1987, -1, + 1989, 1988, 1990, -1, 1990, 1991, 1989, -1, + 1991, 1990, 1992, -1, 1992, 1993, 1991, -1, + 1993, 1992, 1994, -1, 1994, 1995, 1993, -1, + 1995, 1994, 1996, -1, 1996, 1997, 1995, -1, + 1997, 1996, 1998, -1, 1998, 1999, 1997, -1, + 1999, 1998, 2000, -1, 2000, 2001, 1999, -1, + 2001, 2000, 2002, -1, 2002, 2003, 2001, -1, + 2003, 2002, 2004, -1, 2004, 2005, 2003, -1, + 2005, 2004, 2006, -1, 2006, 2007, 2005, -1, + 2007, 2006, 2008, -1, 2008, 2009, 2007, -1, + 2009, 2008, 2010, -1, 2010, 2011, 2009, -1, + 2011, 2010, 2012, -1, 2012, 2013, 2011, -1, + 2013, 2012, 2014, -1, 2014, 2015, 2013, -1, + 2015, 2014, 2016, -1, 2016, 2017, 2015, -1, + 2017, 2016, 2018, -1, 2018, 2019, 2017, -1, + 2019, 2018, 2020, -1, 2020, 2021, 2019, -1, + 2021, 2020, 2022, -1, 2022, 2023, 2021, -1, + 2023, 2022, 2024, -1, 2024, 2025, 2023, -1, + 2025, 2024, 2026, -1, 2026, 2027, 2025, -1, + 2027, 2026, 2028, -1, 2028, 2029, 2027, -1, + 2029, 2028, 2030, -1, 2030, 2031, 2029, -1, + 2031, 2030, 2032, -1, 2032, 2033, 2031, -1, + 2033, 2032, 2034, -1, 2034, 2035, 2033, -1, + 2035, 2034, 2036, -1, 2036, 2037, 2035, -1, + 2037, 2036, 2038, -1, 2038, 2039, 2037, -1, + 2039, 2038, 2040, -1, 2040, 2041, 2039, -1, + 2041, 2040, 2042, -1, 2042, 2043, 2041, -1, + 2043, 2042, 2044, -1, 2044, 2045, 2043, -1, + 2045, 2044, 2046, -1, 2046, 2047, 2045, -1, + 2047, 2046, 2048, -1, 2048, 2049, 2047, -1, + 2049, 2048, 2050, -1, 2050, 2051, 2049, -1, + 2051, 2050, 2052, -1, 2052, 2053, 2051, -1, + 2053, 2052, 2054, -1, 2054, 2055, 2053, -1, + 2055, 2054, 2056, -1, 2056, 2057, 2055, -1, + 2057, 2056, 2058, -1, 2058, 2059, 2057, -1, + 2059, 2058, 2060, -1, 2060, 2061, 2059, -1, + 2061, 2060, 2062, -1, 2062, 2063, 2061, -1, + 2063, 2062, 2064, -1, 2064, 2065, 2063, -1, + 2065, 2064, 2066, -1, 2066, 2067, 2065, -1, + 2067, 2066, 2068, -1, 2068, 2069, 2067, -1, + 2069, 2068, 2070, -1, 2070, 2071, 2069, -1, + 2071, 2070, 2072, -1, 2072, 2073, 2071, -1, + 2073, 2072, 2074, -1, 2074, 2075, 2073, -1, + 2075, 2074, 2076, -1, 2076, 2077, 2075, -1, + 2077, 2076, 2078, -1, 2078, 2079, 2077, -1, + 2079, 2078, 1967, -1, 1967, 1966, 2079, -1, + 1966, 2080, 2081, -1, 2081, 2079, 1966, -1, + 2079, 2081, 2082, -1, 2082, 2077, 2079, -1, + 2077, 2082, 2083, -1, 2083, 2075, 2077, -1, + 2075, 2083, 2084, -1, 2084, 2073, 2075, -1, + 2073, 2084, 2085, -1, 2085, 2071, 2073, -1, + 2071, 2085, 2086, -1, 2086, 2069, 2071, -1, + 2069, 2086, 2087, -1, 2087, 2067, 2069, -1, + 2067, 2087, 2088, -1, 2088, 2065, 2067, -1, + 2065, 2088, 2089, -1, 2089, 2063, 2065, -1, + 2063, 2089, 2090, -1, 2090, 2061, 2063, -1, + 2061, 2090, 2091, -1, 2091, 2059, 2061, -1, + 2059, 2091, 2092, -1, 2092, 2057, 2059, -1, + 2057, 2092, 2093, -1, 2093, 2055, 2057, -1, + 2055, 2093, 2094, -1, 2094, 2053, 2055, -1, + 2053, 2094, 2095, -1, 2095, 2051, 2053, -1, + 2051, 2095, 2096, -1, 2096, 2049, 2051, -1, + 2049, 2096, 2097, -1, 2097, 2047, 2049, -1, + 2047, 2097, 2098, -1, 2098, 2045, 2047, -1, + 2045, 2098, 2099, -1, 2099, 2043, 2045, -1, + 2043, 2099, 2100, -1, 2100, 2041, 2043, -1, + 2041, 2100, 2101, -1, 2101, 2039, 2041, -1, + 2039, 2101, 2102, -1, 2102, 2037, 2039, -1, + 2037, 2102, 2103, -1, 2103, 2035, 2037, -1, + 2035, 2103, 2104, -1, 2104, 2033, 2035, -1, + 2033, 2104, 2105, -1, 2105, 2031, 2033, -1, + 2031, 2105, 2106, -1, 2106, 2029, 2031, -1, + 2029, 2106, 2107, -1, 2107, 2027, 2029, -1, + 2027, 2107, 2108, -1, 2108, 2025, 2027, -1, + 2025, 2108, 2109, -1, 2109, 2023, 2025, -1, + 2023, 2109, 2110, -1, 2110, 2021, 2023, -1, + 2021, 2110, 2111, -1, 2111, 2019, 2021, -1, + 2019, 2111, 2112, -1, 2112, 2017, 2019, -1, + 2017, 2112, 2113, -1, 2113, 2015, 2017, -1, + 2015, 2113, 2114, -1, 2114, 2013, 2015, -1, + 2013, 2114, 2115, -1, 2115, 2011, 2013, -1, + 2011, 2115, 2116, -1, 2116, 2009, 2011, -1, + 2009, 2116, 2117, -1, 2117, 2007, 2009, -1, + 2007, 2117, 2118, -1, 2118, 2005, 2007, -1, + 2005, 2118, 2119, -1, 2119, 2003, 2005, -1, + 2003, 2119, 2120, -1, 2120, 2001, 2003, -1, + 2001, 2120, 2121, -1, 2121, 1999, 2001, -1, + 1999, 2121, 2122, -1, 2122, 1997, 1999, -1, + 1997, 2122, 2123, -1, 2123, 1995, 1997, -1, + 1995, 2123, 2124, -1, 2124, 1993, 1995, -1, + 1993, 2124, 2125, -1, 2125, 1991, 1993, -1, + 1991, 2125, 2126, -1, 2126, 1989, 1991, -1, + 1989, 2126, 2127, -1, 2127, 1987, 1989, -1, + 1987, 2127, 2128, -1, 2128, 1985, 1987, -1, + 1985, 2128, 2129, -1, 2129, 1983, 1985, -1, + 1983, 2129, 2130, -1, 2130, 1981, 1983, -1, + 1981, 2130, 2131, -1, 2131, 1979, 1981, -1, + 1979, 2131, 2132, -1, 2132, 1977, 1979, -1, + 1977, 2132, 2133, -1, 2133, 1975, 1977, -1, + 1975, 2133, 2134, -1, 2134, 1974, 1975, -1, + 1974, 2134, 2135, -1, 2135, 1558, 1974, -1, + 2135, 1964, 1558, -1, 1964, 2135, 2136, -1, + 2136, 1963, 1964, -1, 1963, 2136, 2137, -1, + 2137, 1962, 1963, -1, 1962, 2137, 2138, -1, + 2138, 1961, 1962, -1, 1961, 2138, 2139, -1, + 2139, 1960, 1961, -1, 1960, 2139, 2140, -1, + 2140, 1959, 1960, -1, 1959, 2140, 2141, -1, + 2141, 1958, 1959, -1, 1958, 2141, 2142, -1, + 2142, 1957, 1958, -1, 1957, 2142, 2143, -1, + 2143, 1956, 1957, -1, 1956, 2143, 2144, -1, + 2144, 1955, 1956, -1, 1955, 2144, 2145, -1, + 2145, 1954, 1955, -1, 1954, 2145, 2146, -1, + 2146, 1953, 1954, -1, 1953, 2146, 2147, -1, + 2147, 1952, 1953, -1, 1952, 2147, 2148, -1, + 2148, 1951, 1952, -1, 1951, 2148, 2149, -1, + 2149, 1950, 1951, -1, 1950, 2149, 2150, -1, + 2150, 1949, 1950, -1, 1949, 2150, 2151, -1, + 2151, 1948, 1949, -1, 1948, 2151, 2152, -1, + 2152, 1947, 1948, -1, 1947, 2152, 2153, -1, + 2153, 1946, 1947, -1, 1946, 2153, 2154, -1, + 2154, 1945, 1946, -1, 1945, 2154, 2155, -1, + 2155, 1944, 1945, -1, 1944, 2155, 2156, -1, + 2156, 1943, 1944, -1, 1943, 2156, 2157, -1, + 2157, 1942, 1943, -1, 1942, 2157, 2158, -1, + 2158, 1941, 1942, -1, 1941, 2158, 2159, -1, + 2159, 1940, 1941, -1, 1940, 2159, 2160, -1, + 2160, 1939, 1940, -1, 1939, 2160, 2161, -1, + 2161, 1938, 1939, -1, 1938, 2161, 2162, -1, + 2162, 1937, 1938, -1, 1937, 2162, 2163, -1, + 2163, 1936, 1937, -1, 1936, 2163, 2164, -1, + 2164, 1935, 1936, -1, 1935, 2164, 2165, -1, + 2165, 1934, 1935, -1, 1934, 2165, 2166, -1, + 2166, 1933, 1934, -1, 1933, 2166, 2167, -1, + 2167, 1932, 1933, -1, 1932, 2167, 2168, -1, + 2168, 1931, 1932, -1, 1931, 2168, 2169, -1, + 2169, 1930, 1931, -1, 1930, 2169, 2170, -1, + 2170, 1929, 1930, -1, 1929, 2170, 2171, -1, + 2171, 1928, 1929, -1, 1928, 2171, 2172, -1, + 2172, 1927, 1928, -1, 1927, 2172, 2173, -1, + 2173, 1926, 1927, -1, 1926, 2173, 2174, -1, + 2174, 1925, 1926, -1, 1925, 2174, 2175, -1, + 2175, 1924, 1925, -1, 1924, 2175, 2176, -1, + 2176, 1923, 1924, -1, 1923, 2176, 2177, -1, + 2177, 1922, 1923, -1, 1922, 2177, 2178, -1, + 2178, 1921, 1922, -1, 1921, 2178, 2179, -1, + 2179, 1920, 1921, -1, 1920, 2179, 2180, -1, + 2180, 1919, 1920, -1, 1919, 2180, 2181, -1, + 2181, 1918, 1919, -1, 1918, 2181, 2182, -1, + 2182, 1917, 1918, -1, 1917, 2182, 2183, -1, + 2183, 1916, 1917, -1, 1916, 2183, 2184, -1, + 2184, 1915, 1916, -1, 1915, 2184, 2185, -1, + 2185, 1914, 1915, -1, 1914, 2185, 2186, -1, + 2186, 1913, 1914, -1, 1913, 2186, 2187, -1, + 2187, 1912, 1913, -1, 1912, 2187, 2188, -1, + 2188, 1911, 1912, -1, 1911, 2188, 2189, -1, + 2189, 1909, 1911, -1, 1909, 2189, 2190, -1, + 2191, 2192, 2189, -1, 2192, 2190, 2189, -1, + 2192, 2193, 2190, -1, 2192, 2191, 2193, -1, + 2194, 2193, 2195, -1, 2196, 2197, 2194, -1, + 2198, 2199, 2200, -1, 2199, 2198, 2201, -1, + 2201, 2202, 2199, -1, 2202, 2201, 2203, -1, + 2203, 2204, 2202, -1, 2204, 2203, 2205, -1, + 2205, 2206, 2204, -1, 2206, 2205, 2207, -1, + 2207, 2208, 2206, -1, 2208, 2207, 2209, -1, + 2209, 2210, 2208, -1, 2210, 2209, 2211, -1, + 2211, 2212, 2210, -1, 2212, 2211, 2213, -1, + 2213, 2214, 2212, -1, 2214, 2213, 2215, -1, + 2215, 2216, 2214, -1, 2216, 2215, 2217, -1, + 2217, 2218, 2216, -1, 2218, 2217, 2219, -1, + 2219, 2220, 2218, -1, 2220, 2219, 2221, -1, + 2221, 2222, 2220, -1, 2222, 2221, 2223, -1, + 2223, 2224, 2222, -1, 2224, 2223, 2225, -1, + 2225, 2226, 2224, -1, 2226, 2225, 2227, -1, + 2227, 2228, 2226, -1, 2228, 2227, 2229, -1, + 2229, 2230, 2228, -1, 2230, 2229, 2231, -1, + 2231, 2232, 2230, -1, 2232, 2231, 2233, -1, + 2233, 2234, 2232, -1, 2235, 2236, 2237, -1, + 2237, 2236, 2238, -1, 2237, 2238, 2239, -1, + 2239, 2240, 2237, -1, 2240, 2239, 2241, -1, + 2241, 2242, 2240, -1, 2242, 2241, 2243, -1, + 2243, 2244, 2242, -1, 2244, 2243, 2245, -1, + 2245, 2246, 2244, -1, 2246, 2245, 2247, -1, + 2247, 2248, 2246, -1, 2248, 2247, 2249, -1, + 2249, 2250, 2248, -1, 2250, 2249, 2251, -1, + 2251, 2252, 2250, -1, 2252, 2251, 2253, -1, + 2253, 2254, 2252, -1, 2254, 2253, 2255, -1, + 2255, 2256, 2254, -1, 2256, 2255, 2257, -1, + 2257, 2258, 2256, -1, 2258, 2257, 2259, -1, + 2259, 2260, 2258, -1, 2260, 2259, 2261, -1, + 2261, 2262, 2260, -1, 2262, 2261, 2263, -1, + 2263, 2264, 2262, -1, 2264, 2263, 2265, -1, + 2265, 2266, 2264, -1, 2266, 2265, 2267, -1, + 2267, 2268, 2266, -1, 2269, 2266, 2268, -1, + 2268, 2270, 2269, -1, 2270, 2268, 2271, -1, + 2271, 2272, 2270, -1, 2273, 2274, 2275, -1, + 2275, 2276, 2273, -1, 2276, 2275, 2277, -1, + 2277, 2278, 2276, -1, 2278, 2277, 2279, -1, + 2279, 2280, 2278, -1, 2280, 2279, 2281, -1, + 2281, 2282, 2280, -1, 2282, 2281, 2283, -1, + 2283, 2284, 2282, -1, 2284, 2283, 2285, -1, + 2285, 2286, 2284, -1, 2286, 2285, 2287, -1, + 2287, 2288, 2286, -1, 2288, 2287, 2272, -1, + 2272, 2271, 2288, -1, 2289, 2288, 2271, -1, + 2271, 2234, 2289, -1, 2234, 2271, 2268, -1, + 2268, 2232, 2234, -1, 2232, 2268, 2267, -1, + 2267, 2230, 2232, -1, 2230, 2267, 2265, -1, + 2265, 2228, 2230, -1, 2228, 2265, 2263, -1, + 2263, 2226, 2228, -1, 2226, 2263, 2261, -1, + 2261, 2224, 2226, -1, 2224, 2261, 2259, -1, + 2259, 2222, 2224, -1, 2222, 2259, 2257, -1, + 2257, 2220, 2222, -1, 2220, 2257, 2255, -1, + 2255, 2218, 2220, -1, 2218, 2255, 2253, -1, + 2253, 2216, 2218, -1, 2216, 2253, 2251, -1, + 2251, 2214, 2216, -1, 2214, 2251, 2249, -1, + 2249, 2212, 2214, -1, 2212, 2249, 2247, -1, + 2247, 2210, 2212, -1, 2210, 2247, 2245, -1, + 2245, 2208, 2210, -1, 2208, 2245, 2243, -1, + 2243, 2206, 2208, -1, 2206, 2243, 2241, -1, + 2241, 2204, 2206, -1, 2204, 2241, 2239, -1, + 2239, 2202, 2204, -1, 2202, 2239, 2238, -1, + 2238, 2199, 2202, -1, 2199, 2238, 2290, -1, + 2291, 2290, 2238, -1, 2290, 2291, 2194, -1, + 2290, 2194, 2197, -1, 2197, 2199, 2290, -1, + 2197, 2196, 2199, -1, 2196, 2200, 2199, -1, + 2196, 2194, 2200, -1, 2200, 2194, 2195, -1, + 2195, 2198, 2200, -1, 2195, 2292, 2198, -1, + 2292, 2195, 2193, -1, 2292, 2193, 2191, -1, + 2191, 2189, 2292, -1, 2189, 2198, 2292, -1, + 2198, 2189, 2188, -1, 2188, 2201, 2198, -1, + 2201, 2188, 2187, -1, 2187, 2203, 2201, -1, + 2203, 2187, 2186, -1, 2186, 2205, 2203, -1, + 2205, 2186, 2185, -1, 2185, 2207, 2205, -1, + 2207, 2185, 2184, -1, 2184, 2209, 2207, -1, + 2209, 2184, 2183, -1, 2183, 2211, 2209, -1, + 2211, 2183, 2182, -1, 2182, 2213, 2211, -1, + 2213, 2182, 2181, -1, 2181, 2215, 2213, -1, + 2215, 2181, 2180, -1, 2180, 2217, 2215, -1, + 2217, 2180, 2179, -1, 2179, 2219, 2217, -1, + 2219, 2179, 2178, -1, 2178, 2221, 2219, -1, + 2221, 2178, 2177, -1, 2177, 2223, 2221, -1, + 2223, 2177, 2176, -1, 2176, 2225, 2223, -1, + 2225, 2176, 2175, -1, 2175, 2227, 2225, -1, + 2227, 2175, 2174, -1, 2174, 2229, 2227, -1, + 2229, 2174, 2173, -1, 2173, 2231, 2229, -1, + 2231, 2173, 2172, -1, 2172, 2233, 2231, -1, + 2233, 2172, 2171, -1, 2171, 2234, 2233, -1, + 2234, 2171, 2170, -1, 2170, 2289, 2234, -1, + 2289, 2170, 2169, -1, 2169, 2288, 2289, -1, + 2288, 2169, 2168, -1, 2168, 2286, 2288, -1, + 2286, 2168, 2167, -1, 2167, 2284, 2286, -1, + 2284, 2167, 2166, -1, 2166, 2282, 2284, -1, + 2282, 2166, 2165, -1, 2165, 2280, 2282, -1, + 2280, 2165, 2164, -1, 2164, 2278, 2280, -1, + 2278, 2164, 2163, -1, 2163, 2276, 2278, -1, + 2276, 2163, 2162, -1, 2162, 2273, 2276, -1, + 2273, 2162, 2161, -1, 2161, 2274, 2273, -1, + 2274, 2161, 2160, -1, 2160, 2293, 2274, -1, + 2293, 2160, 2159, -1, 2159, 2294, 2293, -1, + 2294, 2159, 2158, -1, 2158, 2295, 2294, -1, + 2295, 2158, 2157, -1, 2157, 2296, 2295, -1, + 2296, 2157, 2156, -1, 2156, 2297, 2296, -1, + 2297, 2156, 2155, -1, 2155, 2298, 2297, -1, + 2298, 2155, 2154, -1, 2154, 2299, 2298, -1, + 2299, 2154, 2153, -1, 2153, 2300, 2299, -1, + 2300, 2153, 2152, -1, 2152, 2301, 2300, -1, + 2301, 2152, 2151, -1, 2151, 2302, 2301, -1, + 2302, 2151, 2150, -1, 2150, 2303, 2302, -1, + 2303, 2150, 2149, -1, 2149, 2304, 2303, -1, + 2304, 2149, 2148, -1, 2148, 2305, 2304, -1, + 2305, 2148, 2147, -1, 2147, 2306, 2305, -1, + 2306, 2147, 2146, -1, 2146, 2307, 2306, -1, + 2307, 2146, 2145, -1, 2145, 2308, 2307, -1, + 2308, 2145, 2144, -1, 2144, 2309, 2308, -1, + 2309, 2144, 2143, -1, 2143, 2310, 2309, -1, + 2310, 2143, 2142, -1, 2142, 2311, 2310, -1, + 2311, 2142, 2141, -1, 2141, 2312, 2311, -1, + 2312, 2141, 2140, -1, 2140, 2313, 2312, -1, + 2313, 2140, 2139, -1, 2139, 2314, 2313, -1, + 2314, 2139, 2138, -1, 2138, 2315, 2314, -1, + 2315, 2138, 2137, -1, 2137, 2316, 2315, -1, + 2316, 2137, 2136, -1, 2136, 2317, 2316, -1, + 2317, 2136, 2135, -1, 2317, 2135, 2134, -1, + 2134, 2318, 2317, -1, 2318, 2134, 2133, -1, + 2133, 2319, 2318, -1, 2319, 2133, 2132, -1, + 2132, 2320, 2319, -1, 2320, 2132, 2131, -1, + 2131, 2321, 2320, -1, 2321, 2131, 2130, -1, + 2130, 2322, 2321, -1, 2322, 2130, 2129, -1, + 2129, 2323, 2322, -1, 2323, 2129, 2128, -1, + 2128, 2324, 2323, -1, 2324, 2128, 2127, -1, + 2127, 2325, 2324, -1, 2325, 2127, 2126, -1, + 2126, 2326, 2325, -1, 2326, 2126, 2125, -1, + 2125, 2327, 2326, -1, 2327, 2125, 2124, -1, + 2124, 2328, 2327, -1, 2328, 2124, 2123, -1, + 2123, 2329, 2328, -1, 2329, 2123, 2122, -1, + 2122, 2330, 2329, -1, 2330, 2122, 2121, -1, + 2121, 2331, 2330, -1, 2331, 2121, 2120, -1, + 2120, 2332, 2331, -1, 2332, 2120, 2119, -1, + 2119, 2333, 2332, -1, 2333, 2119, 2118, -1, + 2118, 2334, 2333, -1, 2334, 2118, 2117, -1, + 2117, 2335, 2334, -1, 2335, 2117, 2116, -1, + 2116, 2336, 2335, -1, 2336, 2116, 2115, -1, + 2115, 2337, 2336, -1, 2337, 2115, 2114, -1, + 2114, 2338, 2337, -1, 2338, 2114, 2113, -1, + 2113, 2339, 2338, -1, 2339, 2113, 2112, -1, + 2112, 2340, 2339, -1, 2340, 2112, 2111, -1, + 2111, 2341, 2340, -1, 2341, 2111, 2110, -1, + 2110, 2342, 2341, -1, 2342, 2110, 2109, -1, + 2109, 2343, 2342, -1, 2343, 2109, 2108, -1, + 2108, 2344, 2343, -1, 2344, 2108, 2107, -1, + 2107, 2345, 2344, -1, 2345, 2107, 2106, -1, + 2106, 2346, 2345, -1, 2346, 2106, 2105, -1, + 2105, 2347, 2346, -1, 2347, 2105, 2104, -1, + 2104, 2348, 2347, -1, 2348, 2104, 2103, -1, + 2103, 2349, 2348, -1, 2349, 2103, 2102, -1, + 2102, 2350, 2349, -1, 2350, 2102, 2101, -1, + 2101, 2351, 2350, -1, 2351, 2101, 2100, -1, + 2100, 2352, 2351, -1, 2352, 2100, 2099, -1, + 2099, 2353, 2352, -1, 2353, 2099, 2098, -1, + 2098, 2354, 2353, -1, 2354, 2098, 2097, -1, + 2097, 2355, 2354, -1, 2355, 2097, 2096, -1, + 2096, 2356, 2355, -1, 2356, 2096, 2095, -1, + 2095, 2357, 2356, -1, 2357, 2095, 2094, -1, + 2094, 2358, 2357, -1, 2358, 2094, 2093, -1, + 2093, 2359, 2358, -1, 2359, 2093, 2092, -1, + 2092, 2360, 2359, -1, 2360, 2092, 2091, -1, + 2091, 2361, 2360, -1, 2361, 2091, 2090, -1, + 2090, 2362, 2361, -1, 2362, 2090, 2089, -1, + 2089, 2363, 2362, -1, 2363, 2089, 2088, -1, + 2088, 2364, 2363, -1, 2364, 2088, 2087, -1, + 2087, 2365, 2364, -1, 2365, 2087, 2086, -1, + 2086, 2366, 2365, -1, 2366, 2086, 2085, -1, + 2085, 2367, 2366, -1, 2367, 2085, 2084, -1, + 2084, 2368, 2367, -1, 2368, 2084, 2083, -1, + 2083, 2369, 2368, -1, 2369, 2083, 2082, -1, + 2082, 2370, 2369, -1, 2370, 2082, 2081, -1, + 2081, 2371, 2370, -1, 2372, 2373, 2374, -1, + 2375, 2376, 2377, -1, 2376, 2375, 2378, -1, + 2378, 2379, 2376, -1, 2379, 2378, 2380, -1, + 2380, 2381, 2379, -1, 2381, 2380, 2382, -1, + 2382, 2383, 2381, -1, 2383, 2382, 2384, -1, + 2384, 2385, 2383, -1, 2385, 2384, 2386, -1, + 2386, 2387, 2385, -1, 2387, 2386, 2388, -1, + 2388, 2389, 2387, -1, 2389, 2388, 2390, -1, + 2390, 2391, 2389, -1, 2391, 2390, 2392, -1, + 2392, 2393, 2391, -1, 2393, 2392, 2394, -1, + 2394, 2395, 2393, -1, 2395, 2394, 2396, -1, + 2396, 2397, 2395, -1, 2397, 2396, 2398, -1, + 2398, 2399, 2397, -1, 2399, 2398, 2400, -1, + 2400, 2401, 2399, -1, 2402, 2403, 2404, -1, + 2401, 2404, 2403, -1, 2401, 2400, 2404, -1, + 2405, 2406, 2407, -1, 2405, 2408, 2406, -1, + 2409, 2410, 2411, -1, 2410, 2409, 2412, -1, + 2412, 2413, 2410, -1, 2413, 2412, 2414, -1, + 2414, 2415, 2413, -1, 2415, 2414, 2416, -1, + 2416, 2417, 2415, -1, 2417, 2416, 2418, -1, + 2418, 2419, 2417, -1, 2419, 2418, 2420, -1, + 2420, 2421, 2419, -1, 2421, 2420, 2422, -1, + 2422, 2423, 2421, -1, 2423, 2422, 2424, -1, + 2424, 2425, 2423, -1, 2425, 2424, 2426, -1, + 2426, 2427, 2425, -1, 2427, 2426, 2428, -1, + 2428, 2429, 2427, -1, 2429, 2428, 2430, -1, + 2430, 2431, 2429, -1, 2431, 2430, 2432, -1, + 2432, 2433, 2431, -1, 2433, 2432, 2434, -1, + 2434, 2435, 2433, -1, 2435, 2434, 2436, -1, + 2436, 2437, 2435, -1, 2437, 2436, 2408, -1, + 2408, 2405, 2437, -1, 2405, 2438, 2404, -1, + 2404, 2437, 2405, -1, 2437, 2404, 2400, -1, + 2400, 2435, 2437, -1, 2435, 2400, 2398, -1, + 2398, 2433, 2435, -1, 2433, 2398, 2396, -1, + 2396, 2431, 2433, -1, 2431, 2396, 2394, -1, + 2394, 2429, 2431, -1, 2429, 2394, 2392, -1, + 2392, 2427, 2429, -1, 2427, 2392, 2390, -1, + 2390, 2425, 2427, -1, 2425, 2390, 2388, -1, + 2388, 2423, 2425, -1, 2423, 2388, 2386, -1, + 2386, 2421, 2423, -1, 2421, 2386, 2384, -1, + 2384, 2419, 2421, -1, 2419, 2384, 2382, -1, + 2382, 2417, 2419, -1, 2417, 2382, 2380, -1, + 2380, 2415, 2417, -1, 2415, 2380, 2378, -1, + 2378, 2413, 2415, -1, 2413, 2378, 2375, -1, + 2375, 2410, 2413, -1, 2410, 2375, 2377, -1, + 2377, 2411, 2410, -1, 2411, 2377, 2439, -1, + 2439, 2440, 2411, -1, 2440, 2439, 2441, -1, + 2442, 2443, 2444, -1, 2444, 2445, 2442, -1, + 2445, 2444, 2446, -1, 2446, 2447, 2445, -1, + 2447, 2446, 2448, -1, 2448, 2449, 2447, -1, + 2449, 2448, 2450, -1, 2450, 2451, 2449, -1, + 2451, 2450, 2452, -1, 2452, 2453, 2451, -1, + 2453, 2452, 2454, -1, 2454, 2455, 2453, -1, + 2456, 2457, 2458, -1, 2457, 2456, 2455, -1, + 2455, 2454, 2457, -1, 2459, 2457, 2454, -1, + 2454, 2460, 2459, -1, 2460, 2454, 2452, -1, + 2452, 2461, 2460, -1, 2461, 2452, 2450, -1, + 2450, 2462, 2461, -1, 2462, 2450, 2448, -1, + 2448, 2463, 2462, -1, 2463, 2448, 2446, -1, + 2446, 2464, 2463, -1, 2464, 2446, 2444, -1, + 2444, 2465, 2464, -1, 2465, 2444, 2443, -1, + 2443, 2466, 2465, -1, 2466, 2443, 2467, -1, + 2467, 2468, 2466, -1, 2468, 2467, 2469, -1, + 2469, 2470, 2468, -1, 2470, 2469, 2471, -1, + 2471, 2472, 2470, -1, 2472, 2471, 2473, -1, + 2473, 2474, 2472, -1, 2474, 2473, 2475, -1, + 2475, 2476, 2474, -1, 2476, 2475, 2477, -1, + 2477, 2478, 2476, -1, 2478, 2477, 2479, -1, + 2479, 2480, 2478, -1, 2480, 2479, 2481, -1, + 2481, 2482, 2480, -1, 2482, 2481, 2483, -1, + 2483, 2484, 2482, -1, 2484, 2483, 2485, -1, + 2485, 2486, 2484, -1, 2486, 2485, 2487, -1, + 2487, 2488, 2486, -1, 2488, 2487, 2489, -1, + 2489, 2490, 2488, -1, 2490, 2489, 2491, -1, + 2491, 2492, 2490, -1, 2492, 2491, 2493, -1, + 2493, 802, 2492, -1, 802, 2493, 2494, -1, + 2494, 2495, 2496, -1, 2494, 2497, 2495, -1, + 2497, 2494, 2493, -1, 2493, 2498, 2497, -1, + 2498, 2493, 2491, -1, 2491, 2499, 2498, -1, + 2499, 2491, 2489, -1, 2489, 2500, 2499, -1, + 2500, 2489, 2487, -1, 2487, 2501, 2500, -1, + 2501, 2487, 2485, -1, 2485, 2502, 2501, -1, + 2502, 2485, 2483, -1, 2483, 2503, 2502, -1, + 2503, 2483, 2481, -1, 2481, 2504, 2503, -1, + 2504, 2481, 2479, -1, 2479, 2505, 2504, -1, + 2505, 2479, 2477, -1, 2477, 2506, 2505, -1, + 2506, 2477, 2475, -1, 2475, 2507, 2506, -1, + 2507, 2475, 2473, -1, 2473, 2508, 2507, -1, + 2508, 2473, 2471, -1, 2471, 2509, 2508, -1, + 2509, 2471, 2469, -1, 2469, 2510, 2509, -1, + 2510, 2469, 2467, -1, 2467, 2511, 2510, -1, + 2511, 2467, 2443, -1, 2443, 2442, 2511, -1, + 2512, 2511, 2442, -1, 2511, 2512, 2441, -1, + 2441, 2510, 2511, -1, 2510, 2441, 2439, -1, + 2439, 2509, 2510, -1, 2509, 2439, 2377, -1, + 2377, 2508, 2509, -1, 2508, 2377, 2376, -1, + 2376, 2507, 2508, -1, 2507, 2376, 2379, -1, + 2379, 2506, 2507, -1, 2506, 2379, 2381, -1, + 2381, 2505, 2506, -1, 2505, 2381, 2383, -1, + 2383, 2504, 2505, -1, 2504, 2383, 2385, -1, + 2385, 2503, 2504, -1, 2503, 2385, 2387, -1, + 2387, 2502, 2503, -1, 2502, 2387, 2389, -1, + 2389, 2501, 2502, -1, 2501, 2389, 2391, -1, + 2391, 2500, 2501, -1, 2500, 2391, 2393, -1, + 2393, 2499, 2500, -1, 2499, 2393, 2395, -1, + 2395, 2498, 2499, -1, 2498, 2395, 2397, -1, + 2397, 2497, 2498, -1, 2497, 2397, 2399, -1, + 2399, 2495, 2497, -1, 2495, 2399, 2401, -1, + 2401, 2513, 2495, -1, 2514, 2495, 2513, -1, + 2513, 2372, 2514, -1, 2513, 2515, 2372, -1, + 2515, 2513, 2401, -1, 2515, 2401, 2403, -1, + 2403, 2372, 2515, -1, 2403, 2402, 2372, -1, + 2402, 2373, 2372, -1, 2373, 2402, 2404, -1, + 2373, 2404, 2438, -1, 2438, 2374, 2373, -1, + 2438, 2516, 2374, -1, 2516, 2438, 2405, -1, + 2516, 2405, 2407, -1, 2407, 2374, 2516, -1, + 2407, 2517, 2374, -1, 2517, 2407, 2406, -1, + 2518, 2519, 2520, -1, 2520, 2519, 2521, -1, + 2521, 2406, 2520, -1, 2521, 2517, 2406, -1, + 2521, 2374, 2517, -1, 2374, 2521, 2519, -1, + 2522, 2523, 2524, -1, 2522, 2525, 2526, -1, + 2522, 2524, 2525, -1, 2527, 2525, 2524, -1, + 2527, 2528, 2525, -1, 2528, 2527, 2529, -1, + 2529, 2530, 2528, -1, 2530, 2529, 2531, -1, + 2531, 2532, 2530, -1, 2532, 2531, 2533, -1, + 2533, 2534, 2532, -1, 2534, 2533, 2535, -1, + 2535, 2536, 2534, -1, 2536, 2535, 2537, -1, + 2537, 2538, 2536, -1, 2538, 2537, 2539, -1, + 2539, 2540, 2538, -1, 2540, 2539, 2541, -1, + 2542, 2543, 2544, -1, 2544, 2543, 2545, -1, + 2545, 2546, 2544, -1, 2546, 2545, 2547, -1, + 2547, 2548, 2546, -1, 2548, 2547, 2549, -1, + 2549, 2550, 2548, -1, 2550, 2549, 2551, -1, + 2551, 2552, 2550, -1, 2552, 2551, 2553, -1, + 2553, 2554, 2552, -1, 2554, 2553, 2555, -1, + 2555, 2556, 2554, -1, 2556, 2555, 2557, -1, + 2557, 2558, 2556, -1, 2558, 2557, 2559, -1, + 2559, 2560, 2558, -1, 2560, 2559, 2561, -1, + 2561, 2562, 2560, -1, 2562, 2561, 2563, -1, + 2563, 2564, 2562, -1, 2564, 2563, 2565, -1, + 2565, 2566, 2564, -1, 2566, 2565, 2567, -1, + 2567, 2568, 2566, -1, 2568, 2567, 2569, -1, + 2569, 2570, 2568, -1, 2570, 2569, 2571, -1, + 2571, 2572, 2570, -1, 2572, 2571, 2573, -1, + 2573, 2574, 2572, -1, 2574, 2573, 2575, -1, + 2575, 2576, 2574, -1, 2576, 2575, 2577, -1, + 2577, 2578, 2576, -1, 2578, 2577, 2579, -1, + 2579, 2580, 2578, -1, 2580, 2579, 2581, -1, + 2581, 2582, 2580, -1, 2582, 2581, 2583, -1, + 2583, 2584, 2582, -1, 2584, 2583, 2585, -1, + 2585, 2586, 2584, -1, 2586, 2585, 2587, -1, + 2587, 2588, 2586, -1, 2588, 2587, 2589, -1, + 2589, 2590, 2588, -1, 2590, 2589, 2591, -1, + 2591, 2592, 2590, -1, 2592, 2591, 2593, -1, + 2593, 2594, 2592, -1, 2594, 2593, 2595, -1, + 2595, 2596, 2594, -1, 2596, 2595, 2597, -1, + 2597, 2598, 2596, -1, 2598, 2597, 2599, -1, + 2599, 2600, 2598, -1, 2600, 2599, 2601, -1, + 2601, 2602, 2600, -1, 2602, 2601, 2603, -1, + 2603, 2604, 2602, -1, 2604, 2603, 2605, -1, + 2605, 2606, 2604, -1, 2606, 2605, 2607, -1, + 2607, 2608, 2606, -1, 2608, 2607, 2609, -1, + 2609, 2610, 2608, -1, 2610, 2609, 2611, -1, + 2611, 2612, 2610, -1, 2612, 2611, 2613, -1, + 2613, 2614, 2612, -1, 2614, 2613, 2615, -1, + 2615, 2616, 2614, -1, 2616, 2615, 2617, -1, + 2617, 2618, 2616, -1, 2618, 2617, 2619, -1, + 2619, 2620, 2618, -1, 2620, 2619, 2621, -1, + 2621, 2622, 2620, -1, 2622, 2621, 2623, -1, + 2623, 2624, 2622, -1, 2624, 2623, 2541, -1, + 2541, 2625, 2624, -1, 2625, 2541, 2539, -1, + 2539, 2626, 2625, -1, 2626, 2539, 2537, -1, + 2537, 2627, 2626, -1, 2627, 2537, 2535, -1, + 2535, 2628, 2627, -1, 2628, 2535, 2533, -1, + 2533, 2629, 2628, -1, 2629, 2533, 2531, -1, + 2531, 2630, 2629, -1, 2630, 2531, 2529, -1, + 2529, 2631, 2630, -1, 2631, 2529, 2527, -1, + 2631, 2527, 2632, -1, 2633, 2634, 2635, -1, + 2636, 2637, 2638, -1, 2639, 2637, 2636, -1, + 2636, 2640, 2639, -1, 2636, 2638, 2640, -1, + 2640, 2638, 2641, -1, 2641, 2642, 2640, -1, + 2642, 2641, 2643, -1, 2643, 2644, 2642, -1, + 2645, 2642, 2644, -1, 2642, 2645, 2646, -1, + 2646, 2640, 2642, -1, 2640, 2646, 2647, -1, + 2647, 2639, 2640, -1, 2639, 2647, 2648, -1, + 2648, 2637, 2639, -1, 2648, 2649, 2637, -1, + 2649, 2648, 2647, -1, 2649, 2647, 2650, -1, + 2650, 2637, 2649, -1, 2650, 2651, 2637, -1, + 2652, 2637, 2651, -1, 2651, 2653, 2652, -1, + 2651, 2654, 2653, -1, 2651, 2650, 2654, -1, + 2654, 2650, 2647, -1, 2647, 2655, 2654, -1, + 2655, 2647, 2646, -1, 2646, 2656, 2655, -1, + 2656, 2646, 2645, -1, 2657, 2658, 2659, -1, + 2657, 2660, 2658, -1, 2660, 2657, 2661, -1, + 2661, 2662, 2660, -1, 2662, 2661, 2663, -1, + 2663, 2664, 2662, -1, 2664, 2663, 2665, -1, + 2665, 2666, 2664, -1, 2666, 2665, 2667, -1, + 2667, 2668, 2666, -1, 2668, 2667, 2669, -1, + 2669, 2670, 2668, -1, 2670, 2669, 2671, -1, + 2671, 2672, 2670, -1, 2672, 2671, 2673, -1, + 2673, 2674, 2672, -1, 2674, 2673, 2675, -1, + 2675, 2676, 2674, -1, 2676, 2675, 2677, -1, + 2677, 2678, 2676, -1, 2678, 2677, 2679, -1, + 2679, 2680, 2678, -1, 2680, 2679, 2681, -1, + 2681, 2682, 2680, -1, 2682, 2681, 2683, -1, + 2683, 2684, 2682, -1, 2684, 2683, 2685, -1, + 2685, 2686, 2684, -1, 2686, 2685, 2687, -1, + 2687, 2688, 2686, -1, 2688, 2687, 2689, -1, + 2689, 2690, 2688, -1, 2690, 2689, 2691, -1, + 2691, 2692, 2690, -1, 2692, 2691, 2693, -1, + 2693, 2694, 2692, -1, 2694, 2693, 2695, -1, + 2695, 2696, 2694, -1, 2696, 2695, 2697, -1, + 2697, 2698, 2696, -1, 2698, 2697, 2699, -1, + 2699, 2700, 2698, -1, 2700, 2699, 2701, -1, + 2701, 2702, 2700, -1, 2702, 2701, 2703, -1, + 2703, 2704, 2702, -1, 2704, 2703, 2705, -1, + 2705, 2706, 2704, -1, 2706, 2705, 2707, -1, + 2707, 2708, 2706, -1, 2708, 2707, 2709, -1, + 2709, 2710, 2708, -1, 2710, 2709, 2711, -1, + 2711, 2712, 2710, -1, 2712, 2711, 2713, -1, + 2713, 2714, 2712, -1, 2714, 2713, 2715, -1, + 2715, 2716, 2714, -1, 2716, 2715, 2717, -1, + 2717, 2718, 2716, -1, 2718, 2717, 2719, -1, + 2719, 2720, 2718, -1, 2720, 2719, 2721, -1, + 2721, 2722, 2720, -1, 2722, 2721, 2723, -1, + 2723, 2724, 2722, -1, 2724, 2723, 2725, -1, + 2725, 2726, 2724, -1, 2726, 2725, 2727, -1, + 2727, 2728, 2726, -1, 2728, 2727, 2729, -1, + 2729, 2730, 2728, -1, 2730, 2729, 2731, -1, + 2731, 2732, 2730, -1, 2732, 2731, 2733, -1, + 2733, 2734, 2732, -1, 2734, 2733, 2735, -1, + 2735, 2736, 2734, -1, 2736, 2735, 2737, -1, + 2737, 2738, 2736, -1, 2738, 2737, 2739, -1, + 2739, 2740, 2738, -1, 2740, 2739, 2741, -1, + 2741, 2742, 2740, -1, 2742, 2741, 2743, -1, + 2743, 2744, 2742, -1, 2744, 2743, 2745, -1, + 2745, 2746, 2744, -1, 2746, 2745, 2747, -1, + 2747, 2748, 2746, -1, 2748, 2747, 2749, -1, + 2749, 2750, 2748, -1, 2750, 2749, 2751, -1, + 2751, 2752, 2750, -1, 2752, 2751, 2753, -1, + 2753, 2754, 2752, -1, 2754, 2753, 2755, -1, + 2755, 2756, 2754, -1, 2756, 2755, 2757, -1, + 2757, 2758, 2756, -1, 2759, 2760, 2758, -1, + 2758, 2757, 2759, -1, 2761, 2762, 2763, -1, + 2763, 2764, 2761, -1, 2765, 2766, 2761, -1, + 2761, 2767, 2765, -1, 2767, 2761, 2764, -1, + 2764, 2768, 2767, -1, 2768, 2764, 2769, -1, + 2769, 2770, 2768, -1, 2770, 2769, 2771, -1, + 2771, 2772, 2770, -1, 2772, 2771, 2773, -1, + 2773, 2774, 2772, -1, 2774, 2773, 2775, -1, + 2775, 2776, 2774, -1, 2776, 2775, 2777, -1, + 2777, 2778, 2776, -1, 2778, 2777, 2779, -1, + 2779, 2780, 2778, -1, 2780, 2779, 2781, -1, + 2781, 2782, 2780, -1, 2782, 2781, 2783, -1, + 2783, 2784, 2782, -1, 2784, 2783, 2785, -1, + 2785, 2786, 2784, -1, 2786, 2785, 2787, -1, + 2787, 2788, 2786, -1, 2788, 2787, 2789, -1, + 2789, 2790, 2788, -1, 2790, 2789, 2791, -1, + 2791, 2792, 2790, -1, 2792, 2791, 2793, -1, + 2793, 2794, 2792, -1, 2794, 2793, 2795, -1, + 2795, 2796, 2794, -1, 2796, 2795, 2797, -1, + 2797, 2798, 2796, -1, 2798, 2797, 2799, -1, + 2799, 2800, 2798, -1, 2800, 2799, 2801, -1, + 2801, 2802, 2800, -1, 2802, 2801, 2803, -1, + 2803, 2804, 2802, -1, 2804, 2803, 2805, -1, + 2805, 2806, 2804, -1, 2806, 2805, 2807, -1, + 2807, 2808, 2806, -1, 2808, 2807, 2809, -1, + 2809, 2810, 2808, -1, 2810, 2809, 2811, -1, + 2811, 2812, 2810, -1, 2812, 2811, 2813, -1, + 2813, 2814, 2812, -1, 2814, 2813, 2815, -1, + 2815, 2816, 2814, -1, 2816, 2815, 2817, -1, + 2817, 2818, 2816, -1, 2818, 2817, 2819, -1, + 2819, 2820, 2818, -1, 2820, 2819, 2821, -1, + 2821, 2822, 2820, -1, 2822, 2821, 2823, -1, + 2823, 2824, 2822, -1, 2824, 2823, 2825, -1, + 2825, 2826, 2824, -1, 2826, 2825, 2827, -1, + 2827, 2828, 2826, -1, 2828, 2827, 2829, -1, + 2829, 2830, 2828, -1, 2830, 2829, 2831, -1, + 2831, 2832, 2830, -1, 2832, 2831, 2833, -1, + 2833, 2834, 2832, -1, 2834, 2833, 2835, -1, + 2835, 2836, 2834, -1, 2836, 2835, 2837, -1, + 2837, 2838, 2836, -1, 2838, 2837, 2839, -1, + 2839, 2840, 2838, -1, 2840, 2839, 2841, -1, + 2841, 2842, 2840, -1, 2842, 2841, 2843, -1, + 2843, 2844, 2842, -1, 2844, 2843, 2845, -1, + 2845, 2846, 2844, -1, 2846, 2845, 2847, -1, + 2847, 2848, 2846, -1, 2848, 2847, 2849, -1, + 2849, 2850, 2848, -1, 2850, 2849, 2851, -1, + 2851, 2852, 2850, -1, 2852, 2851, 2853, -1, + 2853, 2854, 2852, -1, 2854, 2853, 2855, -1, + 2855, 2856, 2854, -1, 2856, 2855, 2857, -1, + 2857, 2858, 2856, -1, 2858, 2857, 2859, -1, + 2859, 2860, 2858, -1, 2860, 2859, 2861, -1, + 2861, 2862, 2860, -1, 2862, 2863, 2864, -1, + 2862, 2861, 2863, -1, 2863, 2865, 2866, -1, + 2863, 2867, 2865, -1, 2867, 2863, 2861, -1, + 2861, 2868, 2867, -1, 2868, 2861, 2859, -1, + 2859, 2869, 2868, -1, 2869, 2859, 2857, -1, + 2857, 2870, 2869, -1, 2870, 2857, 2855, -1, + 2855, 2871, 2870, -1, 2871, 2855, 2853, -1, + 2853, 2872, 2871, -1, 2872, 2853, 2851, -1, + 2851, 2873, 2872, -1, 2873, 2851, 2849, -1, + 2849, 2874, 2873, -1, 2874, 2849, 2847, -1, + 2847, 2875, 2874, -1, 2875, 2847, 2845, -1, + 2845, 2876, 2875, -1, 2876, 2845, 2843, -1, + 2843, 2877, 2876, -1, 2877, 2843, 2841, -1, + 2841, 2878, 2877, -1, 2878, 2841, 2839, -1, + 2839, 2879, 2878, -1, 2879, 2839, 2837, -1, + 2837, 2880, 2879, -1, 2880, 2837, 2835, -1, + 2835, 2881, 2880, -1, 2881, 2835, 2833, -1, + 2833, 2882, 2881, -1, 2882, 2833, 2831, -1, + 2831, 2883, 2882, -1, 2883, 2831, 2829, -1, + 2829, 2884, 2883, -1, 2884, 2829, 2827, -1, + 2827, 2885, 2884, -1, 2885, 2827, 2825, -1, + 2825, 2886, 2885, -1, 2886, 2825, 2823, -1, + 2823, 2887, 2886, -1, 2887, 2823, 2821, -1, + 2821, 2888, 2887, -1, 2888, 2821, 2819, -1, + 2819, 2889, 2888, -1, 2889, 2819, 2817, -1, + 2817, 2890, 2889, -1, 2890, 2817, 2815, -1, + 2815, 2891, 2890, -1, 2891, 2815, 2813, -1, + 2813, 2892, 2891, -1, 2892, 2813, 2811, -1, + 2811, 2893, 2892, -1, 2893, 2811, 2809, -1, + 2809, 2894, 2893, -1, 2894, 2809, 2807, -1, + 2807, 2895, 2894, -1, 2895, 2807, 2805, -1, + 2805, 2896, 2895, -1, 2896, 2805, 2803, -1, + 2803, 2897, 2896, -1, 2897, 2803, 2801, -1, + 2801, 2898, 2897, -1, 2898, 2801, 2799, -1, + 2799, 2899, 2898, -1, 2899, 2799, 2797, -1, + 2797, 2900, 2899, -1, 2900, 2797, 2795, -1, + 2795, 2901, 2900, -1, 2901, 2795, 2793, -1, + 2793, 2902, 2901, -1, 2902, 2793, 2791, -1, + 2791, 2903, 2902, -1, 2903, 2791, 2789, -1, + 2789, 2904, 2903, -1, 2904, 2789, 2787, -1, + 2787, 2905, 2904, -1, 2905, 2787, 2785, -1, + 2785, 2906, 2905, -1, 2906, 2785, 2783, -1, + 2783, 2907, 2906, -1, 2907, 2783, 2781, -1, + 2781, 2908, 2907, -1, 2908, 2781, 2779, -1, + 2779, 2909, 2908, -1, 2909, 2779, 2777, -1, + 2777, 2910, 2909, -1, 2910, 2777, 2775, -1, + 2775, 2911, 2910, -1, 2911, 2775, 2773, -1, + 2773, 2912, 2911, -1, 2912, 2773, 2771, -1, + 2771, 2913, 2912, -1, 2913, 2771, 2769, -1, + 2769, 2914, 2913, -1, 2914, 2769, 2764, -1, + 2764, 2763, 2914, -1, 2759, 2763, 2915, -1, + 2759, 2914, 2763, -1, 2914, 2759, 2757, -1, + 2757, 2913, 2914, -1, 2913, 2757, 2755, -1, + 2755, 2912, 2913, -1, 2912, 2755, 2753, -1, + 2753, 2911, 2912, -1, 2911, 2753, 2751, -1, + 2751, 2910, 2911, -1, 2910, 2751, 2749, -1, + 2749, 2909, 2910, -1, 2909, 2749, 2747, -1, + 2747, 2908, 2909, -1, 2908, 2747, 2745, -1, + 2745, 2907, 2908, -1, 2907, 2745, 2743, -1, + 2743, 2906, 2907, -1, 2906, 2743, 2741, -1, + 2741, 2905, 2906, -1, 2905, 2741, 2739, -1, + 2739, 2904, 2905, -1, 2904, 2739, 2737, -1, + 2737, 2903, 2904, -1, 2903, 2737, 2735, -1, + 2735, 2902, 2903, -1, 2902, 2735, 2733, -1, + 2733, 2901, 2902, -1, 2901, 2733, 2731, -1, + 2731, 2900, 2901, -1, 2900, 2731, 2729, -1, + 2729, 2899, 2900, -1, 2899, 2729, 2727, -1, + 2727, 2898, 2899, -1, 2898, 2727, 2725, -1, + 2725, 2897, 2898, -1, 2897, 2725, 2723, -1, + 2723, 2896, 2897, -1, 2896, 2723, 2721, -1, + 2721, 2895, 2896, -1, 2895, 2721, 2719, -1, + 2719, 2894, 2895, -1, 2894, 2719, 2717, -1, + 2717, 2893, 2894, -1, 2893, 2717, 2715, -1, + 2715, 2892, 2893, -1, 2892, 2715, 2713, -1, + 2713, 2891, 2892, -1, 2891, 2713, 2711, -1, + 2711, 2890, 2891, -1, 2890, 2711, 2709, -1, + 2709, 2889, 2890, -1, 2889, 2709, 2707, -1, + 2707, 2888, 2889, -1, 2888, 2707, 2705, -1, + 2705, 2887, 2888, -1, 2887, 2705, 2703, -1, + 2703, 2886, 2887, -1, 2886, 2703, 2701, -1, + 2701, 2885, 2886, -1, 2885, 2701, 2699, -1, + 2699, 2884, 2885, -1, 2884, 2699, 2697, -1, + 2697, 2883, 2884, -1, 2883, 2697, 2695, -1, + 2695, 2882, 2883, -1, 2882, 2695, 2693, -1, + 2693, 2881, 2882, -1, 2881, 2693, 2691, -1, + 2691, 2880, 2881, -1, 2880, 2691, 2689, -1, + 2689, 2879, 2880, -1, 2879, 2689, 2687, -1, + 2687, 2878, 2879, -1, 2878, 2687, 2685, -1, + 2685, 2877, 2878, -1, 2877, 2685, 2683, -1, + 2683, 2876, 2877, -1, 2876, 2683, 2681, -1, + 2681, 2875, 2876, -1, 2875, 2681, 2679, -1, + 2679, 2874, 2875, -1, 2874, 2679, 2677, -1, + 2677, 2873, 2874, -1, 2873, 2677, 2675, -1, + 2675, 2872, 2873, -1, 2872, 2675, 2673, -1, + 2673, 2871, 2872, -1, 2871, 2673, 2671, -1, + 2671, 2870, 2871, -1, 2870, 2671, 2669, -1, + 2669, 2869, 2870, -1, 2869, 2669, 2667, -1, + 2667, 2868, 2869, -1, 2868, 2667, 2665, -1, + 2665, 2867, 2868, -1, 2867, 2665, 2663, -1, + 2663, 2865, 2867, -1, 2865, 2663, 2661, -1, + 2865, 2661, 2916, -1, 2917, 2918, 2656, -1, + 2917, 2919, 2918, -1, 2919, 2917, 2920, -1, + 2920, 2916, 2919, -1, 2916, 2920, 2921, -1, + 2921, 2865, 2916, -1, 2921, 2866, 2865, -1, + 2921, 2922, 2866, -1, 2922, 2921, 2920, -1, + 2920, 2923, 2922, -1, 2923, 2920, 2917, -1, + 2917, 2656, 2923, -1, 2656, 2645, 2923, -1, + 2924, 2923, 2645, -1, 2924, 2922, 2923, -1, + 2922, 2924, 2925, -1, 2925, 2866, 2922, -1, + 2866, 2925, 2926, -1, 2926, 2863, 2866, -1, + 2926, 2864, 2863, -1, 2926, 2927, 2864, -1, + 2927, 2926, 2925, -1, 2925, 2928, 2927, -1, + 2928, 2925, 2924, -1, 2924, 2645, 2928, -1, + 2645, 2644, 2928, -1, 2929, 2928, 2644, -1, + 2929, 2927, 2928, -1, 2927, 2929, 2930, -1, + 2930, 2864, 2927, -1, 2864, 2930, 2931, -1, + 2931, 2862, 2864, -1, 2931, 2932, 2862, -1, + 2931, 2933, 2932, -1, 2933, 2931, 2930, -1, + 2930, 2934, 2933, -1, 2934, 2930, 2929, -1, + 2929, 2644, 2934, -1, 2644, 2935, 2934, -1, + 2644, 2643, 2935, -1, 2936, 2937, 2938, -1, + 2936, 2939, 2937, -1, 2937, 2940, 2941, -1, + 2937, 2942, 2940, -1, 2942, 2937, 2939, -1, + 2939, 2943, 2942, -1, 2944, 2945, 2943, -1, + 2943, 2939, 2944, -1, 2946, 2947, 2948, -1, + 2946, 2949, 2947, -1, 2946, 2950, 2949, -1, + 2946, 2948, 2950, -1, 2950, 2948, 2944, -1, + 2944, 2951, 2950, -1, 2951, 2944, 2939, -1, + 2939, 2936, 2951, -1, 2935, 2936, 2952, -1, + 2935, 2951, 2936, -1, 2951, 2935, 2643, -1, + 2643, 2950, 2951, -1, 2950, 2643, 2641, -1, + 2641, 2949, 2950, -1, 2949, 2641, 2953, -1, + 2953, 2947, 2949, -1, 2953, 2954, 2947, -1, + 2954, 2953, 2641, -1, 2954, 2641, 2638, -1, + 2638, 2947, 2954, -1, 2947, 2638, 2637, -1, + 2955, 2956, 2957, -1, 2958, 2959, 2960, -1, + 2958, 2960, 2961, -1, 2961, 2962, 2958, -1, + 2962, 2961, 2963, -1, 2963, 2964, 2962, -1, + 2965, 2966, 2967, -1, 2967, 2968, 2965, -1, + 2968, 2967, 2969, -1, 2969, 2970, 2968, -1, + 2970, 2969, 2971, -1, 2971, 2972, 2970, -1, + 2972, 2971, 2973, -1, 2973, 2974, 2972, -1, + 2974, 2973, 2975, -1, 2975, 2976, 2974, -1, + 2976, 2975, 2977, -1, 2977, 2978, 2976, -1, + 2978, 2977, 2979, -1, 2979, 2980, 2978, -1, + 2980, 2979, 2981, -1, 2981, 2982, 2980, -1, + 2982, 2981, 2983, -1, 2983, 2984, 2982, -1, + 2984, 2983, 2985, -1, 2985, 2986, 2984, -1, + 2986, 2985, 2987, -1, 2987, 2988, 2986, -1, + 2988, 2987, 2989, -1, 2989, 2990, 2988, -1, + 2990, 2989, 2991, -1, 2991, 2992, 2990, -1, + 2992, 2991, 2993, -1, 2993, 2994, 2992, -1, + 2994, 2993, 2995, -1, 2995, 2996, 2994, -1, + 2996, 2995, 2997, -1, 2997, 2998, 2996, -1, + 2998, 2997, 2999, -1, 2999, 3000, 2998, -1, + 3000, 2999, 3001, -1, 3001, 3002, 3000, -1, + 3002, 3001, 3003, -1, 3003, 3004, 3002, -1, + 3004, 3003, 3005, -1, 3005, 3006, 3004, -1, + 3006, 3005, 3007, -1, 3007, 3008, 3006, -1, + 3008, 3007, 3009, -1, 3009, 3010, 3008, -1, + 3010, 3009, 3011, -1, 3011, 3012, 3010, -1, + 3012, 3011, 3013, -1, 3012, 3013, 3014, -1, + 3014, 3015, 3012, -1, 3015, 3014, 3016, -1, + 3016, 3017, 3015, -1, 3017, 3016, 3018, -1, + 3018, 3019, 3017, -1, 3019, 3018, 3020, -1, + 3020, 3021, 3019, -1, 3021, 3020, 3022, -1, + 3022, 3023, 3021, -1, 3023, 3022, 3024, -1, + 3024, 3025, 3023, -1, 3025, 3024, 3026, -1, + 3026, 3027, 3025, -1, 3027, 3026, 3028, -1, + 3028, 3029, 3027, -1, 3029, 3028, 3030, -1, + 3030, 3031, 3029, -1, 3031, 3030, 3032, -1, + 3032, 3033, 3031, -1, 3033, 3032, 3034, -1, + 3034, 3035, 3033, -1, 3035, 3034, 3036, -1, + 3036, 3037, 3035, -1, 3037, 3036, 3038, -1, + 3038, 3039, 3037, -1, 3039, 3038, 3040, -1, + 3040, 3041, 3039, -1, 3041, 3040, 3042, -1, + 3042, 3043, 3041, -1, 3043, 3042, 3044, -1, + 3044, 3045, 3043, -1, 3045, 3044, 3046, -1, + 3046, 3047, 3045, -1, 3047, 3046, 3048, -1, + 3048, 3049, 3047, -1, 3049, 3048, 3050, -1, + 3050, 3051, 3049, -1, 3051, 3050, 3052, -1, + 3052, 3053, 3051, -1, 3053, 3052, 3054, -1, + 3054, 3055, 3053, -1, 3055, 3054, 3056, -1, + 3056, 3057, 3055, -1, 3057, 3056, 3058, -1, + 3058, 3059, 3057, -1, 3059, 3058, 3060, -1, + 3060, 3061, 3059, -1, 3062, 3063, 3064, -1, + 3065, 3066, 3067, -1, 3067, 3068, 3065, -1, + 3068, 3067, 3069, -1, 3069, 3070, 3068, -1, + 3070, 3069, 3071, -1, 3071, 3072, 3070, -1, + 3073, 3074, 3062, -1, 3073, 3062, 3075, -1, + 3075, 3076, 3073, -1, 3076, 3075, 3077, -1, + 3077, 3078, 3076, -1, 3078, 3077, 3079, -1, + 3079, 3080, 3078, -1, 3080, 3079, 3081, -1, + 3081, 3082, 3080, -1, 3082, 3081, 3083, -1, + 3083, 3084, 3082, -1, 3084, 3083, 3072, -1, + 3072, 3071, 3084, -1, 3071, 3085, 3084, -1, + 3085, 3071, 3069, -1, 3069, 3086, 3085, -1, + 3086, 3069, 3067, -1, 3067, 3087, 3086, -1, + 3087, 3067, 3066, -1, 3066, 3088, 3087, -1, + 3088, 3066, 3089, -1, 3089, 3090, 3088, -1, + 3091, 3092, 3093, -1, 3092, 3091, 3090, -1, + 3092, 3090, 3089, -1, 3089, 3066, 3092, -1, + 3066, 3093, 3092, -1, 3066, 3065, 3093, -1, + 3093, 3094, 3095, -1, 3094, 3093, 3065, -1, + 3065, 3096, 3094, -1, 3096, 3065, 3068, -1, + 3068, 3097, 3096, -1, 3097, 3068, 3070, -1, + 3070, 3098, 3097, -1, 3098, 3070, 3072, -1, + 3072, 3099, 3098, -1, 3099, 3072, 3083, -1, + 3083, 3100, 3099, -1, 3100, 3083, 3081, -1, + 3081, 3101, 3100, -1, 3101, 3081, 3079, -1, + 3079, 3102, 3101, -1, 3102, 3079, 3077, -1, + 3077, 3103, 3102, -1, 3103, 3077, 3075, -1, + 3075, 3104, 3103, -1, 3104, 3075, 3062, -1, + 3062, 3064, 3104, -1, 3064, 3061, 3105, -1, + 3105, 3104, 3064, -1, 3104, 3105, 3106, -1, + 3106, 3103, 3104, -1, 3103, 3106, 3107, -1, + 3107, 3102, 3103, -1, 3102, 3107, 3108, -1, + 3108, 3101, 3102, -1, 3101, 3108, 3109, -1, + 3109, 3100, 3101, -1, 3100, 3109, 3110, -1, + 3110, 3099, 3100, -1, 3099, 3110, 3111, -1, + 3111, 3098, 3099, -1, 3098, 3111, 3112, -1, + 3112, 3097, 3098, -1, 3097, 3112, 3113, -1, + 3113, 3096, 3097, -1, 3096, 3113, 3114, -1, + 3114, 3094, 3096, -1, 3094, 3114, 3115, -1, + 3115, 3095, 3094, -1, 3095, 3116, 3117, -1, + 3095, 3115, 3116, -1, 3118, 3119, 3120, -1, + 3121, 3122, 3123, -1, 3123, 3124, 3121, -1, + 3124, 3123, 3125, -1, 3125, 3126, 3124, -1, + 3126, 3125, 3127, -1, 3127, 3128, 3126, -1, + 3128, 3127, 3129, -1, 3129, 3130, 3128, -1, + 3130, 3129, 3131, -1, 3131, 3132, 3130, -1, + 3132, 3131, 3133, -1, 3133, 3134, 3132, -1, + 3134, 3133, 3135, -1, 3135, 3136, 3134, -1, + 3136, 3135, 3137, -1, 3137, 3138, 3136, -1, + 3138, 3137, 3139, -1, 3139, 3140, 3138, -1, + 3140, 3139, 3141, -1, 3141, 3142, 3140, -1, + 3142, 3141, 3143, -1, 3143, 3144, 3142, -1, + 3144, 3143, 3145, -1, 3145, 3146, 3144, -1, + 3146, 3145, 3147, -1, 3147, 3148, 3146, -1, + 3148, 3147, 3149, -1, 3149, 3150, 3148, -1, + 3151, 3152, 3153, -1, 3151, 3153, 3154, -1, + 3154, 3155, 3151, -1, 3155, 3154, 3156, -1, + 3156, 3157, 3155, -1, 3157, 3156, 3158, -1, + 3158, 3159, 3157, -1, 3159, 3158, 3160, -1, + 3160, 3161, 3159, -1, 3161, 3160, 3162, -1, + 3162, 3163, 3161, -1, 3163, 3162, 3164, -1, + 3164, 3165, 3163, -1, 3165, 3164, 3166, -1, + 3166, 3167, 3165, -1, 3166, 3168, 3167, -1, + 3168, 3166, 3169, -1, 3169, 3170, 3168, -1, + 3170, 3169, 3171, -1, 3171, 3172, 3170, -1, + 3172, 3171, 3173, -1, 3173, 3174, 3172, -1, + 3174, 3173, 3175, -1, 3175, 3176, 3174, -1, + 3176, 3175, 3177, -1, 3177, 3178, 3176, -1, + 3178, 3177, 3179, -1, 3179, 3180, 3178, -1, + 3180, 3179, 3181, -1, 3181, 3182, 3180, -1, + 3182, 3181, 3183, -1, 3183, 3184, 3182, -1, + 3185, 3186, 3187, -1, 3187, 3188, 3185, -1, + 3188, 3187, 3189, -1, 3189, 3190, 3188, -1, + 3190, 3189, 3191, -1, 3191, 3192, 3190, -1, + 3192, 3191, 3193, -1, 3193, 3194, 3192, -1, + 3194, 3193, 3195, -1, 3195, 3196, 3194, -1, + 3196, 3195, 3197, -1, 3197, 3198, 3196, -1, + 3198, 3197, 3199, -1, 3199, 3200, 3198, -1, + 3200, 3199, 3201, -1, 3201, 3202, 3200, -1, + 3202, 3201, 3203, -1, 3203, 3204, 3202, -1, + 3204, 3203, 3205, -1, 3205, 3206, 3204, -1, + 3207, 3208, 3209, -1, 3208, 3207, 3210, -1, + 3210, 3211, 3208, -1, 3211, 3210, 3212, -1, + 3212, 3213, 3211, -1, 3213, 3212, 3214, -1, + 3214, 3215, 3213, -1, 3215, 3214, 3216, -1, + 3216, 3217, 3215, -1, 3217, 3216, 3218, -1, + 3218, 3219, 3217, -1, 3219, 3218, 3220, -1, + 3220, 3221, 3219, -1, 3221, 3220, 3222, -1, + 3222, 3223, 3221, -1, 3223, 3222, 3224, -1, + 3224, 3225, 3223, -1, 3225, 3224, 3226, -1, + 3226, 3227, 3225, -1, 3227, 3226, 3228, -1, + 3228, 3229, 3227, -1, 3229, 3228, 3230, -1, + 3230, 3231, 3229, -1, 3231, 3230, 3232, -1, + 3232, 3233, 3231, -1, 3233, 3232, 3234, -1, + 3234, 3235, 3233, -1, 3235, 3234, 3236, -1, + 3237, 3238, 3239, -1, 3240, 3241, 3242, -1, + 3240, 3242, 3243, -1, 3244, 3245, 3246, -1, + 3246, 3247, 3244, -1, 3247, 3246, 3248, -1, + 3248, 3249, 3247, -1, 3249, 3248, 3250, -1, + 3250, 3251, 3249, -1, 3251, 3250, 3252, -1, + 3252, 3253, 3251, -1, 3253, 3252, 3254, -1, + 3254, 3255, 3253, -1, 3255, 3254, 3256, -1, + 3256, 3257, 3255, -1, 3257, 3256, 3258, -1, + 3258, 3259, 3257, -1, 3259, 3258, 3260, -1, + 3260, 3261, 3259, -1, 3261, 3260, 3262, -1, + 3262, 3263, 3261, -1, 3263, 3262, 3264, -1, + 3264, 3265, 3263, -1, 3265, 3264, 3266, -1, + 3266, 3267, 3265, -1, 3267, 3266, 3268, -1, + 3268, 3269, 3267, -1, 3269, 3268, 3270, -1, + 3270, 3271, 3269, -1, 3271, 3270, 3272, -1, + 3272, 3273, 3271, -1, 3273, 3272, 3274, -1, + 3274, 3275, 3273, -1, 3275, 3274, 3276, -1, + 3276, 3277, 3275, -1, 3277, 3276, 3243, -1, + 3277, 3243, 3242, -1, 3277, 3242, 3278, -1, + 3278, 3275, 3277, -1, 3275, 3278, 3279, -1, + 3279, 3273, 3275, -1, 3273, 3279, 3280, -1, + 3280, 3271, 3273, -1, 3271, 3280, 3281, -1, + 3281, 3269, 3271, -1, 3269, 3281, 3282, -1, + 3282, 3267, 3269, -1, 3267, 3282, 3283, -1, + 3283, 3265, 3267, -1, 3265, 3283, 3284, -1, + 3284, 3263, 3265, -1, 3263, 3284, 3285, -1, + 3285, 3261, 3263, -1, 3261, 3285, 3286, -1, + 3286, 3259, 3261, -1, 3259, 3286, 3287, -1, + 3287, 3257, 3259, -1, 3257, 3287, 3288, -1, + 3288, 3255, 3257, -1, 3255, 3288, 3289, -1, + 3289, 3253, 3255, -1, 3253, 3289, 3290, -1, + 3290, 3251, 3253, -1, 3251, 3290, 3291, -1, + 3291, 3249, 3251, -1, 3249, 3291, 3292, -1, + 3292, 3247, 3249, -1, 3247, 3292, 3293, -1, + 3293, 3244, 3247, -1, 3244, 3293, 3294, -1, + 3294, 3245, 3244, -1, 3295, 3296, 3297, -1, + 3297, 3298, 3295, -1, 3298, 3297, 3299, -1, + 3299, 3300, 3298, -1, 3300, 3299, 3301, -1, + 3301, 3302, 3300, -1, 3302, 3301, 3303, -1, + 3303, 3304, 3302, -1, 3304, 3303, 3305, -1, + 3305, 3306, 3304, -1, 3306, 3305, 3307, -1, + 3307, 3308, 3306, -1, 3308, 3307, 3309, -1, + 3309, 3310, 3308, -1, 3310, 3309, 3311, -1, + 3311, 3312, 3310, -1, 3312, 3311, 3313, -1, + 3313, 3314, 3312, -1, 3314, 3313, 3315, -1, + 3315, 3316, 3314, -1, 3316, 3315, 3317, -1, + 3317, 3318, 3316, -1, 3318, 3317, 3319, -1, + 3319, 3320, 3318, -1, 3320, 3319, 3321, -1, + 3321, 3322, 3320, -1, 3322, 3321, 3245, -1, + 3245, 3294, 3322, -1, 3323, 3322, 3294, -1, + 3294, 3324, 3323, -1, 3324, 3294, 3293, -1, + 3293, 3325, 3324, -1, 3325, 3293, 3292, -1, + 3292, 3326, 3325, -1, 3326, 3292, 3291, -1, + 3291, 3327, 3326, -1, 3327, 3291, 3290, -1, + 3290, 3328, 3327, -1, 3328, 3290, 3289, -1, + 3289, 3329, 3328, -1, 3329, 3289, 3288, -1, + 3288, 3330, 3329, -1, 3330, 3288, 3287, -1, + 3287, 3331, 3330, -1, 3331, 3287, 3286, -1, + 3286, 3332, 3331, -1, 3332, 3286, 3285, -1, + 3285, 3333, 3332, -1, 3333, 3285, 3284, -1, + 3284, 3334, 3333, -1, 3334, 3284, 3283, -1, + 3283, 3335, 3334, -1, 3335, 3283, 3282, -1, + 3282, 3336, 3335, -1, 3336, 3282, 3281, -1, + 3281, 3337, 3336, -1, 3337, 3281, 3280, -1, + 3280, 3338, 3337, -1, 3338, 3280, 3279, -1, + 3279, 3339, 3338, -1, 3339, 3279, 3278, -1, + 3278, 3340, 3339, -1, 3340, 3278, 3242, -1, + 3242, 3341, 3340, -1, 3341, 3242, 3241, -1, + 3241, 3342, 3341, -1, 3342, 3241, 3343, -1, + 3343, 3344, 3342, -1, 3344, 3343, 3345, -1, + 3345, 3346, 3344, -1, 3346, 3345, 3347, -1, + 3347, 3348, 3346, -1, 3348, 3347, 3349, -1, + 3349, 3350, 3348, -1, 3350, 3349, 3351, -1, + 3351, 3352, 3350, -1, 3352, 3351, 3353, -1, + 3352, 3353, 3354, -1, 3354, 3355, 3352, -1, + 3355, 3354, 3356, -1, 3356, 3357, 3355, -1, + 3357, 3356, 3358, -1, 3358, 3359, 3357, -1, + 3359, 3358, 3360, -1, 3360, 3361, 3359, -1, + 3361, 3360, 3362, -1, 3362, 3363, 3361, -1, + 3363, 3362, 3364, -1, 3364, 3365, 3363, -1, + 3366, 3367, 3368, -1, 3367, 3366, 3369, -1, + 3369, 3370, 3367, -1, 3370, 3369, 3371, -1, + 3371, 3372, 3370, -1, 3372, 3371, 3373, -1, + 3373, 3374, 3372, -1, 3374, 3373, 3375, -1, + 3375, 3376, 3374, -1, 3376, 3375, 3377, -1, + 3377, 3378, 3376, -1, 3378, 3377, 3379, -1, + 3379, 3380, 3378, -1, 3380, 3379, 3381, -1, + 3381, 3382, 3380, -1, 3382, 3381, 3383, -1, + 3383, 3384, 3382, -1, 3384, 3383, 3385, -1, + 3385, 3386, 3384, -1, 3386, 3385, 3387, -1, + 3387, 3388, 3386, -1, 3388, 3387, 3389, -1, + 3389, 3390, 3388, -1, 3390, 3389, 3391, -1, + 3391, 3392, 3390, -1, 3392, 3391, 3393, -1, + 3393, 3394, 3392, -1, 3394, 3393, 3395, -1, + 3395, 3396, 3394, -1, 3396, 3395, 3397, -1, + 3397, 3398, 3396, -1, 3398, 3397, 3399, -1, + 3399, 3400, 3398, -1, 3400, 3399, 3401, -1, + 3401, 3402, 3400, -1, 3402, 3401, 3365, -1, + 3365, 3364, 3402, -1, 3403, 3402, 3364, -1, + 3403, 3404, 3402, -1, 3405, 3406, 3407, -1, + 3406, 3405, 3408, -1, 3408, 3409, 3406, -1, + 3409, 3408, 3410, -1, 3410, 3411, 3409, -1, + 3411, 3410, 3412, -1, 3412, 3413, 3411, -1, + 3413, 3412, 3414, -1, 3414, 3415, 3413, -1, + 3415, 3414, 3416, -1, 3416, 3417, 3415, -1, + 3417, 3416, 3418, -1, 3418, 3419, 3417, -1, + 3419, 3418, 3420, -1, 3420, 3421, 3419, -1, + 3421, 3420, 3422, -1, 3422, 3423, 3421, -1, + 3423, 3422, 3424, -1, 3424, 3425, 3423, -1, + 3425, 3424, 3426, -1, 3426, 3427, 3425, -1, + 3427, 3426, 3428, -1, 3428, 3429, 3427, -1, + 3429, 3428, 3430, -1, 3430, 3431, 3429, -1, + 3431, 3430, 3432, -1, 3432, 3433, 3431, -1, + 3433, 3432, 3434, -1, 3434, 3435, 3433, -1, + 3435, 3434, 3436, -1, 3436, 3437, 3435, -1, + 3437, 3436, 3438, -1, 3438, 3404, 3437, -1, + 3438, 3402, 3404, -1, 3438, 3400, 3402, -1, + 3400, 3438, 3436, -1, 3436, 3398, 3400, -1, + 3398, 3436, 3434, -1, 3434, 3396, 3398, -1, + 3396, 3434, 3432, -1, 3432, 3394, 3396, -1, + 3394, 3432, 3430, -1, 3430, 3392, 3394, -1, + 3392, 3430, 3428, -1, 3428, 3390, 3392, -1, + 3390, 3428, 3426, -1, 3426, 3388, 3390, -1, + 3388, 3426, 3424, -1, 3424, 3386, 3388, -1, + 3386, 3424, 3422, -1, 3422, 3384, 3386, -1, + 3384, 3422, 3420, -1, 3420, 3382, 3384, -1, + 3382, 3420, 3418, -1, 3418, 3380, 3382, -1, + 3380, 3418, 3416, -1, 3416, 3378, 3380, -1, + 3378, 3416, 3414, -1, 3414, 3376, 3378, -1, + 3376, 3414, 3412, -1, 3412, 3374, 3376, -1, + 3374, 3412, 3410, -1, 3410, 3372, 3374, -1, + 3372, 3410, 3408, -1, 3408, 3370, 3372, -1, + 3370, 3408, 3405, -1, 3405, 3367, 3370, -1, + 3367, 3405, 3407, -1, 3407, 3368, 3367, -1, + 3368, 3407, 3439, -1, 3439, 3440, 3368, -1, + 3440, 3439, 3441, -1, 3441, 3442, 3440, -1, + 3442, 3441, 3443, -1, 3443, 3444, 3442, -1, + 3444, 3443, 3445, -1, 3445, 3446, 3444, -1, + 3446, 3445, 3447, -1, 3447, 3448, 3446, -1, + 3448, 3447, 3449, -1, 3449, 3450, 3448, -1, + 3450, 3449, 3451, -1, 3451, 3452, 3450, -1, + 3452, 3451, 3453, -1, 3453, 3454, 3452, -1, + 3454, 3453, 3455, -1, 3455, 3456, 3454, -1, + 3456, 3455, 3457, -1, 3457, 3458, 3456, -1, + 3458, 3457, 3459, -1, 3459, 3460, 3458, -1, + 3460, 3459, 3461, -1, 3461, 3462, 3460, -1, + 3462, 3461, 3463, -1, 3463, 3238, 3462, -1, + 3238, 3463, 3464, -1, 3464, 3239, 3238, -1, + 3465, 3466, 3239, -1, 3239, 3464, 3465, -1, + 3465, 3467, 3468, -1, 3465, 3469, 3467, -1, + 3469, 3465, 3464, -1, 3464, 3470, 3469, -1, + 3470, 3464, 3463, -1, 3463, 3471, 3470, -1, + 3471, 3463, 3461, -1, 3461, 3472, 3471, -1, + 3472, 3461, 3459, -1, 3459, 3473, 3472, -1, + 3473, 3459, 3457, -1, 3457, 3474, 3473, -1, + 3474, 3457, 3455, -1, 3455, 3475, 3474, -1, + 3475, 3455, 3453, -1, 3453, 3476, 3475, -1, + 3476, 3453, 3451, -1, 3451, 3477, 3476, -1, + 3477, 3451, 3449, -1, 3449, 3478, 3477, -1, + 3478, 3449, 3447, -1, 3447, 3479, 3478, -1, + 3479, 3447, 3445, -1, 3445, 3480, 3479, -1, + 3480, 3445, 3443, -1, 3443, 3481, 3480, -1, + 3481, 3443, 3441, -1, 3441, 3482, 3481, -1, + 3482, 3441, 3439, -1, 3439, 3483, 3482, -1, + 3483, 3439, 3407, -1, 3407, 3236, 3483, -1, + 3236, 3407, 3406, -1, 3406, 3235, 3236, -1, + 3235, 3406, 3409, -1, 3409, 3233, 3235, -1, + 3233, 3409, 3411, -1, 3411, 3231, 3233, -1, + 3231, 3411, 3413, -1, 3413, 3229, 3231, -1, + 3229, 3413, 3415, -1, 3415, 3227, 3229, -1, + 3227, 3415, 3417, -1, 3417, 3225, 3227, -1, + 3225, 3417, 3419, -1, 3419, 3223, 3225, -1, + 3223, 3419, 3421, -1, 3421, 3221, 3223, -1, + 3221, 3421, 3423, -1, 3423, 3219, 3221, -1, + 3219, 3423, 3425, -1, 3425, 3217, 3219, -1, + 3217, 3425, 3427, -1, 3427, 3215, 3217, -1, + 3215, 3427, 3429, -1, 3429, 3213, 3215, -1, + 3213, 3429, 3431, -1, 3431, 3211, 3213, -1, + 3211, 3431, 3433, -1, 3433, 3208, 3211, -1, + 3208, 3433, 3435, -1, 3435, 3209, 3208, -1, + 3209, 3435, 3437, -1, 3437, 3484, 3209, -1, + 3484, 3437, 3404, -1, 3404, 3485, 3484, -1, + 3485, 3404, 3403, -1, 3403, 3486, 3485, -1, + 3403, 3364, 3486, -1, 3487, 3486, 3364, -1, + 3487, 3364, 3362, -1, 3362, 3488, 3487, -1, + 3488, 3362, 3360, -1, 3360, 3489, 3488, -1, + 3489, 3360, 3358, -1, 3358, 3490, 3489, -1, + 3490, 3358, 3356, -1, 3356, 3491, 3490, -1, + 3491, 3356, 3354, -1, 3354, 3492, 3491, -1, + 3492, 3354, 3353, -1, 3353, 3493, 3492, -1, + 3353, 3494, 3493, -1, 3494, 3353, 3351, -1, + 3351, 3495, 3494, -1, 3495, 3351, 3349, -1, + 3349, 3496, 3495, -1, 3496, 3349, 3347, -1, + 3347, 3497, 3496, -1, 3497, 3347, 3345, -1, + 3345, 3498, 3497, -1, 3498, 3345, 3343, -1, + 3343, 3499, 3498, -1, 3499, 3343, 3241, -1, + 3241, 3240, 3499, -1, 3500, 3240, 3501, -1, + 3500, 3499, 3240, -1, 3499, 3500, 3502, -1, + 3502, 3498, 3499, -1, 3498, 3502, 3503, -1, + 3503, 3497, 3498, -1, 3497, 3503, 3504, -1, + 3504, 3496, 3497, -1, 3496, 3504, 3505, -1, + 3505, 3495, 3496, -1, 3495, 3505, 3506, -1, + 3506, 3494, 3495, -1, 3494, 3506, 3507, -1, + 3507, 3493, 3494, -1, 3493, 3507, 3508, -1, + 3493, 3508, 3509, -1, 3509, 3492, 3493, -1, + 3492, 3509, 3510, -1, 3510, 3491, 3492, -1, + 3491, 3510, 3511, -1, 3511, 3490, 3491, -1, + 3490, 3511, 3512, -1, 3512, 3489, 3490, -1, + 3489, 3512, 3513, -1, 3513, 3488, 3489, -1, + 3488, 3513, 3514, -1, 3514, 3487, 3488, -1, + 3514, 3515, 3487, -1, 3516, 3517, 3518, -1, + 3517, 3516, 3519, -1, 3519, 3520, 3517, -1, + 3520, 3519, 3521, -1, 3521, 3522, 3520, -1, + 3522, 3521, 3523, -1, 3523, 3524, 3522, -1, + 3524, 3523, 3525, -1, 3525, 3526, 3524, -1, + 3526, 3525, 3527, -1, 3527, 3528, 3526, -1, + 3528, 3527, 3515, -1, 3515, 3529, 3528, -1, + 3529, 3515, 3514, -1, 3514, 3530, 3529, -1, + 3530, 3514, 3513, -1, 3513, 3531, 3530, -1, + 3531, 3513, 3512, -1, 3512, 3532, 3531, -1, + 3532, 3512, 3511, -1, 3511, 3533, 3532, -1, + 3533, 3511, 3510, -1, 3510, 3534, 3533, -1, + 3534, 3510, 3509, -1, 3509, 3535, 3534, -1, + 3535, 3509, 3508, -1, 3508, 3536, 3535, -1, + 3508, 3537, 3536, -1, 3537, 3508, 3507, -1, + 3507, 3538, 3537, -1, 3538, 3507, 3506, -1, + 3506, 3539, 3538, -1, 3539, 3506, 3505, -1, + 3505, 3540, 3539, -1, 3540, 3505, 3504, -1, + 3504, 3541, 3540, -1, 3541, 3504, 3503, -1, + 3503, 3542, 3541, -1, 3542, 3503, 3502, -1, + 3502, 3543, 3542, -1, 3543, 3502, 3500, -1, + 3500, 3544, 3543, -1, 3544, 3500, 3501, -1, + 3501, 3545, 3544, -1, 3545, 3501, 3546, -1, + 3546, 3547, 3545, -1, 3547, 3546, 3548, -1, + 3548, 3549, 3547, -1, 3549, 3548, 3550, -1, + 3550, 3551, 3549, -1, 3551, 3550, 3552, -1, + 3552, 3553, 3551, -1, 3553, 3552, 3554, -1, + 3554, 3555, 3553, -1, 3555, 3554, 3556, -1, + 3556, 3557, 3555, -1, 3557, 3556, 3558, -1, + 3558, 3559, 3557, -1, 3559, 3558, 3560, -1, + 3560, 3561, 3559, -1, 3561, 3560, 3562, -1, + 3562, 3563, 3561, -1, 3563, 3562, 3564, -1, + 3564, 3565, 3563, -1, 3565, 3564, 3566, -1, + 3566, 3567, 3565, -1, 3567, 3566, 3568, -1, + 3568, 3569, 3567, -1, 3569, 3568, 3570, -1, + 3570, 3571, 3569, -1, 3571, 3570, 3572, -1, + 3572, 3573, 3571, -1, 3573, 3572, 3574, -1, + 3574, 3575, 3573, -1, 3575, 3574, 3576, -1, + 3576, 3577, 3575, -1, 3575, 3577, 3206, -1, + 3206, 3573, 3575, -1, 3573, 3206, 3205, -1, + 3205, 3571, 3573, -1, 3571, 3205, 3203, -1, + 3203, 3569, 3571, -1, 3569, 3203, 3201, -1, + 3201, 3567, 3569, -1, 3567, 3201, 3199, -1, + 3199, 3565, 3567, -1, 3565, 3199, 3197, -1, + 3197, 3563, 3565, -1, 3563, 3197, 3195, -1, + 3195, 3561, 3563, -1, 3561, 3195, 3193, -1, + 3193, 3559, 3561, -1, 3559, 3193, 3191, -1, + 3191, 3557, 3559, -1, 3557, 3191, 3189, -1, + 3189, 3555, 3557, -1, 3555, 3189, 3187, -1, + 3187, 3553, 3555, -1, 3553, 3187, 3186, -1, + 3186, 3551, 3553, -1, 3551, 3186, 3578, -1, + 3578, 3549, 3551, -1, 3549, 3578, 3579, -1, + 3579, 3547, 3549, -1, 3547, 3579, 3580, -1, + 3580, 3545, 3547, -1, 3545, 3580, 3581, -1, + 3581, 3544, 3545, -1, 3581, 3582, 3544, -1, + 3581, 3583, 3582, -1, 3583, 3581, 3580, -1, + 3580, 3584, 3583, -1, 3584, 3580, 3579, -1, + 3579, 3585, 3584, -1, 3585, 3579, 3578, -1, + 3578, 3586, 3585, -1, 3586, 3578, 3186, -1, + 3186, 3185, 3586, -1, 3586, 3185, 3587, -1, + 3587, 3585, 3586, -1, 3585, 3587, 3588, -1, + 3588, 3584, 3585, -1, 3584, 3588, 3589, -1, + 3589, 3583, 3584, -1, 3583, 3589, 3590, -1, + 3590, 3582, 3583, -1, 3582, 3590, 3184, -1, + 3184, 3183, 3582, -1, 3183, 3544, 3582, -1, + 3183, 3543, 3544, -1, 3543, 3183, 3181, -1, + 3181, 3542, 3543, -1, 3542, 3181, 3179, -1, + 3179, 3541, 3542, -1, 3541, 3179, 3177, -1, + 3177, 3540, 3541, -1, 3540, 3177, 3175, -1, + 3175, 3539, 3540, -1, 3539, 3175, 3173, -1, + 3173, 3538, 3539, -1, 3538, 3173, 3171, -1, + 3171, 3537, 3538, -1, 3537, 3171, 3169, -1, + 3169, 3536, 3537, -1, 3536, 3169, 3166, -1, + 3536, 3166, 3164, -1, 3164, 3535, 3536, -1, + 3535, 3164, 3162, -1, 3162, 3534, 3535, -1, + 3534, 3162, 3160, -1, 3160, 3533, 3534, -1, + 3533, 3160, 3158, -1, 3158, 3532, 3533, -1, + 3532, 3158, 3156, -1, 3156, 3531, 3532, -1, + 3531, 3156, 3154, -1, 3154, 3530, 3531, -1, + 3530, 3154, 3153, -1, 3153, 3529, 3530, -1, + 3153, 3591, 3529, -1, 3592, 3593, 3594, -1, + 3593, 3592, 3595, -1, 3595, 3596, 3593, -1, + 3596, 3595, 3597, -1, 3597, 3598, 3596, -1, + 3598, 3597, 3599, -1, 3599, 3600, 3598, -1, + 3600, 3599, 3601, -1, 3601, 3602, 3600, -1, + 3602, 3601, 3603, -1, 3603, 3604, 3602, -1, + 3604, 3603, 3591, -1, 3591, 3605, 3604, -1, + 3605, 3591, 3153, -1, 3605, 3153, 3152, -1, + 3605, 3152, 3606, -1, 3606, 3604, 3605, -1, + 3604, 3606, 3607, -1, 3607, 3602, 3604, -1, + 3602, 3607, 3608, -1, 3608, 3600, 3602, -1, + 3600, 3608, 3609, -1, 3609, 3598, 3600, -1, + 3598, 3609, 3610, -1, 3610, 3596, 3598, -1, + 3596, 3610, 3611, -1, 3611, 3593, 3596, -1, + 3593, 3611, 3612, -1, 3612, 3594, 3593, -1, + 3594, 3612, 3613, -1, 3613, 3614, 3594, -1, + 3614, 3613, 3615, -1, 3615, 3616, 3614, -1, + 3616, 3615, 3617, -1, 3617, 3618, 3616, -1, + 3618, 3617, 3619, -1, 3619, 3620, 3618, -1, + 3620, 3619, 3621, -1, 3621, 3622, 3620, -1, + 3622, 3621, 3623, -1, 3623, 3624, 3622, -1, + 3624, 3623, 3625, -1, 3625, 3626, 3624, -1, + 3626, 3625, 3627, -1, 3627, 3628, 3626, -1, + 3628, 3627, 3629, -1, 3629, 3630, 3628, -1, + 3631, 3630, 3150, -1, 3630, 3631, 3632, -1, + 3632, 3628, 3630, -1, 3628, 3632, 3633, -1, + 3633, 3626, 3628, -1, 3626, 3633, 3634, -1, + 3634, 3624, 3626, -1, 3624, 3634, 3635, -1, + 3635, 3622, 3624, -1, 3622, 3635, 3636, -1, + 3636, 3620, 3622, -1, 3620, 3636, 3637, -1, + 3637, 3618, 3620, -1, 3618, 3637, 3638, -1, + 3638, 3616, 3618, -1, 3616, 3638, 3639, -1, + 3639, 3614, 3616, -1, 3614, 3639, 3640, -1, + 3640, 3594, 3614, -1, 3594, 3640, 3641, -1, + 3641, 3592, 3594, -1, 3592, 3641, 3642, -1, + 3642, 3595, 3592, -1, 3595, 3642, 3643, -1, + 3643, 3597, 3595, -1, 3597, 3643, 3644, -1, + 3644, 3599, 3597, -1, 3599, 3644, 3645, -1, + 3645, 3601, 3599, -1, 3601, 3645, 3646, -1, + 3646, 3603, 3601, -1, 3603, 3646, 3647, -1, + 3647, 3591, 3603, -1, 3647, 3529, 3591, -1, + 3647, 3528, 3529, -1, 3528, 3647, 3646, -1, + 3646, 3526, 3528, -1, 3526, 3646, 3645, -1, + 3645, 3524, 3526, -1, 3524, 3645, 3644, -1, + 3644, 3522, 3524, -1, 3522, 3644, 3643, -1, + 3643, 3520, 3522, -1, 3520, 3643, 3642, -1, + 3642, 3517, 3520, -1, 3517, 3642, 3641, -1, + 3641, 3518, 3517, -1, 3518, 3641, 3640, -1, + 3640, 3648, 3518, -1, 3648, 3640, 3639, -1, + 3639, 3649, 3648, -1, 3649, 3639, 3638, -1, + 3638, 3650, 3649, -1, 3650, 3638, 3637, -1, + 3637, 3651, 3650, -1, 3651, 3637, 3636, -1, + 3636, 3652, 3651, -1, 3652, 3636, 3635, -1, + 3635, 3653, 3652, -1, 3653, 3635, 3634, -1, + 3634, 3654, 3653, -1, 3654, 3634, 3633, -1, + 3633, 3655, 3654, -1, 3655, 3633, 3632, -1, + 3632, 3656, 3655, -1, 3656, 3632, 3631, -1, + 3631, 3657, 3656, -1, 3657, 3631, 3150, -1, + 3150, 3149, 3657, -1, 3658, 3657, 3149, -1, + 3657, 3658, 3659, -1, 3659, 3656, 3657, -1, + 3656, 3659, 3660, -1, 3660, 3655, 3656, -1, + 3655, 3660, 3661, -1, 3661, 3654, 3655, -1, + 3654, 3661, 3662, -1, 3662, 3653, 3654, -1, + 3653, 3662, 3663, -1, 3663, 3652, 3653, -1, + 3652, 3663, 3664, -1, 3664, 3651, 3652, -1, + 3651, 3664, 3665, -1, 3665, 3650, 3651, -1, + 3650, 3665, 3666, -1, 3666, 3649, 3650, -1, + 3649, 3666, 3667, -1, 3667, 3648, 3649, -1, + 3648, 3667, 3668, -1, 3668, 3518, 3648, -1, + 3518, 3668, 3669, -1, 3669, 3516, 3518, -1, + 3516, 3669, 3670, -1, 3670, 3519, 3516, -1, + 3519, 3670, 3671, -1, 3671, 3521, 3519, -1, + 3521, 3671, 3672, -1, 3672, 3523, 3521, -1, + 3523, 3672, 3673, -1, 3673, 3525, 3523, -1, + 3525, 3673, 3674, -1, 3674, 3527, 3525, -1, + 3527, 3674, 3675, -1, 3675, 3515, 3527, -1, + 3675, 3487, 3515, -1, 3675, 3486, 3487, -1, + 3486, 3675, 3674, -1, 3674, 3485, 3486, -1, + 3485, 3674, 3673, -1, 3673, 3484, 3485, -1, + 3484, 3673, 3672, -1, 3672, 3209, 3484, -1, + 3209, 3672, 3671, -1, 3671, 3207, 3209, -1, + 3207, 3671, 3670, -1, 3670, 3210, 3207, -1, + 3210, 3670, 3669, -1, 3669, 3212, 3210, -1, + 3212, 3669, 3668, -1, 3668, 3214, 3212, -1, + 3214, 3668, 3667, -1, 3667, 3216, 3214, -1, + 3216, 3667, 3666, -1, 3666, 3218, 3216, -1, + 3218, 3666, 3665, -1, 3665, 3220, 3218, -1, + 3220, 3665, 3664, -1, 3664, 3222, 3220, -1, + 3222, 3664, 3663, -1, 3663, 3224, 3222, -1, + 3224, 3663, 3662, -1, 3662, 3226, 3224, -1, + 3226, 3662, 3661, -1, 3661, 3228, 3226, -1, + 3228, 3661, 3660, -1, 3660, 3230, 3228, -1, + 3230, 3660, 3659, -1, 3659, 3232, 3230, -1, + 3232, 3659, 3658, -1, 3658, 3234, 3232, -1, + 3234, 3658, 3149, -1, 3149, 3236, 3234, -1, + 3236, 3149, 3147, -1, 3147, 3483, 3236, -1, + 3483, 3147, 3145, -1, 3145, 3482, 3483, -1, + 3482, 3145, 3143, -1, 3143, 3481, 3482, -1, + 3481, 3143, 3141, -1, 3141, 3480, 3481, -1, + 3480, 3141, 3139, -1, 3139, 3479, 3480, -1, + 3479, 3139, 3137, -1, 3137, 3478, 3479, -1, + 3478, 3137, 3135, -1, 3135, 3477, 3478, -1, + 3477, 3135, 3133, -1, 3133, 3476, 3477, -1, + 3476, 3133, 3131, -1, 3131, 3475, 3476, -1, + 3475, 3131, 3129, -1, 3129, 3474, 3475, -1, + 3474, 3129, 3127, -1, 3127, 3473, 3474, -1, + 3473, 3127, 3125, -1, 3125, 3472, 3473, -1, + 3472, 3125, 3123, -1, 3123, 3471, 3472, -1, + 3471, 3123, 3122, -1, 3122, 3470, 3471, -1, + 3470, 3122, 3676, -1, 3676, 3469, 3470, -1, + 3469, 3676, 3677, -1, 3677, 3467, 3469, -1, + 3467, 3677, 3120, -1, 3120, 3119, 3467, -1, + 3678, 3467, 3119, -1, 3119, 3679, 3678, -1, + 3119, 3118, 3679, -1, 3680, 3681, 3682, -1, + 3681, 3680, 3679, -1, 3681, 3679, 3118, -1, + 3118, 3120, 3681, -1, 3120, 3682, 3681, -1, + 3120, 3683, 3682, -1, 3683, 3120, 3677, -1, + 3677, 3684, 3683, -1, 3684, 3677, 3676, -1, + 3676, 3685, 3684, -1, 3685, 3676, 3122, -1, + 3122, 3121, 3685, -1, 3686, 3685, 3121, -1, + 3685, 3686, 3687, -1, 3687, 3684, 3685, -1, + 3684, 3687, 3688, -1, 3688, 3683, 3684, -1, + 3683, 3688, 3689, -1, 3689, 3682, 3683, -1, + 3690, 3691, 3682, -1, 3682, 3689, 3690, -1, + 3692, 3693, 3694, -1, 3695, 3696, 3697, -1, + 3697, 3698, 3695, -1, 3698, 3697, 3699, -1, + 3699, 3700, 3698, -1, 3700, 3699, 3701, -1, + 3701, 3702, 3700, -1, 3702, 3701, 3703, -1, + 3703, 3704, 3702, -1, 3704, 3703, 3705, -1, + 3705, 3706, 3704, -1, 3706, 3705, 3692, -1, + 3692, 3694, 3706, -1, 3707, 3708, 3709, -1, + 3710, 3711, 3712, -1, 3712, 3713, 3710, -1, + 3713, 3712, 3714, -1, 3714, 3715, 3713, -1, + 3715, 3714, 3716, -1, 3716, 3717, 3715, -1, + 3717, 3716, 3718, -1, 3718, 3719, 3717, -1, + 3720, 3721, 3722, -1, 3722, 3723, 3720, -1, + 3723, 3722, 3719, -1, 3719, 3718, 3723, -1, + 3718, 3724, 3723, -1, 3724, 3718, 3716, -1, + 3716, 3725, 3724, -1, 3725, 3716, 3714, -1, + 3714, 3726, 3725, -1, 3726, 3714, 3712, -1, + 3712, 3727, 3726, -1, 3727, 3712, 3711, -1, + 3711, 3728, 3727, -1, 3728, 3711, 3729, -1, + 3729, 3730, 3728, -1, 3730, 3729, 3731, -1, + 3731, 3732, 3730, -1, 3732, 3731, 3733, -1, + 3733, 3734, 3732, -1, 3735, 3736, 3737, -1, + 3737, 3738, 3735, -1, 3739, 3740, 3741, -1, + 3741, 3742, 3739, -1, 3742, 3741, 3743, -1, + 3743, 3741, 3744, -1, 3743, 3744, 3745, -1, + 3745, 3746, 3743, -1, 3746, 3745, 3738, -1, + 3738, 3737, 3746, -1, 3747, 3746, 3737, -1, + 3737, 3748, 3747, -1, 3748, 3737, 3736, -1, + 3736, 3749, 3748, -1, 3750, 3751, 3709, -1, + 3750, 3709, 3749, -1, 3749, 3736, 3750, -1, + 3752, 3753, 3754, -1, 3750, 3754, 3753, -1, + 3754, 3750, 3736, -1, 3736, 3735, 3754, -1, + 3755, 3756, 3757, -1, 3757, 3756, 3754, -1, + 3757, 3754, 3735, -1, 3735, 3758, 3757, -1, + 3758, 3735, 3738, -1, 3738, 3759, 3758, -1, + 3759, 3738, 3745, -1, 3745, 3760, 3759, -1, + 3760, 3745, 3744, -1, 3744, 3761, 3760, -1, + 3762, 3763, 3764, -1, 3764, 3765, 3762, -1, + 3765, 3764, 3766, -1, 3766, 3767, 3765, -1, + 3767, 3766, 3768, -1, 3768, 3769, 3767, -1, + 3769, 3768, 3761, -1, 3761, 3770, 3769, -1, + 3770, 3761, 3744, -1, 3770, 3744, 3741, -1, + 3770, 3741, 3740, -1, 3740, 3769, 3770, -1, + 3769, 3740, 3771, -1, 3771, 3767, 3769, -1, + 3767, 3771, 3772, -1, 3772, 3765, 3767, -1, + 3765, 3772, 3773, -1, 3773, 3762, 3765, -1, + 3762, 3773, 3774, -1, 3774, 3763, 3762, -1, + 3763, 3774, 3775, -1, 3775, 3776, 3763, -1, + 3776, 3775, 3777, -1, 3777, 3778, 3776, -1, + 3778, 3777, 3779, -1, 3779, 3780, 3778, -1, + 3780, 3779, 3781, -1, 3781, 3782, 3780, -1, + 3782, 3781, 3783, -1, 3783, 3784, 3782, -1, + 3784, 3783, 3785, -1, 3785, 3786, 3784, -1, + 3786, 3785, 3787, -1, 3787, 3788, 3786, -1, + 3788, 3787, 3789, -1, 3789, 3790, 3788, -1, + 3790, 3789, 3791, -1, 3791, 3792, 3790, -1, + 3792, 3791, 3793, -1, 3793, 3794, 3792, -1, + 3794, 3793, 3795, -1, 3795, 3796, 3794, -1, + 3796, 3795, 3797, -1, 3797, 3798, 3796, -1, + 3798, 3797, 3799, -1, 3799, 3800, 3798, -1, + 3800, 3799, 3801, -1, 3801, 3802, 3800, -1, + 3803, 3804, 3805, -1, 3804, 3803, 3806, -1, + 3806, 3807, 3804, -1, 3807, 3806, 3808, -1, + 3808, 3809, 3807, -1, 3809, 3808, 3810, -1, + 3810, 3811, 3809, -1, 3811, 3810, 3812, -1, + 3812, 3813, 3811, -1, 3813, 3812, 3814, -1, + 3814, 3815, 3813, -1, 3815, 3814, 3816, -1, + 3816, 3817, 3815, -1, 3817, 3816, 3818, -1, + 3818, 3819, 3817, -1, 3819, 3818, 3820, -1, + 3820, 3821, 3819, -1, 3821, 3820, 3822, -1, + 3822, 3823, 3821, -1, 3823, 3822, 3824, -1, + 3824, 3825, 3823, -1, 3825, 3824, 3826, -1, + 3826, 3827, 3825, -1, 3827, 3826, 3828, -1, + 3828, 3829, 3827, -1, 3829, 3828, 3830, -1, + 3830, 3831, 3829, -1, 3830, 3832, 3831, -1, + 3832, 3830, 3833, -1, 3833, 3834, 3832, -1, + 3834, 3833, 3835, -1, 3835, 3836, 3834, -1, + 3836, 3835, 3837, -1, 3837, 3838, 3836, -1, + 3838, 3837, 3839, -1, 3839, 3840, 3838, -1, + 3840, 3839, 3841, -1, 3841, 3842, 3840, -1, + 3842, 3841, 3843, -1, 3843, 3844, 3842, -1, + 3844, 3843, 3845, -1, 3845, 3846, 3844, -1, + 3846, 3845, 3847, -1, 3847, 3848, 3846, -1, + 3848, 3847, 3849, -1, 3849, 3850, 3848, -1, + 3850, 3849, 3851, -1, 3851, 3852, 3850, -1, + 3852, 3851, 3853, -1, 3853, 3854, 3852, -1, + 3854, 3853, 3855, -1, 3855, 3856, 3854, -1, + 3856, 3855, 3857, -1, 3857, 3858, 3856, -1, + 3858, 3857, 3859, -1, 3859, 3860, 3858, -1, + 3860, 3859, 3861, -1, 3861, 3862, 3860, -1, + 3862, 3861, 3863, -1, 3863, 3864, 3862, -1, + 3864, 3863, 3865, -1, 3865, 3866, 3864, -1, + 3866, 3865, 3867, -1, 3867, 3868, 3866, -1, + 3868, 3867, 3869, -1, 3869, 3870, 3868, -1, + 3870, 3869, 3871, -1, 3871, 3872, 3870, -1, + 3872, 3871, 3873, -1, 3873, 3874, 3872, -1, + 3874, 3873, 3875, -1, 3875, 3876, 3874, -1, + 3876, 3875, 3802, -1, 3802, 3801, 3876, -1, + 3876, 3801, 3877, -1, 3877, 3874, 3876, -1, + 3874, 3877, 3878, -1, 3878, 3872, 3874, -1, + 3872, 3878, 3879, -1, 3879, 3870, 3872, -1, + 3870, 3879, 3880, -1, 3880, 3868, 3870, -1, + 3868, 3880, 3881, -1, 3881, 3866, 3868, -1, + 3866, 3881, 3882, -1, 3882, 3864, 3866, -1, + 3864, 3882, 3883, -1, 3883, 3862, 3864, -1, + 3862, 3883, 3884, -1, 3884, 3860, 3862, -1, + 3860, 3884, 3885, -1, 3885, 3858, 3860, -1, + 3858, 3885, 3886, -1, 3886, 3856, 3858, -1, + 3856, 3886, 3887, -1, 3887, 3854, 3856, -1, + 3854, 3887, 3888, -1, 3888, 3852, 3854, -1, + 3852, 3888, 3889, -1, 3889, 3850, 3852, -1, + 3850, 3889, 3890, -1, 3890, 3848, 3850, -1, + 3848, 3890, 3891, -1, 3891, 3846, 3848, -1, + 3846, 3891, 3892, -1, 3892, 3844, 3846, -1, + 3844, 3892, 3893, -1, 3893, 3842, 3844, -1, + 3842, 3893, 3894, -1, 3894, 3840, 3842, -1, + 3840, 3894, 3895, -1, 3895, 3838, 3840, -1, + 3838, 3895, 3896, -1, 3896, 3836, 3838, -1, + 3836, 3896, 3897, -1, 3897, 3834, 3836, -1, + 3834, 3897, 3898, -1, 3898, 3832, 3834, -1, + 3832, 3898, 3899, -1, 3899, 3831, 3832, -1, + 3831, 3899, 3900, -1, 3831, 3900, 3901, -1, + 3901, 3829, 3831, -1, 3829, 3901, 3902, -1, + 3902, 3827, 3829, -1, 3827, 3902, 3903, -1, + 3903, 3825, 3827, -1, 3825, 3903, 3904, -1, + 3904, 3823, 3825, -1, 3823, 3904, 3905, -1, + 3905, 3821, 3823, -1, 3821, 3905, 3906, -1, + 3906, 3819, 3821, -1, 3819, 3906, 3907, -1, + 3907, 3817, 3819, -1, 3817, 3907, 3908, -1, + 3908, 3815, 3817, -1, 3815, 3908, 3909, -1, + 3909, 3813, 3815, -1, 3813, 3909, 3910, -1, + 3910, 3811, 3813, -1, 3811, 3910, 3911, -1, + 3911, 3809, 3811, -1, 3809, 3911, 3912, -1, + 3912, 3807, 3809, -1, 3807, 3912, 3913, -1, + 3913, 3804, 3807, -1, 3804, 3913, 3914, -1, + 3914, 3805, 3804, -1, 3805, 3914, 3734, -1, + 3734, 3733, 3805, -1, 3915, 3805, 3733, -1, + 3805, 3915, 3916, -1, 3916, 3803, 3805, -1, + 3803, 3916, 3917, -1, 3917, 3806, 3803, -1, + 3806, 3917, 3918, -1, 3918, 3808, 3806, -1, + 3808, 3918, 3919, -1, 3919, 3810, 3808, -1, + 3810, 3919, 3920, -1, 3920, 3812, 3810, -1, + 3812, 3920, 3921, -1, 3921, 3814, 3812, -1, + 3814, 3921, 3922, -1, 3922, 3816, 3814, -1, + 3816, 3922, 3923, -1, 3923, 3818, 3816, -1, + 3818, 3923, 3924, -1, 3924, 3820, 3818, -1, + 3820, 3924, 3925, -1, 3925, 3822, 3820, -1, + 3822, 3925, 3926, -1, 3926, 3824, 3822, -1, + 3824, 3926, 3927, -1, 3927, 3826, 3824, -1, + 3826, 3927, 3928, -1, 3928, 3828, 3826, -1, + 3828, 3928, 3929, -1, 3929, 3830, 3828, -1, + 3929, 3833, 3830, -1, 3833, 3929, 3930, -1, + 3930, 3835, 3833, -1, 3835, 3930, 3931, -1, + 3931, 3837, 3835, -1, 3837, 3931, 3932, -1, + 3932, 3839, 3837, -1, 3839, 3932, 3933, -1, + 3933, 3841, 3839, -1, 3841, 3933, 3934, -1, + 3934, 3843, 3841, -1, 3843, 3934, 3935, -1, + 3935, 3845, 3843, -1, 3845, 3935, 3936, -1, + 3936, 3847, 3845, -1, 3847, 3936, 3937, -1, + 3937, 3849, 3847, -1, 3849, 3937, 3938, -1, + 3938, 3851, 3849, -1, 3851, 3938, 3939, -1, + 3939, 3853, 3851, -1, 3853, 3939, 3940, -1, + 3940, 3855, 3853, -1, 3855, 3940, 3941, -1, + 3941, 3857, 3855, -1, 3857, 3941, 3942, -1, + 3942, 3859, 3857, -1, 3859, 3942, 3943, -1, + 3943, 3861, 3859, -1, 3861, 3943, 3944, -1, + 3944, 3863, 3861, -1, 3863, 3944, 3945, -1, + 3945, 3865, 3863, -1, 3865, 3945, 3946, -1, + 3946, 3867, 3865, -1, 3867, 3946, 3947, -1, + 3947, 3869, 3867, -1, 3869, 3947, 3948, -1, + 3948, 3871, 3869, -1, 3871, 3948, 3949, -1, + 3949, 3873, 3871, -1, 3873, 3949, 3950, -1, + 3950, 3875, 3873, -1, 3875, 3950, 3951, -1, + 3951, 3802, 3875, -1, 3802, 3951, 3952, -1, + 3952, 3800, 3802, -1, 3953, 3800, 3952, -1, + 3952, 3954, 3953, -1, 3954, 3952, 3951, -1, + 3951, 3955, 3954, -1, 3955, 3951, 3950, -1, + 3950, 3956, 3955, -1, 3956, 3950, 3949, -1, + 3949, 3957, 3956, -1, 3958, 3959, 3960, -1, + 3960, 3961, 3958, -1, 3961, 3960, 3962, -1, + 3962, 3963, 3961, -1, 3963, 3962, 3964, -1, + 3964, 3965, 3963, -1, 3966, 3963, 3965, -1, + 3965, 3967, 3966, -1, 3967, 3965, 3968, -1, + 3968, 3969, 3967, -1, 3969, 3968, 3970, -1, + 3970, 3971, 3969, -1, 3971, 3970, 3972, -1, + 3972, 3973, 3971, -1, 3973, 3972, 3974, -1, + 3974, 3975, 3973, -1, 3975, 3974, 3957, -1, + 3957, 3949, 3975, -1, 3975, 3949, 3948, -1, + 3948, 3973, 3975, -1, 3973, 3948, 3947, -1, + 3947, 3971, 3973, -1, 3971, 3947, 3946, -1, + 3946, 3969, 3971, -1, 3969, 3946, 3945, -1, + 3945, 3967, 3969, -1, 3967, 3945, 3944, -1, + 3944, 3966, 3967, -1, 3966, 3944, 3943, -1, + 3943, 3976, 3966, -1, 3977, 3978, 3979, -1, + 3978, 3977, 3980, -1, 3980, 3981, 3978, -1, + 3981, 3980, 3982, -1, 3982, 3983, 3981, -1, + 3983, 3982, 3984, -1, 3984, 3985, 3983, -1, + 3985, 3984, 3986, -1, 3987, 3986, 3988, -1, + 3986, 3987, 3989, -1, 3989, 3985, 3986, -1, + 3985, 3989, 3990, -1, 3990, 3983, 3985, -1, + 3983, 3990, 3991, -1, 3991, 3981, 3983, -1, + 3981, 3991, 3992, -1, 3992, 3978, 3981, -1, + 3978, 3992, 3993, -1, 3993, 3979, 3978, -1, + 3979, 3993, 3994, -1, 3994, 3995, 3979, -1, + 3995, 3994, 3996, -1, 3996, 3997, 3995, -1, + 3997, 3996, 3998, -1, 3998, 3999, 3997, -1, + 3999, 3998, 4000, -1, 4000, 4001, 3999, -1, + 4001, 4000, 4002, -1, 4002, 4003, 4001, -1, + 4003, 4002, 4004, -1, 4004, 4005, 4003, -1, + 4005, 4004, 4006, -1, 4006, 4007, 4005, -1, + 4007, 4006, 4008, -1, 4008, 4009, 4007, -1, + 4009, 4008, 4010, -1, 4010, 4011, 4009, -1, + 4011, 4010, 4012, -1, 4012, 4013, 4011, -1, + 4012, 4014, 4013, -1, 4014, 4012, 4015, -1, + 4015, 4016, 4014, -1, 4016, 4015, 4017, -1, + 4017, 4018, 4016, -1, 4018, 4017, 4019, -1, + 4019, 4020, 4018, -1, 4020, 4019, 4021, -1, + 4021, 4022, 4020, -1, 4022, 4021, 4023, -1, + 4023, 4024, 4022, -1, 4024, 4023, 4025, -1, + 4025, 4026, 4024, -1, 4026, 4025, 4027, -1, + 4027, 4028, 4026, -1, 4028, 4027, 4029, -1, + 4029, 4030, 4028, -1, 4030, 4029, 4031, -1, + 4031, 4032, 4030, -1, 4032, 4031, 4033, -1, + 4033, 4034, 4032, -1, 4034, 4033, 4035, -1, + 4035, 4036, 4034, -1, 4036, 4035, 4037, -1, + 4037, 4038, 4036, -1, 4038, 4037, 3976, -1, + 3976, 3943, 4038, -1, 4038, 3943, 3942, -1, + 3942, 4036, 4038, -1, 4036, 3942, 3941, -1, + 3941, 4034, 4036, -1, 4034, 3941, 3940, -1, + 3940, 4032, 4034, -1, 4032, 3940, 3939, -1, + 3939, 4030, 4032, -1, 4030, 3939, 3938, -1, + 3938, 4028, 4030, -1, 4028, 3938, 3937, -1, + 3937, 4026, 4028, -1, 4026, 3937, 3936, -1, + 3936, 4024, 4026, -1, 4024, 3936, 3935, -1, + 3935, 4022, 4024, -1, 4022, 3935, 3934, -1, + 3934, 4020, 4022, -1, 4020, 3934, 3933, -1, + 3933, 4018, 4020, -1, 4018, 3933, 3932, -1, + 3932, 4016, 4018, -1, 4016, 3932, 3931, -1, + 3931, 4014, 4016, -1, 4014, 3931, 3930, -1, + 3930, 4013, 4014, -1, 4013, 3930, 3929, -1, + 4013, 3929, 3928, -1, 3928, 4011, 4013, -1, + 4011, 3928, 3927, -1, 3927, 4009, 4011, -1, + 4009, 3927, 3926, -1, 3926, 4007, 4009, -1, + 4007, 3926, 3925, -1, 3925, 4005, 4007, -1, + 4005, 3925, 3924, -1, 3924, 4003, 4005, -1, + 4003, 3924, 3923, -1, 3923, 4001, 4003, -1, + 4001, 3923, 3922, -1, 3922, 3999, 4001, -1, + 3999, 3922, 3921, -1, 3921, 3997, 3999, -1, + 3997, 3921, 3920, -1, 3920, 3995, 3997, -1, + 3995, 3920, 3919, -1, 3919, 3979, 3995, -1, + 3979, 3919, 3918, -1, 3918, 3977, 3979, -1, + 3977, 3918, 3917, -1, 3917, 3980, 3977, -1, + 3980, 3917, 3916, -1, 3916, 3982, 3980, -1, + 3982, 3916, 3915, -1, 3915, 3984, 3982, -1, + 3984, 3915, 3733, -1, 3733, 3986, 3984, -1, + 3986, 3733, 3731, -1, 3731, 3988, 3986, -1, + 3988, 3731, 3729, -1, 3729, 4039, 3988, -1, + 4039, 3729, 3711, -1, 3711, 3710, 4039, -1, + 4040, 4039, 3710, -1, 3710, 4041, 4040, -1, + 4041, 3710, 3713, -1, 3713, 4042, 4041, -1, + 4042, 3713, 3715, -1, 3715, 4043, 4042, -1, + 4043, 3715, 3717, -1, 3717, 4044, 4043, -1, + 4044, 3717, 3719, -1, 3719, 4045, 4044, -1, + 4045, 3719, 3722, -1, 3722, 4046, 4045, -1, + 4046, 3722, 3721, -1, 3721, 4047, 4046, -1, + 4047, 3721, 4048, -1, 4049, 4050, 4051, -1, + 4049, 4052, 4050, -1, 4053, 4054, 4055, -1, + 4053, 4056, 4054, -1, 4057, 4058, 4059, -1, + 4059, 4060, 4057, -1, 4060, 4059, 4061, -1, + 4061, 4062, 4060, -1, 4062, 4061, 4063, -1, + 4063, 4064, 4062, -1, 4064, 4063, 4056, -1, + 4056, 4053, 4064, -1, 4065, 4053, 4066, -1, + 4065, 4064, 4053, -1, 4064, 4065, 4050, -1, + 4050, 4062, 4064, -1, 4062, 4050, 4052, -1, + 4052, 4060, 4062, -1, 4060, 4052, 4067, -1, + 4067, 4057, 4060, -1, 4057, 4067, 4068, -1, + 4068, 4069, 4057, -1, 4070, 4071, 2635, -1, + 2635, 4072, 4070, -1, 4073, 4074, 4072, -1, + 4074, 4070, 4072, -1, 4074, 4068, 4070, -1, + 4074, 4073, 4068, -1, 4073, 4069, 4068, -1, + 4069, 4073, 4072, -1, 4069, 4072, 4075, -1, + 4075, 4057, 4069, -1, 4075, 4058, 4057, -1, + 4058, 4075, 4072, -1, 4072, 4076, 4058, -1, + 4077, 4078, 4079, -1, 4080, 4081, 4082, -1, + 4080, 4082, 4078, -1, 4082, 4079, 4078, -1, + 4082, 4083, 4079, -1, 4084, 4085, 4086, -1, + 4086, 4087, 4084, -1, 4087, 4086, 4088, -1, + 4088, 4089, 4087, -1, 4090, 4091, 4092, -1, + 4091, 4090, 4089, -1, 4089, 4088, 4091, -1, + 4088, 4093, 4091, -1, 4093, 4088, 4086, -1, + 4086, 4094, 4093, -1, 4094, 4086, 4085, -1, + 4085, 4095, 4094, -1, 4095, 4085, 4096, -1, + 4096, 4097, 4095, -1, 4097, 4096, 4098, -1, + 4098, 4099, 4097, -1, 4099, 4098, 4100, -1, + 4100, 4101, 4099, -1, 4101, 4100, 4083, -1, + 4083, 4082, 4101, -1, 4102, 4101, 4082, -1, + 4082, 4081, 4102, -1, 4103, 4102, 4081, -1, + 4081, 4104, 4103, -1, 4081, 4080, 4104, -1, + 4080, 4078, 4104, -1, 4078, 4077, 4104, -1, + 4076, 4104, 4077, -1, 4077, 4105, 4076, -1, + 4077, 4079, 4105, -1, 4105, 4079, 4106, -1, + 4106, 4076, 4105, -1, 4106, 4107, 4076, -1, + 4107, 4108, 4076, -1, 4108, 4058, 4076, -1, + 4108, 4059, 4058, -1, 4108, 4107, 4059, -1, + 4107, 4106, 4059, -1, 4059, 4106, 4079, -1, + 4079, 4061, 4059, -1, 4061, 4079, 4083, -1, + 4083, 4063, 4061, -1, 4063, 4083, 4100, -1, + 4100, 4056, 4063, -1, 4056, 4100, 4098, -1, + 4098, 4054, 4056, -1, 4054, 4098, 4096, -1, + 4096, 4109, 4054, -1, 4109, 4096, 4085, -1, + 4085, 4084, 4109, -1, 4110, 4109, 4084, -1, + 4109, 4110, 4111, -1, 4111, 4054, 4109, -1, + 4111, 4055, 4054, -1, 4111, 4112, 4055, -1, + 4112, 4111, 4110, -1, 4110, 4113, 4112, -1, + 4113, 4110, 4084, -1, 4084, 4114, 4113, -1, + 4114, 4084, 4087, -1, 4087, 4115, 4114, -1, + 4115, 4087, 4089, -1, 4089, 4116, 4115, -1, + 4116, 4089, 4090, -1, 4090, 4117, 4116, -1, + 4117, 4090, 4092, -1, 4092, 4118, 4117, -1, + 4118, 4092, 4119, -1, 4119, 4120, 4118, -1, + 4120, 4119, 4121, -1, 4121, 4122, 4120, -1, + 4122, 4121, 4123, -1, 4123, 4124, 4122, -1, + 4124, 4123, 4125, -1, 4125, 4126, 4124, -1, + 4126, 4125, 4127, -1, 4127, 4128, 4126, -1, + 4128, 4127, 4129, -1, 4129, 4130, 4128, -1, + 4130, 4129, 4131, -1, 4131, 4132, 4130, -1, + 4132, 4131, 4133, -1, 4133, 4134, 4132, -1, + 4134, 4133, 4135, -1, 4135, 4136, 4134, -1, + 4136, 4135, 4137, -1, 4137, 4138, 4136, -1, + 4138, 4137, 4139, -1, 4139, 4140, 4138, -1, + 4140, 4139, 4141, -1, 4141, 4142, 4140, -1, + 4142, 4141, 4048, -1, 4048, 4143, 4142, -1, + 4143, 4048, 3721, -1, 3721, 3720, 4143, -1, + 3720, 4144, 4143, -1, 4144, 3720, 3723, -1, + 3723, 4145, 4144, -1, 4145, 3723, 3724, -1, + 3724, 4146, 4145, -1, 4146, 3724, 3725, -1, + 3725, 4147, 4146, -1, 4147, 3725, 3726, -1, + 3726, 4148, 4147, -1, 4148, 3726, 3727, -1, + 3727, 4149, 4148, -1, 4149, 3727, 3728, -1, + 3728, 4150, 4149, -1, 4150, 3728, 3730, -1, + 3730, 4151, 4150, -1, 4151, 3730, 3732, -1, + 3732, 4152, 4151, -1, 4152, 3732, 3734, -1, + 3734, 4153, 4152, -1, 4153, 3734, 3914, -1, + 3914, 4154, 4153, -1, 4154, 3914, 3913, -1, + 3913, 4155, 4154, -1, 4155, 3913, 3912, -1, + 3912, 4156, 4155, -1, 4156, 3912, 3911, -1, + 3911, 4157, 4156, -1, 4157, 3911, 3910, -1, + 3910, 4158, 4157, -1, 4158, 3910, 3909, -1, + 3909, 4159, 4158, -1, 4159, 3909, 3908, -1, + 3908, 4160, 4159, -1, 4160, 3908, 3907, -1, + 3907, 4161, 4160, -1, 4161, 3907, 3906, -1, + 3906, 4162, 4161, -1, 4162, 3906, 3905, -1, + 3905, 4163, 4162, -1, 4163, 3905, 3904, -1, + 3904, 4164, 4163, -1, 4164, 3904, 3903, -1, + 3903, 4165, 4164, -1, 4165, 3903, 3902, -1, + 3902, 4166, 4165, -1, 4166, 3902, 3901, -1, + 3901, 4167, 4166, -1, 4167, 3901, 3900, -1, + 3900, 4168, 4167, -1, 3900, 4169, 4168, -1, + 4169, 3900, 3899, -1, 3899, 4170, 4169, -1, + 4170, 3899, 3898, -1, 3898, 4171, 4170, -1, + 4171, 3898, 3897, -1, 3897, 4172, 4171, -1, + 4172, 3897, 3896, -1, 3896, 4173, 4172, -1, + 4173, 3896, 3895, -1, 3895, 4174, 4173, -1, + 4174, 3895, 3894, -1, 3894, 4175, 4174, -1, + 4175, 3894, 3893, -1, 3893, 4176, 4175, -1, + 4176, 3893, 3892, -1, 3892, 4177, 4176, -1, + 4177, 3892, 3891, -1, 3891, 4178, 4177, -1, + 4178, 3891, 3890, -1, 3890, 4179, 4178, -1, + 4179, 3890, 3889, -1, 3889, 4180, 4179, -1, + 4180, 3889, 3888, -1, 3888, 4181, 4180, -1, + 4181, 3888, 3887, -1, 3887, 4182, 4181, -1, + 4182, 3887, 3886, -1, 3886, 4183, 4182, -1, + 4183, 3886, 3885, -1, 3885, 4184, 4183, -1, + 4184, 3885, 3884, -1, 3884, 4185, 4184, -1, + 4185, 3884, 3883, -1, 3883, 4186, 4185, -1, + 4186, 3883, 3882, -1, 3882, 4187, 4186, -1, + 4187, 3882, 3881, -1, 3881, 4188, 4187, -1, + 4188, 3881, 3880, -1, 3880, 4189, 4188, -1, + 4189, 3880, 3879, -1, 3879, 4190, 4189, -1, + 4190, 3879, 3878, -1, 3878, 4191, 4190, -1, + 4191, 3878, 3877, -1, 3877, 4192, 4191, -1, + 4192, 3877, 3801, -1, 3801, 4193, 4192, -1, + 4193, 3801, 3799, -1, 3799, 4194, 4193, -1, + 4194, 3799, 3797, -1, 3797, 4195, 4194, -1, + 4195, 3797, 3795, -1, 3795, 4196, 4195, -1, + 4196, 3795, 3793, -1, 3793, 4197, 4196, -1, + 4197, 3793, 3791, -1, 3791, 4198, 4197, -1, + 4198, 3791, 3789, -1, 3789, 4199, 4198, -1, + 4199, 3789, 3787, -1, 3787, 4200, 4199, -1, + 4200, 3787, 3785, -1, 3785, 4201, 4200, -1, + 4201, 3785, 3783, -1, 3783, 4202, 4201, -1, + 4202, 3783, 3781, -1, 3781, 4203, 4202, -1, + 4203, 3781, 3779, -1, 3779, 4204, 4203, -1, + 4204, 3779, 3777, -1, 3777, 4205, 4204, -1, + 4205, 3777, 3775, -1, 3775, 4206, 4205, -1, + 4206, 3775, 3774, -1, 3774, 4207, 4206, -1, + 4207, 3774, 3773, -1, 3773, 4208, 4207, -1, + 4208, 3773, 3772, -1, 3772, 4209, 4208, -1, + 4209, 3772, 3771, -1, 3771, 4210, 4209, -1, + 4210, 3771, 3740, -1, 3740, 3739, 4210, -1, + 3739, 4211, 4210, -1, 4211, 3739, 3742, -1, + 3742, 4212, 4211, -1, 3742, 3743, 4212, -1, + 4213, 4212, 3743, -1, 4213, 3743, 3746, -1, + 3746, 3747, 4213, -1, 4214, 4215, 4213, -1, + 4214, 4213, 3747, -1, 3747, 4216, 4214, -1, + 4216, 3747, 3748, -1, 3748, 4217, 4216, -1, + 4217, 3748, 3749, -1, 3749, 4218, 4217, -1, + 4218, 3749, 3709, -1, 3709, 4219, 4218, -1, + 4219, 3709, 3708, -1, 4220, 4221, 4222, -1, + 4223, 4224, 4220, -1, 4225, 4226, 4227, -1, + 4228, 4229, 4225, -1, 4227, 4230, 4223, -1, + 4231, 4223, 4230, -1, 4231, 4230, 4219, -1, + 4231, 4219, 3708, -1, 3708, 4223, 4231, -1, + 3708, 3707, 4223, -1, 3707, 4224, 4223, -1, + 4224, 3707, 3709, -1, 4224, 3709, 3751, -1, + 3751, 4220, 4224, -1, 3751, 4232, 4220, -1, + 4232, 3751, 3750, -1, 4232, 3750, 3753, -1, + 3753, 4220, 4232, -1, 3753, 3752, 4220, -1, + 3752, 4221, 4220, -1, 4221, 3752, 3754, -1, + 4221, 3754, 3756, -1, 3756, 4222, 4221, -1, + 3756, 3755, 4222, -1, 4233, 4234, 3694, -1, + 4234, 4233, 4222, -1, 4234, 4222, 3755, -1, + 3755, 3757, 4234, -1, 3757, 3694, 4234, -1, + 3694, 3757, 3758, -1, 3758, 3706, 3694, -1, + 3706, 3758, 3759, -1, 3759, 3704, 3706, -1, + 3704, 3759, 3760, -1, 3760, 3702, 3704, -1, + 3702, 3760, 3761, -1, 3761, 3700, 3702, -1, + 3700, 3761, 3768, -1, 3768, 3698, 3700, -1, + 3698, 3768, 3766, -1, 3766, 3695, 3698, -1, + 3695, 3766, 3764, -1, 3764, 3696, 3695, -1, + 3696, 3764, 3763, -1, 3763, 4235, 3696, -1, + 4235, 3763, 3776, -1, 3776, 4236, 4235, -1, + 4236, 3776, 3778, -1, 3778, 4237, 4236, -1, + 4237, 3778, 3780, -1, 3780, 4238, 4237, -1, + 4238, 3780, 3782, -1, 3782, 4239, 4238, -1, + 4239, 3782, 3784, -1, 3784, 4240, 4239, -1, + 4240, 3784, 3786, -1, 3786, 4241, 4240, -1, + 4241, 3786, 3788, -1, 3788, 4242, 4241, -1, + 4242, 3788, 3790, -1, 3790, 4243, 4242, -1, + 4243, 3790, 3792, -1, 3792, 4244, 4243, -1, + 4244, 3792, 3794, -1, 3794, 4245, 4244, -1, + 4245, 3794, 3796, -1, 3796, 4246, 4245, -1, + 4246, 3796, 3798, -1, 3798, 4247, 4246, -1, + 4247, 3798, 3800, -1, 3800, 3953, 4247, -1, + 4248, 4247, 3953, -1, 3953, 4249, 4248, -1, + 4249, 3953, 3954, -1, 3954, 4250, 4249, -1, + 4250, 3954, 3955, -1, 3955, 4251, 4250, -1, + 4251, 3955, 3956, -1, 3956, 4252, 4251, -1, + 4252, 3956, 3957, -1, 3957, 4253, 4252, -1, + 4253, 3957, 3974, -1, 3974, 4254, 4253, -1, + 4254, 3974, 3972, -1, 3972, 4255, 4254, -1, + 4255, 3972, 3970, -1, 3970, 4256, 4255, -1, + 4256, 3970, 3968, -1, 3968, 4257, 4256, -1, + 4258, 4259, 4260, -1, 4260, 4261, 4258, -1, + 4261, 4260, 4262, -1, 4262, 4263, 4261, -1, + 4263, 4262, 4264, -1, 4264, 4265, 4263, -1, + 4265, 4264, 4266, -1, 4266, 4267, 4265, -1, + 4267, 4266, 4257, -1, 4257, 3968, 4267, -1, + 4267, 3968, 3965, -1, 3965, 4265, 4267, -1, + 4265, 3965, 3964, -1, 3964, 4263, 4265, -1, + 4263, 3964, 3962, -1, 3962, 4261, 4263, -1, + 4261, 3962, 3960, -1, 3960, 4258, 4261, -1, + 4258, 3960, 3959, -1, 3959, 4259, 4258, -1, + 4259, 3959, 4268, -1, 4268, 4269, 4259, -1, + 4269, 4268, 4270, -1, 4270, 4271, 4269, -1, + 4271, 4270, 4272, -1, 4272, 4273, 4271, -1, + 4273, 4272, 4274, -1, 4274, 4275, 4273, -1, + 4275, 4274, 4276, -1, 4276, 4277, 4275, -1, + 4277, 4276, 4278, -1, 4278, 4279, 4277, -1, + 4279, 4278, 4280, -1, 4280, 4281, 4279, -1, + 4281, 4280, 4282, -1, 4282, 4283, 4281, -1, + 4283, 4282, 4284, -1, 4284, 4285, 4283, -1, + 4285, 4284, 4286, -1, 4285, 4286, 4287, -1, + 4287, 4288, 4285, -1, 4288, 4287, 4289, -1, + 4289, 4290, 4288, -1, 4290, 4289, 4291, -1, + 4291, 4292, 4290, -1, 4292, 4291, 4293, -1, + 4293, 4294, 4292, -1, 4294, 4293, 4295, -1, + 4295, 4296, 4294, -1, 4296, 4295, 4297, -1, + 4297, 4298, 4296, -1, 4298, 4297, 4299, -1, + 4299, 4300, 4298, -1, 4300, 4299, 4301, -1, + 4301, 4302, 4300, -1, 4301, 4303, 4302, -1, + 4304, 4305, 4306, -1, 4305, 4304, 4307, -1, + 4307, 4308, 4305, -1, 4308, 4307, 4309, -1, + 4309, 4310, 4308, -1, 4310, 4309, 4311, -1, + 4311, 4312, 4310, -1, 4312, 4311, 4313, -1, + 4313, 4314, 4312, -1, 4314, 4313, 4315, -1, + 4315, 4316, 4314, -1, 4316, 4315, 4303, -1, + 4303, 4317, 4316, -1, 4317, 4303, 4301, -1, + 4301, 4318, 4317, -1, 4318, 4301, 4299, -1, + 4299, 4319, 4318, -1, 4319, 4299, 4297, -1, + 4297, 4320, 4319, -1, 4320, 4297, 4295, -1, + 4295, 4321, 4320, -1, 4321, 4295, 4293, -1, + 4293, 4322, 4321, -1, 4322, 4293, 4291, -1, + 4291, 4323, 4322, -1, 4323, 4291, 4289, -1, + 4289, 4324, 4323, -1, 4324, 4289, 4287, -1, + 4287, 4325, 4324, -1, 4325, 4287, 4286, -1, + 4286, 4326, 4325, -1, 4286, 4327, 4326, -1, + 4327, 4286, 4284, -1, 4284, 4328, 4327, -1, + 4328, 4284, 4282, -1, 4282, 4329, 4328, -1, + 4329, 4282, 4280, -1, 4280, 4330, 4329, -1, + 4330, 4280, 4278, -1, 4278, 4331, 4330, -1, + 4331, 4278, 4276, -1, 4276, 4332, 4331, -1, + 4332, 4276, 4274, -1, 4274, 4333, 4332, -1, + 4333, 4274, 4272, -1, 4272, 4334, 4333, -1, + 4334, 4272, 4270, -1, 4270, 4335, 4334, -1, + 4335, 4270, 4268, -1, 4268, 4336, 4335, -1, + 4336, 4268, 3959, -1, 3959, 3958, 4336, -1, + 4337, 4336, 3958, -1, 3958, 4338, 4337, -1, + 4338, 3958, 3961, -1, 3961, 4339, 4338, -1, + 4339, 3961, 3963, -1, 3963, 3966, 4339, -1, + 4339, 3966, 3976, -1, 3976, 4338, 4339, -1, + 4338, 3976, 4037, -1, 4037, 4337, 4338, -1, + 4337, 4037, 4035, -1, 4035, 4336, 4337, -1, + 4336, 4035, 4033, -1, 4033, 4335, 4336, -1, + 4335, 4033, 4031, -1, 4031, 4334, 4335, -1, + 4334, 4031, 4029, -1, 4029, 4333, 4334, -1, + 4333, 4029, 4027, -1, 4027, 4332, 4333, -1, + 4332, 4027, 4025, -1, 4025, 4331, 4332, -1, + 4331, 4025, 4023, -1, 4023, 4330, 4331, -1, + 4330, 4023, 4021, -1, 4021, 4329, 4330, -1, + 4329, 4021, 4019, -1, 4019, 4328, 4329, -1, + 4328, 4019, 4017, -1, 4017, 4327, 4328, -1, + 4327, 4017, 4015, -1, 4015, 4326, 4327, -1, + 4326, 4015, 4012, -1, 4326, 4012, 4010, -1, + 4010, 4325, 4326, -1, 4325, 4010, 4008, -1, + 4008, 4324, 4325, -1, 4324, 4008, 4006, -1, + 4006, 4323, 4324, -1, 4323, 4006, 4004, -1, + 4004, 4322, 4323, -1, 4322, 4004, 4002, -1, + 4002, 4321, 4322, -1, 4321, 4002, 4000, -1, + 4000, 4320, 4321, -1, 4320, 4000, 3998, -1, + 3998, 4319, 4320, -1, 4319, 3998, 3996, -1, + 3996, 4318, 4319, -1, 4318, 3996, 3994, -1, + 3994, 4317, 4318, -1, 4317, 3994, 3993, -1, + 3993, 4316, 4317, -1, 4316, 3993, 3992, -1, + 3992, 4314, 4316, -1, 4314, 3992, 3991, -1, + 3991, 4312, 4314, -1, 4312, 3991, 3990, -1, + 3990, 4310, 4312, -1, 4310, 3990, 3989, -1, + 3989, 4308, 4310, -1, 4308, 3989, 3987, -1, + 3987, 4305, 4308, -1, 4305, 3987, 3988, -1, + 3988, 4306, 4305, -1, 4306, 3988, 4039, -1, + 4039, 4040, 4306, -1, 4340, 4306, 4040, -1, + 4306, 4340, 4341, -1, 4341, 4304, 4306, -1, + 4304, 4341, 4342, -1, 4342, 4307, 4304, -1, + 4307, 4342, 4343, -1, 4343, 4309, 4307, -1, + 4309, 4343, 4344, -1, 4344, 4311, 4309, -1, + 4311, 4344, 4345, -1, 4345, 4313, 4311, -1, + 4313, 4345, 4346, -1, 4346, 4315, 4313, -1, + 4315, 4346, 4347, -1, 4347, 4303, 4315, -1, + 4347, 4302, 4303, -1, 4347, 4348, 4302, -1, + 4348, 4347, 4346, -1, 4346, 4349, 4348, -1, + 4349, 4346, 4345, -1, 4345, 4350, 4349, -1, + 4350, 4345, 4344, -1, 4344, 4351, 4350, -1, + 4351, 4344, 4343, -1, 4343, 4352, 4351, -1, + 4352, 4343, 4342, -1, 4342, 4353, 4352, -1, + 4353, 4342, 4341, -1, 4341, 4354, 4353, -1, + 4354, 4341, 4340, -1, 4340, 4355, 4354, -1, + 4355, 4340, 4040, -1, 4040, 4356, 4355, -1, + 4356, 4040, 4041, -1, 4041, 4357, 4356, -1, + 4357, 4041, 4042, -1, 4042, 4358, 4357, -1, + 4358, 4042, 4043, -1, 4043, 4359, 4358, -1, + 4359, 4043, 4044, -1, 4044, 4360, 4359, -1, + 4360, 4044, 4045, -1, 4045, 4361, 4360, -1, + 4361, 4045, 4046, -1, 4046, 4362, 4361, -1, + 4362, 4046, 4047, -1, 4047, 4363, 4362, -1, + 4363, 4047, 4048, -1, 4048, 4364, 4363, -1, + 4364, 4048, 4141, -1, 4141, 4365, 4364, -1, + 4365, 4141, 4139, -1, 4139, 4366, 4365, -1, + 4366, 4139, 4137, -1, 4137, 4367, 4366, -1, + 4367, 4137, 4135, -1, 4135, 4368, 4367, -1, + 4368, 4135, 4133, -1, 4133, 4369, 4368, -1, + 4369, 4133, 4131, -1, 4131, 4370, 4369, -1, + 4370, 4131, 4129, -1, 4129, 4371, 4370, -1, + 4371, 4129, 4127, -1, 4127, 4372, 4371, -1, + 4372, 4127, 4125, -1, 4125, 4373, 4372, -1, + 4373, 4125, 4123, -1, 4123, 4374, 4373, -1, + 4374, 4123, 4121, -1, 4121, 4375, 4374, -1, + 4375, 4121, 4119, -1, 4119, 4376, 4375, -1, + 4376, 4119, 4092, -1, 4092, 4377, 4376, -1, + 4377, 4092, 4091, -1, 4091, 4378, 4377, -1, + 4378, 4091, 4093, -1, 4093, 4379, 4378, -1, + 4379, 4093, 4094, -1, 4094, 4380, 4379, -1, + 4380, 4094, 4095, -1, 4095, 4381, 4380, -1, + 4381, 4095, 4097, -1, 4097, 4382, 4381, -1, + 4382, 4097, 4099, -1, 4099, 4383, 4382, -1, + 4383, 4099, 4101, -1, 4101, 4102, 4383, -1, + 3690, 4102, 4384, -1, 3690, 4383, 4102, -1, + 4383, 3690, 3689, -1, 3689, 4382, 4383, -1, + 4382, 3689, 3688, -1, 3688, 4381, 4382, -1, + 4381, 3688, 3687, -1, 3687, 4380, 4381, -1, + 4380, 3687, 3686, -1, 3686, 4379, 4380, -1, + 4379, 3686, 3121, -1, 3121, 4378, 4379, -1, + 4378, 3121, 3124, -1, 3124, 4377, 4378, -1, + 4377, 3124, 3126, -1, 3126, 4376, 4377, -1, + 4376, 3126, 3128, -1, 3128, 4375, 4376, -1, + 4375, 3128, 3130, -1, 3130, 4374, 4375, -1, + 4374, 3130, 3132, -1, 3132, 4373, 4374, -1, + 4373, 3132, 3134, -1, 3134, 4372, 4373, -1, + 4372, 3134, 3136, -1, 3136, 4371, 4372, -1, + 4371, 3136, 3138, -1, 3138, 4370, 4371, -1, + 4370, 3138, 3140, -1, 3140, 4369, 4370, -1, + 4369, 3140, 3142, -1, 3142, 4368, 4369, -1, + 4368, 3142, 3144, -1, 3144, 4367, 4368, -1, + 4367, 3144, 3146, -1, 3146, 4366, 4367, -1, + 4366, 3146, 3148, -1, 3148, 4365, 4366, -1, + 4365, 3148, 3150, -1, 3150, 4364, 4365, -1, + 4364, 3150, 3630, -1, 3630, 3629, 4364, -1, + 3629, 4363, 4364, -1, 4363, 3629, 3627, -1, + 3627, 4362, 4363, -1, 4362, 3627, 3625, -1, + 3625, 4361, 4362, -1, 4361, 3625, 3623, -1, + 3623, 4360, 4361, -1, 4360, 3623, 3621, -1, + 3621, 4359, 4360, -1, 4359, 3621, 3619, -1, + 3619, 4358, 4359, -1, 4358, 3619, 3617, -1, + 3617, 4357, 4358, -1, 4357, 3617, 3615, -1, + 3615, 4356, 4357, -1, 4356, 3615, 3613, -1, + 3613, 4355, 4356, -1, 4355, 3613, 3612, -1, + 3612, 4354, 4355, -1, 4354, 3612, 3611, -1, + 3611, 4353, 4354, -1, 4353, 3611, 3610, -1, + 3610, 4352, 4353, -1, 4352, 3610, 3609, -1, + 3609, 4351, 4352, -1, 4351, 3609, 3608, -1, + 3608, 4350, 4351, -1, 4350, 3608, 3607, -1, + 3607, 4349, 4350, -1, 4349, 3607, 3606, -1, + 3606, 4348, 4349, -1, 4348, 3606, 3152, -1, + 3152, 4302, 4348, -1, 4302, 3152, 3151, -1, + 3151, 4300, 4302, -1, 4300, 3151, 3155, -1, + 3155, 4298, 4300, -1, 4298, 3155, 3157, -1, + 3157, 4296, 4298, -1, 4296, 3157, 3159, -1, + 3159, 4294, 4296, -1, 4294, 3159, 3161, -1, + 3161, 4292, 4294, -1, 4292, 3161, 3163, -1, + 3163, 4290, 4292, -1, 4290, 3163, 3165, -1, + 3165, 4288, 4290, -1, 4288, 3165, 3167, -1, + 3167, 4285, 4288, -1, 3167, 4283, 4285, -1, + 4283, 3167, 3168, -1, 3168, 4281, 4283, -1, + 4281, 3168, 3170, -1, 3170, 4279, 4281, -1, + 4279, 3170, 3172, -1, 3172, 4277, 4279, -1, + 4277, 3172, 3174, -1, 3174, 4275, 4277, -1, + 4275, 3174, 3176, -1, 3176, 4273, 4275, -1, + 4273, 3176, 3178, -1, 3178, 4271, 4273, -1, + 4271, 3178, 3180, -1, 3180, 4269, 4271, -1, + 4269, 3180, 3182, -1, 3182, 4259, 4269, -1, + 4259, 3182, 3184, -1, 3184, 4260, 4259, -1, + 4260, 3184, 3590, -1, 3590, 4262, 4260, -1, + 4262, 3590, 3589, -1, 3589, 4264, 4262, -1, + 4264, 3589, 3588, -1, 3588, 4266, 4264, -1, + 4266, 3588, 3587, -1, 3587, 4257, 4266, -1, + 4257, 3587, 3185, -1, 3185, 4256, 4257, -1, + 4256, 3185, 3188, -1, 3188, 4255, 4256, -1, + 4255, 3188, 3190, -1, 3190, 4254, 4255, -1, + 4254, 3190, 3192, -1, 3192, 4253, 4254, -1, + 4253, 3192, 3194, -1, 3194, 4252, 4253, -1, + 4252, 3194, 3196, -1, 3196, 4251, 4252, -1, + 4251, 3196, 3198, -1, 3198, 4250, 4251, -1, + 4250, 3198, 3200, -1, 3200, 4249, 4250, -1, + 4249, 3200, 3202, -1, 3202, 4248, 4249, -1, + 4248, 3202, 3204, -1, 3204, 4247, 4248, -1, + 4247, 3204, 3206, -1, 3206, 4246, 4247, -1, + 4246, 3206, 3577, -1, 3577, 4245, 4246, -1, + 4245, 3577, 4385, -1, 4385, 4244, 4245, -1, + 4244, 4385, 4386, -1, 4386, 4243, 4244, -1, + 4243, 4386, 4387, -1, 4387, 4242, 4243, -1, + 4242, 4387, 4388, -1, 4388, 4241, 4242, -1, + 4241, 4388, 4389, -1, 4389, 4240, 4241, -1, + 4240, 4389, 4390, -1, 4390, 4239, 4240, -1, + 4239, 4390, 4391, -1, 4391, 4238, 4239, -1, + 4238, 4391, 4392, -1, 4392, 4237, 4238, -1, + 4237, 4392, 4393, -1, 4393, 4236, 4237, -1, + 4236, 4393, 4394, -1, 4394, 4235, 4236, -1, + 4235, 4394, 4395, -1, 4395, 3696, 4235, -1, + 3696, 4395, 4396, -1, 4396, 3697, 3696, -1, + 3697, 4396, 4397, -1, 4397, 3699, 3697, -1, + 3699, 4397, 4398, -1, 4398, 3701, 3699, -1, + 3701, 4398, 4399, -1, 4399, 3703, 3701, -1, + 3703, 4399, 4400, -1, 4400, 3705, 3703, -1, + 3705, 4400, 4401, -1, 4401, 3692, 3705, -1, + 4401, 4402, 3692, -1, 4403, 3692, 4402, -1, + 4403, 4402, 4404, -1, 4403, 4404, 4405, -1, + 4405, 3692, 4403, -1, 4405, 3693, 3692, -1, + 4405, 4404, 3693, -1, 3693, 4404, 4406, -1, + 4406, 4222, 4233, -1, 4222, 4406, 4404, -1, + 4404, 4407, 4408, -1, 4407, 4404, 4402, -1, + 4407, 4402, 4401, -1, 4407, 4401, 4409, -1, + 4409, 4408, 4407, -1, 4410, 4408, 4409, -1, + 4411, 4412, 4413, -1, 4411, 4413, 4408, -1, + 4411, 4408, 4410, -1, 4410, 4412, 4411, -1, + 4410, 4409, 4412, -1, 4412, 4409, 4401, -1, + 4412, 4401, 4400, -1, 4400, 4414, 4412, -1, + 4414, 4400, 4399, -1, 4399, 4415, 4414, -1, + 4415, 4399, 4398, -1, 4398, 4416, 4415, -1, + 4416, 4398, 4397, -1, 4397, 4417, 4416, -1, + 4417, 4397, 4396, -1, 4396, 4418, 4417, -1, + 4418, 4396, 4395, -1, 4395, 4419, 4418, -1, + 4419, 4395, 4394, -1, 4394, 4420, 4419, -1, + 4420, 4394, 4393, -1, 4393, 4421, 4420, -1, + 4421, 4393, 4392, -1, 4392, 4422, 4421, -1, + 4422, 4392, 4391, -1, 4391, 4423, 4422, -1, + 4423, 4391, 4390, -1, 4390, 4424, 4423, -1, + 4424, 4390, 4389, -1, 4389, 4425, 4424, -1, + 4425, 4389, 4388, -1, 4388, 4426, 4425, -1, + 4426, 4388, 4387, -1, 4387, 4427, 4426, -1, + 4427, 4387, 4386, -1, 4386, 4428, 4427, -1, + 4428, 4386, 4385, -1, 4385, 4429, 4428, -1, + 4429, 4385, 3577, -1, 3577, 3576, 4429, -1, + 4430, 4429, 3576, -1, 3576, 4431, 4430, -1, + 4431, 3576, 3574, -1, 3574, 4432, 4431, -1, + 4432, 3574, 3572, -1, 3572, 4433, 4432, -1, + 4433, 3572, 3570, -1, 3570, 4434, 4433, -1, + 4434, 3570, 3568, -1, 3568, 4435, 4434, -1, + 4435, 3568, 3566, -1, 3566, 4436, 4435, -1, + 4436, 3566, 3564, -1, 3564, 4437, 4436, -1, + 4437, 3564, 3562, -1, 3562, 4438, 4437, -1, + 4438, 3562, 3560, -1, 3560, 4439, 4438, -1, + 4439, 3560, 3558, -1, 3558, 4440, 4439, -1, + 4440, 3558, 3556, -1, 3556, 4441, 4440, -1, + 4441, 3556, 3554, -1, 3554, 4442, 4441, -1, + 4442, 3554, 3552, -1, 3552, 4443, 4442, -1, + 4443, 3552, 3550, -1, 3550, 4444, 4443, -1, + 4444, 3550, 3548, -1, 3548, 4445, 4444, -1, + 4445, 3548, 3546, -1, 3546, 4446, 4445, -1, + 4446, 3546, 3501, -1, 4446, 3501, 3240, -1, + 4446, 3240, 3243, -1, 3243, 4445, 4446, -1, + 4445, 3243, 3276, -1, 3276, 4444, 4445, -1, + 4444, 3276, 3274, -1, 3274, 4443, 4444, -1, + 4443, 3274, 3272, -1, 3272, 4442, 4443, -1, + 4442, 3272, 3270, -1, 3270, 4441, 4442, -1, + 4441, 3270, 3268, -1, 3268, 4440, 4441, -1, + 4440, 3268, 3266, -1, 3266, 4439, 4440, -1, + 4439, 3266, 3264, -1, 3264, 4438, 4439, -1, + 4438, 3264, 3262, -1, 3262, 4437, 4438, -1, + 4437, 3262, 3260, -1, 3260, 4436, 4437, -1, + 4436, 3260, 3258, -1, 3258, 4435, 4436, -1, + 4435, 3258, 3256, -1, 3256, 4434, 4435, -1, + 4434, 3256, 3254, -1, 3254, 4433, 4434, -1, + 4433, 3254, 3252, -1, 3252, 4432, 4433, -1, + 4432, 3252, 3250, -1, 3250, 4431, 4432, -1, + 4431, 3250, 3248, -1, 3248, 4430, 4431, -1, + 4430, 3248, 3246, -1, 3246, 4429, 4430, -1, + 4429, 3246, 3245, -1, 3245, 4428, 4429, -1, + 4428, 3245, 3321, -1, 3321, 4427, 4428, -1, + 4427, 3321, 3319, -1, 3319, 4426, 4427, -1, + 4426, 3319, 3317, -1, 3317, 4425, 4426, -1, + 4425, 3317, 3315, -1, 3315, 4424, 4425, -1, + 4424, 3315, 3313, -1, 3313, 4423, 4424, -1, + 4423, 3313, 3311, -1, 3311, 4422, 4423, -1, + 4422, 3311, 3309, -1, 3309, 4421, 4422, -1, + 4421, 3309, 3307, -1, 3307, 4420, 4421, -1, + 4420, 3307, 3305, -1, 3305, 4419, 4420, -1, + 4419, 3305, 3303, -1, 3303, 4418, 4419, -1, + 4418, 3303, 3301, -1, 3301, 4417, 4418, -1, + 4417, 3301, 3299, -1, 3299, 4416, 4417, -1, + 4416, 3299, 3297, -1, 3297, 4415, 4416, -1, + 4415, 3297, 3296, -1, 3296, 4414, 4415, -1, + 4414, 3296, 4447, -1, 4447, 4412, 4414, -1, + 4447, 4413, 4412, -1, 4448, 4413, 4447, -1, + 4448, 4408, 4413, -1, 4448, 4449, 4408, -1, + 4448, 4447, 4449, -1, 4450, 4449, 4447, -1, + 4450, 4447, 3296, -1, 3296, 3295, 4450, -1, + 4450, 4451, 4452, -1, 4451, 4450, 3295, -1, + 3295, 4453, 4451, -1, 4453, 3295, 3298, -1, + 3298, 4454, 4453, -1, 4454, 3298, 3300, -1, + 3300, 4455, 4454, -1, 4455, 3300, 3302, -1, + 3302, 4456, 4455, -1, 4456, 3302, 3304, -1, + 3304, 4457, 4456, -1, 4457, 3304, 3306, -1, + 3306, 4458, 4457, -1, 4458, 3306, 3308, -1, + 3308, 4459, 4458, -1, 4459, 3308, 3310, -1, + 3310, 4460, 4459, -1, 4460, 3310, 3312, -1, + 3312, 4461, 4460, -1, 4461, 3312, 3314, -1, + 3314, 4462, 4461, -1, 4462, 3314, 3316, -1, + 3316, 4463, 4462, -1, 4463, 3316, 3318, -1, + 3318, 4464, 4463, -1, 4464, 3318, 3320, -1, + 3320, 4465, 4464, -1, 4465, 3320, 3322, -1, + 3322, 4466, 4465, -1, 4466, 3322, 3323, -1, + 3323, 4467, 4466, -1, 4467, 3323, 3324, -1, + 3324, 4468, 4467, -1, 4468, 3324, 3325, -1, + 3325, 4469, 4468, -1, 4469, 3325, 3326, -1, + 3326, 4470, 4469, -1, 4470, 3326, 3327, -1, + 3327, 4471, 4470, -1, 4471, 3327, 3328, -1, + 3328, 4472, 4471, -1, 4472, 3328, 3329, -1, + 3329, 4473, 4472, -1, 4473, 3329, 3330, -1, + 3330, 4474, 4473, -1, 4474, 3330, 3331, -1, + 3331, 4475, 4474, -1, 4475, 3331, 3332, -1, + 3332, 4476, 4475, -1, 4476, 3332, 3333, -1, + 3333, 4477, 4476, -1, 4477, 3333, 3334, -1, + 3334, 4478, 4477, -1, 4478, 3334, 3335, -1, + 3335, 4479, 4478, -1, 4479, 3335, 3336, -1, + 3336, 4480, 4479, -1, 4480, 3336, 3337, -1, + 3337, 4481, 4480, -1, 4481, 3337, 3338, -1, + 3338, 4482, 4481, -1, 4482, 3338, 3339, -1, + 3339, 4483, 4482, -1, 4483, 3339, 3340, -1, + 3340, 4484, 4483, -1, 4484, 3340, 3341, -1, + 3341, 4485, 4484, -1, 4485, 3341, 3342, -1, + 3342, 4486, 4485, -1, 4486, 3342, 3344, -1, + 3344, 4487, 4486, -1, 4487, 3344, 3346, -1, + 3346, 4488, 4487, -1, 4488, 3346, 3348, -1, + 3348, 4489, 4488, -1, 4489, 3348, 3350, -1, + 3350, 4490, 4489, -1, 4490, 3350, 3352, -1, + 4490, 3352, 3355, -1, 3355, 4491, 4490, -1, + 4491, 3355, 3357, -1, 3357, 4492, 4491, -1, + 4492, 3357, 3359, -1, 3359, 4493, 4492, -1, + 4493, 3359, 3361, -1, 3361, 4494, 4493, -1, + 4494, 3361, 3363, -1, 3363, 4495, 4494, -1, + 4495, 3363, 3365, -1, 3365, 4496, 4495, -1, + 4496, 3365, 3401, -1, 3401, 4497, 4496, -1, + 4497, 3401, 3399, -1, 3399, 4498, 4497, -1, + 4498, 3399, 3397, -1, 3397, 4499, 4498, -1, + 4499, 3397, 3395, -1, 3395, 4500, 4499, -1, + 4500, 3395, 3393, -1, 3393, 4501, 4500, -1, + 4501, 3393, 3391, -1, 3391, 4502, 4501, -1, + 4502, 3391, 3389, -1, 3389, 4503, 4502, -1, + 4503, 3389, 3387, -1, 3387, 4504, 4503, -1, + 4504, 3387, 3385, -1, 3385, 4505, 4504, -1, + 4505, 3385, 3383, -1, 3383, 4506, 4505, -1, + 4506, 3383, 3381, -1, 3381, 4507, 4506, -1, + 4507, 3381, 3379, -1, 3379, 4508, 4507, -1, + 4508, 3379, 3377, -1, 3377, 4509, 4508, -1, + 4509, 3377, 3375, -1, 3375, 4510, 4509, -1, + 4510, 3375, 3373, -1, 3373, 4511, 4510, -1, + 4511, 3373, 3371, -1, 3371, 4512, 4511, -1, + 4512, 3371, 3369, -1, 3369, 4513, 4512, -1, + 4513, 3369, 3366, -1, 3366, 4514, 4513, -1, + 4514, 3366, 3368, -1, 3368, 4515, 4514, -1, + 4515, 3368, 3440, -1, 3440, 4516, 4515, -1, + 4516, 3440, 3442, -1, 3442, 4517, 4516, -1, + 4517, 3442, 3444, -1, 3444, 4518, 4517, -1, + 4518, 3444, 3446, -1, 3446, 4519, 4518, -1, + 4519, 3446, 3448, -1, 3448, 4520, 4519, -1, + 4520, 3448, 3450, -1, 3450, 4521, 4520, -1, + 4521, 3450, 3452, -1, 3452, 4522, 4521, -1, + 4522, 3452, 3454, -1, 3454, 4523, 4522, -1, + 4523, 3454, 3456, -1, 3456, 4524, 4523, -1, + 4524, 3456, 3458, -1, 3458, 4525, 4524, -1, + 4525, 3458, 3460, -1, 3460, 4526, 4525, -1, + 4526, 3460, 3462, -1, 3462, 4527, 4526, -1, + 4527, 3462, 3238, -1, 3238, 3237, 4527, -1, + 3116, 4528, 4529, -1, 4530, 4529, 4528, -1, + 4530, 4531, 4529, -1, 4532, 4531, 4530, -1, + 4530, 4528, 4532, -1, 4532, 4528, 4533, -1, + 4533, 4531, 4532, -1, 4533, 4534, 4531, -1, + 4534, 4533, 3237, -1, 3237, 4533, 4528, -1, + 4528, 4527, 3237, -1, 4527, 4528, 3116, -1, + 3116, 4526, 4527, -1, 4526, 3116, 3115, -1, + 3115, 4525, 4526, -1, 4525, 3115, 3114, -1, + 3114, 4524, 4525, -1, 4524, 3114, 3113, -1, + 3113, 4523, 4524, -1, 4523, 3113, 3112, -1, + 3112, 4522, 4523, -1, 4522, 3112, 3111, -1, + 3111, 4521, 4522, -1, 4521, 3111, 3110, -1, + 3110, 4520, 4521, -1, 4520, 3110, 3109, -1, + 3109, 4519, 4520, -1, 4519, 3109, 3108, -1, + 3108, 4518, 4519, -1, 4518, 3108, 3107, -1, + 3107, 4517, 4518, -1, 4517, 3107, 3106, -1, + 3106, 4516, 4517, -1, 4516, 3106, 3105, -1, + 3105, 4515, 4516, -1, 4515, 3105, 3061, -1, + 3061, 3060, 4515, -1, 3060, 4514, 4515, -1, + 4514, 3060, 3058, -1, 3058, 4513, 4514, -1, + 4513, 3058, 3056, -1, 3056, 4512, 4513, -1, + 4512, 3056, 3054, -1, 3054, 4511, 4512, -1, + 4511, 3054, 3052, -1, 3052, 4510, 4511, -1, + 4510, 3052, 3050, -1, 3050, 4509, 4510, -1, + 4509, 3050, 3048, -1, 3048, 4508, 4509, -1, + 4508, 3048, 3046, -1, 3046, 4507, 4508, -1, + 4507, 3046, 3044, -1, 3044, 4506, 4507, -1, + 4506, 3044, 3042, -1, 3042, 4505, 4506, -1, + 4505, 3042, 3040, -1, 3040, 4504, 4505, -1, + 4504, 3040, 3038, -1, 3038, 4503, 4504, -1, + 4503, 3038, 3036, -1, 3036, 4502, 4503, -1, + 4502, 3036, 3034, -1, 3034, 4501, 4502, -1, + 4501, 3034, 3032, -1, 3032, 4500, 4501, -1, + 4500, 3032, 3030, -1, 3030, 4499, 4500, -1, + 4499, 3030, 3028, -1, 3028, 4498, 4499, -1, + 4498, 3028, 3026, -1, 3026, 4497, 4498, -1, + 4497, 3026, 3024, -1, 3024, 4496, 4497, -1, + 4496, 3024, 3022, -1, 3022, 4495, 4496, -1, + 4495, 3022, 3020, -1, 3020, 4494, 4495, -1, + 4494, 3020, 3018, -1, 3018, 4493, 4494, -1, + 4493, 3018, 3016, -1, 3016, 4492, 4493, -1, + 4492, 3016, 3014, -1, 3014, 4491, 4492, -1, + 4491, 3014, 3013, -1, 3013, 4490, 4491, -1, + 3013, 4489, 4490, -1, 4489, 3013, 3011, -1, + 3011, 4488, 4489, -1, 4488, 3011, 3009, -1, + 3009, 4487, 4488, -1, 4487, 3009, 3007, -1, + 3007, 4486, 4487, -1, 4486, 3007, 3005, -1, + 3005, 4485, 4486, -1, 4485, 3005, 3003, -1, + 3003, 4484, 4485, -1, 4484, 3003, 3001, -1, + 3001, 4483, 4484, -1, 4483, 3001, 2999, -1, + 2999, 4482, 4483, -1, 4482, 2999, 2997, -1, + 2997, 4481, 4482, -1, 4481, 2997, 2995, -1, + 2995, 4480, 4481, -1, 4480, 2995, 2993, -1, + 2993, 4479, 4480, -1, 4479, 2993, 2991, -1, + 2991, 4478, 4479, -1, 4478, 2991, 2989, -1, + 2989, 4477, 4478, -1, 4477, 2989, 2987, -1, + 2987, 4476, 4477, -1, 4476, 2987, 2985, -1, + 2985, 4475, 4476, -1, 4475, 2985, 2983, -1, + 2983, 4474, 4475, -1, 4474, 2983, 2981, -1, + 2981, 4473, 4474, -1, 4473, 2981, 2979, -1, + 2979, 4472, 4473, -1, 4472, 2979, 2977, -1, + 2977, 4471, 4472, -1, 4471, 2977, 2975, -1, + 2975, 4470, 4471, -1, 4470, 2975, 2973, -1, + 2973, 4469, 4470, -1, 4469, 2973, 2971, -1, + 2971, 4468, 4469, -1, 4468, 2971, 2969, -1, + 2969, 4467, 4468, -1, 4467, 2969, 2967, -1, + 2967, 4466, 4467, -1, 4466, 2967, 2966, -1, + 2966, 4465, 4466, -1, 4465, 2966, 4535, -1, + 4535, 4464, 4465, -1, 4464, 4535, 4536, -1, + 4536, 4463, 4464, -1, 4463, 4536, 4537, -1, + 4537, 4462, 4463, -1, 4462, 4537, 4538, -1, + 4538, 4461, 4462, -1, 4461, 4538, 4539, -1, + 4539, 4460, 4461, -1, 4460, 4539, 4540, -1, + 4540, 4459, 4460, -1, 4459, 4540, 4541, -1, + 4541, 4458, 4459, -1, 4458, 4541, 4542, -1, + 4542, 4457, 4458, -1, 4457, 4542, 4543, -1, + 4543, 4456, 4457, -1, 4456, 4543, 2964, -1, + 2964, 4455, 4456, -1, 4455, 2964, 2963, -1, + 2963, 4454, 4455, -1, 4454, 2963, 2961, -1, + 2961, 4453, 4454, -1, 4453, 2961, 2960, -1, + 2960, 4451, 4453, -1, 2960, 4544, 4451, -1, + 4545, 4546, 4547, -1, 4546, 4544, 4547, -1, + 4546, 4451, 4544, -1, 4546, 4545, 4451, -1, + 4545, 4452, 4451, -1, 4452, 4545, 4547, -1, + 4452, 4547, 4548, -1, 4548, 4450, 4452, -1, + 4548, 4449, 4450, -1, 4548, 4547, 4449, -1, + 4547, 4408, 4449, -1, 4549, 4547, 4544, -1, + 4550, 4549, 4544, -1, 4550, 4544, 2960, -1, + 4550, 2960, 2959, -1, 2959, 4549, 4550, -1, + 2959, 4551, 4549, -1, 4551, 2959, 2958, -1, + 4552, 2958, 4553, -1, 4552, 4551, 2958, -1, + 4552, 4549, 4551, -1, 4552, 4553, 4549, -1, + 4554, 2957, 4553, -1, 2957, 4549, 4553, -1, + 4555, 4556, 4557, -1, 4555, 4558, 4556, -1, + 4556, 4559, 4560, -1, 4556, 4561, 4559, -1, + 4561, 4556, 4558, -1, 4558, 4562, 4561, -1, + 4562, 4558, 4563, -1, 4563, 4564, 4562, -1, + 4564, 4563, 4565, -1, 4565, 4566, 4564, -1, + 4566, 4565, 4567, -1, 4567, 4568, 4566, -1, + 4568, 4567, 4569, -1, 4569, 4570, 4568, -1, + 4570, 4569, 4571, -1, 4571, 4572, 4570, -1, + 4572, 4571, 4573, -1, 4573, 4574, 4572, -1, + 4574, 4573, 4575, -1, 4575, 4576, 4574, -1, + 4576, 4575, 4577, -1, 4577, 4578, 4576, -1, + 4578, 4577, 4579, -1, 4579, 4580, 4578, -1, + 4581, 4582, 4583, -1, 4581, 4583, 4580, -1, + 4580, 4579, 4581, -1, 4584, 4585, 4586, -1, + 4586, 4587, 4584, -1, 4587, 4586, 4588, -1, + 4588, 4589, 4587, -1, 4589, 4588, 4590, -1, + 4590, 4591, 4589, -1, 4590, 4592, 4591, -1, + 4593, 4594, 4595, -1, 4592, 4594, 4593, -1, + 4593, 4591, 4592, -1, 4593, 4595, 4591, -1, + 4591, 4595, 4581, -1, 4591, 4581, 4579, -1, + 4579, 4589, 4591, -1, 4589, 4579, 4577, -1, + 4577, 4587, 4589, -1, 4587, 4577, 4575, -1, + 4575, 4584, 4587, -1, 4584, 4575, 4573, -1, + 4573, 4585, 4584, -1, 4585, 4573, 4571, -1, + 4571, 4596, 4585, -1, 4596, 4571, 4569, -1, + 4569, 4597, 4596, -1, 4597, 4569, 4567, -1, + 4567, 4598, 4597, -1, 4598, 4567, 4565, -1, + 4565, 4599, 4598, -1, 4599, 4565, 4563, -1, + 4563, 4600, 4599, -1, 4600, 4563, 4558, -1, + 4558, 4555, 4600, -1, 4601, 4602, 4603, -1, + 4601, 4604, 4602, -1, 4604, 4601, 4605, -1, + 4605, 4606, 4604, -1, 4606, 4605, 4607, -1, + 4607, 4608, 4606, -1, 4608, 4607, 4609, -1, + 4609, 4610, 4608, -1, 4610, 4609, 4611, -1, + 4611, 4612, 4610, -1, 4612, 4611, 4613, -1, + 4613, 4614, 4612, -1, 4613, 4615, 4614, -1, + 4615, 4613, 4616, -1, 4616, 4617, 4615, -1, + 4617, 4618, 4619, -1, 4617, 4616, 4618, -1, + 4620, 4621, 4622, -1, 4620, 4623, 4621, -1, + 4624, 4625, 4621, -1, 4621, 4626, 4624, -1, + 4626, 4621, 4623, -1, 4623, 4627, 4626, -1, + 4627, 4623, 4628, -1, 4628, 4629, 4627, -1, + 4628, 4630, 4629, -1, 4628, 4631, 4630, -1, + 4631, 4628, 4623, -1, 4623, 4620, 4631, -1, + 4620, 4632, 4618, -1, 4618, 4631, 4620, -1, + 4631, 4618, 4616, -1, 4616, 4630, 4631, -1, + 4630, 4616, 4613, -1, 4630, 4613, 4611, -1, + 4611, 4629, 4630, -1, 4629, 4611, 4609, -1, + 4609, 4633, 4629, -1, 4633, 4609, 4607, -1, + 4607, 4634, 4633, -1, 4634, 4607, 4605, -1, + 4605, 4635, 4634, -1, 4635, 4605, 4601, -1, + 4601, 4603, 4635, -1, 4636, 4637, 4638, -1, + 4637, 4636, 4639, -1, 4639, 4640, 4637, -1, + 4641, 4637, 4640, -1, 4641, 4642, 4637, -1, + 4642, 4641, 4643, -1, 4641, 4640, 4643, -1, + 4644, 4645, 4646, -1, 4644, 4647, 4645, -1, + 4647, 4644, 4648, -1, 4644, 4646, 4648, -1, + 4649, 4650, 4646, -1, 4650, 4648, 4646, -1, + 4651, 4652, 4648, -1, 4651, 4648, 4653, -1, + 4653, 4654, 4651, -1, 4653, 4655, 4654, -1, + 4655, 4653, 4656, -1, 4656, 4653, 4648, -1, + 4657, 4658, 4656, -1, 4657, 4656, 4659, -1, + 4659, 4660, 4657, -1, 4659, 4661, 4660, -1, + 4661, 4659, 4662, -1, 4662, 4659, 4656, -1, + 4663, 4664, 4665, -1, 4664, 4663, 4662, -1, + 4666, 4667, 4668, -1, 4668, 4667, 4669, -1, + 4669, 4670, 4668, -1, 4671, 4672, 4673, -1, + 4673, 4674, 4671, -1, 4673, 4675, 4674, -1, + 4673, 4672, 4675, -1, 4676, 4677, 4678, -1, + 4677, 4676, 4679, -1, 4680, 4679, 4676, -1, + 4676, 4681, 4680, -1, 4676, 4678, 4681, -1, + 4682, 4678, 4683, -1, 4682, 4681, 4678, -1, + 4682, 4680, 4681, -1, 4682, 4683, 4680, -1, + 4684, 4680, 4683, -1, 4685, 4686, 4687, -1, + 4686, 4685, 4684, -1, 4686, 4684, 4683, -1, + 4683, 4687, 4686, -1, 4687, 4683, 4678, -1, + 4678, 4675, 4672, -1, 4675, 4678, 4677, -1, + 4677, 4679, 4675, -1, 4679, 4674, 4675, -1, + 4679, 4688, 4674, -1, 4688, 4679, 4680, -1, + 4680, 4689, 4688, -1, 4689, 4680, 4684, -1, + 4689, 4684, 4690, -1, 4690, 4691, 4689, -1, + 4691, 4690, 4692, -1, 4692, 4693, 4691, -1, + 4692, 4694, 4693, -1, 4692, 4695, 4694, -1, + 4695, 4692, 4690, -1, 4690, 4696, 4695, -1, + 4696, 4690, 4684, -1, 4684, 4697, 4696, -1, + 4697, 4684, 4685, -1, 4698, 4697, 4685, -1, + 4698, 4685, 4687, -1, 4698, 4687, 4699, -1, + 4699, 4697, 4698, -1, 4699, 4700, 4697, -1, + 4699, 4687, 4700, -1, 4687, 4701, 4700, -1, + 4702, 4703, 4701, -1, 4704, 4705, 4706, -1, + 4704, 4707, 4705, -1, 4704, 4708, 4707, -1, + 4704, 4706, 4708, -1, 4709, 4710, 4711, -1, + 4709, 4711, 4712, -1, 4712, 4713, 4709, -1, + 4714, 4715, 4716, -1, 4717, 4718, 4719, -1, + 4717, 4720, 4718, -1, 4717, 4721, 4720, -1, + 4717, 4719, 4721, -1, 4722, 4723, 4724, -1, + 4722, 4724, 4719, -1, 4724, 4721, 4719, -1, + 4721, 4724, 4725, -1, 4725, 4726, 4721, -1, + 4726, 4725, 4727, -1, 4727, 4728, 4726, -1, + 4728, 4727, 4729, -1, 4729, 4730, 4728, -1, + 4730, 4729, 4731, -1, 4731, 4732, 4730, -1, + 4732, 4731, 4733, -1, 4733, 4734, 4732, -1, + 4734, 4733, 4735, -1, 4735, 4736, 4734, -1, + 4736, 4735, 4715, -1, 4715, 4714, 4736, -1, + 4737, 4738, 4739, -1, 4737, 4713, 4740, -1, + 4713, 4737, 4741, -1, 4741, 4742, 4713, -1, + 4742, 4741, 4743, -1, 4743, 4744, 4742, -1, + 4743, 4745, 4744, -1, 4743, 4746, 4745, -1, + 4746, 4743, 4741, -1, 4741, 4747, 4746, -1, + 4747, 4741, 4737, -1, 4737, 4739, 4747, -1, + 4748, 4749, 4750, -1, 4751, 4739, 4752, -1, + 4753, 4752, 4739, -1, 4752, 4753, 4750, -1, + 4752, 4750, 4749, -1, 4749, 4751, 4752, -1, + 4749, 4748, 4751, -1, 4748, 4754, 4751, -1, + 4748, 4750, 4754, -1, 4755, 4756, 4757, -1, + 4758, 4759, 4760, -1, 4759, 4758, 4761, -1, + 4761, 4762, 4759, -1, 4762, 4761, 4763, -1, + 4763, 4764, 4762, -1, 4764, 4763, 4765, -1, + 4765, 4766, 4764, -1, 4766, 4765, 4767, -1, + 4767, 4768, 4766, -1, 4768, 4767, 4769, -1, + 4769, 4770, 4768, -1, 4771, 4772, 4770, -1, + 4771, 4770, 4773, -1, 4770, 4769, 4773, -1, + 4774, 4769, 4775, -1, 4774, 4773, 4769, -1, + 4774, 4776, 4773, -1, 4774, 4775, 4776, -1, + 4777, 4778, 4779, -1, 4780, 4781, 4782, -1, + 4780, 4782, 4783, -1, 4783, 4784, 4780, -1, + 4784, 4783, 4785, -1, 4785, 4786, 4784, -1, + 4786, 4785, 4787, -1, 4787, 4788, 4786, -1, + 4788, 4787, 4779, -1, 4779, 4789, 4788, -1, + 4789, 4779, 4778, -1, 4790, 4789, 4778, -1, + 4790, 4791, 4789, -1, 4791, 4790, 4792, -1, + 4790, 4778, 4792, -1, 4778, 4777, 4792, -1, + 4793, 4792, 4777, -1, 4794, 4793, 4777, -1, + 4777, 4779, 4794, -1, 4779, 4795, 4794, -1, + 4795, 4779, 4787, -1, 4787, 4796, 4795, -1, + 4796, 4787, 4785, -1, 4785, 4797, 4796, -1, + 4797, 4785, 4783, -1, 4783, 4798, 4797, -1, + 4798, 4783, 4782, -1, 4782, 4799, 4798, -1, + 4782, 4800, 4799, -1, 4800, 4782, 4781, -1, + 4781, 4801, 4800, -1, 4781, 4802, 4801, -1, + 4781, 4780, 4802, -1, 4803, 4804, 4805, -1, + 4804, 4803, 4806, -1, 4806, 4807, 4804, -1, + 4807, 4806, 4808, -1, 4808, 4809, 4807, -1, + 4809, 4808, 4810, -1, 4810, 4811, 4809, -1, + 4811, 4810, 4812, -1, 4812, 4813, 4811, -1, + 4813, 4812, 4802, -1, 4813, 4802, 4780, -1, + 4813, 4780, 4784, -1, 4784, 4811, 4813, -1, + 4811, 4784, 4786, -1, 4786, 4809, 4811, -1, + 4809, 4786, 4788, -1, 4788, 4807, 4809, -1, + 4807, 4788, 4789, -1, 4789, 4804, 4807, -1, + 4789, 4791, 4804, -1, 4814, 4804, 4791, -1, + 4791, 4792, 4814, -1, 4815, 4814, 4792, -1, + 4815, 4804, 4814, -1, 4815, 4805, 4804, -1, + 4815, 4792, 4805, -1, 4776, 4805, 4792, -1, + 4816, 4805, 4776, -1, 4816, 4803, 4805, -1, + 4816, 4817, 4803, -1, 4817, 4816, 4776, -1, + 4817, 4776, 4775, -1, 4775, 4769, 4817, -1, + 4769, 4803, 4817, -1, 4803, 4769, 4767, -1, + 4767, 4806, 4803, -1, 4806, 4767, 4765, -1, + 4765, 4808, 4806, -1, 4808, 4765, 4763, -1, + 4763, 4810, 4808, -1, 4810, 4763, 4761, -1, + 4761, 4812, 4810, -1, 4812, 4761, 4758, -1, + 4758, 4802, 4812, -1, 4758, 4760, 4802, -1, + 4818, 4802, 4760, -1, 4818, 4801, 4802, -1, + 4819, 4801, 4818, -1, 4801, 4819, 4820, -1, + 4820, 4800, 4801, -1, 4800, 4820, 4821, -1, + 4821, 4799, 4800, -1, 4799, 4821, 4822, -1, + 4799, 4822, 4823, -1, 4823, 4798, 4799, -1, + 4798, 4823, 4824, -1, 4824, 4797, 4798, -1, + 4797, 4824, 4825, -1, 4825, 4796, 4797, -1, + 4796, 4825, 4757, -1, 4757, 4795, 4796, -1, + 4795, 4757, 4756, -1, 4826, 4795, 4756, -1, + 4826, 4827, 4795, -1, 4827, 4794, 4795, -1, + 4827, 4793, 4794, -1, 4827, 4826, 4793, -1, + 4826, 4756, 4793, -1, 4756, 4755, 4793, -1, + 4750, 4793, 4755, -1, 4755, 4754, 4750, -1, + 4755, 4757, 4754, -1, 4757, 4751, 4754, -1, + 4751, 4757, 4825, -1, 4825, 4739, 4751, -1, + 4739, 4825, 4824, -1, 4824, 4747, 4739, -1, + 4747, 4824, 4823, -1, 4823, 4746, 4747, -1, + 4746, 4823, 4822, -1, 4822, 4745, 4746, -1, + 4822, 4828, 4745, -1, 4828, 4822, 4821, -1, + 4821, 4829, 4828, -1, 4829, 4821, 4820, -1, + 4820, 4830, 4829, -1, 4830, 4820, 4819, -1, + 4819, 4831, 4830, -1, 4819, 4818, 4831, -1, + 4832, 4831, 4818, -1, 4818, 4760, 4832, -1, + 4714, 4832, 4760, -1, 4760, 4736, 4714, -1, + 4736, 4760, 4759, -1, 4759, 4734, 4736, -1, + 4734, 4759, 4762, -1, 4762, 4732, 4734, -1, + 4732, 4762, 4764, -1, 4764, 4730, 4732, -1, + 4730, 4764, 4766, -1, 4766, 4728, 4730, -1, + 4728, 4766, 4768, -1, 4768, 4726, 4728, -1, + 4726, 4768, 4770, -1, 4770, 4721, 4726, -1, + 4721, 4770, 4772, -1, 4772, 4720, 4721, -1, + 4772, 4718, 4720, -1, 4772, 4771, 4718, -1, + 4771, 4773, 4718, -1, 4718, 4773, 4776, -1, + 4833, 4750, 4753, -1, 4753, 4834, 4833, -1, + 4753, 4739, 4834, -1, 4834, 4739, 4738, -1, + 4738, 4833, 4834, -1, 4738, 4835, 4833, -1, + 4835, 4738, 4737, -1, 4835, 4737, 4740, -1, + 4740, 4833, 4835, -1, 4740, 4836, 4833, -1, + 4836, 4740, 4713, -1, 4836, 4713, 4712, -1, + 4712, 4711, 4836, -1, 4711, 4833, 4836, -1, + 4708, 4711, 4837, -1, 4838, 4708, 4706, -1, + 4706, 4839, 4838, -1, 4840, 4841, 4842, -1, + 4840, 4842, 4843, -1, 4843, 4844, 4840, -1, + 4844, 4843, 4845, -1, 4844, 4845, 4846, -1, + 4844, 4846, 4847, -1, 4847, 4840, 4844, -1, + 4847, 4848, 4840, -1, 4849, 4838, 4850, -1, + 4849, 4848, 4838, -1, 4849, 4840, 4848, -1, + 4849, 4850, 4840, -1, 4850, 4841, 4840, -1, + 4841, 4850, 4838, -1, 4841, 4838, 4839, -1, + 4839, 4842, 4841, -1, 4839, 4706, 4842, -1, + 4842, 4706, 4705, -1, 4842, 4705, 4851, -1, + 4851, 4843, 4842, -1, 4843, 4851, 4852, -1, + 4852, 4845, 4843, -1, 4852, 4853, 4845, -1, + 4853, 4852, 4854, -1, 4854, 4855, 4853, -1, + 4855, 4854, 4856, -1, 4856, 4857, 4855, -1, + 4857, 4856, 4858, -1, 4858, 4859, 4857, -1, + 4859, 4858, 4860, -1, 4860, 4861, 4859, -1, + 4861, 4860, 4862, -1, 4862, 4863, 4861, -1, + 4863, 4862, 4864, -1, 4864, 4865, 4863, -1, + 4866, 4865, 4867, -1, 4866, 4863, 4865, -1, + 4863, 4866, 4868, -1, 4868, 4861, 4863, -1, + 4861, 4868, 4869, -1, 4869, 4859, 4861, -1, + 4859, 4869, 4870, -1, 4870, 4857, 4859, -1, + 4857, 4870, 4871, -1, 4871, 4855, 4857, -1, + 4855, 4871, 4872, -1, 4872, 4853, 4855, -1, + 4853, 4872, 4873, -1, 4873, 4845, 4853, -1, + 4845, 4873, 4874, -1, 4874, 4846, 4845, -1, + 4846, 4874, 4875, -1, 4846, 4875, 4876, -1, + 4876, 4847, 4846, -1, 4876, 4877, 4847, -1, + 4878, 4879, 4880, -1, 4881, 4879, 4878, -1, + 4878, 4876, 4881, -1, 4878, 4880, 4876, -1, + 4880, 4877, 4876, -1, 4877, 4880, 4879, -1, + 4877, 4879, 4882, -1, 4882, 4847, 4877, -1, + 4882, 4848, 4847, -1, 4882, 4879, 4848, -1, + 4879, 4838, 4848, -1, 4879, 4881, 4883, -1, + 4884, 4883, 4881, -1, 4884, 4885, 4883, -1, + 4884, 4886, 4885, -1, 4884, 4881, 4886, -1, + 4886, 4881, 4876, -1, 4886, 4876, 4875, -1, + 4875, 4887, 4886, -1, 4875, 4888, 4887, -1, + 4888, 4875, 4874, -1, 4874, 4889, 4888, -1, + 4889, 4874, 4873, -1, 4873, 4890, 4889, -1, + 4890, 4873, 4872, -1, 4872, 4891, 4890, -1, + 4891, 4872, 4871, -1, 4871, 4892, 4891, -1, + 4892, 4871, 4870, -1, 4870, 4893, 4892, -1, + 4893, 4870, 4869, -1, 4869, 4894, 4893, -1, + 4894, 4869, 4868, -1, 4868, 4895, 4894, -1, + 4895, 4868, 4866, -1, 4866, 4867, 4895, -1, + 4896, 4897, 4898, -1, 4899, 4900, 4901, -1, + 4901, 4902, 4899, -1, 4902, 4901, 4903, -1, + 4903, 4904, 4902, -1, 4905, 4906, 4907, -1, + 4907, 4908, 4905, -1, 4908, 4907, 4909, -1, + 4909, 4910, 4908, -1, 4910, 4909, 4911, -1, + 4911, 4912, 4910, -1, 4912, 4911, 4913, -1, + 4913, 4914, 4912, -1, 4914, 4913, 4904, -1, + 4904, 4903, 4914, -1, 4915, 4914, 4903, -1, + 4903, 4916, 4915, -1, 4916, 4903, 4901, -1, + 4901, 4917, 4916, -1, 4917, 4901, 4900, -1, + 4900, 4918, 4917, -1, 4900, 4919, 4918, -1, + 4900, 4899, 4919, -1, 4920, 4921, 4922, -1, + 4923, 4924, 4925, -1, 4923, 4925, 4926, -1, + 4927, 4926, 4925, -1, 4928, 4927, 4925, -1, + 4928, 4929, 4927, -1, 4929, 4928, 4930, -1, + 4930, 4931, 4929, -1, 4931, 4930, 4932, -1, + 4932, 4933, 4931, -1, 4933, 4932, 4934, -1, + 4934, 4935, 4933, -1, 4935, 4934, 4936, -1, + 4936, 4937, 4935, -1, 4937, 4936, 4938, -1, + 4938, 4939, 4937, -1, 4939, 4938, 4940, -1, + 4940, 4941, 4939, -1, 4941, 4940, 4942, -1, + 4942, 4943, 4941, -1, 4943, 4942, 4944, -1, + 4944, 4945, 4943, -1, 4945, 4944, 4946, -1, + 4946, 4947, 4945, -1, 4946, 4948, 4947, -1, + 4946, 4949, 4948, -1, 4949, 4946, 4944, -1, + 4944, 4950, 4949, -1, 4950, 4944, 4942, -1, + 4942, 4951, 4950, -1, 4951, 4942, 4940, -1, + 4940, 4952, 4951, -1, 4952, 4940, 4938, -1, + 4938, 4953, 4952, -1, 4953, 4938, 4936, -1, + 4936, 4954, 4953, -1, 4954, 4936, 4934, -1, + 4934, 4955, 4954, -1, 4955, 4934, 4932, -1, + 4932, 4956, 4955, -1, 4956, 4932, 4930, -1, + 4930, 4957, 4956, -1, 4957, 4930, 4928, -1, + 4928, 4925, 4957, -1, 4958, 4959, 4960, -1, + 4958, 4960, 4961, -1, 4962, 4921, 4961, -1, + 4962, 4963, 4921, -1, 4962, 4964, 4963, -1, + 4962, 4961, 4964, -1, 4964, 4961, 4960, -1, + 4964, 4960, 4957, -1, 4964, 4957, 4925, -1, + 4925, 4963, 4964, -1, 4963, 4925, 4924, -1, + 4924, 4921, 4963, -1, 4924, 4923, 4921, -1, + 4923, 4926, 4921, -1, 4926, 4922, 4921, -1, + 4922, 4926, 4927, -1, 4922, 4927, 4965, -1, + 4965, 4920, 4922, -1, 4920, 4966, 4967, -1, + 4968, 4969, 4970, -1, 4968, 4967, 4969, -1, + 4967, 4968, 4971, -1, 4972, 4971, 4968, -1, + 4968, 4970, 4972, -1, 4973, 4974, 4975, -1, + 4975, 4976, 4973, -1, 4976, 4975, 4977, -1, + 4977, 4978, 4976, -1, 4978, 4977, 4979, -1, + 4979, 4980, 4978, -1, 4980, 4979, 4981, -1, + 4981, 4982, 4980, -1, 4982, 4981, 4983, -1, + 4983, 4984, 4982, -1, 4984, 4983, 4985, -1, + 4985, 4986, 4984, -1, 4986, 4985, 4987, -1, + 4987, 4988, 4986, -1, 4988, 4987, 4989, -1, + 4989, 4990, 4988, -1, 4989, 4991, 4990, -1, + 4989, 4992, 4991, -1, 4992, 4989, 4987, -1, + 4987, 4993, 4992, -1, 4993, 4987, 4985, -1, + 4985, 4994, 4993, -1, 4994, 4985, 4983, -1, + 4983, 4995, 4994, -1, 4995, 4983, 4981, -1, + 4981, 4996, 4995, -1, 4996, 4981, 4979, -1, + 4979, 4997, 4996, -1, 4997, 4979, 4977, -1, + 4977, 4998, 4997, -1, 4998, 4977, 4975, -1, + 4975, 4999, 4998, -1, 4999, 4975, 4974, -1, + 4974, 5000, 4999, -1, 5001, 5002, 5003, -1, + 5002, 5001, 5004, -1, 5002, 5004, 5005, -1, + 5002, 5005, 5006, -1, 5006, 5003, 5002, -1, + 5006, 5007, 5003, -1, 5006, 5008, 5007, -1, + 5008, 5006, 5005, -1, 5005, 5009, 5008, -1, + 5005, 5010, 5009, -1, 5010, 5005, 5004, -1, + 5004, 5011, 5010, -1, 5004, 5012, 5011, -1, + 5012, 5004, 5001, -1, 5001, 5013, 5012, -1, + 5001, 5003, 5013, -1, 5014, 5015, 5016, -1, + 5016, 5017, 5014, -1, 5017, 5016, 5018, -1, + 5018, 5019, 5017, -1, 5019, 5018, 5020, -1, + 5020, 5021, 5019, -1, 5020, 5022, 5021, -1, + 5020, 5023, 5022, -1, 5023, 5020, 5018, -1, + 5018, 5024, 5023, -1, 5024, 5018, 5016, -1, + 5016, 5025, 5024, -1, 5025, 5016, 5015, -1, + 5025, 5015, 5026, -1, 5026, 5027, 5025, -1, + 5027, 5026, 5028, -1, 5028, 5029, 5027, -1, + 5029, 5028, 5030, -1, 5029, 5030, 5013, -1, + 5029, 5013, 5003, -1, 5003, 5027, 5029, -1, + 5027, 5003, 5007, -1, 5007, 5025, 5027, -1, + 5007, 5024, 5025, -1, 5024, 5007, 5008, -1, + 5008, 5023, 5024, -1, 5023, 5008, 5009, -1, + 5009, 5022, 5023, -1, 5009, 5031, 5022, -1, + 5031, 5009, 5010, -1, 5010, 5032, 5031, -1, + 5032, 5010, 5011, -1, 5011, 5033, 5032, -1, + 5011, 5034, 5033, -1, 5034, 5011, 5012, -1, + 5012, 5035, 5034, -1, 5035, 5012, 5013, -1, + 5013, 5036, 5035, -1, 5036, 5013, 5030, -1, + 5030, 5037, 5036, -1, 5030, 5038, 5037, -1, + 5038, 5030, 5028, -1, 5028, 5039, 5038, -1, + 5039, 5028, 5026, -1, 5026, 5040, 5039, -1, + 5040, 5026, 5015, -1, 5015, 5041, 5040, -1, + 5015, 5014, 5041, -1, 5042, 5041, 5014, -1, + 5014, 5043, 5042, -1, 5043, 5014, 5017, -1, + 5017, 5044, 5043, -1, 5044, 5017, 5019, -1, + 5019, 5045, 5044, -1, 5045, 5019, 5021, -1, + 5021, 5046, 5045, -1, 5021, 5047, 5046, -1, + 5047, 5021, 5022, -1, 5022, 5048, 5047, -1, + 5048, 5022, 5031, -1, 5031, 5049, 5048, -1, + 5049, 5031, 5032, -1, 5032, 5050, 5049, -1, + 5050, 5032, 5033, -1, 5033, 5051, 5050, -1, + 5033, 5052, 5051, -1, 5052, 5033, 5034, -1, + 5034, 5053, 5052, -1, 5053, 5034, 5035, -1, + 5035, 5054, 5053, -1, 5054, 5035, 5036, -1, + 5036, 5055, 5054, -1, 5055, 5036, 5037, -1, + 5037, 5056, 5055, -1, 5037, 5057, 5056, -1, + 5057, 5037, 5038, -1, 5038, 5058, 5057, -1, + 5058, 5038, 5039, -1, 5039, 5059, 5058, -1, + 5059, 5039, 5040, -1, 5040, 5060, 5059, -1, + 5060, 5040, 5041, -1, 5041, 5061, 5060, -1, + 5041, 5042, 5061, -1, 5062, 5061, 5042, -1, + 5042, 5063, 5062, -1, 5063, 5042, 5043, -1, + 5043, 5064, 5063, -1, 5064, 5043, 5044, -1, + 5044, 5065, 5064, -1, 5065, 5044, 5045, -1, + 5045, 5066, 5065, -1, 5066, 5045, 5046, -1, + 5046, 5067, 5066, -1, 5046, 5068, 5067, -1, + 5068, 5046, 5047, -1, 5047, 5069, 5068, -1, + 5069, 5047, 5048, -1, 5048, 5070, 5069, -1, + 5070, 5048, 5049, -1, 5049, 5071, 5070, -1, + 5071, 5049, 5050, -1, 5050, 5072, 5071, -1, + 5072, 5050, 5051, -1, 5051, 5073, 5072, -1, + 5051, 5074, 5073, -1, 5074, 5051, 5052, -1, + 5052, 5075, 5074, -1, 5075, 5052, 5053, -1, + 5053, 5076, 5075, -1, 5076, 5053, 5054, -1, + 5054, 5077, 5076, -1, 5077, 5054, 5055, -1, + 5055, 5078, 5077, -1, 5078, 5055, 5056, -1, + 5056, 5079, 5078, -1, 5056, 5080, 5079, -1, + 5080, 5056, 5057, -1, 5057, 5081, 5080, -1, + 5081, 5057, 5058, -1, 5058, 5082, 5081, -1, + 5082, 5058, 5059, -1, 5059, 5083, 5082, -1, + 5083, 5059, 5060, -1, 5060, 5084, 5083, -1, + 5084, 5060, 5061, -1, 5061, 5085, 5084, -1, + 5061, 5062, 5085, -1, 5086, 5085, 5062, -1, + 5062, 5087, 5086, -1, 5087, 5062, 5063, -1, + 5063, 5088, 5087, -1, 5088, 5063, 5064, -1, + 5064, 5089, 5088, -1, 5089, 5064, 5065, -1, + 5065, 5090, 5089, -1, 5090, 5065, 5066, -1, + 5066, 5091, 5090, -1, 5091, 5066, 5067, -1, + 5067, 5092, 5091, -1, 5067, 5093, 5092, -1, + 5093, 5067, 5068, -1, 5068, 5094, 5093, -1, + 5094, 5068, 5069, -1, 5069, 5095, 5094, -1, + 5095, 5069, 5070, -1, 5070, 5096, 5095, -1, + 5096, 5070, 5071, -1, 5071, 5097, 5096, -1, + 5097, 5071, 5072, -1, 5072, 5098, 5097, -1, + 5098, 5072, 5073, -1, 5073, 5099, 5098, -1, + 5073, 5100, 5099, -1, 5100, 5073, 5074, -1, + 5074, 5101, 5100, -1, 5101, 5074, 5075, -1, + 5075, 5102, 5101, -1, 5102, 5075, 5076, -1, + 5076, 5103, 5102, -1, 5103, 5076, 5077, -1, + 5077, 5104, 5103, -1, 5104, 5077, 5078, -1, + 5078, 5105, 5104, -1, 5105, 5078, 5079, -1, + 5079, 5106, 5105, -1, 5079, 5107, 5106, -1, + 5107, 5079, 5080, -1, 5080, 5108, 5107, -1, + 5108, 5080, 5081, -1, 5081, 5109, 5108, -1, + 5109, 5081, 5082, -1, 5082, 5110, 5109, -1, + 5110, 5082, 5083, -1, 5083, 5111, 5110, -1, + 5111, 5083, 5084, -1, 5084, 5112, 5111, -1, + 5112, 5084, 5085, -1, 5085, 5113, 5112, -1, + 5085, 5086, 5113, -1, 5114, 5113, 5086, -1, + 5086, 5115, 5114, -1, 5115, 5086, 5087, -1, + 5087, 5116, 5115, -1, 5116, 5087, 5088, -1, + 5088, 5117, 5116, -1, 5117, 5088, 5089, -1, + 5089, 5118, 5117, -1, 5118, 5089, 5090, -1, + 5090, 5119, 5118, -1, 5119, 5090, 5091, -1, + 5091, 5120, 5119, -1, 5120, 5091, 5092, -1, + 5092, 5121, 5120, -1, 5092, 5122, 5121, -1, + 5122, 5092, 5093, -1, 5093, 5123, 5122, -1, + 5123, 5093, 5094, -1, 5094, 5124, 5123, -1, + 5124, 5094, 5095, -1, 5095, 5125, 5124, -1, + 5125, 5095, 5096, -1, 5096, 5126, 5125, -1, + 5126, 5096, 5097, -1, 5097, 5127, 5126, -1, + 5127, 5097, 5098, -1, 5098, 5128, 5127, -1, + 5128, 5098, 5099, -1, 5099, 5129, 5128, -1, + 5099, 5130, 5129, -1, 5130, 5099, 5100, -1, + 5100, 5131, 5130, -1, 5131, 5100, 5101, -1, + 5101, 5132, 5131, -1, 5132, 5101, 5102, -1, + 5102, 5133, 5132, -1, 5133, 5102, 5103, -1, + 5103, 5134, 5133, -1, 5134, 5103, 5104, -1, + 5104, 5135, 5134, -1, 5135, 5104, 5105, -1, + 5105, 5136, 5135, -1, 5136, 5105, 5106, -1, + 5106, 5137, 5136, -1, 5106, 5138, 5137, -1, + 5138, 5106, 5107, -1, 5107, 5139, 5138, -1, + 5139, 5107, 5108, -1, 5108, 5140, 5139, -1, + 5140, 5108, 5109, -1, 5109, 5141, 5140, -1, + 5141, 5109, 5110, -1, 5110, 5142, 5141, -1, + 5142, 5110, 5111, -1, 5111, 5143, 5142, -1, + 5143, 5111, 5112, -1, 5112, 5144, 5143, -1, + 5144, 5112, 5113, -1, 5113, 5145, 5144, -1, + 5113, 5114, 5145, -1, 5146, 5145, 5114, -1, + 5114, 5147, 5146, -1, 5147, 5114, 5115, -1, + 5115, 5148, 5147, -1, 5148, 5115, 5116, -1, + 5116, 5149, 5148, -1, 5149, 5116, 5117, -1, + 5117, 5150, 5149, -1, 5150, 5117, 5118, -1, + 5118, 5151, 5150, -1, 5151, 5118, 5119, -1, + 5119, 5152, 5151, -1, 5152, 5119, 5120, -1, + 5120, 5153, 5152, -1, 5153, 5120, 5121, -1, + 5121, 5154, 5153, -1, 5121, 5155, 5154, -1, + 5155, 5121, 5122, -1, 5122, 5156, 5155, -1, + 5156, 5122, 5123, -1, 5123, 5157, 5156, -1, + 5157, 5123, 5124, -1, 5124, 5158, 5157, -1, + 5158, 5124, 5125, -1, 5125, 5159, 5158, -1, + 5159, 5125, 5126, -1, 5126, 5160, 5159, -1, + 5160, 5126, 5127, -1, 5127, 5161, 5160, -1, + 5161, 5127, 5128, -1, 5128, 5162, 5161, -1, + 5162, 5128, 5129, -1, 5129, 5163, 5162, -1, + 5129, 5164, 5163, -1, 5164, 5129, 5130, -1, + 5130, 5165, 5164, -1, 5165, 5130, 5131, -1, + 5131, 5166, 5165, -1, 5166, 5131, 5132, -1, + 5132, 5167, 5166, -1, 5167, 5132, 5133, -1, + 5133, 5168, 5167, -1, 5168, 5133, 5134, -1, + 5134, 5169, 5168, -1, 5169, 5134, 5135, -1, + 5135, 5170, 5169, -1, 5170, 5135, 5136, -1, + 5136, 5171, 5170, -1, 5171, 5136, 5137, -1, + 5137, 5172, 5171, -1, 5137, 5173, 5172, -1, + 5173, 5137, 5138, -1, 5138, 5174, 5173, -1, + 5174, 5138, 5139, -1, 5139, 5175, 5174, -1, + 5175, 5139, 5140, -1, 5140, 5176, 5175, -1, + 5176, 5140, 5141, -1, 5141, 5177, 5176, -1, + 5177, 5141, 5142, -1, 5142, 5178, 5177, -1, + 5178, 5142, 5143, -1, 5143, 5179, 5178, -1, + 5179, 5143, 5144, -1, 5144, 5180, 5179, -1, + 5180, 5144, 5145, -1, 5145, 5181, 5180, -1, + 5145, 5146, 5181, -1, 5000, 5181, 5146, -1, + 5146, 4999, 5000, -1, 4999, 5146, 5147, -1, + 5147, 4998, 4999, -1, 4998, 5147, 5148, -1, + 5148, 4997, 4998, -1, 4997, 5148, 5149, -1, + 5149, 4996, 4997, -1, 4996, 5149, 5150, -1, + 5150, 4995, 4996, -1, 4995, 5150, 5151, -1, + 5151, 4994, 4995, -1, 4994, 5151, 5152, -1, + 5152, 4993, 4994, -1, 4993, 5152, 5153, -1, + 5153, 4992, 4993, -1, 4992, 5153, 5154, -1, + 5154, 4991, 4992, -1, 5154, 5182, 4991, -1, + 5182, 5154, 5155, -1, 5155, 5183, 5182, -1, + 5183, 5155, 5156, -1, 5156, 5184, 5183, -1, + 5184, 5156, 5157, -1, 5157, 5185, 5184, -1, + 5185, 5157, 5158, -1, 5158, 5186, 5185, -1, + 5186, 5158, 5159, -1, 5159, 5187, 5186, -1, + 5187, 5159, 5160, -1, 5160, 5188, 5187, -1, + 5188, 5160, 5161, -1, 5161, 5189, 5188, -1, + 5189, 5161, 5162, -1, 5162, 5190, 5189, -1, + 5190, 5162, 5163, -1, 5163, 5191, 5190, -1, + 5163, 5192, 5191, -1, 5192, 5163, 5164, -1, + 5164, 5193, 5192, -1, 5193, 5164, 5165, -1, + 5165, 5194, 5193, -1, 5194, 5165, 5166, -1, + 5166, 5195, 5194, -1, 5195, 5166, 5167, -1, + 5167, 5196, 5195, -1, 5196, 5167, 5168, -1, + 5168, 5197, 5196, -1, 5197, 5168, 5169, -1, + 5169, 5198, 5197, -1, 5198, 5169, 5170, -1, + 5170, 5199, 5198, -1, 5199, 5170, 5171, -1, + 5171, 5200, 5199, -1, 5200, 5171, 5172, -1, + 5172, 5201, 5200, -1, 5172, 5202, 5201, -1, + 5202, 5172, 5173, -1, 5173, 5203, 5202, -1, + 5203, 5173, 5174, -1, 5174, 5204, 5203, -1, + 5204, 5174, 5175, -1, 5175, 5205, 5204, -1, + 5205, 5175, 5176, -1, 5176, 5206, 5205, -1, + 5206, 5176, 5177, -1, 5177, 5207, 5206, -1, + 5207, 5177, 5178, -1, 5178, 5208, 5207, -1, + 5208, 5178, 5179, -1, 5179, 5209, 5208, -1, + 5209, 5179, 5180, -1, 5180, 5210, 5209, -1, + 5210, 5180, 5181, -1, 5181, 5211, 5210, -1, + 5181, 5000, 5211, -1, 5212, 5211, 5000, -1, + 5000, 4974, 5212, -1, 5213, 5214, 5212, -1, + 5213, 5212, 4974, -1, 4974, 4973, 5213, -1, + 5215, 5216, 5217, -1, 5213, 5217, 5216, -1, + 5217, 5213, 4973, -1, 4973, 5218, 5217, -1, + 5218, 4973, 4976, -1, 4976, 5219, 5218, -1, + 5219, 4976, 4978, -1, 4978, 5220, 5219, -1, + 5220, 4978, 4980, -1, 4980, 5221, 5220, -1, + 5221, 4980, 4982, -1, 4982, 5222, 5221, -1, + 5222, 4982, 4984, -1, 4984, 5223, 5222, -1, + 5223, 4984, 4986, -1, 4986, 5224, 5223, -1, + 5224, 4986, 4988, -1, 4988, 5225, 5224, -1, + 5225, 4988, 4990, -1, 4990, 5226, 5225, -1, + 4990, 5227, 5226, -1, 5227, 4990, 4991, -1, + 4991, 5228, 5227, -1, 5228, 4991, 5182, -1, + 5182, 5229, 5228, -1, 5229, 5182, 5183, -1, + 5183, 5230, 5229, -1, 5230, 5183, 5184, -1, + 5184, 5231, 5230, -1, 5231, 5184, 5185, -1, + 5185, 5232, 5231, -1, 5232, 5185, 5186, -1, + 5186, 5233, 5232, -1, 5233, 5186, 5187, -1, + 5187, 5234, 5233, -1, 5234, 5187, 5188, -1, + 5188, 5235, 5234, -1, 5235, 5188, 5189, -1, + 5189, 5236, 5235, -1, 5236, 5189, 5190, -1, + 5190, 5237, 5236, -1, 5237, 5190, 5191, -1, + 5191, 5238, 5237, -1, 5191, 5239, 5238, -1, + 5239, 5191, 5192, -1, 5192, 5240, 5239, -1, + 5240, 5192, 5193, -1, 5193, 5241, 5240, -1, + 5241, 5193, 5194, -1, 5194, 5242, 5241, -1, + 5242, 5194, 5195, -1, 5195, 5243, 5242, -1, + 5243, 5195, 5196, -1, 5196, 5244, 5243, -1, + 5244, 5196, 5197, -1, 5197, 5245, 5244, -1, + 5245, 5197, 5198, -1, 5198, 5246, 5245, -1, + 5246, 5198, 5199, -1, 5199, 5247, 5246, -1, + 5247, 5199, 5200, -1, 5200, 5248, 5247, -1, + 5248, 5200, 5201, -1, 5201, 5249, 5248, -1, + 5249, 5201, 5250, -1, 5250, 5251, 5249, -1, + 5250, 5252, 5251, -1, 5252, 5250, 5253, -1, + 5253, 5254, 5252, -1, 5254, 5253, 5255, -1, + 5255, 5256, 5254, -1, 5256, 5255, 5257, -1, + 5257, 5258, 5256, -1, 5258, 5257, 5259, -1, + 5259, 5260, 5258, -1, 5260, 5259, 5261, -1, + 5261, 5262, 5260, -1, 5262, 5261, 5263, -1, + 5263, 5264, 5262, -1, 5264, 5263, 5265, -1, + 5265, 5266, 5264, -1, 5266, 5265, 5267, -1, + 5267, 5268, 5266, -1, 5268, 5267, 5269, -1, + 5269, 4970, 5268, -1, 4970, 5269, 5270, -1, + 5270, 4972, 4970, -1, 5271, 4972, 5270, -1, + 5271, 4971, 4972, -1, 5272, 5273, 5274, -1, + 5273, 5272, 4971, -1, 5273, 4971, 5271, -1, + 5271, 5270, 5273, -1, 5270, 5274, 5273, -1, + 5270, 5275, 5274, -1, 5275, 5270, 5269, -1, + 5269, 5276, 5275, -1, 5276, 5269, 5267, -1, + 5267, 5277, 5276, -1, 5277, 5267, 5265, -1, + 5265, 5278, 5277, -1, 5278, 5265, 5263, -1, + 5263, 5279, 5278, -1, 5279, 5263, 5261, -1, + 5261, 5280, 5279, -1, 5280, 5261, 5259, -1, + 5259, 5281, 5280, -1, 5281, 5259, 5257, -1, + 5257, 5282, 5281, -1, 5282, 5257, 5255, -1, + 5255, 5283, 5282, -1, 5283, 5255, 5253, -1, + 5253, 5284, 5283, -1, 5284, 5253, 5250, -1, + 5284, 5250, 5201, -1, 5284, 5201, 5202, -1, + 5202, 5283, 5284, -1, 5283, 5202, 5203, -1, + 5203, 5282, 5283, -1, 5282, 5203, 5204, -1, + 5204, 5281, 5282, -1, 5281, 5204, 5205, -1, + 5205, 5280, 5281, -1, 5280, 5205, 5206, -1, + 5206, 5279, 5280, -1, 5279, 5206, 5207, -1, + 5207, 5278, 5279, -1, 5278, 5207, 5208, -1, + 5208, 5277, 5278, -1, 5277, 5208, 5209, -1, + 5209, 5276, 5277, -1, 5276, 5209, 5210, -1, + 5210, 5275, 5276, -1, 5275, 5210, 5211, -1, + 5211, 5274, 5275, -1, 5211, 5212, 5274, -1, + 5212, 5285, 5274, -1, 5286, 5274, 5285, -1, + 5286, 5272, 5274, -1, 5286, 4971, 5272, -1, + 5286, 5285, 4971, -1, 5287, 4971, 5285, -1, + 5288, 5287, 5285, -1, 5285, 5212, 5288, -1, + 5288, 5212, 5214, -1, 5214, 5287, 5288, -1, + 5214, 5289, 5287, -1, 5289, 5214, 5213, -1, + 5289, 5213, 5216, -1, 5216, 5287, 5289, -1, + 5216, 5215, 5287, -1, 5290, 5287, 5215, -1, + 5291, 5292, 5293, -1, 5293, 5294, 5291, -1, + 5294, 5293, 5295, -1, 5295, 5296, 5294, -1, + 5296, 5295, 5297, -1, 5297, 5298, 5296, -1, + 5298, 5297, 5299, -1, 5299, 5300, 5298, -1, + 5300, 5299, 5301, -1, 5301, 5302, 5300, -1, + 5302, 5301, 5303, -1, 5303, 5304, 5302, -1, + 5304, 5303, 5305, -1, 5305, 5306, 5304, -1, + 5307, 5308, 5309, -1, 5308, 5307, 5306, -1, + 5306, 5305, 5308, -1, 5310, 5308, 5311, -1, + 5308, 4896, 5311, -1, 4896, 5308, 5305, -1, + 5305, 5312, 4896, -1, 5312, 5305, 5303, -1, + 5303, 5313, 5312, -1, 5313, 5303, 5301, -1, + 5301, 5314, 5313, -1, 5314, 5301, 5299, -1, + 5299, 5315, 5314, -1, 5315, 5299, 5297, -1, + 5297, 5316, 5315, -1, 5316, 5297, 5295, -1, + 5295, 5317, 5316, -1, 5317, 5295, 5293, -1, + 5293, 5318, 5317, -1, 5318, 5293, 5292, -1, + 5292, 5319, 5318, -1, 5292, 5320, 5319, -1, + 5292, 5291, 5320, -1, 5321, 5322, 5323, -1, + 5323, 5324, 5325, -1, 5325, 5326, 5323, -1, + 5326, 5325, 5327, -1, 5327, 5328, 5326, -1, + 5328, 5327, 5329, -1, 5329, 5330, 5328, -1, + 5330, 5329, 5331, -1, 5331, 5332, 5330, -1, + 5332, 5331, 5333, -1, 5333, 5334, 5332, -1, + 5334, 5333, 5335, -1, 5335, 5336, 5334, -1, + 5336, 5335, 5337, -1, 5337, 5338, 5336, -1, + 5338, 5337, 5339, -1, 5339, 5340, 5338, -1, + 5340, 5339, 5341, -1, 5341, 5342, 5340, -1, + 5342, 5341, 5343, -1, 5343, 5344, 5342, -1, + 5344, 5343, 5345, -1, 5344, 5345, 5346, -1, + 5344, 5346, 5347, -1, 5347, 5342, 5344, -1, + 5342, 5347, 5348, -1, 5348, 5340, 5342, -1, + 5340, 5348, 5349, -1, 5349, 5338, 5340, -1, + 5338, 5349, 5350, -1, 5350, 5336, 5338, -1, + 5336, 5350, 5351, -1, 5351, 5334, 5336, -1, + 5334, 5351, 5352, -1, 5352, 5332, 5334, -1, + 5332, 5352, 5353, -1, 5353, 5330, 5332, -1, + 5330, 5353, 5354, -1, 5354, 5328, 5330, -1, + 5328, 5354, 5355, -1, 5355, 5326, 5328, -1, + 5326, 5355, 5356, -1, 5356, 5323, 5326, -1, + 5356, 5321, 5323, -1, 5356, 5357, 5321, -1, + 5357, 5356, 5355, -1, 5355, 5358, 5357, -1, + 5358, 5355, 5354, -1, 5354, 5359, 5358, -1, + 5359, 5354, 5353, -1, 5353, 5360, 5359, -1, + 5360, 5353, 5352, -1, 5352, 5361, 5360, -1, + 5361, 5352, 5351, -1, 5351, 5362, 5361, -1, + 5362, 5351, 5350, -1, 5350, 5363, 5362, -1, + 5363, 5350, 5349, -1, 5349, 5364, 5363, -1, + 5364, 5349, 5348, -1, 5348, 5365, 5364, -1, + 5365, 5348, 5347, -1, 5347, 5366, 5365, -1, + 5366, 5347, 5346, -1, 5366, 5346, 5367, -1, + 5367, 5368, 5366, -1, 5368, 5367, 5369, -1, + 5369, 5370, 5368, -1, 5370, 5369, 5371, -1, + 5371, 5372, 5370, -1, 5372, 5371, 5373, -1, + 5373, 5374, 5372, -1, 5374, 5373, 5375, -1, + 5375, 5376, 5374, -1, 5376, 5375, 5377, -1, + 5377, 5378, 5376, -1, 5378, 5377, 5379, -1, + 5379, 5380, 5378, -1, 5380, 5379, 5381, -1, + 5381, 5382, 5380, -1, 5382, 5381, 5383, -1, + 5383, 5384, 5382, -1, 5384, 5383, 5385, -1, + 5385, 5386, 5384, -1, 5386, 5385, 5387, -1, + 5387, 5388, 5386, -1, 5388, 5387, 5389, -1, + 5389, 5390, 5388, -1, 5390, 5389, 5391, -1, + 5391, 5392, 5390, -1, 5392, 5391, 5393, -1, + 5392, 5393, 5394, -1, 5394, 5395, 5392, -1, + 5395, 5394, 5396, -1, 5396, 5397, 5395, -1, + 5397, 5396, 5398, -1, 5398, 5399, 5397, -1, + 5399, 5398, 5400, -1, 5400, 5401, 5399, -1, + 5401, 5400, 5402, -1, 5402, 5403, 5401, -1, + 5403, 5402, 5404, -1, 5404, 5405, 5403, -1, + 5405, 5404, 5406, -1, 5406, 5407, 5405, -1, + 5407, 5406, 5408, -1, 5408, 5409, 5407, -1, + 5409, 5408, 5410, -1, 5410, 5411, 5409, -1, + 5411, 5410, 5412, -1, 5412, 5413, 5411, -1, + 5413, 5412, 5414, -1, 5414, 5415, 5413, -1, + 5415, 5414, 5416, -1, 5416, 5417, 5415, -1, + 5417, 5416, 5418, -1, 5418, 5419, 5417, -1, + 5419, 5418, 5320, -1, 5419, 5320, 5291, -1, + 5291, 5420, 5419, -1, 5420, 5291, 5294, -1, + 5294, 5421, 5420, -1, 5421, 5294, 5296, -1, + 5296, 5422, 5421, -1, 5422, 5296, 5298, -1, + 5298, 5423, 5422, -1, 5423, 5298, 5300, -1, + 5300, 5424, 5423, -1, 5424, 5300, 5302, -1, + 5302, 5425, 5424, -1, 5425, 5302, 5304, -1, + 5304, 5426, 5425, -1, 5426, 5304, 5306, -1, + 5306, 5427, 5426, -1, 5427, 5306, 5307, -1, + 5307, 5428, 5427, -1, 5428, 5307, 5429, -1, + 5430, 5431, 5290, -1, 5431, 5429, 5290, -1, + 5431, 5428, 5429, -1, 5431, 5430, 5428, -1, + 5430, 5432, 5428, -1, 5430, 5290, 5432, -1, + 5432, 5290, 5215, -1, 5215, 5217, 5432, -1, + 5217, 5428, 5432, -1, 5428, 5217, 5218, -1, + 5218, 5427, 5428, -1, 5427, 5218, 5219, -1, + 5219, 5426, 5427, -1, 5426, 5219, 5220, -1, + 5220, 5425, 5426, -1, 5425, 5220, 5221, -1, + 5221, 5424, 5425, -1, 5424, 5221, 5222, -1, + 5222, 5423, 5424, -1, 5423, 5222, 5223, -1, + 5223, 5422, 5423, -1, 5422, 5223, 5224, -1, + 5224, 5421, 5422, -1, 5421, 5224, 5225, -1, + 5225, 5420, 5421, -1, 5420, 5225, 5226, -1, + 5226, 5419, 5420, -1, 5226, 5417, 5419, -1, + 5417, 5226, 5227, -1, 5227, 5415, 5417, -1, + 5415, 5227, 5228, -1, 5228, 5413, 5415, -1, + 5413, 5228, 5229, -1, 5229, 5411, 5413, -1, + 5411, 5229, 5230, -1, 5230, 5409, 5411, -1, + 5409, 5230, 5231, -1, 5231, 5407, 5409, -1, + 5407, 5231, 5232, -1, 5232, 5405, 5407, -1, + 5405, 5232, 5233, -1, 5233, 5403, 5405, -1, + 5403, 5233, 5234, -1, 5234, 5401, 5403, -1, + 5401, 5234, 5235, -1, 5235, 5399, 5401, -1, + 5399, 5235, 5236, -1, 5236, 5397, 5399, -1, + 5397, 5236, 5237, -1, 5237, 5395, 5397, -1, + 5395, 5237, 5238, -1, 5238, 5392, 5395, -1, + 5238, 5390, 5392, -1, 5390, 5238, 5239, -1, + 5239, 5388, 5390, -1, 5388, 5239, 5240, -1, + 5240, 5386, 5388, -1, 5386, 5240, 5241, -1, + 5241, 5384, 5386, -1, 5384, 5241, 5242, -1, + 5242, 5382, 5384, -1, 5382, 5242, 5243, -1, + 5243, 5380, 5382, -1, 5380, 5243, 5244, -1, + 5244, 5378, 5380, -1, 5378, 5244, 5245, -1, + 5245, 5376, 5378, -1, 5376, 5245, 5246, -1, + 5246, 5374, 5376, -1, 5374, 5246, 5247, -1, + 5247, 5372, 5374, -1, 5372, 5247, 5248, -1, + 5248, 5370, 5372, -1, 5370, 5248, 5249, -1, + 5249, 5368, 5370, -1, 5368, 5249, 5251, -1, + 5251, 5366, 5368, -1, 5251, 5365, 5366, -1, + 5365, 5251, 5252, -1, 5252, 5364, 5365, -1, + 5364, 5252, 5254, -1, 5254, 5363, 5364, -1, + 5363, 5254, 5256, -1, 5256, 5362, 5363, -1, + 5362, 5256, 5258, -1, 5258, 5361, 5362, -1, + 5361, 5258, 5260, -1, 5260, 5360, 5361, -1, + 5360, 5260, 5262, -1, 5262, 5359, 5360, -1, + 5359, 5262, 5264, -1, 5264, 5358, 5359, -1, + 5358, 5264, 5266, -1, 5266, 5357, 5358, -1, + 5357, 5266, 5268, -1, 5268, 5321, 5357, -1, + 5321, 5268, 4970, -1, 4970, 4969, 5321, -1, + 5433, 5321, 4969, -1, 5433, 4969, 4967, -1, + 5433, 4967, 5434, -1, 5434, 5321, 5433, -1, + 5434, 5322, 5321, -1, 5434, 4967, 5322, -1, + 5322, 4967, 4966, -1, 4966, 5323, 5322, -1, + 4966, 5324, 5323, -1, 5324, 4966, 4920, -1, + 5435, 5324, 4920, -1, 5435, 5325, 5324, -1, + 5435, 5436, 5325, -1, 5436, 5435, 4920, -1, + 5436, 4920, 4965, -1, 4965, 5325, 5436, -1, + 5325, 4965, 4927, -1, 4927, 5327, 5325, -1, + 5327, 4927, 4929, -1, 4929, 5329, 5327, -1, + 5329, 4929, 4931, -1, 4931, 5331, 5329, -1, + 5331, 4931, 4933, -1, 4933, 5333, 5331, -1, + 5333, 4933, 4935, -1, 4935, 5335, 5333, -1, + 5335, 4935, 4937, -1, 4937, 5337, 5335, -1, + 5337, 4937, 4939, -1, 4939, 5339, 5337, -1, + 5339, 4939, 4941, -1, 4941, 5341, 5339, -1, + 5341, 4941, 4943, -1, 4943, 5343, 5341, -1, + 5343, 4943, 4945, -1, 4945, 5345, 5343, -1, + 5345, 4945, 4947, -1, 5345, 4947, 5437, -1, + 5437, 5346, 5345, -1, 5346, 5437, 5438, -1, + 5438, 5367, 5346, -1, 5367, 5438, 5439, -1, + 5439, 5369, 5367, -1, 5369, 5439, 5440, -1, + 5440, 5371, 5369, -1, 5371, 5440, 5441, -1, + 5441, 5373, 5371, -1, 5373, 5441, 5442, -1, + 5442, 5375, 5373, -1, 5375, 5442, 5443, -1, + 5443, 5377, 5375, -1, 5377, 5443, 5444, -1, + 5444, 5379, 5377, -1, 5379, 5444, 5445, -1, + 5445, 5381, 5379, -1, 5381, 5445, 5446, -1, + 5446, 5383, 5381, -1, 5383, 5446, 5447, -1, + 5447, 5385, 5383, -1, 5385, 5447, 5448, -1, + 5448, 5387, 5385, -1, 5387, 5448, 5449, -1, + 5449, 5389, 5387, -1, 5389, 5449, 5450, -1, + 5450, 5391, 5389, -1, 5391, 5450, 5451, -1, + 5451, 5393, 5391, -1, 5393, 5451, 5452, -1, + 5393, 5452, 5453, -1, 5453, 5394, 5393, -1, + 5394, 5453, 5454, -1, 5454, 5396, 5394, -1, + 5396, 5454, 5455, -1, 5455, 5398, 5396, -1, + 5398, 5455, 5456, -1, 5456, 5400, 5398, -1, + 5400, 5456, 5457, -1, 5457, 5402, 5400, -1, + 5402, 5457, 5458, -1, 5458, 5404, 5402, -1, + 5404, 5458, 5459, -1, 5459, 5406, 5404, -1, + 5406, 5459, 5460, -1, 5460, 5408, 5406, -1, + 5408, 5460, 5461, -1, 5461, 5410, 5408, -1, + 5410, 5461, 5462, -1, 5462, 5412, 5410, -1, + 5412, 5462, 5463, -1, 5463, 5414, 5412, -1, + 5414, 5463, 5464, -1, 5464, 5416, 5414, -1, + 5416, 5464, 5465, -1, 5465, 5418, 5416, -1, + 5418, 5465, 5466, -1, 5466, 5320, 5418, -1, + 5320, 5466, 5467, -1, 5467, 5319, 5320, -1, + 5319, 5467, 4919, -1, 5319, 4919, 4899, -1, + 4899, 5318, 5319, -1, 5318, 4899, 4902, -1, + 4902, 5317, 5318, -1, 5317, 4902, 4904, -1, + 4904, 5316, 5317, -1, 5316, 4904, 4913, -1, + 4913, 5315, 5316, -1, 5315, 4913, 4911, -1, + 4911, 5314, 5315, -1, 5314, 4911, 4909, -1, + 4909, 5313, 5314, -1, 5313, 4909, 4907, -1, + 4907, 5312, 5313, -1, 5312, 4907, 4906, -1, + 4906, 4896, 5312, -1, 4906, 4897, 4896, -1, + 4906, 4905, 4897, -1, 5468, 4897, 4905, -1, + 4905, 5469, 5468, -1, 5469, 4905, 4908, -1, + 4908, 5470, 5469, -1, 5470, 4908, 4910, -1, + 4910, 5471, 5470, -1, 5471, 4910, 4912, -1, + 4912, 5472, 5471, -1, 5472, 4912, 4914, -1, + 4914, 4915, 5472, -1, 5473, 5472, 4915, -1, + 4915, 5474, 5473, -1, 5474, 4915, 4916, -1, + 4916, 5475, 5474, -1, 5475, 4916, 4917, -1, + 4917, 5476, 5475, -1, 5476, 4917, 4918, -1, + 4918, 5477, 5476, -1, 4918, 5478, 5477, -1, + 5478, 4918, 4919, -1, 4919, 5479, 5478, -1, + 5479, 4919, 5467, -1, 5467, 5480, 5479, -1, + 5480, 5467, 5466, -1, 5466, 5481, 5480, -1, + 5481, 5466, 5465, -1, 5465, 5482, 5481, -1, + 5482, 5465, 5464, -1, 5464, 5483, 5482, -1, + 5483, 5464, 5463, -1, 5463, 5484, 5483, -1, + 5484, 5463, 5462, -1, 5462, 5485, 5484, -1, + 5485, 5462, 5461, -1, 5461, 5486, 5485, -1, + 5486, 5461, 5460, -1, 5460, 5487, 5486, -1, + 5487, 5460, 5459, -1, 5459, 5488, 5487, -1, + 5488, 5459, 5458, -1, 5458, 5489, 5488, -1, + 5489, 5458, 5457, -1, 5457, 5490, 5489, -1, + 5490, 5457, 5456, -1, 5456, 5491, 5490, -1, + 5491, 5456, 5455, -1, 5455, 5492, 5491, -1, + 5492, 5455, 5454, -1, 5454, 5493, 5492, -1, + 5493, 5454, 5453, -1, 5453, 5494, 5493, -1, + 5494, 5453, 5452, -1, 5452, 5495, 5494, -1, + 5452, 5496, 5495, -1, 5496, 5452, 5451, -1, + 5451, 5497, 5496, -1, 5497, 5451, 5450, -1, + 5450, 5498, 5497, -1, 5498, 5450, 5449, -1, + 5449, 5499, 5498, -1, 5499, 5449, 5448, -1, + 5448, 5500, 5499, -1, 5500, 5448, 5447, -1, + 5447, 5501, 5500, -1, 5501, 5447, 5446, -1, + 5446, 5502, 5501, -1, 5502, 5446, 5445, -1, + 5445, 5503, 5502, -1, 5503, 5445, 5444, -1, + 5444, 5504, 5503, -1, 5504, 5444, 5443, -1, + 5443, 5505, 5504, -1, 5505, 5443, 5442, -1, + 5442, 5506, 5505, -1, 5506, 5442, 5441, -1, + 5441, 5507, 5506, -1, 5507, 5441, 5440, -1, + 5440, 5508, 5507, -1, 5508, 5440, 5439, -1, + 5439, 5509, 5508, -1, 5509, 5439, 5438, -1, + 5438, 5510, 5509, -1, 5510, 5438, 5437, -1, + 5437, 5511, 5510, -1, 5511, 5437, 4947, -1, + 4947, 5512, 5511, -1, 5512, 4947, 4948, -1, + 4948, 4867, 5512, -1, 4948, 4895, 4867, -1, + 4895, 4948, 4949, -1, 4949, 4894, 4895, -1, + 4894, 4949, 4950, -1, 4950, 4893, 4894, -1, + 4893, 4950, 4951, -1, 4951, 4892, 4893, -1, + 4892, 4951, 4952, -1, 4952, 4891, 4892, -1, + 4891, 4952, 4953, -1, 4953, 4890, 4891, -1, + 4890, 4953, 4954, -1, 4954, 4889, 4890, -1, + 4889, 4954, 4955, -1, 4955, 4888, 4889, -1, + 4888, 4955, 4956, -1, 4956, 4887, 4888, -1, + 4887, 4956, 4957, -1, 4887, 4957, 4960, -1, + 4960, 4886, 4887, -1, 4960, 4885, 4886, -1, + 4885, 4960, 4959, -1, 4959, 4883, 4885, -1, + 4959, 4958, 4883, -1, 4958, 4961, 4883, -1, + 4883, 4961, 4921, -1, 5290, 5513, 4702, -1, + 5513, 5290, 5429, -1, 5513, 5429, 5307, -1, + 5513, 5307, 5309, -1, 5309, 4702, 5513, -1, + 5514, 4702, 5309, -1, 5514, 5309, 5308, -1, + 5514, 5308, 5310, -1, 5310, 4702, 5514, -1, + 5310, 5311, 4702, -1, 5311, 4703, 4702, -1, + 4703, 5311, 4896, -1, 4703, 4896, 4898, -1, + 4898, 4701, 4703, -1, 5515, 4701, 4898, -1, + 5515, 4898, 4897, -1, 5515, 4897, 5516, -1, + 5516, 4701, 5515, -1, 5516, 5517, 4701, -1, + 5516, 4897, 5517, -1, 4897, 5468, 5517, -1, + 5518, 5517, 5468, -1, 5518, 4701, 5517, -1, + 5518, 4700, 4701, -1, 5518, 5468, 4700, -1, + 5468, 4697, 4700, -1, 4697, 5468, 5469, -1, + 5469, 4696, 4697, -1, 4696, 5469, 5470, -1, + 5470, 4695, 4696, -1, 4695, 5470, 5471, -1, + 5471, 4694, 4695, -1, 4694, 5471, 5472, -1, + 5472, 5473, 4694, -1, 5473, 4693, 4694, -1, + 5473, 5519, 4693, -1, 5519, 5473, 5474, -1, + 5474, 5520, 5519, -1, 5520, 5474, 5475, -1, + 5475, 5521, 5520, -1, 5521, 5475, 5476, -1, + 5476, 5522, 5521, -1, 5522, 5476, 5477, -1, + 5522, 5477, 5523, -1, 5522, 5523, 5524, -1, + 5524, 5521, 5522, -1, 5521, 5524, 5525, -1, + 5525, 5520, 5521, -1, 5520, 5525, 5526, -1, + 5526, 5519, 5520, -1, 5519, 5526, 5527, -1, + 5527, 4693, 5519, -1, 4693, 5527, 5528, -1, + 5528, 4691, 4693, -1, 4691, 5528, 5529, -1, + 5529, 4689, 4691, -1, 5529, 4688, 4689, -1, + 4688, 5529, 5530, -1, 5530, 4674, 4688, -1, + 4674, 5530, 4670, -1, 4674, 4670, 5531, -1, + 5531, 4671, 4674, -1, 5531, 4672, 4671, -1, + 5531, 5532, 4672, -1, 5532, 5531, 4670, -1, + 5532, 4670, 4669, -1, 4669, 4672, 5532, -1, + 4672, 4669, 4667, -1, 5533, 4667, 5534, -1, + 4667, 5533, 4664, -1, 5535, 4643, 4640, -1, + 5536, 5535, 4640, -1, 5536, 4640, 4639, -1, + 5536, 4639, 5537, -1, 5537, 5535, 5536, -1, + 5537, 5538, 5535, -1, 5537, 5539, 5538, -1, + 5539, 5537, 4639, -1, 4639, 5540, 5539, -1, + 5540, 4639, 4636, -1, 4636, 5541, 5540, -1, + 5541, 4636, 4638, -1, 4638, 5542, 5541, -1, + 5542, 4638, 5543, -1, 5543, 5544, 5542, -1, + 5544, 5543, 5545, -1, 5545, 5546, 5544, -1, + 5546, 5545, 5547, -1, 5547, 5548, 5546, -1, + 5548, 5547, 5549, -1, 5549, 5550, 5548, -1, + 5551, 5552, 5553, -1, 5551, 5553, 5550, -1, + 5550, 5549, 5551, -1, 5551, 5554, 5555, -1, + 5554, 5551, 5549, -1, 5554, 5549, 5556, -1, + 5556, 5557, 5554, -1, 5556, 5558, 5557, -1, + 5558, 5556, 5559, -1, 5559, 5560, 5558, -1, + 5560, 5559, 5561, -1, 5561, 5562, 5560, -1, + 5562, 5561, 5563, -1, 5563, 5564, 5562, -1, + 5564, 5565, 5566, -1, 5564, 5563, 5565, -1, + 5567, 5568, 5565, -1, 5565, 5569, 5567, -1, + 5569, 5565, 5563, -1, 5563, 5570, 5569, -1, + 5570, 5563, 5561, -1, 5561, 5571, 5570, -1, + 5571, 5561, 5559, -1, 5559, 5572, 5571, -1, + 5572, 5559, 5556, -1, 5572, 5556, 5549, -1, + 5572, 5549, 5547, -1, 5547, 5571, 5572, -1, + 5571, 5547, 5545, -1, 5545, 5570, 5571, -1, + 5570, 5545, 5543, -1, 5543, 5569, 5570, -1, + 5569, 5543, 4638, -1, 4638, 5567, 5569, -1, + 5567, 4638, 4637, -1, 4637, 5573, 5567, -1, + 5573, 4637, 4642, -1, 5573, 4642, 4643, -1, + 5573, 4643, 5574, -1, 5574, 5567, 5573, -1, + 5574, 5568, 5567, -1, 5568, 5574, 4643, -1, + 4643, 4650, 5568, -1, 5575, 5576, 4650, -1, + 5576, 5568, 4650, -1, 5576, 5565, 5568, -1, + 5576, 5575, 5565, -1, 5575, 5566, 5565, -1, + 5566, 5575, 4650, -1, 5566, 4650, 4649, -1, + 4649, 5564, 5566, -1, 4649, 4646, 5564, -1, + 5564, 4646, 4645, -1, 4645, 5562, 5564, -1, + 5562, 4645, 5577, -1, 5577, 5560, 5562, -1, + 5560, 5577, 5578, -1, 5578, 5558, 5560, -1, + 5558, 5578, 5579, -1, 5579, 5557, 5558, -1, + 5579, 5580, 5557, -1, 5579, 5581, 5580, -1, + 5581, 5579, 5578, -1, 5578, 5582, 5581, -1, + 5582, 5578, 5577, -1, 5577, 5583, 5582, -1, + 5583, 5577, 4645, -1, 4645, 4647, 5583, -1, + 5584, 5583, 4647, -1, 5584, 4647, 4648, -1, + 5584, 4648, 4652, -1, 4652, 5583, 5584, -1, + 4652, 4651, 5583, -1, 5583, 4651, 4654, -1, + 4654, 5582, 5583, -1, 5582, 4654, 5585, -1, + 5585, 5581, 5582, -1, 5581, 5585, 5586, -1, + 5586, 5580, 5581, -1, 5580, 5586, 5587, -1, + 5580, 5587, 5588, -1, 5588, 5557, 5580, -1, + 5557, 5588, 5589, -1, 5589, 5554, 5557, -1, + 5589, 5555, 5554, -1, 5589, 5590, 5555, -1, + 5590, 5589, 5588, -1, 5588, 5591, 5590, -1, + 5591, 5588, 5587, -1, 5587, 5592, 5591, -1, + 5587, 5593, 5592, -1, 5593, 5587, 5586, -1, + 5586, 5594, 5593, -1, 5594, 5586, 5585, -1, + 5585, 5595, 5594, -1, 5595, 5585, 4654, -1, + 4654, 4655, 5595, -1, 4658, 4657, 5595, -1, + 5595, 4657, 4660, -1, 4660, 5594, 5595, -1, + 5594, 4660, 5596, -1, 5596, 5593, 5594, -1, + 5593, 5596, 5597, -1, 5597, 5592, 5593, -1, + 5592, 5597, 5598, -1, 5592, 5598, 5599, -1, + 5599, 5591, 5592, -1, 5591, 5599, 5600, -1, + 5600, 5590, 5591, -1, 5590, 5600, 5601, -1, + 5601, 5555, 5590, -1, 5601, 4603, 5555, -1, + 5601, 4635, 4603, -1, 4635, 5601, 5600, -1, + 5600, 4634, 4635, -1, 4634, 5600, 5599, -1, + 5599, 4633, 4634, -1, 4633, 5599, 5598, -1, + 5598, 4629, 4633, -1, 5598, 4627, 4629, -1, + 4627, 5598, 5597, -1, 5597, 4626, 4627, -1, + 4626, 5597, 5596, -1, 5596, 4624, 4626, -1, + 4624, 5596, 4660, -1, 4660, 4661, 4624, -1, + 5602, 4624, 4661, -1, 5602, 4661, 4662, -1, + 5602, 4662, 5603, -1, 5603, 4624, 5602, -1, + 5603, 4625, 4624, -1, 5603, 4662, 4625, -1, + 4625, 4662, 4663, -1, 4663, 4621, 4625, -1, + 4663, 4665, 4621, -1, 4665, 4622, 4621, -1, + 4622, 4665, 4664, -1, 4622, 4664, 5604, -1, + 5604, 4620, 4622, -1, 5604, 4632, 4620, -1, + 5604, 4664, 4632, -1, 4632, 4664, 5533, -1, + 5533, 4618, 4632, -1, 5533, 5534, 4618, -1, + 5534, 4619, 4618, -1, 4619, 5534, 4667, -1, + 4619, 4667, 4666, -1, 4666, 4617, 4619, -1, + 4666, 4668, 4617, -1, 4617, 4668, 4670, -1, + 4670, 4615, 4617, -1, 4615, 4670, 5530, -1, + 5530, 4614, 4615, -1, 4614, 5530, 5529, -1, + 4614, 5529, 5528, -1, 5528, 4612, 4614, -1, + 4612, 5528, 5527, -1, 5527, 4610, 4612, -1, + 4610, 5527, 5526, -1, 5526, 4608, 4610, -1, + 4608, 5526, 5525, -1, 5525, 4606, 4608, -1, + 4606, 5525, 5524, -1, 5524, 4604, 4606, -1, + 4604, 5524, 5523, -1, 5523, 4602, 4604, -1, + 5523, 5605, 4602, -1, 5605, 5523, 5477, -1, + 5477, 5606, 5605, -1, 5606, 5477, 5478, -1, + 5478, 5607, 5606, -1, 5607, 5478, 5479, -1, + 5479, 5608, 5607, -1, 5608, 5479, 5480, -1, + 5480, 5609, 5608, -1, 5609, 5480, 5481, -1, + 5481, 5610, 5609, -1, 5610, 5481, 5482, -1, + 5482, 5611, 5610, -1, 5611, 5482, 5483, -1, + 5483, 5612, 5611, -1, 5612, 5483, 5484, -1, + 5484, 5613, 5612, -1, 5613, 5484, 5485, -1, + 5485, 5614, 5613, -1, 5614, 5485, 5486, -1, + 5486, 5615, 5614, -1, 5615, 5486, 5487, -1, + 5487, 5616, 5615, -1, 5616, 5487, 5488, -1, + 5488, 5617, 5616, -1, 5617, 5488, 5489, -1, + 5489, 5618, 5617, -1, 5618, 5489, 5490, -1, + 5490, 5619, 5618, -1, 5619, 5490, 5491, -1, + 5491, 5620, 5619, -1, 5620, 5491, 5492, -1, + 5492, 5621, 5620, -1, 5621, 5492, 5493, -1, + 5493, 5622, 5621, -1, 5622, 5493, 5494, -1, + 5494, 5623, 5622, -1, 5623, 5494, 5495, -1, + 5495, 5624, 5623, -1, 5495, 5625, 5624, -1, + 5625, 5495, 5496, -1, 5496, 5626, 5625, -1, + 5626, 5496, 5497, -1, 5497, 5627, 5626, -1, + 5627, 5497, 5498, -1, 5498, 5628, 5627, -1, + 5628, 5498, 5499, -1, 5499, 5629, 5628, -1, + 5629, 5499, 5500, -1, 5500, 5630, 5629, -1, + 5630, 5500, 5501, -1, 5501, 5631, 5630, -1, + 5631, 5501, 5502, -1, 5502, 5632, 5631, -1, + 5632, 5502, 5503, -1, 5503, 5633, 5632, -1, + 5633, 5503, 5504, -1, 5504, 5634, 5633, -1, + 5634, 5504, 5505, -1, 5505, 5635, 5634, -1, + 5635, 5505, 5506, -1, 5506, 5636, 5635, -1, + 5636, 5506, 5507, -1, 5507, 5637, 5636, -1, + 5637, 5507, 5508, -1, 5508, 5638, 5637, -1, + 5638, 5508, 5509, -1, 5509, 5639, 5638, -1, + 5639, 5509, 5510, -1, 5510, 5640, 5639, -1, + 5640, 5510, 5511, -1, 5511, 5641, 5640, -1, + 5641, 5511, 5512, -1, 5512, 5642, 5641, -1, + 5642, 5512, 4867, -1, 4867, 5643, 5642, -1, + 5643, 4867, 4865, -1, 4865, 5644, 5643, -1, + 4865, 4864, 5644, -1, 5645, 5646, 5647, -1, + 5646, 5645, 5648, -1, 5648, 5649, 5646, -1, + 5649, 5648, 5650, -1, 5650, 5651, 5649, -1, + 5650, 5652, 5651, -1, 5652, 5650, 5653, -1, + 5653, 5654, 5652, -1, 5654, 5653, 5655, -1, + 5655, 5656, 5654, -1, 5656, 5655, 5657, -1, + 5657, 5658, 5656, -1, 5658, 5657, 5659, -1, + 5659, 5660, 5658, -1, 5660, 5659, 5661, -1, + 5661, 5662, 5660, -1, 5662, 5661, 5663, -1, + 5662, 5663, 5644, -1, 5662, 5644, 4864, -1, + 4864, 5660, 5662, -1, 5660, 4864, 4862, -1, + 4862, 5658, 5660, -1, 5658, 4862, 4860, -1, + 4860, 5656, 5658, -1, 5656, 4860, 4858, -1, + 4858, 5654, 5656, -1, 5654, 4858, 4856, -1, + 4856, 5652, 5654, -1, 5652, 4856, 4854, -1, + 4854, 5651, 5652, -1, 5651, 4854, 4852, -1, + 5651, 4852, 4851, -1, 4851, 5649, 5651, -1, + 5649, 4851, 4705, -1, 4705, 5646, 5649, -1, + 4705, 5664, 5646, -1, 5664, 4705, 4707, -1, + 5664, 4707, 4708, -1, 5664, 4708, 4837, -1, + 4837, 5646, 5664, -1, 4837, 5647, 5646, -1, + 5647, 4837, 4711, -1, 5647, 4711, 4710, -1, + 4710, 5645, 5647, -1, 4710, 4709, 5645, -1, + 5645, 4709, 4713, -1, 5645, 4713, 4742, -1, + 4742, 5648, 5645, -1, 5648, 4742, 4744, -1, + 4744, 5650, 5648, -1, 4744, 5653, 5650, -1, + 5653, 4744, 4745, -1, 4745, 5655, 5653, -1, + 5655, 4745, 4828, -1, 4828, 5657, 5655, -1, + 5657, 4828, 4829, -1, 4829, 5659, 5657, -1, + 5659, 4829, 4830, -1, 4830, 5661, 5659, -1, + 5661, 4830, 4831, -1, 4831, 5663, 5661, -1, + 5663, 4831, 4832, -1, 5663, 4832, 5665, -1, + 5665, 5644, 5663, -1, 5644, 5665, 5666, -1, + 5666, 5643, 5644, -1, 5643, 5666, 5667, -1, + 5667, 5642, 5643, -1, 5642, 5667, 5668, -1, + 5668, 5641, 5642, -1, 5641, 5668, 5669, -1, + 5669, 5640, 5641, -1, 5640, 5669, 5670, -1, + 5670, 5639, 5640, -1, 5639, 5670, 5671, -1, + 5671, 5638, 5639, -1, 5638, 5671, 5672, -1, + 5672, 5637, 5638, -1, 5637, 5672, 5673, -1, + 5673, 5636, 5637, -1, 5636, 5673, 5674, -1, + 5674, 5635, 5636, -1, 5635, 5674, 5675, -1, + 5675, 5634, 5635, -1, 5634, 5675, 5676, -1, + 5676, 5633, 5634, -1, 5633, 5676, 5677, -1, + 5677, 5632, 5633, -1, 5632, 5677, 5678, -1, + 5678, 5631, 5632, -1, 5631, 5678, 5679, -1, + 5679, 5630, 5631, -1, 5630, 5679, 5680, -1, + 5680, 5629, 5630, -1, 5629, 5680, 5681, -1, + 5681, 5628, 5629, -1, 5628, 5681, 5682, -1, + 5682, 5627, 5628, -1, 5627, 5682, 5683, -1, + 5683, 5626, 5627, -1, 5626, 5683, 5684, -1, + 5684, 5625, 5626, -1, 5625, 5684, 5685, -1, + 5685, 5624, 5625, -1, 5624, 5685, 5686, -1, + 5624, 5686, 5687, -1, 5687, 5623, 5624, -1, + 5623, 5687, 5688, -1, 5688, 5622, 5623, -1, + 5622, 5688, 5689, -1, 5689, 5621, 5622, -1, + 5621, 5689, 5690, -1, 5690, 5620, 5621, -1, + 5620, 5690, 5691, -1, 5691, 5619, 5620, -1, + 5619, 5691, 5692, -1, 5692, 5618, 5619, -1, + 5618, 5692, 5693, -1, 5693, 5617, 5618, -1, + 5617, 5693, 5694, -1, 5694, 5616, 5617, -1, + 5616, 5694, 5695, -1, 5695, 5615, 5616, -1, + 5615, 5695, 5696, -1, 5696, 5614, 5615, -1, + 5614, 5696, 5697, -1, 5697, 5613, 5614, -1, + 5613, 5697, 5698, -1, 5698, 5612, 5613, -1, + 5612, 5698, 5699, -1, 5699, 5611, 5612, -1, + 5611, 5699, 5700, -1, 5700, 5610, 5611, -1, + 5610, 5700, 5701, -1, 5701, 5609, 5610, -1, + 5609, 5701, 5702, -1, 5702, 5608, 5609, -1, + 5608, 5702, 5703, -1, 5703, 5607, 5608, -1, + 5607, 5703, 5704, -1, 5704, 5606, 5607, -1, + 5606, 5704, 5705, -1, 5705, 5605, 5606, -1, + 5605, 5705, 5706, -1, 5706, 4602, 5605, -1, + 4602, 5706, 5707, -1, 5707, 4603, 4602, -1, + 4603, 5707, 5708, -1, 5708, 5555, 4603, -1, + 5708, 5551, 5555, -1, 5708, 5552, 5551, -1, + 5552, 5708, 5707, -1, 5707, 5709, 5552, -1, + 5709, 5707, 5706, -1, 5706, 5710, 5709, -1, + 5710, 5706, 5705, -1, 5705, 5711, 5710, -1, + 5711, 5705, 5704, -1, 5704, 5712, 5711, -1, + 5712, 5704, 5703, -1, 5703, 5713, 5712, -1, + 5713, 5703, 5702, -1, 5702, 5714, 5713, -1, + 5714, 5702, 5701, -1, 5701, 5715, 5714, -1, + 5715, 5701, 5700, -1, 5700, 5716, 5715, -1, + 5716, 5700, 5699, -1, 5699, 5717, 5716, -1, + 5717, 5699, 5698, -1, 5698, 5718, 5717, -1, + 5718, 5698, 5697, -1, 5697, 5719, 5718, -1, + 5719, 5697, 5696, -1, 5696, 5720, 5719, -1, + 5720, 5696, 5695, -1, 5695, 5721, 5720, -1, + 5721, 5695, 5694, -1, 5694, 5722, 5721, -1, + 5722, 5694, 5693, -1, 5693, 5723, 5722, -1, + 5723, 5693, 5692, -1, 5692, 5724, 5723, -1, + 5724, 5692, 5691, -1, 5691, 5725, 5724, -1, + 5725, 5691, 5690, -1, 5690, 5726, 5725, -1, + 5726, 5690, 5689, -1, 5689, 5727, 5726, -1, + 5727, 5689, 5688, -1, 5688, 5728, 5727, -1, + 5728, 5688, 5687, -1, 5687, 5729, 5728, -1, + 5729, 5687, 5686, -1, 5686, 5730, 5729, -1, + 5686, 5731, 5730, -1, 5731, 5686, 5685, -1, + 5685, 5732, 5731, -1, 5732, 5685, 5684, -1, + 5684, 5733, 5732, -1, 5733, 5684, 5683, -1, + 5683, 5734, 5733, -1, 5734, 5683, 5682, -1, + 5682, 5735, 5734, -1, 5735, 5682, 5681, -1, + 5681, 5736, 5735, -1, 5736, 5681, 5680, -1, + 5680, 5737, 5736, -1, 5737, 5680, 5679, -1, + 5679, 5738, 5737, -1, 5738, 5679, 5678, -1, + 5678, 5739, 5738, -1, 5739, 5678, 5677, -1, + 5677, 5740, 5739, -1, 5740, 5677, 5676, -1, + 5676, 5741, 5740, -1, 5741, 5676, 5675, -1, + 5675, 5742, 5741, -1, 5742, 5675, 5674, -1, + 5674, 5743, 5742, -1, 5743, 5674, 5673, -1, + 5673, 5744, 5743, -1, 5744, 5673, 5672, -1, + 5672, 5745, 5744, -1, 5745, 5672, 5671, -1, + 5671, 5746, 5745, -1, 5746, 5671, 5670, -1, + 5670, 5747, 5746, -1, 5747, 5670, 5669, -1, + 5669, 5748, 5747, -1, 5748, 5669, 5668, -1, + 5668, 5749, 5748, -1, 5749, 5668, 5667, -1, + 5667, 5750, 5749, -1, 5750, 5667, 5666, -1, + 5666, 5751, 5750, -1, 5751, 5666, 5665, -1, + 5665, 5752, 5751, -1, 5752, 5665, 4832, -1, + 4832, 4714, 5752, -1, 4714, 4716, 5752, -1, + 5753, 5752, 4716, -1, 5753, 5751, 5752, -1, + 5751, 5753, 5754, -1, 5754, 5750, 5751, -1, + 5750, 5754, 5755, -1, 5755, 5749, 5750, -1, + 5749, 5755, 5756, -1, 5756, 5748, 5749, -1, + 5748, 5756, 5757, -1, 5757, 5747, 5748, -1, + 5747, 5757, 5758, -1, 5758, 5746, 5747, -1, + 5746, 5758, 5759, -1, 5759, 5745, 5746, -1, + 5745, 5759, 5760, -1, 5760, 5744, 5745, -1, + 5744, 5760, 5761, -1, 5761, 5743, 5744, -1, + 5743, 5761, 5762, -1, 5762, 5742, 5743, -1, + 5742, 5762, 5763, -1, 5763, 5741, 5742, -1, + 5741, 5763, 5764, -1, 5764, 5740, 5741, -1, + 5740, 5764, 5765, -1, 5765, 5739, 5740, -1, + 5739, 5765, 5766, -1, 5766, 5738, 5739, -1, + 5738, 5766, 5767, -1, 5767, 5737, 5738, -1, + 5737, 5767, 5768, -1, 5768, 5736, 5737, -1, + 5736, 5768, 5769, -1, 5769, 5735, 5736, -1, + 5735, 5769, 5770, -1, 5770, 5734, 5735, -1, + 5734, 5770, 5771, -1, 5771, 5733, 5734, -1, + 5733, 5771, 5772, -1, 5772, 5732, 5733, -1, + 5732, 5772, 5773, -1, 5773, 5731, 5732, -1, + 5731, 5773, 5774, -1, 5774, 5730, 5731, -1, + 5730, 5774, 5775, -1, 5730, 5775, 5776, -1, + 5776, 5729, 5730, -1, 5729, 5776, 5777, -1, + 5777, 5728, 5729, -1, 5728, 5777, 5778, -1, + 5778, 5727, 5728, -1, 5727, 5778, 5779, -1, + 5779, 5726, 5727, -1, 5726, 5779, 5780, -1, + 5780, 5725, 5726, -1, 5725, 5780, 5781, -1, + 5781, 5724, 5725, -1, 5724, 5781, 5782, -1, + 5782, 5723, 5724, -1, 5723, 5782, 5783, -1, + 5783, 5722, 5723, -1, 5722, 5783, 5784, -1, + 5784, 5721, 5722, -1, 5721, 5784, 5785, -1, + 5785, 5720, 5721, -1, 5720, 5785, 5786, -1, + 5786, 5719, 5720, -1, 5719, 5786, 5787, -1, + 5787, 5718, 5719, -1, 5718, 5787, 5788, -1, + 5788, 5717, 5718, -1, 5717, 5788, 5789, -1, + 5789, 5716, 5717, -1, 5716, 5789, 5790, -1, + 5790, 5715, 5716, -1, 5715, 5790, 5791, -1, + 5791, 5714, 5715, -1, 5714, 5791, 5792, -1, + 5792, 5713, 5714, -1, 5713, 5792, 5793, -1, + 5793, 5712, 5713, -1, 5712, 5793, 5794, -1, + 5794, 5711, 5712, -1, 5711, 5794, 5795, -1, + 5795, 5710, 5711, -1, 5710, 5795, 5796, -1, + 5796, 5709, 5710, -1, 5709, 5796, 5797, -1, + 5797, 5552, 5709, -1, 5797, 5553, 5552, -1, + 5797, 5798, 5553, -1, 5798, 5797, 5796, -1, + 5796, 5799, 5798, -1, 5799, 5796, 5795, -1, + 5795, 5800, 5799, -1, 5800, 5795, 5794, -1, + 5794, 5801, 5800, -1, 5801, 5794, 5793, -1, + 5793, 5802, 5801, -1, 5802, 5793, 5792, -1, + 5792, 5803, 5802, -1, 5803, 5792, 5791, -1, + 5791, 5804, 5803, -1, 5804, 5791, 5790, -1, + 5790, 5805, 5804, -1, 5805, 5790, 5789, -1, + 5789, 5806, 5805, -1, 5806, 5789, 5788, -1, + 5788, 5807, 5806, -1, 5807, 5788, 5787, -1, + 5787, 5808, 5807, -1, 5808, 5787, 5786, -1, + 5786, 5809, 5808, -1, 5809, 5786, 5785, -1, + 5785, 5810, 5809, -1, 5810, 5785, 5784, -1, + 5784, 5811, 5810, -1, 5811, 5784, 5783, -1, + 5783, 5812, 5811, -1, 5812, 5783, 5782, -1, + 5782, 5813, 5812, -1, 5813, 5782, 5781, -1, + 5781, 5814, 5813, -1, 5814, 5781, 5780, -1, + 5780, 5815, 5814, -1, 5815, 5780, 5779, -1, + 5779, 5816, 5815, -1, 5816, 5779, 5778, -1, + 5778, 5817, 5816, -1, 5817, 5778, 5777, -1, + 5777, 5818, 5817, -1, 5818, 5777, 5776, -1, + 5776, 5819, 5818, -1, 5819, 5776, 5775, -1, + 5775, 5820, 5819, -1, 5775, 5821, 5820, -1, + 5821, 5775, 5774, -1, 5774, 5822, 5821, -1, + 5822, 5774, 5773, -1, 5773, 5823, 5822, -1, + 5823, 5773, 5772, -1, 5772, 5824, 5823, -1, + 5824, 5772, 5771, -1, 5771, 5825, 5824, -1, + 5825, 5771, 5770, -1, 5770, 5826, 5825, -1, + 5826, 5770, 5769, -1, 5769, 5827, 5826, -1, + 5827, 5769, 5768, -1, 5768, 5828, 5827, -1, + 5828, 5768, 5767, -1, 5767, 5829, 5828, -1, + 5829, 5767, 5766, -1, 5766, 5830, 5829, -1, + 5830, 5766, 5765, -1, 5765, 5831, 5830, -1, + 5831, 5765, 5764, -1, 5764, 5832, 5831, -1, + 5832, 5764, 5763, -1, 5763, 5833, 5832, -1, + 5833, 5763, 5762, -1, 5762, 5834, 5833, -1, + 5834, 5762, 5761, -1, 5761, 5835, 5834, -1, + 5835, 5761, 5760, -1, 5760, 5836, 5835, -1, + 5836, 5760, 5759, -1, 5759, 5837, 5836, -1, + 5837, 5759, 5758, -1, 5758, 5838, 5837, -1, + 5838, 5758, 5757, -1, 5757, 5839, 5838, -1, + 5839, 5757, 5756, -1, 5756, 5840, 5839, -1, + 5840, 5756, 5755, -1, 5755, 5841, 5840, -1, + 5841, 5755, 5754, -1, 5754, 5842, 5841, -1, + 5842, 5754, 5753, -1, 5753, 4716, 5842, -1, + 4716, 4555, 5842, -1, 4716, 4600, 4555, -1, + 4600, 4716, 4715, -1, 4715, 4599, 4600, -1, + 4599, 4715, 4735, -1, 4735, 4598, 4599, -1, + 4598, 4735, 4733, -1, 4733, 4597, 4598, -1, + 4597, 4733, 4731, -1, 4731, 4596, 4597, -1, + 4596, 4731, 4729, -1, 4729, 4585, 4596, -1, + 4585, 4729, 4727, -1, 4727, 4586, 4585, -1, + 4586, 4727, 4725, -1, 4725, 4588, 4586, -1, + 4588, 4725, 4724, -1, 4724, 4590, 4588, -1, + 4590, 4724, 4723, -1, 4723, 4592, 4590, -1, + 4723, 4594, 4592, -1, 4723, 4722, 4594, -1, + 4722, 4719, 4594, -1, 4594, 4719, 4718, -1, + 2957, 4595, 4594, -1, 4595, 2957, 2956, -1, + 2956, 4581, 4595, -1, 2956, 2955, 4581, -1, + 2955, 4582, 4581, -1, 4582, 2955, 2957, -1, + 4582, 2957, 4554, -1, 4554, 4583, 4582, -1, + 4554, 4553, 4583, -1, 4583, 4553, 2958, -1, + 4583, 2958, 2962, -1, 2962, 4580, 4583, -1, + 4580, 2962, 2964, -1, 2964, 4578, 4580, -1, + 4578, 2964, 4543, -1, 4543, 4576, 4578, -1, + 4576, 4543, 4542, -1, 4542, 4574, 4576, -1, + 4574, 4542, 4541, -1, 4541, 4572, 4574, -1, + 4572, 4541, 4540, -1, 4540, 4570, 4572, -1, + 4570, 4540, 4539, -1, 4539, 4568, 4570, -1, + 4568, 4539, 4538, -1, 4538, 4566, 4568, -1, + 4566, 4538, 4537, -1, 4537, 4564, 4566, -1, + 4564, 4537, 4536, -1, 4536, 4562, 4564, -1, + 4562, 4536, 4535, -1, 4535, 4561, 4562, -1, + 4561, 4535, 2966, -1, 2966, 4559, 4561, -1, + 4559, 2966, 2965, -1, 2965, 5843, 4559, -1, + 5843, 2965, 2968, -1, 2968, 5844, 5843, -1, + 5844, 2968, 2970, -1, 2970, 5845, 5844, -1, + 5845, 2970, 2972, -1, 2972, 5846, 5845, -1, + 5846, 2972, 2974, -1, 2974, 5847, 5846, -1, + 5847, 2974, 2976, -1, 2976, 5848, 5847, -1, + 5848, 2976, 2978, -1, 2978, 5849, 5848, -1, + 5849, 2978, 2980, -1, 2980, 5850, 5849, -1, + 5850, 2980, 2982, -1, 2982, 5851, 5850, -1, + 5851, 2982, 2984, -1, 2984, 5852, 5851, -1, + 5852, 2984, 2986, -1, 2986, 5853, 5852, -1, + 5853, 2986, 2988, -1, 2988, 5854, 5853, -1, + 5854, 2988, 2990, -1, 2990, 5855, 5854, -1, + 5855, 2990, 2992, -1, 2992, 5856, 5855, -1, + 5856, 2992, 2994, -1, 2994, 5857, 5856, -1, + 5857, 2994, 2996, -1, 2996, 5858, 5857, -1, + 5858, 2996, 2998, -1, 2998, 5859, 5858, -1, + 5859, 2998, 3000, -1, 3000, 5860, 5859, -1, + 5860, 3000, 3002, -1, 3002, 5861, 5860, -1, + 5861, 3002, 3004, -1, 3004, 5862, 5861, -1, + 5862, 3004, 3006, -1, 3006, 5863, 5862, -1, + 5863, 3006, 3008, -1, 3008, 5864, 5863, -1, + 5864, 3008, 3010, -1, 3010, 5865, 5864, -1, + 5865, 3010, 3012, -1, 5865, 3012, 3015, -1, + 3015, 5866, 5865, -1, 5866, 3015, 3017, -1, + 3017, 5867, 5866, -1, 5867, 3017, 3019, -1, + 3019, 5868, 5867, -1, 5868, 3019, 3021, -1, + 3021, 5869, 5868, -1, 5869, 3021, 3023, -1, + 3023, 5870, 5869, -1, 5870, 3023, 3025, -1, + 3025, 5871, 5870, -1, 5871, 3025, 3027, -1, + 3027, 5872, 5871, -1, 5872, 3027, 3029, -1, + 3029, 5873, 5872, -1, 5873, 3029, 3031, -1, + 3031, 5874, 5873, -1, 5874, 3031, 3033, -1, + 3033, 5875, 5874, -1, 5875, 3033, 3035, -1, + 3035, 5876, 5875, -1, 5876, 3035, 3037, -1, + 3037, 5877, 5876, -1, 5877, 3037, 3039, -1, + 3039, 5878, 5877, -1, 5878, 3039, 3041, -1, + 3041, 5879, 5878, -1, 5879, 3041, 3043, -1, + 3043, 5880, 5879, -1, 5880, 3043, 3045, -1, + 3045, 5881, 5880, -1, 5881, 3045, 3047, -1, + 3047, 5882, 5881, -1, 5882, 3047, 3049, -1, + 3049, 5883, 5882, -1, 5883, 3049, 3051, -1, + 3051, 5884, 5883, -1, 5884, 3051, 3053, -1, + 3053, 5885, 5884, -1, 5885, 3053, 3055, -1, + 3055, 5886, 5885, -1, 5886, 3055, 3057, -1, + 3057, 5887, 5886, -1, 5887, 3057, 3059, -1, + 3059, 5888, 5887, -1, 5888, 3059, 3061, -1, + 3061, 3064, 5888, -1, 5889, 5888, 3064, -1, + 5888, 5889, 5890, -1, 5890, 5887, 5888, -1, + 5887, 5890, 5891, -1, 5891, 5886, 5887, -1, + 5886, 5891, 5892, -1, 5892, 5885, 5886, -1, + 5885, 5892, 5893, -1, 5893, 5884, 5885, -1, + 5884, 5893, 5894, -1, 5894, 5883, 5884, -1, + 5883, 5894, 5895, -1, 5895, 5882, 5883, -1, + 5882, 5895, 5896, -1, 5896, 5881, 5882, -1, + 5881, 5896, 5897, -1, 5897, 5880, 5881, -1, + 5880, 5897, 5898, -1, 5898, 5879, 5880, -1, + 5879, 5898, 5899, -1, 5899, 5878, 5879, -1, + 5878, 5899, 5900, -1, 5900, 5877, 5878, -1, + 5877, 5900, 5901, -1, 5901, 5876, 5877, -1, + 5876, 5901, 5902, -1, 5902, 5875, 5876, -1, + 5875, 5902, 5903, -1, 5903, 5874, 5875, -1, + 5874, 5903, 5904, -1, 5904, 5873, 5874, -1, + 5873, 5904, 5905, -1, 5905, 5872, 5873, -1, + 5872, 5905, 5906, -1, 5906, 5871, 5872, -1, + 5871, 5906, 5907, -1, 5907, 5870, 5871, -1, + 5870, 5907, 5908, -1, 5908, 5869, 5870, -1, + 5869, 5908, 5909, -1, 5909, 5868, 5869, -1, + 5868, 5909, 5910, -1, 5910, 5867, 5868, -1, + 5867, 5910, 5911, -1, 5911, 5866, 5867, -1, + 5866, 5911, 5912, -1, 5912, 5865, 5866, -1, + 5912, 5864, 5865, -1, 5864, 5912, 5913, -1, + 5913, 5863, 5864, -1, 5863, 5913, 5914, -1, + 5914, 5862, 5863, -1, 5862, 5914, 5915, -1, + 5915, 5861, 5862, -1, 5861, 5915, 5916, -1, + 5916, 5860, 5861, -1, 5860, 5916, 5917, -1, + 5917, 5859, 5860, -1, 5859, 5917, 5918, -1, + 5918, 5858, 5859, -1, 5858, 5918, 5919, -1, + 5919, 5857, 5858, -1, 5857, 5919, 5920, -1, + 5920, 5856, 5857, -1, 5856, 5920, 5921, -1, + 5921, 5855, 5856, -1, 5855, 5921, 5922, -1, + 5922, 5854, 5855, -1, 5854, 5922, 5923, -1, + 5923, 5853, 5854, -1, 5853, 5923, 5924, -1, + 5924, 5852, 5853, -1, 5852, 5924, 5925, -1, + 5925, 5851, 5852, -1, 5851, 5925, 5926, -1, + 5926, 5850, 5851, -1, 5850, 5926, 5927, -1, + 5927, 5849, 5850, -1, 5849, 5927, 5928, -1, + 5928, 5848, 5849, -1, 5848, 5928, 5929, -1, + 5929, 5847, 5848, -1, 5847, 5929, 5930, -1, + 5930, 5846, 5847, -1, 5846, 5930, 5931, -1, + 5931, 5845, 5846, -1, 5845, 5931, 5932, -1, + 5932, 5844, 5845, -1, 5844, 5932, 5933, -1, + 5933, 5843, 5844, -1, 5843, 5933, 5934, -1, + 5934, 4559, 5843, -1, 5934, 4560, 4559, -1, + 5934, 5935, 4560, -1, 5935, 5934, 5933, -1, + 5933, 5936, 5935, -1, 5936, 5933, 5932, -1, + 5932, 5937, 5936, -1, 5937, 5932, 5931, -1, + 5931, 5938, 5937, -1, 5938, 5931, 5930, -1, + 5930, 5939, 5938, -1, 5939, 5930, 5929, -1, + 5929, 5940, 5939, -1, 5940, 5929, 5928, -1, + 5928, 5941, 5940, -1, 5941, 5928, 5927, -1, + 5927, 5942, 5941, -1, 5942, 5927, 5926, -1, + 5926, 5943, 5942, -1, 5943, 5926, 5925, -1, + 5925, 5944, 5943, -1, 5944, 5925, 5924, -1, + 5924, 5945, 5944, -1, 5945, 5924, 5923, -1, + 5923, 5946, 5945, -1, 5946, 5923, 5922, -1, + 5922, 5947, 5946, -1, 5947, 5922, 5921, -1, + 5921, 5948, 5947, -1, 5948, 5921, 5920, -1, + 5920, 5949, 5948, -1, 5949, 5920, 5919, -1, + 5919, 5950, 5949, -1, 5950, 5919, 5918, -1, + 5918, 5951, 5950, -1, 5951, 5918, 5917, -1, + 5917, 5952, 5951, -1, 5952, 5917, 5916, -1, + 5916, 5953, 5952, -1, 5953, 5916, 5915, -1, + 5915, 5954, 5953, -1, 5954, 5915, 5914, -1, + 5914, 5955, 5954, -1, 5955, 5914, 5913, -1, + 5913, 5956, 5955, -1, 5956, 5913, 5912, -1, + 5956, 5912, 5911, -1, 5911, 5957, 5956, -1, + 5957, 5911, 5910, -1, 5910, 5958, 5957, -1, + 5958, 5910, 5909, -1, 5909, 5959, 5958, -1, + 5959, 5909, 5908, -1, 5908, 5960, 5959, -1, + 5960, 5908, 5907, -1, 5907, 5961, 5960, -1, + 5961, 5907, 5906, -1, 5906, 5962, 5961, -1, + 5962, 5906, 5905, -1, 5905, 5963, 5962, -1, + 5963, 5905, 5904, -1, 5904, 5964, 5963, -1, + 5964, 5904, 5903, -1, 5903, 5965, 5964, -1, + 5965, 5903, 5902, -1, 5902, 5966, 5965, -1, + 5966, 5902, 5901, -1, 5901, 5967, 5966, -1, + 5967, 5901, 5900, -1, 5900, 5968, 5967, -1, + 5968, 5900, 5899, -1, 5899, 5969, 5968, -1, + 5969, 5899, 5898, -1, 5898, 5970, 5969, -1, + 5970, 5898, 5897, -1, 5897, 5971, 5970, -1, + 5971, 5897, 5896, -1, 5896, 5972, 5971, -1, + 5972, 5896, 5895, -1, 5895, 5973, 5972, -1, + 5973, 5895, 5894, -1, 5894, 5974, 5973, -1, + 5974, 5894, 5893, -1, 5893, 5975, 5974, -1, + 5975, 5893, 5892, -1, 5892, 5976, 5975, -1, + 5976, 5892, 5891, -1, 5891, 5977, 5976, -1, + 5977, 5891, 5890, -1, 5890, 5978, 5977, -1, + 5978, 5890, 5889, -1, 5889, 5979, 5978, -1, + 5979, 5889, 3064, -1, 5979, 3064, 3063, -1, + 5979, 3063, 5980, -1, 5980, 5978, 5979, -1, + 5978, 5980, 5981, -1, 5981, 5977, 5978, -1, + 5977, 5981, 5982, -1, 5982, 5976, 5977, -1, + 5976, 5982, 5983, -1, 5983, 5975, 5976, -1, + 5975, 5983, 5984, -1, 5984, 5974, 5975, -1, + 5974, 5984, 5985, -1, 5985, 5973, 5974, -1, + 5973, 5985, 5986, -1, 5986, 5972, 5973, -1, + 5972, 5986, 5987, -1, 5987, 5971, 5972, -1, + 5971, 5987, 5988, -1, 5988, 5970, 5971, -1, + 5970, 5988, 5989, -1, 5989, 5969, 5970, -1, + 5969, 5989, 5990, -1, 5990, 5968, 5969, -1, + 5968, 5990, 5991, -1, 5991, 5967, 5968, -1, + 5967, 5991, 5992, -1, 5992, 5966, 5967, -1, + 5966, 5992, 5993, -1, 5993, 5965, 5966, -1, + 5965, 5993, 5994, -1, 5994, 5964, 5965, -1, + 5964, 5994, 5995, -1, 5995, 5963, 5964, -1, + 5963, 5995, 5996, -1, 5996, 5962, 5963, -1, + 5962, 5996, 5997, -1, 5997, 5961, 5962, -1, + 5961, 5997, 5998, -1, 5998, 5960, 5961, -1, + 5960, 5998, 5999, -1, 5999, 5959, 5960, -1, + 5959, 5999, 6000, -1, 6000, 5958, 5959, -1, + 5958, 6000, 6001, -1, 6001, 5957, 5958, -1, + 5957, 6001, 6002, -1, 6002, 5956, 5957, -1, + 6002, 5955, 5956, -1, 5955, 6002, 6003, -1, + 6003, 5954, 5955, -1, 5954, 6003, 6004, -1, + 6004, 5953, 5954, -1, 5953, 6004, 6005, -1, + 6005, 5952, 5953, -1, 5952, 6005, 6006, -1, + 6006, 5951, 5952, -1, 5951, 6006, 6007, -1, + 6007, 5950, 5951, -1, 5950, 6007, 6008, -1, + 6008, 5949, 5950, -1, 5949, 6008, 6009, -1, + 6009, 5948, 5949, -1, 5948, 6009, 6010, -1, + 6010, 5947, 5948, -1, 5947, 6010, 6011, -1, + 6011, 5946, 5947, -1, 5946, 6011, 6012, -1, + 6012, 5945, 5946, -1, 5945, 6012, 6013, -1, + 6013, 5944, 5945, -1, 5944, 6013, 6014, -1, + 6014, 5943, 5944, -1, 5943, 6014, 6015, -1, + 6015, 5942, 5943, -1, 5942, 6015, 6016, -1, + 6016, 5941, 5942, -1, 5941, 6016, 6017, -1, + 6017, 5940, 5941, -1, 5940, 6017, 6018, -1, + 6018, 5939, 5940, -1, 5939, 6018, 6019, -1, + 6019, 5938, 5939, -1, 5938, 6019, 6020, -1, + 6020, 5937, 5938, -1, 5937, 6020, 6021, -1, + 6021, 5936, 5937, -1, 5936, 6021, 6022, -1, + 6022, 5935, 5936, -1, 5935, 6022, 6023, -1, + 6023, 4560, 5935, -1, 4560, 6023, 6024, -1, + 6024, 4556, 4560, -1, 6024, 4557, 4556, -1, + 6024, 6025, 4557, -1, 6025, 6024, 6023, -1, + 6023, 6026, 6025, -1, 6026, 6023, 6022, -1, + 6022, 6027, 6026, -1, 6027, 6022, 6021, -1, + 6021, 6028, 6027, -1, 6028, 6021, 6020, -1, + 6020, 6029, 6028, -1, 6029, 6020, 6019, -1, + 6019, 6030, 6029, -1, 6030, 6019, 6018, -1, + 6018, 6031, 6030, -1, 6031, 6018, 6017, -1, + 6017, 6032, 6031, -1, 6032, 6017, 6016, -1, + 6016, 6033, 6032, -1, 6033, 6016, 6015, -1, + 6015, 6034, 6033, -1, 6034, 6015, 6014, -1, + 6014, 6035, 6034, -1, 6035, 6014, 6013, -1, + 6013, 6036, 6035, -1, 6036, 6013, 6012, -1, + 6012, 6037, 6036, -1, 6037, 6012, 6011, -1, + 6011, 6038, 6037, -1, 6038, 6011, 6010, -1, + 6010, 6039, 6038, -1, 6039, 6010, 6009, -1, + 6009, 6040, 6039, -1, 6040, 6009, 6008, -1, + 6008, 6041, 6040, -1, 6041, 6008, 6007, -1, + 6007, 6042, 6041, -1, 6042, 6007, 6006, -1, + 6006, 6043, 6042, -1, 6043, 6006, 6005, -1, + 6005, 6044, 6043, -1, 6044, 6005, 6004, -1, + 6004, 6045, 6044, -1, 6045, 6004, 6003, -1, + 6003, 6046, 6045, -1, 6046, 6003, 6002, -1, + 6046, 6002, 6001, -1, 6001, 6047, 6046, -1, + 6047, 6001, 6000, -1, 6000, 6048, 6047, -1, + 6048, 6000, 5999, -1, 5999, 6049, 6048, -1, + 6049, 5999, 5998, -1, 5998, 6050, 6049, -1, + 6050, 5998, 5997, -1, 5997, 6051, 6050, -1, + 6051, 5997, 5996, -1, 5996, 6052, 6051, -1, + 6052, 5996, 5995, -1, 5995, 6053, 6052, -1, + 6053, 5995, 5994, -1, 5994, 6054, 6053, -1, + 6054, 5994, 5993, -1, 5993, 6055, 6054, -1, + 6055, 5993, 5992, -1, 5992, 6056, 6055, -1, + 6056, 5992, 5991, -1, 5991, 6057, 6056, -1, + 6057, 5991, 5990, -1, 5990, 6058, 6057, -1, + 6058, 5990, 5989, -1, 5989, 6059, 6058, -1, + 6059, 5989, 5988, -1, 5988, 6060, 6059, -1, + 6060, 5988, 5987, -1, 5987, 6061, 6060, -1, + 6061, 5987, 5986, -1, 5986, 6062, 6061, -1, + 6062, 5986, 5985, -1, 5985, 6063, 6062, -1, + 6063, 5985, 5984, -1, 5984, 6064, 6063, -1, + 6064, 5984, 5983, -1, 5983, 6065, 6064, -1, + 6065, 5983, 5982, -1, 5982, 6066, 6065, -1, + 6066, 5982, 5981, -1, 5981, 6067, 6066, -1, + 6067, 5981, 5980, -1, 5980, 6068, 6067, -1, + 6068, 5980, 3063, -1, 3063, 6069, 6068, -1, + 6069, 3063, 3062, -1, 6069, 3062, 3074, -1, + 6069, 3074, 6070, -1, 6070, 6068, 6069, -1, + 6068, 6070, 6071, -1, 6071, 6067, 6068, -1, + 6067, 6071, 6072, -1, 6072, 6066, 6067, -1, + 6066, 6072, 6073, -1, 6073, 6065, 6066, -1, + 6065, 6073, 6074, -1, 6074, 6064, 6065, -1, + 6064, 6074, 6075, -1, 6075, 6063, 6064, -1, + 6063, 6075, 6076, -1, 6076, 6062, 6063, -1, + 6062, 6076, 6077, -1, 6077, 6061, 6062, -1, + 6061, 6077, 6078, -1, 6078, 6060, 6061, -1, + 6060, 6078, 6079, -1, 6079, 6059, 6060, -1, + 6059, 6079, 6080, -1, 6080, 6058, 6059, -1, + 6058, 6080, 6081, -1, 6081, 6057, 6058, -1, + 6057, 6081, 6082, -1, 6082, 6056, 6057, -1, + 6056, 6082, 6083, -1, 6083, 6055, 6056, -1, + 6055, 6083, 6084, -1, 6084, 6054, 6055, -1, + 6054, 6084, 6085, -1, 6085, 6053, 6054, -1, + 6053, 6085, 6086, -1, 6086, 6052, 6053, -1, + 6052, 6086, 6087, -1, 6087, 6051, 6052, -1, + 6051, 6087, 6088, -1, 6088, 6050, 6051, -1, + 6050, 6088, 6089, -1, 6089, 6049, 6050, -1, + 6049, 6089, 6090, -1, 6090, 6048, 6049, -1, + 6048, 6090, 6091, -1, 6091, 6047, 6048, -1, + 6047, 6091, 6092, -1, 6092, 6046, 6047, -1, + 6092, 6045, 6046, -1, 6045, 6092, 6093, -1, + 6093, 6044, 6045, -1, 6044, 6093, 6094, -1, + 6094, 6043, 6044, -1, 6043, 6094, 6095, -1, + 6095, 6042, 6043, -1, 6042, 6095, 6096, -1, + 6096, 6041, 6042, -1, 6041, 6096, 6097, -1, + 6097, 6040, 6041, -1, 6040, 6097, 6098, -1, + 6098, 6039, 6040, -1, 6039, 6098, 6099, -1, + 6099, 6038, 6039, -1, 6038, 6099, 6100, -1, + 6100, 6037, 6038, -1, 6037, 6100, 6101, -1, + 6101, 6036, 6037, -1, 6036, 6101, 6102, -1, + 6102, 6035, 6036, -1, 6035, 6102, 6103, -1, + 6103, 6034, 6035, -1, 6034, 6103, 6104, -1, + 6104, 6033, 6034, -1, 6033, 6104, 6105, -1, + 6105, 6032, 6033, -1, 6032, 6105, 6106, -1, + 6106, 6031, 6032, -1, 6031, 6106, 6107, -1, + 6107, 6030, 6031, -1, 6030, 6107, 6108, -1, + 6108, 6029, 6030, -1, 6029, 6108, 6109, -1, + 6109, 6028, 6029, -1, 6028, 6109, 6110, -1, + 6110, 6027, 6028, -1, 6027, 6110, 6111, -1, + 6111, 6026, 6027, -1, 6026, 6111, 6112, -1, + 6112, 6025, 6026, -1, 6025, 6112, 6113, -1, + 6113, 4557, 6025, -1, 4557, 6113, 6114, -1, + 6114, 4555, 4557, -1, 6114, 5842, 4555, -1, + 6114, 5841, 5842, -1, 5841, 6114, 6113, -1, + 6113, 5840, 5841, -1, 5840, 6113, 6112, -1, + 6112, 5839, 5840, -1, 5839, 6112, 6111, -1, + 6111, 5838, 5839, -1, 5838, 6111, 6110, -1, + 6110, 5837, 5838, -1, 5837, 6110, 6109, -1, + 6109, 5836, 5837, -1, 5836, 6109, 6108, -1, + 6108, 5835, 5836, -1, 5835, 6108, 6107, -1, + 6107, 5834, 5835, -1, 5834, 6107, 6106, -1, + 6106, 5833, 5834, -1, 5833, 6106, 6105, -1, + 6105, 5832, 5833, -1, 5832, 6105, 6104, -1, + 6104, 5831, 5832, -1, 5831, 6104, 6103, -1, + 6103, 5830, 5831, -1, 5830, 6103, 6102, -1, + 6102, 5829, 5830, -1, 5829, 6102, 6101, -1, + 6101, 5828, 5829, -1, 5828, 6101, 6100, -1, + 6100, 5827, 5828, -1, 5827, 6100, 6099, -1, + 6099, 5826, 5827, -1, 5826, 6099, 6098, -1, + 6098, 5825, 5826, -1, 5825, 6098, 6097, -1, + 6097, 5824, 5825, -1, 5824, 6097, 6096, -1, + 6096, 5823, 5824, -1, 5823, 6096, 6095, -1, + 6095, 5822, 5823, -1, 5822, 6095, 6094, -1, + 6094, 5821, 5822, -1, 5821, 6094, 6093, -1, + 6093, 5820, 5821, -1, 5820, 6093, 6092, -1, + 5820, 6092, 6091, -1, 6091, 5819, 5820, -1, + 5819, 6091, 6090, -1, 6090, 5818, 5819, -1, + 5818, 6090, 6089, -1, 6089, 5817, 5818, -1, + 5817, 6089, 6088, -1, 6088, 5816, 5817, -1, + 5816, 6088, 6087, -1, 6087, 5815, 5816, -1, + 5815, 6087, 6086, -1, 6086, 5814, 5815, -1, + 5814, 6086, 6085, -1, 6085, 5813, 5814, -1, + 5813, 6085, 6084, -1, 6084, 5812, 5813, -1, + 5812, 6084, 6083, -1, 6083, 5811, 5812, -1, + 5811, 6083, 6082, -1, 6082, 5810, 5811, -1, + 5810, 6082, 6081, -1, 6081, 5809, 5810, -1, + 5809, 6081, 6080, -1, 6080, 5808, 5809, -1, + 5808, 6080, 6079, -1, 6079, 5807, 5808, -1, + 5807, 6079, 6078, -1, 6078, 5806, 5807, -1, + 5806, 6078, 6077, -1, 6077, 5805, 5806, -1, + 5805, 6077, 6076, -1, 6076, 5804, 5805, -1, + 5804, 6076, 6075, -1, 6075, 5803, 5804, -1, + 5803, 6075, 6074, -1, 6074, 5802, 5803, -1, + 5802, 6074, 6073, -1, 6073, 5801, 5802, -1, + 5801, 6073, 6072, -1, 6072, 5800, 5801, -1, + 5800, 6072, 6071, -1, 6071, 5799, 5800, -1, + 5799, 6071, 6070, -1, 6070, 5798, 5799, -1, + 5798, 6070, 3074, -1, 3074, 5553, 5798, -1, + 5553, 3074, 3073, -1, 3073, 5550, 5553, -1, + 5550, 3073, 3076, -1, 3076, 5548, 5550, -1, + 5548, 3076, 3078, -1, 3078, 5546, 5548, -1, + 5546, 3078, 3080, -1, 3080, 5544, 5546, -1, + 5544, 3080, 3082, -1, 3082, 5542, 5544, -1, + 5542, 3082, 3084, -1, 3084, 5541, 5542, -1, + 5541, 3084, 3085, -1, 3085, 5540, 5541, -1, + 5540, 3085, 3086, -1, 3086, 5539, 5540, -1, + 5539, 3086, 3087, -1, 3087, 6115, 5539, -1, + 6116, 5539, 6115, -1, 6116, 5538, 5539, -1, + 6116, 5535, 5538, -1, 6116, 6115, 5535, -1, + 6115, 6117, 5535, -1, 6117, 6115, 3087, -1, + 6117, 3087, 3088, -1, 6117, 3088, 3090, -1, + 3090, 5535, 6117, -1, 3090, 6118, 6119, -1, + 6118, 3090, 3091, -1, 3091, 3093, 6118, -1, + 3093, 3095, 6118, -1, 6120, 6118, 3095, -1, + 6120, 6119, 6118, -1, 6121, 6119, 6120, -1, + 6120, 3095, 6121, -1, 6121, 3095, 3117, -1, + 3117, 6119, 6121, -1, 3117, 6122, 6119, -1, + 6122, 3117, 3116, -1, 6122, 3116, 4529, -1, + 4529, 6119, 6122, -1, 6119, 4529, 4531, -1, + 4531, 6123, 6124, -1, 6123, 4531, 4534, -1, + 4534, 3237, 6123, -1, 3237, 3239, 6123, -1, + 6125, 6123, 3239, -1, 6125, 6124, 6123, -1, + 6126, 6124, 6125, -1, 6125, 3239, 6126, -1, + 6126, 3239, 3466, -1, 3466, 6124, 6126, -1, + 3466, 6127, 6124, -1, 6127, 3466, 3465, -1, + 6127, 3465, 3468, -1, 3468, 6124, 6127, -1, + 3468, 6128, 6124, -1, 6128, 3468, 3467, -1, + 6128, 3467, 3678, -1, 3678, 3679, 6128, -1, + 3679, 6124, 6128, -1, 6129, 3679, 3680, -1, + 3680, 6130, 6129, -1, 3680, 3682, 6130, -1, + 6130, 3682, 3691, -1, 3691, 6129, 6130, -1, + 3691, 6131, 6129, -1, 6131, 3691, 3690, -1, + 6131, 3690, 4384, -1, 4384, 6129, 6131, -1, + 4384, 6132, 6129, -1, 6132, 4384, 4102, -1, + 6132, 4102, 4103, -1, 4103, 4104, 6132, -1, + 4104, 6129, 6132, -1, 2635, 2948, 2947, -1, + 2948, 2635, 2634, -1, 2634, 2944, 2948, -1, + 2634, 2633, 2944, -1, 2633, 2945, 2944, -1, + 2945, 2633, 2635, -1, 2945, 2635, 4071, -1, + 4071, 2943, 2945, -1, 4071, 4070, 2943, -1, + 2943, 4070, 4068, -1, 4068, 2942, 2943, -1, + 2942, 4068, 4067, -1, 4067, 2940, 2942, -1, + 2940, 4067, 4052, -1, 4052, 4049, 2940, -1, + 6133, 4049, 6134, -1, 6133, 2940, 4049, -1, + 6133, 2941, 2940, -1, 6133, 6135, 2941, -1, + 6135, 6133, 6134, -1, 6134, 6136, 6135, -1, + 6136, 6134, 6137, -1, 6137, 6138, 6136, -1, + 6138, 6137, 6139, -1, 6138, 6139, 2631, -1, + 6138, 2631, 2632, -1, 2632, 6136, 6138, -1, + 6136, 2632, 6140, -1, 6140, 6135, 6136, -1, + 6135, 6140, 6141, -1, 6141, 2941, 6135, -1, + 2941, 6141, 6142, -1, 6142, 2937, 2941, -1, + 6142, 2938, 2937, -1, 6142, 6143, 2938, -1, + 6143, 6142, 6141, -1, 6141, 6144, 6143, -1, + 6144, 6141, 6140, -1, 6140, 6145, 6144, -1, + 6145, 6140, 2632, -1, 6145, 2632, 2527, -1, + 6145, 2527, 2524, -1, 2524, 6144, 6145, -1, + 6144, 2524, 2523, -1, 2523, 6143, 6144, -1, + 6143, 2523, 6146, -1, 6146, 2938, 6143, -1, + 2938, 6146, 6147, -1, 6147, 2936, 2938, -1, + 6147, 2952, 2936, -1, 6147, 6148, 2952, -1, + 6148, 6147, 6146, -1, 6146, 6149, 6148, -1, + 6149, 6146, 2523, -1, 2523, 2522, 6149, -1, + 2522, 2526, 6149, -1, 6150, 6149, 2526, -1, + 6150, 6148, 6149, -1, 6148, 6150, 6151, -1, + 6151, 2952, 6148, -1, 2952, 6151, 6152, -1, + 6152, 2935, 2952, -1, 6152, 2934, 2935, -1, + 6152, 2933, 2934, -1, 2933, 6152, 6151, -1, + 6151, 2932, 2933, -1, 2932, 6151, 6150, -1, + 6150, 2526, 2932, -1, 2526, 2862, 2932, -1, + 2526, 2860, 2862, -1, 2860, 2526, 2525, -1, + 2525, 2858, 2860, -1, 2858, 2525, 2528, -1, + 2528, 2856, 2858, -1, 2856, 2528, 2530, -1, + 2530, 2854, 2856, -1, 2854, 2530, 2532, -1, + 2532, 2852, 2854, -1, 2852, 2532, 2534, -1, + 2534, 2850, 2852, -1, 2850, 2534, 2536, -1, + 2536, 2848, 2850, -1, 2848, 2536, 2538, -1, + 2538, 2846, 2848, -1, 2846, 2538, 2540, -1, + 2540, 2844, 2846, -1, 2844, 2540, 2541, -1, + 2541, 2842, 2844, -1, 2842, 2541, 2623, -1, + 2623, 2840, 2842, -1, 2840, 2623, 2621, -1, + 2621, 2838, 2840, -1, 2838, 2621, 2619, -1, + 2619, 2836, 2838, -1, 2836, 2619, 2617, -1, + 2617, 2834, 2836, -1, 2834, 2617, 2615, -1, + 2615, 2832, 2834, -1, 2832, 2615, 2613, -1, + 2613, 2830, 2832, -1, 2830, 2613, 2611, -1, + 2611, 2828, 2830, -1, 2828, 2611, 2609, -1, + 2609, 2826, 2828, -1, 2826, 2609, 2607, -1, + 2607, 2824, 2826, -1, 2824, 2607, 2605, -1, + 2605, 2822, 2824, -1, 2822, 2605, 2603, -1, + 2603, 2820, 2822, -1, 2820, 2603, 2601, -1, + 2601, 2818, 2820, -1, 2818, 2601, 2599, -1, + 2599, 2816, 2818, -1, 2816, 2599, 2597, -1, + 2597, 2814, 2816, -1, 2814, 2597, 2595, -1, + 2595, 2812, 2814, -1, 2812, 2595, 2593, -1, + 2593, 2810, 2812, -1, 2810, 2593, 2591, -1, + 2591, 2808, 2810, -1, 2808, 2591, 2589, -1, + 2589, 2806, 2808, -1, 2806, 2589, 2587, -1, + 2587, 2804, 2806, -1, 2804, 2587, 2585, -1, + 2585, 2802, 2804, -1, 2802, 2585, 2583, -1, + 2583, 2800, 2802, -1, 2800, 2583, 2581, -1, + 2581, 2798, 2800, -1, 2798, 2581, 2579, -1, + 2579, 2796, 2798, -1, 2796, 2579, 2577, -1, + 2577, 2794, 2796, -1, 2794, 2577, 2575, -1, + 2575, 2792, 2794, -1, 2792, 2575, 2573, -1, + 2573, 2790, 2792, -1, 2790, 2573, 2571, -1, + 2571, 2788, 2790, -1, 2788, 2571, 2569, -1, + 2569, 2786, 2788, -1, 2786, 2569, 2567, -1, + 2567, 2784, 2786, -1, 2784, 2567, 2565, -1, + 2565, 2782, 2784, -1, 2782, 2565, 2563, -1, + 2563, 2780, 2782, -1, 2780, 2563, 2561, -1, + 2561, 2778, 2780, -1, 2778, 2561, 2559, -1, + 2559, 2776, 2778, -1, 2776, 2559, 2557, -1, + 2557, 2774, 2776, -1, 2774, 2557, 2555, -1, + 2555, 2772, 2774, -1, 2772, 2555, 2553, -1, + 2553, 2770, 2772, -1, 2770, 2553, 2551, -1, + 2551, 2768, 2770, -1, 2768, 2551, 2549, -1, + 2549, 2767, 2768, -1, 2767, 2549, 2547, -1, + 2547, 2765, 2767, -1, 2765, 2547, 2545, -1, + 2545, 6153, 2765, -1, 6154, 6155, 6156, -1, + 6155, 6153, 6156, -1, 6155, 2765, 6153, -1, + 6155, 6154, 2765, -1, 6154, 2766, 2765, -1, + 2766, 6154, 6156, -1, 6157, 2761, 2766, -1, + 6157, 2762, 2761, -1, 6156, 6158, 2762, -1, + 6159, 6160, 6158, -1, 6160, 2762, 6158, -1, + 6160, 2763, 2762, -1, 6160, 6159, 2763, -1, + 6159, 2915, 2763, -1, 2915, 6159, 6158, -1, + 2915, 6158, 6161, -1, 6161, 2759, 2915, -1, + 6161, 2760, 2759, -1, 2760, 6161, 6158, -1, + 6158, 6162, 2760, -1, 6163, 6164, 6162, -1, + 2519, 6165, 6163, -1, 6166, 6165, 2519, -1, + 6165, 6166, 2370, -1, 6165, 2370, 2371, -1, + 2371, 6163, 6165, -1, 2371, 6167, 6163, -1, + 6167, 2371, 2081, -1, 2080, 6164, 6163, -1, + 6164, 2080, 1966, -1, 6164, 1966, 1965, -1, + 1965, 6162, 6164, -1, 6168, 6162, 1965, -1, + 6168, 1965, 1171, -1, 6168, 1171, 1170, -1, + 1170, 6162, 6168, -1, 1170, 1172, 6162, -1, + 1172, 6169, 6162, -1, 6169, 2760, 6162, -1, + 6169, 2758, 2760, -1, 6169, 1172, 2758, -1, + 2758, 1172, 1171, -1, 1171, 2756, 2758, -1, + 2756, 1171, 1967, -1, 1967, 2754, 2756, -1, + 2754, 1967, 2078, -1, 2078, 2752, 2754, -1, + 2752, 2078, 2076, -1, 2076, 2750, 2752, -1, + 2750, 2076, 2074, -1, 2074, 2748, 2750, -1, + 2748, 2074, 2072, -1, 2072, 2746, 2748, -1, + 2746, 2072, 2070, -1, 2070, 2744, 2746, -1, + 2744, 2070, 2068, -1, 2068, 2742, 2744, -1, + 2742, 2068, 2066, -1, 2066, 2740, 2742, -1, + 2740, 2066, 2064, -1, 2064, 2738, 2740, -1, + 2738, 2064, 2062, -1, 2062, 2736, 2738, -1, + 2736, 2062, 2060, -1, 2060, 2734, 2736, -1, + 2734, 2060, 2058, -1, 2058, 2732, 2734, -1, + 2732, 2058, 2056, -1, 2056, 2730, 2732, -1, + 2730, 2056, 2054, -1, 2054, 2728, 2730, -1, + 2728, 2054, 2052, -1, 2052, 2726, 2728, -1, + 2726, 2052, 2050, -1, 2050, 2724, 2726, -1, + 2724, 2050, 2048, -1, 2048, 2722, 2724, -1, + 2722, 2048, 2046, -1, 2046, 2720, 2722, -1, + 2720, 2046, 2044, -1, 2044, 2718, 2720, -1, + 2718, 2044, 2042, -1, 2042, 2716, 2718, -1, + 2716, 2042, 2040, -1, 2040, 2714, 2716, -1, + 2714, 2040, 2038, -1, 2038, 2712, 2714, -1, + 2712, 2038, 2036, -1, 2036, 2710, 2712, -1, + 2710, 2036, 2034, -1, 2034, 2708, 2710, -1, + 2708, 2034, 2032, -1, 2032, 2706, 2708, -1, + 2706, 2032, 2030, -1, 2030, 2704, 2706, -1, + 2704, 2030, 2028, -1, 2028, 2702, 2704, -1, + 2702, 2028, 2026, -1, 2026, 2700, 2702, -1, + 2700, 2026, 2024, -1, 2024, 2698, 2700, -1, + 2698, 2024, 2022, -1, 2022, 2696, 2698, -1, + 2696, 2022, 2020, -1, 2020, 2694, 2696, -1, + 2694, 2020, 2018, -1, 2018, 2692, 2694, -1, + 2692, 2018, 2016, -1, 2016, 2690, 2692, -1, + 2690, 2016, 2014, -1, 2014, 2688, 2690, -1, + 2688, 2014, 2012, -1, 2012, 2686, 2688, -1, + 2686, 2012, 2010, -1, 2010, 2684, 2686, -1, + 2684, 2010, 2008, -1, 2008, 2682, 2684, -1, + 2682, 2008, 2006, -1, 2006, 2680, 2682, -1, + 2680, 2006, 2004, -1, 2004, 2678, 2680, -1, + 2678, 2004, 2002, -1, 2002, 2676, 2678, -1, + 2676, 2002, 2000, -1, 2000, 2674, 2676, -1, + 2674, 2000, 1998, -1, 1998, 2672, 2674, -1, + 2672, 1998, 1996, -1, 1996, 2670, 2672, -1, + 2670, 1996, 1994, -1, 1994, 2668, 2670, -1, + 2668, 1994, 1992, -1, 1992, 2666, 2668, -1, + 2666, 1992, 1990, -1, 1990, 2664, 2666, -1, + 2664, 1990, 1988, -1, 1988, 2662, 2664, -1, + 2662, 1988, 1986, -1, 1986, 2660, 2662, -1, + 2660, 1986, 1984, -1, 1984, 2658, 2660, -1, + 2658, 1984, 1982, -1, 1982, 6170, 2658, -1, + 6170, 1982, 1980, -1, 1980, 6171, 6170, -1, + 6171, 1980, 1978, -1, 1978, 6172, 6171, -1, + 6172, 1978, 1976, -1, 1976, 6173, 6172, -1, + 6173, 1976, 1972, -1, 1972, 1971, 6173, -1, + 1971, 6174, 6175, -1, 6175, 6173, 1971, -1, + 6173, 6175, 6176, -1, 6176, 6172, 6173, -1, + 6172, 6176, 6177, -1, 6177, 6171, 6172, -1, + 6171, 6177, 6178, -1, 6178, 6170, 6171, -1, + 6170, 6178, 6179, -1, 6179, 2658, 6170, -1, + 6179, 2659, 2658, -1, 6179, 6180, 2659, -1, + 6180, 6179, 6178, -1, 6178, 6181, 6180, -1, + 6181, 6178, 6177, -1, 6177, 6182, 6181, -1, + 6182, 6177, 6176, -1, 6176, 6183, 6182, -1, + 6183, 6176, 6175, -1, 6175, 6184, 6183, -1, + 6185, 6183, 6184, -1, 6185, 6184, 1169, -1, + 6185, 1169, 1168, -1, 1168, 6183, 6185, -1, + 1168, 1167, 6183, -1, 6183, 1167, 1165, -1, + 1165, 6182, 6183, -1, 6182, 1165, 1163, -1, + 1163, 6181, 6182, -1, 6181, 1163, 1161, -1, + 1161, 6180, 6181, -1, 6180, 1161, 1159, -1, + 1159, 2659, 6180, -1, 2659, 1159, 1156, -1, + 1156, 2657, 2659, -1, 1156, 1158, 2657, -1, + 6186, 2657, 1158, -1, 6186, 2661, 2657, -1, + 6186, 2916, 2661, -1, 6186, 2919, 2916, -1, + 2919, 6186, 1158, -1, 1158, 2918, 2919, -1, + 2918, 1158, 1157, -1, 1157, 1160, 2918, -1, + 1160, 2656, 2918, -1, 1160, 2655, 2656, -1, + 2655, 1160, 1162, -1, 1162, 2654, 2655, -1, + 2654, 1162, 1164, -1, 1164, 2653, 2654, -1, + 2653, 1164, 6187, -1, 6187, 2652, 2653, -1, + 6187, 6188, 2652, -1, 6188, 6187, 1164, -1, + 6188, 1164, 1166, -1, 1166, 2652, 6188, -1, + 1166, 6189, 2652, -1, 6189, 1166, 1165, -1, + 6189, 1165, 1167, -1, 1167, 1169, 6189, -1, + 1169, 2652, 6189, -1, 6190, 6191, 6192, -1, + 1169, 6193, 6190, -1, 6193, 1169, 6184, -1, + 6193, 6184, 6175, -1, 6193, 6175, 6174, -1, + 6174, 6190, 6193, -1, 6174, 6194, 6190, -1, + 6194, 6174, 1971, -1, 6194, 1971, 1969, -1, + 1969, 6190, 6194, -1, 1969, 1968, 6190, -1, + 1968, 6191, 6190, -1, 6191, 1968, 1970, -1, + 6191, 1970, 1973, -1, 1973, 6192, 6191, -1, + 1973, 6195, 6192, -1, 6195, 1973, 1558, -1, + 6195, 1558, 1557, -1, 1557, 6192, 6195, -1, + 1557, 1559, 6192, -1, 1559, 1560, 6192, -1, + 1560, 6196, 6192, -1, 6196, 1560, 1561, -1, + 6196, 1561, 1719, -1, 6196, 1719, 1720, -1, + 1720, 6192, 6196, -1, 6197, 1720, 1721, -1, + 1721, 1722, 6197, -1, 1722, 6198, 6197, -1, + 6198, 1722, 1723, -1, 6198, 1723, 1729, -1, + 1729, 6197, 6198, -1, 1729, 1728, 6197, -1, + 1728, 1730, 6197, -1, 6197, 1730, 1531, -1, + 4228, 1531, 1529, -1, 1529, 6199, 4228, -1, + 6199, 1529, 1503, -1, 6199, 1503, 6200, -1, + 6200, 4228, 6199, -1, 6200, 6201, 4228, -1, + 6201, 6200, 1503, -1, 1503, 1502, 6201, -1, + 6202, 6201, 1502, -1, 6202, 4228, 6201, -1, + 6202, 4229, 4228, -1, 6202, 1502, 4229, -1, + 1502, 1506, 4229, -1, 6203, 4229, 1506, -1, + 6203, 4225, 4229, -1, 6203, 6204, 4225, -1, + 6203, 1506, 6204, -1, 6204, 1506, 1508, -1, + 1508, 4225, 6204, -1, 1508, 1507, 4225, -1, + 1507, 4226, 4225, -1, 1507, 1509, 4226, -1, + 1509, 1179, 4226, -1, 6205, 4226, 1179, -1, + 6205, 4227, 4226, -1, 6205, 6206, 4227, -1, + 6205, 1179, 6206, -1, 6206, 1179, 1177, -1, + 1177, 4227, 6206, -1, 1177, 1176, 4227, -1, + 1176, 4230, 4227, -1, 1176, 1178, 4230, -1, + 1178, 4219, 4230, -1, 4219, 1178, 1488, -1, + 1488, 4218, 4219, -1, 4218, 1488, 1486, -1, + 1486, 4217, 4218, -1, 4217, 1486, 1485, -1, + 1485, 4216, 4217, -1, 4216, 1485, 1484, -1, + 1484, 4214, 4216, -1, 1484, 6207, 4214, -1, + 6208, 6209, 6210, -1, 6209, 6208, 6211, -1, + 6211, 6212, 6209, -1, 6212, 6211, 6207, -1, + 6207, 6213, 6212, -1, 6213, 6207, 1484, -1, + 6213, 1484, 1180, -1, 6213, 1180, 1183, -1, + 1183, 6212, 6213, -1, 6212, 1183, 1184, -1, + 1184, 6209, 6212, -1, 6209, 1184, 1186, -1, + 1186, 6210, 6209, -1, 6210, 1186, 1190, -1, + 1190, 6214, 6210, -1, 6214, 1190, 1192, -1, + 1192, 6215, 6214, -1, 6215, 1192, 1194, -1, + 1194, 6216, 6215, -1, 6216, 1194, 1196, -1, + 1196, 6217, 6216, -1, 6217, 1196, 1198, -1, + 1198, 6218, 6217, -1, 6218, 1198, 1200, -1, + 1200, 6219, 6218, -1, 6219, 1200, 1202, -1, + 1202, 6220, 6219, -1, 6220, 1202, 1204, -1, + 1204, 6221, 6220, -1, 6221, 1204, 1206, -1, + 1206, 6222, 6221, -1, 6222, 1206, 1208, -1, + 1208, 6223, 6222, -1, 6223, 1208, 1210, -1, + 1210, 6224, 6223, -1, 6224, 1210, 1212, -1, + 1212, 6225, 6224, -1, 6225, 1212, 1214, -1, + 1214, 6226, 6225, -1, 6226, 1214, 1216, -1, + 1216, 6227, 6226, -1, 6227, 1216, 1218, -1, + 1218, 6228, 6227, -1, 6228, 1218, 1220, -1, + 1220, 6229, 6228, -1, 6229, 1220, 1222, -1, + 1222, 6230, 6229, -1, 6230, 1222, 1224, -1, + 1224, 6231, 6230, -1, 6231, 1224, 1226, -1, + 1226, 6232, 6231, -1, 6232, 1226, 1228, -1, + 1228, 6233, 6232, -1, 6233, 1228, 1230, -1, + 1230, 6234, 6233, -1, 6234, 1230, 1232, -1, + 1232, 6235, 6234, -1, 6235, 1232, 1234, -1, + 1234, 6236, 6235, -1, 6236, 1234, 1236, -1, + 1236, 6237, 6236, -1, 6237, 1236, 1238, -1, + 1238, 6238, 6237, -1, 6238, 1238, 1240, -1, + 1240, 6239, 6238, -1, 6239, 1240, 1242, -1, + 1242, 6240, 6239, -1, 6240, 1242, 1244, -1, + 1244, 6241, 6240, -1, 6241, 1244, 1246, -1, + 1246, 6242, 6241, -1, 6242, 1246, 1248, -1, + 1248, 6243, 6242, -1, 6243, 1248, 1250, -1, + 1250, 6244, 6243, -1, 6244, 1250, 1252, -1, + 1252, 6245, 6244, -1, 6245, 1252, 1254, -1, + 1254, 6246, 6245, -1, 6246, 1254, 1256, -1, + 1256, 6247, 6246, -1, 6247, 1256, 1258, -1, + 1258, 6248, 6247, -1, 6248, 1258, 1260, -1, + 1260, 6249, 6248, -1, 6249, 1260, 1262, -1, + 1262, 6250, 6249, -1, 6250, 1262, 1264, -1, + 1264, 6251, 6250, -1, 6251, 1264, 1266, -1, + 1266, 6252, 6251, -1, 6252, 1266, 1268, -1, + 1268, 6253, 6252, -1, 6253, 1268, 1270, -1, + 1270, 6254, 6253, -1, 6254, 1270, 1272, -1, + 1272, 6255, 6254, -1, 6255, 1272, 1274, -1, + 1274, 6256, 6255, -1, 6256, 1274, 1276, -1, + 1276, 6257, 6256, -1, 6257, 1276, 1278, -1, + 6257, 1278, 1281, -1, 1281, 6258, 6257, -1, + 6258, 1281, 1283, -1, 1283, 6259, 6258, -1, + 6259, 1283, 1285, -1, 1285, 6260, 6259, -1, + 6260, 1285, 1287, -1, 1287, 6261, 6260, -1, + 6261, 1287, 1289, -1, 1289, 6262, 6261, -1, + 6262, 1289, 1291, -1, 1291, 6263, 6262, -1, + 6263, 1291, 1293, -1, 1293, 6264, 6263, -1, + 6264, 1293, 1295, -1, 1295, 6265, 6264, -1, + 6265, 1295, 1297, -1, 1297, 6266, 6265, -1, + 6266, 1297, 1299, -1, 1299, 6267, 6266, -1, + 6267, 1299, 1301, -1, 1301, 6268, 6267, -1, + 6268, 1301, 1303, -1, 1303, 6269, 6268, -1, + 6269, 1303, 1305, -1, 1305, 6270, 6269, -1, + 6270, 1305, 1307, -1, 1307, 6271, 6270, -1, + 6271, 1307, 1309, -1, 1309, 6272, 6271, -1, + 6272, 1309, 1311, -1, 1311, 6273, 6272, -1, + 6273, 1311, 1313, -1, 1313, 6274, 6273, -1, + 6274, 1313, 1315, -1, 1315, 6275, 6274, -1, + 6275, 1315, 1317, -1, 1317, 6276, 6275, -1, + 6276, 1317, 1319, -1, 1319, 6277, 6276, -1, + 6277, 1319, 1321, -1, 1321, 6278, 6277, -1, + 6278, 1321, 1323, -1, 1323, 6279, 6278, -1, + 6279, 1323, 1325, -1, 1325, 6280, 6279, -1, + 6280, 1325, 1327, -1, 1327, 6281, 6280, -1, + 6281, 1327, 1329, -1, 1329, 6282, 6281, -1, + 6282, 1329, 1331, -1, 1331, 6283, 6282, -1, + 6283, 1331, 1333, -1, 1333, 6284, 6283, -1, + 6284, 1333, 1335, -1, 1335, 6285, 6284, -1, + 6285, 1335, 1337, -1, 1337, 6286, 6285, -1, + 6286, 1337, 1339, -1, 1339, 6287, 6286, -1, + 6287, 1339, 1341, -1, 1341, 6288, 6287, -1, + 6288, 1341, 1343, -1, 1343, 6289, 6288, -1, + 6289, 1343, 1345, -1, 1345, 6290, 6289, -1, + 6290, 1345, 1347, -1, 1347, 6291, 6290, -1, + 6291, 1347, 1349, -1, 1349, 6292, 6291, -1, + 6292, 1349, 1351, -1, 1351, 6293, 6292, -1, + 6293, 1351, 1353, -1, 1353, 6294, 6293, -1, + 6294, 1353, 1355, -1, 1355, 6295, 6294, -1, + 6295, 1355, 1357, -1, 1357, 6296, 6295, -1, + 6296, 1357, 1359, -1, 1359, 6297, 6296, -1, + 6297, 1359, 1376, -1, 1376, 6298, 6297, -1, + 6298, 1376, 1374, -1, 1374, 6299, 6298, -1, + 6299, 1374, 1372, -1, 1372, 6300, 6299, -1, + 6300, 1372, 1370, -1, 1370, 6301, 6300, -1, + 6301, 1370, 1366, -1, 1366, 1365, 6301, -1, + 6302, 1365, 6303, -1, 6302, 6301, 1365, -1, + 6301, 6302, 6304, -1, 6304, 6300, 6301, -1, + 6300, 6304, 6305, -1, 6305, 6299, 6300, -1, + 6299, 6305, 6306, -1, 6306, 6298, 6299, -1, + 6298, 6306, 6307, -1, 6307, 6297, 6298, -1, + 6297, 6307, 6308, -1, 6308, 6296, 6297, -1, + 6296, 6308, 6309, -1, 6309, 6295, 6296, -1, + 6295, 6309, 6310, -1, 6310, 6294, 6295, -1, + 6294, 6310, 6311, -1, 6311, 6293, 6294, -1, + 6293, 6311, 6312, -1, 6312, 6292, 6293, -1, + 6292, 6312, 6313, -1, 6313, 6291, 6292, -1, + 6291, 6313, 6314, -1, 6314, 6290, 6291, -1, + 6290, 6314, 6315, -1, 6315, 6289, 6290, -1, + 6289, 6315, 6316, -1, 6316, 6288, 6289, -1, + 6288, 6316, 6317, -1, 6317, 6287, 6288, -1, + 6287, 6317, 6318, -1, 6318, 6286, 6287, -1, + 6286, 6318, 6319, -1, 6319, 6285, 6286, -1, + 6285, 6319, 6320, -1, 6320, 6284, 6285, -1, + 6284, 6320, 6321, -1, 6321, 6283, 6284, -1, + 6283, 6321, 6322, -1, 6322, 6282, 6283, -1, + 6282, 6322, 6323, -1, 6323, 6281, 6282, -1, + 6281, 6323, 6324, -1, 6324, 6280, 6281, -1, + 6280, 6324, 6325, -1, 6325, 6279, 6280, -1, + 6279, 6325, 6326, -1, 6326, 6278, 6279, -1, + 6278, 6326, 6327, -1, 6327, 6277, 6278, -1, + 6277, 6327, 6328, -1, 6328, 6276, 6277, -1, + 6276, 6328, 6329, -1, 6329, 6275, 6276, -1, + 6275, 6329, 6330, -1, 6330, 6274, 6275, -1, + 6274, 6330, 6331, -1, 6331, 6273, 6274, -1, + 6273, 6331, 6332, -1, 6332, 6272, 6273, -1, + 6272, 6332, 6333, -1, 6333, 6271, 6272, -1, + 6271, 6333, 6334, -1, 6334, 6270, 6271, -1, + 6270, 6334, 6335, -1, 6335, 6269, 6270, -1, + 6269, 6335, 6336, -1, 6336, 6268, 6269, -1, + 6268, 6336, 6337, -1, 6337, 6267, 6268, -1, + 6267, 6337, 6338, -1, 6338, 6266, 6267, -1, + 6266, 6338, 6339, -1, 6339, 6265, 6266, -1, + 6265, 6339, 6340, -1, 6340, 6264, 6265, -1, + 6264, 6340, 6341, -1, 6341, 6263, 6264, -1, + 6263, 6341, 6342, -1, 6342, 6262, 6263, -1, + 6262, 6342, 6343, -1, 6343, 6261, 6262, -1, + 6261, 6343, 6344, -1, 6344, 6260, 6261, -1, + 6260, 6344, 6345, -1, 6345, 6259, 6260, -1, + 6259, 6345, 6346, -1, 6346, 6258, 6259, -1, + 6258, 6346, 6347, -1, 6347, 6257, 6258, -1, + 6347, 6256, 6257, -1, 6256, 6347, 6348, -1, + 6348, 6255, 6256, -1, 6255, 6348, 6349, -1, + 6349, 6254, 6255, -1, 6254, 6349, 6350, -1, + 6350, 6253, 6254, -1, 6253, 6350, 6351, -1, + 6351, 6252, 6253, -1, 6252, 6351, 6352, -1, + 6352, 6251, 6252, -1, 6251, 6352, 6353, -1, + 6353, 6250, 6251, -1, 6250, 6353, 6354, -1, + 6354, 6249, 6250, -1, 6249, 6354, 6355, -1, + 6355, 6248, 6249, -1, 6248, 6355, 6356, -1, + 6356, 6247, 6248, -1, 6247, 6356, 6357, -1, + 6357, 6246, 6247, -1, 6246, 6357, 6358, -1, + 6358, 6245, 6246, -1, 6245, 6358, 6359, -1, + 6359, 6244, 6245, -1, 6244, 6359, 6360, -1, + 6360, 6243, 6244, -1, 6243, 6360, 6361, -1, + 6361, 6242, 6243, -1, 6242, 6361, 6362, -1, + 6362, 6241, 6242, -1, 6241, 6362, 6363, -1, + 6363, 6240, 6241, -1, 6240, 6363, 6364, -1, + 6364, 6239, 6240, -1, 6239, 6364, 6365, -1, + 6365, 6238, 6239, -1, 6238, 6365, 6366, -1, + 6366, 6237, 6238, -1, 6237, 6366, 6367, -1, + 6367, 6236, 6237, -1, 6236, 6367, 6368, -1, + 6368, 6235, 6236, -1, 6235, 6368, 6369, -1, + 6369, 6234, 6235, -1, 6234, 6369, 6370, -1, + 6370, 6233, 6234, -1, 6233, 6370, 6371, -1, + 6371, 6232, 6233, -1, 6232, 6371, 6372, -1, + 6372, 6231, 6232, -1, 6231, 6372, 6373, -1, + 6373, 6230, 6231, -1, 6230, 6373, 6374, -1, + 6374, 6229, 6230, -1, 6229, 6374, 6375, -1, + 6375, 6228, 6229, -1, 6228, 6375, 6376, -1, + 6376, 6227, 6228, -1, 6227, 6376, 6377, -1, + 6377, 6226, 6227, -1, 6226, 6377, 6378, -1, + 6378, 6225, 6226, -1, 6225, 6378, 6379, -1, + 6379, 6224, 6225, -1, 6224, 6379, 6380, -1, + 6380, 6223, 6224, -1, 6223, 6380, 6381, -1, + 6381, 6222, 6223, -1, 6222, 6381, 6382, -1, + 6382, 6221, 6222, -1, 6221, 6382, 6383, -1, + 6383, 6220, 6221, -1, 6220, 6383, 6384, -1, + 6384, 6219, 6220, -1, 6219, 6384, 6385, -1, + 6385, 6218, 6219, -1, 6218, 6385, 6386, -1, + 6386, 6217, 6218, -1, 6217, 6386, 6387, -1, + 6387, 6216, 6217, -1, 6216, 6387, 6388, -1, + 6388, 6215, 6216, -1, 6215, 6388, 6389, -1, + 6389, 6214, 6215, -1, 6214, 6389, 1155, -1, + 1155, 6210, 6214, -1, 6210, 1155, 1154, -1, + 1154, 6208, 6210, -1, 6208, 1154, 6390, -1, + 6390, 6211, 6208, -1, 6211, 6390, 6391, -1, + 6391, 6207, 6211, -1, 6391, 4214, 6207, -1, + 6391, 4215, 4214, -1, 4215, 6391, 6390, -1, + 6390, 6392, 4215, -1, 6392, 6390, 1154, -1, + 1154, 1153, 6392, -1, 6392, 1153, 6393, -1, + 6393, 4215, 6392, -1, 6393, 4213, 4215, -1, + 6393, 4212, 4213, -1, 4212, 6393, 1153, -1, + 1153, 4211, 4212, -1, 4211, 1153, 1155, -1, + 1155, 4210, 4211, -1, 4210, 1155, 6389, -1, + 6389, 4209, 4210, -1, 4209, 6389, 6388, -1, + 6388, 4208, 4209, -1, 4208, 6388, 6387, -1, + 6387, 4207, 4208, -1, 4207, 6387, 6386, -1, + 6386, 4206, 4207, -1, 4206, 6386, 6385, -1, + 6385, 4205, 4206, -1, 4205, 6385, 6384, -1, + 6384, 4204, 4205, -1, 4204, 6384, 6383, -1, + 6383, 4203, 4204, -1, 4203, 6383, 6382, -1, + 6382, 4202, 4203, -1, 4202, 6382, 6381, -1, + 6381, 4201, 4202, -1, 4201, 6381, 6380, -1, + 6380, 4200, 4201, -1, 4200, 6380, 6379, -1, + 6379, 4199, 4200, -1, 4199, 6379, 6378, -1, + 6378, 4198, 4199, -1, 4198, 6378, 6377, -1, + 6377, 4197, 4198, -1, 4197, 6377, 6376, -1, + 6376, 4196, 4197, -1, 4196, 6376, 6375, -1, + 6375, 4195, 4196, -1, 4195, 6375, 6374, -1, + 6374, 4194, 4195, -1, 4194, 6374, 6373, -1, + 6373, 4193, 4194, -1, 4193, 6373, 6372, -1, + 6372, 4192, 4193, -1, 4192, 6372, 6371, -1, + 6371, 4191, 4192, -1, 4191, 6371, 6370, -1, + 6370, 4190, 4191, -1, 4190, 6370, 6369, -1, + 6369, 4189, 4190, -1, 4189, 6369, 6368, -1, + 6368, 4188, 4189, -1, 4188, 6368, 6367, -1, + 6367, 4187, 4188, -1, 4187, 6367, 6366, -1, + 6366, 4186, 4187, -1, 4186, 6366, 6365, -1, + 6365, 4185, 4186, -1, 4185, 6365, 6364, -1, + 6364, 4184, 4185, -1, 4184, 6364, 6363, -1, + 6363, 4183, 4184, -1, 4183, 6363, 6362, -1, + 6362, 4182, 4183, -1, 4182, 6362, 6361, -1, + 6361, 4181, 4182, -1, 4181, 6361, 6360, -1, + 6360, 4180, 4181, -1, 4180, 6360, 6359, -1, + 6359, 4179, 4180, -1, 4179, 6359, 6358, -1, + 6358, 4178, 4179, -1, 4178, 6358, 6357, -1, + 6357, 4177, 4178, -1, 4177, 6357, 6356, -1, + 6356, 4176, 4177, -1, 4176, 6356, 6355, -1, + 6355, 4175, 4176, -1, 4175, 6355, 6354, -1, + 6354, 4174, 4175, -1, 4174, 6354, 6353, -1, + 6353, 4173, 4174, -1, 4173, 6353, 6352, -1, + 6352, 4172, 4173, -1, 4172, 6352, 6351, -1, + 6351, 4171, 4172, -1, 4171, 6351, 6350, -1, + 6350, 4170, 4171, -1, 4170, 6350, 6349, -1, + 6349, 4169, 4170, -1, 4169, 6349, 6348, -1, + 6348, 4168, 4169, -1, 4168, 6348, 6347, -1, + 4168, 6347, 6346, -1, 6346, 4167, 4168, -1, + 4167, 6346, 6345, -1, 6345, 4166, 4167, -1, + 4166, 6345, 6344, -1, 6344, 4165, 4166, -1, + 4165, 6344, 6343, -1, 6343, 4164, 4165, -1, + 4164, 6343, 6342, -1, 6342, 4163, 4164, -1, + 4163, 6342, 6341, -1, 6341, 4162, 4163, -1, + 4162, 6341, 6340, -1, 6340, 4161, 4162, -1, + 4161, 6340, 6339, -1, 6339, 4160, 4161, -1, + 4160, 6339, 6338, -1, 6338, 4159, 4160, -1, + 4159, 6338, 6337, -1, 6337, 4158, 4159, -1, + 4158, 6337, 6336, -1, 6336, 4157, 4158, -1, + 4157, 6336, 6335, -1, 6335, 4156, 4157, -1, + 4156, 6335, 6334, -1, 6334, 4155, 4156, -1, + 4155, 6334, 6333, -1, 6333, 4154, 4155, -1, + 4154, 6333, 6332, -1, 6332, 4153, 4154, -1, + 4153, 6332, 6331, -1, 6331, 4152, 4153, -1, + 4152, 6331, 6330, -1, 6330, 4151, 4152, -1, + 4151, 6330, 6329, -1, 6329, 4150, 4151, -1, + 4150, 6329, 6328, -1, 6328, 4149, 4150, -1, + 4149, 6328, 6327, -1, 6327, 4148, 4149, -1, + 4148, 6327, 6326, -1, 6326, 4147, 4148, -1, + 4147, 6326, 6325, -1, 6325, 4146, 4147, -1, + 4146, 6325, 6324, -1, 6324, 4145, 4146, -1, + 4145, 6324, 6323, -1, 6323, 4144, 4145, -1, + 4144, 6323, 6322, -1, 6322, 4143, 4144, -1, + 4143, 6322, 6321, -1, 6321, 4142, 4143, -1, + 4142, 6321, 6320, -1, 6320, 4140, 4142, -1, + 4140, 6320, 6319, -1, 6319, 4138, 4140, -1, + 4138, 6319, 6318, -1, 6318, 4136, 4138, -1, + 4136, 6318, 6317, -1, 6317, 4134, 4136, -1, + 4134, 6317, 6316, -1, 6316, 4132, 4134, -1, + 4132, 6316, 6315, -1, 6315, 4130, 4132, -1, + 4130, 6315, 6314, -1, 6314, 4128, 4130, -1, + 4128, 6314, 6313, -1, 6313, 4126, 4128, -1, + 4126, 6313, 6312, -1, 6312, 4124, 4126, -1, + 4124, 6312, 6311, -1, 6311, 4122, 4124, -1, + 4122, 6311, 6310, -1, 6310, 4120, 4122, -1, + 4120, 6310, 6309, -1, 6309, 4118, 4120, -1, + 4118, 6309, 6308, -1, 6308, 4117, 4118, -1, + 4117, 6308, 6307, -1, 6307, 4116, 4117, -1, + 4116, 6307, 6306, -1, 6306, 4115, 4116, -1, + 4115, 6306, 6305, -1, 6305, 4114, 4115, -1, + 4114, 6305, 6304, -1, 6304, 4113, 4114, -1, + 4113, 6304, 6302, -1, 6302, 4112, 4113, -1, + 4112, 6302, 6303, -1, 6303, 4055, 4112, -1, + 4055, 6303, 6394, -1, 6394, 4053, 4055, -1, + 6394, 4066, 4053, -1, 6394, 6395, 4066, -1, + 6395, 6394, 6303, -1, 6395, 6303, 1365, -1, + 6395, 1365, 1363, -1, 1363, 4066, 6395, -1, + 4066, 1363, 1360, -1, 1360, 4065, 4066, -1, + 1360, 1362, 4065, -1, 6396, 4065, 1362, -1, + 6396, 4050, 4065, -1, 6396, 4051, 4050, -1, + 6396, 6397, 4051, -1, 6397, 6396, 1362, -1, + 1362, 6398, 6397, -1, 6398, 1362, 1361, -1, + 1361, 1364, 6398, -1, 1364, 1368, 6398, -1, + 6399, 6398, 1368, -1, 6399, 6397, 6398, -1, + 6397, 6399, 6400, -1, 6400, 4051, 6397, -1, + 4051, 6400, 6401, -1, 6401, 4049, 4051, -1, + 6401, 6134, 4049, -1, 6401, 6137, 6134, -1, + 6137, 6401, 6400, -1, 6400, 6139, 6137, -1, + 6139, 6400, 6399, -1, 6399, 1368, 6139, -1, + 1368, 2631, 6139, -1, 1368, 2630, 2631, -1, + 2630, 1368, 1367, -1, 1367, 2629, 2630, -1, + 2629, 1367, 1369, -1, 1369, 2628, 2629, -1, + 2628, 1369, 1371, -1, 1371, 2627, 2628, -1, + 2627, 1371, 1373, -1, 1373, 2626, 2627, -1, + 2626, 1373, 1375, -1, 1375, 2625, 2626, -1, + 2625, 1375, 1377, -1, 1377, 2624, 2625, -1, + 2624, 1377, 1378, -1, 1378, 2622, 2624, -1, + 2622, 1378, 1379, -1, 1379, 2620, 2622, -1, + 2620, 1379, 1380, -1, 1380, 2618, 2620, -1, + 2618, 1380, 1381, -1, 1381, 2616, 2618, -1, + 2616, 1381, 1382, -1, 1382, 2614, 2616, -1, + 2614, 1382, 1383, -1, 1383, 2612, 2614, -1, + 2612, 1383, 1384, -1, 1384, 2610, 2612, -1, + 2610, 1384, 1385, -1, 1385, 2608, 2610, -1, + 2608, 1385, 1386, -1, 1386, 2606, 2608, -1, + 2606, 1386, 1387, -1, 1387, 2604, 2606, -1, + 2604, 1387, 1388, -1, 1388, 2602, 2604, -1, + 2602, 1388, 1389, -1, 1389, 2600, 2602, -1, + 2600, 1389, 1390, -1, 1390, 2598, 2600, -1, + 2598, 1390, 1391, -1, 1391, 2596, 2598, -1, + 2596, 1391, 1392, -1, 1392, 2594, 2596, -1, + 2594, 1392, 1393, -1, 1393, 2592, 2594, -1, + 2592, 1393, 1394, -1, 1394, 2590, 2592, -1, + 2590, 1394, 1395, -1, 1395, 2588, 2590, -1, + 2588, 1395, 1396, -1, 1396, 2586, 2588, -1, + 2586, 1396, 1397, -1, 1397, 2584, 2586, -1, + 2584, 1397, 1398, -1, 1398, 2582, 2584, -1, + 2582, 1398, 1399, -1, 1399, 2580, 2582, -1, + 2580, 1399, 1400, -1, 1400, 2578, 2580, -1, + 2578, 1400, 1401, -1, 1401, 2576, 2578, -1, + 2576, 1401, 1402, -1, 1402, 2574, 2576, -1, + 2574, 1402, 1403, -1, 1403, 2572, 2574, -1, + 2572, 1403, 1404, -1, 1404, 2570, 2572, -1, + 2570, 1404, 1405, -1, 1405, 2568, 2570, -1, + 2568, 1405, 1406, -1, 1406, 2566, 2568, -1, + 2566, 1406, 1407, -1, 1407, 2564, 2566, -1, + 2564, 1407, 1408, -1, 1408, 2562, 2564, -1, + 2562, 1408, 1409, -1, 1409, 2560, 2562, -1, + 2560, 1409, 1410, -1, 1410, 2558, 2560, -1, + 2558, 1410, 1411, -1, 1411, 2556, 2558, -1, + 2556, 1411, 1412, -1, 1412, 2554, 2556, -1, + 2554, 1412, 1413, -1, 1413, 2552, 2554, -1, + 2552, 1413, 1414, -1, 1414, 2550, 2552, -1, + 2550, 1414, 1415, -1, 1415, 2548, 2550, -1, + 2548, 1415, 1416, -1, 1416, 2546, 2548, -1, + 2546, 1416, 1417, -1, 1417, 2544, 2546, -1, + 2544, 1417, 1418, -1, 1418, 6402, 2544, -1, + 1152, 6402, 1418, -1, 1418, 1062, 1152, -1, + 1062, 1418, 1419, -1, 1419, 1150, 1062, -1, + 1150, 1419, 1420, -1, 1420, 1148, 1150, -1, + 1148, 1420, 1421, -1, 1421, 1146, 1148, -1, + 1146, 1421, 1422, -1, 1422, 1144, 1146, -1, + 1144, 1422, 1423, -1, 1423, 1142, 1144, -1, + 1142, 1423, 1424, -1, 1424, 1140, 1142, -1, + 1140, 1424, 1425, -1, 1425, 1138, 1140, -1, + 1138, 1425, 1426, -1, 1426, 1136, 1138, -1, + 1136, 1426, 1427, -1, 1427, 1134, 1136, -1, + 1134, 1427, 1428, -1, 1428, 1132, 1134, -1, + 1132, 1428, 1429, -1, 1429, 1130, 1132, -1, + 1130, 1429, 1430, -1, 1430, 1128, 1130, -1, + 1128, 1430, 1431, -1, 1431, 1126, 1128, -1, + 1126, 1431, 1432, -1, 1432, 1124, 1126, -1, + 1124, 1432, 1433, -1, 1433, 1122, 1124, -1, + 1122, 1433, 1434, -1, 1434, 1120, 1122, -1, + 1120, 1434, 1435, -1, 1435, 1118, 1120, -1, + 1118, 1435, 1436, -1, 1436, 1116, 1118, -1, + 1116, 1436, 1437, -1, 1437, 1114, 1116, -1, + 1114, 1437, 1438, -1, 1438, 1112, 1114, -1, + 1112, 1438, 1439, -1, 1439, 1110, 1112, -1, + 1110, 1439, 1440, -1, 1440, 1108, 1110, -1, + 1108, 1440, 1441, -1, 1441, 1106, 1108, -1, + 1106, 1441, 1442, -1, 1442, 1104, 1106, -1, + 1104, 1442, 1443, -1, 1443, 1102, 1104, -1, + 1102, 1443, 1444, -1, 1444, 1100, 1102, -1, + 1100, 1444, 1445, -1, 1445, 1098, 1100, -1, + 1098, 1445, 1446, -1, 1446, 1096, 1098, -1, + 1096, 1446, 1447, -1, 1447, 1094, 1096, -1, + 1094, 1447, 1448, -1, 1448, 1092, 1094, -1, + 1092, 1448, 1449, -1, 1449, 1090, 1092, -1, + 1090, 1449, 1450, -1, 1450, 1088, 1090, -1, + 1088, 1450, 1451, -1, 1451, 1086, 1088, -1, + 1086, 1451, 1452, -1, 1452, 1084, 1086, -1, + 1084, 1452, 1453, -1, 1453, 1082, 1084, -1, + 1082, 1453, 1454, -1, 1454, 1080, 1082, -1, + 1080, 1454, 1455, -1, 1455, 1078, 1080, -1, + 1078, 1455, 1456, -1, 1456, 1076, 1078, -1, + 1076, 1456, 1457, -1, 1457, 1074, 1076, -1, + 1074, 1457, 1458, -1, 1458, 1072, 1074, -1, + 1072, 1458, 1459, -1, 1459, 1070, 1072, -1, + 1070, 1459, 1460, -1, 1460, 1068, 1070, -1, + 1068, 1460, 1474, -1, 1474, 1065, 1068, -1, + 1065, 1474, 1472, -1, 1472, 1066, 1065, -1, + 1066, 1472, 1470, -1, 1470, 6403, 1066, -1, + 6403, 1470, 1468, -1, 1468, 6404, 6403, -1, + 6404, 1468, 1466, -1, 1466, 6405, 6404, -1, + 6405, 1466, 1464, -1, 1464, 6406, 6405, -1, + 6406, 1464, 1463, -1, 1463, 1517, 6406, -1, + 1517, 6407, 6406, -1, 6407, 1517, 1518, -1, + 1518, 6408, 6407, -1, 6408, 1518, 1519, -1, + 1519, 6409, 6408, -1, 6409, 1519, 1520, -1, + 1520, 6410, 6409, -1, 6410, 1520, 1521, -1, + 1521, 6411, 6410, -1, 6411, 1521, 1522, -1, + 6411, 1522, 1524, -1, 6411, 1524, 1845, -1, + 1845, 6410, 6411, -1, 6410, 1845, 1846, -1, + 1846, 6409, 6410, -1, 6409, 1846, 1850, -1, + 1850, 6408, 6409, -1, 6408, 1850, 1847, -1, + 1847, 6407, 6408, -1, 6407, 1847, 1849, -1, + 1849, 6406, 6407, -1, 6406, 1849, 1852, -1, + 1852, 6405, 6406, -1, 6405, 1852, 1853, -1, + 1853, 6404, 6405, -1, 6404, 1853, 1854, -1, + 1854, 6403, 6404, -1, 6403, 1854, 1855, -1, + 1855, 1066, 6403, -1, 1066, 1855, 1856, -1, + 1856, 1067, 1066, -1, 1067, 1856, 1857, -1, + 1857, 1069, 1067, -1, 1069, 1857, 1858, -1, + 1858, 1071, 1069, -1, 1071, 1858, 1859, -1, + 1859, 1073, 1071, -1, 1073, 1859, 1860, -1, + 1860, 1075, 1073, -1, 1075, 1860, 1861, -1, + 1861, 1077, 1075, -1, 1077, 1861, 1862, -1, + 1862, 1079, 1077, -1, 1079, 1862, 1863, -1, + 1863, 1081, 1079, -1, 1081, 1863, 1864, -1, + 1864, 1083, 1081, -1, 1083, 1864, 1865, -1, + 1865, 1085, 1083, -1, 1085, 1865, 1866, -1, + 1866, 1087, 1085, -1, 1087, 1866, 1867, -1, + 1867, 1089, 1087, -1, 1089, 1867, 1868, -1, + 1868, 1091, 1089, -1, 1091, 1868, 1869, -1, + 1869, 1093, 1091, -1, 1093, 1869, 1870, -1, + 1870, 1095, 1093, -1, 1095, 1870, 1871, -1, + 1871, 1097, 1095, -1, 1097, 1871, 1872, -1, + 1872, 1099, 1097, -1, 1099, 1872, 1873, -1, + 1873, 1101, 1099, -1, 1101, 1873, 1874, -1, + 1874, 1103, 1101, -1, 1103, 1874, 1875, -1, + 1875, 1105, 1103, -1, 1105, 1875, 1876, -1, + 1876, 1107, 1105, -1, 1107, 1876, 1877, -1, + 1877, 1109, 1107, -1, 1109, 1877, 1878, -1, + 1878, 1111, 1109, -1, 1111, 1878, 1879, -1, + 1879, 1113, 1111, -1, 1113, 1879, 1880, -1, + 1880, 1115, 1113, -1, 1115, 1880, 1881, -1, + 1881, 1117, 1115, -1, 1117, 1881, 1882, -1, + 1882, 1119, 1117, -1, 1119, 1882, 1883, -1, + 1883, 1121, 1119, -1, 1121, 1883, 1884, -1, + 1884, 1123, 1121, -1, 1123, 1884, 1885, -1, + 1885, 1125, 1123, -1, 1125, 1885, 1886, -1, + 1886, 1127, 1125, -1, 1127, 1886, 1887, -1, + 1887, 1129, 1127, -1, 1129, 1887, 1888, -1, + 1888, 1131, 1129, -1, 1131, 1888, 1889, -1, + 1889, 1133, 1131, -1, 1133, 1889, 1890, -1, + 1890, 1135, 1133, -1, 1135, 1890, 1891, -1, + 1891, 1137, 1135, -1, 1137, 1891, 1892, -1, + 1892, 1139, 1137, -1, 1139, 1892, 1893, -1, + 1893, 1141, 1139, -1, 1141, 1893, 1894, -1, + 1894, 1143, 1141, -1, 1143, 1894, 1895, -1, + 1895, 1145, 1143, -1, 1145, 1895, 1896, -1, + 1896, 1147, 1145, -1, 1147, 1896, 1897, -1, + 1897, 1149, 1147, -1, 1149, 1897, 1901, -1, + 1901, 1063, 1149, -1, 1063, 1901, 6412, -1, + 6413, 6412, 1901, -1, 6413, 6414, 6412, -1, + 6415, 6414, 6413, -1, 6413, 1901, 6415, -1, + 6415, 1901, 1899, -1, 1899, 6414, 6415, -1, + 1899, 1898, 6414, -1, 6416, 6417, 6418, -1, + 6418, 6419, 6416, -1, 6419, 6418, 6420, -1, + 6420, 6421, 6419, -1, 6421, 6420, 6422, -1, + 6422, 6423, 6421, -1, 6423, 6422, 6424, -1, + 6424, 6425, 6423, -1, 6425, 6424, 6426, -1, + 6426, 6427, 6425, -1, 6427, 6426, 6428, -1, + 6428, 6429, 6427, -1, 6429, 6428, 6430, -1, + 6429, 6430, 6431, -1, 6431, 6432, 6429, -1, + 6432, 6431, 6433, -1, 6433, 6434, 6432, -1, + 6434, 6433, 6435, -1, 6435, 6436, 6434, -1, + 6436, 6435, 6437, -1, 6437, 6438, 6436, -1, + 6438, 6437, 6439, -1, 6439, 6440, 6438, -1, + 6440, 6439, 6441, -1, 6441, 6442, 6440, -1, + 6442, 6441, 6443, -1, 6443, 6444, 6442, -1, + 6445, 6442, 6444, -1, 6444, 6446, 6445, -1, + 6447, 6446, 6444, -1, 6447, 6444, 6448, -1, + 6444, 6449, 6448, -1, 6444, 6443, 6449, -1, + 6450, 6451, 6452, -1, 6453, 6454, 6455, -1, + 6456, 6457, 6458, -1, 6456, 6458, 6459, -1, + 6459, 6460, 6456, -1, 6460, 6459, 6461, -1, + 6461, 6462, 6460, -1, 6462, 6461, 6463, -1, + 6463, 6464, 6462, -1, 6464, 6463, 6465, -1, + 6465, 6466, 6464, -1, 6466, 6465, 6467, -1, + 6467, 6468, 6466, -1, 6468, 6467, 6469, -1, + 6469, 6470, 6468, -1, 6470, 6469, 6471, -1, + 6471, 6472, 6470, -1, 6472, 6471, 6473, -1, + 6473, 6474, 6472, -1, 6474, 6473, 6475, -1, + 6475, 6476, 6474, -1, 6476, 6475, 6477, -1, + 6477, 6478, 6476, -1, 6478, 6477, 6479, -1, + 6479, 6480, 6478, -1, 6480, 6479, 6481, -1, + 6481, 6482, 6480, -1, 6482, 6481, 6483, -1, + 6483, 6484, 6482, -1, 6484, 6483, 6485, -1, + 6484, 6485, 6486, -1, 6486, 6487, 6484, -1, + 6487, 6486, 6488, -1, 6488, 6489, 6487, -1, + 6489, 6488, 6490, -1, 6490, 6491, 6489, -1, + 6491, 6490, 6492, -1, 6492, 6493, 6491, -1, + 6493, 6492, 6494, -1, 6494, 6495, 6493, -1, + 6495, 6494, 6496, -1, 6496, 6497, 6495, -1, + 6497, 6496, 6498, -1, 6498, 6499, 6497, -1, + 6499, 6498, 6500, -1, 6500, 6501, 6499, -1, + 6501, 6500, 6502, -1, 6502, 6503, 6501, -1, + 6503, 6502, 6504, -1, 6504, 6505, 6503, -1, + 6505, 6504, 6506, -1, 6506, 6507, 6505, -1, + 6507, 6506, 6508, -1, 6508, 6509, 6507, -1, + 6509, 6508, 6510, -1, 6510, 6511, 6509, -1, + 6511, 6510, 6512, -1, 6511, 6512, 6513, -1, + 6514, 6513, 6512, -1, 6513, 6514, 6515, -1, + 6516, 6517, 6518, -1, 6518, 6515, 6516, -1, + 6518, 6519, 6515, -1, 6519, 6513, 6515, -1, + 6519, 6511, 6513, -1, 6519, 6518, 6511, -1, + 6511, 6518, 6517, -1, 6517, 6509, 6511, -1, + 6509, 6517, 6520, -1, 6520, 6507, 6509, -1, + 6507, 6520, 6521, -1, 6521, 6505, 6507, -1, + 6505, 6521, 6522, -1, 6522, 6503, 6505, -1, + 6503, 6522, 6523, -1, 6523, 6501, 6503, -1, + 6501, 6523, 6524, -1, 6524, 6499, 6501, -1, + 6499, 6524, 6525, -1, 6525, 6497, 6499, -1, + 6497, 6525, 6526, -1, 6526, 6495, 6497, -1, + 6495, 6526, 6527, -1, 6527, 6493, 6495, -1, + 6493, 6527, 6528, -1, 6528, 6491, 6493, -1, + 6491, 6528, 6529, -1, 6529, 6489, 6491, -1, + 6489, 6529, 6530, -1, 6530, 6487, 6489, -1, + 6487, 6530, 6531, -1, 6531, 6484, 6487, -1, + 6531, 6482, 6484, -1, 6482, 6531, 6532, -1, + 6532, 6480, 6482, -1, 6480, 6532, 6533, -1, + 6533, 6478, 6480, -1, 6478, 6533, 6534, -1, + 6534, 6476, 6478, -1, 6476, 6534, 6535, -1, + 6535, 6474, 6476, -1, 6474, 6535, 6536, -1, + 6536, 6472, 6474, -1, 6472, 6536, 6537, -1, + 6537, 6470, 6472, -1, 6470, 6537, 6538, -1, + 6538, 6468, 6470, -1, 6468, 6538, 6539, -1, + 6539, 6466, 6468, -1, 6466, 6539, 6540, -1, + 6540, 6464, 6466, -1, 6464, 6540, 6541, -1, + 6541, 6462, 6464, -1, 6462, 6541, 6542, -1, + 6542, 6460, 6462, -1, 6460, 6542, 6543, -1, + 6543, 6456, 6460, -1, 6456, 6543, 6544, -1, + 6545, 6546, 6547, -1, 6547, 6546, 6548, -1, + 6549, 6548, 6550, -1, 6550, 6548, 6546, -1, + 6545, 6544, 6543, -1, 6544, 6545, 6547, -1, + 6544, 6547, 6551, -1, 6551, 6456, 6544, -1, + 6551, 6457, 6456, -1, 6457, 6551, 6547, -1, + 6457, 6547, 6552, -1, 6552, 6458, 6457, -1, + 6552, 6553, 6458, -1, 6553, 6554, 6458, -1, + 6453, 6458, 6554, -1, 6458, 6453, 6555, -1, + 6555, 6459, 6458, -1, 6459, 6555, 6556, -1, + 6556, 6461, 6459, -1, 6461, 6556, 6557, -1, + 6557, 6463, 6461, -1, 6463, 6557, 6558, -1, + 6558, 6465, 6463, -1, 6465, 6558, 6559, -1, + 6559, 6467, 6465, -1, 6467, 6559, 6560, -1, + 6560, 6469, 6467, -1, 6469, 6560, 6561, -1, + 6561, 6471, 6469, -1, 6471, 6561, 6562, -1, + 6562, 6473, 6471, -1, 6473, 6562, 6563, -1, + 6563, 6475, 6473, -1, 6475, 6563, 6564, -1, + 6564, 6477, 6475, -1, 6477, 6564, 6565, -1, + 6565, 6479, 6477, -1, 6479, 6565, 6566, -1, + 6566, 6481, 6479, -1, 6481, 6566, 6567, -1, + 6567, 6483, 6481, -1, 6483, 6567, 6568, -1, + 6568, 6485, 6483, -1, 6485, 6568, 6569, -1, + 6485, 6569, 6570, -1, 6570, 6486, 6485, -1, + 6486, 6570, 6571, -1, 6571, 6488, 6486, -1, + 6488, 6571, 6572, -1, 6572, 6490, 6488, -1, + 6490, 6572, 6573, -1, 6573, 6492, 6490, -1, + 6492, 6573, 6574, -1, 6574, 6494, 6492, -1, + 6494, 6574, 6575, -1, 6575, 6496, 6494, -1, + 6496, 6575, 6576, -1, 6576, 6498, 6496, -1, + 6498, 6576, 6577, -1, 6577, 6500, 6498, -1, + 6500, 6577, 6578, -1, 6578, 6502, 6500, -1, + 6502, 6578, 6579, -1, 6579, 6504, 6502, -1, + 6504, 6579, 6580, -1, 6580, 6506, 6504, -1, + 6506, 6580, 6581, -1, 6581, 6508, 6506, -1, + 6508, 6581, 6582, -1, 6582, 6510, 6508, -1, + 6510, 6582, 6583, -1, 6583, 6512, 6510, -1, + 6512, 6583, 6584, -1, 6584, 6585, 6512, -1, + 6586, 6585, 6584, -1, 6586, 6584, 6587, -1, + 6584, 6588, 6587, -1, 6584, 6589, 6588, -1, + 6589, 6584, 6583, -1, 6583, 6590, 6589, -1, + 6590, 6583, 6582, -1, 6582, 6591, 6590, -1, + 6591, 6582, 6581, -1, 6581, 6592, 6591, -1, + 6592, 6581, 6580, -1, 6580, 6593, 6592, -1, + 6593, 6580, 6579, -1, 6579, 6594, 6593, -1, + 6594, 6579, 6578, -1, 6578, 6595, 6594, -1, + 6595, 6578, 6577, -1, 6577, 6596, 6595, -1, + 6596, 6577, 6576, -1, 6576, 6597, 6596, -1, + 6597, 6576, 6575, -1, 6575, 6598, 6597, -1, + 6598, 6575, 6574, -1, 6574, 6599, 6598, -1, + 6599, 6574, 6573, -1, 6573, 6600, 6599, -1, + 6600, 6573, 6572, -1, 6572, 6601, 6600, -1, + 6601, 6572, 6571, -1, 6571, 6602, 6601, -1, + 6602, 6571, 6570, -1, 6570, 6603, 6602, -1, + 6603, 6570, 6569, -1, 6569, 6604, 6603, -1, + 6569, 6605, 6604, -1, 6605, 6569, 6568, -1, + 6568, 6606, 6605, -1, 6606, 6568, 6567, -1, + 6567, 6607, 6606, -1, 6607, 6567, 6566, -1, + 6566, 6608, 6607, -1, 6608, 6566, 6565, -1, + 6565, 6609, 6608, -1, 6609, 6565, 6564, -1, + 6564, 6610, 6609, -1, 6610, 6564, 6563, -1, + 6563, 6611, 6610, -1, 6611, 6563, 6562, -1, + 6562, 6612, 6611, -1, 6612, 6562, 6561, -1, + 6561, 6613, 6612, -1, 6613, 6561, 6560, -1, + 6560, 6614, 6613, -1, 6614, 6560, 6559, -1, + 6559, 6615, 6614, -1, 6615, 6559, 6558, -1, + 6558, 6616, 6615, -1, 6616, 6558, 6557, -1, + 6557, 6617, 6616, -1, 6617, 6557, 6556, -1, + 6556, 6618, 6617, -1, 6618, 6556, 6555, -1, + 6555, 6619, 6618, -1, 6619, 6555, 6453, -1, + 6453, 6455, 6619, -1, 6620, 6621, 6455, -1, + 6622, 6455, 6621, -1, 6455, 6622, 6623, -1, + 6623, 6619, 6455, -1, 6619, 6623, 6624, -1, + 6624, 6618, 6619, -1, 6618, 6624, 6625, -1, + 6625, 6617, 6618, -1, 6617, 6625, 6626, -1, + 6626, 6616, 6617, -1, 6616, 6626, 6627, -1, + 6627, 6615, 6616, -1, 6615, 6627, 6628, -1, + 6628, 6614, 6615, -1, 6614, 6628, 6629, -1, + 6629, 6613, 6614, -1, 6613, 6629, 6630, -1, + 6630, 6612, 6613, -1, 6612, 6630, 6631, -1, + 6631, 6611, 6612, -1, 6611, 6631, 6632, -1, + 6632, 6610, 6611, -1, 6610, 6632, 6633, -1, + 6633, 6609, 6610, -1, 6609, 6633, 6634, -1, + 6634, 6608, 6609, -1, 6608, 6634, 6635, -1, + 6635, 6607, 6608, -1, 6607, 6635, 6636, -1, + 6636, 6606, 6607, -1, 6606, 6636, 6637, -1, + 6637, 6605, 6606, -1, 6605, 6637, 6638, -1, + 6638, 6604, 6605, -1, 6639, 6603, 6604, -1, + 6603, 6639, 6640, -1, 6640, 6602, 6603, -1, + 6602, 6640, 6641, -1, 6641, 6601, 6602, -1, + 6601, 6641, 6642, -1, 6642, 6600, 6601, -1, + 6600, 6642, 6643, -1, 6643, 6599, 6600, -1, + 6599, 6643, 6644, -1, 6644, 6598, 6599, -1, + 6598, 6644, 6645, -1, 6645, 6597, 6598, -1, + 6597, 6645, 6646, -1, 6646, 6596, 6597, -1, + 6596, 6646, 6647, -1, 6647, 6595, 6596, -1, + 6595, 6647, 6648, -1, 6648, 6594, 6595, -1, + 6594, 6648, 6649, -1, 6649, 6593, 6594, -1, + 6593, 6649, 6650, -1, 6650, 6592, 6593, -1, + 6592, 6650, 6651, -1, 6651, 6591, 6592, -1, + 6591, 6651, 6652, -1, 6652, 6590, 6591, -1, + 6590, 6652, 6653, -1, 6653, 6589, 6590, -1, + 6589, 6653, 6654, -1, 6654, 6588, 6589, -1, + 6588, 6654, 6655, -1, 6655, 6656, 6588, -1, + 6656, 6657, 6658, -1, 6656, 6655, 6657, -1, + 6659, 6657, 6655, -1, 6659, 6658, 6657, -1, + 6659, 6660, 6658, -1, 6659, 6655, 6660, -1, + 6661, 6660, 6655, -1, 6655, 6662, 6661, -1, + 6662, 6655, 6654, -1, 6654, 6663, 6662, -1, + 6663, 6654, 6653, -1, 6653, 6664, 6663, -1, + 6664, 6653, 6652, -1, 6652, 6665, 6664, -1, + 6665, 6652, 6651, -1, 6651, 6666, 6665, -1, + 6666, 6651, 6650, -1, 6650, 6667, 6666, -1, + 6667, 6650, 6649, -1, 6649, 6668, 6667, -1, + 6668, 6649, 6648, -1, 6648, 6669, 6668, -1, + 6669, 6648, 6647, -1, 6647, 6670, 6669, -1, + 6670, 6647, 6646, -1, 6646, 6671, 6670, -1, + 6671, 6646, 6645, -1, 6645, 6672, 6671, -1, + 6672, 6645, 6644, -1, 6644, 6673, 6672, -1, + 6673, 6644, 6643, -1, 6643, 6674, 6673, -1, + 6674, 6643, 6642, -1, 6642, 6675, 6674, -1, + 6675, 6642, 6641, -1, 6641, 6676, 6675, -1, + 6676, 6641, 6640, -1, 6640, 6677, 6676, -1, + 6677, 6640, 6639, -1, 6639, 6678, 6677, -1, + 6679, 6680, 6678, -1, 6679, 6681, 6680, -1, + 6638, 6682, 6681, -1, 6682, 6638, 6637, -1, + 6637, 6683, 6682, -1, 6683, 6637, 6636, -1, + 6636, 6684, 6683, -1, 6684, 6636, 6635, -1, + 6635, 6685, 6684, -1, 6685, 6635, 6634, -1, + 6634, 6686, 6685, -1, 6686, 6634, 6633, -1, + 6633, 6687, 6686, -1, 6687, 6633, 6632, -1, + 6632, 6688, 6687, -1, 6688, 6632, 6631, -1, + 6631, 6689, 6688, -1, 6689, 6631, 6630, -1, + 6630, 6690, 6689, -1, 6690, 6630, 6629, -1, + 6629, 6691, 6690, -1, 6691, 6629, 6628, -1, + 6628, 6692, 6691, -1, 6692, 6628, 6627, -1, + 6627, 6693, 6692, -1, 6693, 6627, 6626, -1, + 6626, 6694, 6693, -1, 6694, 6626, 6625, -1, + 6625, 6695, 6694, -1, 6695, 6625, 6624, -1, + 6624, 6696, 6695, -1, 6696, 6624, 6623, -1, + 6623, 6697, 6696, -1, 6697, 6623, 6622, -1, + 6622, 6698, 6697, -1, 6699, 6700, 6698, -1, + 6699, 6698, 6701, -1, 6698, 6622, 6701, -1, + 6702, 6450, 6701, -1, 6702, 6701, 6622, -1, + 6702, 6622, 6621, -1, 6621, 6450, 6702, -1, + 6621, 6620, 6450, -1, 6620, 6451, 6450, -1, + 6451, 6620, 6455, -1, 6451, 6455, 6454, -1, + 6454, 6452, 6451, -1, 6454, 6703, 6452, -1, + 6703, 6454, 6453, -1, 6703, 6453, 6554, -1, + 6554, 6452, 6703, -1, 6554, 6553, 6452, -1, + 6553, 6552, 6452, -1, 6452, 6552, 6547, -1, + 6548, 6704, 6705, -1, 6706, 6704, 6548, -1, + 6704, 6706, 6707, -1, 6704, 6707, 6708, -1, + 6708, 6705, 6704, -1, 6708, 6709, 6705, -1, + 6710, 6711, 6712, -1, 6710, 6712, 6705, -1, + 6710, 6705, 6709, -1, 6709, 6711, 6710, -1, + 6709, 6708, 6711, -1, 6711, 6708, 6707, -1, + 6711, 6707, 6713, -1, 6713, 6714, 6711, -1, + 6714, 6713, 6715, -1, 6715, 6716, 6714, -1, + 6716, 6715, 6717, -1, 6717, 6718, 6716, -1, + 6718, 6717, 6719, -1, 6719, 6720, 6718, -1, + 6720, 6719, 6721, -1, 6721, 6722, 6720, -1, + 6722, 6721, 6723, -1, 6723, 6724, 6722, -1, + 6724, 6723, 6725, -1, 6725, 6726, 6724, -1, + 6726, 6725, 6727, -1, 6727, 6728, 6726, -1, + 6728, 6727, 6729, -1, 6729, 6730, 6728, -1, + 6730, 6729, 6731, -1, 6730, 6731, 6732, -1, + 6732, 6733, 6730, -1, 6733, 6732, 6734, -1, + 6734, 6735, 6733, -1, 6735, 6734, 6736, -1, + 6736, 6737, 6735, -1, 6737, 6736, 6738, -1, + 6738, 6739, 6737, -1, 6739, 6738, 6740, -1, + 6740, 6741, 6739, -1, 6741, 6740, 6742, -1, + 6742, 6743, 6741, -1, 6743, 6742, 6744, -1, + 6744, 6745, 6743, -1, 6745, 6744, 6746, -1, + 6746, 6747, 6745, -1, 6747, 6746, 6748, -1, + 6748, 6749, 6747, -1, 6749, 6748, 6750, -1, + 6749, 6750, 6751, -1, 6752, 6751, 6750, -1, + 6751, 6752, 6753, -1, 6754, 6753, 6755, -1, + 6754, 6756, 6753, -1, 6756, 6751, 6753, -1, + 6756, 6749, 6751, -1, 6756, 6754, 6749, -1, + 6754, 6755, 6749, -1, 6449, 6749, 6755, -1, + 6449, 6747, 6749, -1, 6747, 6449, 6443, -1, + 6443, 6745, 6747, -1, 6745, 6443, 6441, -1, + 6441, 6743, 6745, -1, 6743, 6441, 6439, -1, + 6439, 6741, 6743, -1, 6741, 6439, 6437, -1, + 6437, 6739, 6741, -1, 6739, 6437, 6435, -1, + 6435, 6737, 6739, -1, 6737, 6435, 6433, -1, + 6433, 6735, 6737, -1, 6735, 6433, 6431, -1, + 6431, 6733, 6735, -1, 6733, 6431, 6430, -1, + 6430, 6730, 6733, -1, 6430, 6728, 6730, -1, + 6728, 6430, 6428, -1, 6428, 6726, 6728, -1, + 6726, 6428, 6426, -1, 6426, 6724, 6726, -1, + 6724, 6426, 6424, -1, 6424, 6722, 6724, -1, + 6722, 6424, 6422, -1, 6422, 6720, 6722, -1, + 6720, 6422, 6420, -1, 6420, 6718, 6720, -1, + 6718, 6420, 6418, -1, 6418, 6716, 6718, -1, + 6716, 6418, 6417, -1, 6417, 6714, 6716, -1, + 6714, 6417, 6757, -1, 6757, 6711, 6714, -1, + 6757, 6712, 6711, -1, 6758, 6712, 6757, -1, + 6758, 6705, 6712, -1, 6758, 6759, 6705, -1, + 6758, 6757, 6759, -1, 6760, 6759, 6757, -1, + 6760, 6757, 6417, -1, 6417, 6416, 6760, -1, + 6760, 6761, 6762, -1, 6761, 6760, 6416, -1, + 6416, 6763, 6761, -1, 6763, 6416, 6419, -1, + 6419, 6764, 6763, -1, 6764, 6419, 6421, -1, + 6421, 6765, 6764, -1, 6765, 6421, 6423, -1, + 6423, 6766, 6765, -1, 6766, 6423, 6425, -1, + 6425, 6767, 6766, -1, 6767, 6425, 6427, -1, + 6427, 6768, 6767, -1, 6768, 6427, 6429, -1, + 6768, 6429, 6432, -1, 6432, 6769, 6768, -1, + 6769, 6432, 6434, -1, 6434, 6770, 6769, -1, + 6770, 6434, 6436, -1, 6436, 6771, 6770, -1, + 6771, 6436, 6438, -1, 6438, 6772, 6771, -1, + 6772, 6438, 6440, -1, 6440, 6773, 6772, -1, + 6773, 6440, 6442, -1, 6442, 6445, 6773, -1, + 113, 6773, 6445, -1, 6773, 113, 6774, -1, + 6774, 6772, 6773, -1, 6772, 6774, 6775, -1, + 6775, 6771, 6772, -1, 6771, 6775, 6776, -1, + 6776, 6770, 6771, -1, 6770, 6776, 6777, -1, + 6777, 6769, 6770, -1, 6769, 6777, 6778, -1, + 6778, 6768, 6769, -1, 6778, 6767, 6768, -1, + 6767, 6778, 6779, -1, 6779, 6766, 6767, -1, + 6766, 6779, 6780, -1, 6780, 6765, 6766, -1, + 6765, 6780, 6781, -1, 6781, 6764, 6765, -1, + 6764, 6781, 6782, -1, 6782, 6763, 6764, -1, + 6763, 6782, 6783, -1, 6783, 6761, 6763, -1, + 6783, 6784, 6761, -1, 6785, 6786, 6787, -1, + 6785, 6784, 6786, -1, 6785, 6761, 6784, -1, + 6785, 6787, 6761, -1, 6787, 6762, 6761, -1, + 6762, 6787, 6786, -1, 6762, 6786, 6788, -1, + 6788, 6760, 6762, -1, 6788, 6759, 6760, -1, + 6759, 6788, 6786, -1, 6786, 6705, 6759, -1, + 6414, 6789, 6790, -1, 6789, 6414, 1898, -1, + 1898, 1900, 6789, -1, 1900, 1902, 6789, -1, + 6791, 6789, 1902, -1, 6791, 6790, 6789, -1, + 6792, 6790, 6791, -1, 6791, 1902, 6792, -1, + 6792, 1902, 1904, -1, 1904, 6790, 6792, -1, + 1904, 1903, 6790, -1, 6793, 6794, 6795, -1, + 6793, 6796, 6794, -1, 6796, 6793, 6797, -1, + 6798, 6799, 6800, -1, 6798, 6793, 6799, -1, + 6798, 6797, 6793, -1, 6798, 6800, 6797, -1, + 6801, 6797, 6800, -1, 6801, 6796, 6797, -1, + 6801, 6802, 6796, -1, 6802, 6801, 6800, -1, + 6800, 6803, 6802, -1, 6790, 6804, 6805, -1, + 6804, 6790, 1903, -1, 1903, 1905, 6804, -1, + 1905, 1906, 6804, -1, 6806, 6804, 1906, -1, + 6806, 6805, 6804, -1, 6807, 6805, 6806, -1, + 6806, 1906, 6807, -1, 6807, 1906, 1908, -1, + 1908, 6805, 6807, -1, 1908, 6808, 6805, -1, + 6808, 1908, 1907, -1, 6808, 1907, 1910, -1, + 1910, 6805, 6808, -1, 1910, 6809, 6805, -1, + 6809, 1910, 1909, -1, 6809, 1909, 2190, -1, + 2190, 2193, 6809, -1, 2193, 6805, 6809, -1, + 6810, 2194, 2291, -1, 6811, 6810, 2291, -1, + 2291, 2238, 6811, -1, 6811, 2238, 2236, -1, + 2236, 6810, 6811, -1, 2236, 2235, 6810, -1, + 6812, 6813, 6814, -1, 6813, 6812, 6810, -1, + 6813, 6810, 2235, -1, 2235, 2237, 6813, -1, + 2237, 6814, 6813, -1, 6814, 2237, 2240, -1, + 2240, 6815, 6814, -1, 6815, 2240, 2242, -1, + 2242, 6816, 6815, -1, 6816, 2242, 2244, -1, + 2244, 6817, 6816, -1, 6817, 2244, 2246, -1, + 2246, 6818, 6817, -1, 6818, 2246, 2248, -1, + 2248, 6819, 6818, -1, 6819, 2248, 2250, -1, + 2250, 6820, 6819, -1, 6820, 2250, 2252, -1, + 2252, 6821, 6820, -1, 6821, 2252, 2254, -1, + 2254, 6822, 6821, -1, 6822, 2254, 2256, -1, + 2256, 6823, 6822, -1, 6823, 2256, 2258, -1, + 2258, 6824, 6823, -1, 6824, 2258, 2260, -1, + 2260, 6825, 6824, -1, 6825, 2260, 2262, -1, + 2262, 6826, 6825, -1, 6826, 2262, 2264, -1, + 2264, 6827, 6826, -1, 6827, 2264, 2266, -1, + 2266, 2269, 6827, -1, 6827, 2269, 6828, -1, + 6828, 6826, 6827, -1, 6826, 6828, 6829, -1, + 6829, 6825, 6826, -1, 6825, 6829, 6830, -1, + 6830, 6824, 6825, -1, 6824, 6830, 6831, -1, + 6831, 6823, 6824, -1, 6823, 6831, 6832, -1, + 6832, 6822, 6823, -1, 6822, 6832, 6833, -1, + 6833, 6821, 6822, -1, 6821, 6833, 6834, -1, + 6834, 6820, 6821, -1, 6820, 6834, 6835, -1, + 6835, 6819, 6820, -1, 6819, 6835, 6836, -1, + 6836, 6818, 6819, -1, 6818, 6836, 6837, -1, + 6837, 6817, 6818, -1, 6817, 6837, 6838, -1, + 6838, 6816, 6817, -1, 6816, 6838, 6839, -1, + 6839, 6815, 6816, -1, 6815, 6839, 6840, -1, + 6840, 6814, 6815, -1, 6840, 6841, 6814, -1, + 6842, 6841, 6840, -1, 6843, 6842, 6840, -1, + 6843, 6840, 6844, -1, 805, 6844, 6840, -1, + 805, 6840, 6839, -1, 6839, 1061, 805, -1, + 1061, 6839, 6838, -1, 6838, 1060, 1061, -1, + 1060, 6838, 6837, -1, 6837, 1059, 1060, -1, + 1059, 6837, 6836, -1, 6836, 1058, 1059, -1, + 1058, 6836, 6835, -1, 6835, 1057, 1058, -1, + 1057, 6835, 6834, -1, 6834, 1056, 1057, -1, + 1056, 6834, 6833, -1, 6833, 1055, 1056, -1, + 1055, 6833, 6832, -1, 6832, 1054, 1055, -1, + 1054, 6832, 6831, -1, 6831, 1053, 1054, -1, + 1053, 6831, 6830, -1, 6830, 1052, 1053, -1, + 1052, 6830, 6829, -1, 6829, 1051, 1052, -1, + 1051, 6829, 6828, -1, 6828, 1050, 1051, -1, + 1050, 6828, 2269, -1, 2269, 1049, 1050, -1, + 1049, 2269, 2270, -1, 2270, 1048, 1049, -1, + 1048, 2270, 2272, -1, 2272, 1047, 1048, -1, + 1047, 2272, 2287, -1, 2287, 1046, 1047, -1, + 1046, 2287, 2285, -1, 2285, 1045, 1046, -1, + 1045, 2285, 2283, -1, 2283, 1044, 1045, -1, + 1044, 2283, 2281, -1, 2281, 1043, 1044, -1, + 1043, 2281, 2279, -1, 2279, 1042, 1043, -1, + 1042, 2279, 2277, -1, 2277, 1041, 1042, -1, + 1041, 2277, 2275, -1, 2275, 923, 1041, -1, + 923, 2275, 2274, -1, 2274, 924, 923, -1, + 924, 2274, 2293, -1, 2293, 926, 924, -1, + 926, 2293, 2294, -1, 2294, 928, 926, -1, + 928, 2294, 2295, -1, 2295, 930, 928, -1, + 930, 2295, 2296, -1, 2296, 932, 930, -1, + 932, 2296, 2297, -1, 2297, 934, 932, -1, + 934, 2297, 2298, -1, 2298, 936, 934, -1, + 936, 2298, 2299, -1, 2299, 938, 936, -1, + 938, 2299, 2300, -1, 2300, 940, 938, -1, + 940, 2300, 2301, -1, 2301, 942, 940, -1, + 942, 2301, 2302, -1, 2302, 944, 942, -1, + 944, 2302, 2303, -1, 2303, 946, 944, -1, + 946, 2303, 2304, -1, 2304, 948, 946, -1, + 948, 2304, 2305, -1, 2305, 950, 948, -1, + 950, 2305, 2306, -1, 2306, 952, 950, -1, + 952, 2306, 2307, -1, 2307, 954, 952, -1, + 954, 2307, 2308, -1, 2308, 956, 954, -1, + 956, 2308, 2309, -1, 2309, 958, 956, -1, + 958, 2309, 2310, -1, 2310, 960, 958, -1, + 960, 2310, 2311, -1, 2311, 962, 960, -1, + 962, 2311, 2312, -1, 2312, 921, 962, -1, + 921, 2312, 2313, -1, 2313, 919, 921, -1, + 919, 2313, 2314, -1, 2314, 917, 919, -1, + 917, 2314, 2315, -1, 2315, 915, 917, -1, + 915, 2315, 2316, -1, 2316, 914, 915, -1, + 914, 2316, 2317, -1, 914, 2317, 2318, -1, + 2318, 912, 914, -1, 912, 2318, 2319, -1, + 2319, 910, 912, -1, 910, 2319, 2320, -1, + 2320, 908, 910, -1, 908, 2320, 2321, -1, + 2321, 905, 908, -1, 905, 2321, 2322, -1, + 2322, 906, 905, -1, 906, 2322, 2323, -1, + 2323, 6845, 906, -1, 6845, 2323, 2324, -1, + 2324, 6846, 6845, -1, 6846, 2324, 2325, -1, + 2325, 6847, 6846, -1, 6847, 2325, 2326, -1, + 2326, 6848, 6847, -1, 6848, 2326, 2327, -1, + 2327, 6849, 6848, -1, 6849, 2327, 2328, -1, + 2328, 6850, 6849, -1, 6850, 2328, 2329, -1, + 2329, 6851, 6850, -1, 6851, 2329, 2330, -1, + 2330, 6852, 6851, -1, 6852, 2330, 2331, -1, + 2331, 6853, 6852, -1, 6853, 2331, 2332, -1, + 2332, 6854, 6853, -1, 6854, 2332, 2333, -1, + 2333, 6855, 6854, -1, 6855, 2333, 2334, -1, + 2334, 6856, 6855, -1, 6856, 2334, 2335, -1, + 2335, 6857, 6856, -1, 6857, 2335, 2336, -1, + 2336, 6858, 6857, -1, 6858, 2336, 2337, -1, + 2337, 6859, 6858, -1, 6859, 2337, 2338, -1, + 2338, 6860, 6859, -1, 6860, 2338, 2339, -1, + 2339, 6861, 6860, -1, 6861, 2339, 2340, -1, + 2340, 6862, 6861, -1, 6862, 2340, 2341, -1, + 2341, 6863, 6862, -1, 6863, 2341, 2342, -1, + 2342, 6864, 6863, -1, 6864, 2342, 2343, -1, + 2343, 6865, 6864, -1, 6865, 2343, 2344, -1, + 2344, 6866, 6865, -1, 6866, 2344, 2345, -1, + 2345, 6867, 6866, -1, 6867, 2345, 2346, -1, + 2346, 6868, 6867, -1, 6868, 2346, 2347, -1, + 2347, 6869, 6868, -1, 6869, 2347, 2348, -1, + 2348, 6870, 6869, -1, 6870, 2348, 2349, -1, + 2349, 6871, 6870, -1, 6871, 2349, 2350, -1, + 2350, 6872, 6871, -1, 6872, 2350, 2351, -1, + 2351, 6873, 6872, -1, 6873, 2351, 2352, -1, + 2352, 6874, 6873, -1, 6874, 2352, 2353, -1, + 2353, 6875, 6874, -1, 6875, 2353, 2354, -1, + 2354, 6876, 6875, -1, 6876, 2354, 2355, -1, + 2355, 6877, 6876, -1, 6877, 2355, 2356, -1, + 2356, 6878, 6877, -1, 6878, 2356, 2357, -1, + 2357, 6879, 6878, -1, 6879, 2357, 2358, -1, + 2358, 6880, 6879, -1, 6880, 2358, 2359, -1, + 2359, 6881, 6880, -1, 6881, 2359, 2360, -1, + 2360, 6882, 6881, -1, 6882, 2360, 2361, -1, + 2361, 6883, 6882, -1, 6883, 2361, 2362, -1, + 2362, 6884, 6883, -1, 6884, 2362, 2363, -1, + 2363, 6885, 6884, -1, 6885, 2363, 2364, -1, + 2364, 6886, 6885, -1, 6886, 2364, 2365, -1, + 2365, 6887, 6886, -1, 6887, 2365, 2366, -1, + 2366, 6888, 6887, -1, 6888, 2366, 2367, -1, + 2367, 6889, 6888, -1, 6889, 2367, 2368, -1, + 2368, 6890, 6889, -1, 6890, 2368, 2369, -1, + 2369, 6891, 6890, -1, 6891, 2369, 2370, -1, + 2370, 6166, 6891, -1, 6892, 6891, 6166, -1, + 6892, 6166, 2519, -1, 6892, 2519, 2518, -1, + 2518, 6891, 6892, -1, 2518, 2520, 6891, -1, + 6891, 2520, 2406, -1, 2406, 6890, 6891, -1, + 6890, 2406, 2408, -1, 2408, 6889, 6890, -1, + 6889, 2408, 2436, -1, 2436, 6888, 6889, -1, + 6888, 2436, 2434, -1, 2434, 6887, 6888, -1, + 6887, 2434, 2432, -1, 2432, 6886, 6887, -1, + 6886, 2432, 2430, -1, 2430, 6885, 6886, -1, + 6885, 2430, 2428, -1, 2428, 6884, 6885, -1, + 6884, 2428, 2426, -1, 2426, 6883, 6884, -1, + 6883, 2426, 2424, -1, 2424, 6882, 6883, -1, + 6882, 2424, 2422, -1, 2422, 6881, 6882, -1, + 6881, 2422, 2420, -1, 2420, 6880, 6881, -1, + 6880, 2420, 2418, -1, 2418, 6879, 6880, -1, + 6879, 2418, 2416, -1, 2416, 6878, 6879, -1, + 6878, 2416, 2414, -1, 2414, 6877, 6878, -1, + 6877, 2414, 2412, -1, 2412, 6876, 6877, -1, + 6876, 2412, 2409, -1, 2409, 6875, 6876, -1, + 6875, 2409, 2411, -1, 2411, 6874, 6875, -1, + 6874, 2411, 2440, -1, 2440, 6873, 6874, -1, + 6873, 2440, 2441, -1, 2441, 6872, 6873, -1, + 6872, 2441, 2512, -1, 2512, 6871, 6872, -1, + 6871, 2512, 2442, -1, 2442, 6870, 6871, -1, + 6870, 2442, 2445, -1, 2445, 6869, 6870, -1, + 6869, 2445, 2447, -1, 2447, 6868, 6869, -1, + 6868, 2447, 2449, -1, 2449, 6867, 6868, -1, + 6867, 2449, 2451, -1, 2451, 6866, 6867, -1, + 6866, 2451, 2453, -1, 2453, 6865, 6866, -1, + 6865, 2453, 2455, -1, 2455, 6864, 6865, -1, + 6864, 2455, 2456, -1, 2456, 6863, 6864, -1, + 6863, 2456, 2458, -1, 2458, 6862, 6863, -1, + 6862, 2458, 6893, -1, 6893, 6861, 6862, -1, + 6861, 6893, 6894, -1, 6894, 6860, 6861, -1, + 6860, 6894, 6895, -1, 6895, 6859, 6860, -1, + 6859, 6895, 6896, -1, 6896, 6858, 6859, -1, + 6858, 6896, 6897, -1, 6897, 6857, 6858, -1, + 6857, 6897, 6898, -1, 6898, 6856, 6857, -1, + 6856, 6898, 6899, -1, 6899, 6855, 6856, -1, + 6855, 6899, 6900, -1, 6900, 6854, 6855, -1, + 6854, 6900, 6901, -1, 6901, 6853, 6854, -1, + 6853, 6901, 6902, -1, 6902, 6852, 6853, -1, + 6852, 6902, 6903, -1, 6903, 6851, 6852, -1, + 6851, 6903, 6904, -1, 6904, 6850, 6851, -1, + 6850, 6904, 6905, -1, 6905, 6849, 6850, -1, + 6849, 6905, 6906, -1, 6906, 6848, 6849, -1, + 6848, 6906, 6907, -1, 6907, 6847, 6848, -1, + 6847, 6907, 6908, -1, 6908, 6846, 6847, -1, + 6846, 6908, 6909, -1, 6909, 6845, 6846, -1, + 6845, 6909, 6910, -1, 6910, 906, 6845, -1, + 6910, 904, 906, -1, 6910, 902, 904, -1, + 902, 6910, 6909, -1, 6909, 900, 902, -1, + 900, 6909, 6908, -1, 6908, 898, 900, -1, + 898, 6908, 6907, -1, 6907, 896, 898, -1, + 896, 6907, 6906, -1, 6906, 894, 896, -1, + 894, 6906, 6905, -1, 6905, 892, 894, -1, + 892, 6905, 6904, -1, 6904, 890, 892, -1, + 890, 6904, 6903, -1, 6903, 888, 890, -1, + 888, 6903, 6902, -1, 6902, 886, 888, -1, + 886, 6902, 6901, -1, 6901, 884, 886, -1, + 884, 6901, 6900, -1, 6900, 882, 884, -1, + 882, 6900, 6899, -1, 6899, 880, 882, -1, + 880, 6899, 6898, -1, 6898, 878, 880, -1, + 878, 6898, 6897, -1, 6897, 876, 878, -1, + 876, 6897, 6896, -1, 6896, 874, 876, -1, + 874, 6896, 6895, -1, 6895, 872, 874, -1, + 872, 6895, 6894, -1, 6894, 870, 872, -1, + 870, 6894, 6893, -1, 6893, 867, 870, -1, + 867, 6893, 2458, -1, 2458, 868, 867, -1, + 868, 2458, 2457, -1, 2457, 2459, 868, -1, + 2459, 6911, 868, -1, 6911, 2459, 2460, -1, + 2460, 6912, 6911, -1, 6912, 2460, 2461, -1, + 2461, 6913, 6912, -1, 6913, 2461, 2462, -1, + 2462, 6914, 6913, -1, 6914, 2462, 2463, -1, + 2463, 6915, 6914, -1, 6915, 2463, 2464, -1, + 2464, 6916, 6915, -1, 6916, 2464, 2465, -1, + 2465, 6917, 6916, -1, 6917, 2465, 2466, -1, + 2466, 6918, 6917, -1, 6918, 2466, 2468, -1, + 2468, 6919, 6918, -1, 6919, 2468, 2470, -1, + 2470, 6920, 6919, -1, 6920, 2470, 2472, -1, + 2472, 6921, 6920, -1, 6921, 2472, 2474, -1, + 2474, 6922, 6921, -1, 6922, 2474, 2476, -1, + 2476, 6923, 6922, -1, 6923, 2476, 2478, -1, + 2478, 6924, 6923, -1, 6924, 2478, 2480, -1, + 2480, 6925, 6924, -1, 6925, 2480, 2482, -1, + 2482, 6926, 6925, -1, 6926, 2482, 2484, -1, + 2484, 6927, 6926, -1, 6927, 2484, 2486, -1, + 2486, 6928, 6927, -1, 6928, 2486, 2488, -1, + 2488, 6929, 6928, -1, 6929, 2488, 2490, -1, + 2490, 6930, 6929, -1, 6930, 2490, 2492, -1, + 2492, 6931, 6930, -1, 6931, 2492, 802, -1, + 6931, 802, 800, -1, 6932, 6931, 800, -1, + 800, 798, 6932, -1, 6932, 798, 797, -1, + 797, 6931, 6932, -1, 797, 799, 6931, -1, + 796, 6931, 799, -1, 796, 6930, 6931, -1, + 6930, 796, 793, -1, 793, 6929, 6930, -1, + 6929, 793, 792, -1, 792, 6928, 6929, -1, + 6928, 792, 791, -1, 791, 6927, 6928, -1, + 6927, 791, 790, -1, 790, 6926, 6927, -1, + 6926, 790, 789, -1, 789, 6925, 6926, -1, + 6925, 789, 788, -1, 788, 6924, 6925, -1, + 6924, 788, 787, -1, 787, 6923, 6924, -1, + 6923, 787, 786, -1, 786, 6922, 6923, -1, + 6922, 786, 785, -1, 785, 6921, 6922, -1, + 6921, 785, 784, -1, 784, 6920, 6921, -1, + 6920, 784, 783, -1, 783, 6919, 6920, -1, + 6919, 783, 782, -1, 782, 6918, 6919, -1, + 6918, 782, 781, -1, 781, 6917, 6918, -1, + 6917, 781, 780, -1, 780, 6916, 6917, -1, + 6916, 780, 779, -1, 779, 6915, 6916, -1, + 6915, 779, 778, -1, 778, 6914, 6915, -1, + 6914, 778, 777, -1, 777, 6913, 6914, -1, + 6913, 777, 776, -1, 776, 6912, 6913, -1, + 6912, 776, 775, -1, 775, 6911, 6912, -1, + 6911, 775, 716, -1, 716, 868, 6911, -1, + 868, 716, 715, -1, 715, 866, 868, -1, + 866, 715, 718, -1, 718, 869, 866, -1, + 869, 718, 720, -1, 720, 871, 869, -1, + 871, 720, 722, -1, 722, 873, 871, -1, + 873, 722, 724, -1, 724, 875, 873, -1, + 875, 724, 726, -1, 726, 877, 875, -1, + 877, 726, 728, -1, 728, 879, 877, -1, + 879, 728, 730, -1, 730, 881, 879, -1, + 881, 730, 732, -1, 732, 883, 881, -1, + 883, 732, 734, -1, 734, 885, 883, -1, + 885, 734, 736, -1, 736, 887, 885, -1, + 887, 736, 738, -1, 738, 889, 887, -1, + 889, 738, 740, -1, 740, 891, 889, -1, + 891, 740, 742, -1, 742, 893, 891, -1, + 893, 742, 744, -1, 744, 895, 893, -1, + 895, 744, 746, -1, 746, 897, 895, -1, + 897, 746, 748, -1, 748, 899, 897, -1, + 899, 748, 750, -1, 750, 901, 899, -1, + 901, 750, 752, -1, 752, 903, 901, -1, + 752, 971, 903, -1, 752, 751, 971, -1, + 971, 751, 756, -1, 971, 756, 6933, -1, + 6933, 972, 971, -1, 972, 6933, 6934, -1, + 6934, 973, 972, -1, 973, 6934, 6935, -1, + 6935, 974, 973, -1, 6935, 975, 974, -1, + 975, 6935, 6936, -1, 6936, 976, 975, -1, + 976, 6936, 6937, -1, 6937, 977, 976, -1, + 977, 6937, 6938, -1, 6938, 980, 977, -1, + 6939, 6940, 6941, -1, 6942, 6943, 6940, -1, + 6944, 6945, 6940, -1, 6944, 6940, 6943, -1, + 6943, 6946, 6944, -1, 6943, 6942, 6946, -1, + 6947, 6948, 672, -1, 6947, 6949, 6948, -1, + 6949, 6947, 6950, -1, 6950, 6951, 6949, -1, + 6951, 6950, 6952, -1, 6952, 6953, 6951, -1, + 6953, 6952, 6954, -1, 6954, 6955, 6953, -1, + 6955, 6954, 6956, -1, 6956, 6957, 6955, -1, + 6957, 6956, 6958, -1, 6958, 6959, 6957, -1, + 6959, 6958, 6960, -1, 6960, 6961, 6959, -1, + 6961, 6960, 6962, -1, 6962, 6963, 6961, -1, + 6963, 6962, 6964, -1, 6964, 6965, 6963, -1, + 6965, 6964, 6966, -1, 6966, 6967, 6965, -1, + 6967, 6966, 6968, -1, 6968, 6969, 6967, -1, + 6969, 6968, 6970, -1, 6970, 6971, 6969, -1, + 6971, 6970, 6972, -1, 6972, 6973, 6971, -1, + 6973, 6972, 6974, -1, 6974, 6975, 6973, -1, + 6975, 6974, 6976, -1, 6976, 6977, 6975, -1, + 6977, 6976, 6978, -1, 6978, 6979, 6977, -1, + 6979, 6978, 6980, -1, 6980, 6981, 6979, -1, + 6981, 6980, 6982, -1, 6982, 6983, 6981, -1, + 6983, 6982, 6984, -1, 6984, 6985, 6983, -1, + 6985, 6984, 6986, -1, 6986, 6987, 6985, -1, + 6987, 6986, 6988, -1, 6988, 6989, 6987, -1, + 6989, 6988, 6990, -1, 6990, 6991, 6989, -1, + 6991, 6990, 6992, -1, 6992, 6993, 6991, -1, + 6993, 6992, 6994, -1, 6994, 6995, 6993, -1, + 6995, 6994, 6996, -1, 6996, 6997, 6995, -1, + 6997, 6996, 6998, -1, 6998, 6999, 6997, -1, + 6999, 6998, 7000, -1, 7000, 7001, 6999, -1, + 7001, 7000, 7002, -1, 7002, 7003, 7001, -1, + 7003, 7002, 7004, -1, 7004, 7005, 7003, -1, + 7005, 7004, 7006, -1, 7006, 7007, 7005, -1, + 7007, 7006, 7008, -1, 7008, 7009, 7007, -1, + 7009, 7008, 7010, -1, 7010, 7011, 7009, -1, + 7011, 7010, 7012, -1, 7012, 7013, 7011, -1, + 7013, 7012, 7014, -1, 7014, 7015, 7013, -1, + 7015, 7014, 7016, -1, 7016, 7017, 7015, -1, + 7017, 7016, 7018, -1, 7018, 7019, 7017, -1, + 7019, 7018, 6946, -1, 6946, 7020, 7019, -1, + 6946, 7021, 7020, -1, 7021, 6946, 6942, -1, + 6942, 6940, 7021, -1, 7021, 6940, 6939, -1, + 6939, 7020, 7021, -1, 6939, 6941, 7020, -1, + 7020, 6941, 7022, -1, 7020, 7022, 7023, -1, + 7023, 7019, 7020, -1, 7019, 7023, 7024, -1, + 7024, 7017, 7019, -1, 7017, 7024, 7025, -1, + 7025, 7015, 7017, -1, 7015, 7025, 7026, -1, + 7026, 7013, 7015, -1, 7013, 7026, 7027, -1, + 7027, 7011, 7013, -1, 7011, 7027, 7028, -1, + 7028, 7009, 7011, -1, 7009, 7028, 7029, -1, + 7029, 7007, 7009, -1, 7007, 7029, 7030, -1, + 7030, 7005, 7007, -1, 7005, 7030, 7031, -1, + 7031, 7003, 7005, -1, 7003, 7031, 7032, -1, + 7032, 7001, 7003, -1, 7001, 7032, 7033, -1, + 7033, 6999, 7001, -1, 6999, 7033, 7034, -1, + 7034, 6997, 6999, -1, 6997, 7034, 7035, -1, + 7035, 6995, 6997, -1, 6995, 7035, 7036, -1, + 7036, 6993, 6995, -1, 6993, 7036, 7037, -1, + 7037, 6991, 6993, -1, 6991, 7037, 7038, -1, + 7038, 6989, 6991, -1, 6989, 7038, 7039, -1, + 7039, 6987, 6989, -1, 6987, 7039, 7040, -1, + 7040, 6985, 6987, -1, 6985, 7040, 7041, -1, + 7041, 6983, 6985, -1, 6983, 7041, 7042, -1, + 7042, 6981, 6983, -1, 6981, 7042, 7043, -1, + 7043, 6979, 6981, -1, 6979, 7043, 7044, -1, + 7044, 6977, 6979, -1, 6977, 7044, 7045, -1, + 7045, 6975, 6977, -1, 6975, 7045, 7046, -1, + 7046, 6973, 6975, -1, 6973, 7046, 7047, -1, + 7047, 6971, 6973, -1, 6971, 7047, 7048, -1, + 7048, 6969, 6971, -1, 6969, 7048, 7049, -1, + 7049, 6967, 6969, -1, 6967, 7049, 7050, -1, + 7050, 6965, 6967, -1, 6965, 7050, 7051, -1, + 7051, 6963, 6965, -1, 6963, 7051, 7052, -1, + 7052, 6961, 6963, -1, 6961, 7052, 7053, -1, + 7053, 6959, 6961, -1, 6959, 7053, 7054, -1, + 7054, 6957, 6959, -1, 6957, 7054, 7055, -1, + 7055, 6955, 6957, -1, 6955, 7055, 7056, -1, + 7056, 6953, 6955, -1, 6953, 7056, 7057, -1, + 7057, 6951, 6953, -1, 6951, 7057, 7058, -1, + 7058, 6949, 6951, -1, 6949, 7058, 7059, -1, + 7059, 6948, 6949, -1, 6948, 7059, 980, -1, + 980, 6938, 6948, -1, 6938, 672, 6948, -1, + 6938, 670, 672, -1, 670, 6938, 6937, -1, + 6937, 668, 670, -1, 668, 6937, 6936, -1, + 6936, 667, 668, -1, 667, 6936, 6935, -1, + 667, 6935, 6934, -1, 6934, 665, 667, -1, + 665, 6934, 6933, -1, 6933, 663, 665, -1, + 663, 6933, 756, -1, 756, 659, 663, -1, + 659, 756, 755, -1, 755, 660, 659, -1, + 660, 755, 7060, -1, 7060, 7061, 660, -1, + 7061, 7060, 7062, -1, 7062, 7063, 7061, -1, + 7063, 7062, 7064, -1, 7064, 7065, 7063, -1, + 7065, 7064, 7066, -1, 7066, 7067, 7065, -1, + 7067, 7066, 7068, -1, 7068, 7069, 7067, -1, + 7069, 7068, 7070, -1, 7070, 7071, 7069, -1, + 7071, 7070, 7072, -1, 7072, 7073, 7071, -1, + 7073, 7072, 7074, -1, 7074, 7075, 7073, -1, + 7075, 7074, 7076, -1, 7076, 7077, 7075, -1, + 7077, 7076, 7078, -1, 7078, 7079, 7077, -1, + 7079, 7078, 7080, -1, 7080, 7081, 7079, -1, + 7081, 7080, 7082, -1, 7082, 7083, 7081, -1, + 7083, 7082, 7084, -1, 7084, 7085, 7083, -1, + 7085, 7084, 7086, -1, 7086, 7087, 7085, -1, + 7087, 7086, 7088, -1, 7088, 7089, 7087, -1, + 7089, 7088, 7090, -1, 7090, 7091, 7089, -1, + 7091, 7090, 7092, -1, 7092, 7093, 7091, -1, + 7093, 7092, 7094, -1, 7094, 7095, 7093, -1, + 7095, 7094, 7096, -1, 7096, 7097, 7095, -1, + 7098, 7099, 7100, -1, 7098, 7101, 7099, -1, + 7101, 7098, 7102, -1, 7102, 7103, 7101, -1, + 7103, 7102, 7104, -1, 7104, 7105, 7103, -1, + 7105, 7104, 7106, -1, 7106, 7107, 7105, -1, + 7107, 7106, 7108, -1, 7108, 7109, 7107, -1, + 7109, 7108, 7110, -1, 7110, 7111, 7109, -1, + 7111, 7110, 7112, -1, 7112, 7113, 7111, -1, + 7113, 7112, 7114, -1, 7114, 7115, 7113, -1, + 7115, 7114, 7116, -1, 7116, 7117, 7115, -1, + 7117, 7116, 7118, -1, 7118, 7119, 7117, -1, + 7119, 7118, 7120, -1, 7120, 7121, 7119, -1, + 7121, 7120, 7122, -1, 7122, 7123, 7121, -1, + 7123, 7122, 7124, -1, 7124, 7125, 7123, -1, + 7125, 7124, 7126, -1, 7126, 7127, 7125, -1, + 7127, 7126, 7128, -1, 7128, 7129, 7127, -1, + 7129, 7128, 7130, -1, 7130, 7131, 7129, -1, + 7131, 7130, 7097, -1, 7097, 7096, 7131, -1, + 7096, 7132, 7131, -1, 7132, 7096, 7094, -1, + 7094, 7133, 7132, -1, 7133, 7094, 7092, -1, + 7092, 7134, 7133, -1, 7134, 7092, 7090, -1, + 7090, 7135, 7134, -1, 7135, 7090, 7088, -1, + 7088, 7136, 7135, -1, 7136, 7088, 7086, -1, + 7086, 7137, 7136, -1, 7137, 7086, 7084, -1, + 7084, 7138, 7137, -1, 7138, 7084, 7082, -1, + 7082, 7139, 7138, -1, 7139, 7082, 7080, -1, + 7080, 7140, 7139, -1, 7140, 7080, 7078, -1, + 7078, 7141, 7140, -1, 7141, 7078, 7076, -1, + 7076, 7142, 7141, -1, 7142, 7076, 7074, -1, + 7074, 7143, 7142, -1, 7143, 7074, 7072, -1, + 7072, 7144, 7143, -1, 7144, 7072, 7070, -1, + 7070, 7145, 7144, -1, 7145, 7070, 7068, -1, + 7068, 7146, 7145, -1, 7146, 7068, 7066, -1, + 7066, 7147, 7146, -1, 7147, 7066, 7064, -1, + 7064, 7148, 7147, -1, 7148, 7064, 7062, -1, + 7062, 7149, 7148, -1, 7149, 7062, 7060, -1, + 7060, 7150, 7149, -1, 7150, 7060, 755, -1, + 7150, 755, 754, -1, 7150, 754, 757, -1, + 757, 7149, 7150, -1, 7149, 757, 758, -1, + 758, 7148, 7149, -1, 7148, 758, 759, -1, + 759, 7147, 7148, -1, 7147, 759, 760, -1, + 760, 7146, 7147, -1, 7146, 760, 761, -1, + 761, 7145, 7146, -1, 7145, 761, 762, -1, + 762, 7144, 7145, -1, 7144, 762, 763, -1, + 763, 7143, 7144, -1, 7143, 763, 764, -1, + 764, 7142, 7143, -1, 7142, 764, 765, -1, + 765, 7141, 7142, -1, 7141, 765, 766, -1, + 766, 7140, 7141, -1, 7140, 766, 767, -1, + 767, 7139, 7140, -1, 7139, 767, 768, -1, + 768, 7138, 7139, -1, 7138, 768, 769, -1, + 769, 7137, 7138, -1, 7137, 769, 770, -1, + 770, 7136, 7137, -1, 7136, 770, 771, -1, + 771, 7135, 7136, -1, 7135, 771, 772, -1, + 772, 7134, 7135, -1, 7134, 772, 773, -1, + 773, 7133, 7134, -1, 7133, 773, 774, -1, + 774, 7132, 7133, -1, 7132, 774, 713, -1, + 713, 712, 7132, -1, 712, 7131, 7132, -1, + 7131, 712, 710, -1, 710, 7129, 7131, -1, + 7129, 710, 708, -1, 708, 7127, 7129, -1, + 7127, 708, 706, -1, 706, 7125, 7127, -1, + 7125, 706, 704, -1, 704, 7123, 7125, -1, + 7123, 704, 702, -1, 702, 7121, 7123, -1, + 7121, 702, 700, -1, 700, 7119, 7121, -1, + 7119, 700, 698, -1, 698, 7117, 7119, -1, + 7117, 698, 696, -1, 696, 7115, 7117, -1, + 7115, 696, 694, -1, 694, 7113, 7115, -1, + 7113, 694, 692, -1, 692, 7111, 7113, -1, + 7111, 692, 690, -1, 690, 7109, 7111, -1, + 7109, 690, 688, -1, 688, 7107, 7109, -1, + 7107, 688, 686, -1, 686, 7105, 7107, -1, + 7105, 686, 684, -1, 684, 7103, 7105, -1, + 7103, 684, 682, -1, 682, 7101, 7103, -1, + 7101, 682, 680, -1, 680, 7099, 7101, -1, + 7099, 680, 675, -1, 7099, 675, 674, -1, + 674, 7151, 7099, -1, 7151, 674, 676, -1, + 7151, 676, 7152, -1, 7152, 7099, 7151, -1, + 7152, 7100, 7099, -1, 7100, 7152, 676, -1, + 7100, 676, 7153, -1, 7153, 7098, 7100, -1, + 7153, 7154, 7098, -1, 7153, 7155, 7154, -1, + 7155, 7153, 676, -1, 7156, 676, 677, -1, + 677, 7157, 7156, -1, 7157, 677, 678, -1, + 7157, 678, 795, -1, 795, 7156, 7157, -1, + 795, 794, 7156, -1, 7158, 7156, 794, -1, + 7158, 794, 796, -1, 7158, 796, 799, -1, + 799, 7156, 7158, -1, 7156, 799, 798, -1, + 798, 7159, 7160, -1, 7159, 798, 801, -1, + 801, 802, 7159, -1, 802, 2494, 7159, -1, + 7161, 7159, 2494, -1, 7161, 7160, 7159, -1, + 7162, 7160, 7161, -1, 7161, 2494, 7162, -1, + 7162, 2494, 2496, -1, 2496, 7160, 7162, -1, + 2496, 7163, 7160, -1, 7163, 2496, 2495, -1, + 7163, 2495, 2514, -1, 2514, 7160, 7163, -1, + 7160, 2514, 2372, -1, 7164, 7165, 7155, -1, + 7164, 658, 7166, -1, 7167, 7168, 7169, -1, + 7168, 7167, 7170, -1, 7170, 7171, 7168, -1, + 7171, 7170, 7172, -1, 7172, 7173, 7171, -1, + 7173, 7172, 7174, -1, 7174, 7175, 7173, -1, + 7175, 7174, 7176, -1, 7176, 7177, 7175, -1, + 7177, 7176, 7178, -1, 7178, 7179, 7177, -1, + 7179, 7178, 7180, -1, 7180, 7181, 7179, -1, + 7181, 7180, 7182, -1, 7182, 7183, 7181, -1, + 7183, 7182, 7184, -1, 7184, 7185, 7183, -1, + 7185, 7184, 7186, -1, 7186, 7187, 7185, -1, + 7187, 7186, 7188, -1, 7188, 7189, 7187, -1, + 7189, 7188, 7190, -1, 7190, 7191, 7189, -1, + 7191, 7190, 7192, -1, 7192, 7193, 7191, -1, + 7193, 7192, 7194, -1, 7194, 7195, 7193, -1, + 7195, 7194, 7196, -1, 7196, 7197, 7195, -1, + 7197, 7196, 7198, -1, 7198, 7199, 7197, -1, + 7200, 7201, 7199, -1, 7199, 7198, 7200, -1, + 7202, 7203, 7204, -1, 7202, 7205, 7203, -1, + 7206, 7207, 7208, -1, 7206, 7208, 7209, -1, + 7209, 7210, 7206, -1, 7210, 7209, 7211, -1, + 7211, 7212, 7210, -1, 7212, 7211, 7213, -1, + 7213, 7214, 7212, -1, 7213, 7215, 7214, -1, + 7215, 7213, 7216, -1, 7216, 7217, 7215, -1, + 7217, 7216, 7218, -1, 7218, 7219, 7217, -1, + 7219, 7218, 7205, -1, 7205, 7202, 7219, -1, + 7220, 7221, 7222, -1, 7223, 7224, 7225, -1, + 7225, 7226, 7223, -1, 7226, 7225, 7227, -1, + 7227, 7228, 7226, -1, 7228, 7227, 7229, -1, + 7229, 7230, 7228, -1, 7230, 7229, 7231, -1, + 7231, 7232, 7230, -1, 7232, 7231, 7233, -1, + 7233, 7234, 7232, -1, 7234, 7233, 7235, -1, + 7235, 7236, 7234, -1, 7236, 7235, 7237, -1, + 7237, 7238, 7236, -1, 7238, 7237, 7239, -1, + 7239, 7240, 7238, -1, 7240, 7239, 7241, -1, + 7241, 7242, 7240, -1, 7242, 7241, 7243, -1, + 7243, 7244, 7242, -1, 7244, 7243, 7245, -1, + 7245, 7246, 7244, -1, 7246, 7245, 7247, -1, + 7247, 7248, 7246, -1, 7248, 7247, 7249, -1, + 7249, 7250, 7248, -1, 7250, 7249, 7251, -1, + 7251, 7252, 7250, -1, 7252, 7251, 7253, -1, + 7253, 7254, 7252, -1, 7254, 7253, 7255, -1, + 7255, 7256, 7254, -1, 7256, 7255, 7257, -1, + 7257, 7258, 7256, -1, 7258, 7257, 7259, -1, + 7259, 7260, 7258, -1, 7260, 7259, 7261, -1, + 7261, 7262, 7260, -1, 7262, 7261, 7263, -1, + 7263, 7264, 7262, -1, 7264, 7263, 7221, -1, + 7221, 7220, 7264, -1, 7220, 7202, 7264, -1, + 7220, 7219, 7202, -1, 7220, 7222, 7219, -1, + 7265, 7219, 7222, -1, 7265, 7217, 7219, -1, + 7217, 7265, 7266, -1, 7266, 7215, 7217, -1, + 7215, 7266, 7267, -1, 7267, 7214, 7215, -1, + 7214, 7267, 7268, -1, 7214, 7268, 7269, -1, + 7269, 7212, 7214, -1, 7212, 7269, 7270, -1, + 7270, 7210, 7212, -1, 7210, 7270, 7271, -1, + 7271, 7206, 7210, -1, 7271, 7272, 7206, -1, + 7273, 7274, 7275, -1, 7274, 7273, 7276, -1, + 7276, 7277, 7274, -1, 7277, 7276, 7278, -1, + 7278, 7279, 7277, -1, 7279, 7278, 7280, -1, + 7280, 7281, 7279, -1, 7281, 7280, 7282, -1, + 7282, 7283, 7281, -1, 7283, 7282, 7284, -1, + 7284, 7285, 7283, -1, 7285, 7284, 7286, -1, + 7286, 7287, 7285, -1, 7287, 7286, 7288, -1, + 7288, 7289, 7287, -1, 7289, 7288, 7290, -1, + 7290, 7291, 7289, -1, 7291, 7290, 7292, -1, + 7292, 7293, 7291, -1, 7293, 7292, 7294, -1, + 7294, 7295, 7293, -1, 7295, 7294, 7296, -1, + 7296, 7297, 7295, -1, 7297, 7296, 7298, -1, + 7298, 7299, 7297, -1, 7299, 7298, 7300, -1, + 7300, 7301, 7299, -1, 7301, 7300, 7302, -1, + 7302, 7303, 7301, -1, 7303, 7302, 7304, -1, + 7304, 7305, 7303, -1, 7305, 7304, 7306, -1, + 7306, 7307, 7305, -1, 7307, 7306, 7308, -1, + 7308, 7309, 7307, -1, 7309, 7308, 7310, -1, + 7310, 7311, 7309, -1, 7311, 7310, 7312, -1, + 7312, 7313, 7311, -1, 7313, 7312, 7272, -1, + 7272, 7314, 7313, -1, 7314, 7272, 7271, -1, + 7314, 7271, 7200, -1, 7314, 7200, 7198, -1, + 7198, 7313, 7314, -1, 7313, 7198, 7196, -1, + 7196, 7311, 7313, -1, 7311, 7196, 7194, -1, + 7194, 7309, 7311, -1, 7309, 7194, 7192, -1, + 7192, 7307, 7309, -1, 7307, 7192, 7190, -1, + 7190, 7305, 7307, -1, 7305, 7190, 7188, -1, + 7188, 7303, 7305, -1, 7303, 7188, 7186, -1, + 7186, 7301, 7303, -1, 7301, 7186, 7184, -1, + 7184, 7299, 7301, -1, 7299, 7184, 7182, -1, + 7182, 7297, 7299, -1, 7297, 7182, 7180, -1, + 7180, 7295, 7297, -1, 7295, 7180, 7178, -1, + 7178, 7293, 7295, -1, 7293, 7178, 7176, -1, + 7176, 7291, 7293, -1, 7291, 7176, 7174, -1, + 7174, 7289, 7291, -1, 7289, 7174, 7172, -1, + 7172, 7287, 7289, -1, 7287, 7172, 7170, -1, + 7170, 7285, 7287, -1, 7285, 7170, 7167, -1, + 7167, 7283, 7285, -1, 7283, 7167, 7169, -1, + 7169, 7281, 7283, -1, 7281, 7169, 7315, -1, + 7315, 7279, 7281, -1, 7279, 7315, 7316, -1, + 7316, 7277, 7279, -1, 7277, 7316, 7317, -1, + 7317, 7274, 7277, -1, 7274, 7317, 7318, -1, + 7318, 7275, 7274, -1, 7275, 7318, 7319, -1, + 7319, 7320, 7275, -1, 7320, 7319, 7321, -1, + 7321, 7322, 7320, -1, 7322, 7321, 7323, -1, + 7323, 7324, 7322, -1, 7324, 7323, 7325, -1, + 7325, 7326, 7324, -1, 7326, 7325, 7327, -1, + 7327, 7328, 7326, -1, 7328, 7327, 7329, -1, + 7329, 7330, 7328, -1, 7330, 7329, 7331, -1, + 7331, 7332, 7330, -1, 7332, 7331, 7333, -1, + 7333, 7334, 7332, -1, 7334, 7333, 7335, -1, + 7335, 7336, 7334, -1, 7336, 7335, 7337, -1, + 7337, 7338, 7336, -1, 7338, 7337, 7339, -1, + 7338, 7339, 7340, -1, 7341, 7342, 7164, -1, + 7342, 7341, 7339, -1, 7341, 7340, 7339, -1, + 7341, 7164, 7340, -1, 7340, 7164, 7166, -1, + 7166, 7338, 7340, -1, 7166, 7343, 7338, -1, + 7343, 7166, 658, -1, 7343, 658, 551, -1, + 551, 553, 7343, -1, 553, 7338, 7343, -1, + 553, 7336, 7338, -1, 7336, 553, 655, -1, + 655, 7334, 7336, -1, 7334, 655, 653, -1, + 653, 7332, 7334, -1, 7332, 653, 651, -1, + 651, 7330, 7332, -1, 7330, 651, 649, -1, + 649, 7328, 7330, -1, 7328, 649, 647, -1, + 647, 7326, 7328, -1, 7326, 647, 645, -1, + 645, 7324, 7326, -1, 7324, 645, 643, -1, + 643, 7322, 7324, -1, 7322, 643, 641, -1, + 641, 7320, 7322, -1, 7320, 641, 610, -1, + 610, 7275, 7320, -1, 7275, 610, 609, -1, + 609, 7273, 7275, -1, 7273, 609, 612, -1, + 612, 7276, 7273, -1, 7276, 612, 614, -1, + 614, 7278, 7276, -1, 7278, 614, 616, -1, + 616, 7280, 7278, -1, 7280, 616, 618, -1, + 618, 7282, 7280, -1, 7282, 618, 580, -1, + 580, 7284, 7282, -1, 7284, 580, 578, -1, + 578, 7286, 7284, -1, 7286, 578, 576, -1, + 576, 7288, 7286, -1, 7288, 576, 574, -1, + 574, 7290, 7288, -1, 7290, 574, 572, -1, + 572, 7292, 7290, -1, 7292, 572, 570, -1, + 570, 7294, 7292, -1, 7294, 570, 568, -1, + 568, 7296, 7294, -1, 7296, 568, 566, -1, + 566, 7298, 7296, -1, 7298, 566, 564, -1, + 564, 7300, 7298, -1, 7300, 564, 562, -1, + 562, 7302, 7300, -1, 7302, 562, 560, -1, + 560, 7304, 7302, -1, 7304, 560, 558, -1, + 558, 7306, 7304, -1, 7306, 558, 556, -1, + 556, 7308, 7306, -1, 7308, 556, 555, -1, + 555, 7310, 7308, -1, 7310, 555, 7344, -1, + 7344, 7312, 7310, -1, 7312, 7344, 7345, -1, + 7345, 7272, 7312, -1, 7345, 7206, 7272, -1, + 7345, 7207, 7206, -1, 7207, 7345, 7344, -1, + 7344, 7346, 7207, -1, 7346, 7344, 555, -1, + 555, 554, 7346, -1, 7346, 554, 619, -1, + 7346, 619, 7347, -1, 7347, 7207, 7346, -1, + 7347, 7208, 7207, -1, 7347, 7348, 7208, -1, + 7348, 7347, 619, -1, 619, 620, 7348, -1, + 7348, 620, 7349, -1, 7348, 7349, 7350, -1, + 7350, 7208, 7348, -1, 7208, 7350, 7351, -1, + 7351, 7209, 7208, -1, 7209, 7351, 7352, -1, + 7352, 7211, 7209, -1, 7211, 7352, 7353, -1, + 7353, 7213, 7211, -1, 7353, 7216, 7213, -1, + 7216, 7353, 7354, -1, 7354, 7218, 7216, -1, + 7218, 7354, 7355, -1, 7355, 7205, 7218, -1, + 7205, 7355, 7356, -1, 7356, 7203, 7205, -1, + 7203, 7356, 7357, -1, 7203, 7357, 7358, -1, + 7359, 7358, 7357, -1, 7359, 7360, 7358, -1, + 7360, 7359, 7361, -1, 7361, 7362, 7360, -1, + 7362, 7361, 7363, -1, 7363, 7364, 7362, -1, + 7364, 7363, 7365, -1, 7365, 7366, 7364, -1, + 7366, 7365, 7367, -1, 7367, 7368, 7366, -1, + 7368, 7367, 7369, -1, 7369, 7370, 7368, -1, + 7370, 7369, 7371, -1, 7371, 7372, 7370, -1, + 7372, 7371, 7373, -1, 7373, 7374, 7372, -1, + 7374, 7373, 7375, -1, 7375, 7376, 7374, -1, + 7376, 7375, 7377, -1, 7377, 7378, 7376, -1, + 7378, 7377, 7379, -1, 7379, 7380, 7378, -1, + 7380, 7379, 7381, -1, 7381, 7382, 7380, -1, + 7382, 7381, 7383, -1, 7383, 7384, 7382, -1, + 7384, 7383, 7385, -1, 7385, 7386, 7384, -1, + 7386, 7385, 7387, -1, 7387, 7388, 7386, -1, + 7388, 7387, 7389, -1, 7389, 7390, 7388, -1, + 7390, 7389, 7391, -1, 7391, 7392, 7390, -1, + 7392, 7391, 7393, -1, 7393, 7394, 7392, -1, + 7394, 7393, 7395, -1, 7395, 7396, 7394, -1, + 7396, 7395, 7397, -1, 7397, 7398, 7396, -1, + 7398, 7397, 7399, -1, 7399, 7400, 7398, -1, + 7401, 7402, 7403, -1, 7403, 7404, 7401, -1, + 7404, 7403, 7405, -1, 7405, 7406, 7404, -1, + 7406, 7405, 7407, -1, 7407, 7408, 7406, -1, + 7408, 7407, 7409, -1, 7409, 7410, 7408, -1, + 7410, 7409, 7411, -1, 7411, 7412, 7410, -1, + 7412, 7411, 7413, -1, 7413, 7400, 7412, -1, + 7400, 7413, 550, -1, 550, 7398, 7400, -1, + 7398, 550, 549, -1, 549, 7396, 7398, -1, + 7396, 549, 547, -1, 547, 7394, 7396, -1, + 7394, 547, 545, -1, 545, 7392, 7394, -1, + 7392, 545, 543, -1, 543, 7390, 7392, -1, + 7390, 543, 541, -1, 541, 7388, 7390, -1, + 7388, 541, 539, -1, 539, 7386, 7388, -1, + 7386, 539, 537, -1, 537, 7384, 7386, -1, + 7384, 537, 536, -1, 536, 7382, 7384, -1, + 7382, 536, 7414, -1, 7414, 7380, 7382, -1, + 7380, 7414, 7415, -1, 7415, 7378, 7380, -1, + 7378, 7415, 7416, -1, 7416, 7376, 7378, -1, + 7376, 7416, 7417, -1, 7417, 7374, 7376, -1, + 7374, 7417, 7418, -1, 7418, 7372, 7374, -1, + 7372, 7418, 7419, -1, 7419, 7370, 7372, -1, + 7370, 7419, 7420, -1, 7420, 7368, 7370, -1, + 7368, 7420, 7421, -1, 7421, 7366, 7368, -1, + 7366, 7421, 7422, -1, 7422, 7364, 7366, -1, + 7364, 7422, 7423, -1, 7423, 7362, 7364, -1, + 7362, 7423, 7424, -1, 7424, 7360, 7362, -1, + 7360, 7424, 7425, -1, 7425, 7358, 7360, -1, + 7358, 7425, 7426, -1, 7426, 7203, 7358, -1, + 7426, 7204, 7203, -1, 7426, 7427, 7204, -1, + 7427, 7426, 7425, -1, 7425, 7428, 7427, -1, + 7428, 7425, 7424, -1, 7424, 7429, 7428, -1, + 7429, 7424, 7423, -1, 7423, 7430, 7429, -1, + 7430, 7423, 7422, -1, 7422, 7431, 7430, -1, + 7431, 7422, 7421, -1, 7421, 7432, 7431, -1, + 7432, 7421, 7420, -1, 7420, 7433, 7432, -1, + 7433, 7420, 7419, -1, 7419, 7434, 7433, -1, + 7434, 7419, 7418, -1, 7418, 7435, 7434, -1, + 7435, 7418, 7417, -1, 7417, 7436, 7435, -1, + 7436, 7417, 7416, -1, 7416, 7437, 7436, -1, + 7437, 7416, 7415, -1, 7415, 7438, 7437, -1, + 7438, 7415, 7414, -1, 7414, 7439, 7438, -1, + 7439, 7414, 536, -1, 536, 535, 7439, -1, + 7439, 535, 7440, -1, 7440, 7438, 7439, -1, + 7438, 7440, 7441, -1, 7441, 7437, 7438, -1, + 7437, 7441, 7442, -1, 7442, 7436, 7437, -1, + 7436, 7442, 7443, -1, 7443, 7435, 7436, -1, + 7435, 7443, 7444, -1, 7444, 7434, 7435, -1, + 7434, 7444, 7445, -1, 7445, 7433, 7434, -1, + 7433, 7445, 7446, -1, 7446, 7432, 7433, -1, + 7432, 7446, 7447, -1, 7447, 7431, 7432, -1, + 7431, 7447, 7448, -1, 7448, 7430, 7431, -1, + 7430, 7448, 7449, -1, 7449, 7429, 7430, -1, + 7429, 7449, 7450, -1, 7450, 7428, 7429, -1, + 7428, 7450, 7451, -1, 7451, 7427, 7428, -1, + 7427, 7451, 7452, -1, 7452, 7204, 7427, -1, + 7204, 7452, 7453, -1, 7453, 7202, 7204, -1, + 7453, 7264, 7202, -1, 7453, 7262, 7264, -1, + 7262, 7453, 7452, -1, 7452, 7260, 7262, -1, + 7260, 7452, 7451, -1, 7451, 7258, 7260, -1, + 7258, 7451, 7450, -1, 7450, 7256, 7258, -1, + 7256, 7450, 7449, -1, 7449, 7254, 7256, -1, + 7254, 7449, 7448, -1, 7448, 7252, 7254, -1, + 7252, 7448, 7447, -1, 7447, 7250, 7252, -1, + 7250, 7447, 7446, -1, 7446, 7248, 7250, -1, + 7248, 7446, 7445, -1, 7445, 7246, 7248, -1, + 7246, 7445, 7444, -1, 7444, 7244, 7246, -1, + 7244, 7444, 7443, -1, 7443, 7242, 7244, -1, + 7242, 7443, 7442, -1, 7442, 7240, 7242, -1, + 7240, 7442, 7441, -1, 7441, 7238, 7240, -1, + 7238, 7441, 7440, -1, 7440, 7236, 7238, -1, + 7236, 7440, 535, -1, 535, 7234, 7236, -1, + 7234, 535, 538, -1, 538, 7232, 7234, -1, + 7232, 538, 540, -1, 540, 7230, 7232, -1, + 7230, 540, 542, -1, 542, 7228, 7230, -1, + 7228, 542, 544, -1, 544, 7226, 7228, -1, + 7226, 544, 546, -1, 546, 7223, 7226, -1, + 7223, 546, 548, -1, 548, 7224, 7223, -1, + 7224, 548, 550, -1, 550, 7454, 7224, -1, + 7454, 550, 7413, -1, 7413, 7455, 7454, -1, + 7455, 7413, 7411, -1, 7411, 7456, 7455, -1, + 7456, 7411, 7409, -1, 7409, 7457, 7456, -1, + 7457, 7409, 7407, -1, 7407, 7458, 7457, -1, + 7458, 7407, 7405, -1, 7405, 7459, 7458, -1, + 7459, 7405, 7403, -1, 7403, 7460, 7459, -1, + 7460, 7403, 7402, -1, 7402, 7461, 7460, -1, + 7462, 7463, 3, -1, 7462, 3, 7461, -1, + 7461, 7402, 7462, -1, 7464, 7465, 7466, -1, + 7462, 7466, 7465, -1, 7466, 7462, 7402, -1, + 7402, 7401, 7466, -1, 7467, 7466, 7401, -1, + 7401, 7468, 7467, -1, 7468, 7401, 7404, -1, + 7404, 7469, 7468, -1, 7469, 7404, 7406, -1, + 7406, 7470, 7469, -1, 7470, 7406, 7408, -1, + 7408, 7471, 7470, -1, 7471, 7408, 7410, -1, + 7410, 7472, 7471, -1, 7472, 7410, 7412, -1, + 7412, 7473, 7472, -1, 7473, 7412, 7400, -1, + 7400, 7399, 7473, -1, 7399, 7474, 533, -1, + 533, 7473, 7399, -1, 7473, 533, 531, -1, + 531, 7472, 7473, -1, 7472, 531, 529, -1, + 529, 7471, 7472, -1, 7471, 529, 527, -1, + 527, 7470, 7471, -1, 7470, 527, 525, -1, + 525, 7469, 7470, -1, 7469, 525, 524, -1, + 524, 7468, 7469, -1, 7468, 524, 7475, -1, + 7475, 7467, 7468, -1, 7475, 7476, 7467, -1, + 7477, 7476, 7475, -1, 7477, 7475, 7478, -1, + 7475, 7479, 7478, -1, 7479, 7475, 524, -1, + 524, 523, 7479, -1, 7479, 7480, 7481, -1, + 7480, 7479, 523, -1, 523, 7482, 7480, -1, + 7482, 523, 526, -1, 526, 7483, 7482, -1, + 7483, 526, 528, -1, 528, 7484, 7483, -1, + 7484, 528, 530, -1, 530, 7485, 7484, -1, + 7485, 530, 532, -1, 532, 487, 7485, -1, + 487, 532, 534, -1, 534, 522, 487, -1, + 522, 534, 7486, -1, 7486, 521, 522, -1, + 521, 7486, 7487, -1, 7487, 520, 521, -1, + 520, 7487, 7488, -1, 7488, 519, 520, -1, + 519, 7488, 7489, -1, 7489, 518, 519, -1, + 518, 7489, 7490, -1, 7490, 517, 518, -1, + 517, 7490, 7491, -1, 7491, 516, 517, -1, + 516, 7491, 7492, -1, 7492, 515, 516, -1, + 515, 7492, 7493, -1, 7493, 514, 515, -1, + 514, 7493, 7494, -1, 7494, 513, 514, -1, + 513, 7494, 7495, -1, 7495, 512, 513, -1, + 512, 7495, 7496, -1, 7496, 511, 512, -1, + 511, 7496, 7497, -1, 7497, 510, 511, -1, + 510, 7497, 7498, -1, 7498, 509, 510, -1, + 509, 7498, 7499, -1, 7499, 508, 509, -1, + 508, 7499, 7500, -1, 7500, 507, 508, -1, + 507, 7500, 7501, -1, 7501, 506, 507, -1, + 506, 7501, 7502, -1, 7502, 432, 506, -1, + 432, 7502, 7503, -1, 7503, 430, 432, -1, + 430, 7503, 7504, -1, 7504, 428, 430, -1, + 7504, 429, 428, -1, 7504, 7505, 429, -1, + 7505, 7504, 7503, -1, 7503, 7506, 7505, -1, + 7506, 7503, 7502, -1, 7502, 7507, 7506, -1, + 7507, 7502, 7501, -1, 7501, 7508, 7507, -1, + 7508, 7501, 7500, -1, 7500, 7509, 7508, -1, + 7509, 7500, 7499, -1, 7499, 7510, 7509, -1, + 7510, 7499, 7498, -1, 7498, 7511, 7510, -1, + 7511, 7498, 7497, -1, 7497, 7512, 7511, -1, + 7512, 7497, 7496, -1, 7496, 7513, 7512, -1, + 7513, 7496, 7495, -1, 7495, 7514, 7513, -1, + 7514, 7495, 7494, -1, 7494, 7515, 7514, -1, + 7515, 7494, 7493, -1, 7493, 7516, 7515, -1, + 7516, 7493, 7492, -1, 7492, 7517, 7516, -1, + 7517, 7492, 7491, -1, 7491, 7518, 7517, -1, + 7518, 7491, 7490, -1, 7490, 7519, 7518, -1, + 7519, 7490, 7489, -1, 7489, 7520, 7519, -1, + 7520, 7489, 7488, -1, 7488, 7521, 7520, -1, + 7521, 7488, 7487, -1, 7487, 7522, 7521, -1, + 7522, 7487, 7486, -1, 7486, 7523, 7522, -1, + 7523, 7486, 534, -1, 534, 533, 7523, -1, + 7523, 533, 7474, -1, 7474, 7522, 7523, -1, + 7522, 7474, 7524, -1, 7524, 7521, 7522, -1, + 7521, 7524, 7525, -1, 7525, 7520, 7521, -1, + 7520, 7525, 7526, -1, 7526, 7519, 7520, -1, + 7519, 7526, 7527, -1, 7527, 7518, 7519, -1, + 7518, 7527, 7528, -1, 7528, 7517, 7518, -1, + 7517, 7528, 7529, -1, 7529, 7516, 7517, -1, + 7516, 7529, 7530, -1, 7530, 7515, 7516, -1, + 7515, 7530, 7531, -1, 7531, 7514, 7515, -1, + 7514, 7531, 7532, -1, 7532, 7513, 7514, -1, + 7513, 7532, 7533, -1, 7533, 7512, 7513, -1, + 7512, 7533, 7534, -1, 7534, 7511, 7512, -1, + 7511, 7534, 7535, -1, 7535, 7510, 7511, -1, + 7510, 7535, 7536, -1, 7536, 7509, 7510, -1, + 7509, 7536, 7537, -1, 7537, 7508, 7509, -1, + 7508, 7537, 7538, -1, 7538, 7507, 7508, -1, + 7507, 7538, 7539, -1, 7539, 7506, 7507, -1, + 7506, 7539, 7540, -1, 7540, 7505, 7506, -1, + 7505, 7540, 7541, -1, 7541, 429, 7505, -1, + 429, 7541, 7542, -1, 7542, 427, 429, -1, + 7542, 7543, 427, -1, 7542, 7544, 7543, -1, + 7544, 7542, 7541, -1, 7541, 7545, 7544, -1, + 7545, 7541, 7540, -1, 7540, 7546, 7545, -1, + 7546, 7540, 7539, -1, 7539, 7547, 7546, -1, + 7547, 7539, 7538, -1, 7538, 7548, 7547, -1, + 7548, 7538, 7537, -1, 7537, 7549, 7548, -1, + 7549, 7537, 7536, -1, 7536, 7550, 7549, -1, + 7550, 7536, 7535, -1, 7535, 7551, 7550, -1, + 7551, 7535, 7534, -1, 7534, 7552, 7551, -1, + 7552, 7534, 7533, -1, 7533, 7553, 7552, -1, + 7553, 7533, 7532, -1, 7532, 7554, 7553, -1, + 7554, 7532, 7531, -1, 7531, 7555, 7554, -1, + 7555, 7531, 7530, -1, 7530, 7556, 7555, -1, + 7556, 7530, 7529, -1, 7529, 7557, 7556, -1, + 7557, 7529, 7528, -1, 7528, 7558, 7557, -1, + 7558, 7528, 7527, -1, 7527, 7559, 7558, -1, + 7559, 7527, 7526, -1, 7526, 7560, 7559, -1, + 7560, 7526, 7525, -1, 7525, 7561, 7560, -1, + 7561, 7525, 7524, -1, 7524, 7562, 7561, -1, + 7562, 7524, 7474, -1, 7474, 7399, 7562, -1, + 7562, 7399, 7397, -1, 7397, 7561, 7562, -1, + 7561, 7397, 7395, -1, 7395, 7560, 7561, -1, + 7560, 7395, 7393, -1, 7393, 7559, 7560, -1, + 7559, 7393, 7391, -1, 7391, 7558, 7559, -1, + 7558, 7391, 7389, -1, 7389, 7557, 7558, -1, + 7557, 7389, 7387, -1, 7387, 7556, 7557, -1, + 7556, 7387, 7385, -1, 7385, 7555, 7556, -1, + 7555, 7385, 7383, -1, 7383, 7554, 7555, -1, + 7554, 7383, 7381, -1, 7381, 7553, 7554, -1, + 7553, 7381, 7379, -1, 7379, 7552, 7553, -1, + 7552, 7379, 7377, -1, 7377, 7551, 7552, -1, + 7551, 7377, 7375, -1, 7375, 7550, 7551, -1, + 7550, 7375, 7373, -1, 7373, 7549, 7550, -1, + 7549, 7373, 7371, -1, 7371, 7548, 7549, -1, + 7548, 7371, 7369, -1, 7369, 7547, 7548, -1, + 7547, 7369, 7367, -1, 7367, 7546, 7547, -1, + 7546, 7367, 7365, -1, 7365, 7545, 7546, -1, + 7545, 7365, 7363, -1, 7363, 7544, 7545, -1, + 7544, 7363, 7361, -1, 7361, 7543, 7544, -1, + 7543, 7361, 7359, -1, 7359, 7357, 7543, -1, + 7357, 427, 7543, -1, 7357, 425, 427, -1, + 425, 7357, 7356, -1, 7356, 423, 425, -1, + 423, 7356, 7355, -1, 7355, 421, 423, -1, + 421, 7355, 7354, -1, 7354, 420, 421, -1, + 420, 7354, 7353, -1, 420, 7353, 7352, -1, + 7352, 418, 420, -1, 418, 7352, 7351, -1, + 7351, 416, 418, -1, 416, 7351, 7350, -1, + 7350, 414, 416, -1, 414, 7350, 7349, -1, + 7349, 412, 414, -1, 7349, 7563, 412, -1, + 7564, 7565, 7566, -1, 7565, 7564, 7567, -1, + 7567, 7568, 7565, -1, 7568, 7567, 7569, -1, + 7569, 7570, 7568, -1, 7570, 7569, 7571, -1, + 7571, 7572, 7570, -1, 7572, 7571, 7573, -1, + 7573, 7574, 7572, -1, 7574, 7573, 7575, -1, + 7575, 7576, 7574, -1, 7576, 7575, 7577, -1, + 7577, 7578, 7576, -1, 7578, 7577, 7579, -1, + 7579, 7580, 7578, -1, 7580, 7579, 7581, -1, + 7581, 7582, 7580, -1, 7582, 7581, 7583, -1, + 7583, 7584, 7582, -1, 7584, 7583, 7585, -1, + 7585, 7586, 7584, -1, 7586, 7585, 7587, -1, + 7587, 7588, 7586, -1, 7588, 7587, 7589, -1, + 7589, 7590, 7588, -1, 7590, 7589, 7591, -1, + 7591, 7592, 7590, -1, 7592, 7591, 7593, -1, + 7593, 7594, 7592, -1, 7595, 7594, 7596, -1, + 7594, 7595, 7597, -1, 7597, 7592, 7594, -1, + 7592, 7597, 7598, -1, 7598, 7590, 7592, -1, + 7590, 7598, 7599, -1, 7599, 7588, 7590, -1, + 7588, 7599, 7600, -1, 7600, 7586, 7588, -1, + 7586, 7600, 7601, -1, 7601, 7584, 7586, -1, + 7584, 7601, 7602, -1, 7602, 7582, 7584, -1, + 7582, 7602, 7603, -1, 7603, 7580, 7582, -1, + 7580, 7603, 7604, -1, 7604, 7578, 7580, -1, + 7578, 7604, 7605, -1, 7605, 7576, 7578, -1, + 7576, 7605, 7606, -1, 7606, 7574, 7576, -1, + 7574, 7606, 7607, -1, 7607, 7572, 7574, -1, + 7572, 7607, 7608, -1, 7608, 7570, 7572, -1, + 7570, 7608, 7609, -1, 7609, 7568, 7570, -1, + 7568, 7609, 7610, -1, 7610, 7565, 7568, -1, + 7565, 7610, 7611, -1, 7611, 7566, 7565, -1, + 7566, 7611, 7612, -1, 7612, 7613, 7566, -1, + 7613, 7612, 7614, -1, 7614, 7615, 7613, -1, + 7615, 7614, 7616, -1, 7616, 7563, 7615, -1, + 7616, 412, 7563, -1, 7616, 411, 412, -1, + 411, 7616, 7614, -1, 7614, 410, 411, -1, + 410, 7614, 7612, -1, 7612, 409, 410, -1, + 409, 7612, 7611, -1, 7611, 408, 409, -1, + 408, 7611, 7610, -1, 7610, 407, 408, -1, + 407, 7610, 7609, -1, 7609, 406, 407, -1, + 406, 7609, 7608, -1, 7608, 405, 406, -1, + 405, 7608, 7607, -1, 7607, 404, 405, -1, + 404, 7607, 7606, -1, 7606, 403, 404, -1, + 403, 7606, 7605, -1, 7605, 402, 403, -1, + 402, 7605, 7604, -1, 7604, 401, 402, -1, + 401, 7604, 7603, -1, 7603, 400, 401, -1, + 400, 7603, 7602, -1, 7602, 399, 400, -1, + 399, 7602, 7601, -1, 7601, 398, 399, -1, + 398, 7601, 7600, -1, 7600, 397, 398, -1, + 397, 7600, 7599, -1, 7599, 396, 397, -1, + 396, 7599, 7598, -1, 7598, 395, 396, -1, + 395, 7598, 7597, -1, 7597, 394, 395, -1, + 394, 7597, 7595, -1, 7595, 393, 394, -1, + 393, 7595, 7596, -1, 7596, 392, 393, -1, + 392, 7596, 7617, -1, 7617, 391, 392, -1, + 391, 7617, 7618, -1, 7618, 390, 391, -1, + 390, 7618, 7619, -1, 7619, 389, 390, -1, + 389, 7619, 7620, -1, 7620, 388, 389, -1, + 388, 7620, 7621, -1, 7621, 387, 388, -1, + 387, 7621, 7622, -1, 7622, 386, 387, -1, + 7623, 7624, 386, -1, 386, 7622, 7623, -1, + 7623, 7625, 7626, -1, 7623, 7627, 7625, -1, + 7627, 7623, 7622, -1, 7622, 7628, 7627, -1, + 7628, 7622, 7621, -1, 7621, 7629, 7628, -1, + 7629, 7621, 7620, -1, 7620, 7630, 7629, -1, + 7630, 7620, 7619, -1, 7619, 7631, 7630, -1, + 7631, 7619, 7618, -1, 7618, 7632, 7631, -1, + 7632, 7618, 7617, -1, 7617, 7633, 7632, -1, + 7633, 7617, 7596, -1, 7596, 7634, 7633, -1, + 7634, 7596, 7594, -1, 7594, 7593, 7634, -1, + 7593, 7635, 7634, -1, 7635, 7593, 7591, -1, + 7591, 7636, 7635, -1, 7636, 7591, 7589, -1, + 7589, 7637, 7636, -1, 7637, 7589, 7587, -1, + 7587, 7638, 7637, -1, 7638, 7587, 7585, -1, + 7585, 7639, 7638, -1, 7639, 7585, 7583, -1, + 7583, 7640, 7639, -1, 7640, 7583, 7581, -1, + 7581, 7641, 7640, -1, 7641, 7581, 7579, -1, + 7579, 7642, 7641, -1, 7642, 7579, 7577, -1, + 7577, 7643, 7642, -1, 7643, 7577, 7575, -1, + 7575, 7644, 7643, -1, 7644, 7575, 7573, -1, + 7573, 7645, 7644, -1, 7645, 7573, 7571, -1, + 7571, 7646, 7645, -1, 7646, 7571, 7569, -1, + 7569, 7647, 7646, -1, 7647, 7569, 7567, -1, + 7567, 7648, 7647, -1, 7648, 7567, 7564, -1, + 7564, 7649, 7648, -1, 7649, 7564, 7566, -1, + 7566, 7650, 7649, -1, 7650, 7566, 7613, -1, + 7613, 7651, 7650, -1, 7651, 7613, 7615, -1, + 7615, 7652, 7651, -1, 7652, 7615, 7563, -1, + 7563, 7653, 7652, -1, 7653, 7563, 7349, -1, + 7653, 7349, 620, -1, 7653, 620, 621, -1, + 621, 7652, 7653, -1, 7652, 621, 622, -1, + 622, 7651, 7652, -1, 7651, 622, 623, -1, + 623, 7650, 7651, -1, 7650, 623, 624, -1, + 624, 7649, 7650, -1, 7649, 624, 625, -1, + 625, 7648, 7649, -1, 7648, 625, 626, -1, + 626, 7647, 7648, -1, 7647, 626, 627, -1, + 627, 7646, 7647, -1, 7646, 627, 628, -1, + 628, 7645, 7646, -1, 7645, 628, 629, -1, + 629, 7644, 7645, -1, 7644, 629, 630, -1, + 630, 7643, 7644, -1, 7643, 630, 631, -1, + 631, 7642, 7643, -1, 7642, 631, 632, -1, + 632, 7641, 7642, -1, 7641, 632, 633, -1, + 633, 7640, 7641, -1, 7640, 633, 634, -1, + 634, 7639, 7640, -1, 7639, 634, 635, -1, + 635, 7638, 7639, -1, 7638, 635, 636, -1, + 636, 7637, 7638, -1, 7637, 636, 637, -1, + 637, 7636, 7637, -1, 7636, 637, 638, -1, + 638, 7635, 7636, -1, 7635, 638, 639, -1, + 639, 7634, 7635, -1, 7634, 639, 640, -1, + 640, 7633, 7634, -1, 7633, 640, 642, -1, + 642, 7632, 7633, -1, 7632, 642, 644, -1, + 644, 7631, 7632, -1, 7631, 644, 646, -1, + 646, 7630, 7631, -1, 7630, 646, 648, -1, + 648, 7629, 7630, -1, 7629, 648, 650, -1, + 650, 7628, 7629, -1, 7628, 650, 652, -1, + 652, 7627, 7628, -1, 7627, 652, 654, -1, + 654, 7625, 7627, -1, 7625, 654, 656, -1, + 656, 7654, 7625, -1, 7654, 656, 657, -1, + 657, 658, 7654, -1, 658, 7655, 7654, -1, + 7656, 7655, 7657, -1, 7656, 7654, 7655, -1, + 7656, 7625, 7654, -1, 7656, 7657, 7625, -1, + 7657, 7626, 7625, -1, 7626, 7657, 7655, -1, + 7626, 7655, 7658, -1, 7658, 7623, 7626, -1, + 7658, 7624, 7623, -1, 7624, 7658, 7655, -1, + 7624, 7655, 7659, -1, 7659, 386, 7624, -1, + 7659, 385, 386, -1, 7659, 382, 385, -1, + 382, 7659, 7655, -1, 7660, 6156, 6153, -1, + 2543, 2542, 7660, -1, 7661, 7660, 2542, -1, + 7661, 2542, 2544, -1, 7661, 2544, 6402, -1, + 6402, 7660, 7661, -1, 6402, 1152, 7660, -1, + 7662, 7663, 7664, -1, 7665, 7666, 7667, -1, + 7665, 7668, 7666, -1, 7665, 7669, 7668, -1, + 7665, 7667, 7669, -1, 7670, 7662, 7671, -1, + 7670, 7672, 7662, -1, 7670, 7673, 7672, -1, + 7670, 7671, 7673, -1, 7674, 7675, 7676, -1, + 7674, 7676, 7671, -1, 7676, 7673, 7671, -1, + 7676, 7677, 7673, -1, 7677, 7676, 7678, -1, + 7678, 7679, 7677, -1, 7679, 7678, 7680, -1, + 7680, 7681, 7679, -1, 7681, 7680, 7682, -1, + 7682, 7683, 7681, -1, 7682, 7684, 7683, -1, + 7684, 7682, 7685, -1, 7685, 7686, 7684, -1, + 7686, 7685, 7687, -1, 7687, 7688, 7686, -1, + 7688, 7687, 7689, -1, 7689, 7690, 7688, -1, + 7689, 7691, 7690, -1, 7692, 7690, 7691, -1, + 7692, 7693, 7690, -1, 7693, 7692, 7694, -1, + 7692, 7691, 7694, -1, 7695, 7694, 7691, -1, + 7696, 7695, 7691, -1, 7696, 7691, 7689, -1, + 7696, 7689, 7697, -1, 7697, 7695, 7696, -1, + 7697, 7698, 7695, -1, 7697, 7699, 7698, -1, + 7699, 7697, 7689, -1, 7699, 7689, 7687, -1, + 7687, 7700, 7699, -1, 7700, 7687, 7685, -1, + 7685, 7701, 7700, -1, 7701, 7685, 7682, -1, + 7701, 7682, 7680, -1, 7680, 7702, 7701, -1, + 7702, 7680, 7678, -1, 7678, 7667, 7702, -1, + 7667, 7678, 7676, -1, 7667, 7676, 7675, -1, + 7675, 7669, 7667, -1, 7675, 7668, 7669, -1, + 7675, 7674, 7668, -1, 7674, 7671, 7668, -1, + 7668, 7671, 7662, -1, 7703, 7666, 7668, -1, + 7704, 7705, 7706, -1, 7704, 7703, 7705, -1, + 7704, 7707, 7703, -1, 7704, 7706, 7707, -1, + 7708, 7707, 7706, -1, 7708, 7706, 7709, -1, + 7708, 7709, 7710, -1, 7710, 7711, 7708, -1, + 7712, 7708, 7711, -1, 7712, 7707, 7708, -1, + 7712, 7703, 7707, -1, 7712, 7711, 7703, -1, + 7711, 7666, 7703, -1, 7711, 7710, 7666, -1, + 7710, 7667, 7666, -1, 7710, 7702, 7667, -1, + 7702, 7710, 7709, -1, 7709, 7701, 7702, -1, + 7709, 7700, 7701, -1, 7700, 7709, 7706, -1, + 7706, 7699, 7700, -1, 7706, 7705, 7699, -1, + 7713, 7699, 7705, -1, 7713, 7698, 7699, -1, + 7713, 7695, 7698, -1, 7713, 7705, 7695, -1, + 7695, 7705, 7703, -1, 7714, 7660, 1152, -1, + 1152, 1151, 7714, -1, 7715, 7714, 1151, -1, + 1151, 1062, 7715, -1, 7715, 1062, 1064, -1, + 1064, 7714, 7715, -1, 1064, 7716, 7714, -1, + 7716, 1064, 1063, -1, 7716, 1063, 6412, -1, + 6412, 7714, 7716, -1, 7714, 6412, 6414, -1, + 7694, 6786, 6784, -1, 7717, 7694, 6784, -1, + 7717, 6784, 6783, -1, 7717, 6783, 7718, -1, + 7718, 7694, 7717, -1, 7718, 7693, 7694, -1, + 7718, 7690, 7693, -1, 7690, 7718, 6783, -1, + 7690, 6783, 6782, -1, 6782, 7688, 7690, -1, + 7688, 6782, 6781, -1, 6781, 7686, 7688, -1, + 7686, 6781, 6780, -1, 6780, 7684, 7686, -1, + 7684, 6780, 6779, -1, 6779, 7683, 7684, -1, + 7683, 6779, 6778, -1, 7683, 6778, 6777, -1, + 6777, 7681, 7683, -1, 7681, 6777, 6776, -1, + 6776, 7679, 7681, -1, 7679, 6776, 6775, -1, + 6775, 7677, 7679, -1, 7677, 6775, 6774, -1, + 6774, 7673, 7677, -1, 7673, 6774, 113, -1, + 7673, 113, 112, -1, 112, 7672, 7673, -1, + 112, 7662, 7672, -1, 112, 111, 7662, -1, + 111, 7663, 7662, -1, 111, 113, 7663, -1, + 113, 6445, 7663, -1, 7719, 7663, 6445, -1, + 7719, 7664, 7663, -1, 7719, 7720, 7664, -1, + 7719, 6445, 7720, -1, 7720, 6445, 6446, -1, + 6446, 7664, 7720, -1, 6446, 6447, 7664, -1, + 6447, 6448, 7664, -1, 6448, 7721, 7664, -1, + 7721, 6448, 6449, -1, 7721, 6449, 6755, -1, + 7721, 6755, 6753, -1, 6753, 7664, 7721, -1, + 7722, 6753, 6752, -1, 6752, 7723, 7722, -1, + 6752, 6750, 7723, -1, 6750, 7724, 7723, -1, + 6750, 7725, 7724, -1, 7725, 6750, 6748, -1, + 6748, 7726, 7725, -1, 7726, 6748, 6746, -1, + 6746, 7727, 7726, -1, 7727, 6746, 6744, -1, + 6744, 7728, 7727, -1, 7728, 6744, 6742, -1, + 6742, 7729, 7728, -1, 7729, 6742, 6740, -1, + 6740, 7730, 7729, -1, 7730, 6740, 6738, -1, + 6738, 7731, 7730, -1, 7731, 6738, 6736, -1, + 6736, 7732, 7731, -1, 7732, 6736, 6734, -1, + 6734, 7733, 7732, -1, 7733, 6734, 6732, -1, + 6732, 7734, 7733, -1, 7734, 6732, 6731, -1, + 6731, 7735, 7734, -1, 6731, 7736, 7735, -1, + 7736, 6731, 6729, -1, 6729, 7737, 7736, -1, + 7737, 6729, 6727, -1, 6727, 7738, 7737, -1, + 7738, 6727, 6725, -1, 6725, 7739, 7738, -1, + 7739, 6725, 6723, -1, 6723, 7740, 7739, -1, + 7740, 6723, 6721, -1, 6721, 7741, 7740, -1, + 7741, 6721, 6719, -1, 6719, 7742, 7741, -1, + 7742, 6719, 6717, -1, 6717, 7743, 7742, -1, + 7743, 6717, 6715, -1, 6715, 7744, 7743, -1, + 7744, 6715, 6713, -1, 6713, 7745, 7744, -1, + 7745, 6713, 6707, -1, 6707, 7746, 7745, -1, + 6707, 6706, 7746, -1, 7747, 7746, 6706, -1, + 7747, 6706, 6548, -1, 7747, 6548, 6549, -1, + 6549, 7746, 7747, -1, 6549, 6550, 7746, -1, + 7746, 6550, 6543, -1, 7746, 6543, 6542, -1, + 6542, 7745, 7746, -1, 7745, 6542, 6541, -1, + 6541, 7744, 7745, -1, 7744, 6541, 6540, -1, + 6540, 7743, 7744, -1, 7743, 6540, 6539, -1, + 6539, 7742, 7743, -1, 7742, 6539, 6538, -1, + 6538, 7741, 7742, -1, 7741, 6538, 6537, -1, + 6537, 7740, 7741, -1, 7740, 6537, 6536, -1, + 6536, 7739, 7740, -1, 7739, 6536, 6535, -1, + 6535, 7738, 7739, -1, 7738, 6535, 6534, -1, + 6534, 7737, 7738, -1, 7737, 6534, 6533, -1, + 6533, 7736, 7737, -1, 7736, 6533, 6532, -1, + 6532, 7735, 7736, -1, 7735, 6532, 6531, -1, + 7735, 6531, 6530, -1, 6530, 7734, 7735, -1, + 7734, 6530, 6529, -1, 6529, 7733, 7734, -1, + 7733, 6529, 6528, -1, 6528, 7732, 7733, -1, + 7732, 6528, 6527, -1, 6527, 7731, 7732, -1, + 7731, 6527, 6526, -1, 6526, 7730, 7731, -1, + 7730, 6526, 6525, -1, 6525, 7729, 7730, -1, + 7729, 6525, 6524, -1, 6524, 7728, 7729, -1, + 7728, 6524, 6523, -1, 6523, 7727, 7728, -1, + 7727, 6523, 6522, -1, 6522, 7726, 7727, -1, + 7726, 6522, 6521, -1, 6521, 7725, 7726, -1, + 7725, 6521, 6520, -1, 6520, 7724, 7725, -1, + 7724, 6520, 6517, -1, 7724, 6517, 7748, -1, + 7749, 7724, 7748, -1, 7749, 7750, 7724, -1, + 7750, 7723, 7724, -1, 7750, 7722, 7723, -1, + 7750, 7749, 7722, -1, 7749, 7748, 7722, -1, + 7748, 7751, 7722, -1, 7751, 7748, 6517, -1, + 7751, 6517, 6516, -1, 7751, 6516, 6515, -1, + 6515, 7722, 7751, -1, 7752, 6515, 6514, -1, + 6514, 7753, 7752, -1, 6514, 6512, 7753, -1, + 7753, 6512, 6585, -1, 6585, 7752, 7753, -1, + 6585, 6586, 7752, -1, 6586, 6587, 7752, -1, + 6587, 7754, 7752, -1, 7754, 6587, 6588, -1, + 7754, 6588, 6656, -1, 6656, 6658, 7754, -1, + 6658, 7752, 7754, -1, 253, 6658, 6660, -1, + 6660, 7755, 253, -1, 7755, 6660, 6661, -1, + 7755, 6661, 7756, -1, 7756, 253, 7755, -1, + 7756, 251, 253, -1, 7756, 252, 251, -1, + 252, 7756, 6661, -1, 6661, 376, 252, -1, + 376, 6661, 6662, -1, 6662, 375, 376, -1, + 375, 6662, 6663, -1, 6663, 374, 375, -1, + 374, 6663, 6664, -1, 6664, 373, 374, -1, + 373, 6664, 6665, -1, 6665, 372, 373, -1, + 372, 6665, 6666, -1, 6666, 371, 372, -1, + 371, 6666, 6667, -1, 6667, 370, 371, -1, + 370, 6667, 6668, -1, 6668, 369, 370, -1, + 369, 6668, 6669, -1, 6669, 368, 369, -1, + 368, 6669, 6670, -1, 6670, 367, 368, -1, + 367, 6670, 6671, -1, 6671, 366, 367, -1, + 366, 6671, 6672, -1, 6672, 365, 366, -1, + 365, 6672, 6673, -1, 6673, 364, 365, -1, + 364, 6673, 6674, -1, 6674, 363, 364, -1, + 363, 6674, 6675, -1, 6675, 362, 363, -1, + 362, 6675, 6676, -1, 6676, 361, 362, -1, + 361, 6676, 6677, -1, 6677, 360, 361, -1, + 360, 6677, 6678, -1, 6678, 359, 360, -1, + 359, 6678, 6680, -1, 6680, 358, 359, -1, + 6680, 357, 358, -1, 357, 6680, 6681, -1, + 6681, 356, 357, -1, 356, 6681, 6682, -1, + 6682, 355, 356, -1, 355, 6682, 6683, -1, + 6683, 354, 355, -1, 354, 6683, 6684, -1, + 6684, 353, 354, -1, 353, 6684, 6685, -1, + 6685, 352, 353, -1, 352, 6685, 6686, -1, + 6686, 351, 352, -1, 351, 6686, 6687, -1, + 6687, 350, 351, -1, 350, 6687, 6688, -1, + 6688, 349, 350, -1, 349, 6688, 6689, -1, + 6689, 348, 349, -1, 348, 6689, 6690, -1, + 6690, 347, 348, -1, 347, 6690, 6691, -1, + 6691, 346, 347, -1, 346, 6691, 6692, -1, + 6692, 345, 346, -1, 345, 6692, 6693, -1, + 6693, 344, 345, -1, 344, 6693, 6694, -1, + 6694, 343, 344, -1, 343, 6694, 6695, -1, + 6695, 342, 343, -1, 342, 6695, 6696, -1, + 6696, 341, 342, -1, 341, 6696, 6697, -1, + 6697, 340, 341, -1, 340, 6697, 6698, -1, + 6698, 260, 340, -1, 260, 6698, 6700, -1, + 6700, 259, 260, -1, 6700, 257, 259, -1, + 6700, 6699, 257, -1, 6699, 6701, 257, -1, + 257, 6701, 6450, -1, 6800, 258, 257, -1, + 7757, 258, 6800, -1, 7757, 261, 258, -1, + 7757, 7758, 261, -1, 7758, 7757, 6800, -1, + 7758, 6800, 6799, -1, 7758, 6799, 6793, -1, + 6793, 261, 7758, -1, 261, 6793, 6795, -1, + 6795, 338, 261, -1, 338, 6795, 7759, -1, + 7759, 336, 338, -1, 336, 7759, 7760, -1, + 7760, 334, 336, -1, 334, 7760, 7761, -1, + 7761, 332, 334, -1, 332, 7761, 7762, -1, + 7762, 330, 332, -1, 330, 7762, 7763, -1, + 7763, 328, 330, -1, 328, 7763, 7764, -1, + 7764, 326, 328, -1, 326, 7764, 7765, -1, + 7765, 324, 326, -1, 324, 7765, 7766, -1, + 7766, 322, 324, -1, 322, 7766, 7767, -1, + 7767, 320, 322, -1, 320, 7767, 7768, -1, + 7768, 318, 320, -1, 318, 7768, 7769, -1, + 7769, 316, 318, -1, 316, 7769, 7770, -1, + 7770, 314, 316, -1, 314, 7770, 7771, -1, + 7771, 312, 314, -1, 312, 7771, 7772, -1, + 7772, 310, 312, -1, 310, 7772, 7773, -1, + 7773, 308, 310, -1, 308, 7773, 7774, -1, + 7774, 306, 308, -1, 306, 7774, 7775, -1, + 7775, 304, 306, -1, 304, 7775, 7776, -1, + 7776, 302, 304, -1, 302, 7776, 7777, -1, + 7777, 301, 302, -1, 301, 7777, 7778, -1, + 301, 7778, 7779, -1, 7779, 299, 301, -1, + 299, 7779, 7780, -1, 7780, 297, 299, -1, + 297, 7780, 7781, -1, 7781, 295, 297, -1, + 295, 7781, 7782, -1, 7782, 293, 295, -1, + 293, 7782, 7783, -1, 7783, 291, 293, -1, + 291, 7783, 7784, -1, 7784, 289, 291, -1, + 289, 7784, 7785, -1, 7785, 287, 289, -1, + 287, 7785, 7786, -1, 7786, 285, 287, -1, + 285, 7786, 7787, -1, 7787, 283, 285, -1, + 283, 7787, 7788, -1, 7788, 281, 283, -1, + 281, 7788, 7789, -1, 7789, 279, 281, -1, + 279, 7789, 7790, -1, 7790, 277, 279, -1, + 277, 7790, 7791, -1, 7791, 275, 277, -1, + 275, 7791, 7792, -1, 7792, 273, 275, -1, + 273, 7792, 7793, -1, 7793, 271, 273, -1, + 271, 7793, 7794, -1, 7794, 269, 271, -1, + 269, 7794, 7795, -1, 7795, 267, 269, -1, + 267, 7795, 7796, -1, 7796, 265, 267, -1, + 265, 7796, 7797, -1, 7797, 262, 265, -1, + 7797, 377, 262, -1, 7797, 7798, 377, -1, + 7798, 7797, 7796, -1, 7796, 7799, 7798, -1, + 7799, 7796, 7795, -1, 7795, 7800, 7799, -1, + 7800, 7795, 7794, -1, 7794, 7801, 7800, -1, + 7801, 7794, 7793, -1, 7793, 7802, 7801, -1, + 7802, 7793, 7792, -1, 7792, 7803, 7802, -1, + 7803, 7792, 7791, -1, 7791, 7804, 7803, -1, + 7804, 7791, 7790, -1, 7790, 7805, 7804, -1, + 7805, 7790, 7789, -1, 7789, 7806, 7805, -1, + 7806, 7789, 7788, -1, 7788, 7807, 7806, -1, + 7807, 7788, 7787, -1, 7787, 7808, 7807, -1, + 7808, 7787, 7786, -1, 7786, 7809, 7808, -1, + 7809, 7786, 7785, -1, 7785, 7810, 7809, -1, + 7810, 7785, 7784, -1, 7784, 7811, 7810, -1, + 7811, 7784, 7783, -1, 7783, 7812, 7811, -1, + 7812, 7783, 7782, -1, 7782, 7813, 7812, -1, + 7813, 7782, 7781, -1, 7781, 7814, 7813, -1, + 7814, 7781, 7780, -1, 7780, 7815, 7814, -1, + 7815, 7780, 7779, -1, 7779, 7816, 7815, -1, + 7816, 7779, 7778, -1, 7778, 7817, 7816, -1, + 7778, 7818, 7817, -1, 7818, 7778, 7777, -1, + 7777, 7819, 7818, -1, 7819, 7777, 7776, -1, + 7776, 7820, 7819, -1, 7820, 7776, 7775, -1, + 7775, 7821, 7820, -1, 7821, 7775, 7774, -1, + 7774, 7822, 7821, -1, 7822, 7774, 7773, -1, + 7773, 7823, 7822, -1, 7823, 7773, 7772, -1, + 7772, 7824, 7823, -1, 7824, 7772, 7771, -1, + 7771, 7825, 7824, -1, 7825, 7771, 7770, -1, + 7770, 7826, 7825, -1, 7826, 7770, 7769, -1, + 7769, 7827, 7826, -1, 7827, 7769, 7768, -1, + 7768, 7828, 7827, -1, 7828, 7768, 7767, -1, + 7767, 7829, 7828, -1, 7829, 7767, 7766, -1, + 7766, 7830, 7829, -1, 7830, 7766, 7765, -1, + 7765, 7831, 7830, -1, 7831, 7765, 7764, -1, + 7764, 7832, 7831, -1, 7832, 7764, 7763, -1, + 7763, 7833, 7832, -1, 7833, 7763, 7762, -1, + 7762, 7834, 7833, -1, 7834, 7762, 7761, -1, + 7761, 7835, 7834, -1, 7835, 7761, 7760, -1, + 7760, 7836, 7835, -1, 7836, 7760, 7759, -1, + 7759, 7837, 7836, -1, 7837, 7759, 6795, -1, + 7837, 6795, 6794, -1, 7837, 6794, 7838, -1, + 7838, 7836, 7837, -1, 7836, 7838, 7839, -1, + 7839, 7835, 7836, -1, 7835, 7839, 7840, -1, + 7840, 7834, 7835, -1, 7834, 7840, 7841, -1, + 7841, 7833, 7834, -1, 7833, 7841, 7842, -1, + 7842, 7832, 7833, -1, 7832, 7842, 7843, -1, + 7843, 7831, 7832, -1, 7831, 7843, 7844, -1, + 7844, 7830, 7831, -1, 7830, 7844, 7845, -1, + 7845, 7829, 7830, -1, 7829, 7845, 7846, -1, + 7846, 7828, 7829, -1, 7828, 7846, 7847, -1, + 7847, 7827, 7828, -1, 7827, 7847, 7848, -1, + 7848, 7826, 7827, -1, 7826, 7848, 7849, -1, + 7849, 7825, 7826, -1, 7825, 7849, 7850, -1, + 7850, 7824, 7825, -1, 7824, 7850, 7851, -1, + 7851, 7823, 7824, -1, 7823, 7851, 7852, -1, + 7852, 7822, 7823, -1, 7822, 7852, 7853, -1, + 7853, 7821, 7822, -1, 7821, 7853, 7854, -1, + 7854, 7820, 7821, -1, 7820, 7854, 7855, -1, + 7855, 7819, 7820, -1, 7819, 7855, 7856, -1, + 7856, 7818, 7819, -1, 7818, 7856, 7857, -1, + 7857, 7817, 7818, -1, 7817, 7857, 7858, -1, + 7817, 7858, 7859, -1, 7859, 7816, 7817, -1, + 7816, 7859, 7860, -1, 7860, 7815, 7816, -1, + 7815, 7860, 7861, -1, 7861, 7814, 7815, -1, + 7814, 7861, 7862, -1, 7862, 7813, 7814, -1, + 7813, 7862, 7863, -1, 7863, 7812, 7813, -1, + 7812, 7863, 7864, -1, 7864, 7811, 7812, -1, + 7811, 7864, 7865, -1, 7865, 7810, 7811, -1, + 7810, 7865, 7866, -1, 7866, 7809, 7810, -1, + 7809, 7866, 7867, -1, 7867, 7808, 7809, -1, + 7808, 7867, 7868, -1, 7868, 7807, 7808, -1, + 7807, 7868, 7869, -1, 7869, 7806, 7807, -1, + 7806, 7869, 7870, -1, 7870, 7805, 7806, -1, + 7805, 7870, 7871, -1, 7871, 7804, 7805, -1, + 7804, 7871, 7872, -1, 7872, 7803, 7804, -1, + 7803, 7872, 7873, -1, 7873, 7802, 7803, -1, + 7802, 7873, 7874, -1, 7874, 7801, 7802, -1, + 7801, 7874, 7875, -1, 7875, 7800, 7801, -1, + 7800, 7875, 7876, -1, 7876, 7799, 7800, -1, + 7799, 7876, 7877, -1, 7877, 7798, 7799, -1, + 7798, 7877, 109, -1, 109, 377, 7798, -1, + 377, 109, 108, -1, 108, 249, 377, -1, + 249, 108, 7878, -1, 7878, 245, 249, -1, + 7879, 7878, 7880, -1, 7879, 245, 7878, -1, + 7879, 246, 245, -1, 7879, 7880, 246, -1, + 7881, 246, 7880, -1, 7881, 7882, 246, -1, + 7882, 380, 246, -1, 7882, 7883, 380, -1, + 7882, 7881, 7883, -1, 7881, 7880, 7883, -1, + 7883, 7880, 7878, -1, 7878, 7884, 7883, -1, + 7884, 7878, 108, -1, 108, 110, 7884, -1, + 110, 7885, 7886, -1, 110, 7886, 7887, -1, + 7887, 7884, 110, -1, 7884, 7887, 7888, -1, + 7888, 7883, 7884, -1, 7883, 7888, 7889, -1, + 7889, 380, 7883, -1, 7890, 7889, 7891, -1, + 7890, 380, 7889, -1, 7890, 243, 380, -1, + 7890, 7891, 243, -1, 7892, 243, 7891, -1, + 7892, 7893, 243, -1, 7893, 241, 243, -1, + 7893, 240, 241, -1, 7893, 7892, 240, -1, + 7892, 7891, 240, -1, 240, 7891, 7889, -1, + 7889, 239, 240, -1, 239, 7889, 7888, -1, + 7888, 238, 239, -1, 238, 7888, 7887, -1, + 7887, 236, 238, -1, 236, 7887, 7886, -1, + 7886, 237, 236, -1, 237, 7886, 7894, -1, + 7894, 7895, 237, -1, 7895, 7894, 7896, -1, + 7896, 7897, 7895, -1, 7897, 7896, 7898, -1, + 7898, 7899, 7897, -1, 7899, 7898, 7900, -1, + 7900, 7901, 7899, -1, 7901, 7900, 7902, -1, + 7902, 7903, 7901, -1, 7903, 7902, 7904, -1, + 7904, 7905, 7903, -1, 7905, 7904, 7906, -1, + 7906, 7907, 7905, -1, 7907, 7906, 7908, -1, + 7908, 7909, 7907, -1, 7909, 7908, 7910, -1, + 7910, 7911, 7909, -1, 7911, 7910, 7912, -1, + 7912, 7913, 7911, -1, 7913, 7912, 7914, -1, + 7914, 7915, 7913, -1, 7915, 7914, 7916, -1, + 7916, 7917, 7915, -1, 7917, 7916, 7918, -1, + 7918, 7919, 7917, -1, 7919, 7918, 7920, -1, + 7920, 7921, 7919, -1, 7921, 7920, 7922, -1, + 7922, 7923, 7921, -1, 7923, 7922, 7924, -1, + 7924, 7925, 7923, -1, 7925, 7924, 7926, -1, + 7926, 7927, 7925, -1, 7927, 7926, 7928, -1, + 7928, 7929, 7927, -1, 7929, 7928, 107, -1, + 107, 106, 7929, -1, 7930, 7929, 106, -1, + 7929, 7930, 7931, -1, 7931, 7927, 7929, -1, + 7927, 7931, 7932, -1, 7932, 7925, 7927, -1, + 7925, 7932, 7933, -1, 7933, 7923, 7925, -1, + 7923, 7933, 7934, -1, 7934, 7921, 7923, -1, + 7921, 7934, 7935, -1, 7935, 7919, 7921, -1, + 7919, 7935, 7936, -1, 7936, 7917, 7919, -1, + 7917, 7936, 7937, -1, 7937, 7915, 7917, -1, + 7915, 7937, 7938, -1, 7938, 7913, 7915, -1, + 7913, 7938, 7939, -1, 7939, 7911, 7913, -1, + 7911, 7939, 7940, -1, 7940, 7909, 7911, -1, + 7909, 7940, 7941, -1, 7941, 7907, 7909, -1, + 7907, 7941, 7942, -1, 7942, 7905, 7907, -1, + 7905, 7942, 7943, -1, 7943, 7903, 7905, -1, + 7903, 7943, 7944, -1, 7944, 7901, 7903, -1, + 7901, 7944, 7945, -1, 7945, 7899, 7901, -1, + 7899, 7945, 7946, -1, 7946, 7897, 7899, -1, + 7897, 7946, 7947, -1, 7947, 7895, 7897, -1, + 7895, 7947, 7948, -1, 7948, 237, 7895, -1, + 7948, 234, 237, -1, 7948, 235, 234, -1, + 235, 7948, 7947, -1, 7947, 7949, 235, -1, + 7949, 7947, 7946, -1, 7946, 7950, 7949, -1, + 7950, 7946, 7945, -1, 7945, 7951, 7950, -1, + 7951, 7945, 7944, -1, 7944, 7952, 7951, -1, + 7952, 7944, 7943, -1, 7943, 7953, 7952, -1, + 7953, 7943, 7942, -1, 7942, 7954, 7953, -1, + 7954, 7942, 7941, -1, 7941, 7955, 7954, -1, + 7955, 7941, 7940, -1, 7940, 7956, 7955, -1, + 7956, 7940, 7939, -1, 7939, 7957, 7956, -1, + 7957, 7939, 7938, -1, 7938, 7958, 7957, -1, + 7958, 7938, 7937, -1, 7937, 7959, 7958, -1, + 7959, 7937, 7936, -1, 7936, 7960, 7959, -1, + 7960, 7936, 7935, -1, 7935, 7961, 7960, -1, + 7961, 7935, 7934, -1, 7934, 7962, 7961, -1, + 7962, 7934, 7933, -1, 7933, 7963, 7962, -1, + 7963, 7933, 7932, -1, 7932, 7964, 7963, -1, + 7964, 7932, 7931, -1, 7931, 7965, 7964, -1, + 7965, 7931, 7930, -1, 7930, 7966, 7965, -1, + 7930, 106, 7966, -1, 7967, 7966, 106, -1, + 7967, 106, 104, -1, 104, 7968, 7967, -1, + 7968, 104, 103, -1, 103, 7969, 7968, -1, + 103, 7970, 7969, -1, 7970, 103, 101, -1, + 101, 7971, 7970, -1, 7971, 101, 99, -1, + 99, 7972, 7971, -1, 7972, 99, 12, -1, + 12, 7973, 7972, -1, 7973, 12, 11, -1, + 11, 7974, 7973, -1, 7974, 11, 14, -1, + 14, 7975, 7974, -1, 7975, 14, 16, -1, + 16, 7976, 7975, -1, 7976, 16, 18, -1, + 18, 7977, 7976, -1, 7977, 18, 20, -1, + 20, 7978, 7977, -1, 7978, 20, 22, -1, + 22, 7979, 7978, -1, 7979, 22, 24, -1, + 24, 7980, 7979, -1, 7980, 24, 26, -1, + 26, 7981, 7980, -1, 7981, 26, 28, -1, + 28, 7982, 7981, -1, 7982, 28, 30, -1, + 30, 7983, 7982, -1, 7983, 30, 32, -1, + 32, 7984, 7983, -1, 7984, 32, 34, -1, + 34, 7985, 7984, -1, 7985, 34, 36, -1, + 36, 7986, 7985, -1, 7986, 36, 38, -1, + 38, 7987, 7986, -1, 7987, 38, 40, -1, + 40, 7988, 7987, -1, 7988, 40, 42, -1, + 42, 7989, 7988, -1, 7989, 42, 44, -1, + 44, 7990, 7989, -1, 7990, 44, 46, -1, + 46, 7991, 7990, -1, 7991, 46, 48, -1, + 48, 50, 7991, -1, 50, 58, 7991, -1, + 7992, 7993, 7994, -1, 7993, 7992, 7995, -1, + 7995, 7996, 7993, -1, 7996, 7995, 7997, -1, + 7997, 7998, 7996, -1, 7998, 7997, 7999, -1, + 7999, 8000, 7998, -1, 8000, 7999, 8001, -1, + 8001, 8002, 8000, -1, 8002, 8001, 8003, -1, + 8003, 8004, 8002, -1, 8004, 8003, 8005, -1, + 8005, 8006, 8004, -1, 8006, 8005, 8007, -1, + 8007, 8008, 8006, -1, 8008, 8007, 8009, -1, + 8009, 8010, 8008, -1, 8010, 8009, 8011, -1, + 8011, 8012, 8010, -1, 8012, 8011, 8013, -1, + 8013, 8014, 8012, -1, 8014, 8013, 8015, -1, + 8015, 8016, 8014, -1, 8016, 8015, 8017, -1, + 8017, 8018, 8016, -1, 8018, 8017, 8019, -1, + 8019, 8020, 8018, -1, 8020, 8019, 8021, -1, + 8021, 8022, 8020, -1, 8022, 8021, 8023, -1, + 8023, 8024, 8022, -1, 8024, 8023, 8025, -1, + 8025, 8026, 8024, -1, 8026, 8025, 8027, -1, + 8027, 8028, 8026, -1, 8028, 8027, 8029, -1, + 8029, 58, 8028, -1, 8029, 7991, 58, -1, + 8029, 7990, 7991, -1, 7990, 8029, 8027, -1, + 8027, 7989, 7990, -1, 7989, 8027, 8025, -1, + 8025, 7988, 7989, -1, 7988, 8025, 8023, -1, + 8023, 7987, 7988, -1, 7987, 8023, 8021, -1, + 8021, 7986, 7987, -1, 7986, 8021, 8019, -1, + 8019, 7985, 7986, -1, 7985, 8019, 8017, -1, + 8017, 7984, 7985, -1, 7984, 8017, 8015, -1, + 8015, 7983, 7984, -1, 7983, 8015, 8013, -1, + 8013, 7982, 7983, -1, 7982, 8013, 8011, -1, + 8011, 7981, 7982, -1, 7981, 8011, 8009, -1, + 8009, 7980, 7981, -1, 7980, 8009, 8007, -1, + 8007, 7979, 7980, -1, 7979, 8007, 8005, -1, + 8005, 7978, 7979, -1, 7978, 8005, 8003, -1, + 8003, 7977, 7978, -1, 7977, 8003, 8001, -1, + 8001, 7976, 7977, -1, 7976, 8001, 7999, -1, + 7999, 7975, 7976, -1, 7975, 7999, 7997, -1, + 7997, 7974, 7975, -1, 7974, 7997, 7995, -1, + 7995, 7973, 7974, -1, 7973, 7995, 7992, -1, + 7992, 7972, 7973, -1, 7992, 7994, 7972, -1, + 8030, 7972, 7994, -1, 8030, 7971, 7972, -1, + 7971, 8030, 8031, -1, 8031, 7970, 7971, -1, + 7970, 8031, 8032, -1, 8032, 7969, 7970, -1, + 7969, 8032, 8033, -1, 7969, 8033, 8034, -1, + 8034, 7968, 7969, -1, 7968, 8034, 8035, -1, + 8035, 7967, 7968, -1, 7967, 8035, 8036, -1, + 8036, 7966, 7967, -1, 7966, 8036, 8037, -1, + 8037, 7965, 7966, -1, 7965, 8037, 8038, -1, + 8038, 7964, 7965, -1, 7964, 8038, 8039, -1, + 8039, 7963, 7964, -1, 7963, 8039, 8040, -1, + 8040, 7962, 7963, -1, 7962, 8040, 8041, -1, + 8041, 7961, 7962, -1, 7961, 8041, 8042, -1, + 8042, 7960, 7961, -1, 7960, 8042, 8043, -1, + 8043, 7959, 7960, -1, 7959, 8043, 8044, -1, + 8044, 7958, 7959, -1, 7958, 8044, 8045, -1, + 8045, 7957, 7958, -1, 7957, 8045, 8046, -1, + 8046, 7956, 7957, -1, 7956, 8046, 8047, -1, + 8047, 7955, 7956, -1, 7955, 8047, 8048, -1, + 8048, 7954, 7955, -1, 7954, 8048, 8049, -1, + 8049, 7953, 7954, -1, 7953, 8049, 8050, -1, + 8050, 7952, 7953, -1, 7952, 8050, 8051, -1, + 8051, 7951, 7952, -1, 7951, 8051, 8052, -1, + 8052, 7950, 7951, -1, 7950, 8052, 8053, -1, + 8053, 7949, 7950, -1, 7949, 8053, 8054, -1, + 8054, 235, 7949, -1, 8054, 233, 235, -1, + 8054, 232, 233, -1, 232, 8054, 8053, -1, + 8053, 231, 232, -1, 231, 8053, 8052, -1, + 8052, 230, 231, -1, 230, 8052, 8051, -1, + 8051, 229, 230, -1, 229, 8051, 8050, -1, + 8050, 228, 229, -1, 228, 8050, 8049, -1, + 8049, 227, 228, -1, 227, 8049, 8048, -1, + 8048, 226, 227, -1, 226, 8048, 8047, -1, + 8047, 225, 226, -1, 225, 8047, 8046, -1, + 8046, 224, 225, -1, 224, 8046, 8045, -1, + 8045, 223, 224, -1, 223, 8045, 8044, -1, + 8044, 222, 223, -1, 222, 8044, 8043, -1, + 8043, 221, 222, -1, 221, 8043, 8042, -1, + 8042, 220, 221, -1, 220, 8042, 8041, -1, + 8041, 219, 220, -1, 219, 8041, 8040, -1, + 8040, 218, 219, -1, 218, 8040, 8039, -1, + 8039, 217, 218, -1, 217, 8039, 8038, -1, + 8038, 216, 217, -1, 216, 8038, 8037, -1, + 8037, 215, 216, -1, 215, 8037, 8036, -1, + 8036, 442, 215, -1, 442, 8036, 8035, -1, + 8035, 443, 442, -1, 443, 8035, 8034, -1, + 8034, 444, 443, -1, 444, 8034, 8033, -1, + 8033, 445, 444, -1, 8033, 446, 445, -1, + 446, 8033, 8032, -1, 8032, 447, 446, -1, + 447, 8032, 8031, -1, 8031, 448, 447, -1, + 448, 8031, 8030, -1, 8030, 449, 448, -1, + 449, 8030, 7994, -1, 7994, 450, 449, -1, + 450, 7994, 7993, -1, 7993, 452, 450, -1, + 452, 7993, 7996, -1, 7996, 454, 452, -1, + 454, 7996, 7998, -1, 7998, 456, 454, -1, + 456, 7998, 8000, -1, 8000, 458, 456, -1, + 458, 8000, 8002, -1, 8002, 460, 458, -1, + 460, 8002, 8004, -1, 8004, 462, 460, -1, + 462, 8004, 8006, -1, 8006, 464, 462, -1, + 464, 8006, 8008, -1, 8008, 466, 464, -1, + 466, 8008, 8010, -1, 8010, 468, 466, -1, + 468, 8010, 8012, -1, 8012, 470, 468, -1, + 470, 8012, 8014, -1, 8014, 472, 470, -1, + 472, 8014, 8016, -1, 8016, 474, 472, -1, + 474, 8016, 8018, -1, 8018, 476, 474, -1, + 476, 8018, 8020, -1, 8020, 478, 476, -1, + 478, 8020, 8022, -1, 8022, 480, 478, -1, + 480, 8022, 8024, -1, 8024, 482, 480, -1, + 482, 8024, 8026, -1, 8026, 484, 482, -1, + 484, 8026, 8028, -1, 8028, 486, 484, -1, + 486, 8028, 58, -1, 58, 59, 486, -1, + 59, 487, 486, -1, 59, 7485, 487, -1, + 7485, 59, 60, -1, 60, 7484, 7485, -1, + 7484, 60, 61, -1, 61, 7483, 7484, -1, + 7483, 61, 62, -1, 62, 7482, 7483, -1, + 7482, 62, 65, -1, 65, 7480, 7482, -1, + 7480, 65, 64, -1, 8055, 7480, 64, -1, + 8055, 8056, 7480, -1, 8056, 7481, 7480, -1, + 8056, 8057, 7481, -1, 8056, 8055, 8057, -1, + 8055, 64, 8057, -1, 64, 63, 8057, -1, + 7, 8057, 63, -1, 63, 66, 7, -1, + 66, 8058, 7, -1, 8058, 66, 67, -1, + 8058, 67, 68, -1, 68, 7, 8058, -1, + 68, 69, 7, -1, 69, 8, 7, -1, + 8, 69, 70, -1, 8, 70, 72, -1, + 72, 9, 8, -1, 72, 8059, 9, -1, + 8059, 72, 71, -1, 8059, 71, 76, -1, + 76, 9, 8059, -1, 76, 74, 9, -1, + 74, 73, 9, -1, 73, 8060, 9, -1, + 73, 75, 8060, -1, 75, 8061, 8060, -1, + 8061, 75, 77, -1, 77, 8062, 8061, -1, + 8062, 77, 78, -1, 8062, 78, 8063, -1, + 8064, 8065, 8066, -1, 8066, 8067, 8064, -1, + 8067, 8066, 8068, -1, 8068, 8069, 8067, -1, + 8069, 8068, 8070, -1, 8070, 8071, 8069, -1, + 8071, 8070, 8072, -1, 8072, 8073, 8071, -1, + 8073, 8072, 8074, -1, 8074, 8075, 8073, -1, + 8075, 8074, 8076, -1, 8076, 8077, 8075, -1, + 8077, 8076, 8078, -1, 8078, 8079, 8077, -1, + 8079, 8078, 8080, -1, 8080, 8081, 8079, -1, + 8081, 8080, 8082, -1, 8082, 8083, 8081, -1, + 8083, 8082, 8084, -1, 8084, 8085, 8083, -1, + 8085, 8084, 8086, -1, 8086, 8087, 8085, -1, + 8087, 8086, 8088, -1, 8088, 8089, 8087, -1, + 8089, 8088, 8090, -1, 8090, 8091, 8089, -1, + 8091, 8090, 8092, -1, 8092, 8093, 8091, -1, + 8093, 8092, 8094, -1, 8094, 8095, 8093, -1, + 8095, 8094, 8096, -1, 8096, 8097, 8095, -1, + 8097, 8096, 8098, -1, 8098, 8099, 8097, -1, + 8099, 8098, 8100, -1, 8100, 8101, 8099, -1, + 8101, 8100, 8102, -1, 8102, 8103, 8101, -1, + 8103, 8102, 8104, -1, 8104, 8105, 8103, -1, + 8105, 8104, 8106, -1, 8106, 8107, 8105, -1, + 8107, 8106, 8063, -1, 8107, 8063, 78, -1, + 8107, 78, 79, -1, 79, 8105, 8107, -1, + 8105, 79, 80, -1, 80, 8103, 8105, -1, + 8103, 80, 81, -1, 81, 8101, 8103, -1, + 8101, 81, 82, -1, 82, 8099, 8101, -1, + 8099, 82, 83, -1, 83, 8097, 8099, -1, + 8097, 83, 84, -1, 84, 8095, 8097, -1, + 8095, 84, 85, -1, 85, 8093, 8095, -1, + 8093, 85, 86, -1, 86, 8091, 8093, -1, + 8091, 86, 87, -1, 87, 8089, 8091, -1, + 8089, 87, 88, -1, 88, 8087, 8089, -1, + 8087, 88, 89, -1, 89, 8085, 8087, -1, + 8085, 89, 90, -1, 90, 8083, 8085, -1, + 8083, 90, 91, -1, 91, 8081, 8083, -1, + 8081, 91, 92, -1, 92, 8079, 8081, -1, + 8079, 92, 93, -1, 93, 8077, 8079, -1, + 8077, 93, 94, -1, 94, 8075, 8077, -1, + 8075, 94, 95, -1, 95, 8073, 8075, -1, + 8073, 95, 96, -1, 96, 8071, 8073, -1, + 8071, 96, 97, -1, 97, 8069, 8071, -1, + 8069, 97, 98, -1, 98, 8067, 8069, -1, + 8067, 98, 100, -1, 100, 8064, 8067, -1, + 8064, 100, 102, -1, 8064, 102, 105, -1, + 105, 8065, 8064, -1, 8065, 105, 107, -1, + 107, 8108, 8065, -1, 8108, 107, 7928, -1, + 7928, 8109, 8108, -1, 8109, 7928, 7926, -1, + 7926, 8110, 8109, -1, 8110, 7926, 7924, -1, + 7924, 8111, 8110, -1, 8111, 7924, 7922, -1, + 7922, 8112, 8111, -1, 8112, 7922, 7920, -1, + 7920, 8113, 8112, -1, 8113, 7920, 7918, -1, + 7918, 8114, 8113, -1, 8114, 7918, 7916, -1, + 7916, 8115, 8114, -1, 8115, 7916, 7914, -1, + 7914, 8116, 8115, -1, 8116, 7914, 7912, -1, + 7912, 8117, 8116, -1, 8117, 7912, 7910, -1, + 7910, 8118, 8117, -1, 8118, 7910, 7908, -1, + 7908, 8119, 8118, -1, 8119, 7908, 7906, -1, + 7906, 8120, 8119, -1, 8120, 7906, 7904, -1, + 7904, 8121, 8120, -1, 8121, 7904, 7902, -1, + 7902, 8122, 8121, -1, 8122, 7902, 7900, -1, + 7900, 8123, 8122, -1, 8123, 7900, 7898, -1, + 7898, 8124, 8123, -1, 8124, 7898, 7896, -1, + 7896, 8125, 8124, -1, 8125, 7896, 7894, -1, + 7894, 8126, 8125, -1, 8126, 7894, 7886, -1, + 8126, 7886, 7885, -1, 8126, 7885, 8127, -1, + 8127, 8125, 8126, -1, 8125, 8127, 8128, -1, + 8128, 8124, 8125, -1, 8124, 8128, 8129, -1, + 8129, 8123, 8124, -1, 8123, 8129, 8130, -1, + 8130, 8122, 8123, -1, 8122, 8130, 8131, -1, + 8131, 8121, 8122, -1, 8121, 8131, 8132, -1, + 8132, 8120, 8121, -1, 8120, 8132, 8133, -1, + 8133, 8119, 8120, -1, 8119, 8133, 8134, -1, + 8134, 8118, 8119, -1, 8118, 8134, 8135, -1, + 8135, 8117, 8118, -1, 8117, 8135, 8136, -1, + 8136, 8116, 8117, -1, 8116, 8136, 8137, -1, + 8137, 8115, 8116, -1, 8115, 8137, 8138, -1, + 8138, 8114, 8115, -1, 8114, 8138, 8139, -1, + 8139, 8113, 8114, -1, 8113, 8139, 8140, -1, + 8140, 8112, 8113, -1, 8112, 8140, 8141, -1, + 8141, 8111, 8112, -1, 8111, 8141, 8142, -1, + 8142, 8110, 8111, -1, 8110, 8142, 8143, -1, + 8143, 8109, 8110, -1, 8109, 8143, 8144, -1, + 8144, 8108, 8109, -1, 8108, 8144, 8145, -1, + 8145, 8065, 8108, -1, 8145, 8066, 8065, -1, + 8145, 8146, 8066, -1, 8146, 8145, 8144, -1, + 8144, 8147, 8146, -1, 8147, 8144, 8143, -1, + 8143, 8148, 8147, -1, 8148, 8143, 8142, -1, + 8142, 8149, 8148, -1, 8149, 8142, 8141, -1, + 8141, 8150, 8149, -1, 8150, 8141, 8140, -1, + 8140, 8151, 8150, -1, 8151, 8140, 8139, -1, + 8139, 8152, 8151, -1, 8152, 8139, 8138, -1, + 8138, 8153, 8152, -1, 8153, 8138, 8137, -1, + 8137, 8154, 8153, -1, 8154, 8137, 8136, -1, + 8136, 8155, 8154, -1, 8155, 8136, 8135, -1, + 8135, 8156, 8155, -1, 8156, 8135, 8134, -1, + 8134, 8157, 8156, -1, 8157, 8134, 8133, -1, + 8133, 8158, 8157, -1, 8158, 8133, 8132, -1, + 8132, 8159, 8158, -1, 8159, 8132, 8131, -1, + 8131, 8160, 8159, -1, 8160, 8131, 8130, -1, + 8130, 8161, 8160, -1, 8161, 8130, 8129, -1, + 8129, 8162, 8161, -1, 8162, 8129, 8128, -1, + 8128, 8163, 8162, -1, 8163, 8128, 8127, -1, + 8127, 8164, 8163, -1, 8164, 8127, 7885, -1, + 7885, 8165, 8164, -1, 8165, 7885, 110, -1, + 8165, 110, 109, -1, 8165, 109, 7877, -1, + 7877, 8164, 8165, -1, 8164, 7877, 7876, -1, + 7876, 8163, 8164, -1, 8163, 7876, 7875, -1, + 7875, 8162, 8163, -1, 8162, 7875, 7874, -1, + 7874, 8161, 8162, -1, 8161, 7874, 7873, -1, + 7873, 8160, 8161, -1, 8160, 7873, 7872, -1, + 7872, 8159, 8160, -1, 8159, 7872, 7871, -1, + 7871, 8158, 8159, -1, 8158, 7871, 7870, -1, + 7870, 8157, 8158, -1, 8157, 7870, 7869, -1, + 7869, 8156, 8157, -1, 8156, 7869, 7868, -1, + 7868, 8155, 8156, -1, 8155, 7868, 7867, -1, + 7867, 8154, 8155, -1, 8154, 7867, 7866, -1, + 7866, 8153, 8154, -1, 8153, 7866, 7865, -1, + 7865, 8152, 8153, -1, 8152, 7865, 7864, -1, + 7864, 8151, 8152, -1, 8151, 7864, 7863, -1, + 7863, 8150, 8151, -1, 8150, 7863, 7862, -1, + 7862, 8149, 8150, -1, 8149, 7862, 7861, -1, + 7861, 8148, 8149, -1, 8148, 7861, 7860, -1, + 7860, 8147, 8148, -1, 8147, 7860, 7859, -1, + 7859, 8146, 8147, -1, 8146, 7859, 7858, -1, + 7858, 8066, 8146, -1, 7858, 8068, 8066, -1, + 8068, 7858, 7857, -1, 7857, 8070, 8068, -1, + 8070, 7857, 7856, -1, 7856, 8072, 8070, -1, + 8072, 7856, 7855, -1, 7855, 8074, 8072, -1, + 8074, 7855, 7854, -1, 7854, 8076, 8074, -1, + 8076, 7854, 7853, -1, 7853, 8078, 8076, -1, + 8078, 7853, 7852, -1, 7852, 8080, 8078, -1, + 8080, 7852, 7851, -1, 7851, 8082, 8080, -1, + 8082, 7851, 7850, -1, 7850, 8084, 8082, -1, + 8084, 7850, 7849, -1, 7849, 8086, 8084, -1, + 8086, 7849, 7848, -1, 7848, 8088, 8086, -1, + 8088, 7848, 7847, -1, 7847, 8090, 8088, -1, + 8090, 7847, 7846, -1, 7846, 8092, 8090, -1, + 8092, 7846, 7845, -1, 7845, 8094, 8092, -1, + 8094, 7845, 7844, -1, 7844, 8096, 8094, -1, + 8096, 7844, 7843, -1, 7843, 8098, 8096, -1, + 8098, 7843, 7842, -1, 7842, 8100, 8098, -1, + 8100, 7842, 7841, -1, 7841, 8102, 8100, -1, + 8102, 7841, 7840, -1, 7840, 8104, 8102, -1, + 8104, 7840, 7839, -1, 7839, 8106, 8104, -1, + 8106, 7839, 7838, -1, 7838, 8063, 8106, -1, + 8063, 7838, 6794, -1, 6794, 8062, 8063, -1, + 8062, 6794, 6796, -1, 6796, 8061, 8062, -1, + 8061, 6796, 6802, -1, 8166, 8061, 6802, -1, + 8166, 6802, 6803, -1, 8166, 6803, 8167, -1, + 8167, 8061, 8166, -1, 8167, 8060, 8061, -1, + 8167, 6803, 8060, -1, 6803, 9, 8060, -1, + 8168, 6810, 6812, -1, 8169, 8168, 6812, -1, + 6812, 6814, 8169, -1, 8169, 6814, 6841, -1, + 6841, 8168, 8169, -1, 6841, 6842, 8168, -1, + 6842, 6843, 8168, -1, 6843, 6844, 8168, -1, + 8170, 8171, 8172, -1, 8173, 8168, 6844, -1, + 6844, 8174, 8173, -1, 8174, 6844, 805, -1, + 8174, 805, 804, -1, 804, 8173, 8174, -1, + 804, 8175, 8173, -1, 8175, 804, 803, -1, + 8176, 8175, 803, -1, 8176, 8173, 8175, -1, + 8176, 8177, 8173, -1, 8176, 803, 8177, -1, + 8178, 8177, 803, -1, 8178, 803, 845, -1, + 845, 844, 8178, -1, 8179, 8180, 8178, -1, + 8179, 8178, 844, -1, 844, 846, 8179, -1, + 8181, 8182, 8183, -1, 8184, 8182, 8181, -1, + 8181, 8185, 8184, -1, 8181, 8183, 8185, -1, + 8185, 8183, 8179, -1, 8185, 8179, 846, -1, + 846, 8186, 8185, -1, 8186, 846, 847, -1, + 847, 8187, 8186, -1, 8187, 847, 848, -1, + 848, 8188, 8187, -1, 8188, 848, 849, -1, + 849, 8189, 8188, -1, 8189, 849, 850, -1, + 850, 8190, 8189, -1, 8190, 850, 851, -1, + 851, 8191, 8190, -1, 8191, 851, 852, -1, + 852, 8192, 8191, -1, 8192, 852, 853, -1, + 853, 8193, 8192, -1, 8193, 853, 854, -1, + 854, 8194, 8193, -1, 8194, 854, 855, -1, + 855, 8195, 8194, -1, 8195, 855, 856, -1, + 856, 8196, 8195, -1, 8196, 856, 857, -1, + 857, 8197, 8196, -1, 8197, 857, 858, -1, + 858, 8198, 8197, -1, 8198, 858, 859, -1, + 859, 8199, 8198, -1, 8199, 859, 860, -1, + 860, 8200, 8199, -1, 8200, 860, 861, -1, + 861, 8201, 8200, -1, 8201, 861, 862, -1, + 862, 8202, 8201, -1, 8202, 862, 863, -1, + 863, 8203, 8202, -1, 8203, 863, 864, -1, + 864, 8204, 8203, -1, 8204, 864, 865, -1, + 865, 8205, 8204, -1, 8205, 865, 1018, -1, + 1018, 8206, 8205, -1, 8206, 1018, 1016, -1, + 1016, 8207, 8206, -1, 8207, 1016, 1014, -1, + 1014, 8208, 8207, -1, 8208, 1014, 1012, -1, + 1012, 8209, 8208, -1, 8209, 1012, 1010, -1, + 1010, 8210, 8209, -1, 8210, 1010, 1008, -1, + 1008, 8211, 8210, -1, 8211, 1008, 1006, -1, + 1006, 8212, 8211, -1, 8212, 1006, 1004, -1, + 1004, 8213, 8212, -1, 8213, 1004, 1002, -1, + 1002, 8214, 8213, -1, 8214, 1002, 1000, -1, + 1000, 8215, 8214, -1, 8215, 1000, 998, -1, + 998, 8216, 8215, -1, 8216, 998, 996, -1, + 996, 8217, 8216, -1, 8217, 996, 994, -1, + 994, 8218, 8217, -1, 8218, 994, 992, -1, + 992, 8219, 8218, -1, 8219, 992, 990, -1, + 990, 8220, 8219, -1, 8220, 990, 988, -1, + 988, 8221, 8220, -1, 8221, 988, 986, -1, + 986, 8222, 8221, -1, 8222, 986, 984, -1, + 984, 8223, 8222, -1, 8223, 984, 981, -1, + 8223, 981, 980, -1, 8223, 980, 7059, -1, + 7059, 8222, 8223, -1, 8222, 7059, 7058, -1, + 7058, 8221, 8222, -1, 8221, 7058, 7057, -1, + 7057, 8220, 8221, -1, 8220, 7057, 7056, -1, + 7056, 8219, 8220, -1, 8219, 7056, 7055, -1, + 7055, 8218, 8219, -1, 8218, 7055, 7054, -1, + 7054, 8217, 8218, -1, 8217, 7054, 7053, -1, + 7053, 8216, 8217, -1, 8216, 7053, 7052, -1, + 7052, 8215, 8216, -1, 8215, 7052, 7051, -1, + 7051, 8214, 8215, -1, 8214, 7051, 7050, -1, + 7050, 8213, 8214, -1, 8213, 7050, 7049, -1, + 7049, 8212, 8213, -1, 8212, 7049, 7048, -1, + 7048, 8211, 8212, -1, 8211, 7048, 7047, -1, + 7047, 8210, 8211, -1, 8210, 7047, 7046, -1, + 7046, 8209, 8210, -1, 8209, 7046, 7045, -1, + 7045, 8208, 8209, -1, 8208, 7045, 7044, -1, + 7044, 8207, 8208, -1, 8207, 7044, 7043, -1, + 7043, 8206, 8207, -1, 8206, 7043, 7042, -1, + 7042, 8205, 8206, -1, 8205, 7042, 7041, -1, + 7041, 8204, 8205, -1, 8204, 7041, 7040, -1, + 7040, 8203, 8204, -1, 8203, 7040, 7039, -1, + 7039, 8202, 8203, -1, 8202, 7039, 7038, -1, + 7038, 8201, 8202, -1, 8201, 7038, 7037, -1, + 7037, 8200, 8201, -1, 8200, 7037, 7036, -1, + 7036, 8199, 8200, -1, 8199, 7036, 7035, -1, + 7035, 8198, 8199, -1, 8198, 7035, 7034, -1, + 7034, 8197, 8198, -1, 8197, 7034, 7033, -1, + 7033, 8196, 8197, -1, 8196, 7033, 7032, -1, + 7032, 8195, 8196, -1, 8195, 7032, 7031, -1, + 7031, 8194, 8195, -1, 8194, 7031, 7030, -1, + 7030, 8193, 8194, -1, 8193, 7030, 7029, -1, + 7029, 8192, 8193, -1, 8192, 7029, 7028, -1, + 7028, 8191, 8192, -1, 8191, 7028, 7027, -1, + 7027, 8190, 8191, -1, 8190, 7027, 7026, -1, + 7026, 8189, 8190, -1, 8189, 7026, 7025, -1, + 7025, 8188, 8189, -1, 8188, 7025, 7024, -1, + 7024, 8187, 8188, -1, 8187, 7024, 7023, -1, + 7023, 8186, 8187, -1, 8186, 7023, 7022, -1, + 7022, 8185, 8186, -1, 7022, 8184, 8185, -1, + 8184, 7022, 8224, -1, 8224, 8182, 8184, -1, + 8224, 8225, 8182, -1, 8225, 8224, 7022, -1, + 8225, 7022, 6941, -1, 6941, 8182, 8225, -1, + 8182, 6941, 6940, -1, 5, 8183, 8182, -1, + 8183, 5, 4, -1, 4, 8179, 8183, -1, + 4, 6, 8179, -1, 6, 8180, 8179, -1, + 8180, 6, 5, -1, 8180, 5, 8226, -1, + 8226, 8178, 8180, -1, 8226, 8177, 8178, -1, + 8226, 5, 8177, -1, 5, 8173, 8177, -1, + 8227, 8228, 8170, -1, 8227, 8229, 8230, -1, + 8229, 6940, 6945, -1, 8231, 8229, 6945, -1, + 6945, 8232, 8231, -1, 6945, 6944, 8232, -1, + 8232, 6944, 6946, -1, 8232, 6946, 7018, -1, + 7018, 8233, 8232, -1, 8233, 7018, 7016, -1, + 7016, 8234, 8233, -1, 8234, 7016, 7014, -1, + 7014, 8235, 8234, -1, 8235, 7014, 7012, -1, + 7012, 8236, 8235, -1, 8236, 7012, 7010, -1, + 7010, 8237, 8236, -1, 8237, 7010, 7008, -1, + 7008, 8238, 8237, -1, 8238, 7008, 7006, -1, + 7006, 8239, 8238, -1, 8239, 7006, 7004, -1, + 7004, 8240, 8239, -1, 8240, 7004, 7002, -1, + 7002, 8241, 8240, -1, 8241, 7002, 7000, -1, + 7000, 8242, 8241, -1, 8242, 7000, 6998, -1, + 6998, 8243, 8242, -1, 8243, 6998, 6996, -1, + 6996, 8244, 8243, -1, 8244, 6996, 6994, -1, + 6994, 8245, 8244, -1, 8245, 6994, 6992, -1, + 6992, 8246, 8245, -1, 8246, 6992, 6990, -1, + 6990, 8247, 8246, -1, 8247, 6990, 6988, -1, + 6988, 8248, 8247, -1, 8248, 6988, 6986, -1, + 6986, 8249, 8248, -1, 8249, 6986, 6984, -1, + 6984, 8250, 8249, -1, 8250, 6984, 6982, -1, + 6982, 8251, 8250, -1, 8251, 6982, 6980, -1, + 6980, 8252, 8251, -1, 8252, 6980, 6978, -1, + 6978, 8253, 8252, -1, 8253, 6978, 6976, -1, + 6976, 8254, 8253, -1, 8254, 6976, 6974, -1, + 6974, 8255, 8254, -1, 8255, 6974, 6972, -1, + 6972, 8256, 8255, -1, 8256, 6972, 6970, -1, + 6970, 8257, 8256, -1, 8257, 6970, 6968, -1, + 6968, 8258, 8257, -1, 8258, 6968, 6966, -1, + 6966, 8259, 8258, -1, 8259, 6966, 6964, -1, + 6964, 8260, 8259, -1, 8260, 6964, 6962, -1, + 6962, 8261, 8260, -1, 8261, 6962, 6960, -1, + 6960, 8262, 8261, -1, 8262, 6960, 6958, -1, + 6958, 8263, 8262, -1, 8263, 6958, 6956, -1, + 6956, 8264, 8263, -1, 8264, 6956, 6954, -1, + 6954, 8265, 8264, -1, 8265, 6954, 6952, -1, + 6952, 8266, 8265, -1, 8266, 6952, 6950, -1, + 6950, 8267, 8266, -1, 8267, 6950, 6947, -1, + 6947, 672, 8267, -1, 672, 8268, 8267, -1, + 672, 671, 8268, -1, 8269, 8270, 8271, -1, + 8269, 8272, 8270, -1, 8273, 8274, 8275, -1, + 8273, 8275, 8276, -1, 8276, 8277, 8273, -1, + 8277, 8276, 8278, -1, 8278, 8279, 8277, -1, + 8279, 8278, 8280, -1, 8280, 8281, 8279, -1, + 8280, 8282, 8281, -1, 8282, 8280, 8283, -1, + 8283, 8284, 8282, -1, 8284, 8283, 8272, -1, + 8272, 8269, 8284, -1, 8268, 8269, 8285, -1, + 8268, 8284, 8269, -1, 8284, 8268, 671, -1, + 671, 8282, 8284, -1, 8282, 671, 669, -1, + 669, 8281, 8282, -1, 8281, 669, 666, -1, + 8281, 666, 664, -1, 664, 8279, 8281, -1, + 8279, 664, 662, -1, 662, 8277, 8279, -1, + 8277, 662, 661, -1, 661, 8273, 8277, -1, + 661, 8286, 8273, -1, 8287, 8288, 8289, -1, + 8288, 8287, 8290, -1, 8290, 8291, 8288, -1, + 8291, 8290, 8292, -1, 8292, 8293, 8291, -1, + 8293, 8292, 8294, -1, 8294, 8295, 8293, -1, + 8295, 8294, 8296, -1, 8296, 8297, 8295, -1, + 8297, 8296, 8298, -1, 8298, 8299, 8297, -1, + 8299, 8298, 8300, -1, 8300, 8301, 8299, -1, + 8301, 8300, 8302, -1, 8302, 8303, 8301, -1, + 8303, 8302, 8304, -1, 8304, 8305, 8303, -1, + 8305, 8304, 8306, -1, 8306, 8307, 8305, -1, + 8307, 8306, 8308, -1, 8308, 8309, 8307, -1, + 8309, 8308, 8310, -1, 8310, 8311, 8309, -1, + 8311, 8310, 8312, -1, 8312, 8313, 8311, -1, + 8313, 8312, 8314, -1, 8314, 8315, 8313, -1, + 8315, 8314, 8316, -1, 8316, 8317, 8315, -1, + 8317, 8316, 8318, -1, 8318, 8319, 8317, -1, + 8319, 8318, 8320, -1, 8320, 8321, 8319, -1, + 8321, 8320, 8322, -1, 8322, 8286, 8321, -1, + 8322, 8273, 8286, -1, 8322, 8274, 8273, -1, + 8274, 8322, 8320, -1, 8320, 8323, 8274, -1, + 8323, 8320, 8318, -1, 8318, 8324, 8323, -1, + 8324, 8318, 8316, -1, 8316, 8325, 8324, -1, + 8325, 8316, 8314, -1, 8314, 8326, 8325, -1, + 8326, 8314, 8312, -1, 8312, 8327, 8326, -1, + 8327, 8312, 8310, -1, 8310, 8328, 8327, -1, + 8328, 8310, 8308, -1, 8308, 8329, 8328, -1, + 8329, 8308, 8306, -1, 8306, 8330, 8329, -1, + 8330, 8306, 8304, -1, 8304, 8331, 8330, -1, + 8331, 8304, 8302, -1, 8302, 8332, 8331, -1, + 8332, 8302, 8300, -1, 8300, 8333, 8332, -1, + 8333, 8300, 8298, -1, 8298, 8334, 8333, -1, + 8334, 8298, 8296, -1, 8296, 8335, 8334, -1, + 8335, 8296, 8294, -1, 8294, 8336, 8335, -1, + 8336, 8294, 8292, -1, 8292, 8337, 8336, -1, + 8337, 8292, 8290, -1, 8290, 8338, 8337, -1, + 8338, 8290, 8287, -1, 8287, 8339, 8338, -1, + 8339, 8287, 8289, -1, 8289, 8340, 8339, -1, + 8340, 8289, 8341, -1, 8341, 8342, 8340, -1, + 8342, 8341, 8343, -1, 8343, 8344, 8342, -1, + 8344, 8343, 8345, -1, 8345, 8346, 8344, -1, + 8346, 8345, 8347, -1, 8348, 8349, 8350, -1, + 8348, 8351, 8349, -1, 8351, 8348, 8352, -1, + 8352, 8353, 8351, -1, 8353, 8352, 8354, -1, + 8354, 8355, 8353, -1, 8355, 8354, 8356, -1, + 8356, 8357, 8355, -1, 8357, 8356, 8358, -1, + 8358, 8359, 8357, -1, 8359, 8358, 8360, -1, + 8360, 8361, 8359, -1, 8361, 8360, 8362, -1, + 8362, 8363, 8361, -1, 8363, 8362, 8364, -1, + 8364, 8365, 8363, -1, 8365, 8364, 8366, -1, + 8366, 8367, 8365, -1, 8367, 8366, 8368, -1, + 8368, 8369, 8367, -1, 8369, 8368, 8370, -1, + 8370, 8371, 8369, -1, 8371, 8370, 8347, -1, + 8347, 8372, 8371, -1, 8372, 8347, 8345, -1, + 8345, 8373, 8372, -1, 8373, 8345, 8343, -1, + 8343, 8374, 8373, -1, 8343, 8341, 8374, -1, + 8375, 8374, 8341, -1, 8375, 8341, 8289, -1, + 8289, 8376, 8375, -1, 8376, 8289, 8288, -1, + 8288, 8377, 8376, -1, 8377, 8288, 8291, -1, + 8291, 8378, 8377, -1, 8378, 8291, 8293, -1, + 8293, 8379, 8378, -1, 8379, 8293, 8295, -1, + 8295, 8380, 8379, -1, 8380, 8295, 8297, -1, + 8297, 8381, 8380, -1, 8381, 8297, 8299, -1, + 8299, 8382, 8381, -1, 8382, 8299, 8301, -1, + 8301, 8383, 8382, -1, 8383, 8301, 8303, -1, + 8303, 8384, 8383, -1, 8384, 8303, 8305, -1, + 8305, 8385, 8384, -1, 8385, 8305, 8307, -1, + 8307, 8386, 8385, -1, 8386, 8307, 8309, -1, + 8309, 8387, 8386, -1, 8387, 8309, 8311, -1, + 8311, 8388, 8387, -1, 8388, 8311, 8313, -1, + 8313, 8389, 8388, -1, 8389, 8313, 8315, -1, + 8315, 8390, 8389, -1, 8390, 8315, 8317, -1, + 8317, 8391, 8390, -1, 8391, 8317, 8319, -1, + 8319, 8392, 8391, -1, 8392, 8319, 8321, -1, + 8321, 8393, 8392, -1, 8393, 8321, 8286, -1, + 8286, 8394, 8393, -1, 8394, 8286, 661, -1, + 8394, 661, 660, -1, 8394, 660, 7061, -1, + 7061, 8393, 8394, -1, 8393, 7061, 7063, -1, + 7063, 8392, 8393, -1, 8392, 7063, 7065, -1, + 7065, 8391, 8392, -1, 8391, 7065, 7067, -1, + 7067, 8390, 8391, -1, 8390, 7067, 7069, -1, + 7069, 8389, 8390, -1, 8389, 7069, 7071, -1, + 7071, 8388, 8389, -1, 8388, 7071, 7073, -1, + 7073, 8387, 8388, -1, 8387, 7073, 7075, -1, + 7075, 8386, 8387, -1, 8386, 7075, 7077, -1, + 7077, 8385, 8386, -1, 8385, 7077, 7079, -1, + 7079, 8384, 8385, -1, 8384, 7079, 7081, -1, + 7081, 8383, 8384, -1, 8383, 7081, 7083, -1, + 7083, 8382, 8383, -1, 8382, 7083, 7085, -1, + 7085, 8381, 8382, -1, 8381, 7085, 7087, -1, + 7087, 8380, 8381, -1, 8380, 7087, 7089, -1, + 7089, 8379, 8380, -1, 8379, 7089, 7091, -1, + 7091, 8378, 8379, -1, 8378, 7091, 7093, -1, + 7093, 8377, 8378, -1, 8377, 7093, 7095, -1, + 7095, 8376, 8377, -1, 8376, 7095, 7097, -1, + 7097, 8375, 8376, -1, 8375, 7097, 7130, -1, + 7130, 8374, 8375, -1, 8374, 7130, 7128, -1, + 7128, 8373, 8374, -1, 8373, 7128, 7126, -1, + 7126, 8372, 8373, -1, 8372, 7126, 7124, -1, + 7124, 8371, 8372, -1, 8371, 7124, 7122, -1, + 7122, 8369, 8371, -1, 8369, 7122, 7120, -1, + 7120, 8367, 8369, -1, 8367, 7120, 7118, -1, + 7118, 8365, 8367, -1, 8365, 7118, 7116, -1, + 7116, 8363, 8365, -1, 8363, 7116, 7114, -1, + 7114, 8361, 8363, -1, 8361, 7114, 7112, -1, + 7112, 8359, 8361, -1, 8359, 7112, 7110, -1, + 7110, 8357, 8359, -1, 8357, 7110, 7108, -1, + 7108, 8355, 8357, -1, 8355, 7108, 7106, -1, + 7106, 8353, 8355, -1, 8353, 7106, 7104, -1, + 7104, 8351, 8353, -1, 8351, 7104, 7102, -1, + 7102, 8349, 8351, -1, 8349, 7102, 7098, -1, + 8349, 7098, 7154, -1, 7154, 8395, 8349, -1, + 8395, 7154, 7155, -1, 8395, 7155, 8396, -1, + 8396, 8349, 8395, -1, 8396, 8350, 8349, -1, + 8396, 7155, 8350, -1, 8350, 7155, 7165, -1, + 7165, 8348, 8350, -1, 7165, 8397, 8348, -1, + 7165, 7164, 8397, -1, 8397, 7164, 7342, -1, + 7342, 7339, 8397, -1, 7339, 8348, 8397, -1, + 7339, 8352, 8348, -1, 8352, 7339, 7337, -1, + 7337, 8354, 8352, -1, 8354, 7337, 7335, -1, + 7335, 8356, 8354, -1, 8356, 7335, 7333, -1, + 7333, 8358, 8356, -1, 8358, 7333, 7331, -1, + 7331, 8360, 8358, -1, 8360, 7331, 7329, -1, + 7329, 8362, 8360, -1, 8362, 7329, 7327, -1, + 7327, 8364, 8362, -1, 8364, 7327, 7325, -1, + 7325, 8366, 8364, -1, 8366, 7325, 7323, -1, + 7323, 8368, 8366, -1, 8368, 7323, 7321, -1, + 7321, 8370, 8368, -1, 8370, 7321, 7319, -1, + 7319, 8347, 8370, -1, 8347, 7319, 7318, -1, + 7318, 8346, 8347, -1, 8346, 7318, 7317, -1, + 7317, 8344, 8346, -1, 8344, 7317, 7316, -1, + 7316, 8342, 8344, -1, 8342, 7316, 7315, -1, + 7315, 8340, 8342, -1, 8340, 7315, 7169, -1, + 7169, 8339, 8340, -1, 8339, 7169, 7168, -1, + 7168, 8338, 8339, -1, 8338, 7168, 7171, -1, + 7171, 8337, 8338, -1, 8337, 7171, 7173, -1, + 7173, 8336, 8337, -1, 8336, 7173, 7175, -1, + 7175, 8335, 8336, -1, 8335, 7175, 7177, -1, + 7177, 8334, 8335, -1, 8334, 7177, 7179, -1, + 7179, 8333, 8334, -1, 8333, 7179, 7181, -1, + 7181, 8332, 8333, -1, 8332, 7181, 7183, -1, + 7183, 8331, 8332, -1, 8331, 7183, 7185, -1, + 7185, 8330, 8331, -1, 8330, 7185, 7187, -1, + 7187, 8329, 8330, -1, 8329, 7187, 7189, -1, + 7189, 8328, 8329, -1, 8328, 7189, 7191, -1, + 7191, 8327, 8328, -1, 8327, 7191, 7193, -1, + 7193, 8326, 8327, -1, 8326, 7193, 7195, -1, + 7195, 8325, 8326, -1, 8325, 7195, 7197, -1, + 7197, 8324, 8325, -1, 8324, 7197, 7199, -1, + 7199, 8323, 8324, -1, 8323, 7199, 7201, -1, + 7201, 8274, 8323, -1, 7201, 8275, 8274, -1, + 7201, 7200, 8275, -1, 8275, 7200, 7271, -1, + 8275, 7271, 7270, -1, 7270, 8276, 8275, -1, + 8276, 7270, 7269, -1, 7269, 8278, 8276, -1, + 8278, 7269, 7268, -1, 7268, 8280, 8278, -1, + 7268, 8283, 8280, -1, 8283, 7268, 7267, -1, + 7267, 8272, 8283, -1, 8272, 7267, 7266, -1, + 7266, 8270, 8272, -1, 8270, 7266, 7265, -1, + 8270, 7265, 8398, -1, 8399, 8400, 8401, -1, + 8401, 8402, 8399, -1, 8402, 8401, 8403, -1, + 8403, 8404, 8402, -1, 8404, 8403, 8405, -1, + 8405, 8406, 8404, -1, 8406, 8405, 8407, -1, + 8407, 8408, 8406, -1, 8408, 8407, 8409, -1, + 8409, 8410, 8408, -1, 8410, 8409, 8411, -1, + 8411, 8412, 8410, -1, 8412, 8411, 8413, -1, + 8413, 8414, 8412, -1, 8414, 8413, 8415, -1, + 8415, 8416, 8414, -1, 8416, 8415, 8417, -1, + 8417, 8418, 8416, -1, 8418, 8417, 8419, -1, + 8419, 8420, 8418, -1, 8420, 8419, 8421, -1, + 8421, 8422, 8420, -1, 8422, 8421, 8423, -1, + 8423, 8424, 8422, -1, 8424, 8423, 8425, -1, + 8425, 8426, 8424, -1, 8426, 8425, 8427, -1, + 8427, 8428, 8426, -1, 8428, 8427, 8429, -1, + 8429, 8430, 8428, -1, 8430, 8429, 8431, -1, + 8431, 8432, 8430, -1, 8432, 8431, 8398, -1, + 8432, 8398, 7265, -1, 8432, 7265, 7222, -1, + 7222, 8430, 8432, -1, 8430, 7222, 7221, -1, + 7221, 8428, 8430, -1, 8428, 7221, 7263, -1, + 7263, 8426, 8428, -1, 8426, 7263, 7261, -1, + 7261, 8424, 8426, -1, 8424, 7261, 7259, -1, + 7259, 8422, 8424, -1, 8422, 7259, 7257, -1, + 7257, 8420, 8422, -1, 8420, 7257, 7255, -1, + 7255, 8418, 8420, -1, 8418, 7255, 7253, -1, + 7253, 8416, 8418, -1, 8416, 7253, 7251, -1, + 7251, 8414, 8416, -1, 8414, 7251, 7249, -1, + 7249, 8412, 8414, -1, 8412, 7249, 7247, -1, + 7247, 8410, 8412, -1, 8410, 7247, 7245, -1, + 7245, 8408, 8410, -1, 8408, 7245, 7243, -1, + 7243, 8406, 8408, -1, 8406, 7243, 7241, -1, + 7241, 8404, 8406, -1, 8404, 7241, 7239, -1, + 7239, 8402, 8404, -1, 8402, 7239, 7237, -1, + 7237, 8399, 8402, -1, 8399, 7237, 7235, -1, + 7235, 8400, 8399, -1, 8400, 7235, 7233, -1, + 7233, 8433, 8400, -1, 8433, 7233, 7231, -1, + 7231, 8434, 8433, -1, 8434, 7231, 7229, -1, + 7229, 8435, 8434, -1, 8435, 7229, 7227, -1, + 7227, 8436, 8435, -1, 8436, 7227, 7225, -1, + 7225, 8437, 8436, -1, 8437, 7225, 7224, -1, + 7224, 8438, 8437, -1, 8438, 7224, 7454, -1, + 7454, 8439, 8438, -1, 8439, 7454, 7455, -1, + 7455, 8440, 8439, -1, 8440, 7455, 7456, -1, + 7456, 8441, 8440, -1, 8441, 7456, 7457, -1, + 7457, 8442, 8441, -1, 8442, 7457, 7458, -1, + 7458, 8443, 8442, -1, 8443, 7458, 7459, -1, + 7459, 8444, 8443, -1, 8444, 7459, 7460, -1, + 7460, 8445, 8444, -1, 8445, 7460, 7461, -1, + 7461, 8446, 8445, -1, 8446, 7461, 3, -1, + 3, 1, 8446, -1, 8447, 8448, 8449, -1, + 8449, 8450, 8447, -1, 8450, 8449, 8451, -1, + 8451, 8452, 8450, -1, 8452, 8451, 8453, -1, + 8453, 8454, 8452, -1, 8454, 8453, 8455, -1, + 8455, 8456, 8454, -1, 8456, 8455, 8457, -1, + 8457, 8458, 8456, -1, 8459, 8456, 8458, -1, + 8458, 8460, 8459, -1, 8460, 8458, 8461, -1, + 8461, 8462, 8460, -1, 8462, 8461, 8463, -1, + 8463, 8464, 8462, -1, 8464, 8463, 8465, -1, + 8465, 8466, 8464, -1, 8466, 8465, 8467, -1, + 8467, 8468, 8466, -1, 8468, 8467, 8469, -1, + 8469, 8470, 8468, -1, 8470, 8469, 8471, -1, + 8471, 8472, 8470, -1, 8472, 8471, 8473, -1, + 8473, 8474, 8472, -1, 8474, 8473, 8475, -1, + 8475, 8476, 8474, -1, 8476, 8475, 8477, -1, + 8477, 8478, 8476, -1, 8479, 8480, 8481, -1, + 8479, 8481, 8478, -1, 8478, 8477, 8479, -1, + 1, 8482, 8479, -1, 1, 8479, 8477, -1, + 8477, 8446, 1, -1, 8446, 8477, 8475, -1, + 8475, 8445, 8446, -1, 8445, 8475, 8473, -1, + 8473, 8444, 8445, -1, 8444, 8473, 8471, -1, + 8471, 8443, 8444, -1, 8443, 8471, 8469, -1, + 8469, 8442, 8443, -1, 8442, 8469, 8467, -1, + 8467, 8441, 8442, -1, 8441, 8467, 8465, -1, + 8465, 8440, 8441, -1, 8440, 8465, 8463, -1, + 8463, 8439, 8440, -1, 8439, 8463, 8461, -1, + 8461, 8438, 8439, -1, 8438, 8461, 8458, -1, + 8458, 8437, 8438, -1, 8437, 8458, 8457, -1, + 8457, 8436, 8437, -1, 8436, 8457, 8455, -1, + 8455, 8435, 8436, -1, 8435, 8455, 8453, -1, + 8453, 8434, 8435, -1, 8434, 8453, 8451, -1, + 8451, 8433, 8434, -1, 8433, 8451, 8449, -1, + 8449, 8400, 8433, -1, 8400, 8449, 8448, -1, + 8448, 8401, 8400, -1, 8401, 8448, 8483, -1, + 8483, 8403, 8401, -1, 8403, 8483, 8484, -1, + 8484, 8405, 8403, -1, 8405, 8484, 8485, -1, + 8485, 8407, 8405, -1, 8407, 8485, 8486, -1, + 8486, 8409, 8407, -1, 8409, 8486, 8487, -1, + 8487, 8411, 8409, -1, 8411, 8487, 8488, -1, + 8488, 8413, 8411, -1, 8413, 8488, 8489, -1, + 8489, 8415, 8413, -1, 8415, 8489, 8490, -1, + 8490, 8417, 8415, -1, 8417, 8490, 8491, -1, + 8491, 8419, 8417, -1, 8419, 8491, 8492, -1, + 8492, 8421, 8419, -1, 8421, 8492, 8493, -1, + 8493, 8423, 8421, -1, 8423, 8493, 8494, -1, + 8494, 8425, 8423, -1, 8425, 8494, 8495, -1, + 8495, 8427, 8425, -1, 8427, 8495, 8496, -1, + 8496, 8429, 8427, -1, 8429, 8496, 8497, -1, + 8497, 8431, 8429, -1, 8431, 8497, 8498, -1, + 8498, 8398, 8431, -1, 8398, 8498, 8499, -1, + 8499, 8270, 8398, -1, 8499, 8271, 8270, -1, + 8499, 8500, 8271, -1, 8500, 8499, 8498, -1, + 8498, 8501, 8500, -1, 8501, 8498, 8497, -1, + 8497, 8502, 8501, -1, 8502, 8497, 8496, -1, + 8496, 8503, 8502, -1, 8503, 8496, 8495, -1, + 8495, 8504, 8503, -1, 8504, 8495, 8494, -1, + 8494, 8505, 8504, -1, 8505, 8494, 8493, -1, + 8493, 8506, 8505, -1, 8506, 8493, 8492, -1, + 8492, 8507, 8506, -1, 8507, 8492, 8491, -1, + 8491, 8508, 8507, -1, 8508, 8491, 8490, -1, + 8490, 8509, 8508, -1, 8509, 8490, 8489, -1, + 8489, 8510, 8509, -1, 8510, 8489, 8488, -1, + 8488, 8511, 8510, -1, 8511, 8488, 8487, -1, + 8487, 8512, 8511, -1, 8512, 8487, 8486, -1, + 8486, 8513, 8512, -1, 8513, 8486, 8485, -1, + 8485, 8514, 8513, -1, 8514, 8485, 8484, -1, + 8484, 8515, 8514, -1, 8515, 8484, 8483, -1, + 8483, 8516, 8515, -1, 8516, 8483, 8448, -1, + 8448, 8447, 8516, -1, 8516, 8447, 8517, -1, + 8517, 8515, 8516, -1, 8515, 8517, 8518, -1, + 8518, 8514, 8515, -1, 8514, 8518, 8519, -1, + 8519, 8513, 8514, -1, 8513, 8519, 8520, -1, + 8520, 8512, 8513, -1, 8512, 8520, 8521, -1, + 8521, 8511, 8512, -1, 8511, 8521, 8522, -1, + 8522, 8510, 8511, -1, 8510, 8522, 8523, -1, + 8523, 8509, 8510, -1, 8509, 8523, 8524, -1, + 8524, 8508, 8509, -1, 8508, 8524, 8525, -1, + 8525, 8507, 8508, -1, 8507, 8525, 8526, -1, + 8526, 8506, 8507, -1, 8506, 8526, 8527, -1, + 8527, 8505, 8506, -1, 8505, 8527, 8528, -1, + 8528, 8504, 8505, -1, 8504, 8528, 8529, -1, + 8529, 8503, 8504, -1, 8503, 8529, 8530, -1, + 8530, 8502, 8503, -1, 8502, 8530, 8531, -1, + 8531, 8501, 8502, -1, 8501, 8531, 8532, -1, + 8532, 8500, 8501, -1, 8500, 8532, 8533, -1, + 8533, 8271, 8500, -1, 8271, 8533, 8534, -1, + 8534, 8269, 8271, -1, 8534, 8285, 8269, -1, + 8534, 8535, 8285, -1, 8535, 8534, 8533, -1, + 8533, 8536, 8535, -1, 8536, 8533, 8532, -1, + 8532, 8537, 8536, -1, 8537, 8532, 8531, -1, + 8531, 8538, 8537, -1, 8538, 8531, 8530, -1, + 8530, 8539, 8538, -1, 8539, 8530, 8529, -1, + 8529, 8540, 8539, -1, 8540, 8529, 8528, -1, + 8528, 8541, 8540, -1, 8541, 8528, 8527, -1, + 8527, 8542, 8541, -1, 8542, 8527, 8526, -1, + 8526, 8543, 8542, -1, 8543, 8526, 8525, -1, + 8525, 8544, 8543, -1, 8544, 8525, 8524, -1, + 8524, 8545, 8544, -1, 8545, 8524, 8523, -1, + 8523, 8546, 8545, -1, 8546, 8523, 8522, -1, + 8522, 8547, 8546, -1, 8547, 8522, 8521, -1, + 8521, 8548, 8547, -1, 8548, 8521, 8520, -1, + 8520, 8549, 8548, -1, 8549, 8520, 8519, -1, + 8519, 8550, 8549, -1, 8550, 8519, 8518, -1, + 8518, 8551, 8550, -1, 8551, 8518, 8517, -1, + 8517, 8552, 8551, -1, 8552, 8517, 8447, -1, + 8447, 8553, 8552, -1, 8553, 8447, 8450, -1, + 8450, 8554, 8553, -1, 8554, 8450, 8452, -1, + 8452, 8555, 8554, -1, 8555, 8452, 8454, -1, + 8454, 8556, 8555, -1, 8556, 8454, 8456, -1, + 8456, 8459, 8556, -1, 8556, 8459, 8557, -1, + 8557, 8555, 8556, -1, 8555, 8557, 8558, -1, + 8558, 8554, 8555, -1, 8554, 8558, 8559, -1, + 8559, 8553, 8554, -1, 8553, 8559, 8560, -1, + 8560, 8552, 8553, -1, 8552, 8560, 8561, -1, + 8561, 8551, 8552, -1, 8551, 8561, 8562, -1, + 8562, 8550, 8551, -1, 8550, 8562, 8563, -1, + 8563, 8549, 8550, -1, 8549, 8563, 8564, -1, + 8564, 8548, 8549, -1, 8548, 8564, 8565, -1, + 8565, 8547, 8548, -1, 8547, 8565, 8566, -1, + 8566, 8546, 8547, -1, 8546, 8566, 8567, -1, + 8567, 8545, 8546, -1, 8545, 8567, 8568, -1, + 8568, 8544, 8545, -1, 8544, 8568, 8569, -1, + 8569, 8543, 8544, -1, 8543, 8569, 8570, -1, + 8570, 8542, 8543, -1, 8542, 8570, 8571, -1, + 8571, 8541, 8542, -1, 8541, 8571, 8572, -1, + 8572, 8540, 8541, -1, 8540, 8572, 8573, -1, + 8573, 8539, 8540, -1, 8539, 8573, 8574, -1, + 8574, 8538, 8539, -1, 8538, 8574, 8575, -1, + 8575, 8537, 8538, -1, 8537, 8575, 8576, -1, + 8576, 8536, 8537, -1, 8536, 8576, 8577, -1, + 8577, 8535, 8536, -1, 8535, 8577, 8578, -1, + 8578, 8285, 8535, -1, 8285, 8578, 8579, -1, + 8579, 8268, 8285, -1, 8579, 8267, 8268, -1, + 8579, 8266, 8267, -1, 8266, 8579, 8578, -1, + 8578, 8265, 8266, -1, 8265, 8578, 8577, -1, + 8577, 8264, 8265, -1, 8264, 8577, 8576, -1, + 8576, 8263, 8264, -1, 8263, 8576, 8575, -1, + 8575, 8262, 8263, -1, 8262, 8575, 8574, -1, + 8574, 8261, 8262, -1, 8261, 8574, 8573, -1, + 8573, 8260, 8261, -1, 8260, 8573, 8572, -1, + 8572, 8259, 8260, -1, 8259, 8572, 8571, -1, + 8571, 8258, 8259, -1, 8258, 8571, 8570, -1, + 8570, 8257, 8258, -1, 8257, 8570, 8569, -1, + 8569, 8256, 8257, -1, 8256, 8569, 8568, -1, + 8568, 8255, 8256, -1, 8255, 8568, 8567, -1, + 8567, 8254, 8255, -1, 8254, 8567, 8566, -1, + 8566, 8253, 8254, -1, 8253, 8566, 8565, -1, + 8565, 8252, 8253, -1, 8252, 8565, 8564, -1, + 8564, 8251, 8252, -1, 8251, 8564, 8563, -1, + 8563, 8250, 8251, -1, 8250, 8563, 8562, -1, + 8562, 8249, 8250, -1, 8249, 8562, 8561, -1, + 8561, 8248, 8249, -1, 8248, 8561, 8560, -1, + 8560, 8247, 8248, -1, 8247, 8560, 8559, -1, + 8559, 8246, 8247, -1, 8246, 8559, 8558, -1, + 8558, 8245, 8246, -1, 8245, 8558, 8557, -1, + 8557, 8244, 8245, -1, 8244, 8557, 8459, -1, + 8459, 8243, 8244, -1, 8243, 8459, 8460, -1, + 8460, 8242, 8243, -1, 8242, 8460, 8462, -1, + 8462, 8241, 8242, -1, 8241, 8462, 8464, -1, + 8464, 8240, 8241, -1, 8240, 8464, 8466, -1, + 8466, 8239, 8240, -1, 8239, 8466, 8468, -1, + 8468, 8238, 8239, -1, 8238, 8468, 8470, -1, + 8470, 8237, 8238, -1, 8237, 8470, 8472, -1, + 8472, 8236, 8237, -1, 8236, 8472, 8474, -1, + 8474, 8235, 8236, -1, 8235, 8474, 8476, -1, + 8476, 8234, 8235, -1, 8234, 8476, 8478, -1, + 8478, 8233, 8234, -1, 8233, 8478, 8481, -1, + 8481, 8232, 8233, -1, 8481, 8231, 8232, -1, + 8231, 8481, 8580, -1, 8580, 8229, 8231, -1, + 8580, 8581, 8229, -1, 8581, 8580, 8481, -1, + 8581, 8481, 8480, -1, 8480, 8229, 8581, -1, + 8480, 8230, 8229, -1, 8230, 8480, 8479, -1, + 8230, 8479, 8482, -1, 8482, 8227, 8230, -1, + 8582, 8227, 8482, -1, 8582, 8482, 1, -1, + 8582, 1, 0, -1, 0, 8227, 8582, -1, + 0, 2, 8227, -1, 2, 8228, 8227, -1, + 8228, 2, 3, -1, 8228, 3, 7463, -1, + 7463, 8170, 8228, -1, 8583, 8170, 7463, -1, + 8583, 7463, 7462, -1, 8583, 7462, 7465, -1, + 7465, 8170, 8583, -1, 7465, 7464, 8170, -1, + 7464, 8171, 8170, -1, 8171, 7464, 7466, -1, + 7466, 7467, 8171, -1, 8584, 8171, 7467, -1, + 8584, 8172, 8171, -1, 8584, 8585, 8172, -1, + 8585, 8584, 7467, -1, 8585, 7467, 7476, -1, + 7476, 8172, 8585, -1, 7476, 7477, 8172, -1, + 7477, 7478, 8172, -1, 7478, 8586, 8172, -1, + 8586, 7478, 7479, -1, 8586, 7479, 7481, -1, + 8586, 7481, 8057, -1, 8057, 8172, 8586, -1, + 3693, 4406, 3694, -1, 3694, 4406, 4233, -1, + 4655, 4656, 8587, -1, 8587, 4656, 4658, -1, + 2080, 8588, 2081, -1, 2081, 8588, 6167, -1, + 6167, 8588, 6163, -1, 6163, 8588, 2080, -1, + 6604, 6638, 6679, -1, 6679, 6638, 6681, -1, + 6604, 6679, 6639, -1, 6639, 6679, 6678, -1, + 798, 7160, 7156, -1, 7156, 7160, 676, -1, + 676, 7160, 7155, -1, 7155, 7160, 2372, -1, + 7155, 2372, 7164, -1, 7164, 2372, 658, -1, + 658, 2372, 7655, -1, 7655, 2372, 2374, -1, + 7655, 2374, 2519, -1, 2519, 6163, 7655, -1, + 7655, 6163, 6162, -1, 7655, 6162, 6158, -1, + 6158, 6156, 7655, -1, 7655, 6156, 7660, -1, + 7655, 7660, 382, -1, 382, 7660, 131, -1, + 131, 7660, 243, -1, 243, 7660, 246, -1, + 246, 7660, 244, -1, 244, 7660, 253, -1, + 253, 7660, 6658, -1, 6658, 7660, 7752, -1, + 7752, 7660, 6515, -1, 6515, 7660, 7722, -1, + 7722, 7660, 6753, -1, 6753, 7660, 7664, -1, + 7664, 7660, 7662, -1, 7662, 7660, 7668, -1, + 7668, 7660, 7703, -1, 7703, 7660, 7714, -1, + 7703, 7714, 7695, -1, 7695, 7714, 7694, -1, + 7694, 7714, 6786, -1, 6786, 7714, 6414, -1, + 6786, 6414, 6790, -1, 6786, 6790, 6705, -1, + 6705, 6790, 6548, -1, 6548, 6790, 6547, -1, + 6547, 6790, 6452, -1, 6452, 6790, 6450, -1, + 6450, 6790, 257, -1, 257, 6790, 6800, -1, + 6800, 6790, 6803, -1, 6790, 6805, 6803, -1, + 6803, 6805, 2193, -1, 6803, 2193, 2194, -1, + 2194, 6810, 6803, -1, 6803, 6810, 8168, -1, + 6803, 8168, 9, -1, 9, 8168, 7, -1, + 7, 8168, 8057, -1, 8057, 8168, 8172, -1, + 8172, 8168, 8170, -1, 8170, 8168, 8173, -1, + 8170, 8173, 5, -1, 8170, 5, 8227, -1, + 8227, 5, 8229, -1, 8229, 5, 6940, -1, + 6940, 5, 8182, -1, 4655, 8587, 5595, -1, + 5595, 8587, 4658, -1, 2766, 6156, 6157, -1, + 6157, 6156, 2762, -1, 6550, 6546, 6543, -1, + 6543, 6546, 6545, -1, 6153, 8589, 7660, -1, + 7660, 8589, 2543, -1, 6153, 2545, 8589, -1, + 8589, 2545, 2543, -1, 8590, 8591, 2652, -1, + 2652, 8591, 2637, -1, 8591, 8592, 2637, -1, + 2637, 8592, 2947, -1, 8592, 8593, 2947, -1, + 2947, 8593, 2635, -1, 8593, 8594, 2635, -1, + 2635, 8594, 4072, -1, 8594, 8595, 4072, -1, + 4072, 8595, 4076, -1, 8595, 8596, 4076, -1, + 4076, 8596, 4104, -1, 4104, 8596, 6129, -1, + 6129, 8596, 8597, -1, 6129, 8597, 3679, -1, + 3679, 8597, 8598, -1, 3679, 8598, 6124, -1, + 6124, 8598, 8599, -1, 6124, 8599, 4531, -1, + 4531, 8599, 8600, -1, 4531, 8600, 6119, -1, + 6119, 8600, 8601, -1, 6119, 8601, 3090, -1, + 3090, 8601, 8602, -1, 3090, 8602, 5535, -1, + 5535, 8602, 8603, -1, 5535, 8603, 4643, -1, + 4643, 8603, 8604, -1, 4643, 8604, 4650, -1, + 4650, 8604, 8605, -1, 4650, 8605, 4648, -1, + 4648, 8605, 8606, -1, 4648, 8606, 4656, -1, + 4656, 8606, 8607, -1, 4656, 8607, 4662, -1, + 4662, 8607, 8608, -1, 4662, 8608, 4664, -1, + 4664, 8608, 4667, -1, 8608, 8609, 4667, -1, + 4667, 8609, 4672, -1, 8609, 8610, 4672, -1, + 4672, 8610, 4678, -1, 8610, 8611, 4678, -1, + 4678, 8611, 4687, -1, 8611, 8612, 4687, -1, + 4687, 8612, 4701, -1, 8612, 8613, 4701, -1, + 4701, 8613, 4702, -1, 8613, 8614, 4702, -1, + 4702, 8614, 5290, -1, 8614, 8615, 5290, -1, + 5290, 8615, 5287, -1, 8615, 8616, 5287, -1, + 5287, 8616, 4971, -1, 8616, 8617, 4971, -1, + 4971, 8617, 4967, -1, 8617, 8618, 4967, -1, + 4967, 8618, 4920, -1, 8618, 8619, 4920, -1, + 4920, 8619, 4921, -1, 4921, 8619, 4883, -1, + 4883, 8619, 8620, -1, 4883, 8620, 4879, -1, + 4879, 8620, 8621, -1, 4879, 8621, 4838, -1, + 4838, 8621, 8622, -1, 4838, 8622, 4708, -1, + 4708, 8622, 8623, -1, 4708, 8623, 4711, -1, + 4711, 8623, 8624, -1, 4711, 8624, 4833, -1, + 4833, 8624, 8625, -1, 4833, 8625, 4750, -1, + 4750, 8625, 8626, -1, 4750, 8626, 4793, -1, + 4793, 8626, 8627, -1, 4793, 8627, 4792, -1, + 4792, 8627, 8628, -1, 4792, 8628, 4776, -1, + 4776, 8628, 8629, -1, 4776, 8629, 4718, -1, + 4718, 8629, 8630, -1, 4718, 8630, 4594, -1, + 4594, 8630, 2957, -1, 8630, 8631, 2957, -1, + 2957, 8631, 4549, -1, 8631, 8632, 4549, -1, + 4549, 8632, 4547, -1, 8632, 8633, 4547, -1, + 4547, 8633, 4408, -1, 8633, 8634, 4408, -1, + 4408, 8634, 4404, -1, 8634, 8635, 4404, -1, + 4404, 8635, 4222, -1, 8635, 8636, 4222, -1, + 4222, 8636, 4220, -1, 8636, 8637, 4220, -1, + 4220, 8637, 4223, -1, 8637, 8638, 4223, -1, + 4223, 8638, 4227, -1, 8638, 8639, 4227, -1, + 4227, 8639, 4225, -1, 8639, 8640, 4225, -1, + 4225, 8640, 4228, -1, 8640, 8641, 4228, -1, + 4228, 8641, 1531, -1, 1531, 8641, 6197, -1, + 6197, 8641, 8642, -1, 6197, 8642, 1720, -1, + 1720, 8642, 8643, -1, 1720, 8643, 6192, -1, + 6192, 8643, 8644, -1, 6192, 8644, 6190, -1, + 6190, 8644, 8645, -1, 6190, 8645, 1169, -1, + 1169, 8645, 8590, -1, 1169, 8590, 2652, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5712, 5712, 5712, -1, 5713, 5713, 5713, -1, + 5714, 5714, 5714, -1, 5715, 5715, 5715, -1, + 5716, 5716, 5716, -1, 5717, 5717, 5717, -1, + 5718, 5718, 5718, -1, 5719, 5719, 5719, -1, + 5720, 5720, 5720, -1, 5721, 5721, 5721, -1, + 5722, 5722, 5722, -1, 5723, 5723, 5723, -1, + 5724, 5724, 5724, -1, 5725, 5725, 5725, -1, + 5726, 5726, 5726, -1, 5727, 5727, 5727, -1, + 5728, 5728, 5728, -1, 5729, 5729, 5729, -1, + 5730, 5730, 5730, -1, 5731, 5731, 5731, -1, + 5732, 5732, 5732, -1, 5733, 5733, 5733, -1, + 5734, 5734, 5734, -1, 5735, 5735, 5735, -1, + 5736, 5736, 5736, -1, 5737, 5737, 5737, -1, + 5738, 5738, 5738, -1, 5739, 5739, 5739, -1, + 5740, 5740, 5740, -1, 5741, 5741, 5741, -1, + 5742, 5742, 5742, -1, 5743, 5743, 5743, -1, + 5744, 5744, 5744, -1, 5745, 5745, 5745, -1, + 5746, 5746, 5746, -1, 5747, 5747, 5747, -1, + 5748, 5748, 5748, -1, 5749, 5749, 5749, -1, + 5750, 5750, 5750, -1, 5751, 5751, 5751, -1, + 5752, 5752, 5752, -1, 5753, 5753, 5753, -1, + 5754, 5754, 5754, -1, 5755, 5755, 5755, -1, + 5756, 5756, 5756, -1, 5757, 5757, 5757, -1, + 5758, 5758, 5758, -1, 5759, 5759, 5759, -1, + 5760, 5760, 5760, -1, 5761, 5761, 5761, -1, + 5762, 5762, 5762, -1, 5763, 5763, 5763, -1, + 5764, 5764, 5764, -1, 5765, 5765, 5765, -1, + 5766, 5766, 5766, -1, 5767, 5767, 5767, -1, + 5768, 5768, 5768, -1, 5769, 5769, 5769, -1, + 5770, 5770, 5770, -1, 5771, 5771, 5771, -1, + 5772, 5772, 5772, -1, 5773, 5773, 5773, -1, + 5774, 5774, 5774, -1, 5775, 5775, 5775, -1, + 5776, 5776, 5776, -1, 5777, 5777, 5777, -1, + 5778, 5778, 5778, -1, 5779, 5779, 5779, -1, + 5780, 5780, 5780, -1, 5781, 5781, 5781, -1, + 5782, 5782, 5782, -1, 5783, 5783, 5783, -1, + 5784, 5784, 5784, -1, 5785, 5785, 5785, -1, + 5786, 5786, 5786, -1, 5787, 5787, 5787, -1, + 5788, 5788, 5788, -1, 5789, 5789, 5789, -1, + 5790, 5790, 5790, -1, 5791, 5791, 5791, -1, + 5792, 5792, 5792, -1, 5793, 5793, 5793, -1, + 5794, 5794, 5794, -1, 5795, 5795, 5795, -1, + 5796, 5796, 5796, -1, 5797, 5797, 5797, -1, + 5798, 5798, 5798, -1, 5799, 5799, 5799, -1, + 5800, 5800, 5800, -1, 5801, 5801, 5801, -1, + 5802, 5802, 5802, -1, 5803, 5803, 5803, -1, + 5804, 5804, 5804, -1, 5805, 5805, 5805, -1, + 5806, 5806, 5806, -1, 5807, 5807, 5807, -1, + 5808, 5808, 5808, -1, 5809, 5809, 5809, -1, + 5810, 5810, 5810, -1, 5811, 5811, 5811, -1, + 5812, 5812, 5812, -1, 5813, 5813, 5813, -1, + 5814, 5814, 5814, -1, 5815, 5815, 5815, -1, + 5816, 5816, 5816, -1, 5817, 5817, 5817, -1, + 5818, 5818, 5818, -1, 5819, 5819, 5819, -1, + 5820, 5820, 5820, -1, 5821, 5821, 5821, -1, + 5822, 5822, 5822, -1, 5823, 5823, 5823, -1, + 5824, 5824, 5824, -1, 5825, 5825, 5825, -1, + 5826, 5826, 5826, -1, 5827, 5827, 5827, -1, + 5828, 5828, 5828, -1, 5829, 5829, 5829, -1, + 5830, 5830, 5830, -1, 5831, 5831, 5831, -1, + 5832, 5832, 5832, -1, 5833, 5833, 5833, -1, + 5834, 5834, 5834, -1, 5835, 5835, 5835, -1, + 5836, 5836, 5836, -1, 5837, 5837, 5837, -1, + 5838, 5838, 5838, -1, 5839, 5839, 5839, -1, + 5840, 5840, 5840, -1, 5841, 5841, 5841, -1, + 5842, 5842, 5842, -1, 5843, 5843, 5843, -1, + 5844, 5844, 5844, -1, 5845, 5845, 5845, -1, + 5846, 5846, 5846, -1, 5847, 5847, 5847, -1, + 5848, 5848, 5848, -1, 5849, 5849, 5849, -1, + 5850, 5850, 5850, -1, 5851, 5851, 5851, -1, + 5852, 5852, 5852, -1, 5853, 5853, 5853, -1, + 5854, 5854, 5854, -1, 5855, 5855, 5855, -1, + 5856, 5856, 5856, -1, 5857, 5857, 5857, -1, + 5858, 5858, 5858, -1, 5859, 5859, 5859, -1, + 5860, 5860, 5860, -1, 5861, 5861, 5861, -1, + 5862, 5862, 5862, -1, 5863, 5863, 5863, -1, + 5864, 5864, 5864, -1, 5865, 5865, 5865, -1, + 5866, 5866, 5866, -1, 5867, 5867, 5867, -1, + 5868, 5868, 5868, -1, 5869, 5869, 5869, -1, + 5870, 5870, 5870, -1, 5871, 5871, 5871, -1, + 5872, 5872, 5872, -1, 5873, 5873, 5873, -1, + 5874, 5874, 5874, -1, 5875, 5875, 5875, -1, + 5876, 5876, 5876, -1, 5877, 5877, 5877, -1, + 5878, 5878, 5878, -1, 5879, 5879, 5879, -1, + 5880, 5880, 5880, -1, 5881, 5881, 5881, -1, + 5882, 5882, 5882, -1, 5883, 5883, 5883, -1, + 5884, 5884, 5884, -1, 5885, 5885, 5885, -1, + 5886, 5886, 5886, -1, 5887, 5887, 5887, -1, + 5888, 5888, 5888, -1, 5889, 5889, 5889, -1, + 5890, 5890, 5890, -1, 5891, 5891, 5891, -1, + 5892, 5892, 5892, -1, 5893, 5893, 5893, -1, + 5894, 5894, 5894, -1, 5895, 5895, 5895, -1, + 5896, 5896, 5896, -1, 5897, 5897, 5897, -1, + 5898, 5898, 5898, -1, 5899, 5899, 5899, -1, + 5900, 5900, 5900, -1, 5901, 5901, 5901, -1, + 5902, 5902, 5902, -1, 5903, 5903, 5903, -1, + 5904, 5904, 5904, -1, 5905, 5905, 5905, -1, + 5906, 5906, 5906, -1, 5907, 5907, 5907, -1, + 5908, 5908, 5908, -1, 5909, 5909, 5909, -1, + 5910, 5910, 5910, -1, 5911, 5911, 5911, -1, + 5912, 5912, 5912, -1, 5913, 5913, 5913, -1, + 5914, 5914, 5914, -1, 5915, 5915, 5915, -1, + 5916, 5916, 5916, -1, 5917, 5917, 5917, -1, + 5918, 5918, 5918, -1, 5919, 5919, 5919, -1, + 5920, 5920, 5920, -1, 5921, 5921, 5921, -1, + 5922, 5922, 5922, -1, 5923, 5923, 5923, -1, + 5924, 5924, 5924, -1, 5925, 5925, 5925, -1, + 5926, 5926, 5926, -1, 5927, 5927, 5927, -1, + 5928, 5928, 5928, -1, 5929, 5929, 5929, -1, + 5930, 5930, 5930, -1, 5931, 5931, 5931, -1, + 5932, 5932, 5932, -1, 5933, 5933, 5933, -1, + 5934, 5934, 5934, -1, 5935, 5935, 5935, -1, + 5936, 5936, 5936, -1, 5937, 5937, 5937, -1, + 5938, 5938, 5938, -1, 5939, 5939, 5939, -1, + 5940, 5940, 5940, -1, 5941, 5941, 5941, -1, + 5942, 5942, 5942, -1, 5943, 5943, 5943, -1, + 5944, 5944, 5944, -1, 5945, 5945, 5945, -1, + 5946, 5946, 5946, -1, 5947, 5947, 5947, -1, + 5948, 5948, 5948, -1, 5949, 5949, 5949, -1, + 5950, 5950, 5950, -1, 5951, 5951, 5951, -1, + 5952, 5952, 5952, -1, 5953, 5953, 5953, -1, + 5954, 5954, 5954, -1, 5955, 5955, 5955, -1, + 5956, 5956, 5956, -1, 5957, 5957, 5957, -1, + 5958, 5958, 5958, -1, 5959, 5959, 5959, -1, + 5960, 5960, 5960, -1, 5961, 5961, 5961, -1, + 5962, 5962, 5962, -1, 5963, 5963, 5963, -1, + 5964, 5964, 5964, -1, 5965, 5965, 5965, -1, + 5966, 5966, 5966, -1, 5967, 5967, 5967, -1, + 5968, 5968, 5968, -1, 5969, 5969, 5969, -1, + 5970, 5970, 5970, -1, 5971, 5971, 5971, -1, + 5972, 5972, 5972, -1, 5973, 5973, 5973, -1, + 5974, 5974, 5974, -1, 5975, 5975, 5975, -1, + 5976, 5976, 5976, -1, 5977, 5977, 5977, -1, + 5978, 5978, 5978, -1, 5979, 5979, 5979, -1, + 5980, 5980, 5980, -1, 5981, 5981, 5981, -1, + 5982, 5982, 5982, -1, 5983, 5983, 5983, -1, + 5984, 5984, 5984, -1, 5985, 5985, 5985, -1, + 5986, 5986, 5986, -1, 5987, 5987, 5987, -1, + 5988, 5988, 5988, -1, 5989, 5989, 5989, -1, + 5990, 5990, 5990, -1, 5991, 5991, 5991, -1, + 5992, 5992, 5992, -1, 5993, 5993, 5993, -1, + 5994, 5994, 5994, -1, 5995, 5995, 5995, -1, + 5996, 5996, 5996, -1, 5997, 5997, 5997, -1, + 5998, 5998, 5998, -1, 5999, 5999, 5999, -1, + 6000, 6000, 6000, -1, 6001, 6001, 6001, -1, + 6002, 6002, 6002, -1, 6003, 6003, 6003, -1, + 6004, 6004, 6004, -1, 6005, 6005, 6005, -1, + 6006, 6006, 6006, -1, 6007, 6007, 6007, -1, + 6008, 6008, 6008, -1, 6009, 6009, 6009, -1, + 6010, 6010, 6010, -1, 6011, 6011, 6011, -1, + 6012, 6012, 6012, -1, 6013, 6013, 6013, -1, + 6014, 6014, 6014, -1, 6015, 6015, 6015, -1, + 6016, 6016, 6016, -1, 6017, 6017, 6017, -1, + 6018, 6018, 6018, -1, 6019, 6019, 6019, -1, + 6020, 6020, 6020, -1, 6021, 6021, 6021, -1, + 6022, 6022, 6022, -1, 6023, 6023, 6023, -1, + 6024, 6024, 6024, -1, 6025, 6025, 6025, -1, + 6026, 6026, 6026, -1, 6027, 6027, 6027, -1, + 6028, 6028, 6028, -1, 6029, 6029, 6029, -1, + 6030, 6030, 6030, -1, 6031, 6031, 6031, -1, + 6032, 6032, 6032, -1, 6033, 6033, 6033, -1, + 6034, 6034, 6034, -1, 6035, 6035, 6035, -1, + 6036, 6036, 6036, -1, 6037, 6037, 6037, -1, + 6038, 6038, 6038, -1, 6039, 6039, 6039, -1, + 6040, 6040, 6040, -1, 6041, 6041, 6041, -1, + 6042, 6042, 6042, -1, 6043, 6043, 6043, -1, + 6044, 6044, 6044, -1, 6045, 6045, 6045, -1, + 6046, 6046, 6046, -1, 6047, 6047, 6047, -1, + 6048, 6048, 6048, -1, 6049, 6049, 6049, -1, + 6050, 6050, 6050, -1, 6051, 6051, 6051, -1, + 6052, 6052, 6052, -1, 6053, 6053, 6053, -1, + 6054, 6054, 6054, -1, 6055, 6055, 6055, -1, + 6056, 6056, 6056, -1, 6057, 6057, 6057, -1, + 6058, 6058, 6058, -1, 6059, 6059, 6059, -1, + 6060, 6060, 6060, -1, 6061, 6061, 6061, -1, + 6062, 6062, 6062, -1, 6063, 6063, 6063, -1, + 6064, 6064, 6064, -1, 6065, 6065, 6065, -1, + 6066, 6066, 6066, -1, 6067, 6067, 6067, -1, + 6068, 6068, 6068, -1, 6069, 6069, 6069, -1, + 6070, 6070, 6070, -1, 6071, 6071, 6071, -1, + 6072, 6072, 6072, -1, 6073, 6073, 6073, -1, + 6074, 6074, 6074, -1, 6075, 6075, 6075, -1, + 6076, 6076, 6076, -1, 6077, 6077, 6077, -1, + 6078, 6078, 6078, -1, 6079, 6079, 6079, -1, + 6080, 6080, 6080, -1, 6081, 6081, 6081, -1, + 6082, 6082, 6082, -1, 6083, 6083, 6083, -1, + 6084, 6084, 6084, -1, 6085, 6085, 6085, -1, + 6086, 6086, 6086, -1, 6087, 6087, 6087, -1, + 6088, 6088, 6088, -1, 6089, 6089, 6089, -1, + 6090, 6090, 6090, -1, 6091, 6091, 6091, -1, + 6092, 6092, 6092, -1, 6093, 6093, 6093, -1, + 6094, 6094, 6094, -1, 6095, 6095, 6095, -1, + 6096, 6096, 6096, -1, 6097, 6097, 6097, -1, + 6098, 6098, 6098, -1, 6099, 6099, 6099, -1, + 6100, 6100, 6100, -1, 6101, 6101, 6101, -1, + 6102, 6102, 6102, -1, 6103, 6103, 6103, -1, + 6104, 6104, 6104, -1, 6105, 6105, 6105, -1, + 6106, 6106, 6106, -1, 6107, 6107, 6107, -1, + 6108, 6108, 6108, -1, 6109, 6109, 6109, -1, + 6110, 6110, 6110, -1, 6111, 6111, 6111, -1, + 6112, 6112, 6112, -1, 6113, 6113, 6113, -1, + 6114, 6114, 6114, -1, 6115, 6115, 6115, -1, + 6116, 6116, 6116, -1, 6117, 6117, 6117, -1, + 6118, 6118, 6118, -1, 6119, 6119, 6119, -1, + 6120, 6120, 6120, -1, 6121, 6121, 6121, -1, + 6122, 6122, 6122, -1, 6123, 6123, 6123, -1, + 6124, 6124, 6124, -1, 6125, 6125, 6125, -1, + 6126, 6126, 6126, -1, 6127, 6127, 6127, -1, + 6128, 6128, 6128, -1, 6129, 6129, 6129, -1, + 6130, 6130, 6130, -1, 6131, 6131, 6131, -1, + 6132, 6132, 6132, -1, 6133, 6133, 6133, -1, + 6134, 6134, 6134, -1, 6135, 6135, 6135, -1, + 6136, 6136, 6136, -1, 6137, 6137, 6137, -1, + 6138, 6138, 6138, -1, 6139, 6139, 6139, -1, + 6140, 6140, 6140, -1, 6141, 6141, 6141, -1, + 6142, 6142, 6142, -1, 6143, 6143, 6143, -1, + 6144, 6144, 6144, -1, 6145, 6145, 6145, -1, + 6146, 6146, 6146, -1, 6147, 6147, 6147, -1, + 6148, 6148, 6148, -1, 6149, 6149, 6149, -1, + 6150, 6150, 6150, -1, 6151, 6151, 6151, -1, + 6152, 6152, 6152, -1, 6153, 6153, 6153, -1, + 6154, 6154, 6154, -1, 6155, 6155, 6155, -1, + 6156, 6156, 6156, -1, 6157, 6157, 6157, -1, + 6158, 6158, 6158, -1, 6159, 6159, 6159, -1, + 6160, 6160, 6160, -1, 6161, 6161, 6161, -1, + 6162, 6162, 6162, -1, 6163, 6163, 6163, -1, + 6164, 6164, 6164, -1, 6165, 6165, 6165, -1, + 6166, 6166, 6166, -1, 6167, 6167, 6167, -1, + 6168, 6168, 6168, -1, 6169, 6169, 6169, -1, + 6170, 6170, 6170, -1, 6171, 6171, 6171, -1, + 6172, 6172, 6172, -1, 6173, 6173, 6173, -1, + 6174, 6174, 6174, -1, 6175, 6175, 6175, -1, + 6176, 6176, 6176, -1, 6177, 6177, 6177, -1, + 6178, 6178, 6178, -1, 6179, 6179, 6179, -1, + 6180, 6180, 6180, -1, 6181, 6181, 6181, -1, + 6182, 6182, 6182, -1, 6183, 6183, 6183, -1, + 6184, 6184, 6184, -1, 6185, 6185, 6185, -1, + 6186, 6186, 6186, -1, 6187, 6187, 6187, -1, + 6188, 6188, 6188, -1, 6189, 6189, 6189, -1, + 6190, 6190, 6190, -1, 6191, 6191, 6191, -1, + 6192, 6192, 6192, -1, 6193, 6193, 6193, -1, + 6194, 6194, 6194, -1, 6195, 6195, 6195, -1, + 6196, 6196, 6196, -1, 6197, 6197, 6197, -1, + 6198, 6198, 6198, -1, 6199, 6199, 6199, -1, + 6200, 6200, 6200, -1, 6201, 6201, 6201, -1, + 6202, 6202, 6202, -1, 6203, 6203, 6203, -1, + 6204, 6204, 6204, -1, 6205, 6205, 6205, -1, + 6206, 6206, 6206, -1, 6207, 6207, 6207, -1, + 6208, 6208, 6208, -1, 6209, 6209, 6209, -1, + 6210, 6210, 6210, -1, 6211, 6211, 6211, -1, + 6212, 6212, 6212, -1, 6213, 6213, 6213, -1, + 6214, 6214, 6214, -1, 6215, 6215, 6215, -1, + 6216, 6216, 6216, -1, 6217, 6217, 6217, -1, + 6218, 6218, 6218, -1, 6219, 6219, 6219, -1, + 6220, 6220, 6220, -1, 6221, 6221, 6221, -1, + 6222, 6222, 6222, -1, 6223, 6223, 6223, -1, + 6224, 6224, 6224, -1, 6225, 6225, 6225, -1, + 6226, 6226, 6226, -1, 6227, 6227, 6227, -1, + 6228, 6228, 6228, -1, 6229, 6229, 6229, -1, + 6230, 6230, 6230, -1, 6231, 6231, 6231, -1, + 6232, 6232, 6232, -1, 6233, 6233, 6233, -1, + 6234, 6234, 6234, -1, 6235, 6235, 6235, -1, + 6236, 6236, 6236, -1, 6237, 6237, 6237, -1, + 6238, 6238, 6238, -1, 6239, 6239, 6239, -1, + 6240, 6240, 6240, -1, 6241, 6241, 6241, -1, + 6242, 6242, 6242, -1, 6243, 6243, 6243, -1, + 6244, 6244, 6244, -1, 6245, 6245, 6245, -1, + 6246, 6246, 6246, -1, 6247, 6247, 6247, -1, + 6248, 6248, 6248, -1, 6249, 6249, 6249, -1, + 6250, 6250, 6250, -1, 6251, 6251, 6251, -1, + 6252, 6252, 6252, -1, 6253, 6253, 6253, -1, + 6254, 6254, 6254, -1, 6255, 6255, 6255, -1, + 6256, 6256, 6256, -1, 6257, 6257, 6257, -1, + 6258, 6258, 6258, -1, 6259, 6259, 6259, -1, + 6260, 6260, 6260, -1, 6261, 6261, 6261, -1, + 6262, 6262, 6262, -1, 6263, 6263, 6263, -1, + 6264, 6264, 6264, -1, 6265, 6265, 6265, -1, + 6266, 6266, 6266, -1, 6267, 6267, 6267, -1, + 6268, 6268, 6268, -1, 6269, 6269, 6269, -1, + 6270, 6270, 6270, -1, 6271, 6271, 6271, -1, + 6272, 6272, 6272, -1, 6273, 6273, 6273, -1, + 6274, 6274, 6274, -1, 6275, 6275, 6275, -1, + 6276, 6276, 6276, -1, 6277, 6277, 6277, -1, + 6278, 6278, 6278, -1, 6279, 6279, 6279, -1, + 6280, 6280, 6280, -1, 6281, 6281, 6281, -1, + 6282, 6282, 6282, -1, 6283, 6283, 6283, -1, + 6284, 6284, 6284, -1, 6285, 6285, 6285, -1, + 6286, 6286, 6286, -1, 6287, 6287, 6287, -1, + 6288, 6288, 6288, -1, 6289, 6289, 6289, -1, + 6290, 6290, 6290, -1, 6291, 6291, 6291, -1, + 6292, 6292, 6292, -1, 6293, 6293, 6293, -1, + 6294, 6294, 6294, -1, 6295, 6295, 6295, -1, + 6296, 6296, 6296, -1, 6297, 6297, 6297, -1, + 6298, 6298, 6298, -1, 6299, 6299, 6299, -1, + 6300, 6300, 6300, -1, 6301, 6301, 6301, -1, + 6302, 6302, 6302, -1, 6303, 6303, 6303, -1, + 6304, 6304, 6304, -1, 6305, 6305, 6305, -1, + 6306, 6306, 6306, -1, 6307, 6307, 6307, -1, + 6308, 6308, 6308, -1, 6309, 6309, 6309, -1, + 6310, 6310, 6310, -1, 6311, 6311, 6311, -1, + 6312, 6312, 6312, -1, 6313, 6313, 6313, -1, + 6314, 6314, 6314, -1, 6315, 6315, 6315, -1, + 6316, 6316, 6316, -1, 6317, 6317, 6317, -1, + 6318, 6318, 6318, -1, 6319, 6319, 6319, -1, + 6320, 6320, 6320, -1, 6321, 6321, 6321, -1, + 6322, 6322, 6322, -1, 6323, 6323, 6323, -1, + 6324, 6324, 6324, -1, 6325, 6325, 6325, -1, + 6326, 6326, 6326, -1, 6327, 6327, 6327, -1, + 6328, 6328, 6328, -1, 6329, 6329, 6329, -1, + 6330, 6330, 6330, -1, 6331, 6331, 6331, -1, + 6332, 6332, 6332, -1, 6333, 6333, 6333, -1, + 6334, 6334, 6334, -1, 6335, 6335, 6335, -1, + 6336, 6336, 6336, -1, 6337, 6337, 6337, -1, + 6338, 6338, 6338, -1, 6339, 6339, 6339, -1, + 6340, 6340, 6340, -1, 6341, 6341, 6341, -1, + 6342, 6342, 6342, -1, 6343, 6343, 6343, -1, + 6344, 6344, 6344, -1, 6345, 6345, 6345, -1, + 6346, 6346, 6346, -1, 6347, 6347, 6347, -1, + 6348, 6348, 6348, -1, 6349, 6349, 6349, -1, + 6350, 6350, 6350, -1, 6351, 6351, 6351, -1, + 6352, 6352, 6352, -1, 6353, 6353, 6353, -1, + 6354, 6354, 6354, -1, 6355, 6355, 6355, -1, + 6356, 6356, 6356, -1, 6357, 6357, 6357, -1, + 6358, 6358, 6358, -1, 6359, 6359, 6359, -1, + 6360, 6360, 6360, -1, 6361, 6361, 6361, -1, + 6362, 6362, 6362, -1, 6363, 6363, 6363, -1, + 6364, 6364, 6364, -1, 6365, 6365, 6365, -1, + 6366, 6366, 6366, -1, 6367, 6367, 6367, -1, + 6368, 6368, 6368, -1, 6369, 6369, 6369, -1, + 6370, 6370, 6370, -1, 6371, 6371, 6371, -1, + 6372, 6372, 6372, -1, 6373, 6373, 6373, -1, + 6374, 6374, 6374, -1, 6375, 6375, 6375, -1, + 6376, 6376, 6376, -1, 6377, 6377, 6377, -1, + 6378, 6378, 6378, -1, 6379, 6379, 6379, -1, + 6380, 6380, 6380, -1, 6381, 6381, 6381, -1, + 6382, 6382, 6382, -1, 6383, 6383, 6383, -1, + 6384, 6384, 6384, -1, 6385, 6385, 6385, -1, + 6386, 6386, 6386, -1, 6387, 6387, 6387, -1, + 6388, 6388, 6388, -1, 6389, 6389, 6389, -1, + 6390, 6390, 6390, -1, 6391, 6391, 6391, -1, + 6392, 6392, 6392, -1, 6393, 6393, 6393, -1, + 6394, 6394, 6394, -1, 6395, 6395, 6395, -1, + 6396, 6396, 6396, -1, 6397, 6397, 6397, -1, + 6398, 6398, 6398, -1, 6399, 6399, 6399, -1, + 6400, 6400, 6400, -1, 6401, 6401, 6401, -1, + 6402, 6402, 6402, -1, 6403, 6403, 6403, -1, + 6404, 6404, 6404, -1, 6405, 6405, 6405, -1, + 6406, 6406, 6406, -1, 6407, 6407, 6407, -1, + 6408, 6408, 6408, -1, 6409, 6409, 6409, -1, + 6410, 6410, 6410, -1, 6411, 6411, 6411, -1, + 6412, 6412, 6412, -1, 6413, 6413, 6413, -1, + 6414, 6414, 6414, -1, 6415, 6415, 6415, -1, + 6416, 6416, 6416, -1, 6417, 6417, 6417, -1, + 6418, 6418, 6418, -1, 6419, 6419, 6419, -1, + 6420, 6420, 6420, -1, 6421, 6421, 6421, -1, + 6422, 6422, 6422, -1, 6423, 6423, 6423, -1, + 6424, 6424, 6424, -1, 6425, 6425, 6425, -1, + 6426, 6426, 6426, -1, 6427, 6427, 6427, -1, + 6428, 6428, 6428, -1, 6429, 6429, 6429, -1, + 6430, 6430, 6430, -1, 6431, 6431, 6431, -1, + 6432, 6432, 6432, -1, 6433, 6433, 6433, -1, + 6434, 6434, 6434, -1, 6435, 6435, 6435, -1, + 6436, 6436, 6436, -1, 6437, 6437, 6437, -1, + 6438, 6438, 6438, -1, 6439, 6439, 6439, -1, + 6440, 6440, 6440, -1, 6441, 6441, 6441, -1, + 6442, 6442, 6442, -1, 6443, 6443, 6443, -1, + 6444, 6444, 6444, -1, 6445, 6445, 6445, -1, + 6446, 6446, 6446, -1, 6447, 6447, 6447, -1, + 6448, 6448, 6448, -1, 6449, 6449, 6449, -1, + 6450, 6450, 6450, -1, 6451, 6451, 6451, -1, + 6452, 6452, 6452, -1, 6453, 6453, 6453, -1, + 6454, 6454, 6454, -1, 6455, 6455, 6455, -1, + 6456, 6456, 6456, -1, 6457, 6457, 6457, -1, + 6458, 6458, 6458, -1, 6459, 6459, 6459, -1, + 6460, 6460, 6460, -1, 6461, 6461, 6461, -1, + 6462, 6462, 6462, -1, 6463, 6463, 6463, -1, + 6464, 6464, 6464, -1, 6465, 6465, 6465, -1, + 6466, 6466, 6466, -1, 6467, 6467, 6467, -1, + 6468, 6468, 6468, -1, 6469, 6469, 6469, -1, + 6470, 6470, 6470, -1, 6471, 6471, 6471, -1, + 6472, 6472, 6472, -1, 6473, 6473, 6473, -1, + 6474, 6474, 6474, -1, 6475, 6475, 6475, -1, + 6476, 6476, 6476, -1, 6477, 6477, 6477, -1, + 6478, 6478, 6478, -1, 6479, 6479, 6479, -1, + 6480, 6480, 6480, -1, 6481, 6481, 6481, -1, + 6482, 6482, 6482, -1, 6483, 6483, 6483, -1, + 6484, 6484, 6484, -1, 6485, 6485, 6485, -1, + 6486, 6486, 6486, -1, 6487, 6487, 6487, -1, + 6488, 6488, 6488, -1, 6489, 6489, 6489, -1, + 6490, 6490, 6490, -1, 6491, 6491, 6491, -1, + 6492, 6492, 6492, -1, 6493, 6493, 6493, -1, + 6494, 6494, 6494, -1, 6495, 6495, 6495, -1, + 6496, 6496, 6496, -1, 6497, 6497, 6497, -1, + 6498, 6498, 6498, -1, 6499, 6499, 6499, -1, + 6500, 6500, 6500, -1, 6501, 6501, 6501, -1, + 6502, 6502, 6502, -1, 6503, 6503, 6503, -1, + 6504, 6504, 6504, -1, 6505, 6505, 6505, -1, + 6506, 6506, 6506, -1, 6507, 6507, 6507, -1, + 6508, 6508, 6508, -1, 6509, 6509, 6509, -1, + 6510, 6510, 6510, -1, 6511, 6511, 6511, -1, + 6512, 6512, 6512, -1, 6513, 6513, 6513, -1, + 6514, 6514, 6514, -1, 6515, 6515, 6515, -1, + 6516, 6516, 6516, -1, 6517, 6517, 6517, -1, + 6518, 6518, 6518, -1, 6519, 6519, 6519, -1, + 6520, 6520, 6520, -1, 6521, 6521, 6521, -1, + 6522, 6522, 6522, -1, 6523, 6523, 6523, -1, + 6524, 6524, 6524, -1, 6525, 6525, 6525, -1, + 6526, 6526, 6526, -1, 6527, 6527, 6527, -1, + 6528, 6528, 6528, -1, 6529, 6529, 6529, -1, + 6530, 6530, 6530, -1, 6531, 6531, 6531, -1, + 6532, 6532, 6532, -1, 6533, 6533, 6533, -1, + 6534, 6534, 6534, -1, 6535, 6535, 6535, -1, + 6536, 6536, 6536, -1, 6537, 6537, 6537, -1, + 6538, 6538, 6538, -1, 6539, 6539, 6539, -1, + 6540, 6540, 6540, -1, 6541, 6541, 6541, -1, + 6542, 6542, 6542, -1, 6543, 6543, 6543, -1, + 6544, 6544, 6544, -1, 6545, 6545, 6545, -1, + 6546, 6546, 6546, -1, 6547, 6547, 6547, -1, + 6548, 6548, 6548, -1, 6549, 6549, 6549, -1, + 6550, 6550, 6550, -1, 6551, 6551, 6551, -1, + 6552, 6552, 6552, -1, 6553, 6553, 6553, -1, + 6554, 6554, 6554, -1, 6555, 6555, 6555, -1, + 6556, 6556, 6556, -1, 6557, 6557, 6557, -1, + 6558, 6558, 6558, -1, 6559, 6559, 6559, -1, + 6560, 6560, 6560, -1, 6561, 6561, 6561, -1, + 6562, 6562, 6562, -1, 6563, 6563, 6563, -1, + 6564, 6564, 6564, -1, 6565, 6565, 6565, -1, + 6566, 6566, 6566, -1, 6567, 6567, 6567, -1, + 6568, 6568, 6568, -1, 6569, 6569, 6569, -1, + 6570, 6570, 6570, -1, 6571, 6571, 6571, -1, + 6572, 6572, 6572, -1, 6573, 6573, 6573, -1, + 6574, 6574, 6574, -1, 6575, 6575, 6575, -1, + 6576, 6576, 6576, -1, 6577, 6577, 6577, -1, + 6578, 6578, 6578, -1, 6579, 6579, 6579, -1, + 6580, 6580, 6580, -1, 6581, 6581, 6581, -1, + 6582, 6582, 6582, -1, 6583, 6583, 6583, -1, + 6584, 6584, 6584, -1, 6585, 6585, 6585, -1, + 6586, 6586, 6586, -1, 6587, 6587, 6587, -1, + 6588, 6588, 6588, -1, 6589, 6589, 6589, -1, + 6590, 6590, 6590, -1, 6591, 6591, 6591, -1, + 6592, 6592, 6592, -1, 6593, 6593, 6593, -1, + 6594, 6594, 6594, -1, 6595, 6595, 6595, -1, + 6596, 6596, 6596, -1, 6597, 6597, 6597, -1, + 6598, 6598, 6598, -1, 6599, 6599, 6599, -1, + 6600, 6600, 6600, -1, 6601, 6601, 6601, -1, + 6602, 6602, 6602, -1, 6603, 6603, 6603, -1, + 6604, 6604, 6604, -1, 6605, 6605, 6605, -1, + 6606, 6606, 6606, -1, 6607, 6607, 6607, -1, + 6608, 6608, 6608, -1, 6609, 6609, 6609, -1, + 6610, 6610, 6610, -1, 6611, 6611, 6611, -1, + 6612, 6612, 6612, -1, 6613, 6613, 6613, -1, + 6614, 6614, 6614, -1, 6615, 6615, 6615, -1, + 6616, 6616, 6616, -1, 6617, 6617, 6617, -1, + 6618, 6618, 6618, -1, 6619, 6619, 6619, -1, + 6620, 6620, 6620, -1, 6621, 6621, 6621, -1, + 6622, 6622, 6622, -1, 6623, 6623, 6623, -1, + 6624, 6624, 6624, -1, 6625, 6625, 6625, -1, + 6626, 6626, 6626, -1, 6627, 6627, 6627, -1, + 6628, 6628, 6628, -1, 6629, 6629, 6629, -1, + 6630, 6630, 6630, -1, 6631, 6631, 6631, -1, + 6632, 6632, 6632, -1, 6633, 6633, 6633, -1, + 6634, 6634, 6634, -1, 6635, 6635, 6635, -1, + 6636, 6636, 6636, -1, 6637, 6637, 6637, -1, + 6638, 6638, 6638, -1, 6639, 6639, 6639, -1, + 6640, 6640, 6640, -1, 6641, 6641, 6641, -1, + 6642, 6642, 6642, -1, 6643, 6643, 6643, -1, + 6644, 6644, 6644, -1, 6645, 6645, 6645, -1, + 6646, 6646, 6646, -1, 6647, 6647, 6647, -1, + 6648, 6648, 6648, -1, 6649, 6649, 6649, -1, + 6650, 6650, 6650, -1, 6651, 6651, 6651, -1, + 6652, 6652, 6652, -1, 6653, 6653, 6653, -1, + 6654, 6654, 6654, -1, 6655, 6655, 6655, -1, + 6656, 6656, 6656, -1, 6657, 6657, 6657, -1, + 6658, 6658, 6658, -1, 6659, 6659, 6659, -1, + 6660, 6660, 6660, -1, 6661, 6661, 6661, -1, + 6662, 6662, 6662, -1, 6663, 6663, 6663, -1, + 6664, 6664, 6664, -1, 6665, 6665, 6665, -1, + 6666, 6666, 6666, -1, 6667, 6667, 6667, -1, + 6668, 6668, 6668, -1, 6669, 6669, 6669, -1, + 6670, 6670, 6670, -1, 6671, 6671, 6671, -1, + 6672, 6672, 6672, -1, 6673, 6673, 6673, -1, + 6674, 6674, 6674, -1, 6675, 6675, 6675, -1, + 6676, 6676, 6676, -1, 6677, 6677, 6677, -1, + 6678, 6678, 6678, -1, 6679, 6679, 6679, -1, + 6680, 6680, 6680, -1, 6681, 6681, 6681, -1, + 6682, 6682, 6682, -1, 6683, 6683, 6683, -1, + 6684, 6684, 6684, -1, 6685, 6685, 6685, -1, + 6686, 6686, 6686, -1, 6687, 6687, 6687, -1, + 6688, 6688, 6688, -1, 6689, 6689, 6689, -1, + 6690, 6690, 6690, -1, 6691, 6691, 6691, -1, + 6692, 6692, 6692, -1, 6693, 6693, 6693, -1, + 6694, 6694, 6694, -1, 6695, 6695, 6695, -1, + 6696, 6696, 6696, -1, 6697, 6697, 6697, -1, + 6698, 6698, 6698, -1, 6699, 6699, 6699, -1, + 6700, 6700, 6700, -1, 6701, 6701, 6701, -1, + 6702, 6702, 6702, -1, 6703, 6703, 6703, -1, + 6704, 6704, 6704, -1, 6705, 6705, 6705, -1, + 6706, 6706, 6706, -1, 6707, 6707, 6707, -1, + 6708, 6708, 6708, -1, 6709, 6709, 6709, -1, + 6710, 6710, 6710, -1, 6711, 6711, 6711, -1, + 6712, 6712, 6712, -1, 6713, 6713, 6713, -1, + 6714, 6714, 6714, -1, 6715, 6715, 6715, -1, + 6716, 6716, 6716, -1, 6717, 6717, 6717, -1, + 6718, 6718, 6718, -1, 6719, 6719, 6719, -1, + 6720, 6720, 6720, -1, 6721, 6721, 6721, -1, + 6722, 6722, 6722, -1, 6723, 6723, 6723, -1, + 6724, 6724, 6724, -1, 6725, 6725, 6725, -1, + 6726, 6726, 6726, -1, 6727, 6727, 6727, -1, + 6728, 6728, 6728, -1, 6729, 6729, 6729, -1, + 6730, 6730, 6730, -1, 6731, 6731, 6731, -1, + 6732, 6732, 6732, -1, 6733, 6733, 6733, -1, + 6734, 6734, 6734, -1, 6735, 6735, 6735, -1, + 6736, 6736, 6736, -1, 6737, 6737, 6737, -1, + 6738, 6738, 6738, -1, 6739, 6739, 6739, -1, + 6740, 6740, 6740, -1, 6741, 6741, 6741, -1, + 6742, 6742, 6742, -1, 6743, 6743, 6743, -1, + 6744, 6744, 6744, -1, 6745, 6745, 6745, -1, + 6746, 6746, 6746, -1, 6747, 6747, 6747, -1, + 6748, 6748, 6748, -1, 6749, 6749, 6749, -1, + 6750, 6750, 6750, -1, 6751, 6751, 6751, -1, + 6752, 6752, 6752, -1, 6753, 6753, 6753, -1, + 6754, 6754, 6754, -1, 6755, 6755, 6755, -1, + 6756, 6756, 6756, -1, 6757, 6757, 6757, -1, + 6758, 6758, 6758, -1, 6759, 6759, 6759, -1, + 6760, 6760, 6760, -1, 6761, 6761, 6761, -1, + 6762, 6762, 6762, -1, 6763, 6763, 6763, -1, + 6764, 6764, 6764, -1, 6765, 6765, 6765, -1, + 6766, 6766, 6766, -1, 6767, 6767, 6767, -1, + 6768, 6768, 6768, -1, 6769, 6769, 6769, -1, + 6770, 6770, 6770, -1, 6771, 6771, 6771, -1, + 6772, 6772, 6772, -1, 6773, 6773, 6773, -1, + 6774, 6774, 6774, -1, 6775, 6775, 6775, -1, + 6776, 6776, 6776, -1, 6777, 6777, 6777, -1, + 6778, 6778, 6778, -1, 6779, 6779, 6779, -1, + 6780, 6780, 6780, -1, 6781, 6781, 6781, -1, + 6782, 6782, 6782, -1, 6783, 6783, 6783, -1, + 6784, 6784, 6784, -1, 6785, 6785, 6785, -1, + 6786, 6786, 6786, -1, 6787, 6787, 6787, -1, + 6788, 6788, 6788, -1, 6789, 6789, 6789, -1, + 6790, 6790, 6790, -1, 6791, 6791, 6791, -1, + 6792, 6792, 6792, -1, 6793, 6793, 6793, -1, + 6794, 6794, 6794, -1, 6795, 6795, 6795, -1, + 6796, 6796, 6796, -1, 6797, 6797, 6797, -1, + 6798, 6798, 6798, -1, 6799, 6799, 6799, -1, + 6800, 6800, 6800, -1, 6801, 6801, 6801, -1, + 6802, 6802, 6802, -1, 6803, 6803, 6803, -1, + 6804, 6804, 6804, -1, 6805, 6805, 6805, -1, + 6806, 6806, 6806, -1, 6807, 6807, 6807, -1, + 6808, 6808, 6808, -1, 6809, 6809, 6809, -1, + 6810, 6810, 6810, -1, 6811, 6811, 6811, -1, + 6812, 6812, 6812, -1, 6813, 6813, 6813, -1, + 6814, 6814, 6814, -1, 6815, 6815, 6815, -1, + 6816, 6816, 6816, -1, 6817, 6817, 6817, -1, + 6818, 6818, 6818, -1, 6819, 6819, 6819, -1, + 6820, 6820, 6820, -1, 6821, 6821, 6821, -1, + 6822, 6822, 6822, -1, 6823, 6823, 6823, -1, + 6824, 6824, 6824, -1, 6825, 6825, 6825, -1, + 6826, 6826, 6826, -1, 6827, 6827, 6827, -1, + 6828, 6828, 6828, -1, 6829, 6829, 6829, -1, + 6830, 6830, 6830, -1, 6831, 6831, 6831, -1, + 6832, 6832, 6832, -1, 6833, 6833, 6833, -1, + 6834, 6834, 6834, -1, 6835, 6835, 6835, -1, + 6836, 6836, 6836, -1, 6837, 6837, 6837, -1, + 6838, 6838, 6838, -1, 6839, 6839, 6839, -1, + 6840, 6840, 6840, -1, 6841, 6841, 6841, -1, + 6842, 6842, 6842, -1, 6843, 6843, 6843, -1, + 6844, 6844, 6844, -1, 6845, 6845, 6845, -1, + 6846, 6846, 6846, -1, 6847, 6847, 6847, -1, + 6848, 6848, 6848, -1, 6849, 6849, 6849, -1, + 6850, 6850, 6850, -1, 6851, 6851, 6851, -1, + 6852, 6852, 6852, -1, 6853, 6853, 6853, -1, + 6854, 6854, 6854, -1, 6855, 6855, 6855, -1, + 6856, 6856, 6856, -1, 6857, 6857, 6857, -1, + 6858, 6858, 6858, -1, 6859, 6859, 6859, -1, + 6860, 6860, 6860, -1, 6861, 6861, 6861, -1, + 6862, 6862, 6862, -1, 6863, 6863, 6863, -1, + 6864, 6864, 6864, -1, 6865, 6865, 6865, -1, + 6866, 6866, 6866, -1, 6867, 6867, 6867, -1, + 6868, 6868, 6868, -1, 6869, 6869, 6869, -1, + 6870, 6870, 6870, -1, 6871, 6871, 6871, -1, + 6872, 6872, 6872, -1, 6873, 6873, 6873, -1, + 6874, 6874, 6874, -1, 6875, 6875, 6875, -1, + 6876, 6876, 6876, -1, 6877, 6877, 6877, -1, + 6878, 6878, 6878, -1, 6879, 6879, 6879, -1, + 6880, 6880, 6880, -1, 6881, 6881, 6881, -1, + 6882, 6882, 6882, -1, 6883, 6883, 6883, -1, + 6884, 6884, 6884, -1, 6885, 6885, 6885, -1, + 6886, 6886, 6886, -1, 6887, 6887, 6887, -1, + 6888, 6888, 6888, -1, 6889, 6889, 6889, -1, + 6890, 6890, 6890, -1, 6891, 6891, 6891, -1, + 6892, 6892, 6892, -1, 6893, 6893, 6893, -1, + 6894, 6894, 6894, -1, 6895, 6895, 6895, -1, + 6896, 6896, 6896, -1, 6897, 6897, 6897, -1, + 6898, 6898, 6898, -1, 6899, 6899, 6899, -1, + 6900, 6900, 6900, -1, 6901, 6901, 6901, -1, + 6902, 6902, 6902, -1, 6903, 6903, 6903, -1, + 6904, 6904, 6904, -1, 6905, 6905, 6905, -1, + 6906, 6906, 6906, -1, 6907, 6907, 6907, -1, + 6908, 6908, 6908, -1, 6909, 6909, 6909, -1, + 6910, 6910, 6910, -1, 6911, 6911, 6911, -1, + 6912, 6912, 6912, -1, 6913, 6913, 6913, -1, + 6914, 6914, 6914, -1, 6915, 6915, 6915, -1, + 6916, 6916, 6916, -1, 6917, 6917, 6917, -1, + 6918, 6918, 6918, -1, 6919, 6919, 6919, -1, + 6920, 6920, 6920, -1, 6921, 6921, 6921, -1, + 6922, 6922, 6922, -1, 6923, 6923, 6923, -1, + 6924, 6924, 6924, -1, 6925, 6925, 6925, -1, + 6926, 6926, 6926, -1, 6927, 6927, 6927, -1, + 6928, 6928, 6928, -1, 6929, 6929, 6929, -1, + 6930, 6930, 6930, -1, 6931, 6931, 6931, -1, + 6932, 6932, 6932, -1, 6933, 6933, 6933, -1, + 6934, 6934, 6934, -1, 6935, 6935, 6935, -1, + 6936, 6936, 6936, -1, 6937, 6937, 6937, -1, + 6938, 6938, 6938, -1, 6939, 6939, 6939, -1, + 6940, 6940, 6940, -1, 6941, 6941, 6941, -1, + 6942, 6942, 6942, -1, 6943, 6943, 6943, -1, + 6944, 6944, 6944, -1, 6945, 6945, 6945, -1, + 6946, 6946, 6946, -1, 6947, 6947, 6947, -1, + 6948, 6948, 6948, -1, 6949, 6949, 6949, -1, + 6950, 6950, 6950, -1, 6951, 6951, 6951, -1, + 6952, 6952, 6952, -1, 6953, 6953, 6953, -1, + 6954, 6954, 6954, -1, 6955, 6955, 6955, -1, + 6956, 6956, 6956, -1, 6957, 6957, 6957, -1, + 6958, 6958, 6958, -1, 6959, 6959, 6959, -1, + 6960, 6960, 6960, -1, 6961, 6961, 6961, -1, + 6962, 6962, 6962, -1, 6963, 6963, 6963, -1, + 6964, 6964, 6964, -1, 6965, 6965, 6965, -1, + 6966, 6966, 6966, -1, 6967, 6967, 6967, -1, + 6968, 6968, 6968, -1, 6969, 6969, 6969, -1, + 6970, 6970, 6970, -1, 6971, 6971, 6971, -1, + 6972, 6972, 6972, -1, 6973, 6973, 6973, -1, + 6974, 6974, 6974, -1, 6975, 6975, 6975, -1, + 6976, 6976, 6976, -1, 6977, 6977, 6977, -1, + 6978, 6978, 6978, -1, 6979, 6979, 6979, -1, + 6980, 6980, 6980, -1, 6981, 6981, 6981, -1, + 6982, 6982, 6982, -1, 6983, 6983, 6983, -1, + 6984, 6984, 6984, -1, 6985, 6985, 6985, -1, + 6986, 6986, 6986, -1, 6987, 6987, 6987, -1, + 6988, 6988, 6988, -1, 6989, 6989, 6989, -1, + 6990, 6990, 6990, -1, 6991, 6991, 6991, -1, + 6992, 6992, 6992, -1, 6993, 6993, 6993, -1, + 6994, 6994, 6994, -1, 6995, 6995, 6995, -1, + 6996, 6996, 6996, -1, 6997, 6997, 6997, -1, + 6998, 6998, 6998, -1, 6999, 6999, 6999, -1, + 7000, 7000, 7000, -1, 7001, 7001, 7001, -1, + 7002, 7002, 7002, -1, 7003, 7003, 7003, -1, + 7004, 7004, 7004, -1, 7005, 7005, 7005, -1, + 7006, 7006, 7006, -1, 7007, 7007, 7007, -1, + 7008, 7008, 7008, -1, 7009, 7009, 7009, -1, + 7010, 7010, 7010, -1, 7011, 7011, 7011, -1, + 7012, 7012, 7012, -1, 7013, 7013, 7013, -1, + 7014, 7014, 7014, -1, 7015, 7015, 7015, -1, + 7016, 7016, 7016, -1, 7017, 7017, 7017, -1, + 7018, 7018, 7018, -1, 7019, 7019, 7019, -1, + 7020, 7020, 7020, -1, 7021, 7021, 7021, -1, + 7022, 7022, 7022, -1, 7023, 7023, 7023, -1, + 7024, 7024, 7024, -1, 7025, 7025, 7025, -1, + 7026, 7026, 7026, -1, 7027, 7027, 7027, -1, + 7028, 7028, 7028, -1, 7029, 7029, 7029, -1, + 7030, 7030, 7030, -1, 7031, 7031, 7031, -1, + 7032, 7032, 7032, -1, 7033, 7033, 7033, -1, + 7034, 7034, 7034, -1, 7035, 7035, 7035, -1, + 7036, 7036, 7036, -1, 7037, 7037, 7037, -1, + 7038, 7038, 7038, -1, 7039, 7039, 7039, -1, + 7040, 7040, 7040, -1, 7041, 7041, 7041, -1, + 7042, 7042, 7042, -1, 7043, 7043, 7043, -1, + 7044, 7044, 7044, -1, 7045, 7045, 7045, -1, + 7046, 7046, 7046, -1, 7047, 7047, 7047, -1, + 7048, 7048, 7048, -1, 7049, 7049, 7049, -1, + 7050, 7050, 7050, -1, 7051, 7051, 7051, -1, + 7052, 7052, 7052, -1, 7053, 7053, 7053, -1, + 7054, 7054, 7054, -1, 7055, 7055, 7055, -1, + 7056, 7056, 7056, -1, 7057, 7057, 7057, -1, + 7058, 7058, 7058, -1, 7059, 7059, 7059, -1, + 7060, 7060, 7060, -1, 7061, 7061, 7061, -1, + 7062, 7062, 7062, -1, 7063, 7063, 7063, -1, + 7064, 7064, 7064, -1, 7065, 7065, 7065, -1, + 7066, 7066, 7066, -1, 7067, 7067, 7067, -1, + 7068, 7068, 7068, -1, 7069, 7069, 7069, -1, + 7070, 7070, 7070, -1, 7071, 7071, 7071, -1, + 7072, 7072, 7072, -1, 7073, 7073, 7073, -1, + 7074, 7074, 7074, -1, 7075, 7075, 7075, -1, + 7076, 7076, 7076, -1, 7077, 7077, 7077, -1, + 7078, 7078, 7078, -1, 7079, 7079, 7079, -1, + 7080, 7080, 7080, -1, 7081, 7081, 7081, -1, + 7082, 7082, 7082, -1, 7083, 7083, 7083, -1, + 7084, 7084, 7084, -1, 7085, 7085, 7085, -1, + 7086, 7086, 7086, -1, 7087, 7087, 7087, -1, + 7088, 7088, 7088, -1, 7089, 7089, 7089, -1, + 7090, 7090, 7090, -1, 7091, 7091, 7091, -1, + 7092, 7092, 7092, -1, 7093, 7093, 7093, -1, + 7094, 7094, 7094, -1, 7095, 7095, 7095, -1, + 7096, 7096, 7096, -1, 7097, 7097, 7097, -1, + 7098, 7098, 7098, -1, 7099, 7099, 7099, -1, + 7100, 7100, 7100, -1, 7101, 7101, 7101, -1, + 7102, 7102, 7102, -1, 7103, 7103, 7103, -1, + 7104, 7104, 7104, -1, 7105, 7105, 7105, -1, + 7106, 7106, 7106, -1, 7107, 7107, 7107, -1, + 7108, 7108, 7108, -1, 7109, 7109, 7109, -1, + 7110, 7110, 7110, -1, 7111, 7111, 7111, -1, + 7112, 7112, 7112, -1, 7113, 7113, 7113, -1, + 7114, 7114, 7114, -1, 7115, 7115, 7115, -1, + 7116, 7116, 7116, -1, 7117, 7117, 7117, -1, + 7118, 7118, 7118, -1, 7119, 7119, 7119, -1, + 7120, 7120, 7120, -1, 7121, 7121, 7121, -1, + 7122, 7122, 7122, -1, 7123, 7123, 7123, -1, + 7124, 7124, 7124, -1, 7125, 7125, 7125, -1, + 7126, 7126, 7126, -1, 7127, 7127, 7127, -1, + 7128, 7128, 7128, -1, 7129, 7129, 7129, -1, + 7130, 7130, 7130, -1, 7131, 7131, 7131, -1, + 7132, 7132, 7132, -1, 7133, 7133, 7133, -1, + 7134, 7134, 7134, -1, 7135, 7135, 7135, -1, + 7136, 7136, 7136, -1, 7137, 7137, 7137, -1, + 7138, 7138, 7138, -1, 7139, 7139, 7139, -1, + 7140, 7140, 7140, -1, 7141, 7141, 7141, -1, + 7142, 7142, 7142, -1, 7143, 7143, 7143, -1, + 7144, 7144, 7144, -1, 7145, 7145, 7145, -1, + 7146, 7146, 7146, -1, 7147, 7147, 7147, -1, + 7148, 7148, 7148, -1, 7149, 7149, 7149, -1, + 7150, 7150, 7150, -1, 7151, 7151, 7151, -1, + 7152, 7152, 7152, -1, 7153, 7153, 7153, -1, + 7154, 7154, 7154, -1, 7155, 7155, 7155, -1, + 7156, 7156, 7156, -1, 7157, 7157, 7157, -1, + 7158, 7158, 7158, -1, 7159, 7159, 7159, -1, + 7160, 7160, 7160, -1, 7161, 7161, 7161, -1, + 7162, 7162, 7162, -1, 7163, 7163, 7163, -1, + 7164, 7164, 7164, -1, 7165, 7165, 7165, -1, + 7166, 7166, 7166, -1, 7167, 7167, 7167, -1, + 7168, 7168, 7168, -1, 7169, 7169, 7169, -1, + 7170, 7170, 7170, -1, 7171, 7171, 7171, -1, + 7172, 7172, 7172, -1, 7173, 7173, 7173, -1, + 7174, 7174, 7174, -1, 7175, 7175, 7175, -1, + 7176, 7176, 7176, -1, 7177, 7177, 7177, -1, + 7178, 7178, 7178, -1, 7179, 7179, 7179, -1, + 7180, 7180, 7180, -1, 7181, 7181, 7181, -1, + 7182, 7182, 7182, -1, 7183, 7183, 7183, -1, + 7184, 7184, 7184, -1, 7185, 7185, 7185, -1, + 7186, 7186, 7186, -1, 7187, 7187, 7187, -1, + 7188, 7188, 7188, -1, 7189, 7189, 7189, -1, + 7190, 7190, 7190, -1, 7191, 7191, 7191, -1, + 7192, 7192, 7192, -1, 7193, 7193, 7193, -1, + 7194, 7194, 7194, -1, 7195, 7195, 7195, -1, + 7196, 7196, 7196, -1, 7197, 7197, 7197, -1, + 7198, 7198, 7198, -1, 7199, 7199, 7199, -1, + 7200, 7200, 7200, -1, 7201, 7201, 7201, -1, + 7202, 7202, 7202, -1, 7203, 7203, 7203, -1, + 7204, 7204, 7204, -1, 7205, 7205, 7205, -1, + 7206, 7206, 7206, -1, 7207, 7207, 7207, -1, + 7208, 7208, 7208, -1, 7209, 7209, 7209, -1, + 7210, 7210, 7210, -1, 7211, 7211, 7211, -1, + 7212, 7212, 7212, -1, 7213, 7213, 7213, -1, + 7214, 7214, 7214, -1, 7215, 7215, 7215, -1, + 7216, 7216, 7216, -1, 7217, 7217, 7217, -1, + 7218, 7218, 7218, -1, 7219, 7219, 7219, -1, + 7220, 7220, 7220, -1, 7221, 7221, 7221, -1, + 7222, 7222, 7222, -1, 7223, 7223, 7223, -1, + 7224, 7224, 7224, -1, 7225, 7225, 7225, -1, + 7226, 7226, 7226, -1, 7227, 7227, 7227, -1, + 7228, 7228, 7228, -1, 7229, 7229, 7229, -1, + 7230, 7230, 7230, -1, 7231, 7231, 7231, -1, + 7232, 7232, 7232, -1, 7233, 7233, 7233, -1, + 7234, 7234, 7234, -1, 7235, 7235, 7235, -1, + 7236, 7236, 7236, -1, 7237, 7237, 7237, -1, + 7238, 7238, 7238, -1, 7239, 7239, 7239, -1, + 7240, 7240, 7240, -1, 7241, 7241, 7241, -1, + 7242, 7242, 7242, -1, 7243, 7243, 7243, -1, + 7244, 7244, 7244, -1, 7245, 7245, 7245, -1, + 7246, 7246, 7246, -1, 7247, 7247, 7247, -1, + 7248, 7248, 7248, -1, 7249, 7249, 7249, -1, + 7250, 7250, 7250, -1, 7251, 7251, 7251, -1, + 7252, 7252, 7252, -1, 7253, 7253, 7253, -1, + 7254, 7254, 7254, -1, 7255, 7255, 7255, -1, + 7256, 7256, 7256, -1, 7257, 7257, 7257, -1, + 7258, 7258, 7258, -1, 7259, 7259, 7259, -1, + 7260, 7260, 7260, -1, 7261, 7261, 7261, -1, + 7262, 7262, 7262, -1, 7263, 7263, 7263, -1, + 7264, 7264, 7264, -1, 7265, 7265, 7265, -1, + 7266, 7266, 7266, -1, 7267, 7267, 7267, -1, + 7268, 7268, 7268, -1, 7269, 7269, 7269, -1, + 7270, 7270, 7270, -1, 7271, 7271, 7271, -1, + 7272, 7272, 7272, -1, 7273, 7273, 7273, -1, + 7274, 7274, 7274, -1, 7275, 7275, 7275, -1, + 7276, 7276, 7276, -1, 7277, 7277, 7277, -1, + 7278, 7278, 7278, -1, 7279, 7279, 7279, -1, + 7280, 7280, 7280, -1, 7281, 7281, 7281, -1, + 7282, 7282, 7282, -1, 7283, 7283, 7283, -1, + 7284, 7284, 7284, -1, 7285, 7285, 7285, -1, + 7286, 7286, 7286, -1, 7287, 7287, 7287, -1, + 7288, 7288, 7288, -1, 7289, 7289, 7289, -1, + 7290, 7290, 7290, -1, 7291, 7291, 7291, -1, + 7292, 7292, 7292, -1, 7293, 7293, 7293, -1, + 7294, 7294, 7294, -1, 7295, 7295, 7295, -1, + 7296, 7296, 7296, -1, 7297, 7297, 7297, -1, + 7298, 7298, 7298, -1, 7299, 7299, 7299, -1, + 7300, 7300, 7300, -1, 7301, 7301, 7301, -1, + 7302, 7302, 7302, -1, 7303, 7303, 7303, -1, + 7304, 7304, 7304, -1, 7305, 7305, 7305, -1, + 7306, 7306, 7306, -1, 7307, 7307, 7307, -1, + 7308, 7308, 7308, -1, 7309, 7309, 7309, -1, + 7310, 7310, 7310, -1, 7311, 7311, 7311, -1, + 7312, 7312, 7312, -1, 7313, 7313, 7313, -1, + 7314, 7314, 7314, -1, 7315, 7315, 7315, -1, + 7316, 7316, 7316, -1, 7317, 7317, 7317, -1, + 7318, 7318, 7318, -1, 7319, 7319, 7319, -1, + 7320, 7320, 7320, -1, 7321, 7321, 7321, -1, + 7322, 7322, 7322, -1, 7323, 7323, 7323, -1, + 7324, 7324, 7324, -1, 7325, 7325, 7325, -1, + 7326, 7326, 7326, -1, 7327, 7327, 7327, -1, + 7328, 7328, 7328, -1, 7329, 7329, 7329, -1, + 7330, 7330, 7330, -1, 7331, 7331, 7331, -1, + 7332, 7332, 7332, -1, 7333, 7333, 7333, -1, + 7334, 7334, 7334, -1, 7335, 7335, 7335, -1, + 7336, 7336, 7336, -1, 7337, 7337, 7337, -1, + 7338, 7338, 7338, -1, 7339, 7339, 7339, -1, + 7340, 7340, 7340, -1, 7341, 7341, 7341, -1, + 7342, 7342, 7342, -1, 7343, 7343, 7343, -1, + 7344, 7344, 7344, -1, 7345, 7345, 7345, -1, + 7346, 7346, 7346, -1, 7347, 7347, 7347, -1, + 7348, 7348, 7348, -1, 7349, 7349, 7349, -1, + 7350, 7350, 7350, -1, 7351, 7351, 7351, -1, + 7352, 7352, 7352, -1, 7353, 7353, 7353, -1, + 7354, 7354, 7354, -1, 7355, 7355, 7355, -1, + 7356, 7356, 7356, -1, 7357, 7357, 7357, -1, + 7358, 7358, 7358, -1, 7359, 7359, 7359, -1, + 7360, 7360, 7360, -1, 7361, 7361, 7361, -1, + 7362, 7362, 7362, -1, 7363, 7363, 7363, -1, + 7364, 7364, 7364, -1, 7365, 7365, 7365, -1, + 7366, 7366, 7366, -1, 7367, 7367, 7367, -1, + 7368, 7368, 7368, -1, 7369, 7369, 7369, -1, + 7370, 7370, 7370, -1, 7371, 7371, 7371, -1, + 7372, 7372, 7372, -1, 7373, 7373, 7373, -1, + 7374, 7374, 7374, -1, 7375, 7375, 7375, -1, + 7376, 7376, 7376, -1, 7377, 7377, 7377, -1, + 7378, 7378, 7378, -1, 7379, 7379, 7379, -1, + 7380, 7380, 7380, -1, 7381, 7381, 7381, -1, + 7382, 7382, 7382, -1, 7383, 7383, 7383, -1, + 7384, 7384, 7384, -1, 7385, 7385, 7385, -1, + 7386, 7386, 7386, -1, 7387, 7387, 7387, -1, + 7388, 7388, 7388, -1, 7389, 7389, 7389, -1, + 7390, 7390, 7390, -1, 7391, 7391, 7391, -1, + 7392, 7392, 7392, -1, 7393, 7393, 7393, -1, + 7394, 7394, 7394, -1, 7395, 7395, 7395, -1, + 7396, 7396, 7396, -1, 7397, 7397, 7397, -1, + 7398, 7398, 7398, -1, 7399, 7399, 7399, -1, + 7400, 7400, 7400, -1, 7401, 7401, 7401, -1, + 7402, 7402, 7402, -1, 7403, 7403, 7403, -1, + 7404, 7404, 7404, -1, 7405, 7405, 7405, -1, + 7406, 7406, 7406, -1, 7407, 7407, 7407, -1, + 7408, 7408, 7408, -1, 7409, 7409, 7409, -1, + 7410, 7410, 7410, -1, 7411, 7411, 7411, -1, + 7412, 7412, 7412, -1, 7413, 7413, 7413, -1, + 7414, 7414, 7414, -1, 7415, 7415, 7415, -1, + 7416, 7416, 7416, -1, 7417, 7417, 7417, -1, + 7418, 7418, 7418, -1, 7419, 7419, 7419, -1, + 7420, 7420, 7420, -1, 7421, 7421, 7421, -1, + 7422, 7422, 7422, -1, 7423, 7423, 7423, -1, + 7424, 7424, 7424, -1, 7425, 7425, 7425, -1, + 7426, 7426, 7426, -1, 7427, 7427, 7427, -1, + 7428, 7428, 7428, -1, 7429, 7429, 7429, -1, + 7430, 7430, 7430, -1, 7431, 7431, 7431, -1, + 7432, 7432, 7432, -1, 7433, 7433, 7433, -1, + 7434, 7434, 7434, -1, 7435, 7435, 7435, -1, + 7436, 7436, 7436, -1, 7437, 7437, 7437, -1, + 7438, 7438, 7438, -1, 7439, 7439, 7439, -1, + 7440, 7440, 7440, -1, 7441, 7441, 7441, -1, + 7442, 7442, 7442, -1, 7443, 7443, 7443, -1, + 7444, 7444, 7444, -1, 7445, 7445, 7445, -1, + 7446, 7446, 7446, -1, 7447, 7447, 7447, -1, + 7448, 7448, 7448, -1, 7449, 7449, 7449, -1, + 7450, 7450, 7450, -1, 7451, 7451, 7451, -1, + 7452, 7452, 7452, -1, 7453, 7453, 7453, -1, + 7454, 7454, 7454, -1, 7455, 7455, 7455, -1, + 7456, 7456, 7456, -1, 7457, 7457, 7457, -1, + 7458, 7458, 7458, -1, 7459, 7459, 7459, -1, + 7460, 7460, 7460, -1, 7461, 7461, 7461, -1, + 7462, 7462, 7462, -1, 7463, 7463, 7463, -1, + 7464, 7464, 7464, -1, 7465, 7465, 7465, -1, + 7466, 7466, 7466, -1, 7467, 7467, 7467, -1, + 7468, 7468, 7468, -1, 7469, 7469, 7469, -1, + 7470, 7470, 7470, -1, 7471, 7471, 7471, -1, + 7472, 7472, 7472, -1, 7473, 7473, 7473, -1, + 7474, 7474, 7474, -1, 7475, 7475, 7475, -1, + 7476, 7476, 7476, -1, 7477, 7477, 7477, -1, + 7478, 7478, 7478, -1, 7479, 7479, 7479, -1, + 7480, 7480, 7480, -1, 7481, 7481, 7481, -1, + 7482, 7482, 7482, -1, 7483, 7483, 7483, -1, + 7484, 7484, 7484, -1, 7485, 7485, 7485, -1, + 7486, 7486, 7486, -1, 7487, 7487, 7487, -1, + 7488, 7488, 7488, -1, 7489, 7489, 7489, -1, + 7490, 7490, 7490, -1, 7491, 7491, 7491, -1, + 7492, 7492, 7492, -1, 7493, 7493, 7493, -1, + 7494, 7494, 7494, -1, 7495, 7495, 7495, -1, + 7496, 7496, 7496, -1, 7497, 7497, 7497, -1, + 7498, 7498, 7498, -1, 7499, 7499, 7499, -1, + 7500, 7500, 7500, -1, 7501, 7501, 7501, -1, + 7502, 7502, 7502, -1, 7503, 7503, 7503, -1, + 7504, 7504, 7504, -1, 7505, 7505, 7505, -1, + 7506, 7506, 7506, -1, 7507, 7507, 7507, -1, + 7508, 7508, 7508, -1, 7509, 7509, 7509, -1, + 7510, 7510, 7510, -1, 7511, 7511, 7511, -1, + 7512, 7512, 7512, -1, 7513, 7513, 7513, -1, + 7514, 7514, 7514, -1, 7515, 7515, 7515, -1, + 7516, 7516, 7516, -1, 7517, 7517, 7517, -1, + 7518, 7518, 7518, -1, 7519, 7519, 7519, -1, + 7520, 7520, 7520, -1, 7521, 7521, 7521, -1, + 7522, 7522, 7522, -1, 7523, 7523, 7523, -1, + 7524, 7524, 7524, -1, 7525, 7525, 7525, -1, + 7526, 7526, 7526, -1, 7527, 7527, 7527, -1, + 7528, 7528, 7528, -1, 7529, 7529, 7529, -1, + 7530, 7530, 7530, -1, 7531, 7531, 7531, -1, + 7532, 7532, 7532, -1, 7533, 7533, 7533, -1, + 7534, 7534, 7534, -1, 7535, 7535, 7535, -1, + 7536, 7536, 7536, -1, 7537, 7537, 7537, -1, + 7538, 7538, 7538, -1, 7539, 7539, 7539, -1, + 7540, 7540, 7540, -1, 7541, 7541, 7541, -1, + 7542, 7542, 7542, -1, 7543, 7543, 7543, -1, + 7544, 7544, 7544, -1, 7545, 7545, 7545, -1, + 7546, 7546, 7546, -1, 7547, 7547, 7547, -1, + 7548, 7548, 7548, -1, 7549, 7549, 7549, -1, + 7550, 7550, 7550, -1, 7551, 7551, 7551, -1, + 7552, 7552, 7552, -1, 7553, 7553, 7553, -1, + 7554, 7554, 7554, -1, 7555, 7555, 7555, -1, + 7556, 7556, 7556, -1, 7557, 7557, 7557, -1, + 7558, 7558, 7558, -1, 7559, 7559, 7559, -1, + 7560, 7560, 7560, -1, 7561, 7561, 7561, -1, + 7562, 7562, 7562, -1, 7563, 7563, 7563, -1, + 7564, 7564, 7564, -1, 7565, 7565, 7565, -1, + 7566, 7566, 7566, -1, 7567, 7567, 7567, -1, + 7568, 7568, 7568, -1, 7569, 7569, 7569, -1, + 7570, 7570, 7570, -1, 7571, 7571, 7571, -1, + 7572, 7572, 7572, -1, 7573, 7573, 7573, -1, + 7574, 7574, 7574, -1, 7575, 7575, 7575, -1, + 7576, 7576, 7576, -1, 7577, 7577, 7577, -1, + 7578, 7578, 7578, -1, 7579, 7579, 7579, -1, + 7580, 7580, 7580, -1, 7581, 7581, 7581, -1, + 7582, 7582, 7582, -1, 7583, 7583, 7583, -1, + 7584, 7584, 7584, -1, 7585, 7585, 7585, -1, + 7586, 7586, 7586, -1, 7587, 7587, 7587, -1, + 7588, 7588, 7588, -1, 7589, 7589, 7589, -1, + 7590, 7590, 7590, -1, 7591, 7591, 7591, -1, + 7592, 7592, 7592, -1, 7593, 7593, 7593, -1, + 7594, 7594, 7594, -1, 7595, 7595, 7595, -1, + 7596, 7596, 7596, -1, 7597, 7597, 7597, -1, + 7598, 7598, 7598, -1, 7599, 7599, 7599, -1, + 7600, 7600, 7600, -1, 7601, 7601, 7601, -1, + 7602, 7602, 7602, -1, 7603, 7603, 7603, -1, + 7604, 7604, 7604, -1, 7605, 7605, 7605, -1, + 7606, 7606, 7606, -1, 7607, 7607, 7607, -1, + 7608, 7608, 7608, -1, 7609, 7609, 7609, -1, + 7610, 7610, 7610, -1, 7611, 7611, 7611, -1, + 7612, 7612, 7612, -1, 7613, 7613, 7613, -1, + 7614, 7614, 7614, -1, 7615, 7615, 7615, -1, + 7616, 7616, 7616, -1, 7617, 7617, 7617, -1, + 7618, 7618, 7618, -1, 7619, 7619, 7619, -1, + 7620, 7620, 7620, -1, 7621, 7621, 7621, -1, + 7622, 7622, 7622, -1, 7623, 7623, 7623, -1, + 7624, 7624, 7624, -1, 7625, 7625, 7625, -1, + 7626, 7626, 7626, -1, 7627, 7627, 7627, -1, + 7628, 7628, 7628, -1, 7629, 7629, 7629, -1, + 7630, 7630, 7630, -1, 7631, 7631, 7631, -1, + 7632, 7632, 7632, -1, 7633, 7633, 7633, -1, + 7634, 7634, 7634, -1, 7635, 7635, 7635, -1, + 7636, 7636, 7636, -1, 7637, 7637, 7637, -1, + 7638, 7638, 7638, -1, 7639, 7639, 7639, -1, + 7640, 7640, 7640, -1, 7641, 7641, 7641, -1, + 7642, 7642, 7642, -1, 7643, 7643, 7643, -1, + 7644, 7644, 7644, -1, 7645, 7645, 7645, -1, + 7646, 7646, 7646, -1, 7647, 7647, 7647, -1, + 7648, 7648, 7648, -1, 7649, 7649, 7649, -1, + 7650, 7650, 7650, -1, 7651, 7651, 7651, -1, + 7652, 7652, 7652, -1, 7653, 7653, 7653, -1, + 7654, 7654, 7654, -1, 7655, 7655, 7655, -1, + 7656, 7656, 7656, -1, 7657, 7657, 7657, -1, + 7658, 7658, 7658, -1, 7659, 7659, 7659, -1, + 7660, 7660, 7660, -1, 7661, 7661, 7661, -1, + 7662, 7662, 7662, -1, 7663, 7663, 7663, -1, + 7664, 7664, 7664, -1, 7665, 7665, 7665, -1, + 7666, 7666, 7666, -1, 7667, 7667, 7667, -1, + 7668, 7668, 7668, -1, 7669, 7669, 7669, -1, + 7670, 7670, 7670, -1, 7671, 7671, 7671, -1, + 7672, 7672, 7672, -1, 7673, 7673, 7673, -1, + 7674, 7674, 7674, -1, 7675, 7675, 7675, -1, + 7676, 7676, 7676, -1, 7677, 7677, 7677, -1, + 7678, 7678, 7678, -1, 7679, 7679, 7679, -1, + 7680, 7680, 7680, -1, 7681, 7681, 7681, -1, + 7682, 7682, 7682, -1, 7683, 7683, 7683, -1, + 7684, 7684, 7684, -1, 7685, 7685, 7685, -1, + 7686, 7686, 7686, -1, 7687, 7687, 7687, -1, + 7688, 7688, 7688, -1, 7689, 7689, 7689, -1, + 7690, 7690, 7690, -1, 7691, 7691, 7691, -1, + 7692, 7692, 7692, -1, 7693, 7693, 7693, -1, + 7694, 7694, 7694, -1, 7695, 7695, 7695, -1, + 7696, 7696, 7696, -1, 7697, 7697, 7697, -1, + 7698, 7698, 7698, -1, 7699, 7699, 7699, -1, + 7700, 7700, 7700, -1, 7701, 7701, 7701, -1, + 7702, 7702, 7702, -1, 7703, 7703, 7703, -1, + 7704, 7704, 7704, -1, 7705, 7705, 7705, -1, + 7706, 7706, 7706, -1, 7707, 7707, 7707, -1, + 7708, 7708, 7708, -1, 7709, 7709, 7709, -1, + 7710, 7710, 7710, -1, 7711, 7711, 7711, -1, + 7712, 7712, 7712, -1, 7713, 7713, 7713, -1, + 7714, 7714, 7714, -1, 7715, 7715, 7715, -1, + 7716, 7716, 7716, -1, 7717, 7717, 7717, -1, + 7718, 7718, 7718, -1, 7719, 7719, 7719, -1, + 7720, 7720, 7720, -1, 7721, 7721, 7721, -1, + 7722, 7722, 7722, -1, 7723, 7723, 7723, -1, + 7724, 7724, 7724, -1, 7725, 7725, 7725, -1, + 7726, 7726, 7726, -1, 7727, 7727, 7727, -1, + 7728, 7728, 7728, -1, 7729, 7729, 7729, -1, + 7730, 7730, 7730, -1, 7731, 7731, 7731, -1, + 7732, 7732, 7732, -1, 7733, 7733, 7733, -1, + 7734, 7734, 7734, -1, 7735, 7735, 7735, -1, + 7736, 7736, 7736, -1, 7737, 7737, 7737, -1, + 7738, 7738, 7738, -1, 7739, 7739, 7739, -1, + 7740, 7740, 7740, -1, 7741, 7741, 7741, -1, + 7742, 7742, 7742, -1, 7743, 7743, 7743, -1, + 7744, 7744, 7744, -1, 7745, 7745, 7745, -1, + 7746, 7746, 7746, -1, 7747, 7747, 7747, -1, + 7748, 7748, 7748, -1, 7749, 7749, 7749, -1, + 7750, 7750, 7750, -1, 7751, 7751, 7751, -1, + 7752, 7752, 7752, -1, 7753, 7753, 7753, -1, + 7754, 7754, 7754, -1, 7755, 7755, 7755, -1, + 7756, 7756, 7756, -1, 7757, 7757, 7757, -1, + 7758, 7758, 7758, -1, 7759, 7759, 7759, -1, + 7760, 7760, 7760, -1, 7761, 7761, 7761, -1, + 7762, 7762, 7762, -1, 7763, 7763, 7763, -1, + 7764, 7764, 7764, -1, 7765, 7765, 7765, -1, + 7766, 7766, 7766, -1, 7767, 7767, 7767, -1, + 7768, 7768, 7768, -1, 7769, 7769, 7769, -1, + 7770, 7770, 7770, -1, 7771, 7771, 7771, -1, + 7772, 7772, 7772, -1, 7773, 7773, 7773, -1, + 7774, 7774, 7774, -1, 7775, 7775, 7775, -1, + 7776, 7776, 7776, -1, 7777, 7777, 7777, -1, + 7778, 7778, 7778, -1, 7779, 7779, 7779, -1, + 7780, 7780, 7780, -1, 7781, 7781, 7781, -1, + 7782, 7782, 7782, -1, 7783, 7783, 7783, -1, + 7784, 7784, 7784, -1, 7785, 7785, 7785, -1, + 7786, 7786, 7786, -1, 7787, 7787, 7787, -1, + 7788, 7788, 7788, -1, 7789, 7789, 7789, -1, + 7790, 7790, 7790, -1, 7791, 7791, 7791, -1, + 7792, 7792, 7792, -1, 7793, 7793, 7793, -1, + 7794, 7794, 7794, -1, 7795, 7795, 7795, -1, + 7796, 7796, 7796, -1, 7797, 7797, 7797, -1, + 7798, 7798, 7798, -1, 7799, 7799, 7799, -1, + 7800, 7800, 7800, -1, 7801, 7801, 7801, -1, + 7802, 7802, 7802, -1, 7803, 7803, 7803, -1, + 7804, 7804, 7804, -1, 7805, 7805, 7805, -1, + 7806, 7806, 7806, -1, 7807, 7807, 7807, -1, + 7808, 7808, 7808, -1, 7809, 7809, 7809, -1, + 7810, 7810, 7810, -1, 7811, 7811, 7811, -1, + 7812, 7812, 7812, -1, 7813, 7813, 7813, -1, + 7814, 7814, 7814, -1, 7815, 7815, 7815, -1, + 7816, 7816, 7816, -1, 7817, 7817, 7817, -1, + 7818, 7818, 7818, -1, 7819, 7819, 7819, -1, + 7820, 7820, 7820, -1, 7821, 7821, 7821, -1, + 7822, 7822, 7822, -1, 7823, 7823, 7823, -1, + 7824, 7824, 7824, -1, 7825, 7825, 7825, -1, + 7826, 7826, 7826, -1, 7827, 7827, 7827, -1, + 7828, 7828, 7828, -1, 7829, 7829, 7829, -1, + 7830, 7830, 7830, -1, 7831, 7831, 7831, -1, + 7832, 7832, 7832, -1, 7833, 7833, 7833, -1, + 7834, 7834, 7834, -1, 7835, 7835, 7835, -1, + 7836, 7836, 7836, -1, 7837, 7837, 7837, -1, + 7838, 7838, 7838, -1, 7839, 7839, 7839, -1, + 7840, 7840, 7840, -1, 7841, 7841, 7841, -1, + 7842, 7842, 7842, -1, 7843, 7843, 7843, -1, + 7844, 7844, 7844, -1, 7845, 7845, 7845, -1, + 7846, 7846, 7846, -1, 7847, 7847, 7847, -1, + 7848, 7848, 7848, -1, 7849, 7849, 7849, -1, + 7850, 7850, 7850, -1, 7851, 7851, 7851, -1, + 7852, 7852, 7852, -1, 7853, 7853, 7853, -1, + 7854, 7854, 7854, -1, 7855, 7855, 7855, -1, + 7856, 7856, 7856, -1, 7857, 7857, 7857, -1, + 7858, 7858, 7858, -1, 7859, 7859, 7859, -1, + 7860, 7860, 7860, -1, 7861, 7861, 7861, -1, + 7862, 7862, 7862, -1, 7863, 7863, 7863, -1, + 7864, 7864, 7864, -1, 7865, 7865, 7865, -1, + 7866, 7866, 7866, -1, 7867, 7867, 7867, -1, + 7868, 7868, 7868, -1, 7869, 7869, 7869, -1, + 7870, 7870, 7870, -1, 7871, 7871, 7871, -1, + 7872, 7872, 7872, -1, 7873, 7873, 7873, -1, + 7874, 7874, 7874, -1, 7875, 7875, 7875, -1, + 7876, 7876, 7876, -1, 7877, 7877, 7877, -1, + 7878, 7878, 7878, -1, 7879, 7879, 7879, -1, + 7880, 7880, 7880, -1, 7881, 7881, 7881, -1, + 7882, 7882, 7882, -1, 7883, 7883, 7883, -1, + 7884, 7884, 7884, -1, 7885, 7885, 7885, -1, + 7886, 7886, 7886, -1, 7887, 7887, 7887, -1, + 7888, 7888, 7888, -1, 7889, 7889, 7889, -1, + 7890, 7890, 7890, -1, 7891, 7891, 7891, -1, + 7892, 7892, 7892, -1, 7893, 7893, 7893, -1, + 7894, 7894, 7894, -1, 7895, 7895, 7895, -1, + 7896, 7896, 7896, -1, 7897, 7897, 7897, -1, + 7898, 7898, 7898, -1, 7899, 7899, 7899, -1, + 7900, 7900, 7900, -1, 7901, 7901, 7901, -1, + 7902, 7902, 7902, -1, 7903, 7903, 7903, -1, + 7904, 7904, 7904, -1, 7905, 7905, 7905, -1, + 7906, 7906, 7906, -1, 7907, 7907, 7907, -1, + 7908, 7908, 7908, -1, 7909, 7909, 7909, -1, + 7910, 7910, 7910, -1, 7911, 7911, 7911, -1, + 7912, 7912, 7912, -1, 7913, 7913, 7913, -1, + 7914, 7914, 7914, -1, 7915, 7915, 7915, -1, + 7916, 7916, 7916, -1, 7917, 7917, 7917, -1, + 7918, 7918, 7918, -1, 7919, 7919, 7919, -1, + 7920, 7920, 7920, -1, 7921, 7921, 7921, -1, + 7922, 7922, 7922, -1, 7923, 7923, 7923, -1, + 7924, 7924, 7924, -1, 7925, 7925, 7925, -1, + 7926, 7926, 7926, -1, 7927, 7927, 7927, -1, + 7928, 7928, 7928, -1, 7929, 7929, 7929, -1, + 7930, 7930, 7930, -1, 7931, 7931, 7931, -1, + 7932, 7932, 7932, -1, 7933, 7933, 7933, -1, + 7934, 7934, 7934, -1, 7935, 7935, 7935, -1, + 7936, 7936, 7936, -1, 7937, 7937, 7937, -1, + 7938, 7938, 7938, -1, 7939, 7939, 7939, -1, + 7940, 7940, 7940, -1, 7941, 7941, 7941, -1, + 7942, 7942, 7942, -1, 7943, 7943, 7943, -1, + 7944, 7944, 7944, -1, 7945, 7945, 7945, -1, + 7946, 7946, 7946, -1, 7947, 7947, 7947, -1, + 7948, 7948, 7948, -1, 7949, 7949, 7949, -1, + 7950, 7950, 7950, -1, 7951, 7951, 7951, -1, + 7952, 7952, 7952, -1, 7953, 7953, 7953, -1, + 7954, 7954, 7954, -1, 7955, 7955, 7955, -1, + 7956, 7956, 7956, -1, 7957, 7957, 7957, -1, + 7958, 7958, 7958, -1, 7959, 7959, 7959, -1, + 7960, 7960, 7960, -1, 7961, 7961, 7961, -1, + 7962, 7962, 7962, -1, 7963, 7963, 7963, -1, + 7964, 7964, 7964, -1, 7965, 7965, 7965, -1, + 7966, 7966, 7966, -1, 7967, 7967, 7967, -1, + 7968, 7968, 7968, -1, 7969, 7969, 7969, -1, + 7970, 7970, 7970, -1, 7971, 7971, 7971, -1, + 7972, 7972, 7972, -1, 7973, 7973, 7973, -1, + 7974, 7974, 7974, -1, 7975, 7975, 7975, -1, + 7976, 7976, 7976, -1, 7977, 7977, 7977, -1, + 7978, 7978, 7978, -1, 7979, 7979, 7979, -1, + 7980, 7980, 7980, -1, 7981, 7981, 7981, -1, + 7982, 7982, 7982, -1, 7983, 7983, 7983, -1, + 7984, 7984, 7984, -1, 7985, 7985, 7985, -1, + 7986, 7986, 7986, -1, 7987, 7987, 7987, -1, + 7988, 7988, 7988, -1, 7989, 7989, 7989, -1, + 7990, 7990, 7990, -1, 7991, 7991, 7991, -1, + 7992, 7992, 7992, -1, 7993, 7993, 7993, -1, + 7994, 7994, 7994, -1, 7995, 7995, 7995, -1, + 7996, 7996, 7996, -1, 7997, 7997, 7997, -1, + 7998, 7998, 7998, -1, 7999, 7999, 7999, -1, + 8000, 8000, 8000, -1, 8001, 8001, 8001, -1, + 8002, 8002, 8002, -1, 8003, 8003, 8003, -1, + 8004, 8004, 8004, -1, 8005, 8005, 8005, -1, + 8006, 8006, 8006, -1, 8007, 8007, 8007, -1, + 8008, 8008, 8008, -1, 8009, 8009, 8009, -1, + 8010, 8010, 8010, -1, 8011, 8011, 8011, -1, + 8012, 8012, 8012, -1, 8013, 8013, 8013, -1, + 8014, 8014, 8014, -1, 8015, 8015, 8015, -1, + 8016, 8016, 8016, -1, 8017, 8017, 8017, -1, + 8018, 8018, 8018, -1, 8019, 8019, 8019, -1, + 8020, 8020, 8020, -1, 8021, 8021, 8021, -1, + 8022, 8022, 8022, -1, 8023, 8023, 8023, -1, + 8024, 8024, 8024, -1, 8025, 8025, 8025, -1, + 8026, 8026, 8026, -1, 8027, 8027, 8027, -1, + 8028, 8028, 8028, -1, 8029, 8029, 8029, -1, + 8030, 8030, 8030, -1, 8031, 8031, 8031, -1, + 8032, 8032, 8032, -1, 8033, 8033, 8033, -1, + 8034, 8034, 8034, -1, 8035, 8035, 8035, -1, + 8036, 8036, 8036, -1, 8037, 8037, 8037, -1, + 8038, 8038, 8038, -1, 8039, 8039, 8039, -1, + 8040, 8040, 8040, -1, 8041, 8041, 8041, -1, + 8042, 8042, 8042, -1, 8043, 8043, 8043, -1, + 8044, 8044, 8044, -1, 8045, 8045, 8045, -1, + 8046, 8046, 8046, -1, 8047, 8047, 8047, -1, + 8048, 8048, 8048, -1, 8049, 8049, 8049, -1, + 8050, 8050, 8050, -1, 8051, 8051, 8051, -1, + 8052, 8052, 8052, -1, 8053, 8053, 8053, -1, + 8054, 8054, 8054, -1, 8055, 8055, 8055, -1, + 8056, 8056, 8056, -1, 8057, 8057, 8057, -1, + 8058, 8058, 8058, -1, 8059, 8059, 8059, -1, + 8060, 8060, 8060, -1, 8061, 8061, 8061, -1, + 8062, 8062, 8062, -1, 8063, 8063, 8063, -1, + 8064, 8064, 8064, -1, 8065, 8065, 8065, -1, + 8066, 8066, 8066, -1, 8067, 8067, 8067, -1, + 8068, 8068, 8068, -1, 8069, 8069, 8069, -1, + 8070, 8070, 8070, -1, 8071, 8071, 8071, -1, + 8072, 8072, 8072, -1, 8073, 8073, 8073, -1, + 8074, 8074, 8074, -1, 8075, 8075, 8075, -1, + 8076, 8076, 8076, -1, 8077, 8077, 8077, -1, + 8078, 8078, 8078, -1, 8079, 8079, 8079, -1, + 8080, 8080, 8080, -1, 8081, 8081, 8081, -1, + 8082, 8082, 8082, -1, 8083, 8083, 8083, -1, + 8084, 8084, 8084, -1, 8085, 8085, 8085, -1, + 8086, 8086, 8086, -1, 8087, 8087, 8087, -1, + 8088, 8088, 8088, -1, 8089, 8089, 8089, -1, + 8090, 8090, 8090, -1, 8091, 8091, 8091, -1, + 8092, 8092, 8092, -1, 8093, 8093, 8093, -1, + 8094, 8094, 8094, -1, 8095, 8095, 8095, -1, + 8096, 8096, 8096, -1, 8097, 8097, 8097, -1, + 8098, 8098, 8098, -1, 8099, 8099, 8099, -1, + 8100, 8100, 8100, -1, 8101, 8101, 8101, -1, + 8102, 8102, 8102, -1, 8103, 8103, 8103, -1, + 8104, 8104, 8104, -1, 8105, 8105, 8105, -1, + 8106, 8106, 8106, -1, 8107, 8107, 8107, -1, + 8108, 8108, 8108, -1, 8109, 8109, 8109, -1, + 8110, 8110, 8110, -1, 8111, 8111, 8111, -1, + 8112, 8112, 8112, -1, 8113, 8113, 8113, -1, + 8114, 8114, 8114, -1, 8115, 8115, 8115, -1, + 8116, 8116, 8116, -1, 8117, 8117, 8117, -1, + 8118, 8118, 8118, -1, 8119, 8119, 8119, -1, + 8120, 8120, 8120, -1, 8121, 8121, 8121, -1, + 8122, 8122, 8122, -1, 8123, 8123, 8123, -1, + 8124, 8124, 8124, -1, 8125, 8125, 8125, -1, + 8126, 8126, 8126, -1, 8127, 8127, 8127, -1, + 8128, 8128, 8128, -1, 8129, 8129, 8129, -1, + 8130, 8130, 8130, -1, 8131, 8131, 8131, -1, + 8132, 8132, 8132, -1, 8133, 8133, 8133, -1, + 8134, 8134, 8134, -1, 8135, 8135, 8135, -1, + 8136, 8136, 8136, -1, 8137, 8137, 8137, -1, + 8138, 8138, 8138, -1, 8139, 8139, 8139, -1, + 8140, 8140, 8140, -1, 8141, 8141, 8141, -1, + 8142, 8142, 8142, -1, 8143, 8143, 8143, -1, + 8144, 8144, 8144, -1, 8145, 8145, 8145, -1, + 8146, 8146, 8146, -1, 8147, 8147, 8147, -1, + 8148, 8148, 8148, -1, 8149, 8149, 8149, -1, + 8150, 8150, 8150, -1, 8151, 8151, 8151, -1, + 8152, 8152, 8152, -1, 8153, 8153, 8153, -1, + 8154, 8154, 8154, -1, 8155, 8155, 8155, -1, + 8156, 8156, 8156, -1, 8157, 8157, 8157, -1, + 8158, 8158, 8158, -1, 8159, 8159, 8159, -1, + 8160, 8160, 8160, -1, 8161, 8161, 8161, -1, + 8162, 8162, 8162, -1, 8163, 8163, 8163, -1, + 8164, 8164, 8164, -1, 8165, 8165, 8165, -1, + 8166, 8166, 8166, -1, 8167, 8167, 8167, -1, + 8168, 8168, 8168, -1, 8169, 8169, 8169, -1, + 8170, 8170, 8170, -1, 8171, 8171, 8171, -1, + 8172, 8172, 8172, -1, 8173, 8173, 8173, -1, + 8174, 8174, 8174, -1, 8175, 8175, 8175, -1, + 8176, 8176, 8176, -1, 8177, 8177, 8177, -1, + 8178, 8178, 8178, -1, 8179, 8179, 8179, -1, + 8180, 8180, 8180, -1, 8181, 8181, 8181, -1, + 8182, 8182, 8182, -1, 8183, 8183, 8183, -1, + 8184, 8184, 8184, -1, 8185, 8185, 8185, -1, + 8186, 8186, 8186, -1, 8187, 8187, 8187, -1, + 8188, 8188, 8188, -1, 8189, 8189, 8189, -1, + 8190, 8190, 8190, -1, 8191, 8191, 8191, -1, + 8192, 8192, 8192, -1, 8193, 8193, 8193, -1, + 8194, 8194, 8194, -1, 8195, 8195, 8195, -1, + 8196, 8196, 8196, -1, 8197, 8197, 8197, -1, + 8198, 8198, 8198, -1, 8199, 8199, 8199, -1, + 8200, 8200, 8200, -1, 8201, 8201, 8201, -1, + 8202, 8202, 8202, -1, 8203, 8203, 8203, -1, + 8204, 8204, 8204, -1, 8205, 8205, 8205, -1, + 8206, 8206, 8206, -1, 8207, 8207, 8207, -1, + 8208, 8208, 8208, -1, 8209, 8209, 8209, -1, + 8210, 8210, 8210, -1, 8211, 8211, 8211, -1, + 8212, 8212, 8212, -1, 8213, 8213, 8213, -1, + 8214, 8214, 8214, -1, 8215, 8215, 8215, -1, + 8216, 8216, 8216, -1, 8217, 8217, 8217, -1, + 8218, 8218, 8218, -1, 8219, 8219, 8219, -1, + 8220, 8220, 8220, -1, 8221, 8221, 8221, -1, + 8222, 8222, 8222, -1, 8223, 8223, 8223, -1, + 8224, 8224, 8224, -1, 8225, 8225, 8225, -1, + 8226, 8226, 8226, -1, 8227, 8227, 8227, -1, + 8228, 8228, 8228, -1, 8229, 8229, 8229, -1, + 8230, 8230, 8230, -1, 8231, 8231, 8231, -1, + 8232, 8232, 8232, -1, 8233, 8233, 8233, -1, + 8234, 8234, 8234, -1, 8235, 8235, 8235, -1, + 8236, 8236, 8236, -1, 8237, 8237, 8237, -1, + 8238, 8238, 8238, -1, 8239, 8239, 8239, -1, + 8240, 8240, 8240, -1, 8241, 8241, 8241, -1, + 8242, 8242, 8242, -1, 8243, 8243, 8243, -1, + 8244, 8244, 8244, -1, 8245, 8245, 8245, -1, + 8246, 8246, 8246, -1, 8247, 8247, 8247, -1, + 8248, 8248, 8248, -1, 8249, 8249, 8249, -1, + 8250, 8250, 8250, -1, 8251, 8251, 8251, -1, + 8252, 8252, 8252, -1, 8253, 8253, 8253, -1, + 8254, 8254, 8254, -1, 8255, 8255, 8255, -1, + 8256, 8256, 8256, -1, 8257, 8257, 8257, -1, + 8258, 8258, 8258, -1, 8259, 8259, 8259, -1, + 8260, 8260, 8260, -1, 8261, 8261, 8261, -1, + 8262, 8262, 8262, -1, 8263, 8263, 8263, -1, + 8264, 8264, 8264, -1, 8265, 8265, 8265, -1, + 8266, 8266, 8266, -1, 8267, 8267, 8267, -1, + 8268, 8268, 8268, -1, 8269, 8269, 8269, -1, + 8270, 8270, 8270, -1, 8271, 8271, 8271, -1, + 8272, 8272, 8272, -1, 8273, 8273, 8273, -1, + 8274, 8274, 8274, -1, 8275, 8275, 8275, -1, + 8276, 8276, 8276, -1, 8277, 8277, 8277, -1, + 8278, 8278, 8278, -1, 8279, 8279, 8279, -1, + 8280, 8280, 8280, -1, 8281, 8281, 8281, -1, + 8282, 8282, 8282, -1, 8283, 8283, 8283, -1, + 8284, 8284, 8284, -1, 8285, 8285, 8285, -1, + 8286, 8286, 8286, -1, 8287, 8287, 8287, -1, + 8288, 8288, 8288, -1, 8289, 8289, 8289, -1, + 8290, 8290, 8290, -1, 8291, 8291, 8291, -1, + 8292, 8292, 8292, -1, 8293, 8293, 8293, -1, + 8294, 8294, 8294, -1, 8295, 8295, 8295, -1, + 8296, 8296, 8296, -1, 8297, 8297, 8297, -1, + 8298, 8298, 8298, -1, 8299, 8299, 8299, -1, + 8300, 8300, 8300, -1, 8301, 8301, 8301, -1, + 8302, 8302, 8302, -1, 8303, 8303, 8303, -1, + 8304, 8304, 8304, -1, 8305, 8305, 8305, -1, + 8306, 8306, 8306, -1, 8307, 8307, 8307, -1, + 8308, 8308, 8308, -1, 8309, 8309, 8309, -1, + 8310, 8310, 8310, -1, 8311, 8311, 8311, -1, + 8312, 8312, 8312, -1, 8313, 8313, 8313, -1, + 8314, 8314, 8314, -1, 8315, 8315, 8315, -1, + 8316, 8316, 8316, -1, 8317, 8317, 8317, -1, + 8318, 8318, 8318, -1, 8319, 8319, 8319, -1, + 8320, 8320, 8320, -1, 8321, 8321, 8321, -1, + 8322, 8322, 8322, -1, 8323, 8323, 8323, -1, + 8324, 8324, 8324, -1, 8325, 8325, 8325, -1, + 8326, 8326, 8326, -1, 8327, 8327, 8327, -1, + 8328, 8328, 8328, -1, 8329, 8329, 8329, -1, + 8330, 8330, 8330, -1, 8331, 8331, 8331, -1, + 8332, 8332, 8332, -1, 8333, 8333, 8333, -1, + 8334, 8334, 8334, -1, 8335, 8335, 8335, -1, + 8336, 8336, 8336, -1, 8337, 8337, 8337, -1, + 8338, 8338, 8338, -1, 8339, 8339, 8339, -1, + 8340, 8340, 8340, -1, 8341, 8341, 8341, -1, + 8342, 8342, 8342, -1, 8343, 8343, 8343, -1, + 8344, 8344, 8344, -1, 8345, 8345, 8345, -1, + 8346, 8346, 8346, -1, 8347, 8347, 8347, -1, + 8348, 8348, 8348, -1, 8349, 8349, 8349, -1, + 8350, 8350, 8350, -1, 8351, 8351, 8351, -1, + 8352, 8352, 8352, -1, 8353, 8353, 8353, -1, + 8354, 8354, 8354, -1, 8355, 8355, 8355, -1, + 8356, 8356, 8356, -1, 8357, 8357, 8357, -1, + 8358, 8358, 8358, -1, 8359, 8359, 8359, -1, + 8360, 8360, 8360, -1, 8361, 8361, 8361, -1, + 8362, 8362, 8362, -1, 8363, 8363, 8363, -1, + 8364, 8364, 8364, -1, 8365, 8365, 8365, -1, + 8366, 8366, 8366, -1, 8367, 8367, 8367, -1, + 8368, 8368, 8368, -1, 8369, 8369, 8369, -1, + 8370, 8370, 8370, -1, 8371, 8371, 8371, -1, + 8372, 8372, 8372, -1, 8373, 8373, 8373, -1, + 8374, 8374, 8374, -1, 8375, 8375, 8375, -1, + 8376, 8376, 8376, -1, 8377, 8377, 8377, -1, + 8378, 8378, 8378, -1, 8379, 8379, 8379, -1, + 8380, 8380, 8380, -1, 8381, 8381, 8381, -1, + 8382, 8382, 8382, -1, 8383, 8383, 8383, -1, + 8384, 8384, 8384, -1, 8385, 8385, 8385, -1, + 8386, 8386, 8386, -1, 8387, 8387, 8387, -1, + 8388, 8388, 8388, -1, 8389, 8389, 8389, -1, + 8390, 8390, 8390, -1, 8391, 8391, 8391, -1, + 8392, 8392, 8392, -1, 8393, 8393, 8393, -1, + 8394, 8394, 8394, -1, 8395, 8395, 8395, -1, + 8396, 8396, 8396, -1, 8397, 8397, 8397, -1, + 8398, 8398, 8398, -1, 8399, 8399, 8399, -1, + 8400, 8400, 8400, -1, 8401, 8401, 8401, -1, + 8402, 8402, 8402, -1, 8403, 8403, 8403, -1, + 8404, 8404, 8404, -1, 8405, 8405, 8405, -1, + 8406, 8406, 8406, -1, 8407, 8407, 8407, -1, + 8408, 8408, 8408, -1, 8409, 8409, 8409, -1, + 8410, 8410, 8410, -1, 8411, 8411, 8411, -1, + 8412, 8412, 8412, -1, 8413, 8413, 8413, -1, + 8414, 8414, 8414, -1, 8415, 8415, 8415, -1, + 8416, 8416, 8416, -1, 8417, 8417, 8417, -1, + 8418, 8418, 8418, -1, 8419, 8419, 8419, -1, + 8420, 8420, 8420, -1, 8421, 8421, 8421, -1, + 8422, 8422, 8422, -1, 8423, 8423, 8423, -1, + 8424, 8424, 8424, -1, 8425, 8425, 8425, -1, + 8426, 8426, 8426, -1, 8427, 8427, 8427, -1, + 8428, 8428, 8428, -1, 8429, 8429, 8429, -1, + 8430, 8430, 8430, -1, 8431, 8431, 8431, -1, + 8432, 8432, 8432, -1, 8433, 8433, 8433, -1, + 8434, 8434, 8434, -1, 8435, 8435, 8435, -1, + 8436, 8436, 8436, -1, 8437, 8437, 8437, -1, + 8438, 8438, 8438, -1, 8439, 8439, 8439, -1, + 8440, 8440, 8440, -1, 8441, 8441, 8441, -1, + 8442, 8442, 8442, -1, 8443, 8443, 8443, -1, + 8444, 8444, 8444, -1, 8445, 8445, 8445, -1, + 8446, 8446, 8446, -1, 8447, 8447, 8447, -1, + 8448, 8448, 8448, -1, 8449, 8449, 8449, -1, + 8450, 8450, 8450, -1, 8451, 8451, 8451, -1, + 8452, 8452, 8452, -1, 8453, 8453, 8453, -1, + 8454, 8454, 8454, -1, 8455, 8455, 8455, -1, + 8456, 8456, 8456, -1, 8457, 8457, 8457, -1, + 8458, 8458, 8458, -1, 8459, 8459, 8459, -1, + 8460, 8460, 8460, -1, 8461, 8461, 8461, -1, + 8462, 8462, 8462, -1, 8463, 8463, 8463, -1, + 8464, 8464, 8464, -1, 8465, 8465, 8465, -1, + 8466, 8466, 8466, -1, 8467, 8467, 8467, -1, + 8468, 8468, 8468, -1, 8469, 8469, 8469, -1, + 8470, 8470, 8470, -1, 8471, 8471, 8471, -1, + 8472, 8472, 8472, -1, 8473, 8473, 8473, -1, + 8474, 8474, 8474, -1, 8475, 8475, 8475, -1, + 8476, 8476, 8476, -1, 8477, 8477, 8477, -1, + 8478, 8478, 8478, -1, 8479, 8479, 8479, -1, + 8480, 8480, 8480, -1, 8481, 8481, 8481, -1, + 8482, 8482, 8482, -1, 8483, 8483, 8483, -1, + 8484, 8484, 8484, -1, 8485, 8485, 8485, -1, + 8486, 8486, 8486, -1, 8487, 8487, 8487, -1, + 8488, 8488, 8488, -1, 8489, 8489, 8489, -1, + 8490, 8490, 8490, -1, 8491, 8491, 8491, -1, + 8492, 8492, 8492, -1, 8493, 8493, 8493, -1, + 8494, 8494, 8494, -1, 8495, 8495, 8495, -1, + 8496, 8496, 8496, -1, 8497, 8497, 8497, -1, + 8498, 8498, 8498, -1, 8499, 8499, 8499, -1, + 8500, 8500, 8500, -1, 8501, 8501, 8501, -1, + 8502, 8502, 8502, -1, 8503, 8503, 8503, -1, + 8504, 8504, 8504, -1, 8505, 8505, 8505, -1, + 8506, 8506, 8506, -1, 8507, 8507, 8507, -1, + 8508, 8508, 8508, -1, 8509, 8509, 8509, -1, + 8510, 8510, 8510, -1, 8511, 8511, 8511, -1, + 8512, 8512, 8512, -1, 8513, 8513, 8513, -1, + 8514, 8514, 8514, -1, 8515, 8515, 8515, -1, + 8516, 8516, 8516, -1, 8517, 8517, 8517, -1, + 8518, 8518, 8518, -1, 8519, 8519, 8519, -1, + 8520, 8520, 8520, -1, 8521, 8521, 8521, -1, + 8522, 8522, 8522, -1, 8523, 8523, 8523, -1, + 8524, 8524, 8524, -1, 8525, 8525, 8525, -1, + 8526, 8526, 8526, -1, 8527, 8527, 8527, -1, + 8528, 8528, 8528, -1, 8529, 8529, 8529, -1, + 8530, 8530, 8530, -1, 8531, 8531, 8531, -1, + 8532, 8532, 8532, -1, 8533, 8533, 8533, -1, + 8534, 8534, 8534, -1, 8535, 8535, 8535, -1, + 8536, 8536, 8536, -1, 8537, 8537, 8537, -1, + 8538, 8538, 8538, -1, 8539, 8539, 8539, -1, + 8540, 8540, 8540, -1, 8541, 8541, 8541, -1, + 8542, 8542, 8542, -1, 8543, 8543, 8543, -1, + 8544, 8544, 8544, -1, 8545, 8545, 8545, -1, + 8546, 8546, 8546, -1, 8547, 8547, 8547, -1, + 8548, 8548, 8548, -1, 8549, 8549, 8549, -1, + 8550, 8550, 8550, -1, 8551, 8551, 8551, -1, + 8552, 8552, 8552, -1, 8553, 8553, 8553, -1, + 8554, 8554, 8554, -1, 8555, 8555, 8555, -1, + 8556, 8556, 8556, -1, 8557, 8557, 8557, -1, + 8558, 8558, 8558, -1, 8559, 8559, 8559, -1, + 8560, 8560, 8560, -1, 8561, 8561, 8561, -1, + 8562, 8562, 8562, -1, 8563, 8563, 8563, -1, + 8564, 8564, 8564, -1, 8565, 8565, 8565, -1, + 8566, 8566, 8566, -1, 8567, 8567, 8567, -1, + 8568, 8568, 8568, -1, 8569, 8569, 8569, -1, + 8570, 8570, 8570, -1, 8571, 8571, 8571, -1, + 8572, 8572, 8572, -1, 8573, 8573, 8573, -1, + 8574, 8574, 8574, -1, 8575, 8575, 8575, -1, + 8576, 8576, 8576, -1, 8577, 8577, 8577, -1, + 8578, 8578, 8578, -1, 8579, 8579, 8579, -1, + 8580, 8580, 8580, -1, 8581, 8581, 8581, -1, + 8582, 8582, 8582, -1, 8583, 8583, 8583, -1, + 8584, 8584, 8584, -1, 8585, 8585, 8585, -1, + 8586, 8586, 8586, -1, 8587, 8587, 8587, -1, + 8588, 8588, 8588, -1, 8589, 8589, 8589, -1, + 8590, 8590, 8590, -1, 8591, 8591, 8591, -1, + 8592, 8592, 8592, -1, 8593, 8593, 8593, -1, + 8594, 8594, 8594, -1, 8595, 8595, 8595, -1, + 8596, 8596, 8596, -1, 8597, 8597, 8597, -1, + 8598, 8598, 8598, -1, 8599, 8599, 8599, -1, + 8600, 8600, 8600, -1, 8601, 8601, 8601, -1, + 8602, 8602, 8602, -1, 8603, 8603, 8603, -1, + 8604, 8604, 8604, -1, 8605, 8605, 8605, -1, + 8606, 8606, 8606, -1, 8607, 8607, 8607, -1, + 8608, 8608, 8608, -1, 8609, 8609, 8609, -1, + 8610, 8610, 8610, -1, 8611, 8611, 8611, -1, + 8612, 8612, 8612, -1, 8613, 8613, 8613, -1, + 8614, 8614, 8614, -1, 8615, 8615, 8615, -1, + 8616, 8616, 8616, -1, 8617, 8617, 8617, -1, + 8618, 8618, 8618, -1, 8619, 8619, 8619, -1, + 8620, 8620, 8620, -1, 8621, 8621, 8621, -1, + 8622, 8622, 8622, -1, 8623, 8623, 8623, -1, + 8624, 8624, 8624, -1, 8625, 8625, 8625, -1, + 8626, 8626, 8626, -1, 8627, 8627, 8627, -1, + 8628, 8628, 8628, -1, 8629, 8629, 8629, -1, + 8630, 8630, 8630, -1, 8631, 8631, 8631, -1, + 8632, 8632, 8632, -1, 8633, 8633, 8633, -1, + 8634, 8634, 8634, -1, 8635, 8635, 8635, -1, + 8636, 8636, 8636, -1, 8637, 8637, 8637, -1, + 8638, 8638, 8638, -1, 8639, 8639, 8639, -1, + 8640, 8640, 8640, -1, 8641, 8641, 8641, -1, + 8642, 8642, 8642, -1, 8643, 8643, 8643, -1, + 8644, 8644, 8644, -1, 8645, 8645, 8645, -1, + 8646, 8646, 8646, -1, 8647, 8647, 8647, -1, + 8648, 8648, 8648, -1, 8649, 8649, 8649, -1, + 8650, 8650, 8650, -1, 8651, 8651, 8651, -1, + 8652, 8652, 8652, -1, 8653, 8653, 8653, -1, + 8654, 8654, 8654, -1, 8655, 8655, 8655, -1, + 8656, 8656, 8656, -1, 8657, 8657, 8657, -1, + 8658, 8658, 8658, -1, 8659, 8659, 8659, -1, + 8660, 8660, 8660, -1, 8661, 8661, 8661, -1, + 8662, 8662, 8662, -1, 8663, 8663, 8663, -1, + 8664, 8664, 8664, -1, 8665, 8665, 8665, -1, + 8666, 8666, 8666, -1, 8667, 8667, 8667, -1, + 8668, 8668, 8668, -1, 8669, 8669, 8669, -1, + 8670, 8670, 8670, -1, 8671, 8671, 8671, -1, + 8672, 8672, 8672, -1, 8673, 8673, 8673, -1, + 8674, 8674, 8674, -1, 8675, 8675, 8675, -1, + 8676, 8676, 8676, -1, 8677, 8677, 8677, -1, + 8678, 8678, 8678, -1, 8679, 8679, 8679, -1, + 8680, 8680, 8680, -1, 8681, 8681, 8681, -1, + 8682, 8682, 8682, -1, 8683, 8683, 8683, -1, + 8684, 8684, 8684, -1, 8685, 8685, 8685, -1, + 8686, 8686, 8686, -1, 8687, 8687, 8687, -1, + 8688, 8688, 8688, -1, 8689, 8689, 8689, -1, + 8690, 8690, 8690, -1, 8691, 8691, 8691, -1, + 8692, 8692, 8692, -1, 8693, 8693, 8693, -1, + 8694, 8694, 8694, -1, 8695, 8695, 8695, -1, + 8696, 8696, 8696, -1, 8697, 8697, 8697, -1, + 8698, 8698, 8698, -1, 8699, 8699, 8699, -1, + 8700, 8700, 8700, -1, 8701, 8701, 8701, -1, + 8702, 8702, 8702, -1, 8703, 8703, 8703, -1, + 8704, 8704, 8704, -1, 8705, 8705, 8705, -1, + 8706, 8706, 8706, -1, 8707, 8707, 8707, -1, + 8708, 8708, 8708, -1, 8709, 8709, 8709, -1, + 8710, 8710, 8710, -1, 8711, 8711, 8711, -1, + 8712, 8712, 8712, -1, 8713, 8713, 8713, -1, + 8714, 8714, 8714, -1, 8715, 8715, 8715, -1, + 8716, 8716, 8716, -1, 8717, 8717, 8717, -1, + 8718, 8718, 8718, -1, 8719, 8719, 8719, -1, + 8720, 8720, 8720, -1, 8721, 8721, 8721, -1, + 8722, 8722, 8722, -1, 8723, 8723, 8723, -1, + 8724, 8724, 8724, -1, 8725, 8725, 8725, -1, + 8726, 8726, 8726, -1, 8727, 8727, 8727, -1, + 8728, 8728, 8728, -1, 8729, 8729, 8729, -1, + 8730, 8730, 8730, -1, 8731, 8731, 8731, -1, + 8732, 8732, 8732, -1, 8733, 8733, 8733, -1, + 8734, 8734, 8734, -1, 8735, 8735, 8735, -1, + 8736, 8736, 8736, -1, 8737, 8737, 8737, -1, + 8738, 8738, 8738, -1, 8739, 8739, 8739, -1, + 8740, 8740, 8740, -1, 8741, 8741, 8741, -1, + 8742, 8742, 8742, -1, 8743, 8743, 8743, -1, + 8744, 8744, 8744, -1, 8745, 8745, 8745, -1, + 8746, 8746, 8746, -1, 8747, 8747, 8747, -1, + 8748, 8748, 8748, -1, 8749, 8749, 8749, -1, + 8750, 8750, 8750, -1, 8751, 8751, 8751, -1, + 8752, 8752, 8752, -1, 8753, 8753, 8753, -1, + 8754, 8754, 8754, -1, 8755, 8755, 8755, -1, + 8756, 8756, 8756, -1, 8757, 8757, 8757, -1, + 8758, 8758, 8758, -1, 8759, 8759, 8759, -1, + 8760, 8760, 8760, -1, 8761, 8761, 8761, -1, + 8762, 8762, 8762, -1, 8763, 8763, 8763, -1, + 8764, 8764, 8764, -1, 8765, 8765, 8765, -1, + 8766, 8766, 8766, -1, 8767, 8767, 8767, -1, + 8768, 8768, 8768, -1, 8769, 8769, 8769, -1, + 8770, 8770, 8770, -1, 8771, 8771, 8771, -1, + 8772, 8772, 8772, -1, 8773, 8773, 8773, -1, + 8774, 8774, 8774, -1, 8775, 8775, 8775, -1, + 8776, 8776, 8776, -1, 8777, 8777, 8777, -1, + 8778, 8778, 8778, -1, 8779, 8779, 8779, -1, + 8780, 8780, 8780, -1, 8781, 8781, 8781, -1, + 8782, 8782, 8782, -1, 8783, 8783, 8783, -1, + 8784, 8784, 8784, -1, 8785, 8785, 8785, -1, + 8786, 8786, 8786, -1, 8787, 8787, 8787, -1, + 8788, 8788, 8788, -1, 8789, 8789, 8789, -1, + 8790, 8790, 8790, -1, 8791, 8791, 8791, -1, + 8792, 8792, 8792, -1, 8793, 8793, 8793, -1, + 8794, 8794, 8794, -1, 8795, 8795, 8795, -1, + 8796, 8796, 8796, -1, 8797, 8797, 8797, -1, + 8798, 8798, 8798, -1, 8799, 8799, 8799, -1, + 8800, 8800, 8800, -1, 8801, 8801, 8801, -1, + 8802, 8802, 8802, -1, 8803, 8803, 8803, -1, + 8804, 8804, 8804, -1, 8805, 8805, 8805, -1, + 8806, 8806, 8806, -1, 8807, 8807, 8807, -1, + 8808, 8808, 8808, -1, 8809, 8809, 8809, -1, + 8810, 8810, 8810, -1, 8811, 8811, 8811, -1, + 8812, 8812, 8812, -1, 8813, 8813, 8813, -1, + 8814, 8814, 8814, -1, 8815, 8815, 8815, -1, + 8816, 8816, 8816, -1, 8817, 8817, 8817, -1, + 8818, 8818, 8818, -1, 8819, 8819, 8819, -1, + 8820, 8820, 8820, -1, 8821, 8821, 8821, -1, + 8822, 8822, 8822, -1, 8823, 8823, 8823, -1, + 8824, 8824, 8824, -1, 8825, 8825, 8825, -1, + 8826, 8826, 8826, -1, 8827, 8827, 8827, -1, + 8828, 8828, 8828, -1, 8829, 8829, 8829, -1, + 8830, 8830, 8830, -1, 8831, 8831, 8831, -1, + 8832, 8832, 8832, -1, 8833, 8833, 8833, -1, + 8834, 8834, 8834, -1, 8835, 8835, 8835, -1, + 8836, 8836, 8836, -1, 8837, 8837, 8837, -1, + 8838, 8838, 8838, -1, 8839, 8839, 8839, -1, + 8840, 8840, 8840, -1, 8841, 8841, 8841, -1, + 8842, 8842, 8842, -1, 8843, 8843, 8843, -1, + 8844, 8844, 8844, -1, 8845, 8845, 8845, -1, + 8846, 8846, 8846, -1, 8847, 8847, 8847, -1, + 8848, 8848, 8848, -1, 8849, 8849, 8849, -1, + 8850, 8850, 8850, -1, 8851, 8851, 8851, -1, + 8852, 8852, 8852, -1, 8853, 8853, 8853, -1, + 8854, 8854, 8854, -1, 8855, 8855, 8855, -1, + 8856, 8856, 8856, -1, 8857, 8857, 8857, -1, + 8858, 8858, 8858, -1, 8859, 8859, 8859, -1, + 8860, 8860, 8860, -1, 8861, 8861, 8861, -1, + 8862, 8862, 8862, -1, 8863, 8863, 8863, -1, + 8864, 8864, 8864, -1, 8865, 8865, 8865, -1, + 8866, 8866, 8866, -1, 8867, 8867, 8867, -1, + 8868, 8868, 8868, -1, 8869, 8869, 8869, -1, + 8870, 8870, 8870, -1, 8871, 8871, 8871, -1, + 8872, 8872, 8872, -1, 8873, 8873, 8873, -1, + 8874, 8874, 8874, -1, 8875, 8875, 8875, -1, + 8876, 8876, 8876, -1, 8877, 8877, 8877, -1, + 8878, 8878, 8878, -1, 8879, 8879, 8879, -1, + 8880, 8880, 8880, -1, 8881, 8881, 8881, -1, + 8882, 8882, 8882, -1, 8883, 8883, 8883, -1, + 8884, 8884, 8884, -1, 8885, 8885, 8885, -1, + 8886, 8886, 8886, -1, 8887, 8887, 8887, -1, + 8888, 8888, 8888, -1, 8889, 8889, 8889, -1, + 8890, 8890, 8890, -1, 8891, 8891, 8891, -1, + 8892, 8892, 8892, -1, 8893, 8893, 8893, -1, + 8894, 8894, 8894, -1, 8895, 8895, 8895, -1, + 8896, 8896, 8896, -1, 8897, 8897, 8897, -1, + 8898, 8898, 8898, -1, 8899, 8899, 8899, -1, + 8900, 8900, 8900, -1, 8901, 8901, 8901, -1, + 8902, 8902, 8902, -1, 8903, 8903, 8903, -1, + 8904, 8904, 8904, -1, 8905, 8905, 8905, -1, + 8906, 8906, 8906, -1, 8907, 8907, 8907, -1, + 8908, 8908, 8908, -1, 8909, 8909, 8909, -1, + 8910, 8910, 8910, -1, 8911, 8911, 8911, -1, + 8912, 8912, 8912, -1, 8913, 8913, 8913, -1, + 8914, 8914, 8914, -1, 8915, 8915, 8915, -1, + 8916, 8916, 8916, -1, 8917, 8917, 8917, -1, + 8918, 8918, 8918, -1, 8919, 8919, 8919, -1, + 8920, 8920, 8920, -1, 8921, 8921, 8921, -1, + 8922, 8922, 8922, -1, 8923, 8923, 8923, -1, + 8924, 8924, 8924, -1, 8925, 8925, 8925, -1, + 8926, 8926, 8926, -1, 8927, 8927, 8927, -1, + 8928, 8928, 8928, -1, 8929, 8929, 8929, -1, + 8930, 8930, 8930, -1, 8931, 8931, 8931, -1, + 8932, 8932, 8932, -1, 8933, 8933, 8933, -1, + 8934, 8934, 8934, -1, 8935, 8935, 8935, -1, + 8936, 8936, 8936, -1, 8937, 8937, 8937, -1, + 8938, 8938, 8938, -1, 8939, 8939, 8939, -1, + 8940, 8940, 8940, -1, 8941, 8941, 8941, -1, + 8942, 8942, 8942, -1, 8943, 8943, 8943, -1, + 8944, 8944, 8944, -1, 8945, 8945, 8945, -1, + 8946, 8946, 8946, -1, 8947, 8947, 8947, -1, + 8948, 8948, 8948, -1, 8949, 8949, 8949, -1, + 8950, 8950, 8950, -1, 8951, 8951, 8951, -1, + 8952, 8952, 8952, -1, 8953, 8953, 8953, -1, + 8954, 8954, 8954, -1, 8955, 8955, 8955, -1, + 8956, 8956, 8956, -1, 8957, 8957, 8957, -1, + 8958, 8958, 8958, -1, 8959, 8959, 8959, -1, + 8960, 8960, 8960, -1, 8961, 8961, 8961, -1, + 8962, 8962, 8962, -1, 8963, 8963, 8963, -1, + 8964, 8964, 8964, -1, 8965, 8965, 8965, -1, + 8966, 8966, 8966, -1, 8967, 8967, 8967, -1, + 8968, 8968, 8968, -1, 8969, 8969, 8969, -1, + 8970, 8970, 8970, -1, 8971, 8971, 8971, -1, + 8972, 8972, 8972, -1, 8973, 8973, 8973, -1, + 8974, 8974, 8974, -1, 8975, 8975, 8975, -1, + 8976, 8976, 8976, -1, 8977, 8977, 8977, -1, + 8978, 8978, 8978, -1, 8979, 8979, 8979, -1, + 8980, 8980, 8980, -1, 8981, 8981, 8981, -1, + 8982, 8982, 8982, -1, 8983, 8983, 8983, -1, + 8984, 8984, 8984, -1, 8985, 8985, 8985, -1, + 8986, 8986, 8986, -1, 8987, 8987, 8987, -1, + 8988, 8988, 8988, -1, 8989, 8989, 8989, -1, + 8990, 8990, 8990, -1, 8991, 8991, 8991, -1, + 8992, 8992, 8992, -1, 8993, 8993, 8993, -1, + 8994, 8994, 8994, -1, 8995, 8995, 8995, -1, + 8996, 8996, 8996, -1, 8997, 8997, 8997, -1, + 8998, 8998, 8998, -1, 8999, 8999, 8999, -1, + 9000, 9000, 9000, -1, 9001, 9001, 9001, -1, + 9002, 9002, 9002, -1, 9003, 9003, 9003, -1, + 9004, 9004, 9004, -1, 9005, 9005, 9005, -1, + 9006, 9006, 9006, -1, 9007, 9007, 9007, -1, + 9008, 9008, 9008, -1, 9009, 9009, 9009, -1, + 9010, 9010, 9010, -1, 9011, 9011, 9011, -1, + 9012, 9012, 9012, -1, 9013, 9013, 9013, -1, + 9014, 9014, 9014, -1, 9015, 9015, 9015, -1, + 9016, 9016, 9016, -1, 9017, 9017, 9017, -1, + 9018, 9018, 9018, -1, 9019, 9019, 9019, -1, + 9020, 9020, 9020, -1, 9021, 9021, 9021, -1, + 9022, 9022, 9022, -1, 9023, 9023, 9023, -1, + 9024, 9024, 9024, -1, 9025, 9025, 9025, -1, + 9026, 9026, 9026, -1, 9027, 9027, 9027, -1, + 9028, 9028, 9028, -1, 9029, 9029, 9029, -1, + 9030, 9030, 9030, -1, 9031, 9031, 9031, -1, + 9032, 9032, 9032, -1, 9033, 9033, 9033, -1, + 9034, 9034, 9034, -1, 9035, 9035, 9035, -1, + 9036, 9036, 9036, -1, 9037, 9037, 9037, -1, + 9038, 9038, 9038, -1, 9039, 9039, 9039, -1, + 9040, 9040, 9040, -1, 9041, 9041, 9041, -1, + 9042, 9042, 9042, -1, 9043, 9043, 9043, -1, + 9044, 9044, 9044, -1, 9045, 9045, 9045, -1, + 9046, 9046, 9046, -1, 9047, 9047, 9047, -1, + 9048, 9048, 9048, -1, 9049, 9049, 9049, -1, + 9050, 9050, 9050, -1, 9051, 9051, 9051, -1, + 9052, 9052, 9052, -1, 9053, 9053, 9053, -1, + 9054, 9054, 9054, -1, 9055, 9055, 9055, -1, + 9056, 9056, 9056, -1, 9057, 9057, 9057, -1, + 9058, 9058, 9058, -1, 9059, 9059, 9059, -1, + 9060, 9060, 9060, -1, 9061, 9061, 9061, -1, + 9062, 9062, 9062, -1, 9063, 9063, 9063, -1, + 9064, 9064, 9064, -1, 9065, 9065, 9065, -1, + 9066, 9066, 9066, -1, 9067, 9067, 9067, -1, + 9068, 9068, 9068, -1, 9069, 9069, 9069, -1, + 9070, 9070, 9070, -1, 9071, 9071, 9071, -1, + 9072, 9072, 9072, -1, 9073, 9073, 9073, -1, + 9074, 9074, 9074, -1, 9075, 9075, 9075, -1, + 9076, 9076, 9076, -1, 9077, 9077, 9077, -1, + 9078, 9078, 9078, -1, 9079, 9079, 9079, -1, + 9080, 9080, 9080, -1, 9081, 9081, 9081, -1, + 9082, 9082, 9082, -1, 9083, 9083, 9083, -1, + 9084, 9084, 9084, -1, 9085, 9085, 9085, -1, + 9086, 9086, 9086, -1, 9087, 9087, 9087, -1, + 9088, 9088, 9088, -1, 9089, 9089, 9089, -1, + 9090, 9090, 9090, -1, 9091, 9091, 9091, -1, + 9092, 9092, 9092, -1, 9093, 9093, 9093, -1, + 9094, 9094, 9094, -1, 9095, 9095, 9095, -1, + 9096, 9096, 9096, -1, 9097, 9097, 9097, -1, + 9098, 9098, 9098, -1, 9099, 9099, 9099, -1, + 9100, 9100, 9100, -1, 9101, 9101, 9101, -1, + 9102, 9102, 9102, -1, 9103, 9103, 9103, -1, + 9104, 9104, 9104, -1, 9105, 9105, 9105, -1, + 9106, 9106, 9106, -1, 9107, 9107, 9107, -1, + 9108, 9108, 9108, -1, 9109, 9109, 9109, -1, + 9110, 9110, 9110, -1, 9111, 9111, 9111, -1, + 9112, 9112, 9112, -1, 9113, 9113, 9113, -1, + 9114, 9114, 9114, -1, 9115, 9115, 9115, -1, + 9116, 9116, 9116, -1, 9117, 9117, 9117, -1, + 9118, 9118, 9118, -1, 9119, 9119, 9119, -1, + 9120, 9120, 9120, -1, 9121, 9121, 9121, -1, + 9122, 9122, 9122, -1, 9123, 9123, 9123, -1, + 9124, 9124, 9124, -1, 9125, 9125, 9125, -1, + 9126, 9126, 9126, -1, 9127, 9127, 9127, -1, + 9128, 9128, 9128, -1, 9129, 9129, 9129, -1, + 9130, 9130, 9130, -1, 9131, 9131, 9131, -1, + 9132, 9132, 9132, -1, 9133, 9133, 9133, -1, + 9134, 9134, 9134, -1, 9135, 9135, 9135, -1, + 9136, 9136, 9136, -1, 9137, 9137, 9137, -1, + 9138, 9138, 9138, -1, 9139, 9139, 9139, -1, + 9140, 9140, 9140, -1, 9141, 9141, 9141, -1, + 9142, 9142, 9142, -1, 9143, 9143, 9143, -1, + 9144, 9144, 9144, -1, 9145, 9145, 9145, -1, + 9146, 9146, 9146, -1, 9147, 9147, 9147, -1, + 9148, 9148, 9148, -1, 9149, 9149, 9149, -1, + 9150, 9150, 9150, -1, 9151, 9151, 9151, -1, + 9152, 9152, 9152, -1, 9153, 9153, 9153, -1, + 9154, 9154, 9154, -1, 9155, 9155, 9155, -1, + 9156, 9156, 9156, -1, 9157, 9157, 9157, -1, + 9158, 9158, 9158, -1, 9159, 9159, 9159, -1, + 9160, 9160, 9160, -1, 9161, 9161, 9161, -1, + 9162, 9162, 9162, -1, 9163, 9163, 9163, -1, + 9164, 9164, 9164, -1, 9165, 9165, 9165, -1, + 9166, 9166, 9166, -1, 9167, 9167, 9167, -1, + 9168, 9168, 9168, -1, 9169, 9169, 9169, -1, + 9170, 9170, 9170, -1, 9171, 9171, 9171, -1, + 9172, 9172, 9172, -1, 9173, 9173, 9173, -1, + 9174, 9174, 9174, -1, 9175, 9175, 9175, -1, + 9176, 9176, 9176, -1, 9177, 9177, 9177, -1, + 9178, 9178, 9178, -1, 9179, 9179, 9179, -1, + 9180, 9180, 9180, -1, 9181, 9181, 9181, -1, + 9182, 9182, 9182, -1, 9183, 9183, 9183, -1, + 9184, 9184, 9184, -1, 9185, 9185, 9185, -1, + 9186, 9186, 9186, -1, 9187, 9187, 9187, -1, + 9188, 9188, 9188, -1, 9189, 9189, 9189, -1, + 9190, 9190, 9190, -1, 9191, 9191, 9191, -1, + 9192, 9192, 9192, -1, 9193, 9193, 9193, -1, + 9194, 9194, 9194, -1, 9195, 9195, 9195, -1, + 9196, 9196, 9196, -1, 9197, 9197, 9197, -1, + 9198, 9198, 9198, -1, 9199, 9199, 9199, -1, + 9200, 9200, 9200, -1, 9201, 9201, 9201, -1, + 9202, 9202, 9202, -1, 9203, 9203, 9203, -1, + 9204, 9204, 9204, -1, 9205, 9205, 9205, -1, + 9206, 9206, 9206, -1, 9207, 9207, 9207, -1, + 9208, 9208, 9208, -1, 9209, 9209, 9209, -1, + 9210, 9210, 9210, -1, 9211, 9211, 9211, -1, + 9212, 9212, 9212, -1, 9213, 9213, 9213, -1, + 9214, 9214, 9214, -1, 9215, 9215, 9215, -1, + 9216, 9216, 9216, -1, 9217, 9217, 9217, -1, + 9218, 9218, 9218, -1, 9219, 9219, 9219, -1, + 9220, 9220, 9220, -1, 9221, 9221, 9221, -1, + 9222, 9222, 9222, -1, 9223, 9223, 9223, -1, + 9224, 9224, 9224, -1, 9225, 9225, 9225, -1, + 9226, 9226, 9226, -1, 9227, 9227, 9227, -1, + 9228, 9228, 9228, -1, 9229, 9229, 9229, -1, + 9230, 9230, 9230, -1, 9231, 9231, 9231, -1, + 9232, 9232, 9232, -1, 9233, 9233, 9233, -1, + 9234, 9234, 9234, -1, 9235, 9235, 9235, -1, + 9236, 9236, 9236, -1, 9237, 9237, 9237, -1, + 9238, 9238, 9238, -1, 9239, 9239, 9239, -1, + 9240, 9240, 9240, -1, 9241, 9241, 9241, -1, + 9242, 9242, 9242, -1, 9243, 9243, 9243, -1, + 9244, 9244, 9244, -1, 9245, 9245, 9245, -1, + 9246, 9246, 9246, -1, 9247, 9247, 9247, -1, + 9248, 9248, 9248, -1, 9249, 9249, 9249, -1, + 9250, 9250, 9250, -1, 9251, 9251, 9251, -1, + 9252, 9252, 9252, -1, 9253, 9253, 9253, -1, + 9254, 9254, 9254, -1, 9255, 9255, 9255, -1, + 9256, 9256, 9256, -1, 9257, 9257, 9257, -1, + 9258, 9258, 9258, -1, 9259, 9259, 9259, -1, + 9260, 9260, 9260, -1, 9261, 9261, 9261, -1, + 9262, 9262, 9262, -1, 9263, 9263, 9263, -1, + 9264, 9264, 9264, -1, 9265, 9265, 9265, -1, + 9266, 9266, 9266, -1, 9267, 9267, 9267, -1, + 9268, 9268, 9268, -1, 9269, 9269, 9269, -1, + 9270, 9270, 9270, -1, 9271, 9271, 9271, -1, + 9272, 9272, 9272, -1, 9273, 9273, 9273, -1, + 9274, 9274, 9274, -1, 9275, 9275, 9275, -1, + 9276, 9276, 9276, -1, 9277, 9277, 9277, -1, + 9278, 9278, 9278, -1, 9279, 9279, 9279, -1, + 9280, 9280, 9280, -1, 9281, 9281, 9281, -1, + 9282, 9282, 9282, -1, 9283, 9283, 9283, -1, + 9284, 9284, 9284, -1, 9285, 9285, 9285, -1, + 9286, 9286, 9286, -1, 9287, 9287, 9287, -1, + 9288, 9288, 9288, -1, 9289, 9289, 9289, -1, + 9290, 9290, 9290, -1, 9291, 9291, 9291, -1, + 9292, 9292, 9292, -1, 9293, 9293, 9293, -1, + 9294, 9294, 9294, -1, 9295, 9295, 9295, -1, + 9296, 9296, 9296, -1, 9297, 9297, 9297, -1, + 9298, 9298, 9298, -1, 9299, 9299, 9299, -1, + 9300, 9300, 9300, -1, 9301, 9301, 9301, -1, + 9302, 9302, 9302, -1, 9303, 9303, 9303, -1, + 9304, 9304, 9304, -1, 9305, 9305, 9305, -1, + 9306, 9306, 9306, -1, 9307, 9307, 9307, -1, + 9308, 9308, 9308, -1, 9309, 9309, 9309, -1, + 9310, 9310, 9310, -1, 9311, 9311, 9311, -1, + 9312, 9312, 9312, -1, 9313, 9313, 9313, -1, + 9314, 9314, 9314, -1, 9315, 9315, 9315, -1, + 9316, 9316, 9316, -1, 9317, 9317, 9317, -1, + 9318, 9318, 9318, -1, 9319, 9319, 9319, -1, + 9320, 9320, 9320, -1, 9321, 9321, 9321, -1, + 9322, 9322, 9322, -1, 9323, 9323, 9323, -1, + 9324, 9324, 9324, -1, 9325, 9325, 9325, -1, + 9326, 9326, 9326, -1, 9327, 9327, 9327, -1, + 9328, 9328, 9328, -1, 9329, 9329, 9329, -1, + 9330, 9330, 9330, -1, 9331, 9331, 9331, -1, + 9332, 9332, 9332, -1, 9333, 9333, 9333, -1, + 9334, 9334, 9334, -1, 9335, 9335, 9335, -1, + 9336, 9336, 9336, -1, 9337, 9337, 9337, -1, + 9338, 9338, 9338, -1, 9339, 9339, 9339, -1, + 9340, 9340, 9340, -1, 9341, 9341, 9341, -1, + 9342, 9342, 9342, -1, 9343, 9343, 9343, -1, + 9344, 9344, 9344, -1, 9345, 9345, 9345, -1, + 9346, 9346, 9346, -1, 9347, 9347, 9347, -1, + 9348, 9348, 9348, -1, 9349, 9349, 9349, -1, + 9350, 9350, 9350, -1, 9351, 9351, 9351, -1, + 9352, 9352, 9352, -1, 9353, 9353, 9353, -1, + 9354, 9354, 9354, -1, 9355, 9355, 9355, -1, + 9356, 9356, 9356, -1, 9357, 9357, 9357, -1, + 9358, 9358, 9358, -1, 9359, 9359, 9359, -1, + 9360, 9360, 9360, -1, 9361, 9361, 9361, -1, + 9362, 9362, 9362, -1, 9363, 9363, 9363, -1, + 9364, 9364, 9364, -1, 9365, 9365, 9365, -1, + 9366, 9366, 9366, -1, 9367, 9367, 9367, -1, + 9368, 9368, 9368, -1, 9369, 9369, 9369, -1, + 9370, 9370, 9370, -1, 9371, 9371, 9371, -1, + 9372, 9372, 9372, -1, 9373, 9373, 9373, -1, + 9374, 9374, 9374, -1, 9375, 9375, 9375, -1, + 9376, 9376, 9376, -1, 9377, 9377, 9377, -1, + 9378, 9378, 9378, -1, 9379, 9379, 9379, -1, + 9380, 9380, 9380, -1, 9381, 9381, 9381, -1, + 9382, 9382, 9382, -1, 9383, 9383, 9383, -1, + 9384, 9384, 9384, -1, 9385, 9385, 9385, -1, + 9386, 9386, 9386, -1, 9387, 9387, 9387, -1, + 9388, 9388, 9388, -1, 9389, 9389, 9389, -1, + 9390, 9390, 9390, -1, 9391, 9391, 9391, -1, + 9392, 9392, 9392, -1, 9393, 9393, 9393, -1, + 9394, 9394, 9394, -1, 9395, 9395, 9395, -1, + 9396, 9396, 9396, -1, 9397, 9397, 9397, -1, + 9398, 9398, 9398, -1, 9399, 9399, 9399, -1, + 9400, 9400, 9400, -1, 9401, 9401, 9401, -1, + 9402, 9402, 9402, -1, 9403, 9403, 9403, -1, + 9404, 9404, 9404, -1, 9405, 9405, 9405, -1, + 9406, 9406, 9406, -1, 9407, 9407, 9407, -1, + 9408, 9408, 9408, -1, 9409, 9409, 9409, -1, + 9410, 9410, 9410, -1, 9411, 9411, 9411, -1, + 9412, 9412, 9412, -1, 9413, 9413, 9413, -1, + 9414, 9414, 9414, -1, 9415, 9415, 9415, -1, + 9416, 9416, 9416, -1, 9417, 9417, 9417, -1, + 9418, 9418, 9418, -1, 9419, 9419, 9419, -1, + 9420, 9420, 9420, -1, 9421, 9421, 9421, -1, + 9422, 9422, 9422, -1, 9423, 9423, 9423, -1, + 9424, 9424, 9424, -1, 9425, 9425, 9425, -1, + 9426, 9426, 9426, -1, 9427, 9427, 9427, -1, + 9428, 9428, 9428, -1, 9429, 9429, 9429, -1, + 9430, 9430, 9430, -1, 9431, 9431, 9431, -1, + 9432, 9432, 9432, -1, 9433, 9433, 9433, -1, + 9434, 9434, 9434, -1, 9435, 9435, 9435, -1, + 9436, 9436, 9436, -1, 9437, 9437, 9437, -1, + 9438, 9438, 9438, -1, 9439, 9439, 9439, -1, + 9440, 9440, 9440, -1, 9441, 9441, 9441, -1, + 9442, 9442, 9442, -1, 9443, 9443, 9443, -1, + 9444, 9444, 9444, -1, 9445, 9445, 9445, -1, + 9446, 9446, 9446, -1, 9447, 9447, 9447, -1, + 9448, 9448, 9448, -1, 9449, 9449, 9449, -1, + 9450, 9450, 9450, -1, 9451, 9451, 9451, -1, + 9452, 9452, 9452, -1, 9453, 9453, 9453, -1, + 9454, 9454, 9454, -1, 9455, 9455, 9455, -1, + 9456, 9456, 9456, -1, 9457, 9457, 9457, -1, + 9458, 9458, 9458, -1, 9459, 9459, 9459, -1, + 9460, 9460, 9460, -1, 9461, 9461, 9461, -1, + 9462, 9462, 9462, -1, 9463, 9463, 9463, -1, + 9464, 9464, 9464, -1, 9465, 9465, 9465, -1, + 9466, 9466, 9466, -1, 9467, 9467, 9467, -1, + 9468, 9468, 9468, -1, 9469, 9469, 9469, -1, + 9470, 9470, 9470, -1, 9471, 9471, 9471, -1, + 9472, 9472, 9472, -1, 9473, 9473, 9473, -1, + 9474, 9474, 9474, -1, 9475, 9475, 9475, -1, + 9476, 9476, 9476, -1, 9477, 9477, 9477, -1, + 9478, 9478, 9478, -1, 9479, 9479, 9479, -1, + 9480, 9480, 9480, -1, 9481, 9481, 9481, -1, + 9482, 9482, 9482, -1, 9483, 9483, 9483, -1, + 9484, 9484, 9484, -1, 9485, 9485, 9485, -1, + 9486, 9486, 9486, -1, 9487, 9487, 9487, -1, + 9488, 9488, 9488, -1, 9489, 9489, 9489, -1, + 9490, 9490, 9490, -1, 9491, 9491, 9491, -1, + 9492, 9492, 9492, -1, 9493, 9493, 9493, -1, + 9494, 9494, 9494, -1, 9495, 9495, 9495, -1, + 9496, 9496, 9496, -1, 9497, 9497, 9497, -1, + 9498, 9498, 9498, -1, 9499, 9499, 9499, -1, + 9500, 9500, 9500, -1, 9501, 9501, 9501, -1, + 9502, 9502, 9502, -1, 9503, 9503, 9503, -1, + 9504, 9504, 9504, -1, 9505, 9505, 9505, -1, + 9506, 9506, 9506, -1, 9507, 9507, 9507, -1, + 9508, 9508, 9508, -1, 9509, 9509, 9509, -1, + 9510, 9510, 9510, -1, 9511, 9511, 9511, -1, + 9512, 9512, 9512, -1, 9513, 9513, 9513, -1, + 9514, 9514, 9514, -1, 9515, 9515, 9515, -1, + 9516, 9516, 9516, -1, 9517, 9517, 9517, -1, + 9518, 9518, 9518, -1, 9519, 9519, 9519, -1, + 9520, 9520, 9520, -1, 9521, 9521, 9521, -1, + 9522, 9522, 9522, -1, 9523, 9523, 9523, -1, + 9524, 9524, 9524, -1, 9525, 9525, 9525, -1, + 9526, 9526, 9526, -1, 9527, 9527, 9527, -1, + 9528, 9528, 9528, -1, 9529, 9529, 9529, -1, + 9530, 9530, 9530, -1, 9531, 9531, 9531, -1, + 9532, 9532, 9532, -1, 9533, 9533, 9533, -1, + 9534, 9534, 9534, -1, 9535, 9535, 9535, -1, + 9536, 9536, 9536, -1, 9537, 9537, 9537, -1, + 9538, 9538, 9538, -1, 9539, 9539, 9539, -1, + 9540, 9540, 9540, -1, 9541, 9541, 9541, -1, + 9542, 9542, 9542, -1, 9543, 9543, 9543, -1, + 9544, 9544, 9544, -1, 9545, 9545, 9545, -1, + 9546, 9546, 9546, -1, 9547, 9547, 9547, -1, + 9548, 9548, 9548, -1, 9549, 9549, 9549, -1, + 9550, 9550, 9550, -1, 9551, 9551, 9551, -1, + 9552, 9552, 9552, -1, 9553, 9553, 9553, -1, + 9554, 9554, 9554, -1, 9555, 9555, 9555, -1, + 9556, 9556, 9556, -1, 9557, 9557, 9557, -1, + 9558, 9558, 9558, -1, 9559, 9559, 9559, -1, + 9560, 9560, 9560, -1, 9561, 9561, 9561, -1, + 9562, 9562, 9562, -1, 9563, 9563, 9563, -1, + 9564, 9564, 9564, -1, 9565, 9565, 9565, -1, + 9566, 9566, 9566, -1, 9567, 9567, 9567, -1, + 9568, 9568, 9568, -1, 9569, 9569, 9569, -1, + 9570, 9570, 9570, -1, 9571, 9571, 9571, -1, + 9572, 9572, 9572, -1, 9573, 9573, 9573, -1, + 9574, 9574, 9574, -1, 9575, 9575, 9575, -1, + 9576, 9576, 9576, -1, 9577, 9577, 9577, -1, + 9578, 9578, 9578, -1, 9579, 9579, 9579, -1, + 9580, 9580, 9580, -1, 9581, 9581, 9581, -1, + 9582, 9582, 9582, -1, 9583, 9583, 9583, -1, + 9584, 9584, 9584, -1, 9585, 9585, 9585, -1, + 9586, 9586, 9586, -1, 9587, 9587, 9587, -1, + 9588, 9588, 9588, -1, 9589, 9589, 9589, -1, + 9590, 9590, 9590, -1, 9591, 9591, 9591, -1, + 9592, 9592, 9592, -1, 9593, 9593, 9593, -1, + 9594, 9594, 9594, -1, 9595, 9595, 9595, -1, + 9596, 9596, 9596, -1, 9597, 9597, 9597, -1, + 9598, 9598, 9598, -1, 9599, 9599, 9599, -1, + 9600, 9600, 9600, -1, 9601, 9601, 9601, -1, + 9602, 9602, 9602, -1, 9603, 9603, 9603, -1, + 9604, 9604, 9604, -1, 9605, 9605, 9605, -1, + 9606, 9606, 9606, -1, 9607, 9607, 9607, -1, + 9608, 9608, 9608, -1, 9609, 9609, 9609, -1, + 9610, 9610, 9610, -1, 9611, 9611, 9611, -1, + 9612, 9612, 9612, -1, 9613, 9613, 9613, -1, + 9614, 9614, 9614, -1, 9615, 9615, 9615, -1, + 9616, 9616, 9616, -1, 9617, 9617, 9617, -1, + 9618, 9618, 9618, -1, 9619, 9619, 9619, -1, + 9620, 9620, 9620, -1, 9621, 9621, 9621, -1, + 9622, 9622, 9622, -1, 9623, 9623, 9623, -1, + 9624, 9624, 9624, -1, 9625, 9625, 9625, -1, + 9626, 9626, 9626, -1, 9627, 9627, 9627, -1, + 9628, 9628, 9628, -1, 9629, 9629, 9629, -1, + 9630, 9630, 9630, -1, 9631, 9631, 9631, -1, + 9632, 9632, 9632, -1, 9633, 9633, 9633, -1, + 9634, 9634, 9634, -1, 9635, 9635, 9635, -1, + 9636, 9636, 9636, -1, 9637, 9637, 9637, -1, + 9638, 9638, 9638, -1, 9639, 9639, 9639, -1, + 9640, 9640, 9640, -1, 9641, 9641, 9641, -1, + 9642, 9642, 9642, -1, 9643, 9643, 9643, -1, + 9644, 9644, 9644, -1, 9645, 9645, 9645, -1, + 9646, 9646, 9646, -1, 9647, 9647, 9647, -1, + 9648, 9648, 9648, -1, 9649, 9649, 9649, -1, + 9650, 9650, 9650, -1, 9651, 9651, 9651, -1, + 9652, 9652, 9652, -1, 9653, 9653, 9653, -1, + 9654, 9654, 9654, -1, 9655, 9655, 9655, -1, + 9656, 9656, 9656, -1, 9657, 9657, 9657, -1, + 9658, 9658, 9658, -1, 9659, 9659, 9659, -1, + 9660, 9660, 9660, -1, 9661, 9661, 9661, -1, + 9662, 9662, 9662, -1, 9663, 9663, 9663, -1, + 9664, 9664, 9664, -1, 9665, 9665, 9665, -1, + 9666, 9666, 9666, -1, 9667, 9667, 9667, -1, + 9668, 9668, 9668, -1, 9669, 9669, 9669, -1, + 9670, 9670, 9670, -1, 9671, 9671, 9671, -1, + 9672, 9672, 9672, -1, 9673, 9673, 9673, -1, + 9674, 9674, 9674, -1, 9675, 9675, 9675, -1, + 9676, 9676, 9676, -1, 9677, 9677, 9677, -1, + 9678, 9678, 9678, -1, 9679, 9679, 9679, -1, + 9680, 9680, 9680, -1, 9681, 9681, 9681, -1, + 9682, 9682, 9682, -1, 9683, 9683, 9683, -1, + 9684, 9684, 9684, -1, 9685, 9685, 9685, -1, + 9686, 9686, 9686, -1, 9687, 9687, 9687, -1, + 9688, 9688, 9688, -1, 9689, 9689, 9689, -1, + 9690, 9690, 9690, -1, 9691, 9691, 9691, -1, + 9692, 9692, 9692, -1, 9693, 9693, 9693, -1, + 9694, 9694, 9694, -1, 9695, 9695, 9695, -1, + 9696, 9696, 9696, -1, 9697, 9697, 9697, -1, + 9698, 9698, 9698, -1, 9699, 9699, 9699, -1, + 9700, 9700, 9700, -1, 9701, 9701, 9701, -1, + 9702, 9702, 9702, -1, 9703, 9703, 9703, -1, + 9704, 9704, 9704, -1, 9705, 9705, 9705, -1, + 9706, 9706, 9706, -1, 9707, 9707, 9707, -1, + 9708, 9708, 9708, -1, 9709, 9709, 9709, -1, + 9710, 9710, 9710, -1, 9711, 9711, 9711, -1, + 9712, 9712, 9712, -1, 9713, 9713, 9713, -1, + 9714, 9714, 9714, -1, 9715, 9715, 9715, -1, + 9716, 9716, 9716, -1, 9717, 9717, 9717, -1, + 9718, 9718, 9718, -1, 9719, 9719, 9719, -1, + 9720, 9720, 9720, -1, 9721, 9721, 9721, -1, + 9722, 9722, 9722, -1, 9723, 9723, 9723, -1, + 9724, 9724, 9724, -1, 9725, 9725, 9725, -1, + 9726, 9726, 9726, -1, 9727, 9727, 9727, -1, + 9728, 9728, 9728, -1, 9729, 9729, 9729, -1, + 9730, 9730, 9730, -1, 9731, 9731, 9731, -1, + 9732, 9732, 9732, -1, 9733, 9733, 9733, -1, + 9734, 9734, 9734, -1, 9735, 9735, 9735, -1, + 9736, 9736, 9736, -1, 9737, 9737, 9737, -1, + 9738, 9738, 9738, -1, 9739, 9739, 9739, -1, + 9740, 9740, 9740, -1, 9741, 9741, 9741, -1, + 9742, 9742, 9742, -1, 9743, 9743, 9743, -1, + 9744, 9744, 9744, -1, 9745, 9745, 9745, -1, + 9746, 9746, 9746, -1, 9747, 9747, 9747, -1, + 9748, 9748, 9748, -1, 9749, 9749, 9749, -1, + 9750, 9750, 9750, -1, 9751, 9751, 9751, -1, + 9752, 9752, 9752, -1, 9753, 9753, 9753, -1, + 9754, 9754, 9754, -1, 9755, 9755, 9755, -1, + 9756, 9756, 9756, -1, 9757, 9757, 9757, -1, + 9758, 9758, 9758, -1, 9759, 9759, 9759, -1, + 9760, 9760, 9760, -1, 9761, 9761, 9761, -1, + 9762, 9762, 9762, -1, 9763, 9763, 9763, -1, + 9764, 9764, 9764, -1, 9765, 9765, 9765, -1, + 9766, 9766, 9766, -1, 9767, 9767, 9767, -1, + 9768, 9768, 9768, -1, 9769, 9769, 9769, -1, + 9770, 9770, 9770, -1, 9771, 9771, 9771, -1, + 9772, 9772, 9772, -1, 9773, 9773, 9773, -1, + 9774, 9774, 9774, -1, 9775, 9775, 9775, -1, + 9776, 9776, 9776, -1, 9777, 9777, 9777, -1, + 9778, 9778, 9778, -1, 9779, 9779, 9779, -1, + 9780, 9780, 9780, -1, 9781, 9781, 9781, -1, + 9782, 9782, 9782, -1, 9783, 9783, 9783, -1, + 9784, 9784, 9784, -1, 9785, 9785, 9785, -1, + 9786, 9786, 9786, -1, 9787, 9787, 9787, -1, + 9788, 9788, 9788, -1, 9789, 9789, 9789, -1, + 9790, 9790, 9790, -1, 9791, 9791, 9791, -1, + 9792, 9792, 9792, -1, 9793, 9793, 9793, -1, + 9794, 9794, 9794, -1, 9795, 9795, 9795, -1, + 9796, 9796, 9796, -1, 9797, 9797, 9797, -1, + 9798, 9798, 9798, -1, 9799, 9799, 9799, -1, + 9800, 9800, 9800, -1, 9801, 9801, 9801, -1, + 9802, 9802, 9802, -1, 9803, 9803, 9803, -1, + 9804, 9804, 9804, -1, 9805, 9805, 9805, -1, + 9806, 9806, 9806, -1, 9807, 9807, 9807, -1, + 9808, 9808, 9808, -1, 9809, 9809, 9809, -1, + 9810, 9810, 9810, -1, 9811, 9811, 9811, -1, + 9812, 9812, 9812, -1, 9813, 9813, 9813, -1, + 9814, 9814, 9814, -1, 9815, 9815, 9815, -1, + 9816, 9816, 9816, -1, 9817, 9817, 9817, -1, + 9818, 9818, 9818, -1, 9819, 9819, 9819, -1, + 9820, 9820, 9820, -1, 9821, 9821, 9821, -1, + 9822, 9822, 9822, -1, 9823, 9823, 9823, -1, + 9824, 9824, 9824, -1, 9825, 9825, 9825, -1, + 9826, 9826, 9826, -1, 9827, 9827, 9827, -1, + 9828, 9828, 9828, -1, 9829, 9829, 9829, -1, + 9830, 9830, 9830, -1, 9831, 9831, 9831, -1, + 9832, 9832, 9832, -1, 9833, 9833, 9833, -1, + 9834, 9834, 9834, -1, 9835, 9835, 9835, -1, + 9836, 9836, 9836, -1, 9837, 9837, 9837, -1, + 9838, 9838, 9838, -1, 9839, 9839, 9839, -1, + 9840, 9840, 9840, -1, 9841, 9841, 9841, -1, + 9842, 9842, 9842, -1, 9843, 9843, 9843, -1, + 9844, 9844, 9844, -1, 9845, 9845, 9845, -1, + 9846, 9846, 9846, -1, 9847, 9847, 9847, -1, + 9848, 9848, 9848, -1, 9849, 9849, 9849, -1, + 9850, 9850, 9850, -1, 9851, 9851, 9851, -1, + 9852, 9852, 9852, -1, 9853, 9853, 9853, -1, + 9854, 9854, 9854, -1, 9855, 9855, 9855, -1, + 9856, 9856, 9856, -1, 9857, 9857, 9857, -1, + 9858, 9858, 9858, -1, 9859, 9859, 9859, -1, + 9860, 9860, 9860, -1, 9861, 9861, 9861, -1, + 9862, 9862, 9862, -1, 9863, 9863, 9863, -1, + 9864, 9864, 9864, -1, 9865, 9865, 9865, -1, + 9866, 9866, 9866, -1, 9867, 9867, 9867, -1, + 9868, 9868, 9868, -1, 9869, 9869, 9869, -1, + 9870, 9870, 9870, -1, 9871, 9871, 9871, -1, + 9872, 9872, 9872, -1, 9873, 9873, 9873, -1, + 9874, 9874, 9874, -1, 9875, 9875, 9875, -1, + 9876, 9876, 9876, -1, 9877, 9877, 9877, -1, + 9878, 9878, 9878, -1, 9879, 9879, 9879, -1, + 9880, 9880, 9880, -1, 9881, 9881, 9881, -1, + 9882, 9882, 9882, -1, 9883, 9883, 9883, -1, + 9884, 9884, 9884, -1, 9885, 9885, 9885, -1, + 9886, 9886, 9886, -1, 9887, 9887, 9887, -1, + 9888, 9888, 9888, -1, 9889, 9889, 9889, -1, + 9890, 9890, 9890, -1, 9891, 9891, 9891, -1, + 9892, 9892, 9892, -1, 9893, 9893, 9893, -1, + 9894, 9894, 9894, -1, 9895, 9895, 9895, -1, + 9896, 9896, 9896, -1, 9897, 9897, 9897, -1, + 9898, 9898, 9898, -1, 9899, 9899, 9899, -1, + 9900, 9900, 9900, -1, 9901, 9901, 9901, -1, + 9902, 9902, 9902, -1, 9903, 9903, 9903, -1, + 9904, 9904, 9904, -1, 9905, 9905, 9905, -1, + 9906, 9906, 9906, -1, 9907, 9907, 9907, -1, + 9908, 9908, 9908, -1, 9909, 9909, 9909, -1, + 9910, 9910, 9910, -1, 9911, 9911, 9911, -1, + 9912, 9912, 9912, -1, 9913, 9913, 9913, -1, + 9914, 9914, 9914, -1, 9915, 9915, 9915, -1, + 9916, 9916, 9916, -1, 9917, 9917, 9917, -1, + 9918, 9918, 9918, -1, 9919, 9919, 9919, -1, + 9920, 9920, 9920, -1, 9921, 9921, 9921, -1, + 9922, 9922, 9922, -1, 9923, 9923, 9923, -1, + 9924, 9924, 9924, -1, 9925, 9925, 9925, -1, + 9926, 9926, 9926, -1, 9927, 9927, 9927, -1, + 9928, 9928, 9928, -1, 9929, 9929, 9929, -1, + 9930, 9930, 9930, -1, 9931, 9931, 9931, -1, + 9932, 9932, 9932, -1, 9933, 9933, 9933, -1, + 9934, 9934, 9934, -1, 9935, 9935, 9935, -1, + 9936, 9936, 9936, -1, 9937, 9937, 9937, -1, + 9938, 9938, 9938, -1, 9939, 9939, 9939, -1, + 9940, 9940, 9940, -1, 9941, 9941, 9941, -1, + 9942, 9942, 9942, -1, 9943, 9943, 9943, -1, + 9944, 9944, 9944, -1, 9945, 9945, 9945, -1, + 9946, 9946, 9946, -1, 9947, 9947, 9947, -1, + 9948, 9948, 9948, -1, 9949, 9949, 9949, -1, + 9950, 9950, 9950, -1, 9951, 9951, 9951, -1, + 9952, 9952, 9952, -1, 9953, 9953, 9953, -1, + 9954, 9954, 9954, -1, 9955, 9955, 9955, -1, + 9956, 9956, 9956, -1, 9957, 9957, 9957, -1, + 9958, 9958, 9958, -1, 9959, 9959, 9959, -1, + 9960, 9960, 9960, -1, 9961, 9961, 9961, -1, + 9962, 9962, 9962, -1, 9963, 9963, 9963, -1, + 9964, 9964, 9964, -1, 9965, 9965, 9965, -1, + 9966, 9966, 9966, -1, 9967, 9967, 9967, -1, + 9968, 9968, 9968, -1, 9969, 9969, 9969, -1, + 9970, 9970, 9970, -1, 9971, 9971, 9971, -1, + 9972, 9972, 9972, -1, 9973, 9973, 9973, -1, + 9974, 9974, 9974, -1, 9975, 9975, 9975, -1, + 9976, 9976, 9976, -1, 9977, 9977, 9977, -1, + 9978, 9978, 9978, -1, 9979, 9979, 9979, -1, + 9980, 9980, 9980, -1, 9981, 9981, 9981, -1, + 9982, 9982, 9982, -1, 9983, 9983, 9983, -1, + 9984, 9984, 9984, -1, 9985, 9985, 9985, -1, + 9986, 9986, 9986, -1, 9987, 9987, 9987, -1, + 9988, 9988, 9988, -1, 9989, 9989, 9989, -1, + 9990, 9990, 9990, -1, 9991, 9991, 9991, -1, + 9992, 9992, 9992, -1, 9993, 9993, 9993, -1, + 9994, 9994, 9994, -1, 9995, 9995, 9995, -1, + 9996, 9996, 9996, -1, 9997, 9997, 9997, -1, + 9998, 9998, 9998, -1, 9999, 9999, 9999, -1, + 10000, 10000, 10000, -1, 10001, 10001, 10001, -1, + 10002, 10002, 10002, -1, 10003, 10003, 10003, -1, + 10004, 10004, 10004, -1, 10005, 10005, 10005, -1, + 10006, 10006, 10006, -1, 10007, 10007, 10007, -1, + 10008, 10008, 10008, -1, 10009, 10009, 10009, -1, + 10010, 10010, 10010, -1, 10011, 10011, 10011, -1, + 10012, 10012, 10012, -1, 10013, 10013, 10013, -1, + 10014, 10014, 10014, -1, 10015, 10015, 10015, -1, + 10016, 10016, 10016, -1, 10017, 10017, 10017, -1, + 10018, 10018, 10018, -1, 10019, 10019, 10019, -1, + 10020, 10020, 10020, -1, 10021, 10021, 10021, -1, + 10022, 10022, 10022, -1, 10023, 10023, 10023, -1, + 10024, 10024, 10024, -1, 10025, 10025, 10025, -1, + 10026, 10026, 10026, -1, 10027, 10027, 10027, -1, + 10028, 10028, 10028, -1, 10029, 10029, 10029, -1, + 10030, 10030, 10030, -1, 10031, 10031, 10031, -1, + 10032, 10032, 10032, -1, 10033, 10033, 10033, -1, + 10034, 10034, 10034, -1, 10035, 10035, 10035, -1, + 10036, 10036, 10036, -1, 10037, 10037, 10037, -1, + 10038, 10038, 10038, -1, 10039, 10039, 10039, -1, + 10040, 10040, 10040, -1, 10041, 10041, 10041, -1, + 10042, 10042, 10042, -1, 10043, 10043, 10043, -1, + 10044, 10044, 10044, -1, 10045, 10045, 10045, -1, + 10046, 10046, 10046, -1, 10047, 10047, 10047, -1, + 10048, 10048, 10048, -1, 10049, 10049, 10049, -1, + 10050, 10050, 10050, -1, 10051, 10051, 10051, -1, + 10052, 10052, 10052, -1, 10053, 10053, 10053, -1, + 10054, 10054, 10054, -1, 10055, 10055, 10055, -1, + 10056, 10056, 10056, -1, 10057, 10057, 10057, -1, + 10058, 10058, 10058, -1, 10059, 10059, 10059, -1, + 10060, 10060, 10060, -1, 10061, 10061, 10061, -1, + 10062, 10062, 10062, -1, 10063, 10063, 10063, -1, + 10064, 10064, 10064, -1, 10065, 10065, 10065, -1, + 10066, 10066, 10066, -1, 10067, 10067, 10067, -1, + 10068, 10068, 10068, -1, 10069, 10069, 10069, -1, + 10070, 10070, 10070, -1, 10071, 10071, 10071, -1, + 10072, 10072, 10072, -1, 10073, 10073, 10073, -1, + 10074, 10074, 10074, -1, 10075, 10075, 10075, -1, + 10076, 10076, 10076, -1, 10077, 10077, 10077, -1, + 10078, 10078, 10078, -1, 10079, 10079, 10079, -1, + 10080, 10080, 10080, -1, 10081, 10081, 10081, -1, + 10082, 10082, 10082, -1, 10083, 10083, 10083, -1, + 10084, 10084, 10084, -1, 10085, 10085, 10085, -1, + 10086, 10086, 10086, -1, 10087, 10087, 10087, -1, + 10088, 10088, 10088, -1, 10089, 10089, 10089, -1, + 10090, 10090, 10090, -1, 10091, 10091, 10091, -1, + 10092, 10092, 10092, -1, 10093, 10093, 10093, -1, + 10094, 10094, 10094, -1, 10095, 10095, 10095, -1, + 10096, 10096, 10096, -1, 10097, 10097, 10097, -1, + 10098, 10098, 10098, -1, 10099, 10099, 10099, -1, + 10100, 10100, 10100, -1, 10101, 10101, 10101, -1, + 10102, 10102, 10102, -1, 10103, 10103, 10103, -1, + 10104, 10104, 10104, -1, 10105, 10105, 10105, -1, + 10106, 10106, 10106, -1, 10107, 10107, 10107, -1, + 10108, 10108, 10108, -1, 10109, 10109, 10109, -1, + 10110, 10110, 10110, -1, 10111, 10111, 10111, -1, + 10112, 10112, 10112, -1, 10113, 10113, 10113, -1, + 10114, 10114, 10114, -1, 10115, 10115, 10115, -1, + 10116, 10116, 10116, -1, 10117, 10117, 10117, -1, + 10118, 10118, 10118, -1, 10119, 10119, 10119, -1, + 10120, 10120, 10120, -1, 10121, 10121, 10121, -1, + 10122, 10122, 10122, -1, 10123, 10123, 10123, -1, + 10124, 10124, 10124, -1, 10125, 10125, 10125, -1, + 10126, 10126, 10126, -1, 10127, 10127, 10127, -1, + 10128, 10128, 10128, -1, 10129, 10129, 10129, -1, + 10130, 10130, 10130, -1, 10131, 10131, 10131, -1, + 10132, 10132, 10132, -1, 10133, 10133, 10133, -1, + 10134, 10134, 10134, -1, 10135, 10135, 10135, -1, + 10136, 10136, 10136, -1, 10137, 10137, 10137, -1, + 10138, 10138, 10138, -1, 10139, 10139, 10139, -1, + 10140, 10140, 10140, -1, 10141, 10141, 10141, -1, + 10142, 10142, 10142, -1, 10143, 10143, 10143, -1, + 10144, 10144, 10144, -1, 10145, 10145, 10145, -1, + 10146, 10146, 10146, -1, 10147, 10147, 10147, -1, + 10148, 10148, 10148, -1, 10149, 10149, 10149, -1, + 10150, 10150, 10150, -1, 10151, 10151, 10151, -1, + 10152, 10152, 10152, -1, 10153, 10153, 10153, -1, + 10154, 10154, 10154, -1, 10155, 10155, 10155, -1, + 10156, 10156, 10156, -1, 10157, 10157, 10157, -1, + 10158, 10158, 10158, -1, 10159, 10159, 10159, -1, + 10160, 10160, 10160, -1, 10161, 10161, 10161, -1, + 10162, 10162, 10162, -1, 10163, 10163, 10163, -1, + 10164, 10164, 10164, -1, 10165, 10165, 10165, -1, + 10166, 10166, 10166, -1, 10167, 10167, 10167, -1, + 10168, 10168, 10168, -1, 10169, 10169, 10169, -1, + 10170, 10170, 10170, -1, 10171, 10171, 10171, -1, + 10172, 10172, 10172, -1, 10173, 10173, 10173, -1, + 10174, 10174, 10174, -1, 10175, 10175, 10175, -1, + 10176, 10176, 10176, -1, 10177, 10177, 10177, -1, + 10178, 10178, 10178, -1, 10179, 10179, 10179, -1, + 10180, 10180, 10180, -1, 10181, 10181, 10181, -1, + 10182, 10182, 10182, -1, 10183, 10183, 10183, -1, + 10184, 10184, 10184, -1, 10185, 10185, 10185, -1, + 10186, 10186, 10186, -1, 10187, 10187, 10187, -1, + 10188, 10188, 10188, -1, 10189, 10189, 10189, -1, + 10190, 10190, 10190, -1, 10191, 10191, 10191, -1, + 10192, 10192, 10192, -1, 10193, 10193, 10193, -1, + 10194, 10194, 10194, -1, 10195, 10195, 10195, -1, + 10196, 10196, 10196, -1, 10197, 10197, 10197, -1, + 10198, 10198, 10198, -1, 10199, 10199, 10199, -1, + 10200, 10200, 10200, -1, 10201, 10201, 10201, -1, + 10202, 10202, 10202, -1, 10203, 10203, 10203, -1, + 10204, 10204, 10204, -1, 10205, 10205, 10205, -1, + 10206, 10206, 10206, -1, 10207, 10207, 10207, -1, + 10208, 10208, 10208, -1, 10209, 10209, 10209, -1, + 10210, 10210, 10210, -1, 10211, 10211, 10211, -1, + 10212, 10212, 10212, -1, 10213, 10213, 10213, -1, + 10214, 10214, 10214, -1, 10215, 10215, 10215, -1, + 10216, 10216, 10216, -1, 10217, 10217, 10217, -1, + 10218, 10218, 10218, -1, 10219, 10219, 10219, -1, + 10220, 10220, 10220, -1, 10221, 10221, 10221, -1, + 10222, 10222, 10222, -1, 10223, 10223, 10223, -1, + 10224, 10224, 10224, -1, 10225, 10225, 10225, -1, + 10226, 10226, 10226, -1, 10227, 10227, 10227, -1, + 10228, 10228, 10228, -1, 10229, 10229, 10229, -1, + 10230, 10230, 10230, -1, 10231, 10231, 10231, -1, + 10232, 10232, 10232, -1, 10233, 10233, 10233, -1, + 10234, 10234, 10234, -1, 10235, 10235, 10235, -1, + 10236, 10236, 10236, -1, 10237, 10237, 10237, -1, + 10238, 10238, 10238, -1, 10239, 10239, 10239, -1, + 10240, 10240, 10240, -1, 10241, 10241, 10241, -1, + 10242, 10242, 10242, -1, 10243, 10243, 10243, -1, + 10244, 10244, 10244, -1, 10245, 10245, 10245, -1, + 10246, 10246, 10246, -1, 10247, 10247, 10247, -1, + 10248, 10248, 10248, -1, 10249, 10249, 10249, -1, + 10250, 10250, 10250, -1, 10251, 10251, 10251, -1, + 10252, 10252, 10252, -1, 10253, 10253, 10253, -1, + 10254, 10254, 10254, -1, 10255, 10255, 10255, -1, + 10256, 10256, 10256, -1, 10257, 10257, 10257, -1, + 10258, 10258, 10258, -1, 10259, 10259, 10259, -1, + 10260, 10260, 10260, -1, 10261, 10261, 10261, -1, + 10262, 10262, 10262, -1, 10263, 10263, 10263, -1, + 10264, 10264, 10264, -1, 10265, 10265, 10265, -1, + 10266, 10266, 10266, -1, 10267, 10267, 10267, -1, + 10268, 10268, 10268, -1, 10269, 10269, 10269, -1, + 10270, 10270, 10270, -1, 10271, 10271, 10271, -1, + 10272, 10272, 10272, -1, 10273, 10273, 10273, -1, + 10274, 10274, 10274, -1, 10275, 10275, 10275, -1, + 10276, 10276, 10276, -1, 10277, 10277, 10277, -1, + 10278, 10278, 10278, -1, 10279, 10279, 10279, -1, + 10280, 10280, 10280, -1, 10281, 10281, 10281, -1, + 10282, 10282, 10282, -1, 10283, 10283, 10283, -1, + 10284, 10284, 10284, -1, 10285, 10285, 10285, -1, + 10286, 10286, 10286, -1, 10287, 10287, 10287, -1, + 10288, 10288, 10288, -1, 10289, 10289, 10289, -1, + 10290, 10290, 10290, -1, 10291, 10291, 10291, -1, + 10292, 10292, 10292, -1, 10293, 10293, 10293, -1, + 10294, 10294, 10294, -1, 10295, 10295, 10295, -1, + 10296, 10296, 10296, -1, 10297, 10297, 10297, -1, + 10298, 10298, 10298, -1, 10299, 10299, 10299, -1, + 10300, 10300, 10300, -1, 10301, 10301, 10301, -1, + 10302, 10302, 10302, -1, 10303, 10303, 10303, -1, + 10304, 10304, 10304, -1, 10305, 10305, 10305, -1, + 10306, 10306, 10306, -1, 10307, 10307, 10307, -1, + 10308, 10308, 10308, -1, 10309, 10309, 10309, -1, + 10310, 10310, 10310, -1, 10311, 10311, 10311, -1, + 10312, 10312, 10312, -1, 10313, 10313, 10313, -1, + 10314, 10314, 10314, -1, 10315, 10315, 10315, -1, + 10316, 10316, 10316, -1, 10317, 10317, 10317, -1, + 10318, 10318, 10318, -1, 10319, 10319, 10319, -1, + 10320, 10320, 10320, -1, 10321, 10321, 10321, -1, + 10322, 10322, 10322, -1, 10323, 10323, 10323, -1, + 10324, 10324, 10324, -1, 10325, 10325, 10325, -1, + 10326, 10326, 10326, -1, 10327, 10327, 10327, -1, + 10328, 10328, 10328, -1, 10329, 10329, 10329, -1, + 10330, 10330, 10330, -1, 10331, 10331, 10331, -1, + 10332, 10332, 10332, -1, 10333, 10333, 10333, -1, + 10334, 10334, 10334, -1, 10335, 10335, 10335, -1, + 10336, 10336, 10336, -1, 10337, 10337, 10337, -1, + 10338, 10338, 10338, -1, 10339, 10339, 10339, -1, + 10340, 10340, 10340, -1, 10341, 10341, 10341, -1, + 10342, 10342, 10342, -1, 10343, 10343, 10343, -1, + 10344, 10344, 10344, -1, 10345, 10345, 10345, -1, + 10346, 10346, 10346, -1, 10347, 10347, 10347, -1, + 10348, 10348, 10348, -1, 10349, 10349, 10349, -1, + 10350, 10350, 10350, -1, 10351, 10351, 10351, -1, + 10352, 10352, 10352, -1, 10353, 10353, 10353, -1, + 10354, 10354, 10354, -1, 10355, 10355, 10355, -1, + 10356, 10356, 10356, -1, 10357, 10357, 10357, -1, + 10358, 10358, 10358, -1, 10359, 10359, 10359, -1, + 10360, 10360, 10360, -1, 10361, 10361, 10361, -1, + 10362, 10362, 10362, -1, 10363, 10363, 10363, -1, + 10364, 10364, 10364, -1, 10365, 10365, 10365, -1, + 10366, 10366, 10366, -1, 10367, 10367, 10367, -1, + 10368, 10368, 10368, -1, 10369, 10369, 10369, -1, + 10370, 10370, 10370, -1, 10371, 10371, 10371, -1, + 10372, 10372, 10372, -1, 10373, 10373, 10373, -1, + 10374, 10374, 10374, -1, 10375, 10375, 10375, -1, + 10376, 10376, 10376, -1, 10377, 10377, 10377, -1, + 10378, 10378, 10378, -1, 10379, 10379, 10379, -1, + 10380, 10380, 10380, -1, 10381, 10381, 10381, -1, + 10382, 10382, 10382, -1, 10383, 10383, 10383, -1, + 10384, 10384, 10384, -1, 10385, 10385, 10385, -1, + 10386, 10386, 10386, -1, 10387, 10387, 10387, -1, + 10388, 10388, 10388, -1, 10389, 10389, 10389, -1, + 10390, 10390, 10390, -1, 10391, 10391, 10391, -1, + 10392, 10392, 10392, -1, 10393, 10393, 10393, -1, + 10394, 10394, 10394, -1, 10395, 10395, 10395, -1, + 10396, 10396, 10396, -1, 10397, 10397, 10397, -1, + 10398, 10398, 10398, -1, 10399, 10399, 10399, -1, + 10400, 10400, 10400, -1, 10401, 10401, 10401, -1, + 10402, 10402, 10402, -1, 10403, 10403, 10403, -1, + 10404, 10404, 10404, -1, 10405, 10405, 10405, -1, + 10406, 10406, 10406, -1, 10407, 10407, 10407, -1, + 10408, 10408, 10408, -1, 10409, 10409, 10409, -1, + 10410, 10410, 10410, -1, 10411, 10411, 10411, -1, + 10412, 10412, 10412, -1, 10413, 10413, 10413, -1, + 10414, 10414, 10414, -1, 10415, 10415, 10415, -1, + 10416, 10416, 10416, -1, 10417, 10417, 10417, -1, + 10418, 10418, 10418, -1, 10419, 10419, 10419, -1, + 10420, 10420, 10420, -1, 10421, 10421, 10421, -1, + 10422, 10422, 10422, -1, 10423, 10423, 10423, -1, + 10424, 10424, 10424, -1, 10425, 10425, 10425, -1, + 10426, 10426, 10426, -1, 10427, 10427, 10427, -1, + 10428, 10428, 10428, -1, 10429, 10429, 10429, -1, + 10430, 10430, 10430, -1, 10431, 10431, 10431, -1, + 10432, 10432, 10432, -1, 10433, 10433, 10433, -1, + 10434, 10434, 10434, -1, 10435, 10435, 10435, -1, + 10436, 10436, 10436, -1, 10437, 10437, 10437, -1, + 10438, 10438, 10438, -1, 10439, 10439, 10439, -1, + 10440, 10440, 10440, -1, 10441, 10441, 10441, -1, + 10442, 10442, 10442, -1, 10443, 10443, 10443, -1, + 10444, 10444, 10444, -1, 10445, 10445, 10445, -1, + 10446, 10446, 10446, -1, 10447, 10447, 10447, -1, + 10448, 10448, 10448, -1, 10449, 10449, 10449, -1, + 10450, 10450, 10450, -1, 10451, 10451, 10451, -1, + 10452, 10452, 10452, -1, 10453, 10453, 10453, -1, + 10454, 10454, 10454, -1, 10455, 10455, 10455, -1, + 10456, 10456, 10456, -1, 10457, 10457, 10457, -1, + 10458, 10458, 10458, -1, 10459, 10459, 10459, -1, + 10460, 10460, 10460, -1, 10461, 10461, 10461, -1, + 10462, 10462, 10462, -1, 10463, 10463, 10463, -1, + 10464, 10464, 10464, -1, 10465, 10465, 10465, -1, + 10466, 10466, 10466, -1, 10467, 10467, 10467, -1, + 10468, 10468, 10468, -1, 10469, 10469, 10469, -1, + 10470, 10470, 10470, -1, 10471, 10471, 10471, -1, + 10472, 10472, 10472, -1, 10473, 10473, 10473, -1, + 10474, 10474, 10474, -1, 10475, 10475, 10475, -1, + 10476, 10476, 10476, -1, 10477, 10477, 10477, -1, + 10478, 10478, 10478, -1, 10479, 10479, 10479, -1, + 10480, 10480, 10480, -1, 10481, 10481, 10481, -1, + 10482, 10482, 10482, -1, 10483, 10483, 10483, -1, + 10484, 10484, 10484, -1, 10485, 10485, 10485, -1, + 10486, 10486, 10486, -1, 10487, 10487, 10487, -1, + 10488, 10488, 10488, -1, 10489, 10489, 10489, -1, + 10490, 10490, 10490, -1, 10491, 10491, 10491, -1, + 10492, 10492, 10492, -1, 10493, 10493, 10493, -1, + 10494, 10494, 10494, -1, 10495, 10495, 10495, -1, + 10496, 10496, 10496, -1, 10497, 10497, 10497, -1, + 10498, 10498, 10498, -1, 10499, 10499, 10499, -1, + 10500, 10500, 10500, -1, 10501, 10501, 10501, -1, + 10502, 10502, 10502, -1, 10503, 10503, 10503, -1, + 10504, 10504, 10504, -1, 10505, 10505, 10505, -1, + 10506, 10506, 10506, -1, 10507, 10507, 10507, -1, + 10508, 10508, 10508, -1, 10509, 10509, 10509, -1, + 10510, 10510, 10510, -1, 10511, 10511, 10511, -1, + 10512, 10512, 10512, -1, 10513, 10513, 10513, -1, + 10514, 10514, 10514, -1, 10515, 10515, 10515, -1, + 10516, 10516, 10516, -1, 10517, 10517, 10517, -1, + 10518, 10518, 10518, -1, 10519, 10519, 10519, -1, + 10520, 10520, 10520, -1, 10521, 10521, 10521, -1, + 10522, 10522, 10522, -1, 10523, 10523, 10523, -1, + 10524, 10524, 10524, -1, 10525, 10525, 10525, -1, + 10526, 10526, 10526, -1, 10527, 10527, 10527, -1, + 10528, 10528, 10528, -1, 10529, 10529, 10529, -1, + 10530, 10530, 10530, -1, 10531, 10531, 10531, -1, + 10532, 10532, 10532, -1, 10533, 10533, 10533, -1, + 10534, 10534, 10534, -1, 10535, 10535, 10535, -1, + 10536, 10536, 10536, -1, 10537, 10537, 10537, -1, + 10538, 10538, 10538, -1, 10539, 10539, 10539, -1, + 10540, 10540, 10540, -1, 10541, 10541, 10541, -1, + 10542, 10542, 10542, -1, 10543, 10543, 10543, -1, + 10544, 10544, 10544, -1, 10545, 10545, 10545, -1, + 10546, 10546, 10546, -1, 10547, 10547, 10547, -1, + 10548, 10548, 10548, -1, 10549, 10549, 10549, -1, + 10550, 10550, 10550, -1, 10551, 10551, 10551, -1, + 10552, 10552, 10552, -1, 10553, 10553, 10553, -1, + 10554, 10554, 10554, -1, 10555, 10555, 10555, -1, + 10556, 10556, 10556, -1, 10557, 10557, 10557, -1, + 10558, 10558, 10558, -1, 10559, 10559, 10559, -1, + 10560, 10560, 10560, -1, 10561, 10561, 10561, -1, + 10562, 10562, 10562, -1, 10563, 10563, 10563, -1, + 10564, 10564, 10564, -1, 10565, 10565, 10565, -1, + 10566, 10566, 10566, -1, 10567, 10567, 10567, -1, + 10568, 10568, 10568, -1, 10569, 10569, 10569, -1, + 10570, 10570, 10570, -1, 10571, 10571, 10571, -1, + 10572, 10572, 10572, -1, 10573, 10573, 10573, -1, + 10574, 10574, 10574, -1, 10575, 10575, 10575, -1, + 10576, 10576, 10576, -1, 10577, 10577, 10577, -1, + 10578, 10578, 10578, -1, 10579, 10579, 10579, -1, + 10580, 10580, 10580, -1, 10581, 10581, 10581, -1, + 10582, 10582, 10582, -1, 10583, 10583, 10583, -1, + 10584, 10584, 10584, -1, 10585, 10585, 10585, -1, + 10586, 10586, 10586, -1, 10587, 10587, 10587, -1, + 10588, 10588, 10588, -1, 10589, 10589, 10589, -1, + 10590, 10590, 10590, -1, 10591, 10591, 10591, -1, + 10592, 10592, 10592, -1, 10593, 10593, 10593, -1, + 10594, 10594, 10594, -1, 10595, 10595, 10595, -1, + 10596, 10596, 10596, -1, 10597, 10597, 10597, -1, + 10598, 10598, 10598, -1, 10599, 10599, 10599, -1, + 10600, 10600, 10600, -1, 10601, 10601, 10601, -1, + 10602, 10602, 10602, -1, 10603, 10603, 10603, -1, + 10604, 10604, 10604, -1, 10605, 10605, 10605, -1, + 10606, 10606, 10606, -1, 10607, 10607, 10607, -1, + 10608, 10608, 10608, -1, 10609, 10609, 10609, -1, + 10610, 10610, 10610, -1, 10611, 10611, 10611, -1, + 10612, 10612, 10612, -1, 10613, 10613, 10613, -1, + 10614, 10614, 10614, -1, 10615, 10615, 10615, -1, + 10616, 10616, 10616, -1, 10617, 10617, 10617, -1, + 10618, 10618, 10618, -1, 10619, 10619, 10619, -1, + 10620, 10620, 10620, -1, 10621, 10621, 10621, -1, + 10622, 10622, 10622, -1, 10623, 10623, 10623, -1, + 10624, 10624, 10624, -1, 10625, 10625, 10625, -1, + 10626, 10626, 10626, -1, 10627, 10627, 10627, -1, + 10628, 10628, 10628, -1, 10629, 10629, 10629, -1, + 10630, 10630, 10630, -1, 10631, 10631, 10631, -1, + 10632, 10632, 10632, -1, 10633, 10633, 10633, -1, + 10634, 10634, 10634, -1, 10635, 10635, 10635, -1, + 10636, 10636, 10636, -1, 10637, 10637, 10637, -1, + 10638, 10638, 10638, -1, 10639, 10639, 10639, -1, + 10640, 10640, 10640, -1, 10641, 10641, 10641, -1, + 10642, 10642, 10642, -1, 10643, 10643, 10643, -1, + 10644, 10644, 10644, -1, 10645, 10645, 10645, -1, + 10646, 10646, 10646, -1, 10647, 10647, 10647, -1, + 10648, 10648, 10648, -1, 10649, 10649, 10649, -1, + 10650, 10650, 10650, -1, 10651, 10651, 10651, -1, + 10652, 10652, 10652, -1, 10653, 10653, 10653, -1, + 10654, 10654, 10654, -1, 10655, 10655, 10655, -1, + 10656, 10656, 10656, -1, 10657, 10657, 10657, -1, + 10658, 10658, 10658, -1, 10659, 10659, 10659, -1, + 10660, 10660, 10660, -1, 10661, 10661, 10661, -1, + 10662, 10662, 10662, -1, 10663, 10663, 10663, -1, + 10664, 10664, 10664, -1, 10665, 10665, 10665, -1, + 10666, 10666, 10666, -1, 10667, 10667, 10667, -1, + 10668, 10668, 10668, -1, 10669, 10669, 10669, -1, + 10670, 10670, 10670, -1, 10671, 10671, 10671, -1, + 10672, 10672, 10672, -1, 10673, 10673, 10673, -1, + 10674, 10674, 10674, -1, 10675, 10675, 10675, -1, + 10676, 10676, 10676, -1, 10677, 10677, 10677, -1, + 10678, 10678, 10678, -1, 10679, 10679, 10679, -1, + 10680, 10680, 10680, -1, 10681, 10681, 10681, -1, + 10682, 10682, 10682, -1, 10683, 10683, 10683, -1, + 10684, 10684, 10684, -1, 10685, 10685, 10685, -1, + 10686, 10686, 10686, -1, 10687, 10687, 10687, -1, + 10688, 10688, 10688, -1, 10689, 10689, 10689, -1, + 10690, 10690, 10690, -1, 10691, 10691, 10691, -1, + 10692, 10692, 10692, -1, 10693, 10693, 10693, -1, + 10694, 10694, 10694, -1, 10695, 10695, 10695, -1, + 10696, 10696, 10696, -1, 10697, 10697, 10697, -1, + 10698, 10698, 10698, -1, 10699, 10699, 10699, -1, + 10700, 10700, 10700, -1, 10701, 10701, 10701, -1, + 10702, 10702, 10702, -1, 10703, 10703, 10703, -1, + 10704, 10704, 10704, -1, 10705, 10705, 10705, -1, + 10706, 10706, 10706, -1, 10707, 10707, 10707, -1, + 10708, 10708, 10708, -1, 10709, 10709, 10709, -1, + 10710, 10710, 10710, -1, 10711, 10711, 10711, -1, + 10712, 10712, 10712, -1, 10713, 10713, 10713, -1, + 10714, 10714, 10714, -1, 10715, 10715, 10715, -1, + 10716, 10716, 10716, -1, 10717, 10717, 10717, -1, + 10718, 10718, 10718, -1, 10719, 10719, 10719, -1, + 10720, 10720, 10720, -1, 10721, 10721, 10721, -1, + 10722, 10722, 10722, -1, 10723, 10723, 10723, -1, + 10724, 10724, 10724, -1, 10725, 10725, 10725, -1, + 10726, 10726, 10726, -1, 10727, 10727, 10727, -1, + 10728, 10728, 10728, -1, 10729, 10729, 10729, -1, + 10730, 10730, 10730, -1, 10731, 10731, 10731, -1, + 10732, 10732, 10732, -1, 10733, 10733, 10733, -1, + 10734, 10734, 10734, -1, 10735, 10735, 10735, -1, + 10736, 10736, 10736, -1, 10737, 10737, 10737, -1, + 10738, 10738, 10738, -1, 10739, 10739, 10739, -1, + 10740, 10740, 10740, -1, 10741, 10741, 10741, -1, + 10742, 10742, 10742, -1, 10743, 10743, 10743, -1, + 10744, 10744, 10744, -1, 10745, 10745, 10745, -1, + 10746, 10746, 10746, -1, 10747, 10747, 10747, -1, + 10748, 10748, 10748, -1, 10749, 10749, 10749, -1, + 10750, 10750, 10750, -1, 10751, 10751, 10751, -1, + 10752, 10752, 10752, -1, 10753, 10753, 10753, -1, + 10754, 10754, 10754, -1, 10755, 10755, 10755, -1, + 10756, 10756, 10756, -1, 10757, 10757, 10757, -1, + 10758, 10758, 10758, -1, 10759, 10759, 10759, -1, + 10760, 10760, 10760, -1, 10761, 10761, 10761, -1, + 10762, 10762, 10762, -1, 10763, 10763, 10763, -1, + 10764, 10764, 10764, -1, 10765, 10765, 10765, -1, + 10766, 10766, 10766, -1, 10767, 10767, 10767, -1, + 10768, 10768, 10768, -1, 10769, 10769, 10769, -1, + 10770, 10770, 10770, -1, 10771, 10771, 10771, -1, + 10772, 10772, 10772, -1, 10773, 10773, 10773, -1, + 10774, 10774, 10774, -1, 10775, 10775, 10775, -1, + 10776, 10776, 10776, -1, 10777, 10777, 10777, -1, + 10778, 10778, 10778, -1, 10779, 10779, 10779, -1, + 10780, 10780, 10780, -1, 10781, 10781, 10781, -1, + 10782, 10782, 10782, -1, 10783, 10783, 10783, -1, + 10784, 10784, 10784, -1, 10785, 10785, 10785, -1, + 10786, 10786, 10786, -1, 10787, 10787, 10787, -1, + 10788, 10788, 10788, -1, 10789, 10789, 10789, -1, + 10790, 10790, 10790, -1, 10791, 10791, 10791, -1, + 10792, 10792, 10792, -1, 10793, 10793, 10793, -1, + 10794, 10794, 10794, -1, 10795, 10795, 10795, -1, + 10796, 10796, 10796, -1, 10797, 10797, 10797, -1, + 10798, 10798, 10798, -1, 10799, 10799, 10799, -1, + 10800, 10800, 10800, -1, 10801, 10801, 10801, -1, + 10802, 10802, 10802, -1, 10803, 10803, 10803, -1, + 10804, 10804, 10804, -1, 10805, 10805, 10805, -1, + 10806, 10806, 10806, -1, 10807, 10807, 10807, -1, + 10808, 10808, 10808, -1, 10809, 10809, 10809, -1, + 10810, 10810, 10810, -1, 10811, 10811, 10811, -1, + 10812, 10812, 10812, -1, 10813, 10813, 10813, -1, + 10814, 10814, 10814, -1, 10815, 10815, 10815, -1, + 10816, 10816, 10816, -1, 10817, 10817, 10817, -1, + 10818, 10818, 10818, -1, 10819, 10819, 10819, -1, + 10820, 10820, 10820, -1, 10821, 10821, 10821, -1, + 10822, 10822, 10822, -1, 10823, 10823, 10823, -1, + 10824, 10824, 10824, -1, 10825, 10825, 10825, -1, + 10826, 10826, 10826, -1, 10827, 10827, 10827, -1, + 10828, 10828, 10828, -1, 10829, 10829, 10829, -1, + 10830, 10830, 10830, -1, 10831, 10831, 10831, -1, + 10832, 10832, 10832, -1, 10833, 10833, 10833, -1, + 10834, 10834, 10834, -1, 10835, 10835, 10835, -1, + 10836, 10836, 10836, -1, 10837, 10837, 10837, -1, + 10838, 10838, 10838, -1, 10839, 10839, 10839, -1, + 10840, 10840, 10840, -1, 10841, 10841, 10841, -1, + 10842, 10842, 10842, -1, 10843, 10843, 10843, -1, + 10844, 10844, 10844, -1, 10845, 10845, 10845, -1, + 10846, 10846, 10846, -1, 10847, 10847, 10847, -1, + 10848, 10848, 10848, -1, 10849, 10849, 10849, -1, + 10850, 10850, 10850, -1, 10851, 10851, 10851, -1, + 10852, 10852, 10852, -1, 10853, 10853, 10853, -1, + 10854, 10854, 10854, -1, 10855, 10855, 10855, -1, + 10856, 10856, 10856, -1, 10857, 10857, 10857, -1, + 10858, 10858, 10858, -1, 10859, 10859, 10859, -1, + 10860, 10860, 10860, -1, 10861, 10861, 10861, -1, + 10862, 10862, 10862, -1, 10863, 10863, 10863, -1, + 10864, 10864, 10864, -1, 10865, 10865, 10865, -1, + 10866, 10866, 10866, -1, 10867, 10867, 10867, -1, + 10868, 10868, 10868, -1, 10869, 10869, 10869, -1, + 10870, 10870, 10870, -1, 10871, 10871, 10871, -1, + 10872, 10872, 10872, -1, 10873, 10873, 10873, -1, + 10874, 10874, 10874, -1, 10875, 10875, 10875, -1, + 10876, 10876, 10876, -1, 10877, 10877, 10877, -1, + 10878, 10878, 10878, -1, 10879, 10879, 10879, -1, + 10880, 10880, 10880, -1, 10881, 10881, 10881, -1, + 10882, 10882, 10882, -1, 10883, 10883, 10883, -1, + 10884, 10884, 10884, -1, 10885, 10885, 10885, -1, + 10886, 10886, 10886, -1, 10887, 10887, 10887, -1, + 10888, 10888, 10888, -1, 10889, 10889, 10889, -1, + 10890, 10890, 10890, -1, 10891, 10891, 10891, -1, + 10892, 10892, 10892, -1, 10893, 10893, 10893, -1, + 10894, 10894, 10894, -1, 10895, 10895, 10895, -1, + 10896, 10896, 10896, -1, 10897, 10897, 10897, -1, + 10898, 10898, 10898, -1, 10899, 10899, 10899, -1, + 10900, 10900, 10900, -1, 10901, 10901, 10901, -1, + 10902, 10902, 10902, -1, 10903, 10903, 10903, -1, + 10904, 10904, 10904, -1, 10905, 10905, 10905, -1, + 10906, 10906, 10906, -1, 10907, 10907, 10907, -1, + 10908, 10908, 10908, -1, 10909, 10909, 10909, -1, + 10910, 10910, 10910, -1, 10911, 10911, 10911, -1, + 10912, 10912, 10912, -1, 10913, 10913, 10913, -1, + 10914, 10914, 10914, -1, 10915, 10915, 10915, -1, + 10916, 10916, 10916, -1, 10917, 10917, 10917, -1, + 10918, 10918, 10918, -1, 10919, 10919, 10919, -1, + 10920, 10920, 10920, -1, 10921, 10921, 10921, -1, + 10922, 10922, 10922, -1, 10923, 10923, 10923, -1, + 10924, 10924, 10924, -1, 10925, 10925, 10925, -1, + 10926, 10926, 10926, -1, 10927, 10927, 10927, -1, + 10928, 10928, 10928, -1, 10929, 10929, 10929, -1, + 10930, 10930, 10930, -1, 10931, 10931, 10931, -1, + 10932, 10932, 10932, -1, 10933, 10933, 10933, -1, + 10934, 10934, 10934, -1, 10935, 10935, 10935, -1, + 10936, 10936, 10936, -1, 10937, 10937, 10937, -1, + 10938, 10938, 10938, -1, 10939, 10939, 10939, -1, + 10940, 10940, 10940, -1, 10941, 10941, 10941, -1, + 10942, 10942, 10942, -1, 10943, 10943, 10943, -1, + 10944, 10944, 10944, -1, 10945, 10945, 10945, -1, + 10946, 10946, 10946, -1, 10947, 10947, 10947, -1, + 10948, 10948, 10948, -1, 10949, 10949, 10949, -1, + 10950, 10950, 10950, -1, 10951, 10951, 10951, -1, + 10952, 10952, 10952, -1, 10953, 10953, 10953, -1, + 10954, 10954, 10954, -1, 10955, 10955, 10955, -1, + 10956, 10956, 10956, -1, 10957, 10957, 10957, -1, + 10958, 10958, 10958, -1, 10959, 10959, 10959, -1, + 10960, 10960, 10960, -1, 10961, 10961, 10961, -1, + 10962, 10962, 10962, -1, 10963, 10963, 10963, -1, + 10964, 10964, 10964, -1, 10965, 10965, 10965, -1, + 10966, 10966, 10966, -1, 10967, 10967, 10967, -1, + 10968, 10968, 10968, -1, 10969, 10969, 10969, -1, + 10970, 10970, 10970, -1, 10971, 10971, 10971, -1, + 10972, 10972, 10972, -1, 10973, 10973, 10973, -1, + 10974, 10974, 10974, -1, 10975, 10975, 10975, -1, + 10976, 10976, 10976, -1, 10977, 10977, 10977, -1, + 10978, 10978, 10978, -1, 10979, 10979, 10979, -1, + 10980, 10980, 10980, -1, 10981, 10981, 10981, -1, + 10982, 10982, 10982, -1, 10983, 10983, 10983, -1, + 10984, 10984, 10984, -1, 10985, 10985, 10985, -1, + 10986, 10986, 10986, -1, 10987, 10987, 10987, -1, + 10988, 10988, 10988, -1, 10989, 10989, 10989, -1, + 10990, 10990, 10990, -1, 10991, 10991, 10991, -1, + 10992, 10992, 10992, -1, 10993, 10993, 10993, -1, + 10994, 10994, 10994, -1, 10995, 10995, 10995, -1, + 10996, 10996, 10996, -1, 10997, 10997, 10997, -1, + 10998, 10998, 10998, -1, 10999, 10999, 10999, -1, + 11000, 11000, 11000, -1, 11001, 11001, 11001, -1, + 11002, 11002, 11002, -1, 11003, 11003, 11003, -1, + 11004, 11004, 11004, -1, 11005, 11005, 11005, -1, + 11006, 11006, 11006, -1, 11007, 11007, 11007, -1, + 11008, 11008, 11008, -1, 11009, 11009, 11009, -1, + 11010, 11010, 11010, -1, 11011, 11011, 11011, -1, + 11012, 11012, 11012, -1, 11013, 11013, 11013, -1, + 11014, 11014, 11014, -1, 11015, 11015, 11015, -1, + 11016, 11016, 11016, -1, 11017, 11017, 11017, -1, + 11018, 11018, 11018, -1, 11019, 11019, 11019, -1, + 11020, 11020, 11020, -1, 11021, 11021, 11021, -1, + 11022, 11022, 11022, -1, 11023, 11023, 11023, -1, + 11024, 11024, 11024, -1, 11025, 11025, 11025, -1, + 11026, 11026, 11026, -1, 11027, 11027, 11027, -1, + 11028, 11028, 11028, -1, 11029, 11029, 11029, -1, + 11030, 11030, 11030, -1, 11031, 11031, 11031, -1, + 11032, 11032, 11032, -1, 11033, 11033, 11033, -1, + 11034, 11034, 11034, -1, 11035, 11035, 11035, -1, + 11036, 11036, 11036, -1, 11037, 11037, 11037, -1, + 11038, 11038, 11038, -1, 11039, 11039, 11039, -1, + 11040, 11040, 11040, -1, 11041, 11041, 11041, -1, + 11042, 11042, 11042, -1, 11043, 11043, 11043, -1, + 11044, 11044, 11044, -1, 11045, 11045, 11045, -1, + 11046, 11046, 11046, -1, 11047, 11047, 11047, -1, + 11048, 11048, 11048, -1, 11049, 11049, 11049, -1, + 11050, 11050, 11050, -1, 11051, 11051, 11051, -1, + 11052, 11052, 11052, -1, 11053, 11053, 11053, -1, + 11054, 11054, 11054, -1, 11055, 11055, 11055, -1, + 11056, 11056, 11056, -1, 11057, 11057, 11057, -1, + 11058, 11058, 11058, -1, 11059, 11059, 11059, -1, + 11060, 11060, 11060, -1, 11061, 11061, 11061, -1, + 11062, 11062, 11062, -1, 11063, 11063, 11063, -1, + 11064, 11064, 11064, -1, 11065, 11065, 11065, -1, + 11066, 11066, 11066, -1, 11067, 11067, 11067, -1, + 11068, 11068, 11068, -1, 11069, 11069, 11069, -1, + 11070, 11070, 11070, -1, 11071, 11071, 11071, -1, + 11072, 11072, 11072, -1, 11073, 11073, 11073, -1, + 11074, 11074, 11074, -1, 11075, 11075, 11075, -1, + 11076, 11076, 11076, -1, 11077, 11077, 11077, -1, + 11078, 11078, 11078, -1, 11079, 11079, 11079, -1, + 11080, 11080, 11080, -1, 11081, 11081, 11081, -1, + 11082, 11082, 11082, -1, 11083, 11083, 11083, -1, + 11084, 11084, 11084, -1, 11085, 11085, 11085, -1, + 11086, 11086, 11086, -1, 11087, 11087, 11087, -1, + 11088, 11088, 11088, -1, 11089, 11089, 11089, -1, + 11090, 11090, 11090, -1, 11091, 11091, 11091, -1, + 11092, 11092, 11092, -1, 11093, 11093, 11093, -1, + 11094, 11094, 11094, -1, 11095, 11095, 11095, -1, + 11096, 11096, 11096, -1, 11097, 11097, 11097, -1, + 11098, 11098, 11098, -1, 11099, 11099, 11099, -1, + 11100, 11100, 11100, -1, 11101, 11101, 11101, -1, + 11102, 11102, 11102, -1, 11103, 11103, 11103, -1, + 11104, 11104, 11104, -1, 11105, 11105, 11105, -1, + 11106, 11106, 11106, -1, 11107, 11107, 11107, -1, + 11108, 11108, 11108, -1, 11109, 11109, 11109, -1, + 11110, 11110, 11110, -1, 11111, 11111, 11111, -1, + 11112, 11112, 11112, -1, 11113, 11113, 11113, -1, + 11114, 11114, 11114, -1, 11115, 11115, 11115, -1, + 11116, 11116, 11116, -1, 11117, 11117, 11117, -1, + 11118, 11118, 11118, -1, 11119, 11119, 11119, -1, + 11120, 11120, 11120, -1, 11121, 11121, 11121, -1, + 11122, 11122, 11122, -1, 11123, 11123, 11123, -1, + 11124, 11124, 11124, -1, 11125, 11125, 11125, -1, + 11126, 11126, 11126, -1, 11127, 11127, 11127, -1, + 11128, 11128, 11128, -1, 11129, 11129, 11129, -1, + 11130, 11130, 11130, -1, 11131, 11131, 11131, -1, + 11132, 11132, 11132, -1, 11133, 11133, 11133, -1, + 11134, 11134, 11134, -1, 11135, 11135, 11135, -1, + 11136, 11136, 11136, -1, 11137, 11137, 11137, -1, + 11138, 11138, 11138, -1, 11139, 11139, 11139, -1, + 11140, 11140, 11140, -1, 11141, 11141, 11141, -1, + 11142, 11142, 11142, -1, 11143, 11143, 11143, -1, + 11144, 11144, 11144, -1, 11145, 11145, 11145, -1, + 11146, 11146, 11146, -1, 11147, 11147, 11147, -1, + 11148, 11148, 11148, -1, 11149, 11149, 11149, -1, + 11150, 11150, 11150, -1, 11151, 11151, 11151, -1, + 11152, 11152, 11152, -1, 11153, 11153, 11153, -1, + 11154, 11154, 11154, -1, 11155, 11155, 11155, -1, + 11156, 11156, 11156, -1, 11157, 11157, 11157, -1, + 11158, 11158, 11158, -1, 11159, 11159, 11159, -1, + 11160, 11160, 11160, -1, 11161, 11161, 11161, -1, + 11162, 11162, 11162, -1, 11163, 11163, 11163, -1, + 11164, 11164, 11164, -1, 11165, 11165, 11165, -1, + 11166, 11166, 11166, -1, 11167, 11167, 11167, -1, + 11168, 11168, 11168, -1, 11169, 11169, 11169, -1, + 11170, 11170, 11170, -1, 11171, 11171, 11171, -1, + 11172, 11172, 11172, -1, 11173, 11173, 11173, -1, + 11174, 11174, 11174, -1, 11175, 11175, 11175, -1, + 11176, 11176, 11176, -1, 11177, 11177, 11177, -1, + 11178, 11178, 11178, -1, 11179, 11179, 11179, -1, + 11180, 11180, 11180, -1, 11181, 11181, 11181, -1, + 11182, 11182, 11182, -1, 11183, 11183, 11183, -1, + 11184, 11184, 11184, -1, 11185, 11185, 11185, -1, + 11186, 11186, 11186, -1, 11187, 11187, 11187, -1, + 11188, 11188, 11188, -1, 11189, 11189, 11189, -1, + 11190, 11190, 11190, -1, 11191, 11191, 11191, -1, + 11192, 11192, 11192, -1, 11193, 11193, 11193, -1, + 11194, 11194, 11194, -1, 11195, 11195, 11195, -1, + 11196, 11196, 11196, -1, 11197, 11197, 11197, -1, + 11198, 11198, 11198, -1, 11199, 11199, 11199, -1, + 11200, 11200, 11200, -1, 11201, 11201, 11201, -1, + 11202, 11202, 11202, -1, 11203, 11203, 11203, -1, + 11204, 11204, 11204, -1, 11205, 11205, 11205, -1, + 11206, 11206, 11206, -1, 11207, 11207, 11207, -1, + 11208, 11208, 11208, -1, 11209, 11209, 11209, -1, + 11210, 11210, 11210, -1, 11211, 11211, 11211, -1, + 11212, 11212, 11212, -1, 11213, 11213, 11213, -1, + 11214, 11214, 11214, -1, 11215, 11215, 11215, -1, + 11216, 11216, 11216, -1, 11217, 11217, 11217, -1, + 11218, 11218, 11218, -1, 11219, 11219, 11219, -1, + 11220, 11220, 11220, -1, 11221, 11221, 11221, -1, + 11222, 11222, 11222, -1, 11223, 11223, 11223, -1, + 11224, 11224, 11224, -1, 11225, 11225, 11225, -1, + 11226, 11226, 11226, -1, 11227, 11227, 11227, -1, + 11228, 11228, 11228, -1, 11229, 11229, 11229, -1, + 11230, 11230, 11230, -1, 11231, 11231, 11231, -1, + 11232, 11232, 11232, -1, 11233, 11233, 11233, -1, + 11234, 11234, 11234, -1, 11235, 11235, 11235, -1, + 11236, 11236, 11236, -1, 11237, 11237, 11237, -1, + 11238, 11238, 11238, -1, 11239, 11239, 11239, -1, + 11240, 11240, 11240, -1, 11241, 11241, 11241, -1, + 11242, 11242, 11242, -1, 11243, 11243, 11243, -1, + 11244, 11244, 11244, -1, 11245, 11245, 11245, -1, + 11246, 11246, 11246, -1, 11247, 11247, 11247, -1, + 11248, 11248, 11248, -1, 11249, 11249, 11249, -1, + 11250, 11250, 11250, -1, 11251, 11251, 11251, -1, + 11252, 11252, 11252, -1, 11253, 11253, 11253, -1, + 11254, 11254, 11254, -1, 11255, 11255, 11255, -1, + 11256, 11256, 11256, -1, 11257, 11257, 11257, -1, + 11258, 11258, 11258, -1, 11259, 11259, 11259, -1, + 11260, 11260, 11260, -1, 11261, 11261, 11261, -1, + 11262, 11262, 11262, -1, 11263, 11263, 11263, -1, + 11264, 11264, 11264, -1, 11265, 11265, 11265, -1, + 11266, 11266, 11266, -1, 11267, 11267, 11267, -1, + 11268, 11268, 11268, -1, 11269, 11269, 11269, -1, + 11270, 11270, 11270, -1, 11271, 11271, 11271, -1, + 11272, 11272, 11272, -1, 11273, 11273, 11273, -1, + 11274, 11274, 11274, -1, 11275, 11275, 11275, -1, + 11276, 11276, 11276, -1, 11277, 11277, 11277, -1, + 11278, 11278, 11278, -1, 11279, 11279, 11279, -1, + 11280, 11280, 11280, -1, 11281, 11281, 11281, -1, + 11282, 11282, 11282, -1, 11283, 11283, 11283, -1, + 11284, 11284, 11284, -1, 11285, 11285, 11285, -1, + 11286, 11286, 11286, -1, 11287, 11287, 11287, -1, + 11288, 11288, 11288, -1, 11289, 11289, 11289, -1, + 11290, 11290, 11290, -1, 11291, 11291, 11291, -1, + 11292, 11292, 11292, -1, 11293, 11293, 11293, -1, + 11294, 11294, 11294, -1, 11295, 11295, 11295, -1, + 11296, 11296, 11296, -1, 11297, 11297, 11297, -1, + 11298, 11298, 11298, -1, 11299, 11299, 11299, -1, + 11300, 11300, 11300, -1, 11301, 11301, 11301, -1, + 11302, 11302, 11302, -1, 11303, 11303, 11303, -1, + 11304, 11304, 11304, -1, 11305, 11305, 11305, -1, + 11306, 11306, 11306, -1, 11307, 11307, 11307, -1, + 11308, 11308, 11308, -1, 11309, 11309, 11309, -1, + 11310, 11310, 11310, -1, 11311, 11311, 11311, -1, + 11312, 11312, 11312, -1, 11313, 11313, 11313, -1, + 11314, 11314, 11314, -1, 11315, 11315, 11315, -1, + 11316, 11316, 11316, -1, 11317, 11317, 11317, -1, + 11318, 11318, 11318, -1, 11319, 11319, 11319, -1, + 11320, 11320, 11320, -1, 11321, 11321, 11321, -1, + 11322, 11322, 11322, -1, 11323, 11323, 11323, -1, + 11324, 11324, 11324, -1, 11325, 11325, 11325, -1, + 11326, 11326, 11326, -1, 11327, 11327, 11327, -1, + 11328, 11328, 11328, -1, 11329, 11329, 11329, -1, + 11330, 11330, 11330, -1, 11331, 11331, 11331, -1, + 11332, 11332, 11332, -1, 11333, 11333, 11333, -1, + 11334, 11334, 11334, -1, 11335, 11335, 11335, -1, + 11336, 11336, 11336, -1, 11337, 11337, 11337, -1, + 11338, 11338, 11338, -1, 11339, 11339, 11339, -1, + 11340, 11340, 11340, -1, 11341, 11341, 11341, -1, + 11342, 11342, 11342, -1, 11343, 11343, 11343, -1, + 11344, 11344, 11344, -1, 11345, 11345, 11345, -1, + 11346, 11346, 11346, -1, 11347, 11347, 11347, -1, + 11348, 11348, 11348, -1, 11349, 11349, 11349, -1, + 11350, 11350, 11350, -1, 11351, 11351, 11351, -1, + 11352, 11352, 11352, -1, 11353, 11353, 11353, -1, + 11354, 11354, 11354, -1, 11355, 11355, 11355, -1, + 11356, 11356, 11356, -1, 11357, 11357, 11357, -1, + 11358, 11358, 11358, -1, 11359, 11359, 11359, -1, + 11360, 11360, 11360, -1, 11361, 11361, 11361, -1, + 11362, 11362, 11362, -1, 11363, 11363, 11363, -1, + 11364, 11364, 11364, -1, 11365, 11365, 11365, -1, + 11366, 11366, 11366, -1, 11367, 11367, 11367, -1, + 11368, 11368, 11368, -1, 11369, 11369, 11369, -1, + 11370, 11370, 11370, -1, 11371, 11371, 11371, -1, + 11372, 11372, 11372, -1, 11373, 11373, 11373, -1, + 11374, 11374, 11374, -1, 11375, 11375, 11375, -1, + 11376, 11376, 11376, -1, 11377, 11377, 11377, -1, + 11378, 11378, 11378, -1, 11379, 11379, 11379, -1, + 11380, 11380, 11380, -1, 11381, 11381, 11381, -1, + 11382, 11382, 11382, -1, 11383, 11383, 11383, -1, + 11384, 11384, 11384, -1, 11385, 11385, 11385, -1, + 11386, 11386, 11386, -1, 11387, 11387, 11387, -1, + 11388, 11388, 11388, -1, 11389, 11389, 11389, -1, + 11390, 11390, 11390, -1, 11391, 11391, 11391, -1, + 11392, 11392, 11392, -1, 11393, 11393, 11393, -1, + 11394, 11394, 11394, -1, 11395, 11395, 11395, -1, + 11396, 11396, 11396, -1, 11397, 11397, 11397, -1, + 11398, 11398, 11398, -1, 11399, 11399, 11399, -1, + 11400, 11400, 11400, -1, 11401, 11401, 11401, -1, + 11402, 11402, 11402, -1, 11403, 11403, 11403, -1, + 11404, 11404, 11404, -1, 11405, 11405, 11405, -1, + 11406, 11406, 11406, -1, 11407, 11407, 11407, -1, + 11408, 11408, 11408, -1, 11409, 11409, 11409, -1, + 11410, 11410, 11410, -1, 11411, 11411, 11411, -1, + 11412, 11412, 11412, -1, 11413, 11413, 11413, -1, + 11414, 11414, 11414, -1, 11415, 11415, 11415, -1, + 11416, 11416, 11416, -1, 11417, 11417, 11417, -1, + 11418, 11418, 11418, -1, 11419, 11419, 11419, -1, + 11420, 11420, 11420, -1, 11421, 11421, 11421, -1, + 11422, 11422, 11422, -1, 11423, 11423, 11423, -1, + 11424, 11424, 11424, -1, 11425, 11425, 11425, -1, + 11426, 11426, 11426, -1, 11427, 11427, 11427, -1, + 11428, 11428, 11428, -1, 11429, 11429, 11429, -1, + 11430, 11430, 11430, -1, 11431, 11431, 11431, -1, + 11432, 11432, 11432, -1, 11433, 11433, 11433, -1, + 11434, 11434, 11434, -1, 11435, 11435, 11435, -1, + 11436, 11436, 11436, -1, 11437, 11437, 11437, -1, + 11438, 11438, 11438, -1, 11439, 11439, 11439, -1, + 11440, 11440, 11440, -1, 11441, 11441, 11441, -1, + 11442, 11442, 11442, -1, 11443, 11443, 11443, -1, + 11444, 11444, 11444, -1, 11445, 11445, 11445, -1, + 11446, 11446, 11446, -1, 11447, 11447, 11447, -1, + 11448, 11448, 11448, -1, 11449, 11449, 11449, -1, + 11450, 11450, 11450, -1, 11451, 11451, 11451, -1, + 11452, 11452, 11452, -1, 11453, 11453, 11453, -1, + 11454, 11454, 11454, -1, 11455, 11455, 11455, -1, + 11456, 11456, 11456, -1, 11457, 11457, 11457, -1, + 11458, 11458, 11458, -1, 11459, 11459, 11459, -1, + 11460, 11460, 11460, -1, 11461, 11461, 11461, -1, + 11462, 11462, 11462, -1, 11463, 11463, 11463, -1, + 11464, 11464, 11464, -1, 11465, 11465, 11465, -1, + 11466, 11466, 11466, -1, 11467, 11467, 11467, -1, + 11468, 11468, 11468, -1, 11469, 11469, 11469, -1, + 11470, 11470, 11470, -1, 11471, 11471, 11471, -1, + 11472, 11472, 11472, -1, 11473, 11473, 11473, -1, + 11474, 11474, 11474, -1, 11475, 11475, 11475, -1, + 11476, 11476, 11476, -1, 11477, 11477, 11477, -1, + 11478, 11478, 11478, -1, 11479, 11479, 11479, -1, + 11480, 11480, 11480, -1, 11481, 11481, 11481, -1, + 11482, 11482, 11482, -1, 11483, 11483, 11483, -1, + 11484, 11484, 11484, -1, 11485, 11485, 11485, -1, + 11486, 11486, 11486, -1, 11487, 11487, 11487, -1, + 11488, 11488, 11488, -1, 11489, 11489, 11489, -1, + 11490, 11490, 11490, -1, 11491, 11491, 11491, -1, + 11492, 11492, 11492, -1, 11493, 11493, 11493, -1, + 11494, 11494, 11494, -1, 11495, 11495, 11495, -1, + 11496, 11496, 11496, -1, 11497, 11497, 11497, -1, + 11498, 11498, 11498, -1, 11499, 11499, 11499, -1, + 11500, 11500, 11500, -1, 11501, 11501, 11501, -1, + 11502, 11502, 11502, -1, 11503, 11503, 11503, -1, + 11504, 11504, 11504, -1, 11505, 11505, 11505, -1, + 11506, 11506, 11506, -1, 11507, 11507, 11507, -1, + 11508, 11508, 11508, -1, 11509, 11509, 11509, -1, + 11510, 11510, 11510, -1, 11511, 11511, 11511, -1, + 11512, 11512, 11512, -1, 11513, 11513, 11513, -1, + 11514, 11514, 11514, -1, 11515, 11515, 11515, -1, + 11516, 11516, 11516, -1, 11517, 11517, 11517, -1, + 11518, 11518, 11518, -1, 11519, 11519, 11519, -1, + 11520, 11520, 11520, -1, 11521, 11521, 11521, -1, + 11522, 11522, 11522, -1, 11523, 11523, 11523, -1, + 11524, 11524, 11524, -1, 11525, 11525, 11525, -1, + 11526, 11526, 11526, -1, 11527, 11527, 11527, -1, + 11528, 11528, 11528, -1, 11529, 11529, 11529, -1, + 11530, 11530, 11530, -1, 11531, 11531, 11531, -1, + 11532, 11532, 11532, -1, 11533, 11533, 11533, -1, + 11534, 11534, 11534, -1, 11535, 11535, 11535, -1, + 11536, 11536, 11536, -1, 11537, 11537, 11537, -1, + 11538, 11538, 11538, -1, 11539, 11539, 11539, -1, + 11540, 11540, 11540, -1, 11541, 11541, 11541, -1, + 11542, 11542, 11542, -1, 11543, 11543, 11543, -1, + 11544, 11544, 11544, -1, 11545, 11545, 11545, -1, + 11546, 11546, 11546, -1, 11547, 11547, 11547, -1, + 11548, 11548, 11548, -1, 11549, 11549, 11549, -1, + 11550, 11550, 11550, -1, 11551, 11551, 11551, -1, + 11552, 11552, 11552, -1, 11553, 11553, 11553, -1, + 11554, 11554, 11554, -1, 11555, 11555, 11555, -1, + 11556, 11556, 11556, -1, 11557, 11557, 11557, -1, + 11558, 11558, 11558, -1, 11559, 11559, 11559, -1, + 11560, 11560, 11560, -1, 11561, 11561, 11561, -1, + 11562, 11562, 11562, -1, 11563, 11563, 11563, -1, + 11564, 11564, 11564, -1, 11565, 11565, 11565, -1, + 11566, 11566, 11566, -1, 11567, 11567, 11567, -1, + 11568, 11568, 11568, -1, 11569, 11569, 11569, -1, + 11570, 11570, 11570, -1, 11571, 11571, 11571, -1, + 11572, 11572, 11572, -1, 11573, 11573, 11573, -1, + 11574, 11574, 11574, -1, 11575, 11575, 11575, -1, + 11576, 11576, 11576, -1, 11577, 11577, 11577, -1, + 11578, 11578, 11578, -1, 11579, 11579, 11579, -1, + 11580, 11580, 11580, -1, 11581, 11581, 11581, -1, + 11582, 11582, 11582, -1, 11583, 11583, 11583, -1, + 11584, 11584, 11584, -1, 11585, 11585, 11585, -1, + 11586, 11586, 11586, -1, 11587, 11587, 11587, -1, + 11588, 11588, 11588, -1, 11589, 11589, 11589, -1, + 11590, 11590, 11590, -1, 11591, 11591, 11591, -1, + 11592, 11592, 11592, -1, 11593, 11593, 11593, -1, + 11594, 11594, 11594, -1, 11595, 11595, 11595, -1, + 11596, 11596, 11596, -1, 11597, 11597, 11597, -1, + 11598, 11598, 11598, -1, 11599, 11599, 11599, -1, + 11600, 11600, 11600, -1, 11601, 11601, 11601, -1, + 11602, 11602, 11602, -1, 11603, 11603, 11603, -1, + 11604, 11604, 11604, -1, 11605, 11605, 11605, -1, + 11606, 11606, 11606, -1, 11607, 11607, 11607, -1, + 11608, 11608, 11608, -1, 11609, 11609, 11609, -1, + 11610, 11610, 11610, -1, 11611, 11611, 11611, -1, + 11612, 11612, 11612, -1, 11613, 11613, 11613, -1, + 11614, 11614, 11614, -1, 11615, 11615, 11615, -1, + 11616, 11616, 11616, -1, 11617, 11617, 11617, -1, + 11618, 11618, 11618, -1, 11619, 11619, 11619, -1, + 11620, 11620, 11620, -1, 11621, 11621, 11621, -1, + 11622, 11622, 11622, -1, 11623, 11623, 11623, -1, + 11624, 11624, 11624, -1, 11625, 11625, 11625, -1, + 11626, 11626, 11626, -1, 11627, 11627, 11627, -1, + 11628, 11628, 11628, -1, 11629, 11629, 11629, -1, + 11630, 11630, 11630, -1, 11631, 11631, 11631, -1, + 11632, 11632, 11632, -1, 11633, 11633, 11633, -1, + 11634, 11634, 11634, -1, 11635, 11635, 11635, -1, + 11636, 11636, 11636, -1, 11637, 11637, 11637, -1, + 11638, 11638, 11638, -1, 11639, 11639, 11639, -1, + 11640, 11640, 11640, -1, 11641, 11641, 11641, -1, + 11642, 11642, 11642, -1, 11643, 11643, 11643, -1, + 11644, 11644, 11644, -1, 11645, 11645, 11645, -1, + 11646, 11646, 11646, -1, 11647, 11647, 11647, -1, + 11648, 11648, 11648, -1, 11649, 11649, 11649, -1, + 11650, 11650, 11650, -1, 11651, 11651, 11651, -1, + 11652, 11652, 11652, -1, 11653, 11653, 11653, -1, + 11654, 11654, 11654, -1, 11655, 11655, 11655, -1, + 11656, 11656, 11656, -1, 11657, 11657, 11657, -1, + 11658, 11658, 11658, -1, 11659, 11659, 11659, -1, + 11660, 11660, 11660, -1, 11661, 11661, 11661, -1, + 11662, 11662, 11662, -1, 11663, 11663, 11663, -1, + 11664, 11664, 11664, -1, 11665, 11665, 11665, -1, + 11666, 11666, 11666, -1, 11667, 11667, 11667, -1, + 11668, 11668, 11668, -1, 11669, 11669, 11669, -1, + 11670, 11670, 11670, -1, 11671, 11671, 11671, -1, + 11672, 11672, 11672, -1, 11673, 11673, 11673, -1, + 11674, 11674, 11674, -1, 11675, 11675, 11675, -1, + 11676, 11676, 11676, -1, 11677, 11677, 11677, -1, + 11678, 11678, 11678, -1, 11679, 11679, 11679, -1, + 11680, 11680, 11680, -1, 11681, 11681, 11681, -1, + 11682, 11682, 11682, -1, 11683, 11683, 11683, -1, + 11684, 11684, 11684, -1, 11685, 11685, 11685, -1, + 11686, 11686, 11686, -1, 11687, 11687, 11687, -1, + 11688, 11688, 11688, -1, 11689, 11689, 11689, -1, + 11690, 11690, 11690, -1, 11691, 11691, 11691, -1, + 11692, 11692, 11692, -1, 11693, 11693, 11693, -1, + 11694, 11694, 11694, -1, 11695, 11695, 11695, -1, + 11696, 11696, 11696, -1, 11697, 11697, 11697, -1, + 11698, 11698, 11698, -1, 11699, 11699, 11699, -1, + 11700, 11700, 11700, -1, 11701, 11701, 11701, -1, + 11702, 11702, 11702, -1, 11703, 11703, 11703, -1, + 11704, 11704, 11704, -1, 11705, 11705, 11705, -1, + 11706, 11706, 11706, -1, 11707, 11707, 11707, -1, + 11708, 11708, 11708, -1, 11709, 11709, 11709, -1, + 11710, 11710, 11710, -1, 11711, 11711, 11711, -1, + 11712, 11712, 11712, -1, 11713, 11713, 11713, -1, + 11714, 11714, 11714, -1, 11715, 11715, 11715, -1, + 11716, 11716, 11716, -1, 11717, 11717, 11717, -1, + 11718, 11718, 11718, -1, 11719, 11719, 11719, -1, + 11720, 11720, 11720, -1, 11721, 11721, 11721, -1, + 11722, 11722, 11722, -1, 11723, 11723, 11723, -1, + 11724, 11724, 11724, -1, 11725, 11725, 11725, -1, + 11726, 11726, 11726, -1, 11727, 11727, 11727, -1, + 11728, 11728, 11728, -1, 11729, 11729, 11729, -1, + 11730, 11730, 11730, -1, 11731, 11731, 11731, -1, + 11732, 11732, 11732, -1, 11733, 11733, 11733, -1, + 11734, 11734, 11734, -1, 11735, 11735, 11735, -1, + 11736, 11736, 11736, -1, 11737, 11737, 11737, -1, + 11738, 11738, 11738, -1, 11739, 11739, 11739, -1, + 11740, 11740, 11740, -1, 11741, 11741, 11741, -1, + 11742, 11742, 11742, -1, 11743, 11743, 11743, -1, + 11744, 11744, 11744, -1, 11745, 11745, 11745, -1, + 11746, 11746, 11746, -1, 11747, 11747, 11747, -1, + 11748, 11748, 11748, -1, 11749, 11749, 11749, -1, + 11750, 11750, 11750, -1, 11751, 11751, 11751, -1, + 11752, 11752, 11752, -1, 11753, 11753, 11753, -1, + 11754, 11754, 11754, -1, 11755, 11755, 11755, -1, + 11756, 11756, 11756, -1, 11757, 11757, 11757, -1, + 11758, 11758, 11758, -1, 11759, 11759, 11759, -1, + 11760, 11760, 11760, -1, 11761, 11761, 11761, -1, + 11762, 11762, 11762, -1, 11763, 11763, 11763, -1, + 11764, 11764, 11764, -1, 11765, 11765, 11765, -1, + 11766, 11766, 11766, -1, 11767, 11767, 11767, -1, + 11768, 11768, 11768, -1, 11769, 11769, 11769, -1, + 11770, 11770, 11770, -1, 11771, 11771, 11771, -1, + 11772, 11772, 11772, -1, 11773, 11773, 11773, -1, + 11774, 11774, 11774, -1, 11775, 11775, 11775, -1, + 11776, 11776, 11776, -1, 11777, 11777, 11777, -1, + 11778, 11778, 11778, -1, 11779, 11779, 11779, -1, + 11780, 11780, 11780, -1, 11781, 11781, 11781, -1, + 11782, 11782, 11782, -1, 11783, 11783, 11783, -1, + 11784, 11784, 11784, -1, 11785, 11785, 11785, -1, + 11786, 11786, 11786, -1, 11787, 11787, 11787, -1, + 11788, 11788, 11788, -1, 11789, 11789, 11789, -1, + 11790, 11790, 11790, -1, 11791, 11791, 11791, -1, + 11792, 11792, 11792, -1, 11793, 11793, 11793, -1, + 11794, 11794, 11794, -1, 11795, 11795, 11795, -1, + 11796, 11796, 11796, -1, 11797, 11797, 11797, -1, + 11798, 11798, 11798, -1, 11799, 11799, 11799, -1, + 11800, 11800, 11800, -1, 11801, 11801, 11801, -1, + 11802, 11802, 11802, -1, 11803, 11803, 11803, -1, + 11804, 11804, 11804, -1, 11805, 11805, 11805, -1, + 11806, 11806, 11806, -1, 11807, 11807, 11807, -1, + 11808, 11808, 11808, -1, 11809, 11809, 11809, -1, + 11810, 11810, 11810, -1, 11811, 11811, 11811, -1, + 11812, 11812, 11812, -1, 11813, 11813, 11813, -1, + 11814, 11814, 11814, -1, 11815, 11815, 11815, -1, + 11816, 11816, 11816, -1, 11817, 11817, 11817, -1, + 11818, 11818, 11818, -1, 11819, 11819, 11819, -1, + 11820, 11820, 11820, -1, 11821, 11821, 11821, -1, + 11822, 11822, 11822, -1, 11823, 11823, 11823, -1, + 11824, 11824, 11824, -1, 11825, 11825, 11825, -1, + 11826, 11826, 11826, -1, 11827, 11827, 11827, -1, + 11828, 11828, 11828, -1, 11829, 11829, 11829, -1, + 11830, 11830, 11830, -1, 11831, 11831, 11831, -1, + 11832, 11832, 11832, -1, 11833, 11833, 11833, -1, + 11834, 11834, 11834, -1, 11835, 11835, 11835, -1, + 11836, 11836, 11836, -1, 11837, 11837, 11837, -1, + 11838, 11838, 11838, -1, 11839, 11839, 11839, -1, + 11840, 11840, 11840, -1, 11841, 11841, 11841, -1, + 11842, 11842, 11842, -1, 11843, 11843, 11843, -1, + 11844, 11844, 11844, -1, 11845, 11845, 11845, -1, + 11846, 11846, 11846, -1, 11847, 11847, 11847, -1, + 11848, 11848, 11848, -1, 11849, 11849, 11849, -1, + 11850, 11850, 11850, -1, 11851, 11851, 11851, -1, + 11852, 11852, 11852, -1, 11853, 11853, 11853, -1, + 11854, 11854, 11854, -1, 11855, 11855, 11855, -1, + 11856, 11856, 11856, -1, 11857, 11857, 11857, -1, + 11858, 11858, 11858, -1, 11859, 11859, 11859, -1, + 11860, 11860, 11860, -1, 11861, 11861, 11861, -1, + 11862, 11862, 11862, -1, 11863, 11863, 11863, -1, + 11864, 11864, 11864, -1, 11865, 11865, 11865, -1, + 11866, 11866, 11866, -1, 11867, 11867, 11867, -1, + 11868, 11868, 11868, -1, 11869, 11869, 11869, -1, + 11870, 11870, 11870, -1, 11871, 11871, 11871, -1, + 11872, 11872, 11872, -1, 11873, 11873, 11873, -1, + 11874, 11874, 11874, -1, 11875, 11875, 11875, -1, + 11876, 11876, 11876, -1, 11877, 11877, 11877, -1, + 11878, 11878, 11878, -1, 11879, 11879, 11879, -1, + 11880, 11880, 11880, -1, 11881, 11881, 11881, -1, + 11882, 11882, 11882, -1, 11883, 11883, 11883, -1, + 11884, 11884, 11884, -1, 11885, 11885, 11885, -1, + 11886, 11886, 11886, -1, 11887, 11887, 11887, -1, + 11888, 11888, 11888, -1, 11889, 11889, 11889, -1, + 11890, 11890, 11890, -1, 11891, 11891, 11891, -1, + 11892, 11892, 11892, -1, 11893, 11893, 11893, -1, + 11894, 11894, 11894, -1, 11895, 11895, 11895, -1, + 11896, 11896, 11896, -1, 11897, 11897, 11897, -1, + 11898, 11898, 11898, -1, 11899, 11899, 11899, -1, + 11900, 11900, 11900, -1, 11901, 11901, 11901, -1, + 11902, 11902, 11902, -1, 11903, 11903, 11903, -1, + 11904, 11904, 11904, -1, 11905, 11905, 11905, -1, + 11906, 11906, 11906, -1, 11907, 11907, 11907, -1, + 11908, 11908, 11908, -1, 11909, 11909, 11909, -1, + 11910, 11910, 11910, -1, 11911, 11911, 11911, -1, + 11912, 11912, 11912, -1, 11913, 11913, 11913, -1, + 11914, 11914, 11914, -1, 11915, 11915, 11915, -1, + 11916, 11916, 11916, -1, 11917, 11917, 11917, -1, + 11918, 11918, 11918, -1, 11919, 11919, 11919, -1, + 11920, 11920, 11920, -1, 11921, 11921, 11921, -1, + 11922, 11922, 11922, -1, 11923, 11923, 11923, -1, + 11924, 11924, 11924, -1, 11925, 11925, 11925, -1, + 11926, 11926, 11926, -1, 11927, 11927, 11927, -1, + 11928, 11928, 11928, -1, 11929, 11929, 11929, -1, + 11930, 11930, 11930, -1, 11931, 11931, 11931, -1, + 11932, 11932, 11932, -1, 11933, 11933, 11933, -1, + 11934, 11934, 11934, -1, 11935, 11935, 11935, -1, + 11936, 11936, 11936, -1, 11937, 11937, 11937, -1, + 11938, 11938, 11938, -1, 11939, 11939, 11939, -1, + 11940, 11940, 11940, -1, 11941, 11941, 11941, -1, + 11942, 11942, 11942, -1, 11943, 11943, 11943, -1, + 11944, 11944, 11944, -1, 11945, 11945, 11945, -1, + 11946, 11946, 11946, -1, 11947, 11947, 11947, -1, + 11948, 11948, 11948, -1, 11949, 11949, 11949, -1, + 11950, 11950, 11950, -1, 11951, 11951, 11951, -1, + 11952, 11952, 11952, -1, 11953, 11953, 11953, -1, + 11954, 11954, 11954, -1, 11955, 11955, 11955, -1, + 11956, 11956, 11956, -1, 11957, 11957, 11957, -1, + 11958, 11958, 11958, -1, 11959, 11959, 11959, -1, + 11960, 11960, 11960, -1, 11961, 11961, 11961, -1, + 11962, 11962, 11962, -1, 11963, 11963, 11963, -1, + 11964, 11964, 11964, -1, 11965, 11965, 11965, -1, + 11966, 11966, 11966, -1, 11967, 11967, 11967, -1, + 11968, 11968, 11968, -1, 11969, 11969, 11969, -1, + 11970, 11970, 11970, -1, 11971, 11971, 11971, -1, + 11972, 11972, 11972, -1, 11973, 11973, 11973, -1, + 11974, 11974, 11974, -1, 11975, 11975, 11975, -1, + 11976, 11976, 11976, -1, 11977, 11977, 11977, -1, + 11978, 11978, 11978, -1, 11979, 11979, 11979, -1, + 11980, 11980, 11980, -1, 11981, 11981, 11981, -1, + 11982, 11982, 11982, -1, 11983, 11983, 11983, -1, + 11984, 11984, 11984, -1, 11985, 11985, 11985, -1, + 11986, 11986, 11986, -1, 11987, 11987, 11987, -1, + 11988, 11988, 11988, -1, 11989, 11989, 11989, -1, + 11990, 11990, 11990, -1, 11991, 11991, 11991, -1, + 11992, 11992, 11992, -1, 11993, 11993, 11993, -1, + 11994, 11994, 11994, -1, 11995, 11995, 11995, -1, + 11996, 11996, 11996, -1, 11997, 11997, 11997, -1, + 11998, 11998, 11998, -1, 11999, 11999, 11999, -1, + 12000, 12000, 12000, -1, 12001, 12001, 12001, -1, + 12002, 12002, 12002, -1, 12003, 12003, 12003, -1, + 12004, 12004, 12004, -1, 12005, 12005, 12005, -1, + 12006, 12006, 12006, -1, 12007, 12007, 12007, -1, + 12008, 12008, 12008, -1, 12009, 12009, 12009, -1, + 12010, 12010, 12010, -1, 12011, 12011, 12011, -1, + 12012, 12012, 12012, -1, 12013, 12013, 12013, -1, + 12014, 12014, 12014, -1, 12015, 12015, 12015, -1, + 12016, 12016, 12016, -1, 12017, 12017, 12017, -1, + 12018, 12018, 12018, -1, 12019, 12019, 12019, -1, + 12020, 12020, 12020, -1, 12021, 12021, 12021, -1, + 12022, 12022, 12022, -1, 12023, 12023, 12023, -1, + 12024, 12024, 12024, -1, 12025, 12025, 12025, -1, + 12026, 12026, 12026, -1, 12027, 12027, 12027, -1, + 12028, 12028, 12028, -1, 12029, 12029, 12029, -1, + 12030, 12030, 12030, -1, 12031, 12031, 12031, -1, + 12032, 12032, 12032, -1, 12033, 12033, 12033, -1, + 12034, 12034, 12034, -1, 12035, 12035, 12035, -1, + 12036, 12036, 12036, -1, 12037, 12037, 12037, -1, + 12038, 12038, 12038, -1, 12039, 12039, 12039, -1, + 12040, 12040, 12040, -1, 12041, 12041, 12041, -1, + 12042, 12042, 12042, -1, 12043, 12043, 12043, -1, + 12044, 12044, 12044, -1, 12045, 12045, 12045, -1, + 12046, 12046, 12046, -1, 12047, 12047, 12047, -1, + 12048, 12048, 12048, -1, 12049, 12049, 12049, -1, + 12050, 12050, 12050, -1, 12051, 12051, 12051, -1, + 12052, 12052, 12052, -1, 12053, 12053, 12053, -1, + 12054, 12054, 12054, -1, 12055, 12055, 12055, -1, + 12056, 12056, 12056, -1, 12057, 12057, 12057, -1, + 12058, 12058, 12058, -1, 12059, 12059, 12059, -1, + 12060, 12060, 12060, -1, 12061, 12061, 12061, -1, + 12062, 12062, 12062, -1, 12063, 12063, 12063, -1, + 12064, 12064, 12064, -1, 12065, 12065, 12065, -1, + 12066, 12066, 12066, -1, 12067, 12067, 12067, -1, + 12068, 12068, 12068, -1, 12069, 12069, 12069, -1, + 12070, 12070, 12070, -1, 12071, 12071, 12071, -1, + 12072, 12072, 12072, -1, 12073, 12073, 12073, -1, + 12074, 12074, 12074, -1, 12075, 12075, 12075, -1, + 12076, 12076, 12076, -1, 12077, 12077, 12077, -1, + 12078, 12078, 12078, -1, 12079, 12079, 12079, -1, + 12080, 12080, 12080, -1, 12081, 12081, 12081, -1, + 12082, 12082, 12082, -1, 12083, 12083, 12083, -1, + 12084, 12084, 12084, -1, 12085, 12085, 12085, -1, + 12086, 12086, 12086, -1, 12087, 12087, 12087, -1, + 12088, 12088, 12088, -1, 12089, 12089, 12089, -1, + 12090, 12090, 12090, -1, 12091, 12091, 12091, -1, + 12092, 12092, 12092, -1, 12093, 12093, 12093, -1, + 12094, 12094, 12094, -1, 12095, 12095, 12095, -1, + 12096, 12096, 12096, -1, 12097, 12097, 12097, -1, + 12098, 12098, 12098, -1, 12099, 12099, 12099, -1, + 12100, 12100, 12100, -1, 12101, 12101, 12101, -1, + 12102, 12102, 12102, -1, 12103, 12103, 12103, -1, + 12104, 12104, 12104, -1, 12105, 12105, 12105, -1, + 12106, 12106, 12106, -1, 12107, 12107, 12107, -1, + 12108, 12108, 12108, -1, 12109, 12109, 12109, -1, + 12110, 12110, 12110, -1, 12111, 12111, 12111, -1, + 12112, 12112, 12112, -1, 12113, 12113, 12113, -1, + 12114, 12114, 12114, -1, 12115, 12115, 12115, -1, + 12116, 12116, 12116, -1, 12117, 12117, 12117, -1, + 12118, 12118, 12118, -1, 12119, 12119, 12119, -1, + 12120, 12120, 12120, -1, 12121, 12121, 12121, -1, + 12122, 12122, 12122, -1, 12123, 12123, 12123, -1, + 12124, 12124, 12124, -1, 12125, 12125, 12125, -1, + 12126, 12126, 12126, -1, 12127, 12127, 12127, -1, + 12128, 12128, 12128, -1, 12129, 12129, 12129, -1, + 12130, 12130, 12130, -1, 12131, 12131, 12131, -1, + 12132, 12132, 12132, -1, 12133, 12133, 12133, -1, + 12134, 12134, 12134, -1, 12135, 12135, 12135, -1, + 12136, 12136, 12136, -1, 12137, 12137, 12137, -1, + 12138, 12138, 12138, -1, 12139, 12139, 12139, -1, + 12140, 12140, 12140, -1, 12141, 12141, 12141, -1, + 12142, 12142, 12142, -1, 12143, 12143, 12143, -1, + 12144, 12144, 12144, -1, 12145, 12145, 12145, -1, + 12146, 12146, 12146, -1, 12147, 12147, 12147, -1, + 12148, 12148, 12148, -1, 12149, 12149, 12149, -1, + 12150, 12150, 12150, -1, 12151, 12151, 12151, -1, + 12152, 12152, 12152, -1, 12153, 12153, 12153, -1, + 12154, 12154, 12154, -1, 12155, 12155, 12155, -1, + 12156, 12156, 12156, -1, 12157, 12157, 12157, -1, + 12158, 12158, 12158, -1, 12159, 12159, 12159, -1, + 12160, 12160, 12160, -1, 12161, 12161, 12161, -1, + 12162, 12162, 12162, -1, 12163, 12163, 12163, -1, + 12164, 12164, 12164, -1, 12165, 12165, 12165, -1, + 12166, 12166, 12166, -1, 12167, 12167, 12167, -1, + 12168, 12168, 12168, -1, 12169, 12169, 12169, -1, + 12170, 12170, 12170, -1, 12171, 12171, 12171, -1, + 12172, 12172, 12172, -1, 12173, 12173, 12173, -1, + 12174, 12174, 12174, -1, 12175, 12175, 12175, -1, + 12176, 12176, 12176, -1, 12177, 12177, 12177, -1, + 12178, 12178, 12178, -1, 12179, 12179, 12179, -1, + 12180, 12180, 12180, -1, 12181, 12181, 12181, -1, + 12182, 12182, 12182, -1, 12183, 12183, 12183, -1, + 12184, 12184, 12184, -1, 12185, 12185, 12185, -1, + 12186, 12186, 12186, -1, 12187, 12187, 12187, -1, + 12188, 12188, 12188, -1, 12189, 12189, 12189, -1, + 12190, 12190, 12190, -1, 12191, 12191, 12191, -1, + 12192, 12192, 12192, -1, 12193, 12193, 12193, -1, + 12194, 12194, 12194, -1, 12195, 12195, 12195, -1, + 12196, 12196, 12196, -1, 12197, 12197, 12197, -1, + 12198, 12198, 12198, -1, 12199, 12199, 12199, -1, + 12200, 12200, 12200, -1, 12201, 12201, 12201, -1, + 12202, 12202, 12202, -1, 12203, 12203, 12203, -1, + 12204, 12204, 12204, -1, 12205, 12205, 12205, -1, + 12206, 12206, 12206, -1, 12207, 12207, 12207, -1, + 12208, 12208, 12208, -1, 12209, 12209, 12209, -1, + 12210, 12210, 12210, -1, 12211, 12211, 12211, -1, + 12212, 12212, 12212, -1, 12213, 12213, 12213, -1, + 12214, 12214, 12214, -1, 12215, 12215, 12215, -1, + 12216, 12216, 12216, -1, 12217, 12217, 12217, -1, + 12218, 12218, 12218, -1, 12219, 12219, 12219, -1, + 12220, 12220, 12220, -1, 12221, 12221, 12221, -1, + 12222, 12222, 12222, -1, 12223, 12223, 12223, -1, + 12224, 12224, 12224, -1, 12225, 12225, 12225, -1, + 12226, 12226, 12226, -1, 12227, 12227, 12227, -1, + 12228, 12228, 12228, -1, 12229, 12229, 12229, -1, + 12230, 12230, 12230, -1, 12231, 12231, 12231, -1, + 12232, 12232, 12232, -1, 12233, 12233, 12233, -1, + 12234, 12234, 12234, -1, 12235, 12235, 12235, -1, + 12236, 12236, 12236, -1, 12237, 12237, 12237, -1, + 12238, 12238, 12238, -1, 12239, 12239, 12239, -1, + 12240, 12240, 12240, -1, 12241, 12241, 12241, -1, + 12242, 12242, 12242, -1, 12243, 12243, 12243, -1, + 12244, 12244, 12244, -1, 12245, 12245, 12245, -1, + 12246, 12246, 12246, -1, 12247, 12247, 12247, -1, + 12248, 12248, 12248, -1, 12249, 12249, 12249, -1, + 12250, 12250, 12250, -1, 12251, 12251, 12251, -1, + 12252, 12252, 12252, -1, 12253, 12253, 12253, -1, + 12254, 12254, 12254, -1, 12255, 12255, 12255, -1, + 12256, 12256, 12256, -1, 12257, 12257, 12257, -1, + 12258, 12258, 12258, -1, 12259, 12259, 12259, -1, + 12260, 12260, 12260, -1, 12261, 12261, 12261, -1, + 12262, 12262, 12262, -1, 12263, 12263, 12263, -1, + 12264, 12264, 12264, -1, 12265, 12265, 12265, -1, + 12266, 12266, 12266, -1, 12267, 12267, 12267, -1, + 12268, 12268, 12268, -1, 12269, 12269, 12269, -1, + 12270, 12270, 12270, -1, 12271, 12271, 12271, -1, + 12272, 12272, 12272, -1, 12273, 12273, 12273, -1, + 12274, 12274, 12274, -1, 12275, 12275, 12275, -1, + 12276, 12276, 12276, -1, 12277, 12277, 12277, -1, + 12278, 12278, 12278, -1, 12279, 12279, 12279, -1, + 12280, 12280, 12280, -1, 12281, 12281, 12281, -1, + 12282, 12282, 12282, -1, 12283, 12283, 12283, -1, + 12284, 12284, 12284, -1, 12285, 12285, 12285, -1, + 12286, 12286, 12286, -1, 12287, 12287, 12287, -1, + 12288, 12288, 12288, -1, 12289, 12289, 12289, -1, + 12290, 12290, 12290, -1, 12291, 12291, 12291, -1, + 12292, 12292, 12292, -1, 12293, 12293, 12293, -1, + 12294, 12294, 12294, -1, 12295, 12295, 12295, -1, + 12296, 12296, 12296, -1, 12297, 12297, 12297, -1, + 12298, 12298, 12298, -1, 12299, 12299, 12299, -1, + 12300, 12300, 12300, -1, 12301, 12301, 12301, -1, + 12302, 12302, 12302, -1, 12303, 12303, 12303, -1, + 12304, 12304, 12304, -1, 12305, 12305, 12305, -1, + 12306, 12306, 12306, -1, 12307, 12307, 12307, -1, + 12308, 12308, 12308, -1, 12309, 12309, 12309, -1, + 12310, 12310, 12310, -1, 12311, 12311, 12311, -1, + 12312, 12312, 12312, -1, 12313, 12313, 12313, -1, + 12314, 12314, 12314, -1, 12315, 12315, 12315, -1, + 12316, 12316, 12316, -1, 12317, 12317, 12317, -1, + 12318, 12318, 12318, -1, 12319, 12319, 12319, -1, + 12320, 12320, 12320, -1, 12321, 12321, 12321, -1, + 12322, 12322, 12322, -1, 12323, 12323, 12323, -1, + 12324, 12324, 12324, -1, 12325, 12325, 12325, -1, + 12326, 12326, 12326, -1, 12327, 12327, 12327, -1, + 12328, 12328, 12328, -1, 12329, 12329, 12329, -1, + 12330, 12330, 12330, -1, 12331, 12331, 12331, -1, + 12332, 12332, 12332, -1, 12333, 12333, 12333, -1, + 12334, 12334, 12334, -1, 12335, 12335, 12335, -1, + 12336, 12336, 12336, -1, 12337, 12337, 12337, -1, + 12338, 12338, 12338, -1, 12339, 12339, 12339, -1, + 12340, 12340, 12340, -1, 12341, 12341, 12341, -1, + 12342, 12342, 12342, -1, 12343, 12343, 12343, -1, + 12344, 12344, 12344, -1, 12345, 12345, 12345, -1, + 12346, 12346, 12346, -1, 12347, 12347, 12347, -1, + 12348, 12348, 12348, -1, 12349, 12349, 12349, -1, + 12350, 12350, 12350, -1, 12351, 12351, 12351, -1, + 12352, 12352, 12352, -1, 12353, 12353, 12353, -1, + 12354, 12354, 12354, -1, 12355, 12355, 12355, -1, + 12356, 12356, 12356, -1, 12357, 12357, 12357, -1, + 12358, 12358, 12358, -1, 12359, 12359, 12359, -1, + 12360, 12360, 12360, -1, 12361, 12361, 12361, -1, + 12362, 12362, 12362, -1, 12363, 12363, 12363, -1, + 12364, 12364, 12364, -1, 12365, 12365, 12365, -1, + 12366, 12366, 12366, -1, 12367, 12367, 12367, -1, + 12368, 12368, 12368, -1, 12369, 12369, 12369, -1, + 12370, 12370, 12370, -1, 12371, 12371, 12371, -1, + 12372, 12372, 12372, -1, 12373, 12373, 12373, -1, + 12374, 12374, 12374, -1, 12375, 12375, 12375, -1, + 12376, 12376, 12376, -1, 12377, 12377, 12377, -1, + 12378, 12378, 12378, -1, 12379, 12379, 12379, -1, + 12380, 12380, 12380, -1, 12381, 12381, 12381, -1, + 12382, 12382, 12382, -1, 12383, 12383, 12383, -1, + 12384, 12384, 12384, -1, 12385, 12385, 12385, -1, + 12386, 12386, 12386, -1, 12387, 12387, 12387, -1, + 12388, 12388, 12388, -1, 12389, 12389, 12389, -1, + 12390, 12390, 12390, -1, 12391, 12391, 12391, -1, + 12392, 12392, 12392, -1, 12393, 12393, 12393, -1, + 12394, 12394, 12394, -1, 12395, 12395, 12395, -1, + 12396, 12396, 12396, -1, 12397, 12397, 12397, -1, + 12398, 12398, 12398, -1, 12399, 12399, 12399, -1, + 12400, 12400, 12400, -1, 12401, 12401, 12401, -1, + 12402, 12402, 12402, -1, 12403, 12403, 12403, -1, + 12404, 12404, 12404, -1, 12405, 12405, 12405, -1, + 12406, 12406, 12406, -1, 12407, 12407, 12407, -1, + 12408, 12408, 12408, -1, 12409, 12409, 12409, -1, + 12410, 12410, 12410, -1, 12411, 12411, 12411, -1, + 12412, 12412, 12412, -1, 12413, 12413, 12413, -1, + 12414, 12414, 12414, -1, 12415, 12415, 12415, -1, + 12416, 12416, 12416, -1, 12417, 12417, 12417, -1, + 12418, 12418, 12418, -1, 12419, 12419, 12419, -1, + 12420, 12420, 12420, -1, 12421, 12421, 12421, -1, + 12422, 12422, 12422, -1, 12423, 12423, 12423, -1, + 12424, 12424, 12424, -1, 12425, 12425, 12425, -1, + 12426, 12426, 12426, -1, 12427, 12427, 12427, -1, + 12428, 12428, 12428, -1, 12429, 12429, 12429, -1, + 12430, 12430, 12430, -1, 12431, 12431, 12431, -1, + 12432, 12432, 12432, -1, 12433, 12433, 12433, -1, + 12434, 12434, 12434, -1, 12435, 12435, 12435, -1, + 12436, 12436, 12436, -1, 12437, 12437, 12437, -1, + 12438, 12438, 12438, -1, 12439, 12439, 12439, -1, + 12440, 12440, 12440, -1, 12441, 12441, 12441, -1, + 12442, 12442, 12442, -1, 12443, 12443, 12443, -1, + 12444, 12444, 12444, -1, 12445, 12445, 12445, -1, + 12446, 12446, 12446, -1, 12447, 12447, 12447, -1, + 12448, 12448, 12448, -1, 12449, 12449, 12449, -1, + 12450, 12450, 12450, -1, 12451, 12451, 12451, -1, + 12452, 12452, 12452, -1, 12453, 12453, 12453, -1, + 12454, 12454, 12454, -1, 12455, 12455, 12455, -1, + 12456, 12456, 12456, -1, 12457, 12457, 12457, -1, + 12458, 12458, 12458, -1, 12459, 12459, 12459, -1, + 12460, 12460, 12460, -1, 12461, 12461, 12461, -1, + 12462, 12462, 12462, -1, 12463, 12463, 12463, -1, + 12464, 12464, 12464, -1, 12465, 12465, 12465, -1, + 12466, 12466, 12466, -1, 12467, 12467, 12467, -1, + 12468, 12468, 12468, -1, 12469, 12469, 12469, -1, + 12470, 12470, 12470, -1, 12471, 12471, 12471, -1, + 12472, 12472, 12472, -1, 12473, 12473, 12473, -1, + 12474, 12474, 12474, -1, 12475, 12475, 12475, -1, + 12476, 12476, 12476, -1, 12477, 12477, 12477, -1, + 12478, 12478, 12478, -1, 12479, 12479, 12479, -1, + 12480, 12480, 12480, -1, 12481, 12481, 12481, -1, + 12482, 12482, 12482, -1, 12483, 12483, 12483, -1, + 12484, 12484, 12484, -1, 12485, 12485, 12485, -1, + 12486, 12486, 12486, -1, 12487, 12487, 12487, -1, + 12488, 12488, 12488, -1, 12489, 12489, 12489, -1, + 12490, 12490, 12490, -1, 12491, 12491, 12491, -1, + 12492, 12492, 12492, -1, 12493, 12493, 12493, -1, + 12494, 12494, 12494, -1, 12495, 12495, 12495, -1, + 12496, 12496, 12496, -1, 12497, 12497, 12497, -1, + 12498, 12498, 12498, -1, 12499, 12499, 12499, -1, + 12500, 12500, 12500, -1, 12501, 12501, 12501, -1, + 12502, 12502, 12502, -1, 12503, 12503, 12503, -1, + 12504, 12504, 12504, -1, 12505, 12505, 12505, -1, + 12506, 12506, 12506, -1, 12507, 12507, 12507, -1, + 12508, 12508, 12508, -1, 12509, 12509, 12509, -1, + 12510, 12510, 12510, -1, 12511, 12511, 12511, -1, + 12512, 12512, 12512, -1, 12513, 12513, 12513, -1, + 12514, 12514, 12514, -1, 12515, 12515, 12515, -1, + 12516, 12516, 12516, -1, 12517, 12517, 12517, -1, + 12518, 12518, 12518, -1, 12519, 12519, 12519, -1, + 12520, 12520, 12520, -1, 12521, 12521, 12521, -1, + 12522, 12522, 12522, -1, 12523, 12523, 12523, -1, + 12524, 12524, 12524, -1, 12525, 12525, 12525, -1, + 12526, 12526, 12526, -1, 12527, 12527, 12527, -1, + 12528, 12528, 12528, -1, 12529, 12529, 12529, -1, + 12530, 12530, 12530, -1, 12531, 12531, 12531, -1, + 12532, 12532, 12532, -1, 12533, 12533, 12533, -1, + 12534, 12534, 12534, -1, 12535, 12535, 12535, -1, + 12536, 12536, 12536, -1, 12537, 12537, 12537, -1, + 12538, 12538, 12538, -1, 12539, 12539, 12539, -1, + 12540, 12540, 12540, -1, 12541, 12541, 12541, -1, + 12542, 12542, 12542, -1, 12543, 12543, 12543, -1, + 12544, 12544, 12544, -1, 12545, 12545, 12545, -1, + 12546, 12546, 12546, -1, 12547, 12547, 12547, -1, + 12548, 12548, 12548, -1, 12549, 12549, 12549, -1, + 12550, 12550, 12550, -1, 12551, 12551, 12551, -1, + 12552, 12552, 12552, -1, 12553, 12553, 12553, -1, + 12554, 12554, 12554, -1, 12555, 12555, 12555, -1, + 12556, 12556, 12556, -1, 12557, 12557, 12557, -1, + 12558, 12558, 12558, -1, 12559, 12559, 12559, -1, + 12560, 12560, 12560, -1, 12561, 12561, 12561, -1, + 12562, 12562, 12562, -1, 12563, 12563, 12563, -1, + 12564, 12564, 12564, -1, 12565, 12565, 12565, -1, + 12566, 12566, 12566, -1, 12567, 12567, 12567, -1, + 12568, 12568, 12568, -1, 12569, 12569, 12569, -1, + 12570, 12570, 12570, -1, 12571, 12571, 12571, -1, + 12572, 12572, 12572, -1, 12573, 12573, 12573, -1, + 12574, 12574, 12574, -1, 12575, 12575, 12575, -1, + 12576, 12576, 12576, -1, 12577, 12577, 12577, -1, + 12578, 12578, 12578, -1, 12579, 12579, 12579, -1, + 12580, 12580, 12580, -1, 12581, 12581, 12581, -1, + 12582, 12582, 12582, -1, 12583, 12583, 12583, -1, + 12584, 12584, 12584, -1, 12585, 12585, 12585, -1, + 12586, 12586, 12586, -1, 12587, 12587, 12587, -1, + 12588, 12588, 12588, -1, 12589, 12589, 12589, -1, + 12590, 12590, 12590, -1, 12591, 12591, 12591, -1, + 12592, 12592, 12592, -1, 12593, 12593, 12593, -1, + 12594, 12594, 12594, -1, 12595, 12595, 12595, -1, + 12596, 12596, 12596, -1, 12597, 12597, 12597, -1, + 12598, 12598, 12598, -1, 12599, 12599, 12599, -1, + 12600, 12600, 12600, -1, 12601, 12601, 12601, -1, + 12602, 12602, 12602, -1, 12603, 12603, 12603, -1, + 12604, 12604, 12604, -1, 12605, 12605, 12605, -1, + 12606, 12606, 12606, -1, 12607, 12607, 12607, -1, + 12608, 12608, 12608, -1, 12609, 12609, 12609, -1, + 12610, 12610, 12610, -1, 12611, 12611, 12611, -1, + 12612, 12612, 12612, -1, 12613, 12613, 12613, -1, + 12614, 12614, 12614, -1, 12615, 12615, 12615, -1, + 12616, 12616, 12616, -1, 12617, 12617, 12617, -1, + 12618, 12618, 12618, -1, 12619, 12619, 12619, -1, + 12620, 12620, 12620, -1, 12621, 12621, 12621, -1, + 12622, 12622, 12622, -1, 12623, 12623, 12623, -1, + 12624, 12624, 12624, -1, 12625, 12625, 12625, -1, + 12626, 12626, 12626, -1, 12627, 12627, 12627, -1, + 12628, 12628, 12628, -1, 12629, 12629, 12629, -1, + 12630, 12630, 12630, -1, 12631, 12631, 12631, -1, + 12632, 12632, 12632, -1, 12633, 12633, 12633, -1, + 12634, 12634, 12634, -1, 12635, 12635, 12635, -1, + 12636, 12636, 12636, -1, 12637, 12637, 12637, -1, + 12638, 12638, 12638, -1, 12639, 12639, 12639, -1, + 12640, 12640, 12640, -1, 12641, 12641, 12641, -1, + 12642, 12642, 12642, -1, 12643, 12643, 12643, -1, + 12644, 12644, 12644, -1, 12645, 12645, 12645, -1, + 12646, 12646, 12646, -1, 12647, 12647, 12647, -1, + 12648, 12648, 12648, -1, 12649, 12649, 12649, -1, + 12650, 12650, 12650, -1, 12651, 12651, 12651, -1, + 12652, 12652, 12652, -1, 12653, 12653, 12653, -1, + 12654, 12654, 12654, -1, 12655, 12655, 12655, -1, + 12656, 12656, 12656, -1, 12657, 12657, 12657, -1, + 12658, 12658, 12658, -1, 12659, 12659, 12659, -1, + 12660, 12660, 12660, -1, 12661, 12661, 12661, -1, + 12662, 12662, 12662, -1, 12663, 12663, 12663, -1, + 12664, 12664, 12664, -1, 12665, 12665, 12665, -1, + 12666, 12666, 12666, -1, 12667, 12667, 12667, -1, + 12668, 12668, 12668, -1, 12669, 12669, 12669, -1, + 12670, 12670, 12670, -1, 12671, 12671, 12671, -1, + 12672, 12672, 12672, -1, 12673, 12673, 12673, -1, + 12674, 12674, 12674, -1, 12675, 12675, 12675, -1, + 12676, 12676, 12676, -1, 12677, 12677, 12677, -1, + 12678, 12678, 12678, -1, 12679, 12679, 12679, -1, + 12680, 12680, 12680, -1, 12681, 12681, 12681, -1, + 12682, 12682, 12682, -1, 12683, 12683, 12683, -1, + 12684, 12684, 12684, -1, 12685, 12685, 12685, -1, + 12686, 12686, 12686, -1, 12687, 12687, 12687, -1, + 12688, 12688, 12688, -1, 12689, 12689, 12689, -1, + 12690, 12690, 12690, -1, 12691, 12691, 12691, -1, + 12692, 12692, 12692, -1, 12693, 12693, 12693, -1, + 12694, 12694, 12694, -1, 12695, 12695, 12695, -1, + 12696, 12696, 12696, -1, 12697, 12697, 12697, -1, + 12698, 12698, 12698, -1, 12699, 12699, 12699, -1, + 12700, 12700, 12700, -1, 12701, 12701, 12701, -1, + 12702, 12702, 12702, -1, 12703, 12703, 12703, -1, + 12704, 12704, 12704, -1, 12705, 12705, 12705, -1, + 12706, 12706, 12706, -1, 12707, 12707, 12707, -1, + 12708, 12708, 12708, -1, 12709, 12709, 12709, -1, + 12710, 12710, 12710, -1, 12711, 12711, 12711, -1, + 12712, 12712, 12712, -1, 12713, 12713, 12713, -1, + 12714, 12714, 12714, -1, 12715, 12715, 12715, -1, + 12716, 12716, 12716, -1, 12717, 12717, 12717, -1, + 12718, 12718, 12718, -1, 12719, 12719, 12719, -1, + 12720, 12720, 12720, -1, 12721, 12721, 12721, -1, + 12722, 12722, 12722, -1, 12723, 12723, 12723, -1, + 12724, 12724, 12724, -1, 12725, 12725, 12725, -1, + 12726, 12726, 12726, -1, 12727, 12727, 12727, -1, + 12728, 12728, 12728, -1, 12729, 12729, 12729, -1, + 12730, 12730, 12730, -1, 12731, 12731, 12731, -1, + 12732, 12732, 12732, -1, 12733, 12733, 12733, -1, + 12734, 12734, 12734, -1, 12735, 12735, 12735, -1, + 12736, 12736, 12736, -1, 12737, 12737, 12737, -1, + 12738, 12738, 12738, -1, 12739, 12739, 12739, -1, + 12740, 12740, 12740, -1, 12741, 12741, 12741, -1, + 12742, 12742, 12742, -1, 12743, 12743, 12743, -1, + 12744, 12744, 12744, -1, 12745, 12745, 12745, -1, + 12746, 12746, 12746, -1, 12747, 12747, 12747, -1, + 12748, 12748, 12748, -1, 12749, 12749, 12749, -1, + 12750, 12750, 12750, -1, 12751, 12751, 12751, -1, + 12752, 12752, 12752, -1, 12753, 12753, 12753, -1, + 12754, 12754, 12754, -1, 12755, 12755, 12755, -1, + 12756, 12756, 12756, -1, 12757, 12757, 12757, -1, + 12758, 12758, 12758, -1, 12759, 12759, 12759, -1, + 12760, 12760, 12760, -1, 12761, 12761, 12761, -1, + 12762, 12762, 12762, -1, 12763, 12763, 12763, -1, + 12764, 12764, 12764, -1, 12765, 12765, 12765, -1, + 12766, 12766, 12766, -1, 12767, 12767, 12767, -1, + 12768, 12768, 12768, -1, 12769, 12769, 12769, -1, + 12770, 12770, 12770, -1, 12771, 12771, 12771, -1, + 12772, 12772, 12772, -1, 12773, 12773, 12773, -1, + 12774, 12774, 12774, -1, 12775, 12775, 12775, -1, + 12776, 12776, 12776, -1, 12777, 12777, 12777, -1, + 12778, 12778, 12778, -1, 12779, 12779, 12779, -1, + 12780, 12780, 12780, -1, 12781, 12781, 12781, -1, + 12782, 12782, 12782, -1, 12783, 12783, 12783, -1, + 12784, 12784, 12784, -1, 12785, 12785, 12785, -1, + 12786, 12786, 12786, -1, 12787, 12787, 12787, -1, + 12788, 12788, 12788, -1, 12789, 12789, 12789, -1, + 12790, 12790, 12790, -1, 12791, 12791, 12791, -1, + 12792, 12792, 12792, -1, 12793, 12793, 12793, -1, + 12794, 12794, 12794, -1, 12795, 12795, 12795, -1, + 12796, 12796, 12796, -1, 12797, 12797, 12797, -1, + 12798, 12798, 12798, -1, 12799, 12799, 12799, -1, + 12800, 12800, 12800, -1, 12801, 12801, 12801, -1, + 12802, 12802, 12802, -1, 12803, 12803, 12803, -1, + 12804, 12804, 12804, -1, 12805, 12805, 12805, -1, + 12806, 12806, 12806, -1, 12807, 12807, 12807, -1, + 12808, 12808, 12808, -1, 12809, 12809, 12809, -1, + 12810, 12810, 12810, -1, 12811, 12811, 12811, -1, + 12812, 12812, 12812, -1, 12813, 12813, 12813, -1, + 12814, 12814, 12814, -1, 12815, 12815, 12815, -1, + 12816, 12816, 12816, -1, 12817, 12817, 12817, -1, + 12818, 12818, 12818, -1, 12819, 12819, 12819, -1, + 12820, 12820, 12820, -1, 12821, 12821, 12821, -1, + 12822, 12822, 12822, -1, 12823, 12823, 12823, -1, + 12824, 12824, 12824, -1, 12825, 12825, 12825, -1, + 12826, 12826, 12826, -1, 12827, 12827, 12827, -1, + 12828, 12828, 12828, -1, 12829, 12829, 12829, -1, + 12830, 12830, 12830, -1, 12831, 12831, 12831, -1, + 12832, 12832, 12832, -1, 12833, 12833, 12833, -1, + 12834, 12834, 12834, -1, 12835, 12835, 12835, -1, + 12836, 12836, 12836, -1, 12837, 12837, 12837, -1, + 12838, 12838, 12838, -1, 12839, 12839, 12839, -1, + 12840, 12840, 12840, -1, 12841, 12841, 12841, -1, + 12842, 12842, 12842, -1, 12843, 12843, 12843, -1, + 12844, 12844, 12844, -1, 12845, 12845, 12845, -1, + 12846, 12846, 12846, -1, 12847, 12847, 12847, -1, + 12848, 12848, 12848, -1, 12849, 12849, 12849, -1, + 12850, 12850, 12850, -1, 12851, 12851, 12851, -1, + 12852, 12852, 12852, -1, 12853, 12853, 12853, -1, + 12854, 12854, 12854, -1, 12855, 12855, 12855, -1, + 12856, 12856, 12856, -1, 12857, 12857, 12857, -1, + 12858, 12858, 12858, -1, 12859, 12859, 12859, -1, + 12860, 12860, 12860, -1, 12861, 12861, 12861, -1, + 12862, 12862, 12862, -1, 12863, 12863, 12863, -1, + 12864, 12864, 12864, -1, 12865, 12865, 12865, -1, + 12866, 12866, 12866, -1, 12867, 12867, 12867, -1, + 12868, 12868, 12868, -1, 12869, 12869, 12869, -1, + 12870, 12870, 12870, -1, 12871, 12871, 12871, -1, + 12872, 12872, 12872, -1, 12873, 12873, 12873, -1, + 12874, 12874, 12874, -1, 12875, 12875, 12875, -1, + 12876, 12876, 12876, -1, 12877, 12877, 12877, -1, + 12878, 12878, 12878, -1, 12879, 12879, 12879, -1, + 12880, 12880, 12880, -1, 12881, 12881, 12881, -1, + 12882, 12882, 12882, -1, 12883, 12883, 12883, -1, + 12884, 12884, 12884, -1, 12885, 12885, 12885, -1, + 12886, 12886, 12886, -1, 12887, 12887, 12887, -1, + 12888, 12888, 12888, -1, 12889, 12889, 12889, -1, + 12890, 12890, 12890, -1, 12891, 12891, 12891, -1, + 12892, 12892, 12892, -1, 12893, 12893, 12893, -1, + 12894, 12894, 12894, -1, 12895, 12895, 12895, -1, + 12896, 12896, 12896, -1, 12897, 12897, 12897, -1, + 12898, 12898, 12898, -1, 12899, 12899, 12899, -1, + 12900, 12900, 12900, -1, 12901, 12901, 12901, -1, + 12902, 12902, 12902, -1, 12903, 12903, 12903, -1, + 12904, 12904, 12904, -1, 12905, 12905, 12905, -1, + 12906, 12906, 12906, -1, 12907, 12907, 12907, -1, + 12908, 12908, 12908, -1, 12909, 12909, 12909, -1, + 12910, 12910, 12910, -1, 12911, 12911, 12911, -1, + 12912, 12912, 12912, -1, 12913, 12913, 12913, -1, + 12914, 12914, 12914, -1, 12915, 12915, 12915, -1, + 12916, 12916, 12916, -1, 12917, 12917, 12917, -1, + 12918, 12918, 12918, -1, 12919, 12919, 12919, -1, + 12920, 12920, 12920, -1, 12921, 12921, 12921, -1, + 12922, 12922, 12922, -1, 12923, 12923, 12923, -1, + 12924, 12924, 12924, -1, 12925, 12925, 12925, -1, + 12926, 12926, 12926, -1, 12927, 12927, 12927, -1, + 12928, 12928, 12928, -1, 12929, 12929, 12929, -1, + 12930, 12930, 12930, -1, 12931, 12931, 12931, -1, + 12932, 12932, 12932, -1, 12933, 12933, 12933, -1, + 12934, 12934, 12934, -1, 12935, 12935, 12935, -1, + 12936, 12936, 12936, -1, 12937, 12937, 12937, -1, + 12938, 12938, 12938, -1, 12939, 12939, 12939, -1, + 12940, 12940, 12940, -1, 12941, 12941, 12941, -1, + 12942, 12942, 12942, -1, 12943, 12943, 12943, -1, + 12944, 12944, 12944, -1, 12945, 12945, 12945, -1, + 12946, 12946, 12946, -1, 12947, 12947, 12947, -1, + 12948, 12948, 12948, -1, 12949, 12949, 12949, -1, + 12950, 12950, 12950, -1, 12951, 12951, 12951, -1, + 12952, 12952, 12952, -1, 12953, 12953, 12953, -1, + 12954, 12954, 12954, -1, 12955, 12955, 12955, -1, + 12956, 12956, 12956, -1, 12957, 12957, 12957, -1, + 12958, 12958, 12958, -1, 12959, 12959, 12959, -1, + 12960, 12960, 12960, -1, 12961, 12961, 12961, -1, + 12962, 12962, 12962, -1, 12963, 12963, 12963, -1, + 12964, 12964, 12964, -1, 12965, 12965, 12965, -1, + 12966, 12966, 12966, -1, 12967, 12967, 12967, -1, + 12968, 12968, 12968, -1, 12969, 12969, 12969, -1, + 12970, 12970, 12970, -1, 12971, 12971, 12971, -1, + 12972, 12972, 12972, -1, 12973, 12973, 12973, -1, + 12974, 12974, 12974, -1, 12975, 12975, 12975, -1, + 12976, 12976, 12976, -1, 12977, 12977, 12977, -1, + 12978, 12978, 12978, -1, 12979, 12979, 12979, -1, + 12980, 12980, 12980, -1, 12981, 12981, 12981, -1, + 12982, 12982, 12982, -1, 12983, 12983, 12983, -1, + 12984, 12984, 12984, -1, 12985, 12985, 12985, -1, + 12986, 12986, 12986, -1, 12987, 12987, 12987, -1, + 12988, 12988, 12988, -1, 12989, 12989, 12989, -1, + 12990, 12990, 12990, -1, 12991, 12991, 12991, -1, + 12992, 12992, 12992, -1, 12993, 12993, 12993, -1, + 12994, 12994, 12994, -1, 12995, 12995, 12995, -1, + 12996, 12996, 12996, -1, 12997, 12997, 12997, -1, + 12998, 12998, 12998, -1, 12999, 12999, 12999, -1, + 13000, 13000, 13000, -1, 13001, 13001, 13001, -1, + 13002, 13002, 13002, -1, 13003, 13003, 13003, -1, + 13004, 13004, 13004, -1, 13005, 13005, 13005, -1, + 13006, 13006, 13006, -1, 13007, 13007, 13007, -1, + 13008, 13008, 13008, -1, 13009, 13009, 13009, -1, + 13010, 13010, 13010, -1, 13011, 13011, 13011, -1, + 13012, 13012, 13012, -1, 13013, 13013, 13013, -1, + 13014, 13014, 13014, -1, 13015, 13015, 13015, -1, + 13016, 13016, 13016, -1, 13017, 13017, 13017, -1, + 13018, 13018, 13018, -1, 13019, 13019, 13019, -1, + 13020, 13020, 13020, -1, 13021, 13021, 13021, -1, + 13022, 13022, 13022, -1, 13023, 13023, 13023, -1, + 13024, 13024, 13024, -1, 13025, 13025, 13025, -1, + 13026, 13026, 13026, -1, 13027, 13027, 13027, -1, + 13028, 13028, 13028, -1, 13029, 13029, 13029, -1, + 13030, 13030, 13030, -1, 13031, 13031, 13031, -1, + 13032, 13032, 13032, -1, 13033, 13033, 13033, -1, + 13034, 13034, 13034, -1, 13035, 13035, 13035, -1, + 13036, 13036, 13036, -1, 13037, 13037, 13037, -1, + 13038, 13038, 13038, -1, 13039, 13039, 13039, -1, + 13040, 13040, 13040, -1, 13041, 13041, 13041, -1, + 13042, 13042, 13042, -1, 13043, 13043, 13043, -1, + 13044, 13044, 13044, -1, 13045, 13045, 13045, -1, + 13046, 13046, 13046, -1, 13047, 13047, 13047, -1, + 13048, 13048, 13048, -1, 13049, 13049, 13049, -1, + 13050, 13050, 13050, -1, 13051, 13051, 13051, -1, + 13052, 13052, 13052, -1, 13053, 13053, 13053, -1, + 13054, 13054, 13054, -1, 13055, 13055, 13055, -1, + 13056, 13056, 13056, -1, 13057, 13057, 13057, -1, + 13058, 13058, 13058, -1, 13059, 13059, 13059, -1, + 13060, 13060, 13060, -1, 13061, 13061, 13061, -1, + 13062, 13062, 13062, -1, 13063, 13063, 13063, -1, + 13064, 13064, 13064, -1, 13065, 13065, 13065, -1, + 13066, 13066, 13066, -1, 13067, 13067, 13067, -1, + 13068, 13068, 13068, -1, 13069, 13069, 13069, -1, + 13070, 13070, 13070, -1, 13071, 13071, 13071, -1, + 13072, 13072, 13072, -1, 13073, 13073, 13073, -1, + 13074, 13074, 13074, -1, 13075, 13075, 13075, -1, + 13076, 13076, 13076, -1, 13077, 13077, 13077, -1, + 13078, 13078, 13078, -1, 13079, 13079, 13079, -1, + 13080, 13080, 13080, -1, 13081, 13081, 13081, -1, + 13082, 13082, 13082, -1, 13083, 13083, 13083, -1, + 13084, 13084, 13084, -1, 13085, 13085, 13085, -1, + 13086, 13086, 13086, -1, 13087, 13087, 13087, -1, + 13088, 13088, 13088, -1, 13089, 13089, 13089, -1, + 13090, 13090, 13090, -1, 13091, 13091, 13091, -1, + 13092, 13092, 13092, -1, 13093, 13093, 13093, -1, + 13094, 13094, 13094, -1, 13095, 13095, 13095, -1, + 13096, 13096, 13096, -1, 13097, 13097, 13097, -1, + 13098, 13098, 13098, -1, 13099, 13099, 13099, -1, + 13100, 13100, 13100, -1, 13101, 13101, 13101, -1, + 13102, 13102, 13102, -1, 13103, 13103, 13103, -1, + 13104, 13104, 13104, -1, 13105, 13105, 13105, -1, + 13106, 13106, 13106, -1, 13107, 13107, 13107, -1, + 13108, 13108, 13108, -1, 13109, 13109, 13109, -1, + 13110, 13110, 13110, -1, 13111, 13111, 13111, -1, + 13112, 13112, 13112, -1, 13113, 13113, 13113, -1, + 13114, 13114, 13114, -1, 13115, 13115, 13115, -1, + 13116, 13116, 13116, -1, 13117, 13117, 13117, -1, + 13118, 13118, 13118, -1, 13119, 13119, 13119, -1, + 13120, 13120, 13120, -1, 13121, 13121, 13121, -1, + 13122, 13122, 13122, -1, 13123, 13123, 13123, -1, + 13124, 13124, 13124, -1, 13125, 13125, 13125, -1, + 13126, 13126, 13126, -1, 13127, 13127, 13127, -1, + 13128, 13128, 13128, -1, 13129, 13129, 13129, -1, + 13130, 13130, 13130, -1, 13131, 13131, 13131, -1, + 13132, 13132, 13132, -1, 13133, 13133, 13133, -1, + 13134, 13134, 13134, -1, 13135, 13135, 13135, -1, + 13136, 13136, 13136, -1, 13137, 13137, 13137, -1, + 13138, 13138, 13138, -1, 13139, 13139, 13139, -1, + 13140, 13140, 13140, -1, 13141, 13141, 13141, -1, + 13142, 13142, 13142, -1, 13143, 13143, 13143, -1, + 13144, 13144, 13144, -1, 13145, 13145, 13145, -1, + 13146, 13146, 13146, -1, 13147, 13147, 13147, -1, + 13148, 13148, 13148, -1, 13149, 13149, 13149, -1, + 13150, 13150, 13150, -1, 13151, 13151, 13151, -1, + 13152, 13152, 13152, -1, 13153, 13153, 13153, -1, + 13154, 13154, 13154, -1, 13155, 13155, 13155, -1, + 13156, 13156, 13156, -1, 13157, 13157, 13157, -1, + 13158, 13158, 13158, -1, 13159, 13159, 13159, -1, + 13160, 13160, 13160, -1, 13161, 13161, 13161, -1, + 13162, 13162, 13162, -1, 13163, 13163, 13163, -1, + 13164, 13164, 13164, -1, 13165, 13165, 13165, -1, + 13166, 13166, 13166, -1, 13167, 13167, 13167, -1, + 13168, 13168, 13168, -1, 13169, 13169, 13169, -1, + 13170, 13170, 13170, -1, 13171, 13171, 13171, -1, + 13172, 13172, 13172, -1, 13173, 13173, 13173, -1, + 13174, 13174, 13174, -1, 13175, 13175, 13175, -1, + 13176, 13176, 13176, -1, 13177, 13177, 13177, -1, + 13178, 13178, 13178, -1, 13179, 13179, 13179, -1, + 13180, 13180, 13180, -1, 13181, 13181, 13181, -1, + 13182, 13182, 13182, -1, 13183, 13183, 13183, -1, + 13184, 13184, 13184, -1, 13185, 13185, 13185, -1, + 13186, 13186, 13186, -1, 13187, 13187, 13187, -1, + 13188, 13188, 13188, -1, 13189, 13189, 13189, -1, + 13190, 13190, 13190, -1, 13191, 13191, 13191, -1, + 13192, 13192, 13192, -1, 13193, 13193, 13193, -1, + 13194, 13194, 13194, -1, 13195, 13195, 13195, -1, + 13196, 13196, 13196, -1, 13197, 13197, 13197, -1, + 13198, 13198, 13198, -1, 13199, 13199, 13199, -1, + 13200, 13200, 13200, -1, 13201, 13201, 13201, -1, + 13202, 13202, 13202, -1, 13203, 13203, 13203, -1, + 13204, 13204, 13204, -1, 13205, 13205, 13205, -1, + 13206, 13206, 13206, -1, 13207, 13207, 13207, -1, + 13208, 13208, 13208, -1, 13209, 13209, 13209, -1, + 13210, 13210, 13210, -1, 13211, 13211, 13211, -1, + 13212, 13212, 13212, -1, 13213, 13213, 13213, -1, + 13214, 13214, 13214, -1, 13215, 13215, 13215, -1, + 13216, 13216, 13216, -1, 13217, 13217, 13217, -1, + 13218, 13218, 13218, -1, 13219, 13219, 13219, -1, + 13220, 13220, 13220, -1, 13221, 13221, 13221, -1, + 13222, 13222, 13222, -1, 13223, 13223, 13223, -1, + 13224, 13224, 13224, -1, 13225, 13225, 13225, -1, + 13226, 13226, 13226, -1, 13227, 13227, 13227, -1, + 13228, 13228, 13228, -1, 13229, 13229, 13229, -1, + 13230, 13230, 13230, -1, 13231, 13231, 13231, -1, + 13232, 13232, 13232, -1, 13233, 13233, 13233, -1, + 13234, 13234, 13234, -1, 13235, 13235, 13235, -1, + 13236, 13236, 13236, -1, 13237, 13237, 13237, -1, + 13238, 13238, 13238, -1, 13239, 13239, 13239, -1, + 13240, 13240, 13240, -1, 13241, 13241, 13241, -1, + 13242, 13242, 13242, -1, 13243, 13243, 13243, -1, + 13244, 13244, 13244, -1, 13245, 13245, 13245, -1, + 13246, 13246, 13246, -1, 13247, 13247, 13247, -1, + 13248, 13248, 13248, -1, 13249, 13249, 13249, -1, + 13250, 13250, 13250, -1, 13251, 13251, 13251, -1, + 13252, 13252, 13252, -1, 13253, 13253, 13253, -1, + 13254, 13254, 13254, -1, 13255, 13255, 13255, -1, + 13256, 13256, 13256, -1, 13257, 13257, 13257, -1, + 13258, 13258, 13258, -1, 13259, 13259, 13259, -1, + 13260, 13260, 13260, -1, 13261, 13261, 13261, -1, + 13262, 13262, 13262, -1, 13263, 13263, 13263, -1, + 13264, 13264, 13264, -1, 13265, 13265, 13265, -1, + 13266, 13266, 13266, -1, 13267, 13267, 13267, -1, + 13268, 13268, 13268, -1, 13269, 13269, 13269, -1, + 13270, 13270, 13270, -1, 13271, 13271, 13271, -1, + 13272, 13272, 13272, -1, 13273, 13273, 13273, -1, + 13274, 13274, 13274, -1, 13275, 13275, 13275, -1, + 13276, 13276, 13276, -1, 13277, 13277, 13277, -1, + 13278, 13278, 13278, -1, 13279, 13279, 13279, -1, + 13280, 13280, 13280, -1, 13281, 13281, 13281, -1, + 13282, 13282, 13282, -1, 13283, 13283, 13283, -1, + 13284, 13284, 13284, -1, 13285, 13285, 13285, -1, + 13286, 13286, 13286, -1, 13287, 13287, 13287, -1, + 13288, 13288, 13288, -1, 13289, 13289, 13289, -1, + 13290, 13290, 13290, -1, 13291, 13291, 13291, -1, + 13292, 13292, 13292, -1, 13293, 13293, 13293, -1, + 13294, 13294, 13294, -1, 13295, 13295, 13295, -1, + 13296, 13296, 13296, -1, 13297, 13297, 13297, -1, + 13298, 13298, 13298, -1, 13299, 13299, 13299, -1, + 13300, 13300, 13300, -1, 13301, 13301, 13301, -1, + 13302, 13302, 13302, -1, 13303, 13303, 13303, -1, + 13304, 13304, 13304, -1, 13305, 13305, 13305, -1, + 13306, 13306, 13306, -1, 13307, 13307, 13307, -1, + 13308, 13308, 13308, -1, 13309, 13309, 13309, -1, + 13310, 13310, 13310, -1, 13311, 13311, 13311, -1, + 13312, 13312, 13312, -1, 13313, 13313, 13313, -1, + 13314, 13314, 13314, -1, 13315, 13315, 13315, -1, + 13316, 13316, 13316, -1, 13317, 13317, 13317, -1, + 13318, 13318, 13318, -1, 13319, 13319, 13319, -1, + 13320, 13320, 13320, -1, 13321, 13321, 13321, -1, + 13322, 13322, 13322, -1, 13323, 13323, 13323, -1, + 13324, 13324, 13324, -1, 13325, 13325, 13325, -1, + 13326, 13326, 13326, -1, 13327, 13327, 13327, -1, + 13328, 13328, 13328, -1, 13329, 13329, 13329, -1, + 13330, 13330, 13330, -1, 13331, 13331, 13331, -1, + 13332, 13332, 13332, -1, 13333, 13333, 13333, -1, + 13334, 13334, 13334, -1, 13335, 13335, 13335, -1, + 13336, 13336, 13336, -1, 13337, 13337, 13337, -1, + 13338, 13338, 13338, -1, 13339, 13339, 13339, -1, + 13340, 13340, 13340, -1, 13341, 13341, 13341, -1, + 13342, 13342, 13342, -1, 13343, 13343, 13343, -1, + 13344, 13344, 13344, -1, 13345, 13345, 13345, -1, + 13346, 13346, 13346, -1, 13347, 13347, 13347, -1, + 13348, 13348, 13348, -1, 13349, 13349, 13349, -1, + 13350, 13350, 13350, -1, 13351, 13351, 13351, -1, + 13352, 13352, 13352, -1, 13353, 13353, 13353, -1, + 13354, 13354, 13354, -1, 13355, 13355, 13355, -1, + 13356, 13356, 13356, -1, 13357, 13357, 13357, -1, + 13358, 13358, 13358, -1, 13359, 13359, 13359, -1, + 13360, 13360, 13360, -1, 13361, 13361, 13361, -1, + 13362, 13362, 13362, -1, 13363, 13363, 13363, -1, + 13364, 13364, 13364, -1, 13365, 13365, 13365, -1, + 13366, 13366, 13366, -1, 13367, 13367, 13367, -1, + 13368, 13368, 13368, -1, 13369, 13369, 13369, -1, + 13370, 13370, 13370, -1, 13371, 13371, 13371, -1, + 13372, 13372, 13372, -1, 13373, 13373, 13373, -1, + 13374, 13374, 13374, -1, 13375, 13375, 13375, -1, + 13376, 13376, 13376, -1, 13377, 13377, 13377, -1, + 13378, 13378, 13378, -1, 13379, 13379, 13379, -1, + 13380, 13380, 13380, -1, 13381, 13381, 13381, -1, + 13382, 13382, 13382, -1, 13383, 13383, 13383, -1, + 13384, 13384, 13384, -1, 13385, 13385, 13385, -1, + 13386, 13386, 13386, -1, 13387, 13387, 13387, -1, + 13388, 13388, 13388, -1, 13389, 13389, 13389, -1, + 13390, 13390, 13390, -1, 13391, 13391, 13391, -1, + 13392, 13392, 13392, -1, 13393, 13393, 13393, -1, + 13394, 13394, 13394, -1, 13395, 13395, 13395, -1, + 13396, 13396, 13396, -1, 13397, 13397, 13397, -1, + 13398, 13398, 13398, -1, 13399, 13399, 13399, -1, + 13400, 13400, 13400, -1, 13401, 13401, 13401, -1, + 13402, 13402, 13402, -1, 13403, 13403, 13403, -1, + 13404, 13404, 13404, -1, 13405, 13405, 13405, -1, + 13406, 13406, 13406, -1, 13407, 13407, 13407, -1, + 13408, 13408, 13408, -1, 13409, 13409, 13409, -1, + 13410, 13410, 13410, -1, 13411, 13411, 13411, -1, + 13412, 13412, 13412, -1, 13413, 13413, 13413, -1, + 13414, 13414, 13414, -1, 13415, 13415, 13415, -1, + 13416, 13416, 13416, -1, 13417, 13417, 13417, -1, + 13418, 13418, 13418, -1, 13419, 13419, 13419, -1, + 13420, 13420, 13420, -1, 13421, 13421, 13421, -1, + 13422, 13422, 13422, -1, 13423, 13423, 13423, -1, + 13424, 13424, 13424, -1, 13425, 13425, 13425, -1, + 13426, 13426, 13426, -1, 13427, 13427, 13427, -1, + 13428, 13428, 13428, -1, 13429, 13429, 13429, -1, + 13430, 13430, 13430, -1, 13431, 13431, 13431, -1, + 13432, 13432, 13432, -1, 13433, 13433, 13433, -1, + 13434, 13434, 13434, -1, 13435, 13435, 13435, -1, + 13436, 13436, 13436, -1, 13437, 13437, 13437, -1, + 13438, 13438, 13438, -1, 13439, 13439, 13439, -1, + 13440, 13440, 13440, -1, 13441, 13441, 13441, -1, + 13442, 13442, 13442, -1, 13443, 13443, 13443, -1, + 13444, 13444, 13444, -1, 13445, 13445, 13445, -1, + 13446, 13446, 13446, -1, 13447, 13447, 13447, -1, + 13448, 13448, 13448, -1, 13449, 13449, 13449, -1, + 13450, 13450, 13450, -1, 13451, 13451, 13451, -1, + 13452, 13452, 13452, -1, 13453, 13453, 13453, -1, + 13454, 13454, 13454, -1, 13455, 13455, 13455, -1, + 13456, 13456, 13456, -1, 13457, 13457, 13457, -1, + 13458, 13458, 13458, -1, 13459, 13459, 13459, -1, + 13460, 13460, 13460, -1, 13461, 13461, 13461, -1, + 13462, 13462, 13462, -1, 13463, 13463, 13463, -1, + 13464, 13464, 13464, -1, 13465, 13465, 13465, -1, + 13466, 13466, 13466, -1, 13467, 13467, 13467, -1, + 13468, 13468, 13468, -1, 13469, 13469, 13469, -1, + 13470, 13470, 13470, -1, 13471, 13471, 13471, -1, + 13472, 13472, 13472, -1, 13473, 13473, 13473, -1, + 13474, 13474, 13474, -1, 13475, 13475, 13475, -1, + 13476, 13476, 13476, -1, 13477, 13477, 13477, -1, + 13478, 13478, 13478, -1, 13479, 13479, 13479, -1, + 13480, 13480, 13480, -1, 13481, 13481, 13481, -1, + 13482, 13482, 13482, -1, 13483, 13483, 13483, -1, + 13484, 13484, 13484, -1, 13485, 13485, 13485, -1, + 13486, 13486, 13486, -1, 13487, 13487, 13487, -1, + 13488, 13488, 13488, -1, 13489, 13489, 13489, -1, + 13490, 13490, 13490, -1, 13491, 13491, 13491, -1, + 13492, 13492, 13492, -1, 13493, 13493, 13493, -1, + 13494, 13494, 13494, -1, 13495, 13495, 13495, -1, + 13496, 13496, 13496, -1, 13497, 13497, 13497, -1, + 13498, 13498, 13498, -1, 13499, 13499, 13499, -1, + 13500, 13500, 13500, -1, 13501, 13501, 13501, -1, + 13502, 13502, 13502, -1, 13503, 13503, 13503, -1, + 13504, 13504, 13504, -1, 13505, 13505, 13505, -1, + 13506, 13506, 13506, -1, 13507, 13507, 13507, -1, + 13508, 13508, 13508, -1, 13509, 13509, 13509, -1, + 13510, 13510, 13510, -1, 13511, 13511, 13511, -1, + 13512, 13512, 13512, -1, 13513, 13513, 13513, -1, + 13514, 13514, 13514, -1, 13515, 13515, 13515, -1, + 13516, 13516, 13516, -1, 13517, 13517, 13517, -1, + 13518, 13518, 13518, -1, 13519, 13519, 13519, -1, + 13520, 13520, 13520, -1, 13521, 13521, 13521, -1, + 13522, 13522, 13522, -1, 13523, 13523, 13523, -1, + 13524, 13524, 13524, -1, 13525, 13525, 13525, -1, + 13526, 13526, 13526, -1, 13527, 13527, 13527, -1, + 13528, 13528, 13528, -1, 13529, 13529, 13529, -1, + 13530, 13530, 13530, -1, 13531, 13531, 13531, -1, + 13532, 13532, 13532, -1, 13533, 13533, 13533, -1, + 13534, 13534, 13534, -1, 13535, 13535, 13535, -1, + 13536, 13536, 13536, -1, 13537, 13537, 13537, -1, + 13538, 13538, 13538, -1, 13539, 13539, 13539, -1, + 13540, 13540, 13540, -1, 13541, 13541, 13541, -1, + 13542, 13542, 13542, -1, 13543, 13543, 13543, -1, + 13544, 13544, 13544, -1, 13545, 13545, 13545, -1, + 13546, 13546, 13546, -1, 13547, 13547, 13547, -1, + 13548, 13548, 13548, -1, 13549, 13549, 13549, -1, + 13550, 13550, 13550, -1, 13551, 13551, 13551, -1, + 13552, 13552, 13552, -1, 13553, 13553, 13553, -1, + 13554, 13554, 13554, -1, 13555, 13555, 13555, -1, + 13556, 13556, 13556, -1, 13557, 13557, 13557, -1, + 13558, 13558, 13558, -1, 13559, 13559, 13559, -1, + 13560, 13560, 13560, -1, 13561, 13561, 13561, -1, + 13562, 13562, 13562, -1, 13563, 13563, 13563, -1, + 13564, 13564, 13564, -1, 13565, 13565, 13565, -1, + 13566, 13566, 13566, -1, 13567, 13567, 13567, -1, + 13568, 13568, 13568, -1, 13569, 13569, 13569, -1, + 13570, 13570, 13570, -1, 13571, 13571, 13571, -1, + 13572, 13572, 13572, -1, 13573, 13573, 13573, -1, + 13574, 13574, 13574, -1, 13575, 13575, 13575, -1, + 13576, 13576, 13576, -1, 13577, 13577, 13577, -1, + 13578, 13578, 13578, -1, 13579, 13579, 13579, -1, + 13580, 13580, 13580, -1, 13581, 13581, 13581, -1, + 13582, 13582, 13582, -1, 13583, 13583, 13583, -1, + 13584, 13584, 13584, -1, 13585, 13585, 13585, -1, + 13586, 13586, 13586, -1, 13587, 13587, 13587, -1, + 13588, 13588, 13588, -1, 13589, 13589, 13589, -1, + 13590, 13590, 13590, -1, 13591, 13591, 13591, -1, + 13592, 13592, 13592, -1, 13593, 13593, 13593, -1, + 13594, 13594, 13594, -1, 13595, 13595, 13595, -1, + 13596, 13596, 13596, -1, 13597, 13597, 13597, -1, + 13598, 13598, 13598, -1, 13599, 13599, 13599, -1, + 13600, 13600, 13600, -1, 13601, 13601, 13601, -1, + 13602, 13602, 13602, -1, 13603, 13603, 13603, -1, + 13604, 13604, 13604, -1, 13605, 13605, 13605, -1, + 13606, 13606, 13606, -1, 13607, 13607, 13607, -1, + 13608, 13608, 13608, -1, 13609, 13609, 13609, -1, + 13610, 13610, 13610, -1, 13611, 13611, 13611, -1, + 13612, 13612, 13612, -1, 13613, 13613, 13613, -1, + 13614, 13614, 13614, -1, 13615, 13615, 13615, -1, + 13616, 13616, 13616, -1, 13617, 13617, 13617, -1, + 13618, 13618, 13618, -1, 13619, 13619, 13619, -1, + 13620, 13620, 13620, -1, 13621, 13621, 13621, -1, + 13622, 13622, 13622, -1, 13623, 13623, 13623, -1, + 13624, 13624, 13624, -1, 13625, 13625, 13625, -1, + 13626, 13626, 13626, -1, 13627, 13627, 13627, -1, + 13628, 13628, 13628, -1, 13629, 13629, 13629, -1, + 13630, 13630, 13630, -1, 13631, 13631, 13631, -1, + 13632, 13632, 13632, -1, 13633, 13633, 13633, -1, + 13634, 13634, 13634, -1, 13635, 13635, 13635, -1, + 13636, 13636, 13636, -1, 13637, 13637, 13637, -1, + 13638, 13638, 13638, -1, 13639, 13639, 13639, -1, + 13640, 13640, 13640, -1, 13641, 13641, 13641, -1, + 13642, 13642, 13642, -1, 13643, 13643, 13643, -1, + 13644, 13644, 13644, -1, 13645, 13645, 13645, -1, + 13646, 13646, 13646, -1, 13647, 13647, 13647, -1, + 13648, 13648, 13648, -1, 13649, 13649, 13649, -1, + 13650, 13650, 13650, -1, 13651, 13651, 13651, -1, + 13652, 13652, 13652, -1, 13653, 13653, 13653, -1, + 13654, 13654, 13654, -1, 13655, 13655, 13655, -1, + 13656, 13656, 13656, -1, 13657, 13657, 13657, -1, + 13658, 13658, 13658, -1, 13659, 13659, 13659, -1, + 13660, 13660, 13660, -1, 13661, 13661, 13661, -1, + 13662, 13662, 13662, -1, 13663, 13663, 13663, -1, + 13664, 13664, 13664, -1, 13665, 13665, 13665, -1, + 13666, 13666, 13666, -1, 13667, 13667, 13667, -1, + 13668, 13668, 13668, -1, 13669, 13669, 13669, -1, + 13670, 13670, 13670, -1, 13671, 13671, 13671, -1, + 13672, 13672, 13672, -1, 13673, 13673, 13673, -1, + 13674, 13674, 13674, -1, 13675, 13675, 13675, -1, + 13676, 13676, 13676, -1, 13677, 13677, 13677, -1, + 13678, 13678, 13678, -1, 13679, 13679, 13679, -1, + 13680, 13680, 13680, -1, 13681, 13681, 13681, -1, + 13682, 13682, 13682, -1, 13683, 13683, 13683, -1, + 13684, 13684, 13684, -1, 13685, 13685, 13685, -1, + 13686, 13686, 13686, -1, 13687, 13687, 13687, -1, + 13688, 13688, 13688, -1, 13689, 13689, 13689, -1, + 13690, 13690, 13690, -1, 13691, 13691, 13691, -1, + 13692, 13692, 13692, -1, 13693, 13693, 13693, -1, + 13694, 13694, 13694, -1, 13695, 13695, 13695, -1, + 13696, 13696, 13696, -1, 13697, 13697, 13697, -1, + 13698, 13698, 13698, -1, 13699, 13699, 13699, -1, + 13700, 13700, 13700, -1, 13701, 13701, 13701, -1, + 13702, 13702, 13702, -1, 13703, 13703, 13703, -1, + 13704, 13704, 13704, -1, 13705, 13705, 13705, -1, + 13706, 13706, 13706, -1, 13707, 13707, 13707, -1, + 13708, 13708, 13708, -1, 13709, 13709, 13709, -1, + 13710, 13710, 13710, -1, 13711, 13711, 13711, -1, + 13712, 13712, 13712, -1, 13713, 13713, 13713, -1, + 13714, 13714, 13714, -1, 13715, 13715, 13715, -1, + 13716, 13716, 13716, -1, 13717, 13717, 13717, -1, + 13718, 13718, 13718, -1, 13719, 13719, 13719, -1, + 13720, 13720, 13720, -1, 13721, 13721, 13721, -1, + 13722, 13722, 13722, -1, 13723, 13723, 13723, -1, + 13724, 13724, 13724, -1, 13725, 13725, 13725, -1, + 13726, 13726, 13726, -1, 13727, 13727, 13727, -1, + 13728, 13728, 13728, -1, 13729, 13729, 13729, -1, + 13730, 13730, 13730, -1, 13731, 13731, 13731, -1, + 13732, 13732, 13732, -1, 13733, 13733, 13733, -1, + 13734, 13734, 13734, -1, 13735, 13735, 13735, -1, + 13736, 13736, 13736, -1, 13737, 13737, 13737, -1, + 13738, 13738, 13738, -1, 13739, 13739, 13739, -1, + 13740, 13740, 13740, -1, 13741, 13741, 13741, -1, + 13742, 13742, 13742, -1, 13743, 13743, 13743, -1, + 13744, 13744, 13744, -1, 13745, 13745, 13745, -1, + 13746, 13746, 13746, -1, 13747, 13747, 13747, -1, + 13748, 13748, 13748, -1, 13749, 13749, 13749, -1, + 13750, 13750, 13750, -1, 13751, 13751, 13751, -1, + 13752, 13752, 13752, -1, 13753, 13753, 13753, -1, + 13754, 13754, 13754, -1, 13755, 13755, 13755, -1, + 13756, 13756, 13756, -1, 13757, 13757, 13757, -1, + 13758, 13758, 13758, -1, 13759, 13759, 13759, -1, + 13760, 13760, 13760, -1, 13761, 13761, 13761, -1, + 13762, 13762, 13762, -1, 13763, 13763, 13763, -1, + 13764, 13764, 13764, -1, 13765, 13765, 13765, -1, + 13766, 13766, 13766, -1, 13767, 13767, 13767, -1, + 13768, 13768, 13768, -1, 13769, 13769, 13769, -1, + 13770, 13770, 13770, -1, 13771, 13771, 13771, -1, + 13772, 13772, 13772, -1, 13773, 13773, 13773, -1, + 13774, 13774, 13774, -1, 13775, 13775, 13775, -1, + 13776, 13776, 13776, -1, 13777, 13777, 13777, -1, + 13778, 13778, 13778, -1, 13779, 13779, 13779, -1, + 13780, 13780, 13780, -1, 13781, 13781, 13781, -1, + 13782, 13782, 13782, -1, 13783, 13783, 13783, -1, + 13784, 13784, 13784, -1, 13785, 13785, 13785, -1, + 13786, 13786, 13786, -1, 13787, 13787, 13787, -1, + 13788, 13788, 13788, -1, 13789, 13789, 13789, -1, + 13790, 13790, 13790, -1, 13791, 13791, 13791, -1, + 13792, 13792, 13792, -1, 13793, 13793, 13793, -1, + 13794, 13794, 13794, -1, 13795, 13795, 13795, -1, + 13796, 13796, 13796, -1, 13797, 13797, 13797, -1, + 13798, 13798, 13798, -1, 13799, 13799, 13799, -1, + 13800, 13800, 13800, -1, 13801, 13801, 13801, -1, + 13802, 13802, 13802, -1, 13803, 13803, 13803, -1, + 13804, 13804, 13804, -1, 13805, 13805, 13805, -1, + 13806, 13806, 13806, -1, 13807, 13807, 13807, -1, + 13808, 13808, 13808, -1, 13809, 13809, 13809, -1, + 13810, 13810, 13810, -1, 13811, 13811, 13811, -1, + 13812, 13812, 13812, -1, 13813, 13813, 13813, -1, + 13814, 13814, 13814, -1, 13815, 13815, 13815, -1, + 13816, 13816, 13816, -1, 13817, 13817, 13817, -1, + 13818, 13818, 13818, -1, 13819, 13819, 13819, -1, + 13820, 13820, 13820, -1, 13821, 13821, 13821, -1, + 13822, 13822, 13822, -1, 13823, 13823, 13823, -1, + 13824, 13824, 13824, -1, 13825, 13825, 13825, -1, + 13826, 13826, 13826, -1, 13827, 13827, 13827, -1, + 13828, 13828, 13828, -1, 13829, 13829, 13829, -1, + 13830, 13830, 13830, -1, 13831, 13831, 13831, -1, + 13832, 13832, 13832, -1, 13833, 13833, 13833, -1, + 13834, 13834, 13834, -1, 13835, 13835, 13835, -1, + 13836, 13836, 13836, -1, 13837, 13837, 13837, -1, + 13838, 13838, 13838, -1, 13839, 13839, 13839, -1, + 13840, 13840, 13840, -1, 13841, 13841, 13841, -1, + 13842, 13842, 13842, -1, 13843, 13843, 13843, -1, + 13844, 13844, 13844, -1, 13845, 13845, 13845, -1, + 13846, 13846, 13846, -1, 13847, 13847, 13847, -1, + 13848, 13848, 13848, -1, 13849, 13849, 13849, -1, + 13850, 13850, 13850, -1, 13851, 13851, 13851, -1, + 13852, 13852, 13852, -1, 13853, 13853, 13853, -1, + 13854, 13854, 13854, -1, 13855, 13855, 13855, -1, + 13856, 13856, 13856, -1, 13857, 13857, 13857, -1, + 13858, 13858, 13858, -1, 13859, 13859, 13859, -1, + 13860, 13860, 13860, -1, 13861, 13861, 13861, -1, + 13862, 13862, 13862, -1, 13863, 13863, 13863, -1, + 13864, 13864, 13864, -1, 13865, 13865, 13865, -1, + 13866, 13866, 13866, -1, 13867, 13867, 13867, -1, + 13868, 13868, 13868, -1, 13869, 13869, 13869, -1, + 13870, 13870, 13870, -1, 13871, 13871, 13871, -1, + 13872, 13872, 13872, -1, 13873, 13873, 13873, -1, + 13874, 13874, 13874, -1, 13875, 13875, 13875, -1, + 13876, 13876, 13876, -1, 13877, 13877, 13877, -1, + 13878, 13878, 13878, -1, 13879, 13879, 13879, -1, + 13880, 13880, 13880, -1, 13881, 13881, 13881, -1, + 13882, 13882, 13882, -1, 13883, 13883, 13883, -1, + 13884, 13884, 13884, -1, 13885, 13885, 13885, -1, + 13886, 13886, 13886, -1, 13887, 13887, 13887, -1, + 13888, 13888, 13888, -1, 13889, 13889, 13889, -1, + 13890, 13890, 13890, -1, 13891, 13891, 13891, -1, + 13892, 13892, 13892, -1, 13893, 13893, 13893, -1, + 13894, 13894, 13894, -1, 13895, 13895, 13895, -1, + 13896, 13896, 13896, -1, 13897, 13897, 13897, -1, + 13898, 13898, 13898, -1, 13899, 13899, 13899, -1, + 13900, 13900, 13900, -1, 13901, 13901, 13901, -1, + 13902, 13902, 13902, -1, 13903, 13903, 13903, -1, + 13904, 13904, 13904, -1, 13905, 13905, 13905, -1, + 13906, 13906, 13906, -1, 13907, 13907, 13907, -1, + 13908, 13908, 13908, -1, 13909, 13909, 13909, -1, + 13910, 13910, 13910, -1, 13911, 13911, 13911, -1, + 13912, 13912, 13912, -1, 13913, 13913, 13913, -1, + 13914, 13914, 13914, -1, 13915, 13915, 13915, -1, + 13916, 13916, 13916, -1, 13917, 13917, 13917, -1, + 13918, 13918, 13918, -1, 13919, 13919, 13919, -1, + 13920, 13920, 13920, -1, 13921, 13921, 13921, -1, + 13922, 13922, 13922, -1, 13923, 13923, 13923, -1, + 13924, 13924, 13924, -1, 13925, 13925, 13925, -1, + 13926, 13926, 13926, -1, 13927, 13927, 13927, -1, + 13928, 13928, 13928, -1, 13929, 13929, 13929, -1, + 13930, 13930, 13930, -1, 13931, 13931, 13931, -1, + 13932, 13932, 13932, -1, 13933, 13933, 13933, -1, + 13934, 13934, 13934, -1, 13935, 13935, 13935, -1, + 13936, 13936, 13936, -1, 13937, 13937, 13937, -1, + 13938, 13938, 13938, -1, 13939, 13939, 13939, -1, + 13940, 13940, 13940, -1, 13941, 13941, 13941, -1, + 13942, 13942, 13942, -1, 13943, 13943, 13943, -1, + 13944, 13944, 13944, -1, 13945, 13945, 13945, -1, + 13946, 13946, 13946, -1, 13947, 13947, 13947, -1, + 13948, 13948, 13948, -1, 13949, 13949, 13949, -1, + 13950, 13950, 13950, -1, 13951, 13951, 13951, -1, + 13952, 13952, 13952, -1, 13953, 13953, 13953, -1, + 13954, 13954, 13954, -1, 13955, 13955, 13955, -1, + 13956, 13956, 13956, -1, 13957, 13957, 13957, -1, + 13958, 13958, 13958, -1, 13959, 13959, 13959, -1, + 13960, 13960, 13960, -1, 13961, 13961, 13961, -1, + 13962, 13962, 13962, -1, 13963, 13963, 13963, -1, + 13964, 13964, 13964, -1, 13965, 13965, 13965, -1, + 13966, 13966, 13966, -1, 13967, 13967, 13967, -1, + 13968, 13968, 13968, -1, 13969, 13969, 13969, -1, + 13970, 13970, 13970, -1, 13971, 13971, 13971, -1, + 13972, 13972, 13972, -1, 13973, 13973, 13973, -1, + 13974, 13974, 13974, -1, 13975, 13975, 13975, -1, + 13976, 13976, 13976, -1, 13977, 13977, 13977, -1, + 13978, 13978, 13978, -1, 13979, 13979, 13979, -1, + 13980, 13980, 13980, -1, 13981, 13981, 13981, -1, + 13982, 13982, 13982, -1, 13983, 13983, 13983, -1, + 13984, 13984, 13984, -1, 13985, 13985, 13985, -1, + 13986, 13986, 13986, -1, 13987, 13987, 13987, -1, + 13988, 13988, 13988, -1, 13989, 13989, 13989, -1, + 13990, 13990, 13990, -1, 13991, 13991, 13991, -1, + 13992, 13992, 13992, -1, 13993, 13993, 13993, -1, + 13994, 13994, 13994, -1, 13995, 13995, 13995, -1, + 13996, 13996, 13996, -1, 13997, 13997, 13997, -1, + 13998, 13998, 13998, -1, 13999, 13999, 13999, -1, + 14000, 14000, 14000, -1, 14001, 14001, 14001, -1, + 14002, 14002, 14002, -1, 14003, 14003, 14003, -1, + 14004, 14004, 14004, -1, 14005, 14005, 14005, -1, + 14006, 14006, 14006, -1, 14007, 14007, 14007, -1, + 14008, 14008, 14008, -1, 14009, 14009, 14009, -1, + 14010, 14010, 14010, -1, 14011, 14011, 14011, -1, + 14012, 14012, 14012, -1, 14013, 14013, 14013, -1, + 14014, 14014, 14014, -1, 14015, 14015, 14015, -1, + 14016, 14016, 14016, -1, 14017, 14017, 14017, -1, + 14018, 14018, 14018, -1, 14019, 14019, 14019, -1, + 14020, 14020, 14020, -1, 14021, 14021, 14021, -1, + 14022, 14022, 14022, -1, 14023, 14023, 14023, -1, + 14024, 14024, 14024, -1, 14025, 14025, 14025, -1, + 14026, 14026, 14026, -1, 14027, 14027, 14027, -1, + 14028, 14028, 14028, -1, 14029, 14029, 14029, -1, + 14030, 14030, 14030, -1, 14031, 14031, 14031, -1, + 14032, 14032, 14032, -1, 14033, 14033, 14033, -1, + 14034, 14034, 14034, -1, 14035, 14035, 14035, -1, + 14036, 14036, 14036, -1, 14037, 14037, 14037, -1, + 14038, 14038, 14038, -1, 14039, 14039, 14039, -1, + 14040, 14040, 14040, -1, 14041, 14041, 14041, -1, + 14042, 14042, 14042, -1, 14043, 14043, 14043, -1, + 14044, 14044, 14044, -1, 14045, 14045, 14045, -1, + 14046, 14046, 14046, -1, 14047, 14047, 14047, -1, + 14048, 14048, 14048, -1, 14049, 14049, 14049, -1, + 14050, 14050, 14050, -1, 14051, 14051, 14051, -1, + 14052, 14052, 14052, -1, 14053, 14053, 14053, -1, + 14054, 14054, 14054, -1, 14055, 14055, 14055, -1, + 14056, 14056, 14056, -1, 14057, 14057, 14057, -1, + 14058, 14058, 14058, -1, 14059, 14059, 14059, -1, + 14060, 14060, 14060, -1, 14061, 14061, 14061, -1, + 14062, 14062, 14062, -1, 14063, 14063, 14063, -1, + 14064, 14064, 14064, -1, 14065, 14065, 14065, -1, + 14066, 14066, 14066, -1, 14067, 14067, 14067, -1, + 14068, 14068, 14068, -1, 14069, 14069, 14069, -1, + 14070, 14070, 14070, -1, 14071, 14071, 14071, -1, + 14072, 14072, 14072, -1, 14073, 14073, 14073, -1, + 14074, 14074, 14074, -1, 14075, 14075, 14075, -1, + 14076, 14076, 14076, -1, 14077, 14077, 14077, -1, + 14078, 14078, 14078, -1, 14079, 14079, 14079, -1, + 14080, 14080, 14080, -1, 14081, 14081, 14081, -1, + 14082, 14082, 14082, -1, 14083, 14083, 14083, -1, + 14084, 14084, 14084, -1, 14085, 14085, 14085, -1, + 14086, 14086, 14086, -1, 14087, 14087, 14087, -1, + 14088, 14088, 14088, -1, 14089, 14089, 14089, -1, + 14090, 14090, 14090, -1, 14091, 14091, 14091, -1, + 14092, 14092, 14092, -1, 14093, 14093, 14093, -1, + 14094, 14094, 14094, -1, 14095, 14095, 14095, -1, + 14096, 14096, 14096, -1, 14097, 14097, 14097, -1, + 14098, 14098, 14098, -1, 14099, 14099, 14099, -1, + 14100, 14100, 14100, -1, 14101, 14101, 14101, -1, + 14102, 14102, 14102, -1, 14103, 14103, 14103, -1, + 14104, 14104, 14104, -1, 14105, 14105, 14105, -1, + 14106, 14106, 14106, -1, 14107, 14107, 14107, -1, + 14108, 14108, 14108, -1, 14109, 14109, 14109, -1, + 14110, 14110, 14110, -1, 14111, 14111, 14111, -1, + 14112, 14112, 14112, -1, 14113, 14113, 14113, -1, + 14114, 14114, 14114, -1, 14115, 14115, 14115, -1, + 14116, 14116, 14116, -1, 14117, 14117, 14117, -1, + 14118, 14118, 14118, -1, 14119, 14119, 14119, -1, + 14120, 14120, 14120, -1, 14121, 14121, 14121, -1, + 14122, 14122, 14122, -1, 14123, 14123, 14123, -1, + 14124, 14124, 14124, -1, 14125, 14125, 14125, -1, + 14126, 14126, 14126, -1, 14127, 14127, 14127, -1, + 14128, 14128, 14128, -1, 14129, 14129, 14129, -1, + 14130, 14130, 14130, -1, 14131, 14131, 14131, -1, + 14132, 14132, 14132, -1, 14133, 14133, 14133, -1, + 14134, 14134, 14134, -1, 14135, 14135, 14135, -1, + 14136, 14136, 14136, -1, 14137, 14137, 14137, -1, + 14138, 14138, 14138, -1, 14139, 14139, 14139, -1, + 14140, 14140, 14140, -1, 14141, 14141, 14141, -1, + 14142, 14142, 14142, -1, 14143, 14143, 14143, -1, + 14144, 14144, 14144, -1, 14145, 14145, 14145, -1, + 14146, 14146, 14146, -1, 14147, 14147, 14147, -1, + 14148, 14148, 14148, -1, 14149, 14149, 14149, -1, + 14150, 14150, 14150, -1, 14151, 14151, 14151, -1, + 14152, 14152, 14152, -1, 14153, 14153, 14153, -1, + 14154, 14154, 14154, -1, 14155, 14155, 14155, -1, + 14156, 14156, 14156, -1, 14157, 14157, 14157, -1, + 14158, 14158, 14158, -1, 14159, 14159, 14159, -1, + 14160, 14160, 14160, -1, 14161, 14161, 14161, -1, + 14162, 14162, 14162, -1, 14163, 14163, 14163, -1, + 14164, 14164, 14164, -1, 14165, 14165, 14165, -1, + 14166, 14166, 14166, -1, 14167, 14167, 14167, -1, + 14168, 14168, 14168, -1, 14169, 14169, 14169, -1, + 14170, 14170, 14170, -1, 14171, 14171, 14171, -1, + 14172, 14172, 14172, -1, 14173, 14173, 14173, -1, + 14174, 14174, 14174, -1, 14175, 14175, 14175, -1, + 14176, 14176, 14176, -1, 14177, 14177, 14177, -1, + 14178, 14178, 14178, -1, 14179, 14179, 14179, -1, + 14180, 14180, 14180, -1, 14181, 14181, 14181, -1, + 14182, 14182, 14182, -1, 14183, 14183, 14183, -1, + 14184, 14184, 14184, -1, 14185, 14185, 14185, -1, + 14186, 14186, 14186, -1, 14187, 14187, 14187, -1, + 14188, 14188, 14188, -1, 14189, 14189, 14189, -1, + 14190, 14190, 14190, -1, 14191, 14191, 14191, -1, + 14192, 14192, 14192, -1, 14193, 14193, 14193, -1, + 14194, 14194, 14194, -1, 14195, 14195, 14195, -1, + 14196, 14196, 14196, -1, 14197, 14197, 14197, -1, + 14198, 14198, 14198, -1, 14199, 14199, 14199, -1, + 14200, 14200, 14200, -1, 14201, 14201, 14201, -1, + 14202, 14202, 14202, -1, 14203, 14203, 14203, -1, + 14204, 14204, 14204, -1, 14205, 14205, 14205, -1, + 14206, 14206, 14206, -1, 14207, 14207, 14207, -1, + 14208, 14208, 14208, -1, 14209, 14209, 14209, -1, + 14210, 14210, 14210, -1, 14211, 14211, 14211, -1, + 14212, 14212, 14212, -1, 14213, 14213, 14213, -1, + 14214, 14214, 14214, -1, 14215, 14215, 14215, -1, + 14216, 14216, 14216, -1, 14217, 14217, 14217, -1, + 14218, 14218, 14218, -1, 14219, 14219, 14219, -1, + 14220, 14220, 14220, -1, 14221, 14221, 14221, -1, + 14222, 14222, 14222, -1, 14223, 14223, 14223, -1, + 14224, 14224, 14224, -1, 14225, 14225, 14225, -1, + 14226, 14226, 14226, -1, 14227, 14227, 14227, -1, + 14228, 14228, 14228, -1, 14229, 14229, 14229, -1, + 14230, 14230, 14230, -1, 14231, 14231, 14231, -1, + 14232, 14232, 14232, -1, 14233, 14233, 14233, -1, + 14234, 14234, 14234, -1, 14235, 14235, 14235, -1, + 14236, 14236, 14236, -1, 14237, 14237, 14237, -1, + 14238, 14238, 14238, -1, 14239, 14239, 14239, -1, + 14240, 14240, 14240, -1, 14241, 14241, 14241, -1, + 14242, 14242, 14242, -1, 14243, 14243, 14243, -1, + 14244, 14244, 14244, -1, 14245, 14245, 14245, -1, + 14246, 14246, 14246, -1, 14247, 14247, 14247, -1, + 14248, 14248, 14248, -1, 14249, 14249, 14249, -1, + 14250, 14250, 14250, -1, 14251, 14251, 14251, -1, + 14252, 14252, 14252, -1, 14253, 14253, 14253, -1, + 14254, 14254, 14254, -1, 14255, 14255, 14255, -1, + 14256, 14256, 14256, -1, 14257, 14257, 14257, -1, + 14258, 14258, 14258, -1, 14259, 14259, 14259, -1, + 14260, 14260, 14260, -1, 14261, 14261, 14261, -1, + 14262, 14262, 14262, -1, 14263, 14263, 14263, -1, + 14264, 14264, 14264, -1, 14265, 14265, 14265, -1, + 14266, 14266, 14266, -1, 14267, 14267, 14267, -1, + 14268, 14268, 14268, -1, 14269, 14269, 14269, -1, + 14270, 14270, 14270, -1, 14271, 14271, 14271, -1, + 14272, 14272, 14272, -1, 14273, 14273, 14273, -1, + 14274, 14274, 14274, -1, 14275, 14275, 14275, -1, + 14276, 14276, 14276, -1, 14277, 14277, 14277, -1, + 14278, 14278, 14278, -1, 14279, 14279, 14279, -1, + 14280, 14280, 14280, -1, 14281, 14281, 14281, -1, + 14282, 14282, 14282, -1, 14283, 14283, 14283, -1, + 14284, 14284, 14284, -1, 14285, 14285, 14285, -1, + 14286, 14286, 14286, -1, 14287, 14287, 14287, -1, + 14288, 14288, 14288, -1, 14289, 14289, 14289, -1, + 14290, 14290, 14290, -1, 14291, 14291, 14291, -1, + 14292, 14292, 14292, -1, 14293, 14293, 14293, -1, + 14294, 14294, 14294, -1, 14295, 14295, 14295, -1, + 14296, 14296, 14296, -1, 14297, 14297, 14297, -1, + 14298, 14298, 14298, -1, 14299, 14299, 14299, -1, + 14300, 14300, 14300, -1, 14301, 14301, 14301, -1, + 14302, 14302, 14302, -1, 14303, 14303, 14303, -1, + 14304, 14304, 14304, -1, 14305, 14305, 14305, -1, + 14306, 14306, 14306, -1, 14307, 14307, 14307, -1, + 14308, 14308, 14308, -1, 14309, 14309, 14309, -1, + 14310, 14310, 14310, -1, 14311, 14311, 14311, -1, + 14312, 14312, 14312, -1, 14313, 14313, 14313, -1, + 14314, 14314, 14314, -1, 14315, 14315, 14315, -1, + 14316, 14316, 14316, -1, 14317, 14317, 14317, -1, + 14318, 14318, 14318, -1, 14319, 14319, 14319, -1, + 14320, 14320, 14320, -1, 14321, 14321, 14321, -1, + 14322, 14322, 14322, -1, 14323, 14323, 14323, -1, + 14324, 14324, 14324, -1, 14325, 14325, 14325, -1, + 14326, 14326, 14326, -1, 14327, 14327, 14327, -1, + 14328, 14328, 14328, -1, 14329, 14329, 14329, -1, + 14330, 14330, 14330, -1, 14331, 14331, 14331, -1, + 14332, 14332, 14332, -1, 14333, 14333, 14333, -1, + 14334, 14334, 14334, -1, 14335, 14335, 14335, -1, + 14336, 14336, 14336, -1, 14337, 14337, 14337, -1, + 14338, 14338, 14338, -1, 14339, 14339, 14339, -1, + 14340, 14340, 14340, -1, 14341, 14341, 14341, -1, + 14342, 14342, 14342, -1, 14343, 14343, 14343, -1, + 14344, 14344, 14344, -1, 14345, 14345, 14345, -1, + 14346, 14346, 14346, -1, 14347, 14347, 14347, -1, + 14348, 14348, 14348, -1, 14349, 14349, 14349, -1, + 14350, 14350, 14350, -1, 14351, 14351, 14351, -1, + 14352, 14352, 14352, -1, 14353, 14353, 14353, -1, + 14354, 14354, 14354, -1, 14355, 14355, 14355, -1, + 14356, 14356, 14356, -1, 14357, 14357, 14357, -1, + 14358, 14358, 14358, -1, 14359, 14359, 14359, -1, + 14360, 14360, 14360, -1, 14361, 14361, 14361, -1, + 14362, 14362, 14362, -1, 14363, 14363, 14363, -1, + 14364, 14364, 14364, -1, 14365, 14365, 14365, -1, + 14366, 14366, 14366, -1, 14367, 14367, 14367, -1, + 14368, 14368, 14368, -1, 14369, 14369, 14369, -1, + 14370, 14370, 14370, -1, 14371, 14371, 14371, -1, + 14372, 14372, 14372, -1, 14373, 14373, 14373, -1, + 14374, 14374, 14374, -1, 14375, 14375, 14375, -1, + 14376, 14376, 14376, -1, 14377, 14377, 14377, -1, + 14378, 14378, 14378, -1, 14379, 14379, 14379, -1, + 14380, 14380, 14380, -1, 14381, 14381, 14381, -1, + 14382, 14382, 14382, -1, 14383, 14383, 14383, -1, + 14384, 14384, 14384, -1, 14385, 14385, 14385, -1, + 14386, 14386, 14386, -1, 14387, 14387, 14387, -1, + 14388, 14388, 14388, -1, 14389, 14389, 14389, -1, + 14390, 14390, 14390, -1, 14391, 14391, 14391, -1, + 14392, 14392, 14392, -1, 14393, 14393, 14393, -1, + 14394, 14394, 14394, -1, 14395, 14395, 14395, -1, + 14396, 14396, 14396, -1, 14397, 14397, 14397, -1, + 14398, 14398, 14398, -1, 14399, 14399, 14399, -1, + 14400, 14400, 14400, -1, 14401, 14401, 14401, -1, + 14402, 14402, 14402, -1, 14403, 14403, 14403, -1, + 14404, 14404, 14404, -1, 14405, 14405, 14405, -1, + 14406, 14406, 14406, -1, 14407, 14407, 14407, -1, + 14408, 14408, 14408, -1, 14409, 14409, 14409, -1, + 14410, 14410, 14410, -1, 14411, 14411, 14411, -1, + 14412, 14412, 14412, -1, 14413, 14413, 14413, -1, + 14414, 14414, 14414, -1, 14415, 14415, 14415, -1, + 14416, 14416, 14416, -1, 14417, 14417, 14417, -1, + 14418, 14418, 14418, -1, 14419, 14419, 14419, -1, + 14420, 14420, 14420, -1, 14421, 14421, 14421, -1, + 14422, 14422, 14422, -1, 14423, 14423, 14423, -1, + 14424, 14424, 14424, -1, 14425, 14425, 14425, -1, + 14426, 14426, 14426, -1, 14427, 14427, 14427, -1, + 14428, 14428, 14428, -1, 14429, 14429, 14429, -1, + 14430, 14430, 14430, -1, 14431, 14431, 14431, -1, + 14432, 14432, 14432, -1, 14433, 14433, 14433, -1, + 14434, 14434, 14434, -1, 14435, 14435, 14435, -1, + 14436, 14436, 14436, -1, 14437, 14437, 14437, -1, + 14438, 14438, 14438, -1, 14439, 14439, 14439, -1, + 14440, 14440, 14440, -1, 14441, 14441, 14441, -1, + 14442, 14442, 14442, -1, 14443, 14443, 14443, -1, + 14444, 14444, 14444, -1, 14445, 14445, 14445, -1, + 14446, 14446, 14446, -1, 14447, 14447, 14447, -1, + 14448, 14448, 14448, -1, 14449, 14449, 14449, -1, + 14450, 14450, 14450, -1, 14451, 14451, 14451, -1, + 14452, 14452, 14452, -1, 14453, 14453, 14453, -1, + 14454, 14454, 14454, -1, 14455, 14455, 14455, -1, + 14456, 14456, 14456, -1, 14457, 14457, 14457, -1, + 14458, 14458, 14458, -1, 14459, 14459, 14459, -1, + 14460, 14460, 14460, -1, 14461, 14461, 14461, -1, + 14462, 14462, 14462, -1, 14463, 14463, 14463, -1, + 14464, 14464, 14464, -1, 14465, 14465, 14465, -1, + 14466, 14466, 14466, -1, 14467, 14467, 14467, -1, + 14468, 14468, 14468, -1, 14469, 14469, 14469, -1, + 14470, 14470, 14470, -1, 14471, 14471, 14471, -1, + 14472, 14472, 14472, -1, 14473, 14473, 14473, -1, + 14474, 14474, 14474, -1, 14475, 14475, 14475, -1, + 14476, 14476, 14476, -1, 14477, 14477, 14477, -1, + 14478, 14478, 14478, -1, 14479, 14479, 14479, -1, + 14480, 14480, 14480, -1, 14481, 14481, 14481, -1, + 14482, 14482, 14482, -1, 14483, 14483, 14483, -1, + 14484, 14484, 14484, -1, 14485, 14485, 14485, -1, + 14486, 14486, 14486, -1, 14487, 14487, 14487, -1, + 14488, 14488, 14488, -1, 14489, 14489, 14489, -1, + 14490, 14490, 14490, -1, 14491, 14491, 14491, -1, + 14492, 14492, 14492, -1, 14493, 14493, 14493, -1, + 14494, 14494, 14494, -1, 14495, 14495, 14495, -1, + 14496, 14496, 14496, -1, 14497, 14497, 14497, -1, + 14498, 14498, 14498, -1, 14499, 14499, 14499, -1, + 14500, 14500, 14500, -1, 14501, 14501, 14501, -1, + 14502, 14502, 14502, -1, 14503, 14503, 14503, -1, + 14504, 14504, 14504, -1, 14505, 14505, 14505, -1, + 14506, 14506, 14506, -1, 14507, 14507, 14507, -1, + 14508, 14508, 14508, -1, 14509, 14509, 14509, -1, + 14510, 14510, 14510, -1, 14511, 14511, 14511, -1, + 14512, 14512, 14512, -1, 14513, 14513, 14513, -1, + 14514, 14514, 14514, -1, 14515, 14515, 14515, -1, + 14516, 14516, 14516, -1, 14517, 14517, 14517, -1, + 14518, 14518, 14518, -1, 14519, 14519, 14519, -1, + 14520, 14520, 14520, -1, 14521, 14521, 14521, -1, + 14522, 14522, 14522, -1, 14523, 14523, 14523, -1, + 14524, 14524, 14524, -1, 14525, 14525, 14525, -1, + 14526, 14526, 14526, -1, 14527, 14527, 14527, -1, + 14528, 14528, 14528, -1, 14529, 14529, 14529, -1, + 14530, 14530, 14530, -1, 14531, 14531, 14531, -1, + 14532, 14532, 14532, -1, 14533, 14533, 14533, -1, + 14534, 14534, 14534, -1, 14535, 14535, 14535, -1, + 14536, 14536, 14536, -1, 14537, 14537, 14537, -1, + 14538, 14538, 14538, -1, 14539, 14539, 14539, -1, + 14540, 14540, 14540, -1, 14541, 14541, 14541, -1, + 14542, 14542, 14542, -1, 14543, 14543, 14543, -1, + 14544, 14544, 14544, -1, 14545, 14545, 14545, -1, + 14546, 14546, 14546, -1, 14547, 14547, 14547, -1, + 14548, 14548, 14548, -1, 14549, 14549, 14549, -1, + 14550, 14550, 14550, -1, 14551, 14551, 14551, -1, + 14552, 14552, 14552, -1, 14553, 14553, 14553, -1, + 14554, 14554, 14554, -1, 14555, 14555, 14555, -1, + 14556, 14556, 14556, -1, 14557, 14557, 14557, -1, + 14558, 14558, 14558, -1, 14559, 14559, 14559, -1, + 14560, 14560, 14560, -1, 14561, 14561, 14561, -1, + 14562, 14562, 14562, -1, 14563, 14563, 14563, -1, + 14564, 14564, 14564, -1, 14565, 14565, 14565, -1, + 14566, 14566, 14566, -1, 14567, 14567, 14567, -1, + 14568, 14568, 14568, -1, 14569, 14569, 14569, -1, + 14570, 14570, 14570, -1, 14571, 14571, 14571, -1, + 14572, 14572, 14572, -1, 14573, 14573, 14573, -1, + 14574, 14574, 14574, -1, 14575, 14575, 14575, -1, + 14576, 14576, 14576, -1, 14577, 14577, 14577, -1, + 14578, 14578, 14578, -1, 14579, 14579, 14579, -1, + 14580, 14580, 14580, -1, 14581, 14581, 14581, -1, + 14582, 14582, 14582, -1, 14583, 14583, 14583, -1, + 14584, 14584, 14584, -1, 14585, 14585, 14585, -1, + 14586, 14586, 14586, -1, 14587, 14587, 14587, -1, + 14588, 14588, 14588, -1, 14589, 14589, 14589, -1, + 14590, 14590, 14590, -1, 14591, 14591, 14591, -1, + 14592, 14592, 14592, -1, 14593, 14593, 14593, -1, + 14594, 14594, 14594, -1, 14595, 14595, 14595, -1, + 14596, 14596, 14596, -1, 14597, 14597, 14597, -1, + 14598, 14598, 14598, -1, 14599, 14599, 14599, -1, + 14600, 14600, 14600, -1, 14601, 14601, 14601, -1, + 14602, 14602, 14602, -1, 14603, 14603, 14603, -1, + 14604, 14604, 14604, -1, 14605, 14605, 14605, -1, + 14606, 14606, 14606, -1, 14607, 14607, 14607, -1, + 14608, 14608, 14608, -1, 14609, 14609, 14609, -1, + 14610, 14610, 14610, -1, 14611, 14611, 14611, -1, + 14612, 14612, 14612, -1, 14613, 14613, 14613, -1, + 14614, 14614, 14614, -1, 14615, 14615, 14615, -1, + 14616, 14616, 14616, -1, 14617, 14617, 14617, -1, + 14618, 14618, 14618, -1, 14619, 14619, 14619, -1, + 14620, 14620, 14620, -1, 14621, 14621, 14621, -1, + 14622, 14622, 14622, -1, 14623, 14623, 14623, -1, + 14624, 14624, 14624, -1, 14625, 14625, 14625, -1, + 14626, 14626, 14626, -1, 14627, 14627, 14627, -1, + 14628, 14628, 14628, -1, 14629, 14629, 14629, -1, + 14630, 14630, 14630, -1, 14631, 14631, 14631, -1, + 14632, 14632, 14632, -1, 14633, 14633, 14633, -1, + 14634, 14634, 14634, -1, 14635, 14635, 14635, -1, + 14636, 14636, 14636, -1, 14637, 14637, 14637, -1, + 14638, 14638, 14638, -1, 14639, 14639, 14639, -1, + 14640, 14640, 14640, -1, 14641, 14641, 14641, -1, + 14642, 14642, 14642, -1, 14643, 14643, 14643, -1, + 14644, 14644, 14644, -1, 14645, 14645, 14645, -1, + 14646, 14646, 14646, -1, 14647, 14647, 14647, -1, + 14648, 14648, 14648, -1, 14649, 14649, 14649, -1, + 14650, 14650, 14650, -1, 14651, 14651, 14651, -1, + 14652, 14652, 14652, -1, 14653, 14653, 14653, -1, + 14654, 14654, 14654, -1, 14655, 14655, 14655, -1, + 14656, 14656, 14656, -1, 14657, 14657, 14657, -1, + 14658, 14658, 14658, -1, 14659, 14659, 14659, -1, + 14660, 14660, 14660, -1, 14661, 14661, 14661, -1, + 14662, 14662, 14662, -1, 14663, 14663, 14663, -1, + 14664, 14664, 14664, -1, 14665, 14665, 14665, -1, + 14666, 14666, 14666, -1, 14667, 14667, 14667, -1, + 14668, 14668, 14668, -1, 14669, 14669, 14669, -1, + 14670, 14670, 14670, -1, 14671, 14671, 14671, -1, + 14672, 14672, 14672, -1, 14673, 14673, 14673, -1, + 14674, 14674, 14674, -1, 14675, 14675, 14675, -1, + 14676, 14676, 14676, -1, 14677, 14677, 14677, -1, + 14678, 14678, 14678, -1, 14679, 14679, 14679, -1, + 14680, 14680, 14680, -1, 14681, 14681, 14681, -1, + 14682, 14682, 14682, -1, 14683, 14683, 14683, -1, + 14684, 14684, 14684, -1, 14685, 14685, 14685, -1, + 14686, 14686, 14686, -1, 14687, 14687, 14687, -1, + 14688, 14688, 14688, -1, 14689, 14689, 14689, -1, + 14690, 14690, 14690, -1, 14691, 14691, 14691, -1, + 14692, 14692, 14692, -1, 14693, 14693, 14693, -1, + 14694, 14694, 14694, -1, 14695, 14695, 14695, -1, + 14696, 14696, 14696, -1, 14697, 14697, 14697, -1, + 14698, 14698, 14698, -1, 14699, 14699, 14699, -1, + 14700, 14700, 14700, -1, 14701, 14701, 14701, -1, + 14702, 14702, 14702, -1, 14703, 14703, 14703, -1, + 14704, 14704, 14704, -1, 14705, 14705, 14705, -1, + 14706, 14706, 14706, -1, 14707, 14707, 14707, -1, + 14708, 14708, 14708, -1, 14709, 14709, 14709, -1, + 14710, 14710, 14710, -1, 14711, 14711, 14711, -1, + 14712, 14712, 14712, -1, 14713, 14713, 14713, -1, + 14714, 14714, 14714, -1, 14715, 14715, 14715, -1, + 14716, 14716, 14716, -1, 14717, 14717, 14717, -1, + 14718, 14718, 14718, -1, 14719, 14719, 14719, -1, + 14720, 14720, 14720, -1, 14721, 14721, 14721, -1, + 14722, 14722, 14722, -1, 14723, 14723, 14723, -1, + 14724, 14724, 14724, -1, 14725, 14725, 14725, -1, + 14726, 14726, 14726, -1, 14727, 14727, 14727, -1, + 14728, 14728, 14728, -1, 14729, 14729, 14729, -1, + 14730, 14730, 14730, -1, 14731, 14731, 14731, -1, + 14732, 14732, 14732, -1, 14733, 14733, 14733, -1, + 14734, 14734, 14734, -1, 14735, 14735, 14735, -1, + 14736, 14736, 14736, -1, 14737, 14737, 14737, -1, + 14738, 14738, 14738, -1, 14739, 14739, 14739, -1, + 14740, 14740, 14740, -1, 14741, 14741, 14741, -1, + 14742, 14742, 14742, -1, 14743, 14743, 14743, -1, + 14744, 14744, 14744, -1, 14745, 14745, 14745, -1, + 14746, 14746, 14746, -1, 14747, 14747, 14747, -1, + 14748, 14748, 14748, -1, 14749, 14749, 14749, -1, + 14750, 14750, 14750, -1, 14751, 14751, 14751, -1, + 14752, 14752, 14752, -1, 14753, 14753, 14753, -1, + 14754, 14754, 14754, -1, 14755, 14755, 14755, -1, + 14756, 14756, 14756, -1, 14757, 14757, 14757, -1, + 14758, 14758, 14758, -1, 14759, 14759, 14759, -1, + 14760, 14760, 14760, -1, 14761, 14761, 14761, -1, + 14762, 14762, 14762, -1, 14763, 14763, 14763, -1, + 14764, 14764, 14764, -1, 14765, 14765, 14765, -1, + 14766, 14766, 14766, -1, 14767, 14767, 14767, -1, + 14768, 14768, 14768, -1, 14769, 14769, 14769, -1, + 14770, 14770, 14770, -1, 14771, 14771, 14771, -1, + 14772, 14772, 14772, -1, 14773, 14773, 14773, -1, + 14774, 14774, 14774, -1, 14775, 14775, 14775, -1, + 14776, 14776, 14776, -1, 14777, 14777, 14777, -1, + 14778, 14778, 14778, -1, 14779, 14779, 14779, -1, + 14780, 14780, 14780, -1, 14781, 14781, 14781, -1, + 14782, 14782, 14782, -1, 14783, 14783, 14783, -1, + 14784, 14784, 14784, -1, 14785, 14785, 14785, -1, + 14786, 14786, 14786, -1, 14787, 14787, 14787, -1, + 14788, 14788, 14788, -1, 14789, 14789, 14789, -1, + 14790, 14790, 14790, -1, 14791, 14791, 14791, -1, + 14792, 14792, 14792, -1, 14793, 14793, 14793, -1, + 14794, 14794, 14794, -1, 14795, 14795, 14795, -1, + 14796, 14796, 14796, -1, 14797, 14797, 14797, -1, + 14798, 14798, 14798, -1, 14799, 14799, 14799, -1, + 14800, 14800, 14800, -1, 14801, 14801, 14801, -1, + 14802, 14802, 14802, -1, 14803, 14803, 14803, -1, + 14804, 14804, 14804, -1, 14805, 14805, 14805, -1, + 14806, 14806, 14806, -1, 14807, 14807, 14807, -1, + 14808, 14808, 14808, -1, 14809, 14809, 14809, -1, + 14810, 14810, 14810, -1, 14811, 14811, 14811, -1, + 14812, 14812, 14812, -1, 14813, 14813, 14813, -1, + 14814, 14814, 14814, -1, 14815, 14815, 14815, -1, + 14816, 14816, 14816, -1, 14817, 14817, 14817, -1, + 14818, 14818, 14818, -1, 14819, 14819, 14819, -1, + 14820, 14820, 14820, -1, 14821, 14821, 14821, -1, + 14822, 14822, 14822, -1, 14823, 14823, 14823, -1, + 14824, 14824, 14824, -1, 14825, 14825, 14825, -1, + 14826, 14826, 14826, -1, 14827, 14827, 14827, -1, + 14828, 14828, 14828, -1, 14829, 14829, 14829, -1, + 14830, 14830, 14830, -1, 14831, 14831, 14831, -1, + 14832, 14832, 14832, -1, 14833, 14833, 14833, -1, + 14834, 14834, 14834, -1, 14835, 14835, 14835, -1, + 14836, 14836, 14836, -1, 14837, 14837, 14837, -1, + 14838, 14838, 14838, -1, 14839, 14839, 14839, -1, + 14840, 14840, 14840, -1, 14841, 14841, 14841, -1, + 14842, 14842, 14842, -1, 14843, 14843, 14843, -1, + 14844, 14844, 14844, -1, 14845, 14845, 14845, -1, + 14846, 14846, 14846, -1, 14847, 14847, 14847, -1, + 14848, 14848, 14848, -1, 14849, 14849, 14849, -1, + 14850, 14850, 14850, -1, 14851, 14851, 14851, -1, + 14852, 14852, 14852, -1, 14853, 14853, 14853, -1, + 14854, 14854, 14854, -1, 14855, 14855, 14855, -1, + 14856, 14856, 14856, -1, 14857, 14857, 14857, -1, + 14858, 14858, 14858, -1, 14859, 14859, 14859, -1, + 14860, 14860, 14860, -1, 14861, 14861, 14861, -1, + 14862, 14862, 14862, -1, 14863, 14863, 14863, -1, + 14864, 14864, 14864, -1, 14865, 14865, 14865, -1, + 14866, 14866, 14866, -1, 14867, 14867, 14867, -1, + 14868, 14868, 14868, -1, 14869, 14869, 14869, -1, + 14870, 14870, 14870, -1, 14871, 14871, 14871, -1, + 14872, 14872, 14872, -1, 14873, 14873, 14873, -1, + 14874, 14874, 14874, -1, 14875, 14875, 14875, -1, + 14876, 14876, 14876, -1, 14877, 14877, 14877, -1, + 14878, 14878, 14878, -1, 14879, 14879, 14879, -1, + 14880, 14880, 14880, -1, 14881, 14881, 14881, -1, + 14882, 14882, 14882, -1, 14883, 14883, 14883, -1, + 14884, 14884, 14884, -1, 14885, 14885, 14885, -1, + 14886, 14886, 14886, -1, 14887, 14887, 14887, -1, + 14888, 14888, 14888, -1, 14889, 14889, 14889, -1, + 14890, 14890, 14890, -1, 14891, 14891, 14891, -1, + 14892, 14892, 14892, -1, 14893, 14893, 14893, -1, + 14894, 14894, 14894, -1, 14895, 14895, 14895, -1, + 14896, 14896, 14896, -1, 14897, 14897, 14897, -1, + 14898, 14898, 14898, -1, 14899, 14899, 14899, -1, + 14900, 14900, 14900, -1, 14901, 14901, 14901, -1, + 14902, 14902, 14902, -1, 14903, 14903, 14903, -1, + 14904, 14904, 14904, -1, 14905, 14905, 14905, -1, + 14906, 14906, 14906, -1, 14907, 14907, 14907, -1, + 14908, 14908, 14908, -1, 14909, 14909, 14909, -1, + 14910, 14910, 14910, -1, 14911, 14911, 14911, -1, + 14912, 14912, 14912, -1, 14913, 14913, 14913, -1, + 14914, 14914, 14914, -1, 14915, 14915, 14915, -1, + 14916, 14916, 14916, -1, 14917, 14917, 14917, -1, + 14918, 14918, 14918, -1, 14919, 14919, 14919, -1, + 14920, 14920, 14920, -1, 14921, 14921, 14921, -1, + 14922, 14922, 14922, -1, 14923, 14923, 14923, -1, + 14924, 14924, 14924, -1, 14925, 14925, 14925, -1, + 14926, 14926, 14926, -1, 14927, 14927, 14927, -1, + 14928, 14928, 14928, -1, 14929, 14929, 14929, -1, + 14930, 14930, 14930, -1, 14931, 14931, 14931, -1, + 14932, 14932, 14932, -1, 14933, 14933, 14933, -1, + 14934, 14934, 14934, -1, 14935, 14935, 14935, -1, + 14936, 14936, 14936, -1, 14937, 14937, 14937, -1, + 14938, 14938, 14938, -1, 14939, 14939, 14939, -1, + 14940, 14940, 14940, -1, 14941, 14941, 14941, -1, + 14942, 14942, 14942, -1, 14943, 14943, 14943, -1, + 14944, 14944, 14944, -1, 14945, 14945, 14945, -1, + 14946, 14946, 14946, -1, 14947, 14947, 14947, -1, + 14948, 14948, 14948, -1, 14949, 14949, 14949, -1, + 14950, 14950, 14950, -1, 14951, 14951, 14951, -1, + 14952, 14952, 14952, -1, 14953, 14953, 14953, -1, + 14954, 14954, 14954, -1, 14955, 14955, 14955, -1, + 14956, 14956, 14956, -1, 14957, 14957, 14957, -1, + 14958, 14958, 14958, -1, 14959, 14959, 14959, -1, + 14960, 14960, 14960, -1, 14961, 14961, 14961, -1, + 14962, 14962, 14962, -1, 14963, 14963, 14963, -1, + 14964, 14964, 14964, -1, 14965, 14965, 14965, -1, + 14966, 14966, 14966, -1, 14967, 14967, 14967, -1, + 14968, 14968, 14968, -1, 14969, 14969, 14969, -1, + 14970, 14970, 14970, -1, 14971, 14971, 14971, -1, + 14972, 14972, 14972, -1, 14973, 14973, 14973, -1, + 14974, 14974, 14974, -1, 14975, 14975, 14975, -1, + 14976, 14976, 14976, -1, 14977, 14977, 14977, -1, + 14978, 14978, 14978, -1, 14979, 14979, 14979, -1, + 14980, 14980, 14980, -1, 14981, 14981, 14981, -1, + 14982, 14982, 14982, -1, 14983, 14983, 14983, -1, + 14984, 14984, 14984, -1, 14985, 14985, 14985, -1, + 14986, 14986, 14986, -1, 14987, 14987, 14987, -1, + 14988, 14988, 14988, -1, 14989, 14989, 14989, -1, + 14990, 14990, 14990, -1, 14991, 14991, 14991, -1, + 14992, 14992, 14992, -1, 14993, 14993, 14993, -1, + 14994, 14994, 14994, -1, 14995, 14995, 14995, -1, + 14996, 14996, 14996, -1, 14997, 14997, 14997, -1, + 14998, 14998, 14998, -1, 14999, 14999, 14999, -1, + 15000, 15000, 15000, -1, 15001, 15001, 15001, -1, + 15002, 15002, 15002, -1, 15003, 15003, 15003, -1, + 15004, 15004, 15004, -1, 15005, 15005, 15005, -1, + 15006, 15006, 15006, -1, 15007, 15007, 15007, -1, + 15008, 15008, 15008, -1, 15009, 15009, 15009, -1, + 15010, 15010, 15010, -1, 15011, 15011, 15011, -1, + 15012, 15012, 15012, -1, 15013, 15013, 15013, -1, + 15014, 15014, 15014, -1, 15015, 15015, 15015, -1, + 15016, 15016, 15016, -1, 15017, 15017, 15017, -1, + 15018, 15018, 15018, -1, 15019, 15019, 15019, -1, + 15020, 15020, 15020, -1, 15021, 15021, 15021, -1, + 15022, 15022, 15022, -1, 15023, 15023, 15023, -1, + 15024, 15024, 15024, -1, 15025, 15025, 15025, -1, + 15026, 15026, 15026, -1, 15027, 15027, 15027, -1, + 15028, 15028, 15028, -1, 15029, 15029, 15029, -1, + 15030, 15030, 15030, -1, 15031, 15031, 15031, -1, + 15032, 15032, 15032, -1, 15033, 15033, 15033, -1, + 15034, 15034, 15034, -1, 15035, 15035, 15035, -1, + 15036, 15036, 15036, -1, 15037, 15037, 15037, -1, + 15038, 15038, 15038, -1, 15039, 15039, 15039, -1, + 15040, 15040, 15040, -1, 15041, 15041, 15041, -1, + 15042, 15042, 15042, -1, 15043, 15043, 15043, -1, + 15044, 15044, 15044, -1, 15045, 15045, 15045, -1, + 15046, 15046, 15046, -1, 15047, 15047, 15047, -1, + 15048, 15048, 15048, -1, 15049, 15049, 15049, -1, + 15050, 15050, 15050, -1, 15051, 15051, 15051, -1, + 15052, 15052, 15052, -1, 15053, 15053, 15053, -1, + 15054, 15054, 15054, -1, 15055, 15055, 15055, -1, + 15056, 15056, 15056, -1, 15057, 15057, 15057, -1, + 15058, 15058, 15058, -1, 15059, 15059, 15059, -1, + 15060, 15060, 15060, -1, 15061, 15061, 15061, -1, + 15062, 15062, 15062, -1, 15063, 15063, 15063, -1, + 15064, 15064, 15064, -1, 15065, 15065, 15065, -1, + 15066, 15066, 15066, -1, 15067, 15067, 15067, -1, + 15068, 15068, 15068, -1, 15069, 15069, 15069, -1, + 15070, 15070, 15070, -1, 15071, 15071, 15071, -1, + 15072, 15072, 15072, -1, 15073, 15073, 15073, -1, + 15074, 15074, 15074, -1, 15075, 15075, 15075, -1, + 15076, 15076, 15076, -1, 15077, 15077, 15077, -1, + 15078, 15078, 15078, -1, 15079, 15079, 15079, -1, + 15080, 15080, 15080, -1, 15081, 15081, 15081, -1, + 15082, 15082, 15082, -1, 15083, 15083, 15083, -1, + 15084, 15084, 15084, -1, 15085, 15085, 15085, -1, + 15086, 15086, 15086, -1, 15087, 15087, 15087, -1, + 15088, 15088, 15088, -1, 15089, 15089, 15089, -1, + 15090, 15090, 15090, -1, 15091, 15091, 15091, -1, + 15092, 15092, 15092, -1, 15093, 15093, 15093, -1, + 15094, 15094, 15094, -1, 15095, 15095, 15095, -1, + 15096, 15096, 15096, -1, 15097, 15097, 15097, -1, + 15098, 15098, 15098, -1, 15099, 15099, 15099, -1, + 15100, 15100, 15100, -1, 15101, 15101, 15101, -1, + 15102, 15102, 15102, -1, 15103, 15103, 15103, -1, + 15104, 15104, 15104, -1, 15105, 15105, 15105, -1, + 15106, 15106, 15106, -1, 15107, 15107, 15107, -1, + 15108, 15108, 15108, -1, 15109, 15109, 15109, -1, + 15110, 15110, 15110, -1, 15111, 15111, 15111, -1, + 15112, 15112, 15112, -1, 15113, 15113, 15113, -1, + 15114, 15114, 15114, -1, 15115, 15115, 15115, -1, + 15116, 15116, 15116, -1, 15117, 15117, 15117, -1, + 15118, 15118, 15118, -1, 15119, 15119, 15119, -1, + 15120, 15120, 15120, -1, 15121, 15121, 15121, -1, + 15122, 15122, 15122, -1, 15123, 15123, 15123, -1, + 15124, 15124, 15124, -1, 15125, 15125, 15125, -1, + 15126, 15126, 15126, -1, 15127, 15127, 15127, -1, + 15128, 15128, 15128, -1, 15129, 15129, 15129, -1, + 15130, 15130, 15130, -1, 15131, 15131, 15131, -1, + 15132, 15132, 15132, -1, 15133, 15133, 15133, -1, + 15134, 15134, 15134, -1, 15135, 15135, 15135, -1, + 15136, 15136, 15136, -1, 15137, 15137, 15137, -1, + 15138, 15138, 15138, -1, 15139, 15139, 15139, -1, + 15140, 15140, 15140, -1, 15141, 15141, 15141, -1, + 15142, 15142, 15142, -1, 15143, 15143, 15143, -1, + 15144, 15144, 15144, -1, 15145, 15145, 15145, -1, + 15146, 15146, 15146, -1, 15147, 15147, 15147, -1, + 15148, 15148, 15148, -1, 15149, 15149, 15149, -1, + 15150, 15150, 15150, -1, 15151, 15151, 15151, -1, + 15152, 15152, 15152, -1, 15153, 15153, 15153, -1, + 15154, 15154, 15154, -1, 15155, 15155, 15155, -1, + 15156, 15156, 15156, -1, 15157, 15157, 15157, -1, + 15158, 15158, 15158, -1, 15159, 15159, 15159, -1, + 15160, 15160, 15160, -1, 15161, 15161, 15161, -1, + 15162, 15162, 15162, -1, 15163, 15163, 15163, -1, + 15164, 15164, 15164, -1, 15165, 15165, 15165, -1, + 15166, 15166, 15166, -1, 15167, 15167, 15167, -1, + 15168, 15168, 15168, -1, 15169, 15169, 15169, -1, + 15170, 15170, 15170, -1, 15171, 15171, 15171, -1, + 15172, 15172, 15172, -1, 15173, 15173, 15173, -1, + 15174, 15174, 15174, -1, 15175, 15175, 15175, -1, + 15176, 15176, 15176, -1, 15177, 15177, 15177, -1, + 15178, 15178, 15178, -1, 15179, 15179, 15179, -1, + 15180, 15180, 15180, -1, 15181, 15181, 15181, -1, + 15182, 15182, 15182, -1, 15183, 15183, 15183, -1, + 15184, 15184, 15184, -1, 15185, 15185, 15185, -1, + 15186, 15186, 15186, -1, 15187, 15187, 15187, -1, + 15188, 15188, 15188, -1, 15189, 15189, 15189, -1, + 15190, 15190, 15190, -1, 15191, 15191, 15191, -1, + 15192, 15192, 15192, -1, 15193, 15193, 15193, -1, + 15194, 15194, 15194, -1, 15195, 15195, 15195, -1, + 15196, 15196, 15196, -1, 15197, 15197, 15197, -1, + 15198, 15198, 15198, -1, 15199, 15199, 15199, -1, + 15200, 15200, 15200, -1, 15201, 15201, 15201, -1, + 15202, 15202, 15202, -1, 15203, 15203, 15203, -1, + 15204, 15204, 15204, -1, 15205, 15205, 15205, -1, + 15206, 15206, 15206, -1, 15207, 15207, 15207, -1, + 15208, 15208, 15208, -1, 15209, 15209, 15209, -1, + 15210, 15210, 15210, -1, 15211, 15211, 15211, -1, + 15212, 15212, 15212, -1, 15213, 15213, 15213, -1, + 15214, 15214, 15214, -1, 15215, 15215, 15215, -1, + 15216, 15216, 15216, -1, 15217, 15217, 15217, -1, + 15218, 15218, 15218, -1, 15219, 15219, 15219, -1, + 15220, 15220, 15220, -1, 15221, 15221, 15221, -1, + 15222, 15222, 15222, -1, 15223, 15223, 15223, -1, + 15224, 15224, 15224, -1, 15225, 15225, 15225, -1, + 15226, 15226, 15226, -1, 15227, 15227, 15227, -1, + 15228, 15228, 15228, -1, 15229, 15229, 15229, -1, + 15230, 15230, 15230, -1, 15231, 15231, 15231, -1, + 15232, 15232, 15232, -1, 15233, 15233, 15233, -1, + 15234, 15234, 15234, -1, 15235, 15235, 15235, -1, + 15236, 15236, 15236, -1, 15237, 15237, 15237, -1, + 15238, 15238, 15238, -1, 15239, 15239, 15239, -1, + 15240, 15240, 15240, -1, 15241, 15241, 15241, -1, + 15242, 15242, 15242, -1, 15243, 15243, 15243, -1, + 15244, 15244, 15244, -1, 15245, 15245, 15245, -1, + 15246, 15246, 15246, -1, 15247, 15247, 15247, -1, + 15248, 15248, 15248, -1, 15249, 15249, 15249, -1, + 15250, 15250, 15250, -1, 15251, 15251, 15251, -1, + 15252, 15252, 15252, -1, 15253, 15253, 15253, -1, + 15254, 15254, 15254, -1, 15255, 15255, 15255, -1, + 15256, 15256, 15256, -1, 15257, 15257, 15257, -1, + 15258, 15258, 15258, -1, 15259, 15259, 15259, -1, + 15260, 15260, 15260, -1, 15261, 15261, 15261, -1, + 15262, 15262, 15262, -1, 15263, 15263, 15263, -1, + 15264, 15264, 15264, -1, 15265, 15265, 15265, -1, + 15266, 15266, 15266, -1, 15267, 15267, 15267, -1, + 15268, 15268, 15268, -1, 15269, 15269, 15269, -1, + 15270, 15270, 15270, -1, 15271, 15271, 15271, -1, + 15272, 15272, 15272, -1, 15273, 15273, 15273, -1, + 15274, 15274, 15274, -1, 15275, 15275, 15275, -1, + 15276, 15276, 15276, -1, 15277, 15277, 15277, -1, + 15278, 15278, 15278, -1, 15279, 15279, 15279, -1, + 15280, 15280, 15280, -1, 15281, 15281, 15281, -1, + 15282, 15282, 15282, -1, 15283, 15283, 15283, -1, + 15284, 15284, 15284, -1, 15285, 15285, 15285, -1, + 15286, 15286, 15286, -1, 15287, 15287, 15287, -1, + 15288, 15288, 15288, -1, 15289, 15289, 15289, -1, + 15290, 15290, 15290, -1, 15291, 15291, 15291, -1, + 15292, 15292, 15292, -1, 15293, 15293, 15293, -1, + 15294, 15294, 15294, -1, 15295, 15295, 15295, -1, + 15296, 15296, 15296, -1, 15297, 15297, 15297, -1, + 15298, 15298, 15298, -1, 15299, 15299, 15299, -1, + 15300, 15300, 15300, -1, 15301, 15301, 15301, -1, + 15302, 15302, 15302, -1, 15303, 15303, 15303, -1, + 15304, 15304, 15304, -1, 15305, 15305, 15305, -1, + 15306, 15306, 15306, -1, 15307, 15307, 15307, -1, + 15308, 15308, 15308, -1, 15309, 15309, 15309, -1, + 15310, 15310, 15310, -1, 15311, 15311, 15311, -1, + 15312, 15312, 15312, -1, 15313, 15313, 15313, -1, + 15314, 15314, 15314, -1, 15315, 15315, 15315, -1, + 15316, 15316, 15316, -1, 15317, 15317, 15317, -1, + 15318, 15318, 15318, -1, 15319, 15319, 15319, -1, + 15320, 15320, 15320, -1, 15321, 15321, 15321, -1, + 15322, 15322, 15322, -1, 15323, 15323, 15323, -1, + 15324, 15324, 15324, -1, 15325, 15325, 15325, -1, + 15326, 15326, 15326, -1, 15327, 15327, 15327, -1, + 15328, 15328, 15328, -1, 15329, 15329, 15329, -1, + 15330, 15330, 15330, -1, 15331, 15331, 15331, -1, + 15332, 15332, 15332, -1, 15333, 15333, 15333, -1, + 15334, 15334, 15334, -1, 15335, 15335, 15335, -1, + 15336, 15336, 15336, -1, 15337, 15337, 15337, -1, + 15338, 15338, 15338, -1, 15339, 15339, 15339, -1, + 15340, 15340, 15340, -1, 15341, 15341, 15341, -1, + 15342, 15342, 15342, -1, 15343, 15343, 15343, -1, + 15344, 15344, 15344, -1, 15345, 15345, 15345, -1, + 15346, 15346, 15346, -1, 15347, 15347, 15347, -1, + 15348, 15348, 15348, -1, 15349, 15349, 15349, -1, + 15350, 15350, 15350, -1, 15351, 15351, 15351, -1, + 15352, 15352, 15352, -1, 15353, 15353, 15353, -1, + 15354, 15354, 15354, -1, 15355, 15355, 15355, -1, + 15356, 15356, 15356, -1, 15357, 15357, 15357, -1, + 15358, 15358, 15358, -1, 15359, 15359, 15359, -1, + 15360, 15360, 15360, -1, 15361, 15361, 15361, -1, + 15362, 15362, 15362, -1, 15363, 15363, 15363, -1, + 15364, 15364, 15364, -1, 15365, 15365, 15365, -1, + 15366, 15366, 15366, -1, 15367, 15367, 15367, -1, + 15368, 15368, 15368, -1, 15369, 15369, 15369, -1, + 15370, 15370, 15370, -1, 15371, 15371, 15371, -1, + 15372, 15372, 15372, -1, 15373, 15373, 15373, -1, + 15374, 15374, 15374, -1, 15375, 15375, 15375, -1, + 15376, 15376, 15376, -1, 15377, 15377, 15377, -1, + 15378, 15378, 15378, -1, 15379, 15379, 15379, -1, + 15380, 15380, 15380, -1, 15381, 15381, 15381, -1, + 15382, 15382, 15382, -1, 15383, 15383, 15383, -1, + 15384, 15384, 15384, -1, 15385, 15385, 15385, -1, + 15386, 15386, 15386, -1, 15387, 15387, 15387, -1, + 15388, 15388, 15388, -1, 15389, 15389, 15389, -1, + 15390, 15390, 15390, -1, 15391, 15391, 15391, -1, + 15392, 15392, 15392, -1, 15393, 15393, 15393, -1, + 15394, 15394, 15394, -1, 15395, 15395, 15395, -1, + 15396, 15396, 15396, -1, 15397, 15397, 15397, -1, + 15398, 15398, 15398, -1, 15399, 15399, 15399, -1, + 15400, 15400, 15400, -1, 15401, 15401, 15401, -1, + 15402, 15402, 15402, -1, 15403, 15403, 15403, -1, + 15404, 15404, 15404, -1, 15405, 15405, 15405, -1, + 15406, 15406, 15406, -1, 15407, 15407, 15407, -1, + 15408, 15408, 15408, -1, 15409, 15409, 15409, -1, + 15410, 15410, 15410, -1, 15411, 15411, 15411, -1, + 15412, 15412, 15412, -1, 15413, 15413, 15413, -1, + 15414, 15414, 15414, -1, 15415, 15415, 15415, -1, + 15416, 15416, 15416, -1, 15417, 15417, 15417, -1, + 15418, 15418, 15418, -1, 15419, 15419, 15419, -1, + 15420, 15420, 15420, -1, 15421, 15421, 15421, -1, + 15422, 15422, 15422, -1, 15423, 15423, 15423, -1, + 15424, 15424, 15424, -1, 15425, 15425, 15425, -1, + 15426, 15426, 15426, -1, 15427, 15427, 15427, -1, + 15428, 15428, 15428, -1, 15429, 15429, 15429, -1, + 15430, 15430, 15430, -1, 15431, 15431, 15431, -1, + 15432, 15432, 15432, -1, 15433, 15433, 15433, -1, + 15434, 15434, 15434, -1, 15435, 15435, 15435, -1, + 15436, 15436, 15436, -1, 15437, 15437, 15437, -1, + 15438, 15438, 15438, -1, 15439, 15439, 15439, -1, + 15440, 15440, 15440, -1, 15441, 15441, 15441, -1, + 15442, 15442, 15442, -1, 15443, 15443, 15443, -1, + 15444, 15444, 15444, -1, 15445, 15445, 15445, -1, + 15446, 15446, 15446, -1, 15447, 15447, 15447, -1, + 15448, 15448, 15448, -1, 15449, 15449, 15449, -1, + 15450, 15450, 15450, -1, 15451, 15451, 15451, -1, + 15452, 15452, 15452, -1, 15453, 15453, 15453, -1, + 15454, 15454, 15454, -1, 15455, 15455, 15455, -1, + 15456, 15456, 15456, -1, 15457, 15457, 15457, -1, + 15458, 15458, 15458, -1, 15459, 15459, 15459, -1, + 15460, 15460, 15460, -1, 15461, 15461, 15461, -1, + 15462, 15462, 15462, -1, 15463, 15463, 15463, -1, + 15464, 15464, 15464, -1, 15465, 15465, 15465, -1, + 15466, 15466, 15466, -1, 15467, 15467, 15467, -1, + 15468, 15468, 15468, -1, 15469, 15469, 15469, -1, + 15470, 15470, 15470, -1, 15471, 15471, 15471, -1, + 15472, 15472, 15472, -1, 15473, 15473, 15473, -1, + 15474, 15474, 15474, -1, 15475, 15475, 15475, -1, + 15476, 15476, 15476, -1, 15477, 15477, 15477, -1, + 15478, 15478, 15478, -1, 15479, 15479, 15479, -1, + 15480, 15480, 15480, -1, 15481, 15481, 15481, -1, + 15482, 15482, 15482, -1, 15483, 15483, 15483, -1, + 15484, 15484, 15484, -1, 15485, 15485, 15485, -1, + 15486, 15486, 15486, -1, 15487, 15487, 15487, -1, + 15488, 15488, 15488, -1, 15489, 15489, 15489, -1, + 15490, 15490, 15490, -1, 15491, 15491, 15491, -1, + 15492, 15492, 15492, -1, 15493, 15493, 15493, -1, + 15494, 15494, 15494, -1, 15495, 15495, 15495, -1, + 15496, 15496, 15496, -1, 15497, 15497, 15497, -1, + 15498, 15498, 15498, -1, 15499, 15499, 15499, -1, + 15500, 15500, 15500, -1, 15501, 15501, 15501, -1, + 15502, 15502, 15502, -1, 15503, 15503, 15503, -1, + 15504, 15504, 15504, -1, 15505, 15505, 15505, -1, + 15506, 15506, 15506, -1, 15507, 15507, 15507, -1, + 15508, 15508, 15508, -1, 15509, 15509, 15509, -1, + 15510, 15510, 15510, -1, 15511, 15511, 15511, -1, + 15512, 15512, 15512, -1, 15513, 15513, 15513, -1, + 15514, 15514, 15514, -1, 15515, 15515, 15515, -1, + 15516, 15516, 15516, -1, 15517, 15517, 15517, -1, + 15518, 15518, 15518, -1, 15519, 15519, 15519, -1, + 15520, 15520, 15520, -1, 15521, 15521, 15521, -1, + 15522, 15522, 15522, -1, 15523, 15523, 15523, -1, + 15524, 15524, 15524, -1, 15525, 15525, 15525, -1, + 15526, 15526, 15526, -1, 15527, 15527, 15527, -1, + 15528, 15528, 15528, -1, 15529, 15529, 15529, -1, + 15530, 15530, 15530, -1, 15531, 15531, 15531, -1, + 15532, 15532, 15532, -1, 15533, 15533, 15533, -1, + 15534, 15534, 15534, -1, 15535, 15535, 15535, -1, + 15536, 15536, 15536, -1, 15537, 15537, 15537, -1, + 15538, 15538, 15538, -1, 15539, 15539, 15539, -1, + 15540, 15540, 15540, -1, 15541, 15541, 15541, -1, + 15542, 15542, 15542, -1, 15543, 15543, 15543, -1, + 15544, 15544, 15544, -1, 15545, 15545, 15545, -1, + 15546, 15546, 15546, -1, 15547, 15547, 15547, -1, + 15548, 15548, 15548, -1, 15549, 15549, 15549, -1, + 15550, 15550, 15550, -1, 15551, 15551, 15551, -1, + 15552, 15552, 15552, -1, 15553, 15553, 15553, -1, + 15554, 15554, 15554, -1, 15555, 15555, 15555, -1, + 15556, 15556, 15556, -1, 15557, 15557, 15557, -1, + 15558, 15558, 15558, -1, 15559, 15559, 15559, -1, + 15560, 15560, 15560, -1, 15561, 15561, 15561, -1, + 15562, 15562, 15562, -1, 15563, 15563, 15563, -1, + 15564, 15564, 15564, -1, 15565, 15565, 15565, -1, + 15566, 15566, 15566, -1, 15567, 15567, 15567, -1, + 15568, 15568, 15568, -1, 15569, 15569, 15569, -1, + 15570, 15570, 15570, -1, 15571, 15571, 15571, -1, + 15572, 15572, 15572, -1, 15573, 15573, 15573, -1, + 15574, 15574, 15574, -1, 15575, 15575, 15575, -1, + 15576, 15576, 15576, -1, 15577, 15577, 15577, -1, + 15578, 15578, 15578, -1, 15579, 15579, 15579, -1, + 15580, 15580, 15580, -1, 15581, 15581, 15581, -1, + 15582, 15582, 15582, -1, 15583, 15583, 15583, -1, + 15584, 15584, 15584, -1, 15585, 15585, 15585, -1, + 15586, 15586, 15586, -1, 15587, 15587, 15587, -1, + 15588, 15588, 15588, -1, 15589, 15589, 15589, -1, + 15590, 15590, 15590, -1, 15591, 15591, 15591, -1, + 15592, 15592, 15592, -1, 15593, 15593, 15593, -1, + 15594, 15594, 15594, -1, 15595, 15595, 15595, -1, + 15596, 15596, 15596, -1, 15597, 15597, 15597, -1, + 15598, 15598, 15598, -1, 15599, 15599, 15599, -1, + 15600, 15600, 15600, -1, 15601, 15601, 15601, -1, + 15602, 15602, 15602, -1, 15603, 15603, 15603, -1, + 15604, 15604, 15604, -1, 15605, 15605, 15605, -1, + 15606, 15606, 15606, -1, 15607, 15607, 15607, -1, + 15608, 15608, 15608, -1, 15609, 15609, 15609, -1, + 15610, 15610, 15610, -1, 15611, 15611, 15611, -1, + 15612, 15612, 15612, -1, 15613, 15613, 15613, -1, + 15614, 15614, 15614, -1, 15615, 15615, 15615, -1, + 15616, 15616, 15616, -1, 15617, 15617, 15617, -1, + 15618, 15618, 15618, -1, 15619, 15619, 15619, -1, + 15620, 15620, 15620, -1, 15621, 15621, 15621, -1, + 15622, 15622, 15622, -1, 15623, 15623, 15623, -1, + 15624, 15624, 15624, -1, 15625, 15625, 15625, -1, + 15626, 15626, 15626, -1, 15627, 15627, 15627, -1, + 15628, 15628, 15628, -1, 15629, 15629, 15629, -1, + 15630, 15630, 15630, -1, 15631, 15631, 15631, -1, + 15632, 15632, 15632, -1, 15633, 15633, 15633, -1, + 15634, 15634, 15634, -1, 15635, 15635, 15635, -1, + 15636, 15636, 15636, -1, 15637, 15637, 15637, -1, + 15638, 15638, 15638, -1, 15639, 15639, 15639, -1, + 15640, 15640, 15640, -1, 15641, 15641, 15641, -1, + 15642, 15642, 15642, -1, 15643, 15643, 15643, -1, + 15644, 15644, 15644, -1, 15645, 15645, 15645, -1, + 15646, 15646, 15646, -1, 15647, 15647, 15647, -1, + 15648, 15648, 15648, -1, 15649, 15649, 15649, -1, + 15650, 15650, 15650, -1, 15651, 15651, 15651, -1, + 15652, 15652, 15652, -1, 15653, 15653, 15653, -1, + 15654, 15654, 15654, -1, 15655, 15655, 15655, -1, + 15656, 15656, 15656, -1, 15657, 15657, 15657, -1, + 15658, 15658, 15658, -1, 15659, 15659, 15659, -1, + 15660, 15660, 15660, -1, 15661, 15661, 15661, -1, + 15662, 15662, 15662, -1, 15663, 15663, 15663, -1, + 15664, 15664, 15664, -1, 15665, 15665, 15665, -1, + 15666, 15666, 15666, -1, 15667, 15667, 15667, -1, + 15668, 15668, 15668, -1, 15669, 15669, 15669, -1, + 15670, 15670, 15670, -1, 15671, 15671, 15671, -1, + 15672, 15672, 15672, -1, 15673, 15673, 15673, -1, + 15674, 15674, 15674, -1, 15675, 15675, 15675, -1, + 15676, 15676, 15676, -1, 15677, 15677, 15677, -1, + 15678, 15678, 15678, -1, 15679, 15679, 15679, -1, + 15680, 15680, 15680, -1, 15681, 15681, 15681, -1, + 15682, 15682, 15682, -1, 15683, 15683, 15683, -1, + 15684, 15684, 15684, -1, 15685, 15685, 15685, -1, + 15686, 15686, 15686, -1, 15687, 15687, 15687, -1, + 15688, 15688, 15688, -1, 15689, 15689, 15689, -1, + 15690, 15690, 15690, -1, 15691, 15691, 15691, -1, + 15692, 15692, 15692, -1, 15693, 15693, 15693, -1, + 15694, 15694, 15694, -1, 15695, 15695, 15695, -1, + 15696, 15696, 15696, -1, 15697, 15697, 15697, -1, + 15698, 15698, 15698, -1, 15699, 15699, 15699, -1, + 15700, 15700, 15700, -1, 15701, 15701, 15701, -1, + 15702, 15702, 15702, -1, 15703, 15703, 15703, -1, + 15704, 15704, 15704, -1, 15705, 15705, 15705, -1, + 15706, 15706, 15706, -1, 15707, 15707, 15707, -1, + 15708, 15708, 15708, -1, 15709, 15709, 15709, -1, + 15710, 15710, 15710, -1, 15711, 15711, 15711, -1, + 15712, 15712, 15712, -1, 15713, 15713, 15713, -1, + 15714, 15714, 15714, -1, 15715, 15715, 15715, -1, + 15716, 15716, 15716, -1, 15717, 15717, 15717, -1, + 15718, 15718, 15718, -1, 15719, 15719, 15719, -1, + 15720, 15720, 15720, -1, 15721, 15721, 15721, -1, + 15722, 15722, 15722, -1, 15723, 15723, 15723, -1, + 15724, 15724, 15724, -1, 15725, 15725, 15725, -1, + 15726, 15726, 15726, -1, 15727, 15727, 15727, -1, + 15728, 15728, 15728, -1, 15729, 15729, 15729, -1, + 15730, 15730, 15730, -1, 15731, 15731, 15731, -1, + 15732, 15732, 15732, -1, 15733, 15733, 15733, -1, + 15734, 15734, 15734, -1, 15735, 15735, 15735, -1, + 15736, 15736, 15736, -1, 15737, 15737, 15737, -1, + 15738, 15738, 15738, -1, 15739, 15739, 15739, -1, + 15740, 15740, 15740, -1, 15741, 15741, 15741, -1, + 15742, 15742, 15742, -1, 15743, 15743, 15743, -1, + 15744, 15744, 15744, -1, 15745, 15745, 15745, -1, + 15746, 15746, 15746, -1, 15747, 15747, 15747, -1, + 15748, 15748, 15748, -1, 15749, 15749, 15749, -1, + 15750, 15750, 15750, -1, 15751, 15751, 15751, -1, + 15752, 15752, 15752, -1, 15753, 15753, 15753, -1, + 15754, 15754, 15754, -1, 15755, 15755, 15755, -1, + 15756, 15756, 15756, -1, 15757, 15757, 15757, -1, + 15758, 15758, 15758, -1, 15759, 15759, 15759, -1, + 15760, 15760, 15760, -1, 15761, 15761, 15761, -1, + 15762, 15762, 15762, -1, 15763, 15763, 15763, -1, + 15764, 15764, 15764, -1, 15765, 15765, 15765, -1, + 15766, 15766, 15766, -1, 15767, 15767, 15767, -1, + 15768, 15768, 15768, -1, 15769, 15769, 15769, -1, + 15770, 15770, 15770, -1, 15771, 15771, 15771, -1, + 15772, 15772, 15772, -1, 15773, 15773, 15773, -1, + 15774, 15774, 15774, -1, 15775, 15775, 15775, -1, + 15776, 15776, 15776, -1, 15777, 15777, 15777, -1, + 15778, 15778, 15778, -1, 15779, 15779, 15779, -1, + 15780, 15780, 15780, -1, 15781, 15781, 15781, -1, + 15782, 15782, 15782, -1, 15783, 15783, 15783, -1, + 15784, 15784, 15784, -1, 15785, 15785, 15785, -1, + 15786, 15786, 15786, -1, 15787, 15787, 15787, -1, + 15788, 15788, 15788, -1, 15789, 15789, 15789, -1, + 15790, 15790, 15790, -1, 15791, 15791, 15791, -1, + 15792, 15792, 15792, -1, 15793, 15793, 15793, -1, + 15794, 15794, 15794, -1, 15795, 15795, 15795, -1, + 15796, 15796, 15796, -1, 15797, 15797, 15797, -1, + 15798, 15798, 15798, -1, 15799, 15799, 15799, -1, + 15800, 15800, 15800, -1, 15801, 15801, 15801, -1, + 15802, 15802, 15802, -1, 15803, 15803, 15803, -1, + 15804, 15804, 15804, -1, 15805, 15805, 15805, -1, + 15806, 15806, 15806, -1, 15807, 15807, 15807, -1, + 15808, 15808, 15808, -1, 15809, 15809, 15809, -1, + 15810, 15810, 15810, -1, 15811, 15811, 15811, -1, + 15812, 15812, 15812, -1, 15813, 15813, 15813, -1, + 15814, 15814, 15814, -1, 15815, 15815, 15815, -1, + 15816, 15816, 15816, -1, 15817, 15817, 15817, -1, + 15818, 15818, 15818, -1, 15819, 15819, 15819, -1, + 15820, 15820, 15820, -1, 15821, 15821, 15821, -1, + 15822, 15822, 15822, -1, 15823, 15823, 15823, -1, + 15824, 15824, 15824, -1, 15825, 15825, 15825, -1, + 15826, 15826, 15826, -1, 15827, 15827, 15827, -1, + 15828, 15828, 15828, -1, 15829, 15829, 15829, -1, + 15830, 15830, 15830, -1, 15831, 15831, 15831, -1, + 15832, 15832, 15832, -1, 15833, 15833, 15833, -1, + 15834, 15834, 15834, -1, 15835, 15835, 15835, -1, + 15836, 15836, 15836, -1, 15837, 15837, 15837, -1, + 15838, 15838, 15838, -1, 15839, 15839, 15839, -1, + 15840, 15840, 15840, -1, 15841, 15841, 15841, -1, + 15842, 15842, 15842, -1, 15843, 15843, 15843, -1, + 15844, 15844, 15844, -1, 15845, 15845, 15845, -1, + 15846, 15846, 15846, -1, 15847, 15847, 15847, -1, + 15848, 15848, 15848, -1, 15849, 15849, 15849, -1, + 15850, 15850, 15850, -1, 15851, 15851, 15851, -1, + 15852, 15852, 15852, -1, 15853, 15853, 15853, -1, + 15854, 15854, 15854, -1, 15855, 15855, 15855, -1, + 15856, 15856, 15856, -1, 15857, 15857, 15857, -1, + 15858, 15858, 15858, -1, 15859, 15859, 15859, -1, + 15860, 15860, 15860, -1, 15861, 15861, 15861, -1, + 15862, 15862, 15862, -1, 15863, 15863, 15863, -1, + 15864, 15864, 15864, -1, 15865, 15865, 15865, -1, + 15866, 15866, 15866, -1, 15867, 15867, 15867, -1, + 15868, 15868, 15868, -1, 15869, 15869, 15869, -1, + 15870, 15870, 15870, -1, 15871, 15871, 15871, -1, + 15872, 15872, 15872, -1, 15873, 15873, 15873, -1, + 15874, 15874, 15874, -1, 15875, 15875, 15875, -1, + 15876, 15876, 15876, -1, 15877, 15877, 15877, -1, + 15878, 15878, 15878, -1, 15879, 15879, 15879, -1, + 15880, 15880, 15880, -1, 15881, 15881, 15881, -1, + 15882, 15882, 15882, -1, 15883, 15883, 15883, -1, + 15884, 15884, 15884, -1, 15885, 15885, 15885, -1, + 15886, 15886, 15886, -1, 15887, 15887, 15887, -1, + 15888, 15888, 15888, -1, 15889, 15889, 15889, -1, + 15890, 15890, 15890, -1, 15891, 15891, 15891, -1, + 15892, 15892, 15892, -1, 15893, 15893, 15893, -1, + 15894, 15894, 15894, -1, 15895, 15895, 15895, -1, + 15896, 15896, 15896, -1, 15897, 15897, 15897, -1, + 15898, 15898, 15898, -1, 15899, 15899, 15899, -1, + 15900, 15900, 15900, -1, 15901, 15901, 15901, -1, + 15902, 15902, 15902, -1, 15903, 15903, 15903, -1, + 15904, 15904, 15904, -1, 15905, 15905, 15905, -1, + 15906, 15906, 15906, -1, 15907, 15907, 15907, -1, + 15908, 15908, 15908, -1, 15909, 15909, 15909, -1, + 15910, 15910, 15910, -1, 15911, 15911, 15911, -1, + 15912, 15912, 15912, -1, 15913, 15913, 15913, -1, + 15914, 15914, 15914, -1, 15915, 15915, 15915, -1, + 15916, 15916, 15916, -1, 15917, 15917, 15917, -1, + 15918, 15918, 15918, -1, 15919, 15919, 15919, -1, + 15920, 15920, 15920, -1, 15921, 15921, 15921, -1, + 15922, 15922, 15922, -1, 15923, 15923, 15923, -1, + 15924, 15924, 15924, -1, 15925, 15925, 15925, -1, + 15926, 15926, 15926, -1, 15927, 15927, 15927, -1, + 15928, 15928, 15928, -1, 15929, 15929, 15929, -1, + 15930, 15930, 15930, -1, 15931, 15931, 15931, -1, + 15932, 15932, 15932, -1, 15933, 15933, 15933, -1, + 15934, 15934, 15934, -1, 15935, 15935, 15935, -1, + 15936, 15936, 15936, -1, 15937, 15937, 15937, -1, + 15938, 15938, 15938, -1, 15939, 15939, 15939, -1, + 15940, 15940, 15940, -1, 15941, 15941, 15941, -1, + 15942, 15942, 15942, -1, 15943, 15943, 15943, -1, + 15944, 15944, 15944, -1, 15945, 15945, 15945, -1, + 15946, 15946, 15946, -1, 15947, 15947, 15947, -1, + 15948, 15948, 15948, -1, 15949, 15949, 15949, -1, + 15950, 15950, 15950, -1, 15951, 15951, 15951, -1, + 15952, 15952, 15952, -1, 15953, 15953, 15953, -1, + 15954, 15954, 15954, -1, 15955, 15955, 15955, -1, + 15956, 15956, 15956, -1, 15957, 15957, 15957, -1, + 15958, 15958, 15958, -1, 15959, 15959, 15959, -1, + 15960, 15960, 15960, -1, 15961, 15961, 15961, -1, + 15962, 15962, 15962, -1, 15963, 15963, 15963, -1, + 15964, 15964, 15964, -1, 15965, 15965, 15965, -1, + 15966, 15966, 15966, -1, 15967, 15967, 15967, -1, + 15968, 15968, 15968, -1, 15969, 15969, 15969, -1, + 15970, 15970, 15970, -1, 15971, 15971, 15971, -1, + 15972, 15972, 15972, -1, 15973, 15973, 15973, -1, + 15974, 15974, 15974, -1, 15975, 15975, 15975, -1, + 15976, 15976, 15976, -1, 15977, 15977, 15977, -1, + 15978, 15978, 15978, -1, 15979, 15979, 15979, -1, + 15980, 15980, 15980, -1, 15981, 15981, 15981, -1, + 15982, 15982, 15982, -1, 15983, 15983, 15983, -1, + 15984, 15984, 15984, -1, 15985, 15985, 15985, -1, + 15986, 15986, 15986, -1, 15987, 15987, 15987, -1, + 15988, 15988, 15988, -1, 15989, 15989, 15989, -1, + 15990, 15990, 15990, -1, 15991, 15991, 15991, -1, + 15992, 15992, 15992, -1, 15993, 15993, 15993, -1, + 15994, 15994, 15994, -1, 15995, 15995, 15995, -1, + 15996, 15996, 15996, -1, 15997, 15997, 15997, -1, + 15998, 15998, 15998, -1, 15999, 15999, 15999, -1, + 16000, 16000, 16000, -1, 16001, 16001, 16001, -1, + 16002, 16002, 16002, -1, 16003, 16003, 16003, -1, + 16004, 16004, 16004, -1, 16005, 16005, 16005, -1, + 16006, 16006, 16006, -1, 16007, 16007, 16007, -1, + 16008, 16008, 16008, -1, 16009, 16009, 16009, -1, + 16010, 16010, 16010, -1, 16011, 16011, 16011, -1, + 16012, 16012, 16012, -1, 16013, 16013, 16013, -1, + 16014, 16014, 16014, -1, 16015, 16015, 16015, -1, + 16016, 16016, 16016, -1, 16017, 16017, 16017, -1, + 16018, 16018, 16018, -1, 16019, 16019, 16019, -1, + 16020, 16020, 16020, -1, 16021, 16021, 16021, -1, + 16022, 16022, 16022, -1, 16023, 16023, 16023, -1, + 16024, 16024, 16024, -1, 16025, 16025, 16025, -1, + 16026, 16026, 16026, -1, 16027, 16027, 16027, -1, + 16028, 16028, 16028, -1, 16029, 16029, 16029, -1, + 16030, 16030, 16030, -1, 16031, 16031, 16031, -1, + 16032, 16032, 16032, -1, 16033, 16033, 16033, -1, + 16034, 16034, 16034, -1, 16035, 16035, 16035, -1, + 16036, 16036, 16036, -1, 16037, 16037, 16037, -1, + 16038, 16038, 16038, -1, 16039, 16039, 16039, -1, + 16040, 16040, 16040, -1, 16041, 16041, 16041, -1, + 16042, 16042, 16042, -1, 16043, 16043, 16043, -1, + 16044, 16044, 16044, -1, 16045, 16045, 16045, -1, + 16046, 16046, 16046, -1, 16047, 16047, 16047, -1, + 16048, 16048, 16048, -1, 16049, 16049, 16049, -1, + 16050, 16050, 16050, -1, 16051, 16051, 16051, -1, + 16052, 16052, 16052, -1, 16053, 16053, 16053, -1, + 16054, 16054, 16054, -1, 16055, 16055, 16055, -1, + 16056, 16056, 16056, -1, 16057, 16057, 16057, -1, + 16058, 16058, 16058, -1, 16059, 16059, 16059, -1, + 16060, 16060, 16060, -1, 16061, 16061, 16061, -1, + 16062, 16062, 16062, -1, 16063, 16063, 16063, -1, + 16064, 16064, 16064, -1, 16065, 16065, 16065, -1, + 16066, 16066, 16066, -1, 16067, 16067, 16067, -1, + 16068, 16068, 16068, -1, 16069, 16069, 16069, -1, + 16070, 16070, 16070, -1, 16071, 16071, 16071, -1, + 16072, 16072, 16072, -1, 16073, 16073, 16073, -1, + 16074, 16074, 16074, -1, 16075, 16075, 16075, -1, + 16076, 16076, 16076, -1, 16077, 16077, 16077, -1, + 16078, 16078, 16078, -1, 16079, 16079, 16079, -1, + 16080, 16080, 16080, -1, 16081, 16081, 16081, -1, + 16082, 16082, 16082, -1, 16083, 16083, 16083, -1, + 16084, 16084, 16084, -1, 16085, 16085, 16085, -1, + 16086, 16086, 16086, -1, 16087, 16087, 16087, -1, + 16088, 16088, 16088, -1, 16089, 16089, 16089, -1, + 16090, 16090, 16090, -1, 16091, 16091, 16091, -1, + 16092, 16092, 16092, -1, 16093, 16093, 16093, -1, + 16094, 16094, 16094, -1, 16095, 16095, 16095, -1, + 16096, 16096, 16096, -1, 16097, 16097, 16097, -1, + 16098, 16098, 16098, -1, 16099, 16099, 16099, -1, + 16100, 16100, 16100, -1, 16101, 16101, 16101, -1, + 16102, 16102, 16102, -1, 16103, 16103, 16103, -1, + 16104, 16104, 16104, -1, 16105, 16105, 16105, -1, + 16106, 16106, 16106, -1, 16107, 16107, 16107, -1, + 16108, 16108, 16108, -1, 16109, 16109, 16109, -1, + 16110, 16110, 16110, -1, 16111, 16111, 16111, -1, + 16112, 16112, 16112, -1, 16113, 16113, 16113, -1, + 16114, 16114, 16114, -1, 16115, 16115, 16115, -1, + 16116, 16116, 16116, -1, 16117, 16117, 16117, -1, + 16118, 16118, 16118, -1, 16119, 16119, 16119, -1, + 16120, 16120, 16120, -1, 16121, 16121, 16121, -1, + 16122, 16122, 16122, -1, 16123, 16123, 16123, -1, + 16124, 16124, 16124, -1, 16125, 16125, 16125, -1, + 16126, 16126, 16126, -1, 16127, 16127, 16127, -1, + 16128, 16128, 16128, -1, 16129, 16129, 16129, -1, + 16130, 16130, 16130, -1, 16131, 16131, 16131, -1, + 16132, 16132, 16132, -1, 16133, 16133, 16133, -1, + 16134, 16134, 16134, -1, 16135, 16135, 16135, -1, + 16136, 16136, 16136, -1, 16137, 16137, 16137, -1, + 16138, 16138, 16138, -1, 16139, 16139, 16139, -1, + 16140, 16140, 16140, -1, 16141, 16141, 16141, -1, + 16142, 16142, 16142, -1, 16143, 16143, 16143, -1, + 16144, 16144, 16144, -1, 16145, 16145, 16145, -1, + 16146, 16146, 16146, -1, 16147, 16147, 16147, -1, + 16148, 16148, 16148, -1, 16149, 16149, 16149, -1, + 16150, 16150, 16150, -1, 16151, 16151, 16151, -1, + 16152, 16152, 16152, -1, 16153, 16153, 16153, -1, + 16154, 16154, 16154, -1, 16155, 16155, 16155, -1, + 16156, 16156, 16156, -1, 16157, 16157, 16157, -1, + 16158, 16158, 16158, -1, 16159, 16159, 16159, -1, + 16160, 16160, 16160, -1, 16161, 16161, 16161, -1, + 16162, 16162, 16162, -1, 16163, 16163, 16163, -1, + 16164, 16164, 16164, -1, 16165, 16165, 16165, -1, + 16166, 16166, 16166, -1, 16167, 16167, 16167, -1, + 16168, 16168, 16168, -1, 16169, 16169, 16169, -1, + 16170, 16170, 16170, -1, 16171, 16171, 16171, -1, + 16172, 16172, 16172, -1, 16173, 16173, 16173, -1, + 16174, 16174, 16174, -1, 16175, 16175, 16175, -1, + 16176, 16176, 16176, -1, 16177, 16177, 16177, -1, + 16178, 16178, 16178, -1, 16179, 16179, 16179, -1, + 16180, 16180, 16180, -1, 16181, 16181, 16181, -1, + 16182, 16182, 16182, -1, 16183, 16183, 16183, -1, + 16184, 16184, 16184, -1, 16185, 16185, 16185, -1, + 16186, 16186, 16186, -1, 16187, 16187, 16187, -1, + 16188, 16188, 16188, -1, 16189, 16189, 16189, -1, + 16190, 16190, 16190, -1, 16191, 16191, 16191, -1, + 16192, 16192, 16192, -1, 16193, 16193, 16193, -1, + 16194, 16194, 16194, -1, 16195, 16195, 16195, -1, + 16196, 16196, 16196, -1, 16197, 16197, 16197, -1, + 16198, 16198, 16198, -1, 16199, 16199, 16199, -1, + 16200, 16200, 16200, -1, 16201, 16201, 16201, -1, + 16202, 16202, 16202, -1, 16203, 16203, 16203, -1, + 16204, 16204, 16204, -1, 16205, 16205, 16205, -1, + 16206, 16206, 16206, -1, 16207, 16207, 16207, -1, + 16208, 16208, 16208, -1, 16209, 16209, 16209, -1, + 16210, 16210, 16210, -1, 16211, 16211, 16211, -1, + 16212, 16212, 16212, -1, 16213, 16213, 16213, -1, + 16214, 16214, 16214, -1, 16215, 16215, 16215, -1, + 16216, 16216, 16216, -1, 16217, 16217, 16217, -1, + 16218, 16218, 16218, -1, 16219, 16219, 16219, -1, + 16220, 16220, 16220, -1, 16221, 16221, 16221, -1, + 16222, 16222, 16222, -1, 16223, 16223, 16223, -1, + 16224, 16224, 16224, -1, 16225, 16225, 16225, -1, + 16226, 16226, 16226, -1, 16227, 16227, 16227, -1, + 16228, 16228, 16228, -1, 16229, 16229, 16229, -1, + 16230, 16230, 16230, -1, 16231, 16231, 16231, -1, + 16232, 16232, 16232, -1, 16233, 16233, 16233, -1, + 16234, 16234, 16234, -1, 16235, 16235, 16235, -1, + 16236, 16236, 16236, -1, 16237, 16237, 16237, -1, + 16238, 16238, 16238, -1, 16239, 16239, 16239, -1, + 16240, 16240, 16240, -1, 16241, 16241, 16241, -1, + 16242, 16242, 16242, -1, 16243, 16243, 16243, -1, + 16244, 16244, 16244, -1, 16245, 16245, 16245, -1, + 16246, 16246, 16246, -1, 16247, 16247, 16247, -1, + 16248, 16248, 16248, -1, 16249, 16249, 16249, -1, + 16250, 16250, 16250, -1, 16251, 16251, 16251, -1, + 16252, 16252, 16252, -1, 16253, 16253, 16253, -1, + 16254, 16254, 16254, -1, 16255, 16255, 16255, -1, + 16256, 16256, 16256, -1, 16257, 16257, 16257, -1, + 16258, 16258, 16258, -1, 16259, 16259, 16259, -1, + 16260, 16260, 16260, -1, 16261, 16261, 16261, -1, + 16262, 16262, 16262, -1, 16263, 16263, 16263, -1, + 16264, 16264, 16264, -1, 16265, 16265, 16265, -1, + 16266, 16266, 16266, -1, 16267, 16267, 16267, -1, + 16268, 16268, 16268, -1, 16269, 16269, 16269, -1, + 16270, 16270, 16270, -1, 16271, 16271, 16271, -1, + 16272, 16272, 16272, -1, 16273, 16273, 16273, -1, + 16274, 16274, 16274, -1, 16275, 16275, 16275, -1, + 16276, 16276, 16276, -1, 16277, 16277, 16277, -1, + 16278, 16278, 16278, -1, 16279, 16279, 16279, -1, + 16280, 16280, 16280, -1, 16281, 16281, 16281, -1, + 16282, 16282, 16282, -1, 16283, 16283, 16283, -1, + 16284, 16284, 16284, -1, 16285, 16285, 16285, -1, + 16286, 16286, 16286, -1, 16287, 16287, 16287, -1, + 16288, 16288, 16288, -1, 16289, 16289, 16289, -1, + 16290, 16290, 16290, -1, 16291, 16291, 16291, -1, + 16292, 16292, 16292, -1, 16293, 16293, 16293, -1, + 16294, 16294, 16294, -1, 16295, 16295, 16295, -1, + 16296, 16296, 16296, -1, 16297, 16297, 16297, -1, + 16298, 16298, 16298, -1, 16299, 16299, 16299, -1, + 16300, 16300, 16300, -1, 16301, 16301, 16301, -1, + 16302, 16302, 16302, -1, 16303, 16303, 16303, -1, + 16304, 16304, 16304, -1, 16305, 16305, 16305, -1, + 16306, 16306, 16306, -1, 16307, 16307, 16307, -1, + 16308, 16308, 16308, -1, 16309, 16309, 16309, -1, + 16310, 16310, 16310, -1, 16311, 16311, 16311, -1, + 16312, 16312, 16312, -1, 16313, 16313, 16313, -1, + 16314, 16314, 16314, -1, 16315, 16315, 16315, -1, + 16316, 16316, 16316, -1, 16317, 16317, 16317, -1, + 16318, 16318, 16318, -1, 16319, 16319, 16319, -1, + 16320, 16320, 16320, -1, 16321, 16321, 16321, -1, + 16322, 16322, 16322, -1, 16323, 16323, 16323, -1, + 16324, 16324, 16324, -1, 16325, 16325, 16325, -1, + 16326, 16326, 16326, -1, 16327, 16327, 16327, -1, + 16328, 16328, 16328, -1, 16329, 16329, 16329, -1, + 16330, 16330, 16330, -1, 16331, 16331, 16331, -1, + 16332, 16332, 16332, -1, 16333, 16333, 16333, -1, + 16334, 16334, 16334, -1, 16335, 16335, 16335, -1, + 16336, 16336, 16336, -1, 16337, 16337, 16337, -1, + 16338, 16338, 16338, -1, 16339, 16339, 16339, -1, + 16340, 16340, 16340, -1, 16341, 16341, 16341, -1, + 16342, 16342, 16342, -1, 16343, 16343, 16343, -1, + 16344, 16344, 16344, -1, 16345, 16345, 16345, -1, + 16346, 16346, 16346, -1, 16347, 16347, 16347, -1, + 16348, 16348, 16348, -1, 16349, 16349, 16349, -1, + 16350, 16350, 16350, -1, 16351, 16351, 16351, -1, + 16352, 16352, 16352, -1, 16353, 16353, 16353, -1, + 16354, 16354, 16354, -1, 16355, 16355, 16355, -1, + 16356, 16356, 16356, -1, 16357, 16357, 16357, -1, + 16358, 16358, 16358, -1, 16359, 16359, 16359, -1, + 16360, 16360, 16360, -1, 16361, 16361, 16361, -1, + 16362, 16362, 16362, -1, 16363, 16363, 16363, -1, + 16364, 16364, 16364, -1, 16365, 16365, 16365, -1, + 16366, 16366, 16366, -1, 16367, 16367, 16367, -1, + 16368, 16368, 16368, -1, 16369, 16369, 16369, -1, + 16370, 16370, 16370, -1, 16371, 16371, 16371, -1, + 16372, 16372, 16372, -1, 16373, 16373, 16373, -1, + 16374, 16374, 16374, -1, 16375, 16375, 16375, -1, + 16376, 16376, 16376, -1, 16377, 16377, 16377, -1, + 16378, 16378, 16378, -1, 16379, 16379, 16379, -1, + 16380, 16380, 16380, -1, 16381, 16381, 16381, -1, + 16382, 16382, 16382, -1, 16383, 16383, 16383, -1, + 16384, 16384, 16384, -1, 16385, 16385, 16385, -1, + 16386, 16386, 16386, -1, 16387, 16387, 16387, -1, + 16388, 16388, 16388, -1, 16389, 16389, 16389, -1, + 16390, 16390, 16390, -1, 16391, 16391, 16391, -1, + 16392, 16392, 16392, -1, 16393, 16393, 16393, -1, + 16394, 16394, 16394, -1, 16395, 16395, 16395, -1, + 16396, 16396, 16396, -1, 16397, 16397, 16397, -1, + 16398, 16398, 16398, -1, 16399, 16399, 16399, -1, + 16400, 16400, 16400, -1, 16401, 16401, 16401, -1, + 16402, 16402, 16402, -1, 16403, 16403, 16403, -1, + 16404, 16404, 16404, -1, 16405, 16405, 16405, -1, + 16406, 16406, 16406, -1, 16407, 16407, 16407, -1, + 16408, 16408, 16408, -1, 16409, 16409, 16409, -1, + 16410, 16410, 16410, -1, 16411, 16411, 16411, -1, + 16412, 16412, 16412, -1, 16413, 16413, 16413, -1, + 16414, 16414, 16414, -1, 16415, 16415, 16415, -1, + 16416, 16416, 16416, -1, 16417, 16417, 16417, -1, + 16418, 16418, 16418, -1, 16419, 16419, 16419, -1, + 16420, 16420, 16420, -1, 16421, 16421, 16421, -1, + 16422, 16422, 16422, -1, 16423, 16423, 16423, -1, + 16424, 16424, 16424, -1, 16425, 16425, 16425, -1, + 16426, 16426, 16426, -1, 16427, 16427, 16427, -1, + 16428, 16428, 16428, -1, 16429, 16429, 16429, -1, + 16430, 16430, 16430, -1, 16431, 16431, 16431, -1, + 16432, 16432, 16432, -1, 16433, 16433, 16433, -1, + 16434, 16434, 16434, -1, 16435, 16435, 16435, -1, + 16436, 16436, 16436, -1, 16437, 16437, 16437, -1, + 16438, 16438, 16438, -1, 16439, 16439, 16439, -1, + 16440, 16440, 16440, -1, 16441, 16441, 16441, -1, + 16442, 16442, 16442, -1, 16443, 16443, 16443, -1, + 16444, 16444, 16444, -1, 16445, 16445, 16445, -1, + 16446, 16446, 16446, -1, 16447, 16447, 16447, -1, + 16448, 16448, 16448, -1, 16449, 16449, 16449, -1, + 16450, 16450, 16450, -1, 16451, 16451, 16451, -1, + 16452, 16452, 16452, -1, 16453, 16453, 16453, -1, + 16454, 16454, 16454, -1, 16455, 16455, 16455, -1, + 16456, 16456, 16456, -1, 16457, 16457, 16457, -1, + 16458, 16458, 16458, -1, 16459, 16459, 16459, -1, + 16460, 16460, 16460, -1, 16461, 16461, 16461, -1, + 16462, 16462, 16462, -1, 16463, 16463, 16463, -1, + 16464, 16464, 16464, -1, 16465, 16465, 16465, -1, + 16466, 16466, 16466, -1, 16467, 16467, 16467, -1, + 16468, 16468, 16468, -1, 16469, 16469, 16469, -1, + 16470, 16470, 16470, -1, 16471, 16471, 16471, -1, + 16472, 16472, 16472, -1, 16473, 16473, 16473, -1, + 16474, 16474, 16474, -1, 16475, 16475, 16475, -1, + 16476, 16476, 16476, -1, 16477, 16477, 16477, -1, + 16478, 16478, 16478, -1, 16479, 16479, 16479, -1, + 16480, 16480, 16480, -1, 16481, 16481, 16481, -1, + 16482, 16482, 16482, -1, 16483, 16483, 16483, -1, + 16484, 16484, 16484, -1, 16485, 16485, 16485, -1, + 16486, 16486, 16486, -1, 16487, 16487, 16487, -1, + 16488, 16488, 16488, -1, 16489, 16489, 16489, -1, + 16490, 16490, 16490, -1, 16491, 16491, 16491, -1, + 16492, 16492, 16492, -1, 16493, 16493, 16493, -1, + 16494, 16494, 16494, -1, 16495, 16495, 16495, -1, + 16496, 16496, 16496, -1, 16497, 16497, 16497, -1, + 16498, 16498, 16498, -1, 16499, 16499, 16499, -1, + 16500, 16500, 16500, -1, 16501, 16501, 16501, -1, + 16502, 16502, 16502, -1, 16503, 16503, 16503, -1, + 16504, 16504, 16504, -1, 16505, 16505, 16505, -1, + 16506, 16506, 16506, -1, 16507, 16507, 16507, -1, + 16508, 16508, 16508, -1, 16509, 16509, 16509, -1, + 16510, 16510, 16510, -1, 16511, 16511, 16511, -1, + 16512, 16512, 16512, -1, 16513, 16513, 16513, -1, + 16514, 16514, 16514, -1, 16515, 16515, 16515, -1, + 16516, 16516, 16516, -1, 16517, 16517, 16517, -1, + 16518, 16518, 16518, -1, 16519, 16519, 16519, -1, + 16520, 16520, 16520, -1, 16521, 16521, 16521, -1, + 16522, 16522, 16522, -1, 16523, 16523, 16523, -1, + 16524, 16524, 16524, -1, 16525, 16525, 16525, -1, + 16526, 16526, 16526, -1, 16527, 16527, 16527, -1, + 16528, 16528, 16528, -1, 16529, 16529, 16529, -1, + 16530, 16530, 16530, -1, 16531, 16531, 16531, -1, + 16532, 16532, 16532, -1, 16533, 16533, 16533, -1, + 16534, 16534, 16534, -1, 16535, 16535, 16535, -1, + 16536, 16536, 16536, -1, 16537, 16537, 16537, -1, + 16538, 16538, 16538, -1, 16539, 16539, 16539, -1, + 16540, 16540, 16540, -1, 16541, 16541, 16541, -1, + 16542, 16542, 16542, -1, 16543, 16543, 16543, -1, + 16544, 16544, 16544, -1, 16545, 16545, 16545, -1, + 16546, 16546, 16546, -1, 16547, 16547, 16547, -1, + 16548, 16548, 16548, -1, 16549, 16549, 16549, -1, + 16550, 16550, 16550, -1, 16551, 16551, 16551, -1, + 16552, 16552, 16552, -1, 16553, 16553, 16553, -1, + 16554, 16554, 16554, -1, 16555, 16555, 16555, -1, + 16556, 16556, 16556, -1, 16557, 16557, 16557, -1, + 16558, 16558, 16558, -1, 16559, 16559, 16559, -1, + 16560, 16560, 16560, -1, 16561, 16561, 16561, -1, + 16562, 16562, 16562, -1, 16563, 16563, 16563, -1, + 16564, 16564, 16564, -1, 16565, 16565, 16565, -1, + 16566, 16566, 16566, -1, 16567, 16567, 16567, -1, + 16568, 16568, 16568, -1, 16569, 16569, 16569, -1, + 16570, 16570, 16570, -1, 16571, 16571, 16571, -1, + 16572, 16572, 16572, -1, 16573, 16573, 16573, -1, + 16574, 16574, 16574, -1, 16575, 16575, 16575, -1, + 16576, 16576, 16576, -1, 16577, 16577, 16577, -1, + 16578, 16578, 16578, -1, 16579, 16579, 16579, -1, + 16580, 16580, 16580, -1, 16581, 16581, 16581, -1, + 16582, 16582, 16582, -1, 16583, 16583, 16583, -1, + 16584, 16584, 16584, -1, 16585, 16585, 16585, -1, + 16586, 16586, 16586, -1, 16587, 16587, 16587, -1, + 16588, 16588, 16588, -1, 16589, 16589, 16589, -1, + 16590, 16590, 16590, -1, 16591, 16591, 16591, -1, + 16592, 16592, 16592, -1, 16593, 16593, 16593, -1, + 16594, 16594, 16594, -1, 16595, 16595, 16595, -1, + 16596, 16596, 16596, -1, 16597, 16597, 16597, -1, + 16598, 16598, 16598, -1, 16599, 16599, 16599, -1, + 16600, 16600, 16600, -1, 16601, 16601, 16601, -1, + 16602, 16602, 16602, -1, 16603, 16603, 16603, -1, + 16604, 16604, 16604, -1, 16605, 16605, 16605, -1, + 16606, 16606, 16606, -1, 16607, 16607, 16607, -1, + 16608, 16608, 16608, -1, 16609, 16609, 16609, -1, + 16610, 16610, 16610, -1, 16611, 16611, 16611, -1, + 16612, 16612, 16612, -1, 16613, 16613, 16613, -1, + 16614, 16614, 16614, -1, 16615, 16615, 16615, -1, + 16616, 16616, 16616, -1, 16617, 16617, 16617, -1, + 16618, 16618, 16618, -1, 16619, 16619, 16619, -1, + 16620, 16620, 16620, -1, 16621, 16621, 16621, -1, + 16622, 16622, 16622, -1, 16623, 16623, 16623, -1, + 16624, 16624, 16624, -1, 16625, 16625, 16625, -1, + 16626, 16626, 16626, -1, 16627, 16627, 16627, -1, + 16628, 16628, 16628, -1, 16629, 16629, 16629, -1, + 16630, 16630, 16630, -1, 16631, 16631, 16631, -1, + 16632, 16632, 16632, -1, 16633, 16633, 16633, -1, + 16634, 16634, 16634, -1, 16635, 16635, 16635, -1, + 16636, 16636, 16636, -1, 16637, 16637, 16637, -1, + 16638, 16638, 16638, -1, 16639, 16639, 16639, -1, + 16640, 16640, 16640, -1, 16641, 16641, 16641, -1, + 16642, 16642, 16642, -1, 16643, 16643, 16643, -1, + 16644, 16644, 16644, -1, 16645, 16645, 16645, -1, + 16646, 16646, 16646, -1, 16647, 16647, 16647, -1, + 16648, 16648, 16648, -1, 16649, 16649, 16649, -1, + 16650, 16650, 16650, -1, 16651, 16651, 16651, -1, + 16652, 16652, 16652, -1, 16653, 16653, 16653, -1, + 16654, 16654, 16654, -1, 16655, 16655, 16655, -1, + 16656, 16656, 16656, -1, 16657, 16657, 16657, -1, + 16658, 16658, 16658, -1, 16659, 16659, 16659, -1, + 16660, 16660, 16660, -1, 16661, 16661, 16661, -1, + 16662, 16662, 16662, -1, 16663, 16663, 16663, -1, + 16664, 16664, 16664, -1, 16665, 16665, 16665, -1, + 16666, 16666, 16666, -1, 16667, 16667, 16667, -1, + 16668, 16668, 16668, -1, 16669, 16669, 16669, -1, + 16670, 16670, 16670, -1, 16671, 16671, 16671, -1, + 16672, 16672, 16672, -1, 16673, 16673, 16673, -1, + 16674, 16674, 16674, -1, 16675, 16675, 16675, -1, + 16676, 16676, 16676, -1, 16677, 16677, 16677, -1, + 16678, 16678, 16678, -1, 16679, 16679, 16679, -1, + 16680, 16680, 16680, -1, 16681, 16681, 16681, -1, + 16682, 16682, 16682, -1, 16683, 16683, 16683, -1, + 16684, 16684, 16684, -1, 16685, 16685, 16685, -1, + 16686, 16686, 16686, -1, 16687, 16687, 16687, -1, + 16688, 16688, 16688, -1, 16689, 16689, 16689, -1, + 16690, 16690, 16690, -1, 16691, 16691, 16691, -1, + 16692, 16692, 16692, -1, 16693, 16693, 16693, -1, + 16694, 16694, 16694, -1, 16695, 16695, 16695, -1, + 16696, 16696, 16696, -1, 16697, 16697, 16697, -1, + 16698, 16698, 16698, -1, 16699, 16699, 16699, -1, + 16700, 16700, 16700, -1, 16701, 16701, 16701, -1, + 16702, 16702, 16702, -1, 16703, 16703, 16703, -1, + 16704, 16704, 16704, -1, 16705, 16705, 16705, -1, + 16706, 16706, 16706, -1, 16707, 16707, 16707, -1, + 16708, 16708, 16708, -1, 16709, 16709, 16709, -1, + 16710, 16710, 16710, -1, 16711, 16711, 16711, -1, + 16712, 16712, 16712, -1, 16713, 16713, 16713, -1, + 16714, 16714, 16714, -1, 16715, 16715, 16715, -1, + 16716, 16716, 16716, -1, 16717, 16717, 16717, -1, + 16718, 16718, 16718, -1, 16719, 16719, 16719, -1, + 16720, 16720, 16720, -1, 16721, 16721, 16721, -1, + 16722, 16722, 16722, -1, 16723, 16723, 16723, -1, + 16724, 16724, 16724, -1, 16725, 16725, 16725, -1, + 16726, 16726, 16726, -1, 16727, 16727, 16727, -1, + 16728, 16728, 16728, -1, 16729, 16729, 16729, -1, + 16730, 16730, 16730, -1, 16731, 16731, 16731, -1, + 16732, 16732, 16732, -1, 16733, 16733, 16733, -1, + 16734, 16734, 16734, -1, 16735, 16735, 16735, -1, + 16736, 16736, 16736, -1, 16737, 16737, 16737, -1, + 16738, 16738, 16738, -1, 16739, 16739, 16739, -1, + 16740, 16740, 16740, -1, 16741, 16741, 16741, -1, + 16742, 16742, 16742, -1, 16743, 16743, 16743, -1, + 16744, 16744, 16744, -1, 16745, 16745, 16745, -1, + 16746, 16746, 16746, -1, 16747, 16747, 16747, -1, + 16748, 16748, 16748, -1, 16749, 16749, 16749, -1, + 16750, 16750, 16750, -1, 16751, 16751, 16751, -1, + 16752, 16752, 16752, -1, 16753, 16753, 16753, -1, + 16754, 16754, 16754, -1, 16755, 16755, 16755, -1, + 16756, 16756, 16756, -1, 16757, 16757, 16757, -1, + 16758, 16758, 16758, -1, 16759, 16759, 16759, -1, + 16760, 16760, 16760, -1, 16761, 16761, 16761, -1, + 16762, 16762, 16762, -1, 16763, 16763, 16763, -1, + 16764, 16764, 16764, -1, 16765, 16765, 16765, -1, + 16766, 16766, 16766, -1, 16767, 16767, 16767, -1, + 16768, 16768, 16768, -1, 16769, 16769, 16769, -1, + 16770, 16770, 16770, -1, 16771, 16771, 16771, -1, + 16772, 16772, 16772, -1, 16773, 16773, 16773, -1, + 16774, 16774, 16774, -1, 16775, 16775, 16775, -1, + 16776, 16776, 16776, -1, 16777, 16777, 16777, -1, + 16778, 16778, 16778, -1, 16779, 16779, 16779, -1, + 16780, 16780, 16780, -1, 16781, 16781, 16781, -1, + 16782, 16782, 16782, -1, 16783, 16783, 16783, -1, + 16784, 16784, 16784, -1, 16785, 16785, 16785, -1, + 16786, 16786, 16786, -1, 16787, 16787, 16787, -1, + 16788, 16788, 16788, -1, 16789, 16789, 16789, -1, + 16790, 16790, 16790, -1, 16791, 16791, 16791, -1, + 16792, 16792, 16792, -1, 16793, 16793, 16793, -1, + 16794, 16794, 16794, -1, 16795, 16795, 16795, -1, + 16796, 16796, 16796, -1, 16797, 16797, 16797, -1, + 16798, 16798, 16798, -1, 16799, 16799, 16799, -1, + 16800, 16800, 16800, -1, 16801, 16801, 16801, -1, + 16802, 16802, 16802, -1, 16803, 16803, 16803, -1, + 16804, 16804, 16804, -1, 16805, 16805, 16805, -1, + 16806, 16806, 16806, -1, 16807, 16807, 16807, -1, + 16808, 16808, 16808, -1, 16809, 16809, 16809, -1, + 16810, 16810, 16810, -1, 16811, 16811, 16811, -1, + 16812, 16812, 16812, -1, 16813, 16813, 16813, -1, + 16814, 16814, 16814, -1, 16815, 16815, 16815, -1, + 16816, 16816, 16816, -1, 16817, 16817, 16817, -1, + 16818, 16818, 16818, -1, 16819, 16819, 16819, -1, + 16820, 16820, 16820, -1, 16821, 16821, 16821, -1, + 16822, 16822, 16822, -1, 16823, 16823, 16823, -1, + 16824, 16824, 16824, -1, 16825, 16825, 16825, -1, + 16826, 16826, 16826, -1, 16827, 16827, 16827, -1, + 16828, 16828, 16828, -1, 16829, 16829, 16829, -1, + 16830, 16830, 16830, -1, 16831, 16831, 16831, -1, + 16832, 16832, 16832, -1, 16833, 16833, 16833, -1, + 16834, 16834, 16834, -1, 16835, 16835, 16835, -1, + 16836, 16836, 16836, -1, 16837, 16837, 16837, -1, + 16838, 16838, 16838, -1, 16839, 16839, 16839, -1, + 16840, 16840, 16840, -1, 16841, 16841, 16841, -1, + 16842, 16842, 16842, -1, 16843, 16843, 16843, -1, + 16844, 16844, 16844, -1, 16845, 16845, 16845, -1, + 16846, 16846, 16846, -1, 16847, 16847, 16847, -1, + 16848, 16848, 16848, -1, 16849, 16849, 16849, -1, + 16850, 16850, 16850, -1, 16851, 16851, 16851, -1, + 16852, 16852, 16852, -1, 16853, 16853, 16853, -1, + 16854, 16854, 16854, -1, 16855, 16855, 16855, -1, + 16856, 16856, 16856, -1, 16857, 16857, 16857, -1, + 16858, 16858, 16858, -1, 16859, 16859, 16859, -1, + 16860, 16860, 16860, -1, 16861, 16861, 16861, -1, + 16862, 16862, 16862, -1, 16863, 16863, 16863, -1, + 16864, 16864, 16864, -1, 16865, 16865, 16865, -1, + 16866, 16866, 16866, -1, 16867, 16867, 16867, -1, + 16868, 16868, 16868, -1, 16869, 16869, 16869, -1, + 16870, 16870, 16870, -1, 16871, 16871, 16871, -1, + 16872, 16872, 16872, -1, 16873, 16873, 16873, -1, + 16874, 16874, 16874, -1, 16875, 16875, 16875, -1, + 16876, 16876, 16876, -1, 16877, 16877, 16877, -1, + 16878, 16878, 16878, -1, 16879, 16879, 16879, -1, + 16880, 16880, 16880, -1, 16881, 16881, 16881, -1, + 16882, 16882, 16882, -1, 16883, 16883, 16883, -1, + 16884, 16884, 16884, -1, 16885, 16885, 16885, -1, + 16886, 16886, 16886, -1, 16887, 16887, 16887, -1, + 16888, 16888, 16888, -1, 16889, 16889, 16889, -1, + 16890, 16890, 16890, -1, 16891, 16891, 16891, -1, + 16892, 16892, 16892, -1, 16893, 16893, 16893, -1, + 16894, 16894, 16894, -1, 16895, 16895, 16895, -1, + 16896, 16896, 16896, -1, 16897, 16897, 16897, -1, + 16898, 16898, 16898, -1, 16899, 16899, 16899, -1, + 16900, 16900, 16900, -1, 16901, 16901, 16901, -1, + 16902, 16902, 16902, -1, 16903, 16903, 16903, -1, + 16904, 16904, 16904, -1, 16905, 16905, 16905, -1, + 16906, 16906, 16906, -1, 16907, 16907, 16907, -1, + 16908, 16908, 16908, -1, 16909, 16909, 16909, -1, + 16910, 16910, 16910, -1, 16911, 16911, 16911, -1, + 16912, 16912, 16912, -1, 16913, 16913, 16913, -1, + 16914, 16914, 16914, -1, 16915, 16915, 16915, -1, + 16916, 16916, 16916, -1, 16917, 16917, 16917, -1, + 16918, 16918, 16918, -1, 16919, 16919, 16919, -1, + 16920, 16920, 16920, -1, 16921, 16921, 16921, -1, + 16922, 16922, 16922, -1, 16923, 16923, 16923, -1, + 16924, 16924, 16924, -1, 16925, 16925, 16925, -1, + 16926, 16926, 16926, -1, 16927, 16927, 16927, -1, + 16928, 16928, 16928, -1, 16929, 16929, 16929, -1, + 16930, 16930, 16930, -1, 16931, 16931, 16931, -1, + 16932, 16932, 16932, -1, 16933, 16933, 16933, -1, + 16934, 16934, 16934, -1, 16935, 16935, 16935, -1, + 16936, 16936, 16936, -1, 16937, 16937, 16937, -1, + 16938, 16938, 16938, -1, 16939, 16939, 16939, -1, + 16940, 16940, 16940, -1, 16941, 16941, 16941, -1, + 16942, 16942, 16942, -1, 16943, 16943, 16943, -1, + 16944, 16944, 16944, -1, 16945, 16945, 16945, -1, + 16946, 16946, 16946, -1, 16947, 16947, 16947, -1, + 16948, 16948, 16948, -1, 16949, 16949, 16949, -1, + 16950, 16950, 16950, -1, 16951, 16951, 16951, -1, + 16952, 16952, 16952, -1, 16953, 16953, 16953, -1, + 16954, 16954, 16954, -1, 16955, 16955, 16955, -1, + 16956, 16956, 16956, -1, 16957, 16957, 16957, -1, + 16958, 16958, 16958, -1, 16959, 16959, 16959, -1, + 16960, 16960, 16960, -1, 16961, 16961, 16961, -1, + 16962, 16962, 16962, -1, 16963, 16963, 16963, -1, + 16964, 16964, 16964, -1, 16965, 16965, 16965, -1, + 16966, 16966, 16966, -1, 16967, 16967, 16967, -1, + 16968, 16968, 16968, -1, 16969, 16969, 16969, -1, + 16970, 16970, 16970, -1, 16971, 16971, 16971, -1, + 16972, 16972, 16972, -1, 16973, 16973, 16973, -1, + 16974, 16974, 16974, -1, 16975, 16975, 16975, -1, + 16976, 16976, 16976, -1, 16977, 16977, 16977, -1, + 16978, 16978, 16978, -1, 16979, 16979, 16979, -1, + 16980, 16980, 16980, -1, 16981, 16981, 16981, -1, + 16982, 16982, 16982, -1, 16983, 16983, 16983, -1, + 16984, 16984, 16984, -1, 16985, 16985, 16985, -1, + 16986, 16986, 16986, -1, 16987, 16987, 16987, -1, + 16988, 16988, 16988, -1, 16989, 16989, 16989, -1, + 16990, 16990, 16990, -1, 16991, 16991, 16991, -1, + 16992, 16992, 16992, -1, 16993, 16993, 16993, -1, + 16994, 16994, 16994, -1, 16995, 16995, 16995, -1, + 16996, 16996, 16996, -1, 16997, 16997, 16997, -1, + 16998, 16998, 16998, -1, 16999, 16999, 16999, -1, + 17000, 17000, 17000, -1, 17001, 17001, 17001, -1, + 17002, 17002, 17002, -1, 17003, 17003, 17003, -1, + 17004, 17004, 17004, -1, 17005, 17005, 17005, -1, + 17006, 17006, 17006, -1, 17007, 17007, 17007, -1, + 17008, 17008, 17008, -1, 17009, 17009, 17009, -1, + 17010, 17010, 17010, -1, 17011, 17011, 17011, -1, + 17012, 17012, 17012, -1, 17013, 17013, 17013, -1, + 17014, 17014, 17014, -1, 17015, 17015, 17015, -1, + 17016, 17016, 17016, -1, 17017, 17017, 17017, -1, + 17018, 17018, 17018, -1, 17019, 17019, 17019, -1, + 17020, 17020, 17020, -1, 17021, 17021, 17021, -1, + 17022, 17022, 17022, -1, 17023, 17023, 17023, -1, + 17024, 17024, 17024, -1, 17025, 17025, 17025, -1, + 17026, 17026, 17026, -1, 17027, 17027, 17027, -1, + 17028, 17028, 17028, -1, 17029, 17029, 17029, -1, + 17030, 17030, 17030, -1, 17031, 17031, 17031, -1, + 17032, 17032, 17032, -1, 17033, 17033, 17033, -1, + 17034, 17034, 17034, -1, 17035, 17035, 17035, -1, + 17036, 17036, 17036, -1, 17036, 17036, 17036, -1, + 17037, 17037, 17037, -1, 17037, 17037, 17037, -1, + 17038, 17038, 17038, -1, 17038, 17038, 17038, -1, + 17039, 17039, 17039, -1, 17039, 17039, 17039, -1, + 17040, 17040, 17040, -1, 17040, 17040, 17040, -1, + 17041, 17041, 17041, -1, 17041, 17041, 17041, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17042, 17042, 17042, -1, + 17042, 17042, 17042, -1, 17043, 17043, 17043, -1, + 17043, 17043, 17043, -1, 17044, 17044, 17044, -1, + 17044, 17044, 17044, -1, 17045, 17045, 17045, -1, + 17045, 17045, 17045, -1, 17046, 17046, 17046, -1, + 17046, 17046, 17046, -1, 17047, 17047, 17047, -1, + 17047, 17047, 17047, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1, + 17048, 17048, 17048, -1, 17048, 17048, 17048, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } ] + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link5.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link5.wrl new file mode 100644 index 0000000..ee577dd --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link5.wrl @@ -0,0 +1,48339 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.0078125 0.1875 0.65625 + ambientIntensity 0.46584472 + specularColor 0 0.1 0.5 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.058412101 0.0131967 -0.085859999, + 0.058998398 0.0138405 -0.087223001, + 0.058412101 0.0150343 -0.083612002, + 0.0576833 0.0126108 -0.084657997, + 0.0576833 0.0144875 -0.082520999, + 0.056809202 0.0120942 -0.083621003, + 0.056809202 0.0140091 -0.081598997, + 0.055787299 0.0116562 -0.082751997, + 0.055787299 0.0136075 -0.080851004, + 0.0546159 0.0113049 -0.082052, + 0.0546159 0.0132904 -0.080275998, + 0.0532961 0.011048 -0.081522003, + 0.0532961 0.0130652 -0.079874001, + 0.051830001 0.0108928 -0.081160001, + 0.051830001 0.0129399 -0.079641998, + 0.050219599 0.0108466 -0.080962002, + 0.050219599 0.0129215 -0.079576999, + 0.048467699 0.0109156 -0.080923997, + 0.048467699 0.0130158 -0.079671003, + 0.0465803 0.0111045 -0.081037, + 0.0465803 0.0132245 -0.079919003, + 0.044564299 0.0114141 -0.081294999, + 0.044564299 0.0135371 -0.080319002, + 0.0424264 0.0118337 -0.081696004, + 0.0424264 0.016318399 -0.079880998, + 0.040174201 0.014758 -0.081306003, + 0.040174201 0.017043 -0.080362, + 0.0378174 0.015599 -0.081759997, + 0.0378174 0.0179026 -0.080807, + 0.035366699 0.016577501 -0.082162999, + 0.035366699 0.0188783 -0.081205003, + 0.0328326 0.0176764 -0.082505003, + 0.0328326 0.019976201 -0.08151, + 0.0302257 0.0189001 -0.082742997, + 0.0302257 0.0211985 -0.081712, + 0.027557701 0.0202477 -0.082869999, + 0.027557701 0.022543 -0.081799999, + 0.0248404 0.021715701 -0.082874, + 0.0248404 0.0240054 -0.081763998, + 0.0220857 0.023298901 -0.082745001, + 0.0220857 0.025580199 -0.081592001, + 0.019305199 0.024990199 -0.082471997, + 0.019305199 0.027259899 -0.081271999, + 0.0165099 0.026779599 -0.082043998, + 0.0165099 0.0290347 -0.080796003, + 0.0137106 0.0286562 -0.081455, + 0.0137106 0.030893 -0.080155998, + 0.0109179 0.0306074 -0.080697998, + 0.0109179 0.032821599 -0.079345003, + 0.0081428103 0.032619301 -0.079767004, + 0.0081428103 0.034805499 -0.078359, + 0.0053973799 0.0346753 -0.078658998, + 0.0053973799 0.0368274 -0.077193998, + 0.00268824 0.036757998 -0.077372, + 0.00268824 0.038869299 -0.075850002, + 0 0.038849201 -0.075909004, + 0 0.040912598 -0.074327998, + -0.00268824 0.038869999 -0.075848997, + -0.00268824 0.036758799 -0.077372, + -0.0053973799 0.036828998 -0.077192999, + -0.0053973799 0.034677099 -0.078658, + -0.0081428103 0.034808099 -0.078357004, + -0.0081428103 0.0326222 -0.079765998, + -0.0109179 0.0328255 -0.079343997, + -0.0109179 0.0306115 -0.080697, + -0.0137106 0.0308982 -0.080154002, + -0.0137106 0.028661501 -0.081454001, + -0.0165099 0.029041201 -0.080793999, + -0.0165099 0.026786299 -0.082043, + -0.019305199 0.027267599 -0.081271, + -0.019305199 0.0249981 -0.082471997, + -0.0220857 0.0255892 -0.081592001, + -0.0220857 0.023307901 -0.082745999, + -0.0248404 0.0240156 -0.081765004, + -0.0248404 0.021725601 -0.082875997, + -0.027557701 0.022554001 -0.081802003, + -0.027557701 0.020257801 -0.082873002, + -0.0302257 0.021209501 -0.081715003, + -0.0302257 0.018908899 -0.082746997, + -0.0328326 0.0199857 -0.081514001, + -0.0328326 0.017682301 -0.082509004, + -0.035366699 0.0188847 -0.081210002, + -0.035366699 0.0165809 -0.082166001, + -0.0378174 0.0179062 -0.080810003, + -0.0378174 0.0156034 -0.081749998, + -0.040174201 0.0170477 -0.080352001, + -0.040174201 0.0147592 -0.081306003, + -0.0424264 0.016319601 -0.079879999, + -0.0424264 0.0140484 -0.080819003, + -0.044564299 0.015722901 -0.079379, + -0.044564299 0.0135283 -0.080320999, + -0.0465803 0.0153102 -0.078879997, + -0.0465803 0.0132123 -0.079919003, + -0.048467699 0.0150944 -0.078488, + -0.048467699 0.0130109 -0.079666004, + -0.050219599 0.0149871 -0.078253999, + -0.050219599 0.0129224 -0.079567999, + -0.051830001 0.014986 -0.078183003, + -0.051830001 0.0129437 -0.079631999, + -0.0532961 0.0150862 -0.078281, + -0.0532961 0.0130696 -0.079862997, + -0.0546159 0.0152822 -0.078552999, + -0.0546159 0.013294 -0.080265, + -0.055787299 0.0155673 -0.079002, + -0.055787299 0.0136102 -0.080840997, + -0.056809202 0.015934501 -0.079628997, + -0.056809202 0.0140109 -0.081591003, + -0.0576833 0.0163764 -0.080433004, + -0.0576833 0.0144885 -0.082514003, + -0.058412101 0.0150346 -0.083605997, + -0.0576833 0.0107479 -0.086847998, + -0.0576833 0.0126111 -0.084651999, + -0.058412101 0.0113733 -0.088157997, + -0.056809202 0.0101912 -0.085695997, + -0.056809202 0.0120952 -0.083613999, + -0.055787299 0.0097145298 -0.084707998, + -0.055787299 0.0116579 -0.082742997, + -0.0546159 0.00932677 -0.083884999, + -0.0546159 0.0113075 -0.082043, + -0.0532961 0.00903612 -0.083228, + -0.0532961 0.0110516 -0.081511997, + -0.051830001 0.0088498704 -0.082736, + -0.051830001 0.0108971 -0.081148997, + -0.050219599 0.0087743597 -0.082405999, + -0.050219599 0.0108503 -0.080952004, + -0.048467699 0.0088152196 -0.082235999, + -0.048467699 0.0109165 -0.080914997, + -0.0465803 0.0089766299 -0.082217999, + -0.0465803 0.0110997 -0.081032, + -0.044564299 0.0092618 -0.082346, + -0.044564299 0.0114025 -0.081295997, + -0.0424264 0.0096728504 -0.082611002, + -0.0424264 0.0118253 -0.081698, + -0.040174201 0.0102089 -0.083006002, + -0.040174201 0.012459 -0.082185999, + -0.0378174 0.0109602 -0.083475001, + -0.0378174 0.0132876 -0.082649, + -0.035366699 0.01191 -0.083907999, + -0.035366699 0.0142513 -0.083058998, + -0.0328326 0.0129963 -0.084274001, + -0.0328326 0.0153507 -0.083424002, + -0.0302257 0.0142199 -0.084581003, + -0.0302257 0.0165771 -0.083704002, + -0.027557701 0.0155709 -0.084790997, + -0.027557701 0.0179285 -0.083869003, + -0.0248404 0.0170459 -0.084880002, + -0.0248404 0.019401001 -0.083915003, + -0.0220857 0.018640401 -0.08484, + -0.0220857 0.020990301 -0.083829999, + -0.019305199 0.0203487 -0.084660999, + -0.019305199 0.022690499 -0.083601996, + -0.0165099 0.0221623 -0.084334001, + -0.0165099 0.024492299 -0.083223999, + -0.0137106 0.024070499 -0.083851002, + -0.0137106 0.026384801 -0.082686998, + -0.0109179 0.026061799 -0.083205, + -0.0109179 0.0283561 -0.081984997, + -0.0081428103 0.0281232 -0.082388997, + -0.0081428103 0.030393001 -0.081110001, + -0.0053973799 0.0302401 -0.081399001, + -0.0053973799 0.032479901 -0.080059998, + -0.00268824 0.032396302 -0.080233, + -0.00268824 0.034600001 -0.078833997, + 0 0.034574602 -0.078892, + 0 0.036735602 -0.077430002, + 0.00268824 0.034599099 -0.078833997, + 0.00268824 0.0323953 -0.080233999, + 0.0053973799 0.032478001 -0.080061004, + 0.0053973799 0.030238099 -0.0814, + 0.0081428103 0.030389899 -0.081110999, + 0.0081428103 0.0281201 -0.082388997, + 0.0109179 0.028351801 -0.081984997, + 0.0109179 0.0260574 -0.083205998, + 0.0137106 0.0263793 -0.082687996, + 0.0137106 0.024064999 -0.083851002, + 0.0165099 0.024485599 -0.083223999, + 0.0165099 0.022155499 -0.084333003, + 0.019305199 0.0226826 -0.083600998, + 0.019305199 0.020341 -0.084659003, + 0.0220857 0.0209815 -0.083828002, + 0.0220857 0.0186323 -0.084838003, + 0.0248404 0.0193919 -0.083912998, + 0.0248404 0.017038699 -0.084876999, + 0.027557701 0.0179205 -0.083866, + 0.027557701 0.0155659 -0.084787004, + 0.0302257 0.0165716 -0.083700001, + 0.0302257 0.014217 -0.084578, + 0.0328326 0.0153475 -0.083421998, + 0.0328326 0.0129924 -0.084283002, + 0.035366699 0.0142472 -0.083067998, + 0.035366699 0.011909 -0.083907999, + 0.0378174 0.0132865 -0.082649998, + 0.0378174 0.0086920196 -0.084237002, + 0.040174201 0.0102168 -0.083003998, + 0.040174201 0.0080415504 -0.083860002, + 0.0424264 0.00968388 -0.082611002, + 0.0424264 0.0075097699 -0.083605997, + 0.044564299 0.0092663802 -0.082350001, + 0.044564299 0.00711028 -0.083477996, + 0.0465803 0.0089757303 -0.082226001, + 0.0465803 0.0068437802 -0.083485998, + 0.048467699 0.0088116601 -0.082245, + 0.048467699 0.0067068702 -0.083637998, + 0.050219599 0.0087702395 -0.082416996, + 0.050219599 0.0066951602 -0.083940998, + 0.051830001 0.0088463798 -0.082745001, + 0.051830001 0.0068033501 -0.084399998, + 0.0532961 0.0090335105 -0.083237, + 0.0532961 0.0070255799 -0.085019, + 0.0546159 0.0093250396 -0.083893001, + 0.0546159 0.0073550199 -0.085799001, + 0.055787299 0.0097135799 -0.084715001, + 0.055787299 0.0077837398 -0.086741, + 0.056809202 0.0101908 -0.085702002, + 0.056809202 0.00830267 -0.087843001, + 0.0576833 0.0107479 -0.086851999, + 0.0576833 0.00890134 -0.089102, + 0.058412101 0.0113739 -0.088161997, + 0.058412101 0.0095733199 -0.090515003, + 0.058998398 0.010329 -0.092083, + 0.058998398 0.0086476598 -0.094596997, + 0.059445001 0.0095581599 -0.096418999, + 0.058412101 0.0078183096 -0.092926003, + 0.0576833 0.0070785098 -0.091407001, + 0.056809202 0.0064324099 -0.090042002, + 0.055787299 0.00587042 -0.088827997, + 0.0546159 0.0053989398 -0.08777, + 0.0532961 0.0050285002 -0.086868003, + 0.051830001 0.00476781 -0.086125001, + 0.050219599 0.0046242699 -0.085537001, + 0.048467699 0.0046039601 -0.085102998, + 0.0465803 0.0047114701 -0.084818996, + 0.044564299 0.0049513699 -0.084679998, + 0.0424264 0.00532754 -0.084674999, + 0.040174201 0.00584235 -0.084797002, + 0.0378174 0.00649276 -0.085037, + 0.035366699 0.0072645098 -0.085391, + 0.0328326 0.0106303 -0.085074998, + 0.0302257 0.0118391 -0.085399002, + 0.027557701 0.0131877 -0.085631996, + 0.0248404 0.0146605 -0.085767001, + 0.0220857 0.016256001 -0.085773997, + 0.019305199 0.0179698 -0.085644998, + 0.0165099 0.0197933 -0.085371003, + 0.0137106 0.021716099 -0.084944002, + 0.0109179 0.0237268 -0.084356003, + 0.0081428103 0.0258123 -0.0836, + 0.0053973799 0.0279583 -0.082672, + 0.00268824 0.030149201 -0.081569001, + 0 0.0323686 -0.080289997, + -0.00268824 0.030150199 -0.081569001, + -0.0053973799 0.027960399 -0.082671002, + -0.0081428103 0.0258155 -0.0836, + -0.0109179 0.0237312 -0.084356003, + -0.0137106 0.0217217 -0.084945001, + -0.0165099 0.019799899 -0.085372001, + -0.019305199 0.017976901 -0.085647002, + -0.0220857 0.0162625 -0.085777, + -0.0248404 0.014665 -0.085770003, + -0.027557701 0.0131904 -0.085634001, + -0.0302257 0.0118426 -0.085391, + -0.0328326 0.0106312 -0.085074998, + -0.035366699 0.0095570302 -0.084682003, + -0.0378174 0.0086845299 -0.084238999, + -0.040174201 0.0080311 -0.083860002, + -0.0424264 0.0075054099 -0.083601996, + -0.044564299 0.0071111498 -0.083471, + -0.0465803 0.0068472 -0.083476998, + -0.048467699 0.0067108399 -0.083627999, + -0.050219599 0.0066985399 -0.083931997, + -0.051830001 0.00680588 -0.084390998, + -0.0532961 0.00702726 -0.085010998, + -0.0546159 0.0073559401 -0.085791998, + -0.055787299 0.00778409 -0.086735003, + -0.056809202 0.0083026597 -0.087839, + -0.0576833 0.00890077 -0.089098997, + -0.058412101 0.00781149 -0.092918001, + -0.058998398 0.0103221 -0.092074998, + -0.058998398 0.0086369496 -0.094586998, + -0.059445001 0.0095448997 -0.096405998, + -0.059999999 -4.7590001e-005 -0.16150001, + -0.0599989 -2.7e-008 -0.16150001, + -0.059980098 -0.00154487 -0.1815, + -0.051818501 -0.0302191 -0.16150001, + -0.051830001 -0.0301961 -0.15875401, + -0.0528998 -0.0283127 -0.16150001, + -0.0514476 -0.030873001 -0.16150001, + -0.051438902 -0.0308876 -0.1815, + -0.055772301 -0.0220799 -0.16150001, + -0.055419099 -0.022994 -0.16150001, + -0.055787299 -0.0220578 -0.158657, + -0.056669399 -0.0197125 -0.1815, + -0.056480099 -0.0202484 -0.16150001, + 0.053285599 -0.0275524 -0.16150001, + 0.054305699 -0.0255125 -0.16150001, + 0.0532961 -0.0274012 -0.155919, + -0.055787299 -0.021951299 -0.155792, + -0.055787299 -0.021506101 -0.15001801, + -0.056809202 -0.0191726 -0.155726, + -0.0546159 -0.024254199 -0.15014701, + -0.0546159 -0.0234922 -0.144399, + -0.0532961 -0.0266195 -0.147434, + 0.0576833 -0.016358901 -0.155656, + 0.056809202 -0.0191528 -0.15572301, + 0.057460099 -0.017272299 -0.16150001, + 0.056809202 -0.0187189 -0.14988901, + 0.055787299 -0.0214929 -0.15002, + 0.0546159 -0.0246852 -0.155855, + 0.0546159 -0.0242412 -0.150149, + 0.0532961 -0.0272156 -0.15310401, + 0.055787299 -0.0219319 -0.155789, + 0.0554916 -0.0228185 -0.16150001, + 0.0557741 -0.0220806 -0.16150001, + 0.056543902 -0.0200695 -0.16150001, + 0.056661699 -0.019710001 -0.16150001, + 0.0546159 -0.023900401 -0.14727899, + 0.0532961 -0.0266075 -0.147438, + 0.0532961 -0.026180301 -0.144592, + 0.051830001 -0.0288336 -0.144778, + 0.051830001 -0.028317699 -0.14196, + 0.050219599 -0.030904699 -0.142171, + 0.050219599 -0.030297801 -0.139384, + 0.048467699 -0.032806199 -0.13961799, + 0.048467699 -0.032106001 -0.136866, + 0.0465803 -0.034524601 -0.137119, + 0.0465803 -0.033728901 -0.134406, + 0.044564299 -0.036047 -0.13467599, + 0.044564299 -0.035154 -0.132006, + 0.0424264 -0.037360799 -0.13229001, + 0.0424264 -0.036369 -0.129667, + 0.040174201 -0.038454801 -0.129961, + 0.040174201 -0.037362799 -0.12739, + 0.0378174 -0.039320599 -0.127691, + 0.0378174 -0.038128801 -0.125175, + 0.035366699 -0.0399523 -0.125479, + 0.035366699 -0.038661402 -0.123024, + 0.0328326 -0.040344801 -0.123328, + 0.0328326 -0.038955901 -0.120938, + 0.0302257 -0.040494099 -0.121238, + 0.0302257 -0.0390088 -0.118917, + 0.027557701 -0.0404003 -0.119208, + 0.027557701 -0.038821399 -0.116961, + 0.0248404 -0.040065601 -0.117241, + 0.0248404 -0.038396601 -0.115071, + 0.0220857 -0.039493199 -0.115336, + 0.0220857 -0.037737601 -0.113247, + 0.019305199 -0.038687099 -0.113492, + 0.019305199 -0.0368491 -0.111488, + 0.0165099 -0.0376551 -0.111711, + 0.0165099 -0.035739802 -0.109794, + 0.0137106 -0.036406498 -0.10999, + 0.0137106 -0.034419399 -0.108163, + 0.0109179 -0.034951199 -0.10833, + 0.0109179 -0.032898001 -0.106594, + 0.0081428103 -0.033299699 -0.106729, + 0.0081428103 -0.031186201 -0.105086, + 0.0053973799 -0.031464301 -0.105185, + 0.0053973799 -0.0292967 -0.103636, + 0.00268824 -0.0294584 -0.103697, + 0.00268824 -0.027243201 -0.102242, + 0 -0.027295601 -0.102263, + 0 -0.0250393 -0.100901, + -0.00268824 -0.027243201 -0.102242, + -0.00268824 -0.0294585 -0.103697, + -0.0053973799 -0.0292967 -0.103636, + -0.0053973799 -0.031464599 -0.105185, + -0.0081428103 -0.031186501 -0.105085, + -0.0081428103 -0.033300601 -0.106728, + -0.0109179 -0.032899301 -0.106593, + -0.0109179 -0.034953199 -0.108328, + -0.0137106 -0.034421898 -0.10816, + -0.0137106 -0.036409501 -0.109987, + -0.0165099 -0.0357434 -0.10979, + -0.0165099 -0.037659202 -0.111707, + -0.019305199 -0.036853898 -0.111484, + -0.019305199 -0.038692299 -0.113488, + -0.0220857 -0.037743501 -0.113242, + -0.0220857 -0.039499398 -0.11533, + -0.0248404 -0.0384036 -0.115065, + -0.0248404 -0.040073 -0.117235, + -0.027557701 -0.038829599 -0.116954, + -0.027557701 -0.040408801 -0.119202, + -0.0302257 -0.039018098 -0.11891, + -0.0302257 -0.040503699 -0.121231, + -0.0328326 -0.038966302 -0.120931, + -0.0328326 -0.0403555 -0.123322, + -0.035366699 -0.038672999 -0.123017, + -0.035366699 -0.039964098 -0.12547299, + -0.0378174 -0.0381414 -0.125168, + -0.0378174 -0.039333601 -0.127684, + -0.040174201 -0.037376601 -0.12738299, + -0.040174201 -0.038469099 -0.12995499, + -0.0424264 -0.036384098 -0.12966099, + -0.0424264 -0.037376702 -0.132285, + -0.044564299 -0.0351707 -0.132, + -0.044564299 -0.036064301 -0.134671, + -0.0465803 -0.033747099 -0.13440099, + -0.0465803 -0.034542799 -0.137115, + -0.048467699 -0.032124899 -0.136861, + -0.048467699 -0.032824099 -0.139613, + -0.050219599 -0.030316301 -0.13937999, + -0.050219599 -0.030920699 -0.142167, + -0.051830001 -0.0283342 -0.141956, + -0.051830001 -0.028847201 -0.144774, + -0.0532961 -0.0261942 -0.14458799, + -0.0532961 -0.0256871 -0.14173999, + -0.051830001 -0.0277365 -0.13913999, + -0.050219599 -0.0296246 -0.136599, + -0.048467699 -0.031337399 -0.13412, + -0.0465803 -0.032862298 -0.131703, + -0.044564299 -0.034187399 -0.12935001, + -0.0424264 -0.035301302 -0.12706301, + -0.040174201 -0.036194399 -0.124842, + -0.0378174 -0.036860298 -0.122689, + -0.035366699 -0.037293799 -0.120604, + -0.0328326 -0.037490498 -0.118589, + -0.0302257 -0.037448201 -0.116643, + -0.027557701 -0.037168901 -0.114766, + -0.0248404 -0.036655799 -0.11296, + -0.0220857 -0.035912398 -0.111223, + -0.019305199 -0.034944601 -0.109554, + -0.0165099 -0.0337613 -0.107952, + -0.0137106 -0.0323724 -0.106415, + -0.0109179 -0.0307885 -0.104943, + -0.0081428103 -0.029021099 -0.103531, + -0.0053973799 -0.027083 -0.102177, + -0.00268824 -0.0249875 -0.100878, + 0 -0.0227481 -0.0996328, + 0.00268824 -0.024987601 -0.100879, + 0.0053973799 -0.027083 -0.102177, + 0.0081428103 -0.029021 -0.103531, + 0.0109179 -0.030788099 -0.104943, + 0.0137106 -0.032370798 -0.106417, + 0.0165099 -0.033758301 -0.107955, + 0.019305199 -0.034940299 -0.109558, + 0.0220857 -0.0359069 -0.111228, + 0.0248404 -0.036649201 -0.112966, + 0.027557701 -0.037161201 -0.114773, + 0.0302257 -0.037439302 -0.11665, + 0.0328326 -0.037480298 -0.118596, + 0.035366699 -0.037282601 -0.120612, + 0.0378174 -0.036848001 -0.122696, + 0.040174201 -0.036180999 -0.12485, + 0.0424264 -0.035286799 -0.12706999, + 0.044564299 -0.0341716 -0.129357, + 0.0465803 -0.032844901 -0.13170899, + 0.048467699 -0.031318501 -0.13412499, + 0.050219599 -0.029604999 -0.136604, + 0.051830001 -0.0277174 -0.139145, + 0.0532961 -0.0256701 -0.141745, + 0.0546159 -0.023477901 -0.144403, + 0.055787299 -0.021155899 -0.147119, + 0.056809202 -0.0179733 -0.14401799, + 0.0576833 -0.015930099 -0.149758, + 0.058412101 -0.013561 -0.15559, + 0.058383498 -0.0137785 -0.16150001, + 0.0582381 -0.0144335 -0.16150001, + 0.057670102 -0.016506299 -0.16150001, + 0.056669399 -0.0197125 -0.1815, + 0.056795701 -0.0193008 -0.16150001, + 0.054342099 -0.0254349 -0.1815, + 0.054603901 -0.0248351 -0.16150001, + 0.054340299 -0.025434 -0.16150001, + 0.051830001 -0.0298803 -0.153199, + 0.051830001 -0.0296141 -0.150401, + 0.050219599 -0.0322151 -0.15052301, + 0.050219599 -0.031862799 -0.147745, + 0.048467699 -0.0343876 -0.147892, + 0.048467699 -0.033946499 -0.145135, + 0.0465803 -0.0363838 -0.14530601, + 0.0465803 -0.035851698 -0.142574, + 0.044564299 -0.038190499 -0.142764, + 0.044564299 -0.037565 -0.14005999, + 0.0424264 -0.039794501 -0.140268, + 0.0424264 -0.0390734 -0.137595, + 0.040174201 -0.041183401 -0.137816, + 0.040174201 -0.0403651 -0.13518, + 0.0378174 -0.042348199 -0.13541099, + 0.0378174 -0.041431099 -0.13281401, + 0.035366699 -0.043280501 -0.13305201, + 0.035366699 -0.0422634 -0.13049901, + 0.0328326 -0.043972801 -0.13074, + 0.0328326 -0.042854901 -0.128234, + 0.0302257 -0.044419002 -0.128475, + 0.0302257 -0.043200999 -0.126022, + 0.027557701 -0.044617601 -0.126258, + 0.027557701 -0.043300901 -0.123862, + 0.0248404 -0.044569101 -0.124091, + 0.0248404 -0.0431551 -0.121756, + 0.0220857 -0.0442742 -0.121974, + 0.0220857 -0.042764898 -0.119704, + 0.019305199 -0.043734901 -0.119907, + 0.019305199 -0.0421336 -0.117707, + 0.0165099 -0.042957801 -0.117892, + 0.0165099 -0.0412682 -0.115764, + 0.0137106 -0.041950699 -0.115929, + 0.0137106 -0.040176801 -0.113877, + 0.0109179 -0.0407217 -0.114018, + 0.0109179 -0.038867898 -0.112045, + 0.0081428103 -0.0392798 -0.112159, + 0.0081428103 -0.0373514 -0.110269, + 0.0053973799 -0.037636999 -0.110353, + 0.0053973799 -0.035639599 -0.108546, + 0.00268824 -0.0358059 -0.108598, + 0.00268824 -0.033745199 -0.106878, + 0 -0.033799101 -0.106896, + 0 -0.031681001 -0.105262, + -0.00268824 -0.033745501 -0.106877, + -0.00268824 -0.035806399 -0.108598, + -0.0053973799 -0.035640601 -0.108545, + -0.0053973799 -0.037638199 -0.110352, + -0.0081428103 -0.037353199 -0.110267, + -0.0081428103 -0.0392818 -0.112157, + -0.0109179 -0.038870599 -0.112043, + -0.0109179 -0.040724602 -0.114015, + -0.0137106 -0.040180501 -0.113874, + -0.0137106 -0.041954599 -0.115925, + -0.0165099 -0.041272901 -0.11576, + -0.0165099 -0.0429627 -0.117888, + -0.019305199 -0.042139299 -0.117702, + -0.019305199 -0.043740898 -0.119903, + -0.0220857 -0.042771701 -0.119699, + -0.0220857 -0.0442812 -0.121969, + -0.0248404 -0.043163098 -0.121751, + -0.0248404 -0.0445772 -0.124086, + -0.027557701 -0.043309901 -0.123857, + -0.027557701 -0.044626798 -0.12625299, + -0.0302257 -0.043211099 -0.12601601, + -0.0302257 -0.044429298 -0.12847, + -0.0328326 -0.0428662 -0.12822901, + -0.0328326 -0.043984499 -0.130735, + -0.035366699 -0.042275999 -0.130493, + -0.035366699 -0.0432938 -0.133047, + -0.0378174 -0.041445199 -0.132809, + -0.0378174 -0.042362899 -0.135406, + -0.040174201 -0.040380798 -0.135175, + -0.040174201 -0.041199099 -0.137812, + -0.0424264 -0.03909 -0.137591, + -0.0424264 -0.039810099 -0.140264, + -0.044564299 -0.037581399 -0.140056, + -0.044564299 -0.0382047 -0.14275999, + -0.0465803 -0.035866499 -0.14257, + -0.0465803 -0.036396001 -0.145302, + -0.048467699 -0.033959199 -0.14513201, + -0.048467699 -0.0343986 -0.147889, + -0.050219599 -0.031874198 -0.147742, + -0.050219599 -0.032226998 -0.15052199, + -0.051830001 -0.029626399 -0.1504, + -0.051830001 -0.029896 -0.1532, + -0.0532961 -0.026964899 -0.15027501, + -0.051830001 -0.0292773 -0.14759, + -0.050219599 -0.031439401 -0.14495499, + -0.048467699 -0.033435099 -0.142372, + -0.0465803 -0.0352493 -0.13983899, + -0.044564299 -0.036867999 -0.13735799, + -0.0424264 -0.0382788 -0.13493, + -0.040174201 -0.039470699 -0.13255399, + -0.0378174 -0.040435299 -0.130233, + -0.035366699 -0.041165698 -0.127967, + -0.0328326 -0.041655999 -0.125756, + -0.0302257 -0.041901998 -0.123602, + -0.027557701 -0.041903201 -0.121505, + -0.0248404 -0.041660599 -0.119465, + -0.0220857 -0.041176599 -0.117485, + -0.019305199 -0.0404553 -0.115562, + -0.0165099 -0.039503802 -0.113698, + -0.0137106 -0.0383306 -0.111893, + -0.0109179 -0.036945201 -0.110146, + -0.0081428103 -0.035357799 -0.108456, + -0.0053973799 -0.033581 -0.106822, + -0.00268824 -0.0316277 -0.105243, + 0 -0.029511301 -0.103717, + 0.00268824 -0.031627599 -0.105243, + 0.0053973799 -0.0335804 -0.106823, + 0.0081428103 -0.035356399 -0.108457, + 0.0109179 -0.036942702 -0.110148, + 0.0137106 -0.038327198 -0.111896, + 0.0165099 -0.039499398 -0.113702, + 0.019305199 -0.040449899 -0.115567, + 0.0220857 -0.041170102 -0.11749, + 0.0248404 -0.041652899 -0.119471, + 0.027557701 -0.041894499 -0.12151, + 0.0302257 -0.041892201 -0.123608, + 0.0328326 -0.041645002 -0.125762, + 0.035366699 -0.041153599 -0.12797301, + 0.0378174 -0.040421899 -0.13023899, + 0.040174201 -0.0394556 -0.13256, + 0.0424264 -0.0382623 -0.13493501, + 0.044564299 -0.036850501 -0.137363, + 0.0465803 -0.035232101 -0.139843, + 0.048467699 -0.033419602 -0.14237601, + 0.050219599 -0.031426199 -0.144959, + 0.051830001 -0.029265599 -0.14759301, + 0.0532961 -0.0269523 -0.15027601, + -0.0546159 -0.0247043 -0.155858, + -0.056793999 -0.0193002 -0.16150001, + -0.0574052 -0.017454101 -0.16150001, + -0.0566587 -0.019709 -0.16150001, + -0.057668298 -0.0165058 -0.16150001, + -0.0583959 -0.0137813 -0.1815, + -0.0581921 -0.0146178 -0.16150001, + -0.0576833 -0.016379001 -0.15566, + -0.056809202 -0.0187323 -0.149887, + -0.055787299 -0.020753 -0.144208, + -0.0546159 -0.022991 -0.14152101, + -0.0532961 -0.0250962 -0.13889401, + -0.051830001 -0.0270526 -0.13632999, + -0.050219599 -0.028845601 -0.133829, + -0.048467699 -0.030461799 -0.131394, + -0.0465803 -0.031888802 -0.129026, + -0.044564299 -0.033114899 -0.126726, + -0.0424264 -0.034129702 -0.124497, + -0.040174201 -0.034924101 -0.122338, + -0.0378174 -0.035491899 -0.120252, + -0.035366699 -0.035828602 -0.118239, + -0.0328326 -0.035930801 -0.1163, + -0.0302257 -0.035797399 -0.114434, + -0.027557701 -0.035430301 -0.112642, + -0.0248404 -0.0348331 -0.110924, + -0.0220857 -0.0340106 -0.109278, + -0.019305199 -0.032969002 -0.107702, + -0.0165099 -0.031717401 -0.106195, + -0.0137106 -0.030266101 -0.104756, + -0.0109179 -0.0286266 -0.103381, + -0.0081428103 -0.02681 -0.102066, + -0.0053973799 -0.024829 -0.10081, + -0.00268824 -0.022696899 -0.099609002, + 0 -0.0204277 -0.098458998, + 0.00268824 -0.022696899 -0.099609397, + 0.0053973799 -0.024829 -0.10081, + 0.0081428103 -0.02681 -0.102067, + 0.0109179 -0.0286265 -0.103381, + 0.0137106 -0.030265599 -0.104757, + 0.0165099 -0.031715401 -0.106197, + 0.019305199 -0.0329655 -0.107705, + 0.0220857 -0.034005702 -0.109282, + 0.0248404 -0.034826901 -0.11093, + 0.027557701 -0.035422899 -0.112649, + 0.0302257 -0.035788801 -0.114442, + 0.0328326 -0.035921101 -0.116308, + 0.035366699 -0.035817601 -0.118247, + 0.0378174 -0.035479899 -0.12026, + 0.040174201 -0.034910999 -0.122346, + 0.0424264 -0.034115601 -0.124505, + 0.044564299 -0.0330997 -0.126734, + 0.0465803 -0.031872202 -0.129033, + 0.048467699 -0.0304437 -0.1314, + 0.050219599 -0.028826101 -0.133835, + 0.051830001 -0.027032301 -0.136335, + 0.0532961 -0.025076499 -0.138899, + 0.0546159 -0.022973601 -0.141525, + 0.055787299 -0.020738401 -0.14421199, + 0.055787299 -0.02024 -0.141302, + 0.0546159 -0.022386899 -0.138649, + 0.0532961 -0.024399299 -0.136059, + 0.051830001 -0.026262101 -0.133536, + 0.050219599 -0.0279608 -0.131081, + 0.048467699 -0.029481299 -0.128695, + 0.0465803 -0.030811099 -0.12638199, + 0.044564299 -0.0319396 -0.124141, + 0.0424264 -0.0328569 -0.121975, + 0.040174201 -0.033554401 -0.119885, + 0.0378174 -0.034026399 -0.117872, + 0.035366699 -0.034269601 -0.115936, + 0.0328326 -0.0342815 -0.114078, + 0.0302257 -0.034060799 -0.112297, + 0.027557701 -0.033610199 -0.110593, + 0.0248404 -0.032934401 -0.108966, + 0.0220857 -0.0320387 -0.107414, + 0.019305199 -0.0309294 -0.105934, + 0.0165099 -0.029616 -0.104525, + 0.0137106 -0.0281088 -0.103184, + 0.0109179 -0.026419399 -0.101908, + 0.0081428103 -0.024558799 -0.100694, + 0.0053973799 -0.022540201 -0.099537499, + 0.00268824 -0.0203771 -0.098435, + 0 -0.0180839 -0.097381003, + -0.00268824 -0.0203771 -0.098434001, + -0.0053973799 -0.0225401 -0.099536799, + -0.0081428103 -0.024558799 -0.100693, + -0.0109179 -0.026419399 -0.101908, + -0.0137106 -0.0281089 -0.103183, + -0.0165099 -0.0296166 -0.104524, + -0.019305199 -0.0309317 -0.105931, + -0.0220857 -0.032042701 -0.10741, + -0.0248404 -0.0329399 -0.108961, + -0.027557701 -0.033617102 -0.110587, + -0.0302257 -0.034068901 -0.11229, + -0.0328326 -0.034290701 -0.11407, + -0.035366699 -0.034280099 -0.115927, + -0.0378174 -0.0340381 -0.117863, + -0.040174201 -0.033567201 -0.119876, + -0.0424264 -0.032870799 -0.121967, + -0.044564299 -0.031954501 -0.124133, + -0.0465803 -0.030827099 -0.12637401, + -0.048467699 -0.029498501 -0.12868799, + -0.050219599 -0.027979599 -0.131074, + -0.051830001 -0.026282299 -0.13353001, + -0.0532961 -0.024420099 -0.13605399, + -0.0546159 -0.0224071 -0.13864399, + -0.055787299 -0.020257801 -0.141298, + -0.056809202 -0.017988199 -0.144014, + -0.0576833 -0.015943799 -0.149756, + -0.058412101 -0.0135813 -0.15559299, + -0.0583813 -0.013778 -0.16150001, + -0.0583972 -0.0137072 -0.16150001, + -0.058839001 -0.0117463 -0.16150001, + -0.058983799 -0.0109153 -0.16150001, + -0.058998398 -0.0107903 -0.155527, + -0.059344199 -0.0088465102 -0.16150001, + -0.058412101 -0.0131511 -0.149625, + -0.0576833 -0.0152085 -0.14382, + -0.056809202 -0.017499 -0.141073, + -0.055787299 -0.0196809 -0.13839, + -0.0546159 -0.021739099 -0.135773, + -0.0532961 -0.023658801 -0.133224, + -0.051830001 -0.025426 -0.13074499, + -0.050219599 -0.0270268 -0.12833899, + -0.048467699 -0.028448001 -0.12600701, + -0.0465803 -0.0296783 -0.123752, + -0.044564299 -0.0307076 -0.121575, + -0.0424264 -0.0315261 -0.119478, + -0.040174201 -0.032125499 -0.117461, + -0.0378174 -0.032501601 -0.115526, + -0.035366699 -0.032651599 -0.113673, + -0.0328326 -0.032573398 -0.111902, + -0.0302257 -0.0322662 -0.110213, + -0.027557701 -0.031733599 -0.108604, + -0.0248404 -0.030980799 -0.107075, + -0.0220857 -0.0300132 -0.105622, + -0.019305199 -0.028837699 -0.104245, + -0.0165099 -0.027465099 -0.102938, + -0.0137106 -0.0259066 -0.1017, + -0.0109179 -0.0241722 -0.100526, + -0.0081428103 -0.022272799 -0.099413797, + -0.0053973799 -0.020222001 -0.098357998, + -0.00268824 -0.018033801 -0.097354002, + 0 -0.0157224 -0.096396998, + 0.00268824 -0.018033899 -0.097355001, + 0.0053973799 -0.0202222 -0.098359004, + 0.0081428103 -0.022273 -0.099414803, + 0.0109179 -0.0241722 -0.100527, + 0.0137106 -0.0259066 -0.101701, + 0.0165099 -0.027465001 -0.102939, + 0.019305199 -0.0288369 -0.104246, + 0.0220857 -0.0300106 -0.105625, + 0.0248404 -0.030976299 -0.107079, + 0.027557701 -0.0317275 -0.10861, + 0.0302257 -0.032258701 -0.11022, + 0.0328326 -0.032564599 -0.11191, + 0.035366699 -0.032641701 -0.113682, + 0.0378174 -0.032490399 -0.115535, + 0.040174201 -0.032113101 -0.11747, + 0.0424264 -0.031512599 -0.119487, + 0.044564299 -0.030693101 -0.121584, + 0.0465803 -0.029662799 -0.123761, + 0.048467699 -0.028431401 -0.12601499, + 0.050219599 -0.0270089 -0.128346, + 0.051830001 -0.025406601 -0.130752, + 0.0532961 -0.023638001 -0.13323, + 0.0546159 -0.021717699 -0.13577899, + 0.055787299 -0.0196603 -0.138395, + 0.056809202 -0.0174808 -0.141078, + 0.0576833 -0.0151934 -0.143824, + 0.058412101 -0.0131373 -0.149627, + 0.058998398 -0.0107698 -0.155523, + 0.0588759 -0.01156 -0.16150001, + 0.0583992 -0.0137077 -0.16150001, + 0.0583959 -0.0137813 -0.1815, + 0.051820699 -0.030220401 -0.16150001, + 0.0529892 -0.028145101 -0.16150001, + 0.051830001 -0.030068001 -0.155983, + 0.051438902 -0.0308876 -0.1815, + 0.051545098 -0.030710001 -0.16150001, + 0.054601401 0.024833901 -0.16150001, + 0.055579402 0.0226037 -0.1815, + 0.054184102 0.025769901 -0.16150001, + 0.050208401 0.032825399 -0.16150001, + 0.0497806 0.033494599 -0.1815, + 0.049818899 0.033437699 -0.16150001, + -0.0053966301 -0.059746899 -0.16150001, + -0.0058778701 -0.0597114 -0.16150001, + -0.00616926 -0.059682 -0.1815, + -0.0053973799 -0.059716899 -0.159107, + -0.00294237 -0.059927799 -0.16150001, + 0 -0.059999999 -0.1815, + 0.0026879699 -0.059931099 -0.16150001, + 0.0031320599 -0.059918199 -0.16150001, + 0.00268824 -0.059898902 -0.159109, + 0.000344617 -0.059999 -0.16150001, + 0 -0.059959099 -0.159109, + 0 -0.059834599 -0.156693, + -0.00268824 -0.059899699 -0.159109, + -0.0026880901 -0.059934001 -0.16150001, + 0 -0.059999999 -0.16150001, + -0.00268824 -0.0597753 -0.156691, + 0 -0.059623901 -0.154254, + 0.00268824 -0.059774399 -0.156691, + 0.0053973799 -0.059715401 -0.159106, + 0.0053963801 -0.059744101 -0.16150001, + 0.0060668602 -0.059692498 -0.16150001, + 0.00616926 -0.059682 -0.1815, + -0.0109154 -0.058984298 -0.16150001, + -0.0122731 -0.058731299 -0.1815, + -0.0087992204 -0.059351299 -0.16150001, + -0.0116994 -0.058848299 -0.16150001, + -0.0109179 -0.0589591 -0.159098, + -0.0081428103 -0.059405301 -0.15910301, + -0.0081428103 -0.059281301 -0.15668, + -0.0053973799 -0.059592701 -0.15668701, + -0.0053973799 -0.0593821 -0.154245, + -0.00268824 -0.059564602 -0.15425199, + -0.00268824 -0.059264898 -0.151794, + 0 -0.059324302 -0.151797, + 0 -0.058933198 -0.149327, + 0.00268824 -0.059264299 -0.151794, + 0.00268824 -0.059563801 -0.15425099, + 0.0053973799 -0.059380401 -0.154245, + 0.0053973799 -0.059590898 -0.15668701, + 0.0081428103 -0.059278499 -0.156679, + 0.0081428103 -0.059402999 -0.15910301, + 0.0109179 -0.058956102 -0.159097, + 0.0089870598 -0.059323099 -0.16150001, + 0.010915 -0.058982499 -0.16150001, + 0.0122731 -0.058731299 -0.1815, + 0.0118856 -0.058811001 -0.16150001, + -0.00267493 0.0599325 -0.16150001, + -0.0030887299 0.0599204 -0.1815, + -0.0030374301 0.059923101 -0.16150001, + 0.0081421202 0.059544701 -0.153852, + 0.0109179 0.059098799 -0.153862, + 0.0092316195 0.0592747 -0.16150001, + 0.049361002 0.067199603 -0.040943, + 0.050219599 0.0662039 -0.041655, + 0.048467699 0.065611802 -0.046425, + 0.050219599 0.068746097 -0.035670001, + 0.051042698 0.067766897 -0.036462002, + 0.051830001 0.069347002 -0.031452, + 0.0576833 0.065951303 -0.02637, + 0.058412101 0.064567603 -0.027269, + 0.0576833 0.065535203 -0.027734, + 0.056809202 0.067349002 -0.025526, + 0.056809202 0.066918798 -0.026906, + 0.055787299 0.068750903 -0.024743, + 0.055787299 0.068305098 -0.026137, + 0.0546159 0.070146598 -0.024027999, + 0.0546159 0.069683798 -0.025435001, + 0.0532961 0.071525 -0.023386, + 0.0532961 0.071043603 -0.024801999, + 0.051830001 0.072874397 -0.022822, + 0.051830001 0.072372802 -0.024242001, + 0.050219599 0.074183099 -0.022338999, + 0.050219599 0.0736598 -0.023757, + 0.048467699 0.0754392 -0.021935999, + 0.048467699 0.074297398 -0.024943, + 0.0465803 0.076052897 -0.023243001, + 0.0465803 0.074888296 -0.026392, + 0.044564299 0.076608501 -0.024821, + 0.043510102 0.0751592 -0.030483, + 0.0424264 0.076000303 -0.029803, + -0.0378174 0.074619599 -0.040738001, + -0.040174201 0.0741859 -0.038431, + -0.0378174 0.076921098 -0.033987001, + -0.035366699 0.076135099 -0.039781999, + -0.035366699 0.073789097 -0.046642002, + -0.0328326 0.075234704 -0.045839, + -0.0328326 0.072845504 -0.052781999, + -0.0302257 0.074208297 -0.052115001, + -0.0302257 0.071774401 -0.059124999, + -0.027557701 0.0730436 -0.058577001, + -0.027557701 0.0705567 -0.065637998, + -0.0248404 0.071722403 -0.065195002, + -0.0248404 0.069238603 -0.072295003, + -0.0220857 0.070291899 -0.071941003, + -0.0220857 0.067998201 -0.079144001, + -0.019305199 0.068932697 -0.078868002, + -0.019305199 0.066842496 -0.086179003, + -0.0165099 0.067654803 -0.085969001, + -0.0165099 0.0657674 -0.093370996, + -0.0137106 0.066454798 -0.093216002, + -0.0137106 0.064769901 -0.100693, + -0.0109179 0.065330103 -0.100584, + -0.0109179 0.063846998 -0.108121, + -0.0081421202 0.064278901 -0.108049, + -0.0081421202 0.062996 -0.115634, + -0.0053918599 0.0633009 -0.115591, + -0.0053918599 0.0622168 -0.123213, + -0.00267513 0.062397499 -0.123192, + -0.00267513 0.061511699 -0.13084, + 0 0.0615713 -0.130835, + 0 0.060883202 -0.13849901, + 0.00267513 0.061512601 -0.13084, + 0.00267513 0.062398501 -0.123193, + 0.0053918599 0.062218901 -0.123214, + 0.0053918599 0.0633028 -0.115592, + 0.0081421202 0.062998898 -0.115635, + 0.0081421202 0.064281598 -0.10805, + 0.0109179 0.063850597 -0.108123, + 0.0109179 0.065333597 -0.100586, + 0.0137106 0.0647742 -0.100696, + 0.0137106 0.066458799 -0.093218997, + 0.0165099 0.065772302 -0.093374997, + 0.0165099 0.067659199 -0.085973002, + 0.019305199 0.0668476 -0.086182997, + 0.019305199 0.068937004 -0.078872003, + 0.0220857 0.068003103 -0.079148002, + 0.0220857 0.070294499 -0.071943998, + 0.0248404 0.069241501 -0.072297998, + 0.0248404 0.071722597 -0.065196998, + 0.027557701 0.070556901 -0.065640002, + 0.027557701 0.073043503 -0.05858, + 0.0302257 0.0717742 -0.059128001, + 0.0302257 0.074207298 -0.052119002, + 0.0328326 0.072844498 -0.052786998, + 0.0328326 0.075232498 -0.045844998, + 0.035366699 0.073786698 -0.046649002, + 0.035366699 0.076132499 -0.039788999, + 0.0378174 0.074616797 -0.040745001, + 0.0378174 0.076924898 -0.033991002, + 0.040174201 0.075352803 -0.035115, + 0.040174201 0.076499 -0.031799, + 0.0424264 0.074857302 -0.033048, + 0.043510102 0.0728181 -0.036927, + 0.044564299 0.074297301 -0.03118, + 0.045588002 0.073415697 -0.031893, + 0.044564299 0.071929201 -0.037562001, + 0.0424264 0.071281001 -0.042849001, + 0.048887499 0.050999999 0.034754999, + 0.048460599 0.050999999 0.035362002, + 0.048901699 0.046 0.034765001, + -0.0465803 0.052742701 0.037354, + -0.046333499 0.050999999 0.038121, + -0.044564299 0.0527553 0.039708, + -0.044564299 0.054297701 0.039128002, + 0.048467699 0.051873401 0.03514, + 0.0465803 0.051879801 0.037588, + 0.048204001 0.050999999 0.035726, + 0.0465803 0.052735198 0.037317999, + 0.044564299 0.052748099 0.039673001, + 0.044564299 0.054273002 0.039111, + 0.0424264 0.054304302 0.041373, + 0.0424264 0.0557306 0.040736999, + 0.040174201 0.0557913 0.042897001, + 0.040174201 0.0571835 0.042242002, + 0.0378174 0.0572812 0.044286001, + 0.0378174 0.058691598 0.043589, + 0.035366699 0.058823001 0.045506999, + 0.035366699 0.060260698 0.044764001, + 0.0328326 0.060419898 0.046546999, + 0.0328326 0.061884701 0.04575, + 0.0302257 0.062065601 0.047391001, + 0.0302257 0.063553497 0.046535999, + 0.027557701 0.063749403 0.048030999, + 0.027557701 0.065255202 0.047115002, + 0.0248404 0.0654599 0.048459999, + 0.0248404 0.066976897 0.047481999, + 0.0220857 0.067183599 0.048675999, + 0.0220857 0.068704702 0.047635, + 0.019305199 0.068906702 0.048675001, + 0.019305199 0.070424497 0.047570001, + 0.0165099 0.070615903 0.048457999, + 0.0165099 0.072123103 0.047288999, + 0.0137106 0.072298102 0.048027001, + 0.0137106 0.073787801 0.046794999, + 0.0109179 0.073940903 0.047387, + 0.0109179 0.075406499 0.046092, + 0.0081421202 0.075532503 0.046542, + 0.0081421202 0.076967299 0.045186002, + 0.0053918599 0.077061802 0.045499001, + 0.0053918599 0.078459397 0.044082999, + 0.00267513 0.078518704 0.044266, + 0.00267513 0.0798731 0.042794, + 0 0.079893902 0.042854, + 0 0.0811994 0.041328002, + -0.00267513 0.0798738 0.042794999, + -0.00267513 0.078519396 0.044266999, + -0.0053918599 0.078460701 0.044085, + -0.0053918599 0.077063002 0.045499999, + -0.0081421202 0.076969102 0.045187999, + -0.0081421202 0.075534202 0.046544001, + -0.0109179 0.075408801 0.046094999, + -0.0109179 0.073942997 0.047389999, + -0.0137106 0.073790498 0.046799, + -0.0137106 0.072300501 0.048030999, + -0.0165099 0.072126001 0.047293, + -0.0165099 0.070618503 0.048462, + -0.019305199 0.070427597 0.047575001, + -0.019305199 0.068909504 0.04868, + -0.0220857 0.068707898 0.047641002, + -0.0220857 0.067186497 0.048682, + -0.0248404 0.066980198 0.047488999, + -0.0248404 0.065462798 0.048466001, + -0.027557701 0.065258503 0.047121, + -0.027557701 0.063752197 0.048037, + -0.0302257 0.0635565 0.046542, + -0.0302257 0.062067799 0.047396999, + -0.0328326 0.061887201 0.045756001, + -0.0328326 0.0604202 0.046553999, + -0.035366699 0.060261 0.044771001, + -0.035366699 0.058820099 0.045515001, + -0.0378174 0.058688499 0.043598, + -0.0378174 0.0572812 0.044287, + -0.040174201 0.057183601 0.042243998, + -0.040174201 0.055809699 0.042897999, + -0.0424264 0.055750102 0.040738001, + -0.0424264 0.0543277 0.041389, + 0.0328261 0.050999999 0.050209001, + 0.031530101 0.050999999 0.051031001, + 0.0308876 0.046 0.051438998, + 0.0302257 0.052812401 0.051325999, + 0.0308873 0.050999999 0.051438, + 0.031537499 0.052808002 0.050539002, + 0.030873001 0.050999999 0.051447999, + 0.0599402 0.051788099 0.00250101, + 0.059757002 0.0517952 0.0052069998, + 0.059927799 0.050999999 0.0029420001, + 0.059757002 0.052558601 0.0049170102, + 0.059445001 0.052573498 0.0076609999, + 0.059445001 0.053247198 0.0073289899, + 0.058998398 0.053272098 0.010108, + 0.058998398 0.0538706 0.0097380104, + 0.058412101 0.053908799 0.012542, + 0.058412101 0.0549196 0.011728, + 0.0576833 0.054998402 0.014556, + 0.0576833 0.055824202 0.013803, + 0.056809202 0.055959702 0.016636999, + 0.056809202 0.0576091 0.01508, + 0.055787299 0.057861902 0.01791, + 0.055787299 0.059579398 0.016209999, + 0.0546159 0.059947401 0.019018, + -0.0532961 0.0612728 0.020888001, + -0.0532961 0.062213302 0.019932, + -0.0546159 0.059953 0.019029999, + -0.051830001 0.062683403 0.022648999, + -0.051830001 0.063661098 0.021645, + -0.050219599 0.064175896 0.024296001, + -0.050219599 0.065186203 0.023241, + -0.048467699 0.065740302 0.025813, + -0.048467699 0.066778101 0.024704, + -0.0465803 0.067365497 0.027185, + -0.0465803 0.068425402 0.026021, + -0.044564299 0.069039501 0.028399, + -0.044564299 0.070115797 0.027179001, + -0.0424264 0.070749298 0.029441999, + -0.0424264 0.071835898 0.028163999, + -0.040174201 0.072480999 0.030303, + -0.040174201 0.0735716 0.028966, + -0.0378174 0.074220598 0.030972, + -0.0378174 0.075308897 0.029577, + -0.035366699 0.075954102 0.031445, + -0.035366699 0.077033497 0.029991999, + -0.0328326 0.077666797 0.031714, + -0.0328326 0.078730501 0.030205, + -0.0302257 0.079343602 0.031776998, + -0.0302257 0.080385096 0.030213, + -0.027557701 0.080970898 0.031633001, + -0.027557701 0.081983902 0.030015999, + -0.0248404 0.082535602 0.031284999, + -0.0248404 0.083513997 0.029618001, + -0.0220857 0.084024802 0.030734001, + -0.0220857 0.084962599 0.029022001, + -0.019305199 0.085426196 0.029986, + -0.019305199 0.086317703 0.028231001, + -0.0165099 0.086729199 0.029048, + -0.0165099 0.087569498 0.027255001, + -0.0137106 0.087924697 0.027929001, + -0.0137106 0.088709399 0.026102999, + -0.0109179 0.089004502 0.026639, + -0.0109179 0.089729302 0.024784001, + -0.0081421202 0.089961097 0.025188001, + -0.0081421202 0.090622202 0.023308, + -0.0053918599 0.090788797 0.023587, + -0.0053918599 0.091383502 0.02169, + -0.00267513 0.091483697 0.021850999, + -0.00267513 0.092009798 0.01994, + 0 0.092043102 0.019991999, + 0 0.092498504 0.018073, + 0.00267513 0.092008799 0.01994, + 0.00267513 0.091482699 0.021850999, + 0.0053918599 0.091381401 0.021689, + 0.0053918599 0.090786599 0.023587, + 0.0081421202 0.090618998 0.023308, + 0.0081421202 0.0899579 0.025187001, + 0.0109179 0.0897251 0.024783, + 0.0109179 0.0890003 0.026637999, + 0.0137106 0.088704102 0.026101001, + 0.0137106 0.0879196 0.027928, + 0.0165099 0.087563299 0.027253, + 0.0165099 0.086723201 0.029046001, + 0.019305199 0.086310603 0.028229, + 0.019305199 0.085419402 0.029983001, + 0.0220857 0.084954798 0.029018, + 0.0220857 0.084017299 0.03073, + 0.0248404 0.083505496 0.029614, + 0.0248404 0.082527503 0.03128, + 0.027557701 0.081974797 0.030011, + 0.027557701 0.0809623 0.031628001, + 0.0302257 0.080375597 0.030206, + 0.0302257 0.079334602 0.031771, + 0.0328326 0.078720704 0.030198, + 0.0328326 0.077657498 0.031707, + 0.035366699 0.077023499 0.029983999, + 0.035366699 0.075944699 0.031436, + 0.0378174 0.075298898 0.029568, + 0.0378174 0.074211203 0.030963, + 0.040174201 0.073561601 0.028956, + 0.040174201 0.072471701 0.030292001, + 0.0424264 0.0718261 0.028153, + 0.0424264 0.070740201 0.029431, + 0.044564299 0.070106298 0.027167, + 0.044564299 0.069030799 0.028387001, + 0.0465803 0.068416297 0.026009001, + 0.0465803 0.067357302 0.027172999, + 0.048467699 0.066769503 0.024691001, + 0.048467699 0.065732501 0.025800001, + 0.050219599 0.065178096 0.023227001, + 0.050219599 0.064168498 0.024282999, + 0.051830001 0.063653499 0.021631001, + 0.051830001 0.062676497 0.022636, + 0.0532961 0.062206201 0.019918, + 0.0532961 0.061266501 0.020876, + 0.0546159 0.0617272 0.01715, + 0.059692498 0.050999999 -0.0060669999, + 0.059679601 0.050999999 -0.00616901, + 0.059757002 0.051766999 -0.0055740098, + 0.059445001 0.051759899 -0.0083159897, + 0.059757002 0.0525002 -0.00587, + 0.0599402 0.0525149 -0.0031620001, + 0.0599402 0.053150501 -0.00351401, + 0.059999999 0.053174399 -0.000822998, + 0.059999999 0.0537217 -0.001222, + 0.0599402 0.053758301 0.00147701, + 0.0599402 0.0542331 0.001039, + 0.059757002 0.0546855 0.00333, + 0.0546159 0.065790698 0.011753, + 0.055787299 0.064314701 0.010133, + 0.0546159 0.066516198 0.010555, + 0.0532961 0.067336597 0.013274, + 0.0532961 0.068082303 0.012025, + 0.051830001 0.068941802 0.014681, + 0.051830001 0.069703102 0.01338, + 0.050219599 0.070594899 0.015961001, + 0.050219599 0.071366601 0.014607, + 0.048467699 0.072283402 0.017099001, + 0.048467699 0.073059998 0.015691999, + 0.0465803 0.073993899 0.018084999, + 0.0465803 0.074769601 0.016625, + 0.044564299 0.075712301 0.018909, + 0.044564299 0.076481603 0.017395999, + 0.0424264 0.0774244 0.019561, + 0.0424264 0.078181498 0.017997, + 0.040174201 0.0791151 0.020035001, + 0.040174201 0.079854101 0.018422, + 0.0378174 0.080770202 0.020324999, + 0.0378174 0.081485301 0.018665001, + 0.035366699 0.082375497 0.02043, + 0.035366699 0.0830613 0.018726001, + 0.0328326 0.083916903 0.020346999, + 0.0328326 0.084568299 0.018603001, + 0.0302257 0.085381001 0.020076999, + 0.0302257 0.085992798 0.018296, + 0.027557701 0.086755902 0.019622, + 0.027557701 0.087323301 0.017809, + 0.0248404 0.088030398 0.018989, + 0.0248404 0.088549502 0.017147999, + 0.0220857 0.089194402 0.018183, + 0.0220857 0.089661598 0.016318001, + 0.019305199 0.090238698 0.017209001, + 0.019305199 0.090650603 0.015326, + 0.0165099 0.091156296 0.016078999, + 0.0165099 0.091509998 0.014183, + 0.0137106 0.091941297 0.014802, + 0.0137106 0.092234798 0.012898, + 0.0109179 0.0925892 0.013389, + 0.0109179 0.092820898 0.011482, + 0.0081421202 0.093096398 0.011851, + 0.0081421202 0.093264997 0.0099470103, + 0.0053918599 0.093461297 0.010201, + 0.0053918599 0.093566097 0.0083039999, + 0.00267513 0.093683504 0.0084509999, + 0.00267513 0.093724497 0.0065659899, + 0 0.093763798 0.0066140001, + 0 0.093741402 0.004745, + -0.00267513 0.093725502 0.0065659899, + -0.00267513 0.093684599 0.0084509999, + -0.0053918599 0.093568198 0.0083039999, + -0.0053918599 0.093463503 0.0102, + -0.0081421202 0.093268298 0.0099459998, + -0.0081421202 0.093099698 0.01185, + -0.0109179 0.092825301 0.011481, + -0.0109179 0.0925937 0.013388, + -0.0137106 0.092240401 0.012897, + -0.0137106 0.0919469 0.014801, + -0.0165099 0.091516703 0.014182, + -0.0165099 0.091163099 0.016078999, + -0.019305199 0.090658501 0.015326, + -0.019305199 0.090246499 0.017209999, + -0.0220857 0.089670502 0.016318001, + -0.0220857 0.089203298 0.018183, + -0.0248404 0.088559501 0.017148999, + -0.0248404 0.0880403 0.018990999, + -0.027557701 0.087334298 0.017811, + -0.027557701 0.086766697 0.019625001, + -0.0302257 0.086004697 0.018298, + -0.0302257 0.085392602 0.02008, + -0.0328326 0.084580898 0.018606, + -0.0328326 0.083929203 0.020351, + -0.035366699 0.083074503 0.01873, + -0.035366699 0.082388401 0.020435, + -0.0378174 0.0814991 0.018671, + -0.0378174 0.080783598 0.020331001, + -0.040174201 0.079868302 0.018428, + -0.040174201 0.079128802 0.020042, + -0.0424264 0.0781959 0.018005, + -0.0424264 0.077438198 0.019569, + -0.044564299 0.076496199 0.017405, + -0.044564299 0.0757263 0.018918, + -0.0465803 0.074784197 0.016634, + -0.0465803 0.074007697 0.018095, + -0.048467699 0.0730744 0.015702, + -0.048467699 0.072297104 0.017109999, + -0.050219599 0.071380801 0.014618, + -0.050219599 0.070608303 0.015973, + -0.051830001 0.069716796 0.013393, + -0.051830001 0.068954699 0.014694, + -0.0532961 0.068095498 0.012038, + -0.0532961 0.067348897 0.013288, + -0.0546159 0.066528797 0.010569, + -0.0546159 0.065802298 0.011767, + -0.055787299 0.064325497 0.010148, + 0.0546159 0.064245097 0.014033, + 0.055787299 0.062827297 0.012317, + 0.0546159 0.065032899 0.012913, + 0.0532961 0.065741301 0.015655, + 0.0532961 0.066555403 0.014484, + 0.051830001 0.067306302 0.017166, + 0.051830001 0.068142101 0.015944, + 0.050219599 0.068929203 0.018553, + 0.050219599 0.069781698 0.017276, + 0.048467699 0.070598103 0.019799, + 0.048467699 0.071461998 0.018469, + 0.0465803 0.072300397 0.020894, + 0.0465803 0.073169999 0.019509001, + 0.044564299 0.074022703 0.021826999, + 0.044564299 0.074891999 0.020386999, + 0.0424264 0.075750299 0.022585999, + 0.0424264 0.0766133 0.021091999, + 0.040174201 0.077468596 0.023164, + 0.040174201 0.078319199 0.021616001, + 0.0378174 0.079163201 0.023554999, + 0.0378174 0.079995602 0.021956, + 0.035366699 0.080819897 0.023755001, + 0.035366699 0.081627898 0.022107, + 0.0328326 0.082424097 0.023761, + 0.0328326 0.083201803 0.022067999, + 0.0302257 0.083961397 0.023573, + 0.0302257 0.084703498 0.021837, + 0.027557701 0.0854197 0.023194, + 0.027557701 0.086121 0.021419, + 0.0248404 0.086787201 0.022627, + 0.0248404 0.087442897 0.020817, + 0.0220857 0.088052697 0.021877, + 0.0220857 0.088658102 0.020036999, + 0.019305199 0.089205697 0.020950999, + 0.019305199 0.0897571 0.019084999, + 0.0165099 0.0902384 0.019857001, + 0.0165099 0.0907325 0.017971, + 0.0137106 0.091144301 0.018607, + 0.0137106 0.091578104 0.016705999, + 0.0109179 0.0919175 0.017211, + 0.0109179 0.092288397 0.015299, + 0.0081421202 0.0925529 0.015679, + 0.0081421202 0.092859298 0.013763, + 0.0053918599 0.093048297 0.014024, + 0.0053918599 0.0932891 0.012109, + 0.00267513 0.093402401 0.01226, + 0.00267513 0.093576796 0.01035, + 0 0.093614802 0.010398, + 0 0.093722202 0.00849899, + -0.00267513 0.093577802 0.010349, + -0.00267513 0.093403503 0.012259, + -0.0053918599 0.093291298 0.012108, + -0.0053918599 0.093050502 0.014024, + -0.0081421202 0.092862703 0.013762, + -0.0081421202 0.092556201 0.015678, + -0.0109179 0.092292801 0.015299, + -0.0109179 0.091921903 0.017211, + -0.0137106 0.091583699 0.016705999, + -0.0137106 0.091149896 0.018608, + -0.0165099 0.090739198 0.017972, + -0.0165099 0.090245098 0.019858001, + -0.019305199 0.089764804 0.019086, + -0.019305199 0.089213401 0.020951999, + -0.0220857 0.088666901 0.020037999, + -0.0220857 0.0880614 0.021879001, + -0.0248404 0.087452598 0.020819001, + -0.0248404 0.086796701 0.022629, + -0.027557701 0.086131603 0.021421, + -0.027557701 0.085430004 0.023197001, + -0.0302257 0.0847148 0.021841001, + -0.0302257 0.083972499 0.023577999, + -0.0328326 0.083213799 0.022072, + -0.0328326 0.082435697 0.023766, + -0.035366699 0.0816404 0.022112999, + -0.035366699 0.0808319 0.023761, + -0.0378174 0.080008402 0.021963, + -0.0378174 0.079175599 0.023561999, + -0.040174201 0.078332402 0.021624001, + -0.040174201 0.077481203 0.023172, + -0.0424264 0.076626599 0.0211, + -0.0424264 0.075763002 0.022595, + -0.044564299 0.074905299 0.020396, + -0.044564299 0.074035197 0.021837, + -0.0465803 0.073183201 0.01952, + -0.0465803 0.072312802 0.020905999, + -0.048467699 0.071474798 0.018479999, + -0.048467699 0.070610203 0.019811001, + -0.050219599 0.0697942 0.017289, + -0.050219599 0.068940803 0.018564999, + -0.051830001 0.068154097 0.015957, + -0.051830001 0.0673173 0.01718, + -0.0532961 0.066566698 0.014498, + -0.0532961 0.065751597 0.015668999, + -0.0546159 0.065043502 0.012927, + -0.0546159 0.064254701 0.014048, + -0.055787299 0.0628362 0.012332, + -0.055787299 0.061248999 0.014359, + -0.056809202 0.060759101 0.011527, + -0.056809202 0.059213798 0.013387, + -0.0576833 0.058840498 0.010538, + -0.0576833 0.057355501 0.012246, + -0.058412101 0.057101 0.0093970001, + -0.058412101 0.055688601 0.010967, + -0.058998398 0.055553298 0.0081359996, + -0.058998398 0.054868001 0.0089079998, + -0.059445001 0.054790098 0.0061050002, + -0.059445001 0.0538655 0.00697501, + -0.0599977 0.050999999 0, + -0.059999902 0.050999999 9.5001204e-005, + -0.059999999 0.051782701 -0.00016799899, + -0.059935998 0.050999999 -0.002688, + -0.0599402 0.051775701 -0.0028530001, + -0.0599324 0.050999999 -0.00284801, + -0.059999999 0.052538998 -0.000429001, + -0.0599402 0.052553602 0.002257, + -0.0599402 0.0532244 0.001908, + -0.059757002 0.053248599 0.0046199998, + -0.059757002 0.053828198 0.00421899, + -0.059757002 0.054712899 0.003332, + -0.059445001 0.055418901 0.0053229998, + -0.058998398 0.056847099 0.0065540001, + -0.058412101 0.058466598 0.0076840101, + -0.0576833 0.060266498 0.0086799897, + -0.056809202 0.062228199 0.00950999, + 0.056809202 0.062219098 0.0094950004, + 0.056809202 0.060751501 0.011512, + 0.0576833 0.060258798 0.0086649898, + 0.0576833 0.058834601 0.010525, + 0.058412101 0.058460701 0.0076710102, + 0.058412101 0.0571004 0.0093849897, + 0.058998398 0.056846499 0.0065430002, + 0.058998398 0.055553298 0.008134, + 0.059445001 0.055418801 0.0053209998, + 0.059445001 0.054762799 0.0061030001, + 0.059757002 0.0537952 0.0041959998, + 0.0599402 0.053198401 0.001869, + 0.059999999 0.052529398 -0.00047599801, + 0.0599402 0.051774099 -0.002869, + 0.059918199 0.050999999 -0.0031320001, + 0.059999 0.050999999 -0.000345001, + 0.059931099 0.050999999 -0.002688, + 0.059999999 0.051781099 -0.000184006, + 0.059999999 0.046 0, + 0.0599402 0.052544001 0.0022100101, + 0.059757002 0.0532226 0.0045809899, + 0.059445001 0.053832699 0.0069519999, + 0.058998398 0.0548409 0.0089069996, + 0.058412101 0.055688601 0.010965, + 0.0576833 0.057354901 0.012235, + 0.056809202 0.059207998 0.013375, + 0.055787299 0.061241601 0.014344, + 0.0546159 0.063429803 0.015114, + 0.0532961 0.064896703 0.016785, + 0.051830001 0.066436902 0.018347001, + 0.050219599 0.068039902 0.019787, + 0.048467699 0.0696944 0.021088, + 0.0465803 0.071387701 0.022239, + 0.044564299 0.073106803 0.023227001, + 0.0424264 0.074837498 0.024041999, + 0.040174201 0.076565102 0.024674, + 0.0378174 0.078275099 0.025118001, + 0.035366699 0.079953298 0.025369, + 0.0328326 0.081585102 0.025424, + 0.0302257 0.083155997 0.025281999, + 0.027557701 0.084652998 0.024944, + 0.0248404 0.086064398 0.024414999, + 0.0220857 0.087378599 0.023699, + 0.019305199 0.088584803 0.022802001, + 0.0165099 0.089674197 0.021732001, + 0.0137106 0.090639897 0.020501001, + 0.0109179 0.091475703 0.019119, + 0.0081421202 0.092176102 0.017595001, + 0.0053918599 0.092737898 0.015944, + 0.00267513 0.0931594 0.014177, + 0 0.093439803 0.012309, + -0.00267513 0.093160503 0.014177, + -0.0053918599 0.092740104 0.015944, + -0.0081421202 0.092179403 0.017595001, + -0.0109179 0.091480099 0.019119, + -0.0137106 0.090645403 0.020501999, + -0.0165099 0.089680798 0.021733001, + -0.019305199 0.088592298 0.022802999, + -0.0220857 0.0873871 0.023700999, + -0.0248404 0.086073697 0.024418, + -0.027557701 0.084663101 0.024948001, + -0.0302257 0.083166704 0.025287, + -0.0328326 0.081596203 0.025429999, + -0.035366699 0.079964899 0.025376, + -0.0378174 0.078286998 0.025126001, + -0.040174201 0.076577097 0.024683001, + -0.0424264 0.074849501 0.024052, + -0.044564299 0.073118597 0.023238, + -0.0465803 0.071399301 0.02225, + -0.048467699 0.069705598 0.021101, + -0.050219599 0.068050601 0.0198, + -0.051830001 0.066446997 0.018361, + -0.0532961 0.064906098 0.016798999, + -0.0546159 0.063438602 0.015129, + -0.0546159 0.062597603 0.016167, + -0.0532961 0.0640328 0.017887, + -0.051830001 0.0655457 0.0195, + -0.050219599 0.067126296 0.020992, + -0.048467699 0.068763502 0.022346999, + -0.0465803 0.070445098 0.023553001, + -0.044564299 0.072158098 0.024596, + -0.0424264 0.073888697 0.025466001, + -0.040174201 0.075622402 0.026154, + -0.0378174 0.077344798 0.026651001, + -0.035366699 0.079041302 0.026954999, + -0.0328326 0.080697499 0.02706, + -0.0302257 0.0822988 0.026963999, + -0.027557701 0.0838321 0.026671, + -0.0248404 0.085284702 0.026182, + -0.0220857 0.086645 0.025502, + -0.019305199 0.087901898 0.024636, + -0.0165099 0.089046396 0.023593999, + -0.0137106 0.090070397 0.022384999, + -0.0109179 0.090967298 0.021020001, + -0.0081421202 0.091731504 0.019508, + -0.0053918599 0.0923592 0.017864, + -0.00267513 0.092847802 0.016099, + 0 0.093195997 0.014227, + 0.00267513 0.092846699 0.016099, + 0.0053918599 0.092357002 0.017864, + 0.0081421202 0.091728203 0.019508, + 0.0109179 0.090962902 0.021019001, + 0.0137106 0.090065002 0.022383999, + 0.0165099 0.089039899 0.023592999, + 0.019305199 0.087894499 0.024634, + 0.0220857 0.0866367 0.025498999, + 0.0248404 0.085275702 0.026178, + 0.027557701 0.083822303 0.026666, + 0.0302257 0.082288504 0.026959, + 0.0328326 0.080686703 0.027053, + 0.035366699 0.079030298 0.026946999, + 0.0378174 0.077333502 0.026643001, + 0.040174201 0.0756111 0.026145, + 0.0424264 0.073877402 0.025456, + 0.044564299 0.072146997 0.024584999, + 0.0465803 0.070434302 0.023541, + 0.048467699 0.068753198 0.022334, + 0.050219599 0.067116603 0.020978, + 0.051830001 0.065536499 0.019486001, + 0.0532961 0.064024203 0.017872, + 0.059999999 0.050999999 0, + 0.059934001 0.050999999 0.002688, + 0.059682 0.046 0.00616901, + 0.059746899 0.050999999 0.0053969999, + 0.0597114 0.050999999 0.0058780098, + 0.059445001 0.0518023 0.0079490095, + 0.058998398 0.051809501 0.01072, + 0.059351299 0.050999999 0.0087989997, + 0.058998398 0.052588601 0.010434, + 0.058412101 0.0526038 0.013224, + 0.058412101 0.053297099 0.012904, + 0.0576833 0.053947099 0.015352, + 0.055772699 0.050999999 0.02208, + 0.056496199 0.050999999 0.020203, + 0.055787299 0.0518387 0.021875, + 0.053284001 0.050999999 0.027551999, + 0.054245099 0.050999999 0.025641, + 0.0532961 0.051853001 0.02734, + 0.0546159 0.051845901 0.024626, + 0.051830001 0.0518599 0.030005001, + 0.051830001 0.052693699 0.029728999, + 0.050219599 0.052707899 0.032334998, + 0.050219599 0.054171499 0.031739999, + 0.048467699 0.054206502 0.034283999, + 0.048467699 0.055530801 0.033604998, + 0.0465803 0.055600099 0.036081001, + 0.0465803 0.056856599 0.035402998, + 0.044564299 0.056970801 0.037792001, + 0.044564299 0.0582457 0.037078999, + 0.0424264 0.058402501 0.039368, + 0.0424264 0.0597113 0.038615, + 0.040174201 0.0599057 0.040791001, + 0.040174201 0.0612498 0.039987002, + 0.0378174 0.0614761 0.042041, + 0.0378174 0.062851898 0.041182999, + 0.035366699 0.063104101 0.043108001, + 0.035366699 0.064506799 0.042192001, + 0.0328326 0.064778298 0.043977998, + 0.0328326 0.066201597 0.043003999, + 0.0302257 0.066485599 0.044643998, + 0.0302257 0.067922398 0.043609001, + 0.027557701 0.068212204 0.0451, + 0.027557701 0.0696555 0.044002999, + 0.0248404 0.0699443 0.045343, + 0.0248404 0.071386904 0.044181999, + 0.0220857 0.071667999 0.045368999, + 0.0220857 0.073102802 0.044144999, + 0.019305199 0.073369399 0.045177002, + 0.019305199 0.074789599 0.043891001, + 0.0165099 0.0750359 0.044769999, + 0.0165099 0.076434501 0.043421999, + 0.0137106 0.076654904 0.044151999, + 0.0137106 0.078025199 0.042744, + 0.0109179 0.078214303 0.043327998, + 0.0109179 0.079549901 0.041861001, + 0.0081421202 0.079703003 0.042303, + 0.0081421202 0.080997497 0.040780999, + 0.0053918599 0.081110798 0.041088998, + 0.0053918599 0.082358301 0.039514001, + 0.00267513 0.082428403 0.039693002, + 0.00267513 0.083623096 0.038068999, + 0 0.0836474 0.038127001, + 0 0.084784403 0.036458001, + -0.00267513 0.083623901 0.038070001, + -0.00267513 0.0824292 0.039694, + -0.0053918599 0.082359903 0.039515, + -0.0053918599 0.081112303 0.04109, + -0.0081421202 0.080999799 0.040782999, + -0.0081421202 0.079705201 0.042305, + -0.0109179 0.079552799 0.041864, + -0.0109179 0.078217 0.043329999, + -0.0137106 0.078028597 0.042746998, + -0.0137106 0.076658003 0.044155002, + -0.0165099 0.0764383 0.043426, + -0.0165099 0.075039402 0.044774, + -0.019305199 0.074793696 0.043896001, + -0.019305199 0.073373199 0.045182001, + -0.0220857 0.073107101 0.044151001, + -0.0220857 0.071671903 0.045375001, + -0.0248404 0.071391299 0.044188999, + -0.0248404 0.069948301 0.045348998, + -0.027557701 0.069659904 0.044009998, + -0.027557701 0.068216197 0.045108002, + -0.0302257 0.067926802 0.043616999, + -0.0302257 0.0664896 0.044652, + -0.0328326 0.066206001 0.043012001, + -0.0328326 0.064782202 0.043986, + -0.035366699 0.064511001 0.042201001, + -0.035366699 0.063107699 0.043115001, + -0.0378174 0.062855802 0.041191, + -0.0378174 0.061478999 0.042048, + -0.040174201 0.061252799 0.039995, + -0.040174201 0.059906099 0.040798999, + -0.0424264 0.059711698 0.038623001, + -0.0424264 0.058398899 0.039377999, + -0.044564299 0.058242001 0.037089001, + -0.044564299 0.056970902 0.037792999, + -0.0465803 0.056856699 0.035404, + -0.0465803 0.055621501 0.036082, + -0.048467699 0.055553 0.033606999, + -0.048467699 0.054233301 0.034302998, + -0.050219599 0.0541992 0.031759001, + -0.050219599 0.052715998 0.032375, + -0.050611299 0.050999999 0.032191999, + -0.051423199 0.050999999 0.030913999, + -0.051830001 0.052701999 0.02977, + -0.0532961 0.052687701 0.027105, + -0.0528774 0.050999999 0.028354, + -0.051830001 0.054164201 0.029142, + -0.050219599 0.055482101 0.031047, + -0.048467699 0.0567379 0.032919999, + -0.0465803 0.0580777 0.034694999, + -0.044564299 0.059507001 0.036331002, + -0.0424264 0.061012901 0.037815999, + -0.040174201 0.062586598 0.039136, + -0.0378174 0.064218797 0.040277001, + -0.035366699 0.065897398 0.041228, + -0.0328326 0.067608997 0.041979, + -0.0302257 0.069339499 0.042521998, + -0.027557701 0.071075097 0.042853002, + -0.0248404 0.072802 0.042969, + -0.0220857 0.074506499 0.042869002, + -0.019305199 0.076174803 0.042552002, + -0.0165099 0.077794202 0.042022001, + -0.0137106 0.079352699 0.041283999, + -0.0109179 0.080838703 0.040344, + -0.0081421202 0.082241401 0.039211001, + -0.0053918599 0.083551101 0.037891999, + -0.00267513 0.084759802 0.036401, + 0 0.085859999 0.034747001, + 0.00267513 0.0847589 0.036400001, + 0.0053918599 0.083549403 0.037891001, + 0.0081421202 0.082239002 0.039209001, + 0.0109179 0.080835603 0.040341999, + 0.0137106 0.079348996 0.041281, + 0.0165099 0.077790096 0.042018, + 0.019305199 0.076170303 0.042546999, + 0.0220857 0.074501798 0.042863, + 0.0248404 0.072797202 0.042962998, + 0.027557701 0.071070202 0.042846002, + 0.0302257 0.069334596 0.042514, + 0.0328326 0.067604102 0.04197, + 0.035366699 0.0658926 0.041219, + 0.0378174 0.064214297 0.040268, + 0.040174201 0.0625825 0.039128002, + 0.0424264 0.061009798 0.037808001, + 0.044564299 0.059506599 0.036322001, + 0.0465803 0.058081601 0.034683999, + 0.048467699 0.0567379 0.032919001, + 0.050219599 0.055459101 0.031044999, + 0.051830001 0.054135501 0.029123001, + 0.0532961 0.052679099 0.027062999, + 0.0546159 0.052664299 0.024347, + 0.0532961 0.0540988 0.026443999, + 0.051830001 0.0553854 0.028411999, + 0.050219599 0.056615099 0.03035, + 0.048467699 0.057910901 0.032194, + 0.0465803 0.059292302 0.033923, + 0.044564299 0.060756899 0.035512999, + 0.0424264 0.062296901 0.036947999, + 0.040174201 0.063901797 0.038213, + 0.0378174 0.065559797 0.039296001, + 0.035366699 0.067257904 0.040188, + 0.0328326 0.068982199 0.040879, + 0.0302257 0.070718497 0.041361, + 0.027557701 0.072452903 0.041630998, + 0.0248404 0.074171901 0.041685, + 0.0220857 0.075861499 0.041524, + 0.019305199 0.077508204 0.041147001, + 0.0165099 0.079099298 0.040559001, + 0.0137106 0.080623202 0.039765, + 0.0109179 0.082068399 0.038773, + 0.0081421202 0.083424203 0.037588999, + 0.0053918599 0.084681801 0.036224, + 0.00267513 0.085833497 0.034689002, + 0 0.086872101 0.032997001, + -0.00267513 0.085834399 0.03469, + -0.0053918599 0.084683597 0.036224999, + -0.0081421202 0.083426803 0.037590001, + -0.0109179 0.082071699 0.038775001, + -0.0137106 0.080627099 0.039767999, + -0.0165099 0.079103701 0.040562999, + -0.019305199 0.077513002 0.041152, + -0.0220857 0.075866699 0.041529998, + -0.0248404 0.074177198 0.041692, + -0.027557701 0.072458297 0.041638002, + -0.0302257 0.070723802 0.041368999, + -0.0328326 0.068987504 0.040888, + -0.035366699 0.067263097 0.040197, + -0.0378174 0.065564901 0.039306, + -0.040174201 0.063906603 0.038222, + -0.0424264 0.0623012 0.036956999, + -0.044564299 0.060760301 0.035521001, + -0.0465803 0.0592927 0.033932, + -0.048467699 0.0579069 0.032205001, + -0.050219599 0.056615099 0.030351, + -0.051830001 0.0554092 0.028413, + -0.0532961 0.0541282 0.026464, + -0.053653602 0.050999999 0.026818, + -0.054204401 0.050999999 0.025727, + -0.0546159 0.052673101 0.024390001, + -0.055787299 0.051840201 0.02189, + -0.055400901 0.050999999 0.023038, + -0.056128498 0.050999999 0.021159999, + -0.056464098 0.050999999 0.020292999, + 0.051830001 0.059640199 0.025374999, + 0.0532961 0.058359399 0.02348, + 0.051830001 0.0606668 0.024509, + 0.050219599 0.061015099 0.027167, + 0.050219599 0.062083799 0.026253, + 0.048467699 0.062476501 0.028836001, + 0.048467699 0.0635828 0.027873, + 0.0465803 0.0640148 0.030369001, + 0.0465803 0.065153398 0.029354, + 0.044564299 0.065619104 0.031750999, + 0.044564299 0.066784203 0.030680001, + 0.0424264 0.067276999 0.032967001, + 0.0424264 0.0684627 0.031838998, + 0.040174201 0.068975501 0.034003999, + 0.040174201 0.070175603 0.032818001, + 0.0378174 0.070701301 0.034853, + 0.0378174 0.071909502 0.033606999, + 0.035366699 0.072440803 0.035503998, + 0.035366699 0.073650502 0.034198999, + 0.0328326 0.074179597 0.035952002, + 0.0328326 0.075383998 0.034586001, + 0.0302257 0.075903103 0.036189999, + 0.0302257 0.077095501 0.034763999, + 0.027557701 0.077597298 0.036215998, + 0.027557701 0.078770898 0.034733001, + 0.0248404 0.0792486 0.036031, + 0.0248404 0.080396697 0.034490999, + 0.0220857 0.080843396 0.035636, + 0.0220857 0.081959397 0.034042001, + 0.019305199 0.082368404 0.035032999, + 0.019305199 0.0834461 0.033388998, + 0.0165099 0.083812296 0.034228999, + 0.0165099 0.084845901 0.032538, + 0.0137106 0.085164599 0.033232, + 0.0137106 0.0861485 0.031497002, + 0.0109179 0.086415201 0.032051001, + 0.0109179 0.087344103 0.030276, + 0.0081421202 0.0875552 0.030694, + 0.0081421202 0.088424802 0.028883999, + 0.0053918599 0.088577703 0.029173, + 0.0053918599 0.089384101 0.027333001, + 0.00267513 0.089477003 0.0275, + 0.00267513 0.090216503 0.025635, + 0 0.090248197 0.025690001, + 0 0.090917803 0.023805, + -0.00267513 0.090217598 0.025636001, + -0.00267513 0.089478001 0.027501, + -0.0053918599 0.089386098 0.027333001, + -0.0053918599 0.088579699 0.029173, + -0.0081421202 0.088427901 0.028884999, + -0.0081421202 0.087558202 0.030695001, + -0.0109179 0.087348104 0.030277001, + -0.0109179 0.086419098 0.032051999, + -0.0137106 0.086153299 0.031498998, + -0.0137106 0.085169204 0.033234999, + -0.0165099 0.084851503 0.032540999, + -0.0165099 0.083817698 0.034232002, + -0.019305199 0.083452404 0.033392001, + -0.019305199 0.082374498 0.035037, + -0.0220857 0.081966303 0.034047, + -0.0220857 0.080849998 0.035641, + -0.0248404 0.080404103 0.034497, + -0.0248404 0.079255603 0.036036, + -0.027557701 0.078778699 0.034738999, + -0.027557701 0.077604599 0.036222, + -0.0302257 0.077103503 0.034772001, + -0.0302257 0.075910598 0.036196999, + -0.0328326 0.075392202 0.034593999, + -0.0328326 0.074187197 0.03596, + -0.035366699 0.073658697 0.034208, + -0.035366699 0.072448403 0.035514001, + -0.0378174 0.071917601 0.033617001, + -0.0378174 0.0707087 0.034862999, + -0.040174201 0.070183396 0.032827999, + -0.040174201 0.068982601 0.034015, + -0.0424264 0.068470202 0.031851001, + -0.0424264 0.067283802 0.032977998, + -0.044564299 0.0667914 0.030692, + -0.044564299 0.065625601 0.031762999, + -0.0465803 0.065160297 0.029366, + -0.0465803 0.064020999 0.030381, + -0.048467699 0.063589297 0.027884999, + -0.048467699 0.062482301 0.028848, + -0.050219599 0.062089801 0.026265001, + -0.050219599 0.061020199 0.027177, + -0.051830001 0.060672101 0.02452, + -0.051830001 0.059644099 0.025385, + -0.0532961 0.059344701 0.022667, + -0.0532961 0.058359899 0.023490001, + 0.051830001 0.057553001 0.026969999, + 0.0532961 0.0563595 0.025002001, + 0.051830001 0.058602002 0.026195001, + 0.050219599 0.058839001 0.028849, + 0.050219599 0.059932798 0.028031999, + 0.048467699 0.060217299 0.030614, + 0.048467699 0.061353698 0.029750001, + 0.0465803 0.061681099 0.032249, + 0.0465803 0.062856302 0.031335, + 0.044564299 0.063221499 0.033737, + 0.044564299 0.064430296 0.03277, + 0.0424264 0.064827397 0.035064001, + 0.0424264 0.066064097 0.034042001, + 0.040174201 0.0664865 0.036217, + 0.040174201 0.067744799 0.035137001, + 0.0378174 0.068185903 0.037184, + 0.0378174 0.069459103 0.036045, + 0.035366699 0.0699118 0.037955999, + 0.035366699 0.071193598 0.036757, + 0.0328326 0.071650498 0.038525999, + 0.0328326 0.072934099 0.037266001, + 0.0302257 0.073387504 0.038885001, + 0.0302257 0.074666098 0.037563998, + 0.027557701 0.075108901 0.039030999, + 0.027557701 0.076375604 0.037648998, + 0.0248404 0.076801002 0.038963001, + 0.0248404 0.078048997 0.037521999, + 0.0220857 0.078450099 0.038681999, + 0.0220857 0.079672702 0.037183002, + 0.019305199 0.080042697 0.038187999, + 0.019305199 0.081233099 0.036633998, + 0.0165099 0.081566602 0.037487999, + 0.0165099 0.082718402 0.035879999, + 0.0137106 0.083010301 0.036587, + 0.0137106 0.084117703 0.034929998, + 0.0109179 0.084363498 0.035494, + 0.0109179 0.085420899 0.033790998, + 0.0081421202 0.085616402 0.034217, + 0.0081421202 0.086618498 0.032473002, + 0.0053918599 0.086760797 0.032767002, + 0.0053918599 0.087702803 0.030985, + 0.00267513 0.087789603 0.031157, + 0.00267513 0.088667601 0.029341999, + 0 0.088697299 0.029398, + 0 0.089507602 0.027555, + -0.00267513 0.0886686 0.029343, + -0.00267513 0.087790601 0.031157, + -0.0053918599 0.0877048 0.030986, + -0.0053918599 0.086762697 0.032768, + -0.0081421202 0.086621404 0.032474, + -0.0081421202 0.085619099 0.034219, + -0.0109179 0.085424699 0.033792999, + -0.0109179 0.084367 0.035496, + -0.0137106 0.084122203 0.034933001, + -0.0137106 0.0830146 0.036589999, + -0.0165099 0.082723603 0.035884, + -0.0165099 0.081571497 0.037491001, + -0.019305199 0.081238903 0.036637999, + -0.019305199 0.080048099 0.038192999, + -0.0220857 0.079678901 0.037188001, + -0.0220857 0.078455999 0.038686998, + -0.0248404 0.078055598 0.037528001, + -0.0248404 0.076807201 0.038968999, + -0.027557701 0.076382503 0.037656002, + -0.027557701 0.075115301 0.039037999, + -0.0302257 0.074672997 0.037571002, + -0.0302257 0.073393904 0.038892001, + -0.0328326 0.072940998 0.037273999, + -0.0328326 0.071656801 0.038534001, + -0.035366699 0.071200401 0.036766998, + -0.035366699 0.069918104 0.037966002, + -0.0378174 0.069465801 0.036056001, + -0.0378174 0.068191901 0.037193999, + -0.040174201 0.067751199 0.035147998, + -0.040174201 0.066492401 0.036228001, + -0.0424264 0.066070303 0.034053002, + -0.0424264 0.064833097 0.035075001, + -0.044564299 0.064436302 0.032781001, + -0.044564299 0.063226797 0.033748001, + -0.0465803 0.0628618 0.031346001, + -0.0465803 0.061685801 0.032258999, + -0.048467699 0.061358601 0.029759999, + -0.048467699 0.060220901 0.030623, + -0.050219599 0.059936602 0.028041, + -0.050219599 0.0588395 0.028859001, + -0.051830001 0.058602501 0.026206, + -0.051830001 0.057548702 0.026982, + -0.0532961 0.057362799 0.024271, + -0.0532961 0.0563596 0.025003999, + -0.0580099 0.050999999 0.015277, + -0.0576833 0.051825698 0.016321, + -0.0581805 0.050999999 0.014664, + -0.056809202 0.053371999 0.018541999, + -0.056809202 0.052643299 0.018859999, + -0.055787299 0.054054402 0.020971, + -0.0576833 0.052628201 0.016067, + -0.058412101 0.051818401 0.013525, + -0.058396801 0.050999999 0.013707, + -0.058829699 0.050999999 0.011793, + -0.058998398 0.0518112 0.010736, + -0.058412101 0.052613098 0.01327, + -0.0576833 0.053347301 0.015744001, + -0.056809202 0.054016799 0.01818, + -0.055787299 0.055181298 0.020190001, + -0.0546159 0.055258401 0.022972999, + -0.0546159 0.0562279 0.022249, + 0.0546159 0.0562279 0.022248, + 0.0546159 0.0552334 0.022971001, + 0.055787299 0.055155698 0.020189, + 0.055787299 0.054023601 0.020950001, + 0.056809202 0.053985398 0.018159, + 0.056809202 0.052634198 0.018815, + 0.0576833 0.052618999 0.016022, + 0.0576833 0.0518241 0.016306, + 0.058412101 0.051816799 0.01351, + 0.058397699 0.050999999 0.013707, + 0.058720101 0.050999999 0.012271, + 0.058731299 0.046 0.012273, + 0.058203701 0.050999999 0.014571, + 0.057158101 0.046 0.018247001, + 0.057668701 0.050999999 0.016505999, + 0.057419099 0.050999999 0.017408, + 0.056809202 0.051831398 0.019098001, + 0.055787299 0.052649301 0.021593999, + 0.0546159 0.054061402 0.023716001, + 0.0532961 0.0553101 0.025715999, + 0.051830001 0.056488801 0.027706999, + 0.050219599 0.057734501 0.029619001, + 0.048467699 0.059069499 0.031428002, + 0.0465803 0.0604924 0.033112001, + 0.044564299 0.061995901 0.034651998, + 0.0424264 0.063570499 0.036033001, + 0.040174201 0.065204397 0.037241999, + 0.0378174 0.066884898 0.038268, + 0.035366699 0.068598904 0.039099999, + 0.0328326 0.070332102 0.039730001, + 0.0302257 0.072070502 0.040151, + 0.027557701 0.073800303 0.040359002, + 0.0248404 0.075507604 0.040352002, + 0.0220857 0.077178702 0.040130001, + 0.019305199 0.0788 0.039693002, + 0.0165099 0.080359198 0.039048001, + 0.0137106 0.081844702 0.038199998, + 0.0109179 0.083245203 0.037156001, + 0.0081421202 0.084550798 0.035923, + 0.0053918599 0.085753098 0.034515001, + 0.00267513 0.0868444 0.032940999, + 0 0.087818302 0.031213, + -0.00267513 0.086845398 0.032940999, + -0.0053918599 0.085754901 0.034515999, + -0.0081421202 0.084553503 0.035925001, + -0.0109179 0.0832486 0.037158001, + -0.0137106 0.081848703 0.038203001, + -0.0165099 0.080363899 0.039051998, + -0.019305199 0.078805096 0.039698001, + -0.0220857 0.0771842 0.040135, + -0.0248404 0.0755134 0.040358, + -0.027557701 0.0738061 0.040366001, + -0.0302257 0.072076403 0.040158998, + -0.0328326 0.070337899 0.039739002, + -0.035366699 0.068604499 0.039110001, + -0.0378174 0.0668905 0.038277999, + -0.040174201 0.065209702 0.037253, + -0.0424264 0.063575603 0.036042999, + -0.044564299 0.062000498 0.034660999, + -0.0465803 0.060495902 0.033119999, + -0.048467699 0.059069902 0.031438001, + -0.050219599 0.057730298 0.02963, + -0.051830001 0.056488801 0.027708, + -0.0532961 0.055334501 0.025718, + -0.0546159 0.054091599 0.023736, + -0.055787299 0.0526582 0.021638, + -0.056809202 0.051833 0.019113, + -0.057391401 0.050999999 0.017499, + -0.056793701 0.050999999 0.019300001, + 0.056794401 0.050999999 0.019300001, + 0.0571438 0.050999999 0.018242, + 0.054979 0.046 0.024026999, + 0.055437401 0.050999999 0.022949999, + 0.054963201 0.050999999 0.024019999, + 0.0546025 0.050999999 0.024834, + 0.0522171 0.046 0.029553, + 0.052922402 0.050999999 0.028271001, + 0.051819 0.050999999 0.030219, + 0.052201401 0.050999999 0.029544, + 0.050209999 0.050999999 0.032827001, + 0.051472198 0.050999999 0.030832, + 0.050219599 0.0518668 0.032609001, + 0.048467699 0.052721798 0.034867998, + 0.0465803 0.054240402 0.036745001, + 0.044564299 0.055666801 0.038462002, + 0.0424264 0.057080001 0.040075, + 0.040174201 0.0585513 0.041540001, + 0.0378174 0.060089 0.042842999, + 0.035366699 0.061687998 0.043965001, + 0.0328326 0.063338198 0.044893999, + 0.0302257 0.065027997 0.045620002, + 0.027557701 0.066744097 0.046138, + 0.0248404 0.068473101 0.046443, + 0.0220857 0.070200801 0.046532001, + 0.019305199 0.071913198 0.046404, + 0.0165099 0.073597603 0.046059001, + 0.0137106 0.075241297 0.045503002, + 0.0109179 0.076832101 0.044739, + 0.0081421202 0.078358501 0.043772001, + 0.0053918599 0.079810098 0.042613, + 0.00267513 0.081177399 0.041269001, + 0 0.082451597 0.039751999, + -0.00267513 0.081178203 0.041269999, + -0.0053918599 0.079811603 0.042614002, + -0.0081421202 0.078360498 0.043774001, + -0.0109179 0.076834597 0.044741001, + -0.0137106 0.075244203 0.045506001, + -0.0165099 0.073600799 0.046062998, + -0.019305199 0.071916699 0.046409, + -0.0220857 0.070204303 0.046537999, + -0.0248404 0.068476699 0.04645, + -0.027557701 0.0667478 0.046145, + -0.0302257 0.065031603 0.045627002, + -0.0328326 0.063341603 0.044900998, + -0.035366699 0.061690699 0.043970998, + -0.0378174 0.060089398 0.042849999, + -0.040174201 0.058548 0.041549999, + -0.0424264 0.057080001 0.040077001, + -0.044564299 0.055687301 0.038463, + -0.0465803 0.054266099 0.036763001, + -0.048467699 0.052729499 0.034906, + -0.0498452 0.050999999 0.033397999, + -0.047047202 0.046 0.037237, + -0.048459399 0.050999999 0.035360999, + -0.050626501 0.046 0.032202002, + -0.048147298 0.050999999 0.035803001, + -0.0502089 0.050999999 0.032825999, + -0.051817998 0.050999999 0.030219, + -0.053669199 0.046 0.026826, + -0.0532832 0.050999999 0.027550999, + -0.054601699 0.050999999 0.024834, + -0.056143001 0.046 0.021165, + -0.055771999 0.050999999 0.02208, + -0.058021698 0.046 0.01528, + -0.0576679 0.050999999 0.016505999, + -0.059285302 0.046 0.0092329998, + -0.0589833 0.050999999 0.010915, + -0.0592779 0.050999999 0.0092319902, + -0.059337199 0.050999999 0.0088930102, + -0.059445001 0.051803902 0.0079650003, + -0.058998398 0.052598 0.01048, + -0.058412101 0.053322401 0.012942, + -0.0576833 0.053978998 0.015374, + -0.056809202 0.055103298 0.017380999, + -0.055787299 0.056094401 0.019456999, + -0.0546159 0.058112901 0.020725001, + -0.0532961 0.060315799 0.0218, + -0.051830001 0.061686099 0.023607999, + -0.050219599 0.063142702 0.025304001, + -0.048467699 0.0646763 0.026874, + -0.0465803 0.066276103 0.0283, + -0.044564299 0.0679304 0.029571, + -0.0424264 0.069626398 0.030672001, + -0.040174201 0.071350597 0.031590998, + -0.0378174 0.073089197 0.03232, + -0.035366699 0.074828297 0.032850999, + -0.0328326 0.076553002 0.033178002, + -0.0302257 0.078248799 0.033296999, + -0.027557701 0.0799018 0.033208001, + -0.0248404 0.081498303 0.032912001, + -0.0220857 0.083025299 0.03241, + -0.019305199 0.084470399 0.031707998, + -0.0165099 0.085822701 0.030811001, + -0.0137106 0.087072298 0.02973, + -0.0109179 0.088210396 0.028472001, + -0.0081421202 0.089229301 0.027047999, + -0.0053918599 0.090122901 0.02547, + -0.00267513 0.090886302 0.023751, + 0 0.0915161 0.021903999, + 0.00267513 0.0908852 0.023751, + 0.0053918599 0.0901208 0.025469, + 0.0081421202 0.089226097 0.027047001, + 0.0109179 0.088206299 0.02847, + 0.0137106 0.087067299 0.029727999, + 0.0165099 0.085816897 0.030809, + 0.019305199 0.084463902 0.031704001, + 0.0220857 0.083018102 0.032405999, + 0.0248404 0.081490502 0.032907002, + 0.027557701 0.0798935 0.033202, + 0.0302257 0.078240298 0.033291001, + 0.0328326 0.0765443 0.03317, + 0.035366699 0.074819498 0.032841999, + 0.0378174 0.073080502 0.032310002, + 0.040174201 0.071341999 0.031580001, + 0.0424264 0.069618098 0.03066, + 0.044564299 0.067922503 0.029558999, + 0.0465803 0.066268697 0.028287999, + 0.048467699 0.064669199 0.026861001, + 0.050219599 0.063135996 0.025292, + 0.051830001 0.0616799 0.023595, + 0.0532961 0.060310401 0.021787999, + 0.0546159 0.058112402 0.020714, + 0.055787299 0.056094401 0.019455001, + 0.056809202 0.055077199 0.017379999, + 0.058848299 0.050999999 0.011699, + 0.058984298 0.050999999 0.010915, + 0.059432399 0.050999999 0.0081410101, + 0.0596756 0.050999999 0.0061679999, + -0.055787299 0.057862401 0.017921001, + -0.056809202 0.055959702 0.016638, + -0.0576833 0.0550249 0.014558, + -0.058412101 0.053941101 0.012564, + -0.058998398 0.053297698 0.010146, + -0.059445001 0.052583098 0.0077069998, + -0.059757002 0.051796801 0.0052230102, + -0.059702002 0.050999999 0.0059730099, + -0.059431199 0.050999999 0.0081410101, + -0.0599204 0.046 0.003089, + -0.059745401 0.050999999 0.0053960001, + -0.059919201 0.050999999 0.003089, + -0.059923101 0.050999999 0.0030370001, + -0.0599402 0.051789701 0.0025170001, + -0.059757002 0.052568201 0.0049640001, + -0.059445001 0.053273 0.0073680002, + -0.058998398 0.0539032 0.0097610001, + -0.058412101 0.0549464 0.01173, + -0.0576833 0.055824298 0.013805, + -0.056809202 0.057609599 0.015091, + -0.055787299 0.059585098 0.016222, + -0.0546159 0.061734501 0.017163999, + -0.0532961 0.063134201 0.018931, + -0.051830001 0.064616203 0.020594999, + -0.050219599 0.066170603 0.022139, + -0.048467699 0.067786701 0.023549, + -0.0465803 0.069452897 0.024809999, + -0.044564299 0.071156301 0.025911, + -0.0424264 0.0728833 0.026838001, + -0.040174201 0.074619703 0.027581999, + -0.0378174 0.076351203 0.028136, + -0.035366699 0.078063503 0.028494, + -0.0328326 0.0797415 0.028651999, + -0.0302257 0.081370898 0.028607, + -0.027557701 0.082938299 0.028361, + -0.0248404 0.084431 0.027915999, + -0.0220857 0.085836403 0.027276, + -0.019305199 0.087143302 0.026447, + -0.0165099 0.088342302 0.025436001, + -0.0137106 0.089424998 0.024253, + -0.0109179 0.090383701 0.022909001, + -0.0081421202 0.091212399 0.021414001, + -0.0053918599 0.091907099 0.019780001, + -0.00267513 0.092464499 0.018021001, + 0 0.092882603 0.01615, + 0.00267513 0.092463396 0.018021001, + 0.0053918599 0.091904901 0.019780001, + 0.0081421202 0.091209203 0.021414001, + 0.0109179 0.090379402 0.022909001, + 0.0137106 0.089419603 0.024251999, + 0.0165099 0.088335998 0.025434, + 0.019305199 0.087136097 0.026443999, + 0.0220857 0.085828401 0.027272999, + 0.0248404 0.084422201 0.027912, + 0.027557701 0.082928903 0.028356001, + 0.0302257 0.081361003 0.028602, + 0.0328326 0.079731204 0.028646, + 0.035366699 0.078052901 0.028487001, + 0.0378174 0.076340497 0.028127, + 0.040174201 0.074608997 0.027572, + 0.0424264 0.072872698 0.026827, + 0.044564299 0.071145996 0.025899, + 0.0465803 0.069442898 0.024798, + 0.048467699 0.067777298 0.023536, + 0.050219599 0.0661617 0.022125, + 0.051830001 0.064607903 0.020581, + 0.0532961 0.0631264 0.018917, + -0.059932198 0.050999999 0.002688, + -0.0599204 0.046 -0.003089, + -0.059748501 0.050999999 -0.0053969999, + -0.059914999 0.050999999 -0.003088, + -0.059757002 0.051768702 -0.0055579999, + -0.0599402 0.0525245 -0.00311501, + -0.059999999 0.053200498 -0.00078300497, + -0.0599402 0.0537914 0.00149899, + -0.0599402 0.054263402 0.001052, + -0.059999999 0.053754799 -0.0011990099, + -0.0599402 0.0531765 -0.0034750099, + -0.059757002 0.0525098 -0.0058220099, + -0.059445001 0.051761501 -0.0083009899, + 0.058998398 0.051752701 -0.011088, + 0.0587232 0.050999999 -0.012271, + 0.058412101 0.0517454 -0.013877, + 0 0.093309604 -0.00073700002, + -0.00267513 0.093472198 0.00102, + 0 0.093656898 0.0028939999, + 0.00267513 0.093471497 0.001021, + 0.0546159 0.067206897 0.0093200104, + 0.055787299 0.065684497 0.007799, + 0.0546159 0.0678607 0.0080500003, + 0.0532961 0.068790302 0.01074, + 0.0532961 0.069458403 0.00941901, + 0.051830001 0.070423499 0.012043, + 0.051830001 0.071100898 0.010671, + 0.050219599 0.072094299 0.013217, + 0.050219599 0.072775602 0.011793, + 0.048467699 0.073789299 0.01425, + 0.048467699 0.074469499 0.012775, + 0.0465803 0.075495198 0.01513, + 0.0465803 0.076168798 0.013605, + 0.044564299 0.077197999 0.015851, + 0.044564299 0.077859402 0.014277, + 0.0424264 0.078882702 0.016403001, + 0.0424264 0.079526298 0.014782, + 0.040174201 0.080534503 0.016781, + 0.040174201 0.081154898 0.015114, + 0.0378174 0.082139499 0.01698, + 0.0378174 0.082731701 0.015272, + 0.035366699 0.083684199 0.016999001, + 0.035366699 0.084243 0.015253, + 0.0328326 0.085154697 0.016838999, + 0.0328326 0.085675299 0.015058, + 0.0302257 0.086537898 0.016497999, + 0.0302257 0.087016001 0.014687, + 0.027557701 0.087823004 0.015982, + 0.027557701 0.088254802 0.014145, + 0.0248404 0.089000002 0.015296, + 0.0248404 0.089382 0.013438, + 0.0220857 0.090059496 0.014447, + 0.0220857 0.090388298 0.012573, + 0.019305199 0.090992801 0.013441, + 0.019305199 0.091265999 0.011556, + 0.0165099 0.0917942 0.012287, + 0.0165099 0.092009999 0.010396, + 0.0137106 0.092459403 0.010998, + 0.0137106 0.092616104 0.0091069899, + 0.0109179 0.092984401 0.0095829898, + 0.0109179 0.093080796 0.0076959999, + 0.0081421202 0.093366399 0.0080540003, + 0.0081421202 0.093402199 0.0061759902, + 0.0053918599 0.093605198 0.006422, + 0.0053918599 0.093580402 0.0045560002, + 0.00267513 0.093701497 0.0046979999, + 0.00267513 0.093616597 0.002849, + 0.0053918599 0.093493797 0.0027079899, + 0.0081421202 0.093374297 0.004313, + 0.0109179 0.093111902 0.0058229999, + 0.0137106 0.092706099 0.0072260001, + 0.0165099 0.092158303 0.0085140103, + 0.019305199 0.0914713 0.0096749999, + 0.0220857 0.090648599 0.0107, + 0.0248404 0.089695297 0.011578, + 0.027557701 0.088618703 0.012302, + 0.0302257 0.087427102 0.012867, + 0.0328326 0.086129703 0.013265, + 0.035366699 0.084736899 0.013491, + 0.0378174 0.083260797 0.013545, + 0.040174201 0.081714399 0.013427, + 0.0424264 0.0801109 0.013136, + 0.044564299 0.078464203 0.012676, + 0.0465803 0.076788597 0.012052, + 0.048467699 0.075098701 0.01127, + 0.050219599 0.073408902 0.010339, + 0.051830001 0.071732901 0.0092669996, + 0.0532961 0.070084199 0.0080659902, + 0.0546159 0.068475403 0.0067469901, + 0.055787299 0.066918299 0.0053240098, + 0.056809202 0.0648451 0.0050160098, + 0.056809202 0.063589796 0.0073270001, + 0.0576833 0.0628611 0.0045059999, + 0.0576833 0.0616077 0.0066570002, + 0.058412101 0.060995299 0.0038159899, + 0.058412101 0.059765302 0.0058129998, + 0.058998398 0.059273101 0.00296899, + 0.058998398 0.058087699 0.0048240102, + 0.059445001 0.057716999 0.0019950001, + 0.059445001 0.0565942 0.0037179999, + 0.059757002 0.056344599 0.00092399598, + 0.059757002 0.0552858 0.00253799, + 0.0599402 0.055154599 -0.000207993, + 0.0599402 0.054609299 0.00059300201, + 0.059999999 0.054533701 -0.0021230001, + 0.059999999 0.054179501 -0.001668, + 0.0599402 0.054125901 -0.00437601, + 0.0599402 0.053685099 -0.0039210101, + 0.059757002 0.0536482 -0.0066410098, + 0.059757002 0.053126302 -0.0062259999, + 0.059445001 0.053101901 -0.0089739999, + 0.059445001 0.052485399 -0.0086130099, + 0.058998398 0.052470401 -0.011385, + 0.048901699 0.046 -0.034765001, + 0.050207902 0.050999999 -0.032825001, + 0.0522171 0.046 -0.029553, + 0.045067899 0.046 -0.039609, + 0.046573199 0.050999999 -0.037811998, + 0.040756401 0.046 -0.044032998, + 0.042423598 0.050999999 -0.042424001, + 0.0220857 0.055891499 -0.153938, + 0.021159001 0.056127101 -0.16150001, + 0.019305199 0.056912299 -0.153914, + -0.057264499 0.0574499 -0.044799998, + -0.056809202 0.055648498 -0.04919, + -0.0576833 0.0563921 -0.045655001, + -0.0576833 0.0593375 -0.040594999, + -0.058065701 0.058315702 -0.041528001, + -0.058412101 0.058791202 -0.039944999, + -0.0220796 0.050999999 -0.055771999, + -0.0225999 0.050999999 -0.055569999, + -0.0220857 0.051636901 -0.055891, + -0.020698 0.0516355 -0.056419998, + -0.0220857 0.052234001 -0.056189001, + -0.0107539 0.050999999 -0.059011001, + -0.0109179 0.0516284 -0.059099, + -0.0089402199 0.050999999 -0.059330001, + -0.013707 0.050999999 -0.058396, + -0.0147097 0.050999999 -0.058169, + -0.0137106 0.051629901 -0.058513001, + -0.0118392 0.050999999 -0.058820002, + -0.0137106 0.051936202 -0.058639999, + -0.0165099 0.0519391 -0.057911001, + -0.0165099 0.052223299 -0.058084998, + -0.0179088 0.052225702 -0.057666998, + -0.0179088 0.051940799 -0.057491999, + -0.0165099 0.051631901 -0.057785001, + -0.0167653 0.050999999 -0.057595, + -0.0175448 0.050999999 -0.057378002, + -0.0167691 0.046 -0.057608999, + -0.016505601 0.050999999 -0.057668, + -0.0107568 0.046 -0.059028, + -0.0109151 0.050999999 -0.058983002, + -0.0081410101 0.050999999 -0.059431002, + -0.0046305298 0.046 -0.059820998, + -0.000142344 0.050999999 -0.059999999, + -7.3000002e-008 0.050999999 -0.059997, + 0.00154487 0.046 -0.059980001, + -0.002688 0.050999999 -0.059930999, + -0.00268824 0.051311798 -0.059965, + -0.0030847499 0.050999999 -0.059921, + 0.0546159 0.050507098 -0.042107999, + 0.055787299 0.0511714 -0.040412001, + 0.0546159 0.0508679 -0.041118, + 0.0532961 0.049938701 -0.043807, + 0.0532961 0.050699499 -0.041873001, + 0.052581199 0.050294802 -0.043214999, + 0.051830001 0.0506793 -0.042653002, + 0.051042698 0.049498402 -0.045855001, + 0.051830001 0.049894299 -0.044543002, + 0.050219599 0.0499999 -0.045283001, + 0.051830001 0.049026299 -0.046448, + 0.052581199 0.049480099 -0.045134, + 0.052581199 0.0485764 -0.047065001, + 0.0532961 0.0490871 -0.045756001, + 0.0532961 0.049524602 -0.044780001, + 0.0546159 0.050122101 -0.043102, + 0.0546159 0.0497122 -0.044100001, + 0.055787299 0.050429299 -0.042452, + 0.051042698 0.047571301 -0.049642, + 0.050219599 0.047077999 -0.050905999, + 0.051830001 0.047559101 -0.049318999, + 0.050219599 0.048134901 -0.049027, + 0.048467699 0.047268301 -0.051534999, + 0.048467699 0.048342802 -0.049686, + 0.0465803 0.047603201 -0.052138001, + 0.0465803 0.048700899 -0.050313, + 0.044564299 0.0480868 -0.052691001, + 0.044564299 0.049211498 -0.050880998, + 0.0424264 0.048719101 -0.053167, + 0.0424264 0.0498726 -0.051364001, + 0.040174201 0.049495898 -0.053541001, + 0.040174201 0.050678302 -0.051736001, + 0.0378174 0.050409202 -0.053791001, + 0.0378174 0.0516189 -0.051978, + 0.035366699 0.051447298 -0.053899001, + 0.035366699 0.052676 -0.052065998, + 0.0328326 0.0525911 -0.053842001, + 0.0328326 0.0529024 -0.053378001, + 0.031537499 0.052871399 -0.054211002, + 0.031537499 0.0530053 -0.053959999, + 0.0302257 0.0530832 -0.054481, + 0.0302257 0.053142801 -0.05418, + 0.031537499 0.053105 -0.053686, + 0.0328326 0.053180501 -0.052554999, + 0.0302257 0.053153399 -0.053865001, + 0.027557701 0.053124901 -0.055341002, + 0.027557701 0.053089101 -0.055025, + 0.0248404 0.053068001 -0.056352001, + 0.0248404 0.052987602 -0.056044001, + 0.0220857 0.052972399 -0.057218999, + 0.0220857 0.052850202 -0.056928001, + 0.019305199 0.0528396 -0.057951, + 0.020698 0.052680399 -0.057188999, + 0.0179088 0.052672599 -0.058136001, + 0.019305199 0.052676398 -0.057681002, + 0.0179088 0.052468002 -0.057893001, + 0.0165099 0.052465301 -0.058311, + 0.0165099 0.052220602 -0.058098, + 0.0137106 0.052216899 -0.058825999, + 0.0137106 0.051629599 -0.058517002, + 0.0109179 0.051628102 -0.059101999, + 0.0081428103 0.051626999 -0.059548002, + 0.0109179 0.052214 -0.059409998, + 0.0137106 0.0524606 -0.059039, + 0.0165099 0.052669201 -0.058555, + 0.0165099 0.052830599 -0.058827002, + 0.0137106 0.0526633 -0.059284002, + 0.0109179 0.0524569 -0.059624001, + 0.0081428103 0.052211799 -0.059854999, + 0.0067656301 0.0516265 -0.059719998, + 0.0081428103 0.0513114 -0.059469, + 0.00814154 0.050999999 -0.059434, + 0.0077019902 0.050999999 -0.059487998, + 0.0086586103 0.050999999 -0.059372, + 0.0109179 0.051311702 -0.059021998, + 0.0137077 0.050999999 -0.058398999, + 0.0137813 0.046 -0.058396, + 0.01156 0.050999999 -0.058876, + 0.0165099 0.0513128 -0.057707001, + 0.019305199 0.051313698 -0.056832999, + 0.017272299 0.050999999 -0.057459999, + 0.019305199 0.051633701 -0.056917001, + 0.020698 0.052227698 -0.056735002, + 0.0220857 0.051636301 -0.055895999, + 0.0165099 0.051631398 -0.057789002, + 0.0179088 0.0522228 -0.057681002, + 0.0137106 0.0513121 -0.058435999, + 0.0144335 0.050999999 -0.058238, + 0.0137785 0.050999999 -0.058382999, + 0.019305199 0.052471001 -0.057438001, + 0.019305199 0.0529592 -0.058244999, + 0.0220857 0.0530493 -0.057528999, + 0.0248404 0.053099301 -0.056669999, + 0.027557701 0.053108599 -0.055658001, + 0.0328326 0.0530321 -0.053128, + 0.035366699 0.052968498 -0.051603999, + 0.0378174 0.0527674 -0.050152998, + 0.040174201 0.051802199 -0.049926002, + 0.0424264 0.0509637 -0.049557, + 0.044564299 0.050269399 -0.049070001, + 0.0465803 0.049726699 -0.048489001, + 0.048467699 0.049339499 -0.047839999, + 0.050219599 0.049107499 -0.047150999, + 0.051042698 0.0485777 -0.047745999, + 0.051830001 0.0480709 -0.048361, + 0.0532961 0.048625801 -0.046732999, + 0.0532961 0.048140202 -0.047711998, + 0.0546159 0.0492769 -0.0451, + 0.0546159 0.048815802 -0.046101, + 0.055787299 0.0495793 -0.044500999, + 0.056809202 0.050841998 -0.041875999, + 0.048467699 0.0502626 -0.046000998, + 0.0465803 0.050684601 -0.046668999, + 0.044564299 0.051264402 -0.047261, + 0.0424264 0.051996499 -0.04775, + 0.040174201 0.052865099 -0.048108999, + 0.0378174 0.0530398 -0.049693, + 0.035366699 0.053089201 -0.051355999, + 0.0328326 0.0531279 -0.052854002, + 0.035366699 0.0531766 -0.051084999, + 0.0378174 0.053150699 -0.049447, + 0.040174201 0.053115901 -0.047651999, + 0.0424264 0.052968699 -0.045942001, + 0.044564299 0.052201301 -0.045458, + 0.0465803 0.051579099 -0.044859, + 0.048467699 0.051116399 -0.044174001, + 0.050219599 0.0508167 -0.043428998, + 0.056809202 0.0515926 -0.039779, + 0.0576833 0.052111398 -0.039237, + 0.0576833 0.0513389 -0.041391, + 0.058412101 0.052705299 -0.038802002, + 0.058412101 0.051897898 -0.041009001, + 0.058998398 0.0533504 -0.038481999, + 0.058998398 0.052494999 -0.040738001, + 0.059445001 0.054021399 -0.038286999, + 0.059445001 0.0535817 -0.039438002, + 0.059757002 0.054692999 -0.038219001, + 0.059757002 0.054218601 -0.039384998, + 0.0599402 0.0553433 -0.038272999, + 0.059445001 0.053106502 -0.040582001, + 0.058998398 0.052016001 -0.041857999, + 0.058412101 0.050958999 -0.043205, + 0.0576833 0.050441999 -0.043542001, + 0.056809202 0.049974602 -0.043977, + 0.055787299 0.049112499 -0.045526002, + 0.0546159 0.048328299 -0.047102001, + 0.0532961 0.0476298 -0.048689999, + 0.051830001 0.047024101 -0.050276, + 0.050219599 0.046516899 -0.051844999, + 0.048467699 0.046112899 -0.053381, + 0.0465803 0.046430301 -0.053959999, + 0.044564299 0.046891998 -0.054496001, + 0.0424264 0.047499899 -0.054963, + 0.040174201 0.0482517 -0.055335999, + 0.0378174 0.0491408 -0.055594001, + 0.035366699 0.050157201 -0.055714998, + 0.0328326 0.051288001 -0.055682, + 0.0302257 0.0525131 -0.055473998, + 0.0081428103 0.0524542 -0.060070001, + 0.0067656301 0.052211002 -0.060027, + 0.0053973799 0.0524524 -0.060380999, + 0.0081428103 0.052655298 -0.060316, + 0.0109179 0.052658599 -0.059870001, + 0.0109179 0.052817501 -0.060144, + 0.0137106 0.052823301 -0.059556998, + 0.0137106 0.052939001 -0.059852999, + 0.0165099 0.052948099 -0.059122, + 0.0165099 0.053019401 -0.059434999, + 0.019305199 0.053033099 -0.058556002, + 0.019305199 0.053056899 -0.058878001, + 0.0220857 0.053076599 -0.057849001, + 0.0220857 0.0530506 -0.058171, + 0.0248404 0.053077798 -0.056990001, + 0.0248404 0.053006101 -0.057294998, + 0.027557701 0.053042602 -0.055962, + 0.027557701 0.052786499 -0.056492999, + 0.0302257 0.052841701 -0.055008002, + 0.0053973799 0.051930699 -0.05999, + 0.0053973799 0.051626202 -0.059859, + 0.00268824 0.051625699 -0.060042001, + 0.00268824 0.051311299 -0.059964001, + 0.00154448 0.050999999 -0.059962001, + 0 0.0513115 -0.060024999, + 0.0053973799 0.051311299 -0.059781, + 0.0028003999 0.050999999 -0.059935, + 0.0057364102 0.050999999 -0.059725001, + 0.0077038999 0.046 -0.059503, + 0.0109157 0.050999999 -0.058986001, + 0.0053968299 0.050999999 -0.059749, + 0.0026881699 0.050999999 -0.059937, + -0.00268824 0.051625799 -0.060040999, + -0.0302257 0.053097099 -0.054480001, + -0.0302257 0.052990399 -0.054758999, + -0.0288986 0.053075701 -0.055238999, + -0.0328326 0.053043801 -0.053130001, + -0.0328326 0.0529099 -0.053382002, + -0.035366699 0.052976601 -0.051608, + -0.035366699 0.052676 -0.052065, + -0.0378174 0.0527674 -0.050151002, + -0.0378174 0.051619198 -0.051971, + -0.040174201 0.051802501 -0.049918, + -0.040174201 0.050682399 -0.051727001, + -0.0424264 0.050968099 -0.049548, + -0.0424264 0.049878199 -0.051353, + -0.044564299 0.0502753 -0.049058001, + -0.044564299 0.049218599 -0.050868999, + -0.0465803 0.049734201 -0.048475999, + -0.0465803 0.048709899 -0.050301, + -0.048467699 0.049348898 -0.047827002, + -0.048467699 0.048354 -0.049674001, + -0.050219599 0.0491191 -0.047138002, + -0.050219599 0.0481482 -0.049015, + -0.051830001 0.049040101 -0.046434999, + -0.051830001 0.0485745 -0.047392, + -0.0532961 0.049102999 -0.045743998, + -0.0053973799 0.051626299 -0.059858002, + -0.0060197199 0.050999999 -0.059696998, + -0.0081428103 0.0516272 -0.059546001, + -0.0081428103 0.0519321 -0.059673, + -0.0109179 0.0519339 -0.059227001, + -0.0109179 0.052215699 -0.059402, + -0.0137106 0.0522191 -0.058814999, + -0.0137106 0.052464899 -0.059028, + -0.0165099 0.052470401 -0.058297999, + -0.0165099 0.052676301 -0.058545001, + -0.019305199 0.052684698 -0.057668999, + -0.019305199 0.052849598 -0.057941999, + -0.0220857 0.052861702 -0.056917001, + -0.0220857 0.052984599 -0.057211, + -0.0248404 0.0530013 -0.056035001, + -0.0248404 0.0530813 -0.056343999, + -0.027557701 0.053103901 -0.055016998, + -0.027557701 0.0531388 -0.055335, + -0.0302257 0.053168699 -0.053858001, + -0.0302257 0.053157799 -0.054175999, + -0.0328326 0.053196799 -0.052551001, + -0.0328326 0.053142998 -0.052852999, + -0.035366699 0.053192802 -0.051082999, + -0.035366699 0.0531018 -0.051357999, + -0.0378174 0.053164199 -0.049449001, + -0.0378174 0.053048301 -0.049697999, + -0.040174201 0.053125001 -0.047657002, + -0.040174201 0.052865099 -0.048108, + -0.0424264 0.052968699 -0.045940999, + -0.0424264 0.051996902 -0.047742002, + -0.044564299 0.052201699 -0.045449998, + -0.044564299 0.051268999 -0.047251001, + -0.0465803 0.0515838 -0.044849001, + -0.0465803 0.0506908 -0.046658002, + -0.048467699 0.0511229 -0.044160999, + -0.048467699 0.050270401 -0.045988001, + -0.050219599 0.050824702 -0.043416001, + -0.050219599 0.050009701 -0.04527, + -0.051830001 0.050689399 -0.042638998, + -0.051830001 0.049906202 -0.044530001, + -0.0532961 0.050711799 -0.041859999, + -0.0532961 0.049952898 -0.043793999, + -0.0546159 0.050882399 -0.041104998, + -0.0546159 0.050138399 -0.043090001, + -0.055787299 0.051188 -0.040399998, + -0.055787299 0.050447602 -0.042440999, + -0.056809202 0.0516112 -0.039769001, + -0.056809202 0.050861999 -0.041866999, + -0.0576833 0.052131802 -0.039228, + -0.0576833 0.0513606 -0.041384, + -0.058412101 0.0527272 -0.038794, + -0.058412101 0.051920801 -0.041003998, + -0.058998398 0.0533734 -0.038477, + -0.058998398 0.052518699 -0.040734999, + -0.059445001 0.0540452 -0.038284, + -0.059445001 0.053605702 -0.039436001, + -0.059757002 0.054717299 -0.038219001, + -0.059757002 0.054242998 -0.039386999, + -0.0599402 0.055367801 -0.038276002, + -0.059445001 0.053130701 -0.040582001, + -0.058998398 0.052039798 -0.041857, + -0.058412101 0.050982401 -0.043202002, + -0.0576833 0.0504646 -0.043536998, + -0.056809202 0.049995899 -0.043970998, + -0.055787299 0.049598999 -0.044491999, + -0.0546159 0.0492948 -0.045088999, + -0.027557701 0.0531222 -0.055654999, + -0.0248404 0.053111799 -0.056665, + -0.0220857 0.053061102 -0.057523001, + -0.019305199 0.052969899 -0.058237001, + -0.0165099 0.052839201 -0.058818001, + -0.0137106 0.052669201 -0.059275001, + -0.0109179 0.052460302 -0.059615999, + -0.0081428103 0.052213099 -0.059849001, + -0.0053973799 0.0519308 -0.059985999, + -0.0046291598 0.050999999 -0.059803002, + -0.0053964402 0.050999999 -0.059744999, + -0.019305199 0.052476998 -0.057422999, + -0.0220857 0.052694499 -0.056644998, + -0.023467001 0.052699801 -0.056077, + -0.0220857 0.052484699 -0.056400001, + -0.020698 0.052230999 -0.056717999, + -0.0203376 0.050999999 -0.056448001, + -0.019300001 0.050999999 -0.056793001, + -0.0226037 0.046 -0.055578999, + -0.019305199 0.0516342 -0.056910999, + -0.0179088 0.051633 -0.057365999, + -0.019305199 0.052228201 -0.057211, + -0.028196299 0.050999999 -0.052956, + -0.0275509 0.050999999 -0.053282999, + -0.0281986 0.046 -0.052960999, + -0.025769901 0.050999999 -0.054184001, + -0.027557701 0.051643498 -0.053401999, + -0.052581199 0.065761 -0.038077999, + -0.051830001 0.064165503 -0.043102998, + -0.0532961 0.064746901 -0.038899001, + -0.0532961 0.067401104 -0.033231001, + -0.053974401 0.066413403 -0.034132998, + -0.0546159 0.066763401 -0.032228, + -0.049361002 0.072183199 -0.028863, + -0.050219599 0.072487898 -0.026687, + -0.048467699 0.073100902 -0.028024999, + -0.048467699 0.070652701 -0.034123, + -0.047540501 0.071587801 -0.033365998, + -0.0465803 0.070086502 -0.038871001, + -0.047540501 0.069139503 -0.039547998, + -0.0465803 0.067583203 -0.045175001, + -0.045588002 0.068539403 -0.044571999, + -0.044564299 0.066945396 -0.050446, + -0.047540501 0.066608198 -0.045790002, + -0.0465803 0.065000601 -0.051525999, + -0.048467699 0.065615296 -0.046416, + -0.048467699 0.068175197 -0.040236998, + -0.049361002 0.067194603 -0.040938001, + -0.050219599 0.068736203 -0.035672002, + -0.049361002 0.069701798 -0.034892, + -0.050219599 0.071251199 -0.029713999, + -0.051042698 0.070306003 -0.030578, + -0.051830001 0.070620701 -0.028495001, + -0.056316901 0.059559301 -0.043094002, + -0.055787299 0.057817001 -0.04764, + -0.056809202 0.058506001 -0.043946002, + -0.056809202 0.0613777 -0.038731001, + -0.057264499 0.060358498 -0.039662, + -0.0576833 0.060796399 -0.038004, + -0.056316901 0.062394299 -0.037803002, + -0.056809202 0.062798597 -0.036065999, + -0.055787299 0.063407198 -0.036878001, + -0.055787299 0.0606087 -0.042245001, + -0.055220202 0.061653301 -0.0414, + -0.0546159 0.059965499 -0.046105001, + -0.055220202 0.064415403 -0.035957001, + -0.055787299 0.064790197 -0.034138002, + -0.0546159 0.065417796 -0.035041999, + -0.0546159 0.062692001 -0.04056, + -0.053974401 0.063723497 -0.039726, + -0.0532961 0.062084701 -0.04459, + -0.0137071 0.058396801 -0.16150001, + -0.0146637 0.0581805 -0.16150001, + -0.0137106 0.058508601 -0.153877, + -0.015277 0.0580099 -0.16150001, + -0.0165099 0.0577797 -0.15389401, + -0.0165099 0.058079001 -0.146277, + -0.019305199 0.057206701 -0.146318, + -0.019305199 0.0577076 -0.13872001, + -0.0220857 0.056691099 -0.13879099, + -0.0220857 0.057397898 -0.13122199, + -0.0248404 0.056237999 -0.131329, + -0.0248404 0.0571572 -0.123802, + -0.027557701 0.055858798 -0.123953, + -0.027557701 0.056994401 -0.116479, + -0.0302257 0.0555638 -0.116681, + -0.0302257 0.0569195 -0.109277, + -0.0328326 0.055363499 -0.109536, + -0.0328326 0.0569437 -0.102217, + -0.035366699 0.0552704 -0.102543, + -0.035366699 0.0570792 -0.095326997, + -0.0378174 0.055300001 -0.095728002, + -0.0378174 0.057338901 -0.088634998, + -0.040174201 0.055466 -0.089119002, + -0.040174201 0.057735302 -0.082172997, + -0.0424264 0.0557805 -0.08275, + -0.0424264 0.058279298 -0.075972997, + -0.044564299 0.056254402 -0.076653004, + -0.044564299 0.0589667 -0.070047997, + -0.0465803 0.056885101 -0.070840001, + -0.0465803 0.0596435 -0.064358003, + -0.048467699 0.057521898 -0.065274, + -0.048467699 0.060276601 -0.058936, + -0.050219599 0.058132101 -0.059985999, + -0.050219599 0.060887098 -0.053812001, + -0.051830001 0.0587359 -0.055008002, + -0.051830001 0.061487101 -0.049019001, + -0.0532961 0.059344701 -0.05037, + -0.056809202 0.064167097 -0.033479001, + -0.0576833 0.062204499 -0.035487, + -0.0576833 0.062856197 -0.034262002, + -0.058412101 0.0609124 -0.036306001, + -0.058412101 0.0615521 -0.035082001, + -0.0302257 0.052907702 -0.052948002, + -0.0302257 0.053040698 -0.053236999, + -0.027557701 0.052890699 -0.054418001, + -0.027557701 0.05302 -0.054708999, + -0.0248404 0.0528754 -0.055741999, + -0.0302257 0.053128801 -0.053543001, + -0.0328326 0.053156201 -0.051922999, + -0.0328326 0.0532015 -0.052235998, + -0.035366699 0.053237099 -0.050471999, + -0.035366699 0.0532391 -0.050783999, + -0.0378174 0.0532846 -0.04888, + -0.0378174 0.053246401 -0.049176998, + -0.040174201 0.0533037 -0.047139999, + -0.040174201 0.0532309 -0.04741, + -0.0424264 0.053301498 -0.045248002, + -0.0424264 0.053206299 -0.045492999, + -0.044564299 0.053291801 -0.043212999, + -0.044564299 0.053077798 -0.043657001, + -0.0465803 0.053192001 -0.041267999, + -0.0465803 0.052416001 -0.043051001, + -0.048467699 0.052638799 -0.040555999, + -0.048467699 0.051911298 -0.042350002, + -0.050219599 0.0522498 -0.039765999, + -0.050219599 0.0515696 -0.041579999, + -0.051830001 0.0520292 -0.038924001, + -0.051830001 0.051394999 -0.040769, + -0.0532961 0.0519787 -0.038061, + -0.0532961 0.051385 -0.039946999, + -0.0546159 0.052093402 -0.037204999, + -0.0546159 0.051532201 -0.039140999, + -0.055787299 0.052363802 -0.036384001, + -0.055787299 0.051824801 -0.038378999, + -0.056809202 0.052776001 -0.035627, + -0.056809202 0.052247498 -0.037684999, + -0.0576833 0.053312499 -0.034954999, + -0.0576833 0.0527809 -0.037082002, + -0.058412101 0.053952299 -0.034391001, + -0.058412101 0.0534034 -0.036584999, + -0.058998398 0.054671898 -0.033948999, + -0.058998398 0.0540905 -0.036210999, + -0.059445001 0.055445202 -0.033643, + -0.059445001 0.054816902 -0.035966001, + -0.059757002 0.056244899 -0.033482, + -0.059757002 0.0555554 -0.035859, + -0.0599402 0.057045698 -0.033466, + -0.0599402 0.056283001 -0.035886999, + -0.059999999 0.0578366 -0.033573002, + -0.059999999 0.056990501 -0.036024999, + -0.0599402 0.0586132 -0.033773001, + -0.0599402 0.057677299 -0.036244001, + -0.059757002 0.059376601 -0.03404, + -0.059757002 0.058346301 -0.036516, + -0.059445001 0.060127601 -0.034348, + -0.059445001 0.0590018 -0.036821, + -0.058998398 0.0608567 -0.034696002, + -0.058998398 0.0596359 -0.037154, + -0.058412101 0.060238998 -0.037498001, + -0.0546159 0.057162698 -0.051746, + -0.0532961 0.056534201 -0.056232002, + -0.051830001 0.055925999 -0.061066002, + -0.050219599 0.055328 -0.06622, + -0.048467699 0.054720599 -0.071663998, + -0.0465803 0.054135598 -0.077363998, + -0.044564299 0.0537211 -0.083357997, + -0.0424264 0.053479899 -0.089633003, + -0.040174201 0.0533996 -0.096156001, + -0.0378174 0.053467698 -0.102895, + -0.035366699 0.053670801 -0.109819, + -0.0328326 0.053992402 -0.116903, + -0.0302257 0.0544165 -0.124121, + -0.027557701 0.054931302 -0.131451, + -0.0248404 0.055525798 -0.138872, + -0.0220857 0.0561869 -0.146366, + -0.019305199 0.056905601 -0.153915, + -0.0174994 0.057391401 -0.16150001, + -0.019300099 0.056793701 -0.16150001, + -0.020292999 0.056464098 -0.16150001, + -0.021165101 0.056143001 -0.1815, + -0.025727101 0.054204401 -0.16150001, + -0.0248341 0.054601699 -0.16150001, + -0.026825599 0.053669199 -0.1815, + -0.022079799 0.055771999 -0.16150001, + -0.023037801 0.055400901 -0.16150001, + -0.0248404 0.0547125 -0.15396699, + -0.058065701 0.055333499 -0.046510998, + -0.0576833 0.053468499 -0.050748002, + -0.058412101 0.054275099 -0.047366999, + -0.058412101 0.057294201 -0.042461, + -0.058722898 0.0562739 -0.043391999, + -0.058998398 0.056790799 -0.041880999, + -0.050219599 0.032937098 -0.154486, + -0.048467699 0.035470098 -0.15442599, + -0.049775898 0.033491299 -0.16150001, + -0.050219599 0.0332831 -0.147442, + -0.051830001 0.0306821 -0.14756501, + -0.051830001 0.031267799 -0.140568, + -0.0532961 0.0286144 -0.140754, + -0.0532961 0.0294526 -0.13382, + -0.0546159 0.026763 -0.13406999, + -0.0546159 0.0278698 -0.127215, + -0.055787299 0.025160599 -0.12753101, + -0.055787299 0.0265441 -0.120775, + -0.056809202 0.0238316 -0.121158, + -0.056809202 0.025497699 -0.114526, + -0.0576833 0.0227974 -0.114978, + -0.0576833 0.024750199 -0.108495, + -0.058412101 0.022076899 -0.109017, + -0.058412101 0.024318 -0.102711, + -0.058998398 0.0216858 -0.103304, + -0.058998398 0.0242109 -0.097204, + -0.059445001 0.0216332 -0.097870998, + -0.059445001 0.0244343 -0.092007004, + -0.059757002 0.0219242 -0.092749, + -0.059757002 0.0249894 -0.08715, + -0.0599402 0.0225539 -0.087967999, + -0.0599402 0.0258574 -0.082645997, + -0.059999999 0.023483099 -0.083549999, + -0.059999999 0.026904199 -0.078484997, + -0.0599402 0.024576901 -0.079489, + -0.0599402 0.028073 -0.074704997, + -0.059757002 0.0257804 -0.075828001, + -0.059757002 0.029339099 -0.071346998, + -0.059445001 0.027073501 -0.072605997, + -0.059445001 0.030676899 -0.068448, + 0.0576833 0.033314802 -0.064246997, + 0.056809202 0.0331944 -0.064469002, + 0.0576833 0.0314335 -0.065846004, + 0.058065701 0.032492202 -0.064989999, + 0.058412101 0.031741899 -0.065838002, + 0.058722898 0.030996 -0.066820003, + 0.058412101 0.0299058 -0.067598999, + 0.058998398 0.030268 -0.067929, + 0.0576833 0.0295917 -0.067473002, + 0.056809202 0.029319599 -0.067556001, + 0.055787299 0.031164899 -0.066321999, + 0.055787299 0.033143599 -0.064778998, + 0.0546159 0.0311704 -0.066688001, + 0.0546159 0.033165898 -0.065187998, + 0.0532961 0.031258099 -0.067140996, + 0.0532961 0.033224698 -0.065691002, + 0.051830001 0.031394102 -0.067670003, + 0.051830001 0.033338301 -0.066197999, + 0.050219599 0.031595901 -0.068194002, + 0.050219599 0.033521101 -0.066706002, + 0.048467699 0.031877201 -0.068708003, + 0.048467699 0.033785202 -0.067208, + 0.0465803 0.0322484 -0.069202997, + 0.0465803 0.034141 -0.067694999, + 0.044564299 0.0327188 -0.069669001, + 0.044564299 0.0345985 -0.068153001, + 0.0424264 0.0332973 -0.070092, + 0.0424264 0.035166699 -0.068567999, + 0.040174201 0.033991098 -0.070456997, + 0.040174201 0.035853598 -0.068925999, + 0.0378174 0.034805499 -0.070749998, + 0.0378174 0.036664099 -0.069210999, + 0.035366699 0.0357433 -0.070956998, + 0.035366699 0.037600301 -0.069406003, + 0.0328326 0.036805 -0.071059003, + 0.0328326 0.038661402 -0.069493003, + 0.0302257 0.037988 -0.071041003, + 0.0302257 0.0398436 -0.069456004, + 0.027557701 0.0392855 -0.070886999, + 0.027557701 0.0411385 -0.069277003, + 0.0248404 0.040687501 -0.070583001, + 0.0248404 0.042535 -0.068944, + 0.0220857 0.0421817 -0.070115998, + 0.0220857 0.044019099 -0.068443, + 0.019305199 0.043753002 -0.069473997, + 0.019305199 0.045575298 -0.067763001, + 0.0165099 0.045384299 -0.06865, + 0.0165099 0.047185302 -0.0669, + 0.0137106 0.0470571 -0.067642003, + 0.0137106 0.048830099 -0.065851003, + 0.0109179 0.048751902 -0.066448003, + 0.0109179 0.050489999 -0.064614996, + 0.0081428103 0.050449401 -0.065068997, + 0.0081428103 0.052144099 -0.063193001, + 0.0053973799 0.052129 -0.063510001, + 0.0053973799 0.052544199 -0.063033998, + 0.00268824 0.052537601 -0.063220002, + 0.00268824 0.052861501 -0.062674001, + 0 0.052860402 -0.062734, + 0 0.052955799 -0.062419001, + -0.00268824 0.0528627 -0.062674001, + -0.00268824 0.052538201 -0.063220002, + -0.0053973799 0.052545398 -0.063034996, + -0.0053973799 0.052129 -0.063510001, + -0.0081428103 0.052144099 -0.063193001, + -0.0081428103 0.050449502 -0.065067001, + -0.0109179 0.0504901 -0.064613, + -0.0109179 0.048753101 -0.066445999, + -0.0137106 0.0488315 -0.065848, + -0.0137106 0.047058899 -0.067639001, + -0.0165099 0.0471875 -0.066895999, + -0.0165099 0.045387 -0.068645999, + -0.019305199 0.045578402 -0.067758001, + -0.019305199 0.043756802 -0.069467999, + -0.0220857 0.044023398 -0.068437003, + -0.0220857 0.0421868 -0.070110001, + -0.0248404 0.042540699 -0.068937004, + -0.0248404 0.040694099 -0.070577003, + -0.027557701 0.041145898 -0.069270998, + -0.027557701 0.039293699 -0.070881002, + -0.0302257 0.039852601 -0.069449, + -0.0302257 0.037997901 -0.071034998, + -0.0328326 0.038672201 -0.069486998, + -0.0328326 0.036816601 -0.071053997, + -0.035366699 0.0376128 -0.069399998, + -0.035366699 0.035756499 -0.070952997, + -0.0378174 0.036678299 -0.069205999, + -0.0378174 0.0348203 -0.070747003, + -0.040174201 0.035869401 -0.068922997, + -0.040174201 0.0340073 -0.070455, + -0.0424264 0.035183702 -0.068567, + -0.0424264 0.033314601 -0.070092, + -0.044564299 0.034616601 -0.068153001, + -0.044564299 0.032737002 -0.069670998, + -0.0465803 0.034159999 -0.067697003, + -0.0465803 0.032267001 -0.069206998, + -0.048467699 0.033804599 -0.067212999, + -0.048467699 0.0318949 -0.068713002, + -0.050219599 0.0335395 -0.066711001, + -0.050219599 0.031610601 -0.0682, + -0.051830001 0.033353399 -0.066202998, + -0.051830001 0.031403501 -0.067676999, + -0.0532961 0.033234298 -0.065697998, + -0.0532961 0.031263199 -0.067144997, + -0.0546159 0.033171199 -0.065192997, + -0.0546159 0.0311768 -0.066675, + -0.055787299 0.033150099 -0.064764999, + -0.055787299 0.031166499 -0.066321999, + -0.056809202 0.033195999 -0.064467996, + -0.056809202 0.031237699 -0.066036001, + -0.0576833 0.033315901 -0.064249001, + -0.0576833 0.031422101 -0.065848999, + -0.058065701 0.032480702 -0.064993002, + -0.058412101 0.031726699 -0.065838002, + -0.058722898 0.0309899 -0.066814996, + -0.058998398 0.0302692 -0.067919001, + -0.058412101 0.0298998 -0.067593999, + -0.0576833 0.0295767 -0.067473002, + -0.056809202 0.029308399 -0.067558996, + -0.055787299 0.029170601 -0.067814, + -0.0546159 0.0291558 -0.068158001, + -0.0532961 0.0292303 -0.068558998, + -0.051830001 0.029389899 -0.069061004, + -0.050219599 0.029614501 -0.069610998, + -0.048467699 0.0299164 -0.070139997, + -0.0465803 0.0303044 -0.070648, + -0.044564299 0.030788301 -0.071125001, + -0.0424264 0.031377099 -0.071557, + -0.040174201 0.032078698 -0.071932003, + -0.0378174 0.032897901 -0.072236001, + -0.035366699 0.033838101 -0.072454996, + -0.0328326 0.0349009 -0.072572999, + -0.0302257 0.0360847 -0.072575003, + -0.027557701 0.0373841 -0.072444998, + -0.0248404 0.038790502 -0.072169997, + -0.0220857 0.040293101 -0.071736999, + -0.019305199 0.041878 -0.071133003, + -0.0165099 0.043528698 -0.070350997, + -0.0137106 0.045227401 -0.069385998, + -0.0109179 0.046955399 -0.068236001, + -0.0081428103 0.048693299 -0.066900998, + -0.0053973799 0.0504211 -0.065384999, + -0.00268824 0.052120101 -0.063694999, + 0 0.052535601 -0.063281, + 0.00268824 0.052120101 -0.063694999, + 0.0053973799 0.050421 -0.065385997, + 0.0081428103 0.048692401 -0.066903003, + 0.0109179 0.046953902 -0.068239003, + 0.0137106 0.045225199 -0.069389999, + 0.0165099 0.043525498 -0.070354998, + 0.019305199 0.0418735 -0.071138002, + 0.0220857 0.0402872 -0.071741998, + 0.0248404 0.0387831 -0.072175004, + 0.027557701 0.037374999 -0.072449997, + 0.0302257 0.036074001 -0.072580002, + 0.0328326 0.034888599 -0.072577, + 0.035366699 0.033824299 -0.072457999, + 0.0378174 0.032882702 -0.072237998, + 0.040174201 0.0320623 -0.071932003, + 0.0424264 0.031359699 -0.071555004, + 0.044564299 0.030770499 -0.071121, + 0.0465803 0.0302874 -0.070643999, + 0.048467699 0.029902199 -0.070134997, + 0.050219599 0.0296054 -0.069604002, + 0.051830001 0.0293849 -0.069057003, + 0.0532961 0.0292241 -0.068572, + 0.0546159 0.029154301 -0.068158001, + 0.055787299 0.0272169 -0.069256, + 0.056809202 0.027444599 -0.069104999, + 0.0576833 0.0277225 -0.069159999, + 0.058412101 0.0280574 -0.069413997, + 0.058998398 0.0284441 -0.069865003, + 0.059445001 0.0306725 -0.068460003, + 0.059445001 0.028873499 -0.070514001, + 0.059757002 0.0293351 -0.071358003, + 0.037815198 0.046577401 -0.16150001, + 0.0372269 0.0470348 -0.16150001, + 0.0378174 0.046692401 -0.154157, + 0.058998398 0.049113199 -0.053870998, + 0.058412101 0.051291201 -0.052313998, + 0.058998398 0.052174799 -0.049072001, + 0.058412101 0.045103502 -0.062593997, + 0.0576833 0.0504691 -0.055975001, + 0.035366699 0.048891399 -0.14670999, + 0.0328326 0.050638899 -0.14662801, + 0.035366699 0.049419701 -0.139302, + 0.0378174 0.047543202 -0.13943399, + 0.0378174 0.048296601 -0.132072, + 0.040174201 0.0463017 -0.132258, + 0.040174201 0.047285002 -0.124958, + 0.0424264 0.045182999 -0.125203, + 0.0424264 0.046403602 -0.117982, + 0.044564299 0.044206999 -0.118292, + 0.044564299 0.045673002 -0.111166, + 0.0465803 0.043396801 -0.111547, + 0.0465803 0.0451134 -0.104536, + 0.048467699 0.042773601 -0.104993, + 0.048467699 0.044744201 -0.098121002, + 0.050219599 0.0423561 -0.098659702, + 0.050219599 0.044581 -0.091949999, + 0.051830001 0.042159799 -0.092577003, + 0.051830001 0.044636302 -0.086055003, + 0.0532961 0.042197201 -0.086776003, + 0.0532961 0.044918001 -0.080467999, + 0.0546159 0.042475201 -0.081288002, + 0.0546159 0.045423701 -0.075204998, + 0.055787299 0.042990699 -0.076131001, + 0.055787299 0.046023801 -0.070239998, + 0.056809202 0.043616701 -0.071278997, + 0.056809202 0.046682999 -0.065599002, + 0.0576833 0.044317398 -0.066757999, + 0.0576833 0.047413599 -0.061310001, + 0.056809202 0.049720399 -0.060027, + 0.055787299 0.049035899 -0.064447001, + 0.0546159 0.048408698 -0.069210999, + 0.0532961 0.047823701 -0.074291997, + 0.051830001 0.047316398 -0.079662003, + 0.050219599 0.0470195 -0.085350998, + 0.048467699 0.046934601 -0.091340996, + 0.0465803 0.047053698 -0.097599998, + 0.044564299 0.047363602 -0.104097, + 0.0424264 0.047848199 -0.110802, + 0.040174201 0.048488699 -0.117687, + 0.0378174 0.049267098 -0.124727, + 0.035366699 0.0501641 -0.131898, + 0.0328326 0.051161598 -0.13918, + 0.0302257 0.052245099 -0.14655299, + 0.0248404 0.054721199 -0.15396599, + 0.027557701 0.0534027 -0.153997, + 0.0255554 0.054285601 -0.16150001, + 0.0275521 0.053284999 -0.16150001, + 0.026817599 0.053653099 -0.16150001, + 0.026825599 0.053669199 -0.1815, + 0.030220101 0.051820099 -0.16150001, + 0.028186901 0.0529669 -0.16150001, + 0.0302257 0.0519379 -0.15403201, + 0.0328326 0.050328799 -0.15407, + 0.032192402 0.0506116 -0.16150001, + 0.035366699 0.0485783 -0.154112, + 0.0332404 0.0499507 -0.16150001, + 0.0378174 0.047008701 -0.146799, + 0.040174201 0.045538601 -0.13957401, + 0.0424264 0.044186201 -0.13245501, + 0.044564299 0.0429685 -0.125462, + 0.0465803 0.041908398 -0.118617, + 0.048467699 0.0410299 -0.111942, + 0.050219599 0.040353999 -0.105465, + 0.051830001 0.039899401 -0.099214002, + 0.0532961 0.0396818 -0.093217999, + 0.0546159 0.039712999 -0.087509997, + 0.055787299 0.0399988 -0.082120001, + 0.056809202 0.040534802 -0.077064998, + 0.0576833 0.041196801 -0.072323002, + 0.058412101 0.041948501 -0.067918003, + 0.058998398 0.042798799 -0.063874997, + 0.059445001 0.046948999 -0.055418, + 0.059445001 0.053228602 -0.046172, + 0.059757002 0.051224701 -0.048002001, + 0.059985202 0.052643798 -0.044078998, + 0.059999999 0.0535414 -0.043049999, + 0.0599402 0.053078201 -0.042897001, + 0.059999999 0.052133501 -0.045246001, + 0.0599402 0.0539781 -0.043251, + 0.0599402 0.052494202 -0.045412, + 0.059757002 0.054396398 -0.043466002, + 0.059445001 0.0547961 -0.043820001, + 0.058998398 0.055254102 -0.044323001, + 0.058412101 0.0542867 -0.047364, + 0.0576833 0.0534744 -0.050754, + 0.056809202 0.0527138 -0.054559998, + 0.055787299 0.052014899 -0.058752, + 0.0546159 0.0513671 -0.063304998, + 0.0532961 0.0507611 -0.068195999, + 0.051830001 0.0501802 -0.073394999, + 0.050219599 0.0496599 -0.078874998, + 0.048467699 0.049336199 -0.084665999, + 0.0465803 0.049210701 -0.090751998, + 0.044564299 0.0492745 -0.097098999, + 0.0424264 0.049513899 -0.103677, + 0.040174201 0.0499129 -0.110456, + 0.0378174 0.0504549 -0.117409, + 0.035366699 0.051122699 -0.12451, + 0.0328326 0.0518975 -0.13173699, + 0.0302257 0.052762698 -0.13906799, + 0.027557701 0.053707398 -0.146484, + 0.0228623 0.0554736 -0.16150001, + 0.0248404 0.055023801 -0.146422, + 0.027557701 0.0542202 -0.13896599, + 0.0302257 0.0534909 -0.131588, + 0.0328326 0.052845102 -0.124309, + 0.035366699 0.052295599 -0.117149, + 0.0378174 0.0518599 -0.110131, + 0.040174201 0.051555 -0.103278, + 0.0424264 0.051396899 -0.096620001, + 0.044564299 0.051399499 -0.090185001, + 0.0465803 0.051576599 -0.084004, + 0.048467699 0.051938001 -0.078110002, + 0.050219599 0.052482799 -0.072518997, + 0.051830001 0.053070799 -0.067198999, + 0.0532961 0.053666599 -0.062178999, + 0.0546159 0.054288201 -0.057487998, + 0.055787299 0.054946601 -0.053151999, + 0.056809202 0.055654399 -0.049196001, + 0.0576833 0.056403499 -0.045651998, + 0.058412101 0.057292499 -0.042461, + 0.058998398 0.0567839 -0.041896001, + 0.059445001 0.056324098 -0.041492999, + 0.059757002 0.055837099 -0.041241001, + 0.0599402 0.055338301 -0.040991999, + 0.059999999 0.054822501 -0.040773001, + 0.059864402 0.0528345 -0.042847, + 0.0599402 0.053696599 -0.041763999, + 0.059757002 0.052581601 -0.042819001, + 0.0599402 0.054280899 -0.040615, + 0.059617501 0.052319702 -0.042817, + 0.059757002 0.053162102 -0.041687001, + 0.059445001 0.052050799 -0.042842001, + 0.059757002 0.053707998 -0.040541999, + 0.059445001 0.052595999 -0.041717, + 0.058998398 0.050955899 -0.044073001, + 0.058998398 0.051502801 -0.042970002, + 0.058412101 0.049889099 -0.045373999, + 0.058412101 0.0504403 -0.044293001, + 0.0576833 0.049419299 -0.045676999, + 0.055787299 0.048094202 -0.047571, + 0.056809202 0.048988301 -0.046071, + 0.055787299 0.048617501 -0.046549998, + 0.0546159 0.047273099 -0.049098, + 0.0546159 0.047814101 -0.048101, + 0.0532961 0.046533398 -0.050641, + 0.0532961 0.047094401 -0.049667001, + 0.051830001 0.045882799 -0.052184999, + 0.051830001 0.046465401 -0.051231999, + 0.050219599 0.045327701 -0.053716, + 0.050219599 0.045933601 -0.052781999, + 0.048467699 0.044873498 -0.055218, + 0.048467699 0.045503799 -0.054301001, + 0.0465803 0.045179501 -0.055774, + -0.0576833 0.041197199 -0.072316997, + -0.0576833 0.0380654 -0.078001, + -0.058412101 0.038773701 -0.073362999, + -0.058412101 0.045107398 -0.062582999, + -0.058998398 0.039586999 -0.069067001, + -0.058998398 0.042802799 -0.063863002, + -0.058998398 0.045982901 -0.058796, + -0.059445001 0.0405128 -0.065136001, + -0.059985202 0.048008502 -0.050381999, + -0.059985202 0.049669702 -0.048312001, + -0.059999999 0.047286902 -0.051600002, + -0.059966501 0.0491977 -0.048795, + -0.0599402 0.049525701 -0.048278, + -0.048467699 0.044238299 -0.056122001, + -0.048467699 0.043565501 -0.057030998, + -0.0465803 0.043863699 -0.057564002, + -0.050219599 0.044716801 -0.054637998, + -0.050219599 0.044065699 -0.055565, + -0.051830001 0.045294899 -0.053128, + -0.051830001 0.044664301 -0.054074001, + -0.0532961 0.045966901 -0.051605999, + -0.0532961 0.0453551 -0.052572999, + -0.0546159 0.046131101 -0.051075, + -0.058412101 0.0480676 -0.048556, + -0.058412101 0.047390699 -0.049589001, + -0.0576833 0.047024202 -0.049851999, + -0.058998398 0.049142499 -0.047316998, + -0.058998398 0.0484665 -0.048367999, + -0.059238799 0.049354099 -0.047253001, + -0.059238799 0.048662402 -0.048303999, + -0.059445001 0.049560901 -0.047210999, + -0.059445001 0.048853099 -0.048261002, + -0.059617501 0.049036399 -0.048238002, + -0.050219599 0.039672799 -0.060968999, + -0.050219599 0.0388605 -0.061834, + -0.048467699 0.0390682 -0.062330998, + -0.051830001 0.040367398 -0.059590001, + -0.051830001 0.039567102 -0.060470998, + -0.0532961 0.0411443 -0.058205999, + -0.0532961 0.040354501 -0.059103999, + -0.059238799 0.0421458 -0.056056999, + -0.059445001 0.041343499 -0.057027999, + -0.058998398 0.041149799 -0.057020999, + -0.058998398 0.042946801 -0.055190999, + -0.058412101 0.040985901 -0.057197001, + -0.058412101 0.0427364 -0.055424999, + -0.0576833 0.040815402 -0.057502002, + -0.0576833 0.042522501 -0.0557, + -0.056809202 0.040653899 -0.057840999, + -0.056809202 0.0423178 -0.056026999, + -0.055787299 0.040513501 -0.058223002, + -0.055787299 0.042136699 -0.056405, + -0.0546159 0.0404086 -0.058646999, + -0.0546159 0.041995 -0.056829002, + -0.0532961 0.041909501 -0.057293002, + -0.051830001 0.041143999 -0.058696002, + -0.050219599 0.040462501 -0.060091998, + -0.048467699 0.0398724 -0.061471, + -0.0465803 0.039379802 -0.062817998, + 0.059691299 0.0471626 -0.050747, + 0.059757002 0.0476368 -0.050248001, + 0.059617501 0.0474911 -0.050264999, + 0.059757002 0.046817102 -0.051220998, + 0.059814699 0.047294799 -0.050732002, + 0.059814699 0.046452999 -0.051706001, + 0.059864402 0.0460703 -0.052266002, + 0.0599062 0.046554599 -0.051796999, + 0.0599402 0.047037799 -0.05133, + 0.0599062 0.048245698 -0.049759001, + 0.059864402 0.047770899 -0.050244998, + 0.059814699 0.0481092 -0.049750999, + 0.059864402 0.048580099 -0.049256001, + 0.059757002 0.04843 -0.049249999, + 0.0599062 0.049049601 -0.048762999, + 0.0599402 0.048719302 -0.049274001, + 0.059985202 0.046305101 -0.052494999, + 0.059985202 0.0429033 -0.056570001, + 0.059999999 0.043918699 -0.055748999, + 0.0599402 0.045322999 -0.053392, + 0.059617501 0.048268799 -0.049259, + 0.059445001 0.047335699 -0.050297, + 0.059445001 0.0480984 -0.049286, + 0.059238799 0.0471729 -0.050345998, + 0.059238799 0.047920998 -0.049332, + 0.058998398 0.047004901 -0.050413001, + 0.058998398 0.047738701 -0.049396999, + 0.058412101 0.045926802 -0.051603001, + 0.058412101 0.046661299 -0.050602, + 0.0576833 0.045611601 -0.051863, + 0.059445001 0.050214998 -0.046137001, + 0.059617501 0.050432701 -0.046117, + 0.059445001 0.0508596 -0.045053001, + 0.059238799 0.049991101 -0.046179999, + 0.059238799 0.0506193 -0.045097999, + 0.058998398 0.0497633 -0.046246, + 0.058412101 0.0486902 -0.047504999, + 0.0576833 0.047000598 -0.049849, + 0.058412101 0.048043899 -0.048551999, + 0.058998398 0.049118999 -0.047311999, + 0.059238799 0.0493313 -0.047247998, + 0.059445001 0.049539201 -0.047205001, + 0.059757002 0.051320501 -0.045035999, + 0.059757002 0.049933501 -0.047184002, + 0.059864402 0.0508416 -0.046142999, + 0.059864402 0.050116301 -0.047203999, + 0.0599402 0.050288901 -0.04724, + 0.0599402 0.0495179 -0.048269998, + 0.059985202 0.049663901 -0.048308, + 0.059864402 0.049362101 -0.048241999, + 0.059757002 0.0491958 -0.048227999, + 0.059617501 0.049018901 -0.048230998, + 0.059445001 0.048833199 -0.048255, + 0.059238799 0.048640799 -0.048299, + 0.058998398 0.048443802 -0.048363, + 0.058412101 0.047367401 -0.049584001, + -0.048467699 0.042870801 -0.057934001, + -0.048467699 0.0421541 -0.058830999, + -0.0465803 0.042452101 -0.059344999, + -0.050219599 0.043391399 -0.056485999, + -0.050219599 0.042693999 -0.057401001, + -0.051830001 0.044009201 -0.055015001, + -0.051830001 0.0433295 -0.055948, + -0.0532961 0.044717502 -0.053534001, + -0.0532961 0.044053901 -0.054488, + -0.0546159 0.044859499 -0.053033002, + -0.048467699 0.041415401 -0.059719998, + -0.048467699 0.040654901 -0.060600001, + -0.0465803 0.040957399 -0.061097998, + -0.050219599 0.0419733 -0.058307, + -0.050219599 0.041229401 -0.059204999, + -0.051830001 0.042625301 -0.056874, + -0.051830001 0.041896701 -0.05779, + -0.0532961 0.043364599 -0.055433001, + -0.0532961 0.042649701 -0.056368999, + -0.0546159 0.043480098 -0.054954, + -0.059864402 0.0469396 -0.051224001, + -0.059864402 0.047776699 -0.050248999, + -0.0599062 0.046561599 -0.051782001, + -0.059814699 0.0473006 -0.050735999, + -0.059814699 0.048117001 -0.049759001, + -0.059757002 0.0476446 -0.050255999, + -0.059757002 0.048440799 -0.049258001, + -0.059617501 0.047501899 -0.050273001, + -0.059617501 0.048283 -0.049267001, + -0.058412101 0.046683799 -0.050607, + -0.058412101 0.045948099 -0.051608, + -0.0576833 0.045634601 -0.051867001, + -0.058998398 0.0477602 -0.049401999, + -0.058998398 0.0470246 -0.050418999, + -0.059238799 0.047940802 -0.049338002, + -0.059238799 0.047190201 -0.050353002, + -0.059445001 0.048115801 -0.049293, + -0.059445001 0.0473499 -0.050305001, + -0.059445001 0.044895198 -0.053197, + -0.059535399 0.044517402 -0.053636, + -0.059445001 0.0440281 -0.054124001, + -0.059535399 0.0453794 -0.052701999, + -0.059445001 0.045738202 -0.05226, + -0.059617501 0.045862202 -0.052207999, + -0.059617501 0.045005102 -0.053151, + -0.059691299 0.045491301 -0.052666001, + -0.059691299 0.044615 -0.053667001, + -0.059757002 0.045104198 -0.053192999, + -0.059757002 0.0433474 -0.055197999, + -0.059617501 0.0441241 -0.054141998, + -0.059238799 0.044776801 -0.053270999, + -0.059238799 0.045606799 -0.052322, + -0.059445001 0.046556901 -0.051295001, + -0.059238799 0.046411801 -0.051348999, + -0.058998398 0.045469601 -0.052397002, + -0.058998398 0.0462607 -0.051417999, + -0.058412101 0.0451844 -0.052592002, + -0.058412101 0.044393901 -0.053557001, + -0.0576833 0.044131599 -0.053819001, + -0.058998398 0.0446527 -0.053353999, + -0.058998398 0.043811299 -0.054285999, + -0.059238799 0.043923099 -0.054191999, + -0.059238799 0.0430458 -0.055101998, + -0.059445001 0.043137599 -0.055096999, + -0.059535399 0.043631598 -0.054618999, + -0.059617501 0.042348702 -0.056109998, + -0.059757002 0.041577399 -0.057144001, + -0.059864402 0.042587299 -0.056276001, + -0.059864402 0.040852599 -0.058222, + -0.0599402 0.041873999 -0.057395998, + -0.0599402 0.0401925 -0.0594, + -0.059864402 0.044338901 -0.054292001, + -0.059814699 0.0455916 -0.052721001, + -0.059757002 0.045975801 -0.052184001, + -0.059691299 0.046343401 -0.051716, + -0.059617501 0.046694499 -0.051254999, + -0.056809202 0.043880999 -0.054141998, + -0.056809202 0.045336701 -0.052193001, + -0.055787299 0.0436581 -0.054522, + -0.055787299 0.045072298 -0.052583002, + -0.044564299 0.041381299 -0.06157, + -0.044564299 0.042877302 -0.059829999, + -0.0424264 0.041934598 -0.061995, + -0.0424264 0.0434369 -0.060265001, + -0.040174201 0.042622101 -0.062353, + -0.040174201 0.0441342 -0.060626999, + -0.0378174 0.043444298 -0.062623002, + -0.0378174 0.0449678 -0.060896002, + -0.035366699 0.044397801 -0.062784001, + -0.035366699 0.045932699 -0.061048999, + -0.0328326 0.0454758 -0.062817, + -0.0328326 0.0470207 -0.061067, + -0.0302257 0.046668299 -0.062702, + -0.0302257 0.048220102 -0.060931999, + -0.027557701 0.0479615 -0.062426001, + -0.027557701 0.049515501 -0.060631, + -0.0248404 0.049339101 -0.061976001, + -0.0248404 0.050888602 -0.060151, + -0.0220857 0.050782099 -0.061342999, + -0.0220857 0.0523213 -0.059485, + -0.019305199 0.052271798 -0.060520999, + -0.019305199 0.052658699 -0.060052, + -0.0165099 0.052625202 -0.060936, + -0.0165099 0.052929401 -0.060392998, + -0.0137106 0.052908201 -0.061129998, + -0.0137106 0.052997001 -0.060817, + -0.0109179 0.052982401 -0.061407998, + -0.0109179 0.053020898 -0.061080001, + -0.0081428103 0.053011298 -0.061530001, + -0.0081428103 0.0529969 -0.061202001, + -0.0053973799 0.052990999 -0.061517, + -0.0053973799 0.0529259 -0.061198998, + -0.00268824 0.0529227 -0.061384, + -0.00268824 0.052810598 -0.061083999, + 0 0.052809201 -0.061145, + 0 0.052652098 -0.060869001, + 0.00268824 0.052809201 -0.061085999, + 0.00268824 0.052921198 -0.061384998, + 0.0053973799 0.052922901 -0.061200999, + 0.0053973799 0.052988101 -0.061517999, + 0.0081428103 0.0529925 -0.061205, + 0.0081428103 0.0530072 -0.061531998, + 0.0109179 0.0530154 -0.061082002, + 0.0109179 0.052976999 -0.061409999, + 0.0137106 0.052990202 -0.060818002, + 0.0137106 0.052901901 -0.061129998, + 0.0165099 0.052921802 -0.060394, + 0.0165099 0.052621499 -0.060934, + 0.019305199 0.0526543 -0.060049001, + 0.019305199 0.052271798 -0.060522001, + 0.0220857 0.0523213 -0.059486002, + 0.0220857 0.050781898 -0.061347999, + 0.0248404 0.050888401 -0.060155999, + 0.0248404 0.049336601 -0.061981998, + 0.027557701 0.049512699 -0.060637001, + 0.027557701 0.0479578 -0.062433001, + 0.0302257 0.048216 -0.060940001, + 0.0302257 0.0466634 -0.062711, + 0.0328326 0.047015399 -0.061076, + 0.0328326 0.0454694 -0.062826, + 0.035366699 0.0459258 -0.061058, + 0.035366699 0.044389602 -0.062793002, + 0.0378174 0.044959102 -0.060904998, + 0.0378174 0.043434199 -0.062632002, + 0.040174201 0.044123501 -0.060637001, + 0.040174201 0.042610101 -0.062360998, + 0.0424264 0.043424301 -0.060274001, + 0.0424264 0.041920699 -0.062003002, + 0.044564299 0.042862698 -0.059838001, + 0.044564299 0.041365601 -0.061577, + 0.0465803 0.042435601 -0.059351999, + 0.0465803 0.040940002 -0.061104, + 0.048467699 0.042135902 -0.058837, + 0.056809202 0.045999199 -0.051196001, + 0.056809202 0.046656199 -0.050190002, + 0.055787299 0.0450496 -0.052583002, + 0.055787299 0.045715202 -0.051598001, + 0.0546159 0.0441611 -0.054000001, + 0.0546159 0.044837601 -0.053034998, + 0.0532961 0.043343201 -0.055435002, + 0.0532961 0.044032801 -0.054490998, + 0.051830001 0.0426047 -0.056876998, + 0.051830001 0.043309201 -0.055953, + 0.050219599 0.041953601 -0.058311, + 0.050219599 0.042674702 -0.057406001, + 0.048467699 0.0413968 -0.059725001, + 0.048467699 0.040635899 -0.060603999, + 0.050219599 0.0412094 -0.059207998, + 0.051830001 0.041875899 -0.057792, + 0.0532961 0.042628098 -0.056370001, + 0.0546159 0.043457899 -0.054954, + 0.055787299 0.0443561 -0.053557001, + 0.056809202 0.045313399 -0.052189998, + 0.059999999 0.047285199 -0.051600002, + 0.0599402 0.042695101 -0.058458, + 0.059238799 0.043040302 -0.055105001, + 0.058998398 0.042941101 -0.055186, + 0.059238799 0.042138901 -0.056072, + 0.059445001 0.0431307 -0.055112001, + 0.059535399 0.040047899 -0.058456998, + 0.059617501 0.040559102 -0.058017001, + 0.059445001 0.0413418 -0.057027999, + 0.059617501 0.038802501 -0.059886999, + 0.059691299 0.0393207 -0.059466999, + 0.059757002 0.038127199 -0.060982, + 0.059864402 0.040864501 -0.058219001, + 0.059757002 0.0398372 -0.059050001, + 0.0599402 0.040208101 -0.059399001, + 0.059757002 0.0415763 -0.057142001, + 0.059691299 0.041068599 -0.057579, + 0.059617501 0.042346999 -0.056109998, + 0.059535399 0.043624599 -0.054634001, + 0.059535399 0.045373701 -0.052696999, + 0.059617501 0.045856401 -0.052203, + 0.059445001 0.045730501 -0.052253, + 0.059691299 0.044608101 -0.053681999, + 0.059757002 0.045097198 -0.053208001, + 0.059691299 0.045485798 -0.052669, + 0.059617501 0.044999599 -0.053153001, + 0.059445001 0.044889499 -0.053192999, + 0.059238799 0.044769101 -0.053263001, + 0.059238799 0.0455961 -0.052313998, + 0.058998398 0.044642001 -0.053344999, + 0.058998398 0.045455601 -0.052389, + 0.058412101 0.044376802 -0.053550001, + 0.058412101 0.045164902 -0.052586, + 0.0576833 0.0441106 -0.053814001, + 0.058998398 0.0462435 -0.051410999, + 0.059238799 0.046397701 -0.051341001, + 0.059445001 0.046546198 -0.051286999, + 0.059617501 0.046686701 -0.051247001, + 0.059691299 0.046337601 -0.051711001, + 0.059757002 0.045970298 -0.052186999, + 0.059814699 0.0455846 -0.052735999, + 0.059864402 0.044337198 -0.054292001, + 0.059864402 0.0425862 -0.056274001, + 0.0599402 0.041885901 -0.057393, + 0.059757002 0.0433456 -0.055197999, + 0.059617501 0.044117101 -0.054157, + 0.059999999 0.040598601 -0.059957001, + 0.059999999 0.037211299 -0.064336002, + 0.0599402 0.036007501 -0.067648999, + 0.0599402 0.038502 -0.061455, + 0.058998398 0.0411429 -0.057036001, + 0.058412101 0.040980302 -0.057193, + 0.059238799 0.0403312 -0.057951, + 0.058998398 0.0393163 -0.058878001, + 0.059238799 0.038505901 -0.059783, + 0.059445001 0.039535198 -0.058897998, + 0.059445001 0.0386291 -0.059818, + 0.059535399 0.038282499 -0.060307, + 0.059617501 0.037076298 -0.061781, + 0.059445001 0.036018498 -0.062585004, + 0.059757002 0.036389198 -0.062965997, + 0.058722898 0.036435202 -0.061563998, + 0.058998398 0.0374722 -0.060672, + 0.058412101 0.0372779 -0.060738999, + 0.058998398 0.0365474 -0.061554, + 0.059238799 0.0375905 -0.060683999, + 0.059238799 0.036713999 -0.061576001, + 0.059445001 0.037760999 -0.060729001, + 0.058412101 0.039142501 -0.058972001, + 0.0576833 0.0371374 -0.060913, + 0.0576833 0.039014801 -0.059204001, + 0.056809202 0.037052199 -0.061212, + 0.056809202 0.038887002 -0.059567999, + 0.055787299 0.036979198 -0.061631002, + 0.055787299 0.038778901 -0.059964001, + 0.0546159 0.036937699 -0.062073, + 0.0546159 0.038706001 -0.060392998, + 0.0532961 0.036943201 -0.062540002, + 0.0532961 0.038682599 -0.060853001, + 0.051830001 0.037009399 -0.063024998, + 0.051830001 0.0378768 -0.062187999, + 0.050219599 0.037149299 -0.063519999, + 0.050219599 0.038005501 -0.062684, + 0.048467699 0.037375901 -0.064015001, + 0.051830001 0.0387225 -0.061336, + 0.0532961 0.039519198 -0.059985001, + 0.0546159 0.0403868 -0.058642, + 0.055787299 0.040493101 -0.058217999, + 0.056809202 0.040637299 -0.057833999, + 0.0576833 0.040805001 -0.057494, + 0.0599402 0.035052601 -0.065697998, + 0.059999999 0.033789098 -0.068882003, + 0.0599402 0.032620899 -0.072485998, + 0.059757002 0.034913499 -0.071363002, + 0.059757002 0.031576399 -0.076474003, + 0.059445001 0.033953201 -0.075448997, + 0.059445001 0.0306757 -0.080816999, + 0.058998398 0.033126801 -0.079884, + 0.058998398 0.0299592 -0.085491002, + 0.058412101 0.032469802 -0.084647998, + 0.058412101 0.029537801 -0.090516001, + 0.0576833 0.032097101 -0.089759998, + 0.0576833 0.0294207 -0.095873997, + 0.056809202 0.032016899 -0.095201999, + 0.056809202 0.029607899 -0.101535, + 0.055787299 0.032228298 -0.100944, + 0.055787299 0.030092601 -0.107468, + 0.0546159 0.032722902 -0.106955, + 0.0546159 0.030863 -0.113643, + 0.0532961 0.033487499 -0.113204, + 0.0532961 0.0319013 -0.12003, + 0.051830001 0.034503698 -0.119663, + 0.051830001 0.033186499 -0.12660301, + 0.050219599 0.035749801 -0.126304, + 0.050219599 0.034692399 -0.133338, + 0.048467699 0.037200201 -0.13310499, + 0.0465803 0.039625399 -0.132879, + 0.048467699 0.038241599 -0.126013, + 0.050219599 0.037046399 -0.119303, + 0.051830001 0.036064401 -0.112773, + 0.0532961 0.035317399 -0.106449, + 0.0546159 0.034824301 -0.100359, + 0.055787299 0.034599502 -0.094534002, + 0.056809202 0.034652699 -0.089005001, + 0.0576833 0.034986399 -0.083802998, + 0.058412101 0.035593402 -0.078946002, + 0.058998398 0.0363556 -0.074412003, + 0.059445001 0.037236799 -0.070225, + 0.059757002 0.038243201 -0.066407003, + 0.056809202 0.043858401 -0.054136999, + 0.048467699 0.0398531 -0.061473999, + 0.0465803 0.0393616 -0.062821999, + 0.048467699 0.039048702 -0.062332999, + 0.050219599 0.040442299 -0.060095001, + 0.050219599 0.0396524 -0.060970001, + 0.051830001 0.041122999 -0.058697, + 0.051830001 0.040346298 -0.059590001, + 0.0532961 0.041887801 -0.057293002, + 0.0532961 0.0411225 -0.058203999, + 0.0546159 0.042728201 -0.055897001, + 0.0546159 0.041972701 -0.056825999, + 0.055787299 0.043635301 -0.054519001, + 0.055787299 0.042887799 -0.055466998, + 0.056809202 0.0445996 -0.053171001, + 0.044564299 0.0397899 -0.063284002, + 0.0424264 0.040343001 -0.063703001, + 0.040174201 0.041026499 -0.064057998, + 0.0378174 0.041842502 -0.064329997, + 0.035366699 0.042789001 -0.064498998, + 0.0328326 0.043861099 -0.064545996, + 0.0302257 0.045049898 -0.064451002, + 0.027557701 0.046342999 -0.064198002, + 0.0248404 0.047725402 -0.063777, + 0.0220857 0.049180299 -0.063175999, + 0.019305199 0.050689001 -0.062387001, + 0.0165099 0.052229501 -0.061407998, + 0.0137106 0.0525942 -0.061671998, + 0.0109179 0.052886099 -0.061721999, + 0.0081428103 0.052967001 -0.061859999, + 0.0053973799 0.053001702 -0.061845999, + 0.00268824 0.052985799 -0.061702002, + 0 0.052921101 -0.061443999, + -0.00268824 0.052987199 -0.061701, + -0.0053973799 0.053004399 -0.061845001, + -0.0081428103 0.052971099 -0.061859, + -0.0109179 0.052891102 -0.061721999, + -0.0137106 0.052597299 -0.061673999, + -0.0165099 0.052229501 -0.061407, + -0.019305199 0.050689101 -0.062383998, + -0.0220857 0.049182501 -0.063170999, + -0.0248404 0.047728699 -0.063771002, + -0.027557701 0.046347398 -0.064190999, + -0.0302257 0.045055699 -0.064443, + -0.0328326 0.043868698 -0.064538002, + -0.035366699 0.0427984 -0.064490996, + -0.0378174 0.0418537 -0.064322002, + -0.040174201 0.041039702 -0.064049996, + -0.0424264 0.040358 -0.063695997, + -0.044564299 0.039806701 -0.063279003, + -0.059617501 0.040560201 -0.058019001, + -0.059535399 0.040049002 -0.058458999, + -0.059617501 0.038790699 -0.059889998, + -0.059691299 0.039308898 -0.059471, + -0.059757002 0.038111702 -0.060982998, + -0.059864402 0.0391551 -0.060189001, + -0.0599402 0.038495898 -0.061450001, + -0.059757002 0.039825302 -0.059053, + -0.059691299 0.041069701 -0.057581, + -0.059999999 0.037215699 -0.064324997, + -0.059999999 0.040592398 -0.059951, + -0.0599402 0.036011498 -0.067638002, + -0.059985202 0.042891402 -0.056573, + -0.0599402 0.045324799 -0.053392, + -0.059864402 0.0460773 -0.052251, + -0.059814699 0.046458501 -0.051702999, + -0.059757002 0.046822902 -0.051224999, + -0.059691299 0.047170401 -0.050754, + -0.0599402 0.047044799 -0.051314998, + -0.0599062 0.048251498 -0.049764, + -0.059864402 0.0485879 -0.049263999, + -0.059864402 0.049373001 -0.048250001, + -0.059757002 0.049210101 -0.048234999, + -0.056809202 0.0466794 -0.050190002, + -0.055787299 0.046374999 -0.0506, + -0.044564299 0.0442953 -0.058065001, + -0.0424264 0.044865701 -0.058511, + -0.040174201 0.045576598 -0.058878001, + -0.0378174 0.046424899 -0.059144001, + -0.035366699 0.047403999 -0.059289001, + -0.0328326 0.048504099 -0.059292, + -0.0302257 0.049711499 -0.059136, + -0.027557701 0.051008601 -0.058807001, + -0.0248404 0.052378099 -0.058297001, + -0.0220857 0.0526977 -0.059016999, + -0.019305199 0.052954599 -0.05951, + -0.0165099 0.053015102 -0.060081001, + -0.0137106 0.0530333 -0.060488999, + -0.0109179 0.053004999 -0.060752999, + -0.0081428103 0.052930899 -0.060885001, + -0.0053973799 0.052813299 -0.060899999, + -0.00268824 0.052653201 -0.060807999, + 0 0.052451499 -0.060621999, + 0.00268824 0.052652001 -0.06081, + 0.0053973799 0.052810501 -0.060903002, + 0.0081428103 0.052926399 -0.060888998, + 0.0109179 0.052999198 -0.060756002, + 0.0137106 0.053026401 -0.060492001, + 0.0165099 0.053006899 -0.060083002, + 0.019305199 0.0529457 -0.059510998, + 0.0220857 0.0526927 -0.059014998, + 0.0248404 0.052378099 -0.058297999, + 0.027557701 0.051008299 -0.058812, + 0.0302257 0.0497084 -0.059142001, + 0.0328326 0.0484997 -0.059300002, + 0.035366699 0.047398299 -0.059298001, + 0.0378174 0.046417501 -0.059154, + 0.040174201 0.045567401 -0.058888, + 0.0424264 0.044854399 -0.058520999, + 0.044564299 0.044282001 -0.058075, + 0.0465803 0.043848399 -0.057573002, + 0.048467699 0.043548401 -0.057039, + 0.048467699 0.0442218 -0.056129999, + 0.050219599 0.044699099 -0.054646, + 0.050219599 0.0440474 -0.055571999, + 0.051830001 0.045276001 -0.053135, + 0.051830001 0.044644799 -0.054081, + 0.0532961 0.0459469 -0.051612001, + 0.0532961 0.0453347 -0.052577998, + 0.0546159 0.046705 -0.050092001, + 0.0546159 0.046109699 -0.05108, + 0.055787299 0.0475423 -0.048587002, + 0.055787299 0.046961699 -0.049598001, + 0.056809202 0.047881901 -0.048145998, + 0.056809202 0.047283899 -0.049173001, + 0.0576833 0.048271399 -0.047784001, + 0.055787299 0.046352599 -0.050602, + 0.0546159 0.045487199 -0.052060999, + 0.0532961 0.0446967 -0.053537998, + 0.051830001 0.043989301 -0.055020001, + 0.050219599 0.043372601 -0.056492001, + 0.048467699 0.042853098 -0.057941001, + 0.058412101 0.049305499 -0.046445001, + 0.058998398 0.050375801 -0.045166001, + 0.059238799 0.051215101 -0.044000998, + 0.059445001 0.0514718 -0.043954, + 0.059617501 0.051723398 -0.043933, + 0.059757002 0.051967401 -0.043935999, + 0.059864402 0.052201901 -0.043963999, + 0.0599402 0.051744401 -0.045109, + 0.059985202 0.051212098 -0.046241999, + 0.059999999 0.050606798 -0.047343001, + 0.0599402 0.049247298 -0.049807999, + 0.059757002 0.0448079 -0.056947999, + 0.059445001 0.040508799 -0.065148003, + 0.058998398 0.039585199 -0.069075003, + 0.058412101 0.038773298 -0.073368996, + 0.0576833 0.038065899 -0.078005001, + 0.056809202 0.037499301 -0.082958996, + 0.055787299 0.037194598 -0.088253997, + 0.0546159 0.037158001 -0.093872003, + 0.0532961 0.037385099 -0.099781103, + 0.051830001 0.037864901 -0.105951, + 0.050219599 0.038582299 -0.112352, + 0.048467699 0.039518099 -0.118954, + 0.0465803 0.040651299 -0.125732, + 0.044564299 0.041957501 -0.132662, + 0.0424264 0.042865202 -0.14699399, + 0.040174201 0.0449977 -0.14689299, + 0.0424264 0.043412998 -0.139723, + 0.044564299 0.041173499 -0.13988, + 0.0465803 0.038830198 -0.140044, + 0.048467699 0.0363934 -0.140214, + 0.050219599 0.033873498 -0.14039101, + 0.051830001 0.032112598 -0.133579, + 0.0532961 0.030563001 -0.126909, + 0.0546159 0.029250899 -0.120405, + 0.055787299 0.0282022 -0.114088, + 0.056809202 0.027437599 -0.107987, + 0.0576833 0.026973501 -0.10213, + 0.058412101 0.026820499 -0.096547, + 0.058998398 0.0269846 -0.091270998, + 0.059445001 0.0274645 -0.086328998, + 0.059757002 0.0282508 -0.081739999, + 0.0599402 0.029231001 -0.077486001, + 0.059999999 0.030346001 -0.073600002, + 0.0599402 0.031570699 -0.070115, + 0.059757002 0.032877099 -0.06707, + 0.059238799 0.0331682 -0.065268002, + 0.058998398 0.032083798 -0.066042997, + 0.059445001 0.032464601 -0.066454001, + 0.058998398 0.033886999 -0.064205997, + 0.058722898 0.032815602 -0.065021001, + 0.058722898 0.0346076 -0.063279003, + 0.058412101 0.033550501 -0.064134002, + 0.058065701 0.034355499 -0.063352004, + 0.058412101 0.035395999 -0.062458001, + 0.0576833 0.0352346 -0.062605001, + 0.058722898 0.0355011 -0.062426001, + 0.058998398 0.035662498 -0.062426001, + 0.059238799 0.034954999 -0.063394003, + 0.059445001 0.034248099 -0.064496003, + 0.059757002 0.034637701 -0.064994998, + 0.056809202 0.035135198 -0.062850997, + 0.055787299 0.035100002 -0.063208997, + 0.0546159 0.035089102 -0.063675001, + 0.0532961 0.0351215 -0.064153999, + 0.051830001 0.035212301 -0.064646997, + 0.050219599 0.0353745 -0.065145999, + 0.048467699 0.0356199 -0.065641999, + 0.0465803 0.03596 -0.066124, + -0.059238799 0.038507 -0.059785001, + -0.058998398 0.039317999 -0.058878001, + -0.059445001 0.039536301 -0.058899999, + -0.059445001 0.038626499 -0.05982, + -0.059535399 0.038270701 -0.060309999, + -0.059617501 0.037060801 -0.061781999, + -0.059445001 0.037749201 -0.060732, + -0.059238799 0.0375879 -0.060686, + -0.058998398 0.037473299 -0.060674001, + -0.050219599 0.038026001 -0.062684998, + -0.050219599 0.037169799 -0.063522004, + -0.048467699 0.0373956 -0.064015001, + -0.051830001 0.038743701 -0.061338998, + -0.051830001 0.03703 -0.063028999, + -0.0532961 0.0387039 -0.060858, + -0.0532961 0.036962599 -0.062545002, + -0.0546159 0.038725901 -0.060399, + -0.0546159 0.036953598 -0.06208, + -0.055787299 0.038795199 -0.059969999, + -0.055787299 0.036989301 -0.061639, + -0.056809202 0.038897298 -0.059576001, + -0.056809202 0.037057701 -0.061216, + -0.0576833 0.0390204 -0.059207998, + -0.0576833 0.037144098 -0.060897999, + -0.058412101 0.0391494 -0.058956999, + -0.058412101 0.037279502 -0.060738999, + -0.058722898 0.036436301 -0.061565999, + -0.058998398 0.0365449 -0.061556, + -0.059238799 0.036702201 -0.061579, + -0.059445001 0.036003001 -0.062586002, + -0.059757002 0.0363831 -0.062959999, + -0.058065701 0.034356602 -0.063354, + -0.0576833 0.035236299 -0.062605001, + -0.058412101 0.035397001 -0.062458999, + -0.058412101 0.033539001 -0.064136997, + -0.059238799 0.033162098 -0.065261997, + -0.059445001 0.032465801 -0.066444002, + -0.058998398 0.0320778 -0.066036999, + -0.058998398 0.033871699 -0.064207003, + -0.058722898 0.032800298 -0.065021999, + -0.058722898 0.034596 -0.063281998, + -0.058722898 0.0354986 -0.062428001, + -0.058998398 0.035650801 -0.062429, + -0.059238799 0.034939598 -0.063395001, + -0.059445001 0.034242 -0.064489998, + -0.059757002 0.032881498 -0.067057997, + -0.044562999 0.040173098 -0.16150001, + -0.0460645 0.0384284 -0.16150001, + -0.044564299 0.040275499 -0.154311, + -0.0465803 0.037919801 -0.154368, + -0.0465803 0.0382566 -0.147209, + -0.048467699 0.035811398 -0.147324, + -0.048467699 0.036380701 -0.14021, + -0.050219599 0.0338604 -0.140387, + -0.050219599 0.034673899 -0.133334, + -0.051830001 0.032093499 -0.13357399, + -0.051830001 0.033166301 -0.126597, + -0.0532961 0.030542299 -0.126903, + -0.0532961 0.031882402 -0.120022, + -0.0546159 0.0292315 -0.120396, + -0.0546159 0.0308448 -0.113633, + -0.055787299 0.028183701 -0.114078, + -0.055787299 0.030074799 -0.107456, + -0.056809202 0.0274195 -0.107974, + -0.056809202 0.0295911 -0.101522, + -0.0576833 0.0269564 -0.102116, + -0.0576833 0.0294053 -0.095859997, + -0.058412101 0.026805 -0.096533, + -0.058412101 0.029524799 -0.090503998, + -0.058998398 0.0269715 -0.091257997, + -0.058998398 0.029952301 -0.085483998, + -0.059445001 0.0274575 -0.086320996, + -0.059445001 0.0306751 -0.080812998, + -0.059757002 0.028250299 -0.081735998, + -0.059757002 0.031576801 -0.076467998, + -0.0599402 0.029231399 -0.077480003, + -0.0599402 0.032622799 -0.072476998, + -0.059999999 0.0303479 -0.073591001, + -0.059999999 0.033793099 -0.068870999, + -0.0599402 0.0315747 -0.070104003, + -0.0599402 0.035057001 -0.065686002, + -0.056809202 0.0351418 -0.062836997, + -0.055787299 0.0351054 -0.063213997, + -0.0546159 0.035099 -0.063681997, + -0.0532961 0.035137098 -0.064159997, + -0.051830001 0.035231199 -0.064652003, + -0.050219599 0.035394501 -0.06515, + -0.048467699 0.0356398 -0.065645002, + -0.0465803 0.035978999 -0.066124, + -0.0465803 0.0377197 -0.064496003, + -0.044564299 0.036423001 -0.066577002, + -0.044564299 0.0381536 -0.064949997, + -0.0424264 0.036981799 -0.066987999, + -0.0424264 0.038706802 -0.065362997, + -0.040174201 0.0376628 -0.067341, + -0.040174201 0.0393866 -0.065715, + -0.0378174 0.038470499 -0.067617998, + -0.0378174 0.0401957 -0.065987997, + -0.035366699 0.039405599 -0.067803003, + -0.035366699 0.041134302 -0.066165, + -0.0328326 0.040466499 -0.067876004, + -0.0328326 0.0421988 -0.066225, + -0.0302257 0.041647699 -0.067818999, + -0.0302257 0.043382201 -0.066148996, + -0.027557701 0.042939398 -0.067616999, + -0.027557701 0.044673301 -0.065922, + -0.0248404 0.044328999 -0.067253999, + -0.0248404 0.046058498 -0.065531, + -0.0220857 0.045802101 -0.066720001, + -0.0220857 0.047522102 -0.064963996, + -0.019305199 0.047341801 -0.066004999, + -0.019305199 0.049045902 -0.064213, + -0.0165099 0.048928998 -0.065104, + -0.0165099 0.0506097 -0.063272998, + -0.0137106 0.050543401 -0.064015999, + -0.0137106 0.0521941 -0.062146001, + -0.0109179 0.052165698 -0.062739998, + -0.0109179 0.052574798 -0.062267002, + -0.0081428103 0.052557498 -0.062719002, + -0.0081428103 0.052877899 -0.062173001, + -0.0053973799 0.0528685 -0.062488999, + -0.0053973799 0.052963 -0.062174, + -0.00268824 0.0529579 -0.062359001, + -0.00268824 0.052999999 -0.062029, + 0 0.0529982 -0.062089998, + 0 0.052985501 -0.061762001, + 0.00268824 0.052998699 -0.062029999, + 0.00268824 0.0529566 -0.062359001, + 0.0053973799 0.052960299 -0.062174998, + 0.0053973799 0.052866001 -0.062488999, + 0.0081428103 0.0528742 -0.062173001, + 0.0081428103 0.052555699 -0.062717997, + 0.0109179 0.052572299 -0.062266, + 0.0109179 0.052165698 -0.062740996, + 0.0137106 0.0521941 -0.062146001, + 0.0137106 0.050543301 -0.064018004, + 0.0165099 0.050609499 -0.063276999, + 0.0165099 0.0489273 -0.065108001, + 0.019305199 0.049043901 -0.064217001, + 0.019305199 0.047339201 -0.066009998, + 0.0220857 0.047519099 -0.064970002, + 0.0220857 0.0457986 -0.066725999, + 0.0248404 0.046054501 -0.065537997, + 0.0248404 0.044324201 -0.067261003, + 0.027557701 0.044668 -0.065930001, + 0.027557701 0.042932998 -0.067624003, + 0.0302257 0.043375298 -0.066156998, + 0.0302257 0.0416396 -0.067826003, + 0.0328326 0.042190101 -0.066233002, + 0.0328326 0.040456701 -0.067883, + 0.035366699 0.0411238 -0.066173002, + 0.035366699 0.039393999 -0.067809999, + 0.0378174 0.040183399 -0.065995999, + 0.0378174 0.038457099 -0.067624003, + 0.040174201 0.039372399 -0.065720998, + 0.040174201 0.037647799 -0.067345999, + 0.0424264 0.038690899 -0.065367997, + 0.0424264 0.036965199 -0.066992, + 0.044564299 0.038136199 -0.064953998, + 0.044564299 0.036405101 -0.066578999, + 0.0465803 0.037701 -0.064498, + 0.048467699 0.038222902 -0.06318, + 0.050219599 0.03884 -0.061834, + 0.051830001 0.039545901 -0.06047, + 0.0532961 0.040332701 -0.059101999, + 0.0546159 0.041191999 -0.057742, + 0.055787299 0.0421145 -0.056400001, + 0.056809202 0.042296998 -0.056021001, + 0.0576833 0.0425057 -0.055693999, + 0.058412101 0.042725801 -0.055417001, + 0.058998398 0.043803599 -0.054278001, + 0.059238799 0.043917399 -0.054187, + 0.059445001 0.044022601 -0.054125998, + -0.059757002 0.034915399 -0.071354002, + -0.059445001 0.0339536 -0.075443, + -0.058998398 0.033126201 -0.079880998, + -0.058412101 0.032462999 -0.084641002, + -0.0576833 0.032084301 -0.089748003, + -0.056809202 0.032001801 -0.095188998, + -0.055787299 0.032211699 -0.100931, + -0.0546159 0.032705501 -0.106943, + -0.0532961 0.033469699 -0.113194, + -0.051830001 0.034485199 -0.119655, + -0.050219599 0.035730299 -0.12629899, + -0.048467699 0.037182301 -0.133101, + -0.0465803 0.038818002 -0.14004, + -0.044564299 0.040608 -0.147098, + -0.0424264 0.042526901 -0.154258, + -0.042476799 0.042376 -0.16150001, + -0.040347401 0.044408198 -0.16150001, + -0.0418665 0.042958502 -0.16150001, + -0.040174201 0.044663899 -0.15420701, + -0.0424264 0.042855099 -0.146992, + -0.044564299 0.041161802 -0.13987599, + -0.0465803 0.039608199 -0.132875, + -0.048467699 0.0382227 -0.126008, + -0.050219599 0.037028499 -0.119296, + -0.051830001 0.036047202 -0.112763, + -0.0532961 0.0353004 -0.106437, + -0.0546159 0.034808099 -0.100346, + -0.055787299 0.0345846 -0.094520003, + -0.056809202 0.034639999 -0.088992998, + -0.0576833 0.0349796 -0.083796002, + -0.058412101 0.035592798 -0.078942001, + -0.058998398 0.036355998 -0.074405998, + -0.059445001 0.037238698 -0.070216, + -0.059757002 0.038247202 -0.066395998, + -0.0599402 0.042688899 -0.058453001, + -0.059999999 0.043906901 -0.055752002, + -0.059985202 0.0463068 -0.052494999, + -0.059966501 0.047527 -0.050848, + -0.0599402 0.048725002 -0.049279001, + -0.0599062 0.049057402 -0.048769999, + -0.0599402 0.045939699 -0.054108001, + -0.059757002 0.044801801 -0.056942999, + -0.056809202 0.037492599 -0.082952, + -0.055787299 0.037182201 -0.088242002, + -0.0546159 0.037143499 -0.093858004, + -0.0532961 0.0373693 -0.099768601, + -0.051830001 0.037848301 -0.10594, + -0.050219599 0.038565598 -0.112343, + -0.048467699 0.0395009 -0.118947, + -0.0465803 0.040633202 -0.125727, + -0.044564299 0.041941099 -0.132658, + -0.0424264 0.0434018 -0.13971899, + -0.040174201 0.0449882 -0.146892, + -0.0378174 0.046679299 -0.15415899, + -0.038121 0.046333499 -0.16150001, + -0.0358027 0.048147298 -0.16150001, + -0.037225999 0.047033701 -0.16150001, + -0.035366699 0.048565999 -0.15411399, + -0.0378174 0.046999801 -0.146798, + -0.040174201 0.045528099 -0.139571, + -0.0424264 0.044170499 -0.132451, + -0.044564299 0.0429512 -0.125457, + -0.0465803 0.041891798 -0.11861, + -0.048467699 0.041013699 -0.111934, + -0.050219599 0.040337902 -0.105455, + -0.051830001 0.039884102 -0.099201702, + -0.0532961 0.039667599 -0.093204997, + -0.0546159 0.039700799 -0.087498002, + -0.055787299 0.039992299 -0.082112998, + -0.056809202 0.040534299 -0.077062003, + -0.056809202 0.0436171 -0.071272999, + -0.055787299 0.0429901 -0.076127, + -0.0546159 0.042468902 -0.081280999, + -0.0532961 0.042185299 -0.086764999, + -0.051830001 0.042146001 -0.092564002, + -0.050219599 0.042341199 -0.0986479, + -0.048467699 0.0427581 -0.104983, + -0.0465803 0.0433813 -0.111538, + -0.044564299 0.0441911 -0.118285, + -0.0424264 0.0451665 -0.12519901, + -0.040174201 0.046286799 -0.132254, + -0.0378174 0.047533199 -0.139431, + -0.035366699 0.048882999 -0.146709, + -0.0328326 0.050317399 -0.154072, + -0.033398401 0.0498452 -0.16150001, + -0.0328326 0.050631098 -0.14662699, + -0.035366699 0.0494105 -0.13929901, + -0.0378174 0.048282601 -0.13206901, + -0.040174201 0.0472693 -0.124954, + -0.0424264 0.046388499 -0.117975, + -0.044564299 0.0456581 -0.111158, + -0.0465803 0.045098599 -0.104526, + -0.048467699 0.0447299 -0.098109998, + -0.050219599 0.0445676 -0.091937996, + -0.051830001 0.044624701 -0.086043999, + -0.0532961 0.044911802 -0.080461003, + -0.0546159 0.045423198 -0.075200997, + -0.055787299 0.0460242 -0.070234999, + -0.056809202 0.046684802 -0.065591, + -0.0576833 0.047417499 -0.061299, + -0.058412101 0.048225399 -0.057381999, + -0.058998398 0.049107201 -0.053865001, + -0.058998398 0.050980099 -0.044075001, + -0.058998398 0.0504 -0.045169, + -0.058412101 0.0493294 -0.046447001, + -0.058412101 0.0499129 -0.045373999, + -0.059617501 0.052343901 -0.042821001, + -0.059445001 0.0520752 -0.042844001, + -0.059757002 0.053186402 -0.041692, + -0.059757002 0.052605499 -0.042824, + -0.059864402 0.0528576 -0.042851999, + -0.0599402 0.053719699 -0.041769002, + -0.0599402 0.053100102 -0.042902, + -0.059985202 0.0526613 -0.044085, + -0.059999999 0.053558901 -0.043056998, + -0.059999999 0.052144401 -0.045254, + -0.0599402 0.053989001 -0.043260001, + -0.0599402 0.052499998 -0.045417, + -0.059757002 0.054402199 -0.043469999, + -0.059757002 0.0512264 -0.048002001, + -0.059445001 0.053230301 -0.046172, + -0.059445001 0.050064601 -0.050772, + -0.059238799 0.051111698 -0.049926002, + -0.058998398 0.052163199 -0.049075, + -0.059238799 0.054240901 -0.045249, + -0.059445001 0.056329802 -0.041498002, + -0.059757002 0.055847902 -0.041250002, + -0.0599402 0.055355798 -0.040998001, + -0.059999999 0.054844301 -0.040778998, + -0.0599402 0.054304801 -0.040619999, + -0.059757002 0.053732499 -0.040545002, + -0.059445001 0.052620299 -0.041717999, + -0.058998398 0.0515269 -0.042970002, + -0.058412101 0.0504639 -0.044291999, + -0.0576833 0.049442399 -0.045674998, + -0.0532961 0.0465529 -0.050634, + -0.0532961 0.047113199 -0.049658, + -0.0546159 0.0472936 -0.049091998, + -0.051830001 0.045901101 -0.052177001, + -0.051830001 0.046483099 -0.051222999, + -0.050219599 0.0453448 -0.053707, + -0.050219599 0.045949999 -0.052772, + -0.048467699 0.044889402 -0.055208001, + -0.048467699 0.045519002 -0.054290999, + -0.0465803 0.0451934 -0.055764001, + -0.050219599 0.047631402 -0.049954999, + -0.050219599 0.047093 -0.050896, + -0.048467699 0.047281198 -0.051523998, + -0.051830001 0.048086401 -0.048349999, + -0.051830001 0.047575399 -0.049307998, + -0.0532961 0.048157599 -0.047702, + -0.0532961 0.047648001 -0.048680998, + -0.0546159 0.0483476 -0.047093, + -0.051830001 0.0470411 -0.050266001, + -0.050219599 0.046532702 -0.051835001, + -0.048467699 0.046127301 -0.053369999, + -0.0465803 0.046442699 -0.053948998, + -0.0465803 0.047614001 -0.052126002, + -0.044564299 0.046902299 -0.054485001, + -0.044564299 0.048095401 -0.052678999, + -0.0424264 0.047508098 -0.054951999, + -0.0424264 0.048725899 -0.053155001, + -0.040174201 0.0482581 -0.055326, + -0.040174201 0.0495013 -0.053530999, + -0.0378174 0.049145799 -0.055583999, + -0.0378174 0.050413001 -0.053783, + -0.035366699 0.050160799 -0.055707, + -0.035366699 0.0514476 -0.053892002, + -0.0328326 0.051288299 -0.055675, + -0.0328326 0.0525911 -0.053840999, + -0.0302257 0.0525131 -0.055473, + -0.0302257 0.0528486 -0.055011999, + -0.0288986 0.052965499 -0.055518001, + -0.0288986 0.052820001 -0.055771999, + -0.027557701 0.053055201 -0.055961002, + -0.027557701 0.052441999 -0.056960002, + -0.0302257 0.051141899 -0.057314999, + -0.0328326 0.049926698 -0.057494, + -0.035366699 0.048813 -0.057507001, + -0.0378174 0.047816999 -0.057372, + -0.040174201 0.046950601 -0.057108998, + -0.0424264 0.046222199 -0.056738999, + -0.044564299 0.0456363 -0.056281999, + -0.055787299 0.0486385 -0.046542998, + -0.055787299 0.0475641 -0.048583001, + -0.056809202 0.0490105 -0.046066999, + -0.056809202 0.0479047 -0.048144002, + -0.0576833 0.048294902 -0.047784001, + -0.058412101 0.048714101 -0.047506999, + -0.058998398 0.049787201 -0.046250001, + -0.059238799 0.050643399 -0.045102, + -0.059238799 0.050014801 -0.046185002, + -0.059445001 0.050883301 -0.045058001, + -0.059445001 0.050237902 -0.046142999, + -0.059617501 0.050454501 -0.046123002, + -0.059985202 0.05046 -0.047295999, + -0.059985202 0.051222999 -0.046250001, + -0.059999999 0.050612502 -0.047348, + -0.0599402 0.050299801 -0.047247998, + -0.0599402 0.051761899 -0.045116, + -0.059757002 0.051990401 -0.043942001, + -0.059757002 0.051342301 -0.045042001, + -0.059617501 0.051747199 -0.043938, + -0.059864402 0.052223701 -0.043969002, + -0.059864402 0.050859101 -0.046149999, + -0.059864402 0.050130501 -0.047210999, + -0.059757002 0.049950998 -0.047189999, + -0.059445001 0.051495899 -0.043958001, + -0.059238799 0.051239401 -0.044004001, + -0.0599402 0.049249001 -0.049807999, + -0.059757002 0.0479884 -0.052451, + -0.059445001 0.046942901 -0.055411998, + -0.0248404 0.052742399 -0.057831999, + -0.0220857 0.052983899 -0.058478002, + -0.019305199 0.0530366 -0.059199002, + -0.0165099 0.053048499 -0.059755001, + -0.0137106 0.0530155 -0.060162999, + -0.0109179 0.052937798 -0.060437001, + -0.0081428103 0.052817501 -0.060587, + -0.0053973799 0.052655399 -0.060624, + -0.00268824 0.0524524 -0.060561001, + 0 0.0522094 -0.060407002, + 0.00268824 0.052451499 -0.060563002, + 0.0053973799 0.0526531 -0.060628001, + 0.0081428103 0.052813299 -0.060591001, + 0.0109179 0.0529317 -0.060440999, + 0.0137106 0.053008098 -0.060167, + 0.0165099 0.053040199 -0.059758, + 0.019305199 0.053027 -0.059202, + 0.0220857 0.052973799 -0.058479, + 0.0248404 0.0527368 -0.057829, + 0.027557701 0.052441999 -0.056960002, + 0.0302257 0.051141601 -0.057321001, + 0.0328326 0.049923301 -0.057500999, + 0.035366699 0.048808299 -0.057516001, + 0.0378174 0.047810901 -0.057383001, + 0.040174201 0.0469428 -0.057119999, + 0.0424264 0.046212401 -0.056749001, + 0.044564299 0.045624498 -0.056292001, + 0.035650201 0.048260398 -0.16150001, + 0.037236601 0.047047202 -0.1815, + 0.040173799 0.044563901 -0.16150001, + 0.037974101 0.046453901 -0.16150001, + 0.040174201 0.044677898 -0.154204, + 0.0424264 0.042541601 -0.154255, + 0.041868102 0.0429601 -0.16150001, + 0.044564299 0.040618502 -0.147099, + 0.0465803 0.038267601 -0.14721, + 0.048467699 0.035822898 -0.14732499, + 0.050219599 0.033294901 -0.14744399, + 0.051830001 0.0312814 -0.140572, + 0.0532961 0.029472301 -0.13382401, + 0.0546159 0.027891099 -0.127221, + 0.055787299 0.0265639 -0.120784, + 0.056809202 0.025516599 -0.114537, + 0.0576833 0.0247685 -0.108507, + 0.058412101 0.024335301 -0.102725, + 0.058998398 0.0242266 -0.097218998, + 0.059445001 0.024447501 -0.092019998, + 0.059757002 0.024996299 -0.087158002, + 0.0599402 0.025858 -0.082649998, + 0.059999999 0.026903801 -0.078491002, + 0.0599402 0.0280711 -0.074713998, + -0.048232201 0.0356883 -0.16150001, + -0.046576701 0.037814599 -0.16150001, + -0.0460728 0.038435601 -0.1815, + -0.046423901 0.038010798 -0.16150001, + -0.037236601 0.047047202 -0.1815, + -0.035360798 0.048459399 -0.16150001, + -0.0322018 0.050626501 -0.1815, + -0.041876599 0.0429691 -0.1815, + -0.040171102 0.044560701 -0.16150001, + -0.044503901 0.0402418 -0.16150001, + -0.0424252 0.0424252 -0.16150001, + -0.0378129 0.046574499 -0.16150001, + -0.032825802 0.0502089 -0.16150001, + -0.0321921 0.050611299 -0.16150001, + -0.030913601 0.051423199 -0.16150001, + -0.0302257 0.051927298 -0.154034, + -0.027557701 0.053393099 -0.153999, + -0.028354499 0.0528774 -0.16150001, + -0.0302257 0.052237999 -0.146552, + -0.0328326 0.051153 -0.13917799, + -0.035366699 0.050151099 -0.13189501, + -0.0378174 0.049252398 -0.124723, + -0.040174201 0.048474401 -0.117681, + -0.0424264 0.047834001 -0.110794, + -0.044564299 0.047349401 -0.104087, + -0.0465803 0.0470399 -0.097589001, + -0.048467699 0.0469217 -0.091329001, + -0.050219599 0.047008298 -0.085340001, + -0.051830001 0.047310401 -0.079655997, + -0.0532961 0.047823198 -0.074288003, + -0.0546159 0.048409 -0.069205999, + -0.055787299 0.049037699 -0.064438999, + -0.056809202 0.049724199 -0.060017001, + -0.0576833 0.050473299 -0.055964001, + -0.058412101 0.0512852 -0.052308999, + -0.058722898 0.053218 -0.048222002, + -0.058998398 0.0552558 -0.044321999, + -0.056809202 0.052717999 -0.054547999, + -0.055787299 0.052018698 -0.058741, + -0.0546159 0.051368799 -0.063297004, + -0.0532961 0.050761402 -0.068190999, + -0.051830001 0.050179701 -0.073391996, + -0.050219599 0.0496541 -0.078869, + -0.048467699 0.049325399 -0.084656, + -0.0465803 0.0491983 -0.090740003, + -0.044564299 0.049261302 -0.097088002, + -0.0424264 0.049500398 -0.103668, + -0.040174201 0.0498995 -0.110449, + -0.0378174 0.050441399 -0.117404, + -0.035366699 0.0511089 -0.124506, + -0.0328326 0.0518854 -0.131734, + -0.0302257 0.0527547 -0.139066, + -0.027557701 0.053700902 -0.146483, + -0.0275511 0.0532832 -0.16150001, + -0.030218899 0.051817998 -0.16150001, + -0.0152803 0.058021698 -0.1815, + -0.0165057 0.0576679 -0.16150001, + -0.0117927 0.058829699 -0.16150001, + -0.0109179 0.059094999 -0.153863, + -0.0137106 0.058806501 -0.14624301, + -0.0165099 0.058577199 -0.138659, + -0.019305199 0.058409698 -0.131128, + -0.0220857 0.0583097 -0.123668, + -0.0248404 0.058282301 -0.116298, + -0.027557701 0.058336101 -0.10904, + -0.0302257 0.058481898 -0.101917, + -0.0328326 0.058730699 -0.094954997, + -0.035366699 0.059092298 -0.088182002, + -0.0378174 0.059578799 -0.081629001, + -0.040174201 0.060201399 -0.075328, + -0.0424264 0.060956001 -0.069291003, + -0.044564299 0.0616838 -0.063478, + -0.0465803 0.0623504 -0.057920001, + -0.048467699 0.062978297 -0.052650001, + -0.050219599 0.063580401 -0.047699001, + -0.049361002 0.064605698 -0.047052, + -0.050219599 0.066198699 -0.041650001, + -0.051042698 0.065188698 -0.042371999, + -0.051830001 0.066764601 -0.037266999, + -0.051042698 0.067756698 -0.036463998, + -0.051830001 0.069348499 -0.031452, + -0.052581199 0.068379901 -0.032336999, + -0.0532961 0.068709701 -0.030344, + -0.0576833 0.064052902 -0.031721, + -0.0576833 0.064594597 -0.030414, + -0.056809202 0.065946802 -0.029614, + -0.056809202 0.0653909 -0.030932, + -0.055787299 0.067298703 -0.028868999, + -0.055787299 0.066727698 -0.030191001, + -0.0546159 0.068640403 -0.028179999, + -0.0546159 0.068053402 -0.029502001, + -0.0532961 0.069961198 -0.027550001, + -0.044564299 0.064344801 -0.056944001, + -0.0424264 0.063633598 -0.062637001, + -0.040174201 0.062844299 -0.068572998, + -0.0378174 0.062013999 -0.074718997, + -0.035366699 0.061304599 -0.081119001, + -0.0328326 0.0607199 -0.087761, + -0.0302257 0.0602488 -0.094613001, + -0.027557701 0.059882302 -0.101644, + -0.0248404 0.059611399 -0.108827, + -0.0220857 0.059425499 -0.116137, + -0.019305199 0.059315201 -0.12355, + -0.0165099 0.0592754 -0.13104799, + -0.0137106 0.059302401 -0.13860799, + -0.0109179 0.0593917 -0.14621601, + -0.0081421202 0.059541799 -0.153852, + -0.0092321504 0.0592779 -0.16150001, + -0.0053918599 0.059854198 -0.153845, + -0.0059725801 0.059702002 -0.16150001, + -0.0081421202 0.059837598 -0.14619499, + -0.0109179 0.059885699 -0.138568, + -0.0137106 0.059997302 -0.13098, + -0.0165099 0.0601753 -0.12345, + -0.019305199 0.0604228 -0.115996, + -0.0220857 0.060743399 -0.108638, + -0.0248404 0.061143 -0.101399, + -0.027557701 0.061631002 -0.094301999, + -0.0302257 0.062216099 -0.087374002, + -0.0328326 0.062906601 -0.080646001, + -0.035366699 0.063710898 -0.074150003, + -0.0378174 0.064624898 -0.067895003, + -0.040174201 0.065484397 -0.061838001, + -0.0424264 0.066250697 -0.056010999, + -0.051830001 0.0718344 -0.025634, + -0.0532961 0.070527099 -0.026195999, + -0.0546159 0.069188803 -0.026825, + -0.055787299 0.067830503 -0.027518, + -0.056809202 0.066462897 -0.028272999, + -0.0576833 0.065096103 -0.029085999, + -0.058412101 0.06374 -0.02995, + -0.0302257 0.051647302 -0.051936999, + -0.030954201 0.050999999 -0.051399, + -0.0328326 0.051651601 -0.050328001, + -0.031537499 0.052260399 -0.051444001, + -0.0378174 0.052285101 -0.046983, + -0.040174201 0.052296199 -0.044966999, + -0.0390082 0.0527891 -0.046427999, + -0.0378174 0.0516611 -0.046693001, + -0.035366699 0.051656201 -0.048578002, + -0.035840798 0.050999999 -0.048119001, + -0.033493701 0.050999999 -0.049779002, + -0.035366699 0.0522747 -0.048870001, + -0.036603201 0.052771199 -0.048384, + -0.0378174 0.053114299 -0.047965001, + -0.0390082 0.053128202 -0.046969, + -0.0378174 0.053217798 -0.048262998, + -0.0378174 0.052967899 -0.047683001, + -0.036603201 0.052956901 -0.048645999, + -0.035366699 0.052762602 -0.049313001, + -0.0328326 0.052265 -0.050620999, + -0.0328326 0.052746501 -0.051066998, + -0.035366699 0.052946299 -0.049575999, + -0.036603201 0.053100899 -0.048928998, + -0.035366699 0.053185899 -0.050161, + -0.0378174 0.053275298 -0.04857, + -0.040174201 0.053316101 -0.04654, + -0.040174201 0.053333201 -0.046845999, + -0.0424264 0.053384598 -0.044689, + -0.0424264 0.053364299 -0.044980001, + -0.044564299 0.053428099 -0.042704999, + -0.044564299 0.053375799 -0.042970002, + -0.0465803 0.053453598 -0.040587001, + -0.0465803 0.053381398 -0.040826999, + -0.048467699 0.0534744 -0.038346998, + -0.048467699 0.0533108 -0.038784001, + -0.050219599 0.0534335 -0.036215, + -0.050219599 0.052869201 -0.037976999, + -0.051830001 0.053106301 -0.035323001, + -0.051830001 0.0525981 -0.037108999, + -0.0532961 0.052954499 -0.034387998, + -0.0532961 0.052499499 -0.036207002, + -0.0546159 0.052978501 -0.033438999, + -0.0546159 0.0525731 -0.035301998, + -0.055787299 0.053175598 -0.032506, + -0.055787299 0.0528116 -0.034425002, + -0.056809202 0.0535364 -0.031619001, + -0.056809202 0.053203199 -0.033601999, + -0.0576833 0.0540471 -0.030804999, + -0.0576833 0.053732201 -0.03286, + -0.058412101 0.054689799 -0.03009, + -0.058412101 0.054379102 -0.032221999, + -0.058998398 0.055443101 -0.029494001, + -0.058998398 0.0551209 -0.031706002, + -0.059445001 0.056282099 -0.029038999, + -0.059445001 0.055932399 -0.031328999, + -0.059757002 0.057179399 -0.028736999, + -0.059757002 0.056785401 -0.031103, + -0.0599402 0.058107901 -0.028596999, + -0.0599402 0.057654101 -0.031030999, + -0.059999999 0.0590523 -0.028597999, + -0.059999999 0.0585244 -0.031091999, + -0.0599402 0.060003102 -0.028717, + -0.0599402 0.059390102 -0.031259, + -0.059757002 0.0609557 -0.028927, + -0.059757002 0.060248502 -0.031504001, + -0.059445001 0.061905701 -0.029205, + -0.059445001 0.061098602 -0.031805001, + -0.058998398 0.062839203 -0.029547, + -0.058998398 0.061928101 -0.032156002, + -0.058412101 0.062723398 -0.032556999, + -0.0576833 0.063472897 -0.033004999, + -0.056809202 0.064797103 -0.032221001, + -0.055787299 0.066119298 -0.031481002, + -0.051042698 0.062540501 -0.048354, + -0.0328326 0.0530634 -0.051619999, + -0.0302257 0.0522561 -0.052230999, + -0.0302257 0.052731499 -0.052680001, + -0.0288986 0.052251901 -0.052981999, + -0.031537499 0.052738801 -0.051892001, + -0.0328326 0.052926201 -0.051332999, + -0.035366699 0.053087901 -0.049860001, + -0.0283962 0.050999999 -0.052855, + -0.030218599 0.050999999 -0.051817998, + -0.033494599 0.046 -0.049780998, + -0.032825399 0.050999999 -0.050207999, + -0.033437699 0.050999999 -0.049819, + -0.0353604 0.050999999 -0.048459001, + -0.038435601 0.046 -0.046073001, + -0.024833901 0.050999999 -0.054600999, + -0.0230815 0.050999999 -0.055383001, + -0.0248404 0.05164 -0.054719999, + -0.0262044 0.052244101 -0.054375999, + -0.027557701 0.052503102 -0.053907, + -0.027557701 0.052247901 -0.053697001, + -0.0288986 0.052724499 -0.053433001, + -0.027557701 0.052717902 -0.054149002, + -0.0262044 0.052498098 -0.054586001, + -0.0248404 0.052240599 -0.055016998, + -0.023467001 0.052237201 -0.055622, + -0.0248404 0.0524933 -0.055227999, + -0.0262044 0.052711502 -0.054827999, + -0.0248404 0.0527055 -0.055470999, + -0.023467001 0.052488901 -0.055833001, + -0.059999999 0.055991098 -0.038431998, + -0.0599402 0.056588601 -0.038656, + -0.059757002 0.057166699 -0.038924001, + -0.059445001 0.057731699 -0.039213002, + -0.058998398 0.058278199 -0.039503999, + -0.055787299 0.054950699 -0.053141002, + -0.0546159 0.0542919 -0.057477999, + -0.0532961 0.053668302 -0.062171001, + -0.051830001 0.053071201 -0.067194, + -0.050219599 0.0524823 -0.072515003, + -0.048467699 0.051932398 -0.078103997, + -0.0465803 0.051566198 -0.083994001, + -0.044564299 0.051387601 -0.090173997, + -0.0424264 0.0513843 -0.096610002, + -0.040174201 0.0515422 -0.10327, + -0.0378174 0.051847301 -0.110124, + -0.035366699 0.052283 -0.117144, + -0.0328326 0.052832302 -0.124305, + -0.0302257 0.053479798 -0.131586, + -0.027557701 0.054212999 -0.138964, + -0.0248404 0.0550179 -0.146421, + -0.0220857 0.055883799 -0.15393899, + -0.0211595 0.056128498 -0.16150001, + -0.0248404 0.053090099 -0.056986, + -0.0220857 0.053087801 -0.057845, + -0.019305199 0.0530435 -0.058550999, + -0.0165099 0.0529572 -0.059115, + -0.0137106 0.052830402 -0.059549998, + -0.0109179 0.052663401 -0.059863001, + -0.0081428103 0.052456699 -0.060063001, + -0.0053973799 0.052211199 -0.060162, + -0.00268824 0.0519301 -0.060169999, + 0 0.051625598 -0.060100999, + 0.00268824 0.051929999 -0.060171999, + 0.0053973799 0.052210301 -0.060166001, + 0.00268824 0.0522095 -0.060348, + 0 0.051929802 -0.060231, + -0.00268824 0.052209999 -0.060346, + -0.0053973799 0.052454099 -0.060377002, + -0.0081428103 0.0526588 -0.060311001, + -0.0109179 0.052823201 -0.060137998, + -0.0137106 0.0529465 -0.059847999, + -0.0165099 0.0530283 -0.059429999, + -0.019305199 0.053066701 -0.058874, + -0.0220857 0.053061601 -0.058168001, + -0.0248404 0.053017501 -0.057294998, + -0.027557701 0.052792698 -0.056496002, + 0.059999999 0.0559671 -0.038426999, + 0.0599402 0.0565667 -0.038649999, + 0.059757002 0.057149298 -0.038917001, + 0.059445001 0.057721 -0.039205, + 0.058998398 0.0582725 -0.039500002, + 0.058412101 0.058784399 -0.039958999, + 0.0576833 0.059335802 -0.040594999, + 0.056809202 0.058517199 -0.043942999, + 0.055787299 0.057822801 -0.047646001, + 0.0546159 0.057158701 -0.051755998, + 0.0532961 0.056530599 -0.056242, + 0.051830001 0.055924401 -0.061074, + 0.050219599 0.055327699 -0.066225, + 0.048467699 0.054721002 -0.071667001, + 0.0465803 0.0541411 -0.077370003, + 0.044564299 0.053731099 -0.083368003, + 0.0424264 0.053491201 -0.089643002, + 0.040174201 0.053411499 -0.096165001, + 0.0378174 0.053479798 -0.102903, + 0.035366699 0.053682599 -0.109826, + 0.0328326 0.054004099 -0.116908, + 0.0302257 0.054428302 -0.124124, + 0.027557701 0.054941401 -0.13145299, + 0.0248404 0.055532299 -0.13887399, + 0.0220857 0.0561921 -0.146367, + 0.051042698 0.065193899 -0.042376999, + 0.051830001 0.064170897 -0.043108001, + 0.050219599 0.063576698 -0.047708999, + 0.051830001 0.066774897 -0.037264001, + 0.052581199 0.065771401 -0.038075998, + 0.0532961 0.067399599 -0.033231001, + 0.053974401 0.061034799 -0.04535, + 0.0532961 0.062090199 -0.044594999, + 0.053974401 0.063734204 -0.039723001, + 0.0546159 0.062702797 -0.040557001, + 0.0576833 0.062848702 -0.034255002, + 0.058412101 0.060904801 -0.036297999, + 0.0576833 0.0621989 -0.035482999, + 0.056809202 0.064161599 -0.033473998, + 0.056809202 0.062792003 -0.036079999, + 0.055787299 0.0647837 -0.034152001, + 0.055787299 0.063405603 -0.036878001, + 0.0546159 0.065416202 -0.035041999, + 0.0532961 0.064757504 -0.038895998, + 0.052581199 0.0631359 -0.043848, + 0.051830001 0.061483301 -0.049029, + 0.019305199 0.057211202 -0.146319, + 0.0165099 0.058082901 -0.14627799, + 0.019305199 0.0577127 -0.138721, + 0.0220857 0.056696799 -0.13879199, + 0.0220857 0.057406001 -0.13122401, + 0.0248404 0.0562471 -0.131332, + 0.0248404 0.0571668 -0.123805, + 0.027557701 0.055869501 -0.123956, + 0.027557701 0.057004198 -0.116484, + 0.0302257 0.055574499 -0.116686, + 0.0302257 0.056929599 -0.109282, + 0.0328326 0.055374499 -0.109543, + 0.0328326 0.056954201 -0.102224, + 0.035366699 0.055281699 -0.102551, + 0.035366699 0.057089601 -0.095334999, + 0.0378174 0.055311199 -0.095737003, + 0.0378174 0.057349 -0.088643998, + 0.040174201 0.055476699 -0.089129001, + 0.040174201 0.057744302 -0.082180999, + 0.0424264 0.05579 -0.082759, + 0.0424264 0.058284301 -0.075979002, + 0.044564299 0.056259699 -0.076659001, + 0.044564299 0.058967199 -0.070051, + 0.0465803 0.0568856 -0.070843004, + 0.0465803 0.059643202 -0.064363003, + 0.048467699 0.0575216 -0.065279, + 0.048467699 0.0602751 -0.058943, + 0.050219599 0.058130499 -0.059992999, + 0.050219599 0.060883701 -0.053822, + 0.051830001 0.058732402 -0.055018, + 0.0532961 0.059340801 -0.050379999, + 0.0546159 0.059971102 -0.04611, + 0.055787299 0.060619801 -0.042242002, + 0.056809202 0.061376099 -0.038732, + 0.0576833 0.0607896 -0.038017999, + 0.058412101 0.060233399 -0.037494, + 0.058998398 0.059625201 -0.037145998, + 0.0423088 0.050999999 -0.042544, + 0.040746599 0.050999999 -0.044023, + 0.0424264 0.051670801 -0.042555001, + 0.040174201 0.051665299 -0.044690002, + 0.044564299 0.051676702 -0.040305998, + 0.044344399 0.050999999 -0.040417001, + -0.0532961 0.0537709 -0.030441999, + -0.053974401 0.053822201 -0.029072, + -0.0532961 0.0536891 -0.030867999, + -0.0532961 0.053791799 -0.03021, + -0.052581199 0.053751498 -0.031443, + -0.052581199 0.053747602 -0.031567, + -0.051830001 0.0537095 -0.032655001, + -0.051830001 0.053669602 -0.033142, + -0.0576833 0.065973498 -0.026374999, + -0.0576833 0.065556198 -0.027739, + -0.058412101 0.064590901 -0.027274, + -0.056809202 0.067369796 -0.025531, + -0.056809202 0.0669377 -0.026911, + -0.055787299 0.068769597 -0.024749, + -0.055787299 0.068321399 -0.026144, + -0.0546159 0.070162602 -0.024033999, + -0.0546159 0.069696799 -0.025442, + -0.0532961 0.071537703 -0.023393, + -0.0532961 0.071053199 -0.024808999, + -0.051830001 0.0728838 -0.022829, + -0.051830001 0.072379597 -0.024248, + -0.050219599 0.074189603 -0.022345001, + -0.050219599 0.073664702 -0.023761, + -0.048467699 0.075443901 -0.02194, + -0.048467699 0.074303098 -0.02493, + -0.043510102 0.070390902 -0.043404002, + -0.0424264 0.068803899 -0.049412999, + -0.044564299 0.069475599 -0.043981001, + -0.044564299 0.071924597 -0.037558001, + -0.045588002 0.071015298 -0.038208, + -0.0465803 0.0725061 -0.032623999, + -0.045588002 0.073406696 -0.031895999, + -0.0465803 0.0748896 -0.026392, + -0.047540501 0.074003398 -0.027201001, + -0.0465803 0.076058403 -0.023231, + -0.044564299 0.077746399 -0.021598, + -0.044564299 0.076609798 -0.024821, + -0.0465803 0.077164501 -0.020179, + -0.048467699 0.075949199 -0.020494999, + -0.050219599 0.074672498 -0.020895001, + -0.051830001 0.073345199 -0.021382, + -0.0532961 0.071978703 -0.021953, + -0.0546159 0.070584401 -0.022606, + -0.055787299 0.069173597 -0.023335001, + -0.056809202 0.067757599 -0.024134001, + -0.0576833 0.066346698 -0.024995999, + -0.058412101 0.065266304 -0.024542, + -0.058998398 0.063580699 -0.026881, + -0.058998398 0.064145803 -0.024174999, + -0.059445001 0.0625422 -0.026564, + -0.059445001 0.063003302 -0.023899, + -0.059757002 0.061493199 -0.026324, + -0.059757002 0.0618596 -0.023715001, + -0.0599402 0.060450502 -0.026165999, + -0.0599402 0.060732398 -0.023622001, + -0.059999999 0.059420101 -0.026109001, + -0.059999999 0.059630901 -0.023642, + -0.0599402 0.05841 -0.026179999, + -0.0599402 0.058564499 -0.023794999, + -0.059757002 0.057430901 -0.026399, + -0.059757002 0.057546299 -0.024103999, + -0.059445001 0.056500401 -0.026784001, + -0.059445001 0.056594301 -0.024579, + -0.058998398 0.055645101 -0.027326001, + -0.058998398 0.055735301 -0.025210001, + -0.058412101 0.054892201 -0.028004, + -0.058412101 0.0549949 -0.025973, + -0.0576833 0.054265101 -0.028798001, + -0.0576833 0.054395199 -0.026845001, + -0.056809202 0.0537838 -0.029682999, + -0.056809202 0.053954199 -0.027799999, + -0.055787299 0.0534641 -0.030633001, + -0.055787299 0.053685501 -0.02881, + -0.0546159 0.053317498 -0.031617999, + -0.0546159 0.053595901 -0.029842, + -0.0532961 0.053348798 -0.032607, + -0.051830001 0.053559799 -0.033572, + -0.050219599 0.053570598 -0.035781, + -0.051042698 0.053660698 -0.034235999, + -0.048467699 0.053501699 -0.037276, + -0.048467699 0.053406298 -0.036986001, + -0.050219599 0.053552601 -0.034722999, + -0.0465803 0.053365201 -0.039450999, + -0.0465803 0.053236101 -0.039167002, + -0.057264499 0.0542261 -0.022786001, + -0.0576833 0.054430299 -0.023125, + -0.056809202 0.054099198 -0.024208, + -0.056809202 0.054088999 -0.022502, + -0.056316901 0.0540215 -0.023914, + -0.056316901 0.0540311 -0.023497, + -0.0424245 0.050999999 -0.042424001, + -0.0425102 0.050999999 -0.042342, + -0.0424264 0.051672 -0.042544, + -0.0429601 0.050999999 -0.041868001, + -0.044564299 0.051677901 -0.040293999, + -0.044564299 0.052320302 -0.040578999, + -0.0465803 0.052333198 -0.038222998, + -0.045588002 0.0528493 -0.039839, + -0.044563901 0.050999999 -0.040174, + -0.046453901 0.050999999 -0.037974, + -0.046577401 0.050999999 -0.037815001, + -0.0470348 0.050999999 -0.037227001, + -0.0465803 0.051684 -0.037939999, + -0.048467699 0.052346699 -0.035773002, + -0.048467699 0.052882399 -0.036192998, + -0.050219599 0.052905399 -0.033654999, + -0.050219599 0.053305 -0.034162, + -0.051830001 0.053340901 -0.031544, + -0.051830001 0.0534923 -0.031817, + -0.052581199 0.053514499 -0.030482, + -0.052581199 0.053631701 -0.030761, + -0.0532961 0.053658601 -0.029410999, + -0.0532961 0.053741202 -0.029689999, + -0.053974401 0.053773601 -0.028325001, + -0.053974401 0.053823099 -0.028593, + -0.0546159 0.053861599 -0.027215, + -0.0546159 0.053875402 -0.027341001, + -0.055220202 0.0539173 -0.025953, + -0.055220202 0.053926501 -0.026072999, + -0.055787299 0.053971902 -0.024676001, + -0.055787299 0.053978499 -0.024901999, + -0.055787299 0.0539543 -0.025320999, + -0.055787299 0.0538464 -0.027038001, + -0.0546159 0.0538208 -0.028113, + -0.056809202 0.054056901 -0.025975, + -0.0576833 0.054446898 -0.024953, + -0.058412101 0.054940298 -0.022102, + -0.058412101 0.055007499 -0.024003999, + -0.051830001 0.0517039 -0.030356999, + -0.051830001 0.052374799 -0.030634999, + -0.050219599 0.051697101 -0.032961, + -0.0506116 0.050999999 -0.032191999, + -0.050211199 0.050999999 -0.032827001, + -0.0499507 0.050999999 -0.033240002, + -0.048467699 0.0516905 -0.035491999, + -0.050219599 0.052360501 -0.033240002, + -0.051830001 0.052928999 -0.031044999, + -0.0532961 0.052953102 -0.028374, + -0.052581199 0.053359199 -0.030212, + -0.0532961 0.053377699 -0.028866, + -0.0532961 0.053536799 -0.029134, + -0.053974401 0.0535594 -0.027773, + -0.053974401 0.053685799 -0.028047999, + -0.058065701 0.054480601 -0.019936999, + -0.058412101 0.054804198 -0.020271, + -0.0576833 0.0543533 -0.021361999, + -0.0576833 0.054224402 -0.019668, + -0.057264499 0.054156601 -0.021086, + -0.057264499 0.054136898 -0.020674, + -0.056809202 0.054083899 -0.022088001, + -0.056809202 0.054063398 -0.021864001, + -0.056316901 0.0540176 -0.023273, + -0.056316901 0.054001801 -0.023154, + -0.055787299 0.0539595 -0.024557, + -0.055787299 0.053939302 -0.024432, + -0.055220202 0.053900301 -0.025827, + -0.055220202 0.053839099 -0.025563, + -0.0546159 0.053806201 -0.026949, + -0.0546159 0.053713098 -0.026674001, + -0.053974401 0.053396299 -0.027507, + -0.0546159 0.052977599 -0.025653001, + -0.0532961 0.052389301 -0.027968001, + -0.051820099 0.050999999 -0.03022, + -0.0529669 0.050999999 -0.028186999, + -0.053669199 0.046 -0.026826, + -0.053284999 0.050999999 -0.027551999, + -0.053653099 0.050999999 -0.026818, + -0.0532961 0.0517109 -0.027691999, + -0.0576833 0.053879999 -0.018284, + -0.0576833 0.054005299 -0.018545, + -0.057264499 0.053851999 -0.019693, + -0.058065701 0.0541359 -0.017385, + -0.058398601 0.050999999 -0.013708, + -0.058866698 0.050999999 -0.011606, + -0.058412101 0.051747002 -0.013861, + -0.058021698 0.046 -0.01528, + -0.058226701 0.050999999 -0.014479, + -0.058007602 0.050999999 -0.015276, + -0.057669599 0.050999999 -0.016505999, + -0.0576833 0.0517397 -0.016657, + -0.058412101 0.052464701 -0.01413, + -0.058998398 0.0524798 -0.011339, + -0.058998398 0.053102799 -0.011714, + -0.059445001 0.053127699 -0.0089349998, + -0.059445001 0.0536438 -0.0093739899, + -0.059757002 0.053681199 -0.0066180001, + -0.059757002 0.0541021 -0.007092, + -0.0599402 0.054156199 -0.0043630102, + -0.0599402 0.0544856 -0.004836, + -0.059999999 0.054561201 -0.0021210001, + -0.059999999 0.0550243 -0.00293201, + -0.0599402 0.055154599 -0.00020700099, + -0.0599402 0.0560988 -0.00182201, + -0.059757002 0.056345101 0.00093600497, + -0.059757002 0.057356399 -0.00079100003, + -0.059445001 0.057723101 0.0020079999, + -0.059445001 0.058791898 0.00015699799, + -0.058998398 0.059280999 0.0029839899, + -0.058998398 0.060394 0.000996002, + -0.058412101 0.061004698 0.0038309901, + -0.058412101 0.0621427 0.00169701, + -0.0576833 0.062872298 0.004522, + -0.0576833 0.064014502 0.00223399, + -0.056809202 0.064858198 0.0050310101, + -0.056809202 0.065982297 0.0025850099, + 0.0546159 0.053861599 -0.027683999, + 0.0546159 0.053820699 -0.028115001, + 0.055220202 0.0539135 -0.026294, + 0.053974401 0.05381 -0.029065, + 0.053974401 0.053817101 -0.028837999, + 0.0532961 0.0537728 -0.030207001, + 0.0532961 0.053760398 -0.029960999, + 0.052581199 0.053722899 -0.031316001, + 0.052581199 0.053683098 -0.031049, + 0.051830001 0.053651702 -0.032388002, + 0.051830001 0.053578801 -0.032109, + 0.0465803 0.052839901 -0.038677, + 0.048467699 0.0528614 -0.036224, + 0.0465803 0.0523258 -0.038260002, + 0.048467699 0.053243201 -0.036724001, + 0.050219599 0.053277198 -0.034180999, + 0.050219599 0.053421799 -0.034453001, + 0.051830001 0.053464498 -0.031831998, + 0.052581199 0.053605098 -0.030772001, + 0.0532961 0.053714801 -0.029696999, + 0.053974401 0.053798299 -0.028594, + 0.0546159 0.053861801 -0.027458999, + 0.051830001 0.052906498 -0.031079, + 0.052581199 0.053330202 -0.030231999, + 0.0532961 0.052930001 -0.028408, + 0.051830001 0.052366398 -0.030676, + 0.050219599 0.052352499 -0.03328, + 0.048467699 0.052338898 -0.035812002, + 0.050219599 0.052883599 -0.033688001, + 0.051830001 0.053312302 -0.031564001, + 0.052581199 0.053486299 -0.030497, + 0.0532961 0.0535083 -0.029149, + 0.0532961 0.0536316 -0.029422, + 0.053974401 0.0536584 -0.028059, + 0.053974401 0.053746901 -0.028332001, + 0.0546159 0.0537792 -0.026955999, + 0.0546159 0.053836498 -0.027216, + 0.055220202 0.053874999 -0.025829, + 0.055220202 0.053906798 -0.026069, + 0.055787299 0.053952102 -0.024672, + 0.056316901 0.0540215 -0.023916001, + 0.056809202 0.054088902 -0.022504, + 0.056316901 0.0540183 -0.023491001, + 0.055787299 0.0539658 -0.024896, + 0.046273202 0.050999999 -0.038194001, + 0.045055199 0.050999999 -0.039597999, + 0.0465803 0.0516828 -0.037951998, + 0.048467699 0.0516891 -0.035505001, + 0.0480907 0.050999999 -0.035879001, + 0.049792401 0.050999999 -0.033477001, + 0.048886999 0.050999999 -0.034754999, + 0.050219599 0.051695701 -0.032974001, + 0.051830001 0.051702499 -0.030370999, + 0.051374301 0.050999999 -0.030995, + 0.0532961 0.0523808 -0.02801, + 0.0546159 0.052953899 -0.025688, + 0.053974401 0.053366501 -0.027527001, + 0.053974401 0.053530499 -0.027788, + 0.0546159 0.053685501 -0.026684999, + 0.0532961 0.053348199 -0.028886, + 0.055220202 0.053811699 -0.02557, + 0.055787299 0.053913701 -0.024434, + 0.056316901 0.053997502 -0.023269, + 0.056809202 0.054071002 -0.022081001, + 0.057264499 0.054156601 -0.021088, + 0.0576833 0.054352801 -0.021374, + 0.056809202 0.069069698 -0.0155, + 0.0576833 0.067582302 -0.016511001, + 0.056809202 0.068969302 -0.016956, + 0.055787299 0.0705764 -0.014562, + 0.055787299 0.070462704 -0.016047001, + 0.0546159 0.072090998 -0.013707, + 0.0546159 0.0719615 -0.015218, + 0.0532961 0.073601998 -0.012942, + 0.0532961 0.073454 -0.014477, + 0.051830001 0.075097002 -0.012274, + 0.051830001 0.074928202 -0.01383, + 0.050219599 0.076563701 -0.011708, + 0.050219599 0.076371498 -0.013282, + 0.048467699 0.077989399 -0.011251, + 0.048467699 0.077771902 -0.01284, + 0.0465803 0.0793624 -0.010905, + 0.0465803 0.079117902 -0.012507, + 0.044564299 0.080670998 -0.010674, + 0.044564299 0.080397896 -0.012286, + 0.0424264 0.081903704 -0.010561, + 0.0424264 0.081600502 -0.012179, + 0.040174201 0.0830492 -0.010568, + 0.040174201 0.082714297 -0.012186, + 0.0378174 0.084097899 -0.01069, + 0.0378174 0.0837299 -0.012303, + 0.035366699 0.085040599 -0.010925, + 0.035366699 0.084638402 -0.012525, + 0.0328326 0.085868597 -0.011267, + 0.0328326 0.084937498 -0.014642, + 0.0302257 0.086091198 -0.013525, + 0.0302257 0.085116297 -0.017051, + 0.027557701 0.086186402 -0.016074, + 0.027557701 0.084218599 -0.023155, + 0.0248404 0.085216299 -0.022348, + 0.0248404 0.083191097 -0.029510999, + 0.0220857 0.084104598 -0.028858, + 0.0220857 0.082010701 -0.036081001, + 0.019305199 0.082831398 -0.035564002, + 0.019305199 0.080670796 -0.042822, + 0.0165099 0.081392303 -0.042420998, + 0.0165099 0.079160802 -0.049693, + 0.0137106 0.079777598 -0.049389999, + 0.0137106 0.077472597 -0.056667998, + 0.0109179 0.077980101 -0.056449, + 0.0109179 0.073180601 -0.070974, + 0.0081421202 0.075987801 -0.063573003, + -0.0328326 0.083941802 -0.018124999, + -0.0328326 0.084941298 -0.014634, + -0.0302257 0.085117199 -0.017051, + -0.0302257 0.083104201 -0.024054, + -0.027557701 0.0842131 -0.023157001, + -0.027557701 0.082159199 -0.030244, + -0.0248404 0.083188601 -0.029509, + -0.0248404 0.081071801 -0.036669999, + -0.0220857 0.0820124 -0.036077, + -0.0220857 0.079828903 -0.043285999, + -0.019305199 0.0806721 -0.042817999, + -0.019305199 0.078421697 -0.050051998, + -0.0165099 0.079161301 -0.049690001, + -0.0165099 0.076841697 -0.056938998, + -0.0137106 0.077472702 -0.056667, + -0.0137106 0.0750755 -0.063919, + -0.0109179 0.075593203 -0.063722998, + -0.0109179 0.073179297 -0.070972003, + -0.0081421202 0.073580898 -0.070837997, + -0.0081421202 0.071343802 -0.078157, + -0.0053918599 0.071629398 -0.078073002, + -0.0053918599 0.0695825 -0.085472003, + -0.00267513 0.069752999 -0.085427999, + -0.00267513 0.0678965 -0.092892997, + 0 0.067953303 -0.092880003, + 0 0.0662883 -0.100398, + 0.00267513 0.067897297 -0.092892997, + 0.00267513 0.069753699 -0.085428998, + 0.0053918599 0.0695839 -0.085473001, + 0.0053918599 0.071630597 -0.078074999, + 0.0081421202 0.071345598 -0.078158997, + 0.0081421202 0.073581897 -0.070839003, + 0.0053918599 0.073862299 -0.070744999, + 0.00267513 0.071797803 -0.078024998, + 0 0.0698089 -0.085414, + -0.00267513 0.0717972 -0.078024, + -0.0053918599 0.073861703 -0.070744, + -0.0081421202 0.075987697 -0.063573003, + -0.0109179 0.077980198 -0.056448001, + -0.0137106 0.079778098 -0.049387999, + -0.0165099 0.081393398 -0.042417001, + -0.019305199 0.082832798 -0.035560001, + -0.0220857 0.084102303 -0.028856, + -0.0248404 0.085211404 -0.02235, + -0.027557701 0.086187199 -0.016074, + -0.0302257 0.0860947 -0.013518, + -0.0328326 0.085871696 -0.011269, + -0.035366699 0.084641799 -0.012528, + -0.035366699 0.085045204 -0.010929, + -0.0378174 0.083734803 -0.012307, + -0.0378174 0.084104799 -0.010695, + -0.040174201 0.082721598 -0.012191, + -0.040174201 0.083058797 -0.010573, + -0.0424264 0.081610598 -0.012184, + -0.0424264 0.081916101 -0.010566, + -0.044564299 0.080410898 -0.012291, + -0.044564299 0.080685899 -0.010679, + -0.0465803 0.079133399 -0.012512, + -0.0465803 0.079379298 -0.010909, + -0.048467699 0.077789597 -0.012845, + -0.048467699 0.0780081 -0.011255, + -0.050219599 0.0763909 -0.013287, + -0.050219599 0.076583698 -0.011713, + -0.051830001 0.074948899 -0.013834, + -0.051830001 0.075118102 -0.012277, + -0.0532961 0.073475704 -0.01448, + -0.0532961 0.073623799 -0.012945, + -0.0546159 0.071983799 -0.015221, + -0.0546159 0.072113402 -0.013709, + -0.055787299 0.070485502 -0.016047999, + -0.055787299 0.070599101 -0.014562, + -0.056809202 0.068992503 -0.016956, + -0.056809202 0.069092698 -0.015498, + -0.0576833 0.067605399 -0.016509, + -0.057264499 0.054109398 -0.020452, + -0.057264499 0.054057099 -0.020212, + -0.0576833 0.054155398 -0.019037001, + -0.0576833 0.054189902 -0.019258, + -0.058065701 0.054242998 -0.017841, + -0.058065701 0.054292198 -0.018248999, + -0.058412101 0.054359999 -0.016829999, + -0.058412101 0.054607801 -0.018513, + -0.058998398 0.055177201 -0.017424, + -0.055787299 0.069319002 -0.00137601, + -0.055787299 0.068929598 1.8005399e-005, + -0.0546159 0.070521303 0.00124899, + -0.0546159 0.070912398 -0.000190994, + -0.0532961 0.072146297 0.0023739899, + -0.0532961 0.072534502 0.00088900799, + -0.051830001 0.073792003 0.0033829999, + -0.051830001 0.074173003 0.001854, + -0.050219599 0.075445198 0.0042660101, + -0.050219599 0.0758145 0.00269501, + -0.048467699 0.077092297 0.0050140098, + -0.048467699 0.077445202 0.00340199, + -0.0465803 0.078719497 0.00562, + -0.0465803 0.079051502 0.00397, + -0.044564299 0.080312803 0.0060780002, + -0.044564299 0.080619603 0.0043930099, + -0.0424264 0.081858002 0.0063820002, + -0.0424264 0.082135797 0.0046660001, + -0.040174201 0.083341599 0.0065310099, + -0.040174201 0.083586402 0.0047860001, + -0.0378174 0.084751002 0.0065219998, + -0.0378174 0.084958903 0.0047530099, + -0.035366699 0.086073898 0.006356, + -0.035366699 0.086242102 0.0045679901, + -0.0328326 0.087298997 0.0060350001, + -0.0328326 0.087424599 0.0042319898, + -0.0302257 0.0884156 0.005562, + -0.0302257 0.088496096 0.0037479999, + -0.027557701 0.0894152 0.0049419999, + -0.027557701 0.0894484 0.00312199, + -0.0248404 0.090290301 0.0041809999, + -0.0248404 0.0902749 0.00236, + -0.0220857 0.091034397 0.0032850001, + -0.0220857 0.090969399 0.001467, + -0.019305199 0.091642201 0.00226199, + -0.019305199 0.091526903 0.00044999699, + -0.0165099 0.092110701 0.001119, + -0.0165099 0.091944702 -0.000682007, + -0.0137106 0.092438199 -0.000132004, + -0.0137106 0.092221297 -0.001916, + -0.0109179 0.092623301 -0.001481, + -0.0109179 0.092355803 -0.00324001, + -0.0081421202 0.092665702 -0.0029129901, + -0.0081421202 0.092347898 -0.00464101, + -0.0053918599 0.0925669 -0.0044170101, + -0.0053918599 0.091771401 -0.0080249896, + -0.00267513 0.091902398 -0.0078979898, + -0.00267513 0.091036402 -0.011645, + 0 0.091080002 -0.011605, + 0 0.089285403 -0.019056, + 0.00267513 0.091036297 -0.011645, + 0.00267513 0.0919021 -0.0078990003, + 0.0053918599 0.091770798 -0.0080260001, + 0.0576833 0.066578001 -0.00535201, + 0.056809202 0.067747697 -0.00266499, + 0.0576833 0.0658748 -0.00272301, + 0.058412101 0.064808197 -0.0054569999, + 0.058412101 0.064053401 -0.002965, + 0.058998398 0.063098103 -0.0057290001, + 0.058998398 0.062313002 -0.0033760101, + 0.059445001 0.061475299 -0.0061530001, + 0.059445001 0.060679901 -0.0039369999, + 0.059757002 0.059964199 -0.0067070001, + 0.059757002 0.059177101 -0.004623, + 0.0599402 0.058584601 -0.007373, + 0.0599402 0.0578226 -0.0054139998, + 0.059999999 0.057348799 -0.0081519904, + 0.059999999 0.056629401 -0.0063060001, + 0.0599402 0.056270398 -0.0090469997, + 0.0599402 0.055609401 -0.0073060002, + 0.059757002 0.0553631 -0.010063, + 0.059757002 0.054762799 -0.008405, + 0.059445001 0.054629799 -0.011188, + 0.059445001 0.054304902 -0.010349, + 0.058998398 0.054226901 -0.013152, + 0.058998398 0.053962 -0.012664, + 0.058722898 0.054187801 -0.014561, + 0.058412101 0.0541486 -0.015973, + 0.058412101 0.0539065 -0.015477, + 0.058412101 0.053535402 -0.014986, + 0.0576833 0.053497501 -0.017796, + 0.0576833 0.0530276 -0.017349999, + 0.056809202 0.053002901 -0.020148, + 0.057264499 0.053823002 -0.019704999, + 0.056809202 0.0537953 -0.021111, + 0.057264499 0.0539435 -0.019964, + 0.0576833 0.05407 -0.018801, + 0.056809202 0.069120303 -0.012587, + 0.0576833 0.0676165 -0.013664, + 0.056809202 0.069119997 -0.014042, + 0.055787299 0.070649698 -0.011586, + 0.055787299 0.070638701 -0.013075, + 0.0546159 0.072193302 -0.010672, + 0.0546159 0.072168604 -0.012191, + 0.0532961 0.073739201 -0.0098520098, + 0.0532961 0.073697299 -0.0114, + 0.051830001 0.075274497 -0.0091340002, + 0.051830001 0.075212799 -0.010708, + 0.050219599 0.076786697 -0.0085239997, + 0.050219599 0.076702498 -0.010121, + 0.048467699 0.078263097 -0.0080290101, + 0.048467699 0.0781537 -0.0096460003, + 0.0465803 0.079691298 -0.0076519898, + 0.0465803 0.079554103 -0.0092860004, + 0.044564299 0.081058703 -0.007396, + 0.044564299 0.0808919 -0.0090429997, + 0.0424264 0.082353599 -0.0072650001, + 0.0424264 0.082155302 -0.0089220004, + 0.040174201 0.083564296 -0.0072599901, + 0.040174201 0.083333097 -0.008924, + 0.0378174 0.084681101 -0.0073799998, + 0.0378174 0.084415503 -0.009048, + 0.035366699 0.085694604 -0.0076250001, + 0.035366699 0.085393198 -0.0092899902, + 0.0328326 0.086595602 -0.0079900101, + 0.0328326 0.086257197 -0.0096460003, + 0.0302257 0.087375604 -0.0084699998, + 0.0302257 0.086999401 -0.01011, + 0.027557701 0.0880289 -0.0090570096, + 0.027557701 0.087141499 -0.012509, + 0.0248404 0.088087 -0.011593, + 0.0248404 0.087149799 -0.015194, + 0.0220857 0.088004798 -0.014413, + 0.0220857 0.086101897 -0.021632001, + 0.019305199 0.086874403 -0.021007, + 0.019305199 0.0849014 -0.028287999, + 0.0165099 0.085582897 -0.027801, + 0.0165099 0.083533503 -0.035121001, + 0.0137106 0.084118903 -0.034751002, + 0.0137106 0.081993803 -0.042086001, + 0.0109179 0.082477704 -0.041816998, + 0.0109179 0.0802738 -0.049146999, + 0.0081421202 0.0806517 -0.048962001, + 0.0081421202 0.078366697 -0.056281999, + 0.0053918599 0.0786369 -0.056164999, + 0.0053918599 0.076263398 -0.063468002, + 0.00267513 0.076425202 -0.063405998, + 0.00267513 0.074026801 -0.070689, + 0 0.0740804 -0.070671, + 0 0.0718522 -0.078008004, + -0.00267513 0.074026503 -0.070689, + -0.00267513 0.076425098 -0.063405998, + -0.0053918599 0.076263398 -0.063468002, + -0.0053918599 0.078636996 -0.056164999, + -0.0081421202 0.078366801 -0.056281, + -0.0081421202 0.080651999 -0.048960999, + -0.0109179 0.080274098 -0.049146, + -0.0109179 0.082478397 -0.041815002, + -0.0137106 0.081994802 -0.042082999, + -0.0137106 0.084119901 -0.034749001, + -0.0165099 0.083534703 -0.035117, + -0.0165099 0.085581198 -0.027798999, + -0.019305199 0.084899403 -0.028286001, + -0.019305199 0.086870603 -0.021008, + -0.0220857 0.086097501 -0.021632999, + -0.0220857 0.088005498 -0.014413, + -0.0248404 0.087150499 -0.015194, + -0.0248404 0.088089898 -0.011587, + -0.027557701 0.087144703 -0.012502, + -0.027557701 0.088031597 -0.0090590101, + -0.0302257 0.0870023 -0.010112, + -0.0302257 0.087379597 -0.0084739998, + -0.0328326 0.086261503 -0.0096499901, + -0.0328326 0.086601503 -0.0079950001, + -0.035366699 0.085399598 -0.0092949998, + -0.035366699 0.085703 -0.0076299999, + -0.0378174 0.084424503 -0.00905299, + -0.0378174 0.084692098 -0.0073849899, + -0.040174201 0.083344802 -0.0089290002, + -0.040174201 0.083577797 -0.0072640101, + -0.0424264 0.082169503 -0.0089269998, + -0.0424264 0.082369097 -0.0072690002, + -0.044564299 0.080908097 -0.009048, + -0.044564299 0.081075899 -0.0073999902, + -0.0465803 0.079572 -0.0092899902, + -0.0465803 0.079709798 -0.0076560099, + -0.048467699 0.078172997 -0.0096499901, + -0.048467699 0.078282803 -0.0080319997, + -0.050219599 0.076722898 -0.010125, + -0.050219599 0.076807298 -0.0085269902, + -0.051830001 0.075234003 -0.01071, + -0.051830001 0.075295702 -0.0091349902, + -0.0532961 0.073719099 -0.011401, + -0.0532961 0.073760897 -0.0098520098, + -0.0546159 0.072190799 -0.012191, + -0.0546159 0.072215401 -0.010671, + -0.055787299 0.070661299 -0.013073, + -0.055787299 0.070672102 -0.011584, + -0.056809202 0.069142804 -0.01404, + -0.056809202 0.0691429 -0.012583, + -0.0576833 0.067639098 -0.01366, + 0.056809202 0.068970896 -0.0096909897, + 0.0576833 0.067457199 -0.010842, + 0.056809202 0.0690706 -0.011135, + 0.055787299 0.070517004 -0.0086190002, + 0.055787299 0.0706091 -0.0101, + 0.0546159 0.072084099 -0.0076369899, + 0.0546159 0.072165102 -0.0091530001, + 0.0532961 0.073660098 -0.0067530102, + 0.0532961 0.073726803 -0.0083020004, + 0.051830001 0.075232498 -0.0059750099, + 0.051830001 0.0752813 -0.0075559998, + 0.050219599 0.076788202 -0.0053119999, + 0.050219599 0.076815598 -0.0069200001, + 0.048467699 0.078313701 -0.0047680102, + 0.048467699 0.0783168 -0.0064019901, + 0.0465803 0.079796501 -0.0043500098, + 0.0465803 0.079772398 -0.0060060001, + 0.044564299 0.081223898 -0.0040600002, + 0.044564299 0.081169903 -0.0057339901, + 0.0424264 0.0825831 -0.0039009999, + 0.0424264 0.0824968 -0.0055900002, + 0.040174201 0.083861798 -0.00387601, + 0.040174201 0.083741099 -0.0055760001, + 0.0378174 0.085049704 -0.0039839898, + 0.0378174 0.0848931 -0.005692, + 0.035366699 0.086136997 -0.004224, + 0.035366699 0.085943103 -0.0059349998, + 0.0328326 0.087114498 -0.0045939898, + 0.0328326 0.086881898 -0.00630499, + 0.0302257 0.087973297 -0.0050909999, + 0.0302257 0.087700799 -0.0067960098, + 0.027557701 0.088707 -0.0057079899, + 0.027557701 0.0883938 -0.0073999902, + 0.0248404 0.0893104 -0.0064369999, + 0.0248404 0.0889557 -0.0081089903, + 0.0220857 0.089778297 -0.0072670002, + 0.0220857 0.0889263 -0.010781, + 0.019305199 0.089658402 -0.010072, + 0.019305199 0.088750698 -0.013732, + 0.0165099 0.089388803 -0.01315, + 0.0165099 0.087535098 -0.020473, + 0.0137106 0.088086002 -0.020027, + 0.0137106 0.086151198 -0.027394, + 0.0109179 0.086608298 -0.027067, + 0.0109179 0.084589697 -0.034453999, + 0.0081421202 0.084948398 -0.034228001, + 0.0081421202 0.082846299 -0.041611999, + 0.0053918599 0.083103999 -0.041467998, + 0.0053918599 0.080915898 -0.048831999, + 0.00267513 0.0810709 -0.048756, + 0.00267513 0.0787955 -0.056097001, + 0 0.078847297 -0.056074001, + 0 0.076477997 -0.063386001, + -0.00267513 0.0787955 -0.056097001, + -0.00267513 0.081070997 -0.048756, + -0.0053918599 0.080916099 -0.048831999, + -0.0053918599 0.083104298 -0.041467, + -0.0081421202 0.082846902 -0.041609999, + -0.0081421202 0.084949002 -0.034226, + -0.0109179 0.084590502 -0.034451999, + -0.0109179 0.086607099 -0.027066, + -0.0137106 0.086149797 -0.027393, + -0.0137106 0.088083297 -0.020028001, + -0.0165099 0.087531902 -0.020474, + -0.0165099 0.089389302 -0.01315, + -0.019305199 0.088751301 -0.013732, + -0.019305199 0.089660697 -0.010067, + -0.0220857 0.088928796 -0.010775, + -0.0220857 0.089780398 -0.0072690002, + -0.0248404 0.088958099 -0.0081109898, + -0.0248404 0.089313596 -0.0064400001, + -0.027557701 0.088397399 -0.0074040098, + -0.027557701 0.088711999 -0.00571201, + -0.0302257 0.087706298 -0.0068000001, + -0.0302257 0.087980501 -0.0050949999, + -0.0328326 0.086889699 -0.0063090101, + -0.0328326 0.087124102 -0.0045969998, + -0.035366699 0.0859534 -0.0059389998, + -0.035366699 0.086148903 -0.0042270101, + -0.0378174 0.084905699 -0.0056950101, + -0.0378174 0.085063502 -0.0039880099, + -0.040174201 0.083755799 -0.0055800001, + -0.040174201 0.083877303 -0.00388, + -0.0424264 0.082513101 -0.00559399, + -0.0424264 0.082599998 -0.0039049999, + -0.044564299 0.081187703 -0.0057380102, + -0.044564299 0.081242003 -0.004063, + -0.0465803 0.0797913 -0.0060089999, + -0.0465803 0.079815499 -0.0043520099, + -0.048467699 0.078336596 -0.0064040101, + -0.048467699 0.078333497 -0.0047690002, + -0.050219599 0.076836102 -0.0069220001, + -0.050219599 0.076808602 -0.0053119999, + -0.051830001 0.0753024 -0.0075559998, + -0.051830001 0.075253502 -0.0059739999, + -0.0532961 0.073748402 -0.0083009899, + -0.0532961 0.073681504 -0.0067510102, + -0.0546159 0.072187103 -0.0091509996, + -0.0546159 0.072105698 -0.0076330001, + -0.055787299 0.070631199 -0.010097, + -0.055787299 0.070538796 -0.0086150104, + -0.056809202 0.069092803 -0.01113, + -0.056809202 0.068992697 -0.0096850004, + -0.0576833 0.067478903 -0.010835, + -0.059445001 0.0559217 -0.01643, + -0.059445001 0.0555479 -0.014595, + -0.059757002 0.0564055 -0.013634, + -0.059757002 0.056825802 -0.015565, + -0.0599402 0.057418302 -0.012815, + -0.0599402 0.057868201 -0.01485, + -0.059999999 0.058568899 -0.012138, + -0.059999999 0.059031099 -0.014285, + -0.0599402 0.059842501 -0.011595, + -0.0599402 0.060299002 -0.01386, + -0.059757002 0.061225601 -0.011179, + -0.059757002 0.0616588 -0.013562, + -0.059445001 0.0627046 -0.010881, + -0.059445001 0.0630963 -0.013384, + -0.058998398 0.064257301 -0.010717, + -0.058998398 0.064589597 -0.013335, + -0.058412101 0.065857902 -0.010698, + -0.058412101 0.066112503 -0.013425, + 0.058412101 0.066090599 -0.013432, + 0.058412101 0.065837301 -0.010708, + 0.058998398 0.064568803 -0.013344, + 0.058998398 0.064237997 -0.010728, + 0.059445001 0.063076802 -0.013395, + 0.059445001 0.062686898 -0.010894, + 0.059757002 0.0616409 -0.013575, + 0.059757002 0.061209701 -0.011193, + 0.0599402 0.060283098 -0.013874, + 0.0599402 0.059828699 -0.011611, + 0.059999999 0.0590172 -0.0143, + 0.059999999 0.058557302 -0.012154, + 0.0599402 0.057856601 -0.014866, + 0.0599402 0.057408702 -0.012831, + 0.059757002 0.056816202 -0.015581, + 0.059757002 0.056397598 -0.013649, + 0.059445001 0.055913702 -0.016446, + 0.059445001 0.055541899 -0.014608, + 0.058998398 0.055171199 -0.017437, + 0.058998398 0.054861199 -0.015682001, + 0.058412101 0.054607298 -0.018525001, + 0.055220202 0.0534034 -0.02478, + 0.0546159 0.0533849 -0.026157999, + 0.055220202 0.0537127 -0.025302, + 0.055787299 0.053740099 -0.023910999, + 0.055787299 0.0538445 -0.024177, + 0.056809202 0.053910401 -0.021372, + 0.056316901 0.053952601 -0.023032, + 0.058065701 0.054292198 -0.018251, + 0.0576833 0.054224402 -0.01967, + 0.0576833 0.054176901 -0.019251, + 0.057264499 0.054123901 -0.020667, + 0.057264499 0.054088999 -0.020447999, + 0.056809202 0.0540432 -0.02186, + 0.056809202 0.053991601 -0.021624999, + 0.057264499 0.054030798 -0.020214001, + 0.0576833 0.054134902 -0.019033, + 0.058065701 0.0542299 -0.017834, + 0.058412101 0.054359999 -0.016832, + 0.058722898 0.054427698 -0.015415, + 0.058412101 0.054282799 -0.016417, + 0.058065701 0.054180801 -0.017617, + 0.055787299 0.053422 -0.023393, + 0.055787299 0.0529783 -0.022931, + 0.056809202 0.0534596 -0.020602001, + 0.055787299 0.0524102 -0.022543, + 0.0546159 0.0523954 -0.025296001, + 0.0546159 0.051716499 -0.024993001, + 0.054163702 0.050999999 -0.025813, + 0.0532961 0.051709399 -0.027705999, + 0.055771399 0.050999999 -0.022079, + 0.055364501 0.050999999 -0.023125, + 0.055787299 0.051723599 -0.022241, + 0.054964401 0.050999999 -0.024021, + 0.056809202 0.052425198 -0.019765999, + 0.0576833 0.0524402 -0.016973, + 0.058412101 0.053052399 -0.014548, + 0.058998398 0.053573199 -0.012182, + 0.059445001 0.054017201 -0.0098689999, + 0.059757002 0.054382 -0.0075750002, + 0.0599402 0.054894101 -0.005659, + 0.059999999 0.0558539 -0.0045700101, + 0.0599402 0.0569885 -0.0035659899, + 0.059757002 0.0583001 -0.00265401, + 0.059445001 0.059777599 -0.001836, + 0.058998398 0.061403301 -0.00113699, + 0.058412101 0.063156098 -0.000582001, + 0.0576833 0.065010898 -0.000195007, + 0.056809202 0.066939801 5.9967001e-006, + 0.055787299 0.068911299 7.9956098e-006, + 0.055787299 0.069300003 -0.001386, + 0.0546159 0.070502698 0.001239, + 0.0546159 0.070893101 -0.000199997, + 0.0532961 0.072127499 0.0023650101, + 0.0532961 0.0725151 0.00088099699, + 0.051830001 0.073773101 0.0033760101, + 0.051830001 0.074153498 0.00184801, + 0.050219599 0.0754264 0.0042599901, + 0.050219599 0.075795203 0.00269, + 0.048467699 0.077073701 0.0050090002, + 0.048467699 0.077426299 0.00339799, + 0.0465803 0.078701302 0.0056159999, + 0.0465803 0.079033002 0.0039670002, + 0.044564299 0.080295101 0.0060749999, + 0.044564299 0.0806017 0.0043910099, + 0.0424264 0.081840999 0.0063809999, + 0.0424264 0.082118601 0.0046649901, + 0.040174201 0.083325401 0.0065299999, + 0.040174201 0.083570004 0.0047860001, + 0.0378174 0.084735602 0.0065219998, + 0.0378174 0.084943399 0.0047539999, + 0.035366699 0.086059399 0.00635699, + 0.035366699 0.086227603 0.0045700101, + 0.0328326 0.087285601 0.0060370001, + 0.0328326 0.087411299 0.0042339899, + 0.0302257 0.088403396 0.005564, + 0.0302257 0.088484101 0.0037510099, + 0.027557701 0.089404203 0.0049439999, + 0.027557701 0.089437798 0.003125, + 0.0248404 0.090280697 0.004183, + 0.0248404 0.090265803 0.0023620001, + 0.0220857 0.091026403 0.0032870001, + 0.0220857 0.090962 0.00146899, + 0.019305199 0.091635801 0.00226401, + 0.019305199 0.091521204 0.00045199599, + 0.0165099 0.092105903 0.001121, + 0.0165099 0.091940701 -0.00067999301, + 0.0137106 0.092434898 -0.00013000501, + 0.0137106 0.092218801 -0.001914, + 0.0109179 0.092621297 -0.001479, + 0.0109179 0.092354402 -0.00323801, + 0.0081421202 0.092664599 -0.0029120001, + 0.0081421202 0.0923471 -0.0046399999, + 0.0053918599 0.092566401 -0.0044160001, + 0.00267513 0.092695102 -0.0042849998, + 0 0.091945097 -0.0078569902, + -0.00267513 0.0926954 -0.0042849998, + -0.0053918599 0.092882201 -0.002685, + -0.0081421202 0.092929497 -0.001149, + -0.0109179 0.092835002 0.00030999799, + -0.0137106 0.092597596 0.001677, + -0.0165099 0.092217699 0.0029420001, + -0.019305199 0.091697 0.004092, + -0.0220857 0.091037497 0.0051199999, + -0.0248404 0.090242498 0.00601601, + -0.027557701 0.089317799 0.0067729899, + -0.0302257 0.088270597 0.0073839999, + -0.0328326 0.087108798 0.0078439899, + -0.035366699 0.085841201 0.0081460001, + -0.0378174 0.084478699 0.008289, + -0.040174201 0.083033502 0.0082710003, + -0.0424264 0.081518099 0.0080920001, + -0.044564299 0.079944901 0.0077519999, + -0.0465803 0.078327999 0.0072570001, + -0.048467699 0.076681897 0.00661, + -0.050219599 0.075020596 0.0058200099, + -0.051830001 0.073357902 0.004892, + -0.0532961 0.071707197 0.0038379999, + -0.0546159 0.070082001 0.002666, + -0.055787299 0.0684947 0.00138901, + -0.056809202 0.066956699 1.89972e-005, + -0.059757002 0.054762799 -0.0084030004, + -0.059757002 0.0544094 -0.0075730002, + -0.0599402 0.054894101 -0.005657, + -0.0599402 0.055610001 -0.0072940099, + -0.059999999 0.055854399 -0.0045579998, + -0.059999999 0.056635499 -0.0062930002, + -0.0599402 0.056994598 -0.00355299, + -0.0599402 0.057830598 -0.0053979899, + -0.059757002 0.058308098 -0.0026390101, + -0.059757002 0.059186701 -0.0046069901, + -0.059445001 0.059787098 -0.00182001, + -0.059445001 0.060691401 -0.0039210101, + -0.058998398 0.061414801 -0.001121, + -0.058998398 0.062326599 -0.00336099, + -0.058412101 0.063169599 -0.000567001, + -0.058412101 0.064068899 -0.0029509999, + -0.0576833 0.065026298 -0.000181, + -0.0576833 0.065892003 -0.0027109999, + -0.056809202 0.067766301 -0.002655, + -0.056809202 0.0681054 -0.0040259999, + -0.055787299 0.069661401 -0.0027920101, + -0.0546159 0.071253799 -0.001651, + -0.0532961 0.072870903 -0.00061399798, + -0.051830001 0.074499898 0.00030900599, + -0.050219599 0.076127499 0.0011089901, + -0.048467699 0.077739902 0.0017790101, + -0.0465803 0.079323597 0.0023119999, + -0.044564299 0.080865398 0.0027020001, + -0.0424264 0.082351297 0.0029460001, + -0.040174201 0.083767898 0.0030410001, + -0.0378174 0.085103303 0.0029869999, + -0.035366699 0.0863465 0.002786, + -0.0328326 0.087486498 0.0024379999, + -0.0302257 0.088513099 0.0019470101, + -0.027557701 0.089419097 0.001317, + -0.0248404 0.090198003 0.00055499299, + -0.0220857 0.090844199 -0.00033299299, + -0.019305199 0.091352798 -0.001341, + -0.0165099 0.091721401 -0.0024570001, + -0.0137106 0.091948897 -0.003668, + -0.0109179 0.092034496 -0.0049620098, + -0.0081421202 0.091548003 -0.0082409997, + -0.0053918599 0.090902798 -0.011767, + -0.00267513 0.089239903 -0.019092999, + 0 0.087388903 -0.026508, + 0.00267513 0.089240499 -0.019092999, + 0.0053918599 0.090902597 -0.011767, + 0.0081421202 0.091547102 -0.0082430001, + 0.0109179 0.092033401 -0.0049609998, + 0.0137106 0.091947101 -0.003666, + 0.0165099 0.091718398 -0.00245399, + 0.019305199 0.091348201 -0.001339, + 0.0220857 0.090837799 -0.00033099399, + 0.0248404 0.090189703 0.00055799901, + 0.027557701 0.089409001 0.0013200101, + 0.0302257 0.088501498 0.00194901, + 0.0328326 0.0874734 0.00244, + 0.035366699 0.086332098 0.00278799, + 0.0378174 0.085087799 0.0029889999, + 0.040174201 0.083751403 0.0030420099, + 0.0424264 0.082334101 0.0029460001, + 0.044564299 0.080847397 0.0027010001, + 0.0465803 0.079304896 0.0023099999, + 0.048467699 0.077720597 0.001776, + 0.050219599 0.0761078 0.001105, + 0.051830001 0.074479997 0.00030400101, + 0.0532961 0.072850898 -0.00062100199, + 0.0546159 0.071233898 -0.0016589999, + 0.055787299 0.069641702 -0.0028009899, + 0.056809202 0.068378702 -0.0054259901, + -0.056809202 0.068644904 -0.006825, + -0.056809202 0.068843201 -0.0082489904, + -0.0576833 0.067129299 -0.0080559999, + -0.055787299 0.070200197 -0.0056770002, + -0.055787299 0.070395 -0.0071399999, + -0.0546159 0.071784198 -0.004619, + -0.0546159 0.071971402 -0.0061219898, + -0.0532961 0.073384501 -0.0036629899, + -0.0532961 0.073560201 -0.0052039898, + -0.051830001 0.074988201 -0.00281799, + -0.051830001 0.075148799 -0.0043939999, + -0.050219599 0.076582402 -0.0020910001, + -0.050219599 0.076724097 -0.003701, + -0.048467699 0.078153603 -0.0014909999, + -0.048467699 0.078272797 -0.0031300001, + -0.0465803 0.079688698 -0.001021, + -0.0465803 0.079781599 -0.002688, + -0.044564299 0.081174098 -0.00068699598, + -0.044564299 0.081237704 -0.00237801, + -0.0424264 0.082596801 -0.00049200398, + -0.0424264 0.082628302 -0.002203, + -0.040174201 0.083944097 -0.000438004, + -0.040174201 0.083940603 -0.0021649899, + -0.0378174 0.085204698 -0.00052400201, + -0.0378174 0.085163698 -0.002263, + -0.035366699 0.086368002 -0.00075000001, + -0.035366699 0.086287603 -0.0024969899, + -0.0328326 0.087423898 -0.00111301, + -0.0328326 0.0873027 -0.0028650099, + -0.0302257 0.088363402 -0.0016120001, + -0.0302257 0.088200197 -0.003364, + -0.027557701 0.089179799 -0.0022410001, + -0.027557701 0.0889735 -0.0039900099, + -0.0248404 0.089867398 -0.002995, + -0.0248404 0.089617401 -0.004733, + -0.0220857 0.090420902 -0.0038640001, + -0.0220857 0.090126798 -0.0055850102, + -0.019305199 0.090836197 -0.0048389998, + -0.019305199 0.090497799 -0.0065350002, + -0.0165099 0.091111399 -0.005907, + -0.0165099 0.090286598 -0.0094609996, + -0.0137106 0.090808503 -0.00895599, + -0.0137106 0.089921199 -0.012664, + -0.0109179 0.090349101 -0.012273, + -0.0109179 0.088526897 -0.019669, + -0.0081421202 0.0888649 -0.019396, + -0.0081421202 0.086955599 -0.026818, + -0.0053918599 0.087199099 -0.026644001, + -0.0053918599 0.085199498 -0.034068, + -0.00267513 0.085346498 -0.033976, + -0.00267513 0.083255403 -0.041382998, + 0 0.083304599 -0.041356001, + 0 0.081121601 -0.048730999, + 0.00267513 0.083255202 -0.041384, + 0.00267513 0.085346296 -0.033976, + 0.0053918599 0.085199103 -0.034069002, + 0.0053918599 0.087199703 -0.026644001, + 0.0081421202 0.086956397 -0.026818, + 0.0081421202 0.088866502 -0.019396, + 0.0109179 0.088529103 -0.019669, + 0.0109179 0.090348803 -0.012273, + 0.0137106 0.089920796 -0.012664, + 0.0137106 0.090806901 -0.0089600096, + 0.0165099 0.090284698 -0.0094649997, + 0.0165099 0.091109797 -0.00590601, + 0.019305199 0.090495899 -0.0065330002, + 0.019305199 0.090833701 -0.004836, + 0.0220857 0.090124004 -0.0055820001, + 0.0220857 0.090416901 -0.0038609901, + 0.0248404 0.089612901 -0.0047289999, + 0.0248404 0.0898614 -0.002991, + 0.027557701 0.088966899 -0.0039859898, + 0.027557701 0.0891717 -0.0022380101, + 0.0302257 0.088191301 -0.00336099, + 0.0302257 0.088353299 -0.00160899, + 0.0328326 0.087291799 -0.0028609899, + 0.0328326 0.087411903 -0.00111, + 0.035366699 0.086274698 -0.0024929999, + 0.035366699 0.0863543 -0.00074600201, + 0.0378174 0.085149102 -0.00225999, + 0.0378174 0.085189603 -0.00052099599, + 0.040174201 0.083924599 -0.0021619999, + 0.040174201 0.083927803 -0.00043499799, + 0.0424264 0.082611002 -0.0022, + 0.0424264 0.082579397 -0.00049000501, + 0.044564299 0.081219502 -0.0023760099, + 0.044564299 0.081155799 -0.00068600499, + 0.0465803 0.079762504 -0.002687, + 0.0465803 0.079669699 -0.001021, + 0.048467699 0.078253001 -0.0031300001, + 0.048467699 0.078134 -0.001492, + 0.050219599 0.076703802 -0.003702, + 0.050219599 0.076562203 -0.0020939901, + 0.051830001 0.075127997 -0.0043959999, + 0.051830001 0.074967697 -0.0028210001, + 0.0532961 0.073538996 -0.0052069998, + 0.0532961 0.073363602 -0.003668, + 0.0546159 0.071950004 -0.0061269999, + 0.0546159 0.071763203 -0.0046250001, + 0.055787299 0.070373498 -0.0071459999, + 0.055787299 0.070179299 -0.0056830002, + 0.056809202 0.0688219 -0.0082559995, + 0.0576833 0.067108899 -0.0080650002, + 0.058412101 0.065406598 -0.0080429995, + 0.058998398 0.063744202 -0.0081840102, + 0.059445001 0.062148798 -0.0084760003, + 0.059757002 0.0606465 -0.0088999895, + 0.0599402 0.059257999 -0.0094409902, + 0.059999999 0.057996601 -0.010102, + 0.0599402 0.056875002 -0.01089, + 0.059757002 0.055908501 -0.011809, + 0.059445001 0.055113502 -0.012858, + 0.058998398 0.054495301 -0.014001, + 0.058722898 0.054335799 -0.015002, + 0.058412101 0.0542267 -0.016202001, + 0.058065701 0.054109301 -0.017387001, + 0.0576833 0.0538508 -0.018296, + -0.058412101 0.065425701 -0.0080319997, + -0.058998398 0.063761801 -0.0081710098, + -0.059445001 0.062164601 -0.00846201, + -0.059757002 0.060660299 -0.0088849897, + -0.0599402 0.0592697 -0.0094250003, + -0.059999999 0.058006302 -0.010086, + -0.0599402 0.056883 -0.010875, + -0.059757002 0.055914599 -0.011796, + -0.059445001 0.055114102 -0.012846, + -0.058998398 0.054861799 -0.01567, + -0.058998398 0.054495402 -0.013999, + -0.058722898 0.054349098 -0.015009, + -0.058998398 0.055432498 -0.019257, + -0.059445001 0.0562253 -0.018352, + -0.059757002 0.057162002 -0.017584, + -0.0599402 0.0582196 -0.016975001, + -0.059999999 0.059379499 -0.016519999, + -0.0599402 0.060626701 -0.016208, + -0.059757002 0.061947599 -0.016023001, + -0.059445001 0.063329302 -0.015954001, + -0.058998398 0.064749397 -0.016008999, + -0.058412101 0.066183202 -0.016193001, + 0.058412101 0.066160403 -0.016197, + 0.058998398 0.064727299 -0.016016001, + 0.059445001 0.063308299 -0.015964, + 0.059757002 0.061928 -0.016034, + 0.0599402 0.060608801 -0.016221, + 0.059999999 0.0593636 -0.016535001, + 0.0599402 0.058205798 -0.01699, + 0.059757002 0.057150401 -0.0176, + 0.059445001 0.0562158 -0.018368, + 0.058998398 0.055424701 -0.019272, + 0.058412101 0.054798301 -0.020284001, + 0.052201699 0.050999999 -0.029544, + 0.0528326 0.050999999 -0.028438, + 0.053282399 0.050999999 -0.027550999, + 0.054979 0.046 -0.024026999, + 0.054601099 0.050999999 -0.024834, + 0.056432001 0.050999999 -0.020382, + 0.056809202 0.0517308 -0.019464999, + 0.0576673 0.050999999 -0.016504999, + 0.0573637 0.050999999 -0.017589999, + 0.0576833 0.051738098 -0.016673001, + 0.057145901 0.050999999 -0.018243, + 0.058412101 0.052455299 -0.014176, + 0.058998398 0.053077199 -0.011752, + 0.059445001 0.053610899 -0.0093970001, + 0.059757002 0.0540719 -0.0071040001, + 0.0599402 0.0544581 -0.0048380001, + 0.059999999 0.0550243 -0.00293401, + 0.0599402 0.056098301 -0.001834, + 0.059757002 0.0573503 -0.000804001, + 0.059445001 0.058784001 0.000141998, + 0.058998398 0.060384501 0.00098100305, + 0.058412101 0.062131301 0.00168201, + 0.0576833 0.064001203 0.0022189899, + 0.056809202 0.065967202 0.00257201, + 0.055787299 0.067999199 0.002722, + 0.055787299 0.067478903 0.0040379898, + 0.0546159 0.0690488 0.0054120002, + 0.0546159 0.069578998 0.0040469998, + 0.0532961 0.070665799 0.0066809999, + 0.0532961 0.071201302 0.0052680098, + 0.051830001 0.072317801 0.00783299, + 0.051830001 0.072853997 0.0063709999, + 0.050219599 0.0739922 0.0088550001, + 0.050219599 0.074523903 0.0073459898, + 0.048467699 0.075675197 0.0097380104, + 0.048467699 0.0761972 0.0081820097, + 0.0465803 0.077352799 0.010473, + 0.0465803 0.077860303 0.0088719903, + 0.044564299 0.079011098 0.011052, + 0.044564299 0.0794992 0.0094090002, + 0.0424264 0.080635697 0.01147, + 0.0424264 0.081099398 0.0097859995, + 0.040174201 0.0822118 0.011721, + 0.040174201 0.082646199 0.010001, + 0.0378174 0.083725996 0.011803, + 0.0378174 0.0841268 0.01005, + 0.035366699 0.085165501 0.011717, + 0.035366699 0.085528798 0.00993401, + 0.0328326 0.0865179 0.011462, + 0.0328326 0.086839698 0.0096540097, + 0.0302257 0.087770902 0.01104, + 0.0302257 0.088047698 0.0092120096, + 0.027557701 0.088914797 0.010457, + 0.027557701 0.089143701 0.0086130099, + 0.0248404 0.089940898 0.00971899, + 0.0248404 0.090119697 0.0078640003, + 0.0220857 0.090841502 0.0088309897, + 0.0220857 0.090967901 0.00697099, + 0.019305199 0.0916095 0.0078019998, + 0.019305199 0.091681801 0.0059409901, + 0.0165099 0.092240296 0.0066419998, + 0.0165099 0.092257597 0.0047849999, + 0.0137106 0.092730999 0.0053599998, + 0.0137106 0.092692897 0.0035099899, + 0.0109179 0.093079597 0.0039659999, + 0.0109179 0.092985801 0.0021280099, + 0.0081421202 0.093284696 0.0024699999, + 0.0081421202 0.093135297 0.00064799498, + 0.0053918599 0.093347102 0.00088299601, + 0.0053918599 0.093142398 -0.00091700698, + 0.00267513 0.093268298 -0.00078100601, + 0.0053918599 0.092881501 -0.002685, + 0.0081421202 0.092928 -0.00114799, + 0.0109179 0.092832401 0.00031100499, + 0.0137106 0.092593603 0.001679, + 0.0165099 0.0922122 0.00294299, + 0.019305199 0.0916899 0.0040939902, + 0.0220857 0.091029003 0.0051219901, + 0.0248404 0.090232603 0.00601801, + 0.027557701 0.0893066 0.0067739999, + 0.0302257 0.088258199 0.0073859999, + 0.0328326 0.087095402 0.0078450004, + 0.035366699 0.085826799 0.0081460001, + 0.0378174 0.084463403 0.0082879895, + 0.040174201 0.083017401 0.0082689999, + 0.0424264 0.081501201 0.0080890004, + 0.044564299 0.079927497 0.0077489899, + 0.0465803 0.078310199 0.0072519998, + 0.048467699 0.076663703 0.006604, + 0.050219599 0.075002298 0.0058129998, + 0.051830001 0.073339596 0.0048839999, + 0.0532961 0.071689099 0.003828, + 0.0546159 0.070064098 0.00265601, + 0.055787299 0.068477198 0.00137801, + 0 0.092737198 -0.0042420002, + -0.00267513 0.093268797 -0.00078100601, + -0.055787299 0.067494698 0.0040509901, + -0.055787299 0.068015799 0.0027339901, + -0.0546159 0.069065101 0.0054239999, + -0.0546159 0.069596097 0.0040580002, + -0.0532961 0.070682503 0.0066920002, + -0.0532961 0.071218699 0.0052780001, + -0.051830001 0.072334804 0.0078419996, + -0.051830001 0.072871603 0.0063800002, + -0.050219599 0.074009299 0.0088640004, + -0.050219599 0.074541599 0.0073540001, + -0.048467699 0.075692303 0.0097460002, + -0.048467699 0.076214902 0.0081890002, + -0.0465803 0.077369802 0.01048, + -0.0465803 0.077877797 0.0088780103, + -0.044564299 0.079027802 0.011058, + -0.044564299 0.079516403 0.00941299, + -0.0424264 0.080651902 0.011474, + -0.0424264 0.081115998 0.0097899903, + -0.040174201 0.082227498 0.011724, + -0.040174201 0.082662098 0.010003, + -0.0378174 0.083741002 0.011806, + -0.0378174 0.084141999 0.010052, + -0.035366699 0.085179701 0.011719, + -0.035366699 0.0855432 0.009935, + -0.0328326 0.0865312 0.011463, + -0.0328326 0.086853102 0.0096540097, + -0.0302257 0.087783203 0.01104, + -0.0302257 0.088060103 0.0092120096, + -0.027557701 0.088926002 0.010457, + -0.027557701 0.089155003 0.0086120004, + -0.0248404 0.089951098 0.009718, + -0.0248404 0.0901298 0.0078619998, + -0.0220857 0.090850502 0.0088299997, + -0.0220857 0.090976797 0.00696899, + -0.019305199 0.091617197 0.0078009898, + -0.019305199 0.091689199 0.0059389998, + -0.0165099 0.092246599 0.0066410098, + -0.0165099 0.092263602 0.0047829999, + -0.0137106 0.092735998 0.0053589898, + -0.0137106 0.092697501 0.0035089999, + -0.0109179 0.0930833 0.0039650002, + -0.0109179 0.092988998 0.0021269999, + -0.0081421202 0.093287103 0.0024689899, + -0.0081421202 0.093137302 0.00064700301, + -0.0053918599 0.093348399 0.00088200398, + -0.0053918599 0.093143404 -0.00091700698, + -0.059445001 0.054047301 -0.0098569896, + -0.058998398 0.053605799 -0.01216, + -0.058412101 0.053077798 -0.01451, + -0.0576833 0.052449498 -0.016927, + -0.056809202 0.051732399 -0.019448999, + -0.058412101 0.053936001 -0.015464, + -0.058412101 0.054175399 -0.015970999, + -0.058065701 0.053908002 -0.016874, + -0.058722898 0.054293402 -0.014792, + -0.058722898 0.054214701 -0.014559, + -0.058998398 0.054402001 -0.013597, + -0.058998398 0.053991899 -0.012651, + -0.058412101 0.0535676 -0.014964, + -0.0576833 0.0535293 -0.017774001, + -0.0576833 0.0530526 -0.017312, + -0.056809202 0.053027499 -0.020111, + -0.056809202 0.052434299 -0.019721, + -0.055787299 0.0524191 -0.022500001, + -0.055787299 0.051725201 -0.022226, + -0.0546159 0.051718 -0.024978001, + -0.0554736 0.050999999 -0.022862, + -0.055773601 0.050999999 -0.02208, + -0.056127101 0.050999999 -0.021159001, + -0.059445001 0.0543321 -0.010347, + -0.059445001 0.0545072 -0.010788, + -0.058998398 0.054253999 -0.01315, + -0.059445001 0.054629799 -0.011186, + -0.059757002 0.0553637 -0.010052, + -0.0599402 0.0562765 -0.0090340003, + -0.059999999 0.057356801 -0.0081359996, + -0.0599402 0.058594201 -0.0073569901, + -0.059757002 0.059975799 -0.0066920002, + -0.059445001 0.061489001 -0.0061380002, + -0.058998398 0.063113801 -0.005715, + -0.058412101 0.064825602 -0.005444, + -0.0576833 0.066596903 -0.0053409999, + -0.056809202 0.068398699 -0.0054170098, + -0.055787299 0.069955498 -0.004226, + -0.0546159 0.071544699 -0.0031280101, + -0.0532961 0.073154502 -0.0021329999, + -0.051830001 0.074771903 -0.00124899, + -0.050219599 0.076383501 -0.00048700001, + -0.048467699 0.077976003 0.000147003, + -0.0465803 0.079535998 0.00064700301, + -0.044564299 0.081050202 0.001008, + -0.0424264 0.082504801 0.001226, + -0.040174201 0.083886802 0.001299, + -0.0378174 0.085184902 0.00122701, + -0.035366699 0.086388104 0.00101199, + -0.0328326 0.087485701 0.00065499899, + -0.0302257 0.088468298 0.00015899701, + -0.027557701 0.0893289 -0.00047099299, + -0.0248404 0.090061598 -0.0012300001, + -0.0220857 0.090660699 -0.00211099, + -0.019305199 0.091121897 -0.0031049999, + -0.0165099 0.091443002 -0.0041999999, + -0.0137106 0.091623001 -0.0053829998, + -0.0109179 0.091228299 -0.0085500004, + -0.0081421202 0.090674996 -0.011975, + -0.0053918599 0.089101203 -0.019205, + -0.00267513 0.087342098 -0.026542, + 0 0.085394397 -0.033946, + 0.00267513 0.087342396 -0.026542, + 0.0053918599 0.089102201 -0.019205, + 0.0081421202 0.090674803 -0.011975, + 0.0109179 0.091227002 -0.0085529899, + 0.0137106 0.091621697 -0.005382, + 0.0165099 0.091440797 -0.0041979998, + 0.019305199 0.091118403 -0.0031030001, + 0.0220857 0.090655498 -0.00210899, + 0.0248404 0.090054303 -0.001228, + 0.027557701 0.089319699 -0.00046800199, + 0.0302257 0.088457301 0.00016200299, + 0.0328326 0.087473102 0.00065800501, + 0.035366699 0.086374 0.001015, + 0.0378174 0.085169502 0.0012300001, + 0.040174201 0.083870403 0.00130099, + 0.0424264 0.082487397 0.00122701, + 0.044564299 0.081032 0.001008, + 0.0465803 0.079517201 0.00064599601, + 0.048467699 0.077956498 0.000145004, + 0.050219599 0.076363601 -0.00049000501, + 0.051830001 0.074751601 -0.001254, + 0.0532961 0.073133998 -0.002138, + 0.0546159 0.071524203 -0.0031349901, + 0.055787299 0.069935098 -0.0042339899, + -0.058412101 0.054247499 -0.016206, + -0.056809202 0.053491 -0.020579999, + -0.055787299 0.053002499 -0.022895001, + -0.0546159 0.052404098 -0.025253, + -0.054285601 0.050999999 -0.025555, + -0.055220202 0.053433899 -0.024759, + -0.055787299 0.0537683 -0.023899, + -0.056809202 0.053824101 -0.021098999, + -0.056316901 0.0539052 -0.022770001, + -0.055787299 0.053452902 -0.023372, + -0.057264499 0.053971902 -0.019956, + -0.0576833 0.054096501 -0.018798999, + -0.058065701 0.054201499 -0.017620999, + -0.058412101 0.054296099 -0.016424, + -0.056809202 0.053938501 -0.021365, + -0.056809202 0.0540177 -0.021623001, + -0.056809202 0.054044299 -0.021746, + -0.056316901 0.053978398 -0.02303, + -0.055787299 0.053872101 -0.02417, + -0.055220202 0.053740699 -0.025291, + -0.0546159 0.053415 -0.026138, + -0.058998398 0.055618402 -0.021168999, + -0.059445001 0.056446299 -0.020354999, + -0.059757002 0.057401799 -0.019686, + -0.0599402 0.058460101 -0.019181, + -0.059999999 0.0596026 -0.018833, + -0.0599402 0.060814101 -0.018626999, + -0.059757002 0.062082399 -0.018546, + -0.059445001 0.063394897 -0.018576, + -0.058998398 0.064730801 -0.018719001, + -0.058412101 0.066065699 -0.018981, + -0.0576833 0.067377202 -0.019362001, + -0.056809202 0.068842404 -0.018409001, + -0.055787299 0.070321202 -0.017527999, + -0.0546159 0.071802899 -0.016724, + -0.0532961 0.073275603 -0.016005, + -0.051830001 0.0747272 -0.015377, + -0.050219599 0.076145597 -0.014847, + -0.048467699 0.077519 -0.014418, + -0.0465803 0.078835897 -0.014096, + -0.044564299 0.080084898 -0.013882, + -0.0424264 0.081254803 -0.013777, + -0.040174201 0.0823351 -0.013779, + -0.0378174 0.083316699 -0.013884, + -0.035366699 0.083686598 -0.015848, + -0.035366699 0.081622504 -0.022704, + -0.035366699 0.080561101 -0.026110001, + -0.0378174 0.080219403 -0.023910001, + -0.0378174 0.081285499 -0.02055, + -0.040174201 0.079814099 -0.021894, + -0.040174201 0.080890797 -0.018554, + -0.0424264 0.079359598 -0.020036001, + -0.0424264 0.0804004 -0.016868001, + -0.044564299 0.078819104 -0.018486001, + -0.044564299 0.079287 -0.016984999, + -0.0465803 0.077650703 -0.018704999, + -0.0465803 0.078092702 -0.017197, + -0.048467699 0.076411203 -0.019014999, + -0.048467699 0.0768281 -0.017506, + -0.050219599 0.0751113 -0.019416999, + -0.050219599 0.075504303 -0.017913001, + -0.051830001 0.073762 -0.01991, + -0.051830001 0.074132197 -0.018417001, + -0.0532961 0.072374597 -0.020492001, + -0.0532961 0.072723597 -0.019013001, + -0.0546159 0.070960797 -0.021159001, + -0.0546159 0.071290299 -0.019695999, + -0.055787299 0.069532201 -0.021904999, + -0.055787299 0.069843702 -0.020458, + -0.056809202 0.068099901 -0.022721, + -0.056809202 0.068395302 -0.021295, + -0.0576833 0.066674396 -0.023603, + -0.0576833 0.066955902 -0.022198001, + -0.0576833 0.067190498 -0.020783, + -0.058412101 0.065759599 -0.021771001, + -0.056809202 0.068643101 -0.019856, + -0.055787299 0.070107102 -0.018998999, + -0.0546159 0.071571402 -0.018216999, + -0.0532961 0.073024496 -0.017517, + -0.051830001 0.074454501 -0.016906001, + -0.050219599 0.0758496 -0.016388999, + -0.048467699 0.077197999 -0.015973, + -0.0465803 0.078488298 -0.015659001, + -0.044564299 0.079709597 -0.015448, + -0.0424264 0.080850802 -0.01534, + -0.040174201 0.081901297 -0.015332, + -0.0378174 0.082334802 -0.017157, + -0.035366699 0.082663096 -0.019292001, + -0.058998398 0.064529702 -0.021447999, + -0.059445001 0.063287497 -0.021229999, + -0.059757002 0.062054802 -0.021116, + -0.0599402 0.060851902 -0.021104001, + -0.059999999 0.059689298 -0.021211, + -0.0599402 0.058578402 -0.021458, + -0.059757002 0.057533398 -0.021862, + -0.059445001 0.056573 -0.022433, + -0.058998398 0.0557229 -0.023155, + -0.048260398 0.050999999 -0.03565, + -0.047047202 0.046 -0.037237, + -0.0429691 0.046 -0.041877002, + -0.0445357 0.050999999 -0.040206999, + -0.040382501 0.050999999 -0.044376001, + -0.040174201 0.051666401 -0.044679001, + -0.0424264 0.052308001 -0.042830002, + -0.043510102 0.0528282 -0.042148001, + -0.044564299 0.0532034 -0.041533001, + -0.045588002 0.053219602 -0.040362, + -0.044564299 0.053325601 -0.041820999, + -0.044564299 0.052838601 -0.041007001, + -0.0465803 0.053452302 -0.039744001, + -0.048467699 0.053554099 -0.037567001, + -0.048467699 0.053564198 -0.037849002, + -0.049361002 0.0535997 -0.036578, + -0.0465803 0.0534954 -0.040040001, + -0.044564299 0.053404801 -0.042118002, + -0.0424264 0.0532878 -0.044086002, + -0.0424264 0.0533593 -0.044385999, + -0.040174201 0.053251799 -0.046236001, + -0.044564299 0.053438801 -0.042417001, + -0.0465803 0.0534948 -0.040323999, + -0.048467699 0.0535344 -0.038107999, + -0.050219599 0.053617999 -0.035544999, + -0.050219599 0.053635798 -0.035289001, + -0.049361002 0.0535843 -0.036299001, + -0.050219599 0.0536149 -0.035011001, + -0.051042698 0.053672399 -0.033980001, + -0.051830001 0.0537039 -0.032908998, + -0.051042698 0.053645901 -0.033705, + -0.051830001 0.053605001 -0.032097999, + -0.050219599 0.053448699 -0.034437999, + -0.048467699 0.053270001 -0.036706001, + -0.0465803 0.0528601 -0.038647, + -0.052581199 0.053709101 -0.031042, + -0.0532961 0.053784799 -0.029960001, + -0.053974401 0.053833801 -0.028720001, + -0.0546159 0.053881299 -0.027462, + -0.055220202 0.053926099 -0.0263, + -0.0546159 0.053874001 -0.027690999, + -0.053974401 0.053836301 -0.028842, + -0.0532961 0.053792398 -0.030088, + -0.052581199 0.053746998 -0.031314, + -0.051830001 0.053677302 -0.032381002, + -0.0424264 0.078253701 -0.023319, + -0.040174201 0.078720599 -0.025199, + -0.0378174 0.0791336 -0.027264001, + -0.035366699 0.078393102 -0.032935001, + -0.0328326 0.079759598 -0.031959001, + -0.0328326 0.077541798 -0.038895998, + -0.0302257 0.078834899 -0.038079999, + -0.0302257 0.076563597 -0.045101002, + -0.027557701 0.077773303 -0.044429, + -0.027557701 0.0754489 -0.051507, + -0.0248404 0.076565698 -0.050960999, + -0.0248404 0.074186198 -0.058084, + -0.0220857 0.075200297 -0.057647001, + -0.0220857 0.072756998 -0.064801, + -0.019305199 0.073659599 -0.064457998, + -0.019305199 0.071210697 -0.071633004, + -0.0165099 0.071996696 -0.071369, + -0.0165099 0.069732197 -0.078631997, + -0.0137106 0.070398897 -0.078436002, + -0.0137106 0.068332098 -0.085794002, + -0.0109179 0.068876997 -0.085653998, + -0.0109179 0.067007698 -0.093092002, + -0.0081421202 0.067428999 -0.092997, + -0.0081421202 0.065756999 -0.100501, + -0.0053918599 0.066055402 -0.100443, + -0.0053918599 0.064580798 -0.107999, + -0.00267513 0.0647581 -0.107969, + -0.00267513 0.063479997 -0.115566, + 0 0.063538797 -0.115558, + 0 0.062456802 -0.123186, + 0.00267513 0.063481003 -0.115567, + 0.00267513 0.064759001 -0.10797, + 0.0053918599 0.064582601 -0.108, + 0.0053918599 0.066057198 -0.100444, + 0.0081421202 0.065759599 -0.100503, + 0.0081421202 0.067431398 -0.092998996, + 0.0109179 0.067010902 -0.093093999, + 0.0109179 0.068879902 -0.085656002, + 0.0137106 0.068335801 -0.085796997, + 0.0137106 0.070401996 -0.078438997, + 0.0165099 0.0697359 -0.078635998, + 0.0165099 0.071998604 -0.071370997, + 0.019305199 0.071213 -0.071635, + 0.019305199 0.0760848 -0.057266999, + 0.0220857 0.072757199 -0.064802997, + 0.056809202 0.068819098 -0.018408, + 0.0576833 0.067353703 -0.019362001, + 0.056809202 0.068619803 -0.019854, + 0.055787299 0.070298404 -0.017525, + 0.055787299 0.0700844 -0.018995, + 0.0546159 0.071780697 -0.016720001, + 0.0546159 0.071549602 -0.018212, + 0.0532961 0.073254399 -0.016000999, + 0.0532961 0.073003903 -0.017511999, + 0.051830001 0.074707203 -0.015373, + 0.051830001 0.074435599 -0.016900999, + 0.050219599 0.076127298 -0.014842, + 0.050219599 0.075832799 -0.016384, + 0.048467699 0.077502802 -0.014413, + 0.048467699 0.077183798 -0.015967, + 0.0465803 0.0788223 -0.014091, + 0.0465803 0.078477196 -0.015652999, + 0.044564299 0.080074199 -0.013876, + 0.044564299 0.079701498 -0.015442, + 0.0424264 0.081247203 -0.013771, + 0.0424264 0.080845296 -0.015335, + 0.040174201 0.082329899 -0.013774, + 0.040174201 0.0818974 -0.015329, + 0.0378174 0.0833131 -0.013881, + 0.0378174 0.082330301 -0.017166, + 0.035366699 0.083682403 -0.015857, + 0.035366699 0.082662098 -0.019292001, + 0.0328326 0.083940797 -0.018124999, + 0.0328326 0.081892699 -0.025037, + 0.0302257 0.083110198 -0.024052, + 0.0302257 0.081018701 -0.031064, + 0.027557701 0.082162 -0.030246999, + 0.027557701 0.080010101 -0.037344001, + 0.0248404 0.081069998 -0.036674999, + 0.0248404 0.0788607 -0.043827999, + 0.0220857 0.079827502 -0.043290999, + 0.0220857 0.0775562 -0.050478999, + 0.019305199 0.078420997 -0.050055001, + 0.0165099 0.0768416 -0.056940999, + 0.0137106 0.072653703 -0.071151003, + 0.0109179 0.070937604 -0.078280002, + 0.0081421202 0.069294401 -0.085548997, + 0.0053918599 0.0677251 -0.092932001, + 0.00267513 0.066231601 -0.10041, + 0 0.0648164 -0.10796, + -0.00267513 0.066230796 -0.100409, + -0.0053918599 0.067723498 -0.092931002, + -0.0081421202 0.069292203 -0.085547, + -0.0109179 0.070935197 -0.078277998, + -0.0137106 0.072652102 -0.071148999, + -0.0165099 0.074431702 -0.064163998, + -0.019305199 0.076085001 -0.057264999, + -0.0220857 0.077556901 -0.050475001, + -0.0248404 0.078862302 -0.043823, + -0.027557701 0.080012098 -0.037338, + -0.0302257 0.081015602 -0.031060999, + -0.0328326 0.081886202 -0.025039, + 0.058412101 0.066042297 -0.018983999, + 0.058998398 0.064707696 -0.018724, + 0.059445001 0.063372597 -0.018583, + 0.059757002 0.062061299 -0.018556001, + 0.0599402 0.060794398 -0.018639, + 0.059999999 0.0595847 -0.018846, + 0.0599402 0.058444101 -0.019195, + 0.059757002 0.057388 -0.019701, + 0.059445001 0.056434799 -0.020369999, + 0.058998398 0.055608898 -0.021184999, + 0.058412101 0.054932501 -0.022117, + 0.0576833 0.054424401 -0.023136999, + 0.056809202 0.054098599 -0.024219001, + 0.055787299 0.053954199 -0.025322, + 0.055787299 0.053845901 -0.027048999, + 0.056809202 0.054051101 -0.025986999, + 0.0576833 0.054439198 -0.024968, + 0.058412101 0.0549981 -0.024018999, + 0.058998398 0.0557115 -0.023171, + 0.059445001 0.056559298 -0.022448, + 0.059757002 0.057517499 -0.021876, + 0.0599402 0.058560599 -0.021470999, + 0.059999999 0.059669599 -0.021222999, + 0.0599402 0.060830701 -0.021113001, + 0.059757002 0.062032402 -0.021122999, + 0.059445001 0.063264199 -0.021235, + 0.058998398 0.064506002 -0.021451, + 0.058412101 0.065735802 -0.021771001, + 0.0576833 0.066932298 -0.022195, + 0.056809202 0.068372197 -0.021291001, + 0.055787299 0.069821499 -0.020454001, + 0.0546159 0.071269199 -0.019691, + 0.0532961 0.072704203 -0.019007999, + 0.051830001 0.074114896 -0.018412, + 0.050219599 0.075489603 -0.017907999, + 0.048467699 0.076816604 -0.0175, + 0.0465803 0.078084201 -0.017191, + 0.044564299 0.079281203 -0.016979, + 0.0424264 0.080396302 -0.016865, + 0.040174201 0.080886103 -0.018564001, + 0.0378174 0.081284501 -0.020551, + 0.035366699 0.080568098 -0.026108, + 0.0328326 0.079762898 -0.031962, + 0.0302257 0.078832701 -0.038086001, + 0.027557701 0.0777715 -0.044434, + 0.0248404 0.076564901 -0.050964002, + 0.0220857 0.0752002 -0.057649001, + 0.0248404 0.074185997 -0.058086999, + 0.027557701 0.075447999 -0.051511001, + 0.0302257 0.076561503 -0.045107, + 0.0328326 0.077539399 -0.038902, + 0.035366699 0.078396797 -0.032938, + 0.0378174 0.078047201 -0.030622, + 0.0576833 0.066651002 -0.023599001, + 0.058412101 0.065242402 -0.024538999, + 0.0576833 0.066323698 -0.024991, + 0.056809202 0.068077199 -0.022717001, + 0.056809202 0.067735702 -0.024129, + 0.055787299 0.069510698 -0.021899, + 0.055787299 0.069153301 -0.023329999, + 0.0546159 0.070940897 -0.021153999, + 0.0546159 0.0705662 -0.022600001, + 0.0532961 0.072356798 -0.020486999, + 0.0532961 0.071963198 -0.021947, + 0.051830001 0.0737468 -0.019904001, + 0.051830001 0.073332898 -0.021375, + 0.050219599 0.075099297 -0.019409999, + 0.050219599 0.074663401 -0.020888001, + 0.048467699 0.076402403 -0.019009, + 0.048467699 0.075942799 -0.020489, + 0.0465803 0.077644698 -0.018699, + 0.0465803 0.077160001 -0.020176001, + 0.044564299 0.078814797 -0.018483, + 0.044564299 0.077741198 -0.021609001, + 0.0424264 0.079354599 -0.020047, + 0.0424264 0.078252397 -0.023319, + 0.040174201 0.079812899 -0.021894, + 0.040174201 0.077616803 -0.028495001, + 0.0378174 0.079141103 -0.027262, + 0.058998398 0.064121798 -0.024174999, + 0.059445001 0.062979497 -0.023902001, + 0.059757002 0.061836202 -0.02372, + 0.0599402 0.060709901 -0.023630001, + 0.059999999 0.0596097 -0.023651, + 0.0599402 0.0585448 -0.023807, + 0.059757002 0.0575285 -0.024116, + 0.059445001 0.056578498 -0.024592999, + 0.058998398 0.0557217 -0.025225, + 0.058412101 0.054983601 -0.025989, + 0.0576833 0.054386001 -0.026861001, + 0.056809202 0.053946599 -0.027814999, + 0.055787299 0.053679802 -0.028821999, + 0.0546159 0.053595401 -0.029851999, + 0.0532961 0.0536891 -0.030869, + 0.0532961 0.0537588 -0.030435, + 0.052581199 0.053728901 -0.031562999, + 0.051830001 0.0536578 -0.033135999, + 0.051830001 0.053685699 -0.032657001, + 0.051042698 0.0536207 -0.033711001, + 0.050219599 0.053527199 -0.034734, + 0.048467699 0.053380299 -0.037, + 0.0465803 0.053210299 -0.039184, + 0.045588002 0.0528295 -0.039868999, + 0.044564299 0.052313201 -0.040614001, + 0.0424264 0.052301198 -0.042863, + 0.043510102 0.052809399 -0.042176999, + 0.041313998 0.052981399 -0.044626001, + 0.0424264 0.053148702 -0.043809999, + 0.041313998 0.052790198 -0.044374999, + 0.040174201 0.052781101 -0.045428999, + 0.040174201 0.052289799 -0.044999, + 0.0378174 0.051660102 -0.046703, + 0.037937399 0.050999999 -0.046484001, + 0.0360066 0.050999999 -0.047982, + 0.037815802 0.050999999 -0.046578001, + 0.036012899 0.046 -0.047990002, + 0.035366699 0.051655199 -0.048588, + 0.035611998 0.050999999 -0.048289001, + 0.035363302 0.050999999 -0.048463002, + 0.033201002 0.050999999 -0.049977001, + 0.0308876 0.046 -0.051438998, + 0.032827701 0.050999999 -0.050212, + 0.0308851 0.050999999 -0.051435001, + 0.0328326 0.051320799 -0.050246999, + 0.0302257 0.051318999 -0.051856, + 0.0254349 0.046 -0.054342002, + 0.028145101 0.050999999 -0.052988999, + 0.0275524 0.050999999 -0.053286001, + 0.0255125 0.050999999 -0.054306, + 0.027557701 0.051317401 -0.053321999, + 0.030220401 0.050999999 -0.051821001, + 0.030710001 0.050999999 -0.051545002, + 0.0328326 0.051650599 -0.050337002, + 0.0302257 0.051646501 -0.051945001, + 0.027557701 0.051642701 -0.053408999, + 0.0288986 0.052247301 -0.053004999, + 0.0248404 0.0513159 -0.054641001, + 0.025434 0.050999999 -0.054340001, + 0.0248351 0.050999999 -0.054604001, + 0.0228185 0.050999999 -0.055491999, + 0.0197125 0.046 -0.056669001, + 0.0220806 0.050999999 -0.055774, + 0.0200695 0.050999999 -0.056543998, + 0.0220857 0.0513147 -0.055812001, + 0.0248404 0.0516393 -0.054726999, + 0.0262044 0.052239899 -0.054396, + 0.0302257 0.052891999 -0.052963, + 0.0288986 0.052712001 -0.053452, + 0.027557701 0.052876402 -0.054432001, + 0.0302257 0.053024001 -0.053247999, + 0.031537499 0.053034399 -0.052457999, + 0.0302257 0.053112701 -0.053551, + 0.027557701 0.053004801 -0.054719001, + 0.0248404 0.052862499 -0.055753998, + 0.0262044 0.052700199 -0.054845002, + 0.023467001 0.052233402 -0.055640001, + 0.0220857 0.0522305 -0.056205999, + 0.023467001 0.052689601 -0.056092001, + 0.0248404 0.052694701 -0.055486999, + 0.0248404 0.052236602 -0.055036999, + 0.027557701 0.052705899 -0.054166999, + 0.027557701 0.052243501 -0.053718999, + 0.0302257 0.052718401 -0.052700002, + 0.031537499 0.0529004 -0.052173998, + 0.0328326 0.053045198 -0.051631998, + 0.0328326 0.053138599 -0.051932, + 0.034109399 0.053056601 -0.05077, + 0.0328326 0.0531849 -0.052243002, + 0.035366699 0.053219199 -0.050478999, + 0.035366699 0.053221598 -0.050788, + 0.0378174 0.053265899 -0.048884999, + 0.0378174 0.053229101 -0.049178001, + 0.040174201 0.0532852 -0.047141001, + 0.040174201 0.053216498 -0.047408, + 0.0424264 0.0532864 -0.045244999, + 0.0424264 0.053196602 -0.045488, + 0.044564299 0.053281698 -0.043207999, + 0.044564299 0.053077798 -0.043659002, + 0.0465803 0.053192001 -0.041269999, + 0.0465803 0.052415598 -0.043060001, + 0.048467699 0.0526384 -0.040566001, + 0.048467699 0.051906299 -0.04236, + 0.050219599 0.0522447 -0.039777, + 0.050219599 0.051562902 -0.041593, + 0.051830001 0.0520222 -0.038936999, + 0.051830001 0.051386699 -0.040782999, + 0.0532961 0.051970098 -0.038075, + 0.0532961 0.051374599 -0.039960999, + 0.0546159 0.052082799 -0.037218999, + 0.0546159 0.051519498 -0.039154999, + 0.055787299 0.052350901 -0.036398999, + 0.055787299 0.05181 -0.038392, + 0.056809202 0.052760899 -0.035640001, + 0.056809202 0.0522305 -0.037696999, + 0.0576833 0.053295299 -0.034968, + 0.0576833 0.052762002 -0.037092, + 0.058412101 0.053933199 -0.034402002, + 0.058412101 0.053382799 -0.036595002, + 0.058998398 0.0546511 -0.033957999, + 0.058998398 0.054068401 -0.036217999, + 0.059445001 0.055422898 -0.03365, + 0.059445001 0.0547936 -0.035971001, + 0.059757002 0.056221601 -0.033487, + 0.059757002 0.055531502 -0.035861999, + 0.0599402 0.057021599 -0.033468999, + 0.0599402 0.0562586 -0.035886999, + 0.059999999 0.057812098 -0.033573002, + 0.059999999 0.056965999 -0.036022, + 0.0599402 0.058588699 -0.033771001, + 0.0599402 0.057653401 -0.036238998, + 0.059757002 0.0593528 -0.034035001, + 0.059757002 0.058324501 -0.036509998, + 0.059445001 0.060105901 -0.034341998, + 0.059445001 0.058984499 -0.036814999, + 0.058998398 0.0608395 -0.03469, + 0.058412101 0.061541501 -0.035073999, + 0.0576833 0.063462503 -0.032997001, + 0.056809202 0.064789698 -0.032214001, + 0.055787299 0.066113897 -0.031477001, + 0.0546159 0.066757001 -0.032242, + 0.048467699 0.062974997 -0.05266, + 0.0465803 0.062348999 -0.057927001, + 0.044564299 0.061683498 -0.063483, + 0.0424264 0.0609564 -0.069293998, + 0.040174201 0.0602061 -0.075332999, + 0.0378174 0.059587199 -0.081637003, + 0.035366699 0.059101801 -0.088189997, + 0.0328326 0.0587404 -0.094962999, + 0.0302257 0.058491498 -0.101924, + 0.027557701 0.058345299 -0.109045, + 0.0248404 0.0582911 -0.116302, + 0.0220857 0.058318298 -0.12367, + 0.019305199 0.058416899 -0.13112999, + 0.0165099 0.058581501 -0.13866, + 0.0137106 0.058809798 -0.146244, + 0.0137106 0.058513399 -0.15387601, + 0.0116065 0.058866698 -0.16150001, + 0.0137075 0.058398601 -0.16150001, + 0.0152803 0.058021698 -0.1815, + 0.0144795 0.058226701 -0.16150001, + 0.0152764 0.058007602 -0.16150001, + 0.016506201 0.057669599 -0.16150001, + 0.0165099 0.057785399 -0.15389299, + 0.0220857 0.052684899 -0.056659002, + 0.020698 0.052474301 -0.056945998, + 0.019305199 0.052225199 -0.057225998, + 0.0220857 0.052477799 -0.056417, + 0.019710001 0.050999999 -0.056662001, + 0.0193008 0.050999999 -0.056795999, + 0.016506299 0.050999999 -0.057670001, + 0.0401715 0.050999999 -0.044567, + 0.0445593 0.050999999 -0.040169999, + 0.0484582 0.050999999 -0.035360001, + 0.051817201 0.050999999 -0.030218, + 0.057158101 0.046 -0.018247001, + 0.056793101 0.050999999 -0.019300001, + 0.058157299 0.050999999 -0.014756, + -0.0053918599 0.093495302 0.0027079899, + -0.0081421202 0.093377002 0.0043119998, + -0.0109179 0.093115903 0.0058220099, + -0.0137106 0.0927113 0.0072250101, + -0.0165099 0.092164896 0.0085119903, + -0.019305199 0.0914791 0.0096739996, + -0.0220857 0.090657599 0.010699, + -0.0248404 0.089705497 0.011577, + -0.027557701 0.088629998 0.012302, + -0.0302257 0.087439299 0.012867, + -0.0328326 0.086142898 0.013266, + -0.035366699 0.084750898 0.013494, + -0.0378174 0.083275601 0.013548, + -0.040174201 0.0817298 0.013431, + -0.0424264 0.080126897 0.013141, + -0.044564299 0.0784804 0.012682, + -0.0465803 0.0768051 0.012059, + -0.048467699 0.075115301 0.011278, + -0.050219599 0.0734253 0.010348, + -0.051830001 0.071749099 0.0092769898, + -0.0532961 0.070100099 0.0080770003, + -0.0546159 0.068490803 0.006759, + -0.055787299 0.0669332 0.0053370101, + -0.055787299 0.066333398 0.0065919999, + -0.0546159 0.067875199 0.0080629997, + -0.0532961 0.069473401 0.0094309999, + -0.051830001 0.071116298 0.010682, + -0.050219599 0.072791398 0.011804, + -0.048467699 0.074485399 0.012784, + -0.0465803 0.076184697 0.013613, + -0.044564299 0.0778751 0.014284, + -0.0424264 0.079541802 0.014788, + -0.040174201 0.08117 0.015119, + -0.0378174 0.0827462 0.015276, + -0.035366699 0.084256798 0.015256, + -0.0328326 0.0856883 0.01506, + -0.0302257 0.087028198 0.014688, + -0.027557701 0.088266 0.014146, + -0.0248404 0.089392103 0.013438, + -0.0220857 0.090397298 0.012572, + -0.019305199 0.091273896 0.011555, + -0.0165099 0.092016697 0.010395, + -0.0137106 0.092621602 0.0091049997, + -0.0109179 0.093084998 0.0076950099, + -0.0081421202 0.093405098 0.0061750002, + -0.0053918599 0.093582198 0.0045549902, + -0.00267513 0.093617402 0.00284801, + -0.00267513 0.093702398 0.0046979999, + -0.0053918599 0.093607098 0.00642101, + -0.0081421202 0.093369499 0.0080529898, + -0.0109179 0.0929887 0.0095829898, + -0.0137106 0.092464902 0.010997, + -0.0165099 0.091801003 0.012287, + -0.019305199 0.091000699 0.01344, + -0.0220857 0.090068497 0.014447, + -0.0248404 0.089010097 0.015297, + -0.027557701 0.087834097 0.015983, + -0.0302257 0.0865499 0.0165, + -0.0328326 0.085167602 0.016841, + -0.035366699 0.083697699 0.017003, + -0.0378174 0.0821537 0.016984001, + -0.040174201 0.080549203 0.016786, + -0.0424264 0.0788977 0.016410001, + -0.044564299 0.077213198 0.015859, + -0.0465803 0.075510502 0.015139, + -0.048467699 0.073804498 0.014259, + -0.050219599 0.0721092 0.013228, + -0.051830001 0.070438102 0.012055, + -0.0532961 0.068804502 0.010752, + -0.0546159 0.067220502 0.0093339998, + -0.055787299 0.065697402 0.0078130001, + -0.056809202 0.063600801 0.007342, + -0.0576833 0.061616901 0.0066729998, + -0.058412101 0.059773099 0.0058280001, + -0.058998398 0.058093701 0.0048370101, + -0.059445001 0.0565948 0.00373, + -0.059757002 0.055285901 0.00253999, + -0.0599402 0.054636799 0.00059500098, + -0.059999999 0.054209799 -0.00165601, + -0.0599402 0.053718202 -0.0038979901, + -0.059757002 0.0531522 -0.0061869998, + -0.059445001 0.052494898 -0.0085659903, + -0.058998398 0.0517543 -0.011072, + -0.058985401 0.050999999 -0.010916, + -0.0592747 0.050999999 -0.0092319902, + 0.059323099 0.050999999 -0.0089870002, + 0.058982499 0.050999999 -0.010915, + 0.058731299 0.046 -0.012273, + 0.058811001 0.050999999 -0.011886, + 0.058396202 0.050999999 -0.013707, + 0.059682 0.046 -0.00616901, + 0.0594301 0.050999999 -0.0081410101, + 0.059744101 0.050999999 -0.0053960001, + 0.045067899 0.046 0.039609, + 0.0465759 0.050999999 0.037813999, + -0.037814599 0.050999999 0.046576999, + -0.038435601 0.046 0.046073001, + -0.0356883 0.050999999 0.048232, + -0.035366699 0.0527994 0.047991998, + -0.0378174 0.054382998 0.045558002, + -0.0378174 0.052789401 0.046107002, + -0.035366699 0.0544081 0.047451999, + -0.035366699 0.055918399 0.046840999, + -0.0328326 0.055966999 0.048611, + -0.0328326 0.0574576 0.047977, + -0.0302257 0.0575356 0.049609002, + -0.0302257 0.059054501 0.048930999, + -0.027557701 0.059156701 0.050420001, + -0.027557701 0.060699899 0.049685001, + -0.0248404 0.060819902 0.051027998, + -0.0248404 0.062380299 0.050235, + -0.0220857 0.062511601 0.051429, + -0.0220857 0.064084701 0.050576001, + -0.019305199 0.064221002 0.051617, + -0.019305199 0.065802202 0.050701, + -0.0165099 0.065937497 0.051592, + -0.0165099 0.067520298 0.050611999, + -0.0137106 0.067648597 0.051353998, + -0.0137106 0.069225803 0.050310001, + -0.0109179 0.069341302 0.050905, + -0.0109179 0.0709057 0.049796, + -0.0081421202 0.071003199 0.050248999, + -0.0081421202 0.0725476 0.049075998, + -0.0053918599 0.072622202 0.049391001, + -0.0053918599 0.074140303 0.048154999, + -0.00267513 0.074187703 0.048339002, + -0.00267513 0.075672999 0.047040999, + 0 0.075689502 0.0471, + 0 0.077135697 0.045742001, + 0.00267513 0.075672403 0.047040001, + 0.00267513 0.074187197 0.048338, + 0.0053918599 0.0741392 0.048153002, + 0.0053918599 0.072621301 0.049389999, + 0.0081421202 0.072546199 0.049073, + 0.0081421202 0.071001798 0.050246999, + 0.0109179 0.070904002 0.049793001, + 0.0109179 0.0693397 0.050903, + 0.0137106 0.069223702 0.050306, + 0.0137106 0.067646697 0.051351, + 0.0165099 0.0675181 0.050608002, + 0.0165099 0.0659355 0.051587999, + 0.019305199 0.065799899 0.050696999, + 0.019305199 0.064218998 0.051612999, + 0.0220857 0.064082399 0.050570998, + 0.0220857 0.062509999 0.051424, + 0.0248404 0.062378399 0.05023, + 0.0248404 0.0608197 0.051022999, + 0.027557701 0.060699701 0.049679, + 0.027557701 0.059158999 0.050414, + 0.0302257 0.059057001 0.048923999, + 0.0302257 0.0575356 0.049608, + 0.0328326 0.0574576 0.047975, + 0.0328326 0.055952001 0.048610002, + 0.035366699 0.055902101 0.046840001, + 0.035366699 0.054388501 0.047439002, + 0.0378174 0.0543621 0.045543998, + 0.036603201 0.0527886 0.047037002, + 0.036008701 0.050999999 0.047984999, + 0.035366699 0.052793801 0.047963999, + 0.035764702 0.050999999 0.048176002, + 0.034109399 0.0527987 0.048857, + 0.0328326 0.054413099 0.049198002, + 0.0302257 0.0559978 0.050237, + 0.027557701 0.0576066 0.051093999, + 0.0248404 0.059250802 0.051755, + 0.0220857 0.060926199 0.052214999, + 0.019305199 0.062624797 0.052466001, + 0.0165099 0.064335898 0.052505001, + 0.0137106 0.0660486 0.052331001, + 0.0109179 0.067750201 0.051948, + 0.0081421202 0.069428198 0.051357001, + 0.0053918599 0.071070299 0.050563999, + 0.00267513 0.072665401 0.049575999, + 0 0.074203096 0.048399001, + -0.00267513 0.0726659 0.049575999, + -0.0053918599 0.0710712 0.050565999, + -0.0081421202 0.069429301 0.051359002, + -0.0109179 0.067751698 0.051950999, + -0.0137106 0.066050202 0.052335002, + -0.0165099 0.064337596 0.052508, + -0.019305199 0.062626198 0.052469, + -0.0220857 0.0609264 0.052220002, + -0.0248404 0.059248801 0.051761001, + -0.027557701 0.0576066 0.051095001, + -0.0302257 0.056011699 0.050237998, + -0.0328326 0.0544312 0.049210001, + -0.038010798 0.050999999 0.046424001, + -0.040173098 0.050999999 0.044562999, + -0.0384284 0.050999999 0.046064001, + -0.040174201 0.052778699 0.044093002, + -0.0424264 0.052767299 0.041958001, + -0.042376 0.050999999 0.042477001, + -0.040174201 0.054356199 0.043533999, + -0.0378174 0.055865899 0.044934999, + -0.035366699 0.0573727 0.046201002, + -0.0328326 0.058942199 0.047295, + -0.0302257 0.060566701 0.048193, + -0.027557701 0.062232301 0.048891, + -0.0248404 0.063928299 0.049382001, + -0.0220857 0.0656441 0.049660001, + -0.019305199 0.067366399 0.049722001, + -0.0165099 0.069081999 0.049568001, + -0.0137106 0.070777699 0.049201999, + -0.0109179 0.072440803 0.048624001, + -0.0081421202 0.074059203 0.047839999, + -0.0053918599 0.075621702 0.046856999, + -0.00267513 0.077118002 0.045683, + 0 0.078538299 0.044326, + 0.00267513 0.077117398 0.045682002, + 0.0053918599 0.075620599 0.046856001, + 0.0081421202 0.074057601 0.047837999, + 0.0109179 0.072438903 0.048620999, + 0.0137106 0.070775501 0.049198002, + 0.0165099 0.0690796 0.049564, + 0.019305199 0.067363903 0.049717002, + 0.0220857 0.0656415 0.049655002, + 0.0248404 0.063925803 0.049377002, + 0.027557701 0.0622302 0.048884999, + 0.0302257 0.060566399 0.048186999, + 0.0328326 0.0589449 0.047286998, + 0.035366699 0.0573727 0.0462, + 0.0378174 0.055848502 0.044932999, + 0.040174201 0.054334 0.043519001, + 0.0390082 0.052777901 0.045085002, + 0.0389973 0.050999999 0.045575, + 0.040174201 0.051897399 0.044326998, + 0.0378174 0.052783299 0.046077002, + 0.037813399 0.050999999 0.046574999, + 0.038084399 0.050999999 0.046363998, + 0.040756401 0.046 0.044032998, + 0.040171701 0.050999999 0.044560999, + 0.040312301 0.050999999 0.044440001, + 0.040748298 0.050999999 0.044025, + 0.0424264 0.0518918 0.042192001, + 0.040174201 0.052772202 0.044062, + 0.0424264 0.0527605 0.041924998, + 0.044564299 0.051886 0.039942, + 0.044472098 0.050999999 0.040277001, + 0.045056298 0.050999999 0.039599001, + 0.044562198 0.050999999 0.040171999, + 0.042443302 0.050999999 0.042410001, + 0.036012899 0.046 0.047990002, + 0.036593501 0.050999999 0.047527999, + 0.035361301 0.050999999 0.048459999, + 0.0341007 0.050999999 0.049348999, + 0.033358999 0.050999999 0.049872, + 0.0328326 0.052803401 0.049716, + -0.030219801 0.050999999 0.051819999, + -0.028228801 0.050999999 0.052944999, + -0.0302257 0.052817199 0.051350001, + -0.0281986 0.046 0.052960999, + -0.0332799 0.050999999 0.049924001, + -0.033494599 0.046 0.049780998, + -0.0328269 0.050999999 0.050211001, + -0.0328326 0.052808698 0.049741998, + -0.0307914 0.050999999 0.051497001, + -0.0302257 0.054452401 0.050827, + -0.027557701 0.054471701 0.052297998, + -0.027557701 0.056052301 0.051718999, + -0.0248404 0.056088801 0.053052001, + -0.0248404 0.057670601 0.052432999, + -0.0220857 0.0577273 0.053619999, + -0.0220857 0.059330501 0.052951001, + -0.019305199 0.059401799 0.053989001, + -0.019305199 0.061019301 0.053259999, + -0.0165099 0.061098799 0.054149002, + -0.0165099 0.062724203 0.05336, + -0.0137106 0.062805898 0.054102, + -0.0137106 0.064434797 0.053250998, + -0.0109179 0.064512998 0.053847998, + -0.0109179 0.066140898 0.052932002, + -0.0081421202 0.066209897 0.053387001, + -0.0081421202 0.067830198 0.052405, + -0.0053918599 0.067884997 0.052723002, + -0.0053918599 0.069490798 0.051676001, + -0.00267513 0.069526799 0.051862001, + -0.00267513 0.071111001 0.050751001, + 0 0.071123898 0.050811999, + 0 0.072679996 0.049635999, + 0.00267513 0.071110599 0.050749999, + 0.00267513 0.069526397 0.051862001, + 0.0053918599 0.069490001 0.051674999, + 0.0053918599 0.067884304 0.052722, + 0.0081421202 0.067829102 0.052402999, + 0.0081421202 0.066208899 0.053385001, + 0.0109179 0.066139601 0.052928999, + 0.0109179 0.064511903 0.053846002, + 0.0137106 0.064433403 0.053247999, + 0.0137106 0.0628049 0.054099999, + 0.0165099 0.062723003 0.053357001, + 0.0165099 0.061098602 0.054145999, + 0.019305199 0.0610191 0.053256001, + 0.019305199 0.059403401 0.053984001, + 0.0220857 0.0593323 0.052946001, + 0.0220857 0.0577273 0.053619999, + 0.0248404 0.057670601 0.052432001, + 0.0248404 0.056077398 0.053050999, + 0.027557701 0.056039698 0.051718, + 0.027557701 0.054456402 0.052287001, + 0.0302257 0.0544357 0.050815001, + 0.0288986 0.052816499 0.052076999, + 0.0275514 0.050999999 0.053284001, + 0.0254349 0.046 0.054342002, + 0.0283127 0.050999999 0.052900001, + 0.025684301 0.050999999 0.054225001, + 0.027557701 0.0528205 0.052792002, + 0.0248404 0.054475199 0.053613, + 0.0220857 0.056111 0.054235, + 0.019305199 0.057776801 0.054655999, + 0.0165099 0.059464101 0.054873001, + 0.0137106 0.061164901 0.054887999, + 0.0109179 0.0628708 0.054696999, + 0.0081421202 0.064571701 0.054301001, + 0.0053918599 0.066257402 0.053702999, + 0.00267513 0.067916803 0.052908, + 0 0.0695384 0.051922999, + -0.00267513 0.067917101 0.052909002, + -0.0053918599 0.066258103 0.053704999, + -0.0081421202 0.064572498 0.054303002, + -0.0109179 0.062871598 0.054699, + -0.0137106 0.061165001 0.054891001, + -0.0165099 0.059462801 0.054877002, + -0.019305199 0.057776801 0.054655999, + -0.0220857 0.0561211 0.054235, + -0.0248404 0.054488901 0.053622, + -0.027557701 0.0528249 0.052813999, + -0.028198199 0.050999999 0.052960001, + -0.0275518 0.050999999 0.053284999, + -0.0255982 0.050999999 0.054265, + -0.0226037 0.046 0.055578999, + -0.0167691 0.046 0.057608999, + -0.0193005 0.050999999 0.056795001, + -0.0107568 0.046 0.059028, + -0.0137074 0.050999999 0.058398001, + 0.0137106 0.0528493 0.057909001, + 0.0146178 0.050999999 0.058192, + 0.0165099 0.052845102 0.057179999, + 0.013778 0.050999999 0.058380999, + 0.0137813 0.046 0.058396, + 0.0137072 0.050999999 0.058396999, + 0.0117463 0.050999999 0.058839001, + 0.0109153 0.050999999 0.058984, + 0.0077038999 0.046 0.059503, + 0.0081421202 0.054545499 0.058463998, + 0.0088465102 0.050999999 0.059344001, + 0.0109179 0.052852701 0.058495998, + 0.0053910702 0.050999999 0.059746001, + 0.0059254402 0.050999999 0.059707001, + 0.00154487 0.046 0.059980001, + -0.0053912001 0.050999999 0.059748001, + -0.0046292599 0.050999999 0.059804, + -0.0053918599 0.054553501 0.05878, + 0 0.056234501 0.058490999, + 0.00267513 0.056232199 0.058430001, + 0 0.057931401 0.057891, + -0.00267513 0.056233399 0.058430001, + -0.00267513 0.054555301 0.058963001, + -0.00289505 0.050999999 0.05993, + -0.0046305298 0.046 0.059820998, + -0.0081406701 0.050999999 0.059432998, + -0.0058307201 0.050999999 0.059716001, + -0.0081421202 0.05455 0.058467001, + -0.0053918599 0.056228898 0.058244999, + -0.00267513 0.057928499 0.057829998, + 0 0.059624799 0.057229001, + 0.00267513 0.057928499 0.057829998, + 0.0053918599 0.056226399 0.058244999, + 0.0053918599 0.054550499 0.058777999, + 0.0077017802 0.050999999 0.059486002, + 0.00267513 0.054553799 0.058961999, + 0.0029901101 0.050999999 0.059925001, + 0 0.054555301 0.059023, + 0.00154442 0.050999999 0.059962001, + -0.0026750199 0.050999999 0.059935, + 2.7e-008 0.050999999 0.059999, + 4.7590001e-005 0.050999999 0.059999999, + 0.0026749601 0.050999999 0.059932999, + 0.0081404904 0.050999999 0.059432, + 0.0109179 0.054538701 0.058015, + 0.0081421202 0.056217 0.05793, + 0.0053918599 0.0579197 0.057643998, + 0.00267513 0.059620801 0.057167999, + 0 0.0613093 0.056504998, + -0.00267513 0.0596206 0.057167999, + -0.0053918599 0.0579197 0.057643998, + -0.0081421202 0.0562208 0.05793, + -0.0109179 0.054544698 0.058019001, + -0.0137106 0.052851502 0.057920001, + -0.0116529 0.050999999 0.058858, + -0.0165099 0.052847799 0.057193, + -0.0145255 0.050999999 0.058215, + -0.0137106 0.054537501 0.057431001, + -0.0109179 0.056208801 0.057479002, + -0.0081421202 0.057904501 0.057328001, + -0.0053918599 0.0596077 0.056983002, + -0.00267513 0.061303899 0.056444999, + 0 0.062983602 0.055718999, + 0.00267513 0.061303899 0.056444, + 0.0053918599 0.059608102 0.056981001, + 0.0081421202 0.057904501 0.057328001, + 0.0109179 0.056203801 0.057479002, + 0.0137106 0.054529902 0.057425998, + 0.017454101 0.050999999 0.057404999, + 0.019305199 0.052840199 0.056306001, + 0.0165099 0.054519199 0.056694001, + 0.0137106 0.056186698 0.056885999, + 0.0109179 0.057882901 0.056875002, + 0.0081421202 0.059586499 0.056664001, + 0.0053918599 0.061287198 0.056258, + 0.00267513 0.0629768 0.055658001, + 0 0.064646199 0.054868001, + -0.00267513 0.062977001 0.055658001, + -0.0053918599 0.061287299 0.056258999, + -0.0081421202 0.059585799 0.056666002, + -0.0109179 0.057882901 0.056875002, + -0.0137106 0.056193002 0.056887001, + -0.0165099 0.0545284 0.056699999, + -0.0167659 0.050999999 0.057597, + -0.017363001 0.050999999 0.057433002, + -0.019305199 0.052843299 0.056320999, + -0.0248347 0.050999999 0.054602999, + -0.0229061 0.050999999 0.055454999, + -0.0248404 0.052831899 0.054131001, + -0.0226011 0.050999999 0.055573002, + -0.0220857 0.052838001 0.055300999, + -0.0220857 0.0545041 0.054798, + 0.0220799 0.050999999 0.055771999, + 0.0197125 0.046 0.056669001, + 0.022994 0.050999999 0.055419002, + 0.0202484 0.050999999 0.056480002, + 0.0220857 0.052834399 0.055282999, + 0.0248404 0.052827898 0.054111999, + 0.0220857 0.0544919 0.054788999, + 0.019305199 0.0545066 0.055815998, + 0.019305199 0.0561404 0.055266999, + 0.0165099 0.056165598 0.056150001, + 0.0165099 0.057819199 0.055542, + 0.0137106 0.0578545 0.056281, + 0.0137106 0.059514798 0.055613998, + 0.0109179 0.059555501 0.05621, + 0.0109179 0.061218198 0.055484999, + 0.0081421202 0.0612588 0.055939998, + 0.0081421202 0.062921003 0.055153001, + 0.0053918599 0.062956102 0.055470999, + 0.0053918599 0.064613499 0.054620001, + 0.00267513 0.064638101 0.054807, + 0.00267513 0.066285998 0.053890001, + 0 0.0662954 0.053952001, + 0 0.067927502 0.05297, + -0.00267513 0.066286303 0.053890999, + -0.00267513 0.064638302 0.054807, + -0.0053918599 0.064613998 0.054621, + -0.0053918599 0.062956497 0.055472001, + -0.0081421202 0.062921599 0.055153999, + -0.0081421202 0.061258901 0.055941001, + -0.0109179 0.061218299 0.055486999, + -0.0109179 0.059554599 0.056212001, + -0.0137106 0.059513699 0.055617001, + -0.0137106 0.0578545 0.056281, + -0.0165099 0.057819199 0.055542, + -0.0165099 0.056173101 0.056150999, + -0.019305199 0.0561492 0.055268001, + -0.019305199 0.054517198 0.055822998, + -0.020158799 0.050999999 0.056511998, + 0.019709 0.050999999 0.056659002, + 0.0193002 0.050999999 0.056793999, + 0.0165058 0.050999999 0.057668, + -0.00875236 0.050999999 0.059358001, + -0.0107542 0.050999999 0.059013002, + -0.0109155 0.050999999 0.058984999, + -0.016505999 0.050999999 0.057668999, + -0.0220802 0.050999999 0.055773001, + 0.0254324 0.050999999 0.054336999, + 0.024834299 0.050999999 0.054602001, + 0.0288927 0.050999999 0.052570999, + 0.0302191 0.050999999 0.051817998, + -0.033491299 0.050999999 0.049775999, + -0.035362199 0.050999999 0.048461001, + -0.0402418 0.050999999 0.044504002, + -0.0429691 0.046 0.041877002, + -0.0424252 0.050999999 0.042424999, + -0.042958502 0.050999999 0.041866001, + -0.044408198 0.050999999 0.040346999, + 0.046393901 0.050999999 0.038047001, + 0.0498982 0.050999999 0.033319, + -0.047033701 0.050999999 0.037225999, + -0.046574499 0.050999999 0.037813, + -0.044560701 0.050999999 0.040171001, + -0.059720598 0.050999999 -0.0057839998, + -0.059285302 0.046 -0.0092329998, + -0.059433699 0.050999999 -0.0081410101, + -0.059365101 0.050999999 -0.0087050004, + -0.057446498 0.050999999 -0.017317999, + -0.056143001 0.046 -0.021165, + -0.056795198 0.050999999 -0.019300999, + -0.056527998 0.050999999 -0.020114001, + -0.054603402 0.050999999 -0.024835, + -0.050626501 0.046 -0.032202002, + -0.051520798 0.050999999 -0.030750999, + -0.048462 0.050999999 -0.035363, + -0.040170401 0.050999999 -0.04456, + -0.038430501 0.050999999 -0.046066999, + -0.0381575 0.050999999 -0.046303, + -0.037812401 0.050999999 -0.046574, + -0.041313998 0.052808199 -0.044348001, + -0.0424264 0.053015102 -0.043517999, + -0.0424264 0.052818101 -0.043262001, + -0.043510102 0.053187601 -0.042677, + -0.0424264 0.053172201 -0.043793999, + -0.041313998 0.053002801 -0.044605002, + -0.040174201 0.052798498 -0.045403, + -0.040174201 0.052990802 -0.045662001, + -0.041313998 0.053157099 -0.044881999, + -0.040174201 0.053142399 -0.045940999, + -0.0390082 0.052979201 -0.046688002, + -0.0378174 0.052779999 -0.047421999, + -0.040174201 0.068059802 -0.055125002, + -0.0378174 0.067229703 -0.061085001, + -0.035366699 0.066292003 -0.067261003, + -0.0328326 0.065286003 -0.073620997, + -0.0302257 0.064379297 -0.080211997, + -0.027557701 0.063578203 -0.087021999, + -0.0248404 0.062875196 -0.094021998, + -0.0220857 0.062261999 -0.101181, + -0.019305199 0.061730899 -0.108474, + -0.0165099 0.061276 -0.115876, + -0.0137106 0.060892601 -0.123367, + -0.0109179 0.060578 -0.130927, + -0.0081421202 0.060330201 -0.138537, + -0.0053918599 0.0601492 -0.14618, + -0.00267513 0.060037699 -0.15384001, + -0.00308863 0.059919201 -0.16150001, + 0 0.060098 -0.15383901, + -9.4966999e-005 0.059999902 -0.16150001, + -0.00267513 0.060332298 -0.146172, + -0.0053918599 0.060640901 -0.138515, + -0.0081421202 0.061020501 -0.130886, + -0.0109179 0.0614697 -0.1233, + -0.0137106 0.061987501 -0.115776, + -0.0165099 0.062575802 -0.108333, + -0.019305199 0.0632383 -0.100991, + -0.0220857 0.0639797 -0.093773, + -0.0248404 0.064804502 -0.086704999, + -0.027557701 0.065719903 -0.079815999, + -0.0302257 0.066733897 -0.073135003, + -0.0328326 0.067839399 -0.066671997, + -0.035366699 0.0688636 -0.060380001, + -0.0378174 0.069765799 -0.05429, + -0.040174201 0.070568003 -0.048432, + -0.0424264 0.0712841 -0.042840999, + -0.0424264 0.072493702 -0.039567001, + -0.040174201 0.073000804 -0.041758999, + -0.0378174 0.072231598 -0.047508001, + -0.035366699 0.071363002 -0.053507999, + -0.0328326 0.0703803 -0.059726, + -0.0302257 0.0692617 -0.066131003, + -0.027557701 0.068052001 -0.072692998, + -0.0248404 0.066926897 -0.079460002, + -0.0220857 0.065892898 -0.086424001, + -0.019305199 0.064943202 -0.093556002, + -0.0165099 0.064073399 -0.100828, + -0.0137106 0.063280299 -0.108215, + -0.0109179 0.062559798 -0.115695, + -0.0081421202 0.0619094 -0.123249, + -0.0053918599 0.061329901 -0.13085701, + -0.00267513 0.0608234 -0.138503, + 0 0.060392201 -0.14616901, + 0.00267513 0.060332902 -0.146172, + 0.00267513 0.0608241 -0.138503, + 0.0053918599 0.060642298 -0.13851599, + 0.0053918599 0.061331902 -0.13085701, + 0.0081421202 0.0610235 -0.130886, + 0.0081421202 0.0619126 -0.12325, + 0.0109179 0.061473899 -0.123301, + 0.0109179 0.062563702 -0.115697, + 0.0137106 0.061992399 -0.115778, + 0.0137106 0.063284896 -0.108218, + 0.0165099 0.062581301 -0.108336, + 0.0165099 0.064078704 -0.100832, + 0.019305199 0.063244402 -0.100995, + 0.019305199 0.064948902 -0.093561001, + 0.0220857 0.063986197 -0.093777999, + 0.0220857 0.065898798 -0.086429, + 0.0248404 0.064811103 -0.086710997, + 0.0248404 0.066932403 -0.079465002, + 0.027557701 0.065726101 -0.079821996, + 0.027557701 0.068055198 -0.072696, + 0.0302257 0.066737399 -0.073138997, + 0.0302257 0.069261998 -0.066133, + 0.0328326 0.067839697 -0.066674002, + 0.0328326 0.070380099 -0.059728999, + 0.035366699 0.068863399 -0.060384002, + 0.035366699 0.071361899 -0.053513002, + 0.0378174 0.069764599 -0.054295, + 0.0378174 0.072229102 -0.047515001, + 0.040174201 0.070565298 -0.048439998, + 0.040174201 0.072997801 -0.041767001, + 0.0424264 0.073685601 -0.036306001, + -0.0424264 0.073681198 -0.036302, + -0.043510102 0.0728136 -0.036922, + -0.044564299 0.074288502 -0.031182, + -0.045588002 0.0757588 -0.025598001, + -0.043510102 0.075150602 -0.030485, + -0.0424264 0.075991899 -0.029805001, + -0.040174201 0.075348601 -0.035110999, + -0.040174201 0.077608801 -0.028496999, + -0.0424264 0.077131301 -0.026566001, + -0.043510102 0.0774417 -0.024061, + 0.058998398 0.0635565 -0.026877999, + 0.059445001 0.062518001 -0.026564, + 0.059757002 0.061469201 -0.026327001, + 0.0599402 0.060427099 -0.026171001, + 0.059999999 0.059397601 -0.026117001, + 0.0599402 0.058388799 -0.026188999, + 0.059757002 0.057411298 -0.026411001, + 0.059445001 0.056482598 -0.026797, + 0.058998398 0.055629399 -0.02734, + 0.058412101 0.054878701 -0.028019, + 0.0576833 0.054253899 -0.028813001, + 0.056809202 0.0537747 -0.029697999, + 0.055787299 0.053456601 -0.030647, + 0.0546159 0.053311899 -0.031629998, + 0.0532961 0.0533484 -0.032618001, + 0.051830001 0.053559799 -0.033574, + 0.050219599 0.0535593 -0.035776, + 0.051042698 0.0536425 -0.034232002, + 0.0465803 0.053428698 -0.039754, + 0.044564299 0.053382199 -0.042126998, + 0.0465803 0.053472299 -0.040045999, + 0.048467699 0.053530201 -0.037574001, + 0.048467699 0.053541899 -0.03785, + 0.050219599 0.053612798 -0.035289999, + 0.050219599 0.053600099 -0.035542, + 0.048467699 0.0535172 -0.038105, + 0.0465803 0.053473499 -0.040325999, + 0.044564299 0.053416699 -0.042422999, + 0.0424264 0.053337902 -0.044396002, + 0.0424264 0.053265098 -0.044098001, + 0.041313998 0.0531343 -0.044898, + 0.040174201 0.053230301 -0.046247002, + 0.044564299 0.0533018 -0.041832998, + 0.043510102 0.053163599 -0.042693999, + 0.0465803 0.053340301 -0.039464001, + 0.045588002 0.0531944 -0.040378999, + 0.048467699 0.053477101 -0.037285998, + 0.050219599 0.05359 -0.035016999, + 0.051042698 0.053649001 -0.033982001, + 0.051830001 0.053685401 -0.032905001, + 0.044564299 0.0528193 -0.041035999, + 0.044564299 0.053178798 -0.041549999, + 0.0424264 0.052799702 -0.04329, + 0.040174201 0.05297 -0.045682002, + 0.0390082 0.052772202 -0.046454001, + 0.0378174 0.052278999 -0.047012001, + 0.035366699 0.052269001 -0.048896998, + 0.036603201 0.0527553 -0.048408002, + 0.0328326 0.052259699 -0.050647002, + 0.034109399 0.052739602 -0.05023, + 0.0302257 0.052251201 -0.052255001, + 0.031537499 0.0527252 -0.051911999, + 0.0328326 0.052909199 -0.051348999, + 0.035366699 0.053068399 -0.049874, + 0.034109399 0.052918401 -0.050489001, + 0.0328326 0.052732199 -0.051089, + 0.035366699 0.052928001 -0.049594, + 0.036603201 0.0530807 -0.048943002, + 0.035366699 0.0531669 -0.050170999, + 0.0378174 0.053256199 -0.048578002, + 0.040174201 0.0533133 -0.046851002, + 0.0424264 0.053344801 -0.044982001, + 0.044564299 0.05336 -0.042966999, + 0.0465803 0.0533708 -0.040821999, + 0.048467699 0.0533107 -0.038784999, + 0.050219599 0.052868798 -0.037985999, + 0.051830001 0.052592799 -0.03712, + 0.0532961 0.052492399 -0.036219999, + 0.0546159 0.052564301 -0.035317, + 0.055787299 0.0528007 -0.03444, + 0.056809202 0.053190101 -0.033617001, + 0.0576833 0.053716902 -0.032873999, + 0.058412101 0.054361701 -0.032233998, + 0.058998398 0.0551016 -0.031716999, + 0.059445001 0.055911399 -0.031339001, + 0.059757002 0.056763001 -0.03111, + 0.0599402 0.057630599 -0.031036001, + 0.059999999 0.058500301 -0.031094, + 0.0599402 0.059365701 -0.031259, + 0.059757002 0.060224 -0.031502001, + 0.059445001 0.061074901 -0.031800002, + 0.058998398 0.061906599 -0.03215, + 0.058412101 0.062706403 -0.032551002, + 0.0576833 0.064039201 -0.031714, + 0.056809202 0.065380603 -0.030924, + 0.055787299 0.066720396 -0.030184001, + 0.0546159 0.068048097 -0.029498, + 0.0532961 0.068703398 -0.030358, + 0.0465803 0.064997502 -0.051534999, + 0.044564299 0.0643434 -0.056949999, + 0.0424264 0.0636333 -0.062641002, + 0.040174201 0.062844701 -0.068575002, + 0.0378174 0.062018398 -0.074724004, + 0.035366699 0.0613125 -0.081127003, + 0.0328326 0.060728699 -0.087769002, + 0.0302257 0.0602578 -0.094619997, + 0.027557701 0.059891101 -0.10165, + 0.0248404 0.059619699 -0.108832, + 0.0220857 0.0594333 -0.11614, + 0.019305199 0.0593227 -0.123553, + 0.0165099 0.059281498 -0.13104901, + 0.0137106 0.059305999 -0.13860901, + 0.0109179 0.0593943 -0.14621601, + 0.045588002 0.071019903 -0.038212001, + 0.0465803 0.0700913 -0.038876001, + 0.044564299 0.069472298 -0.043990001, + 0.0465803 0.072515398 -0.032621, + 0.047540501 0.071597204 -0.033364002, + 0.048467699 0.073099501 -0.028024999, + 0.047540501 0.069144398 -0.039553002, + 0.048467699 0.068180099 -0.040242001, + 0.0465803 0.067579798 -0.045184001, + 0.048467699 0.070662297 -0.034120001, + 0.049361002 0.069711603 -0.034889001, + 0.050219599 0.071249798 -0.029713999, + 0.0576833 0.065076798 -0.02908, + 0.058412101 0.063718699 -0.029944001, + 0.0576833 0.064577699 -0.030407, + 0.056809202 0.066446297 -0.028267, + 0.056809202 0.065933198 -0.029607, + 0.055787299 0.067817204 -0.027511001, + 0.055787299 0.0672886 -0.028860999, + 0.0546159 0.069178902 -0.026817, + 0.0546159 0.068633303 -0.028173, + 0.0532961 0.0705202 -0.026188999, + 0.0532961 0.069955997 -0.027546, + 0.051830001 0.071829401 -0.025629999, + 0.051830001 0.070614599 -0.028508, + 0.050219599 0.072482102 -0.026699999, + 0.044564299 0.066942401 -0.050453998, + 0.0424264 0.068801001 -0.049421001, + 0.0424264 0.0662494 -0.056017, + 0.040174201 0.068058498 -0.055131, + 0.040174201 0.065484099 -0.061841998, + 0.0378174 0.067229398 -0.061089002, + 0.0378174 0.0646253 -0.067897998, + 0.035366699 0.066292301 -0.067263, + 0.035366699 0.063715003 -0.074153997, + 0.0328326 0.065289803 -0.073624998, + 0.0328326 0.062913999 -0.080652997, + 0.0302257 0.064386003 -0.080218002, + 0.0302257 0.062224202 -0.087382004, + 0.027557701 0.063585602 -0.087029003, + 0.027557701 0.0616391 -0.094307996, + 0.0248404 0.062882602 -0.094026998, + 0.0248404 0.061150901 -0.101404, + 0.0220857 0.062269099 -0.101186, + 0.0220857 0.060750801 -0.108642, + 0.019305199 0.0617374 -0.108477, + 0.019305199 0.0604297 -0.115999, + 0.0165099 0.0612818 -0.115879, + 0.0165099 0.0601817 -0.123452, + 0.0137106 0.060897999 -0.123369, + 0.0137106 0.060002301 -0.130982, + 0.0109179 0.060582001 -0.13092799, + 0.0109179 0.059888601 -0.138568, + 0.0081421202 0.060332298 -0.138537, + 0.0081421202 0.059839498 -0.14619499, + 0.0053918599 0.0601505 -0.14618, + 0.0030887299 0.0599204 -0.1815, + -5.2000001e-008 0.0599977 -0.16150001, + 0.0026750399 0.0599363 -0.16150001, + 0.00267513 0.060038701 -0.15384001, + 0.0028477299 0.0599324 -0.16150001, + 0.0053912699 0.059748899 -0.16150001, + 0.0030883299 0.059914999 -0.16150001, + 0.0053918599 0.059856098 -0.153844, + 0.058998398 0.062815703 -0.029541999, + 0.059445001 0.0618813 -0.029201999, + 0.059757002 0.060931299 -0.028927, + 0.0599402 0.059978999 -0.028720001, + 0.059999999 0.059028801 -0.028603001, + 0.0599402 0.058085401 -0.028604001, + 0.059757002 0.057158299 -0.028747, + 0.059445001 0.056262601 -0.02905, + 0.058998398 0.055425499 -0.029507, + 0.058412101 0.054674301 -0.030104, + 0.0576833 0.054033801 -0.030820001, + 0.056809202 0.053525399 -0.031633999, + 0.055787299 0.053166602 -0.032520998, + 0.0546159 0.052971199 -0.033452999, + 0.0532961 0.052949101 -0.034400001, + 0.051830001 0.053105801 -0.035333, + 0.050219599 0.0534335 -0.036215998, + 0.048467699 0.053463399 -0.038341001, + 0.0465803 0.053436998 -0.040584002, + 0.044564299 0.053407598 -0.042707, + 0.0424264 0.053363599 -0.044695001, + 0.040174201 0.053295799 -0.046548001, + 0.0378174 0.053197499 -0.048273999, + 0.0378174 0.0530934 -0.047979001, + 0.0390082 0.053106599 -0.046983998, + 0.036603201 0.052937899 -0.048664998, + 0.035366699 0.052747302 -0.049336001, + 0.0378174 0.0529483 -0.047703002, + 0.040174201 0.0531202 -0.045956001, + 0.0390082 0.052958999 -0.046707999, + 0.0378174 0.0527636 -0.047447, + -0.00923343 0.059285302 -0.1815, + -0.0081404103 0.0594313 -0.16150001, + -0.0088933604 0.059337199 -0.16150001, + -0.0109152 0.0589833 -0.16150001, + 0.042423699 -0.042423598 -0.16150001, + 0.044033099 -0.040756401 -0.1815, + 0.042543601 -0.0423088 -0.16150001, + 0.0484627 -0.035363302 -0.16150001, + 0.049977001 -0.033201002 -0.16150001, + 0.048467699 -0.035322402 -0.158812, + 0.0479904 -0.036012899 -0.1815, + 0.048288502 -0.035611998 -0.16150001, + 0.044567399 -0.0401715 -0.16150001, + 0.0464839 -0.037937399 -0.16150001, + 0.044564299 -0.040129799 -0.15887, + 0.046578299 -0.037815802 -0.16150001, + 0.047982302 -0.0360066 -0.16150001, + 0.0465803 -0.037773099 -0.158842, + 0.044564299 -0.040012199 -0.15622, + 0.0424264 -0.0422635 -0.15627301, + 0.0424264 -0.042066701 -0.153631, + 0.040174201 -0.0442021 -0.153707, + 0.040174201 -0.0439202 -0.15107401, + 0.0378174 -0.045931801 -0.151168, + 0.0378174 -0.045559999 -0.148546, + 0.035366699 -0.047440499 -0.148656, + 0.035366699 -0.046976302 -0.146046, + 0.0328326 -0.048718799 -0.14616799, + 0.0328326 -0.048160199 -0.143576, + 0.0302257 -0.049758598 -0.14370599, + 0.0302257 -0.0491037 -0.141133, + 0.027557701 -0.050555199 -0.141268, + 0.027557701 -0.049802199 -0.13871799, + 0.0248404 -0.051105 -0.138854, + 0.0248404 -0.0502529 -0.13633101, + 0.0220857 -0.051405501 -0.136466, + 0.0220857 -0.0504536 -0.133974, + 0.019305199 -0.0514552 -0.134103, + 0.019305199 -0.0504032 -0.13164601, + 0.0165099 -0.0512564 -0.13176601, + 0.0165099 -0.050104301 -0.12934899, + 0.0137106 -0.050812501 -0.129457, + 0.0137106 -0.049561799 -0.127083, + 0.0109179 -0.050128501 -0.127178, + 0.0109179 -0.048781302 -0.124851, + 0.0081428103 -0.049210802 -0.124929, + 0.0081428103 -0.047769099 -0.122654, + 0.0053973799 -0.0480676 -0.122712, + 0.0053973799 -0.046534199 -0.120493, + 0.00268824 -0.046708401 -0.120529, + 0.00268824 -0.045086998 -0.11837, + 0 -0.045143701 -0.118382, + 0 -0.043438599 -0.116286, + -0.00268824 -0.045087799 -0.118369, + -0.00268824 -0.046709199 -0.120529, + -0.0053973799 -0.046535801 -0.120492, + -0.0053973799 -0.048069298 -0.122711, + -0.0081428103 -0.0477717 -0.122652, + -0.0081428103 -0.049213398 -0.124927, + -0.0109179 -0.0487849 -0.124849, + -0.0109179 -0.0501321 -0.127176, + -0.0137106 -0.049566399 -0.12708101, + -0.0137106 -0.050817199 -0.129455, + -0.0165099 -0.050110001 -0.129346, + -0.0165099 -0.0512623 -0.13176399, + -0.019305199 -0.050410099 -0.131643, + -0.019305199 -0.051462501 -0.13410001, + -0.0220857 -0.050461899 -0.13397101, + -0.0220857 -0.051414099 -0.136463, + -0.0248404 -0.0502626 -0.136329, + -0.0248404 -0.051114701 -0.138852, + -0.027557701 -0.049812999 -0.138715, + -0.027557701 -0.050565299 -0.141265, + -0.0302257 -0.049114801 -0.14113, + -0.0302257 -0.049768198 -0.143703, + -0.0328326 -0.048170701 -0.143573, + -0.0328326 -0.048727401 -0.146166, + -0.035366699 -0.0469856 -0.146044, + -0.035366699 -0.047448501 -0.148653, + -0.0378174 -0.0455685 -0.148543, + -0.0378174 -0.045940802 -0.15116701, + -0.040174201 -0.0439297 -0.151072, + -0.040174201 -0.044214301 -0.153708, + -0.0424264 -0.042079501 -0.153632, + -0.0424264 -0.042278301 -0.156276, + -0.044564299 -0.0400277 -0.156222, + -0.044564299 -0.040142201 -0.15887301, + -0.0424264 -0.0423938 -0.15889999, + -0.044024602 -0.040748298 -0.16150001, + -0.044440001 -0.040312301 -0.16150001, + -0.044033099 -0.040756401 -0.1815, + -0.044561401 -0.040171701 -0.16150001, + -0.0463636 -0.038084399 -0.16150001, + -0.0465803 -0.0377861 -0.15884501, + -0.048467699 -0.035335999 -0.15881599, + -0.047984999 -0.036008701 -0.16150001, + -0.0465803 -0.037672602 -0.156166, + -0.044564299 -0.039830498 -0.153552, + -0.0424264 -0.041797198 -0.15097199, + -0.040174201 -0.043560401 -0.148426, + -0.0378174 -0.045109 -0.14591201, + -0.035366699 -0.0464327 -0.14343099, + -0.0328326 -0.047521502 -0.140982, + -0.0302257 -0.0483668 -0.13856401, + -0.027557701 -0.048965301 -0.136177, + -0.0248404 -0.049314801 -0.13382301, + -0.0220857 -0.0494138 -0.131502, + -0.019305199 -0.049261801 -0.129215, + -0.0165099 -0.0488628 -0.126963, + -0.0137106 -0.048222199 -0.124747, + -0.0109179 -0.047345702 -0.122569, + -0.0081428103 -0.046240099 -0.120429, + -0.0053973799 -0.044915602 -0.11833, + -0.00268824 -0.043382999 -0.116272, + 0 -0.041653499 -0.114257, + 0.00268824 -0.043382201 -0.116273, + 0.0053973799 -0.044914 -0.118331, + 0.0081428103 -0.046237599 -0.120431, + 0.0109179 -0.0473422 -0.122571, + 0.0137106 -0.048217699 -0.12475, + 0.0165099 -0.048857301 -0.126966, + 0.019305199 -0.049255099 -0.129218, + 0.0220857 -0.049405899 -0.131506, + 0.0248404 -0.049305499 -0.133827, + 0.027557701 -0.048954502 -0.13618, + 0.0302257 -0.048354998 -0.138567, + 0.0328326 -0.047509301 -0.140985, + 0.035366699 -0.046421401 -0.143434, + 0.0378174 -0.045099098 -0.145915, + 0.040174201 -0.0435513 -0.14842799, + 0.0424264 -0.0417872 -0.15097301, + 0.044564299 -0.039817002 -0.153551, + 0.0465803 -0.0376564 -0.15616401, + 0.039609101 -0.045067899 -0.1815, + 0.0404175 -0.044344399 -0.16150001, + 0.0424264 -0.042381998 -0.158897, + 0.044022799 -0.040746599 -0.16150001, + 0.040174201 -0.044400599 -0.156324, + 0.0378174 -0.046215899 -0.153778, + 0.035366699 -0.047814999 -0.15125699, + 0.0328326 -0.049186099 -0.14875799, + 0.0302257 -0.050320599 -0.14628001, + 0.027557701 -0.051213801 -0.143824, + 0.0248404 -0.051861901 -0.141389, + 0.0220857 -0.052261502 -0.13897499, + 0.019305199 -0.052410901 -0.136583, + 0.0165099 -0.052312098 -0.134213, + 0.0137106 -0.0519679 -0.13186599, + 0.0109179 -0.051382098 -0.129545, + 0.0081428103 -0.0505604 -0.12725, + 0.0053973799 -0.049511001 -0.124982, + 0.00268824 -0.048242901 -0.122746, + 0 -0.046765499 -0.120541, + -0.00268824 -0.048243798 -0.122745, + -0.0053973799 -0.0495128 -0.124981, + -0.0081428103 -0.050563101 -0.127248, + -0.0109179 -0.051385801 -0.12954301, + -0.0137106 -0.051972799 -0.131864, + -0.0165099 -0.052318301 -0.134211, + -0.019305199 -0.0524185 -0.136581, + -0.0220857 -0.0522701 -0.138973, + -0.0248404 -0.051871002 -0.141387, + -0.027557701 -0.051222499 -0.143822, + -0.0302257 -0.050328501 -0.14627799, + -0.0328326 -0.049193501 -0.148756, + -0.035366699 -0.047823399 -0.151255, + -0.0378174 -0.046227299 -0.153779, + -0.040174201 -0.044414598 -0.15632699, + -0.037813999 -0.0465759 -0.16150001, + -0.035726301 -0.048204001 -0.16150001, + -0.0378174 -0.0465465 -0.15895, + -0.034765299 -0.048901699 -0.1815, + -0.0353618 -0.048460599 -0.16150001, + -0.034755301 -0.048887499 -0.16150001, + -0.035366699 -0.0484333 -0.158972, + 0.0302257 -0.051663999 -0.156497, + 0.0328326 -0.050053999 -0.156459, + 0.0302257 -0.051459901 -0.153964, + 0.027557701 -0.052924499 -0.154016, + 0.027557701 -0.052632902 -0.151483, + 0.0248404 -0.0539499 -0.151545, + 0.0248404 -0.053566601 -0.149014, + 0.0220857 -0.054733999 -0.14908201, + 0.0220857 -0.054256901 -0.14655501, + 0.019305199 -0.055273499 -0.146626, + 0.019305199 -0.054701 -0.144108, + 0.0165099 -0.055568799 -0.144178, + 0.0165099 -0.054899301 -0.141671, + 0.0137106 -0.055621199 -0.141738, + 0.0137106 -0.054853201 -0.139246, + 0.0109179 -0.055432301 -0.13930701, + 0.0109179 -0.0545654 -0.136833, + 0.0081428103 -0.0550052 -0.136884, + 0.0081428103 -0.054039501 -0.134434, + 0.0053973799 -0.054345701 -0.13447399, + 0.0053973799 -0.0532813 -0.13205101, + 0.00268824 -0.053460501 -0.132076, + 0.00268824 -0.052297901 -0.129685, + 0 -0.0523565 -0.129694, + 0 -0.0510979 -0.12733901, + -0.00268824 -0.0522989 -0.129685, + -0.00268824 -0.053461399 -0.132076, + -0.0053973799 -0.0532832 -0.13204999, + -0.0053973799 -0.054347798 -0.134473, + -0.0081428103 -0.0540425 -0.134433, + -0.0081428103 -0.0550084 -0.13688301, + -0.0109179 -0.054569699 -0.136832, + -0.0109179 -0.055436499 -0.139305, + -0.0137106 -0.054858599 -0.139245, + -0.0137106 -0.055626199 -0.141737, + -0.0165099 -0.0549054 -0.14167, + -0.0165099 -0.0555741 -0.144177, + -0.019305199 -0.054707199 -0.144106, + -0.019305199 -0.055278499 -0.146625, + -0.0220857 -0.054262701 -0.14655299, + -0.0220857 -0.054738902 -0.14907999, + -0.0248404 -0.0535722 -0.149012, + -0.0248404 -0.053955801 -0.151544, + -0.027557701 -0.052639499 -0.151482, + -0.027557701 -0.052932899 -0.154016, + -0.0302257 -0.051469099 -0.153965, + -0.0302257 -0.0516745 -0.156499, + -0.0328326 -0.050065499 -0.156461, + -0.0328326 -0.0501846 -0.15899301, + -0.033319298 -0.0498982 -0.16150001, + -0.035366699 -0.048315 -0.15641899, + -0.0328326 -0.0498612 -0.153908, + -0.0302257 -0.0511772 -0.15141299, + -0.027557701 -0.052257799 -0.14893501, + -0.0248404 -0.053098101 -0.14647201, + -0.0220857 -0.0536936 -0.144023, + -0.019305199 -0.054040801 -0.141589, + -0.0165099 -0.054139901 -0.13916899, + -0.0137106 -0.053993799 -0.136765, + -0.0109179 -0.053605501 -0.134377, + -0.0081428103 -0.052979302 -0.132007, + -0.0053973799 -0.052121501 -0.129657, + -0.00268824 -0.0510405 -0.12732901, + 0 -0.049745299 -0.12502401, + 0.00268824 -0.051039599 -0.12732901, + 0.0053973799 -0.052119698 -0.129658, + 0.0081428103 -0.0529764 -0.132008, + 0.0109179 -0.0536015 -0.134378, + 0.0137106 -0.053988401 -0.136766, + 0.0165099 -0.054133501 -0.139171, + 0.019305199 -0.0540336 -0.141591, + 0.0220857 -0.0536866 -0.144025, + 0.0248404 -0.053091601 -0.146474, + 0.027557701 -0.0522516 -0.148937, + 0.0302257 -0.051169999 -0.15141401, + 0.0328326 -0.049851201 -0.153907, + 0.035366699 -0.048302699 -0.156417, + 0.0378174 -0.046415899 -0.156372, + 0.035366699 -0.048101202 -0.153845, + 0.0328326 -0.049563099 -0.15133899, + 0.0302257 -0.050790701 -0.14885101, + 0.027557701 -0.051778901 -0.146382, + 0.0248404 -0.052523799 -0.143931, + 0.0220857 -0.0530218 -0.141497, + 0.019305199 -0.0532704 -0.139081, + 0.0165099 -0.0532711 -0.136683, + 0.0137106 -0.053026602 -0.134305, + 0.0109179 -0.052540202 -0.131947, + 0.0081428103 -0.051816199 -0.129611, + 0.0053973799 -0.050862301 -0.12729999, + 0.00268824 -0.0496874 -0.12501401, + 0 -0.0483004 -0.122757, + -0.00268824 -0.049688201 -0.12501299, + -0.0053973799 -0.0508641 -0.127299, + -0.0081428103 -0.051819 -0.12961, + -0.0109179 -0.052544098 -0.131945, + -0.0137106 -0.053031798 -0.134303, + -0.0165099 -0.0532775 -0.13668101, + -0.019305199 -0.053277899 -0.139079, + -0.0220857 -0.053029899 -0.141495, + -0.0248404 -0.052531701 -0.143929, + -0.027557701 -0.051786099 -0.14638001, + -0.0302257 -0.0507975 -0.148849, + -0.0328326 -0.049570899 -0.151338, + -0.035366699 -0.048111901 -0.153846, + -0.0378174 -0.046429101 -0.15637501, + -0.040174201 -0.044531099 -0.158926, + -0.039599199 -0.045056298 -0.16150001, + -0.040172402 -0.044562198 -0.16150001, + -0.0402769 -0.044472098 -0.16150001, + 0.040174201 -0.044519901 -0.158923, + 0.040169802 -0.0445593 -0.16150001, + 0.038194101 -0.046273202 -0.16150001, + 0.0395981 -0.045055199 -0.16150001, + 0.0378174 -0.046535999 -0.15894701, + 0.035366699 -0.048423499 -0.15897, + 0.035878699 -0.0480907 -0.16150001, + 0.0328326 -0.050175499 -0.15899099, + 0.034754898 -0.048886999 -0.16150001, + 0.0302257 -0.051786002 -0.15900999, + 0.030994801 -0.051374301 -0.16150001, + 0.027557701 -0.053129699 -0.156532, + 0.0248404 -0.054242998 -0.154063, + 0.0220857 -0.0551189 -0.1516, + 0.019305199 -0.0557523 -0.149141, + 0.0165099 -0.056143101 -0.146687, + 0.0137106 -0.0562925 -0.144237, + 0.0109179 -0.056201901 -0.141792, + 0.0081428103 -0.055873498 -0.13935301, + 0.0053973799 -0.0553126 -0.13692001, + 0.00268824 -0.054525699 -0.134496, + 0 -0.053519301 -0.132084, + -0.00268824 -0.054526702 -0.134496, + -0.0053973799 -0.055314701 -0.13691901, + -0.0081428103 -0.055876698 -0.13935199, + -0.0109179 -0.056205899 -0.141791, + -0.0137106 -0.0562969 -0.144236, + -0.0165099 -0.0561474 -0.146686, + -0.019305199 -0.055756599 -0.14914, + -0.0220857 -0.0551241 -0.151599, + -0.0248404 -0.054250501 -0.154063, + -0.027557701 -0.053139299 -0.156534, + -0.0302257 -0.051794499 -0.159012, + -0.030832 -0.051472198 -0.16150001, + -0.032826498 -0.050209999 -0.16150001, + -0.029552899 -0.0522171 -0.1815, + -0.019305199 -0.056648899 -0.156617, + -0.019305199 -0.056771401 -0.159072, + -0.0165099 -0.057522099 -0.156638, + -0.0165099 -0.057312701 -0.154172, + -0.0137106 -0.058040202 -0.15419801, + -0.0137106 -0.057741798 -0.151722, + -0.0109179 -0.0583263 -0.15175, + -0.0109179 -0.057936601 -0.149268, + -0.0081428103 -0.0583812 -0.149294, + -0.0081428103 -0.057898201 -0.146809, + -0.0053973799 -0.058208201 -0.14683001, + -0.0053973799 -0.057629999 -0.144345, + -0.00268824 -0.057811301 -0.14436001, + -0.00268824 -0.057136599 -0.14187799, + 0 -0.057195202 -0.141884, + 0 -0.0564228 -0.13941, + 0.00268824 -0.057135601 -0.14187799, + 0.00268824 -0.0578105 -0.14436001, + 0.0053973799 -0.0576283 -0.144345, + 0.0053973799 -0.0582068 -0.14683101, + 0.0081428103 -0.057895999 -0.146809, + 0.0081428103 -0.058379401 -0.149294, + 0.0109179 -0.057934102 -0.149268, + 0.0109179 -0.0583237 -0.15175, + 0.0137106 -0.057738502 -0.151723, + 0.0137106 -0.058036 -0.15419701, + 0.0165099 -0.057307702 -0.154172, + 0.0165099 -0.057516299 -0.156637, + 0.019305199 -0.056642201 -0.156616, + 0.022079499 -0.055771399 -0.16150001, + 0.0231252 -0.055364501 -0.16150001, + 0.0220857 -0.055743899 -0.159058, + 0.0240272 -0.054979 -0.1815, + 0.020382199 -0.056432001 -0.16150001, + 0.019305199 -0.056766 -0.15907, + 0.0165055 -0.0576673 -0.16150001, + 0.0175901 -0.0573637 -0.16150001, + 0.0165099 -0.0576404 -0.159081, + 0.018242801 -0.057145901 -0.16150001, + 0.0137106 -0.058245301 -0.156654, + 0.0109179 -0.058621898 -0.154218, + 0.0081428103 -0.058769599 -0.15177099, + 0.0053973799 -0.0586906 -0.149312, + 0.00268824 -0.058389202 -0.146843, + 0 -0.057870299 -0.144365, + -0.00268824 -0.058389898 -0.146843, + -0.0053973799 -0.0586918 -0.149312, + -0.0081428103 -0.058771499 -0.15177099, + -0.0109179 -0.058625199 -0.154218, + -0.0137106 -0.058249999 -0.156655, + -0.0165099 -0.057645001 -0.159082, + -0.018242201 -0.0571438 -0.16150001, + -0.019300301 -0.056794401 -0.16150001, + -0.0202034 -0.056496199 -0.16150001, + -0.0220857 -0.055750102 -0.15906, + 0.0248404 -0.054572199 -0.159044, + 0.0258127 -0.054163702 -0.16150001, + 0.027557701 -0.053252298 -0.15902799, + 0.0248404 -0.054449201 -0.156564, + 0.0220857 -0.055620398 -0.156592, + 0.0220857 -0.055413298 -0.15410399, + 0.019305199 -0.0564343 -0.15414099, + 0.019305199 -0.056138702 -0.151647, + 0.0165099 -0.057011001 -0.15168899, + 0.0165099 -0.056623399 -0.14919201, + 0.0137106 -0.057349801 -0.149234, + 0.0137106 -0.056868199 -0.14673699, + 0.0109179 -0.057451598 -0.146778, + 0.0109179 -0.056874599 -0.144284, + 0.0081428103 -0.057318199 -0.14432, + 0.0081428103 -0.056644399 -0.14183301, + 0.0053973799 -0.056953799 -0.141862, + 0.0053973799 -0.056182001 -0.139385, + 0.00268824 -0.056363199 -0.139403, + 0.00268824 -0.055493299 -0.136941, + 0 -0.055552602 -0.136948, + 0 -0.054584801 -0.13450401, + -0.00268824 -0.055494301 -0.136941, + -0.00268824 -0.056364302 -0.139403, + -0.0053973799 -0.056184102 -0.139384, + -0.0053973799 -0.056955799 -0.14186101, + -0.0081428103 -0.056647401 -0.14183199, + -0.0081428103 -0.0573208 -0.14432, + -0.0109179 -0.056878101 -0.144283, + -0.0109179 -0.0574544 -0.146777, + -0.0137106 -0.056871802 -0.146736, + -0.0137106 -0.057352901 -0.149234, + -0.0165099 -0.056627098 -0.14919101, + -0.0165099 -0.057014901 -0.15168799, + -0.019305199 -0.056143198 -0.151647, + -0.019305199 -0.0564401 -0.15414099, + -0.0220857 -0.05542 -0.15410499, + -0.0220857 -0.055628099 -0.15659299, + -0.0248404 -0.054457799 -0.156565, + -0.0248404 -0.054579198 -0.15904599, + -0.027557701 -0.053259999 -0.15903001, + -0.0256411 -0.054245099 -0.16150001, + -0.027551601 -0.053284001 -0.16150001, + -0.0240272 -0.054979 -0.1815, + -0.024020201 -0.054963201 -0.16150001, + -0.0229499 -0.055437401 -0.16150001, + -0.024834501 -0.0546025 -0.16150001, + 0.0240207 -0.054964401 -0.16150001, + 0.0248338 -0.054601099 -0.16150001, + 0.027550699 -0.053282399 -0.16150001, + 0.028437899 -0.0528326 -0.16150001, + 0.029552899 -0.0522171 -0.1815, + 0.032825101 -0.050207902 -0.16150001, + 0.034765299 -0.048901699 -0.1815, + 0.033477101 -0.049792401 -0.16150001, + 0.0182469 -0.057158101 -0.1815, + 0.0192999 -0.056793101 -0.16150001, + 0.0147556 -0.058157299 -0.16150001, + 0.0137106 -0.058369599 -0.15909, + 0.0109179 -0.058831599 -0.15666801, + 0.0081428103 -0.0590683 -0.15423401, + 0.0053973799 -0.059081201 -0.151786, + 0.00268824 -0.0588733 -0.149323, + 0 -0.058449101 -0.14684699, + -0.00268824 -0.058873899 -0.149323, + -0.0053973799 -0.059082501 -0.151785, + -0.0081428103 -0.059070799 -0.15423401, + -0.0109179 -0.058835398 -0.15666901, + -0.0137106 -0.058373399 -0.159091, + -0.0137073 -0.058397699 -0.16150001, + -0.0122706 -0.058720101 -0.16150001, + -0.0145714 -0.058203701 -0.16150001, + -0.016505901 -0.057668701 -0.16150001, + -0.0182469 -0.057158101 -0.1815, + -0.017408401 -0.057419099 -0.16150001, + -0.022080099 -0.055772699 -0.16150001, + -0.0282706 -0.052922402 -0.16150001, + -0.029544 -0.052201401 -0.16150001, + -0.0302194 -0.051819 -0.16150001, + 0.0295441 -0.052201699 -0.16150001, + 0.0302184 -0.051817201 -0.16150001, + 0.035360001 -0.0484582 -0.16150001, + 0.037811901 -0.046573199 -0.16150001, + 0.0137069 -0.058396202 -0.16150001, + 0.0122713 -0.0587232 -0.16150001, + -0.0081412597 -0.059432399 -0.16150001, + -0.0061684698 -0.0596756 -0.16150001, + 0.0061689499 -0.059679601 -0.16150001, + 0.00814093 -0.0594301 -0.16150001, + 0.0057835602 0.059720598 -0.16150001, + 0.00923343 0.059285302 -0.1815, + 0.0081407595 0.059433799 -0.16150001, + 0.00870548 0.059365101 -0.16150001, + 0.0109156 0.058985401 -0.16150001, + 0.017317699 0.057446498 -0.16150001, + 0.021165101 0.056143001 -0.1815, + 0.019300601 0.056795198 -0.16150001, + 0.0201142 0.056527998 -0.16150001, + 0.022080399 0.055773601 -0.16150001, + 0.024834899 0.054603402 -0.16150001, + 0.0322018 0.050626501 -0.1815, + 0.030750699 0.051520798 -0.16150001, + 0.032827299 0.050211199 -0.16150001, + 0.035362698 0.048462 -0.16150001, + 0.041876599 0.0429691 -0.1815, + 0.0402066 0.0445357 -0.16150001, + 0.042342398 0.0425102 -0.16150001, + 0.042424399 0.0424245 -0.16150001, + 0.044376299 0.040382501 -0.16150001, + 0.044564299 0.040291 -0.154309, + 0.0465803 0.037935998 -0.154365, + 0.046066999 0.038430501 -0.16150001, + 0.048467699 0.035487 -0.154423, + 0.048119001 0.035840798 -0.16150001, + 0.050219599 0.0329546 -0.15448301, + 0.0497793 0.033493701 -0.16150001, + 0.051830001 0.030694401 -0.14756601, + 0.0532961 0.0286284 -0.14075799, + 0.0546159 0.0267832 -0.134074, + 0.055787299 0.025182299 -0.127537, + 0.056809202 0.023851801 -0.121167, + 0.0576833 0.022816701 -0.114989, + 0.058412101 0.0220955 -0.109029, + 0.058998398 0.021703299 -0.103318, + 0.059445001 0.0216491 -0.097886004, + 0.059757002 0.021937501 -0.092762001, + 0.0599402 0.0225609 -0.087976001, + 0.059999999 0.0234836 -0.083554, + 0.0599402 0.0245765 -0.079494998, + 0.059757002 0.0257785 -0.075836003, + 0.059445001 0.0270695 -0.072617002, + 0.058998398 0.026613999 -0.071851999, + 0.058412101 0.0262015 -0.071280003, + 0.0576833 0.025841599 -0.070900999, + 0.056809202 0.025542499 -0.070717998, + 0.055787299 0.025308801 -0.070730001, + 0.0546159 0.025133699 -0.070941001, + 0.0532961 0.0271709 -0.069968998, + 0.051830001 0.0273131 -0.070422001, + 0.050219599 0.0275546 -0.070929997, + 0.048467699 0.027866701 -0.071483999, + 0.0465803 0.0282644 -0.072012, + 0.044564299 0.028758699 -0.072504997, + 0.0424264 0.029358201 -0.072953999, + 0.040174201 0.0300697 -0.073344998, + 0.0378174 0.030897699 -0.073666997, + 0.035366699 0.031845 -0.073904999, + 0.0328326 0.032913599 -0.074042998, + 0.0302257 0.034102902 -0.074066997, + 0.027557701 0.035408601 -0.073963001, + 0.0248404 0.036823299 -0.073719002, + 0.0220857 0.038337201 -0.073319003, + 0.019305199 0.039937999 -0.072752997, + 0.0165099 0.041609999 -0.072012, + 0.0137106 0.043335699 -0.071089998, + 0.0109179 0.045097198 -0.069983996, + 0.0081428103 0.046875399 -0.068694003, + 0.0053973799 0.048650902 -0.067221001, + 0.00268824 0.0504044 -0.065572999, + 0 0.052117199 -0.063755997, + -0.00268824 0.0504044 -0.065572001, + -0.0053973799 0.048651401 -0.067220002, + -0.0081428103 0.046876501 -0.068691999, + -0.0109179 0.045098901 -0.069982, + -0.0137106 0.043338399 -0.071087003, + -0.0165099 0.041613799 -0.072007999, + -0.019305199 0.0399432 -0.072747998, + -0.0220857 0.038343798 -0.073314004, + -0.0248404 0.036831401 -0.073714003, + -0.027557701 0.035418399 -0.073959, + -0.0302257 0.034114301 -0.074063003, + -0.0328326 0.032926399 -0.074040003, + -0.035366699 0.0318592 -0.073903002, + -0.0378174 0.0309131 -0.073666997, + -0.040174201 0.0300861 -0.073347002, + -0.0424264 0.029375101 -0.072957002, + -0.044564299 0.0287749 -0.072508998, + -0.0465803 0.028278001 -0.072016999, + -0.048467699 0.0278755 -0.071491003, + -0.050219599 0.0275594 -0.070933998, + -0.051830001 0.0273191 -0.070409, + -0.0532961 0.0271725 -0.069968998, + -0.0546159 0.027122701 -0.069576003, + -0.055787299 0.027205899 -0.069259003, + -0.056809202 0.0274298 -0.069105998, + -0.0576833 0.027716599 -0.069155, + -0.058412101 0.0280586 -0.069403999, + -0.058998398 0.028448399 -0.069853999, + -0.058998398 0.026618799 -0.071840003, + -0.058412101 0.0262058 -0.071268, + -0.0576833 0.0258427 -0.070891999, + -0.056809202 0.025536601 -0.070712999, + -0.055787299 0.0252943 -0.070730001, + -0.0546159 0.025122801 -0.070943996, + -0.0532961 0.0251025 -0.071313001, + -0.051830001 0.025225099 -0.071748003, + -0.050219599 0.025451699 -0.072217003, + -0.048467699 0.0257801 -0.072755001, + -0.0465803 0.026193701 -0.073308997, + -0.044564299 0.0267023 -0.073821999, + -0.0424264 0.027313201 -0.074288003, + -0.040174201 0.0280337 -0.074697003, + -0.0378174 0.028868699 -0.075035997, + -0.035366699 0.029821901 -0.075291999, + -0.0328326 0.030895 -0.075451002, + -0.0302257 0.032088298 -0.075498, + -0.027557701 0.033398099 -0.07542, + -0.0248404 0.0348185 -0.075204998, + -0.0220857 0.036340799 -0.074840002, + -0.019305199 0.037954099 -0.074312001, + -0.0165099 0.039643802 -0.073614001, + -0.0137106 0.0413935 -0.072737001, + -0.0109179 0.043185301 -0.071679004, + -0.0081428103 0.045001 -0.070435002, + -0.0053973799 0.0468213 -0.069009997, + -0.00268824 0.0486269 -0.067406997, + 0 0.050398901 -0.065632999, + 0.00268824 0.048626602 -0.067406997, + 0.0053973799 0.0468206 -0.069011003, + 0.0081428103 0.0449997 -0.070436999, + 0.0109179 0.0431832 -0.071681999, + 0.0137106 0.0413903 -0.072741002, + 0.0165099 0.039639398 -0.073618002, + 0.019305199 0.0379484 -0.074317001, + 0.0220857 0.036333598 -0.074844003, + 0.0248404 0.034809701 -0.075208999, + 0.027557701 0.033387799 -0.075423002, + 0.0302257 0.0320765 -0.075499997, + 0.0328326 0.0308818 -0.075452, + 0.035366699 0.029807501 -0.075291999, + 0.0378174 0.0288532 -0.075034, + 0.040174201 0.028017599 -0.074694, + 0.0424264 0.0272977 -0.074284002, + 0.044564299 0.0266893 -0.073817, + 0.0465803 0.0261853 -0.073302999, + 0.048467699 0.025775401 -0.072751001, + 0.050219599 0.0254458 -0.072228998, + 0.051830001 0.0252236 -0.071748003, + 0.0532961 0.023078701 -0.072603002, + 0.0546159 0.023192899 -0.072338998, + 0.055787299 0.023374001 -0.072268002, + 0.056809202 0.023629 -0.072387002, + 0.0576833 0.0239536 -0.072696999, + 0.058412101 0.02434 -0.073197998, + 0.058998398 0.0247794 -0.073890001, + 0.059445001 0.023455201 -0.076973997, + 0.059757002 0.022231201 -0.080507003, + 0.0599402 0.0211093 -0.084457003, + 0.059999999 0.020144099 -0.088786997, + 0.0599402 0.0194607 -0.093493, + 0.059757002 0.019099001 -0.098545499, + 0.059445001 0.019088 -0.103908, + 0.058998398 0.019428801 -0.109549, + 0.058412101 0.020112701 -0.115441, + 0.0576833 0.021125199 -0.121552, + 0.056809202 0.022448201 -0.127856, + 0.055787299 0.024057001 -0.13432799, + 0.0546159 0.0259264 -0.140947, + 0.0532961 0.028032901 -0.147691, + 0.051830001 0.0303494 -0.15454499, + 0.051398799 0.030954201 -0.16150001, + 0.052855 0.0283962 -0.16150001, + 0.052960701 0.0281986 -0.1815, + 0.0518176 0.030218599 -0.16150001, + 0.0484588 0.0353604 -0.16150001, + 0.0460728 0.038435601 -0.1815, + 0.0465739 0.037812401 -0.16150001, + 0.046303399 0.0381575 -0.16150001, + 0.04456 0.040170401 -0.16150001, + 0.058998398 0.00545217 -0.099792004, + 0.059445001 0.0065221102 -0.1018, + 0.058998398 0.0070209899 -0.097167999, + 0.058412101 0.0044676499 -0.097921997, + 0.058412101 0.0061154701 -0.095394999, + 0.0576833 0.00357722 -0.096194997, + 0.0576833 0.0053016501 -0.093771003, + 0.056809202 0.0027886401 -0.094614998, + 0.056809202 0.0045873299 -0.092298001, + 0.055787299 0.00210937 -0.093184002, + 0.055787299 0.0039765802 -0.090976, + 0.0546159 0.0015435 -0.091902003, + 0.0546159 0.0034607199 -0.089805, + 0.0532961 0.00108374 -0.090768002, + 0.0532961 0.0030465301 -0.088785, + 0.051830001 0.00073678 -0.089781001, + 0.051830001 0.0027441599 -0.087917998, + 0.050219599 0.00051215402 -0.088944003, + 0.050219599 0.0025617599 -0.087205, + 0.048467699 0.00041727201 -0.088255003, + 0.048467699 0.00250599 -0.086641997, + 0.0465803 0.00045749001 -0.087710999, + 0.0465803 0.0025816499 -0.086227, + 0.044564299 0.00063688803 -0.087307997, + 0.044564299 0.0027925801 -0.085956, + 0.0424264 0.00095878099 -0.087040998, + 0.0424264 0.00314286 -0.085819997, + 0.040174201 0.0014262 -0.086902, + 0.040174201 0.0036353299 -0.085812002, + 0.0378174 0.0020395501 -0.086883001, + 0.0378174 0.0042699398 -0.085920997, + 0.035366699 0.0027978499 -0.086972997, + 0.035366699 0.0050427802 -0.086139999, + 0.0328326 0.00369685 -0.087163001, + 0.0328326 0.0059394501 -0.086462997, + 0.0302257 0.0047213901 -0.087448001, + 0.0302257 0.0094549004 -0.086149, + 0.027557701 0.0083848396 -0.087126002, + 0.027557701 0.0107891 -0.086415, + 0.0248404 0.0098438701 -0.087329999, + 0.0248404 0.0122612 -0.086580001, + 0.0220857 0.0114389 -0.087421998, + 0.0220857 0.013857 -0.086635999, + 0.019305199 0.013156 -0.087393999, + 0.019305199 0.0155734 -0.086557001, + 0.0165099 0.0149895 -0.087227002, + 0.0165099 0.0174032 -0.086336002, + 0.0137106 0.0169308 -0.086911, + 0.0137106 0.0193367 -0.085964002, + 0.0109179 0.0189695 -0.086441003, + 0.0109179 0.0213628 -0.085435003, + 0.0081428103 0.021093801 -0.085809, + 0.0081428103 0.0234692 -0.084739998, + 0.0053973799 0.023289399 -0.085009001, + 0.0053973799 0.025641199 -0.083875999, + 0.00268824 0.025541 -0.084036998, + 0.00268824 0.027863501 -0.082837, + 0 0.027833 -0.082891002, + 0 0.030120499 -0.081624001, + -0.00268824 0.0278646 -0.082837, + -0.00268824 0.025542 -0.084036998, + -0.0053973799 0.0256433 -0.083875, + -0.0053973799 0.023291601 -0.085009001, + -0.0081428103 0.023472499 -0.084739998, + -0.0081428103 0.0210972 -0.085809, + -0.0109179 0.0213673 -0.085435003, + -0.0109179 0.0189739 -0.086442001, + -0.0137106 0.0193421 -0.085965, + -0.0137106 0.016935799 -0.086912997, + -0.0165099 0.0174092 -0.086337, + -0.0165099 0.0149943 -0.087228999, + -0.019305199 0.015579 -0.086558998, + -0.019305199 0.0131595 -0.087397002, + -0.0220857 0.013861 -0.086639002, + -0.0220857 0.011441 -0.087422997, + -0.0248404 0.0122636 -0.086581998, + -0.0248404 0.0098467804 -0.087323003, + -0.027557701 0.0107923 -0.086407997, + -0.027557701 0.0083856303 -0.087126002, + -0.0302257 0.00945576 -0.086149, + -0.0302257 0.0070573199 -0.086832002, + -0.0328326 0.00825457 -0.085801996, + -0.0328326 0.0059329499 -0.086464003, + -0.035366699 0.00725751 -0.085392997, + -0.035366699 0.0050335899 -0.086139999, + -0.0378174 0.0064829299 -0.085037999, + -0.0378174 0.00426606 -0.085918002, + -0.040174201 0.0058382298 -0.084794, + -0.040174201 0.0036361101 -0.085804999, + -0.0424264 0.00532836 -0.084668003, + -0.0424264 0.0031459699 -0.085812002, + -0.044564299 0.0049546398 -0.084670998, + -0.044564299 0.0027962299 -0.085946001, + -0.0465803 0.0047152801 -0.084810004, + -0.0465803 0.0025847901 -0.086217999, + -0.048467699 0.00460723 -0.085093997, + -0.048467699 0.00250836 -0.086634003, + -0.050219599 0.0046267202 -0.085529, + -0.050219599 0.0025633499 -0.087196998, + -0.051830001 0.0047694501 -0.086116999, + -0.051830001 0.00274504 -0.087912001, + -0.0532961 0.0050293999 -0.086861998, + -0.0532961 0.00304687 -0.088779002, + -0.0546159 0.0053992802 -0.087764002, + -0.0546159 0.0034607099 -0.0898, + -0.055787299 0.0058704098 -0.088823996, + -0.055787299 0.0039760298 -0.090972997, + -0.056809202 0.0064318599 -0.090038002, + -0.056809202 0.00458505 -0.092294, + -0.0576833 0.0070762001 -0.091403, + -0.0576833 0.0052949102 -0.093763001, + -0.058998398 0.0054374901 -0.099778101, + -0.058998398 0.0070078201 -0.097154997, + -0.059445001 0.00650626 -0.101785, + -0.058412101 0.0044546202 -0.097910002, + -0.058412101 0.0061048698 -0.095385, + -0.0576833 0.0035667501 -0.096184999, + -0.056809202 0.00278201 -0.094607003, + -0.055787299 0.0021071299 -0.093180001, + -0.0546159 0.00154297 -0.091899, + -0.0532961 0.00108373 -0.090763003, + -0.051830001 0.000737108 -0.089776002, + -0.050219599 0.000513001 -0.088937998, + -0.048467699 0.000418802 -0.088248, + -0.0465803 0.00045976799 -0.087702997, + -0.044564299 0.00063988997 -0.087298997, + -0.0424264 0.000962255 -0.087033004, + -0.040174201 0.00142915 -0.086893998, + -0.0378174 0.00204028 -0.086877003, + -0.035366699 0.0027942201 -0.086970001, + -0.0328326 0.0036883201 -0.087163001, + -0.0302257 0.0047154101 -0.087448999, + -0.027557701 0.0059673502 -0.087769002, + -0.0248404 0.0074223001 -0.088005997, + -0.0220857 0.00900752 -0.088136002, + -0.019305199 0.0107234 -0.088156998, + -0.0165099 0.0125595 -0.088045001, + -0.0137106 0.0145067 -0.087785996, + -0.0109179 0.0165549 -0.087375998, + -0.0081428103 0.018693199 -0.086805999, + -0.0053973799 0.020908199 -0.086071, + -0.00268824 0.023185199 -0.085166998, + 0 0.025508599 -0.084090002, + 0.00268824 0.0231841 -0.085166998, + 0.0053973799 0.020905999 -0.086070001, + 0.0081428103 0.018689901 -0.086805001, + 0.0109179 0.0165509 -0.087375, + 0.0137106 0.0145027 -0.087784998, + 0.0165099 0.0125565 -0.088042997, + 0.019305199 0.0107215 -0.088156, + 0.0220857 0.00900493 -0.088142, + 0.0248404 0.0074215899 -0.088005997, + 0.027557701 0.0036124601 -0.088344, + 0.0302257 0.0024596101 -0.088104002, + 0.0328326 0.00143143 -0.087949, + 0.035366699 0.00054560002 -0.087885998, + 0.0378174 -0.00019263101 -0.087922998, + 0.040174201 -0.00078188698 -0.088072002, + 0.0424264 -0.00122165 -0.088340998, + 0.044564299 -0.0015124599 -0.088738002, + 0.0465803 -0.00165659 -0.089270003, + 0.048467699 -0.00165758 -0.089941002, + 0.050219599 -0.00152006 -0.090755001, + 0.051830001 -0.00125013 -0.091712996, + 0.0532961 -0.000856528 -0.092814997, + 0.0546159 -0.00034564699 -0.094062001, + 0.055787299 0.00028895601 -0.095454, + 0.056809202 0.00104266 -0.096993998, + 0.0576833 0.0019082 -0.098678201, + 0.058412101 0.00287817 -0.100504, + 0.058998398 0.0039444398 -0.102467, + 0.059999999 0.00900348 -0.111584, + 0.059999999 0.0079012001 -0.114605, + 0.0599402 0.0115705 -0.111083, + 0.0599402 0.0064364602 -0.112085, + 0.0599402 0.0076241498 -0.109129, + 0.059757002 0.0050535402 -0.109669, + 0.059757002 0.0063267401 -0.106785, + 0.059445001 0.0037392001 -0.107369, + 0.058998398 0.00250083 -0.10519, + 0.058412101 0.00135035 -0.103138, + 0.0576833 0.00029800099 -0.101218, + 0.056809202 -0.00064753799 -0.099432997, + 0.055787299 -0.00147847 -0.097787999, + 0.0546159 -0.0021875801 -0.096285, + 0.0532961 -0.00276731 -0.094926998, + 0.051830001 -0.0032130401 -0.093712002, + 0.050219599 -0.00353055 -0.092637002, + 0.048467699 -0.00371394 -0.091701001, + 0.0465803 -0.00375585 -0.090906002, + 0.044564299 -0.00365092 -0.090246998, + 0.0424264 -0.0033950601 -0.089720003, + 0.040174201 -0.0029857899 -0.089321002, + 0.0378174 -0.00242336 -0.089042999, + 0.035366699 -0.00170815 -0.088878997, + 0.0328326 -0.00084110198 -0.088817, + 0.0302257 0.000175361 -0.088846996, + 0.027557701 0.0013332 -0.088959999, + 0.0248404 0.0026141801 -0.089151002, + 0.0220857 0.0065665999 -0.088786997, + 0.019305199 0.00827312 -0.088849999, + 0.0165099 0.0101079 -0.088784002, + 0.0137106 0.0120566 -0.088583998, + 0.0109179 0.0141112 -0.088234, + 0.0081428103 0.0162616 -0.087727003, + 0.0053973799 0.018494699 -0.087058999, + 0.00268824 0.020795999 -0.086223997, + 0 0.023150099 -0.085217997, + -0.00268824 0.0207971 -0.086223997, + -0.0053973799 0.018496901 -0.087058999, + -0.0081428103 0.016264601 -0.087728001, + -0.0109179 0.0141144 -0.088234998, + -0.0137106 0.0120591 -0.088586003, + -0.0165099 0.0101095 -0.088785, + -0.019305199 0.0082753804 -0.088845, + -0.0220857 0.00656723 -0.088786997, + -0.0248404 0.0049861702 -0.088613003, + -0.027557701 0.00360701 -0.088345997, + -0.0302257 0.00245175 -0.088104002, + -0.0328326 0.00142806 -0.087945998, + -0.035366699 0.00054628699 -0.08788, + -0.0378174 -0.00018985401 -0.087916002, + -0.040174201 -0.00077859702 -0.088063002, + -0.0424264 -0.00121879 -0.088333003, + -0.044564299 -0.00151028 -0.088730998, + -0.0465803 -0.0016551201 -0.089263, + -0.048467699 -0.00165676 -0.089934997, + -0.050219599 -0.00151975 -0.090750001, + -0.051830001 -0.00125014 -0.091709003, + -0.0532961 -0.00085705001 -0.092812002, + -0.0546159 -0.00034783999 -0.094058, + -0.055787299 0.00028244001 -0.095446996, + -0.056809202 0.00103235 -0.096983001, + -0.0576833 0.00189533 -0.098665804, + -0.058412101 0.00286363 -0.10049, + -0.058998398 0.0039287098 -0.102453, + -0.059445001 0.0050810101 -0.104548, + -0.059757002 0.0076501402 -0.103927, + -0.059757002 0.0063090301 -0.106771, + -0.059757002 0.0026968899 -0.115531, + -0.059757002 0.00163568 -0.118515, + -0.059445001 5.9643e-005 -0.116008, + -0.059445001 0.00120883 -0.113088, + -0.058998398 -0.00144101 -0.113605, + -0.058998398 -0.000202913 -0.110756, + -0.058412101 -0.0028526899 -0.111312, + -0.058412101 -0.00152574 -0.108538, + -0.0576833 -0.0041639698 -0.109133, + -0.0576833 -0.0027486901 -0.106441, + -0.056809202 -0.0053643999 -0.107073, + -0.056809202 -0.0038616301 -0.104469, + -0.055787299 -0.0064441301 -0.105137, + -0.055787299 -0.0048550898 -0.102626, + -0.0546159 -0.00739385 -0.103328, + -0.0546159 -0.00572058 -0.100916, + -0.0532961 -0.0082047498 -0.10165, + -0.0532961 -0.0064498102 -0.0993414, + -0.051830001 -0.0088687604 -0.100104, + -0.051830001 -0.0070351502 -0.097903997, + -0.050219599 -0.0093786502 -0.0986913, + -0.050219599 -0.0074703898 -0.096603997, + -0.048467699 -0.0097287996 -0.097411998, + -0.048467699 -0.0077543398 -0.095436998, + -0.0465803 -0.0099189002 -0.096261002, + -0.0465803 -0.0078911204 -0.094400004, + -0.044564299 -0.0099526905 -0.095234998, + -0.044564299 -0.00787553 -0.093493, + -0.0424264 -0.00982536 -0.094333999, + -0.0424264 -0.0077012898 -0.092713997, + -0.040174201 -0.0095317401 -0.093555003, + -0.040174201 -0.0073646801 -0.09206, + -0.0378174 -0.0090707904 -0.092895001, + -0.0378174 -0.0068653701 -0.091525003, + -0.035366699 -0.0084431199 -0.092348002, + -0.035366699 -0.0062044701 -0.091104001, + -0.0328326 -0.0076502701 -0.091908, + -0.0328326 -0.00538377 -0.090791002, + -0.0302257 -0.0066951499 -0.091567002, + -0.0302257 -0.0044057299 -0.090575002, + -0.027557701 -0.0055831098 -0.091317996, + -0.027557701 -0.0032756999 -0.090447001, + -0.0248404 -0.0043203901 -0.091149002, + -0.0248404 -0.00200011 -0.090397, + -0.0220857 -0.00291356 -0.091049999, + -0.0220857 -0.00058668002 -0.090415001, + -0.019305199 -0.00137119 -0.091012001, + -0.019305199 0.00095120602 -0.090493999, + -0.0165099 0.00029047899 -0.091027997, + -0.0165099 0.00270566 -0.090573996, + -0.0137106 0.0021637599 -0.09104, + -0.0137106 0.0046512401 -0.090535998, + -0.0109179 0.0042233202 -0.090926997, + -0.0109179 0.00670677 -0.090364002, + -0.0081428103 0.0063867001 -0.090673998, + -0.0081428103 0.00887217 -0.090049997, + -0.0053973799 0.0086529097 -0.090274997, + -0.0053973799 0.0111355 -0.089583002, + -0.00268824 0.0110096 -0.089718997, + -0.00268824 0.0134837 -0.088955998, + 0 0.0134433 -0.089001998, + 0 0.015903 -0.088165998, + 0.00268824 0.0134829 -0.088955998, + 0.00268824 0.0110091 -0.089717999, + 0.0053973799 0.0111345 -0.089582004, + 0.0053973799 0.00865239 -0.090273999, + 0.0081428103 0.0088713802 -0.090049997, + 0.0081428103 0.0063857399 -0.090676002, + 0.0109179 0.0067054899 -0.090366997, + 0.0109179 0.00422301 -0.090926997, + 0.0137106 0.0046508401 -0.090535998, + 0.0137106 -0.00025771401 -0.091472998, + 0.0165099 0.00029375 -0.091027997, + 0.0165099 -0.00203791 -0.091522999, + 0.019305199 -0.00136617 -0.091012001, + 0.019305199 -0.00370838 -0.091622002, + 0.0220857 -0.0029112899 -0.091053002, + 0.0220857 -0.0052481 -0.091775, + 0.0248404 -0.0043208702 -0.091153003, + 0.0248404 -0.0066448199 -0.091991, + 0.027557701 -0.0055851298 -0.091323003, + 0.027557701 -0.0078912703 -0.09228, + 0.0302257 -0.0066976198 -0.091573998, + 0.0302257 -0.0089813396 -0.092652999, + 0.0328326 -0.0076524802 -0.091913998, + 0.0328326 -0.0099092098 -0.093117997, + 0.035366699 -0.0084448503 -0.092354, + 0.035366699 -0.0106691 -0.093682997, + 0.0378174 -0.0090719797 -0.092900999, + 0.0378174 -0.0112585 -0.094354004, + 0.040174201 -0.00953242 -0.093560003, + 0.040174201 -0.0116764 -0.095137, + 0.0424264 -0.0098256199 -0.094338, + 0.0424264 -0.0119229 -0.096037, + 0.044564299 -0.0099526802 -0.095238, + 0.044564299 -0.012 -0.097055003, + 0.0465803 -0.0099184401 -0.096262999, + 0.0465803 -0.0119109 -0.098196, + 0.048467699 -0.0097268503 -0.097415, + 0.048467699 -0.0116511 -0.099462599, + 0.050219599 -0.0093727903 -0.098697796, + 0.050219599 -0.0112232 -0.100858, + 0.051830001 -0.0088593503 -0.100113, + 0.051830001 -0.0106323 -0.102382, + 0.0532961 -0.0081928596 -0.101661, + 0.0532961 -0.0098848399 -0.104034, + 0.0546159 -0.0073802602 -0.103341, + 0.0546159 -0.0089881299 -0.105813, + 0.055787299 -0.0064292601 -0.105151, + 0.055787299 -0.0079504801 -0.107716, + 0.056809202 -0.0053483699 -0.107087, + 0.056809202 -0.0067814901 -0.109741, + 0.0576833 -0.0041468702 -0.109147, + 0.0576833 -0.0054909498 -0.111883, + 0.058412101 -0.00283465 -0.111325, + 0.058412101 -0.00408907 -0.114138, + 0.058998398 -0.0014222 -0.113618, + 0.058998398 -0.0025867801 -0.116502, + 0.059445001 7.9035999e-005 -0.11602, + 0.059445001 -0.00099641294 -0.11897, + 0.059757002 0.0016556 -0.118526, + 0.059757002 0.00066821702 -0.121536, + 0.0599402 0.00329859 -0.121131, + 0.0599402 0.00239812 -0.124196, + 0.059999999 0.0050204601 -0.123826, + 0.059999999 0.0034638001 -0.13007, + 0.0599402 0.00610743 -0.12976199, + 0.0599402 0.0048597101 -0.136114, + 0.059757002 0.0075409701 -0.135865, + 0.059757002 0.00659225 -0.14229999, + 0.059445001 0.0093223602 -0.14210901, + 0.059445001 0.0086645996 -0.14860199, + 0.058998398 0.011433 -0.148472, + 0.058998398 0.0110537 -0.15500399, + 0.058412101 0.0138447 -0.154938, + 0.0588204 0.0118392 -0.16150001, + -0.059757002 0.0050350898 -0.109656, + -0.059757002 0.0038304101 -0.112577, + -0.059445001 0.00243013 -0.110203, + -0.059445001 0.0037215799 -0.107355, + -0.058998398 0.00110623 -0.107945, + -0.058998398 0.00248418 -0.105176, + -0.058412101 -0.000129145 -0.105808, + -0.058412101 0.00133478 -0.103124, + -0.0576833 -0.00126533 -0.103797, + -0.0576833 0.00028363999 -0.101204, + -0.056809202 -0.00229257 -0.101917, + -0.056809202 -0.00066021102 -0.099420801, + -0.055787299 -0.0032021799 -0.100172, + -0.055787299 -0.0014886 -0.097778, + -0.0546159 -0.0039861798 -0.0985649, + -0.0546159 -0.0021939599 -0.096277997, + -0.0532961 -0.00463671 -0.097098999, + -0.0532961 -0.00276945 -0.094922997, + -0.051830001 -0.0051471498 -0.095774002, + -0.051830001 -0.00321355 -0.093708999, + -0.050219599 -0.0055160699 -0.094585001, + -0.050219599 -0.0035305601 -0.092633002, + -0.048467699 -0.0057473499 -0.093530998, + -0.048467699 -0.0037136299 -0.091697, + -0.0465803 -0.0058352598 -0.092611998, + -0.0465803 -0.00375506 -0.090899996, + -0.044564299 -0.0057728998 -0.091826998, + -0.044564299 -0.00364951 -0.090240002, + -0.0424264 -0.00555549 -0.091173999, + -0.0424264 -0.00339299 -0.089713, + -0.040174201 -0.0051800902 -0.090645999, + -0.040174201 -0.00298309 -0.089313999, + -0.0378174 -0.0046468601 -0.090237997, + -0.0378174 -0.0024202601 -0.089036003, + -0.035366699 -0.0039571798 -0.089946002, + -0.035366699 -0.00170555 -0.088872001, + -0.0328326 -0.00311246 -0.089759, + -0.0328326 -0.00084046402 -0.088811003, + -0.0302257 -0.0021152 -0.089667998, + -0.0302257 0.000172259 -0.088844001, + -0.027557701 -0.00097098399 -0.089662001, + -0.027557701 0.00132604 -0.088959999, + -0.0248404 0.00031271399 -0.089731, + -0.0248404 0.0026092599 -0.089152999, + -0.0220857 0.0017236799 -0.089869, + -0.0220857 0.00411525 -0.089362003, + -0.019305199 0.0033555301 -0.090015002, + -0.019305199 0.00582133 -0.089468002, + -0.0165099 0.0051832902 -0.090049997, + -0.0165099 0.0076490999 -0.089451, + -0.0137106 0.0071268301 -0.089956999, + -0.0137106 0.0095976004 -0.089308999, + -0.0109179 0.0091858702 -0.089730002, + -0.0109179 0.0116566 -0.089019999, + -0.0081428103 0.0113499 -0.089351997, + -0.0081428103 0.0138155 -0.088577002, + -0.0053973799 0.0136065 -0.088816002, + -0.0053973799 0.0160616 -0.087975003, + -0.00268824 0.0159423 -0.088119, + -0.00268824 0.018381501 -0.087208003, + 0 0.0183434 -0.087256998, + 0 0.020760501 -0.086273998, + 0.00268824 0.0183804 -0.087208003, + 0.00268824 0.015941299 -0.088119, + 0.0053973799 0.0160597 -0.087973997, + 0.0053973799 0.0136049 -0.088815004, + 0.0081428103 0.0138131 -0.088575996, + 0.0081428103 0.0113484 -0.08935, + 0.0109179 0.0116546 -0.089019001, + 0.0109179 0.0091848196 -0.089729004, + 0.0137106 0.0095962798 -0.089308001, + 0.0137106 0.00712523 -0.089961, + 0.0165099 0.00764716 -0.089455999, + 0.0165099 0.0051828101 -0.090049997, + 0.019305199 0.0058207801 -0.089468002, + 0.019305199 0.00095502997 -0.090493001, + 0.0220857 0.0017280499 -0.089868002, + 0.0220857 -0.00058093801 -0.090415001, + 0.0248404 0.00031917199 -0.089731, + 0.0248404 -0.00199756 -0.090400003, + 0.027557701 -0.00096815597 -0.089663997, + 0.027557701 -0.0032762401 -0.090452, + 0.0302257 -0.00211579 -0.089672998, + 0.0302257 -0.0044079502 -0.090581, + 0.0328326 -0.0031148701 -0.089766003, + 0.0328326 -0.0053864601 -0.090797, + 0.035366699 -0.0039600702 -0.089952998, + 0.035366699 -0.0062068501 -0.091110997, + 0.0378174 -0.00464941 -0.090245999, + 0.0378174 -0.0068672202 -0.091531001, + 0.040174201 -0.0051820599 -0.090651996, + 0.040174201 -0.0073659499 -0.092065997, + 0.0424264 -0.0055568302 -0.091179997, + 0.0424264 -0.007702 -0.092719004, + 0.044564299 -0.00577365 -0.091833003, + 0.044564299 -0.0078758197 -0.093497001, + 0.0465803 -0.0058355602 -0.092616998, + 0.0465803 -0.0078911101 -0.094402999, + 0.048467699 -0.0057473402 -0.093534999, + 0.048467699 -0.00775387 -0.09544, + 0.050219599 -0.0055155801 -0.094587997, + 0.050219599 -0.0074683698 -0.096607998, + 0.051830001 -0.0051450701 -0.095776998, + 0.051830001 -0.0070290999 -0.097911, + 0.0532961 -0.00463048 -0.097106002, + 0.0532961 -0.0064401301 -0.099351101, + 0.0546159 -0.0039762598 -0.098574802, + 0.0546159 -0.0057083899 -0.100928, + 0.055787299 -0.00318973 -0.100184, + 0.055787299 -0.0048412001 -0.102639, + 0.056809202 -0.0022784299 -0.10193, + 0.056809202 -0.00384648 -0.104483, + 0.0576833 -0.00124995 -0.103811, + 0.0576833 -0.0027324201 -0.106455, + 0.058412101 -0.000112664 -0.105822, + 0.058412101 -0.00150842 -0.108552, + 0.058998398 0.00112372 -0.107959, + 0.058998398 -0.000184695 -0.110769, + 0.059445001 0.0024484801 -0.110216, + 0.059445001 0.00122777 -0.113101, + 0.059757002 0.00384945 -0.112589, + 0.059757002 0.0027163799 -0.115543, + 0.0599402 0.00531884 -0.115072, + 0.0599402 0.0042725299 -0.118089, + 0.059999999 0.0068692402 -0.117655, + 0.059999999 0.0059086499 -0.120729, + 0.0599402 0.0094659403 -0.117221, + 0.0599402 0.00764278 -0.123455, + 0.059757002 0.0102855 -0.123082, + 0.059757002 0.00877159 -0.12945101, + 0.059445001 0.0114714 -0.129136, + 0.059445001 0.0102581 -0.135612, + 0.058998398 0.0130046 -0.13535701, + 0.058998398 0.0120819 -0.14191499, + 0.058412101 0.014859 -0.141721, + 0.058412101 0.0142191 -0.148341, + 0.0576833 0.0170117 -0.14821, + 0.0576833 0.016642399 -0.154871, + 0.056809202 0.019436 -0.154805, + 0.057377499 0.0175448 -0.16150001, + 0.0575951 0.0167653 -0.16150001, + 0.057608999 0.0167691 -0.1815, + 0.057667602 0.016505601 -0.16150001, + 0.058168899 0.0147097 -0.16150001, + 0.0583965 0.013707 -0.16150001, + 0.059027899 0.0107568 -0.1815, + 0.059996702 7.3000002e-008 -0.16150001, + 0.059980098 -0.00154487 -0.1815, + 0.059999801 0.000142344 -0.16150001, + 0.059445001 -0.00687264 -0.143242, + 0.059757002 -0.0041424399 -0.143051, + 0.059445001 -0.0058601 -0.13711201, + 0.0599402 -0.0025446101 -0.15532801, + 0.059962399 -0.00154448 -0.16150001, + 0.059999999 0.00014212901 -0.15526401, + 0.0599402 -0.0021408 -0.14911, + 0.059757002 -0.00484356 -0.14923701, + 0.058998398 -0.0096322997 -0.143435, + 0.059445001 -0.0075825402 -0.14936601, + 0.059757002 -0.0052522598 -0.15539201, + 0.059934601 -0.0028003999 -0.16150001, + 0.059749398 -0.0053968299 -0.16150001, + 0.059937101 -0.0026881699 -0.16150001, + 0.059931301 0.002688 -0.16150001, + 0.059920698 0.0030847499 -0.16150001, + 0.059821099 0.0046305298 -0.1815, + 0.059430599 0.0081410101 -0.16150001, + 0.059330199 0.0089402199 -0.16150001, + 0.059011199 0.0107539 -0.16150001, + 0.058982901 0.0109151 -0.16150001, + -0.0599402 0.0064173499 -0.112072, + 0.059757002 0.0120828 -0.116783, + 0.059445001 0.0129635 -0.122704, + 0.058998398 0.0142004 -0.12881801, + 0.058412101 0.0157685 -0.13509899, + 0.0576833 0.017642699 -0.141526, + 0.056809202 0.0198003 -0.14807799, + 0.055787299 0.0222147 -0.15473901, + 0.056448001 0.0203376 -0.16150001, + 0.055569701 0.0225999 -0.16150001, + 0.055771701 0.0220796 -0.16150001, + 0.056793399 0.019300001 -0.16150001, + 0.053282801 0.0275509 -0.16150001, + 0.0532961 0.0276832 -0.15460899, + 0.052956201 0.028196299 -0.16150001, + 0.0546159 0.025322201 -0.147819, + 0.055787299 0.0231872 -0.141138, + 0.056809202 0.0213053 -0.13458399, + 0.0576833 0.0196994 -0.128176, + 0.058412101 0.018394601 -0.121938, + 0.058998398 0.017415199 -0.115892, + 0.059445001 0.016779 -0.110066, + 0.059757002 0.016500499 -0.104491, + 0.0599402 0.016582601 -0.099196702, + 0.059999999 0.017002899 -0.094218999, + 0.0599402 0.017727399 -0.089598998, + 0.059757002 0.0187164 -0.085368, + 0.059445001 0.0198544 -0.081532001, + 0.058998398 0.0211068 -0.078124002, + 0.058998398 0.019275401 -0.080320001, + 0.058412101 0.0187435 -0.079281002, + 0.058412101 0.0206082 -0.077198997, + 0.0576833 0.0182683 -0.078419, + 0.0576833 0.020164801 -0.076454997, + 0.056809202 0.017858099 -0.077737004, + 0.056809202 0.0197846 -0.075894997, + 0.055787299 0.0175207 -0.077235997, + 0.055787299 0.0194763 -0.075521, + 0.0546159 0.017264299 -0.076915003, + 0.0546159 0.0192477 -0.075328998, + 0.0532961 0.017096801 -0.076773003, + 0.0532961 0.019106301 -0.075318001, + 0.051830001 0.017025501 -0.076805003, + 0.051830001 0.019056199 -0.075484, + 0.050219599 0.017053699 -0.077007003, + 0.050219599 0.019089401 -0.075828999, + 0.048467699 0.017172899 -0.077377997, + 0.048467699 0.021471201 -0.075175002, + 0.0465803 0.0196824 -0.076807998, + 0.0465803 0.0218754 -0.075685002, + 0.044564299 0.0201874 -0.077319004, + 0.044564299 0.0224002 -0.076204002, + 0.0424264 0.0208189 -0.077822998, + 0.0424264 0.023023101 -0.076722004, + 0.040174201 0.021556299 -0.078308001, + 0.040174201 0.0237554 -0.077179, + 0.0378174 0.0224081 -0.078722998, + 0.0378174 0.0246033 -0.077564999, + 0.035366699 0.023379199 -0.079056002, + 0.035366699 0.0255701 -0.077871002, + 0.0328326 0.0244717 -0.079296, + 0.0328326 0.026657499 -0.078082003, + 0.0302257 0.025685901 -0.079430997, + 0.0302257 0.027865401 -0.078185998, + 0.027557701 0.0270187 -0.079448, + 0.027557701 0.0291906 -0.078169003, + 0.0248404 0.0284652 -0.079334997, + 0.0248404 0.030628501 -0.078020997, + 0.0220857 0.030019799 -0.079080001, + 0.0220857 0.032172799 -0.077728003, + 0.019305199 0.031674501 -0.078672998, + 0.019305199 0.033814501 -0.077279001, + 0.0165099 0.033417899 -0.078103997, + 0.0165099 0.035541199 -0.076665998, + 0.0137106 0.035236701 -0.077367, + 0.0137106 0.037338499 -0.075880997, + 0.0109179 0.0371156 -0.076453, + 0.0109179 0.0391904 -0.074918002, + 0.0081428103 0.039037999 -0.07536, + 0.0081428103 0.041079201 -0.073774002, + 0.0053973799 0.040985301 -0.074084997, + 0.0053973799 0.042986002 -0.072446004, + 0.00268824 0.042938501 -0.072631001, + 0.00268824 0.044891901 -0.070938997, + 0 0.044879001 -0.071000002, + 0 0.046778101 -0.069257997, + -0.00268824 0.0448923 -0.070938997, + -0.00268824 0.042939 -0.072630003, + -0.0053973799 0.042987 -0.072444998, + -0.0053973799 0.040986501 -0.074083999, + -0.0081428103 0.041081101 -0.073771, + -0.0081428103 0.0390401 -0.075358003, + -0.0109179 0.039193299 -0.074915998, + -0.0109179 0.037118901 -0.076451004, + -0.0137106 0.037342601 -0.075878002, + -0.0137106 0.035241202 -0.077363998, + -0.0165099 0.035546601 -0.076663002, + -0.0165099 0.0334238 -0.078102, + -0.019305199 0.0338213 -0.077275999, + -0.019305199 0.031681702 -0.078671001, + -0.0220857 0.032181099 -0.077725001, + -0.0220857 0.030028399 -0.079079002, + -0.0248404 0.0306383 -0.078019001, + -0.0248404 0.028475201 -0.079333998, + -0.027557701 0.029201699 -0.078167997, + -0.027557701 0.02703 -0.079448, + -0.0302257 0.0278777 -0.078185998, + -0.0302257 0.0256983 -0.079432003, + -0.0328326 0.026670899 -0.078083999, + -0.0328326 0.0244848 -0.079299003, + -0.035366699 0.0255842 -0.077872999, + -0.035366699 0.0233921 -0.079058997, + -0.0378174 0.0246171 -0.077569, + -0.0378174 0.022419199 -0.078726999, + -0.040174201 0.023767101 -0.077183001, + -0.040174201 0.021563601 -0.078313999, + -0.0424264 0.0230307 -0.076728001, + -0.0424264 0.020823 -0.077826001, + -0.044564299 0.022404499 -0.076208003, + -0.044564299 0.020192601 -0.077307999, + -0.0465803 0.0218808 -0.075672999, + -0.0465803 0.019683801 -0.076807998, + -0.048467699 0.021472599 -0.075175002, + -0.048467699 0.019296899 -0.076306, + -0.050219599 0.0211809 -0.074685, + -0.050219599 0.019079501 -0.075831003, + -0.051830001 0.021050701 -0.074236996, + -0.051830001 0.019042701 -0.075484999, + -0.0532961 0.0210918 -0.073926002, + -0.0532961 0.0191008 -0.075313002, + -0.0546159 0.0212199 -0.073798001, + -0.0546159 0.0192487 -0.075319998, + -0.055787299 0.0214292 -0.073856004, + -0.055787299 0.0194804 -0.075508997, + -0.056809202 0.021713199 -0.074101001, + -0.056809202 0.019789301 -0.075883999, + -0.0576833 0.022065399 -0.074536003, + -0.0576833 0.020168699 -0.076444, + -0.058412101 0.0224788 -0.075159997, + -0.058412101 0.0206111 -0.077188998, + -0.058998398 0.0211087 -0.078115001, + -0.052944701 0.028228801 -0.16150001, + -0.052960001 0.028198199 -0.16150001, + -0.0532961 0.0276646 -0.154612, + -0.051830001 0.030331399 -0.154548, + -0.0532961 0.028020199 -0.14769, + -0.0546159 0.025309199 -0.147817, + -0.0546159 0.0259121 -0.14094301, + -0.055787299 0.0231726 -0.14113399, + -0.055787299 0.0240364 -0.134323, + -0.056809202 0.0212844 -0.134579, + -0.056809202 0.022426 -0.12785, + -0.0576833 0.0196769 -0.12817, + -0.0576833 0.021104701 -0.121543, + -0.058412101 0.0183738 -0.121929, + -0.058412101 0.020093299 -0.11543, + -0.058998398 0.0173955 -0.115881, + -0.058998398 0.019409999 -0.109537, + -0.059445001 0.0167601 -0.110054, + -0.059445001 0.0190704 -0.103894, + -0.059757002 0.0164828 -0.104477, + -0.059757002 0.019083099 -0.098531, + -0.0599402 0.016566601 -0.099182099, + -0.0599402 0.019447301 -0.093480997, + -0.059999999 0.016989499 -0.094207004, + -0.059999999 0.0201371 -0.088779002, + -0.0599402 0.017720399 -0.089590997, + -0.0599402 0.0211087 -0.084453002, + -0.059757002 0.018715899 -0.085363999, + -0.059757002 0.022231501 -0.080500998, + -0.059445001 0.019854801 -0.081525996, + -0.059445001 0.023457101 -0.076964997, + -0.058998398 0.024783401 -0.073879004, + -0.058412101 0.0243448 -0.073187001, + -0.0576833 0.023957901 -0.072686002, + -0.056809202 0.023630099 -0.072378002, + -0.055787299 0.0233682 -0.072263002, + -0.0546159 0.0231787 -0.072338998, + -0.0532961 0.0230681 -0.072604999, + -0.051830001 0.023119001 -0.073018998, + -0.050219599 0.023322299 -0.073485002, + -0.048467699 0.023636401 -0.073973998, + -0.0465803 0.024059299 -0.074515, + -0.044564299 0.024576399 -0.075057, + -0.0424264 0.0251965 -0.075545996, + -0.040174201 0.025925601 -0.075976998, + -0.0378174 0.026768601 -0.076338001, + -0.035366699 0.0277289 -0.076617002, + -0.0328326 0.028808899 -0.076800004, + -0.0302257 0.0300087 -0.076872997, + -0.027557701 0.031325199 -0.076824002, + -0.0248404 0.032753401 -0.076641001, + -0.0220857 0.034285899 -0.076311, + -0.019305199 0.035912801 -0.075823002, + -0.0165099 0.037620701 -0.075166002, + -0.0137106 0.039394099 -0.074335001, + -0.0109179 0.041216198 -0.073324002, + -0.0081428103 0.043068599 -0.072130002, + -0.0053973799 0.0449326 -0.070752002, + -0.00268824 0.046788901 -0.069196999, + 0 0.0486187 -0.067468002, + 0.00268824 0.046788499 -0.069196999, + 0.0053973799 0.044931699 -0.070753999, + 0.0081428103 0.043067101 -0.072131999, + 0.0109179 0.041213699 -0.073326997, + 0.0137106 0.039390501 -0.074339002, + 0.0165099 0.037615798 -0.075170003, + 0.019305199 0.035906501 -0.075825997, + 0.0220857 0.034278098 -0.076315001, + 0.0248404 0.032744098 -0.076644003, + 0.027557701 0.031314399 -0.076826997, + 0.0302257 0.029996499 -0.076874003, + 0.0328326 0.0287956 -0.076800004, + 0.035366699 0.0277145 -0.076614998, + 0.0378174 0.0267535 -0.076334, + 0.040174201 0.025911 -0.075972997, + 0.0424264 0.0251841 -0.075542003, + 0.044564299 0.024568301 -0.075051002, + 0.0465803 0.024054799 -0.074510999, + 0.048467699 0.023630699 -0.073986001, + 0.050219599 0.0233208 -0.073486, + 0.051830001 0.021060999 -0.074234001, + 0.0532961 0.021105601 -0.073926002, + 0.0546159 0.021225501 -0.073803, + 0.055787299 0.021428101 -0.073864996, + 0.056809202 0.021709001 -0.074112996, + 0.0576833 0.0220607 -0.074547999, + 0.058412101 0.0224749 -0.075171001, + 0.058998398 0.022942699 -0.075980999, + -0.051496498 0.0307914 -0.16150001, + -0.050210599 0.0328269 -0.16150001, + -0.0497806 0.033494599 -0.1815, + -0.0499245 0.0332799 -0.16150001, + -0.048461299 0.035362199 -0.16150001, + -0.039609101 -0.045067899 -0.1815, + -0.038047399 -0.046393901 -0.16150001, + -0.042409498 -0.042443302 -0.16150001, + -0.0479904 -0.036012899 -0.1815, + -0.0465752 -0.037813399 -0.16150001, + -0.048175599 -0.035764702 -0.16150001, + -0.048459999 -0.035361301 -0.16150001, + -0.049871601 -0.033358999 -0.16150001, + -0.050219599 -0.032802399 -0.158785, + -0.048467699 -0.0352236 -0.15610801, + -0.0465803 -0.037477098 -0.153469, + -0.044564299 -0.039550502 -0.150866, + -0.0424264 -0.041430801 -0.14830101, + -0.040174201 -0.0431045 -0.145772, + -0.0378174 -0.044560298 -0.143279, + -0.035366699 -0.045788001 -0.14082, + -0.0328326 -0.046778198 -0.13839699, + -0.0302257 -0.047524001 -0.13600899, + -0.027557701 -0.048022401 -0.13365699, + -0.0248404 -0.0482715 -0.131341, + -0.0220857 -0.048270099 -0.129062, + -0.019305199 -0.048018899 -0.12682199, + -0.0165099 -0.0475225 -0.12462, + -0.0137106 -0.046786401 -0.122459, + -0.0109179 -0.045816801 -0.12034, + -0.0081428103 -0.044621799 -0.118263, + -0.0053973799 -0.043212 -0.11623, + -0.00268824 -0.041598301 -0.114242, + 0 -0.0397924 -0.112299, + 0.00268824 -0.041597601 -0.114243, + 0.0053973799 -0.043210398 -0.116232, + 0.0081428103 -0.0446194 -0.118266, + 0.0109179 -0.0458134 -0.120343, + 0.0137106 -0.046782002 -0.122462, + 0.0165099 -0.047517098 -0.124623, + 0.019305199 -0.048012499 -0.126825, + 0.0220857 -0.048262499 -0.12906601, + 0.0248404 -0.0482627 -0.13134401, + 0.027557701 -0.0480121 -0.13366, + 0.0302257 -0.0475123 -0.136012, + 0.0328326 -0.046765398 -0.1384, + 0.035366699 -0.045775 -0.14082301, + 0.0378174 -0.044548199 -0.143282, + 0.040174201 -0.043094002 -0.14577501, + 0.0424264 -0.041421302 -0.148304, + 0.044564299 -0.03954 -0.150868, + 0.0465803 -0.037462998 -0.153468, + 0.048467699 -0.035206798 -0.156105, + 0.050219599 -0.0327884 -0.15878201, + 0.050211899 -0.032827701 -0.16150001, + 0.051434901 -0.0308851 -0.16150001, + 0.050219599 -0.032484099 -0.153291, + 0.048467699 -0.034743499 -0.15064199, + 0.0465803 -0.0368293 -0.148035, + 0.044564299 -0.038727701 -0.14546999, + 0.0424264 -0.040425699 -0.142946, + 0.040174201 -0.041910801 -0.14046399, + 0.0378174 -0.043173298 -0.138024, + 0.035366699 -0.044204701 -0.135627, + 0.0328326 -0.044997301 -0.13327201, + 0.0302257 -0.0455442 -0.130961, + 0.027557701 -0.0458428 -0.128694, + 0.0248404 -0.045892902 -0.126471, + 0.0220857 -0.045694899 -0.124295, + 0.019305199 -0.045250401 -0.122164, + 0.0165099 -0.044564702 -0.120081, + 0.0137106 -0.043645199 -0.118047, + 0.0109179 -0.042499699 -0.116061, + 0.0081428103 -0.041136902 -0.114124, + 0.0053973799 -0.039567798 -0.112238, + 0.00268824 -0.0378047 -0.110402, + 0 -0.0358603 -0.108615, + -0.00268824 -0.0378053 -0.110401, + -0.0053973799 -0.039569099 -0.112237, + -0.0081428103 -0.0411391 -0.114122, + -0.0109179 -0.042502798 -0.116058, + -0.0137106 -0.043649301 -0.118043, + -0.0165099 -0.044569802 -0.120077, + -0.019305199 -0.0452566 -0.12216, + -0.0220857 -0.0457021 -0.12429, + -0.0248404 -0.045901202 -0.126467, + -0.027557701 -0.0458523 -0.12868901, + -0.0302257 -0.045554999 -0.13095701, + -0.0328326 -0.045009602 -0.133268, + -0.035366699 -0.044218499 -0.13562299, + -0.0378174 -0.043188099 -0.13802101, + -0.040174201 -0.041925602 -0.140461, + -0.0424264 -0.0404392 -0.14294299, + -0.044564299 -0.038739402 -0.145466, + -0.0465803 -0.036839802 -0.14803199, + -0.048467699 -0.034754898 -0.15064099, + -0.050219599 -0.032499298 -0.153292, + -0.051830001 -0.030086 -0.155986, + -0.0546159 -0.024811899 -0.15869001, + -0.0542247 -0.025684301 -0.16150001, + -0.0532961 -0.027528601 -0.158722, + -0.0532961 -0.0274198 -0.15592299, + -0.054602101 -0.024834299 -0.16150001, + -0.054336499 -0.0254324 -0.16150001, + -0.054342099 -0.0254349 -0.1815, + -0.053283598 -0.0275514 -0.16150001, + -0.050219599 -0.032691199 -0.156048, + -0.048467699 -0.035029899 -0.153382, + -0.0465803 -0.037199602 -0.150756, + -0.044564299 -0.039187402 -0.14816999, + -0.0424264 -0.040978801 -0.145623, + -0.040174201 -0.042560201 -0.143116, + -0.0378174 -0.043920498 -0.140646, + -0.035366699 -0.045049999 -0.138216, + -0.0328326 -0.045940898 -0.13582399, + -0.0302257 -0.0465867 -0.133471, + -0.027557701 -0.046984602 -0.13115899, + -0.0248404 -0.0471332 -0.128887, + -0.0220857 -0.0470323 -0.126656, + -0.019305199 -0.0466833 -0.124468, + -0.0165099 -0.0460908 -0.122323, + -0.0137106 -0.045260999 -0.120223, + -0.0109179 -0.0442013 -0.118168, + -0.0081428103 -0.042920299 -0.11616, + -0.0053973799 -0.0414286 -0.114198, + -0.00268824 -0.039737601 -0.112284, + 0 -0.037859701 -0.110418, + 0.00268824 -0.0397369 -0.112285, + 0.0053973799 -0.041427098 -0.114199, + 0.0081428103 -0.042918 -0.116162, + 0.0109179 -0.0441981 -0.118171, + 0.0137106 -0.045256801 -0.120226, + 0.0165099 -0.0460856 -0.122327, + 0.019305199 -0.046677001 -0.124472, + 0.0220857 -0.047024898 -0.12666, + 0.0248404 -0.047124699 -0.12889101, + 0.027557701 -0.046974801 -0.131163, + 0.0302257 -0.046575401 -0.13347501, + 0.0328326 -0.045928098 -0.135828, + 0.035366699 -0.0450362 -0.138219, + 0.0378174 -0.043906499 -0.14065, + 0.040174201 -0.042547401 -0.14311901, + 0.0424264 -0.040967699 -0.14562599, + 0.044564299 -0.039177299 -0.148173, + 0.0465803 -0.037188601 -0.150757, + 0.048467699 -0.035015199 -0.153381, + 0.050219599 -0.032673702 -0.156045, + -0.051438499 -0.0308873 -0.16150001, + -0.050209399 -0.0328261 -0.16150001, + -0.059503399 -0.0077038999 -0.1815, + -0.059431799 -0.0081411703 -0.16150001, + -0.058412101 -0.0124248 -0.14362501, + -0.0576833 -0.0147254 -0.140847, + -0.058412101 -0.0113924 -0.137619, + -0.058998398 -0.0096477596 -0.14342999, + -0.058998398 -0.010365 -0.14949401, + -0.059445001 -0.0075966101 -0.14936399, + -0.059445001 -0.0080169002 -0.155461, + -0.059757002 -0.0052730702 -0.155396, + -0.059706699 -0.0059254402 -0.16150001, + -0.0594863 -0.0077017802 -0.16150001, + -0.056809202 -0.0169292 -0.138134, + -0.055787299 -0.019021001 -0.135488, + -0.0546159 -0.0209869 -0.132912, + -0.0532961 -0.022812599 -0.130409, + -0.051830001 -0.0244841 -0.12797999, + -0.050219599 -0.0259878 -0.12562799, + -0.048467699 -0.0273114 -0.123356, + -0.0465803 -0.028444 -0.121165, + -0.044564299 -0.0293757 -0.119058, + -0.0424264 -0.0300973 -0.117035, + -0.040174201 -0.0306019 -0.115097, + -0.0378174 -0.030885801 -0.113246, + -0.035366699 -0.030946501 -0.111481, + -0.0328326 -0.030782299 -0.109802, + -0.0302257 -0.0303936 -0.108208, + -0.027557701 -0.0297844 -0.106697, + -0.0248404 -0.028960301 -0.105269, + -0.0220857 -0.027927101 -0.103919, + -0.019305199 -0.0266931 -0.102645, + -0.0165099 -0.025269 -0.101441, + -0.0137106 -0.023664599 -0.100307, + -0.0109179 -0.0218904 -0.099237897, + -0.0081428103 -0.0199579 -0.098228998, + -0.0053973799 -0.0178806 -0.097273998, + -0.00268824 -0.0156729 -0.096369997, + 0 -0.0133488 -0.095509, + 0.00268824 -0.015673099 -0.096369997, + 0.0053973799 -0.0178809 -0.097274996, + 0.0081428103 -0.019958099 -0.098229997, + 0.0109179 -0.021890599 -0.0992392, + 0.0137106 -0.0236647 -0.100308, + 0.0165099 -0.025269 -0.101443, + 0.019305199 -0.026692901 -0.102646, + 0.0220857 -0.027926199 -0.103921, + 0.0248404 -0.0289574 -0.105272, + 0.027557701 -0.029779401 -0.106702, + 0.0302257 -0.0303868 -0.108214, + 0.0328326 -0.0307741 -0.10981, + 0.035366699 -0.030936999 -0.111489, + 0.0378174 -0.0308751 -0.113255, + 0.040174201 -0.03059 -0.115107, + 0.0424264 -0.0300842 -0.117045, + 0.044564299 -0.029361499 -0.119067, + 0.0465803 -0.0284288 -0.121175, + 0.048467699 -0.0272952 -0.123365, + 0.050219599 -0.025970601 -0.12563699, + 0.051830001 -0.024465701 -0.127988, + 0.0532961 -0.0227926 -0.13041601, + 0.0546159 -0.0209656 -0.132919, + 0.055787299 -0.0189992 -0.13549399, + 0.056809202 -0.016908299 -0.13813899, + 0.0576833 -0.014707 -0.140852, + 0.058412101 -0.0124095 -0.143629, + 0.058998398 -0.0103511 -0.149496, + 0.059445001 -0.0079961997 -0.155458, + 0.059372 -0.0086586103 -0.16150001, + 0.059434399 -0.00814154 -0.16150001, + 0.0594876 -0.0077019902 -0.16150001, + 0.059725199 -0.0057364102 -0.16150001, + 0.059503399 -0.0077038999 -0.1815, + 0.058986001 -0.0109157 -0.16150001, + 0.058412101 -0.0119291 -0.140626, + 0.0576833 -0.0141415 -0.13788199, + 0.056809202 -0.0162553 -0.135207, + 0.055787299 -0.018256299 -0.132603, + 0.0546159 -0.0201304 -0.130073, + 0.0532961 -0.021862799 -0.12762, + 0.051830001 -0.023439299 -0.125247, + 0.050219599 -0.0248471 -0.122956, + 0.048467699 -0.0260744 -0.120749, + 0.0465803 -0.0271108 -0.118628, + 0.044564299 -0.027946901 -0.116596, + 0.0424264 -0.0285748 -0.114653, + 0.040174201 -0.028988101 -0.112799, + 0.0378174 -0.0291836 -0.111036, + 0.035366699 -0.029159101 -0.109363, + 0.0328326 -0.0289142 -0.10778, + 0.0302257 -0.0284499 -0.106284, + 0.027557701 -0.0277707 -0.104874, + 0.0248404 -0.026882101 -0.103548, + 0.0220857 -0.0257903 -0.102302, + 0.019305199 -0.0245043 -0.101133, + 0.0165099 -0.023033701 -0.100036, + 0.0137106 -0.0213887 -0.099008702, + 0.0109179 -0.0195802 -0.098044999, + 0.0081428103 -0.0176201 -0.097139001, + 0.0053973799 -0.0155221 -0.096285999, + 0.00268824 -0.0133002 -0.095481001, + 0 -0.0109675 -0.094714999, + -0.00268824 -0.0133 -0.095480002, + -0.0053973799 -0.0155217 -0.096285, + -0.0081428103 -0.017619699 -0.097138003, + -0.0109179 -0.0195799 -0.098043002, + -0.0137106 -0.021388501 -0.099007003, + -0.0165099 -0.0230336 -0.100035, + -0.019305199 -0.024504401 -0.101132, + -0.0220857 -0.0257905 -0.102301, + -0.0248404 -0.026883099 -0.103546, + -0.027557701 -0.027774001 -0.10487, + -0.0302257 -0.028455401 -0.106278, + -0.0328326 -0.0289215 -0.107773, + -0.035366699 -0.0291679 -0.109355, + -0.0378174 -0.029193699 -0.111027, + -0.040174201 -0.0289995 -0.112789, + -0.0424264 -0.0285873 -0.114643, + -0.044564299 -0.0279606 -0.116586, + -0.0465803 -0.027125601 -0.118618, + -0.048467699 -0.026090199 -0.120739, + -0.050219599 -0.0248638 -0.122947, + -0.051830001 -0.023457 -0.125238, + -0.0532961 -0.0218818 -0.12761199, + -0.0546159 -0.020150799 -0.13006601, + -0.055787299 -0.0182781 -0.132596, + -0.056809202 -0.0162776 -0.13520101, + -0.0576833 -0.0141628 -0.137877, + -0.0576833 -0.0135194 -0.134912, + -0.056809202 -0.0155439 -0.132277, + -0.055787299 -0.0174524 -0.12971801, + -0.0546159 -0.019231301 -0.12723801, + -0.0532961 -0.020866901 -0.124839, + -0.051830001 -0.022345901 -0.122526, + -0.050219599 -0.0236561 -0.120299, + -0.048467699 -0.024785699 -0.118162, + -0.0465803 -0.0257247 -0.116116, + -0.044564299 -0.026465001 -0.114164, + -0.0424264 -0.0269992 -0.112305, + -0.040174201 -0.0273214 -0.110542, + -0.0378174 -0.0274287 -0.108873, + -0.035366699 -0.0273201 -0.107299, + -0.0328326 -0.026995501 -0.105818, + -0.0302257 -0.026456101 -0.104427, + -0.027557701 -0.025707001 -0.103125, + -0.0248404 -0.024755901 -0.101907, + -0.0220857 -0.023610501 -0.100769, + -0.019305199 -0.022276901 -0.099707998, + -0.0165099 -0.020764399 -0.098719999, + -0.0137106 -0.0190838 -0.097800002, + -0.0109179 -0.0172463 -0.096942998, + -0.0081428103 -0.0152641 -0.096142001, + -0.0053973799 -0.0131507 -0.095392004, + -0.00268824 -0.0109193 -0.094685003, + 0 -0.0085824504 -0.094012998, + 0.00268824 -0.0109195 -0.094685003, + 0.0053973799 -0.0131512 -0.095393002, + 0.0081428103 -0.0152646 -0.096143, + 0.0109179 -0.0172469 -0.096945003, + 0.0137106 -0.0190842 -0.097801998, + 0.0165099 -0.020764699 -0.098722003, + 0.019305199 -0.022276999 -0.099709898, + 0.0220857 -0.023610501 -0.100771, + 0.0248404 -0.024755601 -0.101909, + 0.027557701 -0.0257059 -0.103127, + 0.0302257 -0.026452599 -0.104431, + 0.0328326 -0.026989499 -0.105824, + 0.035366699 -0.027312201 -0.107307, + 0.0378174 -0.027419301 -0.108882, + 0.040174201 -0.027310699 -0.110552, + 0.0424264 -0.026987201 -0.112316, + 0.044564299 -0.0264518 -0.114174, + 0.0465803 -0.0257104 -0.116127, + 0.048467699 -0.024770301 -0.118172, + 0.050219599 -0.023639699 -0.120309, + 0.051830001 -0.022328701 -0.122535, + 0.0532961 -0.0208486 -0.124848, + 0.0546159 -0.019211899 -0.12724601, + 0.055787299 -0.017431499 -0.12972599, + 0.056809202 -0.0155218 -0.132284, + 0.0576833 -0.0134969 -0.134918, + 0.058412101 -0.0113708 -0.137624, + 0.058998398 -0.0091579203 -0.14040001, + 0.058998398 -0.0086067002 -0.137367, + 0.058412101 -0.0107344 -0.134629, + 0.0576833 -0.0127727 -0.131963, + 0.056809202 -0.0147075 -0.129375, + 0.055787299 -0.016524499 -0.126867, + 0.0546159 -0.018210201 -0.124442, + 0.0532961 -0.019751299 -0.122104, + 0.051830001 -0.0211353 -0.119856, + 0.050219599 -0.022350101 -0.1177, + 0.048467699 -0.0233847 -0.115639, + 0.0465803 -0.0242303 -0.113674, + 0.044564299 -0.024879299 -0.111807, + 0.0424264 -0.0253246 -0.110038, + 0.040174201 -0.0255608 -0.108369, + 0.0378174 -0.0255863 -0.106797, + 0.035366699 -0.025400801 -0.105324, + 0.0328326 -0.0250047 -0.103945, + 0.0302257 -0.024399299 -0.10266, + 0.027557701 -0.02359 -0.101465, + 0.0248404 -0.022585699 -0.100356, + 0.0220857 -0.021392399 -0.099328302, + 0.019305199 -0.0200163 -0.098378003, + 0.0165099 -0.0184674 -0.097499996, + 0.0137106 -0.0167569 -0.096689001, + 0.0109179 -0.0148962 -0.095939003, + 0.0081428103 -0.0128972 -0.095242999, + 0.0053973799 -0.0107726 -0.094593003, + 0.00268824 -0.0085351402 -0.093980998, + 0 -0.0061978698 -0.093400002, + -0.00268824 -0.0085350797 -0.093980998, + -0.0053973799 -0.0107722 -0.094591998, + -0.0081428103 -0.0128965 -0.095241003, + -0.0109179 -0.0148954 -0.095936999, + -0.0137106 -0.016756199 -0.096686997, + -0.0165099 -0.018466899 -0.097498, + -0.019305199 -0.020016 -0.098375998, + -0.0220857 -0.0213922 -0.099326096, + -0.0248404 -0.022585699 -0.100354, + -0.027557701 -0.0235902 -0.101464, + -0.0302257 -0.024400501 -0.102658, + -0.0328326 -0.0250085 -0.103941, + -0.035366699 -0.025407299 -0.105317, + -0.0378174 -0.025594801 -0.106789, + -0.040174201 -0.025570801 -0.108359, + -0.0424264 -0.0253359 -0.110028, + -0.044564299 -0.024891799 -0.111796, + -0.0465803 -0.0242441 -0.113663, + -0.048467699 -0.023399699 -0.115628, + -0.050219599 -0.022366101 -0.117689, + -0.051830001 -0.0211522 -0.119846, + -0.0532961 -0.019769 -0.122094, + -0.0546159 -0.0182289 -0.124433, + -0.055787299 -0.0165444 -0.126858, + -0.056809202 -0.0147287 -0.12936699, + -0.0576833 -0.0127952 -0.13195699, + -0.058412101 -0.0107572 -0.13462301, + -0.058998398 -0.0086284801 -0.137362, + -0.059445001 -0.0068882201 -0.14323699, + -0.059757002 -0.0048576999 -0.149235, + -0.0599402 -0.0025654801 -0.155331, + -0.0599254 -0.0029901101 -0.16150001, + -0.0599331 -0.00268806 -0.16150001, + -0.059746101 -0.0053965598 -0.16150001, + -0.059821099 0.0046305298 -0.1815, + -0.059930101 0.00289505 -0.16150001, + -0.0599402 0.0028079699 -0.155203, + -0.059803601 0.0046292599 -0.16150001, + -0.0597477 0.0053966902 -0.16150001, + -0.058998398 0.0110331 -0.155008, + -0.058412101 0.0138244 -0.15494099, + -0.058857501 0.0116529 -0.16150001, + -0.058998398 0.0114191 -0.14847, + -0.0599402 0.0023767899 -0.124187, + -0.059757002 0.00064776099 -0.121526, + -0.0599402 0.0042525502 -0.118078, + -0.059999999 0.00499911 -0.123817, + -0.059999999 0.0034404199 -0.130063, + -0.0599402 0.0060840701 -0.12975501, + -0.0599402 0.0048375898 -0.13610899, + -0.059757002 0.0075189099 -0.13586, + -0.059757002 0.00657658 -0.142295, + -0.059445001 0.0093067801 -0.142104, + -0.059445001 0.0086505301 -0.1486, + -0.059445001 0.0082595702 -0.155074, + -0.059757002 0.00591155 -0.148729, + -0.0599402 0.0038824901 -0.14248399, + -0.059999999 0.00217697 -0.13635699, + -0.0599402 0.00079678802 -0.130372, + -0.059757002 -0.000265904 -0.12456, + -0.059445001 -0.00201777 -0.121937, + -0.059445001 -0.00101622 -0.118959, + -0.058998398 -0.0036967101 -0.119407, + -0.058998398 -0.0026060201 -0.11649, + -0.058412101 -0.0052886298 -0.116976, + -0.058412101 -0.00410769 -0.114126, + -0.0576833 -0.0067807101 -0.114647, + -0.0576833 -0.00550876 -0.11187, + -0.056809202 -0.0081609497 -0.112427, + -0.056809202 -0.0067983302 -0.109727, + -0.055787299 -0.0094186896 -0.110318, + -0.055787299 -0.0079662204 -0.107703, + -0.0546159 -0.0105439 -0.108326, + -0.0546159 -0.0090026902 -0.105799, + -0.0532961 -0.0115265 -0.106453, + -0.0532961 -0.0098981103 -0.104021, + -0.051830001 -0.0123569 -0.104702, + -0.051830001 -0.0106439 -0.102371, + -0.050219599 -0.0130271 -0.103075, + -0.050219599 -0.0112323 -0.100849, + -0.048467699 -0.0135298 -0.101573, + -0.048467699 -0.0116568 -0.0994564, + -0.0465803 -0.0138598 -0.100196, + -0.0465803 -0.0119128 -0.098192997, + -0.044564299 -0.0140131 -0.098943703, + -0.044564299 -0.0120005 -0.097052999, + -0.0424264 -0.0139897 -0.09781, + -0.0424264 -0.0119229 -0.096032999, + -0.040174201 -0.013793 -0.096790999, + -0.040174201 -0.0116762 -0.095132999, + -0.0378174 -0.0134215 -0.095886, + -0.0378174 -0.0112579 -0.094348997, + -0.035366699 -0.0128739 -0.095091999, + -0.035366699 -0.010668 -0.093677998, + -0.0328326 -0.0121506 -0.094403997, + -0.0328326 -0.0099076098 -0.093111999, + -0.0302257 -0.0112538 -0.093814999, + -0.0302257 -0.0089793 -0.092647001, + -0.027557701 -0.0101892 -0.093319997, + -0.027557701 -0.00788901 -0.092275001, + -0.0248404 -0.0089637404 -0.092910998, + -0.0248404 -0.0066430001 -0.091986001, + -0.0220857 -0.0075837802 -0.092579998, + -0.0220857 -0.0052476702 -0.091771998, + -0.019305199 -0.0060565602 -0.092315003, + -0.019305199 -0.00371036 -0.091619998, + -0.0165099 -0.0043919198 -0.092107996, + -0.0165099 -0.0020422 -0.091522999, + -0.0137106 -0.0026016801 -0.091948003, + -0.0137106 -0.00026043001 -0.091473997, + -0.0109179 -0.00070345303 -0.091833003, + -0.0109179 0.00172792 -0.091415003, + -0.0081428103 0.00139587 -0.091700003, + -0.0081428103 0.0038973 -0.091224998, + -0.0053973799 0.0036694801 -0.091433004, + -0.0053973799 0.0061629899 -0.090891004, + -0.00268824 0.0060316399 -0.091017999, + -0.00268824 0.0085241897 -0.090406001, + 0 0.0084820697 -0.090448998, + 0 0.0109683 -0.089763001, + 0.00268824 0.0085239299 -0.090406001, + 0.00268824 0.0060313302 -0.091018997, + 0.0053973799 0.0061623598 -0.090892002, + 0.0053973799 0.0036693199 -0.091433004, + 0.0081428103 0.00389707 -0.091224998, + 0.059757002 0.00553643 -0.15513501, + 0.0599402 0.0028288399 -0.1552, + 0.059803098 0.0046291598 -0.16150001, + 0.059445001 -0.00454405 -0.13100401, + 0.059445001 -0.0029228199 -0.124947, + 0.058998398 -0.0064903498 -0.128317, + 0.059757002 -0.0018440899 -0.130689, + 0.059757002 -0.00314283 -0.136859, + 0.0599402 -0.00046149699 -0.136609, + 0.0599402 -0.00144835 -0.14286201, + 0.059999999 0.0012249399 -0.142675, + 0.059999999 0.00054109597 -0.148984, + 0.0599402 0.0032229701 -0.148858, + 0.0596973 0.0060197199 -0.16150001, + 0.059445001 0.0082802698 -0.15507001, + 0.059757002 0.0059256898 -0.14873099, + 0.0599402 0.0038982099 -0.142488, + 0.059999999 0.0021991199 -0.136362, + 0.0599402 0.00082014297 -0.13037799, + 0.059757002 -0.000244636 -0.124569, + 0.059445001 -0.0019974201 -0.121947, + 0.058998398 -0.0046918201 -0.122362, + 0.058998398 -0.0036770499 -0.119418, + 0.058412101 -0.0063747601 -0.119869, + 0.058412101 -0.0052695698 -0.116987, + 0.0576833 -0.0079587996 -0.117474, + 0.0576833 -0.0067623202 -0.11466, + 0.056809202 -0.0094317002 -0.11518, + 0.056809202 -0.0081434101 -0.11244, + 0.055787299 -0.0107818 -0.112993, + 0.055787299 -0.0094021596 -0.110331, + 0.0546159 -0.0119986 -0.110917, + 0.0546159 -0.0105285 -0.108339, + 0.0532961 -0.0130715 -0.108954, + 0.0532961 -0.0115123 -0.106466, + 0.051830001 -0.0139907 -0.107107, + 0.051830001 -0.012344 -0.104714, + 0.050219599 -0.0147469 -0.105379, + 0.050219599 -0.0130159 -0.103086, + 0.048467699 -0.015333 -0.10377, + 0.048467699 -0.013521 -0.101582, + 0.0465803 -0.0157433 -0.102282, + 0.0465803 -0.0138544 -0.100202, + 0.044564299 -0.015973199 -0.100914, + 0.044564299 -0.0140113 -0.098946899, + 0.0424264 -0.016018501 -0.099664398, + 0.0424264 -0.0139893 -0.097811997, + 0.040174201 -0.015877601 -0.098530903, + 0.040174201 -0.013793 -0.096794002, + 0.0378174 -0.0155565 -0.097508997, + 0.0378174 -0.0134217 -0.09589, + 0.035366699 -0.0150557 -0.096594997, + 0.035366699 -0.0128745 -0.095096, + 0.0328326 -0.0143745 -0.095785998, + 0.0328326 -0.0121516 -0.094408996, + 0.0302257 -0.0135144 -0.095076002, + 0.0302257 -0.0112553 -0.093819998, + 0.027557701 -0.0124807 -0.094458997, + 0.027557701 -0.0101911 -0.093324997, + 0.0248404 -0.0112801 -0.093929999, + 0.0248404 -0.0089657698 -0.092915997, + 0.0220857 -0.0099195 -0.093480997, + 0.0220857 -0.0075853998 -0.092583999, + 0.019305199 -0.0084058801 -0.093101002, + 0.019305199 -0.0060569299 -0.092317998, + 0.0165099 -0.0067488002 -0.092782997, + 0.0165099 -0.0043902299 -0.092109002, + 0.0137106 -0.0049588201 -0.092514999, + 0.0137106 -0.0025981099 -0.091948003, + 0.0109179 -0.0030487301 -0.092290998, + 0.0109179 -0.00070129102 -0.091831997, + 0.0081428103 -0.00103929 -0.092105001, + 0.0053973799 -0.00127556 -0.092295997, + 0.00268824 0.0010276 -0.092017002, + 0.0081428103 -0.0033921199 -0.092551999, + 0.0109179 -0.00541614 -0.092841998, + 0.0137106 -0.00732572 -0.093170002, + 0.0165099 -0.0091076903 -0.093543999, + 0.019305199 -0.0107515 -0.093973003, + 0.0220857 -0.0122467 -0.094466999, + 0.0248404 -0.0135838 -0.095035002, + 0.027557701 -0.014755 -0.095683001, + 0.0302257 -0.015753301 -0.096418999, + 0.0328326 -0.016572401 -0.097249001, + 0.035366699 -0.0172076 -0.098177001, + 0.0378174 -0.0176582 -0.0992084, + 0.040174201 -0.017923901 -0.100345, + 0.0424264 -0.017998099 -0.101593, + 0.044564299 -0.0178803 -0.102955, + 0.0465803 -0.0175738 -0.104432, + 0.048467699 -0.017082799 -0.106024, + 0.050219599 -0.016412299 -0.107733, + 0.051830001 -0.0155684 -0.109557, + 0.0532961 -0.0145597 -0.111494, + 0.0546159 -0.0133958 -0.113542, + 0.055787299 -0.0120869 -0.115698, + 0.056809202 -0.0106441 -0.117959, + 0.0576833 -0.0090789404 -0.120321, + 0.058412101 -0.0074033998 -0.122779, + 0.058998398 -0.0056299102 -0.125329, + 0.058412101 -0.0083542503 -0.125714, + 0.0576833 -0.0101215 -0.123197, + 0.056809202 -0.0117792 -0.120772, + 0.055787299 -0.0133152 -0.118442, + 0.0546159 -0.0147176 -0.116211, + 0.0532961 -0.0159743 -0.114083, + 0.051830001 -0.017074499 -0.112061, + 0.050219599 -0.0180082 -0.110146, + 0.048467699 -0.018766399 -0.108342, + 0.0465803 -0.0193417 -0.106649, + 0.044564299 -0.0197287 -0.105068, + 0.0424264 -0.019922599 -0.103598, + 0.040174201 -0.0199201 -0.102239, + 0.0378174 -0.019720601 -0.100988, + 0.035366699 -0.019325299 -0.099842697, + 0.0328326 -0.018740101 -0.0987982, + 0.0302257 -0.0179665 -0.097850002, + 0.027557701 -0.0170085 -0.096996002, + 0.0248404 -0.0158718 -0.09623, + 0.0220857 -0.014563 -0.095545001, + 0.019305199 -0.0130899 -0.094935998, + 0.0165099 -0.0114631 -0.094393998, + 0.0137106 -0.0096928896 -0.093911998, + 0.0109179 -0.0077897101 -0.093480997, + 0.0081428103 -0.0057645799 -0.093091004, + 0.0053973799 -0.0036321699 -0.092734002, + 0.00268824 -0.00141433 -0.092408001, + 0 0.00098316499 -0.092055, + 0 0.0034920699 -0.091595002, + -0.00268824 0.00102765 -0.092017002, + -0.00268824 -0.00141486 -0.092408001, + -0.0053973799 -0.00127663 -0.092295997, + -0.0053973799 -0.0036335799 -0.092734002, + -0.0081428103 -0.00339423 -0.092551999, + -0.0081428103 -0.0057654199 -0.093089998, + -0.0109179 -0.0054172599 -0.092840999, + -0.0109179 -0.0077895001 -0.093479, + -0.0137106 -0.00732545 -0.093167998, + -0.0137106 -0.0096918801 -0.093910001, + -0.0165099 -0.0091064796 -0.093539998, + -0.0165099 -0.0114617 -0.094391003, + -0.019305199 -0.0107499 -0.093969002, + -0.019305199 -0.0130886 -0.094931997, + -0.0220857 -0.0122452 -0.094462998, + -0.0220857 -0.0145619 -0.095541999, + -0.0248404 -0.0135826 -0.095030002, + -0.0248404 -0.015871 -0.096225999, + -0.027557701 -0.0147541 -0.095679, + -0.027557701 -0.017007999 -0.096992999, + -0.0302257 -0.0157528 -0.096415997, + -0.0302257 -0.0179663 -0.097847, + -0.0328326 -0.016572099 -0.097245999, + -0.0328326 -0.018740101 -0.098795697, + -0.035366699 -0.0172076 -0.098174997, + -0.035366699 -0.019325599 -0.099840499, + -0.0378174 -0.017658601 -0.099206097, + -0.0378174 -0.0197221 -0.100985, + -0.040174201 -0.017925501 -0.100343, + -0.040174201 -0.019924801 -0.102233, + -0.0424264 -0.018003 -0.101588, + -0.0424264 -0.019930299 -0.10359, + -0.044564299 -0.017888401 -0.102947, + -0.044564299 -0.0197386 -0.105058, + -0.0465803 -0.017584199 -0.104422, + -0.0465803 -0.0193533 -0.106638, + -0.048467699 -0.0170948 -0.106013, + -0.048467699 -0.0187793 -0.10833, + -0.050219599 -0.016425701 -0.107721, + -0.050219599 -0.018022399 -0.110134, + -0.051830001 -0.0155831 -0.109544, + -0.051830001 -0.0170899 -0.112049, + -0.0532961 -0.0145755 -0.111482, + -0.0532961 -0.015990799 -0.114071, + -0.0546159 -0.0134127 -0.11353, + -0.0546159 -0.014735 -0.1162, + -0.055787299 -0.0121047 -0.115686, + -0.055787299 -0.0133334 -0.118431, + -0.056809202 -0.0106627 -0.117948, + -0.056809202 -0.0117981 -0.120762, + -0.0576833 -0.0090981601 -0.12031, + -0.0576833 -0.0101412 -0.123188, + -0.058412101 -0.0074233902 -0.122769, + -0.058412101 -0.0083750403 -0.125705, + -0.058998398 -0.0056509101 -0.12532, + -0.058998398 -0.0065124398 -0.12830999, + -0.059445001 -0.00294398 -0.124938, + -0.058998398 -0.00471202 -0.122352, + -0.058412101 -0.0063942298 -0.119858, + -0.0576833 -0.0079776198 -0.117462, + -0.056809202 -0.0094498098 -0.115168, + -0.055787299 -0.010799 -0.112981, + -0.0546159 -0.0120148 -0.110904, + -0.0532961 -0.0130865 -0.108941, + -0.051830001 -0.0140045 -0.107094, + -0.050219599 -0.0147594 -0.105367, + -0.048467699 -0.0153438 -0.10376, + -0.0465803 -0.015751701 -0.102273, + -0.044564299 -0.0159784 -0.100908, + -0.0424264 -0.016020199 -0.099661402, + -0.040174201 -0.015877999 -0.0985284, + -0.0378174 -0.0155566 -0.097506002, + -0.035366699 -0.0150555 -0.096591003, + -0.0328326 -0.0143739 -0.095781997, + -0.0302257 -0.0135134 -0.095071003, + -0.027557701 -0.0124794 -0.094454996, + -0.0248404 -0.0112784 -0.093924999, + -0.0220857 -0.0099176997 -0.093475997, + -0.019305199 -0.0084044598 -0.093097001, + -0.0165099 -0.0067484798 -0.092780001, + -0.0137106 -0.0049602198 -0.092514001, + -0.0109179 -0.0030515699 -0.092290998, + -0.0081428103 -0.0010409 -0.092106, + -0.0053973799 0.0011638399 -0.091899998, + -0.00268824 0.0035357601 -0.091554999, + 0 0.00598865 -0.091059998, + 0.00268824 0.00353568 -0.091554999, + -0.059757002 -0.00186738 -0.13068201, + -0.0599402 -0.000483624 -0.136604, + -0.059999999 0.00120921 -0.142671, + -0.0599402 0.00320878 -0.148856, + -0.059757002 0.0055156299 -0.155139, + -0.059716001 0.0058307201 -0.16150001, + -0.059432998 0.00814135 -0.16150001, + -0.059999999 0.00052689301 -0.148982, + -0.0599402 -0.00146406 -0.142858, + -0.059757002 -0.00316488 -0.13685399, + -0.059445001 -0.0045672101 -0.130997, + -0.058998398 -0.0072961301 -0.13131499, + -0.058412101 -0.0092482101 -0.12866201, + -0.0576833 -0.0111057 -0.12609001, + -0.056809202 -0.0128551 -0.123605, + -0.055787299 -0.0144838 -0.121211, + -0.0546159 -0.0159794 -0.11891, + -0.0532961 -0.0173296 -0.116706, + -0.051830001 -0.018522101 -0.114603, + -0.050219599 -0.0195466 -0.112603, + -0.048467699 -0.020393601 -0.110708, + -0.0465803 -0.0210554 -0.10892, + -0.044564299 -0.0215252 -0.107239, + -0.0424264 -0.021797501 -0.105667, + -0.040174201 -0.021868501 -0.104201, + -0.0378174 -0.021737101 -0.102842, + -0.035366699 -0.021404101 -0.101587, + -0.0328326 -0.020873001 -0.100429, + -0.0302257 -0.020148801 -0.099366501, + -0.027557701 -0.019235499 -0.098394997, + -0.0248404 -0.018138001 -0.097511999, + -0.0220857 -0.0168624 -0.096712001, + -0.019305199 -0.0154162 -0.095987, + -0.0165099 -0.01381 -0.095333003, + -0.0137106 -0.0120553 -0.094742, + -0.0109179 -0.0101627 -0.094207004, + -0.0081428103 -0.0081430301 -0.093717001, + -0.0053973799 -0.0060086702 -0.093263999, + -0.00268824 -0.0037739 -0.092840999, + 0 -0.00145982 -0.092445001, + 0.00268824 -0.0037732001 -0.092840999, + 0.0053973799 -0.00600811 -0.093264997, + 0.0081428103 -0.0081431903 -0.093718, + 0.0109179 -0.0101635 -0.094209, + 0.0137106 -0.0120564 -0.094745003, + 0.0165099 -0.0138111 -0.095335998, + 0.019305199 -0.0154171 -0.095991001, + 0.0220857 -0.0168631 -0.096715003, + 0.0248404 -0.018138399 -0.097515002, + 0.027557701 -0.0192357 -0.098398, + 0.0302257 -0.020148801 -0.099368803, + 0.0328326 -0.020872699 -0.100431, + 0.035366699 -0.0214027 -0.101589, + 0.0378174 -0.021732699 -0.102847, + 0.040174201 -0.021861199 -0.104209, + 0.0424264 -0.021787999 -0.105676, + 0.044564299 -0.021514099 -0.10725, + 0.0465803 -0.021043001 -0.108931, + 0.048467699 -0.020379899 -0.11072, + 0.050219599 -0.019531701 -0.112615, + 0.051830001 -0.0185061 -0.114615, + 0.0532961 -0.017312599 -0.116718, + 0.0546159 -0.0159616 -0.118921, + 0.055787299 -0.0144652 -0.121221, + 0.056809202 -0.0128356 -0.123615, + 0.0576833 -0.0110851 -0.12609901, + 0.058412101 -0.0092263399 -0.12866899, + 0.058998398 -0.0072731501 -0.131322, + 0.058998398 -0.0079785204 -0.13434, + 0.058412101 -0.0100196 -0.131642, + 0.0576833 -0.0119689 -0.129022, + 0.056809202 -0.013812 -0.12648401, + 0.055787299 -0.0155354 -0.124031, + 0.0546159 -0.017126299 -0.121666, + 0.0532961 -0.0185721 -0.119393, + 0.051830001 -0.0198605 -0.117215, + 0.050219599 -0.0209799 -0.115134, + 0.048467699 -0.021920299 -0.113153, + 0.0465803 -0.022673599 -0.111274, + 0.044564299 -0.0232323 -0.109497, + 0.0424264 -0.0235902 -0.107824, + 0.040174201 -0.023742899 -0.106253, + 0.0378174 -0.0236893 -0.104785, + 0.035366699 -0.023429601 -0.103417, + 0.0328326 -0.022964001 -0.102147, + 0.0302257 -0.022295 -0.100973, + 0.027557701 -0.021431301 -0.099888198, + 0.0248404 -0.0203782 -0.098890901, + 0.0220857 -0.0191414 -0.097975999, + 0.019305199 -0.0177278 -0.097138003, + 0.0165099 -0.016147699 -0.096372001, + 0.0137106 -0.0144125 -0.09567, + 0.0109179 -0.0125337 -0.095027998, + 0.0081428103 -0.0105221 -0.094434999, + 0.0053973799 -0.0083901901 -0.093883999, + 0.00268824 -0.0061510899 -0.093367003, + 0 -0.0038194801 -0.092876002, + -0.00268824 -0.00615136 -0.093365997, + -0.0053973799 -0.0083900904 -0.093883, + -0.0081428103 -0.0105215 -0.094433002, + -0.0109179 -0.0125328 -0.095025003, + -0.0137106 -0.0144116 -0.095668003, + -0.0165099 -0.0161469 -0.096368998, + -0.019305199 -0.0177272 -0.097135, + -0.0220857 -0.019141 -0.097972997, + -0.0248404 -0.0203781 -0.098888397, + -0.027557701 -0.021431301 -0.099886097, + -0.0302257 -0.0222953 -0.100971, + -0.0328326 -0.0229654 -0.102145, + -0.035366699 -0.0234337 -0.103412, + -0.0378174 -0.023696201 -0.104778, + -0.040174201 -0.023751801 -0.106244, + -0.0424264 -0.023600699 -0.107814, + -0.044564299 -0.0232442 -0.109486, + -0.0465803 -0.022686699 -0.111262, + -0.048467699 -0.021934699 -0.113142, + -0.050219599 -0.020995401 -0.115123, + -0.051830001 -0.019877 -0.117203, + -0.0532961 -0.0185895 -0.119382, + -0.0546159 -0.017144499 -0.121656, + -0.055787299 -0.0155545 -0.124021, + -0.056809202 -0.0138323 -0.126476, + -0.0576833 -0.0119905 -0.129015, + -0.058412101 -0.0100424 -0.13163599, + -0.058998398 -0.0080016097 -0.134334, + -0.059445001 -0.0058820401 -0.137106, + -0.059757002 -0.0041581001 -0.14304601, + -0.0599402 -0.0021549801 -0.14910799, + -0.059999999 0.000121237 -0.155267, + -0.059935 0.0026881101 -0.16150001, + -0.059962101 -0.00154442 -0.16150001, + 0.059744701 0.0053964402 -0.16150001, + -0.059999999 0.0068492498 -0.117644, + -0.0599402 0.0076214499 -0.123446, + -0.059757002 0.0087483097 -0.129444, + -0.059445001 0.0102362 -0.135607, + -0.058998398 0.0120664 -0.141911, + -0.058412101 0.0142052 -0.148339, + -0.0576833 0.016622299 -0.154875, + -0.058215201 0.0145255 -0.16150001, + -0.0576833 0.016998099 -0.14820801, + -0.058412101 0.0148437 -0.141717, + -0.058998398 0.0129828 -0.135352, + -0.059445001 0.0114483 -0.12913001, + -0.059757002 0.0102642 -0.123073, + -0.0599402 0.0094459597 -0.11721, + -0.059999999 0.0089843599 -0.111571, + -0.0599402 0.0088622998 -0.106196, + -0.059757002 0.0090563204 -0.101126, + 0.059757002 0.00907226 -0.10114, + 0.0599402 0.0088800704 -0.10621, + 0.059999999 0.0101749 -0.108594, + 0.0599402 0.0139473 -0.105067, + 0.059757002 0.0141574 -0.110578, + 0.059445001 0.0147347 -0.11634, + 0.058998398 0.015670501 -0.122322, + 0.058412101 0.016946601 -0.128498, + 0.0576833 0.0185389 -0.13484199, + 0.056809202 0.0204223 -0.141332, + 0.055787299 0.022574101 -0.147948, + 0.0546159 0.0249676 -0.154673, + 0.055382699 0.0230815 -0.16150001, + 0.059999999 0.0140857 -0.099842802, + 0.0599402 0.0145451 -0.094944999, + 0.059757002 0.0152919 -0.090415999, + 0.059445001 0.0162916 -0.086290002, + 0.058998398 0.017452 -0.082569003, + 0.058412101 0.016884301 -0.081418999, + 0.0576833 0.016374599 -0.080440998, + 0.056809202 0.015931699 -0.079637997, + 0.055787299 0.0155636 -0.079011999, + 0.0546159 0.0152777 -0.078564003, + 0.0532961 0.0150823 -0.078290999, + 0.051830001 0.0149849 -0.078190997, + 0.050219599 0.0149923 -0.078258, + 0.048467699 0.015107 -0.078487001, + 0.0465803 0.0153195 -0.078877002, + 0.044564299 0.017962299 -0.078378998, + 0.0424264 0.018574201 -0.078879997, + 0.040174201 0.019317999 -0.079357997, + 0.0378174 0.020173199 -0.079804003, + 0.035366699 0.0211468 -0.080168001, + 0.0328326 0.0222429 -0.08044, + 0.0302257 0.0234621 -0.080606997, + 0.027557701 0.0248015 -0.080659002, + 0.0248404 0.0262566 -0.080583997, + 0.0220857 0.027821399 -0.080370001, + 0.019305199 0.0294888 -0.080004998, + 0.0165099 0.031248299 -0.079481997, + 0.0137106 0.033087399 -0.078791998, + 0.0109179 0.034991901 -0.077930003, + 0.0081428103 0.036945902 -0.076889001, + 0.0053973799 0.038931601 -0.075668998, + 0.00268824 0.040930301 -0.074267998, + 0 0.042923201 -0.072691001, + -0.00268824 0.040930901 -0.074267998, + -0.0053973799 0.038933001 -0.075667001, + -0.0081428103 0.036948301 -0.076888002, + -0.0109179 0.034995399 -0.077927999, + -0.0137106 0.033092201 -0.078790002, + -0.0165099 0.0312545 -0.07948, + -0.019305199 0.0294964 -0.080003001, + -0.0220857 0.027830301 -0.080369003, + -0.0248404 0.0262667 -0.080583997, + -0.027557701 0.024812801 -0.08066, + -0.0302257 0.023474099 -0.080609001, + -0.0328326 0.022254899 -0.080443002, + -0.035366699 0.0211572 -0.080172002, + -0.0378174 0.02018 -0.079810001, + -0.040174201 0.019321799 -0.079361998, + -0.0424264 0.0185792 -0.078869998, + -0.044564299 0.017963599 -0.078378998, + -0.0465803 0.017475 -0.077872999, + -0.048467699 0.017163301 -0.077381, + -0.050219599 0.017040599 -0.077008002, + -0.051830001 0.017020101 -0.076800004, + -0.0532961 0.017097799 -0.076764002, + -0.0546159 0.0172683 -0.076904997, + -0.055787299 0.0175253 -0.077225, + -0.056809202 0.017861901 -0.077725999, + -0.0576833 0.0182711 -0.078409001, + -0.058412101 0.0187454 -0.079273, + -0.058998398 0.0174523 -0.082562998, + -0.059445001 0.016291 -0.086286999, + -0.059757002 0.0152849 -0.090409003, + -0.0599402 0.0145318 -0.094933003, + -0.059999999 0.0140697 -0.099828199, + -0.0599402 0.0139295 -0.105053, + -0.059757002 0.0141384 -0.110565, + -0.059445001 0.0147149 -0.116329, + -0.058998398 0.015649499 -0.122313, + -0.058412101 0.016923901 -0.128491, + -0.0576833 0.0185176 -0.134837, + -0.056809202 0.020407399 -0.14132801, + -0.055787299 0.0225609 -0.147946, + -0.0546159 0.024948601 -0.15467601, + -0.054265399 0.0255982 -0.16150001, + -0.054602899 0.0248347 -0.16150001, + -0.055455498 0.0229061 -0.16150001, + -0.055579402 0.0226037 -0.1815, + -0.052960701 0.0281986 -0.1815, + -0.0532845 0.0275518 -0.16150001, + -0.0518195 0.030219801 -0.16150001, + -0.059027899 0.0107568 -0.1815, + -0.058398101 0.0137074 -0.16150001, + -0.057608999 0.0167691 -0.1815, + -0.059358198 0.00875236 -0.16150001, + -0.0590127 0.0107542 -0.16150001, + -0.058984801 0.0109155 -0.16150001, + -0.057669099 0.016505999 -0.16150001, + -0.057597399 0.0167659 -0.16150001, + -0.057432801 0.017363001 -0.16150001, + -0.056809202 0.0194162 -0.154808, + -0.055787299 0.0221952 -0.154742, + -0.056512099 0.020158799 -0.16150001, + -0.056809202 0.0197869 -0.148077, + -0.0576833 0.017627601 -0.14152201, + -0.058412101 0.015746901 -0.135094, + -0.058998398 0.0141774 -0.128811, + -0.059445001 0.0129424 -0.122695, + -0.059757002 0.0120629 -0.116772, + -0.0599402 0.0115514 -0.11107, + -0.059999999 0.0113959 -0.105624, + -0.0599402 0.0115727 -0.100474, + -0.059757002 0.0120549 -0.095664002, + -0.059445001 0.0128168 -0.091237001, + -0.058998398 0.0138399 -0.087219, + 0.059445001 0.0128238 -0.091245003, + 0.059757002 0.0120683 -0.095677003, + 0.0599402 0.0115887 -0.100489, + 0.059999999 0.0114137 -0.105638, + -0.0555728 0.0226011 -0.16150001, + -0.055773102 0.0220802 -0.16150001, + -0.0567948 0.0193005 -0.16150001, + -0.0268177 0.053653602 -0.16150001, + -0.011126 0.0487464 -0.19850001, + -0.016514 0.047194201 -0.19850001, + -0.011126 0.0487464 -0.1815, + -0.016514 0.047194201 -0.1815, + -0.00559822 0.049685601 -0.1815, + -0.00559822 0.049685601 -0.19850001, + -0.0266016 0.042336199 -0.19850001, + -0.0311745 0.039091598 -0.19850001, + -0.0266016 0.042336199 -0.1815, + -0.0311745 0.039091598 -0.1815, + -0.0216942 0.045048401 -0.1815, + -0.0216942 0.045048401 -0.19850001, + -0.0353553 0.0353553 -0.19850001, + -0.039091598 0.0311745 -0.19850001, + -0.0353553 0.0353553 -0.1815, + -0.039091598 0.0311745 -0.1815, + 0 0.050000001 -0.1815, + 0 0.050000001 -0.19850001, + 0.00559822 0.049685601 -0.1815, + 0.00559822 0.049685601 -0.19850001, + -0.0266016 -0.042336199 -0.19850001, + -0.0216942 -0.045048401 -0.19850001, + -0.0266016 -0.042336199 -0.1815, + -0.0216942 -0.045048401 -0.1815, + -0.0311745 -0.039091598 -0.1815, + -0.0311745 -0.039091598 -0.19850001, + 0.042336199 -0.0266016 -0.1815, + 0.039091598 -0.0311745 -0.1815, + 0.042336199 -0.0266016 -0.19850001, + 0.039091598 -0.0311745 -0.19850001, + 0.045048401 -0.0216942 -0.19850001, + 0.045048401 -0.0216942 -0.1815, + 0.0353553 -0.0353553 -0.1815, + 0.0353553 -0.0353553 -0.19850001, + -0.016514 -0.047194201 -0.19850001, + -0.016514 -0.047194201 -0.1815, + 0.0216942 -0.045048401 -0.1815, + 0.016514 -0.047194201 -0.1815, + 0.0216942 -0.045048401 -0.19850001, + 0.016514 -0.047194201 -0.19850001, + 0.0266016 -0.042336199 -0.19850001, + 0.0266016 -0.042336199 -0.1815, + 0.0311745 -0.039091598 -0.19850001, + 0.011126 -0.0487464 -0.19850001, + 0.047194201 -0.016514 -0.19850001, + 0.0487464 -0.011126 -0.19850001, + 0.049685601 -0.00559822 -0.19850001, + 0.050000001 0 -0.19850001, + 0.049685601 0.00559822 -0.19850001, + 0.0487464 0.011126 -0.19850001, + 0.047194201 0.016514 -0.19850001, + 0.045048401 0.0216942 -0.19850001, + 0.042336199 0.0266016 -0.19850001, + 0.039091598 0.0311745 -0.19850001, + 0.0353553 0.0353553 -0.19850001, + 0.0311745 0.039091598 -0.19850001, + 0.0266016 0.042336199 -0.19850001, + 0.0216942 0.045048401 -0.19850001, + 0.016514 0.047194201 -0.19850001, + 0.011126 0.0487464 -0.19850001, + 0.00559822 -0.049685601 -0.19850001, + 0 -0.050000001 -0.19850001, + -0.00559822 -0.049685601 -0.19850001, + -0.011126 -0.0487464 -0.19850001, + -0.042336199 0.0266016 -0.19850001, + -0.0353553 -0.0353553 -0.19850001, + -0.039091598 -0.0311745 -0.19850001, + -0.042336199 -0.0266016 -0.19850001, + -0.045048401 -0.0216942 -0.19850001, + -0.047194201 -0.016514 -0.19850001, + -0.0487464 -0.011126 -0.19850001, + -0.049685601 -0.00559822 -0.19850001, + -0.050000001 0 -0.19850001, + -0.049685601 0.00559822 -0.19850001, + -0.045048401 0.0216942 -0.19850001, + -0.047194201 0.016514 -0.19850001, + -0.0487464 0.011126 -0.19850001, + 0.0311745 -0.039091598 -0.1815, + 0.011126 -0.0487464 -0.1815, + -0.011126 -0.0487464 -0.1815, + -0.00559822 -0.049685601 -0.1815, + 0.00559822 -0.049685601 -0.1815, + 0 -0.050000001 -0.1815, + 0.011126 0.0487464 -0.1815, + 0.016514 0.047194201 -0.1815, + 0.0216942 0.045048401 -0.1815, + 0.0266016 0.042336199 -0.1815, + 0.0311745 0.039091598 -0.1815, + 0.0353553 0.0353553 -0.1815, + 0.039091598 0.0311745 -0.1815, + 0.042336199 0.0266016 -0.1815, + 0.0487464 0.011126 -0.1815, + 0.047194201 0.016514 -0.1815, + 0.049685601 0.00559822 -0.1815, + 0.045048401 0.0216942 -0.1815, + 0.050000001 0 -0.1815, + 0.049685601 -0.00559822 -0.1815, + -0.042336199 0.0266016 -0.1815, + -0.0353553 -0.0353553 -0.1815, + -0.039091598 -0.0311745 -0.1815, + -0.042336199 -0.0266016 -0.1815, + 0.047194201 -0.016514 -0.1815, + 0.0487464 -0.011126 -0.1815, + -0.045048401 -0.0216942 -0.1815, + -0.047194201 -0.016514 -0.1815, + -0.0487464 -0.011126 -0.1815, + -0.049685601 -0.00559822 -0.1815, + -0.050000001 0 -0.1815, + -0.047194201 0.016514 -0.1815, + -0.0487464 0.011126 -0.1815, + -0.045048401 0.0216942 -0.1815, + -0.049685601 0.00559822 -0.1815, + -0.0053910101 0.0597458 -0.16150001, + 0.042336199 0.046 -0.026602, + 0.039091598 0.046 -0.031174, + 0.0353553 0.046 -0.035355002, + 0.0311745 0.046 -0.039092001, + 0.0266016 0.046 -0.042335998, + 0.0216942 0.046 -0.045047998, + 0.016514 0.046 -0.047194, + 0.011126 0.046 -0.048746001, + 0.00559822 0.046 -0.049686, + 0 0.046 -0.050000001, + -0.00559822 0.046 -0.049686, + -0.011126 0.046 -0.048746001, + -0.016514 0.046 -0.047194, + -0.0216942 0.046 -0.045047998, + -0.0266016 0.046 -0.042335998, + -0.0311745 0.046 -0.039092001, + -0.0353553 0.046 -0.035355002, + -0.039091598 0.046 -0.031174, + -0.042336199 0.046 -0.026602, + -0.045048401 0.046 -0.021694001, + -0.047194201 0.046 -0.016514, + -0.0487464 0.046 -0.011126, + -0.049685601 0.046 -0.00559801, + -0.050000001 0.046 0, + -0.049685601 0.046 0.00559801, + -0.0487464 0.046 0.011126, + -0.047194201 0.046 0.016514, + -0.045048401 0.046 0.021694001, + -0.042336199 0.046 0.026602, + -0.039091598 0.046 0.031174, + -0.0353553 0.046 0.035355002, + -0.0311745 0.046 0.039092001, + -0.0266016 0.046 0.042335998, + -0.0216942 0.046 0.045047998, + -0.016514 0.046 0.047194, + -0.011126 0.046 0.048746001, + -0.00559822 0.046 0.049686, + 0 0.046 0.050000001, + 0.00559822 0.046 0.049686, + 0.011126 0.046 0.048746001, + 0.016514 0.046 0.047194, + 0.0216942 0.046 0.045047998, + 0.0266016 0.046 0.042335998, + 0.0311745 0.046 0.039092001, + 0.0353553 0.046 0.035355002, + 0.039091598 0.046 0.031174, + 0.042336199 0.046 0.026602, + 0.045048401 0.046 0.021694001, + 0.047194201 0.046 0.016514, + 0.0487464 0.046 0.011126, + 0.049685601 0.046 0.00559801, + 0.050000001 0.046 0, + 0.049685601 0.046 -0.00559801, + 0.0487464 0.046 -0.011126, + 0.047194201 0.046 -0.016514, + 0.045048401 0.046 -0.021694001 ] + + } + normal + Normal { + vector [ 0.91841638 -0.30630112 0.2503821, + 0.8574363 -0.39841616 0.32568011, + 0.84054202 -0.40706 0.35747901, + 0.7751438 -0.47471389 0.4168919, + 0.74672925 -0.48293319 0.45735216, + 0.66729218 -0.5407781 0.51213312, + 0.62399513 -0.54529214 0.5597201, + 0.53743774 -0.58846968 0.60403973, + 0.47944489 -0.58506888 0.6540848, + 0.39431399 -0.61267298 0.68494397, + 0.32515311 -0.59829926 0.73233426, + 0.24999009 -0.61258924 0.74982625, + 0.17526099 -0.58642197 0.79081786, + 0.11508196 -0.59168375 0.79791373, + 0.039879795 -0.55473793 0.83106887, + -0.0038280592 -0.55517489 0.83172482, + -0.073455282 -0.51097089 0.85645384, + -0.10215696 -0.50967485 0.85428071, + -0.165493 -0.46003801 0.87234002, + -0.181756 -0.4587 0.86980402, + -0.23800309 -0.40569714 0.88247627, + -0.24472691 -0.40499884 0.88095671, + -0.28571308 -0.35951313 0.88832331, + -0.31045002 -0.35661504 0.88116211, + -0.30497804 -0.36363804 0.88020211, + -0.29983205 -0.36426109 0.88171124, + -0.29949501 -0.364732 0.88163102, + -0.29137105 -0.36569309 0.88395226, + -0.2899479 -0.36787489 0.8835147, + -0.27965492 -0.36905089 0.8863377, + -0.27185705 -0.3821201 0.88322026, + -0.26082808 -0.38333014 0.88601732, + -0.25398707 -0.39586008 0.88248825, + -0.24268194 -0.39704591 0.88513279, + -0.23596087 -0.41058475 0.88076246, + -0.223772 -0.41180101 0.88337201, + -0.21751004 -0.42578009 0.87829423, + -0.20417804 -0.42703405 0.88088214, + -0.198137 -0.442132 0.87479198, + -0.18357405 -0.44340912 0.87731922, + -0.17773706 -0.45995617 0.86997128, + -0.16168699 -0.46124795 0.87241489, + -0.15649004 -0.47824413 0.86417216, + -0.13914102 -0.47949913 0.86644119, + -0.13444297 -0.49763888 0.85690182, + -0.11568903 -0.49882612 0.8589462, + -0.11158299 -0.51815796 0.8479749, + -0.091364153 -0.51923376 0.8497346, + -0.088031046 -0.53935826 0.83746243, + -0.066044092 -0.54027796 0.83889091, + -0.063513309 -0.56158608 0.8249771, + -0.039866887 -0.56227487 0.82598883, + -0.038290206 -0.58434814 0.81059921, + -0.013429602 -0.58472407 0.81112111, + -0.012872403 -0.60815209 0.79371619, + 0.013009598 -0.6081509 0.79371482, + 0.0135728 -0.58499402 0.81092399, + 0.038397208 -0.58461714 0.81040019, + 0.040003289 -0.56230789 0.8259598, + 0.063644789 -0.56161696 0.82494587, + 0.066153087 -0.5405969 0.83867681, + 0.087783478 -0.53969288 0.83727282, + 0.091173075 -0.51927686 0.84972882, + 0.11167303 -0.51818717 0.84794527, + 0.11573405 -0.49912718 0.8587653, + 0.13445297 -0.49794087 0.8567248, + 0.13915801 -0.47982505 0.86625814, + 0.15622008 -0.47859025 0.86402941, + 0.161423 -0.46160099 0.87227702, + 0.17743905 -0.46031311 0.86984318, + 0.183294 -0.443739 0.87721097, + 0.19782305 -0.44246611 0.87469417, + 0.20389004 -0.42732608 0.88080722, + 0.21721996 -0.42607296 0.8782239, + 0.223529 -0.41200799 0.88333702, + 0.23573309 -0.41079116 0.88072729, + 0.24255303 -0.39706606 0.88515913, + 0.25388592 -0.39587685 0.88250971, + 0.26102304 -0.38280705 0.88618612, + 0.27179 -0.38162699 0.88345402, + 0.27994302 -0.36795303 0.88670313, + 0.29067084 -0.36672881 0.8837536, + 0.29426694 -0.36119291 0.88484275, + 0.30268702 -0.36019704 0.8824051, + 0.29758996 -0.36734098 0.88119286, + 0.30289882 -0.36669779 0.87965047, + 0.30513003 -0.36385202 0.88006109, + 0.30753705 -0.36355609 0.87934524, + 0.29610705 -0.3767471 0.87771422, + 0.29452711 -0.37693915 0.87816328, + 0.24094303 -0.43073606 0.8697201, + 0.23048408 -0.43186215 0.8719933, + 0.16683392 -0.48527676 0.85829657, + 0.14487204 -0.48698217 0.86131328, + 0.07411053 -0.53542918 0.8413223, + 0.037534505 -0.53652704 0.8430481, + -0.040034994 -0.57818496 0.81492287, + -0.093650319 -0.57610613 0.81199217, + -0.17426001 -0.60778201 0.77474803, + -0.24601406 -0.59825611 0.76260519, + -0.32339314 -0.6174463 0.71706134, + -0.40980822 -0.5952003 0.69122636, + -0.47731581 -0.60173577 0.64037776, + -0.5697031 -0.56278515 0.59892511, + -0.62173086 -0.55927485 0.54832691, + -0.70884418 -0.50367409 0.49381411, + -0.74420798 -0.49470499 0.4488, + -0.84214979 -0.39938191 0.3623229, + -0.8761093 -0.36762112 0.31190911, + -0.80106616 -0.45642713 0.38725609, + -0.77765483 -0.46394187 0.42427692, + -0.70593297 -0.52267301 0.47798699, + -0.67044276 -0.52754182 0.52173382, + -0.58929408 -0.57443804 0.56811404, + -0.53982931 -0.57324636 0.61641937, + -0.45750484 -0.60554779 0.65115374, + -0.39660385 -0.59510577 0.69896674, + -0.32009408 -0.61416215 0.72134918, + -0.25185895 -0.59291691 0.76486385, + -0.18730809 -0.60182327 0.77635336, + -0.11607897 -0.56980586 0.8135398, + -0.065956205 -0.57243508 0.81729311, + 0.0022302608 -0.5322262 0.84659928, + 0.037416916 -0.53185517 0.8460083, + 0.100936 -0.48519999 0.86855799, + 0.12346298 -0.48395994 0.86633688, + 0.18069094 -0.43312484 0.88303667, + 0.19229899 -0.43215501 0.88105798, + 0.24283785 -0.37880376 0.89304948, + 0.24654697 -0.37843794 0.89218789, + 0.28727785 -0.32796684 0.89994961, + 0.28393397 -0.32830796 0.90088588, + 0.28974485 -0.32011485 0.90198356, + 0.2839441 -0.32069612 0.9036203, + 0.27970102 -0.32729203 0.90257812, + 0.2713379 -0.32810888 0.90483171, + 0.27212805 -0.32675809 0.90508324, + 0.26080307 -0.32782108 0.90802824, + 0.25589502 -0.33708903 0.90602911, + 0.24284703 -0.33826104 0.90917814, + 0.23528291 -0.35398889 0.90517068, + 0.22248504 -0.35508502 0.90797311, + 0.21591103 -0.37021002 0.90350813, + 0.20178992 -0.37135383 0.90629858, + 0.19561708 -0.38724616 0.9009853, + 0.18045096 -0.38839293 0.90365279, + 0.17451796 -0.4057219 0.89718074, + 0.15870799 -0.40682295 0.89961487, + 0.15330903 -0.4250001 0.89211625, + 0.13612601 -0.42608106 0.8943851, + 0.13124995 -0.44544086 0.88563871, + 0.11300897 -0.44644988 0.88764375, + 0.10881902 -0.46671405 0.87768811, + 0.088782579 -0.46764788 0.87944478, + 0.085318699 -0.48912299 0.86803198, + 0.064236023 -0.48989919 0.86940932, + 0.061657507 -0.51214504 0.85668314, + 0.038947996 -0.51273197 0.85766488, + 0.037348002 -0.53558809 0.84365314, + 0.013149606 -0.53591526 0.84416944, + 0.012574503 -0.56030309 0.82819217, + -0.0127621 -0.56030202 0.82819003, + -0.013323298 -0.53616995 0.84400487, + -0.037507601 -0.53583997 0.84348601, + -0.0391193 -0.512712 0.857669, + -0.061863601 -0.51212198 0.856682, + -0.064464383 -0.48960188 0.86955982, + -0.085576311 -0.48882207 0.8681761, + -0.088938124 -0.46792412 0.87928224, + -0.108939 -0.46698901 0.877527, + -0.11324396 -0.44612986 0.88777471, + -0.13151704 -0.44511816 0.88576132, + -0.13638794 -0.4257378 0.8945086, + -0.15357295 -0.42465585 0.89223468, + -0.15895206 -0.40651414 0.89971131, + -0.17477407 -0.40541115 0.89727128, + -0.18056302 -0.38848206 0.90359211, + -0.19571295 -0.3873359 0.90092576, + -0.20194805 -0.37126908 0.90629822, + -0.21605007 -0.37012613 0.90350932, + -0.22255887 -0.35513979 0.90793347, + -0.23531701 -0.354047 0.90513903, + -0.24257609 -0.33895412 0.90899229, + -0.25523597 -0.33781698 0.90594387, + -0.25848597 -0.33169398 0.9072839, + -0.269887 -0.330621 0.904351, + -0.27302894 -0.32524791 0.90535575, + -0.28122798 -0.32444897 0.90312988, + -0.28882205 -0.31257209 0.90492022, + -0.27254888 -0.31412587 0.90941858, + -0.24246091 -0.35525888 0.9027757, + -0.24164309 -0.35533413 0.90296531, + -0.196877 -0.40800399 0.8915, + -0.18881904 -0.40866306 0.8929401, + -0.13833101 -0.45910305 0.87754714, + -0.12044895 -0.46018481 0.87961471, + -0.063711368 -0.50775975 0.85913956, + -0.035537895 -0.50847197 0.86034489, + 0.027114104 -0.55169809 0.83360314, + 0.068660207 -0.55059808 0.83194214, + 0.13421702 -0.58658314 0.7986902, + 0.18869597 -0.58130497 0.79150391, + 0.25503811 -0.6086393 0.75134134, + 0.3228381 -0.59575009 0.73543018, + 0.38440225 -0.61277437 0.69046539, + 0.46021807 -0.58930308 0.66401905, + 0.51343066 -0.59668756 0.61672759, + 0.5922119 -0.56028789 0.5791049, + 0.6339162 -0.56000614 0.53342611, + 0.70862401 -0.51090199 0.486653, + 0.7381472 -0.50598609 0.44622511, + 0.80317873 -0.44680884 0.39403784, + 0.8219583 -0.44026315 0.36132112, + 0.87464714 -0.37472203 0.30753204, + 0.88596988 -0.36828497 0.28182197, + 0.9355514 -0.28048912 0.2146381, + 0.96960312 -0.20338903 0.13602501, + 0.94020009 -0.28313702 0.18936002, + 0.93407899 -0.28868401 0.21013799, + 0.89854032 -0.35483813 0.25829309, + 0.88748771 -0.36146289 0.2858499, + 0.84004599 -0.425533 0.33651799, + 0.82410157 -0.43148679 0.36698183, + 0.76519954 -0.49040869 0.41709575, + 0.74086738 -0.49508324 0.4538812, + 0.67183816 -0.54597813 0.50054109, + 0.63695025 -0.54717815 0.54303819, + 0.56267607 -0.58676505 0.58232504, + 0.51654321 -0.5817253 0.62831432, + 0.44194907 -0.60943007 0.65823704, + 0.38731101 -0.596053 0.70335698, + 0.31865487 -0.61281168 0.72313267, + 0.25775313 -0.58980727 0.76530439, + 0.19922392 -0.59819674 0.77618968, + 0.13679497 -0.56624389 0.81280684, + 0.09052971 -0.56927007 0.81715113, + 0.029823307 -0.52985114 0.84756619, + -0.0046147779 -0.53008074 0.8479346, + -0.060724214 -0.48555213 0.87209618, + -0.083259881 -0.48476088 0.87067485, + -0.13473295 -0.4359068 0.8898496, + -0.14756703 -0.43510208 0.88820624, + -0.19262607 -0.38462815 0.9027493, + -0.19786808 -0.38421914 0.90178931, + -0.23766391 -0.33205089 0.9128297, + -0.23649091 -0.33214888 0.91309869, + -0.26192009 -0.29355511 0.91936034, + -0.274275 -0.29250899 0.916085, + -0.2662459 -0.30642587 0.91390169, + -0.25638306 -0.30727506 0.91643322, + -0.25188312 -0.31583515 0.91476941, + -0.24026488 -0.31679785 0.9175576, + -0.23620801 -0.325331 0.91562301, + -0.22255494 -0.32640892 0.91865474, + -0.21578303 -0.34223604 0.91450113, + -0.20118396 -0.3433269 0.91741574, + -0.19502208 -0.35944912 0.91255832, + -0.17974502 -0.36051702 0.91527009, + -0.17382006 -0.37810716 0.90929729, + -0.15795396 -0.37913191 0.91176176, + -0.15256298 -0.3975859 0.90479279, + -0.13542095 -0.39858884 0.90707672, + -0.13054402 -0.41827607 0.89889014, + -0.11214703 -0.4192251 0.90092921, + -0.10794196 -0.43991286 0.89152968, + -0.087896332 -0.44078615 0.89329827, + -0.084378034 -0.4629972 0.88233441, + -0.063761815 -0.46370912 0.88369024, + -0.061186515 -0.48632112 0.8716352, + -0.038458604 -0.48687407 0.87262511, + -0.036833216 -0.5105812 0.85904032, + -0.012830897 -0.51088589 0.8595528, + -0.012277502 -0.53524905 0.84460515, + 0.012392502 -0.53524804 0.84460413, + 0.012954103 -0.51116812 0.85938317, + 0.036941286 -0.51086181 0.85886872, + 0.038599193 -0.48688689 0.87261182, + 0.060692132 -0.48635224 0.87165242, + 0.063271485 -0.46373889 0.88370979, + 0.084492221 -0.46300912 0.88231725, + 0.08797802 -0.44109011 0.89314026, + 0.10770603 -0.44023111 0.89140123, + 0.11191701 -0.41956607 0.9007991, + 0.13028397 -0.4186199 0.89876777, + 0.13526 -0.39857 0.90710902, + 0.15209997 -0.3975859 0.90487075, + 0.15751201 -0.37907705 0.91186112, + 0.17371899 -0.37803194 0.90934789, + 0.17957994 -0.36065087 0.91524971, + 0.19488505 -0.3595821 0.91253525, + 0.20123403 -0.34298104 0.91753411, + 0.21555397 -0.34191298 0.91467589, + 0.22259989 -0.32543984 0.91898757, + 0.23633909 -0.32435811 0.91593432, + 0.24174994 -0.31294891 0.91848779, + 0.25421488 -0.31191984 0.91546756, + 0.2551401 -0.31015912 0.91580832, + 0.26453501 -0.30934799 0.913414, + 0.26942593 -0.30091995 0.91479874, + 0.277585 -0.30019501 0.91259497, + 0.27379709 -0.30610612 0.91177529, + 0.27862099 -0.30566499 0.91046101, + 0.24338391 -0.35409689 0.90298373, + 0.24268994 -0.35415992 0.90314579, + 0.19728395 -0.40764591 0.89157379, + 0.18919709 -0.40830821 0.89302242, + 0.13842697 -0.45904988 0.87755978, + 0.12092999 -0.46010995 0.87958789, + 0.063942395 -0.50789595 0.85904187, + 0.035293896 -0.50862092 0.86026686, + -0.026858794 -0.55150086 0.83374184, + -0.067907929 -0.55042624 0.83211744, + -0.13442297 -0.58692986 0.79840082, + -0.18938804 -0.58158606 0.79113209, + -0.25476408 -0.60851222 0.75153732, + -0.32253912 -0.59564525 0.73564625, + -0.38449699 -0.61278301 0.69040501, + -0.46030182 -0.58930779 0.66395676, + -0.51351076 -0.59668767 0.61666071, + -0.59228301 -0.56028301 0.57903701, + -0.63401324 -0.5599972 0.53332019, + -0.70870996 -0.51088393 0.48654693, + -0.73841035 -0.50592822 0.4458552, + -0.80338436 -0.44674122 0.39369518, + -0.82199383 -0.44024789 0.36125892, + -0.87456727 -0.37485412 0.30759811, + -0.8891263 -0.36643213 0.27419308, + -0.93179798 -0.290622 0.217466, + -0.93999499 -0.28333899 0.190075, + -0.96952534 -0.20345208 0.13648404, + -0.99972963 0.023092192 -0.0027235691, + -0.86982512 -0.49336007 0.00048929005, + -0.86981815 -0.49337211 0.00048942113, + -0.86981857 -0.49337175 -1.8248591e-005, + -0.86982518 -0.49336013 -1.8787203e-005, + -0.93278778 -0.3604199 -0.0021192995, + -0.93278939 -0.36042112 -0.00082284131, + -0.93276811 -0.36047602 -0.00083027012, + -0.93276644 -0.36047518 -0.002118761, + 0.89435214 -0.44724205 0.010434601, + -0.93800509 -0.34559602 0.026644204, + -0.91897589 -0.39314693 0.030310096, + -0.91777265 -0.39366186 0.052187782, + -0.89849424 -0.4351781 0.057691514, + 0.95426226 -0.29879507 0.010255203, + 0.95399523 -0.29899606 0.022238405, + 0.93764836 -0.34662813 0.025781009, + 0.90069288 -0.43314695 0.033704396, + 0.91949111 -0.39192605 0.030496905, + 0.91998762 -0.39172584 0.013179195, + 0.93387467 -0.3575289 0.0071511478, + 0.9338966 -0.35747182 0.0071495967, + 0.95026666 -0.31138387 0.005771128, + 0.9384051 -0.34533903 0.011703801, + 0.93803233 -0.34554911 0.026292309, + 0.91900456 -0.39311081 0.029911086, + 0.91812474 -0.3935259 0.046737589, + 0.89642924 -0.44009411 0.052268311, + 0.89536959 -0.44038779 0.06612087, + 0.87076288 -0.48625293 0.073007196, + 0.8691389 -0.48647994 0.089077093, + 0.84134471 -0.53165984 0.097349763, + 0.83898288 -0.53169197 0.11580698, + 0.80785567 -0.57587868 0.12543094, + 0.80455887 -0.57553095 0.14645499, + 0.77051079 -0.61773986 0.15719596, + 0.76608109 -0.61676407 0.18089202, + 0.72921336 -0.6566273 0.19258408, + 0.72347301 -0.65470999 0.21895599, + 0.68367594 -0.69210696 0.23146297, + 0.67647922 -0.68886524 0.26046208, + 0.63410169 -0.72327566 0.27347288, + 0.62535298 -0.71827501 0.30498299, + 0.58145195 -0.74886996 0.31797397, + 0.57126796 -0.74174893 0.35137096, + 0.52647811 -0.76834118 0.3639681, + 0.51498699 -0.75872999 0.398895, + 0.46975994 -0.7813859 0.41080594, + 0.45720479 -0.76898867 0.44678879, + 0.41219214 -0.78778231 0.45770815, + 0.39889276 -0.77237254 0.49429271, + 0.35549608 -0.78726417 0.5038231, + 0.34195292 -0.76892585 0.54020488, + 0.30079904 -0.78035712 0.54823607, + 0.28743091 -0.75920171 0.58394879, + 0.24887194 -0.7677108 0.59049386, + 0.23605086 -0.74388957 0.62522662, + 0.20051897 -0.74997497 0.63034093, + 0.18861803 -0.72376007 0.66377306, + 0.15674199 -0.72787893 0.66755092, + 0.146127 -0.699808 0.69922501, + 0.11800897 -0.7024588 0.70187283, + 0.10888302 -0.67292404 0.73165405, + 0.084538296 -0.67452592 0.73339492, + 0.077001259 -0.64373863 0.76136154, + 0.056333415 -0.64463019 0.76241618, + 0.050476119 -0.61291724 0.78853327, + 0.033590306 -0.61335313 0.78909415, + 0.029458789 -0.58118683 0.81323671, + 0.016262807 -0.58136231 0.8134824, + 0.0138329 -0.54907298 0.83565998, + 0.0041123489 -0.5491209 0.83573282, + 0.0033226605 -0.51683909 0.85607612, + -0.0032910693 -0.51683986 0.85607582, + -0.0040811007 -0.54910403 0.83574414, + -0.013788098 -0.54905593 0.8356719, + -0.016216399 -0.58128703 0.813537, + -0.029387796 -0.58111197 0.81329286, + -0.033501897 -0.61313194 0.78926986, + -0.05026 -0.612701 0.788715, + -0.05611252 -0.64440227 0.76262528, + -0.076667011 -0.64352006 0.76158011, + -0.084214509 -0.67435205 0.73359203, + -0.10852904 -0.67275923 0.73185825, + -0.117668 -0.70234197 0.70204699, + -0.14573 -0.699705 0.69941097, + -0.15636709 -0.7278344 0.66768742, + -0.18824296 -0.72372484 0.66391784, + -0.20016088 -0.74997759 0.63045162, + -0.23569497 -0.74390292 0.62534493, + -0.24852297 -0.76773989 0.59060293, + -0.28706497 -0.75924689 0.58406997, + -0.30044702 -0.7804231 0.54833508, + -0.34164304 -0.76899314 0.54030508, + -0.35520202 -0.78735214 0.50389308, + -0.39859381 -0.77247566 0.49437276, + -0.41189879 -0.78788763 0.45779079, + -0.45692605 -0.76910311 0.44687706, + -0.46949807 -0.7815181 0.41085407, + -0.51475185 -0.75886381 0.3989439, + -0.5262332 -0.76846433 0.36406213, + -0.5710479 -0.7418738 0.3514649, + -0.58123207 -0.74899304 0.31808603, + -0.62514877 -0.71840477 0.30509588, + -0.63388735 -0.72339839 0.27364516, + -0.67628896 -0.68898892 0.26062897, + -0.68350083 -0.69223684 0.23159194, + -0.72330523 -0.65485221 0.21908507, + -0.72907716 -0.65678018 0.19257805, + -0.76599169 -0.61687875 0.18087894, + -0.770459 -0.61786097 0.156974, + -0.80452269 -0.57563484 0.14624594, + -0.80786085 -0.57598191 0.12492298, + -0.83899802 -0.531771 0.115334, + -0.84136117 -0.5317331 0.096805826, + -0.86916971 -0.48651683 0.088573769, + -0.87077099 -0.48628899 0.0726697, + -0.89475071 -0.44166186 0.066000775, + -0.89356899 -0.44197401 0.078698397, + -0.86846119 -0.48808011 0.086908221, + -0.86647367 -0.48834383 0.10365196, + -0.83806199 -0.53368598 0.113276, + -0.83518618 -0.53370315 0.13275903, + -0.80332202 -0.57793301 0.14376099, + -0.79937232 -0.57748318 0.16588306, + -0.76450652 -0.61956161 0.1779699, + -0.75927711 -0.61836207 0.20279703, + -0.72152019 -0.65791517 0.21576904, + -0.71483481 -0.65561783 0.24326193, + -0.67418683 -0.69243282 0.25692195, + -0.66589224 -0.68861526 0.2870481, + -0.6227299 -0.72220284 0.30104893, + -0.61283809 -0.71644717 0.3333661, + -0.56830907 -0.74601007 0.34712204, + -0.55687708 -0.73789406 0.38131407, + -0.51173377 -0.76325667 0.39442083, + -0.49893093 -0.75240189 0.43006894, + -0.4536472 -0.77370638 0.44224721, + -0.43978384 -0.75983769 0.47878683, + -0.39509305 -0.7772131 0.48973605, + -0.38063475 -0.7602545 0.52643168, + -0.337991 -0.77375698 0.53578198, + -0.32339919 -0.75376546 0.57205838, + -0.28334194 -0.7639268 0.57976991, + -0.26905206 -0.74105215 0.61518514, + -0.23194203 -0.74844205 0.62131906, + -0.21832711 -0.72284836 0.65560931, + -0.18457398 -0.72799093 0.66027397, + -0.17213091 -0.70026064 0.69282466, + -0.14220297 -0.70364684 0.6961748, + -0.13118099 -0.67415291 0.72684896, + -0.10527996 -0.67625076 0.72910976, + -0.095824488 -0.64527494 0.75791687, + -0.073792532 -0.64649022 0.75934529, + -0.066048913 -0.61446911 0.7861712, + -0.047836382 -0.61510879 0.78698969, + -0.041917484 -0.5826568 0.81163669, + -0.027463792 -0.58294988 0.81204385, + -0.023300506 -0.5501281 0.83475518, + -0.012506698 -0.55023396 0.83491689, + -0.010055803 -0.51725012 0.85577518, + -0.0028050307 -0.51727414 0.85581517, + -0.0020086002 -0.48424506 0.87493014, + 0.0020872299 -0.48424494 0.8749299, + 0.00287938 -0.51723599 0.855838, + 0.010115601 -0.51721108 0.85579813, + 0.012567995 -0.55023581 0.83491468, + 0.023378607 -0.55012918 0.83475232, + 0.027549203 -0.58301103 0.81199712, + 0.041976284 -0.58271784 0.81158972, + 0.047944188 -0.61543286 0.78672981, + 0.066302806 -0.61478609 0.78590214, + 0.074044593 -0.64679396 0.75906187, + 0.096166402 -0.64556903 0.75762302, + 0.10559696 -0.67645574 0.72887379, + 0.13157997 -0.67434484 0.7265988, + 0.14258002 -0.70377308 0.69597006, + 0.17251495 -0.70037675 0.69261175, + 0.18493198 -0.72804695 0.66011196, + 0.21868703 -0.72289306 0.65544003, + 0.23228306 -0.74844921 0.6211831, + 0.26939499 -0.74104798 0.61504, + 0.28368098 -0.76391786 0.57961595, + 0.32375211 -0.7537393 0.57189316, + 0.33830696 -0.77368391 0.53568792, + 0.38099217 -0.76015335 0.52631927, + 0.39541805 -0.77707809 0.48968807, + 0.44004199 -0.75971401 0.478746, + 0.45392215 -0.77360129 0.44214916, + 0.4991827 -0.7522915 0.42996973, + 0.5119648 -0.76313269 0.39436084, + 0.55709392 -0.73776293 0.38125095, + 0.56853133 -0.74588442 0.3470282, + 0.61302298 -0.71632999 0.333278, + 0.62292308 -0.72209203 0.30091503, + 0.66606194 -0.68850493 0.28691897, + 0.67436707 -0.69232708 0.25673404, + 0.71499193 -0.65551293 0.24308297, + 0.72166938 -0.65780628 0.2156021, + 0.75941002 -0.61825103 0.202638, + 0.76459932 -0.61944222 0.17798705, + 0.79944998 -0.577371 0.16589899, + 0.80336463 -0.57781869 0.14398192, + 0.8352108 -0.53361291 0.13296697, + 0.83805156 -0.53359973 0.11375795, + 0.8664574 -0.48827824 0.10409606, + 0.86844182 -0.48801988 0.087437779, + 0.89355022 -0.44192612 0.079179324, + 0.8948766 -0.4415738 0.064871967, + 0.91695076 -0.3947629 0.057994884, + 0.9177916 -0.39440984 0.045819078, + 0.93697476 -0.34706292 0.040318787, + 0.93805486 -0.34372598 0.043652195, + 0.95301801 -0.30050001 0.038162701, + 0.95370662 -0.29994687 0.021805393, + 0.96743935 -0.25243708 0.018351607, + 0.97623062 -0.21670993 0.0032506289, + 0.96762091 -0.25225598 0.0087517686, + 0.96443588 -0.26427898 0.0044879294, + 0.96440375 -0.26439595 0.004490959, + 0.96439689 -0.26439396 -0.0058686589, + 0.95032436 -0.31126112 0.00040597015, + 0.95030874 -0.31125593 0.0057532988, + 0.9503271 -0.31120002 0.0057518105, + 0.95034277 -0.31120494 0.00040469892, + 0.9502821 -0.31139004 0.00040469805, + 0.93392026 -0.35748109 -0.00052070414, + 0.93389839 -0.35753819 -0.00052847521, + 0.92631388 -0.37673193 -0.0039558997, + 0.91524887 -0.40288895 0.00010190999, + 0.91521412 -0.40287307 0.0087525705, + 0.91523302 -0.40283 0.00875137, + 0.91526777 -0.40284592 0.00010035797, + 0.9150449 -0.40335193 0.00010035998, + 0.91500932 -0.40333614 0.0088294027, + 0.89919591 -0.43729994 0.014675599, + 0.89878589 -0.43743795 0.028841397, + 0.87522388 -0.48266995 0.031823695, + 0.87453109 -0.48278907 0.045937404, + 0.8480981 -0.52745706 0.050187506, + 0.84691328 -0.5275082 0.06688042, + 0.81744087 -0.57143795 0.072450094, + 0.81563872 -0.5712958 0.091403469, + 0.78349835 -0.6135903 0.098170243, + 0.78093672 -0.61309075 0.11940496, + 0.7461378 -0.65351284 0.12727697, + 0.74265873 -0.65243876 0.15093593, + 0.70503181 -0.6909278 0.15983996, + 0.70049775 -0.68900675 0.18593694, + 0.6601882 -0.72515917 0.19569305, + 0.65451092 -0.72207296 0.22411197, + 0.61235189 -0.75505382 0.23434794, + 0.60547078 -0.7504487 0.26501292, + 0.56187803 -0.78001201 0.275453, + 0.55381197 -0.77352887 0.30813196, + 0.50908083 -0.7996127 0.31852189, + 0.49992782 -0.79089671 0.35292289, + 0.45454794 -0.81341189 0.36296996, + 0.44459587 -0.8022688 0.39837092, + 0.39976794 -0.82097489 0.40765893, + 0.38930801 -0.80726898 0.44357201, + 0.34572801 -0.82236701 0.451868, + 0.33502802 -0.80597013 0.48802507, + 0.29307687 -0.81784368 0.49521482, + 0.28249404 -0.79879314 0.53115606, + 0.24256507 -0.80784118 0.53717309, + 0.232529 -0.786421 0.57225198, + 0.19554099 -0.79297501 0.57702202, + 0.18635394 -0.76944172 0.61092675, + 0.15259403 -0.7739892 0.61453712, + 0.14446303 -0.7485112 0.64719516, + 0.11394103 -0.75152016 0.64979619, + 0.10709199 -0.72444993 0.68095791, + 0.079859219 -0.72631317 0.68270916, + 0.074459113 -0.69805419 0.71216315, + 0.05090338 -0.69908977 0.71321976, + 0.047032893 -0.67001194 0.74085891, + 0.026903195 -0.67051184 0.74141079, + 0.024577195 -0.64074785 0.76735783, + 0.0077396398 -0.64092201 0.76756698, + 0.0069704559 -0.61063367 0.79188251, + -0.006815243 -0.61063433 0.79188335, + -0.0075816871 -0.64084274 0.76763469, + -0.024310295 -0.64067185 0.76742983, + -0.026635891 -0.67043978 0.74148577, + -0.046713721 -0.6699453 0.74093938, + -0.050586708 -0.69904608 0.71328509, + -0.0741193 -0.698017 0.71223497, + -0.079515681 -0.72626179 0.68280381, + -0.10670107 -0.7244094 0.6810624, + -0.11356296 -0.75153267 0.64984775, + -0.14409 -0.74853301 0.64725298, + -0.15222202 -0.77401316 0.61459911, + -0.18598394 -0.7694757 0.61099678, + -0.19517688 -0.79302055 0.57708263, + -0.23217091 -0.78647673 0.57232082, + -0.242218 -0.80791402 0.53722, + -0.28212193 -0.79888481 0.53121591, + -0.29271305 -0.81795019 0.49525413, + -0.33471897 -0.80607486 0.48806393, + -0.3454181 -0.82247019 0.45191711, + -0.38900709 -0.80738318 0.44362813, + -0.39947507 -0.82109612 0.40770206, + -0.44429228 -0.80241048 0.39842424, + -0.45423511 -0.81354117 0.3630721, + -0.49967617 -0.7910133 0.35301811, + -0.50880879 -0.7997117 0.31870788, + -0.55357718 -0.77362531 0.30831212, + -0.56165814 -0.78012019 0.27559507, + -0.60522532 -0.75059336 0.26516411, + -0.61214566 -0.75522351 0.23433986, + -0.65434098 -0.72223002 0.22410201, + -0.6600672 -0.72533917 0.19543405, + -0.70041019 -0.68916321 0.18568705, + -0.70498896 -0.69109792 0.15929298, + -0.74264693 -0.65257293 0.15041299, + -0.74613023 -0.65364021 0.12666604, + -0.78094429 -0.61319321 0.11882804, + -0.78347665 -0.61368072 0.097777456, + -0.8156321 -0.57136405 0.091035306, + -0.81739056 -0.57150072 0.072521962, + -0.84687155 -0.52756679 0.066946872, + -0.848023 -0.52752 0.050790802, + -0.87402231 -0.48364916 0.046566915, + -0.87311888 -0.48378795 0.060105592, + -0.84629387 -0.52865195 0.065679394, + -0.84478843 -0.52870226 0.082500935, + -0.81483114 -0.57276708 0.089376904, + -0.81260931 -0.57257617 0.10873204, + -0.77989733 -0.61491829 0.11677206, + -0.77676898 -0.61428899 0.13884901, + -0.74133599 -0.65461999 0.147965, + -0.7371338 -0.65329283 0.17274895, + -0.69882017 -0.69152915 0.18286005, + -0.69344324 -0.68920726 0.21007107, + -0.65247595 -0.72488493 0.22094597, + -0.6458413 -0.72122037 0.25046012, + -0.60306609 -0.75354612 0.26168603, + -0.59514171 -0.74816662 0.29334787, + -0.55114418 -0.77683127 0.30458713, + -0.54198474 -0.76937264 0.33810985, + -0.49698988 -0.79442781 0.34912091, + -0.48678681 -0.78459769 0.38398585, + -0.44138715 -0.80597132 0.39444613, + -0.43039295 -0.79352885 0.43020195, + -0.38594383 -0.81100667 0.43967679, + -0.37445304 -0.79579514 0.47591507, + -0.33154887 -0.80969173 0.48422581, + -0.31990701 -0.79167199 0.520495, + -0.27890113 -0.80242634 0.52756625, + -0.26757494 -0.78183281 0.56315291, + -0.22897094 -0.78986281 0.56893688, + -0.21832493 -0.76691568 0.60346878, + -0.18289696 -0.77261782 0.60795587, + -0.17318304 -0.74748516 0.64130616, + -0.14121604 -0.7513473 0.64462024, + -0.13268797 -0.72434682 0.67654681, + -0.10412698 -0.72683597 0.67887193, + -0.097027734 -0.69848424 0.70901722, + -0.071957402 -0.69997603 0.71053201, + -0.066401318 -0.6705792 0.73886019, + -0.04506819 -0.6713798 0.7397418, + -0.041092087 -0.64117378 0.76629472, + -0.023273494 -0.64154184 0.76673484, + -0.02089881 -0.6107803 0.79152435, + -0.0064883223 -0.61090124 0.79168028, + -0.0057125799 -0.579988 0.814605, + 0.0057644383 -0.57998782 0.8146047, + 0.0065425686 -0.61098289 0.7916168, + 0.021062907 -0.61086023 0.79145831, + 0.023444504 -0.64169908 0.76659811, + 0.041316714 -0.64132726 0.76615429, + 0.04529319 -0.67152882 0.73959285, + 0.066756912 -0.67071921 0.73870116, + 0.072295815 -0.7000162 0.71045816, + 0.097390912 -0.69851607 0.70893604, + 0.10449706 -0.72689641 0.6787504, + 0.13303506 -0.72440135 0.67642027, + 0.14155202 -0.75136411 0.64452708, + 0.17354098 -0.74748993 0.64120394, + 0.18324709 -0.77260536 0.60786629, + 0.21867497 -0.76689291 0.60337096, + 0.22931406 -0.78982419 0.56885213, + 0.26793697 -0.78177786 0.56305695, + 0.27925494 -0.80235684 0.52748489, + 0.32020187 -0.7916047 0.52041584, + 0.33183503 -0.80961514 0.48415807, + 0.37474012 -0.79570532 0.47583917, + 0.386228 -0.81091398 0.43959799, + 0.430691 -0.79341602 0.430112, + 0.44167587 -0.8058508 0.39436892, + 0.48702711 -0.78448421 0.3839131, + 0.497235 -0.794321 0.349015, + 0.54221606 -0.76925713 0.33800203, + 0.55138701 -0.77672601 0.304416, + 0.59540892 -0.74802494 0.29316697, + 0.60331833 -0.75339448 0.26154116, + 0.64602482 -0.72110081 0.25033095, + 0.65263194 -0.72474992 0.22092797, + 0.69359463 -0.68906164 0.2100489, + 0.69891655 -0.69136161 0.1831249, + 0.73720324 -0.65314722 0.17300306, + 0.74136293 -0.65446496 0.14851499, + 0.77678019 -0.61415714 0.13936803, + 0.77990538 -0.61479229 0.11738006, + 0.81259203 -0.572492 0.109303, + 0.8148436 -0.57268971 0.089756958, + 0.84478283 -0.52865589 0.082855575, + 0.84632939 -0.52860522 0.065597929, + 0.87314898 -0.48374301 0.060030598, + 0.8741399 -0.48358294 0.045020696, + 0.89761126 -0.43889013 0.040859811, + 0.89685076 -0.43910587 0.053335488, + 0.8726598 -0.48476589 0.058881484, + 0.87136412 -0.48496005 0.074421205, + 0.84409088 -0.52999592 0.08133249, + 0.84215689 -0.53004092 0.099138089, + 0.81166947 -0.57416034 0.10739007, + 0.80892086 -0.57389492 0.12763898, + 0.77559602 -0.61617398 0.137042, + 0.7718541 -0.61538208 0.15983202, + 0.73573303 -0.65552205 0.17025802, + 0.73083377 -0.65392774 0.19560292, + 0.69183403 -0.69177204 0.20692302, + 0.68561327 -0.68902737 0.23489513, + 0.64396983 -0.72412884 0.24686094, + 0.63635206 -0.71985006 0.27725804, + 0.59305727 -0.75135535 0.28939316, + 0.58401108 -0.74512309 0.32206002, + 0.53960603 -0.7728191 0.33403003, + 0.52931982 -0.7643317 0.36826289, + 0.48416182 -0.78825569 0.37978986, + 0.47283193 -0.77720588 0.41518795, + 0.42760986 -0.79732573 0.42593586, + 0.41549399 -0.78345197 0.462134, + 0.37149402 -0.7996791 0.47170505, + 0.35895303 -0.78289211 0.50816607, + 0.3168349 -0.79557884 0.51640087, + 0.30434585 -0.77603364 0.55239975, + 0.264521 -0.785662 0.55925298, + 0.25246003 -0.76350009 0.59441704, + 0.21533108 -0.7705493 0.59990525, + 0.20405395 -0.74598581 0.63392985, + 0.170312 -0.75088602 0.63809401, + 0.16011396 -0.7242198 0.67072284, + 0.13001399 -0.72745794 0.67372197, + 0.12117203 -0.69915819 0.70462418, + 0.094647817 -0.70118606 0.70666808, + 0.087348022 -0.6717062 0.73565018, + 0.064445816 -0.6728822 0.73693717, + 0.058732707 -0.64231503 0.7641871, + 0.039543383 -0.6429227 0.76490963, + 0.035470292 -0.61160886 0.7903648, + 0.019894099 -0.61187291 0.79070586, + 0.017483702 -0.58027208 0.81423509, + 0.0053323815 -0.58035213 0.81434816, + 0.0045486712 -0.54874218 0.83597928, + -0.004497583 -0.54874229 0.83597946, + -0.0052809082 -0.58035183 0.8143487, + -0.017351804 -0.58027309 0.81423718, + -0.01975459 -0.6117717 0.79078764, + -0.03524911 -0.61151123 0.79045027, + -0.0393162 -0.64277202 0.76504803, + -0.058426622 -0.64217025 0.76433229, + -0.064131111 -0.67270309 0.73712808, + -0.08702369 -0.67153394 0.73584592, + -0.094344117 -0.70109606 0.70679808, + -0.12079406 -0.69908035 0.70476633, + -0.12964903 -0.72742015 0.67383319, + -0.159723 -0.72419399 0.67084402, + -0.169936 -0.75089902 0.638179, + -0.20367996 -0.74600893 0.63402295, + -0.21496403 -0.7705881 0.59998703, + -0.252094 -0.763551 0.59450698, + -0.26415697 -0.78571689 0.55934793, + -0.30399606 -0.77609921 0.55250013, + -0.31651014 -0.79567933 0.51644522, + -0.3586441 -0.78300118 0.50821614, + -0.37118682 -0.79979062 0.47175777, + -0.41518524 -0.78357947 0.46219528, + -0.42730191 -0.79744983 0.4260129, + -0.47258812 -0.77731717 0.4152571, + -0.48391977 -0.78836864 0.37986383, + -0.5290699 -0.7644648 0.36834592, + -0.53935891 -0.77295387 0.33411697, + -0.58377874 -0.74526674 0.32214889, + -0.59280074 -0.7514807 0.28959292, + -0.63614905 -0.71995705 0.27744603, + -0.64378577 -0.72424775 0.24699192, + -0.68544024 -0.68915522 0.23502509, + -0.69168675 -0.69190979 0.20695493, + -0.73071599 -0.65405101 0.195631, + -0.73566765 -0.65565872 0.17001392, + -0.77179915 -0.61551005 0.15960401, + -0.77558315 -0.61630607 0.13652001, + -0.80893314 -0.57398707 0.12714602, + -0.81168413 -0.57424706 0.10681401, + -0.84217846 -0.53010631 0.098603956, + -0.8440882 -0.53005713 0.080960721, + -0.87137055 -0.48500076 0.074078664, + -0.87263012 -0.48481005 0.058958307, + -0.89682102 -0.43915799 0.053406499, + -0.8979156 -0.4388068 0.034584183, + -0.91946089 -0.39196593 0.030892396, + -0.91994274 -0.3917819 0.014567796, + -0.93836737 -0.34540111 0.012843205, + -0.93919289 -0.34323198 0.010419799, + -0.94931436 -0.31429711 0.0044466415, + -0.94934547 -0.31420314 0.0044444823, + -0.94930536 -0.31432411 0.0044567613, + -0.94931465 -0.31432688 0.00056290085, + -0.94935465 -0.31420588 0.00056290085, + -0.94932353 -0.31429985 0.00056503073, + -0.96358764 -0.2673409 -0.0052622883, + -0.96014434 -0.2794871 -0.0031430111, + -0.96360189 -0.26733798 -0.0013623099, + -0.96359736 -0.26733708 0.0033296412, + -0.96359563 -0.26734293 0.0033297888, + -0.95426434 -0.29881111 0.0095669935, + -0.95397764 -0.29902887 0.022549193, + -0.93762612 -0.34666103 0.026141103, + -0.93670738 -0.34720913 0.045002613, + -0.91694087 -0.39571294 0.051289294, + -0.91550672 -0.39633986 0.069007881, + -0.89297968 -0.44342586 0.077206269, + -0.89135146 -0.44384775 0.092150144, + -0.8656708 -0.49016088 0.10176598, + -0.86325282 -0.49045688 0.11935897, + -0.83412385 -0.53593487 0.13042697, + -0.83070844 -0.53592122 0.15070507, + -0.7980392 -0.58010513 0.16313004, + -0.79340601 -0.57953298 0.186141, + -0.75763565 -0.62141073 0.1995919, + -0.7515589 -0.61995995 0.22540797, + -0.71287382 -0.6590808 0.23963194, + -0.70515215 -0.65635216 0.26825806, + -0.66360176 -0.69248074 0.28302491, + -0.65416479 -0.68804175 0.31411287, + -0.61022305 -0.72067904 0.32901302, + -0.59905511 -0.71406317 0.3622801, + -0.55394292 -0.74246395 0.37668893, + -0.54113793 -0.73322594 0.41176394, + -0.49569806 -0.7572571 0.42525905, + -0.48149011 -0.74503618 0.46161512, + -0.43629995 -0.76488489 0.47391295, + -0.42112499 -0.74949801 0.51078999, + -0.37695801 -0.765387 0.52161801, + -0.36133704 -0.74682808 0.55828607, + -0.31954402 -0.75895113 0.56734908, + -0.303882 -0.73722303 0.60345501, + -0.26513991 -0.74612176 0.61073977, + -0.24989709 -0.72141826 0.64583826, + -0.214412 -0.72772902 0.65148902, + -0.20014003 -0.70057106 0.68494105, + -0.16830999 -0.70483792 0.68911195, + -0.15535507 -0.67561424 0.72070122, + -0.12754999 -0.67833191 0.72359991, + -0.11612505 -0.64738321 0.75326627, + -0.092455879 -0.64900082 0.75514883, + -0.082734101 -0.61674899 0.78280002, + -0.063069433 -0.61763829 0.78392935, + -0.055235133 -0.58482534 0.80927646, + -0.039365176 -0.58526564 0.8098855, + -0.033365794 -0.55194485 0.83321279, + -0.021264201 -0.55212808 0.83348811, + -0.017051004 -0.51846111 0.85493118, + -0.0087154638 -0.51851624 0.85502344, + -0.0062414701 -0.48471299 0.87465101, + -0.00148965 -0.48472199 0.87466699, + -0.00069852365 -0.45139179 0.89232558, + 0.0008302115 -0.45139173 0.89232546, + 0.0016176504 -0.48467612 0.8746922, + 0.006322769 -0.48466694 0.87467587, + 0.0087956022 -0.51845914 0.85505718, + 0.017169802 -0.51840305 0.85496414, + 0.021382287 -0.55208963 0.83351052, + 0.033421494 -0.55190688 0.8332358, + 0.039434914 -0.58531523 0.80984628, + 0.055355985 -0.5848729 0.80923384, + 0.063267998 -0.61801302 0.78361797, + 0.083018839 -0.61711627 0.78248036, + 0.092741393 -0.64935791 0.75480688, + 0.11650401 -0.64772707 0.7529121, + 0.12789799 -0.67858201 0.72330397, + 0.15574294 -0.67585278 0.72039378, + 0.168663 -0.70499098 0.688869, + 0.20055109 -0.70070636 0.68468231, + 0.21477507 -0.72777122 0.65132225, + 0.25028506 -0.72144419 0.64565921, + 0.26549897 -0.74609792 0.61061293, + 0.30430287 -0.73717076 0.60330677, + 0.3199411 -0.75886816 0.56723613, + 0.3616811 -0.74674517 0.55817413, + 0.37730283 -0.76530665 0.52148676, + 0.42142695 -0.74941695 0.51065993, + 0.43655914 -0.76476228 0.47387218, + 0.48175317 -0.74489826 0.46156317, + 0.49596488 -0.75712681 0.4251799, + 0.54136389 -0.73310184 0.41168791, + 0.55416083 -0.74233478 0.37662286, + 0.59923869 -0.71394062 0.36221781, + 0.61040992 -0.72056097 0.32892498, + 0.65432894 -0.68792492 0.31402698, + 0.66377473 -0.69236761 0.28289586, + 0.70532399 -0.65622097 0.26812699, + 0.71304685 -0.65894979 0.23947693, + 0.75169927 -0.61984223 0.22526407, + 0.7577728 -0.62129289 0.19943796, + 0.7935065 -0.57943964 0.1860029, + 0.79811013 -0.58000803 0.16312902, + 0.83078486 -0.53580493 0.15069698, + 0.83416039 -0.53582126 0.13066006, + 0.8632732 -0.49036813 0.11957603, + 0.86566216 -0.49008012 0.10222802, + 0.89133286 -0.44379693 0.092573993, + 0.89295989 -0.44338194 0.077686392, + 0.91548401 -0.39631701 0.069440097, + 0.91653758 -0.39588681 0.056854874, + 0.93566567 -0.34930387 0.050164882, + 0.93493813 -0.34971604 0.059912808, + 0.91500568 -0.39764786 0.068124376, + 0.91371322 -0.39816108 0.081215821, + 0.89065826 -0.44550011 0.090871923, + 0.88870168 -0.44597885 0.10635896, + 0.86236459 -0.49247676 0.11744794, + 0.85951716 -0.49279213 0.13559604, + 0.82961184 -0.53833288 0.14812797, + 0.82562572 -0.53827584 0.16911894, + 0.792041 -0.58239901 0.182982, + 0.78664714 -0.58167905 0.20696802, + 0.7499038 -0.6232689 0.22176594, + 0.74285764 -0.62151468 0.24876088, + 0.70319796 -0.66008496 0.26419798, + 0.69435883 -0.65687084 0.29391593, + 0.65187097 -0.69219697 0.30972198, + 0.64115995 -0.68704593 0.34187996, + 0.59644359 -0.71860248 0.35758272, + 0.58387113 -0.71101415 0.39185908, + 0.538243 -0.738114 0.406795, + 0.52394307 -0.72762507 0.44277006, + 0.478331 -0.75019997 0.45650801, + 0.46272928 -0.73657143 0.49329931, + 0.41775894 -0.75489891 0.50557393, + 0.4013091 -0.73798215 0.54252511, + 0.35776904 -0.75237811 0.55310804, + 0.34090003 -0.73206604 0.58980209, + 0.30025885 -0.74277967 0.59843367, + 0.28351197 -0.71924096 0.63428193, + 0.2461751 -0.72693324 0.64106625, + 0.230167 -0.700656 0.67535502, + 0.19646204 -0.70595509 0.68046308, + 0.18159594 -0.67730874 0.71293473, + 0.15174194 -0.68078476 0.71659374, + 0.13830701 -0.65009701 0.74715799, + 0.11270703 -0.65222323 0.74960124, + 0.10093997 -0.61994088 0.7781288, + 0.07947202 -0.6211521 0.77965015, + 0.069524705 -0.58772904 0.80606514, + 0.052174192 -0.58835196 0.80691987, + 0.044205815 -0.55452317 0.83099329, + 0.030662708 -0.5548051 0.83141518, + 0.0245663 -0.52045602 0.853535, + 0.015036806 -0.52055418 0.85369629, + 0.010780699 -0.48600793 0.8738879, + 0.0049189213 -0.48603013 0.87392819, + 0.0024469192 -0.45166788 0.89218277, + 0.00053574221 -0.45166922 0.89218539, + -0.00024643197 -0.41785893 0.90851188, + 0.00058420387 -0.4178589 0.90851176, + -0.00020838097 -0.45185393 0.89209187, + -0.0023761205 -0.45185313 0.89208925, + -0.0048413118 -0.48607218 0.8739053, + -0.010691096 -0.48604983 0.87386572, + -0.014947697 -0.5205819 0.85368085, + -0.02457111 -0.5204832 0.85351831, + -0.03065961 -0.55478716 0.83142728, + -0.044143215 -0.5545072 0.8310073, + -0.052094791 -0.58825892 0.80699289, + -0.069447294 -0.58763695 0.80613887, + -0.079279572 -0.62067974 0.78004569, + -0.10059498 -0.61948192 0.77853888, + -0.112379 -0.65181899 0.75000203, + -0.13788396 -0.64970875 0.74757373, + -0.15137197 -0.68052584 0.71691781, + -0.18115905 -0.67706716 0.71327519, + -0.19606796 -0.70579982 0.68073779, + -0.2297399 -0.70051777 0.67564374, + -0.245802 -0.72688597 0.64126301, + -0.28311297 -0.71921194 0.63449293, + -0.29987699 -0.74277502 0.59863102, + -0.34058899 -0.73205698 0.589993, + -0.35747299 -0.752388 0.55328602, + -0.40094793 -0.73802996 0.54272693, + -0.41744477 -0.75499451 0.50569069, + -0.46245101 -0.73666799 0.49341601, + -0.47807989 -0.7503168 0.45657888, + -0.52370906 -0.72774804 0.44284505, + -0.53801388 -0.73823982 0.40686992, + -0.58365607 -0.71114707 0.39193806, + -0.59624666 -0.71874458 0.35762578, + -0.64098018 -0.68719119 0.34192508, + -0.65169001 -0.69234002 0.30978301, + -0.69419479 -0.65701681 0.29397693, + -0.70301998 -0.66022402 0.26432401, + -0.74273479 -0.62161875 0.24886791, + -0.74977195 -0.62336993 0.22192797, + -0.78652149 -0.58179265 0.20712589, + -0.79192883 -0.58251488 0.18309896, + -0.82552958 -0.53838879 0.16922893, + -0.8295368 -0.53844488 0.14814097, + -0.85947359 -0.49286675 0.13560094, + -0.8623516 -0.49254677 0.11724894, + -0.88869029 -0.44604415 0.10618003, + -0.89067489 -0.44555393 0.090442695, + -0.9137336 -0.39819282 0.080828965, + -0.91502559 -0.39767683 0.067685068, + -0.93495536 -0.34973612 0.059525523, + -0.93605262 -0.34906989 0.044222884, + -0.95301276 -0.30052793 0.038073294, + -0.95368636 -0.29998913 0.022114107, + -0.96742862 -0.2524589 0.018610293, + -0.96762401 -0.252262 0.0082266098, + -0.975546 -0.21978401 0.00223222, + -0.97554803 -0.219785 0.000748355, + -0.97569877 -0.21911494 0.00074835483, + -0.97569674 -0.21911395 0.0022091295, + -0.97554374 -0.21979395 0.0022240095, + -0.98516178 -0.17162396 0.0011831498, + -0.98515576 -0.17165895 0.0011839197, + -0.97858465 -0.20573193 0.0068126279, + -0.97846115 -0.20589703 0.014841202, + -0.96722311 -0.25327104 0.018255902, + -0.96675462 -0.25376692 0.031430289, + -0.95252621 -0.30214807 0.037422508, + -0.95172179 -0.30280095 0.050370689, + -0.93457723 -0.35093808 0.058378216, + -0.93358737 -0.35149813 0.069740824, + -0.91318178 -0.39975992 0.079316579, + -0.91160524 -0.40037107 0.09316162, + -0.8879227 -0.44802386 0.10424996, + -0.88555872 -0.44857985 0.12067296, + -0.85845882 -0.49527487 0.13323396, + -0.8550688 -0.49561489 0.15239197, + -0.82424015 -0.54123306 0.16641802, + -0.81954885 -0.54111791 0.18849696, + -0.784913 -0.58512098 0.203826, + -0.77863783 -0.58421987 0.22893295, + -0.74078393 -0.62543792 0.24508497, + -0.73269296 -0.62334192 0.27314097, + -0.69190484 -0.66128784 0.28976893, + -0.68184608 -0.65752709 0.32053703, + -0.63832921 -0.69192517 0.33730608, + -0.62618899 -0.68595701 0.370608, + -0.58065879 -0.71628875 0.38699585, + -0.56650591 -0.7075808 0.4223749, + -0.52039498 -0.73322701 0.437684, + -0.50455892 -0.72141194 0.47432595, + -0.45884883 -0.74241579 0.48813581, + -0.4417372 -0.72723538 0.52535427, + -0.39709482 -0.74396062 0.53743678, + -0.379186 -0.725272 0.57462901, + -0.33651996 -0.73809195 0.58478594, + -0.31834397 -0.71589494 0.62141097, + -0.27891105 -0.7252152 0.62950116, + -0.26113495 -0.69988781 0.66480482, + -0.225481 -0.70637399 0.67096502, + -0.20861807 -0.67831624 0.70453227, + -0.17694806 -0.68263227 0.70901525, + -0.16137005 -0.65220422 0.74066824, + -0.13377099 -0.65492594 0.74375892, + -0.11984901 -0.62268704 0.77323812, + -0.096662059 -0.62427074 0.77520472, + -0.084712125 -0.59103811 0.80218315, + -0.065815374 -0.59188378 0.80333167, + -0.055820294 -0.55783892 0.82806987, + -0.040815387 -0.55824482 0.82867169, + -0.032728717 -0.52343422 0.85143739, + -0.021688694 -0.52359086 0.85169381, + -0.0155217 -0.488323 0.87252498, + -0.0084560709 -0.48836407 0.87259912, + -0.0041990094 -0.45327294 0.89136189, + -0.00094581925 -0.45327711 0.89136922, + 0.0015127306 -0.41857216 0.90818232, + 0.0013208396 -0.41857192 0.90818274, + 0.0021030102 -0.38462606 0.92307013, + -0.0017713995 -0.38462591 0.92307079, + -0.00099577766 -0.41858384 0.90817767, + -0.0015428197 -0.4185839 0.90817678, + 0.00090693735 -0.45320216 0.89140731, + 0.0042698989 -0.45319787 0.89139974, + 0.008529583 -0.48833919 0.8726123, + 0.015610898 -0.48829693 0.87253785, + 0.021760708 -0.52348119 0.85175931, + 0.032794286 -0.52332377 0.8515026, + 0.040901598 -0.55823392 0.82867485, + 0.055817872 -0.55783075 0.82807559, + 0.065855704 -0.59202003 0.80322814, + 0.084886476 -0.59116685 0.80206984, + 0.096972615 -0.62477207 0.77476209, + 0.12023806 -0.62317628 0.77278334, + 0.13414694 -0.65537369 0.74329662, + 0.16184701 -0.65263206 0.74018705, + 0.17735502 -0.68291306 0.70864308, + 0.20911303 -0.67857206 0.70413905, + 0.225908 -0.70651299 0.67067498, + 0.26157188 -0.70001066 0.66450369, + 0.27929598 -0.72526497 0.62927294, + 0.31875408 -0.71592319 0.62116814, + 0.33686921 -0.73804641 0.58464235, + 0.37951192 -0.72521883 0.57448089, + 0.39744508 -0.74393219 0.53721714, + 0.44204405 -0.72720504 0.52513808, + 0.45911187 -0.74234581 0.48799488, + 0.50482798 -0.72132301 0.47417501, + 0.52062708 -0.73311108 0.43760207, + 0.56673604 -0.70745003 0.42228505, + 0.58087683 -0.71615475 0.38691685, + 0.62636095 -0.68583792 0.37053797, + 0.63849598 -0.69180697 0.33723301, + 0.68199003 -0.65741199 0.320467, + 0.69205195 -0.66117692 0.28967097, + 0.73281807 -0.62323505 0.27304903, + 0.74090898 -0.625332 0.244977, + 0.77875614 -0.58410406 0.22882603, + 0.78504002 -0.585006 0.203667, + 0.81964672 -0.5410198 0.18835293, + 0.82433069 -0.54113382 0.16629194, + 0.85514528 -0.49551919 0.15227406, + 0.85851032 -0.49518219 0.13324705, + 0.88559967 -0.44849586 0.12068395, + 0.88793898 -0.447947 0.104441, + 0.91160691 -0.40032595 0.093337893, + 0.91316271 -0.39972585 0.079706073, + 0.93357462 -0.35146388 0.070082575, + 0.93456274 -0.35090992 0.058775485, + 0.95170438 -0.30279812 0.050717019, + 0.95252764 -0.30213287 0.037506986, + 0.96675354 -0.25376189 0.031502184, + 0.967233 -0.253252 0.017994501, + 0.97846812 -0.20587903 0.014628402, + 0.97858375 -0.20572495 0.007142148, + 0.97624135 -0.21668507 0.00063633325, + 0.97623646 -0.2166841 0.0032474517, + 0.97627527 -0.21650904 0.0032430207, + 0.97628021 -0.21651004 0.0006356822, + 0.97623563 -0.21671093 0.00063568278, + 0.96444523 -0.26428106 -0.0010086203, + 0.9601441 -0.27948704 -0.0032364305, + 0.87130684 -0.49058989 0.012082597, + 0.8713702 -0.49062613 -0.00026725806, + 0.87142271 -0.49053282 -0.00027135291, + 0.87135911 -0.49049705 0.012079902, + 0.91334057 0.40719578 -0.00074399065, + 0.84375143 0.53673422 -8.8755442e-005, + -0.073566914 -0.99729025 -0.0003941771, + -0.073561169 -0.99721265 0.012475995, + -0.073503695 -0.99721688 0.012476098, + -0.07350944 -0.99729449 -0.00039641417, + -0.051477317 -0.99866635 -0.0039680316, + 0.029027604 -0.99948812 0.013454702, + 0.029030314 -0.99957848 -0.00045802322, + 0.028964112 -0.99958038 -0.00044912516, + 0.0289615 -0.99949002 0.0134547, + 0.022377808 -0.99955136 0.019909507, + 0.022343211 -0.9984265 0.051433425, + -0.0220496 -0.99843299 0.051433802, + -0.022084907 -0.99965334 0.014337006, + -0.024542488 -0.99955255 0.017101493, + 0.0028997413 -0.9998495 0.017106608, + 0.0029001692 -0.99999577 0, + -0.024546094 -0.99969876 0, + -0.024371 -0.99970299 2.3548801e-005, + -0.024368405 -0.99960023 0.014336104, + -0.067295067 -0.99755454 0.018874191, + -0.067192383 -0.99642175 0.051272288, + -0.021997603 -0.99843711 0.051376108, + -0.021926893 -0.99604964 0.086048968, + 0.022253908 -0.99604237 0.086048327, + 0.022327993 -0.99842763 0.051416483, + 0.067445874 -0.99640262 0.051312182, + 0.067546487 -0.99750376 0.020587394, + 0.076657914 -0.99698621 0.011920803, + 0.076723911 -0.99698114 0.011920702, + 0.07672929 -0.99705189 -0.00013069199, + 0.076663397 -0.99705702 -0.000133255, + 0.051477309 -0.99866623 -0.0039770207, + -0.17087506 -0.98529238 -0.00086399232, + -0.17091393 -0.98528564 -0.0008612817, + -0.17090504 -0.98523521 0.010157103, + -0.17086695 -0.98524177 0.010157197, + -0.15867402 -0.9871031 0.021214303, + -0.15845293 -0.98607653 0.050455578, + -0.11242203 -0.99236238 0.050777219, + -0.11206397 -0.99002576 0.085384779, + -0.066760987 -0.99407876 0.085734278, + -0.06643258 -0.99045265 0.12078995, + -0.021801993 -0.99240965 0.12102795, + -0.021655992 -0.98746765 0.15632895, + 0.021875894 -0.98746276 0.15632896, + 0.022023199 -0.992414 0.120952, + 0.066764094 -0.99043989 0.12071198, + 0.0670918 -0.99405903 0.085704699, + 0.11241705 -0.98998851 0.08535374, + 0.11277498 -0.99231189 0.050979193, + 0.15868905 -0.98602825 0.050656412, + 0.15890394 -0.98702466 0.023062693, + 0.17397305 -0.98475033 -0.00055474817, + 0.17396301 -0.98469514 0.010607201, + 0.17398696 -0.98469079 0.010607197, + 0.17399701 -0.9847461 -0.00055304903, + -0.0259207 0.99966401 -6.8508198e-005, + 0.15854898 0.98727489 -0.012267398, + 0.59815025 0.73843026 -0.31134713, + 0.59648699 0.73874199 -0.31378901, + 0.58365172 0.74737662 -0.31745684, + 0.57649308 0.74890804 -0.32679102, + 0.8243171 0.54149306 -0.16518702, + 0.78030652 0.59818262 -0.1824809, + 0.77573216 0.60246712 -0.18781105, + 0.73428005 0.64808607 -0.20203303, + 0.728329 0.65266502 -0.20872299, + 0.68834323 0.69091421 -0.22095507, + 0.6813218 0.69533479 -0.22871394, + 0.64324677 0.72732377 -0.23923591, + 0.63458818 0.73172015 -0.24876405, + 0.59876525 0.7583003 -0.2578001, + 0.58836508 0.76242709 -0.26931703, + 0.55452305 0.78465414 -0.27716804, + 0.54231685 0.78821284 -0.29088295, + 0.5100677 0.80693853 -0.29779384, + 0.50208205 0.80849612 -0.30699804, + 0.4817847 0.81921852 -0.31106982, + 0.48856217 0.81835628 -0.30265513, + 0.46828806 0.82871711 -0.30648702, + 0.46050116 0.83556432 -0.29961812, + -0.44004193 0.84994388 -0.28975597, + -0.417487 0.86007702 -0.29321, + -0.41707799 0.85997301 -0.29409599, + -0.40061408 0.86695218 -0.29648307, + -0.39990106 0.86667913 -0.29823902, + -0.38019609 0.87457216 -0.30095607, + -0.37929484 0.8740887 -0.30348688, + -0.35687113 0.88247532 -0.30639911, + -0.35559592 0.88156074 -0.31048694, + -0.33074597 0.89012486 -0.31350398, + -0.33127013 0.89061129 -0.3115631, + -0.30346411 0.8993963 -0.31463611, + -0.309383 0.906106 -0.28853801, + -0.27863795 0.91511875 -0.29140794, + -0.2837019 0.92197263 -0.26358992, + -0.25050002 0.93082213 -0.26612002, + -0.25437191 0.93712163 -0.23895191, + -0.21883206 0.94550925 -0.24109106, + -0.22172198 0.95125389 -0.21437196, + -0.18392396 0.95889276 -0.21609396, + -0.18598996 0.96406478 -0.18970196, + -0.14608999 0.97065789 -0.19099997, + -0.14747399 0.97521585 -0.16494098, + -0.10611203 0.98043025 -0.16582204, + -0.10695001 0.98435712 -0.14001001, + -0.064631477 0.98796564 -0.14052296, + -0.065048069 0.99125552 -0.11480995, + -0.021889806 0.99312127 -0.11502603, + -0.022001108 0.99575233 -0.089405432, + 0.021659592 0.99575967 -0.089406073, + 0.021547202 0.99312711 -0.11504102, + 0.064636528 0.9912805 -0.11482705, + 0.064219005 0.98799515 -0.14050502, + 0.10657501 0.98440009 -0.13999401, + 0.10573599 0.98047286 -0.16580999, + 0.14713499 0.9752689 -0.16492999, + 0.14574793 0.97070855 -0.1910039, + 0.18568391 0.96412253 -0.18970791, + 0.18361498 0.9589569 -0.21607196, + 0.22136207 0.95134133 -0.21435608, + 0.21846695 0.94560379 -0.24105094, + 0.25415987 0.93719059 -0.23890688, + 0.25029507 0.93090022 -0.26604006, + 0.28353497 0.9220469 -0.26350996, + 0.27851191 0.91524971 -0.29111692, + 0.30936307 0.90620726 -0.28824106, + 0.30345798 0.89951789 -0.31429398, + 0.33136699 0.89069802 -0.311212, + 0.33074591 0.89012277 -0.31350991, + 0.35562292 0.88154876 -0.31048995, + 0.35691601 0.88247699 -0.30634201, + 0.3792139 0.87413782 -0.30344695, + 0.38013309 0.87463015 -0.30086705, + 0.39989984 0.86671269 -0.29814288, + 0.40058091 0.86697382 -0.29646495, + 0.41714808 0.85995018 -0.29406306, + 0.41723016 0.85997128 -0.29388511, + 0.43051705 0.85408711 -0.29187402, + 0.42879301 0.85383397 -0.29513401, + 0.45274201 0.84271801 -0.29129201, + 0.44955972 0.8425135 -0.29676083, + 0.46384713 0.83559519 -0.29432407, + 0.47946793 0.8248139 -0.29965398, + 0.47697601 0.82608902 -0.300118, + 0.47689295 0.82609087 -0.30024496, + 0.47225177 0.82844257 -0.30109984, + 0.48933893 0.81634587 -0.30680096, + 0.49197683 0.81622869 -0.30286887, + 0.50235587 0.81065279 -0.30079994, + 0.50152081 0.81065369 -0.30218789, + 0.81795698 0.0034726299 0.57526898, + -0.74818492 0.17564099 0.63981992, + -0.73845476 0.23733291 0.63115579, + 0.78091812 0.16788901 0.60164803, + 0.77788967 0.18915391 0.59925669, + 0.74472594 0.20088397 0.63641894, + 0.7394222 0.23281907 0.63170415, + 0.70634007 0.24479502 0.66419804, + 0.69710493 0.29198998 0.65481794, + 0.66353315 0.30468705 0.68329316, + 0.66032702 0.31970301 0.679528, + 0.62583971 0.33203784 0.70574462, + 0.62272894 0.34664696 0.70145893, + 0.58717304 0.35861903 0.72568607, + 0.58424598 0.372603 0.72098798, + 0.54728413 0.38425109 0.74352616, + 0.54384512 0.40107509 0.7371372, + 0.50565308 0.41233206 0.75782412, + 0.5019539 0.43092391 0.74989784, + 0.46304613 0.4416061 0.76848716, + 0.45917678 0.4616808 0.75895166, + 0.41942692 0.47178587 0.77556384, + 0.41552693 0.49285993 0.76447791, + 0.37534592 0.5022369 0.77902085, + 0.37144908 0.52436912 0.76620018, + 0.33010009 0.53311914 0.7789852, + 0.32626191 0.55636287 0.76420784, + 0.28481409 0.56419218 0.77496332, + 0.28116402 0.58814603 0.75830811, + 0.23945896 0.59503895 0.76719487, + 0.23613009 0.61928123 0.74882126, + 0.19450492 0.62513173 0.75589561, + 0.19153893 0.64988577 0.73550075, + 0.14983492 0.6546706 0.7409156, + 0.14737794 0.67936778 0.71884578, + 0.10571498 0.68301994 0.72270894, + 0.10383302 0.70786917 0.69867021, + 0.062734239 0.71031439 0.70108342, + 0.061559908 0.73449504 0.67581606, + 0.020902505 0.73573017 0.67695218, + 0.020483103 0.75971115 0.64993805, + -0.020042995 0.75971782 0.64994383, + -0.020458706 0.7357372 0.6769582, + -0.061144214 0.73451418 0.67583317, + -0.062327117 0.71005815 0.70137918, + -0.10345398 0.70762384 0.69897485, + -0.10531298 0.68302381 0.72276384, + -0.14698291 0.67938358 0.71891159, + -0.14944009 0.6546604 0.74100441, + -0.19115999 0.649885 0.73559999, + -0.194126 0.62510997 0.75601101, + -0.23603897 0.61922693 0.74889493, + -0.239371 0.59498399 0.76726502, + -0.2808339 0.58813775 0.75843668, + -0.28448397 0.56417793 0.77509487, + -0.32595098 0.55635393 0.7643469, + -0.32978821 0.53310728 0.77912545, + -0.37115896 0.52436292 0.7663449, + -0.37512186 0.50182581 0.77939367, + -0.41555792 0.49240088 0.7647568, + -0.41939101 0.471681 0.77564698, + -0.45916995 0.46157193 0.75902188, + -0.46305317 0.44141915 0.76859027, + -0.50195575 0.4307428 0.75000066, + -0.50563282 0.41226184 0.75787568, + -0.54386485 0.40099585 0.73716575, + -0.54734284 0.38396886 0.74362874, + -0.58413023 0.37238511 0.72119427, + -0.58757913 0.35580409 0.72674221, + -0.62314993 0.34390298 0.70243496, + -0.62493414 0.33553609 0.70489216, + -0.65949595 0.32308498 0.67873496, + -0.66192532 0.31194314 0.68157631, + -0.69532704 0.29909304 0.65350103, + -0.70527792 0.24952097 0.66356796, + 0.53561282 8.0180274e-005 0.84446371, + 0.50071913 0.23427805 0.83330315, + 0.55443102 0.251416 0.79334497, + 0.57283127 0.00019690109 0.81967342, + 0.5349499 0.00019963295 0.8448838, + 0.52159613 0.22204106 0.82379317, + 0.5222562 0.22193207 0.82340431, + 0.99747723 0.022059405 0.067473218, + 0.99739301 0.0256253 0.067458197, + 0.99271387 0.042789496 0.11264198, + 0.99210334 0.055442519 0.11250404, + 0.98446167 0.077622168 0.15751193, + 0.98280233 0.097101137 0.15707006, + 0.97154987 0.12453599 0.20144898, + 0.96650249 0.16097908 0.1998971, + 0.95141834 0.19312008 0.23980808, + 0.94673789 0.21696398 0.23793697, + 0.92848611 0.25022304 0.27441204, + 0.92660177 0.25813293 0.27345294, + 0.90919685 0.28581196 0.30277497, + 0.90613776 0.29755795 0.30062193, + 0.88737398 0.32433799 0.32767701, + -0.86195469 0.36140987 0.35555187, + -0.83677858 0.39032081 0.38399383, + -0.83585387 0.39328393 0.38298294, + -0.8092432 0.42088208 0.40985808, + -0.8075999 0.42592993 0.40787995, + -0.77936155 0.45253974 0.43336272, + -0.77693981 0.45969087 0.43017292, + -0.74753034 0.48499325 0.45385021, + -0.74449497 0.49364299 0.44949299, + -0.71386498 0.51778799 0.471479, + -0.71019167 0.52792877 0.46574578, + -0.67804343 0.55118537 0.4862633, + -0.67360896 0.56307495 0.47874594, + -0.64022022 0.58524722 0.49759817, + -0.63512897 0.59853297 0.488231, + -0.60071105 0.61950207 0.50533503, + -0.59518677 0.63358676 0.49428782, + -0.56028563 0.65307057 0.5094887, + -0.55424911 0.66815919 0.49635813, + -0.51816386 0.68656582 0.51003289, + -0.51182389 0.70217383 0.49496287, + -0.47491005 0.71929204 0.50703007, + -0.46828267 0.73543346 0.48974365, + -0.43108308 0.75102615 0.50012714, + -0.4243432 0.76735538 0.48072723, + -0.38722301 0.78132498 0.48947901, + -0.38053107 0.7975471 0.46809706, + -0.34286198 0.8101539 0.47549593, + -0.33643404 0.8259111 0.45241907, + -0.29852885 0.83704358 0.45851779, + -0.29231903 0.85262012 0.43311507, + -0.2549099 0.86210972 0.43793586, + -0.24921106 0.87692225 0.41097608, + -0.21212992 0.8848837 0.41470686, + -0.20705408 0.89884728 0.38626716, + -0.17033795 0.90533072 0.38905185, + -0.16594101 0.91851211 0.35888603, + -0.12964599 0.92356485 0.36085996, + -0.12604801 0.93584812 0.32909003, + -0.090428606 0.93950713 0.33037704, + -0.087809622 0.95052421 0.29798207, + -0.052848525 0.95287645 0.29872015, + -0.051223326 0.96286547 0.26507813, + -0.0171567 0.96398902 0.26538801, + -0.016595803 0.97284424 0.23086506, + 0.016962003 0.97283822 0.23086406, + 0.017519502 0.96398312 0.26538602, + 0.05170691 0.96284121 0.26507205, + 0.053335894 0.95288187 0.29861596, + 0.088142 0.950526 0.297878, + 0.090777196 0.93942189 0.33052397, + 0.12639798 0.9357509 0.32923198, + 0.12997396 0.92352378 0.36084691, + 0.16641493 0.91843659 0.35885981, + 0.17077895 0.90537268 0.38876086, + 0.207479 0.89887601 0.38597199, + 0.21259093 0.88483071 0.41458386, + 0.24951798 0.87688786 0.41086295, + 0.25524294 0.86199182 0.43797389, + 0.29276106 0.85246021 0.4331311, + 0.29892805 0.83699518 0.45834613, + 0.33667022 0.82589746 0.45226827, + 0.34313911 0.81002527 0.47551519, + 0.38080308 0.79741019 0.46810913, + 0.38741592 0.78136784 0.48925787, + 0.4247959 0.76728481 0.48043987, + 0.43147385 0.7511307 0.49963284, + 0.46847311 0.73560417 0.48930511, + 0.47517899 0.71928501 0.50678802, + 0.51205504 0.70217007 0.49472907, + 0.51846594 0.68638897 0.50996393, + 0.55437887 0.66805983 0.49634689, + 0.56032884 0.65318477 0.50929481, + 0.59535807 0.63361907 0.49404007, + 0.60096091 0.61933488 0.50524288, + 0.63522017 0.59845412 0.48820913, + 0.64022082 0.58540386 0.49741289, + 0.67370921 0.56315619 0.47850919, + 0.67813402 0.55129898 0.48600799, + 0.71015584 0.52812487 0.46557787, + 0.7138176 0.51802272 0.47129273, + 0.74455178 0.49378583 0.44924185, + 0.74759877 0.48510984 0.45361286, + 0.77698636 0.45981321 0.42995819, + 0.77931881 0.45293188 0.43302992, + 0.80754513 0.42631707 0.40758407, + 0.8091833 0.42129314 0.40955415, + 0.8357926 0.39367983 0.38270983, + 0.8366071 0.39107406 0.38360107, + 0.86184669 0.36206487 0.35514688, + 0.86316317 0.36556309 0.3483001, + 0.88297558 0.33985686 0.32380787, + 0.99209267 -0.002775959 -0.12547696, + 0.99351352 -0.012586494 -0.11301495, + 0.99257064 -0.045546085 -0.11282296, + 0.99736077 -0.027179195 -0.067325786, + 0.99704087 -0.037243698 -0.067249492, + 0.99968064 -0.012242596 -0.022105992, + 0.99962687 -0.016090399 -0.022070698, + 0.99963164 0.015988594 0.021930993, + 0.99955714 0.020177502 0.021872602, + 0.99579197 0.0621383 0.067358598, + 0.87348914 0.41643605 0.25218603, + 0.84783256 0.4535768 0.27467787, + 0.84647131 0.45715615 0.27293709, + 0.81988382 0.49158287 0.29349095, + 0.81778616 0.49672711 0.29066807, + 0.78974271 0.52945185 0.30981788, + 0.78678715 0.53624511 0.30562606, + 0.75713319 0.5675531 0.32347009, + 0.75334048 0.57575136 0.31778717, + 0.72278219 0.60503215 0.33394909, + 0.71809959 0.61458266 0.32652879, + 0.68664783 0.64200282 0.34109691, + 0.68113416 0.65264016 0.33183908, + 0.64856684 0.6784898 0.34498191, + 0.64236891 0.68982196 0.33392796, + 0.60878927 0.71406722 0.34566411, + 0.60192174 0.72598773 0.33261389, + 0.5677591 0.74838817 0.34287709, + 0.56029505 0.76071215 0.32769904, + 0.52604395 0.78106791 0.33646798, + 0.51818419 0.79342127 0.31932411, + 0.48329487 0.81214982 0.32686192, + 0.47522518 0.82424629 0.30786213, + 0.43992987 0.8412658 0.31421891, + 0.43165585 0.85310668 0.29305688, + 0.39655292 0.86821383 0.29824594, + 0.38833407 0.87945414 0.27524003, + 0.35362017 0.89269143 0.27938312, + 0.34560898 0.9031629 0.25465897, + 0.31105086 0.91472656 0.25791988, + 0.30338502 0.92430711 0.23154703, + 0.26891693 0.93429375 0.23404895, + 0.26177794 0.94283473 0.20623995, + 0.22812003 0.95114315 0.20805803, + 0.22159603 0.95860112 0.17882702, + 0.18856804 0.96540523 0.18009704, + 0.18282899 0.971668 0.149783, + 0.15047406 0.97707337 0.15061606, + 0.14561304 0.98211938 0.11932504, + 0.11381503 0.98624927 0.11982703, + 0.10991903 0.99006635 0.087672226, + 0.078997023 0.99298924 0.087931022, + 0.076140508 0.99557912 0.054999407, + 0.04608399 0.99741673 0.055100884, + 0.044336922 0.99878049 0.021724211, + 0.015075498 0.99964988 0.021743098, + 0.014472893 0.99982351 -0.011982795, + -0.014099396 0.99982876 -0.011982897, + -0.014701194 0.99965662 0.021690693, + -0.043967396 0.99879789 0.021671997, + -0.045716695 0.99743485 0.055078991, + -0.075740285 0.99561077 0.054978285, + -0.07859996 0.99302053 0.087933056, + -0.109532 0.99010903 0.087675303, + -0.11342404 0.98629934 0.11978605, + -0.14522493 0.98218155 0.11928594, + -0.15009502 0.97713012 0.15062602, + -0.18245994 0.97173566 0.14979394, + -0.18817507 0.96550536 0.17997105, + -0.22120407 0.95871437 0.17870507, + -0.22775207 0.95123935 0.20802107, + -0.26148409 0.94292438 0.20620307, + -0.26865095 0.93436575 0.23406693, + -0.30297396 0.92443389 0.23157898, + -0.31061384 0.91488659 0.25787887, + -0.34526199 0.90330797 0.25461501, + -0.35328698 0.89282888 0.27936497, + -0.388096 0.87956703 0.275215, + -0.39633995 0.86830789 0.29825497, + -0.43138185 0.85323769 0.29307887, + -0.43966007 0.84140015 0.31423703, + -0.47498775 0.82437652 0.30787984, + -0.48305783 0.81228769 0.32686988, + -0.51785594 0.7936219 0.31935796, + -0.52580076 0.78113562 0.33669084, + -0.56018686 0.76071084 0.32788691, + -0.5675931 0.74848616 0.3429381, + -0.60169011 0.7261402 0.3327001, + -0.608652 0.71405399 0.34593299, + -0.6422258 0.68982583 0.3341949, + -0.64842325 0.67848927 0.34525311, + -0.68112868 0.65253973 0.33204785, + -0.68659073 0.64200068 0.34121585, + -0.71804863 0.6145817 0.32664284, + -0.72271395 0.60506696 0.33403397, + -0.7532925 0.57577264 0.31786183, + -0.75709784 0.56754786 0.32356191, + -0.7867108 0.53629088 0.30574194, + -0.78975087 0.52930093 0.31005496, + -0.81786269 0.49649981 0.29084092, + -0.81989318 0.49151811 0.29357305, + -0.84647989 0.45709494 0.27301297, + -0.8479352 0.45326611 0.27487406, + -0.87354219 0.41619807 0.25239506, + 0.87783372 0.39175984 0.27555791, + 0.85298914 0.42690107 0.30027503, + 0.85189539 0.43000722 0.29894516, + 0.82588673 0.46295181 0.32184887, + 0.82421499 0.46740699 0.31968799, + 0.79665899 0.498898 0.34122601, + 0.7939831 0.50562209 0.33754602, + 0.76482832 0.53580821 0.35769713, + 0.76161599 0.54344797 0.35299501, + 0.73136365 0.57192671 0.37149283, + 0.72720277 0.58133382 0.36500287, + 0.69611484 0.60801786 0.3817569, + 0.69114995 0.61871296 0.37350497, + 0.65862304 0.64419204 0.38888606, + 0.65296304 0.65583605 0.37883806, + 0.61942112 0.67979521 0.39267808, + 0.61299968 0.69243467 0.38048083, + 0.57895136 0.71458942 0.39265424, + 0.57211107 0.72750306 0.37871906, + 0.53744507 0.74801308 0.38939607, + 0.5301007 0.76135051 0.37328079, + 0.49483988 0.78025085 0.3825469, + 0.48725012 0.79354417 0.3645201, + 0.45132673 0.81089753 0.37249079, + 0.44352022 0.82412344 0.35229319, + 0.40790015 0.83953631 0.35888213, + 0.40009409 0.85235715 0.33676708, + 0.36445513 0.8660723 0.34218612, + 0.35679099 0.878326 0.31818801, + 0.32121691 0.89038074 0.32255492, + 0.31383988 0.90191168 0.29674888, + 0.2783629 0.91236073 0.30018687, + 0.27143809 0.92300135 0.2727451, + 0.2364829 0.93180466 0.2753469, + 0.230198 0.94137502 0.246621, + 0.19600892 0.94858962 0.24851191, + 0.19042005 0.95709926 0.21840605, + 0.15675394 0.96288562 0.21972592, + 0.15195797 0.97029978 0.18822095, + 0.11876994 0.97475153 0.18908492, + 0.11494497 0.98090875 0.15686196, + 0.082562365 0.98408252 0.15736893, + 0.079769805 0.98902512 0.12436301, + 0.048255607 0.99103111 0.12461501, + 0.046534214 0.99477834 0.090832926, + 0.015776103 0.99573326 0.090920024, + 0.015194206 0.99828935 0.056458719, + -0.014842493 0.99829453 0.056458972, + -0.015437394 0.99574363 0.090864569, + -0.046132602 0.994802 0.090778597, + -0.047855306 0.99105811 0.12455402, + -0.079378799 0.98906398 0.124304, + -0.082195699 0.98410398 0.157427, + -0.114509 0.98095 0.156923, + -0.11831895 0.97480363 0.18909892, + -0.15154992 0.97036052 0.18823691, + -0.15633202 0.9629761 0.21963003, + -0.19003792 0.95719665 0.21831192, + -0.19565095 0.94865876 0.24852994, + -0.22988106 0.94144726 0.24664105, + -0.23616996 0.93187785 0.27536798, + -0.27109709 0.92309338 0.27277309, + -0.27800199 0.912494 0.300116, + -0.31351808 0.90204626 0.29668006, + -0.32095289 0.89043373 0.32267189, + -0.3565079 0.87839675 0.3183099, + -0.36413902 0.86620414 0.34218904, + -0.39970595 0.8525309 0.33678797, + -0.40749592 0.83974284 0.3588579, + -0.44336495 0.82423389 0.35222998, + -0.45120886 0.81096071 0.37249589, + -0.48691511 0.79372317 0.3645781, + -0.49458724 0.78028435 0.38280517, + -0.52988911 0.7613762 0.37352908, + -0.53721607 0.74806505 0.38961205, + -0.571899 0.72755897 0.378932, + -0.57876712 0.71458817 0.39292809, + -0.61295426 0.69235325 0.38070214, + -0.61929286 0.6798768 0.39273891, + -0.65286309 0.65590507 0.37889105, + -0.65854901 0.64421099 0.38898, + -0.69097006 0.61882508 0.37365204, + -0.69593406 0.60813308 0.38190305, + -0.72725993 0.58125097 0.36502096, + -0.7314052 0.5718801 0.37148309, + -0.76148719 0.54356611 0.35309109, + -0.76490486 0.53543097 0.35809797, + -0.79406387 0.50524992 0.33791298, + -0.79657936 0.49892324 0.34137514, + -0.82422268 0.46734083 0.31976488, + -0.82598102 0.462652 0.32203799, + -0.85198414 0.42971507 0.29911202, + -0.85299867 0.42683285 0.30034488, + -0.87789726 0.39161408 0.27556306, + -0.9017393 0.34035313 0.26650709, + -0.90594471 0.32566589 0.2705659, + -0.92371821 0.29465005 0.24479806, + -0.92642826 0.28410605 0.24701107, + -0.94280833 0.25155309 0.21870908, + -0.94446462 0.24430192 0.21977992, + -0.95938712 0.20971704 0.18866703, + -0.95886886 0.21227796 0.18843697, + -0.97397411 0.16950801 0.15047102, + -0.97801989 0.14288898 0.15185499, + -0.99970049 -0.0079095233 -0.023162011, + -0.99970573 -0.0078633083 -0.022946695, + -0.99969488 -0.010198499 -0.022499299, + -0.99970126 -0.010143002 -0.022238506, + -0.99972314 -0.0076769511 -0.022245402, + -0.99972385 0.007666599 0.022215398, + -0.99968702 0.0115467 0.022193501, + -0.99713975 0.034883093 0.067047685, + -0.99668413 0.046295602 0.06691511, + -0.99082762 0.076884769 0.11112797, + -0.98842454 0.10396595 0.11048995, + -0.98819989 0.10844798 0.10816699, + -0.98527324 0.13325202 0.10714702, + -0.97257566 0.18125694 0.14574796, + -0.97305936 0.17847106 0.14595807, + -0.95947826 0.21812604 0.17838904, + -0.95848262 0.22296992 0.17775095, + -0.94331712 0.25951904 0.20688803, + -0.94140637 0.26755708 0.20534708, + -0.92476279 0.30188194 0.23169194, + -0.92152524 0.31388509 0.22862107, + -0.90339601 0.34661299 0.25245801, + -0.89854723 0.36259609 0.24725907, + -0.87894875 0.39402393 0.26868993, + -0.87547922 0.4044171 0.26454306, + -0.8505652 0.44007912 0.28787005, + -0.84944379 0.44314888 0.28646895, + -0.8231293 0.47688818 0.30827913, + -0.82109648 0.4820933 0.30559218, + -0.79330552 0.51421767 0.32595479, + -0.79058719 0.52075911 0.32215208, + -0.7611227 0.55159384 0.34122789, + -0.75755686 0.55969095 0.33593696, + -0.72728676 0.58846974 0.35320988, + -0.72276926 0.59817827 0.34610313, + -0.69139779 0.62534374 0.36182088, + -0.68624604 0.63585407 0.35320804, + -0.65366703 0.66156608 0.36749104, + -0.64769202 0.67316598 0.35685101, + -0.61412263 0.69729358 0.36964178, + -0.60755295 0.70945191 0.35715196, + -0.57338929 0.73178536 0.36839518, + -0.56615812 0.74456918 0.35366908, + -0.53169405 0.76501912 0.36338302, + -0.52409405 0.77787614 0.34674802, + -0.48894218 0.79674232 0.35515812, + -0.48106223 0.80953038 0.33651114, + -0.44553712 0.82668418 0.34364209, + -0.43751207 0.8391971 0.32300404, + -0.40200609 0.85452521 0.32890409, + -0.3940261 0.86651719 0.30641705, + -0.35886204 0.87999111 0.31118104, + -0.35095504 0.8914541 0.28660104, + -0.31584099 0.90327799 0.290402, + -0.30830595 0.91384774 0.26425293, + -0.2733821 0.92404836 0.26720208, + -0.26638103 0.93358314 0.23971602, + -0.23200905 0.94215125 0.24191506, + -0.22559798 0.9506759 0.21288697, + -0.19192991 0.95769054 0.2144569, + -0.18622595 0.96512276 0.18400496, + -0.15323307 0.97070533 0.18507005, + -0.14842503 0.97688824 0.15381603, + -0.11590195 0.9811725 0.15448992, + -0.11203995 0.98615652 0.12223894, + -0.08041431 0.98919111 0.12261502, + -0.077580616 0.99295026 0.089616723, + -0.046779577 0.99486154 0.089789152, + -0.04504041 0.99740726 0.056126114, + -0.015038492 0.99830753 0.056176674, + -0.014445404 0.99965227 0.022063006, + 0.014855904 0.99964625 0.022062905, + 0.015447 0.99830598 0.056094699, + 0.045474913 0.99739224 0.056043416, + 0.047217298 0.99484098 0.089788102, + 0.077977717 0.99291927 0.089614622, + 0.080813698 0.98915303 0.12266, + 0.11242799 0.98610687 0.12228298, + 0.11628599 0.98112285 0.15451698, + 0.14878607 0.97682947 0.15384108, + 0.15358803 0.97063321 0.18515405, + 0.1866421 0.96502745 0.18408409, + 0.19233604 0.95759922 0.21450104, + 0.22596604 0.95057911 0.21292903, + 0.23234896 0.94208491 0.24184696, + 0.26666489 0.9335196 0.23964788, + 0.27368513 0.92394042 0.26726511, + 0.30874506 0.91368622 0.26429906, + 0.31623387 0.90318173 0.2902739, + 0.35133791 0.89134574 0.28646895, + 0.35920003 0.87995511 0.31089303, + 0.39431694 0.86648488 0.30613396, + 0.40239191 0.8543548 0.32887492, + 0.43778411 0.8390612 0.32298809, + 0.44574881 0.82663661 0.34348184, + 0.48133677 0.80943966 0.33633685, + 0.48927069 0.79656351 0.3551068, + 0.52430701 0.77774602 0.34671801, + 0.53187484 0.7649377 0.36328989, + 0.5663318 0.74448174 0.35357487, + 0.57357609 0.73166919 0.3683351, + 0.60767287 0.70937079 0.35710892, + 0.61416304 0.69735807 0.36945304, + 0.64783782 0.67314482 0.35662591, + 0.65377891 0.66161495 0.36720398, + 0.68631291 0.63592696 0.35294697, + 0.69156861 0.6252057 0.36173281, + 0.72284198 0.59811598 0.34605899, + 0.72722697 0.58869302 0.352961, + 0.75758988 0.55981892 0.33564898, + 0.76124269 0.5515278 0.34106687, + 0.79059583 0.52079988 0.32206491, + 0.7932291 0.51446605 0.32574904, + 0.82107872 0.48226881 0.30536288, + 0.82309872 0.47710183 0.30802989, + 0.8493498 0.44343987 0.28629693, + 0.85046881 0.44037989 0.28769493, + 0.8754369 0.40463793 0.26434496, + 0.87891126 0.39424109 0.26849407, + 0.89846289 0.36288598 0.24713998, + 0.90333629 0.34683713 0.2523641, + 0.92146474 0.31411192 0.22855294, + 0.92462802 0.302403 0.23154999, + 0.94128501 0.26805699 0.20525099, + 0.94309789 0.26045597 0.20670997, + 0.95827949 0.22389011 0.17769009, + 0.95921862 0.21934593 0.17828894, + 0.97288787 0.17946899 0.14587699, + 0.97376066 0.17435095 0.14625993, + 0.98594749 0.12798606 0.10736505, + 0.98852378 0.10533098 0.10828698, + 0.99572438 0.064408422 0.066216022, + 0.99669725 0.04657441 0.066523612, + 0.99963713 0.015450102 0.022067903, + 0.99968511 0.011889802 0.022100702, + 0.99968249 -0.011938806 -0.022191711, + 0.99971473 -0.0087842485 -0.022209495, + 0.99736375 -0.026688794 -0.067478083, + 0.99770075 -0.0054014986 -0.067556784, + 0.99956936 0.0046917317 -0.028968111, + 0.99957865 -0.0017990193 -0.028968388, + 0.99957663 -0.0018354394 -0.029036088, + 0.99940652 -0.018538991 -0.029031187, + 0.99960947 -0.016948607 -0.022218712, + 0.99971497 -0.0086792503 -0.0222426, + 0.99971575 0.0086664483 0.022209795, + 0.99968678 0.011564797 0.022193395, + 0.9971379 0.034937795 0.067047089, + 0.99674237 0.045001514 0.066930525, + 0.99098653 0.074746564 0.11116995, + 0.98873252 0.10091896 0.11055895, + 0.97859424 0.13874403 0.15199803, + 0.97495311 0.16354801 0.15072702, + 0.96029335 0.20515507 0.18907207, + 0.95912564 0.21101393 0.18854992, + 0.94417602 0.24565899 0.21950699, + 0.94260448 0.25250211 0.2184941, + 0.92619914 0.28511104 0.24671203, + 0.92359257 0.29521784 0.24458788, + 0.90576673 0.32632887 0.27036291, + 0.90168202 0.34056899 0.26642501, + 0.8824901 0.37044504 0.28979602, + 0.87953639 0.37989518 0.28652316, + 0.85516411 0.41384706 0.31213003, + 0.85433227 0.41629416 0.31115213, + 0.8284682 0.44858113 0.33528408, + 0.82693613 0.45282805 0.33335203, + 0.79965401 0.48356301 0.35597801, + 0.79733986 0.48963293 0.35285798, + 0.76831365 0.51927978 0.37422282, + 0.76512712 0.52721703 0.36962503, + 0.73522598 0.55501002 0.38911, + 0.73126417 0.56441313 0.3830021, + 0.70021665 0.59075671 0.40087783, + 0.69562119 0.6011861 0.39330208, + 0.66321594 0.62630695 0.40973693, + 0.65775293 0.63819093 0.40009195, + 0.62420207 0.66193908 0.41498005, + 0.61818725 0.67450821 0.40358815, + 0.58395571 0.69660866 0.41681179, + 0.57735604 0.70989907 0.40336505, + 0.54261416 0.73032224 0.41496915, + 0.53557187 0.74402481 0.3994869, + 0.50015932 0.76291746 0.40963125, + 0.49274176 0.77690065 0.39195782, + 0.45677105 0.79422909 0.40070006, + 0.44913605 0.80820912 0.38088706, + 0.41304991 0.82380885 0.38823792, + 0.40552691 0.83725482 0.3668139, + 0.36949304 0.85113209 0.37289304, + 0.36202696 0.86422288 0.34936398, + 0.32604298 0.87644887 0.35430697, + 0.31882614 0.88892543 0.32887915, + 0.28286985 0.89956558 0.33281586, + 0.27607095 0.91123676 0.30566695, + 0.24048409 0.92025834 0.30869412, + 0.2342919 0.93093359 0.28012487, + 0.19953991 0.93832952 0.28234985, + 0.194043 0.94795299 0.252453, + 0.15977105 0.95390636 0.25403908, + 0.15506692 0.96243954 0.2228549, + 0.12107105 0.96705735 0.22392407, + 0.11729103 0.97443324 0.19163205, + 0.084293075 0.97771376 0.19227695, + 0.081508867 0.98389763 0.15906493, + 0.049298309 0.98598212 0.15940201, + 0.047597919 0.99093735 0.12560904, + 0.016171202 0.99193209 0.12573501, + 0.015591002 0.9957121 0.091183506, + -0.015213098 0.99571788 0.09118399, + -0.01580669 0.99194539 0.12567593, + -0.047194991 0.99096388 0.12555198, + -0.048900623 0.98600149 0.15940507, + -0.081176266 0.98392451 0.15906893, + -0.08396709 0.9777599 0.19218497, + -0.11689895 0.97449762 0.19154392, + -0.12069398 0.96710289 0.22393097, + -0.15458499 0.96251386 0.22286896, + -0.15928996 0.95396876 0.25410694, + -0.19366004 0.94801313 0.25252104, + -0.19916208 0.93838936 0.2824181, + -0.23395708 0.93099737 0.28019309, + -0.240164 0.920304 0.30880699, + -0.27562606 0.91132826 0.30579606, + -0.2824209 0.89965671 0.33295089, + -0.31856102 0.8889761 0.32899904, + -0.32573491 0.87658274 0.35425892, + -0.3617239 0.86436683 0.3493219, + -0.36919391 0.85128284 0.3728449, + -0.40511692 0.83746284 0.3667919, + -0.41272384 0.82386869 0.38845786, + -0.44897011 0.80821216 0.3810761, + -0.45655501 0.79432899 0.40074801, + -0.49253196 0.77700788 0.39200893, + -0.49993712 0.76305717 0.4096421, + -0.53537893 0.74415892 0.39949593, + -0.54243487 0.73043782 0.4149999, + -0.57720482 0.71000677 0.40339184, + -0.58382106 0.69669205 0.41686106, + -0.61805713 0.67459619 0.40364009, + -0.62408727 0.6620003 0.41505522, + -0.65767694 0.63823092 0.40015295, + -0.66313899 0.62635303 0.40979099, + -0.69543558 0.60132563 0.39341676, + -0.70022702 0.59044498 0.401319, + -0.73129874 0.56409281 0.38340786, + -0.73509008 0.55508906 0.38925406, + -0.76518989 0.52711695 0.36963797, + -0.76837587 0.51918095 0.37423196, + -0.79725087 0.48969194 0.35297698, + -0.79965287 0.48338795 0.35621798, + -0.82702082 0.45256287 0.33350191, + -0.828556 0.44830301 0.335439, + -0.85435116 0.4161081 0.31134906, + -0.85517269 0.41368884 0.31231588, + -0.87960976 0.3796519 0.28661993, + -0.88255775 0.3702119 0.28988793, + -0.88142598 0.366988 0.297335, + -0.85731 0.399993 0.324076, + -0.85646898 0.40255901 0.32312101, + -0.83092469 0.43389884 0.34827587, + -0.82951784 0.43795189 0.34655192, + -0.80240947 0.46798128 0.37031421, + -0.80024731 0.47389218 0.36746511, + -0.77146184 0.5028199 0.38989592, + -0.76859313 0.51029307 0.38583106, + -0.73873496 0.53761894 0.40649295, + -0.73491126 0.54714018 0.40067816, + -0.70397776 0.57300484 0.41961986, + -0.69966179 0.58331281 0.41257685, + -0.66726696 0.60808694 0.43009895, + -0.66216731 0.61980927 0.4211542, + -0.6286642 0.64323419 0.43707108, + -0.62276697 0.65630001 0.42594799, + -0.58846879 0.67820376 0.44016385, + -0.58216983 0.69169676 0.42735684, + -0.54740614 0.71194416 0.43986613, + -0.54053807 0.72620904 0.42478105, + -0.50498569 0.74503356 0.43579173, + -0.49783307 0.75948614 0.41874006, + -0.46144593 0.77690887 0.42834595, + -0.45420179 0.79121763 0.40948179, + -0.41784695 0.80686486 0.41757995, + -0.41035315 0.82138532 0.39615214, + -0.37404591 0.8353318 0.4028779, + -0.36676592 0.84923583 0.37984392, + -0.33033678 0.86160445 0.38537675, + -0.32331604 0.87492609 0.36051503, + -0.28672808 0.88576329 0.36498013, + -0.28011006 0.89835823 0.33836508, + -0.24414806 0.90750122 0.34180909, + -0.23802406 0.91931123 0.3133871, + -0.20259397 0.92688686 0.31596896, + -0.19718195 0.93762475 0.28631994, + -0.16223298 0.9437319 0.28818497, + -0.15760101 0.95342314 0.25718904, + -0.12299895 0.95815766 0.2584669, + -0.11927297 0.96671778 0.22634193, + -0.085636437 0.97009146 0.2271321, + -0.08287321 0.97751009 0.19392303, + -0.049926706 0.97966111 0.19434904, + -0.048235923 0.98587346 0.16039607, + -0.016097492 0.98689443 0.1605619, + -0.015519395 0.99189866 0.12607996, + 0.015926603 0.99189222 0.12608004, + 0.016502701 0.98688799 0.160561, + 0.04863362 0.98585439 0.16039306, + 0.050321922 0.9796415 0.19434609, + 0.083260961 0.9774785 0.1939159, + 0.086021006 0.9700591 0.22712503, + 0.11965203 0.96667325 0.22633205, + 0.12339004 0.95807636 0.25858209, + 0.15798394 0.95332962 0.25730091, + 0.16258605 0.94369125 0.28811905, + 0.19756304 0.93756622 0.28624907, + 0.20296997 0.92682886 0.31589797, + 0.23832409 0.91925734 0.31331712, + 0.24447909 0.9073773 0.34190112, + 0.28046706 0.89821523 0.33844909, + 0.2870701 0.88563228 0.36502913, + 0.32362708 0.87479216 0.3605611, + 0.3306329 0.86148369 0.38539284, + 0.36708099 0.849096 0.379852, + 0.37435803 0.8351841 0.40289405, + 0.41060895 0.82124788 0.39617193, + 0.41802478 0.80687165 0.4173888, + 0.45446506 0.79117614 0.40927005, + 0.46179506 0.77669811 0.42835206, + 0.49804613 0.75932819 0.41877308, + 0.50515777 0.74494964 0.43573579, + 0.5407269 0.72610784 0.42471391, + 0.54751098 0.71201301 0.43962401, + 0.58234203 0.69171602 0.427091, + 0.58863068 0.6782527 0.43987179, + 0.62291092 0.65634692 0.42566493, + 0.62881118 0.64328218 0.4367891, + 0.66226596 0.61987793 0.42089793, + 0.66736269 0.60816872 0.42983478, + 0.69964337 0.58347332 0.4123812, + 0.70404202 0.57296902 0.419561, + 0.73505402 0.54702997 0.400567, + 0.73877263 0.53777277 0.40622082, + 0.76853085 0.51052988 0.3856419, + 0.7714811 0.50284606 0.38982406, + 0.80026317 0.47391713 0.36739808, + 0.80234581 0.46822587 0.37014291, + 0.82943654 0.43821272 0.3464168, + 0.83094251 0.43387672 0.34826079, + 0.85648614 0.40253606 0.32310402, + 0.86009902 0.39132899 0.32724801, + 0.88020802 0.364066 0.30445001, + 0.88520688 0.34736696 0.30942696, + 0.90417314 0.31896904 0.28413004, + 0.90767586 0.30612496 0.28707498, + 0.92522609 0.27676103 0.25953802, + 0.92753088 0.26743996 0.26107898, + 0.94372046 0.23666912 0.23104011, + 0.94521052 0.2299379 0.2317449, + 0.96173263 0.19297993 0.19449693, + 0.96609348 0.16795108 0.19610208, + 0.97892362 0.13284695 0.15511394, + 0.98260415 0.10054001 0.15614401, + 0.99110663 0.072040379 0.11188296, + 0.99207234 0.05674262 0.11212904, + 0.99715137 0.03405701 0.067300223, + 0.99739164 0.025931891 0.067360274, + 0.99971598 0.0085628899 0.022242799, + 0.99973863 0.0052419482 0.022251993, + 0.99999553 -0.00068243768 -0.0028969387, + 0.99999577 0 -0.0028969394, + 0.99969864 0 0.024546791, + 0.99969655 -0.0020437092 0.024546789, + 0.99970025 -0.0020790605 0.024397906, + 0.99970233 8.0068232e-005 0.02439801, + 0.99854833 -0.015867706 0.05147332, + 0.9972949 -0.0015983097 0.073487192, + 0.99728423 0.0048902314 0.073486418, + 0.99727553 0.0049179979 0.073602162, + 0.99728638 -0.0015803205 0.073603027, + 0.98589134 0.053052019 0.15875706, + 0.98560703 0.058255602 0.15869799, + 0.97594124 0.075134516 0.20467904, + 0.97437048 0.094269045 0.20424411, + 0.95988899 0.117498 0.25457299, + 0.93069535 0.071486421 0.35874212, + 0.88903171 0.098516561 0.44712085, + 0.89191473 0.12906195 0.43339485, + 0.86541069 0.15745795 0.47567981, + 0.83853471 0.17121693 0.51724684, + 0.83246118 0.20866905 0.51328909, + 0.80413485 0.22386993 0.55068088, + 0.79291791 0.27800596 0.54221195, + 0.76400286 0.29437798 0.57414395, + 0.76070547 0.30823618 0.57124233, + 0.73053342 0.32427719 0.60097033, + 0.72801083 0.33463591 0.59834689, + 0.69635499 0.35032001 0.62639099, + 0.69425994 0.35891598 0.62384492, + 0.66083896 0.37427697 0.65054494, + 0.65784597 0.38662401 0.64634401, + 0.62336808 0.40139607 0.67103904, + 0.620049 0.41516599 0.66571498, + 0.58481675 0.42924285 0.68828773, + 0.58105499 0.444996 0.68143499, + 0.54421288 0.4587099 0.7024368, + 0.54033011 0.47520813 0.69442117, + 0.50217021 0.48837617 0.71366227, + 0.49790207 0.50689304 0.70367104, + 0.45920905 0.51922208 0.72078806, + 0.45478514 0.53891516 0.70904225, + 0.41558906 0.55038303 0.72413003, + 0.41097808 0.57157314 0.71021217, + 0.37112382 0.58219272 0.72340763, + 0.36661011 0.60382026 0.70781225, + 0.32579592 0.61359787 0.71927381, + 0.3214629 0.63558984 0.70191681, + 0.28050396 0.64426893 0.71150196, + 0.27635893 0.6669358 0.69196981, + 0.23557912 0.67443132 0.69974637, + 0.231811 0.69711298 0.67845201, + 0.19080308 0.70346725 0.68463725, + 0.18746606 0.72634125 0.66127527, + 0.14639094 0.73148477 0.66595775, + 0.14367509 0.75383747 0.64116037, + 0.10338098 0.75765884 0.64441085, + 0.10130398 0.77986181 0.61769986, + 0.061018892 0.78243387 0.61973697, + 0.059718378 0.80407369 0.59152275, + 0.020160293 0.80534768 0.59245974, + 0.01970969 0.82628751 0.56290364, + -0.019250596 0.82629484 0.56290889, + -0.019696308 0.80535531 0.59246522, + -0.059485391 0.8040849 0.59153092, + -0.060793992 0.78241891 0.61977792, + -0.10085595 0.77987164 0.61776072, + -0.10292904 0.75766832 0.64447224, + -0.14326198 0.7538569 0.64122993, + -0.14600407 0.73124826 0.66630226, + -0.18710704 0.72611517 0.66162521, + -0.19040798 0.70344996 0.68476492, + -0.23143101 0.697106 0.67858899, + -0.23519696 0.67442095 0.69988495, + -0.27601403 0.66693103 0.69211209, + -0.28015611 0.64426529 0.71164238, + -0.32114998 0.63558996 0.70205992, + -0.32548696 0.61356694 0.71943992, + -0.36631808 0.60379714 0.7079832, + -0.37089309 0.58185309 0.72379917, + -0.41078806 0.57123607 0.71059304, + -0.41525495 0.55070096 0.72407997, + -0.45466214 0.5391742 0.70892423, + -0.45916867 0.51913363 0.72087747, + -0.49786824 0.50680524 0.70375836, + -0.50214118 0.48827019 0.71375525, + -0.54012525 0.47517022 0.69460636, + -0.54418695 0.45787895 0.70299894, + -0.58105683 0.44417986 0.68196577, + -0.58474714 0.4286871 0.68869317, + -0.62002099 0.41461399 0.666085, + -0.62333322 0.40083915 0.67140424, + -0.65799904 0.38600507 0.64655805, + -0.66086692 0.37415797 0.65058494, + -0.69429761 0.35879478 0.62387264, + -0.69706118 0.3473931 0.62723517, + -0.72871017 0.33179709 0.59907609, + -0.72934699 0.32919201 0.599738, + -0.75935072 0.31309089 0.57040381, + -0.76203811 0.30206802 0.57275903, + -0.79115033 0.28531614 0.54099524, + -0.80324817 0.22846106 0.55008912, + -0.83643061 0.13425994 0.53137374, + -0.8415758 0.14800797 0.51946491, + -0.83157587 0.21302897 0.51293296, + -0.86815417 0.13752703 0.47685912, + -0.85849631 0.20237708 0.47119817, + -0.83234799 0.21872801 0.509269, + -0.8197729 0.27790797 0.50073892, + -0.79201603 0.29625699 0.53380001, + -0.78906101 0.30813101 0.53144902, + -0.76021183 0.32586691 0.56203985, + -0.76010287 0.32629997 0.56193596, + -0.72991526 0.34324011 0.59110922, + -0.72755933 0.35262918 0.58848131, + -0.69582683 0.3691619 0.61607188, + -0.69311297 0.37992293 0.61257893, + -0.65992785 0.39599791 0.63849884, + -0.65683001 0.40827301 0.633946, + -0.62226623 0.42384914 0.65813124, + -0.61883724 0.43749315 0.65241122, + -0.58347905 0.45231307 0.67451108, + -0.57952291 0.46816289 0.6670658, + -0.54274261 0.48249164 0.68748254, + -0.53852391 0.49958494 0.67853296, + -0.50059092 0.51326495 0.69711393, + -0.49605525 0.53193927 0.68627232, + -0.45740986 0.54478282 0.70284277, + -0.452764 0.56435102 0.69029897, + -0.41361514 0.5762642 0.70487022, + -0.40884805 0.59696203 0.69027507, + -0.36898783 0.60797173 0.70300663, + -0.36432099 0.62907499 0.68668401, + -0.32370096 0.63913095 0.69765997, + -0.31913388 0.66094679 0.67919278, + -0.2783649 0.66984975 0.68834174, + -0.27409509 0.69177222 0.66807425, + -0.23351003 0.69943404 0.67547405, + -0.22957598 0.72162396 0.65311092, + -0.18901911 0.72806144 0.65893739, + -0.18556002 0.75019211 0.63464904, + -0.14491209 0.75539249 0.63904834, + -0.14211598 0.77678591 0.61351997, + -0.10179196 0.7806747 0.61659175, + -0.09963914 0.80215627 0.58874226, + -0.060262207 0.80470312 0.59061104, + -0.058916509 0.82526511 0.56166404, + -0.019584198 0.82654285 0.56253296, + -0.019119304 0.84645617 0.5321151, + 0.019604305 0.84644818 0.5321101, + 0.020073412 0.82655746 0.56249434, + 0.059184309 0.82527512 0.56162107, + 0.060523178 0.80471373 0.59056973, + 0.100081 0.80214399 0.58868402, + 0.10223798 0.78066289 0.61653292, + 0.14233091 0.77678555 0.61347061, + 0.14514403 0.7552042 0.63921815, + 0.18579002 0.74999803 0.63481104, + 0.18920396 0.72810882 0.65883183, + 0.229954 0.72163099 0.65297002, + 0.23389097 0.69944197 0.67533392, + 0.27446103 0.69177008 0.66792607, + 0.27872807 0.66987717 0.68816817, + 0.31945911 0.66097021 0.67901725, + 0.32402909 0.63915318 0.69748718, + 0.36439481 0.62915272 0.68657368, + 0.36912322 0.60775334 0.7031244, + 0.4089908 0.59673971 0.69038266, + 0.41367799 0.57637602 0.70474201, + 0.45302188 0.56439489 0.69009382, + 0.45767286 0.54481483 0.70264673, + 0.49629706 0.53196704 0.68607605, + 0.50074995 0.51365292 0.69671392, + 0.5386501 0.49996713 0.67815119, + 0.5429523 0.48255229 0.6872744, + 0.57951927 0.46829921 0.66697329, + 0.5833841 0.45282713 0.67424816, + 0.61872607 0.43800205 0.65217507, + 0.6222201 0.42411709 0.6580022, + 0.65677005 0.40854007 0.63383603, + 0.65977192 0.39666495 0.63824594, + 0.69309157 0.38050377 0.61224264, + 0.69582903 0.36967602 0.61576104, + 0.72753292 0.35313597 0.58820993, + 0.72924507 0.34635904 0.59011608, + 0.75931114 0.32939002 0.56120306, + 0.76162213 0.32017702 0.56339908, + 0.79049486 0.30261096 0.53248894, + 0.79383028 0.28886208 0.53515619, + 0.82149202 0.27085 0.50178802, + 0.83320117 0.21426204 0.50977212, + 0.85932428 0.19816707 0.47147816, + 0.86542481 0.15928395 0.47504589, + 0.88995028 0.14498405 0.43239814, + 0.91210175 0.13228796 0.3880339, + 0.88995332 0.14716005 0.43165615, + 0.88399041 0.18684909 0.4285422, + 0.85996157 0.2039759 0.46782479, + 0.84809971 0.2619749 0.46053883, + 0.82206947 0.28153118 0.49491629, + 0.81852472 0.29599789 0.49234381, + 0.79100251 0.31523883 0.52434671, + 0.78900802 0.323017 0.52261502, + 0.76011068 0.34163389 0.55273682, + 0.75882 0.3466 0.55141699, + 0.72869998 0.364445 0.57980698, + 0.72636515 0.37337708 0.57704711, + 0.69459915 0.39080909 0.6039871, + 0.69188976 0.40111884 0.60032678, + 0.65862048 0.41804829 0.62566346, + 0.65535069 0.43046278 0.6206587, + 0.62089157 0.44674566 0.64413655, + 0.61720908 0.46074206 0.63778508, + 0.58193505 0.47622305 0.65921408, + 0.5778479 0.49182689 0.65130484, + 0.54114491 0.50676286 0.67108381, + 0.53674418 0.52371818 0.66153222, + 0.49889275 0.53794378 0.67950171, + 0.49414393 0.55649793 0.66793096, + 0.45574212 0.56976813 0.68385917, + 0.45086995 0.58918196 0.67050797, + 0.41177908 0.60152113 0.68455118, + 0.40678099 0.62200099 0.66906202, + 0.3671698 0.63332266 0.68124056, + 0.3623139 0.65398884 0.6640988, + 0.32196289 0.66430074 0.67456979, + 0.31720802 0.68562204 0.65521103, + 0.27691698 0.69468594 0.66387391, + 0.27244997 0.71612692 0.64259893, + 0.23212908 0.72395325 0.64962125, + 0.22806303 0.74534309 0.62645906, + 0.18775788 0.75190252 0.63197267, + 0.18424295 0.7728548 0.60724789, + 0.14385997 0.77813685 0.61139786, + 0.14092802 0.79901314 0.58456606, + 0.10105702 0.80293614 0.58743608, + 0.098872066 0.82314169 0.55916184, + 0.059771214 0.8257162 0.56091011, + 0.058388706 0.84538913 0.53095007, + 0.019914901 0.84666598 0.53175199, + 0.019424897 0.86548984 0.50054985, + -0.018947789 0.86549747 0.50055468, + -0.01943229 0.84667552 0.53175467, + -0.058109384 0.8454048 0.53095585, + -0.059500236 0.82570446 0.56095636, + -0.098608181 0.82313883 0.55921286, + -0.100784 0.80308598 0.58727801, + -0.140655 0.79917097 0.58441597, + -0.14361896 0.77811468 0.61148274, + -0.18382595 0.77286685 0.60735887, + -0.18733801 0.75191212 0.63208604, + -0.22768302 0.74536008 0.62657708, + -0.23175105 0.7239452 0.64976519, + -0.27208892 0.71612877 0.64274979, + -0.27655306 0.69469017 0.66402119, + -0.31685996 0.68563491 0.65536594, + -0.32162482 0.6642586 0.67477256, + -0.36200997 0.65395093 0.66430193, + -0.3669281 0.63299519 0.6816752, + -0.40656599 0.62168097 0.66948998, + -0.41148892 0.60148787 0.68475485, + -0.45063099 0.58914399 0.67070198, + -0.45549694 0.56974596 0.68404096, + -0.49391329 0.55648136 0.66811544, + -0.49865982 0.53792983 0.67968374, + -0.53672773 0.52362972 0.66161561, + -0.54112786 0.50667387 0.67116481, + -0.5776599 0.49181488 0.65148079, + -0.58185196 0.47579294 0.65959793, + -0.61730886 0.46024689 0.63804585, + -0.62099701 0.446206 0.644409, + -0.65531808 0.43000406 0.62101108, + -0.65862006 0.41744107 0.62606907, + -0.69204223 0.40045515 0.60059422, + -0.69466722 0.39045116 0.60414022, + -0.72645944 0.3730152 0.57716238, + -0.72876996 0.36416498 0.57989496, + -0.75889897 0.346322 0.55148298, + -0.76090491 0.33855996 0.55353492, + -0.78977501 0.32005399 0.52327901, + -0.78945851 0.32128081 0.52300471, + -0.81710082 0.30175194 0.49121487, + -0.82031286 0.28898597 0.49353194, + -0.84629983 0.26917395 0.45969787, + -0.8591361 0.20804803 0.46754807, + -0.88709247 0.11174794 0.44786072, + -0.8923943 0.12663305 0.43312415, + -0.88328123 0.19060604 0.42835009, + -0.91366291 0.11321699 0.39038694, + -0.93060541 0.064946227 0.36021617, + 0.84049851 0.34935379 0.41414276, + 0.81394029 0.37458712 0.44405615, + 0.81273246 0.37869024 0.44278628, + 0.78476912 0.40283707 0.47102007, + 0.78311187 0.40830594 0.46906495, + 0.75397289 0.43130195 0.49548295, + 0.75160611 0.43892607 0.49237406, + 0.72124916 0.46092811 0.51705414, + 0.71804494 0.47101995 0.51239794, + 0.68627882 0.49223089 0.53547186, + 0.68254906 0.50373507 0.52950704, + 0.649149 0.52429003 0.55111301, + 0.64488268 0.53722775 0.54361075, + 0.61056429 0.55668825 0.56330228, + 0.60569888 0.57123989 0.55390787, + 0.57042307 0.58965904 0.57176906, + 0.56525093 0.60497695 0.56079793, + 0.5290221 0.6223501 0.57690209, + 0.52330714 0.6391772 0.5635621, + 0.48612681 0.65548676 0.57794285, + 0.48020136 0.67290646 0.56267542, + 0.442467 0.68796301 0.57526499, + 0.43653706 0.70549804 0.55830806, + 0.39834195 0.71926093 0.56919897, + 0.39227107 0.73746407 0.54979104, + 0.353944 0.74982399 0.55900598, + 0.34802297 0.76797289 0.53767794, + 0.30901113 0.7790913 0.54546219, + 0.30340812 0.79689831 0.52239519, + 0.26453909 0.80652827 0.52870721, + 0.25931507 0.82404917 0.50368512, + 0.22084494 0.83216882 0.50864786, + 0.21609886 0.84931052 0.48163569, + 0.17803696 0.85596681 0.48541087, + 0.17390302 0.8725071 0.45660606, + 0.13593094 0.8777836 0.45936778, + 0.13258094 0.89341056 0.42923179, + 0.095183402 0.89727497 0.43108901, + 0.092698678 0.91195774 0.39967492, + 0.055906385 0.91446877 0.40077591, + 0.054364692 0.92821491 0.36805096, + 0.018591702 0.92942911 0.36853203, + 0.018046396 0.94215977 0.3346779, + -0.017533707 0.94216835 0.33468112, + -0.018072102 0.92942113 0.36857802, + -0.054162309 0.92820811 0.36809802, + -0.055719066 0.91447848 0.40077975, + -0.092192076 0.91200078 0.39969391, + -0.094674759 0.89729959 0.43114978, + -0.13227193 0.89342844 0.42928973, + -0.13562703 0.87780225 0.45942211, + -0.17347802 0.87255514 0.45667607, + -0.17758399 0.85611689 0.48531196, + -0.21578597 0.84944886 0.48153195, + -0.22057498 0.8321749 0.50875497, + -0.25908297 0.82405686 0.50379193, + -0.26426592 0.80669272 0.52859282, + -0.30299211 0.79711032 0.52231318, + -0.30865198 0.7791189 0.54562593, + -0.34768102 0.76801014 0.53784609, + -0.35367009 0.74963915 0.55942714, + -0.39201793 0.73728693 0.55020893, + -0.39802906 0.71924806 0.56943405, + -0.4360947 0.70554954 0.55858856, + -0.44209212 0.68778819 0.57576209, + -0.48002687 0.67266983 0.56310689, + -0.48587811 0.65545219 0.5781911, + -0.52309507 0.63914007 0.56380105, + -0.528723 0.62256902 0.57694, + -0.56513292 0.60511595 0.56076694, + -0.57040602 0.58950198 0.57194799, + -0.60570407 0.57107604 0.55407107, + -0.61047721 0.55680418 0.56328219, + -0.64465809 0.53742707 0.54368007, + -0.64911509 0.52390504 0.55151904, + -0.68252969 0.50335878 0.52988976, + -0.68616176 0.49214283 0.53570282, + -0.71806383 0.47085088 0.51252687, + -0.72126806 0.46075606 0.51718104, + -0.75163853 0.43875074 0.4924807, + -0.754004 0.43112701 0.495588, + -0.78315383 0.4081279 0.46914989, + -0.78503287 0.40191495 0.47136796, + -0.81289089 0.37788394 0.44318393, + -0.81405014 0.37393504 0.44440407, + -0.84029913 0.34903702 0.41481405, + -0.8408519 0.34708998 0.41532695, + 0.84240949 0.32018617 0.43339026, + 0.81625718 0.34327209 0.46463811, + 0.81537956 0.34644681 0.4638218, + 0.787552 0.368781 0.49372301, + 0.78603488 0.37414396 0.49210295, + 0.75712812 0.39537805 0.52003205, + 0.755072 0.402509 0.51754498, + 0.72470099 0.42302701 0.54392701, + 0.72201365 0.4322018 0.54027575, + 0.69024092 0.45200393 0.56503093, + 0.68701106 0.46288607 0.56013608, + 0.65373224 0.48204717 0.58332217, + 0.64983273 0.49503875 0.57676172, + 0.61550999 0.513309 0.59804797, + 0.61114413 0.52773714 0.58991212, + 0.57583094 0.54510492 0.60932696, + 0.57106918 0.56077516 0.59950924, + 0.53483593 0.57720697 0.61707592, + 0.52967894 0.59417492 0.60530692, + 0.49193588 0.60988986 0.6213159, + 0.48653612 0.62776315 0.60761511, + 0.44840613 0.64225519 0.62164313, + 0.44281673 0.66097361 0.60582763, + 0.40438393 0.67422593 0.61797494, + 0.39883018 0.69319034 0.60035127, + 0.35989892 0.7052598 0.6108039, + 0.35438997 0.72464097 0.59101892, + 0.31472191 0.73555684 0.59992188, + 0.30946305 0.75488418 0.5782581, + 0.27007404 0.7643531 0.58551204, + 0.26506504 0.78388113 0.56149006, + 0.22585396 0.79195487 0.56727195, + 0.22139893 0.81078583 0.54185688, + 0.18229006 0.81748831 0.54633617, + 0.17839894 0.83593172 0.5190298, + 0.139415 0.841263 0.52234101, + 0.13624601 0.85897011 0.49356607, + 0.097650789 0.86291188 0.49582994, + 0.095265061 0.88005769 0.46521282, + 0.057737179 0.8826037 0.46655881, + 0.056242216 0.89877725 0.4347831, + 0.019107196 0.90003777 0.43539292, + 0.018585807 0.91527128 0.40240914, + -0.018092498 0.91527987 0.40241194, + -0.018610096 0.89995277 0.43558991, + -0.05576352 0.89870828 0.43498716, + -0.057245608 0.88260812 0.46661106, + -0.094953679 0.88006377 0.46526489, + -0.097332023 0.86302018 0.49570411, + -0.13589597 0.85909283 0.49344888, + -0.13910002 0.84123313 0.52247304, + -0.17794098 0.83593488 0.51918197, + -0.18182395 0.81751281 0.54645491, + -0.22097807 0.8108182 0.54198015, + -0.22547507 0.79178828 0.56765521, + -0.26471096 0.7837249 0.56187493, + -0.26963007 0.76453817 0.58547515, + -0.30923688 0.75502771 0.57819182, + -0.31454891 0.73552483 0.60005188, + -0.35406411 0.72466123 0.59118927, + -0.35957697 0.70525593 0.61099792, + -0.39852518 0.69319433 0.60054928, + -0.40408495 0.67419994 0.61819893, + -0.44275784 0.66087377 0.60597974, + -0.44834706 0.64215606 0.62178808, + -0.48630899 0.62773597 0.60782498, + -0.49171519 0.60983121 0.62154824, + -0.52930409 0.59419703 0.60561305, + -0.53444678 0.57725972 0.61736369, + -0.57088608 0.56075007 0.59970707, + -0.57575482 0.54470783 0.60975379, + -0.61108571 0.52734774 0.59032071, + -0.61533874 0.51327783 0.59825075, + -0.64983982 0.49492088 0.57685488, + -0.65373671 0.48193377 0.58341068, + -0.68701476 0.46277782 0.56022084, + -0.69026393 0.45182994 0.56514192, + -0.7220518 0.4320229 0.5403679, + -0.72484607 0.42247206 0.54416507, + -0.75521618 0.40196809 0.51775509, + -0.75731546 0.39467224 0.52029532, + -0.78621763 0.37345982 0.49233076, + -0.78768784 0.36825091 0.49390188, + -0.81542885 0.34600496 0.46406493, + -0.81642032 0.34240913 0.46498817, + -0.84253091 0.31939596 0.43373695, + -0.84310579 0.31724992 0.43419492, + -0.96253514 0.042016104 0.26788202, + -0.92561066 0.15137494 0.34688687, + -0.94658285 0.12897098 0.29554597, + -0.95027661 0.093968466 0.29689088, + -0.96465367 0.079518467 0.25123692, + -0.96486586 0.076695889 0.25129998, + -0.97493434 0.030778011 0.22035408, + -0.97490066 0.03081069 0.22049792, + -0.97662526 0.064195715 0.20513904, + -0.9765231 0.065813504 0.20511302, + -0.96465355 0.080511466 0.25092089, + -0.96171725 0.11228503 0.24998406, + -0.94645065 0.13228196 0.29450387, + -0.94193238 0.16439506 0.29281011, + -0.92304999 0.18832301 0.33543, + -0.91485739 0.22999911 0.33186814, + -0.89354289 0.25574598 0.36901897, + -0.889144 0.27382299 0.36666599, + -0.86604887 0.29915196 0.40058395, + -0.86754918 0.29341805 0.40157709, + -0.86656219 0.30773905 0.3928951, + -0.84194928 0.33270511 0.42476916, + -0.84146082 0.33447492 0.42434692, + -0.81524187 0.35849497 0.45482093, + -0.81427789 0.36188397 0.45386294, + -0.78643572 0.38507286 0.48294681, + -0.78485066 0.39050582 0.48115978, + -0.75583202 0.412613 0.508398, + -0.75342166 0.42068678 0.50534976, + -0.72306621 0.44195414 0.5308972, + -0.7202872 0.45108211 0.52698314, + -0.68836898 0.47168601 0.551054, + -0.68479824 0.48322117 0.54548019, + -0.65152693 0.50304294 0.56785595, + -0.64745194 0.51601595 0.56083292, + -0.61312091 0.53489494 0.58135194, + -0.60847276 0.54952884 0.57251984, + -0.57315296 0.56744593 0.59118593, + -0.56815916 0.5830512 0.58072919, + -0.53173304 0.60005105 0.59766108, + -0.52630979 0.61695272 0.58512169, + -0.48891094 0.63294494 0.60028893, + -0.48329577 0.65048468 0.58591372, + -0.44535816 0.66526723 0.59922922, + -0.43952584 0.68364477 0.5826208, + -0.40125892 0.69714284 0.5941239, + -0.39545792 0.71571684 0.57564086, + -0.35671797 0.72797292 0.58549792, + -0.3510668 0.74655956 0.56515563, + -0.31161001 0.75761002 0.57352102, + -0.30609697 0.77649885 0.55077595, + -0.26710108 0.78601629 0.55752617, + -0.26195791 0.8046177 0.5328868, + -0.22318897 0.81270188 0.53823996, + -0.21860507 0.83060628 0.5121572, + -0.179766 0.837327 0.51630199, + -0.17576106 0.85482329 0.48824719, + -0.13737196 0.86010867 0.49126583, + -0.13409895 0.87682658 0.4617278, + -0.096018136 0.88073027 0.46378317, + -0.093579307 0.89666611 0.43270406, + -0.056577682 0.8991757 0.43391484, + -0.055049691 0.91412491 0.40167794, + -0.018246096 0.91536075 0.4022209, + -0.017729696 0.92925477 0.36901391, + 0.018215599 0.9292469 0.36900997, + 0.018739292 0.9153527 0.40221685, + 0.055236485 0.91411579 0.4016729, + 0.056756109 0.89907211 0.43410605, + 0.093917735 0.89654332 0.43288514, + 0.096332103 0.88072503 0.46372801, + 0.13440694 0.87681156 0.46166679, + 0.13769703 0.85997015 0.49141711, + 0.17619394 0.85465771 0.48838082, + 0.18017393 0.8372857 0.51622683, + 0.21885103 0.83058113 0.51209307, + 0.22346207 0.81254327 0.5383662, + 0.26222998 0.80445087 0.53300494, + 0.26731491 0.78603673 0.5573948, + 0.30645704 0.7764731 0.55061203, + 0.31196696 0.7576099 0.57332695, + 0.3512218 0.74660558 0.56499863, + 0.35693008 0.72781318 0.58556712, + 0.39564905 0.71555805 0.57570708, + 0.40144607 0.69697106 0.59419906, + 0.43969107 0.68347603 0.58269405, + 0.44542786 0.66538674 0.59904474, + 0.48354906 0.65052307 0.58566207, + 0.48915687 0.63301581 0.60001385, + 0.526703 0.61694199 0.58477902, + 0.53212088 0.60007387 0.5972929, + 0.56818414 0.58322912 0.58052611, + 0.57327765 0.56730664 0.59119862, + 0.60856098 0.54940599 0.57254398, + 0.61311704 0.53506005 0.58120406, + 0.6474427 0.51617879 0.56069374, + 0.65152401 0.50318903 0.56773001, + 0.68491679 0.48328587 0.5452739, + 0.68839991 0.47204494 0.55070794, + 0.72029173 0.45144084 0.5266698, + 0.72305 0.442395 0.53055203, + 0.75340873 0.42110586 0.50501984, + 0.75569773 0.41345784 0.50791085, + 0.78459436 0.39141819 0.48083624, + 0.78624487 0.38577795 0.48269495, + 0.81418085 0.36248791 0.45355487, + 0.81517202 0.35901099 0.454539, + 0.84121746 0.33513421 0.42430922, + 0.84403616 0.32477909 0.4267571, + 0.86462027 0.30427313 0.39981216, + 0.86780667 0.29218888 0.40191686, + 0.89075774 0.26724294 0.36760291, + 0.89514029 0.24869309 0.36996713, + 0.91627425 0.22345906 0.33242708, + 0.92708778 0.16371195 0.33720392, + 0.94474512 0.14316802 0.29488903, + 0.94915026 0.10592102 0.29647005, + 0.96382576 0.089673877 0.25099495, + 0.97509301 0.035610501 0.21891899, + 0.97570926 0.0022731505 0.21905807, + 0.96692222 -0.014998903 0.25463006, + 0.97570378 0.0022657195 0.21908194, + 0.97508723 0.035616606 0.21894406, + 0.96459979 0.080220081 0.25122094, + 0.96274847 0.047544524 0.26618612, + 0.9638229 -0.0056363493 0.26648396, + 0.96376663 -0.005559078 0.26668891, + 0.96268922 0.04759521 0.26639107, + 0.95027065 0.092855871 0.29725987, + 0.94916165 0.10465796 0.29688188, + 0.93191975 0.12057497 0.34203392, + 0.9268496 0.15930392 0.33995885, + 0.90686023 0.17882304 0.38161108, + 0.89532101 0.238952 0.375902, + 0.87258983 0.26203695 0.41221792, + 0.86852115 0.27882007 0.40979308, + 0.84421921 0.30151606 0.44315013, + 0.84297717 0.30627507 0.44225013, + 0.81693053 0.32835779 0.47413674, + 0.81642473 0.33024088 0.47369981, + 0.78869051 0.35159481 0.50432968, + 0.7873022 0.35667008 0.50293314, + 0.75849372 0.37698185 0.53157485, + 0.75647449 0.38424078 0.52924973, + 0.72619605 0.40390107 0.55633008, + 0.723665 0.412875 0.55303103, + 0.69186908 0.43194205 0.57857007, + 0.68882704 0.44261506 0.57411605, + 0.65553975 0.46107581 0.59806079, + 0.65198106 0.47347605 0.59223408, + 0.61761314 0.49111411 0.61429709, + 0.61345798 0.50552601 0.60672301, + 0.57812011 0.52231312 0.62687016, + 0.57354456 0.53815764 0.61760259, + 0.53711003 0.55414605 0.63595206, + 0.53229624 0.57087028 0.62511432, + 0.49450481 0.58612174 0.64181477, + 0.48929301 0.60439098 0.62873203, + 0.45114827 0.61847937 0.64338833, + 0.44576833 0.63760245 0.62829447, + 0.40711892 0.65058482 0.64108783, + 0.40172115 0.67019522 0.62406623, + 0.36257204 0.68204606 0.63510203, + 0.3572979 0.70184082 0.61624485, + 0.31719208 0.71264017 0.62572616, + 0.31213015 0.73257637 0.60490233, + 0.2724821 0.74192321 0.61262023, + 0.26770496 0.76194388 0.58972496, + 0.22806799 0.76996601 0.59593397, + 0.22368211 0.78998536 0.5708673, + 0.18429901 0.79663801 0.57567501, + 0.18051305 0.81604028 0.54908419, + 0.14084196 0.82139969 0.55268985, + 0.13777801 0.84005511 0.52471405, + 0.099068336 0.84397131 0.52716017, + 0.096721277 0.86228579 0.49709988, + 0.058544677 0.86486173 0.49858481, + 0.057081275 0.88219756 0.46740678, + 0.019277504 0.88347423 0.46808311, + 0.018777302 0.89984912 0.43579707, + -0.018438693 0.89985472 0.43579984, + -0.018945104 0.88347822 0.46808913, + -0.056617275 0.88221955 0.4674218, + -0.058076523 0.86486429 0.49863517, + -0.096266918 0.86230314 0.49715805, + -0.098606385 0.84400988 0.52718496, + -0.13754201 0.84008312 0.52473104, + -0.14061591 0.8214035 0.55274165, + -0.18007194 0.81608468 0.54916281, + -0.18386404 0.79663515 0.57581812, + -0.22345795 0.78995883 0.57099187, + -0.22780506 0.77015215 0.59579414, + -0.26729795 0.76216882 0.58961886, + -0.27212602 0.74193007 0.61277008, + -0.31196201 0.73254901 0.60502201, + -0.31703615 0.71258038 0.62587333, + -0.35697398 0.70183694 0.61643696, + -0.36224589 0.68204176 0.63529277, + -0.40143517 0.67019129 0.62425429, + -0.40684479 0.65052772 0.64131969, + -0.44569889 0.6374858 0.62846184, + -0.45099801 0.61866099 0.64331901, + -0.48917982 0.60456073 0.62865674, + -0.49439088 0.58631086 0.64172983, + -0.53198886 0.5711419 0.62512779, + -0.53690606 0.55405909 0.63620007, + -0.57354271 0.53799075 0.61774969, + -0.57809311 0.52223015 0.62696415, + -0.61328876 0.50551784 0.60690075, + -0.61745822 0.49105117 0.61450326, + -0.6519798 0.4733429 0.5923419, + -0.65563816 0.46058512 0.59833109, + -0.68881005 0.44220406 0.57445306, + -0.6919598 0.4311249 0.57907087, + -0.72377801 0.41207299 0.55348098, + -0.72635102 0.40292001 0.55683899, + -0.75663787 0.38328794 0.52970695, + -0.75849515 0.3765921 0.53184915, + -0.78742373 0.35621288 0.50306684, + -0.78891897 0.350732 0.50457299, + -0.81655902 0.32947901 0.47399899, + -0.81766582 0.3253299 0.47495589, + -0.84365928 0.30339611 0.44293314, + -0.8424722 0.30791405 0.44207412, + -0.86696798 0.28483701 0.408943, + -0.87092614 0.26894504 0.41128606, + -0.8937909 0.24544998 0.37535593, + -0.9062351 0.18224302 0.38147807, + -0.92634261 0.16237493 0.33988786, + -0.93331134 0.10701904 0.34274912, + -0.95027387 0.092816293 0.29726198, + -0.95067036 0.088205732 0.29739812, + -0.9477669 0.052973792 0.31453398, + -0.94775009 0.052985106 0.31458303, + -0.93389636 0.099552236 0.34340513, + -0.93330437 0.10572004 0.34317112, + -0.91374075 0.11961897 0.3882899, + -0.90587574 0.17733596 0.38463092, + -0.88376874 0.19591795 0.42493391, + -0.87095988 0.25843796 0.41789794, + -0.84652948 0.27999619 0.45275828, + -0.8429684 0.29413915 0.4504292, + -0.81704021 0.31525409 0.48276311, + -0.81776482 0.31248394 0.48333687, + -0.79012489 0.33278596 0.51473892, + -0.78861016 0.33853009 0.51331413, + -0.75964969 0.35804087 0.54289883, + -0.75778085 0.36501592 0.5408619, + -0.72757423 0.38376716 0.56864619, + -0.72525883 0.3923189 0.56576091, + -0.69353497 0.41052401 0.592013, + -0.69052643 0.42154825 0.58776736, + -0.65716022 0.43929115 0.61250621, + -0.65380883 0.45150787 0.6071859, + -0.61939001 0.46846801 0.62999499, + -0.61538506 0.48303905 0.62287605, + -0.57997805 0.49922106 0.64374208, + -0.57570499 0.51478601 0.63526303, + -0.539217 0.53021699 0.65430498, + -0.53443718 0.54772019 0.64372325, + -0.49660495 0.56247497 0.66106397, + -0.49172089 0.58055687 0.6489718, + -0.45333001 0.594284 0.66431803, + -0.44821584 0.61355579 0.65011674, + -0.40932491 0.6262278 0.66354483, + -0.40414214 0.64625525 0.64732021, + -0.36472091 0.65785682 0.65894079, + -0.35959089 0.67838478 0.64069378, + -0.31944808 0.68892217 0.6506452, + -0.3145389 0.70955682 0.6305508, + -0.27444696 0.71879393 0.63875991, + -0.26984087 0.73947567 0.61673468, + -0.22971913 0.74742544 0.62336534, + -0.22553697 0.76797187 0.59945995, + -0.18568508 0.77457339 0.6046133, + -0.181998 0.79501802 0.57863897, + -0.14203501 0.80032414 0.58250105, + -0.13902794 0.82015359 0.55499476, + -0.099811301 0.82406098 0.557639, + -0.097550981 0.8432498 0.52859586, + -0.058709223 0.84582931 0.53021318, + -0.057292067 0.86434346 0.49962771, + -0.019114593 0.86560768 0.50035781, + -0.018623609 0.8832804 0.46847522, + 0.018953502 0.88327509 0.46847206, + 0.019440608 0.86550027 0.5005312, + 0.057588208 0.86422712 0.49979505, + 0.058990829 0.84581542 0.53020424, + 0.098013215 0.84321111 0.52857208, + 0.100257 0.82420301 0.55734903, + 0.13942602 0.82028615 0.55469912, + 0.142463 0.80029601 0.58243501, + 0.18238606 0.7949813 0.57856721, + 0.18607698 0.77453887 0.60453695, + 0.22594208 0.76792127 0.59937227, + 0.23011699 0.74742597 0.623218, + 0.27019894 0.73946983 0.6165849, + 0.27480793 0.71879381 0.63860482, + 0.31467804 0.70959806 0.63043505, + 0.3196421 0.68871319 0.6507712, + 0.35976496 0.67817795 0.64081496, + 0.36487898 0.65768695 0.65902293, + 0.40427694 0.64608896 0.64740193, + 0.40939307 0.62630606 0.66342908, + 0.44847184 0.61356479 0.64993179, + 0.45357493 0.59434193 0.66409892, + 0.49194905 0.58060807 0.64875305, + 0.49684006 0.56250805 0.66085905, + 0.53462583 0.54775983 0.64353275, + 0.53932804 0.53055906 0.65393609, + 0.57581103 0.51511401 0.63490099, + 0.58016914 0.49925411 0.6435442, + 0.6155389 0.48307788 0.6226939, + 0.61935377 0.46922281 0.62946874, + 0.65376282 0.45224187 0.60668886, + 0.65719193 0.43977195 0.61212695, + 0.69040018 0.42209509 0.5875231, + 0.69337875 0.41120285 0.59172475, + 0.72508103 0.392993 0.565521, + 0.72747093 0.38418093 0.56849897, + 0.75779301 0.365343 0.54062402, + 0.7595728 0.35871392 0.54256189, + 0.78840172 0.33926687 0.51314783, + 0.78935301 0.335684 0.51404101, + 0.81703889 0.31525898 0.48276195, + 0.81860191 0.30924597 0.48400193, + 0.84455889 0.28830197 0.45122293, + 0.84838432 0.27269909 0.45373914, + 0.87256628 0.25163808 0.41869614, + 0.88445473 0.19206892 0.42526385, + 0.90650523 0.17378004 0.38477108, + 0.91209471 0.13428496 0.38736385, + 0.93193257 0.11877694 0.34262785, + 0.93340164 0.10474596 0.34320489, + 0.9478991 0.059177209 0.31302604, + 0.94789499 0.059180301 0.31303799, + 0.94792789 0.059325092 0.31291097, + 0.94959623 0.0030289006 0.3134611, + 0.94955498 0.0030289099 0.313586, + 0.94955897 0.0030318401 0.31357399, + 0.93294501 -0.017176401 0.35960901, + 0.93565214 -0.011166401 0.35274702, + 0.9330681 -0.0080843214 0.35960904, + 0.93071198 0.071476199 0.35870099, + 0.91384214 0.11711302 0.38881505, + 0.91094899 0.084790401 0.40371099, + 0.91423613 0.0034553804 0.40516707, + 0.91425431 0.0034553811 0.40512615, + 0.91096473 0.084827267 0.40366784, + 0.91105145 0.084780045 0.40348175, + 0.91433787 0.0034921095 0.40493694, + 0.89329129 -0.013905805 0.44926316, + 0.89443469 -0.011950395 0.44703886, + 0.89332801 -0.0108194 0.44927499, + 0.88903427 0.098515339 0.44711614, + 0.8676368 0.14044997 0.47694889, + 0.86471158 0.11084595 0.48988476, + 0.86476141 0.11092405 0.48977923, + 0.87012541 0.0036175917 0.49281725, + 0.87006783 0.0036175891 0.49291888, + 0.84369087 -0.012743098 0.53667796, + 0.83853072 0.12413996 0.53052384, + 0.84501749 -0.010868006 0.53462827, + 0.87036216 0.0037104608 0.49239811, + 0.86501741 0.11071505 0.48937425, + 0.8410666 0.14989392 0.51974875, + 0.83849728 0.16877306 0.51811016, + 0.80918503 0.181982 0.55866098, + 0.80322188 0.21804596 0.55433792, + 0.77338898 0.232048 0.589935, + 0.76277202 0.28376701 0.58108097, + 0.7324366 0.29875982 0.61178362, + 0.729204 0.312729 0.60865599, + 0.69742715 0.32751808 0.63743818, + 0.69470793 0.33911297 0.63433695, + 0.66131818 0.35364008 0.66151118, + 0.65889299 0.36403599 0.65828401, + 0.62448907 0.37797207 0.68348408, + 0.62119228 0.39225417 0.67842227, + 0.58586824 0.40564314 0.70157826, + 0.58239001 0.42088401 0.69546998, + 0.54545707 0.43394706 0.71705407, + 0.54159182 0.45117086 0.70931178, + 0.50357395 0.46368095 0.72898096, + 0.49955517 0.48198318 0.71981722, + 0.46079516 0.49379218 0.73745322, + 0.45655894 0.51362991 0.72645593, + 0.41714486 0.52468383 0.74208975, + 0.41288075 0.5453887 0.7294386, + 0.37254298 0.55570596 0.74323791, + 0.36825401 0.57752901 0.72859401, + 0.32739297 0.58694792 0.74047697, + 0.32315892 0.60978687 0.72369081, + 0.2819719 0.61821377 0.73369175, + 0.27804697 0.64108294 0.71533394, + 0.237021 0.64838302 0.72347802, + 0.23337191 0.67184478 0.70296675, + 0.19214603 0.67804807 0.70945805, + 0.18895003 0.70149004 0.68717504, + 0.14741409 0.7065534 0.69213539, + 0.14477403 0.72990417 0.66804218, + 0.10425795 0.73365563 0.67147571, + 0.10225694 0.75664455 0.64578062, + 0.061539616 0.7591902 0.64795315, + 0.060281277 0.78181571 0.62058878, + 0.020502005 0.78307515 0.62158912, + 0.020054499 0.80526489 0.59257597, + -0.019590398 0.80527186 0.59258193, + -0.020033693 0.78308272 0.62159479, + -0.060085699 0.78182501 0.62059599, + -0.061349876 0.75920069 0.64795876, + -0.10183302 0.75667912 0.64580709, + -0.10383504 0.73363924 0.67155921, + -0.14459902 0.72987407 0.66811305, + -0.14724495 0.70652175 0.69220376, + -0.18857405 0.70149219 0.68727618, + -0.19176792 0.67804569 0.70956266, + -0.23300509 0.67185223 0.70308125, + -0.23665503 0.64836603 0.72361308, + -0.27769497 0.64107597 0.71547693, + -0.28161886 0.61820269 0.73383665, + -0.32286209 0.60977513 0.7238332, + -0.32709688 0.58691376 0.74063474, + -0.368184 0.57744998 0.728692, + -0.37241003 0.55596608 0.74311006, + -0.4125419 0.5457049 0.72939384, + -0.41694221 0.52433026 0.74245334, + -0.45639393 0.51327991 0.72680694, + -0.46063182 0.49339983 0.73781776, + -0.499412 0.48159999 0.720173, + -0.50343394 0.46325094 0.72935092, + -0.54168206 0.45067805 0.70955604, + -0.54556817 0.43333414 0.71734023, + -0.58232206 0.42035106 0.69584906, + -0.58578914 0.4051241 0.70194417, + -0.62115526 0.39174014 0.67875326, + -0.62431675 0.37802586 0.68361175, + -0.65892392 0.36401096 0.65826696, + -0.6619432 0.35100108 0.66229117, + -0.69546402 0.33648801 0.63490599, + -0.6965152 0.33202508 0.6361022, + -0.72807324 0.31719813 0.60769624, + -0.73059708 0.30655003 0.61012703, + -0.7608431 0.29134202 0.57986003, + -0.772425 0.236377 0.58947903, + -0.80224365 0.2221929 0.55410779, + -0.81237727 0.15747306 0.56146717, + -0.8149761 -0.012808002 0.57935303, + -0.81679857 -0.014300893 0.57674569, + -0.80810088 0.14623299 0.57060397, + -0.80815828 0.14621206 0.57052815, + -0.81689441 -0.010297605 0.57669532, + -0.84385228 0.0035142512 0.53656417, + -0.83618689 0.13452598 0.53168994, + -0.83664328 0.13434604 0.53101718, + -0.84429199 0.00363742 0.53587103, + -0.84406716 0.003637451 0.53622514, + -0.87021571 -0.012037395 0.49252382, + -0.86944842 -0.011311206 0.49389425, + -0.86287773 0.12322096 0.49016181, + -0.8628813 0.12321904 0.49015617, + -0.86943132 -0.013245204 0.49387619, + -0.89250398 0.0035036399 0.45102599, + -0.88692731 0.11166604 0.44820815, + -0.88693887 0.11165999 0.44818693, + -0.892515 0.0035076099 0.451004, + -0.89267814 0.0035076004 0.45068106, + -0.91627002 -0.0113644 0.40040001, + -0.91362321 -0.0084510716 0.40647408, + -0.90911114 0.099620618 0.40446606, + -0.90908074 0.099637978 0.4045299, + -0.91349971 -0.016692294 0.40649685, + -0.93247789 0.0030874996 0.36121398, + -0.93053645 0.064568959 0.3604618, + -0.93049324 0.064594015 0.36056909, + -0.93243611 0.0030645705 0.36132202, + -0.93256974 0.0030646194 0.3609769, + -0.94906598 -0.0060096402 0.31501999, + -0.94908249 -0.0060301726 0.31497014, + -0.95252979 -0.014874596 0.30408195, + -0.96334773 0.0023932396 0.26824495, + -0.96249664 0.042095784 0.2680079, + -0.96254212 0.042059503 0.26785004, + -0.9633919 0.0024352898 0.26808596, + -0.96338302 0.00243529 0.26811799, + -0.97538924 -0.0038178109 0.22045706, + -0.97535688 -0.0037699896 0.22060098, + -0.97873914 -0.015531502 0.20452003, + -0.98503935 0.0015275106 0.17232306, + -0.98484963 0.019682592 0.17228994, + -0.98483163 0.019705093 0.17238994, + -0.98502165 0.0014926594 0.17242394, + -0.98504114 0.0014926703 0.17231302, + -0.98285013 0.06667731 0.17193002, + -0.98626387 0.045329798 0.15883599, + -0.98596323 0.051658209 0.15877004, + -0.97652191 0.066650294 0.20484798, + -0.97435355 0.094447955 0.2042419, + -0.96160603 0.115187 0.24909, + -0.95785964 0.14517495 0.24784891, + -0.9414295 0.17043208 0.29097015, + -0.93388724 0.21183704 0.28806207, + -0.91445798 0.239749 0.32601699, + -0.9097504 0.25989112 0.32374516, + -0.88789475 0.28799295 0.35875192, + -0.88741827 0.2898131 0.35846511, + -0.86785561 0.31235284 0.38634482, + -0.86546415 0.32125109 0.38440809, + -0.86440814 0.33485603 0.37506005, + -0.83962584 0.36174491 0.40517792, + -0.8390038 0.36386892 0.4045639, + -0.81262088 0.38972694 0.43331295, + -0.81128085 0.3941389 0.43183091, + -0.78329039 0.41908219 0.45915821, + -0.78145087 0.42494994 0.45689395, + -0.75217468 0.44878384 0.48252082, + -0.74940073 0.45738086 0.47874981, + -0.71898896 0.48011094 0.50254196, + -0.71576023 0.48985717 0.49772218, + -0.6838237 0.51181376 0.52003074, + -0.67982429 0.52361226 0.51348722, + -0.64624763 0.5448547 0.5343197, + -0.6417762 0.55778313 0.52630913, + -0.60756963 0.57769364 0.54509568, + -0.60243189 0.5922969 0.53503287, + -0.56728393 0.61110991 0.55202693, + -0.56173414 0.62666917 0.54013014, + -0.52546906 0.64446604 0.55546904, + -0.51960605 0.66075706 0.54167306, + -0.48256323 0.67734927 0.55527526, + -0.47637293 0.69447196 0.53923792, + -0.43881899 0.709741 0.55109501, + -0.43260807 0.72695804 0.53327507, + -0.39474201 0.74083501 0.54345399, + -0.38850194 0.7583009 0.52349395, + -0.35021096 0.7708289 0.53214192, + -0.34406888 0.78836071 0.51000381, + -0.30546904 0.79949212 0.51720506, + -0.29971802 0.81644315 0.49354807, + -0.26142302 0.82602513 0.49934006, + -0.25594497 0.84294486 0.47321895, + -0.21792589 0.8510316 0.47775877, + -0.21309489 0.86701357 0.45041978, + -0.17517996 0.8736738 0.45387888, + -0.17098492 0.88903159 0.42471978, + -0.13362898 0.89422691 0.42720193, + -0.13019496 0.90877372 0.39645886, + -0.093282372 0.9125787 0.39811885, + -0.090750448 0.92607749 0.36625779, + -0.054803409 0.9285171 0.36722302, + -0.053204212 0.94111925 0.3338621, + -0.017842405 0.94230425 0.3342821, + -0.0172885 0.95372999 0.30016699, + 0.01768001 0.95372349 0.30016515, + 0.018231807 0.94224137 0.33443812, + 0.05355981 0.94104522 0.33401409, + 0.055136316 0.92858624 0.36699808, + 0.091268629 0.92611939 0.36602312, + 0.093819886 0.91255188 0.39805394, + 0.13065295 0.90873772 0.39639086, + 0.13407204 0.89428622 0.4269391, + 0.17141107 0.88907743 0.42445222, + 0.17563294 0.8736437 0.45376185, + 0.2133759 0.86700058 0.45031178, + 0.21823907 0.85089332 0.47786218, + 0.25638399 0.842767 0.47329801, + 0.26177698 0.82611787 0.49900094, + 0.30005306 0.81652617 0.49320713, + 0.30590102 0.79929912 0.51724803, + 0.34432697 0.78820586 0.51006895, + 0.35045797 0.77068686 0.53218496, + 0.38874307 0.75815314 0.52352905, + 0.39490491 0.74089283 0.54325688, + 0.43271214 0.72703022 0.5330922, + 0.43906716 0.70939922 0.55133718, + 0.47662482 0.69412279 0.53946483, + 0.4826543 0.67743039 0.55509734, + 0.51982498 0.66077101 0.54144597, + 0.52568084 0.64450973 0.5552178, + 0.56191319 0.62671626 0.53988916, + 0.56746513 0.61115915 0.55178612, + 0.60259277 0.59234375 0.53479981, + 0.60762012 0.57806814 0.54464209, + 0.64194536 0.55806935 0.52579927, + 0.64651281 0.5448789 0.53397387, + 0.67979693 0.52380794 0.51332396, + 0.68380785 0.51198089 0.51988685, + 0.71571791 0.49003795 0.49760494, + 0.7189638 0.48024389 0.50245088, + 0.74948519 0.45742413 0.47857612, + 0.75214899 0.44917801 0.48219401, + 0.78131562 0.42541879 0.45668879, + 0.78324515 0.41927207 0.45906207, + 0.81132865 0.39423683 0.4316518, + 0.81245112 0.39054805 0.43289205, + 0.83883119 0.36466607 0.4042041, + 0.84209728 0.35335612 0.40744516, + 0.86270171 0.33133388 0.38205186, + 0.8674463 0.31408912 0.38585615, + 0.88702101 0.29148799 0.35809001, + 0.88967389 0.28125197 0.35969096, + 0.91126144 0.25367612 0.32442415, + 0.91593313 0.23309703 0.32669902, + 0.93514025 0.20576805 0.28839606, + 0.94491464 0.14742593 0.29223588, + 0.96018666 0.12582596 0.24941792, + 0.96381199 0.091049999 0.250552, + 0.97594774 0.074458383 0.20489496, + 0.97705287 0.057202794 0.20517197, + 0.97240186 0.083274193 0.21794496, + 0.97578865 0.0022731894 0.21870393, + 0.98528051 -0.0034354883 0.17091092, + 0.98500276 0.023996694 0.17086196, + 0.98500663 0.023991391 0.17083994, + 0.98528433 -0.0034416511 0.17088906, + 0.98796713 -0.015594502 0.15387602, + 0.99248874 0.0012983097 0.12232897, + 0.99239653 0.013686993 0.12231794, + 0.99239564 0.013688795 0.12232496, + 0.99248779 0.0012952397 0.12233697, + 0.99246466 0.0012952395 0.12252396, + 0.99139547 0.046425022 0.12239206, + 0.99299735 0.03478821 0.11289904, + 0.9927181 0.042143602 0.11284801, + 0.98559952 0.059159171 0.15840992, + 0.98452985 0.075431593 0.15814899, + 0.97427011 0.097028315 0.20342903, + 0.97186047 0.11996806 0.20271909, + 0.95809954 0.14587992 0.24650387, + 0.95187122 0.18501705 0.24435607, + 0.93471915 0.21452902 0.28333303, + 0.92996562 0.23678692 0.2812399, + 0.90996814 0.26707804 0.31721804, + 0.90768731 0.2761811 0.31595513, + 0.8891477 0.30117187 0.34454587, + 0.88522357 0.31572884 0.34160584, + 0.86551601 0.33997101 0.367834, + 0.86304015 0.34865308 0.36551708, + 0.83814186 0.37647995 0.39469093, + 0.83737087 0.37902793 0.39388794, + 0.8110103 0.40565214 0.42155516, + 0.8095457 0.41030684 0.41986185, + 0.78140283 0.4361459 0.44630289, + 0.77928621 0.44263911 0.44360313, + 0.74997157 0.46722072 0.46823874, + 0.74716365 0.47556576 0.46430978, + 0.71659964 0.49906677 0.48725477, + 0.71300203 0.50945002 0.481756, + 0.6810528 0.53202689 0.50310487, + 0.67695296 0.54355395 0.49626994, + 0.64350319 0.56527811 0.51610512, + 0.63870096 0.57847196 0.50737697, + 0.60447907 0.59889507 0.52529007, + 0.59915662 0.61322266 0.51475167, + 0.56403816 0.63246024 0.53090018, + 0.55825675 0.6477707 0.51840377, + 0.52217925 0.66585928 0.53287923, + 0.51616198 0.68160802 0.51863998, + 0.47912022 0.69852537 0.53151321, + 0.47272187 0.71515679 0.51486391, + 0.43520516 0.73067325 0.52603519, + 0.42877007 0.74739003 0.50750804, + 0.39131814 0.76132327 0.5169692, + 0.38479984 0.7783457 0.49609181, + 0.34691188 0.79090869 0.50409883, + 0.34062514 0.80757135 0.48145923, + 0.30247489 0.81870168 0.48809481, + 0.29650086 0.83497256 0.4635818, + 0.25865096 0.84453589 0.46889094, + 0.25305602 0.86042011 0.44231206, + 0.2155229 0.86846656 0.44644779, + 0.21053296 0.88354486 0.41835895, + 0.17318405 0.89014524 0.42148408, + 0.16891001 0.90434813 0.39194906, + 0.13206401 0.90949512 0.39418006, + 0.12856898 0.92284274 0.3630859, + 0.092261776 0.92659676 0.3645629, + 0.089672409 0.93894511 0.33217603, + 0.054269891 0.94135386 0.33302796, + 0.052659102 0.95262003 0.29956999, + 0.017852405 0.95379138 0.29993913, + 0.017299805 0.96390635 0.26567909, + -0.016937103 0.96391225 0.26568106, + -0.017492794 0.95381063 0.29989889, + -0.052270226 0.95265245 0.29953516, + -0.053882301 0.941414 0.332921, + -0.089293674 0.93901765 0.33207288, + -0.091897056 0.9266296 0.36457181, + -0.12824206 0.92288339 0.36309817, + -0.13172698 0.90959591 0.39405993, + -0.16871294 0.90443867 0.39182484, + -0.17300095 0.89024669 0.42134485, + -0.21020505 0.88368022 0.4182381, + -0.21524097 0.86848086 0.44655594, + -0.25263792 0.86047667 0.44244084, + -0.25819409 0.8446973 0.46885219, + -0.29620498 0.83510691 0.46352893, + -0.30223206 0.81870419 0.48824111, + -0.3402651 0.80762017 0.48163211, + -0.34655011 0.79095429 0.50427616, + -0.3846381 0.77833617 0.49623212, + -0.39109391 0.7614888 0.51689488, + -0.4285709 0.74755383 0.5074349, + -0.43509978 0.73060167 0.52622175, + -0.47245011 0.71516418 0.5151031, + -0.47878 0.69871002 0.53157699, + -0.51585674 0.6817897 0.51870477, + -0.52195507 0.66582704 0.53313905, + -0.55821389 0.64765781 0.51859087, + -0.56391609 0.63255906 0.53091204, + -0.59890407 0.61340106 0.51483303, + -0.60431796 0.59882796 0.52555192, + -0.63869882 0.57831991 0.50755286, + -0.64341801 0.565355 0.51612699, + -0.67688501 0.54362297 0.49628699, + -0.68108231 0.53182226 0.50328124, + -0.71304882 0.5092389 0.48190987, + -0.71664256 0.4988597 0.48740369, + -0.74708956 0.4754577 0.46453974, + -0.74988997 0.46713194 0.46845794, + -0.77932453 0.44245872 0.44371572, + -0.78154188 0.43564993 0.44654393, + -0.80959821 0.40990409 0.42015409, + -0.81096882 0.40554291 0.42173991, + -0.837506 0.378746 0.39387199, + -0.83829528 0.37613514 0.39469415, + -0.86310232 0.34841111 0.36560112, + -0.86576086 0.33906698 0.36809197, + -0.88547039 0.31483814 0.34178814, + -0.889557 0.29960299 0.34485701, + -0.90812391 0.27460098 0.31607798, + -0.90820974 0.27426293 0.31612492, + -0.9283874 0.24352711 0.28069812, + -0.93341458 0.2207059 0.28288886, + -0.95088536 0.19040707 0.24405409, + -0.95744264 0.15047695 0.2462929, + -0.9714061 0.12378301 0.20260303, + -0.97426033 0.09711004 0.20343708, + -0.98452401 0.075494602 0.15815499, + -0.9859615 0.052483175 0.15850993, + -0.99290526 0.037375707 0.11288203, + -0.99289262 0.037713885 0.11287996, + -0.9922384 0.010100794 0.12393893, + -0.99222738 0.010120003 0.12402605, + -0.99227649 -0.001865531 0.12403206, + -0.99228734 -0.0018848306 0.12394504, + -0.99457479 -0.015856896 0.10280798, + -0.99718326 0.00029500405 0.075003013, + -0.99718177 0.0017656495 0.075002886, + -0.99717265 0.0017920292 0.075123772, + -0.99717426 0.00023888606 0.075123914, + -0.9972015 0.00023889288 0.074760862, + -0.99682099 0.0276234 0.074732304, + -0.99747086 0.022346998 0.067471594, + -0.99746412 0.022653602 0.067470409, + -0.99290425 0.037850406 0.11273203, + -0.99210638 0.05530322 0.11254603, + -0.98446637 0.077430531 0.15757705, + -0.98252589 0.099866785 0.15706499, + -0.97110415 0.12805201 0.20139404, + -0.965729 0.165721 0.19976, + -0.95038652 0.19861591 0.23940988, + -0.94531798 0.22363099 0.237409, + -0.92667335 0.2577211 0.27359909, + -0.92693025 0.25665706 0.27372906, + -0.90961242 0.28417015 0.30307215, + -0.90637875 0.29665294 0.30078995, + -0.88762671 0.32340488 0.32791489, + -0.88312876 0.3393189 0.3239539, + -0.86331481 0.3650209 0.34849292, + -0.860219 0.375274 0.34524301, + -0.8350547 0.40488985 0.37248889, + -0.83399528 0.40817016 0.37128013, + -0.80718768 0.43666786 0.39720184, + -0.80535412 0.44209206 0.39491707, + -0.77692187 0.46953893 0.41943493, + -0.7744658 0.47650588 0.41610691, + -0.74486619 0.5025661 0.43886411, + -0.74157804 0.51154405 0.43403307, + -0.71095926 0.53622419 0.45497316, + -0.70697105 0.54673105 0.44863907, + -0.67475015 0.57054412 0.46817911, + -0.67005777 0.58250684 0.46011782, + -0.63660693 0.60516894 0.47801894, + -0.63132006 0.61824703 0.46819407, + -0.59699893 0.63954794 0.48432493, + -0.59121394 0.65348494 0.47267693, + -0.55629414 0.67331219 0.48701912, + -0.54996991 0.68820095 0.47319394, + -0.51413804 0.70676005 0.48595506, + -0.50747913 0.72212815 0.47010213, + -0.47076601 0.73938698 0.48133799, + -0.46390089 0.7549988 0.46343589, + -0.42690593 0.77068788 0.47306594, + -0.42004699 0.78615099 0.45335099, + -0.38300881 0.80022162 0.46146479, + -0.37612382 0.81570959 0.4394868, + -0.33899197 0.82822788 0.44623193, + -0.3322491 0.84346128 0.42211816, + -0.29479998 0.85452086 0.42765296, + -0.2885271 0.86893427 0.40212616, + -0.25142691 0.87837672 0.40649584, + -0.245598 0.89219201 0.37904501, + -0.20913696 0.90002888 0.38237393, + -0.20389204 0.91306424 0.3531881, + -0.16780506 0.91943133 0.35565111, + -0.16330704 0.93147421 0.32509509, + -0.12744303 0.93645024 0.32683209, + -0.12383599 0.94737089 0.29521698, + -0.088896975 0.95093977 0.29632893, + -0.086207226 0.96082824 0.26339605, + -0.051960688 0.96311575 0.26402295, + -0.050302017 0.97182637 0.23026809, + -0.016845502 0.97292012 0.23052703, + -0.016267596 0.98049974 0.19584596, + 0.016670205 0.98049337 0.19584407, + 0.017244196 0.97292376 0.23048194, + 0.050724499 0.971816 0.23021901, + 0.052385483 0.96307164 0.2640999, + 0.086501889 0.96078086 0.26347196, + 0.089168355 0.95091754 0.29631886, + 0.12420499 0.94732785 0.29519996, + 0.12782 0.93636501 0.326929, + 0.16371502 0.93137109 0.32518503, + 0.16820702 0.91932112 0.35574603, + 0.20422889 0.9129526 0.35328183, + 0.20943996 0.89998686 0.38230693, + 0.24601693 0.89211178 0.37896192, + 0.251811 0.87839198 0.406225, + 0.28886393 0.86894685 0.4018569, + 0.29522005 0.85434818 0.42770809, + 0.33255196 0.84330988 0.42218193, + 0.33922791 0.82821381 0.44607887, + 0.3764599 0.81564879 0.43931189, + 0.38334793 0.80015987 0.46128994, + 0.42020592 0.78614682 0.45321089, + 0.42718521 0.77039737 0.47328722, + 0.46404222 0.75476134 0.46368122, + 0.47081587 0.73933184 0.48137388, + 0.50766712 0.72200316 0.4700911, + 0.51431376 0.70665163 0.48592675, + 0.55025107 0.68802708 0.47312006, + 0.55648017 0.67336524 0.48673317, + 0.59138286 0.65353382 0.47239789, + 0.59717 0.63959801 0.48404801, + 0.63145924 0.61830324 0.46793216, + 0.63673317 0.60526514 0.47772911, + 0.67015493 0.58260894 0.45984694, + 0.67484874 0.57065082 0.46790683, + 0.70694607 0.54692006 0.44844806, + 0.71092296 0.53644896 0.45476493, + 0.74161619 0.51169914 0.43378508, + 0.7449162 0.50269711 0.43862912, + 0.77450728 0.47663116 0.41588616, + 0.77696168 0.46967483 0.41920885, + 0.80528915 0.44232011 0.39479408, + 0.80713397 0.436867 0.39709201, + 0.83394188 0.40836594 0.37118497, + 0.83500087 0.40508893 0.37239298, + 0.86016983 0.3754639 0.3451589, + 0.85883957 0.38854381 0.33380884, + 0.83308691 0.41956493 0.36045998, + 0.83183432 0.42330515 0.35897711, + 0.80481315 0.45267206 0.38388005, + 0.80289012 0.45814106 0.38141105, + 0.77442062 0.48622575 0.40479282, + 0.77163029 0.49380919 0.40092316, + 0.74192899 0.52052099 0.42261001, + 0.73852998 0.529383 0.41752499, + 0.70764184 0.55478388 0.43755889, + 0.70340633 0.56541228 0.43073019, + 0.67121923 0.58965123 0.44919515, + 0.66635293 0.60143197 0.44074193, + 0.63285923 0.62452525 0.45766515, + 0.62743402 0.63723999 0.44749501, + 0.59305906 0.65891808 0.46271807, + 0.58691388 0.67289883 0.45026588, + 0.55224395 0.69287294 0.46363094, + 0.54560304 0.70756608 0.44907406, + 0.50993091 0.72628582 0.46095487, + 0.50304782 0.74115777 0.44455385, + 0.46653768 0.75851744 0.45496568, + 0.45949906 0.77344811 0.43662205, + 0.42270905 0.78919911 0.44551307, + 0.41559076 0.80410755 0.42508274, + 0.37894085 0.81813669 0.43249986, + 0.37185198 0.83286786 0.40994793, + 0.33501011 0.84535933 0.41609615, + 0.32815602 0.85959911 0.39166707, + 0.291172 0.87056202 0.396662, + 0.28470603 0.88413912 0.37046003, + 0.24825101 0.89343703 0.37435499, + 0.24229509 0.90622127 0.34649113, + 0.20623903 0.91397309 0.34945503, + 0.20090103 0.92590511 0.31990403, + 0.16548304 0.93214422 0.32206008, + 0.1609 0.94305098 0.29114601, + 0.125755 0.94791502 0.29264799, + 0.12208205 0.95765138 0.26076809, + 0.087636307 0.96115613 0.26172304, + 0.084935226 0.96975523 0.22882506, + 0.051321581 0.97198963 0.22935191, + 0.049649194 0.9794789 0.19533597, + 0.016885195 0.98054862 0.19554892, + 0.016307902 0.9868471 0.16083202, + -0.015902692 0.98685354 0.16083293, + -0.016482599 0.980555 0.19555099, + -0.049254 0.97949803 0.19533999, + -0.050929599 0.972009 0.229357, + -0.084550492 0.96978688 0.22883298, + -0.087258652 0.96117651 0.26177388, + -0.12158703 0.95769823 0.26082706, + -0.12527004 0.94791436 0.29285812, + -0.16046593 0.9430595 0.29135785, + -0.16501504 0.93222022 0.32208008, + -0.20055307 0.92597437 0.31992212, + -0.20588297 0.91407388 0.34940097, + -0.24194294 0.90633374 0.34644291, + -0.24790195 0.89355874 0.37429592, + -0.28436396 0.88427174 0.37040591, + -0.29088807 0.87058717 0.39681509, + -0.327784 0.85966402 0.39183599, + -0.33462599 0.845442 0.416237, + -0.371481 0.83296198 0.41009301, + -0.37859076 0.81818253 0.43271974, + -0.41541293 0.80409986 0.42527094, + -0.4225359 0.78918582 0.44570088, + -0.45907405 0.77355814 0.43687406, + -0.46619073 0.75844151 0.45544773, + -0.50277489 0.74106681 0.44501388, + -0.5096398 0.72621077 0.46139482, + -0.54546803 0.70742506 0.44946006, + -0.55196619 0.69304127 0.46371019, + -0.58679199 0.67298698 0.450293, + -0.59293795 0.65901095 0.46274093, + -0.62731665 0.63733667 0.44752175, + -0.63275397 0.62459993 0.45770895, + -0.66627419 0.60149413 0.44077611, + -0.67114908 0.58969605 0.44924107, + -0.70333916 0.56546015 0.4307771, + -0.70766956 0.55459166 0.43775773, + -0.73848605 0.52925807 0.41776106, + -0.74189782 0.52035689 0.42286691, + -0.77160728 0.49365017 0.40116316, + -0.77438509 0.48609406 0.40501904, + -0.80294782 0.45792487 0.38154891, + -0.80488384 0.45241487 0.3840349, + -0.8318271 0.42314205 0.35918602, + -0.83316302 0.419148 0.360769, + -0.85853344 0.38862675 0.33449879, + -0.85903984 0.3870289 0.33505091, + -0.88293803 0.354958 0.30728701, + -0.88534272 0.34676889 0.30970889, + -0.90435398 0.31831101 0.28429201, + -0.90792459 0.30517486 0.28729984, + -0.9254514 0.27585611 0.25969812, + -0.92786247 0.26605687 0.26131386, + -0.94401449 0.23536612 0.2311701, + -0.94355166 0.23742591 0.2309529, + -0.96050853 0.19945291 0.19401491, + -0.96526647 0.17305408 0.19573709, + -0.97836947 0.13702007 0.15498008, + -0.98230809 0.10351302 0.15606402, + -0.9909519 0.074187696 0.11185098, + -0.99207449 0.056694727 0.11213405, + -0.99715233 0.03402701 0.067300521, + -0.99746364 0.022933293 0.067381375, + -0.99972385 0.0075713489 0.022245698, + -0.99972552 0.0073484662 0.022246288, + -0.99964935 -0.0044744713 0.02609941, + -0.99965012 -0.0044806604 0.026070803, + -0.99966013 -0.00026882804 0.026071103, + -0.99965936 -0.00026653608 0.026099609, + -0.9992891 -0.029752905 -0.023152502, + -0.99988055 -0.015458393 0, + -0.99973589 -0.0012792099 -0.022947399, + -0.99974602 -0.00131509 -0.0225005, + -0.99707091 -0.026082296 -0.07189779, + -0.99740964 0.0010912496 -0.071922176, + -0.99738175 0.0010912998 -0.072308287, + -0.99732739 -0.010495003 -0.072304323, + -0.99764526 -0.011949803 -0.067536317, + -0.99744034 -0.023615809 -0.067492224, + -0.99972302 -0.0077731502 -0.0222151, + -0.99968326 -0.011876203 -0.022192106, + -0.99968553 0.011832095 0.022109788, + -0.99962962 0.015921995 0.022072192, + -0.9966349 0.047954392 0.06647779, + -0.99560189 0.06633129 0.066159591, + -0.99568009 0.063845105 0.067417204, + -0.99954611 0.020714201 0.021873202, + -0.99962389 0.016460398 0.021932598, + -0.99961966 -0.016554194 -0.022057593, + -0.99968135 -0.012201305 -0.022097807, + -0.99704278 -0.037145894 -0.067274787, + -0.99743915 -0.024000803 -0.067373008, + -0.99280226 -0.040190712 -0.11282003, + 0.97804314 -0.034590904 -0.20551203, + -0.0020303596 0.99545479 -0.095213279, + 0.0023268505 0.99545425 -0.09521322, + 0.8682223 0.44115016 0.22710508, + 0.84174389 0.48000494 0.24710797, + 0.840042 0.48412701 0.244848, + 0.81278372 0.5198608 0.26292092, + 0.81027716 0.52548712 0.25945005, + 0.78160709 0.55931306 0.27615103, + 0.77811116 0.5666151 0.27109107, + 0.74807018 0.5986321 0.28641006, + 0.74378783 0.6069839 0.27991095, + 0.71270281 0.63699681 0.29375094, + 0.70755136 0.64641231 0.28552115, + 0.67590904 0.67415005 0.29777303, + 0.66988277 0.68449175 0.28762493, + 0.63707399 0.71061498 0.29860201, + 0.63027883 0.72157484 0.28649294, + 0.59670275 0.74582678 0.2961219, + 0.58914697 0.75728202 0.28183299, + 0.55529064 0.77942854 0.29007483, + 0.547391 0.79069901 0.27415001, + 0.51327497 0.81086791 0.28114396, + 0.50492507 0.8220861 0.26310703, + 0.47065282 0.84032971 0.2689459, + 0.46199489 0.85126084 0.24882895, + 0.42727193 0.86780888 0.25366598, + 0.41859984 0.8780877 0.23181091, + 0.38436416 0.89260131 0.23564209, + 0.37579191 0.90211678 0.21205096, + 0.34195587 0.91478372 0.21502793, + 0.33364785 0.92338359 0.18984692, + 0.30015889 0.93434566 0.19210093, + 0.29220513 0.94196737 0.16526906, + 0.25893989 0.95136154 0.16691692, + 0.25157592 0.95782965 0.13882296, + 0.21906194 0.96562177 0.13995197, + 0.21243104 0.97087425 0.11079803, + 0.18085502 0.97716713 0.11151601, + 0.17500702 0.98120409 0.081308506, + 0.14398901 0.98619914 0.081722409, + 0.13904098 0.98899674 0.050527088, + 0.10868801 0.9927811 0.050720409, + 0.10474902 0.99431813 0.018952902, + 0.075289167 0.99698067 0.019003693, + 0.072426178 0.99728566 -0.013256095, + 0.043835279 0.99895054 -0.013278194, + 0.042094402 0.99806213 -0.045827705, + 0.014275297 0.99884576 -0.045863688, + 0.013684602 0.9967711 -0.079121806, + 0.040919319 0.9960295 -0.079062939, + 0.04268432 0.99799347 -0.046767924, + 0.07054431 0.99641514 -0.046694003, + 0.073408507 0.99719012 -0.014934202, + 0.10212995 0.99465954 -0.014896292, + 0.10607699 0.99422085 0.016506998, + 0.135681 0.99061602 0.0164472, + 0.14064999 0.9889279 0.047319293, + 0.17092404 0.98415822 0.047091112, + 0.1768429 0.98119742 0.077318057, + 0.20775002 0.97515911 0.076842308, + 0.21445708 0.97096735 0.10597504, + 0.24630894 0.96346974 0.10515698, + 0.25372702 0.95806813 0.13314702, + 0.28637686 0.94899654 0.13188595, + 0.29441613 0.94240236 0.15873607, + 0.32735503 0.93177611 0.15694602, + 0.33585587 0.92407262 0.18245694, + 0.3691009 0.91178578 0.18003096, + 0.37788507 0.90310013 0.20399302, + 0.41173685 0.88890773 0.20078793, + 0.42057422 0.87945539 0.22288011, + 0.45494214 0.8632313 0.21876808, + 0.46376812 0.85307616 0.23912406, + 0.49782911 0.83508819 0.23408106, + 0.50645792 0.82443988 0.25258496, + 0.54026395 0.80458188 0.24650097, + 0.54858792 0.7935859 0.26319697, + 0.5824008 0.77157372 0.2558969, + 0.59000635 0.76083648 0.27022314, + 0.62366199 0.73661399 0.261621, + 0.63076001 0.72590798 0.274225, + 0.66353518 0.69987118 0.26438907, + 0.66995221 0.68951923 0.27518609, + 0.70179808 0.66163003 0.26405504, + 0.70721006 0.65229106 0.27270904, + 0.73838037 0.62219632 0.26012713, + 0.74304897 0.61356294 0.26724297, + 0.77338517 0.58119911 0.25314605, + 0.77698803 0.57403803 0.25839901, + 0.80600435 0.53974622 0.24296312, + 0.80880034 0.53375524 0.24687512, + 0.83639312 0.49749306 0.23010303, + 0.838274 0.49313 0.232636, + 0.8645708 0.45447689 0.21440196, + 0.86924356 0.44245479 0.2205659, + 0.88983011 0.40836406 0.20357104, + 0.89634299 0.38959599 0.211623, + 0.91533375 0.3538619 0.19221295, + 0.91986221 0.3389031 0.19748004, + 0.93726933 0.30120111 0.17551106, + 0.94018221 0.29006705 0.17865804, + 0.95599902 0.249791 0.153852, + 0.95749402 0.243063 0.155324, + 0.97165865 0.19919093 0.12728895, + 0.97222388 0.19609196 0.12778398, + 0.98420477 0.14832097 0.096653774, + 0.9843235 0.14747192 0.096742854, + 0.99363464 0.094191663 0.061790679, + 0.99392003 0.091015697 0.061961502, + 0.99929434 0.031049112 0.021137608, + 0.99940175 0.027290694 0.021244494, + 0.99938613 -0.027646504 -0.021521602, + 0.99951667 -0.022326693 -0.021629792, + 0.99547446 -0.068252929 -0.066122532, + 0.99639565 -0.05279588 -0.06639418, + 0.9897849 -0.088734493 -0.11158898, + 0.99154252 -0.06557887 -0.11199494, + 0.98311889 -0.092453793 -0.15789099, + 0.98520213 -0.065537207 -0.15837201, + 0.97513527 -0.084737323 -0.20477004, + 0.84369683 -0.012174597 -0.53668189, + 0.78406054 -0.013024593 -0.62054765, + 0.71608293 -0.014194098 -0.69787097, + 0.3445079 0.93869376 -0.012972597, + -0.77292299 0.55482501 -0.30783001, + -0.75625312 0.56545705 -0.32915002, + -0.73435605 0.58661807 -0.34146804, + -0.73841274 0.58408576 -0.33703187, + -0.35633296 -0.17490898 -0.91784185, + -0.35083991 -0.17523895 -0.91989279, + -0.32320416 -0.42257521 -0.84674042, + -0.17039299 -0.18013099 -0.96877187, + -0.21720697 -0.17946598 -0.95948589, + -0.2177849 -0.17944591 -0.95935851, + -0.20362711 -0.13215306 -0.97008848, + -0.190485 -0.37599599 -0.90683103, + -0.23425709 -0.37235111 -0.89804131, + -0.21731904 -0.50969511 -0.83245617, + -0.24775504 -0.50589508 -0.82624912, + -0.24786507 -0.50706911 -0.8254962, + -0.26746199 -0.36563399 -0.89150202, + -0.2341859 -0.36890587 -0.8994807, + -0.24970391 -0.12809995 -0.95981163, + -0.26387995 -0.17836896 -0.94791979, + -0.26817894 0.0028997294 -0.96336478, + -0.2705971 0.002899671 -0.96268839, + -0.266314 -0.17724399 -0.94744998, + -0.26445392 -0.17732494 -0.94795567, + -0.26871094 0.0027940292 -0.96321678, + -0.22075494 -0.018295696 -0.97515774, + -0.22968797 -0.012513998 -0.97318387, + -0.22137192 -0.0073574572 -0.97516167, + -0.17369999 0.0033634296 -0.98479289, + -0.17087598 -0.17959198 -0.9687869, + -0.16834894 -0.17965995 -0.96921664, + -0.17113298 0.0034487494 -0.98524189, + -0.17322601 0.0034487206 -0.9848761, + -0.12536199 -0.0143715 -0.99200702, + -0.12836103 -0.012773503 -0.99164522, + 0.0211237 0.00312811 -0.99977201, + -0.027092787 -0.013141293 -0.99954653, + -0.026935609 -0.10837304 -0.99374539, + -0.025034592 -0.10837696 -0.99379462, + -0.025181109 -0.012208505 -0.99960834, + -0.025736395 -0.011992497 -0.99959677, + 0.037032004 -0.93890512 0.34217802, + -0.036136691 -0.93893564 0.34218988, + -0.090307929 -0.92678338 0.36457813, + -0.15836202 -0.91884309 0.36145404, + -0.18602395 -0.90891176 0.3731949, + -0.24719797 -0.87660891 0.41285595, + -0.22726311 -0.88617843 0.40378118, + -0.17290209 -0.8962844 0.4083862, + -0.19072403 -0.88909614 0.41609207, + -0.12804599 -0.8982659 0.42038393, + -0.14422199 -0.9029749 0.40476695, + -0.10633802 -0.90734112 0.40672407, + -0.038556091 -0.92432976 0.37964192, + 0.031748109 -0.92455125 0.37973309, + -0.20578796 -0.85879785 0.46916687, + -0.22460502 -0.84931511 0.47772005, + -0.26128897 -0.84130585 0.47321495, + -0.2799499 -0.8300367 0.48235583, + -0.29952589 -0.82491273 0.47937784, + -0.31663808 -0.81284016 0.48890811, + -0.32777798 -0.80959088 0.48695394, + -0.34189886 -0.79819065 0.49598077, + -0.34595603 -0.79692811 0.49519706, + -0.35704204 -0.78684014 0.50339204, + -0.35523909 -0.7874192 0.50376213, + -0.36314708 -0.77939516 0.5105561, + -0.35708204 -0.78135413 0.51183808, + -0.36251798 -0.77524787 0.51727295, + -0.35261491 -0.77840179 0.51937789, + -0.35381889 -0.77691668 0.5207808, + -0.34071511 -0.78094733 0.52348316, + -0.34092402 -0.7806651 0.52376807, + -0.32060513 -0.78657931 0.52773619, + -0.2710779 -0.84926271 0.45306686, + -0.23276097 -0.85806489 0.45776293, + -0.093024619 -0.98069721 0.17198704, + -0.006513299 -0.99941289 0.033635695, + -0.0079322169 -0.99940264 0.033635389, + 0.072697766 -0.99101454 -0.11227295, + 0.062567189 -0.99169689 -0.11234999, + 0.12975702 -0.95939511 -0.25044802, + 0.11235902 -0.96144813 -0.25098404, + 0.16781899 -0.90892899 -0.38168699, + 0.14443699 -0.91233689 -0.38311794, + 0.20145898 -0.81780487 -0.53908193, + 0.20734403 -0.74832904 -0.63008904, + 0.19038405 -0.7509622 -0.6323052, + 0.22104201 -0.64031303 -0.73562199, + 0.19331197 -0.64416891 -0.74005193, + 0.22485706 -0.45370513 -0.8623172, + 0.182515 -0.45780799 -0.87011498, + 0.14101796 -0.46065983 -0.87630272, + 0.18246701 -0.45749807 -0.87028813, + 0.15619603 -0.65000421 -0.74370515, + 0.19320889 -0.64568162 -0.73875958, + 0.16573104 -0.75671816 -0.63238519, + 0.19038209 -0.75329536 -0.62952429, + 0.15310498 -0.84985679 -0.50428391, + 0.13350104 -0.85229832 -0.50573218, + 0.16532806 -0.75987929 -0.62868923, + 0.13334897 -0.76360083 -0.63176882, + 0.15611503 -0.65293419 -0.74115115, + 0.11997195 -0.65626478 -0.74493176, + 0.14092693 -0.46016079 -0.87657958, + 0.11007605 -0.46197522 -0.8800354, + 0.12035894 -0.24108988 -0.96301055, + 0.154136 -0.239953 -0.95846999, + 0.12117995 -0.11132096 -0.98636866, + 0.11833499 -0.11134799 -0.98671091, + 0.15887295 -0.044077784 -0.98631465, + 0.15431392 -0.24219789 -0.9578765, + 0.19914697 -0.24022397 -0.9500699, + 0.21681599 0.0026046401 -0.97620898, + 0.29832813 -0.026252409 -0.95410234, + 0.30599493 -0.46251887 -0.8321318, + 0.33488309 -0.23927806 -0.91137224, + 0.28954509 -0.24306309 -0.92578834, + 0.26336306 -0.46901011 -0.84301215, + 0.28937504 -0.23859103 -0.9270041, + 0.24460392 -0.24168392 -0.93901962, + 0.25190988 -0.030162085 -0.96728051, + 0.21461605 -0.11798303 -0.96954626, + 0.21612503 0.0026596703 -0.97636211, + 0.220515 0.00265957 -0.97538, + 0.21900395 -0.11688397 -0.96869779, + 0.21532893 -0.11694696 -0.96951365, + 0.20523708 -0.035330713 -0.97807437, + 0.19927791 -0.24222387 -0.94953454, + 0.24450009 -0.23967908 -0.93956035, + 0.22471297 -0.45257396 -0.86294889, + 0.25590906 -0.44898713 -0.85610819, + 0.2209271 -0.63789028 -0.73775834, + 0.24060491 -0.63483775 -0.73422778, + 0.20737892 -0.74711478 -0.63151675, + 0.22436392 -0.74424678 -0.62909275, + 0.18209308 -0.84150541 -0.50863624, + 0.16843893 -0.84358561 -0.50989377, + 0.16975498 -0.82879889 -0.53317493, + 0.12019603 -0.91956621 -0.37410009, + 0.141994 -0.91689599 -0.373014, + 0.093041867 -0.96637464 -0.23971491, + 0.10880803 -0.96482223 -0.23933005, + 0.048551612 -0.99401724 -0.097839624, + 0.057190798 -0.99356198 -0.097794801, + -0.015704891 -0.99855739 0.051345769, + -0.015644807 -0.99855846 0.051345926, + -0.09459994 -0.97655636 0.19336107, + -0.10089102 -0.97595024 0.19324104, + -0.18818496 -0.92293376 0.3358269, + -0.19632405 -0.92143524 0.33528209, + -0.26737204 -0.85533613 0.44374806, + -0.286672 -0.85039699 0.441185, + -0.33239999 -0.79685497 0.50451201, + -0.36014399 -0.78820199 0.499033, + -0.35863701 -0.79005098 0.49719101, + -0.36972082 -0.78638262 0.49488276, + -0.36594689 -0.79061669 0.49092582, + -0.373559 -0.78804302 0.489328, + -0.36465099 -0.79710299 0.481307, + -0.36798391 -0.7959798 0.48062888, + -0.35600713 -0.80689728 0.47135517, + -0.35342801 -0.807742 0.47184899, + -0.33777213 -0.82039028 0.46137819, + -0.32813397 -0.82335687 0.46304595, + -0.30889702 -0.83690113 0.45186207, + -0.29031119 -0.8420375 0.45463428, + -0.26828301 -0.85523498 0.44339299, + -0.23218894 -0.86351883 0.44768688, + -0.24662888 -0.85599458 0.45436478, + -0.19833097 -0.86573291 0.45953393, + -0.20268792 -0.86371571 0.46142483, + -0.18609399 -0.86661589 0.46297494, + -0.13084504 -0.88814932 0.44053414, + -0.10722798 -0.89068574 0.44179288, + -0.045719314 -0.90731829 0.41795114, + 0.020521993 -0.9080767 0.41830084, + 0.15515798 -0.9124909 0.37853193, + 0.042473886 -0.92284364 0.38282585, + -0.000218263 -0.916897 0.399124, + -0.041467905 -0.91610813 0.39878106, + -0.10681102 -0.89909822 0.42451608, + -0.13455896 -0.89604771 0.42307484, + -0.13696404 -0.89340627 0.42786214, + -0.16646095 -0.88215071 0.44056886, + -0.22125594 -0.87245983 0.43572891, + -0.20497292 -0.8800047 0.42845985, + -0.25368792 -0.86968172 0.42343384, + -0.24272494 -0.87533575 0.41817692, + -0.27766088 -0.86683959 0.41411778, + -0.30293906 -0.85172915 0.4275341, + -0.31987008 -0.84677017 0.4250451, + -0.3409639 -0.83188879 0.43784088, + -0.34902403 -0.82926714 0.43646106, + -0.36618292 -0.81534785 0.44846189, + -0.36684397 -0.81511986 0.44833595, + -0.37998909 -0.80307418 0.45899913, + -0.37500799 -0.80483699 0.46000701, + -0.38202399 -0.79769301 0.46663001, + -0.37309504 -0.80083513 0.46846905, + -0.37636584 -0.79718471 0.47206482, + -0.34889403 -0.80638415 0.47751206, + -0.30052102 -0.85759813 0.41738805, + -0.27475306 -0.86455721 0.42077509, + -0.20506103 -0.92390811 0.32302302, + -0.19170904 -0.92645925 0.32391509, + -0.093477845 -0.98056448 0.17249709, + -0.10149094 -0.9797914 0.1723609, + -0.19232699 -0.93395698 0.301222, + -0.21040204 -0.93042022 0.30008206, + -0.28495193 -0.87383968 0.39396286, + -0.31037003 -0.8666141 0.39070505, + -0.36199519 -0.81720841 0.44847521, + -0.38924906 -0.80752313 0.44316107, + -0.38343307 -0.81342614 0.43739805, + -0.38986215 -0.81105232 0.43612114, + -0.37882107 -0.82121617 0.4267301, + -0.38003895 -0.82077289 0.42649993, + -0.36167109 -0.8358112 0.41305408, + -0.35568601 -0.83787298 0.41407299, + -0.33236879 -0.85445148 0.39930376, + -0.31766886 -0.85902858 0.40144283, + -0.28950697 -0.87593687 0.38590193, + -0.2627821 -0.88296431 0.38899815, + -0.23044403 -0.8986541 0.37325102, + -0.18260798 -0.90798187 0.37712494, + -0.19620302 -0.90259111 0.38318905, + -0.13368006 -0.91222042 0.38727719, + -0.13537802 -0.91166312 0.38799906, + -0.10722498 -0.91482878 0.3893469, + -0.037013397 -0.9318589 0.36092797, + 0.0058930623 -0.93248135 0.36117011, + 0.056659691 -0.9382419 0.34130898, + 0.17294104 -0.92559123 0.3367081, + 0.18692805 -0.92490822 0.33106309, + 0.33021399 -0.88869101 0.31809899, + 0.32849291 -0.88906074 0.31884691, + 0.49228993 -0.81933385 0.29384097, + 0.47531211 -0.82626116 0.30227605, + 0.6457808 -0.71704584 0.26232094, + 0.61912203 -0.73428398 0.27841499, + 0.78088802 -0.58409399 0.221468, + 0.77699137 -0.58806229 0.2246491, + 0.88818955 -0.42922381 0.16396992, + 0.95934355 -0.26143089 0.10636595, + 0.88032413 -0.43939707 0.17877302, + 0.87307185 -0.45028889 0.18704395, + 0.75711983 -0.60329789 0.25060195, + 0.73768073 -0.62076074 0.2654869, + 0.60213006 -0.73408008 0.31395203, + 0.60240507 -0.73392403 0.31378904, + 0.42571673 -0.83200151 0.35572278, + 0.4516412 -0.82348043 0.34336615, + 0.2891151 -0.88356131 0.36841813, + 0.29933214 -0.8819434 0.36411017, + 0.15979891 -0.91244644 0.37670377, + 0.13817902 -0.90133715 0.41048506, + 0.05156292 -0.90885627 0.41391015, + -0.012056097 -0.89898479 0.43781388, + -0.050933518 -0.8978833 0.43727714, + -0.11026704 -0.88112527 0.45984718, + -0.13305497 -0.87864876 0.45855489, + -0.18560989 -0.85769647 0.47948471, + -0.196594 -0.85583001 0.478441, + -0.24166703 -0.83297414 0.49774605, + -0.24415803 -0.83243811 0.49742705, + -0.27191591 -0.8157177 0.51055485, + -0.29200193 -0.81071383 0.50742286, + -0.30661398 -0.80034089 0.51521093, + -0.31890884 -0.79693663 0.51301974, + -0.33155599 -0.786699 0.52074498, + -0.33678114 -0.78515434 0.51972222, + -0.3468079 -0.77602082 0.52679789, + -0.34634992 -0.77616084 0.5268929, + -0.35363713 -0.76876229 0.53286517, + -0.34899604 -0.7701931 0.53385806, + -0.35356587 -0.7650587 0.53821582, + -0.3450411 -0.76765817 0.54004413, + -0.34770703 -0.7643581 0.54300708, + -0.33558291 -0.76795083 0.54555988, + -0.33483291 -0.76896882 0.54458588, + -0.31968999 -0.77324897 0.54761702, + -0.32383096 -0.76700187 0.55393296, + 0.087611705 -0.63226807 -0.7697801, + 0.072015688 -0.77219784 -0.63128781, + 0.10210598 -0.77016187 -0.62962294, + 0.081383891 -0.86218888 -0.50000691, + 0.10662996 -0.86012667 -0.49881083, + 0.078215405 -0.92852014 -0.36295003, + 0.097630903 -0.92692399 -0.362326, + 0.061056077 -0.97320366 -0.22169092, + 0.074413359 -0.97231954 -0.22148889, + 0.028054804 -0.99688715 -0.073681206, + 0.034323905 -0.99669212 -0.073666811, + -0.022718189 -0.99649853 0.080464065, + -0.024655197 -0.99645287 0.080460392, + -0.08815632 -0.96967125 0.22796106, + -0.098705165 -0.96870762 0.22773392, + -0.1970671 -0.88304842 0.42589921, + -0.217802 -0.87908798 0.423989, + -0.29072386 -0.78195065 0.55139178, + -0.31476802 -0.77570814 0.54699004, + -0.22648394 -0.88546878 0.4057709, + -0.21245408 -0.88833833 0.40708515, + -0.102363 -0.97210002 0.211053, + -0.092527896 -0.97304088 0.21125796, + -0.021545202 -0.99751914 0.067018107, + -0.020463495 -0.99754179 0.067019686, + 0.044546295 -0.99539191 -0.084915191, + 0.037174907 -0.99569225 -0.084940821, + 0.090679578 -0.96890378 -0.23022294, + 0.076170661 -0.9700855 -0.2305039, + 0.11893395 -0.92242366 -0.36740887, + 0.098441824 -0.92450523 -0.36823809, + 0.132919 -0.85509902 -0.50113702, + 0.10693102 -0.85780716 -0.50272512, + 0.133146 -0.76641899 -0.62839001, + 0.10211901 -0.76926112 -0.63072103, + 0.12000904 -0.65878123 -0.74270123, + 0.093407609 -0.66067606 -0.74483705, + 0.11016399 -0.46215695 -0.87992889, + 0.071144402 -0.46380901 -0.88307399, + 0.092994571 -0.39351484 -0.9146027, + 0.062007576 -0.39446685 -0.91681564, + 0.022584205 -0.089371622 -0.99574226, + 0.021996507 -0.24074009 -0.97034037, + 0.065470099 -0.240281 -0.96849298, + 0.06723661 -0.068525009 -0.99538112, + 0.065427274 -0.23987888 -0.9685955, + 0.098180674 -0.23923194 -0.96598577, + 0.10823104 -0.28551808 -0.95224237, + 0.11237304 -0.098707534 -0.98875135, + 0.11956896 -0.048169482 -0.99165666, + 0.11970696 0.0030240088 -0.99280465, + 0.12193801 0.0030240505 -0.99253315, + 0.11907499 0.0032793996 -0.99287987, + 0.16856696 -0.0063595688 -0.98566973, + 0.16746505 -0.11431303 -0.97922826, + 0.16716793 -0.11431695 -0.9792785, + 0.16823801 -0.019873302 -0.98554611, + 0.179187 -0.013383 -0.983724, + 0.077207386 -0.013421497 -0.99692476, + 0.070451483 -0.016561097 -0.99737775, + 0.07009238 -0.10216796 -0.99229467, + 0.071081594 -0.10216299 -0.99222487, + 0.071452588 -0.0089659085 -0.99740374, + 0.017807703 0.004526481 -0.99983126, + 0.017741306 -0.086425133 -0.99610037, + 0.021780094 -0.086419076 -0.99602073, + 0.021861689 0.0035988383 -0.99975455, + 0.0226468 0.00359884 -0.99973702, + 0.022556093 -0.089508571 -0.99573064, + 0.021039091 -0.089511156 -0.99576354, + -0.022266205 -0.069846414 -0.99730927, + -0.021713011 -0.23520012 -0.97170448, + 0.18593091 -0.91774058 0.35097283, + 0.19995303 -0.91516513 0.34998804, + 0.2652629 -0.85144371 0.45241484, + 0.29194096 -0.8446089 0.44878295, + 0.34098199 -0.78539503 0.51661003, + 0.36981702 -0.77623409 0.51058406, + 0.35943496 -0.78923386 0.49791193, + 0.37059888 -0.7855317 0.49557683, + 0.36532497 -0.79144788 0.49004894, + 0.37256882 -0.78900266 0.48853576, + 0.36456403 -0.79713011 0.48132807, + 0.36808696 -0.7959429 0.48061094, + 0.35568592 -0.80723882 0.47101289, + 0.35302299 -0.80811 0.471522, + 0.3370041 -0.82102519 0.46081012, + 0.3272498 -0.8240205 0.46249074, + 0.30784199 -0.83764499 0.45120299, + 0.28909796 -0.84280586 0.45398295, + 0.26709297 -0.8559429 0.44274494, + 0.23716797 -0.86286891 0.44632795, + 0.198823 -0.881271 0.42875499, + 0.165309 -0.88685203 0.43147001, + -0.11182196 -0.14171995 -0.98357064, + -0.10445695 -0.38240483 -0.91807157, + -0.14699501 -0.38033107 -0.9130941, + -0.13561101 -0.52265906 -0.84168714, + -0.17639405 -0.51926011 -0.83621418, + -0.15764695 -0.64668983 -0.74628383, + -0.194574 -0.64236301 -0.74128997, + -0.16614704 -0.75743818 -0.63141316, + -0.19891405 -0.75276518 -0.62751716, + -0.16241698 -0.84459591 -0.51017493, + -0.19075608 -0.8402434 -0.50754625, + -0.14465897 -0.91291976 -0.38164291, + -0.16783594 -0.90953672 -0.38022885, + -0.11215501 -0.96197313 -0.24905603, + -0.12935494 -0.95994753 -0.24853188, + -0.061427522 -0.99215436 -0.10888704, + -0.0713512 -0.99149799 -0.108815, + 0.0077686473 -0.99938262 0.03426389, + 0.0064066723 -0.99939233 0.034264211, + 0.094172463 -0.98012567 0.17459995, + 0.10260697 -0.97930479 0.17445296, + 0.19683908 -0.93080133 0.30799913, + 0.215358 -0.92709798 0.30677399, + 0.29228416 -0.8670094 0.40356517, + 0.31845409 -0.85940015 0.4000231, + 0.3747431 -0.80329317 0.46291211, + 0.40316409 -0.7928952 0.45692012, + 0.38442394 -0.81243086 0.43837693, + 0.39097908 -0.81000417 0.43706807, + 0.37772799 -0.82220298 0.425798, + 0.3787649 -0.82182682 0.42560291, + 0.36122498 -0.83614987 0.41275895, + 0.35548609 -0.83812517 0.41373408, + 0.3319881 -0.8548072 0.39885908, + 0.31685004 -0.85951209 0.40105507, + 0.28836593 -0.87656575 0.38532791, + 0.26163301 -0.88356602 0.38840601, + 0.22896497 -0.89934886 0.37248698, + 0.18590707 -0.90778631 0.37598214, + 0.15193804 -0.92008924 0.3610411, + 0.088286974 -0.92726165 0.36385587, + 0.055516817 -0.93494326 0.35042709, + -0.033041611 -0.93587637 0.35077611, + -0.059094723 -0.93841434 0.34042111, + -0.17594698 -0.92539185 0.33569697, + -0.189504 -0.92469001 0.33020699, + -0.33266291 -0.88811779 0.3171469, + -0.33117685 -0.88844156 0.31779486, + -0.49432713 -0.81848919 0.29277307, + -0.47743312 -0.82543421 0.30119106, + -0.64767504 -0.71575606 0.26117104, + -0.62053823 -0.73339427 0.2776061, + -0.78180486 -0.58314496 0.22073297, + -0.77774489 -0.58729196 0.22405598, + -0.888708 -0.428359 0.163422, + -0.95952064 -0.26094392 0.10596396, + -0.88099223 -0.43836612 0.17801104, + -0.873896 -0.44906601 0.186133, + -0.75835115 -0.60216904 0.24959204, + -0.73894423 -0.61967921 0.26449808, + -0.6041581 -0.7328952 0.3128221, + -0.60393995 -0.73301995 0.31295097, + -0.42753291 -0.83139884 0.3549529, + -0.45384622 -0.82268244 0.34237015, + -0.29110694 -0.88325673 0.36757892, + -0.30229598 -0.88145286 0.36284697, + -0.16287392 -0.9123686 0.37557381, + -0.15795895 -0.91243076 0.37751693, + -0.045068078 -0.9230926 0.38192782, + -0.027764887 -0.9209646 0.38865581, + 0.058966186 -0.91971678 0.38812891, + 0.083982833 -0.91347432 0.39813516, + 0.14735594 -0.90670568 0.39518484, + 0.17598289 -0.89612448 0.40741977, + 0.21981893 -0.88806576 0.4037559, + 0.24779412 -0.87450641 0.4169372, + 0.27644706 -0.86748016 0.41358808, + 0.30187604 -0.85232711 0.42709407, + 0.31897709 -0.84733421 0.42459208, + 0.34073085 -0.83201057 0.43779078, + 0.34862208 -0.8294462 0.43644208, + 0.36581013 -0.8155123 0.44846714, + 0.36689281 -0.81513858 0.4482618, + 0.37897107 -0.80409312 0.45805606, + 0.37397197 -0.8058579 0.45906195, + 0.38307413 -0.7965883 0.46765518, + 0.37388104 -0.79983014 0.46955806, + 0.38848299 -0.78311598 0.485603, + 0.35998982 -0.79288965 0.49166375, + 0.30721498 -0.85090286 0.42612594, + 0.2808719 -0.85814971 0.42975584, + 0.20945692 -0.92056763 0.32967088, + 0.19030003 -0.92424715 0.33098802, + 0.104363 -0.97528797 0.19473501, + 0.095729925 -0.97613925 0.19490504, + 0.09349899 -0.97689587 0.19217797, + 0.015394893 -0.99853849 0.051805273, + 0.015434198 -0.9985379 0.051805291, + -0.056104083 -0.99394763 -0.094447866, + -0.047732193 -0.99438089 -0.094489083, + -0.10840205 -0.96550745 -0.23673712, + -0.092609391 -0.96705687 -0.23711698, + -0.14275204 -0.91648626 -0.37373108, + -0.120885 -0.91917902 -0.37482899, + -0.16162406 -0.84744632 -0.5056802, + -0.13456999 -0.85092586 -0.50775594, + -0.165837 -0.75989097 -0.62854099, + -0.134239 -0.763587 -0.63159698, + -0.157553 -0.65024197 -0.74321097, + -0.120951 -0.65363097 -0.74708599, + -0.13574201 -0.52588505 -0.83965415, + -0.096417084 -0.52832496 -0.84354991, + -0.10470098 -0.3853609 -0.91680676, + -0.062222023 -0.38674015 -0.92008734, + -0.065554909 -0.23474903 -0.96984309, + -0.04847651 -0.078835919 -0.99570823, + -0.074971311 -0.17813401 -0.9811461, + -0.076189391 0.0036114596 -0.99708688, + -0.075374387 0.0036114592 -0.99714875, + -0.074182272 -0.17718594 -0.98137766, + -0.075552508 -0.17717001 -0.98127609, + -0.076766528 0.0033966212 -0.99704337, + -0.12441798 -0.0099633392 -0.99217987, + -0.12240703 -0.17934005 -0.97614223, + -0.12334298 -0.17932099 -0.97602791, + -0.15759793 -0.13645893 -0.97802955, + -0.14711197 -0.38224691 -0.91227478, + -0.19062096 -0.37936592 -0.90539777, + -0.17637989 -0.51783168 -0.83710253, + -0.21724893 -0.51351482 -0.83012372, + -0.19470502 -0.64040804 -0.74294508, + -0.22178292 -0.63664377 -0.73857778, + -0.241106 -0.59623897 -0.765746, + -0.19964005 -0.7487042 -0.63212818, + -0.23362695 -0.74294084 -0.62726182, + -0.19220801 -0.83603698 -0.51390499, + -0.21356396 -0.83226687 -0.51158792, + -0.26100305 -0.73324716 -0.6278742, + -0.23466603 -0.73836505 -0.63225704, + -0.28127792 -0.58578175 -0.76009369, + -0.31543887 -0.021920092 -0.94869262, + -0.31057096 -0.17633195 -0.93405175, + -0.30507502 -0.17661402 -0.93580812, + -0.27961892 -0.43283886 -0.8570087, + -0.30205604 -0.42976406 -0.85092014, + -0.26131395 -0.62604284 -0.7347008, + -0.24228083 -0.62925452 -0.73847044, + -0.26890987 -0.50412273 -0.82069957, + -0.25544411 -0.36629218 -0.89475042, + -0.2673901 -0.36506611 -0.8917563, + -0.2839891 -0.14532605 -0.94775033, + -0.31203902 -0.16167401 -0.93621212, + -0.31619409 -0.0052277213 -0.94868022, + -0.32857892 -0.012195298 -0.94439775, + -0.45197293 0.0011008299 -0.89203089, + -0.45141721 0.0010106905 -0.89231241, + -0.44505 -0.16737001 -0.87972599, + -0.44560114 -0.16732606 -0.87945527, + -0.63390893 0.70476496 -0.31853697, + -0.62356001 0.70799398 -0.33153799, + -0.60243809 0.72283715 -0.33848909, + -0.604478 0.722184 -0.33623901, + -0.51923102 0.79404199 -0.316064, + -0.51691288 0.79440683 -0.3189339, + -0.534082 0.78456497 -0.31498301, + -0.5392319 0.78388083 -0.30783093, + -0.54758209 0.77707416 -0.31033805, + -0.54875088 0.77696884 -0.30853194, + -0.55737299 0.771649 -0.30642, + -0.55731088 0.7716518 -0.30652595, + -0.59074897 0.74579293 -0.30790997, + -0.5900861 0.74586517 -0.30900407, + -0.58096963 0.75194854 -0.31152481, + -0.57889605 0.75226414 -0.31460804, + -0.57053214 0.75958121 -0.31229705, + -0.5638907 0.76084065 -0.32116786, + -0.54482782 0.77253968 -0.32610589, + -0.54709607 0.77206409 -0.32342404, + -0.73598725 0.59906924 -0.31533912, + -0.72062278 0.60733473 -0.33443588, + -0.69793183 0.62733883 -0.34545192, + -0.70087051 0.62578255 -0.34231076, + -0.66665417 0.66177016 -0.34297609, + -0.66413981 0.66290283 -0.34565592, + -0.68659997 0.64466095 -0.33614397, + -0.70055634 0.63834232 -0.31896716, + -0.63461673 0.69363874 -0.34077388, + -0.63251275 0.69444174 -0.34304288, + -0.65457803 0.67780507 -0.33482504, + -0.66672403 0.673208 -0.31979701, + -0.22052406 0.97527522 -0.014404104, + -0.26798505 0.96339023 -0.007958632, + -0.25189891 0.96768463 -0.011544797, + -0.25158006 0.96709025 -0.038000707, + -0.29718098 0.95408487 -0.037489697, + -0.29646301 0.95297599 -0.0628203, + -0.34130588 0.93791664 -0.061827477, + -0.34007102 0.93632615 -0.087436005, + -0.38377893 0.91942489 -0.085857689, + -0.38189894 0.91738987 -0.11202198, + -0.42355314 0.89919227 -0.10980004, + -0.42093691 0.89679575 -0.13626997, + -0.46048883 0.87759173 -0.13335195, + -0.45702285 0.87491173 -0.16018593, + -0.49465901 0.854877 -0.156518, + -0.49019805 0.85198212 -0.18393601, + -0.52588111 0.8314032 -0.17949304, + -0.52026194 0.82837987 -0.20763998, + -0.55340886 0.80791581 -0.20251095, + -0.54648179 0.80487764 -0.23136489, + -0.57730228 0.78475237 -0.2255791, + -0.56882399 0.78179401 -0.25541601, + -0.59767538 0.76209748 -0.24898115, + -0.58735287 0.7593568 -0.27998894, + -0.61435694 0.74030793 -0.27296498, + -0.60271668 0.73814267 -0.30311385, + -0.62749815 0.7202552 -0.29576805, + -0.62291098 0.71982598 -0.306321, + -0.64511204 0.70307505 -0.29919204, + -0.64205283 0.70311981 -0.30559894, + -0.66220725 0.68721724 -0.29868713, + -0.65791816 0.6877262 -0.30688205, + -0.67595404 0.67298204 -0.30030203, + -0.67053926 0.67414522 -0.30968612, + -0.68615276 0.66104478 -0.30366787, + -0.67932397 0.663104 -0.31434399, + -0.69223791 0.65210795 -0.30913097, + -0.68274301 0.65568203 -0.322402, + -0.68066585 0.65741885 -0.3232559, + -0.67050296 0.66159594 -0.33573297, + -0.64783996 0.67931491 -0.34472397, + -0.64998454 0.67842555 -0.34243077, + -0.66471094 0.66695696 -0.33664197, + -0.64342624 0.67666423 -0.35795012, + -0.67325193 0.65359795 -0.34574798, + -0.67031324 0.65513724 -0.34853312, + -0.71996498 0.612701 -0.325957, + -0.72890633 0.6067453 -0.31710514, + -0.22980691 -0.88410771 -0.40686885, + -0.19893596 -0.89558578 -0.39793292, + -0.225181 -0.89038098 -0.39561999, + -0.15808794 -0.94888061 -0.2731919, + -0.17908894 -0.94542867 -0.2721979, + -0.098927923 -0.98483324 -0.14253703, + -0.11288598 -0.9833619 -0.14232399, + -0.018512599 -0.99980801 -0.0064178002, + -0.023545306 -0.99970222 -0.0064171213, + 0.080437064 -0.98861551 0.12715794, + 0.08582896 -0.98816955 0.12709995, + 0.19755705 -0.94649124 0.25519705, + 0.214523 -0.94304198 0.25426701, + 0.30345297 -0.88815087 0.34511498, + 0.3294999 -0.88004977 0.34196791, + 0.39270899 -0.82845497 0.39930201, + 0.42051309 -0.81730616 0.39392808, + 0.38798401 -0.84509599 0.36780599, + 0.38668007 -0.8455981 0.36802503, + 0.36122108 -0.86413217 0.3504211, + 0.35131097 -0.86763388 0.35184097, + 0.31930909 -0.88732022 0.33272308, + 0.29770097 -0.89388287 0.33518296, + 0.25727591 -0.91385573 0.31412888, + 0.21851203 -0.92283612 0.31721604, + 0.17224406 -0.93959934 0.29577911, + 0.11115898 -0.94794387 0.29840598, + 0.062779486 -0.95856678 0.27786395, + -0.02656761 -0.96012235 0.2783151, + -0.071287997 -0.96293002 0.26016101, + -0.19252108 -0.94732636 0.2559461, + -0.22574197 -0.94357085 0.24231097, + -0.37399697 -0.89828289 0.23068197, + -0.39094308 -0.89294821 0.22317506, + -0.55318606 -0.80819809 0.20199303, + -0.55263978 -0.80850166 0.20227291, + -0.70981115 -0.68333119 0.17095804, + -0.69855094 -0.69303393 0.17813098, + -0.83314782 -0.53563988 0.13767597, + -0.8189109 -0.55401397 0.14984499, + -0.91952026 -0.37941009 0.10261902, + -0.90876889 -0.40077895 0.11625499, + -0.97247761 -0.22377193 0.064909779, + -0.96762776 -0.24071895 0.075834982, + -0.99712211 -0.072309606 0.022780102, + -0.99650937 -0.078915328 0.02723101, + -0.99721354 0.070519961 -0.024333989, + -0.99656725 0.077420019 -0.029323008, + -0.9752745 0.2066699 -0.078276865, + -0.9692961 0.22702603 -0.094468415, + -0.93342 0.33125201 -0.13783801, + -0.91814822 0.36062708 -0.16417104, + -0.87514657 0.44037279 -0.20047492, + -0.84849143 0.47397023 -0.23540312, + -0.80463618 0.53179014 -0.26412106, + -0.78320128 0.55104816 -0.28799608, + -0.76402903 0.56173998 -0.31734499, + -0.70385736 0.61847228 -0.34939519, + -0.70937204 0.61512005 -0.34412003, + -0.67568105 0.64336103 -0.35991904, + -0.69924796 0.63081896 -0.33633298, + -0.68308932 0.64445728 -0.34360415, + -0.68096608 0.64549404 -0.34586504, + -0.70334792 0.62656993 -0.33572596, + -0.71513474 0.62079674 -0.32123789, + -0.71637017 0.61967212 -0.32065609, + -0.72722185 0.61470687 -0.30542395, + -0.71293104 0.62798905 -0.31202403, + -0.72085321 0.62497026 -0.29963812, + -0.70469582 0.63977784 -0.30673793, + -0.71097744 0.63793236 -0.29589418, + -0.69273603 0.65424001 -0.30345801, + -0.69781679 0.65323478 -0.29382989, + -0.67728281 0.67096984 -0.30180693, + -0.68106103 0.67061597 -0.29398999, + -0.65851796 0.68924296 -0.30215597, + -0.6636768 0.68930483 -0.29050294, + -0.63936472 0.70854962 -0.29861385, + -0.6513887 0.70977366 -0.26816788, + -0.62497771 0.73025864 -0.27590787, + -0.63566804 0.73214805 -0.24471503, + -0.60710585 0.75363785 -0.25189793, + -0.61592305 0.75589013 -0.22196603, + -0.58564597 0.77772897 -0.228378, + -0.59288174 0.78019267 -0.19947593, + -0.56069618 0.80221629 -0.20510708, + -0.56661183 0.8047657 -0.17692694, + -0.53208888 0.82693982 -0.18180196, + -0.5368228 0.82944971 -0.15438394, + -0.49980605 0.85151315 -0.15849102, + -0.50351882 0.85389072 -0.13167895, + -0.46460694 0.8751719 -0.13496098, + -0.46744317 0.87733632 -0.10852604, + -0.42666405 0.89756912 -0.11102901, + -0.42872715 0.89943331 -0.084927827, + -0.38595515 0.91843235 -0.086721733, + -0.38733199 0.91990501 -0.061226599, + -0.34272197 0.93736291 -0.062388591, + -0.34353712 0.93840235 -0.037193414, + -0.29798096 0.95382285 -0.037804596, + -0.29836997 0.95439887 -0.0099079888, + -0.31499285 0.94898754 -0.014212294, + -0.3150211 0.94897825 -0.014212104, + -0.31505296 0.9490729 -0.0014993898, + -0.31502384 0.94908249 -0.0015023493, + -0.40648991 0.91365278 -0.0021228495, + -0.400455 0.91631198 -0.00284775, + -0.361213 0.93248302 0.00077759102, + -0.40649399 0.91364402 -0.0041613402, + -0.40645906 0.9135651 -0.013778302, + -0.40645209 0.91356826 -0.013778403, + -0.81145197 0.50436002 -0.29524001, + -0.79421264 0.51750076 -0.31846386, + -0.77489012 0.53832906 -0.33128104, + -0.78030521 0.53429115 -0.3250491, + -0.8223536 0.56893271 -0.0070683467, + -0.82182014 0.56906104 -0.027952204, + -0.849397 0.52711898 -0.025892001, + -0.84846801 0.52740198 -0.044150501, + -0.87334859 0.48539776 -0.040634181, + -0.87202168 0.48592982 -0.058740478, + -0.89446378 0.44390887 -0.053660788, + -0.89276487 0.44476295 -0.071810894, + -0.91315424 0.40240309 -0.064971417, + -0.91118729 0.40361416 -0.082663432, + -0.92975241 0.36069819 -0.07387384, + -0.92760324 0.36230808 -0.09102232, + -0.94433075 0.3190819 -0.08016248, + -0.9420839 0.32112396 -0.096733086, + -0.95716554 0.2772359 -0.083512664, + -0.95491898 0.279726 -0.099413797, + -0.96853113 0.23452203 -0.083348505, + -0.96642345 0.23741812 -0.098277844, + -0.97865248 0.18989609 -0.078606337, + -0.97683161 0.19310893 -0.092243969, + -0.98737901 0.14290801 -0.068264097, + -0.98600763 0.14622194 -0.080049872, + -0.99452478 0.091663375 -0.05018159, + -0.99380255 0.094444655 -0.058624171, + -0.99924749 0.032955814 -0.02045651, + -0.9991641 0.033877105 -0.022881903, + -0.99904412 -0.036225703 0.024468305, + -0.99892163 -0.037484385 0.027393291, + -0.98832542 -0.12301093 0.08989495, + -0.9863379 -0.12900199 0.10244998, + -0.95385987 -0.23512398 0.18672998, + -0.94341302 -0.250608 0.217181, + -0.10375205 -0.64412832 0.75784838, + 0.087036096 -0.64516592 0.75906891, + 0.27270806 -0.66254318 0.69761521, + 0.64121938 -0.55867738 0.5260393, + 0.52639967 -0.58852857 0.6136266, + 0.38964906 -0.63748509 0.66467005, + 0.26240388 -0.6388557 0.72319263, + 0.13372302 -0.65610904 0.74272406, + -0.023158303 -0.62294704 0.78192115, + -0.17784904 -0.6131801 0.7696622, + -0.204261 -0.60197097 0.77195102, + -0.24187203 -0.59667706 0.76516312, + -0.27899694 -0.57700586 0.76760983, + -0.29983389 -0.57321984 0.76257372, + -0.31610197 -0.56301892 0.76360285, + -0.32652509 -0.56092012 0.76075619, + -0.30691588 -0.57449579 0.75878668, + -0.31770089 -0.57235581 0.75595969, + -0.30391404 -0.58261204 0.75379014, + -0.31365904 -0.58067703 0.7512871, + -0.30342403 -0.58890307 0.74908406, + -0.31143612 -0.58730322 0.74704921, + -0.30415484 -0.5936377 0.74503964, + -0.31010586 -0.59244072 0.74353766, + -0.30416998 -0.59803694 0.74150693, + -0.30812103 -0.59723908 0.74051803, + -0.30338103 -0.60208905 0.73854506, + -0.30500397 -0.60176092 0.73814392, + -0.30171913 -0.60541725 0.73650223, + -0.30085295 -0.60559088 0.73671383, + -0.29825088 -0.60874975 0.73516679, + -0.29532588 -0.60932976 0.73586679, + -0.29256904 -0.61298805 0.73392707, + -0.28687701 -0.61409199 0.73525, + -0.28403082 -0.61823463 0.73287958, + -0.27615303 -0.61971706 0.73463607, + -0.27296796 -0.62482291 0.73149496, + -0.26243702 -0.62672406 0.73371905, + -0.25857708 -0.63357222 0.72919422, + -0.24613804 -0.63570005 0.73164308, + -0.241979 -0.64391202 0.72582603, + -0.22706097 -0.64630091 0.72851795, + -0.22251593 -0.65637577 0.72087276, + -0.205274 -0.65891701 0.723665, + -0.20064695 -0.67057282 0.71419382, + -0.18149398 -0.67312497 0.71691191, + -0.17711398 -0.68586195 0.70584995, + -0.15624496 -0.68832082 0.70837981, + -0.152144 -0.70239502 0.695337, + -0.12939703 -0.70469415 0.69761217, + -0.12576498 -0.71987796 0.68261194, + -0.10142495 -0.72189766 0.68452668, + -0.09832982 -0.73845917 0.66709018, + -0.073123492 -0.74006891 0.66854393, + -0.071571335 -0.75166237 0.6556533, + -0.043255385 -0.75288969 0.65672374, + -0.032916389 -0.85959071 0.50992185, + -0.011034706 -0.86000443 0.51016724, + -0.0060780225 -0.95705134 0.28985509, + 0.0056502284 -0.95705366 0.2898559, + 0.010666403 -0.85959119 0.51087111, + 0.032586087 -0.85918361 0.51062876, + 0.042976879 -0.75126964 0.65859473, + 0.071793787 -0.75002384 0.65750283, + 0.07316789 -0.73973095 0.66891295, + 0.098394588 -0.73811996 0.66745591, + 0.10138395 -0.72211766 0.68430072, + 0.12589899 -0.72008193 0.68237191, + 0.12957202 -0.70475608 0.69751704, + 0.15226607 -0.70246035 0.69524437, + 0.15636908 -0.68840533 0.70827037, + 0.17722891 -0.68594569 0.70573962, + 0.18167506 -0.67303222 0.71695322, + 0.20056105 -0.67051518 0.7142722, + 0.20509596 -0.6590988 0.72354984, + 0.22255293 -0.65652579 0.72072476, + 0.22698794 -0.64671081 0.72817683, + 0.24157891 -0.64437574 0.72554779, + 0.24587697 -0.63589793 0.73155892, + 0.25855407 -0.63373017 0.72906518, + 0.26226401 -0.62715697 0.73341101, + 0.27248394 -0.62531382 0.73125583, + 0.27568293 -0.62019086 0.73441285, + 0.28379092 -0.61866677 0.73260778, + 0.2864691 -0.61477625 0.73483723, + 0.29207906 -0.61368811 0.7335372, + 0.29485613 -0.61001027 0.73549122, + 0.29743198 -0.60949993 0.73487693, + 0.30031112 -0.60601121 0.73658925, + 0.30088001 -0.60589701 0.73645103, + 0.30418915 -0.60221928 0.73810637, + 0.30281693 -0.60249591 0.73844481, + 0.30731797 -0.59789795 0.74031997, + 0.30328012 -0.59871125 0.74132723, + 0.30935204 -0.59299606 0.74340904, + 0.30295688 -0.59427875 0.74501675, + 0.31133085 -0.58700073 0.74733067, + 0.30375111 -0.58851421 0.74925727, + 0.31419897 -0.58011192 0.75149786, + 0.3050501 -0.58193219 0.7538563, + 0.31902885 -0.57151473 0.75603664, + 0.30802497 -0.57370591 0.75893486, + 0.32962584 -0.55869877 0.76105362, + 0.31913102 -0.56082803 0.76395512, + 0.30898702 -0.56725603 0.7633791, + 0.2908648 -0.57065457 0.76795244, + 0.23564397 -0.60005695 0.76446289, + 0.19694801 -0.60535097 0.77120799, + 0.17231295 -0.61567473 0.76892972, + 0.10919297 -0.62128687 0.7759378, + 0.027257806 -0.6451292 0.76358718, + -0.076429293 -0.64348096 0.76163685, + -0.26627901 -0.66240299 0.70022702, + -0.64263004 -0.55823505 0.52478606, + -0.52910709 -0.5880301 0.61177313, + -0.39262185 -0.63733178 0.66306579, + -0.25596008 -0.63863325 0.72569424, + -0.12786403 -0.65521818 0.74454015, + 0.037175596 -0.61918592 0.78436387, + 0.11159998 -0.61574292 0.78000391, + 0.17949198 -0.58900791 0.78794187, + 0.22197306 -0.58379513 0.78096819, + 0.24084988 -0.57419068 0.78249365, + 0.26816109 -0.56993818 0.77669829, + 0.31314814 -0.54229325 0.77965134, + 0.32466018 -0.54008132 0.7764715, + 0.33307591 -0.53408891 0.77705181, + 0.33909479 -0.53287268 0.77528155, + 0.32141596 -0.54659593 0.77325588, + 0.32702196 -0.54548693 0.77168685, + 0.31545296 -0.55510694 0.76963991, + 0.32067415 -0.55408221 0.76821935, + 0.31136706 -0.56241411 0.7659902, + 0.31575203 -0.56155705 0.76482314, + 0.30813012 -0.56891918 0.76248729, + 0.31050688 -0.56845683 0.7618677, + 0.30479187 -0.57442784 0.75969368, + 0.30537584 -0.57431471 0.75954467, + 0.30041897 -0.57993191 0.75724989, + 0.29935986 -0.58013368 0.75751466, + 0.29539007 -0.58502513 0.75530815, + 0.29223496 -0.58561891 0.75607491, + 0.28882802 -0.59019804 0.75382012, + 0.28313097 -0.59124595 0.7551589, + 0.27953717 -0.59653836 0.75233048, + 0.27207199 -0.59786898 0.75400901, + 0.26825395 -0.6040529 0.75043982, + 0.25835103 -0.60574806 0.75254512, + 0.25442705 -0.61277515 0.74818015, + 0.242218 -0.61475903 0.75060099, + 0.23791502 -0.62333906 0.74487907, + 0.223701 -0.625503 0.74746501, + 0.21908203 -0.63584304 0.74007207, + 0.20241396 -0.63818485 0.74279779, + 0.19771396 -0.6501478 0.7336328, + 0.17933491 -0.6524877 0.73627365, + 0.17485595 -0.66564578 0.72549379, + 0.15437002 -0.66795719 0.72801316, + 0.15021102 -0.68238509 0.71539307, + 0.12803896 -0.68453574 0.71764678, + 0.12435696 -0.70010877 0.70312375, + 0.10046898 -0.70201582 0.70503885, + 0.097368263 -0.71882778 0.68833578, + 0.072445676 -0.72036177 0.68980473, + 0.070176058 -0.73745859 0.6717366, + 0.043516796 -0.73858094 0.67275894, + 0.042615887 -0.74995577 0.66011375, + 0.014265802 -0.75056112 0.66064703, + 0.010753297 -0.85979581 0.51052487, + -0.010944899 -0.8597939 0.51052392, + -0.014420496 -0.75102884 0.66011184, + -0.042577989 -0.75042582 0.65958184, + -0.043504298 -0.73874193 0.67258292, + -0.069912829 -0.73763233 0.67157328, + -0.072218239 -0.72021735 0.68997937, + -0.097476438 -0.71866423 0.68849123, + -0.10052 -0.70215201 0.70489597, + -0.12440103 -0.70024419 0.70298117, + -0.128085 -0.68466002 0.71752, + -0.15029196 -0.68250483 0.71526182, + -0.15451501 -0.66784406 0.72808605, + -0.17452699 -0.66558796 0.72562593, + -0.179085 -0.65216303 0.73662198, + -0.19774297 -0.64978993 0.73394191, + -0.20244595 -0.6377998 0.74311984, + -0.21916394 -0.63545179 0.7403838, + -0.22377597 -0.62510794 0.74777293, + -0.23803894 -0.6229369 0.74517584, + -0.24235 -0.61432701 0.75091201, + -0.25458902 -0.61233908 0.74848205, + -0.25849512 -0.60533327 0.75282937, + -0.26871997 -0.60358196 0.7506519, + -0.27252278 -0.59741557 0.75420547, + -0.28002399 -0.59607702 0.75251502, + -0.28360283 -0.59080166 0.75532955, + -0.28935903 -0.58974105 0.75397414, + -0.29272997 -0.58520496 0.75620389, + -0.29592714 -0.5846023 0.75542533, + -0.30009311 -0.57946116 0.75773931, + -0.30120006 -0.57924914 0.7574622, + -0.30613196 -0.57365096 0.7597419, + -0.30559695 -0.57375491 0.75987881, + -0.31119812 -0.56789416 0.76200527, + -0.30889198 -0.56834394 0.76260787, + -0.31557184 -0.56188774 0.76465464, + -0.31149611 -0.56268418 0.76573932, + -0.32030711 -0.55480015 0.76785427, + -0.31496009 -0.55584913 0.76930618, + -0.32635397 -0.54638696 0.77133286, + -0.32016298 -0.54760891 0.77305889, + -0.33648089 -0.53498185 0.77496773, + -0.33004308 -0.53627515 0.77684015, + -0.31651402 -0.54582107 0.77582109, + -0.303875 -0.54819399 0.779194, + -0.27375016 -0.56664836 0.77715546, + -0.2473 -0.57085401 0.78292298, + -0.22802907 -0.58076519 0.78148228, + -0.10726202 -0.5930391 0.79799718, + 0.027984507 -0.63665217 0.77064317, + 0.12409694 -0.63197869 0.76498562, + 0.25138801 -0.64848298 0.71852201, + 0.38495108 -0.61836714 0.68515319, + 0.49561477 -0.60852772 0.6197257, + 0.64068615 -0.53794712 0.54784513, + 0.70976216 -0.51273912 0.48304912, + 0.82763386 -0.40852794 0.38487294, + 0.85939389 -0.38463995 0.33688897, + 0.94520915 -0.24558602 0.21509802, + 0.61375207 0.78939915 -0.012546401, + 0.86238486 0.42679593 -0.27228197, + 0.87565774 0.4137609 -0.24904893, + 0.85152817 0.44921112 -0.27038705, + 0.56543064 0.82270652 -0.058669668, + 0.60505605 0.79416615 -0.056634407, + 0.60319108 0.79345214 -0.08120551, + 0.64049816 0.76396918 -0.078188121, + 0.6379168 0.76321185 -0.10280897, + 0.67320871 0.73283362 -0.098716952, + 0.66982895 0.73213196 -0.12374198, + 0.70314908 0.70109904 -0.11849701, + 0.69888222 0.70056623 -0.14412004, + 0.72991478 0.66951776 -0.13773295, + 0.72470915 0.6692822 -0.16388404, + 0.75363028 0.63843721 -0.15633106, + 0.74739498 0.638641 -0.183135, + 0.77480769 0.60770476 -0.17426394, + 0.767456 0.60851902 -0.201782, + 0.79364532 0.57746118 -0.19148308, + 0.78504431 0.57909715 -0.21989107, + 0.80989915 0.54836714 -0.20822304, + 0.7998957 0.55106384 -0.23768792, + 0.82384515 0.52046508 -0.22448903, + 0.81265873 0.52438581 -0.2541759, + 0.83611518 0.49362311 -0.23926505, + 0.82941985 0.49666095 -0.25571597, + 0.85220611 0.46517006 -0.23950303, + 0.84646618 0.46853012 -0.25293207, + 0.86843771 0.43628484 -0.23552391, + 0.86164057 0.4412398 -0.25076488, + 0.88341689 0.40739295 -0.23152897, + 0.88234878 0.40836293 -0.23388094, + 0.8419708 0.46817487 -0.26813695, + 0.85015357 0.46230778 -0.25201288, + 0.82895058 0.49109575 -0.26770487, + 0.83587843 0.48701525 -0.25322613, + 0.81395048 0.51542431 -0.26799715, + 0.81966299 0.512779 -0.25536299, + 0.79696101 0.540694 -0.26926401, + 0.80375612 0.53835207 -0.25328502, + 0.77994412 0.56630307 -0.26643604, + 0.79174781 0.56334686 -0.23616894, + 0.76711166 0.59162772 -0.24802488, + 0.77757233 0.58981228 -0.2179511, + 0.75166732 0.61865526 -0.22860907, + 0.76059198 0.61778998 -0.199588, + 0.73361015 0.64666116 -0.20891504, + 0.74116516 0.64650416 -0.18085004, + 0.71276706 0.67547005 -0.18895303, + 0.71911895 0.67582792 -0.16163099, + 0.68873018 0.70513219 -0.16864005, + 0.69398493 0.70584393 -0.14201899, + 0.66139483 0.73530179 -0.14794597, + 0.66566473 0.73623079 -0.12187996, + 0.63114995 0.76524585 -0.12668298, + 0.63450181 0.76626182 -0.10124398, + 0.59803176 0.79456669 -0.10498396, + 0.60056567 0.79556453 -0.079987258, + 0.56181395 0.82311386 -0.08275719, + 0.56362504 0.82400411 -0.057829008, + 0.52236986 0.85062683 -0.059697386, + 0.4364239 0.89967877 -0.010599397, + 0.44799489 0.89392078 -0.014357796, + 0.44796094 0.89393789 -0.014353798, + 0.44800684 0.89402968 0.00089896563, + 0.44804084 0.89401269 0.00089896563, + 0.49122912 0.87091619 -0.014106404, + 0.49127612 0.87099916 -0.0028535007, + 0.44800207 0.89403212 0.00090074411, + 0.44795614 0.89394027 -0.014358005, + 0.48112983 0.87658572 -0.010567896, + 0.48059106 0.8762061 -0.035988003, + 0.52350491 0.85130489 -0.034965195, + 0.5250662 0.85096431 -0.012853105, + 0.52453911 0.85064816 -0.035444707, + 0.56661105 0.8232711 -0.034304004, + 0.5682078 0.82281572 -0.010685897, + 0.56762892 0.82254887 -0.034795497, + 0.60810512 0.79314721 -0.033551808, + 0.606893 0.79269898 -0.0575254, + 0.64499092 0.76218587 -0.055311091, + 0.64309907 0.7616511 -0.07944341, + 0.67910576 0.73007977 -0.076150373, + 0.67651397 0.72956896 -0.10028999, + 0.71051818 0.69712317 -0.095830023, + 0.70715618 0.6967392 -0.12035203, + 0.73875725 0.66413623 -0.11472104, + 0.73455691 0.66399294 -0.13978398, + 0.76395833 0.63142532 -0.13292806, + 0.7588799 0.63165092 -0.15848799, + 0.78661412 0.59888107 -0.15026602, + 0.78059679 0.5996269 -0.17639795, + 0.80696887 0.56658596 -0.16667798, + 0.79994988 0.56802696 -0.19345698, + 0.82484943 0.53516626 -0.18226509, + 0.81672621 0.53750312 -0.20987804, + 0.84046412 0.50475305 -0.19709003, + 0.83114088 0.50823092 -0.22562397, + 0.85436118 0.47497812 -0.21086204, + 0.84402382 0.47976989 -0.23967594, + 0.86719388 0.44547594 -0.22254397, + 0.8608138 0.44917488 -0.23925194, + 0.88307399 0.414148 -0.220594, + 0.87758821 0.41815808 -0.23448406, + 0.89932227 0.38141215 -0.21387908, + 0.89305979 0.38707691 -0.22938094, + 0.91499591 0.34709498 -0.20568797, + 0.90731359 0.35555282 -0.22441989, + 0.91374642 0.34357014 -0.21685711, + 0.91192991 0.34594196 -0.22069897, + 0.8614583 0.42009914 -0.28531808, + 0.89600122 0.36734009 -0.24948606, + 0.99179554 -0.10305895 0.075633265, + 0.99728012 -0.062047806 0.039780103, + 0.99220479 0.10490898 -0.067259386, + 0.98852438 0.12452904 -0.085511133, + 0.93080562 0.30131587 -0.20690493, + 0.9243331 0.31272104 -0.21866404, + 0.88517398 0.38129401 -0.26661199, + 0.86131614 0.42278007 -0.28176504, + 0.82823455 0.4663108 -0.31077585, + 0.84076983 0.45425689 -0.29454494, + 0.820889 0.479173 -0.3107, + 0.84397715 0.45889512 -0.27770105, + 0.82406259 0.48466375 -0.29329485, + 0.83680016 0.47451213 -0.27313706, + 0.81723249 0.49947229 -0.28750417, + 0.82771099 0.492203 -0.269501, + 0.80776113 0.51707405 -0.28311902, + 0.8159281 0.51229805 -0.26797804, + 0.7952159 0.53726196 -0.28103596, + 0.80201191 0.53405297 -0.26751497, + 0.7806747 0.55875683 -0.2798889, + 0.78611469 0.55680984 -0.26830292, + 0.76354331 0.58174217 -0.2803171, + 0.77021152 0.58009166 -0.26508084, + 0.74607515 0.60562509 -0.27674907, + 0.75824928 0.60371321 -0.2461471, + 0.73278701 0.63009799 -0.25690401, + 0.74354023 0.62920523 -0.22638208, + 0.71716821 0.65574825 -0.2359321, + 0.72625238 0.6556713 -0.2065251, + 0.69848108 0.68256909 -0.21499702, + 0.70612097 0.68308192 -0.18652698, + 0.67647278 0.71045578 -0.19400293, + 0.68284321 0.71138316 -0.16631104, + 0.65106279 0.73909473 -0.17278995, + 0.65629071 0.74028462 -0.14581193, + 0.62267029 0.76773334 -0.15121907, + 0.62687898 0.76905102 -0.124833, + 0.59130806 0.79602712 -0.12921202, + 0.59458494 0.79734886 -0.10345799, + 0.55670112 0.82380718 -0.10689102, + 0.55915606 0.8250401 -0.081568606, + 0.51886606 0.85070813 -0.084106304, + 0.52060086 0.85176581 -0.058904286, + 0.47854689 0.87596977 -0.060578085, + 0.47962299 0.87675399 -0.035555899, + 0.4359161 0.89924824 -0.036468107, + 0.3908999 0.92037076 -0.010718297, + 0.39043286 0.91989166 -0.036897685, + 0.43503305 0.8996911 -0.036087405, + 0.4340308 0.89880961 -0.061308071, + 0.47679412 0.87697726 -0.059818916, + 0.47515595 0.87576085 -0.085262395, + 0.51627797 0.85239089 -0.082987092, + 0.51393116 0.85093433 -0.10856104, + 0.55326611 0.82630718 -0.10541902, + 0.55010581 0.82469171 -0.13140495, + 0.58698577 0.79951173 -0.12739195, + 0.58289188 0.79782182 -0.15400498, + 0.61744905 0.77235311 -0.14908901, + 0.61232024 0.77070028 -0.17631006, + 0.6449728 0.74496084 -0.17042096, + 0.63867199 0.74346799 -0.198377, + 0.66955096 0.71765792 -0.19149096, + 0.66194391 0.71647692 -0.22020698, + 0.69071478 0.69121677 -0.21244393, + 0.68160582 0.69050884 -0.24209695, + 0.708561 0.66590703 -0.233472, + 0.69771034 0.66586131 -0.26425213, + 0.72334403 0.64179498 -0.25470099, + 0.71102577 0.64263576 -0.2854149, + 0.73561996 0.61908293 -0.27495396, + 0.72925335 0.62008327 -0.28928614, + 0.75180984 0.59755087 -0.27877393, + 0.74681079 0.59887087 -0.28918394, + 0.76769084 0.57706386 -0.27865395, + 0.76130933 0.5794332 -0.2909731, + 0.7808798 0.55824691 -0.28033394, + 0.77309769 0.56193882 -0.29418489, + 0.79187191 0.54103094 -0.28323898, + 0.78174263 0.54682177 -0.29977384, + 0.79930049 0.52694333 -0.28887618, + 0.78695989 0.53509092 -0.30719998, + 0.80341315 0.51637411 -0.29645407, + 0.78049183 0.53298187 -0.3267459, + 0.79356933 0.51875615 -0.31802511, + 0.78031111 0.52906108 -0.33348003, + 0.82648885 0.47623995 -0.30018598, + 0.80479819 0.49614713 -0.32578808, + 0.86110157 0.42499879 -0.27906987, + 0.86814588 0.41660193 -0.26975098, + 0.93118858 0.30599284 -0.1981319, + 0.94972998 0.268204 -0.161492, + 0.99225891 0.10638899 -0.064059496, + 0.99428475 0.093044676 -0.052349091, + 0.99228811 -0.10802902 0.060779408, + 0.90587288 -0.35999098 0.22316097, + 0.95279109 -0.26651302 0.14546502, + 0.99328703 -0.101536 0.0554194, + 0.99423265 -0.095594764 0.048612382, + 0.94229949 -0.29840416 0.15174608, + 0.78969085 -0.53457391 0.30102998, + 0.85890687 -0.45570594 0.23368996, + 0.94034952 -0.30272585 0.15524092, + 0.94850045 -0.28593981 0.13632792, + 0.85122216 -0.47371912 0.22585607, + 0.84265172 -0.48455581 0.23482691, + 0.70856392 -0.63500696 0.30773896, + 0.68749404 -0.65060508 0.32259104, + 0.54169202 -0.75308597 0.37340501, + 0.50776982 -0.7674787 0.39133886, + 0.359624 -0.83126903 0.423866, + 0.10846598 -0.88466889 0.45342693, + 0.029196193 -0.88953978 0.45592389, + -0.028649405 -0.87858009 0.47673506, + -0.064835683 -0.87709177 0.47592688, + -0.118831 -0.86040199 0.49556801, + -0.13969897 -0.8580448 0.49420989, + -0.18734404 -0.83809221 0.5123511, + -0.19779097 -0.83634287 0.51128197, + -0.23958898 -0.81450289 0.52837694, + -0.24170594 -0.81406283 0.52809089, + -0.27759895 -0.79171282 0.54417789, + -0.28776494 -0.78924382 0.54248089, + -0.91175872 0.35973489 -0.19820893, + -0.90596873 0.36500588 -0.21445593, + -0.9292801 0.31847402 -0.18711701, + -0.9100939 0.35252497 -0.21784197, + -0.90811598 0.35465601 -0.22258601, + -0.94278914 0.28238204 -0.17722602, + -0.94409078 0.28045794 -0.17330895, + -0.99726051 -0.057689775 0.046296578, + -0.96192586 -0.21315797 0.17106198, + -0.94692612 -0.24746303 0.20516603, + 0.28294191 -0.77094072 0.57060879, + 0.27355409 -0.7731263 0.57222718, + 0.24008709 -0.7943843 0.55795318, + 0.23811799 -0.79478103 0.55823201, + 0.20011403 -0.81524611 0.54344106, + 0.19084595 -0.81678385 0.54446489, + 0.14757502 -0.83581513 0.52880508, + 0.10931802 -0.84000313 0.53145504, + -0.21750107 -0.81639928 0.53496319, + -0.35131109 -0.78310817 0.51314914, + -0.38459408 -0.77635819 0.49935511, + -0.51214308 -0.72237504 0.46463305, + -0.47128901 -0.73673803 0.48487499, + -0.58737487 -0.67603981 0.44492787, + -0.54517025 -0.69513637 0.4685882, + -0.62782121 -0.64541119 0.43506908, + 0.27018592 -0.70185578 0.65908879, + 0.262252 -0.703453 0.66058898, + 0.23734112 -0.71904337 0.65318131, + 0.23567697 -0.71934295 0.65345395, + 0.20784393 -0.73450178 0.64599377, + -0.313023 -0.69844401 0.64357799, + -0.14506102 -0.70596409 0.69323307, + 0.010876195 -0.71346867 0.70060265, + 0.025193406 -0.7111842 0.70255417, + 0.12664102 -0.70568204 0.69711906, + 0.046378486 -0.72518378 0.68699175, + 0.13144498 -0.71966583 0.68176484, + 0.080034479 -0.73457682 0.67378885, + 0.14972799 -0.72863293 0.66833794, + 0.11343002 -0.74112809 0.66171205, + 0.17167906 -0.73486722 0.65612227, + 0.14527595 -0.74547774 0.65050578, + 0.19307496 -0.73929381 0.64510983, + 0.20085397 -0.73559797 0.64695692, + 0.17351002 -0.7547881 0.63260508, + 0.19635305 -0.75149316 0.62984419, + 0.22728898 -0.73517692 0.63863492, + 0.22963899 -0.73475999 0.63827401, + 0.25668603 -0.71822506 0.64673406, + 0.25504494 -0.71854782 0.64702481, + 0.27994391 -0.70120174 0.65570378, + 0.28455096 -0.70021194 0.65477794, + 0.58836299 -0.62340999 0.514965, + 0.53090584 -0.64809877 0.54599184, + 0.65694726 -0.5765962 0.48575419, + 0.58542699 -0.61338198 0.53013003, + 0.8390547 -0.41161785 0.35574988, + 0.90790433 -0.32258311 0.2676751, + 0.79639918 -0.46540913 0.38619009, + 0.74680895 -0.51767296 0.41748193, + 0.71612382 -0.54019588 0.44198987, + 0.81924009 -0.44382206 0.36313602, + 0.79985386 -0.46704593 0.37696394, + 0.8828696 -0.36543682 0.29495284, + 0.86845028 -0.38377213 0.31386811, + 0.96684426 -0.19767505 0.16166905, + 0.99829775 -0.04477229 0.037375692, + 0.96985263 -0.18707494 0.15616894, + 0.97063166 -0.18496694 0.15382294, + 0.90631533 -0.32492512 0.27021509, + 0.87656128 -0.37172312 0.30571613, + 0.85392702 -0.39818099 0.335053, + 0.71438897 -0.53541595 0.45053095, + 0.74344683 -0.51457888 0.42719492, + 0.62348276 -0.60155475 0.49940082, + 0.72415304 -0.53988707 0.42909706, + 0.59578997 -0.62874192 0.49971795, + 0.65840483 -0.5954749 0.46033987, + 0.51403683 -0.67862874 0.5246228, + 0.57034111 -0.65573919 0.49468911, + 0.43797314 -0.71767223 0.54141116, + 0.48849875 -0.70214963 0.51802975, + 0.36889404 -0.74794203 0.55181503, + 0.41522706 -0.73748004 0.53264403, + 0.28935593 -0.77598983 0.56045789, + 0.25676993 -0.77920473 0.57175982, + 0.13634592 -0.79870653 0.58606964, + 0.71595478 -0.60006773 0.35682988, + 0.63716799 -0.66245002 0.39392501, + 0.66822904 -0.64337707 0.37354502, + 0.56321901 -0.71459597 0.41489401, + 0.27261195 -0.81870383 0.50537789, + 0.39464194 -0.78186786 0.48263896, + 0.42928609 -0.77295119 0.46718311, + 0.55600291 -0.71134192 0.42994595, + 0.52162498 -0.72583401 0.44841099, + 0.63137376 -0.65973479 0.40757486, + 0.59510434 -0.67911142 0.42971927, + 0.70869184 -0.59618789 0.3772479, + 0.75257528 -0.5532012 0.35721013, + 0.87920201 -0.400258 0.258452, + 0.83377182 -0.45578787 0.31157994, + 0.90655899 -0.348443 0.238198, + 0.95180851 -0.24552588 0.18378691, + 0.88149285 -0.37802193 0.28296596, + 0.90453476 -0.34495792 0.25064093, + 0.79913336 -0.48633423 0.35336217, + 0.83161587 -0.45354795 0.32048297, + 0.71516877 -0.5708248 0.40335184, + 0.78743201 -0.51237702 0.34266701, + 0.62435722 -0.64931321 0.43424714, + 0.63210005 -0.64304405 0.43237007, + 0.54808384 -0.69411075 0.46670583, + 0.58863813 -0.67562717 0.4438841, + 0.47424513 -0.73579919 0.48341611, + 0.51393914 -0.72172618 0.46365711, + 0.38646701 -0.77597302 0.49850699, + 0.35036999 -0.78331298 0.51348001, + 0.21632987 -0.81652254 0.53524971, + 0.28148681 -0.74965656 0.59898263, + 0.27300707 -0.7515682 0.60051012, + 0.24225394 -0.77163684 0.58812386, + 0.24124987 -0.77183563 0.58827573, + 0.20769103 -0.7906341 0.57598805, + 0.20019403 -0.7918961 0.57690805, + 0.16090199 -0.81023401 0.56358802, + 0.12738803 -0.81424218 0.56637609, + 0.28187796 -0.72593093 0.62735093, + 0.27535591 -0.72736275 0.62858778, + 0.24749804 -0.74612707 0.61809307, + 0.24790008 -0.74604821 0.61802721, + 0.21735796 -0.76390588 0.60762095, + 0.21225102 -0.76478511 0.60832006, + 0.17728609 -0.78212434 0.59737033, + 0.14906693 -0.78583366 0.60020369, + -0.8780247 -0.36313787 0.31177488, + -0.66283596 -0.56810796 0.48775193, + -0.729864 -0.52455699 0.43833601, + -0.60474187 -0.61113685 0.51068491, + -0.71689624 -0.54499221 0.43479115, + -0.58625114 -0.63328516 0.5052321, + -0.6493662 -0.60067111 0.46638811, + -0.13490503 -0.79841417 0.58680111, + -0.25361794 -0.7794348 0.5728519, + -0.28665599 -0.776263 0.56146598, + -0.41240907 -0.73815209 0.53390104, + -0.36382896 -0.74892795 0.55383694, + -0.48367694 -0.70372593 0.52040994, + -0.43057892 -0.71967882 0.54466885, + -0.563398 -0.65878499 0.49858299, + -0.50316179 -0.68259269 0.52999574, + -0.25638804 -0.70589209 0.66028905, + -0.31460592 -0.70446181 0.63620484, + -0.29145795 -0.70788181 0.64339381, + -0.41418299 -0.67355198 0.61219299, + -0.53198504 -0.63711607 0.55774105, + -0.64773166 -0.57324666 0.50182873, + -0.64567965 -0.57433063 0.5032317, + -0.61556792 -0.59384495 0.51809692, + -0.57073194 -0.61368996 0.54557294, + -0.45759499 -0.66452903 0.59076899, + -0.33776397 -0.69167894 0.63835394, + -0.2170399 -0.71734864 0.66204572, + -0.30435199 -0.708148 0.63709998, + -0.18369798 -0.73076493 0.65744793, + -0.27113396 -0.72452396 0.63368094, + -0.27974093 -0.73209882 0.62110889, + -0.35132298 -0.72137493 0.59681696, + -0.2341689 -0.74906766 0.61972773, + -0.29477319 -0.7432394 0.60058635, + -0.05055419 -0.77259785 0.63287979, + -0.14952601 -0.76489013 0.62656605, + -0.1805101 -0.76502246 0.61818838, + -0.11025503 -0.75594717 0.6452812, + -0.22556794 -0.74098182 0.63250685, + -0.15919606 -0.74312025 0.64994526, + -0.15006992 -0.73385465 0.66252267, + -0.075068153 -0.73132759 0.67788261, + -0.17447107 -0.72214824 0.66937423, + -0.14502399 -0.72258294 0.67590094, + -0.13639703 -0.71319616 0.68756616, + -0.29787093 -0.7042048 0.64449084, + -0.46614799 -0.65777701 0.59163803, + -0.41891122 -0.66984427 0.61304331, + -0.377202 -0.68800598 0.619973, + -0.49323681 -0.64622879 0.58232784, + -0.49015576 -0.64719468 0.58385468, + -0.68356478 -0.54194784 0.48890883, + -0.66779608 -0.55064207 0.50084108, + -0.8351112 -0.40693209 0.37012908, + -0.85398746 -0.38838378 0.3462128, + -0.957461 -0.221055 0.185481, + -0.94202346 -0.25047612 0.2232791, + -0.93876934 -0.25828809 0.22803408, + -0.80091715 -0.44887006 0.39629206, + -0.81061155 -0.44043374 0.38591075, + -0.75941873 -0.49676183 0.42013186, + -0.72244275 -0.52323884 0.45199284, + -0.61737603 -0.59530902 0.51425099, + -0.50889969 -0.64081764 0.57478166, + -0.37343013 -0.69056922 0.61940622, + -0.46536306 -0.66666305 0.58223504, + -0.32454887 -0.71241874 0.62219578, + -0.41661084 -0.69321579 0.58812177, + -0.4245559 -0.69936579 0.57501286, + -0.49636012 -0.67755318 0.54272312, + -0.35969201 -0.72824901 0.58333099, + -0.42304108 -0.71394217 0.55796313, + -0.30347493 -0.75076079 0.58673787, + -0.35555801 -0.74246198 0.56774002, + -0.23517209 -0.77209228 0.59039623, + -0.20278093 -0.77357173 0.60038877, + -0.108285 -0.785339 0.60952199, + -0.12307402 -0.7863121 0.60544705, + -0.0017187698 -0.79233485 0.61008394, + -0.049821001 -0.80019802 0.59766299, + 0.047710571 -0.80028051 0.59772462, + 0.015843803 -0.80783916 0.58919013, + 0.094118819 -0.80435419 0.58664811, + 0.076289736 -0.80991036 0.58157128, + 0.13923706 -0.80436534 0.57758927, + 0.15465194 -0.79818869 0.58221781, + 0.16933693 -0.79624063 0.58079767, + 0.2050539 -0.77906567 0.59246069, + 0.21148489 -0.77797562 0.59163171, + 0.245141 -0.758717 0.603535, + 0.24516398 -0.75871187 0.60353196, + 0.27375409 -0.73975122 0.61467624, + 0.26959905 -0.74065316 0.61542612, + 0.28456897 -0.72948295 0.62199295, + 0.29776001 -0.72642797 0.61938798, + 0.30198187 -0.72287178 0.62150079, + 0.30980995 -0.72096485 0.61986089, + 0.31427109 -0.71679115 0.62245011, + 0.31739908 -0.71600521 0.6217671, + 0.32088003 -0.71240103 0.62411606, + 0.32011908 -0.71259516 0.6242851, + 0.32253802 -0.70983106 0.62618607, + 0.31784299 -0.71102101 0.62723601, + 0.31872088 -0.70991677 0.62804079, + 0.31101301 -0.71183199 0.62973499, + 0.31043404 -0.71263409 0.62911308, + 0.29934704 -0.71529508 0.63146204, + 0.29768094 -0.71784383 0.62935382, + 0.28406397 -0.72095692 0.63208294, + 0.28138593 -0.72548783 0.62808383, + 0.26506498 -0.72899294 0.63111794, + 0.26145291 -0.73578376 0.62471175, + 0.24307702 -0.73943603 0.62781209, + 0.23913206 -0.74773818 0.61943811, + 0.21857002 -0.75146013 0.62252307, + 0.2179991 -0.75283837 0.62105632, + 0.18855804 -0.75755417 0.62494612, + 0.14263698 -0.86350089 0.48375693, + 0.121172 -0.86599302 0.48515299, + 0.064438514 -0.96003222 0.27237105, + 0.052656889 -0.96069676 0.27255994, + 0.019474696 -0.99299276 0.11655997, + 0.015466304 -0.99306226 0.11656803, + -0.010568399 -0.99898189 -0.043858796, + -0.0071783792 -0.99901187 -0.043860096, + -0.025109006 -0.97937125 -0.20050305, + -0.014851701 -0.97957212 -0.20054403, + -0.025000596 -0.93644887 -0.34991196, + -0.0084306337 -0.93670839 -0.35000917, + -0.011677696 -0.86901569 -0.49464682, + 0.010857399 -0.86902386 -0.49465093, + 0.0076993089 -0.9364289 -0.35077298, + 0.02440419 -0.93617767 -0.35067889, + 0.014295205 -0.97939837 -0.20143108, + 0.024530495 -0.97920376 -0.20139095, + 0.0067210584 -0.99896878 -0.044902287, + 0.010233301 -0.9989391 -0.044901002, + -0.015917106 -0.99309134 0.11626004, + -0.019950291 -0.99301952 0.11625095, + -0.053101782 -0.96085364 0.27191991, + -0.064621009 -0.96020013 0.27173504, + -0.12068398 -0.86756587 0.48245695, + -0.14215899 -0.86507785 0.48107293, + -0.18661702 -0.76391512 0.61774409, + -0.21527497 -0.75934386 0.61404693, + -0.218297 -0.75212699 0.621813, + -0.23880503 -0.74841607 0.61874509, + -0.24322604 -0.73911607 0.62813103, + -0.26170397 -0.73544192 0.62500894, + -0.26514289 -0.72897166 0.63110971, + -0.28127486 -0.72550762 0.62811071, + -0.28393802 -0.72100109 0.63208908, + -0.29776803 -0.71784008 0.62931705, + -0.29961795 -0.71500784 0.63165879, + -0.31075716 -0.71233237 0.62929529, + -0.31137189 -0.71147877 0.62995678, + -0.319112 -0.70955402 0.62825203, + -0.31825787 -0.71063077 0.62746775, + -0.32278398 -0.70948297 0.62645394, + -0.3207511 -0.71180916 0.62485713, + -0.3215951 -0.71159416 0.62466812, + -0.31788912 -0.71543825 0.62216926, + -0.31512809 -0.71613318 0.62277412, + -0.31061605 -0.72036219 0.62015814, + -0.30290303 -0.72224605 0.62178004, + -0.29861689 -0.72586375 0.61963677, + -0.28552708 -0.72890425 0.62223226, + 0.11578202 -0.83163011 0.54312605, + 0.035843004 -0.83672315 0.54645205, + -0.0084738825 -0.82853228 0.55987716, + -0.048773292 -0.82757586 0.55923092, + -0.090358578 -0.81548184 0.57168591, + -0.11591101 -0.81331211 0.57016504, + -0.15640001 -0.79755515 0.58261907, + -0.17088205 -0.7956152 0.58120209, + -0.20752205 -0.77791017 0.59311914, + -0.21336189 -0.77691066 0.59235668, + -0.24628785 -0.75799853 0.60397065, + -0.24655008 -0.75794631 0.60392922, + -0.27511406 -0.7389462 0.61503714, + -0.270861 -0.73987401 0.61580902, + -0.28312406 -0.72513419 0.62771118, + -0.27671191 -0.72654778 0.62893474, + -0.24879202 -0.74540806 0.61844105, + -0.24929294 -0.74530882 0.61835891, + -0.21865197 -0.76327789 0.60794592, + -0.21371403 -0.7641331 0.60862708, + -0.17877504 -0.78152019 0.59771711, + -0.16594796 -0.78330284 0.59908086, + -0.12939 -0.79818702 0.58835, + -0.10657998 -0.80036891 0.58995795, + -0.066930592 -0.81278586 0.57870495, + -0.030232197 -0.81423986 0.57974094, + 0.011401901 -0.8230511 0.56785303, + 0.067696668 -0.82121658 0.56658667, + 0.068288162 -0.82128555 0.56641567, + 0.20352888 -0.80597651 0.55585766, + 0.19363204 -0.80613911 0.55914807, + 0.30619887 -0.78222263 0.54255879, + 0.3389731 -0.77727532 0.53003818, + 0.46623501 -0.73089701 0.49841201, + 0.42357606 -0.74322504 0.51788008, + 0.54118723 -0.68992937 0.48074323, + 0.49592781 -0.70714277 0.5039888, + 0.62274176 -0.63716179 0.45411184, + 0.576603 -0.66000301 0.48158601, + 0.71120119 -0.56788313 0.41436908, + 0.66318095 -0.59896493 0.44881195, + 0.79650688 -0.48386294 0.36256498, + 0.75199199 -0.52197701 0.40255201, + 0.86083019 -0.40297508 0.31077707, + 0.87894475 -0.37458292 0.29520094, + 0.86861616 -0.38777408 0.30844307, + 0.95067638 -0.24275509 0.19309208, + 0.94677514 -0.25108904 0.20142303, + 0.99739051 -0.056314774 0.045175578, + 0.99719411 -0.058130506 0.047167208, + 0.99689209 0.061174206 -0.049636807, + 0.07188271 -0.72959507 0.68009108, + 0.3251678 -0.69173557 0.64480066, + 0.59293669 -0.5778957 0.56076974, + 0.65591145 -0.55017138 0.51680928, + 0.77374852 -0.46172774 0.43372872, + 0.83728772 -0.41126084 0.36029688, + 0.94051814 -0.26762602 0.20928903, + 0.88045377 -0.35041291 0.31939292, + 0.77605182 -0.46610388 0.42484191, + 0.72652298 -0.49985299 0.471499, + 0.45314494 -0.66138393 0.59768796, + 0.32943979 -0.70210159 0.63128662, + 0.66970092 -0.56126195 0.48629794, + 0.56492227 -0.62362331 0.54033023, + 0.447209 -0.66419703 0.599038, + 0.31859601 -0.703897 0.63484299, + 0.32228789 -0.70258576 0.63443178, + 0.28579196 -0.71123195 0.64223993, + 0.3162981 -0.7069962 0.63254416, + 0.20436896 -0.72952795 0.65270394, + 0.28476903 -0.72269106 0.62978107, + 0.17190394 -0.74268275 0.64720279, + 0.23598611 -0.74003434 0.62980932, + 0.11703903 -0.75630915 0.64366019, + 0.053441901 -0.77309901 0.63203001, + 0.15396008 -0.76497436 0.62538832, + 0.1872129 -0.76496351 0.61626464, + 0.3020559 -0.74235779 0.59805274, + 0.24497113 -0.74829137 0.6164813, + 0.36278713 -0.71922624 0.59253621, + 0.29363182 -0.73036361 0.61672467, + 0.42733493 -0.69076693 0.58328897, + 0.33952287 -0.71015275 0.61677176, + 0.48282406 -0.66116804 0.57422805, + 0.40499923 -0.68328542 0.60753334, + 0.53673106 -0.63055205 0.56064606, + 0.64159173 -0.58295971 0.49851575, + 0.740969 -0.51037401 0.43644401, + 0.75222486 -0.50216895 0.42659593, + 0.94360638 -0.2481131 0.21919608, + 0.80018502 -0.44947201 0.39708799, + 0.80501765 -0.4453178 0.39196783, + 0.63460696 -0.58012092 0.51062095, + 0.60525405 -0.59859806 0.52473605, + 0.59895122 -0.60146326 0.52867717, + 0.55653012 -0.62402713 0.54851115, + 0.47719905 -0.65114409 0.59016305, + 0.67450207 -0.54702407 0.49579406, + 0.66632426 -0.55145919 0.50190115, + 0.83446628 -0.40753916 0.37091511, + 0.85983729 -0.38230315 0.33841413, + 0.94421214 -0.24660203 0.21829103, + 0.95810074 -0.21971194 0.18376495, + 0.99589002 -0.069473997 0.058107499, + 0.998456 0.043937098 -0.033986799, + 0.99676663 -0.063556075 0.049162682, + 0.99588138 -0.069772124 0.057897922, + 0.95508802 -0.228035 0.189227, + 0.94091988 -0.25357196 0.22443497, + 0.8593213 -0.38297215 0.33896813, + 0.82448667 -0.41524884 0.38443485, + 0.71885496 -0.51011497 0.47226095, + 0.69888908 -0.52177507 0.48918805, + 0.52153003 -0.62245107 0.58357608, + 0.53154087 -0.6191259 0.5780549, + 0.32057884 -0.69235766 0.6464287, + 0.30007601 -0.69982302 0.64823002, + 0.17332095 -0.70621979 0.68644983, + 0.012223396 -0.71701878 0.69694674, + 0.25977504 -0.68408108 0.68157905, + 0.45207611 -0.63187915 0.62956816, + 0.47837523 -0.62565827 0.61620528, + 0.72873598 -0.48789501 0.48052299, + 0.86131197 -0.38893399 0.326913, + 0.13719995 -0.66664577 0.73263878, + 0.24693593 -0.66879284 0.70124084, + 0.35176602 -0.64605606 0.67740107, + 0.48757994 -0.62274593 0.61192596, + 0.5962649 -0.5726099 0.56265986, + 0.66493893 -0.54452395 0.51122391, + 0.7881279 -0.44873694 0.42129493, + 0.7537753 -0.48735917 0.44079915, + 0.69103521 -0.52328718 0.49863917, + 0.59957087 -0.57939386 0.55210286, + 0.47518161 -0.61722249 0.62708747, + 0.3558729 -0.65555584 0.6660338, + 0.32843292 -0.65861982 0.67701679, + 0.14753902 -0.68967009 0.70893407, + 0.087201692 -0.68523395 0.72308391, + -0.040652186 -0.68728578 0.72524875, + -0.11664499 -0.66856796 0.73444593, + -0.18414602 -0.66165107 0.72684807, + -0.20792705 -0.65273917 0.72849017, + -0.24953912 -0.64621329 0.72120637, + -0.20778203 -0.66470903 0.71762705, + -0.24504091 -0.65882277 0.71127176, + -0.21732301 -0.67230999 0.70765102, + -0.25108606 -0.66670716 0.7017532, + -0.23138897 -0.67731696 0.69835591, + -0.25968 -0.67232698 0.69321197, + -0.26391813 -0.66976029 0.69409537, + -0.27098504 -0.66839808 0.69268405, + -0.28075898 -0.67051595 0.68671894, + -0.27663797 -0.67135096 0.68757492, + -0.25350696 -0.68654394 0.68146294, + -0.25479504 -0.68630403 0.68122405, + -0.22985902 -0.70072907 0.67538404, + -0.22678603 -0.70124805 0.67588407, + -0.22281797 -0.70328593 0.67508596, + -0.18209104 -0.7093612 0.68091816, + -0.20754504 -0.69803816 0.68532318, + -0.16046007 -0.70432937 0.69150037, + -0.196918 -0.69001001 0.69649798, + -0.13990906 -0.69686836 0.70342034, + -0.19624597 -0.67729092 0.70905894, + -0.13137405 -0.68473524 0.71685326, + -0.10624305 -0.69158435 0.71443933, + 0.00048822988 -0.69552082 0.7185058, + 0.097141184 -0.70671296 0.70079994, + 0.27189201 -0.683321 0.67760402, + 0.28942299 -0.67704499 0.676642, + 0.38303408 -0.66434216 0.64182121, + 0.56760114 -0.59211314 0.57204109, + 0.59237659 -0.58286059 0.55620456, + 0.72424895 -0.49885094 0.47603694, + 0.7772038 -0.46507189 0.42386591, + 0.8631801 -0.37316403 0.34010103, + 0.88415015 -0.35143104 0.30785504, + 0.95552826 -0.22182406 0.19431904, + 0.96616447 -0.20013508 0.16270307, + 0.99732465 -0.056721181 0.046112284, + 0.99782652 -0.052646372 0.03963178, + 0.99832141 0.046270773 -0.034832276, + 0.99855226 0.044064511 -0.030851508, + 0.98915786 0.12030099 -0.084228389, + 0.99029976 0.11634397 -0.075964287, + 0.97700864 0.17851694 -0.11655796, + 0.97889411 0.17442602 -0.10649802, + 0.96343374 0.22868994 -0.13962898, + 0.96625167 0.22428392 -0.12670596, + 0.94934326 0.27359906 -0.15456703, + 0.95415711 0.26774403 -0.13378102, + 0.93680412 0.31296203 -0.15637401, + 0.94177836 0.30801511 -0.13483405, + 0.92378777 0.35076892 -0.15354897, + 0.92861879 0.3467949 -0.13191096, + 0.90973276 0.38806891 -0.14760996, + 0.91428226 0.38497508 -0.12602504, + 0.89421844 0.4254162 -0.13926406, + 0.89842433 0.42307314 -0.11765604, + 0.87717032 0.46262318 -0.12865505, + 0.88095379 0.46092188 -0.10710398, + 0.85824871 0.49991482 -0.11616495, + 0.86156517 0.49874511 -0.094651319, + 0.83693057 0.53771174 -0.10204595, + 0.8397249 0.53697896 -0.080719993, + 0.81289887 0.57593393 -0.086575896, + 0.78182483 0.61688191 -0.090590276, + 0.81038266 0.57968372 -0.085127659, + 0.80737412 0.58017308 -0.10745402, + 0.83406627 0.54243916 -0.10046504, + 0.83044231 0.54333818 -0.12308204, + 0.85509717 0.50565612 -0.11454603, + 0.85088629 0.5070762 -0.13735504, + 0.87382621 0.46932513 -0.12712903, + 0.86904418 0.47139111 -0.15017503, + 0.8907491 0.43305105 -0.13796002, + 0.88543189 0.43590295 -0.16124198, + 0.906232 0.39652199 -0.146676, + 0.90041542 0.40032417 -0.17027207, + 0.92029649 0.36000979 -0.15312491, + 0.91405576 0.3649289 -0.17699996, + 0.93338835 0.32289213 -0.15661106, + 0.92698926 0.32896209 -0.18020804, + 0.94609565 0.28405792 -0.15560894, + 0.94213146 0.28872815 -0.17036608, + 0.96052963 0.23957992 -0.14136596, + 0.95747626 0.24426606 -0.15353604, + 0.97473025 0.18912704 -0.11887803, + 0.97213465 0.19458492 -0.13073196, + 0.98782188 0.12914799 -0.086768396, + 0.98584026 0.13559203 -0.098660022, + 0.99730766 0.059295077 -0.043144584, + 0.99654377 0.065214783 -0.05145419, + 0.99868751 -0.040208582 0.031724487, + 0.99152637 -0.10534403 0.07601463, + 0.98222274 -0.14239196 0.12232297, + 0.90503913 -0.32262802 0.27715603, + 0.90779471 -0.31871289 0.27263692, + 0.78784603 -0.46800101 0.40034199, + 0.80896312 -0.44943807 0.37892506, + 0.71489495 -0.53458595 0.45071393, + 0.62261474 -0.58844477 0.51583284, + 0.49639025 -0.65279227 0.57224029, + 0.5710218 -0.62371176 0.53377682, + 0.44301522 -0.68113428 0.58291829, + 0.5708518 -0.63515878 0.52028984, + 0.43500206 -0.69656307 0.57059008, + 0.50729889 -0.67375982 0.53730386, + 0.37120509 -0.72597116 0.57894111, + 0.43036991 -0.71205884 0.55475587, + 0.31086096 -0.74976796 0.58413494, + 0.36055011 -0.74156523 0.5657602, + 0.239802 -0.771842 0.58885902, + 0.2055019 -0.77351767 0.59953272, + 0.11049704 -0.78554732 0.60885626, + 0.12426797 -0.78643382 0.6050449, + 0.0033562595 -0.79257286 0.60976791, + -0.28568384 -0.69950062 0.65504467, + -0.2807821 -0.70055723 0.65603423, + -0.25664991 -0.71741879 0.64764279, + -0.25882 -0.71698898 0.647255, + -0.23085594 -0.73414481 0.63854283, + -0.2286521 -0.73453736 0.63888431, + -0.19866304 -0.75041819 0.63040119, + -0.18931399 -0.75183398 0.63159001, + -0.15700504 -0.76621115 0.6231131, + -0.14004195 -0.76818764 0.62472069, + -0.10432801 -0.78096712 0.61579704, + -0.075547434 -0.78300834 0.61740631, + -0.038719978 -0.79276854 0.60829163, + 0.0075958162 -0.79334062 0.60873067, + 0.055667002 -0.80734801 0.58744401, + -0.013075097 -0.80853283 0.58830589, + -0.052369811 -0.7991792 0.5988071, + -0.085364275 -0.79735583 0.59744185, + -0.12248492 -0.78491855 0.60737163, + -0.14225002 -0.78283113 0.60575604, + -0.17793001 -0.76763713 0.61569005, + -0.18878403 -0.76605815 0.61442304, + -0.22034806 -0.74985516 0.62383014, + -0.22438003 -0.74914807 0.62324208, + -0.25355095 -0.73166382 0.63275582, + -0.252096 -0.731951 0.63300502, + -0.27820802 -0.71403009 0.64246505, + -0.27331513 -0.71507335 0.6434043, + -0.28548107 -0.70574719 0.64839917, + -0.29739514 -0.70307434 0.64594328, + -0.29980716 -0.70100135 0.6470803, + -0.30739611 -0.69922423 0.64544022, + -0.30983111 -0.69691122 0.64677626, + -0.31309313 -0.69612724 0.64604926, + -0.31529292 -0.6938228 0.64745682, + -0.31498212 -0.69389826 0.64752722, + -0.31658581 -0.6920476 0.64872462, + -0.31246302 -0.69304407 0.64965904, + -0.31273913 -0.69269425 0.64989924, + -0.30583489 -0.69433177 0.65143573, + -0.30489302 -0.69564909 0.65047103, + -0.29452902 -0.69802707 0.65269506, + -0.29247394 -0.70119685 0.65021682, + -0.27932996 -0.70407295 0.65288293, + -0.2764101 -0.70905721 0.64871824, + -0.26135492 -0.71215779 0.65155578, + -0.25772893 -0.71903884 0.64541382, + -0.24007291 -0.72241575 0.64844477, + -0.23609112 -0.73088437 0.64036632, + -0.21590097 -0.73440796 0.64345294, + -0.2114259 -0.74519563 0.6324417, + -0.1900311 -0.74853837 0.63527828, + -0.18698104 -0.75702417 0.6260612, + -0.15847099 -0.76087791 0.62924695, + -0.12078699 -0.86326087 0.49009293, + -0.099243298 -0.86533499 0.49127001, + -0.053785082 -0.95869166 0.27931592, + -0.041861199 -0.95924002 0.279475, + -0.0161463 -0.99244398 0.121632, + -0.011924597 -0.99250275 0.12163897, + 0.0067397621 -0.99911833 -0.041438214, + 0.0036612414 -0.99913436 -0.041438915, + 0.014390705 -0.97975838 -0.19966607, + 0.0044191414 -0.97985035 -0.19968407, + 0.0077278791 -0.93653089 -0.35049996, + -0.0083794398 -0.936526 -0.35049799, + -0.0050326977 -0.97990751 -0.19938891, + -0.014915396 -0.97981077 -0.19936995, + -0.0041731307 -0.99915826 -0.04081041, + -0.007193781 -0.9991411 -0.040809702, + 0.011420299 -0.99255288 0.12127799, + 0.015667096 -0.99249578 0.12127097, + 0.041427881 -0.95940953 0.27895689, + 0.053229783 -0.95887262 0.2788009, + 0.099373326 -0.86391419 0.49373811, + 0.12125996 -0.86180472 0.49253282, + 0.15987006 -0.75580531 0.63498026, + 0.18883993 -0.75187773 0.63167977, + 0.19014807 -0.74820721 0.63563323, + 0.211979 -0.74479198 0.63273197, + 0.21614404 -0.7347672 0.6429612, + 0.23602891 -0.73129374 0.63992178, + 0.24014106 -0.72256321 0.64825517, + 0.25775903 -0.71919209 0.64523107, + 0.26140001 -0.712291 0.65139198, + 0.2766411 -0.70914924 0.64851922, + 0.27941501 -0.70442098 0.65247101, + 0.29227385 -0.70160663 0.64986467, + 0.29428303 -0.69851303 0.65228605, + 0.30460507 -0.69614518 0.6500752, + 0.30554298 -0.69483495 0.65103596, + 0.31237903 -0.69321406 0.64951807, + 0.31212097 -0.69354194 0.64929193, + 0.3159191 -0.69262516 0.64843321, + 0.31450084 -0.69425964 0.64737368, + 0.31479916 -0.69418734 0.64730632, + 0.31238285 -0.69671464 0.6457597, + 0.30903703 -0.69751704 0.64650303, + 0.30633798 -0.70007592 0.64501995, + 0.29895493 -0.70179981 0.64660883, + 0.29664603 -0.70378006 0.64551908, + 0.2842381 -0.70655525 0.64806521, + 0.27213693 -0.7158078 0.64308685, + 0.27694705 -0.71478617 0.64216918, + 0.25165197 -0.73211592 0.63299096, + 0.25274801 -0.73189998 0.63280398, + 0.22270606 -0.74986517 0.62298012, + 0.21887194 -0.75053281 0.62353486, + 0.18742101 -0.76662511 0.61413306, + 0.17644994 -0.7682097 0.61540174, + 0.165204 -0.77312702 0.61235797, + 0.10919798 -0.77921087 0.61717594, + 0.13221395 -0.77100772 0.62294978, + 0.063907221 -0.77624631 0.62718225, + 0.0992212 -0.76595199 0.63519502, + 0.015197096 -0.76966184 0.6382708, + 0.065087095 -0.75827986 0.64867193, + -0.039777119 -0.75929034 0.6495353, + 0.030882703 -0.74763703 0.66338909, + -0.099863447 -0.74425435 0.66038829, + -0.058898602 -0.74097198 0.66894799, + 0.016199896 -0.72300684 0.69065082, + -0.066070303 -0.72152197 0.68923199, + -0.039522804 -0.71936208 0.69351006, + -0.045770396 -0.72699094 0.68511993, + -0.29378784 -0.69563866 0.65557271, + -0.334342 -0.69043899 0.64148998, + -0.54306597 -0.61515594 0.57154393, + -0.52326989 -0.62187988 0.58262688, + -0.59447408 -0.57728308 0.55977207, + -0.64377308 -0.55596006 0.52579904, + -0.76830679 -0.46504489 0.43981588, + -0.83563232 -0.41239116 0.36283913, + -0.95487714 -0.23575103 0.18064101, + -0.92053586 -0.29212898 0.25937298, + -0.85567302 -0.38699201 0.3436, + -0.8164649 -0.42246395 0.39358494, + -0.70910764 -0.51590276 0.48063576, + -0.70006019 -0.52111214 0.48821911, + -0.72765881 -0.49914089 0.47050089, + -0.767061 -0.47266901 0.43382201, + -0.87587386 -0.35550296 0.32628596, + -0.90939224 -0.3148931 0.27175006, + -0.962749 -0.204708 0.176661, + -0.96876854 -0.19102991 0.15809792, + -0.99844575 0.044114888 -0.034056492, + -0.99678123 -0.063459717 0.048990611, + -0.99591291 -0.069579892 0.057584994, + -0.99592686 -0.069071092 0.057955693, + -0.99151754 -0.10538695 0.076068766, + -0.98191625 -0.14340603 0.12359303, + -0.90293229 -0.32555911 0.28057909, + -0.91055697 -0.31470299 0.26804501, + -0.79445767 -0.46234381 0.39379585, + -0.7947343 -0.46210417 0.39351916, + -0.6941632 -0.54802912 0.46669212, + -0.6005441 -0.59927809 0.52935112, + -0.46302482 -0.66429776 0.58678478, + -0.55235213 -0.63213718 0.54342413, + -0.42124608 -0.68774819 0.59123111, + -0.5563938 -0.64183277 0.52770883, + -0.57840294 -0.62751794 0.52122092, + -0.5161081 -0.65326917 0.55396014, + -0.64006716 -0.58599609 0.49691311, + -0.56101006 -0.62427908 0.54363906, + -0.69653422 -0.5411092 0.47121218, + -0.77240616 -0.48641112 0.4084031, + -0.85633099 -0.395504 0.332075, + -0.88030291 -0.36705497 0.30056196, + -0.90931827 -0.32047811 0.26539409, + -0.90104514 -0.33252802 0.27846503, + -0.7831409 -0.47675493 0.39924294, + -0.81216317 -0.45036012 0.37090009, + -0.70073295 -0.55070394 0.45353994, + -0.73991096 -0.52292496 0.42317995, + -0.74512297 -0.52733892 0.40829593, + -0.79176301 -0.48819199 0.36712399, + -0.65433276 -0.60438275 0.45449984, + -0.70423406 -0.57283908 0.41941607, + -0.56960779 -0.66316473 0.48555082, + -0.6185053 -0.63936931 0.45679122, + -0.49105194 -0.70881593 0.50640696, + -0.53849679 -0.69099677 0.48222882, + -0.42068499 -0.74395502 0.51918697, + -0.46326578 -0.73178965 0.49986875, + -0.33599707 -0.7777372 0.53125411, + -0.30417588 -0.78246272 0.5433498, + -0.19268996 -0.80599082 0.5596869, + -0.20468596 -0.80579382 0.55569786, + -0.068673708 -0.82128012 0.56637704, + -0.11164192 -0.82544339 0.55333459, + -0.0024101695 -0.83063382 0.5568139, + -0.028658088 -0.8354407 0.54883283, + 0.058996316 -0.83432817 0.54810214, + 0.046183113 -0.83776516 0.54407412, + 0.115732 -0.83302498 0.540995, + 0.13628298 -0.82550091 0.54769993, + 0.15404798 -0.82332885 0.54625893, + 0.19447196 -0.80503482 0.5604459, + 0.20274498 -0.8036589 0.55948794, + 0.23981602 -0.78331512 0.57350308, + 0.24116705 -0.78304517 0.57330513, + 0.27315095 -0.76244783 0.58656788, + 0.26964596 -0.76323086 0.58717096, + 0.28666997 -0.75080287 0.59507596, + 0.30020797 -0.74754596 0.59249496, + 0.30697086 -0.74193567 0.59607071, + 0.31465316 -0.73997736 0.59449732, + 0.32072508 -0.73436016 0.5982061, + 0.32322398 -0.73370093 0.59766996, + 0.32798892 -0.72880882 0.6010499, + 0.3265532 -0.72919244 0.60136634, + 0.32942903 -0.72593004 0.60374004, + 0.32413501 -0.727337 0.60491103, + 0.325688 -0.72539502 0.60640699, + 0.31676289 -0.72771776 0.60834879, + 0.31668496 -0.72782594 0.60825992, + 0.30462587 -0.73084974 0.61078775, + 0.30312312 -0.73313522 0.60879326, + 0.28862804 -0.73658907 0.61166203, + 0.28566805 -0.74155718 0.60703111, + 0.26884893 -0.74531281 0.61010587, + 0.26547009 -0.75160331 0.60383624, + 0.24620996 -0.75557691 0.60702896, + 0.24637806 -0.7552222 0.60740215, + 0.21705703 -0.76066512 0.61178005, + 0.16381292 -0.86586058 0.47270575, + 0.14200199 -0.86882287 0.47432294, + 0.074761435 -0.96159047 0.26411113, + 0.063275293 -0.96235687 0.26432097, + 0.022487611 -0.99368149 0.10996106, + 0.018860502 -0.99375612 0.10996901, + -0.014710298 -0.99871188 -0.048560791, + -0.0107733 -0.99876201 -0.048563201, + -0.03581281 -0.97837937 -0.20369408, + -0.025088008 -0.97869939 -0.20376007, + -0.041974887 -0.93502074 -0.35209993, + -0.024861103 -0.93555611 -0.35230204, + -0.034492996 -0.86814988 -0.49510193, + -0.011596297 -0.86860883 -0.49536288, + -0.014621694 -0.77617764 -0.63034469, + 0.013807296 -0.77618682 -0.63035184, + 0.010830499 -0.86888987 -0.49488693, + 0.03382881 -0.86844331 -0.49463317, + 0.024280503 -0.93538213 -0.35280403, + 0.041262213 -0.93486136 -0.35260713, + 0.024508294 -0.97851974 -0.20469095, + 0.035468996 -0.97819787 -0.20462397, + 0.0104411 -0.99871302 -0.049631801, + 0.014418994 -0.99866366 -0.049629383, + -0.019398803 -0.99370325 0.11035203, + -0.023044406 -0.99362624 0.11034403, + -0.063417464 -0.9625994 0.26340184, + -0.07491374 -0.9618305 0.26319212, + -0.14148895 -0.87045473 0.47147581, + -0.16276795 -0.86757469 0.46991581, + -0.21432003 -0.76699114 0.60480708, + -0.24330403 -0.76164114 0.60058808, + -0.24589315 -0.75623846 0.60633337, + -0.2651329 -0.7522707 0.60315275, + -0.26907888 -0.74492764 0.61047471, + -0.28597692 -0.74115175 0.60738075, + -0.28861305 -0.73672515 0.61150509, + -0.30309615 -0.73327339 0.60864031, + -0.30471107 -0.73081815 0.6107831, + -0.31679797 -0.72778594 0.60824895, + -0.31708404 -0.72739106 0.60857207, + -0.32584399 -0.72510999 0.606664, + -0.32448903 -0.72680706 0.60535806, + -0.32983822 -0.72538441 0.60417235, + -0.32681999 -0.72881401 0.60167998, + -0.32856303 -0.72834706 0.60129607, + -0.32397014 -0.73307139 0.59803832, + -0.32133603 -0.73376703 0.59860605, + -0.31552288 -0.73915678 0.59505677, + -0.30795494 -0.74109083 0.59661388, + -0.30116096 -0.74674195 0.59302497, + -0.28771985 -0.74998462 0.59560072, + -0.28394714 -0.77045435 0.57076627, + -0.27437395 -0.77269083 0.57242286, + -0.24162397 -0.7935499 0.55847692, + -0.23983894 -0.79391181 0.55873185, + -0.20110695 -0.81483781 0.54368687, + -0.19225807 -0.81631428 0.54467219, + -0.149593 -0.83515799 0.52927601, + -0.13020205 -0.83747244 0.53074223, + -0.082523137 -0.85361439 0.51432723, + -0.050753683 -0.85543168 0.51542282, + 0.00067905703 -0.8671751 0.49800307, + 0.073067613 -0.8648572 0.49667212, + 0.17399302 -0.85099614 0.49551207, + 0.083622172 -0.86115068 0.50142485, + 0.032863598 -0.85450298 0.51840597, + -0.014406203 -0.85487616 0.51863211, + -0.063591577 -0.84264469 0.53470182, + -0.093458906 -0.84065813 0.53344107, + -0.13785301 -0.8248961 0.54821807, + -0.15573195 -0.82268667 0.54674882, + -0.19701104 -0.80390316 0.56118309, + -0.20476903 -0.80259812 0.56027305, + -0.24113794 -0.78255379 0.5739879, + -0.24259706 -0.78226018 0.57377315, + -0.27465612 -0.76154536 0.58703732, + -0.27072302 -0.7624281 0.58771807, + -0.28248698 -0.74890494 0.59945196, + -0.27439705 -0.75073618 0.6009171, + -0.24369594 -0.77083385 0.58858091, + -0.24286106 -0.77100021 0.5887081, + -0.20841002 -0.79035014 0.57611805, + -0.20132592 -0.79154873 0.57699084, + -0.16284005 -0.80957228 0.56398219, + -0.14663303 -0.81165516 0.56543314, + -0.10423301 -0.82741314 0.55183607, + -0.076245867 -0.82952273 0.55324382, + -0.030202111 -0.84190232 0.53878421, + 0.013843901 -0.84220612 0.53897804, + 0.059822615 -0.84944016 0.52428311, + 0.12573895 -0.84421068 0.5210548, + 0.12997797 -0.84442782 0.51966089, + 0.277428 -0.81822199 0.50353402, + 0.29156002 -0.82727814 0.48021206, + 0.43539774 -0.77857453 0.45194075, + 0.47018605 -0.76770115 0.43538505, + 0.59564406 -0.69870603 0.39625505, + 0.60260475 -0.70128375 0.38087887, + 0.701805 -0.62599999 0.339991, + 0.67378271 -0.64552969 0.35959482, + 0.77209967 -0.55517483 0.30926189, + 0.70980066 -0.6064207 0.35838082, + 0.83809811 -0.46963805 0.27754602, + 0.83518898 -0.47406101 0.27879301, + 0.89569259 -0.38330281 0.2254189, + 0.85873967 -0.43466586 0.2713519, + 0.94464737 -0.27830809 0.17374106, + 0.9060654 -0.34941417 0.23865312, + 0.97548687 -0.18171698 0.12411398, + 0.95222479 -0.24439193 0.18314095, + 0.99647689 -0.067114092 0.050293494, + 0.99515122 -0.077544317 0.060505316, + 0.99107349 0.10510705 -0.082011938, + 0.99239224 0.098139919 -0.074339017, + 0.97300726 0.18395704 -0.13934404, + 0.97876751 0.16839293 -0.11686695, + 0.9647311 0.21625903 -0.15008701, + 0.96893466 0.20788492 -0.13397595, + 0.94946736 0.26382309 -0.17002706, + 0.95355576 0.25770593 -0.15594597, + 0.93366802 0.30640599 -0.185417, + 0.93779534 0.30160612 -0.17197005, + 0.91754991 0.34541696 -0.19694997, + 0.92253464 0.34082389 -0.18102194, + 0.90174061 0.38176984 -0.20276991, + 0.90963 0.37584499 -0.176957, + 0.88861269 0.41496485 -0.19537592, + 0.89603829 0.41032314 -0.16955906, + 0.87447172 0.44830784 -0.18525495, + 0.88118529 0.44485816 -0.16004306, + 0.85896629 0.48180118 -0.17333406, + 0.86495984 0.47932088 -0.14864697, + 0.84174627 0.51564616 -0.15991306, + 0.84702784 0.51394886 -0.13564797, + 0.82229912 0.55021405 -0.14522001, + 0.82687312 0.54914504 -0.12132902, + 0.80028301 0.58550203 -0.129362, + 0.80416417 0.58492112 -0.10577002, + 0.77588111 0.62081105 -0.11226001, + 0.77905667 0.62059271 -0.089081258, + 0.74879974 0.65607178 -0.094174065, + 0.68522978 0.72626877 -0.054716382, + 0.7205168 0.69147784 -0.05209529, + 0.71864963 0.69130564 -0.075095065, + 0.7513001 0.65610105 -0.071270905, + 0.75355238 0.65337533 -0.072522335, + 0.78422469 0.61668974 -0.068450376, + 0.78630263 0.61390072 -0.06967067, + 0.81516314 0.57553709 -0.065316804, + 0.81706309 0.57270008 -0.06650281, + 0.84406918 0.53265512 -0.061852816, + 0.84197569 0.53323281 -0.082095467, + 0.8666231 0.49315307 -0.075924911, + 0.8640812 0.49408913 -0.096122921, + 0.88662487 0.45397794 -0.088319495, + 0.8836621 0.45536205 -0.10856701, + 0.90454268 0.41475785 -0.09888646, + 0.90123898 0.41666499 -0.11899, + 0.92069101 0.37528899 -0.107174, + 0.91712034 0.37780416 -0.12710005, + 0.93514943 0.33576214 -0.11295705, + 0.93141174 0.3389529 -0.13260096, + 0.94824255 0.29572284 -0.11568895, + 0.94444436 0.29966012 -0.13501404, + 0.96028 0.254408 -0.114625, + 0.95660251 0.25909787 -0.13334094, + 0.9716295 0.21029389 -0.10822495, + 0.96838766 0.21553993 -0.12556995, + 0.98218286 0.16238098 -0.094600283, + 0.98051852 0.16608092 -0.10488395, + 0.99203354 0.10651195 -0.06726487, + 0.99122024 0.10944003 -0.074198216, + 0.99887174 0.03930679 -0.026649194, + 0.99872035 0.040852115 -0.029813111, + 0.99842763 -0.045279887 0.03304439, + 0.99813926 -0.047887012 0.037749007, + 0.97801077 -0.16378495 0.12910996, + 0.78044581 -0.46872389 0.41376591, + 0.69284564 -0.51459777 0.50512779, + 0.5751121 -0.58381313 0.5730691, + 0.50782883 -0.60046273 0.61770076, + 0.36996204 -0.64757407 0.66616505, + -0.0093735782 -0.64987081 0.75998682, + 0.10819896 -0.66834879 0.73593676, + 0.24267203 -0.65219903 0.71815509, + 0.15706702 -0.68195903 0.71432608, + 0.37501594 -0.64013392 0.67051595, + 0.46439081 -0.62702775 0.62544179, + 0.60508811 -0.56368113 0.5622561, + 0.6625213 -0.54211724 0.51688921, + 0.76999313 -0.46178806 0.44029805, + 0.80367339 -0.43992421 0.40071917, + 0.8944397 -0.33059788 0.30113587, + 0.91614461 -0.30565184 0.25933787, + 0.97292435 -0.17623506 0.14953107, + 0.97307563 -0.17447194 0.15060994, + 0.89355648 -0.33984378 0.29336482, + 0.86212701 -0.37169799 0.34435099, + 0.74510443 -0.48925731 0.45326227, + 0.69939625 -0.51365918 0.49699017, + 0.56505764 -0.59294063 0.57369965, + 0.48300388 -0.61458987 0.62368786, + 0.38030106 -0.64915407 0.65876406, + 0.242112 -0.65799803 0.713036, + 0.151886 -0.67030698 0.72637397, + 0.13012399 -0.66869295 0.73206395, + 0.00043066315 -0.67442721 0.73834121, + -0.050242912 -0.66366118 0.74634415, + -0.13354094 -0.65854871 0.74059463, + -0.192965 -0.63762897 0.74578398, + -0.23694398 -0.63133693 0.73842496, + -0.25891191 -0.62113875 0.73969674, + -0.28617814 -0.6161713 0.73378134, + -0.25339904 -0.63352907 0.73104703, + -0.278837 -0.62892997 0.725739, + -0.25851002 -0.64061004 0.72304308, + -0.28096688 -0.63643873 0.71833366, + -0.26589993 -0.64589781 0.71562082, + -0.28515306 -0.64220017 0.71152419, + -0.27437997 -0.64959395 0.70904392, + -0.29031596 -0.64642596 0.70558494, + -0.28309402 -0.65184605 0.70353007, + -0.29592106 -0.6492092 0.70068419, + -0.35088199 -0.64993203 0.67414403, + -0.46928295 -0.62788391 0.62091494, + -0.71154881 -0.49960387 0.49405888, + -0.75035185 -0.48953289 0.44421789, + -0.67753208 -0.53005505 0.50989407, + -0.58343691 -0.58530587 0.56304389, + -0.46616417 -0.61932427 0.63176626, + -0.346497 -0.65667301 0.66986603, + -0.33030286 -0.65843171 0.67628968, + 0.27969897 -0.67114496 0.68653697, + 0.27509198 -0.67207491 0.68748796, + 0.26867098 -0.67634994 0.68583292, + 0.24496295 -0.68077379 0.69031882, + 0.25985107 -0.6719172 0.69354516, + 0.23170197 -0.67688394 0.69867194, + 0.25192419 -0.66597646 0.70214647, + 0.21951494 -0.67138684 0.70785081, + 0.24781306 -0.6575532 0.71148616, + 0.21051 -0.66351497 0.71793699, + 0.25565085 -0.64333767 0.72163659, + 0.21537302 -0.64983404 0.72892404, + 0.20004596 -0.6557278 0.7280128, + 0.13615403 -0.66302419 0.73611218, + 0.029748708 -0.68958116 0.72359717, + -0.10034494 -0.68640459 0.7202636, + -0.14945108 -0.68974936 0.70845634, + -0.13922597 -0.66676182 0.73215079, + -0.23814803 -0.66894203 0.70413208, + -0.34249684 -0.6471017 0.68114269, + -0.46963176 -0.62683272 0.62171268, + -0.58025503 -0.57824904 0.57352608, + -0.66059607 -0.54650503 0.51472807, + -0.78527534 -0.45071021 0.42450321, + -0.86242098 -0.38786 0.325261, + 0.0087223174 -0.65045375 0.75949568, + -0.095117114 -0.66720408 0.73877704, + -0.78191417 -0.46783412 0.41199708, + -0.69409806 -0.51407808 0.50393605, + -0.57689607 -0.58330208 0.57179505, + -0.50284016 -0.60150623 0.62075925, + -0.36416399 -0.64809901 0.66884398, + -0.23137803 -0.65205508 0.72200304, + -0.15047492 -0.67945671 0.71811962, + -0.35712683 -0.64195973 0.67848969, + -0.45885733 -0.62807745 0.62846547, + -0.60051703 -0.56523603 0.56558603, + -0.66408682 -0.5414899 0.51553589, + -0.77120483 -0.46104887 0.43894988, + -0.80503631 -0.43896914 0.39902714, + -0.9176771 -0.29401004 0.26725802, + -0.7579248 0.65227383 -0.0094289379, + -0.75963372 0.65029478 -0.008563797, + -0.75904679 0.65031683 -0.030594593, + -0.79062682 0.61162186 -0.028774092, + -0.78954566 0.6117357 -0.048960976, + -0.81874585 0.57232594 -0.045806795, + -0.81714809 0.57263106 -0.066051506, + -0.84416711 0.53254908 -0.061428208, + -0.84204745 0.53313732 -0.081980452, + -0.86667717 0.49307412 -0.075819813, + -0.86411256 0.49401775 -0.096207753, + -0.88665044 0.45391273 -0.088397451, + -0.8836931 0.45529306 -0.10860401, + -0.90455902 0.414713 -0.0989246, + -0.90126199 0.41661501 -0.118991, + -0.92070836 0.37524614 -0.10717504, + -0.91713214 0.37776306 -0.12713702, + -0.9351601 0.33572203 -0.11298802, + -0.93141466 0.33891687 -0.13267295, + -0.94823134 0.29572913 -0.11576604, + -0.94441038 0.29968613 -0.13519405, + -0.96026826 0.25439107 -0.11476103, + -0.95652676 0.25914893 -0.13378496, + -0.97157449 0.2103571 -0.10859605, + -0.96832663 0.21559593 -0.12594396, + -0.98213011 0.16250701 -0.094931312, + -0.98051888 0.16608399 -0.10487498, + -0.99203473 0.10650798 -0.067254886, + -0.99122226 0.10943303 -0.074181817, + -0.9988721 0.039303802 -0.026643004, + -0.99871987 0.040856395 -0.029821696, + -0.99842709 -0.045285605 0.033054605, + -0.99813962 -0.047882982 0.037741683, + -0.97801763 -0.16376594 0.12908195, + -0.97234124 -0.17757004 0.15172803, + -0.89720625 -0.33574009 0.28687906, + -0.86301321 -0.37087408 0.3430171, + -0.74654424 -0.48844919 0.45176214, + -0.69554961 -0.51556569 0.50040269, + -0.55991912 -0.59454912 0.57706314, + -0.46523088 -0.61840588 0.6333518, + -0.36218002 -0.65118408 0.66692203, + -0.233436 -0.658068 0.715859, + -0.14620306 -0.66949421 0.72828722, + -0.13320099 -0.66851497 0.73167294, + -0.00084106938 -0.67452532 0.73825133, + 0.038673215 -0.66630125 0.74467921, + 0.12473498 -0.66159195 0.73941696, + 0.20916511 -0.6316213 0.74652839, + 0.25039288 -0.62533271 0.73909563, + 0.26483598 -0.61850196 0.73980892, + 0.28999001 -0.61384302 0.734236, + 0.25613597 -0.63188392 0.73151696, + 0.28113604 -0.62732607 0.72624004, + 0.25922284 -0.63995653 0.72336644, + 0.28194398 -0.63572496 0.71858293, + 0.26596901 -0.64576399 0.715716, + 0.28517303 -0.64207506 0.71162903, + 0.27346298 -0.65010494 0.70892996, + 0.28987986 -0.64684772 0.70537764, + 0.28199786 -0.65275371 0.70312864, + 0.29458487 -0.65017474 0.70035177, + 0.2903541 -0.65363926 0.69889224, + 0.3000572 -0.65159148 0.69670248, + 0.29740098 -0.65396994 0.69561195, + 0.30399996 -0.65254492 0.69409597, + 0.30308613 -0.65344125 0.69365221, + 0.30600101 -0.65280199 0.69297397, + 0.30546889 -0.65337378 0.69266975, + 0.30534095 -0.65340179 0.69269985, + 0.30475086 -0.65409672 0.69230366, + 0.30210695 -0.65467483 0.6929158, + 0.30118197 -0.65587091 0.69218695, + 0.29510912 -0.65717524 0.69356424, + 0.29344296 -0.65954393 0.69202095, + 0.28451097 -0.66140395 0.69397295, + 0.28192991 -0.66545075 0.69115174, + 0.27075109 -0.66768026 0.69346726, + 0.26734105 -0.67359716 0.68905419, + 0.25340387 -0.67622471 0.69174165, + 0.24967809 -0.68342024 0.68600124, + 0.2334539 -0.68627071 0.68886262, + 0.22926103 -0.69536406 0.68110806, + 0.21080998 -0.69833696 0.68402094, + 0.20646195 -0.70904481 0.67426181, + 0.1860439 -0.71200663 0.67707771, + 0.18166399 -0.72443992 0.66496992, + 0.159953 -0.72721303 0.66751498, + 0.15596597 -0.74052584 0.65367883, + 0.13197201 -0.74314308 0.65598905, + 0.13032803 -0.74990219 0.64858419, + 0.10130896 -0.75246173 0.65079778, + 0.076829918 -0.85991615 0.50462013, + 0.05521588 -0.86114973 0.50534379, + 0.02978099 -0.95740062 0.28722292, + 0.017816097 -0.95767379 0.28730395, + 0.0067741713 -0.99193722 0.12654904, + 0.0022067488 -0.99195755 0.12655194, + -0.0015470004 -0.99925023 -0.038687509, + 0.0010491997 -0.99925077 -0.038687494, + -0.0026484388 -0.99190855 0.12692694, + -0.0072652581 -0.99188578 0.12692396, + -0.018223094 -0.95758265 0.28758192, + -0.0302321 -0.957304 0.287498, + -0.055410992 -0.86204886 0.50378692, + -0.076788694 -0.8608259 0.50307292, + -0.10085697 -0.75580484 0.64698285, + -0.12971902 -0.75326014 0.64480406, + -0.13212006 -0.74345636 0.6556043, + -0.15543199 -0.74091595 0.65336394, + -0.15960404 -0.7269572 0.6678772, + -0.18184994 -0.72411877 0.66526878, + -0.18609296 -0.71206683 0.67700082, + -0.20629592 -0.70913774 0.67421478, + -0.21071103 -0.69825208 0.68413806, + -0.22919691 -0.69527477 0.68122077, + -0.23341405 -0.68612117 0.68902516, + -0.24965206 -0.6832692 0.68616116, + -0.25352496 -0.67577791 0.69213396, + -0.26749116 -0.67314541 0.68943739, + -0.27091104 -0.66720206 0.69386506, + -0.28215504 -0.66496009 0.69153208, + -0.28472194 -0.66092885 0.6943388, + -0.29371193 -0.65905583 0.69237185, + -0.29537597 -0.65668595 0.69391394, + -0.30150017 -0.6553694 0.69252342, + -0.30262098 -0.65391797 0.69340593, + -0.30562505 -0.65326017 0.69270819, + -0.30593199 -0.65289801 0.69291401, + -0.30614394 -0.65285081 0.69286484, + -0.30664894 -0.6523068 0.6931538, + -0.30377001 -0.65293998 0.69382501, + -0.30490997 -0.65181994 0.69437796, + -0.29841289 -0.65322673 0.69587678, + -0.30100498 -0.65089995 0.69693995, + -0.29137808 -0.65293825 0.69912124, + -0.29012594 -0.6718508 0.68150079, + -0.28720707 -0.6724692 0.68212718, + -0.26587498 -0.68790191 0.67535293, + -0.27015203 -0.68705308 0.67451906, + -0.24629501 -0.70238203 0.667831, + -0.24620788 -0.70239764 0.66784668, + -0.21925201 -0.71756101 0.66108602, + -0.21427096 -0.71837497 0.66183496, + -0.18531005 -0.73235619 0.65522116, + -0.17426606 -0.73386025 0.65656722, + -0.17065199 -0.73536193 0.65583593, + -0.11284503 -0.74154216 0.66134816, + -0.14800397 -0.72947985 0.6677978, + -0.076269917 -0.73545516 0.67326719, + -0.12664898 -0.7210198 0.68124181, + -0.041465204 -0.72624809 0.68618107, + -0.11715 -0.70829099 0.696132, + -0.014274505 -0.71312922 0.70088726, + -0.0051002912 -0.72503215 0.68869621, + 0.082230292 -0.72258592 0.68637294, + 0.06541831 -0.72148007 0.68933809, + 0.16235892 -0.71343565 0.68165171, + 0.32859588 -0.70042574 0.63358378, + 0.45054707 -0.66207105 0.59889007, + 0.51429576 -0.62827468 0.58375573, + 0.169911 -0.72193301 0.67077798, + 0.19538608 -0.72111523 0.66469324, + 0.091123998 -0.73222798 0.674936, + 0.16305993 -0.73385477 0.65944576, + 0.068702124 -0.74205226 0.66681224, + 0.10660504 -0.74484324 0.65866822, + -0.025529705 -0.74886817 0.66222715, + 0.042580195 -0.75987089 0.64867795, + -0.061182216 -0.7591362 0.64805019, + -0.013641907 -0.76987636 0.63804728, + -0.098668188 -0.76619089 0.63499296, + -0.098777503 -0.76615697 0.63501698, + -0.12379303 -0.76400018 0.6332292, + -0.15605494 -0.7517547 0.64071178, + -0.17036298 -0.74995291 0.63917696, + -0.20159204 -0.73548216 0.64685917, + -0.20855804 -0.73438621 0.64589518, + -0.23744212 -0.71861833 0.65361232, + -0.23854198 -0.71841896 0.65343094, + -0.26345593 -0.70278782 0.6608178, + -0.26037994 -0.70339584 0.66138983, + -0.28416303 -0.68649507 0.66931003, + -0.27807999 -0.68777102 0.67055398, + -0.28745884 -0.68037969 0.67412972, + -0.298316 -0.67801702 0.67178899, + -0.29802001 -0.67827702 0.67165798, + -0.30531088 -0.67663777 0.67003477, + -0.30623588 -0.67574579 0.67051274, + -0.30925086 -0.67505372 0.66982567, + -0.31022501 -0.67401999 0.670416, + -0.310173 -0.67403197 0.67042798, + -0.31060687 -0.67352575 0.67073578, + -0.30724606 -0.67429918 0.67150617, + -0.30688688 -0.67475873 0.67120874, + -0.30046278 -0.67621052 0.67265254, + -0.29925913 -0.67790824 0.67147923, + -0.28953293 -0.68003684 0.6735878, + -0.28726697 -0.68356293 0.67098397, + -0.2751269 -0.68610173 0.67347574, + -0.27183709 -0.69176626 0.66900223, + -0.2575109 -0.69459277 0.67173576, + -0.25381592 -0.70166576 0.66576475, + -0.23683009 -0.70478421 0.66872323, + -0.23272593 -0.71359682 0.66077083, + -0.21335 -0.71684998 0.66378301, + -0.20908792 -0.72724074 0.65376079, + -0.18827809 -0.73037833 0.65658128, + -0.18386005 -0.74276519 0.64381319, + -0.16099107 -0.74579036 0.64643532, + -0.158363 -0.75451797 0.636886, + -0.13008995 -0.75766772 0.63954377, + -0.098997444 -0.8619644 0.49720925, + -0.077258073 -0.86363071 0.49816981, + -0.042047184 -0.95790166 0.2840009, + -0.030261215 -0.95831048 0.28412214, + -0.011903305 -0.99210536 0.12484104, + -0.0073801763 -0.99214852 0.12484694, + 0.0037759286 -0.99922067 -0.039290585, + 0.00098893233 -0.99922734 -0.039290916, + 0.004539819 -0.98009276 -0.19848795, + -0.0051234607 -0.98009014 -0.19848703, + -0.0015169707 -0.99923849 -0.03898922, + -0.0042704083 -0.9992305 -0.038988881, + 0.0068685091 -0.99215287 0.12484199, + 0.0113968 -0.99211198 0.124836, + 0.029805988 -0.95823866 0.28441191, + 0.041645788 -0.95783275 0.28429195, + 0.077231929 -0.86230731 0.50046116, + 0.099126652 -0.86063057 0.49948877, + 0.13066204 -0.75382727 0.64395022, + 0.15977396 -0.75057781 0.64117479, + 0.16136402 -0.74527109 0.64694107, + 0.18384202 -0.74229604 0.64435905, + 0.18800201 -0.73061502 0.65639699, + 0.20917295 -0.72742385 0.65352982, + 0.21353804 -0.71679306 0.66378409, + 0.23266603 -0.71358109 0.66080904, + 0.23678194 -0.7047438 0.66878283, + 0.25375009 -0.70163023 0.66582721, + 0.25742489 -0.69459766 0.67176372, + 0.27172884 -0.69177657 0.66903555, + 0.27486596 -0.68637884 0.67329985, + 0.28693506 -0.6838572 0.6708262, + 0.28920221 -0.68033248 0.67343146, + 0.29889897 -0.67821193 0.67133296, + 0.30010796 -0.67650896 0.67251092, + 0.306501 -0.67506599 0.671076, + 0.30685607 -0.67461115 0.67137116, + 0.31013712 -0.67385721 0.67062026, + 0.30929199 -0.67484099 0.670021, + 0.30954894 -0.6747818 0.66996181, + 0.30859601 -0.67579108 0.66938406, + 0.30518106 -0.67657316 0.67015916, + 0.30461687 -0.67711574 0.66986775, + 0.29728806 -0.67876017 0.67149419, + 0.29730412 -0.67874622 0.67150122, + 0.28632379 -0.68112755 0.67385751, + 0.28860086 -0.67931569 0.67471468, + 0.27322409 -0.68250924 0.67788625, + 0.26481196 -0.68850493 0.67515594, + 0.26901495 -0.68767381 0.67434084, + 0.24426094 -0.70352781 0.66737181, + 0.24440303 -0.70350206 0.66734707, + 0.23760501 -0.70739001 0.66569, + 0.20312503 -0.71306407 0.67102903, + 0.22311592 -0.70304579 0.67523777, + 0.18299706 -0.70904726 0.68100226, + 0.20985202 -0.69706309 0.68561304, + 0.16201094 -0.70351875 0.69196373, + 0.19997603 -0.68852508 0.69709605, + 0.14456098 -0.69533795 0.70399392, + 0.20378707 -0.67445123 0.70963824, + 0.14075501 -0.68204904 0.71763307, + 0.12518403 -0.6864652 0.71630615, + 0.023316406 -0.69172019 0.72178918, + -0.10944799 -0.70764595 0.69803894, + -0.30459306 -0.67809421 0.66888815, + -0.35999608 -0.6712122 0.6479792, + -0.56911707 -0.59157103 0.57109505, + -0.57900298 -0.58795202 0.564861, + -0.71518803 -0.50401801 0.48422301, + -0.77400482 -0.46729589 0.42725992, + -0.86125869 -0.37503484 0.34290287, + -0.8850376 -0.35045183 0.30641785, + -0.95594811 -0.22097903 0.19321403, + -0.96638274 -0.19961095 0.16204895, + -0.99733949 -0.056595426 0.045945622, + -0.99782866 -0.052617382 0.039614685, + -0.99832112 0.046274602 -0.034839205, + -0.99855167 0.044070184 -0.030861888, + -0.9891541 0.12031402 -0.084254608, + -0.99030167 0.11633696 -0.075948969, + -0.97701287 0.17850798 -0.11653598, + -0.9788959 0.17442198 -0.10648798, + -0.96345878 0.22861694 -0.13957597, + -0.96618086 0.22436798 -0.12709698, + -0.94922686 0.27372596 -0.15505598, + -0.954059 0.267865 -0.134238, + -0.93668765 0.31305489 -0.15688494, + -0.94174522 0.30803606 -0.13501804, + -0.92378026 0.35071209 -0.15372403, + -0.92863297 0.346728 -0.13198701, + -0.90972698 0.38804299 -0.147714, + -0.91429102 0.384942 -0.12606201, + -0.89424086 0.42535794 -0.13929799, + -0.8984521 0.42301306 -0.11766002, + -0.87720287 0.46255994 -0.12865998, + -0.88098061 0.46086279 -0.10713895, + -0.85828191 0.49984893 -0.11620299, + -0.86159128 0.49868417 -0.094734535, + -0.83698982 0.53760386 -0.10212798, + -0.83980817 0.53686512 -0.080610722, + -0.81297982 0.5758369 -0.086462379, + -0.81527299 0.57543099 -0.064878501, + -0.78640682 0.6138199 -0.069206685, + -0.78810811 0.61365807 -0.048058007, + -0.75700063 0.6514197 -0.051015273, + -0.75813502 0.65140599 -0.0300264, + -0.72500682 0.6886788 -0.0093042981, + -0.72440577 0.68864274 -0.031742889, + -0.69036078 0.72340977 -0.0089679277, + -0.6881572 0.72549319 -0.0099662431, + -0.68755066 0.72539663 -0.032768086, + -0.72340721 0.68971825 -0.031156411, + -0.72223508 0.68962306 -0.052882608, + -0.75544685 0.65329194 -0.050096594, + -0.75366712 0.65329504 -0.072052307, + -0.7843588 0.61656886 -0.068001688, + -0.78192931 0.61676723 -0.090469733, + -0.81046635 0.57958329 -0.085015535, + -0.80743271 0.5800758 -0.10753796, + -0.83411729 0.54234618 -0.10054304, + -0.8304978 0.54324186 -0.12313297, + -0.8551448 0.50556487 -0.11459297, + -0.85094303 0.50698 -0.13735799, + -0.87386316 0.46925411 -0.12713704, + -0.8690778 0.47131887 -0.15020797, + -0.89077044 0.43299621 -0.13799407, + -0.88544399 0.43585101 -0.16131601, + -0.9061991 0.39656106 -0.14677401, + -0.90034801 0.40038699 -0.170481, + -0.9202581 0.36003402 -0.15329902, + -0.91390568 0.36502987 -0.17756595, + -0.93325257 0.32302985 -0.15713492, + -0.92683923 0.32909608 -0.18073404, + -0.94594437 0.28428009 -0.15612206, + -0.94211262 0.28879091 -0.17036293, + -0.96053988 0.23956397 -0.14132299, + -0.95748246 0.24425712 -0.15351208, + -0.97473437 0.18911807 -0.11885805, + -0.97212511 0.19460402 -0.13077502, + -0.98781687 0.12916498 -0.086799495, + -0.985865 0.135515 -0.0985182, + -0.99731827 0.059196714 -0.04303541, + -0.99654454 0.065196268 -0.051462874, + -0.99868578 -0.04022849 0.031754494, + -0.99827111 -0.045061205 0.037739504, + -0.96913749 -0.1889931 0.15828508, + -0.97143722 -0.18276404 0.15135103, + -0.95897609 -0.22246803 0.17570701, + -0.94321173 -0.25621295 0.21143895, + -0.85681832 -0.39768615 0.3281891, + -0.87797511 -0.37184703 0.30147904, + -0.78845799 -0.47778499 0.38736999, + -0.85463309 -0.41055706 0.31787604, + -0.87509942 -0.37930119 0.30055216, + -0.864097 -0.393051 0.31439999, + -0.93049324 -0.28605404 0.22881305, + -0.91862065 -0.30648187 0.24940892, + -0.97332251 -0.17796092 0.14482093, + -0.97538441 -0.17174089 0.13831191, + -0.99732548 -0.056923926 0.045843724, + -0.99713349 -0.058678228 0.047768023, + -0.99389249 0.085580736 -0.069668531, + -0.9957009 0.074166894 -0.055489492, + -0.97397321 0.18149005 -0.13578503, + -0.97881967 0.16823794 -0.11665396, + -0.96475554 0.2162489 -0.14994393, + -0.96890575 0.20797695 -0.13404197, + -0.94949561 0.26374692 -0.16998693, + -0.95357889 0.25763896 -0.15591499, + -0.93366361 0.30641085 -0.18543091, + -0.93779802 0.30160299 -0.17196099, + -0.91756076 0.3453989 -0.19693096, + -0.92237443 0.34096915 -0.18156409, + -0.90155989 0.38188693 -0.20335197, + -0.9094677 0.37596586 -0.17753394, + -0.88844973 0.41502884 -0.19597992, + -0.89599776 0.41032192 -0.16977595, + -0.87443787 0.44827995 -0.18548198, + -0.88119489 0.44481194 -0.16011798, + -0.8589958 0.48172289 -0.17340496, + -0.86499619 0.47924411 -0.14868303, + -0.84178197 0.51557499 -0.15995499, + -0.84707171 0.5138768 -0.13564695, + -0.82235956 0.55012476 -0.14521493, + -0.8269226 0.54905975 -0.12137694, + -0.8003642 0.58538109 -0.12940703, + -0.80423713 0.58480406 -0.10586301, + -0.77597362 0.62067771 -0.11235695, + -0.779176 0.62045902 -0.088968202, + -0.74893004 0.65594006 -0.094055817, + -0.75146019 0.65596616 -0.070824213, + -0.71877038 0.69123036 -0.074631639, + -0.72060418 0.69139618 -0.051971111, + -0.68534297 0.72617191 -0.054585192, + -0.68653721 0.72638118 -0.032204706, + -0.64978373 0.76006663 -0.0089302249, + -0.64914894 0.75991488 -0.033691395, + -0.61618894 0.78755486 -0.0082712388, + -0.6098637 0.79243165 -0.010875095, + -0.60926509 0.79221612 -0.034492705, + -0.64808077 0.76085073 -0.033127088, + -0.64688206 0.76052511 -0.056083009, + -0.68362606 0.72785604 -0.053673908, + -0.68176705 0.72751206 -0.076941505, + -0.71640021 0.69382018 -0.073378213, + -0.71380579 0.69355482 -0.097278081, + -0.74594903 0.65954703 -0.092508204, + -0.74263 0.65947002 -0.116619, + -0.7724458 0.62537783 -0.11058997, + -0.76838088 0.62560493 -0.13494198, + -0.79637384 0.59120786 -0.12752298, + -0.79151487 0.59187096 -0.15229198, + -0.81799781 0.55707586 -0.14333896, + -0.8122921 0.55832708 -0.16867901, + -0.83709443 0.52368122 -0.15821208, + -0.83052742 0.52568221 -0.18407209, + -0.85400969 0.49102482 -0.17193595, + -0.84647483 0.49399087 -0.19862896, + -0.8692041 0.45875707 -0.18446201, + -0.86058688 0.46296194 -0.21226497, + -0.88301468 0.42663985 -0.19561093, + -0.8737787 0.43210685 -0.22314693, + -0.89590627 0.39471716 -0.20383908, + -0.89033222 0.39878508 -0.21972506, + -0.88309699 0.41413 -0.22053599, + -0.86076629 0.44926816 -0.23924808, + -0.86689788 0.44571593 -0.22321597, + -0.84380603 0.479839 -0.24030399, + -0.8541519 0.47506195 -0.21151997, + -0.83099073 0.5081898 -0.22626893, + -0.84046203 0.50467402 -0.197301, + -0.8166936 0.53745878 -0.21011789, + -0.82486689 0.53511095 -0.18234798, + -0.79999202 0.56794101 -0.193535, + -0.80701703 0.56650299 -0.16672701, + -0.78067362 0.59951371 -0.17644291, + -0.78669786 0.59876996 -0.15026999, + -0.75898647 0.63152254 -0.15848888, + -0.76405472 0.63129973 -0.13296996, + -0.73466009 0.66386908 -0.13983001, + -0.73885316 0.66401517 -0.11480403, + -0.70727897 0.69659996 -0.12043699, + -0.71066576 0.69698775 -0.095719762, + -0.67667305 0.72943705 -0.10017601, + -0.67929405 0.72995204 -0.075694107, + -0.64323723 0.76158327 -0.078974232, + -0.64509684 0.76210582 -0.055179186, + -0.60700506 0.7926231 -0.057388809, + -0.60819006 0.79306513 -0.033950903, + -0.56843317 0.82268029 -0.0090003731, + -0.56781203 0.82240498 -0.035207, + -0.56672782 0.82317472 -0.034683891, + -0.56557018 0.82261831 -0.058562621, + -0.60523003 0.7940411 -0.056528207, + -0.603396 0.79334199 -0.080757901, + -0.64071202 0.763834 -0.077754103, + -0.63810319 0.76307219 -0.10269002, + -0.6733678 0.73270279 -0.098602675, + -0.66996074 0.73199576 -0.12383395, + -0.70327306 0.70096004 -0.11858302, + -0.69901484 0.7004258 -0.14415897, + -0.73000824 0.66940725 -0.13777505, + -0.72481191 0.66916895 -0.16389199, + -0.75373918 0.63830817 -0.15633304, + -0.74749404 0.63850904 -0.18319102, + -0.77489889 0.60757393 -0.17431499, + -0.7675423 0.60838223 -0.20186608, + -0.79370612 0.57734907 -0.19156903, + -0.78506768 0.57898182 -0.22011092, + -0.80985385 0.54834294 -0.20846297, + -0.79969782 0.55106986 -0.23833895, + -0.82362211 0.52053905 -0.22513503, + -0.81241083 0.5244509 -0.25483295, + -0.83586913 0.49372905 -0.23990503, + -0.82941312 0.49665305 -0.25575304, + -0.85225159 0.46508878 -0.23949888, + -0.84652269 0.46843982 -0.2529099, + -0.88168925 0.41518408 -0.22415707, + -0.85982919 0.44461912 -0.25101307, + -0.88431901 0.40656599 -0.22953001, + -0.87560374 0.4142859 -0.24836494, + -0.89795673 0.37745184 -0.22628292, + -0.88887089 0.38701293 -0.24521297, + -0.50950098 -0.76020998 0.40310001, + -0.47558275 -0.77279764 0.4202438, + -0.79078001 -0.53336698 0.300311, + -0.85905987 -0.45541194 0.23370098, + -0.90536386 -0.36083397 0.22386397, + -0.95237464 -0.26753792 0.14630795, + -0.9917081 -0.10353801 0.07612551, + -0.9972235 -0.062611833 0.04031162, + -0.99205351 0.10578695 -0.068108968, + -0.98816651 0.12622994 -0.087137453, + -0.92885262 0.30486587 -0.21045093, + -0.92331636 0.31450713 -0.22039108, + -0.88429713 0.38238505 -0.26795602, + -0.89129686 0.37351596 -0.25705197, + -0.88047725 0.39054209 -0.26876906, + -0.89448243 0.37404278 -0.24493486, + -0.87224412 0.41230506 -0.26304904, + -0.85752213 0.42757306 -0.28607202, + -0.84563231 0.44362915 -0.29681513, + -0.84958154 0.43958575 -0.29150581, + -0.85600859 0.43083879 -0.28570485, + -0.8655259 0.41971293 -0.27332398, + -0.929268 0.30955401 -0.20158701, + -0.94901049 0.26981312 -0.16303408, + -0.99210602 0.10733 -0.064853899, + -0.99420613 0.093615711 -0.052824207, + -0.99219298 -0.108614 0.061287399, + -0.99324036 -0.10184204 0.055694219, + -0.99420238 -0.095817938 0.04879272, + -0.9419865 -0.29910386 0.15230992, + -0.94018286 -0.30309197 0.15553598, + -0.94857275 -0.28581795 0.13607997, + -0.85215682 -0.47246987 0.22494695, + -0.84349227 -0.48346817 0.2340501, + -0.70922363 -0.63453871 0.30718485, + -0.6891166 -0.64948064 0.32139283, + -0.54426211 -0.75189215 0.37207109, + -0.50967795 -0.76667589 0.39043093, + -0.36160392 -0.83080584 0.42308891, + 0.094552182 -0.86336488 0.49564195, + 0.13711798 -0.85905886 0.49316993, + 0.18574998 -0.83882189 0.51173693, + 0.196024 -0.837116 0.51069701, + 0.23774306 -0.81541717 0.52780014, + 0.24010102 -0.81493014 0.52748507, + 0.27671295 -0.7922008 0.54391891, + 0.2869339 -0.78972572 0.54221982, + 0.26180598 -0.83769387 0.47929794, + 0.24228004 -0.84210813 0.48182407, + 0.19591308 -0.8652283 0.46151718, + 0.16296202 -0.8705321 0.46434605, + 0.085047141 -0.8838104 0.4600502, + 0.13084796 -0.87939769 0.45775384, + 0.18358 -0.85851002 0.47881001, + 0.195032 -0.85658199 0.477734, + 0.24074094 -0.83348781 0.49733487, + 0.24275789 -0.83305657 0.49707675, + 0.27061397 -0.81632686 0.51027292, + 0.291127 -0.81123602 0.50709099, + 0.30543202 -0.80110711 0.51472205, + 0.31809011 -0.79761332 0.51247621, + 0.33071896 -0.78741688 0.52019197, + 0.33607602 -0.7858361 0.51914805, + 0.34621599 -0.77661997 0.52630401, + 0.34604409 -0.77667218 0.52634013, + 0.35365519 -0.76895636 0.53257322, + 0.34863281 -0.77050465 0.53364575, + 0.35350099 -0.76503801 0.538288, + 0.34503096 -0.76761991 0.54010493, + 0.34710413 -0.76505631 0.54240918, + 0.33509809 -0.76861018 0.54492915, + 0.33556592 -0.76797384 0.54553789, + 0.32033399 -0.77228498 0.54860002, + 0.32544103 -0.76454014 0.55638707, + 0.21696508 -0.8470453 0.48522219, + 0.25702593 -0.8385638 0.48036289, + 0.30439097 -0.77018785 0.56049693, + 0.30550098 -0.75200188 0.58409095, + 0.29734403 -0.7658661 0.57011908, + 0.31389481 -0.76160455 0.56694663, + 0.31511503 -0.75977415 0.56872308, + 0.32919499 -0.75593799 0.56585199, + 0.32927397 -0.75583088 0.56594896, + 0.34005988 -0.7527647 0.56365281, + 0.33793303 -0.75540215 0.56139904, + 0.34503412 -0.7533313 0.55986017, + 0.34075102 -0.7581501 0.55596507, + 0.34431812 -0.7571013 0.55519617, + 0.33744389 -0.7640847 0.54982382, + 0.33670697 -0.76429886 0.54997796, + 0.3279511 -0.77228415 0.54408211, + 0.32147396 -0.77410185 0.54536295, + 0.31050184 -0.78301263 0.53896177, + 0.29748297 -0.78643489 0.54131693, + 0.27512291 -0.80222672 0.52984881, + 0.27833796 -0.80145389 0.52933896, + 0.24159503 -0.82403213 0.51244807, + 0.239271 -0.82452101 0.512752, + 0.194721 -0.84734201 0.49406001, + 0.18376401 -0.8491661 0.49512407, + 0.13432404 -0.86923331 0.47580519, + 0.11204197 -0.87165982 0.47713289, + 0.078868203 -0.88181603 0.46495199, + -0.00068212935 -0.88457143 0.4664042, + -0.0018309694 -0.88478768 0.46599081, + -0.104457 -0.87994897 0.463442, + -0.091929495 -0.8789559 0.46795893, + -0.21987693 -0.86109167 0.45844883, + -0.19165595 -0.86211181 0.46907488, + -0.34674001 -0.823901 0.448284, + -0.34750813 -0.82375628 0.44795516, + -0.29318002 -0.82685012 0.47996306, + -0.43634993 -0.77817589 0.45170894, + -0.47168812 -0.76708317 0.43484908, + -0.59657496 -0.69817692 0.39578694, + -0.56405407 -0.71415704 0.41451505, + -0.66859424 -0.64314222 0.37329611, + -0.63673615 -0.6627022 0.3941991, + -0.71402705 -0.60171306 0.35792002, + -0.99540436 -0.077366032 0.05643402, + -0.96162522 -0.22166106 0.16168904, + -0.97487265 -0.18371294 0.12598796, + -0.83485001 -0.47428 0.27943501, + -0.89435476 -0.3854349 0.22708894, + -0.85629702 -0.43784401 0.273949, + -0.94401073 -0.27968195 0.17499095, + -0.9034459 -0.35355097 0.24246097, + -0.90423512 -0.35202503 0.24173804, + -0.83006042 -0.4597162 0.31569114, + -0.87778568 -0.40207785 0.26043391, + -0.74853301 -0.55654901 0.360488, + -0.83733582 -0.47051087 0.27836695, + -0.70860434 -0.60728431 0.35928518, + -0.77246583 -0.5548209 0.30898294, + -0.67409778 -0.64531976 0.35938087, + -0.70240474 -0.62556279 0.33955687, + -0.60350305 -0.70077908 0.38038507, + -0.63156909 -0.68498105 0.36321002, + -0.62371862 -0.68255156 0.38091776, + -0.70735508 -0.62713206 0.32612002, + -0.79719818 -0.53562415 0.27853507, + -0.77601188 -0.55631691 0.29718196, + -0.85715902 -0.45429501 0.242682, + -0.8388958 -0.47688088 0.26237094, + -0.90909898 -0.364986 0.200809, + -0.8956089 -0.38688293 0.21955897, + -0.95193338 -0.26639584 0.15118191, + -0.93396264 -0.30584389 0.18485995, + -0.98236364 -0.16002095 0.096720666, + -0.96970838 -0.20345907 0.13516705, + -0.99766755 -0.056856874 0.037772581, + -0.99550498 -0.076438598 0.0559198, + -0.98804462 0.12442695 -0.091026373, + -0.98705 0.128923 -0.095452301, + -0.94207734 0.26955608 -0.19957407, + -0.94626302 0.26147801 -0.190304, + -0.91132772 0.33285788 -0.24225491, + -0.92935514 0.30631503 -0.20608303, + -0.90184247 0.3584848 -0.24118185, + -0.91311687 0.34438896 -0.21820597, + -0.92229825 0.32237208 -0.21317205, + -0.94923538 0.26238808 -0.17350706, + -0.94011074 0.27801794 -0.19722496, + -0.96847361 0.20318292 -0.14413695, + -0.958121 0.22693799 -0.174652, + -0.99172664 0.10172896 -0.078291073, + -0.99095237 0.10571904 -0.082685627, + -0.99508578 -0.077994585 0.061001584, + -0.9953109 -0.076349296 0.059388991, + -0.94835967 -0.25036991 0.19475293, + -0.96125066 -0.22037593 0.16562495, + -0.8777793 -0.38296616 0.2878201, + -0.90224671 -0.34844589 0.25403991, + -0.79440916 -0.49079412 0.35782009, + -0.82797301 -0.45745701 0.32433599, + -0.7082684 -0.57588637 0.40830225, + -0.78371382 -0.51589191 0.34590191, + -0.61996412 -0.65169817 0.4369601, + -0.70655096 -0.59769392 0.37887695, + -0.59380299 -0.67957699 0.43078199, + -0.63081825 -0.65987027 0.40821514, + -0.51981795 -0.72649795 0.44943294, + -0.55690092 -0.71088994 0.42953095, + -0.43002307 -0.77271914 0.46688905, + -0.397571 -0.78113699 0.481417, + -0.27479288 -0.81853658 0.50446677, + -0.27949604 -0.81805611 0.50265908, + -0.13247195 -0.84450269 0.5189088, + -0.16890801 -0.84559214 0.50640309, + -0.049355317 -0.85687327 0.51315916, + -0.068792805 -0.85940415 0.50664806, + 0.026555404 -0.86114115 0.50767207, + 0.020537892 -0.86250669 0.50562882, + 0.095706061 -0.85872871 0.5034138, + 0.12169304 -0.85003829 0.51247019, + 0.14200097 -0.8477248 0.51107585, + 0.18743591 -0.82830757 0.52799076, + 0.19733605 -0.82667118 0.52694714, + 0.23788106 -0.80522716 0.54315913, + 0.24003303 -0.80478811 0.54286307, + 0.27442807 -0.7832042 0.55792511, + 0.2710841 -0.78397632 0.5584752, + 0.29137695 -0.7694298 0.56839889, + 0.30465502 -0.7660951 0.56593609, + 0.31339115 -0.75893337 0.57079428, + 0.32073203 -0.75697213 0.56931907, + 0.32828587 -0.7500397 0.57416785, + 0.33008999 -0.74953997 0.57378602, + 0.33554497 -0.74397594 0.57784891, + 0.3332859 -0.74460882 0.57834089, + 0.3370671 -0.74034119 0.58161914, + 0.33095309 -0.74204516 0.58295715, + 0.33284211 -0.73969424 0.58486623, + 0.32297796 -0.74237996 0.58698994, + 0.32314989 -0.74214476 0.58719277, + 0.31001714 -0.74558234 0.5899123, + 0.30836511 -0.74807626 0.58761626, + 0.29273897 -0.75194889 0.59065795, + 0.29032114 -0.75597936 0.58669329, + 0.27238193 -0.76013482 0.5899179, + 0.27402505 -0.7570532 0.5931111, + 0.24483591 -0.76322669 0.59794676, + 0.18419799 -0.86810291 0.46094295, + 0.16256206 -0.87146729 0.46272919, + 0.084138893 -0.96352488 0.25404796, + 0.072812706 -0.96438712 0.25427502, + 0.024502404 -0.99449313 0.10189801, + 0.021319192 -0.99456567 0.10190497, + -0.019713394 -0.99831873 -0.05450689, + -0.015269607 -0.99839646 -0.054511126, + -0.047566976 -0.97702152 -0.20776489, + -0.035987608 -0.97749525 -0.20786504, + -0.059634984 -0.93294978 -0.35503292, + -0.041939996 -0.93379086 -0.35535297, + -0.057842914 -0.8665362 -0.49575111, + -0.03441279 -0.86747569 -0.49628782, + -0.0434343 -0.775204 -0.630216, + -0.014569804 -0.77585417 -0.63074416, + -0.017183697 -0.6639148 -0.74761081, + 0.0164057 -0.66392303 -0.747621, + 0.013828804 -0.77632016 -0.63018715, + 0.042614199 -0.77568901 -0.62967497, + 0.033703785 -0.8673926 -0.49648178, + 0.057244387 -0.86646283 -0.49594888, + 0.041241415 -0.93413734 -0.35452312, + 0.058966808 -0.9333061 -0.35420704, + 0.035670608 -0.97718221 -0.20938605, + 0.047251519 -0.97671235 -0.20928508, + 0.0150387 -0.99830502 -0.056221701, + 0.019661101 -0.99822497 -0.056217201, + -0.021817207 -0.99455535 0.10190003, + -0.024962705 -0.9944821 0.10189302, + -0.073042333 -0.96450537 0.2537601, + -0.084361628 -0.96364135 0.25353208, + -0.16129392 -0.87400359 0.45836878, + -0.18266004 -0.87070018 0.45663613, + -0.24147096 -0.7708149 0.58952194, + -0.27003399 -0.76481199 0.58493102, + -0.27215105 -0.76089716 0.58904111, + -0.289619 -0.756854 0.58591199, + -0.29292604 -0.75134212 0.59133708, + -0.30868497 -0.74743593 0.58826292, + -0.30992398 -0.74556196 0.58998692, + -0.3230581 -0.74212515 0.58726811, + -0.32303104 -0.74216306 0.58723503, + -0.33273298 -0.73952293 0.58514494, + -0.331076 -0.741588 0.58346897, + -0.33745584 -0.73980963 0.58206969, + -0.33370814 -0.74404633 0.5788213, + -0.33631498 -0.74331492 0.57825196, + -0.33068487 -0.74906874 0.57405883, + -0.3289091 -0.74956119 0.57443613, + -0.32136908 -0.75649118 0.56959909, + -0.31414196 -0.75842589 0.57105595, + -0.30564511 -0.76540631 0.56633419, + -0.29221293 -0.76878881 0.56883687, + -0.27278206 -0.7827642 0.55934811, + -0.27632704 -0.78194112 0.55875903, + -0.24129707 -0.80401421 0.5434491, + -0.23961797 -0.8043589 0.54368192, + -0.19910291 -0.82588059 0.52752179, + -0.18942299 -0.82749599 0.52855402, + -0.14387898 -0.8470639 0.51164591, + -0.12376403 -0.8493892 0.51305014, + -0.072586894 -0.86591285 0.49489993, + -0.038247094 -0.86756784 0.49584588, + 0.014838296 -0.87862879 0.47727489, + 0.068026394 -0.87668985 0.47622195, + 0.089827679 -0.87883276 0.46859789, + 0.21766904 -0.86124218 0.45921913, + 0.18966204 -0.86219716 0.46972811, + 0.34465998 -0.82432985 0.44909894, + 0.34440988 -0.8243767 0.44920486, + 0.47241694 -0.7739349 0.42171896, + 0.50802088 -0.76082879 0.40379992, + 0.63035876 -0.68571174 0.36393288, + 0.62231797 -0.68325692 0.38194293, + 0.70672196 -0.62752295 0.32673997, + 0.7961452 -0.53671014 0.27945507, + 0.77568412 -0.55664408 0.29742503, + 0.85694283 -0.45458889 0.24289495, + 0.83918631 -0.47655219 0.2620391, + 0.90958309 -0.36410803 0.20021003, + 0.89692485 -0.38476393 0.21790497, + 0.95235562 -0.2653859 0.15029694, + 0.93477136 -0.30422312 0.18344206, + 0.9826411 -0.15887001 0.095796317, + 0.97061086 -0.20067698 0.13282798, + 0.99771553 -0.056332573 0.03728658, + 0.99567753 -0.075085863 0.054665472, + 0.98840791 0.12273899 -0.089358993, + 0.9872539 0.12801899 -0.094555683, + 0.94269425 0.26838705 -0.19823204, + 0.94946349 0.25505111 -0.18294309, + 0.93850178 0.28056294 -0.20124295, + 0.94918251 0.26244488 -0.17370991, + 0.93785787 0.28937396 -0.19153397, + 0.94408363 0.28046891 -0.17332993, + 0.92259037 0.32817012 -0.20280908, + 0.92795026 0.32205108 -0.18759404, + 0.90679473 0.36427787 -0.21219093, + 0.91175288 0.35974097 -0.19822498, + 0.89027458 0.39887783 -0.21978989, + 0.8960793 0.39463216 -0.20324208, + 0.87399483 0.43200791 -0.22249094, + 0.88319772 0.42654186 -0.19499692, + 0.86078089 0.46289793 -0.21161696, + 0.86925519 0.45875111 -0.18423605, + 0.84647489 0.49407393 -0.19842197, + 0.8539741 0.49111307 -0.17186101, + 0.83049458 0.52576375 -0.18398692, + 0.83705187 0.52376294 -0.15816599, + 0.81224102 0.55841601 -0.16863, + 0.81793582 0.55716586 -0.14334297, + 0.79144698 0.59196103 -0.15229499, + 0.79631388 0.59129596 -0.12748799, + 0.76830065 0.62571073 -0.13490795, + 0.77237481 0.62548083 -0.11050297, + 0.74252385 0.65960485 -0.11653197, + 0.74581641 0.65968043 -0.092626251, + 0.71367967 0.69366765 -0.097398154, + 0.71624398 0.69393402 -0.073824704, + 0.68160206 0.72761708 -0.077408105, + 0.68349558 0.72796959 -0.053795967, + 0.64676303 0.76061702 -0.056208499, + 0.64798784 0.76094782 -0.032712292, + 0.60911673 0.79234868 -0.034062188, + 0.60967875 0.7925567 -0.012071596, + 0.61368173 0.78948468 -0.010421896, + 0.61371464 0.78952754 0.00078709354, + 0.61380005 0.78946114 0.00078709511, + 0.65164715 0.75842917 -0.011886503, + 0.65169269 0.75848162 -0.0015307793, + 0.61367404 0.78955913 0.0007930611, + 0.61362606 0.78949714 -0.012547902, + 0.64958274 0.76021367 -0.010829496, + 0.6489982 0.76006317 -0.033246607, + 0.68645221 0.72648025 -0.031777613, + 0.68801785 0.72560883 -0.011105197, + 0.68744832 0.72551334 -0.032331716, + 0.7233656 0.68978059 -0.030739281, + 0.72216505 0.68968606 -0.053016808, + 0.75536633 0.65337527 -0.050225619, + 0.75692236 0.65150028 -0.051145427, + 0.78803682 0.61373991 -0.04818099, + 0.78947663 0.61181468 -0.049085177, + 0.81869316 0.57239211 -0.04592241, + 0.81999528 0.57045418 -0.046795916, + 0.8472507 0.52941483 -0.043429386, + 0.84574956 0.52985078 -0.062975168, + 0.87048101 0.48876199 -0.058091599, + 0.86858529 0.48948818 -0.077207826, + 0.89103872 0.44838384 -0.070724376, + 0.88878042 0.4494772 -0.089664742, + 0.9093771 0.40793505 -0.081377506, + 0.90680671 0.40946886 -0.10018396, + 0.92575598 0.36728799 -0.0898638, + 0.92297238 0.36931312 -0.10830504, + 0.94028711 0.32662702 -0.095786616, + 0.93737924 0.3291921 -0.11381003, + 0.95324749 0.28560415 -0.098740347, + 0.95033902 0.288728 -0.116155, + 0.96494597 0.24348401 -0.097953103, + 0.96216977 0.24717194 -0.11460997, + 0.97565091 0.19897898 -0.09226349, + 0.97322047 0.20309909 -0.10767005, + 0.98518634 0.15151305 -0.080322728, + 0.98336214 0.15572202 -0.093539506, + 0.99336654 0.098574355 -0.059211869, + 0.99267888 0.10112298 -0.06605079, + 0.99908745 0.03575892 -0.023356911, + 0.99898267 0.036877785 -0.025953891, + 0.99879938 -0.040061615 0.028194709, + 0.99861676 -0.041841589 0.031839292, + 0.98444098 -0.139834 0.106407, + 0.98122323 -0.14870404 0.12283403, + 0.93383026 -0.27579406 0.22781307, + 0.91715676 -0.29720095 0.26550895, + 0.8263939 -0.41992593 0.37514696, + 0.78148437 -0.44946721 0.4327372, + 0.66411507 -0.53858304 0.51853603, + 0.61031294 -0.55694592 0.56331992, + 0.48829895 -0.61355394 0.62057692, + 0.41469124 -0.62400234 0.66230839, + 0.28422096 -0.65746397 0.69782495, + 0.15911402 -0.65182906 0.74148607, + 0.039004795 -0.65973794 0.75048286, + -0.0097029256 -0.6499517 0.75991362, + -0.10293 -0.64652997 0.75591302, + -0.14189996 -0.63385975 0.76031971, + -0.19723095 -0.62776083 0.75300485, + -0.24405791 -0.60695678 0.7563327, + -0.27339584 -0.60203767 0.75020355, + -0.29339984 -0.59109372 0.75134861, + -0.31087103 -0.58767009 0.74699605, + -0.28509399 -0.60343802 0.74470401, + -0.30258185 -0.60005373 0.74052662, + -0.28606218 -0.61094737 0.73818141, + -0.30078188 -0.60806674 0.73470074, + -0.28903407 -0.61646712 0.73241216, + -0.30157602 -0.61397105 0.72944605, + -0.29285601 -0.62074703 0.72726101, + -0.30360681 -0.61856663 0.72470558, + -0.29701489 -0.62413776 0.72265774, + -0.30500394 -0.62248886 0.7207498, + -0.30062303 -0.62651604 0.71909904, + -0.30559093 -0.62547785 0.71790785, + -0.30300716 -0.6280663 0.71674234, + -0.30525517 -0.62759334 0.71620244, + -0.30327195 -0.62976283 0.71513981, + -0.30307615 -0.62980431 0.71518636, + -0.30124506 -0.63199419 0.71402717, + -0.29851496 -0.63256294 0.71466994, + -0.29682204 -0.63478005 0.71340805, + -0.29084891 -0.63600075 0.71477973, + -0.28860205 -0.63923317 0.7128042, + -0.28047308 -0.64084423 0.71460027, + -0.27742603 -0.64567506 0.71143407, + -0.26649687 -0.64775068 0.71372163, + -0.26314402 -0.65363604 0.70958805, + -0.24987502 -0.65602207 0.71217805, + -0.24571314 -0.6641534 0.70606339, + -0.23029414 -0.66674244 0.7088154, + -0.22588401 -0.67640901 0.701033, + -0.20797811 -0.6791724 0.7038964, + -0.20356996 -0.69015193 0.69444191, + -0.18383509 -0.69289935 0.69720536, + -0.17948894 -0.70539278 0.68571478, + -0.15809701 -0.70802003 0.68826807, + -0.15401101 -0.72186005 0.67468405, + -0.13089104 -0.72429127 0.67695624, + -0.12722299 -0.73939097 0.66114694, + -0.10222695 -0.74154264 0.66307169, + -0.10027397 -0.75192779 0.65157485, + -0.072022602 -0.75377399 0.653175, + -0.054832216 -0.85980016 0.50767809, + -0.03327059 -0.86061871 0.50816184, + -0.018142495 -0.95716566 0.2889719, + -0.0061667301 -0.95730501 0.28901401, + -0.0025578192 -0.99179476 0.12781496, + 0.0020778999 -0.9917959 0.12781498, + 0.0057097515 -0.95722425 0.28929105, + 0.017703399 -0.9570899 0.28924996, + 0.032916289 -0.86014169 0.50899184, + 0.054743506 -0.85931712 0.50850505, + 0.072146185 -0.75167584 0.6555748, + 0.10090798 -0.74979293 0.65393293, + 0.10249098 -0.74136484 0.66322982, + 0.12726302 -0.73923016 0.6613192, + 0.13087296 -0.72436684 0.67687881, + 0.15414993 -0.72191775 0.67459077, + 0.158235 -0.708103 0.688151, + 0.17958996 -0.70547783 0.68560082, + 0.18394391 -0.69298065 0.69709563, + 0.20367095 -0.69023281 0.69433182, + 0.20805803 -0.67931807 0.70373207, + 0.22593197 -0.67655891 0.70087296, + 0.23033811 -0.66691327 0.70864034, + 0.24544802 -0.66437703 0.70594507, + 0.24948303 -0.65650105 0.71187407, + 0.26297098 -0.65407693 0.70924592, + 0.2664749 -0.64793575 0.71356177, + 0.2771129 -0.64591575 0.71133775, + 0.27999303 -0.64135408 0.71433103, + 0.28833899 -0.63970202 0.71249002, + 0.29060295 -0.6364488 0.71448082, + 0.29624403 -0.63529706 0.71318805, + 0.29795504 -0.63305807 0.71446508, + 0.30065987 -0.6324957 0.71382964, + 0.30226213 -0.63058221 0.71484524, + 0.30266905 -0.63049716 0.7147482, + 0.30448803 -0.62851107 0.71572405, + 0.30211589 -0.62900877 0.71629179, + 0.30503997 -0.62608492 0.71761292, + 0.29967317 -0.62720436 0.71889544, + 0.30411595 -0.62312788 0.72057283, + 0.29567698 -0.62486392 0.72257894, + 0.30242985 -0.6191687 0.72468364, + 0.29241386 -0.62119567 0.72705567, + 0.30190006 -0.61382711 0.72943318, + 0.28901702 -0.61639208 0.73248208, + 0.30200997 -0.60709196 0.73500293, + 0.28700206 -0.61003715 0.7385692, + 0.30387288 -0.59888774 0.74094176, + 0.28718701 -0.60213298 0.74495602, + 0.31393391 -0.58569688 0.7472648, + 0.29703581 -0.58904165 0.75153154, + 0.28509799 -0.59566301 0.75093597, + 0.25786796 -0.60043591 0.75695491, + 0.19033712 -0.63064533 0.75236845, + 0.13278097 -0.63670081 0.75959283, + 0.100619 -0.647021 0.755804, + 0.0080959862 -0.65029973 0.75963461, + -0.028116608 -0.65769416 0.75276017, + -0.14759494 -0.65074778 0.74481076, + -0.27764997 -0.65745592 0.70047295, + -0.41011608 -0.62416214 0.66500115, + -0.49212581 -0.61257374 0.61851877, + -0.61121631 -0.55694026 0.56234527, + -0.66502309 -0.53848004 0.51747805, + -0.78278071 -0.44869384 0.43119386, + -0.8267917 -0.41963586 0.37459487, + -0.91735339 -0.29696614 0.2650921, + -0.93385178 -0.27576393 0.22776094, + -0.98122889 -0.14868899 0.12280699, + -0.9844355 -0.13985007 0.10643705, + -0.99861646 -0.04184562 0.031847615, + -0.99879974 -0.04005789 0.028187092, + -0.99898303 0.036874998 -0.025947399, + -0.99908763 0.035757691 -0.023353893, + -0.99268055 0.10111395 -0.066039272, + -0.99334723 0.098646224 -0.059415415, + -0.98331487 0.15582898 -0.093857385, + -0.98514754 0.15161192 -0.080610663, + -0.97316164 0.20318793 -0.10803296, + -0.97563314 0.19900604 -0.092394508, + -0.9621619 0.24714097 -0.11474199, + -0.9649514 0.24344185 -0.098003842, + -0.950333 0.288717 -0.116231, + -0.95325053 0.28558484 -0.098765753, + -0.93738502 0.329166 -0.113838, + -0.94029552 0.32659984 -0.095795259, + -0.92299414 0.36925802 -0.10830701, + -0.92577261 0.36723781 -0.089897357, + -0.9068253 0.40941814 -0.10022303, + -0.90939111 0.40788805 -0.08145681, + -0.88881314 0.44939607 -0.08974611, + -0.89109188 0.44829294 -0.070630796, + -0.86864501 0.489398 -0.077107102, + -0.87056541 0.48865923 -0.057690226, + -0.8458336 0.52976775 -0.06254337, + -0.8473056 0.52933675 -0.043311179, + -0.82003456 0.57040769 -0.046671677, + -0.82104683 0.57020289 -0.027400393, + -0.79147285 0.61049992 -0.029336696, + -0.79204285 0.61041892 -0.007539229, + -0.78900886 0.61430895 -0.0094589889, + -0.78904414 0.61433607 -0.00080481113, + -0.78896266 0.61444068 -0.00079953461, + -0.78892785 0.61441296 -0.0094604893, + -0.75791985 0.65229481 -0.008297218, + -0.75794554 0.65231758 0.00054948067, + -0.75795811 0.65230304 0.00054948108, + -0.57941288 0.81502783 -0.0032060493, + -0.6601584 0.75111848 -0.0034790121, + -0.73387504 0.67927408 -0.0037762704, + -0.75807601 0.65216601 0.000570192, + -0.7580418 0.65213782 -0.0094270082, + -0.725034 0.68865001 -0.0093208496, + -0.72506505 0.68867904 -0.0013364002, + -0.69010597 0.72370797 0.00075148401, + -0.69006979 0.72366983 -0.010276497, + -0.69043475 0.72332174 -0.010271696, + -0.69047081 0.72335982 0.00073201983, + -0.69038802 0.72343898 0.00073202001, + -0.6542058 0.75630385 -0.0043993089, + -0.65417206 0.75626612 -0.010979301, + -0.65405732 0.75636536 -0.010980706, + -0.65409607 0.75640911 -0.0019316502, + -0.61611992 0.7876519 0.0008625589, + -0.61607826 0.78759933 -0.011621104, + -0.61617196 0.78752589 -0.011620099, + -0.61621308 0.78757912 0.00085813215, + -0.61620969 0.78758162 0.00085813162, + -0.57689065 0.81681353 -0.003568738, + -0.57685131 0.81675744 -0.012248806, + -0.57679981 0.81679368 -0.012249296, + -0.57684064 0.81685251 -0.0026019984, + -0.53616232 0.84411448 0.00089678151, + -0.53611785 0.84404582 -0.012820197, + -0.53601199 0.84411299 -0.0128211, + -0.53605598 0.84418201 0.00090149097, + -0.53607917 0.84416729 0.00090149132, + -0.53603518 0.84409827 -0.012823605, + -0.52531677 0.85085857 -0.0090479357, + -0.52471519 0.85052329 -0.035836212, + -0.48140293 0.87645191 -0.0091192992, + -0.48082995 0.87605888 -0.036377996, + -0.52365613 0.85119617 -0.035345607, + -0.52254188 0.85052884 -0.059587486, + -0.56376666 0.82391453 -0.057722867, + -0.56198418 0.82304132 -0.082322031, + -0.60081571 0.79541862 -0.079559162, + -0.59825522 0.79441327 -0.10487304, + -0.63471419 0.76610017 -0.10113602, + -0.63133818 0.76507521 -0.12677602, + -0.66580099 0.73609197 -0.121974, + -0.66154182 0.73516279 -0.14797997, + -0.694107 0.70571703 -0.14205299, + -0.68885964 0.70500362 -0.16864793, + -0.7192238 0.67571384 -0.16164096, + -0.71286792 0.67535394 -0.18898797, + -0.74122578 0.64642274 -0.18089195, + -0.73366082 0.64657885 -0.20899196, + -0.76063699 0.61771101 -0.199661, + -0.75166571 0.61857873 -0.22882092, + -0.77755213 0.58976108 -0.21816203, + -0.76690835 0.59159732 -0.24872512, + -0.79157013 0.56331706 -0.23683503, + -0.77976888 0.56624895 -0.26706296, + -0.80347818 0.53845215 -0.25395307, + -0.79694915 0.54069704 -0.26929304, + -0.81963611 0.51280308 -0.25540102, + -0.81394315 0.51543903 -0.26799104, + -0.83588487 0.48701194 -0.25321096, + -0.8289035 0.49112329 -0.26780015, + -0.85017282 0.46224889 -0.25205594, + -0.84202754 0.46808672 -0.26811284, + -0.86315012 0.43816105 -0.25097203, + -0.85326701 0.446538 -0.26933101, + -0.87532872 0.41404486 -0.24973291, + -0.86249411 0.42663407 -0.27219003, + -0.852045 0.44520599 -0.27533799, + -0.83550858 0.46056581 -0.29967386, + -0.8205533 0.47908419 -0.31172213, + -0.82032359 0.47929075 -0.31200886, + -0.79935414 0.50864905 -0.31985804, + -0.79956716 0.50840914 -0.3197071, + -0.79665691 0.51078391 -0.32316798, + -0.81440455 0.49038869 -0.31026483, + -0.82965612 0.47766006 -0.28898403, + -0.82402283 0.48474589 -0.29327095, + -0.83727813 0.47416207 -0.27227902, + -0.81765813 0.49924707 -0.28668404, + -0.82766014 0.49229506 -0.26948902, + -0.80770791 0.51716596 -0.28310296, + -0.81581455 0.51242375 -0.26808289, + -0.79517668 0.53729081 -0.2810919, + -0.80200237 0.53406823 -0.26751313, + -0.78067887 0.55875593 -0.27987897, + -0.78609985 0.55681592 -0.26833397, + -0.76360887 0.58166093 -0.28030697, + -0.76999652 0.58008665 -0.26571584, + -0.74582773 0.60562575 -0.2774139, + -0.75800753 0.60373062 -0.24684785, + -0.73265404 0.62997705 -0.25757903, + -0.74357104 0.62908804 -0.22660603, + -0.71716356 0.65566456 -0.23617886, + -0.72630382 0.65558982 -0.20660296, + -0.69855404 0.68247008 -0.21507403, + -0.70620722 0.68298423 -0.18655805, + -0.67660904 0.71032006 -0.19402502, + -0.68297958 0.71124959 -0.16632189, + -0.65121979 0.73895377 -0.17280094, + -0.65644103 0.74014407 -0.14584902, + -0.62283504 0.76759213 -0.15125802, + -0.62703615 0.76891017 -0.12491203, + -0.59149098 0.79587799 -0.12929299, + -0.59479123 0.79721028 -0.10334004, + -0.5569188 0.82367569 -0.10676996, + -0.5593968 0.82491672 -0.081163973, + -0.51904404 0.85064012 -0.083694905, + -0.52075374 0.85168058 -0.05878567, + -0.47870618 0.87589127 -0.060456824, + -0.47976193 0.87666386 -0.035901695, + -0.43614814 0.89912128 -0.036821414, + -0.43668285 0.89956772 -0.0092752064, + -0.45081288 0.89251673 -0.013473197, + -0.45085412 0.89259726 0.00087247923, + -0.49403483 0.86943573 -0.0033454788, + -0.49399495 0.86936486 -0.013176798, + -0.49404788 0.86933482 -0.013176397, + -0.49408889 0.86940682 -0.0028085292, + -0.49254295 0.87028289 -0.0030139696, + -0.30412197 0.95262587 -0.0037217496, + -0.26806888 0.96339953 0.0006180167, + -0.268042 0.963301 -0.014308, + -0.268121 0.96327901 -0.0143077, + -0.26814905 0.96337724 0.00061276217, + -0.26799291 0.96342063 0.00061276177, + -0.22054604 0.97537613 -0.00094495114, + -0.22055903 0.97537315 -0.00094389613, + -0.22053589 0.97527254 -0.014403993, + -0.20543402 0.97861511 -0.010463701, + -0.20516308 0.97798336 -0.038165815, + -0.2509211 0.96727133 -0.037747715, + -0.25030792 0.96610266 -0.063178875, + -0.295239 0.95338702 -0.0623473, + -0.2941561 0.95169634 -0.088012926, + -0.33807898 0.93711889 -0.086664692, + -0.3363989 0.93493378 -0.11284797, + -0.37897608 0.91873825 -0.11089303, + -0.37659693 0.91613686 -0.13736099, + -0.41701606 0.89885211 -0.13476901, + -0.41382614 0.89590228 -0.16157706, + -0.452057 0.87782699 -0.158317, + -0.44791105 0.87458611 -0.18567401, + -0.48413587 0.8559168 -0.18171096, + -0.47886789 0.85245681 -0.20976895, + -0.51307911 0.8334772 -0.20509905, + -0.50653511 0.82990819 -0.23382606, + -0.5381729 0.81124979 -0.22856894, + -0.53011793 0.80765086 -0.25821498, + -0.55933809 0.78956819 -0.25243405, + -0.54948318 0.78604633 -0.28319508, + -0.57666063 0.7686215 -0.27691782, + -0.56554109 0.7655791 -0.30667904, + -0.5907141 0.74901921 -0.30004507, + -0.58672303 0.74831897 -0.309475, + -0.60930222 0.73274821 -0.30303612, + -0.60697395 0.73259991 -0.30802596, + -0.62670195 0.71834594 -0.30203298, + -0.62322026 0.71849525 -0.30880612, + -0.6408323 0.70529735 -0.30313316, + -0.63634878 0.70592278 -0.31101987, + -0.62457108 0.71755308 -0.30826703, + -0.62305212 0.71782118 -0.31070706, + -0.61388403 0.72444308 -0.31357402, + -0.61079001 0.72511202 -0.31803799, + -0.60198236 0.73337841 -0.31586918, + -0.59348708 0.73550105 -0.32682002, + -0.57341987 0.74867684 -0.33267492, + -0.57555097 0.748115 -0.33024999, + -0.73334199 0.62805402 -0.26030299, + -0.72726995 0.63240296 -0.26672998, + -0.68321204 0.67282307 -0.28377903, + -0.67440879 0.67783284 -0.29277194, + -0.63327616 0.71048516 -0.30687505, + -0.62261474 0.71519476 -0.31756487, + -0.58480096 0.74137795 -0.32919097, + -0.58142072 0.74251765 -0.33259186, + -0.5589149 0.75677484 -0.3389779, + -0.57286912 0.75292116 -0.32393008, + -0.56143016 0.76015729 -0.32704312, + -0.55935878 0.76064664 -0.32944584, + -0.57868671 0.74837261 -0.32412985, + -0.58400708 0.74721909 -0.31717402, + -0.59675807 0.73863304 -0.31353003, + -0.59730786 0.73853081 -0.31272292, + -0.60665792 0.73203993 -0.30997398, + -0.60686105 0.73201108 -0.30964404, + -0.60245597 0.73509097 -0.310947, + -0.60598868 0.73485166 -0.30458286, + -0.58883411 0.74665821 -0.30947706, + -0.59151405 0.74674308 -0.30411503, + -0.57141298 0.76005 -0.30953401, + -0.57303828 0.76028138 -0.30594015, + -0.55014288 0.77469981 -0.31174195, + -0.55352712 0.77558219 -0.30344707, + -0.5282129 0.79074383 -0.30937895, + -0.5387429 0.79457182 -0.28002095, + -0.51133293 0.81052285 -0.28564197, + -0.52064091 0.81474382 -0.25519693, + -0.49076319 0.8314603 -0.26043308, + -0.49832377 0.83563459 -0.2310589, + -0.46574506 0.85291409 -0.23583703, + -0.47184688 0.85696381 -0.20730096, + -0.43720192 0.87415081 -0.21145895, + -0.442074 0.87799603 -0.183558, + -0.40531692 0.89482975 -0.18707696, + -0.4091149 0.89837575 -0.15983096, + -0.37006101 0.91464502 -0.162725, + -0.37294701 0.91783297 -0.13598999, + -0.33165115 0.93321443 -0.13826907, + -0.33376911 0.93599534 -0.11185304, + -0.29094607 0.94998026 -0.11352503, + -0.29241395 0.95229375 -0.087353081, + -0.24830197 0.96463287 -0.088484995, + -0.24922691 0.96640867 -0.06277068, + -0.20408303 0.97689509 -0.063451804, + -0.20458804 0.97811222 -0.037950207, + -0.15886505 0.98723423 -0.011423303, + -0.15865806 0.98659134 -0.038279217, + -0.11282497 0.99355179 -0.011194397, + -0.11267603 0.99289125 -0.038355108, + -0.15820992 0.98666954 -0.038114782, + -0.15781504 0.98541522 -0.063649118, + -0.20316507 0.97710836 -0.06311252, + -0.20240508 0.97526336 -0.088846333, + -0.24677603 0.96507615 -0.087918304, + -0.24552691 0.96265966 -0.11402997, + -0.28852984 0.95082355 -0.11262795, + -0.28668395 0.94789076 -0.13897997, + -0.32828909 0.93458521 -0.13702904, + -0.32572612 0.93119138 -0.16366206, + -0.36564904 0.91670209 -0.16111502, + -0.3622241 0.91289026 -0.18821605, + -0.39977592 0.89773077 -0.18509096, + -0.39532882 0.89354658 -0.2128139, + -0.43050215 0.8780303 -0.20911908, + -0.42488992 0.87356085 -0.23740295, + -0.45779306 0.85794109 -0.23315804, + -0.45078206 0.85324609 -0.26223403, + -0.48154688 0.83774781 -0.25747094, + -0.47285473 0.83288854 -0.28758481, + -0.50088805 0.81811613 -0.28248402, + -0.49107388 0.81360084 -0.31128794, + -0.51627886 0.79987383 -0.30603594, + -0.51349604 0.79890412 -0.31316802, + -0.53642732 0.78573447 -0.30800518, + -0.53544784 0.78551573 -0.3102589, + -0.55594492 0.7730999 -0.30535498, + -0.55403107 0.77289611 -0.30932403, + -0.57156897 0.76180887 -0.30488697, + -0.56894004 0.76180214 -0.30978203, + -0.57310581 0.75911772 -0.30869088, + -0.5736199 0.75907981 -0.30782795, + -0.56486088 0.76469982 -0.31010693, + -0.56502205 0.76468015 -0.30986202, + -0.55273819 0.77235329 -0.31297112, + -0.54893696 0.77295589 -0.31813097, + -0.53094906 0.78362709 -0.32252404, + -0.53303611 0.78324521 -0.3199991, + -0.54423594 0.77661687 -0.31729096, + -0.53239197 0.77927589 -0.33058697, + -0.55422086 0.7662698 -0.32506892, + -0.55941486 0.76477879 -0.31963792, + -0.59446925 0.74192524 -0.31008613, + -0.60566902 0.737598 -0.29852, + -0.6436677 0.70940763 -0.28711087, + -0.65302908 0.70470208 -0.27739504, + -0.69401437 0.6699273 -0.26370713, + -0.70124435 0.66534728 -0.25606513, + -0.74445719 0.62311614 -0.23981206, + -0.7501002 0.61867911 -0.23363607, + -0.79751313 0.56439805 -0.21313803, + -0.52186406 -0.11516301 -0.84521914, + -0.48106495 -0.40342593 -0.7783469, + -0.532754 -0.57638597 -0.61963898, + -0.61390305 -0.33269504 -0.71584707, + -0.60591513 -0.11304003 -0.78745717, + -0.57256085 -0.34554088 -0.74348879, + -0.56457216 -0.11574204 -0.81722832, + -0.53015888 -0.3619799 -0.76674783, + -0.57241571 -0.35005382 -0.74148667, + -0.48959669 -0.60014766 -0.63254863, + -0.274481 -0.90836602 -0.31548601, + -0.36798018 -0.82524943 -0.4284322, + -0.34986991 -0.83143079 -0.43164092, + -0.42240906 -0.73948306 -0.52415204, + -0.40284616 -0.74671322 -0.52927721, + -0.48920587 -0.58629489 -0.64570582, + -0.45724311 -0.59783912 -0.65842021, + -0.53009009 -0.3654781 -0.76513416, + -0.49843499 -0.37366101 -0.78226602, + -0.42433494 -0.61533195 -0.66430897, + -0.45581487 -0.60484588 -0.65298879, + -0.3726359 -0.76077181 -0.53138387, + -0.40098616 -0.75102139 -0.52457327, + -0.32927597 -0.84155989 -0.42819893, + -0.34690896 -0.8359139 -0.42532593, + -0.26148185 -0.91178149 -0.31667283, + -0.26961997 -0.9035759 -0.33294997, + -0.15352193 -0.97125751 -0.18190591, + -0.17293395 -0.96810079 -0.18131396, + -0.065198526 -0.99631834 -0.055668417, + -0.075996533 -0.99555534 -0.055625819, + 0.043844197 -0.99661589 0.069529496, + 0.044245616 -0.99659836 0.069528319, + 0.17406194 -0.96609962 0.19066693, + 0.18761691 -0.96365452 0.19018391, + 0.29049203 -0.9163081 0.27567002, + 0.31454402 -0.90899712 0.27347103, + 0.38294682 -0.8651306 0.32388386, + 0.40926194 -0.85449791 0.31990296, + 0.35566798 -0.89008087 0.28505498, + 0.34074503 -0.89536011 0.28674603, + 0.29560506 -0.91883624 0.26145306, + 0.26437506 -0.92759824 0.26394606, + 0.20976193 -0.94852865 0.23726191, + 0.15494898 -0.95839489 0.23972897, + 0.090932094 -0.97308487 0.21174797, + 0.0049442216 -0.97712123 0.21262604, + -0.060402501 -0.98068798 0.18601801, + -0.18203591 -0.96606654 0.18324392, + -0.23746689 -0.95796651 0.16096492, + -0.38869494 -0.90862888 0.15267499, + -0.42508906 -0.8947081 0.13710101, + -0.58595097 -0.80099702 0.122741, + -0.60107499 -0.79083902 0.11525, + -0.74735498 -0.65748 0.095815301, + -0.74745321 -0.65737724 0.09575434, + -0.86350888 -0.49906695 0.072694592, + -0.85778511 -0.50811803 0.077593811, + -0.93761802 -0.343683 0.052483302, + -0.93230945 -0.35674879 0.059408061, + -0.9795931 -0.19826102 0.033015605, + -0.97707474 -0.20928995 0.039020393, + -0.99793285 -0.063176289 0.011778698, + -0.99761379 -0.067545086 0.014297197, + -0.99804467 0.061150577 -0.012943695, + -0.9977029 0.065853789 -0.015880598, + -0.98281097 0.17947 -0.043279, + -0.97958177 0.19387795 -0.05320539, + -0.95373124 0.28994107 -0.079567924, + -0.94496155 0.31247184 -0.096999258, + -0.91199589 0.39175794 -0.12161098, + -0.89555103 0.42008099 -0.146698, + -0.85890859 0.48349577 -0.16884293, + -0.83412611 0.51388508 -0.20038903, + -0.79792315 0.56157309 -0.21898504, + -0.77989632 0.57821417 -0.23964609, + -0.76565015 0.58622414 -0.26480407, + -0.71524394 0.63691092 -0.28769898, + -0.70733798 0.64202499 -0.29576501, + -0.66262382 0.68024182 -0.3133699, + -0.65263194 0.68528491 -0.32319698, + -0.61143237 0.71569443 -0.33753821, + -0.60998368 0.71626264 -0.33895084, + -0.58557296 0.73271894 -0.34673798, + -0.60195589 0.72730285 -0.3296659, + -0.59000492 0.73538196 -0.33332798, + -0.58784091 0.73601294 -0.33574998, + -0.60881275 0.72176278 -0.32924989, + -0.61562693 0.71987396 -0.32060096, + -0.62917483 0.71003181 -0.3162179, + -0.63060915 0.70967019 -0.3141661, + -0.64008838 0.70253843 -0.31100917, + -0.64107704 0.70233107 -0.30943704, + -0.65896094 0.68651992 -0.30734497, + -0.65659159 0.68710756 -0.31107983, + -0.6583426 0.68571556 -0.31044981, + -0.65020478 0.68818378 -0.32192689, + -0.64766103 0.69014907 -0.32284603, + -0.63924593 0.69301891 -0.33330098, + -0.61721992 0.70904994 -0.34100997, + -0.61934477 0.70830578 -0.33869588, + -0.63235104 0.69889003 -0.33419302, + -0.61357975 0.70620477 -0.35326287, + -0.64040726 0.68688923 -0.34360111, + -0.63987708 0.68713003 -0.34410703, + -0.68485379 0.65154582 -0.32628691, + -0.69439876 0.64602774 -0.31695187, + -0.74322116 0.60065013 -0.29468906, + -0.76599997 0.583152 -0.27051401, + -0.80418885 0.53918588 -0.25011793, + -0.83469313 0.50742108 -0.21403603, + -0.87496185 0.44612694 -0.18818197, + -0.89580572 0.41520786 -0.15853894, + -0.93338537 0.33526713 -0.12801504, + -0.94503522 0.30920407 -0.10630802, + -0.97528934 0.20892808 -0.071831621, + -0.9795745 0.19211692 -0.059369769, + -0.99722511 0.071127005 -0.021980302, + -0.99769312 0.065418109 -0.018135602, + -0.99715263 -0.072668277 0.020145493, + -0.99758637 -0.067365624 0.016831705, + -0.97304851 -0.22372289 0.055898372, + -0.97655922 -0.20990005 0.047688611, + -0.92222244 -0.37705076 0.085664645, + -0.92979515 -0.36018103 0.07583341, + -0.84080929 -0.52971816 0.11152804, + -0.8503598 -0.51596588 0.10328398, + -0.72593778 -0.67438173 0.13499495, + -0.73107582 -0.66945881 0.13173097, + -0.57997906 -0.79930413 0.15728101, + -0.57256532 -0.80388635 0.16104607, + -0.41097194 -0.89388686 0.17907599, + -0.38482517 -0.9031114 0.19052409, + -0.23499691 -0.95106262 0.20063992, + -0.19055207 -0.95699334 0.21875508, + -0.068688102 -0.97255301 0.222312, + -0.0144248 -0.96956599 0.244405, + 0.07405901 -0.96700412 0.24375904, + 0.13062502 -0.95448822 0.26812205, + 0.18889003 -0.94540614 0.26557103, + 0.240878 -0.92612702 0.29028699, + 0.27595007 -0.91717327 0.28748006, + 0.318014 -0.895908 0.31018701, + 0.33651608 -0.88985223 0.30809107, + 0.37061089 -0.86843771 0.32933789, + 0.37762591 -0.8657918 0.32833391, + 0.41904393 -0.83428091 0.35829797, + 0.39207795 -0.84527588 0.36301997, + 0.32585785 -0.89353758 0.30888087, + 0.30068487 -0.90138668 0.31159389, + 0.20482405 -0.95298421 0.22331207, + 0.18913507 -0.95605338 0.22403108, + 0.068810485 -0.99264574 0.09959688, + 0.065501623 -0.99286735 0.099619135, + -0.04644189 -0.99847174 -0.029955093, + -0.038824484 -0.99879664 -0.029964888, + -0.14005001 -0.97699511 -0.16083102, + -0.12355305 -0.97915936 -0.16118807, + -0.21003005 -0.93483526 -0.28630507, + -0.18662906 -0.93936336 -0.28769109, + -0.25816494 -0.87762576 -0.4038859, + -0.38218409 -0.63450116 -0.67182118, + -0.40314916 -0.62835425 -0.66531324, + -0.31734988 -0.79239368 -0.52096182, + -0.34847403 -0.75619614 -0.55383503, + -0.26389709 -0.87022829 -0.41600615, + -0.29458797 -0.86217487 -0.41215593, + -0.21878503 -0.9278301 -0.30210003, + -0.23622493 -0.92395574 -0.30083793, + -0.32644889 -0.84590268 -0.42175785, + -0.30171987 -0.85322469 -0.42540884, + -0.36714607 -0.77075118 -0.52071714, + -0.33999592 -0.77925581 -0.52646285, + -0.42464399 -0.61884302 -0.66084099, + -0.4028531 -0.62561315 -0.6680702, + -0.47628319 -0.38238016 -0.79179531, + -0.45500085 -0.38725084 -0.8018797, + -0.43822214 -0.41564015 -0.79699731, + -0.47813982 -0.11689696 -0.87046969, + -0.44449511 -0.16863905 -0.87976426, + -0.45095301 0.00110088 -0.89254701, + -0.49456689 -0.0011190098 -0.86913884, + -0.48795301 -0.163003 -0.85751498, + -0.48831701 -0.16297001 -0.85731399, + -0.49493381 -0.0013147396 -0.86892968, + -0.51471591 -0.015877197 -0.8572138, + -0.53623605 -0.00031159603 -0.84406811, + -0.53695422 -0.00017651709 -0.84361142, + -0.5301019 -0.15924795 -0.83284581, + -0.52938676 -0.15932092 -0.83328658, + -0.57851607 -0.095550716 -0.81005514, + -0.58117533 0.00042997522 -0.8137784, + -0.57736504 0.00043037205 -0.81648612, + -0.57067114 -0.15183203 -0.80702019, + -0.57099801 -0.151794 -0.80679601, + -0.57769305 0.00024664204 -0.81625414, + -0.60015893 -0.015789898 -0.79972488, + -0.42376885 -0.015677594 -0.9056347, + -0.40694594 -0.0028441697 -0.91344786, + -0.40750808 -0.0031441906 -0.91319627, + -0.40148184 -0.17136894 -0.8996917, + -0.40092394 -0.17140798 -0.89993286, + -0.43345779 -0.11862994 -0.89333159, + -0.39475906 -0.42853606 -0.81272513, + -0.35348001 -0.59437102 -0.72233999, + -0.3627151 -0.59212011 -0.71960521, + -0.41197222 -0.39969325 -0.81885546, + -0.43310013 -0.39537215 -0.81000328, + -0.36158288 -0.64367378 -0.67449379, + -0.38261586 -0.63785177 -0.66839379, + -0.30141586 -0.79672563 -0.52380979, + -0.30831113 -0.77574438 -0.55060422, + -0.28095192 -0.8074677 -0.51871181, + -0.33716899 -0.70410198 -0.624946, + -0.31835315 -0.70898438 -0.62927932, + -0.36257803 -0.59381908 -0.71827304, + -0.34189704 -0.59877908 -0.72427207, + -0.38909709 -0.40833408 -0.8257522, + -0.36815417 -0.4121322 -0.83343244, + -0.32166603 -0.60686404 -0.72680604, + -0.34166703 -0.60235703 -0.72140807, + -0.29952288 -0.71561074 -0.63102078, + -0.31798196 -0.71111596 -0.62705797, + -0.26529896 -0.81120688 -0.52111393, + -0.2703599 -0.79316771 -0.5457018, + -0.24628694 -0.82117283 -0.51479888, + -0.29904205 -0.7187562 -0.62766516, + -0.28044099 -0.72299802 -0.63136899, + -0.32159799 -0.60830098 -0.72563398, + -0.30136696 -0.61256087 -0.73071682, + -0.345622 -0.41902301 -0.83962202, + -0.35187212 -0.43924314 -0.8265903, + -0.38844183 -0.12126994 -0.91345859, + -0.35640389 -0.17484394 -0.91782665, + -0.36197996 0.0019507898 -0.93218386, + -0.3619121 0.0019507805 -0.93221027, + -0.36177188 0.0019340293 -0.93226463, + -0.35699788 -0.16192394 -0.91996366, + -0.32905409 -0.14550103 -0.93303424, + -0.30102989 -0.42676187 -0.85279268, + -0.32349297 -0.42345795 -0.8461889, + -0.281225 -0.61794102 -0.73420799, + -0.30132505 -0.61400014 -0.72952521, + -0.26131698 -0.73027492 -0.63119894, + -0.280011 -0.72629797 -0.62776202, + -0.23143005 -0.82426918 -0.51674014, + -0.23543695 -0.8063488 -0.54255986, + -0.17043504 -0.90532821 -0.38901508, + -0.19514997 -0.90110588 -0.38720095, + -0.13368501 -0.95618212 -0.26046902, + -0.152408 -0.95357102 -0.259758, + -0.078443535 -0.98901546 -0.12528005, + -0.090301231 -0.98801935 -0.12515405, + -0.0032981911 -0.99988335 0.014917806, + -0.0062886998 -0.99986899 0.0149176, + 0.089849748 -0.98422348 0.15241808, + 0.096949041 -0.98356533 0.15231606, + 0.19992509 -0.9379195 0.28343815, + 0.217822 -0.93426001 0.28233299, + 0.30037189 -0.8766427 0.37586486, + 0.32651892 -0.8687098 0.3724629, + 0.38589901 -0.81501198 0.43224701, + 0.4145031 -0.80397516 0.42639309, + 0.38971105 -0.82744211 0.40430805, + 0.39263186 -0.82632673 0.40376285, + 0.3740809 -0.84161884 0.3895399, + 0.37032902 -0.84298414 0.39017206, + 0.34651801 -0.860075 0.374428, + 0.33393812 -0.86424828 0.37624514, + 0.30270201 -0.883165 0.35831699, + 0.2783449 -0.8900187 0.36109689, + 0.24156497 -0.90790391 0.34257397, + 0.20017895 -0.91667473 0.34588391, + 0.15988694 -0.93116063 0.32768288, + 0.097054534 -0.93884236 0.33038712, + 0.056877974 -0.94784951 0.31360185, + -0.03279249 -0.94887567 0.31394187, + -0.067797303 -0.95157897 0.299835, + -0.187066 -0.93693697 0.295221, + -0.21090993 -0.93489861 0.28544992, + -0.35699496 -0.89339089 0.27277696, + -0.36406702 -0.8914851 0.26964703, + -0.52702177 -0.81345558 0.24604487, + -0.5188098 -0.81744772 0.25023091, + -0.68253118 -0.69884717 0.21392505, + -0.66385794 -0.71300793 0.22563797, + -0.81079769 -0.5580498 0.17659993, + -0.79050899 -0.58109403 0.19345599, + -0.90577471 -0.40206385 0.13385396, + -0.89078432 -0.42822516 0.15207405, + -0.96697134 -0.24018909 0.085297726, + -0.95996761 -0.26157391 0.10020597, + -0.99647236 -0.078367829 0.03002171, + -0.99560165 -0.086525969 0.035925888, + -0.99655235 0.07662423 -0.031814612, + -0.99561912 0.085222907 -0.038466804, + -0.9692561 0.22426704 -0.10122702, + -0.9610495 0.24819613 -0.12158406, + -0.91812438 0.35588512 -0.17433706, + -0.89739132 0.38970613 -0.20692508, + -0.84854984 0.46732289 -0.24813794, + -0.8108623 0.50674319 -0.29276913, + -0.76402712 0.55865008 -0.32275802, + -0.75062817 0.5686481 -0.33644709, + -0.71123219 0.60499513 -0.35795209, + -0.73710406 0.58885103 -0.33156002, + -0.71791375 0.60658574 -0.34154588, + -0.71546477 0.60798877 -0.34417987, + -0.73827004 0.58697808 -0.33228603, + -0.75156385 0.57924587 -0.31563592, + -0.75106782 0.5797419 -0.3159059, + -0.7631672 0.5730741 -0.29860005, + -0.74721903 0.58937103 -0.30709201, + -0.75604701 0.58522201 -0.29310101, + -0.73881799 0.602557 -0.301783, + -0.74588817 0.59987915 -0.28947505, + -0.72718006 0.61823004 -0.29833004, + -0.73301107 0.61659104 -0.28724602, + -0.71231693 0.63620794 -0.29638496, + -0.71674496 0.63542491 -0.28724897, + -0.69407237 0.65599132 -0.29654515, + -0.69973683 0.65559381 -0.28383994, + -0.67523879 0.67688274 -0.29305688, + -0.68751395 0.67710292 -0.26240498, + -0.66175693 0.69905895 -0.27091396, + -0.672674 0.70005 -0.239666, + -0.64495915 0.72301918 -0.24753006, + -0.65399826 0.72452027 -0.21761608, + -0.62422097 0.74822593 -0.22473598, + -0.63169616 0.75007117 -0.19584005, + -0.60013396 0.77395386 -0.20207597, + -0.60628265 0.77599454 -0.17393589, + -0.57284081 0.79982072 -0.17927694, + -0.57779694 0.80191386 -0.15193698, + -0.54206896 0.82564491 -0.15643398, + -0.54598987 0.82768983 -0.12970997, + -0.5077731 0.85110319 -0.13337903, + -0.51079696 0.85301191 -0.10703798, + -0.47071111 0.87542224 -0.10985003, + -0.47293612 0.87709725 -0.083857119, + -0.43105692 0.89822876 -0.085877478, + -0.43256095 0.89957088 -0.060523592, + -0.38885206 0.91922212 -0.061845709, + -0.3897579 0.92018074 -0.036827192, + -0.34440088 0.93807167 -0.037543286, + -0.344843 0.93861002 -0.0097249001, + -0.36112511 0.93241137 -0.014061404, + -0.36116108 0.93250322 0.00077717419, + -0.36122099 0.93247998 0.00077717402, + -0.36118501 0.93238801 -0.0140695, + -0.36117703 0.93239111 -0.014069602, + -0.39119691 0.92025775 -0.009514248, + -0.39070505 0.91976315 -0.037222102, + -0.4351849 0.89960474 -0.036406294, + -0.43419901 0.89873499 -0.061210599, + -0.47700781 0.87686771 -0.059721276, + -0.47539288 0.87566876 -0.084887281, + -0.51655495 0.85225886 -0.082617991, + -0.51419008 0.85079211 -0.10845002, + -0.553514 0.82615501 -0.10531, + -0.55033278 0.82452661 -0.13148995, + -0.58717293 0.79936087 -0.12747599, + -0.58308595 0.79767185 -0.15404698, + -0.61761802 0.77221 -0.14913, + -0.61249888 0.77055681 -0.17631595, + -0.64512193 0.74482995 -0.17042899, + -0.63881922 0.74333322 -0.19840807, + -0.66969526 0.71751624 -0.19151707, + -0.6620788 0.71632481 -0.22029594, + -0.69082165 0.69108266 -0.21253289, + -0.68167472 0.69036162 -0.24232288, + -0.7085408 0.66584283 -0.23371594, + -0.69753194 0.66578597 -0.26491198, + -0.72311783 0.64178681 -0.25536293, + -0.71079999 0.64261198 -0.28602999, + -0.735268 0.61920798 -0.27561301, + -0.72917104 0.62016404 -0.28932002, + -0.75182962 0.59753168 -0.27876189, + -0.746831 0.59885198 -0.28917101, + -0.76769316 0.57706314 -0.27864906, + -0.76125216 0.57945412 -0.29108107, + -0.78089315 0.55819404 -0.28040203, + -0.77315801 0.56186098 -0.294175, + -0.79193383 0.54094785 -0.28322494, + -0.78237027 0.54642415 -0.29886013, + -0.79988581 0.52654189 -0.28798693, + -0.78699166 0.53507078 -0.30715385, + -0.78951609 0.53226608 -0.30554402, + -0.77487767 0.54239577 -0.32460985, + -0.75381351 0.56382763 -0.3374368, + -0.75657851 0.56195462 -0.33435878, + -0.77932888 0.53850394 -0.32040596, + -0.75196981 0.55881089 -0.3496739, + -0.79926914 0.50945306 -0.31878904, + -0.81051147 0.49925029 -0.30630118, + -0.86604381 0.42615592 -0.26145595, + -0.89725071 0.38408184 -0.21776693, + -0.94915801 0.273846 -0.155266, + -0.96097291 0.24479897 -0.12885898, + -0.99423778 0.094857678 -0.049931988, + -0.99559754 0.08421506 -0.041149482, + -0.99423599 -0.096329696 0.047068998, + -0.99555463 -0.085777067 0.038899984, + -0.94912565 -0.28678492 0.13005696, + -0.95372099 -0.275143 0.121296, + -0.8676616 -0.4549118 0.20054591, + -0.85958821 -0.46610311 0.20941804, + -0.73510879 -0.61839986 0.27784294, + -0.71531492 -0.63465697 0.29246396, + -0.57507718 -0.74300325 0.34239212, + -0.5409711 -0.75949317 0.36127609, + -0.4107978 -0.82332456 0.39163983, + -0.4048149 -0.8249588 0.39442092, + -0.24466904 -0.87476712 0.41823405, + -0.26427588 -0.87280357 0.41033179, + -0.13014506 -0.89728141 0.42183921, + -0.134279 -0.89741099 0.42026499, + -0.025758894 -0.90531176 0.4239659, + -0.016995694 -0.90396672 0.42726484, + 0.066876814 -0.90207326 0.42637008, + 0.084617779 -0.89729273 0.43324992, + 0.146841 -0.89076102 0.430096, + 0.18580699 -0.87550086 0.44606495, + 0.19677703 -0.87359613 0.44509405, + 0.24579497 -0.8494119 0.46699494, + 0.24828212 -0.84885639 0.4666892, + 0.27880907 -0.83076918 0.48175511, + 0.29831004 -0.82568514 0.47880605, + 0.31566811 -0.81347328 0.48848218, + 0.32692188 -0.81019968 0.48651683, + 0.34118602 -0.79870713 0.49564007, + 0.34534392 -0.79741579 0.49483889, + 0.35675898 -0.78704089 0.50327891, + 0.35521391 -0.7875368 0.50359589, + 0.36310497 -0.77953589 0.51037097, + 0.35702202 -0.7815001 0.51165706, + 0.3619279 -0.77599883 0.5165599, + 0.35200092 -0.7791568 0.51866186, + 0.35461196 -0.77593386 0.52170593, + 0.34141609 -0.7799992 0.5244391, + 0.34889096 -0.76971686 0.53461295, + 0.31966898 -0.77823091 0.54052591, + 0.274261 -0.83887303 0.470184, + 0.25459099 -0.84357798 0.472821, + 0.18917009 -0.91328841 0.36072019, + 0.18056206 -0.91479433 0.36131513, + 0.099734388 -0.97198689 0.21282497, + 0.09282627 -0.97263962 0.21296793, + 0.021248706 -0.99749726 0.067437917, + 0.020196898 -0.9975189 0.067439295, + -0.044036575 -0.9956134 -0.08255095, + -0.036833696 -0.99590391 -0.08257509, + -0.090169474 -0.96964478 -0.22728494, + -0.075886227 -0.97080338 -0.22755708, + -0.11933496 -0.92270166 -0.36657989, + -0.098982885 -0.92477888 -0.36740497, + -0.13373601 -0.85496813 -0.50114304, + -0.10763695 -0.85770559 -0.50274777, + -0.13410701 -0.76544511 -0.62937206, + -0.10275798 -0.76833379 -0.63174683, + -0.12097404 -0.65515023 -0.74575025, + -0.085790522 -0.65756416 -0.7484982, + -0.096477225 -0.5291701 -0.84301317, + -0.057568185 -0.53076786 -0.84555984, + -0.062512115 -0.38953409 -0.91888821, + -0.020573398 -0.39021495 -0.9204939, + -0.021705102 -0.23513202 -0.97172111, + 0.021332499 -0.23513398 -0.97172886, + 0.020190703 -0.39275604 -0.91942114, + 0.061759487 -0.39208692 -0.91785276, + 0.056896914 -0.53184015 -0.84493119, + 0.085932963 -0.53073275 -0.8431716, + 0.076082505 -0.66208804 -0.74555403, + 0.050366111 -0.66317016 -0.74677217, + 0.056914516 -0.53201312 -0.84482116, + 0.01861041 -0.53278428 -0.84604645, + 0.020209108 -0.39290416 -0.91935736, + -0.020906907 -0.39289814 -0.91934437, + -0.019267211 -0.53219831 -0.8464005, + -0.057633933 -0.5314123 -0.84515047, + -0.051082391 -0.66191995 -0.74783194, + -0.085949421 -0.66033316 -0.7460382, + -0.072789609 -0.7731421 -0.63004208, + -0.10272098 -0.7710979 -0.62837595, + -0.082264476 -0.86168385 -0.5007329, + -0.10739095 -0.85961461 -0.49952975, + -0.078590199 -0.92890102 -0.361893, + -0.098142058 -0.9272846 -0.36126381, + -0.061270524 -0.97362435 -0.21977608, + -0.074337199 -0.972758 -0.21958099, + -0.027941292 -0.99704075 -0.071617588, + -0.034063112 -0.99685138 -0.071604021, + 0.022350589 -0.99647754 0.080827266, + 0.024371412 -0.99643046 0.080823541, + 0.087726198 -0.96974099 0.22782999, + 0.098297566 -0.96877962 0.22760393, + 0.19968608 -0.87968028 0.43161115, + 0.21444708 -0.87687528 0.43023515, + 0.29550597 -0.76214087 0.57603592, + 0.27113605 -0.76788521 0.5803771, + 0.20335592 -0.87141269 0.44641486, + 0.18186194 -0.87516773 0.44833884, + 0.09218511 -0.96586311 0.24209604, + 0.081162132 -0.96679336 0.24232909, + 0.02523461 -0.99542135 0.092193328, + 0.022577489 -0.99548453 0.092199154, + -0.0260393 -0.99773598 -0.0620072, + -0.020802209 -0.99785846 -0.062014829, + -0.060388871 -0.9750545 -0.2135929, + -0.048116188 -0.97570574 -0.21373595, + -0.078150205 -0.9309051 -0.35680303, + -0.059718221 -0.93209434 -0.35725912, + -0.082154363 -0.8639726 -0.49679175, + -0.057804383 -0.86545384 -0.49764287, + -0.072788306 -0.77311212 -0.63007903, + -0.04335501 -0.77443916 -0.63116115, + -0.051161412 -0.66270816 -0.74712819, + -0.017122302 -0.66348004 -0.74799806, + -0.0193203 -0.53260398 -0.84614402, + 0.0185876 -0.53261101 -0.846156, + 0.016427206 -0.66407526 -0.74748522, + 0.050381407 -0.66332108 -0.74663705, + 0.042584501 -0.77540398 -0.63002801, + 0.072100289 -0.77408791 -0.62895894, + 0.057216484 -0.8656618 -0.49734887, + 0.081285819 -0.86421317 -0.49651611, + 0.059119876 -0.93174362 -0.35827187, + 0.077768318 -0.93054926 -0.35781309, + 0.047746878 -0.97551954 -0.2146669, + 0.060033984 -0.97487175 -0.21452495, + 0.020827899 -0.9977169 -0.064242594, + 0.02618191 -0.99759138 -0.064234525, + -0.022974199 -0.99550587 0.091870792, + -0.025614699 -0.99544197 0.091865003, + -0.081204474 -0.96708775 0.24113694, + -0.092215896 -0.96615785 0.24090497, + -0.18007796 -0.87828678 0.44292688, + -0.20087998 -0.8746829 0.44110894, + -0.26708007 -0.7755062 0.57206511, + -0.29539314 -0.76882833 0.56713831, + -0.29666898 -0.76671588 0.56932795, + -0.31314787 -0.76247972 0.56618279, + -0.31541884 -0.75907266 0.56949073, + -0.32961997 -0.75520188 0.56658691, + -0.32919404 -0.75578409 0.56605804, + -0.34001204 -0.75270909 0.56375605, + -0.33788896 -0.75534385 0.56150395, + -0.34541297 -0.75314885 0.55987191, + -0.34120902 -0.7578811 0.55605108, + -0.34462011 -0.7568773 0.55531418, + -0.33822289 -0.76338571 0.5503158, + -0.33738196 -0.76363087 0.55049193, + -0.32860303 -0.77165514 0.54458106, + -0.32225412 -0.7734403 0.54584116, + -0.31130406 -0.78235418 0.53945512, + -0.29835504 -0.78576612 0.54180807, + -0.27636793 -0.80134082 0.53054088, + -0.28005201 -0.80045098 0.52995199, + -0.24249002 -0.82360613 0.51271003, + -0.2402681 -0.82407528 0.51300216, + -0.19662197 -0.84651691 0.49472094, + -0.18585008 -0.84832942 0.49577925, + -0.13548796 -0.86886871 0.47614083, + -0.113368 -0.871301 0.47747499, + -0.058079585 -0.88762975 0.45688087, + -0.020491693 -0.88894367 0.45755786, + 0.041204803 -0.89956212 0.43484506, + 0.099347457 -0.89587259 0.43306178, + 0.12747903 -0.89728922 0.42263609, + 0.26218608 -0.87302232 0.41120616, + 0.242503 -0.87494802 0.41911599, + 0.40274006 -0.8254931 0.39542606, + 0.40834785 -0.8239767 0.39282885, + 0.53825003 -0.76075298 0.36268699, + 0.57338965 -0.74388361 0.34330979, + 0.71401083 -0.63570082 0.29338193, + 0.73424363 -0.6191417 0.27847788, + 0.85889012 -0.46708807 0.21008703, + 0.86703998 -0.455825 0.20116, + 0.95356166 -0.27555791 0.12160596, + 0.94907522 -0.28691006 0.13015004, + 0.99554938 -0.085824527 0.038932417, + 0.99426663 -0.096101664 0.04688758, + 0.99561799 0.084044702 -0.041005101, + 0.99431688 0.094279282 -0.049450193, + 0.96138322 0.24372306 -0.12783404, + 0.94989902 0.27216899 -0.153675, + 0.89872086 0.38185593 -0.21560797, + 0.86862141 0.4228892 -0.25818911, + 0.81337613 0.49651405 -0.30313903, + 0.80371189 0.50541693 -0.31400797, + 0.7559489 0.55605197 -0.34546697, + 0.7780692 0.53954113 -0.32172009, + 0.73895222 0.57868916 -0.34506312, + 0.75206369 0.57017082 -0.33061388, + 0.74330878 0.57869881 -0.33555889, + 0.76496297 0.56554198 -0.308211, + 0.75100315 0.57978809 -0.31597504, + 0.76248789 0.57347292 -0.29956797, + 0.74653482 0.58973187 -0.30806193, + 0.75598371 0.58529979 -0.29310888, + 0.73886025 0.60252821 -0.30173713, + 0.74596864 0.59983468 -0.28935984, + 0.72725725 0.61819422 -0.2982161, + 0.73302138 0.61657327 -0.28725815, + 0.71232581 0.63619184 -0.29639795, + 0.71678174 0.63540375 -0.28720391, + 0.69398195 0.65608394 -0.29655197, + 0.69993067 0.65566069 -0.28320685, + 0.67550015 0.67691219 -0.29238605, + 0.68774974 0.67711574 -0.2617529, + 0.66192079 0.69915277 -0.27027091, + 0.67267478 0.70011973 -0.23945992, + 0.6448462 0.7231822 -0.24734806, + 0.65386218 0.72467017 -0.21752605, + 0.62405407 0.74839205 -0.22464603, + 0.63152331 0.75022733 -0.19579908, + 0.5999831 0.77408415 -0.20202504, + 0.60612303 0.77611911 -0.17393701, + 0.57264584 0.79995972 -0.17927994, + 0.57761282 0.80205369 -0.15189894, + 0.54185003 0.82579613 -0.15639502, + 0.54577976 0.82784057 -0.12963194, + 0.50753105 0.85126013 -0.13329901, + 0.510535 0.85315502 -0.107147, + 0.47044006 0.87555414 -0.10996001, + 0.47264895 0.87721789 -0.084211692, + 0.43084306 0.89829713 -0.086235307, + 0.43236715 0.89965832 -0.060610522, + 0.38864985 0.91930163 -0.061933778, + 0.3895691 0.92027223 -0.036536906, + 0.34411097 0.93818986 -0.037248295, + 0.63156205 0.70947903 -0.31268004, + 0.62894285 0.71014285 -0.31642991, + 0.61516094 0.72014493 -0.32088697, + 0.60614777 0.72261673 -0.33227989, + 0.67762709 0.66305709 -0.31808302, + 0.66370016 0.67441118 -0.32353008, + 0.72296494 0.61065996 -0.32313496, + 0.67291504 0.65382403 -0.34597602, + 0.6764062 0.65197217 -0.34264708, + 0.64655608 0.67528605 -0.35490003, + 0.66406816 0.66725415 -0.3373211, + 0.63622695 0.68852097 -0.34807196, + 0.64683431 0.68429232 -0.33667415, + 0.65580773 0.67738074 -0.33327389, + 0.63652271 0.69393963 -0.33658084, + 0.64744574 0.69025177 -0.32305789, + 0.66141868 0.67929769 -0.31793085, + 0.6651088 0.67810684 -0.31273192, + 0.29627404 0.9530291 -0.062907107, + 0.34111989 0.93797863 -0.061913677, + 0.33987111 0.93637037 -0.087739334, + 0.38346481 0.91952759 -0.086161055, + 0.3815971 0.91750526 -0.11210603, + 0.4232361 0.89933121 -0.10988503, + 0.42063084 0.89694971 -0.13620195, + 0.4602502 0.87772739 -0.13328306, + 0.45677707 0.87504411 -0.16016401, + 0.49441993 0.85501885 -0.15649799, + 0.48995382 0.85212368 -0.18393093, + 0.52567303 0.83153611 -0.17948702, + 0.52005994 0.82851988 -0.20758697, + 0.55318713 0.80807918 -0.20246504, + 0.54626071 0.80504954 -0.23128887, + 0.57713693 0.78489691 -0.22549897, + 0.56869006 0.78196013 -0.25520602, + 0.5975759 0.76224381 -0.24877194, + 0.58737004 0.75954914 -0.27943102, + 0.61451608 0.74039006 -0.27238303, + 0.60291022 0.73824424 -0.30248111, + 0.62777585 0.7202788 -0.29511994, + 0.62290692 0.71982694 -0.30632696, + 0.64510918 0.70307517 -0.29919806, + 0.64207083 0.70311981 -0.30556095, + 0.6622473 0.68719828 -0.29864216, + 0.65796655 0.68770659 -0.30682182, + 0.67600757 0.67295557 -0.30024081, + 0.67058372 0.67412168 -0.30964085, + 0.68619895 0.66101795 -0.30362198, + 0.67877609 0.66325009 -0.31521803, + 0.68003505 0.66219705 -0.31471804, + 0.6990428 0.64385784 -0.31110495, + 0.69437003 0.64571607 -0.31764904, + 0.69277501 0.64709401 -0.31832701, + 0.67509592 0.65469992 -0.34001997, + 0.679555 0.651057 -0.33812699, + 0.6679253 0.65651733 -0.35051519, + 0.69868797 0.63111001 -0.33695, + 0.67900497 0.64164495 -0.35671297, + 0.71282792 0.61298192 -0.34077796, + 0.70744115 0.61630213 -0.3459751, + 0.76693785 0.55957794 -0.31413198, + 0.68155277 -0.13127495 -0.71989775, + 0.68192697 -0.13414998 -0.71901292, + 0.71955508 -0.12167302 -0.68369305, + 0.29314402 -0.93891412 0.18029702, + 0.10531398 -0.99042773 0.089229077, + -0.0051841284 -0.99949276 0.031422492, + -0.0021518697 -0.99950391 0.031422798, + 0.10810198 -0.99012977 0.089202181, + 0.17724702 -0.97516114 0.13283202, + 0.26912987 -0.94582355 0.18162291, + -0.82379973 0.54207879 -0.16584495, + -0.77965468 0.59881175 -0.18320194, + -0.77471715 0.60341913 -0.18894105, + -0.73330683 0.64883482 -0.20316096, + -0.72725219 0.65347117 -0.20995204, + -0.68701595 0.69181293 -0.22226997, + -0.67963779 0.69642776 -0.23039292, + -0.64167893 0.72816193 -0.24089096, + -0.63274539 0.7326594 -0.25068614, + -0.59700078 0.75903869 -0.25971192, + -0.58664066 0.76310754 -0.27114484, + -0.5528332 0.78519928 -0.27899408, + -0.54092401 0.78863198 -0.292337, + -0.50877225 0.80722535 -0.29922915, + -0.50063509 0.80878913 -0.30858502, + -0.52393496 0.79544288 -0.30456996, + -0.52464694 0.79545987 -0.30329698, + -0.51685816 0.79989928 -0.30499011, + -0.51662695 0.7999059 -0.30536398, + -0.50899923 0.80570036 -0.30293015, + -0.50534505 0.80598015 -0.30825704, + -0.48930582 0.8145687 -0.31154087, + -0.49182293 0.81430089 -0.30825996, + -0.48867118 0.81831932 -0.3025791, + -0.48058781 0.8193357 -0.31260887, + -0.46152222 0.83662939 -0.29504016, + -0.45517406 0.83712214 -0.30338603, + -0.47457707 0.82754314 -0.29991502, + -0.48362699 0.82621503 -0.28891799, + -0.51419812 0.80959916 -0.28310707, + -0.52649218 0.80662328 -0.26863509, + -0.55910212 0.78662217 -0.26197407, + -0.56980473 0.78293961 -0.24965589, + -0.60401326 0.75930631 -0.24212009, + -0.61363822 0.75497627 -0.23121209, + -0.6494177 0.72709864 -0.22267489, + -0.65765899 0.722458 -0.21339899, + -0.69535094 0.68923193 -0.20358397, + -0.70248592 0.68431395 -0.19551997, + -0.74201894 0.64458495 -0.18416898, + -0.74771118 0.63982916 -0.17761405, + -0.78824228 0.59294325 -0.16459806, + -0.79272521 0.58841211 -0.15924205, + -0.8335731 0.53322709 -0.14430802, + -0.84629041 0.51715267 -0.12784991, + -0.8779161 0.46482107 -0.11491202, + -0.89431411 0.43799105 -0.091466404, + -0.92427844 0.37365818 -0.078031838, + -0.9345389 0.35065097 -0.060670193, + -0.96033865 0.2747539 -0.047538381, + -0.96557724 0.25758907 -0.036175009, + -0.9852429 0.16949898 -0.023803897, + -0.9871245 0.15898092 -0.01761649, + -0.99832022 0.057584517 -0.0063808714, + -0.99851435 0.054292619 -0.0046392018, + -0.99821824 -0.059452813 0.0050801313, + -0.99839526 -0.056510914 0.003660751, + -0.98237747 -0.18651709 0.012082506, + -0.98367435 -0.17973106 0.0090373624, + -0.94594491 -0.32391798 0.016287398, + -0.94816554 -0.31748885 0.013520094, + -0.88096356 -0.47275576 0.02013199, + -0.88093561 -0.47280675 0.02015429, + -0.7768569 -0.62910593 0.026816897, + -0.7670362 -0.64078516 0.032402009, + -0.62675399 -0.77822298 0.039351702, + -0.59562689 -0.80148482 0.053391289, + -0.43427515 -0.89878827 0.059873223, + -0.37458211 -0.92342037 0.083565332, + -0.22209904 -0.9710561 0.087876104, + -0.14045796 -0.98286462 0.11936796, + -0.022851111 -0.99244648 0.12053206, + 0.060756922 -0.98611033 0.15458006, + 0.13814196 -0.97846365 0.15338095, + 0.21355093 -0.95874763 0.18761392, + 0.25854605 -0.94801825 0.18551405, + 0.34772003 -0.90844911 0.23197202, + 0.32687292 -0.91568679 0.23381995, + 0.25453892 -0.94803464 0.19089292, + -0.43490994 -0.85537988 -0.28138697, + -0.39410084 -0.87304169 -0.28719792, + -0.48880523 -0.79418534 -0.36102518, + -0.40577486 -0.91268671 -0.048473582, + -0.28504896 -0.95849586 -0.0057310495, + -0.15245594 -0.98829263 -0.0059092077, + -0.070876196 -0.99722087 0.022960998, + -0.68548077 -0.12987995 -0.71641278, + -0.72043365 -0.11571795 -0.68380171, + -0.72018325 -0.11611404 -0.68399823, + -0.69370621 -0.29207611 -0.65837926, + -0.66246808 -0.49279505 -0.56417108, + -0.73086816 -0.27677205 -0.62388211, + -0.75348949 -0.11504193 -0.64731663, + -0.78408891 -0.11478899 -0.60994095, + -0.7845335 -0.11468993 -0.60938764, + -0.75527197 -0.107436 -0.64654601, + -0.73110574 -0.27263892 -0.62542176, + -0.766321 -0.25673199 -0.58893198, + -0.71611077 -0.43065384 -0.5492928, + -0.75409287 -0.40522194 -0.51685494, + -0.67185491 -0.58171993 -0.45848995, + -0.71537936 -0.54877621 -0.4325242, + -0.628452 -0.68024302 -0.37724999, + -0.6638912 -0.65399116 -0.36269009, + -0.58189583 -0.74979877 -0.31495887, + -0.60810888 -0.73190379 -0.30744195, + -0.49660206 -0.83227211 -0.24639302, + -0.52513325 -0.81601143 -0.24157912, + -0.38131082 -0.90907156 -0.16790192, + -0.4097288 -0.8970356 -0.16567892, + -0.28165516 -0.95381147 -0.10447105, + -0.30391601 -0.94703501 -0.103729, + -0.23765711 -0.96850848 -0.07423304, + -0.25894296 -0.96306789 -0.073815994, + -0.15020706 -0.98823333 -0.028857712, + -0.17401992 -0.98432255 -0.028743487, + -0.038200013 -0.99900538 0.023002107, + 0.026502287 -0.99798554 0.057640374, + -0.15041602 -0.98857814 -0.0094015207, + 0.035722807 -0.99739426 0.062677912, + -0.073011972 -0.99536765 0.062550478, + -0.17813794 -0.98372364 0.023549691, + -0.32953411 -0.94387335 0.022595707, + -0.41547915 -0.90956527 -0.0082585923, + -0.58027095 -0.81438988 -0.0073944293, + -0.63162202 -0.77479303 -0.0273744, + -0.83126932 -0.21278907 -0.51352918, + -0.84625387 -0.10116498 -0.52308697, + -0.8405571 -0.11201301 -0.53001606, + -0.84048432 -0.11203304 -0.53012717, + -0.8190791 -0.089133009 -0.56671405, + -0.79997009 -0.23262402 -0.55311304, + -0.8311168 -0.21558796 -0.51260787, + -0.79391187 -0.36162496 -0.48880595, + -0.82759947 -0.33384222 -0.45125228, + -0.74992299 -0.52156502 -0.40692201, + -0.780797 -0.47299901 -0.40820101, + -0.70115119 -0.61311615 -0.3639721, + -0.72509009 -0.59217006 -0.35153803, + -0.65560418 -0.68610418 -0.31534809, + -0.62659496 -0.77301991 -0.099090882, + -0.52365726 -0.84947342 -0.064637527, + -0.3859089 -0.91987777 -0.069994688, + -0.30771405 -0.95039326 -0.04544121, + -0.2557959 -0.96562767 -0.046169586, + -0.37056503 -0.92494112 -0.084649704, + -0.33327702 -0.93890512 -0.08592771, + -0.4245958 -0.89750457 -0.11917994, + -0.39340016 -0.9113673 -0.12102105, + -0.44825095 -0.88246089 -0.14259699, + -0.41812509 -0.89675725 -0.14490703, + -0.52848077 -0.82701361 -0.1917199, + -0.49585888 -0.84596884 -0.19611396, + -0.61844695 -0.74433297 -0.25197598, + -0.58808291 -0.76609385 -0.25934294, + -0.68225121 -0.66430926 -0.30533013, + -0.73987299 -0.57351702 -0.35166201, + -0.73081601 -0.58189499 -0.35679999, + -0.79922599 -0.45501599 -0.392681, + -0.79539716 -0.47090811 -0.3815611, + -0.85981172 -0.29837987 -0.41435885, + -0.82893568 -0.32685789 -0.45390484, + -0.85987079 -0.19542596 -0.47162589, + -0.86595881 -0.10725098 -0.48847988, + -0.87092602 -0.0113958 -0.49128199, + -0.88925779 -0.10170898 -0.44595489, + -0.83480012 -0.49632406 -0.23826703, + -0.85103911 -0.47338006 -0.22725303, + -0.97420937 -0.062041722 -0.21694908, + -0.97607636 -0.0052367421 -0.21736507, + -0.97602224 -0.0051556015 -0.21761005, + -0.97415191 -0.062090594 -0.21719296, + -0.96403497 -0.020010499 -0.265021, + -0.96422386 0.0029316195 -0.26507297, + -0.96425164 0.0029316188 -0.26497191, + -0.96176964 -0.071762778 -0.26428992, + -0.96665525 -0.04638721 -0.25184506, + -0.96343899 -0.094037697 -0.25088301, + -0.97584212 -0.07668151 -0.20457803, + -0.97141075 -0.12243197 -0.20339996, + -0.98303825 -0.094581619 -0.15713105, + -0.97877514 -0.13278201 -0.15610301, + -0.98937798 -0.094185002 -0.110727, + -0.98619097 -0.123836 -0.109964, + -0.99514538 -0.07359013 -0.065346621, + -0.99354047 -0.093122147 -0.064851731, + -0.99931401 -0.030390199 -0.021164199, + -0.99910438 -0.036745816 -0.020982608, + -0.99916726 0.035431508 0.020232106, + -0.99919325 0.034669306 0.020269206, + -0.99354565 0.097924963 0.057251181, + -0.99355823 0.09779042 0.057264116, + -0.98413837 0.15308706 0.089644529, + -0.98389167 0.15481094 0.089391068, + -0.97170234 0.20455708 0.11811505, + -0.97081465 0.20926593 0.11716095, + -0.9563089 0.25509897 0.14282098, + -0.95433038 0.26361209 0.14057805, + -0.93805289 0.30573598 0.16304098, + -0.93457788 0.31829998 0.15889998, + -0.91661286 0.35768297 0.17855999, + -0.91129768 0.37413087 0.17193794, + -0.13065197 -0.98699474 0.093655474, + -0.12236205 -0.98804736 0.093755439, + 0.013101693 -0.99942553 0.031255085, + 0.00219131 -0.99950898 0.031257801, + 0.16457105 -0.98511422 -0.049662109, + 0.14622593 -0.98799652 -0.049807377, + 0.31450313 -0.93888336 -0.13995005, + 0.29098099 -0.94627398 -0.14105199, + 0.44077387 -0.86846381 -0.22691195, + 0.71288246 -0.44177866 -0.54463756, + 0.62365311 -0.62128311 -0.47440913, + 0.66746992 -0.59182495 -0.45191494, + 0.57264131 -0.72387534 -0.38482019, + 0.61863524 -0.69374126 -0.36880013, + 0.54222775 -0.77670264 -0.32050285, + 0.57960582 -0.75328368 -0.31083888, + 0.45865017 -0.85534829 -0.24087209, + 0.48547575 -0.84151959 -0.23697688, + 0.34334788 -0.92550462 -0.15985394, + 0.36985019 -0.91553539 -0.15813208, + 0.206008 -0.97565901 -0.075167999, + 0.2284009 -0.97069055 -0.074785165, + 0.067595027 -0.99771249 0.00089649338, + 0.083529092 -0.9965049 0.00089540787, + 0.75213289 -0.51729393 -0.40829295, + 0.82677615 -0.33640903 -0.45085505, + 0.7928822 -0.3644231 -0.48839912, + 0.75484627 -0.39958316 -0.52013516, + 0.79112428 -0.37262812 -0.48504719, + 0.72431403 -0.52878904 -0.44243807, + 0.75632912 -0.50173205 -0.41979906, + 0.67725593 -0.63393694 -0.37342796, + 0.70121205 -0.61429608 -0.36185902, + 0.62667626 -0.71020222 -0.32076412, + 0.65339726 -0.68991125 -0.31160012, + 0.54923511 -0.7949422 -0.25769705, + 0.57857388 -0.77588081 -0.25151795, + 0.45487601 -0.86968899 -0.19164801, + 0.48604283 -0.8534587 -0.18807092, + 0.34256792 -0.93135375 -0.12339897, + 0.37358701 -0.919559 -0.121836, + 0.15655196 -0.98764175 -0.0074375384, + 0.11826696 -0.99295366 -0.0074775373, + 0.25247291 -0.96579862 -0.059079479, + 0.22427706 -0.97270721 -0.059502114, + 0.16335694 -0.98612964 -0.029374588, + 0.14147905 -0.98950237 -0.029475011, + 0.29809105 -0.94940424 -0.098860219, + 0.27114388 -0.95736253 -0.099688955, + 0.4268398 -0.88740855 -0.17410891, + 0.39802894 -0.9002099 -0.17662099, + 0.53185099 -0.81055403 -0.24522801, + 0.50321817 -0.8271333 -0.25024408, + 0.61644202 -0.72284102 -0.31224999, + 0.59034479 -0.74097276 -0.32008189, + 0.67012799 -0.64543003 -0.36653599, + 0.63474673 -0.67192972 -0.38158482, + 0.71780008 -0.54410803 -0.43440706, + 0.67428201 -0.577106 -0.46075201, + 0.75305748 -0.40739524 -0.51665628, + 0.71502358 -0.43287173 -0.54896569, + 0.75104511 -0.10686602 -0.65154505, + 0.75342989 -0.12817699 -0.64491391, + 0.72557318 -0.29727805 -0.62062013, + 0.76092499 -0.28029799 -0.585172, + 0.78787285 -0.10136898 -0.60743791, + 0.7611782 -0.27703506 -0.58639514, + 0.79489797 -0.25918001 -0.54860097, + 0.81317717 -0.082808524 -0.5760951, + 0.81664503 -0.117974 -0.56495398, + 0.79513335 -0.25610411 -0.54970324, + 0.82670909 -0.23760504 -0.50999606, + 0.84748471 -0.08422827 -0.52409482, + 0.82692015 -0.23474106 -0.51097912, + 0.85610014 -0.21574304 -0.46962506, + 0.82827079 -0.32880691 -0.45371088, + 0.85921317 -0.30022305 -0.41426909, + 0.79740781 -0.46646589 -0.38281891, + 0.74575108 -0.56410909 -0.35445204, + 0.73650092 -0.57275593 -0.35988498, + 0.80134165 -0.45021778 -0.39389783, + 0.78297299 -0.46816701 -0.409601, + 0.70728397 -0.60384601 -0.36758599, + 0.73100907 -0.58286607 -0.35481402, + 0.66314495 -0.67689395 -0.31945798, + 0.68964726 -0.65487725 -0.30906713, + 0.5947637 -0.75976664 -0.26269889, + 0.62484092 -0.73788893 -0.25513497, + 0.51246721 -0.83415228 -0.20388107, + 0.54518396 -0.81434488 -0.19903997, + 0.41729799 -0.89716703 -0.14475399, + 0.45192489 -0.88066673 -0.14209098, + 0.31548008 -0.94479525 -0.088511623, + 0.35008088 -0.93263566 -0.087372467, + 0.22235 -0.97409499 -0.041225601, + 0.26968789 -0.9620865 -0.040717382, + 0.37891614 -0.92215937 -0.077747427, + 0.85065186 0.52448392 -0.036167495, + 0.81525087 0.57773596 -0.039839696, + 0.8116011 0.58250707 -0.044600405, + 0.77679402 0.62791699 -0.0480772, + 0.77195686 0.63335294 -0.054281894, + 0.73724103 0.67316198 -0.057693802, + 0.73115915 0.67905819 -0.065470412, + 0.69673181 0.71402085 -0.068841182, + 0.68953496 0.72002792 -0.078111194, + 0.65531003 0.75095409 -0.081466205, + 0.64693177 0.7569257 -0.092427172, + 0.61315799 0.784136 -0.0957499, + 0.60394979 0.78965873 -0.10809096, + 0.5711838 0.81323868 -0.11131896, + 0.56138605 0.81808114 -0.12485602, + 0.52962703 0.838521 -0.127976, + 0.51932192 0.84257287 -0.14274299, + 0.48838183 0.8603707 -0.14575796, + 0.47764507 0.86352211 -0.16181701, + 0.4475598 0.87895459 -0.16470893, + 0.43631405 0.88111812 -0.18237601, + 0.40749606 0.89425212 -0.18509501, + 0.3959319 0.89527476 -0.20425695, + 0.36847082 0.9063496 -0.20678389, + 0.35653102 0.90609312 -0.22777402, + 0.33016887 0.91544068 -0.23012391, + 0.31846303 0.91379809 -0.25210002, + 0.29842016 0.92006344 -0.25382811, + 0.29816011 0.91999835 -0.25436908, + 0.27763498 0.92594588 -0.25601396, + 0.27710107 0.92575824 -0.25726807, + 0.26447791 0.92917967 -0.2582179, + 0.26292995 0.92842078 -0.26249295, + 0.24673991 0.93252665 -0.2636539, + 0.24481513 0.93122941 -0.26995811, + 0.2257399 0.93566459 -0.27124387, + 0.22400407 0.93407935 -0.27806109, + 0.20219107 0.93863934 -0.27941909, + 0.20051493 0.93658566 -0.28740391, + 0.17609894 0.94106162 -0.2887769, + 0.17465304 0.93867826 -0.29728705, + 0.14792107 0.9428435 -0.29860616, + 0.14635201 0.93928313 -0.31036803, + 0.12278406 0.94232249 -0.31137216, + -0.30483285 0.91561759 -0.26214787, + -0.30435905 0.91548622 -0.26315507, + -0.29310593 0.91887176 -0.26412794, + -0.29227006 0.91853923 -0.26620305, + -0.27725297 0.92282391 -0.26744497, + -0.27552009 0.92186236 -0.27250409, + -0.25744194 0.92665577 -0.27392095, + -0.25560588 0.92527056 -0.28024989, + -0.234697 0.93033099 -0.28178301, + -0.2329751 0.92858833 -0.28887108, + -0.209427 0.933689 -0.29045701, + -0.20788898 0.93161887 -0.29810798, + -0.18198901 0.93652213 -0.29967704, + -0.18051505 0.93387324 -0.30869907, + -0.152189 0.938411 -0.31019899, + -0.15192294 0.93776566 -0.31227389, + -0.12111994 0.9417935 -0.31361586, + -0.123303 0.949027 -0.29007599, + -0.090014145 0.95244241 -0.29111981, + -0.091555178 0.95975077 -0.26551095, + -0.056081284 0.96228176 -0.26621193, + -0.056903683 0.96886766 -0.24095091, + -0.019428799 0.97025687 -0.24129698, + -0.019675998 0.97615486 -0.21618196, + 0.019383809 0.97616047 -0.21618311, + 0.019138092 0.97025764 -0.24131691, + 0.056653593 0.9688769 -0.24097297, + 0.055833187 0.96229279 -0.26622394, + 0.091348767 0.95976663 -0.26552492, + 0.089817852 0.95249951 -0.29099384, + 0.12310897 0.94908977 -0.28995293, + 0.12105896 0.94233066 -0.31202188, + 0.085725091 0.94581789 -0.31317696, + 0.087243907 0.95299613 -0.29015002, + 0.053439081 0.95527667 -0.29084492, + 0.05434671 0.96251422 -0.26573107, + 0.018394696 0.96377575 -0.26607895, + 0.018669097 0.97030574 -0.24115995, + -0.019013692 0.97029966 -0.2411579, + -0.018746693 0.96376562 -0.2660909, + -0.054656606 0.96249413 -0.26574004, + -0.053753182 0.95522761 -0.29094791, + -0.087375902 0.95295203 -0.29025501, + -0.085853361 0.94575953 -0.31331787, + -0.11710501 0.94273311 -0.31231502, + -0.11737403 0.94359422 -0.30960205, + -0.14661697 0.93989378 -0.30838794, + -0.14791802 0.94284111 -0.29861504, + -0.17475094 0.93865865 -0.29729089, + -0.17618996 0.94103575 -0.28880593, + -0.20044595 0.93658876 -0.28744194, + -0.20212607 0.93864834 -0.27943608, + -0.22390597 0.93409687 -0.27808097, + -0.22574997 0.93578088 -0.27083397, + -0.2450081 0.93130034 -0.26953807, + -0.24685296 0.93254191 -0.26349398, + -0.2631779 0.92839867 -0.2623229, + -0.26440996 0.92900288 -0.25892296, + -0.27676094 0.92565876 -0.25799093, + -0.2775321 0.92592937 -0.25618508, + -0.29807207 0.91998023 -0.25453806, + -0.29815197 0.9199999 -0.25437298, + -0.31797999 0.91381103 -0.252662, + -0.32956201 0.91545099 -0.230951, + -0.3559621 0.90611023 -0.22859406, + -0.36766902 0.9063881 -0.20803903, + -0.39504516 0.8953793 -0.20551208, + -0.40659884 0.8943907 -0.18639395, + -0.4353289 0.88133574 -0.18367395, + -0.44659701 0.87920099 -0.16600201, + -0.47660011 0.86385715 -0.16310504, + -0.48750025 0.86068839 -0.14683008, + -0.5184018 0.84295869 -0.14380595, + -0.52897388 0.83882582 -0.12867796, + -0.56061089 0.81850481 -0.12555997, + -0.57058084 0.8135947 -0.11180896, + -0.60336608 0.79003912 -0.10857102, + -0.61269176 0.7844587 -0.096089564, + -0.64653593 0.7572239 -0.092753589, + -0.65503979 0.75117171 -0.081632167, + -0.68926585 0.72026783 -0.078273676, + -0.69654119 0.7142002 -0.068908915, + -0.73099965 0.67922372 -0.065534167, + -0.73712003 0.67329305 -0.057711307, + -0.77188385 0.63344079 -0.054295387, + -0.776788 0.62792999 -0.0480037, + -0.81156087 0.58256793 -0.044535898, + -0.81526685 0.57772291 -0.039702591, + -0.85067731 0.5244512 -0.03604161, + -0.63719529 -0.75302637 -0.16411407, + -0.53283501 -0.836092 -0.13052601, + -0.5782488 -0.80609667 -0.12584296, + -0.50267887 -0.8582558 -0.10349398, + -0.56498313 -0.81916815 -0.098780923, + -0.62006795 -0.77617991 -0.11428198, + -0.77626717 -0.62368011 -0.091828525, + -0.84671354 0.51243269 0.14313991, + -0.84465009 0.51660407 0.14030902, + -0.81599718 0.55784714 0.15151003, + -0.81295717 0.56339109 0.14727902, + -0.78330588 0.60142595 0.15722199, + -0.7792958 0.60806286 0.15151797, + -0.74848902 0.643471 0.16034099, + -0.74349183 0.65099984 0.15303297, + -0.7116372 0.68390518 0.16076805, + -0.70554084 0.69227481 0.15155096, + -0.67338616 0.72218817 0.15809904, + -0.66636831 0.73097235 0.14708108, + -0.63390082 0.75821781 0.15256298, + -0.626041 0.76717699 0.139686, + -0.59304595 0.79214489 0.14423199, + -0.58456886 0.80091685 0.12965897, + -0.55132937 0.82356548 0.13332607, + -0.54217201 0.83211899 0.116737, + -0.50922477 0.85228759 0.11956594, + -0.49960512 0.86033219 0.10111002, + -0.46705589 0.87818378 0.10320798, + -0.45731205 0.88539714 0.083292909, + -0.42495999 0.90123302 0.0847826, + -0.41511893 0.90756786 0.06321989, + -0.3830519 0.92149377 0.064189985, + -0.37330192 0.92679775 0.041127488, + -0.34203687 0.93876266 0.041658483, + -0.3325299 0.94293576 0.017202396, + -0.30208087 0.95312363 0.017388195, + -0.29306388 0.95605862 -0.0080832476, + -0.26323813 0.96469647 -0.0081562838, + -0.25483504 0.96636713 -0.034552205, + -0.22562693 0.97359163 -0.034810487, + -0.21795693 0.97398865 -0.061973877, + -0.18972208 0.97985637 -0.062347222, + -0.18286701 0.97898799 -0.090233997, + -0.15559801 0.9836511 -0.090663806, + -0.14958906 0.98152035 -0.11933605, + -0.12315004 0.98513335 -0.11977605, + -0.11806101 0.98171914 -0.14929602, + -0.092269875 0.98441577 -0.14970598, + -0.088151276 0.97967678 -0.18017395, + -0.063456021 0.98152333 -0.18051405, + -0.060116399 0.97477901 -0.21492299, + -0.036996987 0.97587663 -0.21516493, + -0.036429405 0.97367013 -0.22503203, + -0.012511695 0.97424054 -0.22516389, + -0.012342894 0.97212452 -0.23413989, + 0.012379002 0.9721241 -0.23414002, + 0.012547603 0.97423822 -0.22517206, + 0.03653812 0.97366446 -0.22503911, + 0.9018234 0.41743022 0.11165405, + 0.92210859 0.37379083 0.099981055, + 0.92786413 0.35690603 0.10810301, + 0.94626337 0.30951113 0.093747333, + 0.94985622 0.29661205 0.098967522, + 0.9661901 0.24457604 0.081605211, + 0.96813846 0.23569311 0.084598236, + 0.98172277 0.17912695 0.064294688, + 0.98255175 0.17399296 0.065714583, + 0.99286997 0.111514 0.042117201, + 0.99307954 0.10945494 0.042574883, + 0.99913186 0.038827095 0.015102698, + 0.99913365 0.038776286 0.015111495, + 0.99899048 -0.041857619 -0.016312307, + 0.99895746 -0.042679418 -0.016204007, + 0.98871052 -0.14008194 -0.053184476, + 0.98796546 -0.14543608 -0.052656725, + 0.96019423 -0.26264805 -0.095094725, + 0.96387178 -0.24839294 -0.09618818, + 0.92471987 -0.35496297 -0.13745698, + 0.95306242 -0.26609686 -0.14444491, + 0.93168062 -0.31927189 -0.17331094, + 0.90334702 -0.38544601 -0.18813699, + 0.89543331 -0.40780714 -0.17858505, + 0.94766998 -0.25469199 -0.19249301, + 0.92112213 -0.31055403 -0.23471303, + 0.94295454 -0.22918889 -0.24147289, + 0.91962236 -0.2704131 -0.28490609, + 0.80518931 -0.53767616 -0.2501491, + 0.82234412 -0.51589108 -0.24001403, + 0.86452556 0.50258875 -0.00010277895, + 0.83143783 0.55561787 -0.00011362297, + 0.82843548 0.56006938 -0.0041352524, + 0.79530752 0.60618967 -0.004475777, + 0.79116672 0.61151975 -0.0099422764, + 0.75770497 0.652511 -0.0106087, + 0.75223118 0.65865821 -0.017825203, + 0.71868175 0.69508475 -0.018810993, + 0.71214736 0.70149136 -0.027497813, + 0.67843324 0.73409826 -0.02877601, + 0.67083716 0.74057621 -0.039045107, + 0.63716197 0.76966089 -0.040578496, + 0.62856126 0.77598631 -0.052499618, + 0.59561723 0.80143631 -0.054221418, + 0.58612305 0.80738109 -0.067791909, + 0.55389619 0.82966632 -0.069663122, + 0.54384869 0.83491254 -0.084556147, + 0.51223975 0.85447156 -0.086537153, + 0.50174373 0.85888755 -0.10278795, + 0.47069612 0.87604421 -0.10484202, + 0.46002606 0.87945712 -0.12219401, + 0.43006009 0.89421022 -0.12424403, + 0.41927376 0.89656448 -0.14276391, + 0.39046285 0.90916473 -0.14476995, + 0.37947905 0.91040415 -0.16480301, + 0.351549 0.92119801 -0.166756, + 0.34052703 0.92119813 -0.18824303, + 0.31338903 0.93039811 -0.19012304, + 0.302434 0.92904001 -0.21311601, + 0.27662498 0.93664986 -0.21486197, + 0.26556504 0.93373412 -0.24003303, + 0.24533409 0.93891138 -0.24136409, + 0.24420708 0.93846035 -0.24424408, + 0.22318608 0.94335037 -0.24551609, + 0.22216497 0.94280487 -0.24851897, + 0.20678896 0.94606978 -0.24937995, + 0.20492296 0.94470775 -0.25599593, + 0.18642291 0.9482705 -0.25696188, + 0.184578 0.94642502 -0.26497301, + 0.16351306 0.95001036 -0.26597708, + 0.16191594 0.94782662 -0.27460492, + 0.13828397 0.95127279 -0.27560395, + 0.13689993 0.94863355 -0.28522384, + 0.11050501 0.95178515 -0.28617102, + 0.10943603 0.94883925 -0.29618907, + 0.080840833 0.95144838 -0.29700312, + 0.080028273 0.94798267 -0.30809787, + 0.049527694 0.94986588 -0.30870998, + 0.04937169 0.94866377 -0.31240895, + 0.016922101 0.94968611 -0.31274602, + 0.017212193 0.95670652 -0.29054484, + -0.017321298 0.95670485 -0.29054397, + -0.017030092 0.94967651 -0.31276885, + -0.04933608 0.94865751 -0.31243384, + -0.049492594 0.94986385 -0.30872196, + -0.080137759 0.94797051 -0.30810684, + -0.080945492 0.95143288 -0.29702398, + -0.10943404 0.94883233 -0.29621211, + -0.11050404 0.95178133 -0.2861841, + -0.13689999 0.94862998 -0.285236, + -0.13827695 0.95126367 -0.27563891, + -0.16203608 0.94779748 -0.27463511, + -0.16368596 0.95006174 -0.26568693, + -0.18474102 0.94647413 -0.26468402, + -0.18654898 0.94827986 -0.25683597, + -0.20515101 0.94469398 -0.25586399, + -0.2068131 0.94590849 -0.24997112, + -0.2219629 0.94269353 -0.24912088, + -0.22313394 0.94332075 -0.24567693, + -0.244132 0.938438 -0.244405, + -0.24513605 0.93884021 -0.24184206, + -0.26528797 0.93368888 -0.24051496, + -0.2761831 0.93657935 -0.21573608, + -0.30191913 0.92900634 -0.21399108, + -0.31281808 0.93038225 -0.19113804, + -0.33984607 0.92124122 -0.18926005, + -0.3508279 0.92126876 -0.16787995, + -0.37867305 0.91053611 -0.16592401, + -0.389676 0.90932399 -0.14588501, + -0.4184078 0.89679158 -0.14387393, + -0.4293189 0.89443779 -0.12516497, + -0.45920706 0.87975711 -0.12311102, + -0.47005695 0.87630886 -0.10549498, + -0.50108713 0.85919321 -0.10343502, + -0.51169878 0.85474557 -0.087030455, + -0.5433228 0.83520567 -0.085040867, + -0.5534839 0.82991379 -0.069990687, + -0.58568192 0.80767387 -0.068115093, + -0.59528089 0.80167383 -0.054404087, + -0.62823296 0.77623987 -0.052678093, + -0.63691282 0.76986283 -0.040659189, + -0.67064607 0.74074507 -0.039121404, + -0.67830831 0.73421437 -0.028761813, + -0.71202105 0.70162004 -0.027485004, + -0.71858603 0.69518501 -0.0187604, + -0.75216317 0.65873718 -0.017776804, + -0.75763828 0.65258926 -0.010560504, + -0.79110914 0.61159503 -0.009897111, + -0.79527581 0.60623187 -0.0043953289, + -0.82842386 0.56008697 -0.0040607695, + -0.83142698 0.55563402 -3.7823502e-005, + -0.86454701 0.50255197 -3.4210101e-005, + 0.8762309 0.48074695 0.033193197, + 0.84522903 0.533135 0.036810301, + 0.84273845 0.53728527 0.03341322, + 0.81120765 0.58363068 0.03629538, + 0.80762613 0.58885509 0.031463005, + 0.77545881 0.63049883 0.033687994, + 0.77080703 0.63647902 0.027405299, + 0.73820937 0.67394727 0.029018613, + 0.73234284 0.68061185 0.021010494, + 0.69929999 0.71448803 0.0220562, + 0.69228017 0.72152418 0.012293302, + 0.65890121 0.75212032 0.012814605, + 0.65093076 0.75913572 0.0014426295, + 0.6179859 0.78618783 0.0014940397, + 0.60913813 0.79298019 -0.011541002, + 0.57667506 0.81688714 -0.011889002, + 0.5670839 0.82323182 -0.026556294, + 0.53487194 0.84449387 -0.027242197, + 0.52473181 0.85015869 -0.043437283, + 0.49287024 0.86896944 -0.044398423, + 0.482357 0.87377501 -0.0620405, + 0.45149821 0.8900314 -0.063194826, + 0.44092101 0.89379698 -0.081949003, + 0.41093978 0.90785456 -0.083237864, + 0.40035006 0.91053414 -0.10318702, + 0.3711721 0.92265826 -0.10456102, + 0.36071882 0.92417359 -0.12563895, + 0.33212385 0.93463856 -0.12706093, + 0.32183301 0.93493098 -0.149424, + 0.29439989 0.94370562 -0.15082595, + 0.28436604 0.9427011 -0.17450102, + 0.25812694 0.94997275 -0.17584695, + 0.24839605 0.94757122 -0.20101805, + 0.22292803 0.9536131 -0.20230003, + 0.21316904 0.94950521 -0.23021506, + 0.19215305 0.95373225 -0.23124006, + 0.19061697 0.95279986 -0.23629998, + 0.16897993 0.95663851 -0.23725188, + 0.16778998 0.95567989 -0.24191397, + 0.14996594 0.95846063 -0.24261791, + 0.14821506 0.95651734 -0.25121108, + 0.12751606 0.95930445 -0.25194213, + 0.12601101 0.95694309 -0.26149803, + 0.10264897 0.95953667 -0.26220691, + 0.10146904 0.95682138 -0.27239108, + 0.075566433 0.95903534 -0.27302209, + 0.07469631 0.95590115 -0.28403103, + 0.046670876 0.95753455 -0.28451586, + 0.046163678 0.9541505 -0.29574585, + 0.015947105 0.95504737 -0.29602411, + 0.0157676 0.95118701 -0.30821201, + -0.0157676 0.95118701 -0.30821201, + -0.015946895 0.95504361 -0.29603589, + -0.046128377 0.95414853 -0.29575786, + -0.046637088 0.95754278 -0.28449395, + -0.074697092 0.95590788 -0.28400797, + -0.075561203 0.95903599 -0.27302101, + -0.10139895 0.95682853 -0.27239189, + -0.10260306 0.95959848 -0.26199913, + -0.12610897 0.95698774 -0.26128694, + -0.12759702 0.95931911 -0.25184503, + -0.14840397 0.95651478 -0.25110894, + -0.15004899 0.95834088 -0.24303897, + -0.16764802 0.95559615 -0.24234302, + -0.16891795 0.95662075 -0.23736794, + -0.19059595 0.95277578 -0.23641394, + -0.19204298 0.95365685 -0.23164196, + -0.21293096 0.94945979 -0.23062193, + -0.22263803 0.95356011 -0.20286803, + -0.24797399 0.94756001 -0.201591, + -0.25763905 0.94996023 -0.17662905, + -0.28387305 0.94270521 -0.17528005, + -0.293845 0.94372702 -0.15177099, + -0.32120314 0.93499643 -0.15036708, + -0.33151788 0.93472862 -0.12797795, + -0.36000088 0.92432863 -0.12655395, + -0.37051782 0.9228276 -0.10538395, + -0.39969915 0.91072732 -0.10400204, + -0.41035795 0.90805286 -0.083942294, + -0.44025412 0.89406127 -0.082648925, + -0.45099211 0.89025724 -0.063626312, + -0.48186776 0.87401456 -0.06246547, + -0.49245077 0.86919057 -0.044719879, + -0.52427626 0.8504234 -0.043754321, + -0.5345341 0.8447032 -0.027382707, + -0.56677508 0.82344013 -0.026693404, + -0.57643086 0.8170588 -0.011933098, + -0.60889906 0.79316312 -0.011584101, + -0.61777586 0.78635281 0.0014897496, + -0.65075469 0.75928664 0.0014384693, + -0.65875757 0.75224555 0.012847193, + -0.69213903 0.721659 0.0123248, + -0.69916201 0.71462202 0.022087701, + -0.732234 0.68072802 0.021040101, + -0.73813194 0.67402893 0.029089795, + -0.7707352 0.63656318 0.027472807, + -0.77543032 0.63052726 0.033813111, + -0.80762887 0.58884495 0.031577896, + -0.81119686 0.58363992 0.036388896, + -0.84272814 0.53729606 0.033499405, + -0.84524161 0.53310674 0.036928982, + -0.87626475 0.48067787 0.033297192, + -0.95722377 -0.28352594 -0.057755787, + -0.95983565 -0.2741439 -0.059670478, + -0.98783612 -0.15194102 -0.033071704, + -0.98800564 -0.15077694 -0.03333379, + -0.99889266 -0.045938786 -0.010156096, + -0.99886811 -0.046500504 -0.010010501, + -0.99903375 0.04296419 0.0092491983, + -0.99898601 0.044134501 0.0088951299, + -0.99198246 0.12388506 0.024968412, + -0.99144024 0.12845603 0.023351505, + -0.97927237 0.19928208 0.036226813, + -0.97755677 0.20813896 0.032571893, + -0.96135134 0.27201408 0.042567715, + -0.9577691 0.28525004 0.036206104, + -0.93826324 0.34316909 0.04355761, + -0.93203038 0.36081111 0.03368631, + -0.91015971 0.41246384 0.038508784, + -0.90068489 0.43377593 0.024598897, + -0.87689668 0.47990781 0.027214991, + -0.86967772 0.49332681 0.017010994, + -0.83859217 0.5444361 0.018773403, + -0.83587003 0.54872 0.0150902, + -0.80354369 0.59502077 0.016363494, + -0.79966086 0.60034794 0.011176499, + -0.76684183 0.64172482 0.011946797, + -0.76180613 0.64778405 0.0052225804, + -0.72868836 0.68482327 0.0055211927, + -0.72241724 0.69145125 -0.0029333611, + -0.68901324 0.72474223 -0.003074591, + -0.68168759 0.7315256 -0.013126893, + -0.64811605 0.76141912 -0.013663302, + -0.63977826 0.76814032 -0.02538581, + -0.60679823 0.79442227 -0.02625441, + -0.59758431 0.80082637 -0.039626617, + -0.56522304 0.82393014 -0.040769804, + -0.55522376 0.82982558 -0.055821974, + -0.52326286 0.85024983 -0.057195883, + -0.51286906 0.85531211 -0.07352981, + -0.48138776 0.8732866 -0.075074963, + -0.47068 0.87741601 -0.092743903, + -0.44025806 0.89289713 -0.094380312, + -0.42943206 0.89597112 -0.11324301, + -0.40014106 0.9092201 -0.11491802, + -0.38933799 0.91115999 -0.13492, + -0.36082083 0.92257559 -0.13661094, + -0.3501071 0.92331725 -0.15783004, + -0.32232788 0.93309367 -0.15950194, + -0.31178802 0.93255812 -0.18199901, + -0.28523809 0.94070935 -0.18359005, + -0.27492207 0.93880826 -0.20750204, + -0.24948609 0.94555736 -0.20899308, + -0.23911403 0.94205111 -0.23529603, + -0.21861008 0.94672835 -0.23646408, + -0.21734203 0.94610113 -0.24011503, + -0.1958641 0.95049745 -0.24123012, + -0.19460402 0.94967014 -0.24547103, + -0.17833595 0.95265979 -0.24624294, + -0.17662698 0.9511289 -0.25329196, + -0.15698892 0.9543395 -0.25414687, + -0.15531707 0.95227247 -0.26278111, + -0.13295798 0.95541185 -0.26364797, + -0.131502 0.952887 -0.27333799, + -0.10663396 0.95575362 -0.27416092, + -0.10548398 0.95285279 -0.28450793, + -0.07835187 0.95525265 -0.28522491, + -0.077544965 0.95206553 -0.29590186, + -0.048229277 0.95382953 -0.29645085, + -0.047721617 0.95014238 -0.30814311, + -0.016499197 0.95109677 -0.30845195, + -0.016441701 0.94975013 -0.31257704, + 0.016406497 0.94975078 -0.31257692, + 0.016464099 0.95110101 -0.30844101, + 0.047756679 0.95014453 -0.30813086, + 0.048264623 0.95383149 -0.29643914, + 0.077472262 0.95207453 -0.29589185, + 0.078282431 0.95525837 -0.28522509, + 0.10551796 0.95284963 -0.2845059, + 0.10666895 0.95575351 -0.27414787, + 0.13157094 0.95288152 -0.27332389, + 0.13298693 0.95533752 -0.26390287, + 0.15507297 0.95223874 -0.26304695, + 0.15678202 0.95434815 -0.25424203, + 0.17640896 0.95114374 -0.25338793, + 0.1782629 0.95280355 -0.24573888, + 0.19479196 0.94976479 -0.24495494, + 0.19591898 0.95050389 -0.24115998, + 0.21749696 0.94608474 -0.24003895, + 0.21887504 0.94676614 -0.23606703, + 0.23936997 0.94208491 -0.23489997, + 0.24987707 0.94562024 -0.20824005, + 0.27537593 0.93884176 -0.20674695, + 0.28571999 0.940727 -0.182748, + 0.31237501 0.93252599 -0.181155, + 0.32295501 0.93304199 -0.15853301, + 0.35083702 0.92320514 -0.15686202, + 0.36153588 0.92243963 -0.13563496, + 0.39012694 0.91096586 -0.13394798, + 0.40079284 0.9090277 -0.11416596, + 0.43017185 0.89571071 -0.11249296, + 0.44093186 0.89263469 -0.093714371, + 0.47131589 0.87714374 -0.092088081, + 0.48187894 0.8730529 -0.074641295, + 0.51340085 0.85502982 -0.073100388, + 0.52372193 0.84998888 -0.056869593, + 0.55563116 0.82957429 -0.055503719, + 0.56553388 0.82372582 -0.040586088, + 0.59792268 0.80058265 -0.03944578, + 0.60703415 0.79424316 -0.026215805, + 0.64001673 0.76794273 -0.025347691, + 0.64828295 0.76127589 -0.013716298, + 0.68181396 0.73140693 -0.013178098, + 0.68914074 0.72462076 -0.0031250587, + 0.72251785 0.69134581 -0.0029815494, + 0.72879022 0.68471521 0.005476722, + 0.76187885 0.64769882 0.0051806485, + 0.76691782 0.64163482 0.011911097, + 0.79971087 0.60028195 0.011143499, + 0.80353689 0.59503293 0.016255798, + 0.8358829 0.54870296 0.014990098, + 0.83857787 0.54446292 0.018635299, + 0.86964202 0.49339399 0.0168874, + 0.87686056 0.47998077 0.027094787, + 0.90063524 0.4338851 0.024492806, + 0.91009027 0.41263008 0.038368907, + 0.93196267 0.36099687 0.03356779, + 0.93818748 0.34339315 0.043423422, + 0.95771724 0.28543806 0.036094707, + 0.96129376 0.27223694 0.042441089, + 0.97751945 0.20832911 0.032478016, + 0.97922933 0.19951308 0.036116611, + 0.99141812 0.12863901 0.023286702, + 0.99196303 0.124052 0.0249091, + 0.99898314 0.044203505 0.0088758413, + 0.99903047 0.043048322 0.0092255147, + 0.99886388 -0.046596095 -0.0099858195, + 0.99888855 -0.046032976 -0.010131795, + 0.98795748 -0.15110907 -0.033259116, + 0.987786 -0.152283 -0.0329949, + 0.95968074 -0.27471793 -0.059522785, + 0.95696563 -0.28443992 -0.057537977, + 0.90039468 -0.42643684 -0.086261772, + 0.88684279 -0.45502689 -0.080375977, + 0.78565609 -0.60923207 -0.10761502, + 0.76524681 -0.55381787 -0.3281509, + 0.79078311 -0.52659708 -0.31202203, + 0.68533802 -0.677885 -0.26605201, + 0.72831523 -0.63787323 -0.25034907, + 0.5746451 -0.79588616 -0.19065204, + 0.61050922 -0.78173232 -0.12717405, + 0.51080912 -0.85422218 -0.096842423, + 0.45192578 -0.88637757 -0.10048795, + 0.5491271 -0.82532519 -0.13152103, + 0.50647718 -0.85150927 -0.13569404, + 0.60678494 -0.77636987 -0.17047499, + 0.56811184 -0.80380172 -0.17649893, + 0.68829203 -0.690732 -0.221683, + 0.71714294 -0.66358793 -0.21297197, + 0.63938916 -0.74614918 -0.18558805, + 0.67780519 -0.71350217 -0.17746805, + 0.59835327 -0.78676432 -0.15157606, + 0.64189303 -0.75294799 -0.145061, + 0.56489569 -0.8161056 -0.12191994, + 0.62414396 -0.77273387 -0.11544099, + 0.61784792 -0.77804089 -0.11364999, + 0.74868816 -0.65596116 -0.095817626, + 0.79203135 -0.59291428 -0.14539307, + 0.72348303 -0.678698 -0.126259, + 0.66825724 -0.73138225 -0.13606004, + 0.72469324 -0.67208225 -0.15207006, + 0.68268424 -0.71269727 -0.16126005, + 0.74389362 -0.64359272 -0.18002991, + 0.70676482 -0.68129581 -0.19057696, + 0.76839817 -0.6041941 -0.21098304, + 0.73629779 -0.63882875 -0.22307692, + 0.7958383 -0.55402815 -0.24432409, + 0.75601798 -0.59890002 -0.26411301, + 0.82856899 -0.47710499 -0.292992, + 0.79438889 -0.51760095 -0.31786096, + 0.86422443 -0.36286479 -0.34848979, + 0.88675261 -0.33339286 -0.32018584, + 0.8377921 -0.45578307 -0.30061004, + 0.86836642 -0.4139882 -0.27304512, + 0.86273414 -0.43193105 -0.26291704, + 0.91752386 -0.28037098 -0.28203198, + 0.88966125 -0.3219251 -0.32383209, + 0.91464168 -0.22800192 -0.33383489, + 0.88961327 -0.25758308 -0.37714615, + 0.89729226 -0.066933714 -0.43633309, + 0.88280272 -0.19145392 -0.42895785, + 0.90681672 -0.17180094 -0.38492584, + 0.92719024 -0.10112403 -0.36068308, + 0.91252875 -0.035387192 -0.4074789, + 0.91700101 -0.083197102 -0.39011201, + 0.90694028 -0.16960905 -0.38560614, + 0.92813724 -0.14987203 -0.34073409, + 0.91545373 -0.22195794 -0.33567691, + 0.93714398 -0.192461 -0.291067, + 0.93767977 -0.18769695 -0.29244894, + 0.95587987 -0.15866898 -0.24721996, + 0.94435173 -0.22096194 -0.24367094, + 0.96324998 -0.180435 -0.19897901, + 0.95031613 -0.24228603 -0.19544002, + 0.97050345 -0.18764709 -0.15136607, + 0.95759201 -0.247135 -0.148128, + 0.97883445 -0.17553709 -0.10521405, + 0.96915078 -0.22401693 -0.10277697, + 0.98966599 -0.13033 -0.059794199, + 0.98881036 -0.13683105 -0.059426323, + 0.99896634 -0.041694116 -0.018107906, + 0.99900454 -0.040730283 -0.018194892, + 0.99914533 0.037741017 0.016859606, + 0.999156 0.037441 0.0168991, + 0.99326622 0.10559702 0.047661312, + 0.99316752 0.10660095 0.047480978, + 0.98323739 0.16655606 0.074185029, + 0.98261964 0.17056593 0.073251769, + 0.96959913 0.22484103 0.096561015, + 0.96805191 0.23230797 0.094385184, + 0.95245326 0.28227606 0.11468703, + 0.94946688 0.29373398 0.11060298, + 0.93188256 0.33949086 0.12783194, + 0.92703557 0.35482681 0.12125594, + 0.90765321 0.3971701 0.13572603, + 0.90044332 0.41634414 0.12593405, + 0.87940431 0.45568615 0.13783404, + 0.87408632 0.46792018 0.13047504, + 0.846632 0.51262301 0.14294, + 0.8446188 0.51669091 0.14017697, + 0.81598079 0.55791187 0.15135998, + 0.81295973 0.56341982 0.14715494, + 0.78335285 0.60140294 0.15707599, + 0.77934265 0.60803872 0.15137392, + 0.74853158 0.64345866 0.16019191, + 0.74355507 0.65095603 0.15291202, + 0.71170956 0.68385959 0.16064091, + 0.70566142 0.69216442 0.15149409, + 0.67351383 0.72208184 0.15804096, + 0.66649306 0.73087204 0.14701402, + 0.63405508 0.75810313 0.15249202, + 0.62622273 0.76703465 0.13965294, + 0.59330112 0.79196119 0.14419203, + 0.58477873 0.80078262 0.12954193, + 0.55153614 0.82344615 0.13320804, + 0.54241806 0.8319661 0.11668401, + 0.50947899 0.85214299 0.119514, + 0.49988395 0.86017185 0.10109598, + 0.46734005 0.87803411 0.10319602, + 0.45762011 0.88523525 0.083321519, + 0.42529914 0.9010703 0.08481203, + 0.4154689 0.90740478 0.063262284, + 0.38340291 0.92134476 0.064234182, + 0.37369004 0.9266361 0.041248504, + 0.342383 0.938631 0.041782402, + 0.33292186 0.94279355 0.017414892, + 0.30247194 0.95299578 0.017603396, + 0.293484 0.95593202 -0.0078218495, + 0.26367813 0.96457845 -0.007892604, + 0.25529808 0.96625638 -0.034227911, + 0.22605193 0.97350466 -0.034484688, + 0.21839893 0.97391367 -0.061595377, + 0.19011793 0.97980362 -0.061967876, + 0.18327801 0.9789511 -0.089800104, + 0.15592794 0.98363864 -0.09023007, + 0.14992401 0.9815231 -0.11889201, + 0.12339803 0.98515624 -0.11933203, + 0.11829001 0.98174214 -0.14896302, + 0.092469573 0.98444766 -0.14937294, + 0.088340372 0.97969067 -0.18000594, + 0.063577615 0.98154622 -0.18034704, + 0.060230307 0.97479212 -0.21483202, + 0.037111603 0.97589213 -0.21507503, + 0.035914708 0.97613221 -0.21418704, + 0.0123337 0.97668803 -0.21430901, + 0.012129395 0.97430962 -0.22488593, + -0.012105698 0.97430986 -0.22488597, + -0.012304698 0.97667587 -0.21436597, + -0.035758208 0.97612524 -0.21424505, + -0.037803292 0.98312777 -0.17897095, + -0.062477093 0.98190886 -0.17874998, + -0.065452382 0.98688173 -0.14758196, + -0.091028444 0.98489648 -0.14728507, + -0.095075384 0.98858786 -0.11685298, + -0.12161305 0.98571533 -0.11651404, + -0.12661603 0.98812324 -0.087068722, + -0.15391198 0.98427087 -0.086729191, + -0.15987493 0.98544151 -0.057837073, + -0.18786895 0.98050678 -0.057547484, + -0.19470796 0.98042178 -0.029360093, + -0.22369203 0.97422314 -0.029174503, + -0.23135903 0.97286713 -0.0016422402, + -0.26126799 0.96526498 -0.0016294, + -0.26965606 0.96263021 0.025074506, + -0.30013904 0.95357209 0.024838604, + -0.30910513 0.94968534 0.050517019, + -0.34020787 0.93902266 0.049949881, + -0.34956089 0.93396062 0.074329168, + -0.38139394 0.92149889 0.073337391, + -0.39096001 0.915362 0.096243002, + -0.4235442 0.90090942 0.094723448, + -0.43322915 0.8937633 0.11618804, + -0.46592113 0.87744325 0.11406603, + -0.47555107 0.86942512 0.13398202, + -0.50844091 0.85105085 0.13114999, + -0.51772779 0.84244072 0.14916994, + -0.55094481 0.82175869 0.14550796, + -0.55972189 0.81277883 0.16156095, + -0.59308332 0.78969133 0.15697107, + -0.6014533 0.78028637 0.17148508, + -0.63439006 0.75499511 0.16592701, + -0.64190805 0.74575204 0.17834802, + -0.67431998 0.71818697 0.171756, + -0.68103069 0.70918363 0.18236192, + -0.71300358 0.67906857 0.1746189, + -0.71869415 0.67074019 0.18326604, + -0.75026119 0.63776416 0.17425604, + -0.7550419 0.63012195 0.18126799, + -0.78544134 0.59481329 0.17111108, + -0.7891838 0.58826691 0.17643996, + -0.81841099 0.55040902 0.165086, + -0.8212083 0.54503715 0.16897206, + -0.84933543 0.50418025 0.15630607, + -0.851116 0.500404 0.158737, + -0.87861973 0.45516986 0.14438796, + -0.9884811 -0.13924801 -0.059288807, + -0.98892277 -0.13599497 -0.059473787, + -0.99897575 -0.04145829 -0.018130597, + -0.99901462 -0.040470086 -0.018219694, + -0.99915338 0.037515115 0.016889406, + -0.99915987 0.037328098 0.016913999, + -0.9932915 0.10532895 0.047726579, + -0.99318147 0.10645206 0.047524922, + -0.98327422 0.16631004 0.074248217, + -0.98265588 0.17033099 0.073312692, + -0.96965921 0.22454506 0.096647121, + -0.96810538 0.23205508 0.094459139, + -0.95252013 0.28200704 0.11479302, + -0.94953465 0.29347587 0.11070596, + -0.9319641 0.33921802 0.12796101, + -0.92709488 0.35463998 0.12134898, + -0.90773213 0.39695507 0.13582802, + -0.90050226 0.41619408 0.12600903, + -0.87943798 0.45559001 0.13793699, + -0.87417197 0.46771199 0.130648, + -0.87130582 0.47638488 0.11782897, + -0.86991531 0.47938517 0.11591905, + -0.841865 0.52456999 0.126845, + -0.8395732 0.5289771 0.12369303, + -0.81037313 0.57052404 0.13340801, + -0.80716032 0.57607919 0.12893805, + -0.77701402 0.61428499 0.13748901, + -0.77272016 0.62099814 0.13139603, + -0.74155903 0.65635598 0.138878, + -0.73617321 0.66398627 0.13103904, + -0.70402473 0.69673675 0.13750295, + -0.69769245 0.70487148 0.1279901, + -0.66530192 0.73456293 0.13338198, + -0.65797025 0.74310327 0.12195405, + -0.62542784 0.7699818 0.12636498, + -0.61730713 0.77854019 0.11316803, + -0.584409 0.80302 0.116726, + -0.57555985 0.81141579 0.10166298, + -0.5424512 0.8335703 0.10443804, + -0.53301996 0.84156287 0.087530293, + -0.50028187 0.86121684 0.089574479, + -0.49050412 0.86854017 0.071018212, + -0.45835021 0.88581544 0.072430737, + -0.44836888 0.89231879 0.052273788, + -0.41646492 0.90759575 0.053168789, + -0.40645799 0.91312599 0.031509101, + -0.37488702 0.9265191 0.031971205, + -0.3649649 0.93097979 0.0087868478, + -0.33429691 0.94242579 0.0088948784, + -0.32475698 0.94567287 -0.015353198, + -0.29494298 0.9553889 -0.015510998, + -0.28587297 0.95739889 -0.040790997, + -0.25677598 0.96559489 -0.041140195, + -0.24835111 0.96633548 -0.067213632, + -0.21988393 0.97317475 -0.067689285, + -0.21218993 0.97264361 -0.094550461, + -0.18471195 0.97818178 -0.095088877, + -0.17778794 0.97637266 -0.12283295, + -0.15129903 0.98075724 -0.12338503, + -0.14521302 0.97765422 -0.15200503, + -0.11956197 0.98103976 -0.15253197, + -0.11436403 0.97658521 -0.18221505, + -0.089419208 0.97909713 -0.18268302, + -0.084826805 0.97267413 -0.21612403, + -0.062140193 0.97430587 -0.21648698, + -0.061252683 0.97227275 -0.22568494, + -0.037722282 0.97340852 -0.2259489, + -0.037249997 0.97144586 -0.23431897, + -0.013290395 0.97203463 -0.23446091, + -0.013071198 0.96902591 -0.24661297, + 0.012852897 0.96902877 -0.24661294, + 0.013073005 0.97205836 -0.23437509, + 0.037290316 0.97146535 -0.23423208, + 0.037760202 0.97341698 -0.225906, + 0.061280485 0.97228074 -0.22564293, + 0.062181592 0.97433591 -0.21633998, + 0.084950805 0.97269613 -0.21597603, + 0.089559309 0.97913414 -0.18241602, + 0.11455105 0.97661346 -0.18194608, + 0.11976803 0.98107421 -0.15214802, + 0.14552103 0.97766823 -0.15162003, + 0.15161492 0.98076952 -0.12289894, + 0.17810999 0.97637486 -0.12234799, + 0.18506004 0.97817421 -0.094488122, + 0.21259603 0.9726131 -0.093950912, + 0.22027101 0.97312498 -0.067145497, + 0.24884591 0.96624565 -0.066670775, + 0.25721395 0.96549577 -0.04073019, + 0.28635597 0.95727187 -0.040383298, + 0.29536405 0.95526326 -0.015242403, + 0.32517096 0.94553488 -0.015087198, + 0.33469099 0.94228399 0.0091000097, + 0.36539799 0.93080801 0.0089891804, + 0.37527701 0.92635798 0.032064099, + 0.40683293 0.91295588 0.031600196, + 0.41681394 0.90743285 0.053213194, + 0.44868588 0.89215678 0.052317388, + 0.45865589 0.88565475 0.072458886, + 0.49080187 0.86836982 0.071044788, + 0.50055701 0.861058 0.089564502, + 0.53323781 0.84142572 0.087522373, + 0.54269218 0.8334083 0.10447904, + 0.57579571 0.81124365 0.10170095, + 0.58461702 0.80286902 0.116723, + 0.61750895 0.77838087 0.11316299, + 0.62560564 0.76984352 0.12632692, + 0.65814072 0.74295866 0.12191494, + 0.66541904 0.73447806 0.13326502, + 0.69780076 0.70478475 0.12787695, + 0.70413607 0.69664508 0.13739702, + 0.73623794 0.66393292 0.13094598, + 0.74162138 0.65630531 0.13878407, + 0.77279812 0.62092108 0.13130201, + 0.7770502 0.61427414 0.13733304, + 0.80715334 0.5761193 0.12880206, + 0.8103689 0.57056093 0.13327599, + 0.83955401 0.52903497 0.123576, + 0.84182483 0.52466989 0.12669897, + 0.87069988 0.47807294 0.11544698, + 0.87150389 0.47806293 0.10925598, + 0.89347488 0.43782493 0.10005999, + -0.88607842 0.45910522 0.063934229, + -0.85690671 0.51054484 0.071097575, + -0.85498673 0.51411283 0.068452477, + -0.82495791 0.56024992 0.074595593, + -0.82189399 0.56527299 0.070403799, + -0.79097468 0.60715777 0.075620472, + -0.78682363 0.61320472 0.069917567, + -0.75519985 0.6512748 0.074258387, + -0.75002664 0.65799969 0.067054972, + -0.71768302 0.69278198 0.070599496, + -0.71136719 0.70011419 0.061619014, + -0.6784212 0.73184419 0.064411715, + -0.67114216 0.73937619 0.053769913, + -0.63833076 0.76773471 0.055832181, + -0.62998503 0.7754041 0.043213703, + -0.59737188 0.80072182 0.044624589, + -0.58831412 0.80806118 0.030391108, + -0.55571103 0.83078814 0.031245803, + -0.54607701 0.83759302 0.0154212, + -0.51358277 0.8578946 0.015794992, + -0.50342196 0.86403888 -0.0017520498, + -0.47169816 0.88175827 -0.0017879806, + -0.46121493 0.88704187 -0.020913798, + -0.4303239 0.90242374 -0.021276394, + -0.41978416 0.90666431 -0.041725714, + -0.38944086 0.92007762 -0.042342987, + -0.37906992 0.92316175 -0.063862883, + -0.34926912 0.93478835 -0.064667225, + -0.33917809 0.93666726 -0.087251522, + -0.31041306 0.94650424 -0.088167824, + -0.30073497 0.94714189 -0.11171699, + -0.27302405 0.95538425 -0.11268903, + -0.26379201 0.95475298 -0.137334, + -0.23685908 0.96164638 -0.13832605, + -0.228193 0.95970398 -0.164001, + -0.20203905 0.96538323 -0.16497104, + -0.19394991 0.96204853 -0.19195291, + -0.16884699 0.96658999 -0.19285899, + -0.16091195 0.96141762 -0.22312193, + -0.13945499 0.96459287 -0.22385897, + -0.13800505 0.96323735 -0.23049609, + -0.11564697 0.96601778 -0.23116094, + -0.11451802 0.96457714 -0.23764803, + -0.094280779 0.96663976 -0.23815694, + -0.093018331 0.96426934 -0.24805708, + -0.069812708 0.9661051 -0.24853003, + -0.068872698 0.963296 -0.25945601, + -0.0433979 0.964679 -0.25982901, + -0.042832587 0.96150064 -0.2714439, + -0.014957404 0.96227622 -0.27166307, + -0.014770495 0.95877063 -0.28379691, + 0.014734704 0.95877123 -0.28379706, + 0.014927004 0.96228623 -0.27162907, + 0.042806704 0.96151114 -0.27141103, + 0.043370511 0.96465623 -0.25991806, + 0.068795897 0.96327698 -0.259547, + 0.069735013 0.96608526 -0.24862906, + 0.092800781 0.96426374 -0.24815995, + 0.094114475 0.96673077 -0.23785295, + 0.11460906 0.96464247 -0.23733912, + 0.11569395 0.96602654 -0.2311009, + 0.13811901 0.96323609 -0.23043303, + 0.13960405 0.96462333 -0.22363508, + 0.16115105 0.96143025 -0.22289506, + 0.16913006 0.96662939 -0.19241308, + 0.19418509 0.96208948 -0.1915101, + 0.20233603 0.96543413 -0.16430801, + 0.2286389 0.95971155 -0.16333392, + 0.2373459 0.96164566 -0.13749395, + 0.26429889 0.95473152 -0.13650595, + 0.27349803 0.95533812 -0.11192802, + 0.30130595 0.94704974 -0.11095697, + 0.31093407 0.94639426 -0.087510519, + 0.33975109 0.93652022 -0.086597525, + 0.34978411 0.93463433 -0.064107321, + 0.37964115 0.92296535 -0.06330692, + 0.38993493 0.9198879 -0.041916396, + 0.42026085 0.90646273 -0.041304685, + 0.43072081 0.90224057 -0.021010891, + 0.46162489 0.88683474 -0.020652095, + 0.47204182 0.88157469 -0.0016356994, + 0.50379682 0.86382073 -0.0016027595, + 0.51389915 0.85770416 0.015850503, + 0.54633188 0.83742583 0.015475797, + 0.55596614 0.83061516 0.031306706, + 0.58856511 0.80787617 0.030449608, + 0.5975613 0.80058235 0.044592522, + 0.63016808 0.77525711 0.043181904, + 0.6384868 0.76760983 0.055764485, + 0.67126721 0.73926723 0.053705517, + 0.67859894 0.73167795 0.064428493, + 0.71149981 0.69997782 0.061637085, + 0.71773237 0.69274038 0.070506334, + 0.7501083 0.65791625 0.066961922, + 0.75531298 0.65114897 0.074211396, + 0.78689271 0.61312073 0.069877274, + 0.79099071 0.60715073 0.075509071, + 0.82190567 0.56526881 0.070300378, + 0.82489127 0.56037617 0.074384533, + 0.85492915 0.51423413 0.068259515, + 0.86217916 0.50050312 0.078382522, + 0.88515258 0.45969778 0.071992062, + 0.89491373 0.43793288 0.085697874, + 0.9162063 0.39324814 0.076953627, + 0.92298234 0.37493512 0.086760432, + 0.94236976 0.32595992 0.075427584, + 0.94669312 0.31152904 0.081987604, + 0.96391922 0.25742906 0.067749612, + 0.96630889 0.24720497 0.071671292, + 0.9806034 0.18824989 0.054578666, + 0.98167962 0.18193693 0.056605481, + 0.99249136 0.11679304 0.036337413, + 0.99279624 0.11392703 0.037098106, + 0.99909437 0.040460017 0.013175005, + 0.99911249 0.039975218 0.013279906, + 0.99896425 -0.043182213 -0.014345304, + 0.99894965 -0.043539386 -0.014283195, + 0.9886359 -0.14283998 -0.046858996, + 0.98794127 -0.14778703 -0.04616471, + 0.96013314 -0.26682803 -0.083349511, + 0.95604926 -0.28163105 -0.081571721, + 0.89805877 -0.42250991 -0.12237597, + 0.90935075 -0.39667991 -0.12540397, + 0.85888171 -0.48835182 -0.15438494, + 0.86256582 -0.47965389 -0.16097295, + 0.8426677 -0.51045483 -0.17130993, + 0.84476185 -0.50649488 -0.17274396, + 0.81856281 -0.5436669 -0.18542196, + 0.88415271 -0.41985384 -0.20493093, + 0.83443487 -0.51130897 -0.20562497, + 0.91672236 -0.32628912 -0.23055509, + 0.89404076 -0.3658669 -0.25851995, + 0.81383014 -0.53305107 -0.23138103, + 0.8429122 -0.49355912 -0.21423905, + 0.76711887 -0.61258793 -0.19043297, + 0.80124903 -0.57135999 -0.177617, + 0.7572639 -0.63195294 -0.16488399, + 0.7958563 -0.58587223 -0.15286106, + 0.75611699 -0.63881201 -0.142149, + 0.8044647 -0.57981884 -0.12902196, + 0.79957181 -0.5868299 -0.12773298, + 0.88460523 -0.45567113 -0.099184424, + 0.89896226 -0.42546308 -0.10415402, + 0.95639485 -0.28369996 -0.069450192, + 0.96025401 -0.26976001 -0.071706198, + 0.98796499 -0.149487 -0.039735701, + 0.98839062 -0.14649694 -0.040281184, + 0.99892789 -0.044636097 -0.012273198, + 0.99892133 -0.044792615 -0.012239304, + 0.99907726 0.041430913 0.011320802, + 0.99904555 0.04224408 0.011110094, + 0.99243009 0.11877201 0.031236604, + 0.99201345 0.12249206 0.030086314, + 0.98058248 0.19044709 0.046777222, + 0.97923046 0.19790909 0.044042721, + 0.96406889 0.25930896 0.057706494, + 0.96111298 0.27109599 0.052620601, + 0.94284075 0.32713792 0.063498586, + 0.93767726 0.34305608 0.055442914, + 0.91713464 0.39347184 0.063590877, + 0.90911591 0.41330495 0.051837791, + 0.88664758 0.4588508 0.057550173, + 0.88061172 0.47130483 0.048937581, + 0.85128486 0.52189791 0.054190993, + 0.84911633 0.5257172 0.051215719, + 0.8183347 0.57203382 0.05572788, + 0.81504512 0.57712609 0.051254209, + 0.78351015 0.61894304 0.054968107, + 0.77910048 0.62498456 0.048956167, + 0.74703199 0.66275799 0.051915001, + 0.74151826 0.66946822 0.044305816, + 0.70880991 0.70385993 0.046581797, + 0.70219964 0.71100366 0.037274182, + 0.669038 0.74220902 0.038910199, + 0.66133302 0.749578 0.0277771, + 0.62844419 0.77732116 0.028805207, + 0.61989599 0.78451997 0.0160414, + 0.58734995 0.80916387 0.016545298, + 0.57805908 0.81599212 0.0021331103, + 0.54562789 0.8380248 0.0021906996, + 0.53572989 0.84427583 -0.013848197, + 0.50358909 0.86382717 -0.014168904, + 0.49321195 0.86932588 -0.031850297, + 0.4618668 0.88635457 -0.032474186, + 0.45137212 0.89085627 -0.05136551, + 0.42090285 0.90560168 -0.05221568, + 0.41039395 0.90903687 -0.072310694, + 0.38063395 0.92181391 -0.073327094, + 0.37026602 0.92410213 -0.094542816, + 0.34102702 0.93517214 -0.095675416, + 0.33092412 0.93625337 -0.11797904, + 0.30279797 0.94557691 -0.11915398, + 0.29298696 0.94540888 -0.14269099, + 0.26594511 0.95319247 -0.14386608, + 0.25655797 0.95171785 -0.16855599, + 0.2303309 0.95820051 -0.16970393, + 0.22131594 0.95530379 -0.19599496, + 0.195894 0.96061599 -0.19708499, + 0.18699893 0.95595664 -0.22622593, + 0.165701 0.95967001 -0.22710501, + 0.16415395 0.95851374 -0.23303394, + 0.14219393 0.9618215 -0.2338379, + 0.14100499 0.96063203 -0.239382, + 0.12204105 0.96307337 -0.23999108, + 0.12047402 0.96085811 -0.24947503, + 0.098357953 0.96321452 -0.25008687, + 0.097116023 0.96062726 -0.26031506, + 0.072666593 0.9626379 -0.26085997, + 0.071768515 0.95968926 -0.27174607, + 0.045082413 0.96119225 -0.27217105, + 0.044536415 0.95784634 -0.28380808, + 0.015514407 0.95868248 -0.28405514, + 0.015336894 0.95511967 -0.29582289, + -0.015301504 0.95512027 -0.29582307, + -0.015479198 0.95868987 -0.28403196, + -0.044499904 0.95785511 -0.28378403, + -0.045044087 0.96119064 -0.27218291, + -0.071798794 0.9596839 -0.27175698, + -0.072702222 0.96266335 -0.26075608, + -0.097358122 0.96063226 -0.26020607, + -0.098595023 0.96321523 -0.24999106, + -0.120571 0.96087003 -0.249382, + -0.12206894 0.96298254 -0.24034087, + -0.14089903 0.96055925 -0.23973607, + -0.14214003 0.96180326 -0.23394606, + -0.16407594 0.95850062 -0.23314291, + -0.16556294 0.95961565 -0.22743492, + -0.18683006 0.95591134 -0.22655708, + -0.19567607 0.96055734 -0.19758707, + -0.22101189 0.95527053 -0.19649892, + -0.22992402 0.95815212 -0.17052701, + -0.25608203 0.95170009 -0.16937801, + -0.26545185 0.95319539 -0.1447539, + -0.29242188 0.94544965 -0.14357695, + -0.30224887 0.94564253 -0.12002394, + -0.33030987 0.93636066 -0.11884496, + -0.34046584 0.93529761 -0.096444152, + -0.36960879 0.92428648 -0.095308743, + -0.3800661 0.92200124 -0.073916718, + -0.40981191 0.90925276 -0.072894685, + -0.42042685 0.90579969 -0.052613281, + -0.45086712 0.89108926 -0.051758811, + -0.46145573 0.88655949 -0.032722883, + -0.49279588 0.86955285 -0.032095194, + -0.50321108 0.86404413 -0.014369502, + -0.53538519 0.8444913 -0.014044304, + -0.54537588 0.83818883 0.0021366896, + -0.57780987 0.81616884 0.0020805495, + -0.58710265 0.80934453 0.01648719, + -0.61967707 0.78469414 0.015985003, + -0.6282602 0.77747017 0.028796908, + -0.66117907 0.74971408 0.027768904, + -0.66891098 0.74232203 0.0389378, + -0.70205706 0.71114308 0.037302405, + -0.70869708 0.70396906 0.046648204, + -0.74143463 0.66955668 0.044367876, + -0.746948 0.662848 0.051973298, + -0.77904528 0.62504923 0.049009517, + -0.78345209 0.61901206 0.055018809, + -0.8150211 0.57715607 0.051298507, + -0.8183133 0.57206017 0.055773318, + -0.84909898 0.52574098 0.051257301, + -0.85133398 0.52180398 0.054323401, + -0.88064331 0.47123319 0.04905862, + -0.88670361 0.4587228 0.057706475, + -0.90917456 0.4131588 0.051974673, + -0.91720587 0.39327893 0.063757293, + -0.93774891 0.34283796 0.055579994, + -0.94290388 0.32693097 0.063627489, + -0.96116579 0.27088895 0.052720487, + -0.96413177 0.25904796 0.057828285, + -0.97927088 0.19768897 0.044130795, + -0.9806245 0.19020709 0.046871822, + -0.9920311 0.12233402 0.030146103, + -0.99244964 0.11859096 0.031303689, + -0.99904877 0.04216319 0.011129498, + -0.99908012 0.041356303 0.011338701, + -0.99892509 -0.044704605 -0.012256701, + -0.99893177 -0.044544987 -0.012291198, + -0.98843586 -0.14617698 -0.040334396, + -0.98802751 -0.14905293 -0.03980948, + -0.96047515 -0.26893902 -0.071829006, + -0.95703399 -0.28144801 -0.069806501, + -0.90048027 -0.42210716 -0.10469404, + -0.88554025 -0.45378211 -0.099500924, + -0.81959885 -0.55475193 -0.14320599, + -0.78323549 -0.60729736 -0.13316208, + -0.76624811 -0.63240206 -0.11371701, + -0.88867211 -0.45130506 -0.081152506, + -0.90107024 -0.4249461 -0.086563826, + -0.89058685 -0.45046493 -0.062740095, + -0.90040386 -0.42972693 -0.067879491, + -0.95689809 -0.28686702 -0.045313403, + -0.95858598 -0.28093499 -0.0467804, + -0.98745525 -0.15575503 -0.025935806, + -0.9873929 -0.15616798 -0.025824897, + -0.99883825 -0.04754281 -0.0078619616, + -0.99879336 -0.048525918 -0.0075644027, + -0.99897265 0.044775885 0.0069798278, + -0.99890774 0.046278488 0.0064589488, + -0.99140078 0.12960397 0.018088397, + -0.99069387 0.13518098 0.015863799, + -0.9775781 0.20913804 0.024542803, + -0.97546053 0.21927489 0.019879991, + -0.95798337 0.2856521 0.025897909, + -0.95358622 0.30058405 0.017962804, + -0.93258524 0.3603071 0.021531906, + -0.92512459 0.37953982 0.0096933758, + -0.90171885 0.43218195 0.011037899, + -0.89042515 0.45509806 -0.0053830706, + -0.86517859 0.50142878 -0.0059310873, + -0.85668969 0.51552784 -0.017715294, + -0.82368457 0.56671369 -0.01947429, + -0.82036453 0.57134265 -0.023867685, + -0.7864151 0.61716008 -0.025781704, + -0.78183389 0.62267792 -0.031749096, + -0.74770105 0.66317403 -0.033814006, + -0.74193376 0.66919976 -0.041304186, + -0.70791507 0.70495605 -0.043511104, + -0.70096499 0.71125299 -0.052606001, + -0.6670022 0.7430262 -0.054956015, + -0.65894121 0.74932122 -0.065682925, + -0.62511837 0.77754849 -0.068157241, + -0.61605263 0.78358054 -0.080502652, + -0.58315814 0.80810517 -0.083022423, + -0.57332116 0.81358832 -0.096834235, + -0.54138696 0.83488089 -0.099368483, + -0.53108394 0.83956391 -0.11437798, + -0.49976006 0.85823613 -0.11692201, + -0.48899588 0.8620438 -0.13327996, + -0.45844999 0.87828499 -0.135791, + -0.44749716 0.88105232 -0.15327506, + -0.41817507 0.89492512 -0.15568802, + -0.40697005 0.89660513 -0.17457001, + -0.37889591 0.90838176 -0.17686296, + -0.367576 0.90886199 -0.197124, + -0.340455 0.91889602 -0.19930001, + -0.3290849 0.91806579 -0.22103894, + -0.30283704 0.92656511 -0.22308503, + -0.29155305 0.92430222 -0.24629706, + -0.27161899 0.92995501 -0.247804, + -0.27099803 0.9297561 -0.24922603, + -0.25033295 0.93514574 -0.25067094, + -0.24933305 0.93470925 -0.25328207, + -0.23557401 0.93802798 -0.25418201, + -0.23406589 0.93712556 -0.25886089, + -0.21648407 0.94104433 -0.2599431, + -0.21461497 0.9395169 -0.26692396, + -0.19444604 0.94357121 -0.26807505, + -0.19266197 0.94159287 -0.27619597, + -0.17005305 0.94559425 -0.27736905, + -0.16848893 0.94323266 -0.2862229, + -0.14329708 0.94703746 -0.28737816, + -0.14201699 0.94436187 -0.29666796, + -0.114092 0.94780201 -0.29774901, + -0.11301702 0.94459009 -0.30818304, + -0.083169222 0.94738722 -0.30909607, + -0.0829385 0.94633299 -0.31237, + -0.051189389 0.94835979 -0.31303892, + -0.052080099 0.95548803 -0.29039699, + -0.017929394 0.95663261 -0.2907449, + -0.018225705 0.96382338 -0.26591808, + 0.017912099 0.96382898 -0.265919, + 0.01760901 0.9566595 -0.29067615, + 0.051874626 0.9555195 -0.29033014, + 0.050977893 0.94840586 -0.31293398, + 0.082912304 0.94637102 -0.312262, + 0.083134204 0.94738513 -0.30911204, + 0.11301395 0.9445855 -0.30819786, + 0.11409304 0.94780934 -0.29772511, + 0.14198299 0.94437391 -0.29664597, + 0.14326602 0.94704914 -0.28735504, + 0.16842794 0.94324964 -0.28620291, + 0.16999196 0.94560778 -0.27735993, + 0.19273108 0.94158345 -0.27618012, + 0.19443703 0.94347614 -0.26841602, + 0.21442707 0.93946034 -0.26727408, + 0.21634604 0.94103122 -0.26010507, + 0.23394294 0.93711174 -0.25902194, + 0.23570205 0.93816525 -0.25355607, + 0.24960896 0.93480688 -0.25264898, + 0.25041687 0.93515861 -0.25053889, + 0.27115503 0.9297471 -0.24908903, + 0.27192312 0.92999339 -0.24732612, + 0.29185006 0.92433524 -0.24582106, + 0.30335188 0.92662364 -0.22213992, + 0.32967788 0.91808063 -0.22009192, + 0.34113398 0.91888988 -0.19816397, + 0.36837289 0.9087857 -0.19598493, + 0.37970281 0.90827459 -0.17567891, + 0.40785879 0.89643061 -0.17338791, + 0.41904616 0.89472228 -0.15450706, + 0.44844589 0.88077378 -0.15209797, + 0.45927888 0.87800777 -0.13477796, + 0.48986381 0.86170572 -0.13227496, + 0.50042796 0.85794491 -0.11619999, + 0.53173703 0.83924699 -0.113667, + 0.54192102 0.83459902 -0.0988236, + 0.57392901 0.81322402 -0.096292697, + 0.58360398 0.80781698 -0.082693197, + 0.61650497 0.7832579 -0.080179192, + 0.62544882 0.77729779 -0.067984082, + 0.65921921 0.74909121 -0.065517113, + 0.66717279 0.74287474 -0.05493208, + 0.70114219 0.71108019 -0.052581012, + 0.70802617 0.7048412 -0.04356391, + 0.74203902 0.66908002 -0.041353598, + 0.74774116 0.66312218 -0.033942707, + 0.78183645 0.62266839 -0.031872019, + 0.78645509 0.61710608 -0.025855204, + 0.8203811 0.57131606 -0.023936704, + 0.823695 0.56669599 -0.019550901, + 0.85668391 0.51553494 -0.017785897, + 0.86515629 0.50146616 -0.0060243923, + 0.89038926 0.45516711 -0.0054681716, + 0.90165901 0.43230999 0.0109135, + 0.92507237 0.37967014 0.0095846336, + 0.93251258 0.36050382 0.02138469, + 0.95353425 0.30075607 0.017840505, + 0.95792687 0.28585398 0.025758997, + 0.97541678 0.21947894 0.019777695, + 0.97753721 0.20934105 0.024441706, + 0.99067366 0.13533695 0.015801394, + 0.99137723 0.12979503 0.018012004, + 0.99890465 0.046349283 0.0064319978, + 0.9989695 0.044850476 0.0069513465, + 0.99878865 -0.048624583 -0.0075362972, + 0.99883366 -0.04764438 -0.0078329667, + 0.98734051 -0.15651393 -0.025731687, + 0.98740166 -0.15610994 -0.025840191, + 0.95838851 -0.28163484 -0.046617776, + 0.9567309 -0.28744498 -0.045180798, + 0.89995641 -0.4306922 -0.067696631, + 0.88987374 -0.45191488 -0.062430985, + 0.7913841 -0.60556805 -0.083657704, + 0.75643301 -0.650249 -0.070607498, + 0.60967588 -0.78801882 -0.085567281, + 0.54021508 -0.8391481 -0.063231207, + 0.38396394 -0.92073786 -0.069379196, + 0.39004984 -0.91802865 -0.07130608, + 0.33566701 -0.939152 -0.072946802, + 0.44926411 -0.88641423 -0.11149803, + 0.4098289 -0.90503079 -0.11383997, + 0.52937919 -0.83355629 -0.15792906, + 0.49189207 -0.85543811 -0.16207401, + 0.60467988 -0.76907885 -0.20707496, + 0.57042032 -0.79310733 -0.2135451, + 0.67117584 -0.69537282 -0.25686494, + 0.64104402 -0.71995503 -0.265946, + 0.76100111 -0.56352007 -0.32143804, + 0.73447216 -0.58948213 -0.3362461, + 0.82565409 -0.41581205 -0.38130805, + 0.8424688 -0.39706892 -0.3641189, + 0.83864868 -0.41509485 -0.35265389, + 0.88870776 -0.26339093 -0.37526491, + 0.86055779 -0.29261994 -0.4169099, + 0.8826496 -0.19387691 -0.42818379, + 0.85628682 -0.21304396 -0.47051588, + 0.87162185 -0.10298797 -0.47923788, + 0.86724442 -0.056159224 -0.49470523, + 0.88593602 -0.115271 -0.44925499, + 0.88594186 -0.11526898 -0.44924393, + 0.89177102 -0.0161146 -0.4522, + 0.91301358 0.0031669587 -0.40791678, + 0.90760523 -0.10872802 -0.4055011, + 0.90757632 -0.10874104 -0.40556216, + 0.91298586 0.0031550096 -0.40797895, + 0.91309577 0.0031550394 -0.4077329, + 0.93194824 -0.0064523313 -0.36253408, + 0.93186367 -0.0063535278 -0.36275288, + 0.92710102 -0.101171 -0.360899, + 0.93725687 -0.050995294 -0.34488997, + 0.92823112 -0.14795402 -0.34131604, + 0.946684 -0.128132 -0.295587, + 0.95977175 -0.081931375 -0.26856193, + 0.94847703 -0.0176661 -0.31635299, + 0.9526751 -0.059543706 -0.29810202, + 0.94675064 -0.12650895 -0.29607189, + 0.96228588 -0.10689198 -0.25015998, + 0.95624113 -0.15471502 -0.24832703, + 0.97111666 -0.12617296 -0.20251593, + 0.96410537 -0.17393006 -0.20062208, + 0.97869879 -0.13448396 -0.15512197, + 0.97194552 -0.17825891 -0.15344593, + 0.98600566 -0.12634796 -0.10876096, + 0.98072934 -0.16317905 -0.10743704, + 0.99324924 -0.096885726 -0.063789316, + 0.99092978 -0.11868297 -0.063027889, + 0.99908 -0.037876599 -0.0201148, + 0.99901825 -0.039510511 -0.020035405, + 0.99915689 0.036615197 0.018567199, + 0.9991715 0.03619802 0.018604809, + 0.99338114 0.10216101 0.052507907, + 0.99337262 0.10224997 0.05249558, + 0.98371273 0.15990496 0.082095779, + 0.98333353 0.16246493 0.081610359, + 0.97078413 0.21442203 0.10771001, + 0.96954721 0.22069906 0.10616102, + 0.95456433 0.26855108 0.12917905, + 0.9521091 0.27855104 0.12608601, + 0.93521476 0.3225739 0.14601196, + 0.93110901 0.336492 0.140745, + 0.91251272 0.37736785 0.15784194, + 0.9063431 0.39511305 0.14976001, + 0.88606101 0.433476 0.16429999, + 0.8852343 0.43256414 0.17102206, + 0.85896885 0.47616294 0.18825898, + 0.85749573 0.47958282 0.18628295, + 0.83036613 0.51941109 0.20175304, + 0.82811183 0.5241819 0.19865595, + 0.79973984 0.5613839 0.21275395, + 0.7965163 0.56764418 0.20818707, + 0.76681983 0.6026119 0.22101194, + 0.76268387 0.61001194 0.21493897, + 0.73173493 0.64285094 0.22650997, + 0.72652292 0.65146095 0.21854797, + 0.69497591 0.68169594 0.22868997, + 0.68891495 0.69095892 0.21902497, + 0.65675282 0.71885484 0.22786695, + 0.6499145 0.72853845 0.21643186, + 0.61704409 0.75434518 0.22409806, + 0.60932106 0.76447111 0.21050403, + 0.57580888 0.78824681 0.21705095, + 0.56751388 0.79829681 0.20161895, + 0.53390998 0.81979901 0.20705, + 0.52512801 0.829615 0.18968301, + 0.49177206 0.84882009 0.19407403, + 0.48266581 0.85817069 0.17486194, + 0.44924587 0.87541974 0.17837696, + 0.43996984 0.88411772 0.15736094, + 0.40644214 0.89953929 0.16010606, + 0.39717785 0.90739769 0.13740195, + 0.36431682 0.92077857 0.13942795, + 0.35522503 0.92766112 0.11515202, + 0.3229931 0.93919325 0.11658303, + 0.31429896 0.94494486 0.091079094, + 0.28250006 0.95484221 0.092033021, + 0.27428487 0.95943552 0.065202273, + 0.24297506 0.96780026 0.065770812, + 0.23537312 0.97117245 0.037731919, + 0.20494111 0.97803646 0.03799862, + 0.19812103 0.98013514 0.0091288714, + 0.16857308 0.98564649 0.0091802049, + 0.16265498 0.98647386 -0.020316599, + 0.13386002 0.99079013 -0.020405501, + 0.12888105 0.99037135 -0.050540119, + 0.10074602 0.99361926 -0.05070591, + 0.096794724 0.99197525 -0.08133892, + 0.069601007 0.99423814 -0.081524409, + 0.066713825 0.99138236 -0.11274004, + 0.04035642 0.99278647 -0.11290005, + 0.038509216 0.98855233 -0.14588106, + 0.064724192 0.98721188 -0.14568299, + 0.067657024 0.99112839 -0.11439904, + 0.094064303 0.98900002 -0.114153, + 0.098048277 0.99165374 -0.08372248, + 0.12541701 0.98858714 -0.083463609, + 0.13040301 0.99000615 -0.053693108, + 0.15847404 0.98591423 -0.053471211, + 0.16441207 0.98609233 -0.02430561, + 0.19322491 0.98085654 -0.02417649, + 0.20004508 0.97977734 0.0042980914, + 0.22975291 0.97323966 0.0042694085, + 0.23739202 0.97088414 0.032080803, + 0.2680279 0.96288562 0.03181649, + 0.27634993 0.95926476 0.058667984, + 0.30750102 0.94977313 0.058087509, + 0.31633303 0.94494814 0.083705507, + 0.34798187 0.93384463 0.082721867, + 0.35715997 0.92789787 0.10696898, + 0.38954082 0.9149496 0.10547595, + 0.39896709 0.90794021 0.12833503, + 0.4320429 0.89297676 0.12621997, + 0.44153395 0.88503689 0.14750399, + 0.47462681 0.86821169 0.14469896, + 0.48395911 0.8595472 0.16420205, + 0.51711076 0.84071559 0.16060393, + 0.52609926 0.83154041 0.17821409, + 0.55947894 0.8104409 0.17369199, + 0.56809932 0.80081934 0.1896091, + 0.60149902 0.777381 0.18405899, + 0.60950267 0.76764464 0.19806091, + 0.64246398 0.74201602 0.191448, + 0.6496672 0.73249519 0.20342904, + 0.68196344 0.70471442 0.19571312, + 0.68823296 0.69572496 0.20567498, + 0.71997803 0.66552407 0.19674703, + 0.72542101 0.65705502 0.205044, + 0.75669813 0.62408209 0.19475503, + 0.76117629 0.61650425 0.20132907, + 0.79120171 0.5813418 0.18984592, + 0.79466373 0.57495683 0.19476692, + 0.82340819 0.53745013 0.18206105, + 0.82598186 0.53225791 0.18562199, + 0.85357082 0.49192089 0.17155395, + 0.8551569 0.48839894 0.17370398, + 0.88155514 0.44478706 0.15819302, + 0.87859523 0.45526013 0.14425203, + 0.85107583 0.5005179 0.15859295, + 0.84926039 0.50436622 0.15611407, + 0.82114083 0.54520589 0.16875495, + 0.81840318 0.55046111 0.16495104, + 0.78922212 0.58826405 0.17627801, + 0.78549987 0.59477395 0.17097898, + 0.75507587 0.63011795 0.18113999, + 0.75031388 0.63772994 0.17415398, + 0.71875507 0.67070407 0.18315901, + 0.71308506 0.67900306 0.17454101, + 0.68116015 0.70908219 0.18227305, + 0.67444992 0.71808696 0.17166398, + 0.64209592 0.74561495 0.17824498, + 0.63454562 0.75489855 0.16577089, + 0.6015721 0.7802282 0.17133304, + 0.59334606 0.78947514 0.15706502, + 0.55996495 0.8125909 0.16166398, + 0.55114704 0.82162112 0.14551902, + 0.51798117 0.84228331 0.14917906, + 0.50869483 0.85089868 0.13115296, + 0.47583589 0.86926883 0.13398497, + 0.46620718 0.87729132 0.11406504, + 0.43355 0.89360797 0.116186, + 0.423886 0.90074497 0.094758101, + 0.39128095 0.91522086 0.096280888, + 0.38173792 0.92134976 0.073421985, + 0.34988299 0.933833 0.074416801, + 0.34055391 0.93889076 0.05007169, + 0.30949703 0.94955111 0.050640207, + 0.30054593 0.95343977 0.024993695, + 0.27006206 0.96251225 0.025231505, + 0.2617099 0.96514565 -0.0013683696, + 0.23173194 0.97277874 -0.0013791897, + 0.22409894 0.97414076 -0.028798593, + 0.19511002 0.98035312 -0.028982304, + 0.18827602 0.98044914 -0.057198208, + 0.16021805 0.98540622 -0.057487413, + 0.15426393 0.98424953 -0.086345457, + 0.12695396 0.98811364 -0.086684473, + 0.12194403 0.98570621 -0.11624503, + 0.095329098 0.98859501 -0.116586, + 0.091286503 0.984905 -0.14706799, + 0.065669879 0.98689961 -0.14736594, + 0.06268587 0.98189753 -0.17873891, + 0.037944499 0.98312402 -0.17896201, + 0.027356707 0.98651326 -0.16137904, + 0.012934702 0.98680013 -0.16142601, + 0.0119313 0.97675598 -0.214022, + -0.011822605 0.97675735 -0.21402207, + -0.012823993 0.9867925 -0.16148092, + -0.027242614 0.98650748 -0.16143407, + -0.88531959 0.4323678 0.17107692, + -0.8590014 0.47606224 0.18836509, + -0.85752779 0.47948489 0.18638796, + -0.83038771 0.51932883 0.20187593, + -0.82811588 0.52413791 0.19875497, + -0.79969037 0.56140423 0.21288611, + -0.7965191 0.56756508 0.20839202, + -0.76685786 0.60248893 0.22121496, + -0.76265311 0.61001408 0.21504202, + -0.73168182 0.64287084 0.22662494, + -0.72646981 0.65148079 0.21866496, + -0.6948992 0.68173116 0.22881806, + -0.68882096 0.69101995 0.21912797, + -0.6566298 0.71893179 0.22797894, + -0.64972699 0.72870302 0.21644101, + -0.61680621 0.75453532 0.22411308, + -0.60918123 0.76452929 0.21069707, + -0.57561791 0.78832984 0.21725595, + -0.56722683 0.7984947 0.20164293, + -0.5337379 0.81991082 0.20705095, + -0.52495086 0.82972485 0.18969296, + -0.49150476 0.84897059 0.19409291, + -0.48239705 0.85831714 0.17488502, + -0.44894078 0.87557161 0.17839991, + -0.43964586 0.88427973 0.15735593, + -0.40611309 0.89968926 0.16009805, + -0.39687395 0.90752089 0.13746598, + -0.3639749 0.92090374 0.13949397, + -0.35485682 0.92780161 0.11515595, + -0.32264909 0.93931127 0.11658503, + -0.31392184 0.94507855 0.090991959, + -0.28215009 0.95495439 0.091942929, + -0.27392498 0.95954388 0.065119289, + -0.2425831 0.96790433 0.065686725, + -0.23494403 0.97128314 0.037557002, + -0.20454197 0.97812688 0.037821595, + -0.19771297 0.98021889 0.0089717489, + -0.1682009 0.9857114 0.0090220142, + -0.16225894 0.98653466 -0.020529592, + -0.13351099 0.99083287 -0.020618998, + -0.12852199 0.99040401 -0.050813101, + -0.10043002 0.99363726 -0.050979011, + -0.096485116 0.99198711 -0.081560709, + -0.069328405 0.99423909 -0.081745811, + -0.066441 0.99137503 -0.112965, + -0.040160395 0.99276888 -0.11312398, + -0.038316984 0.98853564 -0.14604494, + -0.064478271 0.98720354 -0.14584793, + -0.067412011 0.99111325 -0.11467403, + -0.093814582 0.98899186 -0.11442898, + -0.097792841 0.99165148 -0.084047034, + -0.12505099 0.98860586 -0.083788991, + -0.13005401 0.99003613 -0.053986806, + -0.15810493 0.9859575 -0.053764373, + -0.164047 0.98614597 -0.0245899, + -0.19278792 0.98093551 -0.02445999, + -0.19963896 0.97986078 0.0041365488, + -0.22934394 0.97333676 0.0041090092, + -0.23697397 0.97099286 0.031875998, + -0.26763609 0.96300137 0.031613711, + -0.27599493 0.95937276 0.058571585, + -0.30709898 0.94990885 0.057993792, + -0.31594512 0.94508135 0.083666332, + -0.34765282 0.93397057 0.082682662, + -0.35681888 0.92804062 0.10686796, + -0.38922891 0.91509378 0.10537698, + -0.39868599 0.90807098 0.12828299, + -0.43172586 0.89313668 0.12617296, + -0.44122079 0.88520157 0.14745292, + -0.47434422 0.86837441 0.14465007, + -0.48369688 0.85969782 0.16418596, + -0.51685512 0.84087521 0.16059205, + -0.52591282 0.83163369 0.17832895, + -0.55922401 0.81059003 0.17381699, + -0.56781685 0.80100185 0.18968396, + -0.60138124 0.77746028 0.18410906, + -0.60936534 0.76775348 0.19806212, + -0.64226598 0.74218303 0.19146501, + -0.64948791 0.73264092 0.20347697, + -0.68182802 0.70483398 0.19575401, + -0.68814385 0.69578081 0.20578395, + -0.71991181 0.66556585 0.19684796, + -0.72537398 0.657067 0.205172, + -0.7566582 0.62409312 0.19487505, + -0.76115555 0.61648166 0.20147587, + -0.79115272 0.58135885 0.18999793, + -0.79467899 0.574853 0.195011, + -0.82346988 0.53728592 0.18226698, + -0.82599884 0.53218091 0.18576695, + -0.8536008 0.4918249 0.17167996, + -0.85520327 0.48826519 0.17385206, + -0.88157141 0.44470221 0.15834108, + -0.88612831 0.43325415 0.16452207, + -0.90640777 0.3948909 0.14995398, + -0.91256171 0.37717384 0.15802194, + -0.93118536 0.33622912 0.14086804, + -0.93530703 0.32223901 0.14616001, + -0.95216978 0.27828193 0.12622197, + -0.95463586 0.26822197 0.12933399, + -0.9696039 0.22039597 0.10627299, + -0.97082925 0.21416804 0.10780902, + -0.98336887 0.16222498 0.081661992, + -0.98376364 0.15955395 0.082168169, + -0.99339634 0.10200204 0.052529719, + -0.99343377 0.10160898 0.05258359, + -0.99917865 0.03598759 0.018623792, + -0.99916422 0.036406308 0.018586103, + -0.99902755 -0.039268181 -0.020047192, + -0.99899149 -0.040199518 -0.020001909, + -0.99002725 -0.12612604 -0.062756017, + -0.9929781 -0.099690117 -0.063689508, + -0.9799571 -0.16787401 -0.10725001, + -0.98554087 -0.13003398 -0.10862999, + -0.97104633 -0.18333507 -0.15315805, + -0.97832203 -0.137391 -0.15495101, + -0.96345091 -0.17772499 -0.20043997, + -0.97119755 -0.12552494 -0.20253091, + -0.9563601 -0.15392801 -0.24835803, + -0.96341151 -0.095294252 -0.25051388, + -0.94831526 -0.11282303 -0.29659605, + -0.87541986 -0.43708494 -0.20638996, + -0.86963987 -0.46772593 -0.15798399, + -0.84400088 -0.50813794 -0.17163399, + -0.89912027 -0.39579514 -0.18689306, + -0.89113724 -0.41760108 -0.17743705, + -0.94615322 -0.26061705 -0.19202304, + -0.92741758 -0.30111885 -0.22186489, + -0.90177691 -0.36661798 -0.22888798, + -0.94194162 -0.23368491 -0.24111691, + -0.91828734 -0.27553809 -0.2843011, + -0.93738914 -0.19133203 -0.29102203, + -0.91582114 -0.22061403 -0.33556104, + -0.93023038 -0.13478105 -0.34132913, + -0.90946674 -0.15270497 -0.3867189, + -0.91879362 -0.05458438 -0.39094585, + -0.92991424 -0.089385621 -0.35674909, + -0.92985463 -0.089414172 -0.35689688, + -0.93636161 -0.067969069 -0.34439382, + -0.9303084 -0.13252506 -0.34199914, + -0.94826221 -0.11471603 -0.29603904, + -0.93790025 -0.18666005 -0.29240605, + -0.95601398 -0.157828 -0.24724001, + -0.94335109 -0.22555703 -0.24333704, + -0.96257573 -0.18423596 -0.19875896, + -0.94891876 -0.24802195 -0.19503395, + -0.96963239 -0.19224708 -0.15117607, + -0.95580512 -0.25418502 -0.14773801, + -0.977943 -0.180585 -0.10496, + -0.96555799 -0.239392 -0.101928, + -0.96317691 -0.24989097 -0.099220082, + -0.92737198 -0.34773299 -0.138069, + -0.95092934 -0.27392009 -0.14387904, + -0.92870855 -0.32827985 -0.17243192, + -0.8673746 -0.47243476 -0.15641792, + -0.91040599 -0.39274901 -0.130035, + -0.90098572 -0.41462386 -0.12771796, + -0.94971937 -0.29922813 -0.092172228, + -0.96056324 -0.26125607 -0.095202625, + -0.98807621 -0.14466003 -0.052714612, + -0.98885053 -0.13905895 -0.053266276, + -0.99896878 -0.04239909 -0.016240897, + -0.99899566 -0.041724585 -0.016329795, + -0.99913776 0.038662191 0.015131297, + -0.99913388 0.038770597 0.015112398, + -0.99309427 0.10930903 0.042607512, + -0.99288476 0.11136997 0.042149387, + -0.9825899 0.17375998 0.065761894, + -0.98176664 0.17886694 0.064350277, + -0.96819574 0.23542194 0.084696978, + -0.96624774 0.24431594 0.081701376, + -0.94992745 0.29633981 0.099098638, + -0.94633222 0.30926305 0.093870521, + -0.927926 0.356695 0.108268, + -0.92216814 0.37360302 0.10013402, + -0.90187979 0.4172599 0.11183497, + -0.89762223 0.42787209 0.10583002, + -0.89434028 0.43776214 0.092303127, + -0.86689389 0.48776793 0.10284699, + -0.86533302 0.490978 0.100695, + -0.83663499 0.53659201 0.11005, + -0.83411968 0.54118681 0.10658896, + -0.80439973 0.58289081 0.11480196, + -0.80087185 0.58866388 0.10990497, + -0.7702511 0.62690806 0.11704502, + -0.76569939 0.63361531 0.11061705, + -0.7340914 0.66893339 0.11678207, + -0.728378 0.67652798 0.108515, + -0.69600785 0.7089718 0.11371897, + -0.68930608 0.71700609 0.10372801, + -0.65674281 0.7463448 0.10797298, + -0.6491552 0.75454116 0.09625642, + -0.61655593 0.7809819 0.099629484, + -0.60813826 0.78914928 0.086088628, + -0.57527614 0.81313521 0.088705324, + -0.56611282 0.82106471 0.073273167, + -0.53318423 0.84265041 0.075199537, + -0.52349305 0.85005212 0.058022108, + -0.49108282 0.86909068 0.059321579, + -0.48109883 0.87572569 0.040600084, + -0.44931215 0.8924163 0.041374017, + -0.43912378 0.89817959 0.021063691, + -0.40772286 0.91285473 0.021407893, + -0.39750209 0.91760123 -0.00041226909, + -0.36647996 0.93042588 -0.00041803095, + -0.35649887 0.93400264 -0.023402093, + -0.32646403 0.94491315 -0.023675404, + -0.31684104 0.94727415 -0.047784906, + -0.28770706 0.95650226 -0.048250411, + -0.2786479 0.95760167 -0.073174268, + -0.25023705 0.96537024 -0.073767915, + -0.2417739 0.96520567 -0.099616066, + -0.21408592 0.97165364 -0.10028196, + -0.20632893 0.97020662 -0.12699395, + -0.17959599 0.97541988 -0.12767698, + -0.172589 0.97266501 -0.155357, + -0.14687601 0.97677398 -0.156013, + -0.14065401 0.97265309 -0.18483101, + -0.11582997 0.97580677 -0.18543096, + -0.11004403 0.96974826 -0.21789604, + -0.087627873 0.97192067 -0.21838392, + -0.086480156 0.97009355 -0.2268029, + -0.063307732 0.97178847 -0.22719911, + -0.062572882 0.96999174 -0.23494793, + -0.039883405 0.9711231 -0.23522203, + -0.039266113 0.96829736 -0.24669509, + -0.013812204 0.96895224 -0.24686205, + -0.0136028 0.96578801 -0.25897601, + 0.013495406 0.9657895 -0.25897613, + 0.013703804 0.96894437 -0.24689908, + 0.039120216 0.96829337 -0.24673408, + 0.039747018 0.97116446 -0.23507412, + 0.062589683 0.97002679 -0.23479894, + 0.063315697 0.97180098 -0.227143, + 0.086547792 0.97010088 -0.22674596, + 0.087715425 0.97195321 -0.21820405, + 0.11014505 0.96977746 -0.2177151, + 0.11596697 0.97586274 -0.18504995, + 0.14087202 0.9726941 -0.18444902, + 0.14712407 0.97682136 -0.15548205, + 0.17284 0.97270501 -0.154827, + 0.17987199 0.97544789 -0.12707299, + 0.20670298 0.9702059 -0.12638998, + 0.21447304 0.97163624 -0.09962102, + 0.242287 0.96514499 -0.098955497, + 0.25072113 0.96528947 -0.073180035, + 0.27915299 0.95749903 -0.072589397, + 0.28817102 0.9563871 -0.047762606, + 0.31732184 0.94713753 -0.047300678, + 0.326868 0.94478101 -0.023370899, + 0.35695291 0.93383676 -0.023100095, + 0.36690396 0.93025887 -0.00015532899, + 0.39792705 0.91741711 -0.00015318401, + 0.40808994 0.91268688 0.021569198, + 0.43949389 0.89799476 0.021221993, + 0.44962716 0.89225429 0.041444015, + 0.48139688 0.87555873 0.040668488, + 0.49137613 0.86892021 0.059389416, + 0.52378488 0.84986782 0.058087185, + 0.53339911 0.84252018 0.075134717, + 0.56634408 0.82091111 0.073207706, + 0.57550603 0.8129791 0.088644907, + 0.60831112 0.78902221 0.086032726, + 0.61675394 0.78082687 0.099618986, + 0.6493457 0.75437862 0.096244559, + 0.65690857 0.74620557 0.10792793, + 0.68941998 0.71690202 0.10369, + 0.69612223 0.70886523 0.11368404, + 0.72851735 0.67638427 0.10847505, + 0.73413879 0.66891176 0.11660796, + 0.76570964 0.63363069 0.11045795, + 0.7703262 0.62682819 0.11697903, + 0.80092233 0.5886063 0.10984606, + 0.80438387 0.58294195 0.11465298, + 0.83410418 0.54123813 0.10645002, + 0.83659846 0.53668332 0.10988206, + 0.86527371 0.49111181 0.10055196, + 0.86137384 0.5009079 0.084418274, + 0.83095872 0.54859781 0.092455469, + 0.82825857 0.55327374 0.088745654, + 0.79796582 0.59509587 0.095453978, + 0.79415637 0.60098428 0.090186648, + 0.76305765 0.63917369 0.095917359, + 0.75818533 0.64592624 0.089075528, + 0.72623283 0.68100381 0.09391278, + 0.72019899 0.68851 0.085249104, + 0.68756092 0.72062397 0.089225389, + 0.68062425 0.72836322 0.078978531, + 0.64795768 0.75723761 0.082109362, + 0.64003694 0.76514888 0.069999292, + 0.60740888 0.79108584 0.072372086, + 0.5986169 0.79890484 0.058386184, + 0.56592196 0.82226586 0.060093392, + 0.55652303 0.829642 0.044454899, + 0.52382606 0.85060513 0.045578104, + 0.51398176 0.85733259 0.028349187, + 0.48186418 0.87576729 0.028958712, + 0.47168505 0.8817091 0.010119201, + 0.44034201 0.897771 0.0103036, + 0.42997715 0.90278327 -0.010098804, + 0.3991029 0.91684878 -0.010256098, + 0.38885108 0.92074925 -0.031869609, + 0.35839096 0.9330129 -0.032294095, + 0.34842491 0.93572474 -0.054947585, + 0.31894988 0.94614166 -0.055559281, + 0.30936506 0.94763625 -0.079238623, + 0.28091896 0.9563939 -0.079970896, + 0.27181691 0.95663965 -0.10467196, + 0.24412088 0.96399152 -0.10547695, + 0.23560494 0.96295977 -0.13114397, + 0.20851204 0.96907425 -0.13197704, + 0.20060103 0.9667151 -0.15881202, + 0.17459105 0.97161722 -0.15961805, + 0.16739996 0.96788174 -0.18756896, + 0.14244401 0.97172409 -0.18831404, + 0.13547593 0.96604854 -0.21999189, + 0.11357199 0.9687289 -0.22060297, + 0.11220397 0.96710175 -0.22830795, + 0.08927802 0.96936125 -0.22884107, + 0.088342302 0.96777302 -0.23582, + 0.066675775 0.96940964 -0.23621891, + 0.065680608 0.96672612 -0.24723803, + 0.041550875 0.9679814 -0.24755885, + 0.04095969 0.96497977 -0.25910693, + 0.014457007 0.96568948 -0.25929713, + 0.014261296 0.96235877 -0.27140793, + -0.014189896 0.96235979 -0.27140793, + -0.014386294 0.96570665 -0.2592369, + -0.041071113 0.96499133 -0.25904608, + -0.041661989 0.96798974 -0.24750794, + -0.065893412 0.96672523 -0.24718507, + -0.066864595 0.96934289 -0.23643897, + -0.088280603 0.96772403 -0.236044, + -0.089236327 0.96934736 -0.22891608, + -0.11217197 0.96708775 -0.22838295, + -0.11351106 0.96868646 -0.2208211, + -0.13532896 0.96601874 -0.22021294, + -0.14224993 0.97166651 -0.18875691, + -0.16711895 0.96784377 -0.18801495, + -0.17431694 0.97158962 -0.16008493, + -0.20024303 0.96671212 -0.15928102, + -0.20813197 0.96907586 -0.13256298, + -0.23505397 0.96301389 -0.13173398, + -0.24359009 0.96406037 -0.10607304, + -0.27130309 0.95672035 -0.10526603, + -0.28041598 0.95649087 -0.080572695, + -0.30883288 0.94775963 -0.079837173, + -0.31846896 0.94627488 -0.056048092, + -0.34789896 0.93589187 -0.055433091, + -0.35794109 0.93317425 -0.032621808, + -0.38835016 0.92094934 -0.03219441, + -0.39867195 0.91703385 -0.010462899, + -0.42957315 0.90297329 -0.010302504, + -0.43997085 0.8979547 0.010152997, + -0.47134206 0.88189411 0.0099714007, + -0.48157012 0.87593126 0.028893508, + -0.5136621 0.85752618 0.028286407, + -0.52353811 0.85078317 0.04556141, + -0.55626613 0.82981515 0.044438511, + -0.56569391 0.8224209 0.060117692, + -0.59842271 0.79904866 0.058409173, + -0.60724008 0.79121011 0.072430208, + -0.63987565 0.76527852 0.070056356, + -0.647771 0.75739598 0.082122803, + -0.68044299 0.728531 0.078993, + -0.68746495 0.72069794 0.08936739, + -0.72015595 0.68853897 0.085379593, + -0.72609407 0.68115306 0.093903214, + -0.7580542 0.64608115 0.089068219, + -0.76305014 0.63915807 0.096080914, + -0.79414368 0.60097778 0.090341367, + -0.79794091 0.59510696 0.095593184, + -0.82830018 0.55319309 0.088860624, + -0.83096188 0.54858291 0.092515893, + -0.86030471 0.50268179 0.084774971, + -0.86211884 0.49913287 0.08727818, + -0.88986975 0.4493959 0.078581177, + -0.89496714 0.43779406 0.085850008, + -0.91627342 0.39306718 0.077079237, + -0.92305076 0.37473592 0.086892776, + -0.94242734 0.32576811 0.075538233, + -0.9467659 0.31127098 0.08212629, + -0.96397865 0.2571789 0.067854576, + -0.96637064 0.24693091 0.07178428, + -0.98064274 0.18802196 0.05465899, + -0.98172551 0.18165891 0.056701373, + -0.99250937 0.11662004 0.036400713, + -0.99281287 0.11376198 0.037159394, + -0.99909699 0.040387299 0.0131922, + -0.99911463 0.039914086 0.013294496, + -0.99896777 -0.043097489 -0.014354796, + -0.99895501 -0.043409102 -0.0143006, + -0.98869401 -0.142418 -0.046918198, + -0.98810297 -0.146651 -0.046324398, + -0.96068603 -0.264743 -0.083627596, + -0.95643479 -0.28026193 -0.081766479, + -0.89902091 -0.42037994 -0.12264598, + -0.86432987 -0.48987693 -0.11381798, + -0.80290967 -0.58063483 -0.13490495, + -0.82507086 -0.54728794 -0.14047799, + -0.78665286 -0.59800994 -0.15349698, + -0.82782257 -0.53631479 -0.16454892, + -0.79405397 -0.58111101 -0.178293, + -0.87027031 -0.44986314 -0.20063107, + -0.84324288 -0.49092293 -0.21894297, + -0.90669 -0.347554 -0.238997, + -0.89089227 -0.37426507 -0.25736505, + -0.85878599 -0.440568 -0.26150799, + -0.9162814 -0.28488916 -0.28154314, + -0.88812661 -0.32689986 -0.32305986, + -0.9151113 -0.22605607 -0.33387113, + -0.89012587 -0.25549796 -0.37735495, + -0.90938312 -0.15476002 -0.38609806, + -0.88599771 -0.17251794 -0.43040186, + -0.896101 -0.085470997 -0.435543, + -0.89296126 -0.051419809 -0.44718713, + -0.8941381 0.0035968705 -0.44777706, + -0.8938874 0.0035968616 -0.44827721, + -0.89408171 0.0036680587 -0.44788885, + -0.88945758 -0.10163695 -0.44557279, + -0.87409073 -0.07007508 -0.48068181, + -0.86003083 -0.19228296 -0.47262487, + -0.88589174 -0.17481595 -0.42969191, + -0.8611086 -0.29084885 -0.4170118, + -0.88917774 -0.26175395 -0.37529692, + -0.83693111 -0.41936305 -0.35168302, + -0.67813426 -0.69682223 -0.2336081, + -0.82392985 -0.48626187 -0.29101393, + -0.7891261 -0.52705407 -0.31542704, + -0.86239231 -0.36807811 -0.34756011, + -0.88520843 -0.33823416 -0.31938013, + -0.83325899 -0.465294 -0.298632, + -0.86445141 -0.4230752 -0.27153513, + -0.80073714 -0.54504704 -0.24848303, + -0.82684684 -0.51175487 -0.23330495, + -0.77175981 -0.59850186 -0.21490096, + -0.80283201 -0.56112897 -0.201482, + -0.73673201 -0.65148503 -0.181089, + -0.77388 -0.61019802 -0.16961201, + -0.71353716 -0.68383116 -0.15244603, + -0.75659132 -0.63822126 -0.14227904, + -0.65904981 -0.74295384 -0.11693097, + -0.61864728 -0.77611536 -0.12215006, + -0.67259818 -0.72718316 -0.13717303, + -0.62700301 -0.76551598 -0.14440399, + -0.70941019 -0.68415821 -0.16930704, + -0.66971183 -0.7208758 -0.17839296, + -0.75590938 -0.62118232 -0.2067211, + -0.72308308 -0.65542108 -0.21811503, + -0.79034787 -0.56281793 -0.24204597, + -0.765486 -0.59110701 -0.25421199, + -0.66986632 -0.70978934 -0.21789511, + -0.70433104 -0.67861503 -0.20832503, + -0.59715331 -0.78373033 -0.17080608, + -0.59509927 -0.78549439 -0.16986908, + -0.56350815 -0.80744529 -0.17461605, + -0.64825904 -0.73292506 -0.20635203, + -0.61334831 -0.76025534 -0.21404611, + -0.70849317 -0.65902621 -0.25243205, + -0.67842484 -0.68606281 -0.26278794, + -0.7852971 -0.53632504 -0.30929604, + -0.75937736 -0.56363928 -0.32504916, + -0.84053791 -0.40230995 -0.36282596, + -0.82337517 -0.42142808 -0.38006809, + -0.72827494 -0.59889293 -0.33308098, + -0.75524682 -0.57281089 -0.31857491, + -0.63476783 -0.72661781 -0.26286194, + -0.66496879 -0.70232677 -0.25407392, + -0.55467391 -0.8059808 -0.20671695, + -0.58919299 -0.78266001 -0.200736, + -0.49086577 -0.85612756 -0.16154392, + -0.52394694 -0.83698088 -0.15793198, + -0.47666523 -0.86778939 -0.14047006, + -0.51151788 -0.84823179 -0.13730396, + -0.43384591 -0.89415276 -0.11076297, + -0.47599313 -0.87277818 -0.10811502, + -0.37903893 -0.92212188 -0.07759279, + -0.43843493 -0.89559788 -0.075360894, + -0.50675005 -0.85677314 -0.095625617, + -0.63450676 -0.76814771 -0.085733868, + -0.63470381 -0.76797783 -0.085796878, + -0.7605561 -0.64525807 -0.072087005, + -0.79261649 -0.60389137 -0.08410915, + -0.77691531 -0.62665021 -0.060928423, + -0.89104015 -0.45179406 -0.043927405, + -0.89813375 -0.43706992 -0.048224188, + -0.95588267 -0.29197687 -0.03221529, + -0.95667577 -0.28927895 -0.033001292, + -0.98688036 -0.16041306 -0.018300107, + -0.98657638 -0.16233906 -0.017698305, + -0.99876553 -0.049379978 -0.0053834072, + -0.99869788 -0.050780494 -0.0048980196, + -0.99889576 0.046765387 0.0045107389, + -0.99880826 0.04865991 0.003769621, + -0.99066335 0.13592404 0.010529904, + -0.98976815 0.14248201 0.0076125409, + -0.97549886 0.21969096 0.011737698, + -0.97284365 0.23139091 0.0057892883, + -0.95382935 0.30025512 0.0075122328, + -0.94847387 0.31684798 -0.0021747397, + -0.92571825 0.37820509 -0.0025958708, + -0.91666412 0.39930406 -0.016828602, + -0.891505 0.452609 -0.0190752, + -0.87813109 0.47689706 -0.038145605, + -0.85131413 0.52298605 -0.041832104, + -0.84114373 0.53794885 -0.055572182, + -0.8060587 0.58870274 -0.060815178, + -0.80210489 0.59353691 -0.065890394, + -0.76647162 0.63835669 -0.070865966, + -0.7612173 0.64385027 -0.077493332, + -0.72583991 0.68293494 -0.082197495, + -0.71932626 0.68876827 -0.09037663, + -0.68451393 0.72280395 -0.094842583, + -0.67670995 0.72876596 -0.10470799, + -0.64230305 0.75866014 -0.10900301, + -0.63359779 0.76427168 -0.12017696, + -0.59974694 0.79047686 -0.12429798, + -0.59018195 0.7955839 -0.13686298, + -0.55762702 0.818075 -0.14073201, + -0.54748601 0.82243502 -0.154466, + -0.5161041 0.84180719 -0.15810505, + -0.50534773 0.84535253 -0.1732129, + -0.47493994 0.86210686 -0.17664598, + -0.46368882 0.86469167 -0.19313492, + -0.43427393 0.87911886 -0.19635697, + -0.42259005 0.88061315 -0.21433203, + -0.39452505 0.89282113 -0.21730302, + -0.38252091 0.89309174 -0.23677994, + -0.3559089 0.90331274 -0.23948894, + -0.34422812 0.90228432 -0.25959608, + -0.32475403 0.90892714 -0.26150802, + -0.325409 0.90904897 -0.26026699, + -0.37154612 0.88637328 -0.2762171, + -0.36889604 0.88594413 -0.28110301, + -0.38928086 0.87798369 -0.27857691, + -0.38663885 0.87775069 -0.28295591, + -0.40670505 0.86949712 -0.28029603, + -0.403139 0.86941999 -0.28563601, + -0.42274585 0.86097372 -0.2828609, + -0.43339291 0.86037081 -0.26820293, + -0.46202987 0.84667981 -0.26393494, + -0.47441176 0.84476459 -0.24760088, + -0.50430989 0.8286618 -0.24288094, + -0.51589906 0.82571614 -0.22812504, + -0.54739583 0.80665469 -0.22285892, + -0.55796427 0.80290633 -0.2098031, + -0.59132022 0.78023928 -0.20388007, + -0.60084713 0.77586818 -0.19238305, + -0.63544798 0.749448 -0.18583199, + -0.64397174 0.74459976 -0.17570294, + -0.67964607 0.71393305 -0.16846602, + -0.68712872 0.70878166 -0.15963292, + -0.72408336 0.6728583 -0.15154207, + -0.73072296 0.66738594 -0.14366598, + -0.76879179 0.6251778 -0.13457997, + -0.77383512 0.62021905 -0.12848201, + -0.81219983 0.57125086 -0.11833797, + -0.81600899 0.56677502 -0.113558, + -0.86389458 0.49688977 -0.082380861, + -0.8261053 0.55592716 -0.092169032, + -0.82275909 0.56014603 -0.096457213, + -0.78556269 0.60980678 -0.10500896, + -0.78069437 0.61497128 -0.11102605, + -0.74342602 0.65817797 -0.118826, + -0.737414 0.663562 -0.126119, + -0.70087433 0.70074034 -0.13318506, + -0.69351983 0.70629281 -0.14205897, + -0.65809995 0.73814791 -0.14846599, + -0.64978236 0.74339741 -0.15856609, + -0.61516798 0.77105099 -0.164465, + -0.60599214 0.77580619 -0.17577904, + -0.57245904 0.79966414 -0.18118502, + -0.56234604 0.80383313 -0.19395703, + -0.53032911 0.82414019 -0.19885704, + -0.51958513 0.82748419 -0.21284105, + -0.48902711 0.84477121 -0.21728805, + -0.47741687 0.8472358 -0.23294795, + -0.44814295 0.86197388 -0.23699997, + -0.4357031 0.86336416 -0.25449005, + -0.40762678 0.8758896 -0.25818187, + -0.39641091 0.87600178 -0.27473494, + -0.37716019 0.88370639 -0.27715212, + -0.37952414 0.88388032 -0.2733441, + -0.359593 0.89145398 -0.275686, + -0.36166897 0.89175487 -0.27197197, + -0.32892597 0.9032799 -0.27548698, + -0.33245209 0.90404326 -0.26866606, + -0.35242313 0.89706528 -0.2665931, + -0.35100204 0.89688414 -0.26906604, + -0.37034091 0.88972074 -0.26691693, + -0.38182795 0.89015788 -0.24864897, + -0.40905893 0.87886488 -0.24549396, + -0.42136484 0.87803471 -0.22695093, + -0.450187 0.86452198 -0.22345801, + -0.46184295 0.86253786 -0.20671096, + -0.49173805 0.84676611 -0.20293103, + -0.50283396 0.84376889 -0.18764897, + -0.53377408 0.82546014 -0.18357801, + -0.54430091 0.82156789 -0.16959599, + -0.57662594 0.80013788 -0.16517198, + -0.58629268 0.79557467 -0.15271492, + -0.62002212 0.77051717 -0.14790504, + -0.62909406 0.76525313 -0.13648601, + -0.66359502 0.73646998 -0.13135301, + -0.67164618 0.7308622 -0.12137503, + -0.70683503 0.69782108 -0.11588801, + -0.71379763 0.69208163 -0.10731195, + -0.74973875 0.65391976 -0.10139396, + -0.75541073 0.64841974 -0.094374366, + -0.79192102 0.60425699 -0.087946802, + -0.79619563 0.59938073 -0.082555361, + -0.8323189 0.54911292 -0.07563179, + -0.83540601 0.54495001 -0.071598299, + -0.87065887 0.48769593 -0.064075992, + -0.87925458 0.47351077 -0.051950272, + -0.90636712 0.41997105 -0.046076305, + -0.91729176 0.39713892 -0.029264493, + -0.94211411 0.33438602 -0.024640303, + -0.94873935 0.31580111 -0.012780005, + -0.96960038 0.2444941 -0.0098942835, + -0.97289926 0.23121606 -0.0024833807, + -0.98860151 0.15054692 -0.0016169592, + -0.98974562 0.14282496 0.0021795593, + -0.99868321 0.051296111 0.00078279315, + -0.99879736 0.04899662 0.0017863805, + -0.99857551 -0.053320576 -0.0019440291, + -0.99867165 -0.051456682 -0.002673439, + -0.98551333 -0.16937006 -0.0087996526, + -0.98608953 -0.16591193 -0.010034296, + -0.95402735 -0.29917312 -0.018093806, + -0.95414126 -0.29880205 -0.018218704, + -0.89428073 -0.44667685 -0.027235091, + -0.88953245 -0.45624074 -0.024006685, + -0.79139531 -0.61046022 -0.032121509, + -0.77135336 -0.63601029 -0.022471011, + -0.78599417 -0.6165331 -0.045827512, + -0.62559879 -0.77799869 -0.057829376, + -0.56423968 -0.82482457 -0.03602628, + -0.4117271 -0.91043925 -0.039765712, + -0.40454286 -0.91375571 -0.037356485, + -0.26550588 -0.96330452 -0.039382182, + -0.18359894 -0.98292667 -0.012109095, + -0.14107302 -0.98992413 -0.012195302, + -0.26894805 -0.96141022 -0.057943314, + -0.23842897 -0.96940088 -0.058424894, + -0.33909491 -0.93568379 -0.097521976, + -0.31268603 -0.9447391 -0.098465912, + -0.37371403 -0.91921413 -0.12402902, + -0.34750211 -0.92925835 -0.12538505, + -0.46900913 -0.86463815 -0.18008704, + -0.43792215 -0.88012528 -0.18331306, + -0.57157683 -0.78219169 -0.24794391, + -0.54227394 -0.80092591 -0.25388297, + -0.64567322 -0.69901925 -0.30737311, + -0.61870909 -0.71916407 -0.31623104, + -0.69521904 -0.62307405 -0.35839802, + -0.67110479 -0.64263374 -0.36964887, + -0.753914 -0.50666302 -0.41821799, + -0.72183675 -0.53372484 -0.44055584, + -0.79222435 -0.36973119 -0.48546824, + -0.75601888 -0.39658394 -0.52072692, + -0.79976028 -0.23630808 -0.55185318, + -0.76655054 -0.25278786 -0.59033763, + -0.78734303 -0.109301 -0.606749, + -0.78592485 -0.096198589 -0.61079293, + -0.78958273 0.0031844089 -0.61363578, + -0.78930283 0.0031844394 -0.61399591, + -0.7897408 0.0032907594 -0.61343187, + -0.75851202 -0.0060454002 -0.651631, + -0.75104117 -0.014724704 -0.66009116, + -0.76012599 -0.0212541 -0.64942801, + -0.75528115 -0.11468403 -0.64528918, + -0.72043216 -0.11810403 -0.68339521, + -0.72550803 0.0025454503 -0.68820906, + -0.72530401 0.0025454699 -0.68842399, + -0.69133174 -0.0037440686 -0.72252774, + -0.69099474 -0.0038160086 -0.72284979, + -0.68514192 -0.12993498 -0.71672696, + -0.68362921 -0.11406804 -0.72086024, + -0.65446419 -0.31009007 -0.6895802, + -0.69352102 -0.29546699 -0.65706003, + -0.61948127 -0.5229122 -0.58549625, + -0.41893992 -0.8358798 -0.35467491, + -0.55368102 -0.68427002 -0.474565, + -0.52994704 -0.69684404 -0.48328507, + -0.64356703 -0.48736 -0.59017098, + -0.66332996 -0.47649595 -0.57701397, + -0.55537611 -0.67870015 -0.48054513, + -0.57863086 -0.6656338 -0.47129387, + -0.4567968 -0.80982363 -0.36813381, + -0.47368681 -0.78976268 -0.38973784, + -0.33355096 -0.90364885 -0.26863098, + -0.3695429 -0.89069074 -0.26477894, + -0.24935395 -0.95308477 -0.17161596, + -0.09027753 -0.99527836 -0.035651412, + -0.077749491 -0.9963339 -0.035689197, + -0.21446104 -0.96654022 -0.14073603, + -0.18949395 -0.97163576 -0.14147797, + -0.31010789 -0.91859967 -0.24496491, + -0.27858591 -0.92798162 -0.24746691, + -0.23048402 -0.94656509 -0.22559203, + -0.25764403 -0.93991512 -0.22400703, + -0.13962309 -0.98386461 -0.11187506, + -0.15905702 -0.98094809 -0.11154301, + -0.025579987 -0.99967051 0.0021080491, + -0.033985604 -0.99942011 0.0021075201, + 0.11264004 -0.98712337 0.11357704, + 0.12222997 -0.98599678 0.11344697, + 0.0999268 -0.98989701 0.100591, + 0.23456603 -0.95306712 0.19142103, + 0.25371391 -0.94834065 0.19047092, + 0.058454879 -0.99588567 0.069243677, + 0.062070198 -0.99566799 0.0692285, + -0.12375903 -0.99080426 -0.054688014, + -0.11128996 -0.99227762 -0.054769281, + -0.27392796 -0.9465279 -0.17043598, + -0.2687479 -0.94888562 -0.16550094, + -0.33202499 -0.921947 -0.199432, + -0.14640594 -0.98644066 -0.074163072, + -0.16142705 -0.98410726 -0.073987618, + 0.028173093 -0.99856079 0.045636687, + 0.02213499 -0.99871254 0.045643579, + 0.187778 -0.97174001 0.143041, + 0.19857596 -0.96963674 0.14273097, + -0.018780395 -0.99958074 0.022038095, + -0.0100127 -0.99970698 0.0220409, + -0.20395996 -0.97446477 -0.093907475, + -0.18636905 -0.97794926 -0.094243325, + -0.34888709 -0.91597927 -0.19814104, + -0.33872098 -0.92162585 -0.18940397, + -0.50742608 -0.80957514 -0.29513904, + -0.46197295 -0.83324987 -0.30376896, + -0.54987198 -0.75099701 -0.365574, + -0.50613308 -0.77545911 -0.37748206, + -0.61433214 -0.63940716 -0.46233612, + -0.580374 -0.65991098 -0.477162, + -0.68595099 -0.45618001 -0.56689602, + -0.71420056 -0.43880972 -0.54531068, + -0.62145704 -0.62508804 -0.47228807, + -0.66538292 -0.59560996 -0.45001593, + -0.56698895 -0.73062897 -0.38040093, + -0.61287898 -0.700872 -0.36490801, + -0.53362387 -0.78494483 -0.3148129, + -0.57098907 -0.76196015 -0.30559504, + -0.45213094 -0.85992789 -0.23685797, + -0.47887912 -0.84636217 -0.23312207, + -0.32683009 -0.93299621 -0.15066603, + -0.35278809 -0.92373621 -0.14917102, + -0.21994597 -0.97206789 -0.081901096, + -0.23804994 -0.96782374 -0.081543475, + -0.16710204 -0.98476923 -0.048027713, + -0.18349996 -0.98185277 -0.047885388, + -0.070597619 -0.99750334 0.0017433006, + -0.08774931 -0.99614114 0.0017409202, + 0.04983858 -0.99709564 0.057588976, + 0.11765403 -0.98834324 0.096619621, + 0.19833307 -0.97243834 0.12258805, + -0.0128159 -0.99940997 0.031866301, + -0.0015593797 -0.99949086 0.031868897, + -0.11345004 -0.99333537 -0.020345008, + -0.10179102 -0.99459726 -0.020370906, + -0.17758898 -0.98237491 -0.058324091, + -0.16282593 -0.9849205 -0.058475174, + -0.29938185 -0.94500154 -0.13169093, + -0.27670288 -0.9517585 -0.13263194, + -0.43436906 -0.87270314 -0.22296403, + -0.41408685 -0.88190973 -0.22531593, + -0.2295859 -0.96663654 -0.11359595, + -0.24975997 -0.96168989 -0.11301499, + -0.11139695 -0.99317253 -0.034627084, + -0.12229501 -0.99189115 -0.034582403, + -0.04785312 -0.99884236 0.0049030217, + -0.055616114 -0.99844027 0.0049010515, + 0.057818092 -0.99645686 0.061080392, + 0.051050209 -0.9968251 0.061103009, + 0.18584491 -0.97486353 0.12289294, + 0.24773909 -0.95478934 0.16432506, + 0.16788292 -0.97757155 0.12715794, + 0.096254066 -0.98704165 0.12838995, + 0.003491739 -0.99589676 0.09042868, + -0.11040003 -0.98981524 0.089876525, + -0.20269908 -0.97769433 0.055018518, + -0.35503513 -0.93337637 0.052524518, + -0.4286769 -0.90312076 0.024678594, + -0.59137374 -0.80609667 0.022027293, + -0.63184607 -0.77507812 0.0049598305, + -0.77105969 -0.63674974 0.0040746485, + -0.7858302 -0.61843109 -0.0037309709, + -0.8862431 -0.46321207 -0.0027945302, + -0.88860691 -0.45864695 -0.0045517394, + -0.95159876 -0.30732793 -0.0030500093, + -0.95053023 -0.31062707 -0.0017869305, + -0.98504275 -0.17230695 -0.00099122175, + -0.9841395 -0.17739291 0.0010551495, + -0.99855042 -0.053822566 0.0003201428, + -0.99841976 -0.056180686 0.0013496097, + -0.99867326 0.051481411 -0.0012367204, + -0.99852377 0.05425559 -0.0025748692, + -0.98858577 0.15048997 -0.0071419682, + -0.98713374 0.15944795 -0.011975397, + -0.96966934 0.24373409 -0.018305607, + -0.96549678 0.25895095 -0.027573293, + -0.94240314 0.33259904 -0.035415504, + -0.93423438 0.35317713 -0.049719818, + -0.90702379 0.4169679 -0.058700085, + -0.89364189 0.44183394 -0.078656293, + -0.86434788 0.49510995 -0.088140495, + -0.85398179 0.5101639 -0.10221498, + -0.84584832 0.5192492 -0.12215105, + -0.80490482 0.57763588 -0.13588597, + -0.80069488 0.58223194 -0.14104499, + -0.76132363 0.63014573 -0.15265192, + -0.75569165 0.63525772 -0.15930392, + -0.716811 0.67632598 -0.16960301, + -0.71023494 0.68129194 -0.17722198, + -0.67283815 0.71596318 -0.18624105, + -0.66493976 0.72089773 -0.19534993, + -0.62921107 0.75017911 -0.20328502, + -0.62023687 0.75474185 -0.21370795, + -0.58577996 0.77981186 -0.22080597, + -0.57568389 0.78385681 -0.23271593, + -0.54262501 0.805237 -0.23906399, + -0.53158808 0.80852515 -0.25239104, + -0.50038826 0.82646942 -0.25799212, + -0.487968 0.82893002 -0.27342701, + -0.45880607 0.8438161 -0.27833703, + -0.44883105 0.8448351 -0.29121202, + -0.42926505 0.8538751 -0.29432803, + -0.43408579 0.85373557 -0.28758484, + -0.41384485 0.86271572 -0.2906099, + -0.41716984 0.86282772 -0.28547791, + -0.39654595 0.87154889 -0.28836396, + -0.40011284 0.87191468 -0.28226691, + -0.37866995 0.88053989 -0.28505898, + -0.38140094 0.88102788 -0.27986297, + -0.36925599 0.88571501 -0.28135201, + -0.36846283 0.88548958 -0.28309584, + -0.35288787 0.89122671 -0.2849299, + -0.35161892 0.89069575 -0.28814095, + -0.3336018 0.89694744 -0.29016382, + -0.3321909 0.89612776 -0.29428595, + -0.31147993 0.90281677 -0.29648295, + -0.31007788 0.90172768 -0.30122888, + -0.28638396 0.90874988 -0.30357498, + -0.28480101 0.90714002 -0.30981499, + -0.25825593 0.91422778 -0.31223595, + -0.25829491 0.9142797 -0.31205189, + -0.22932594 0.92117274 -0.3144049, + -0.23367397 0.92824388 -0.28941298, + -0.20226207 0.93494236 -0.29150108, + -0.20585296 0.94212174 -0.26463395, + -0.17170104 0.94844323 -0.26641005, + -0.17430298 0.95499486 -0.24000697, + -0.137539 0.96062398 -0.241422, + -0.139329 0.96654302 -0.21536499, + -0.10080504 0.97109145 -0.21637911, + -0.10192098 0.9763729 -0.19054697, + -0.061868787 0.97960377 -0.19117695, + -0.062445916 0.98421621 -0.16558704, + -0.021174394 0.98591977 -0.16587296, + -0.021337206 0.98986226 -0.14041904, + 0.02094109 0.98987055 -0.14041995, + 0.020775102 0.98593014 -0.16586201, + 0.062091209 0.98424011 -0.16557801, + 0.0615106 0.97962499 -0.191184, + 0.10160105 0.97640449 -0.19055609, + 0.100481 0.97112697 -0.21637, + 0.13905405 0.96658438 -0.21535708, + 0.13726698 0.96066988 -0.24139397, + 0.17395709 0.95506346 -0.23998512, + 0.171351 0.94852197 -0.26635501, + 0.20557804 0.94219726 -0.26457906, + 0.20200898 0.93508089 -0.29123196, + 0.23359805 0.92834926 -0.28913605, + 0.25440603 0.91588014 -0.31055003, + 0.22953486 0.92175448 -0.31254181, + 0.83403927 0.54653817 -0.075329632, + 0.79622167 0.59933877 -0.082607068, + 0.79197955 0.60417867 -0.087957047, + 0.7555092 0.64830416 -0.094380923, + 0.74996001 0.65368801 -0.101252, + 0.71409518 0.69179916 -0.10715503, + 0.70722115 0.69747216 -0.11563303, + 0.67203695 0.73054594 -0.12111598, + 0.66421622 0.73600423 -0.13082305, + 0.62966269 0.76487964 -0.13595594, + 0.62085593 0.77000791 -0.14705698, + 0.58711302 0.79513401 -0.15185601, + 0.57758927 0.79965335 -0.16415007, + 0.54529887 0.82111984 -0.16855696, + 0.53500485 0.82495481 -0.18226196, + 0.50388384 0.84343171 -0.18634394, + 0.49293977 0.8464216 -0.20144691, + 0.46301711 0.86226517 -0.20521705, + 0.45129186 0.86429667 -0.22209692, + 0.42234215 0.87791431 -0.22559607, + 0.40986684 0.87878668 -0.24442391, + 0.38258207 0.89013213 -0.24758004, + 0.37089798 0.88970888 -0.26618198, + 0.35151309 0.89690322 -0.26833406, + 0.352597 0.89704001 -0.26644799, + 0.3325209 0.90405774 -0.26853195, + 0.33284512 0.90412527 -0.26790208, + 0.32227498 0.90763891 -0.26894298, + 0.32151702 0.90739912 -0.27065402, + 0.30746603 0.91186011 -0.27198502, + 0.30583897 0.91112089 -0.27626297, + 0.28895986 0.9161526 -0.27778888, + 0.28737405 0.91516125 -0.28265905, + 0.26766685 0.92060047 -0.28433982, + 0.26597804 0.91918212 -0.29044804, + 0.24310412 0.92492342 -0.29226214, + 0.24152403 0.92316812 -0.29904303, + 0.21637304 0.92879623 -0.30086607, + 0.21445304 0.92597425 -0.31077605, + 0.19314992 0.93017864 -0.31218687, + 0.19649008 0.93681234 -0.2894381, + 0.16417399 0.94247389 -0.29118696, + 0.16705094 0.94968563 -0.26493591, + 0.13230596 0.95475274 -0.26634994, + 0.13428997 0.96133977 -0.24039994, + 0.097227179 0.96553075 -0.24144794, + 0.098489918 0.97148013 -0.21569903, + 0.059824694 0.97447789 -0.21636496, + 0.060485929 0.97975647 -0.19083709, + 0.020347591 0.98135054 -0.19114691, + 0.020540191 0.9859485 -0.16578193, + -0.020903101 0.98594111 -0.16578102, + -0.020713601 0.98134112 -0.19115603, + -0.060880009 0.97973114 -0.19084203, + -0.060221121 0.97444838 -0.21638808, + -0.098846339 0.97143936 -0.21572007, + -0.097591534 0.96549034 -0.24146309, + -0.13452302 0.96130311 -0.24041604, + -0.13253494 0.95470655 -0.26640189, + -0.16736995 0.94961667 -0.26498193, + -0.164482 0.94235897 -0.29138499, + -0.19655508 0.93673438 -0.28964609, + -0.192949 0.92955798 -0.314154, + -0.2222961 0.9236564 -0.31215915, + -0.22241703 0.92384613 -0.31151104, + -0.24945994 0.91762376 -0.30941293, + -0.25108299 0.919595 -0.302163, + -0.27565807 0.91322023 -0.30006906, + -0.27718991 0.91463971 -0.29427889, + -0.29888207 0.90842825 -0.29228005, + -0.30046812 0.9095363 -0.28716308, + -0.31937411 0.90365928 -0.28530708, + -0.32092303 0.90445912 -0.28100204, + -0.33697113 0.89912027 -0.27934408, + -0.33818212 0.89956129 -0.2764461, + -0.35168797 0.89481688 -0.27498797, + -0.3498829 0.89437276 -0.27870995, + -0.34066504 0.90119815 -0.26793504, + -0.32204697 0.90746588 -0.26979896, + -0.32175192 0.90737277 -0.27046293, + -0.30762511 0.9118613 -0.27180108, + -0.30611205 0.91117525 -0.27578107, + -0.28914508 0.91623831 -0.27731308, + -0.2873989 0.91514671 -0.2826809, + -0.26760092 0.92061067 -0.2843689, + -0.26590693 0.91918677 -0.29049793, + -0.243193 0.92488801 -0.29229999, + -0.24162106 0.92313826 -0.29905707, + -0.21633695 0.92879677 -0.30088994, + -0.21476108 0.92648333 -0.30904111, + -0.18711101 0.93186402 -0.31083599, + -0.18689504 0.93144822 -0.31220907, + -0.15688102 0.93641412 -0.31387404, + -0.15976807 0.94364345 -0.28984714, + -0.12687999 0.94819689 -0.29124597, + -0.12908693 0.95549542 -0.26526386, + -0.093994036 0.95929134 -0.26631808, + -0.095388688 0.96589386 -0.24072798, + -0.058305986 0.96866775 -0.24141894, + -0.059039984 0.97460878 -0.21599096, + -0.020100294 0.97611475 -0.21632396, + -0.020316491 0.98137552 -0.1910219, + 0.019980205 0.98138225 -0.19102305, + 0.019760095 0.97612476 -0.21630995, + 0.058677722 0.97463334 -0.21597907, + 0.057936173 0.96869451 -0.24140088, + 0.095023766 0.96593362 -0.24071291, + 0.093623102 0.95933902 -0.26627699, + 0.12888704 0.95553434 -0.26522109, + 0.12668899 0.94825989 -0.29112396, + 0.15968493 0.94369555 -0.28972286, + 0.15703906 0.93708235 -0.31179413, + 0.18010294 0.93333966 -0.31054789, + 0.18188609 0.93654341 -0.29967314, + 0.20795397 0.93160886 -0.29809397, + 0.20949696 0.93368477 -0.29041994, + 0.23292004 0.9286111 -0.28884202, + 0.23465291 0.93036264 -0.28171492, + 0.25556201 0.92530298 -0.28018299, + 0.25725892 0.92658263 -0.27433991, + 0.27519205 0.92183322 -0.27293405, + 0.27701694 0.92284578 -0.26761395, + 0.29205185 0.91855961 -0.26637188, + 0.29326898 0.9190439 -0.26334697, + 0.30476585 0.91558057 -0.26235488, + 0.30492496 0.91562486 -0.26201499, + 0.32551298 0.90904987 -0.26013398, + 0.32516196 0.9089849 -0.26079896, + 0.3447071 0.90230626 -0.25888306, + 0.35648412 0.90332329 -0.23859209, + 0.38325405 0.89301813 -0.23587103, + 0.39541885 0.89271867 -0.21609592, + 0.42354301 0.88044798 -0.213126, + 0.43526584 0.87891871 -0.19505292, + 0.4648298 0.86437058 -0.19182491, + 0.47598106 0.86177814 -0.17544402, + 0.50637287 0.84498185 -0.17202395, + 0.51703602 0.841438 -0.157022, + 0.54848182 0.82197273 -0.15338995, + 0.55844021 0.81766629 -0.13988005, + 0.59098697 0.7951299 -0.13602498, + 0.60036969 0.79010063 -0.12368194, + 0.63418263 0.76388055 -0.11957792, + 0.64271408 0.75836712 -0.10861901, + 0.67712981 0.72842979 -0.10433198, + 0.68479395 0.72256595 -0.094635285, + 0.71963495 0.68847293 -0.090170093, + 0.7259838 0.68278283 -0.08218918, + 0.76132381 0.6437248 -0.077487588, + 0.76650065 0.63831168 -0.070956759, + 0.80213118 0.59349209 -0.065974616, + 0.80609 0.58865201 -0.0608918, + 0.84113359 0.53795677 -0.055647675, + 0.85128188 0.52302992 -0.041937698, + 0.87808824 0.47696811 -0.038244307, + 0.89146268 0.45268786 -0.019183392, + 0.91662669 0.39938584 -0.016924594, + 0.92565733 0.37835315 -0.0027384509, + 0.94841975 0.31700891 -0.0022944496, + 0.95376998 0.30044699 0.0073764799, + 0.97280002 0.23157699 0.0056856, + 0.97545326 0.21990006 0.011622502, + 0.98974752 0.14262892 0.0075384662, + 0.99064112 0.13609202 0.0104461, + 0.99880475 0.048733991 0.003740689, + 0.99889237 0.046840616 0.0044813915, + 0.99869347 -0.050870027 -0.0048669023, + 0.99876064 -0.04948318 -0.0053477781, + 0.98651791 -0.16270599 -0.017583998, + 0.98682165 -0.16078694 -0.018183395, + 0.95645136 -0.29004309 -0.03280101, + 0.95566189 -0.29271996 -0.032020498, + 0.8976469 -0.43810195 -0.047923893, + 0.89050287 -0.45288295 -0.043606795, + 0.7927869 -0.60669297 -0.058416594, + 0.76599663 -0.64112872 -0.046937976, + 0.62350196 -0.77973491 -0.057085592, + 0.5574581 -0.82952118 -0.033689909, + 0.38930917 -0.92034841 -0.037378717, + 0.29541194 -0.95535475 -0.0054017785, + 0.15136194 -0.98846263 -0.0055889781, + 0.14935099 -0.9887439 -0.0089291288, + 0.054679994 -0.9981339 0.027179696, + 0.025076903 -0.99931514 0.027211905, + -0.036035009 -0.99737626 0.062785715, + -0.035463091 -0.99741179 0.062547483, + 0.073273972 -0.99535662 0.062418677, + 0.17029706 -0.98503739 0.02646271, + 0.32135209 -0.94661826 0.025430506, + 0.41294384 -0.91072673 -0.007361887, + 0.57808608 -0.81594914 -0.0065957508, + 0.63003296 -0.77610689 -0.026768597, + 0.77025181 -0.63736081 -0.021983095, + 0.79029047 -0.61191636 -0.031612519, + 0.88895786 -0.45737895 -0.023628896, + 0.8936879 -0.44788593 -0.026834397, + 0.95388788 -0.29962596 -0.017951598, + 0.95380098 -0.29990801 -0.0178567, + 0.98602533 -0.16630106 -0.009901694, + 0.98545676 -0.16970396 -0.0086866478, + 0.99866688 -0.051550392 -0.0026387097, + 0.99857038 -0.053417865 -0.0019079288, + 0.99879366 0.049073581 0.0017527594, + 0.99867976 0.051362887 0.00075364084, + 0.98972315 0.14298202 0.0020979603, + 0.98857874 0.15069596 -0.0016965896, + 0.97285098 0.231418 -0.00260538, + 0.96955538 0.2446681 -0.010000904, + 0.94867998 0.315974 -0.0129156, + 0.94207054 0.33450085 -0.024741689, + 0.91724777 0.39723191 -0.029381692, + 0.90631932 0.42006114 -0.046195414, + 0.87920046 0.47359672 -0.05208287, + 0.86315984 0.49943587 -0.074289687, + 0.83466917 0.54475814 -0.081031226, + 0.82280368 0.56007284 -0.096501365, + 0.78559512 0.60975605 -0.10506202, + 0.78099513 0.61463904 -0.11075001, + 0.7436958 0.6579228 -0.11854997, + 0.73777199 0.66323602 -0.12574001, + 0.70132005 0.70037109 -0.13278002, + 0.69419706 0.70576209 -0.14138702, + 0.65878195 0.73767692 -0.14778098, + 0.65066069 0.74282163 -0.15765992, + 0.61603612 0.77055317 -0.16354604, + 0.60711008 0.77520412 -0.17457402, + 0.57347697 0.79920685 -0.17997898, + 0.56364989 0.80329084 -0.19241296, + 0.53162879 0.8236776 -0.19729692, + 0.52086496 0.82706386 -0.21134096, + 0.49024293 0.8444519 -0.21578397, + 0.47853488 0.84697181 -0.23160994, + 0.44925806 0.86176211 -0.23565502, + 0.43672395 0.86319387 -0.25331497, + 0.40845799 0.87584198 -0.257027, + 0.39708108 0.87597823 -0.27384105, + 0.37767309 0.88376224 -0.27627406, + 0.37965316 0.88390529 -0.2730841, + 0.35964409 0.89151126 -0.27543405, + 0.36048704 0.89163512 -0.27392703, + 0.35157102 0.89488214 -0.27492502, + 0.35143188 0.8948487 -0.2752119, + 0.33803087 0.8995527 -0.27665892, + 0.33668399 0.89906001 -0.27988401, + 0.32079288 0.9043417 -0.28152791, + 0.31942913 0.90363729 -0.2853151, + 0.30052599 0.90951502 -0.28716999, + 0.29895088 0.90841371 -0.29225489, + 0.27732089 0.91460961 -0.29424885, + 0.27578396 0.91318387 -0.30006397, + 0.25105095 0.91960078 -0.30217195, + 0.24861497 0.91662991 -0.31301796, + 0.28473809 0.90716928 -0.30978712, + 0.28633201 0.90878701 -0.30351299, + 0.31003115 0.90176439 -0.30116716, + 0.31143388 0.90285271 -0.29642189, + 0.33220598 0.89614385 -0.29421997, + 0.33359903 0.89695209 -0.29015303, + 0.3516849 0.89067578 -0.28812194, + 0.3527208 0.89110947 -0.28550282, + 0.36807796 0.88545889 -0.28369197, + 0.369039 0.88573301 -0.28158, + 0.38900208 0.87794024 -0.27910307, + 0.84592968 0.51913685 -0.12206496, + 0.80509913 0.57739407 -0.13576302, + 0.80106688 0.58180094 -0.14071098, + 0.76161915 0.62986517 -0.15233603, + 0.75640982 0.63460481 -0.15849596, + 0.71762806 0.67567205 -0.16875201, + 0.71106017 0.68065017 -0.17637704, + 0.67374301 0.715339 -0.185366, + 0.66616917 0.72009319 -0.19412504, + 0.63031918 0.74957615 -0.20207304, + 0.62165612 0.7540102 -0.21216105, + 0.58716202 0.77921098 -0.21925101, + 0.57723773 0.78322363 -0.2309919, + 0.54421598 0.80467898 -0.23732001, + 0.53297508 0.80806512 -0.25093502, + 0.50164407 0.82615614 -0.25655302, + 0.48929906 0.82863814 -0.27192903, + 0.45999801 0.84365398 -0.27685699, + 0.44974613 0.8447262 -0.29011405, + 0.430105 0.853827 -0.293239, + 0.43415114 0.85370529 -0.28757608, + 0.41387305 0.86270314 -0.29060704, + 0.41618609 0.86278421 -0.28704107, + 0.40925795 0.86576289 -0.28803197, + 0.41266495 0.86613691 -0.28198296, + 0.37769416 0.8804453 -0.28664109, + 0.38047299 0.88095099 -0.28136399, + 0.38835686 0.87782371 -0.2803649, + 0.38684809 0.87768823 -0.28286406, + 0.40674293 0.86950189 -0.28022596, + 0.4038009 0.86944181 -0.28463295, + 0.4235549 0.86091083 -0.28183994, + 0.4344798 0.86026657 -0.26677489, + 0.46318406 0.84649414 -0.26250404, + 0.47556511 0.84454417 -0.24613605, + 0.50556183 0.82832873 -0.24140991, + 0.51721179 0.82533067 -0.22654192, + 0.54892117 0.80606031 -0.22125207, + 0.55921078 0.80237764 -0.20850289, + 0.59260368 0.77960265 -0.20258491, + 0.60195327 0.7752853 -0.19127208, + 0.6364978 0.74882585 -0.18474396, + 0.64487606 0.74403703 -0.17476802, + 0.6805492 0.7132892 -0.16754505, + 0.68783081 0.70825779 -0.15893295, + 0.72481161 0.67222971 -0.15084893, + 0.73100501 0.66711497 -0.14349, + 0.76902938 0.62492132 -0.13441406, + 0.77413088 0.61989993 -0.12823999, + 0.81242669 0.57097381 -0.11811796, + 0.81607503 0.56668401 -0.113538, + 0.8540386 0.51007277 -0.10219495, + 0.86429727 0.49517617 -0.088265829, + 0.89358097 0.44193599 -0.0787756, + 0.90696323 0.4170821 -0.058825314, + 0.93417513 0.35331804 -0.049832009, + 0.94235379 0.33272791 -0.035518393, + 0.9654631 0.25906804 -0.027655203, + 0.96962076 0.24391794 -0.018427396, + 0.98710865 0.15959693 -0.012057195, + 0.98856109 0.15064801 -0.007230131, + 0.99852014 0.054322306 -0.0026071302, + 0.99866939 0.051554218 -0.0012719205, + 0.99841464 -0.056269083 0.0013882396, + 0.99854499 -0.053924799 0.00036474, + 0.98407364 -0.17775694 0.0012023195, + 0.98498046 -0.17266409 -0.00084773742, + 0.95030034 -0.31133112 -0.0015285605, + 0.95134324 -0.30812106 -0.0027579106, + 0.88800001 -0.45982501 -0.0041157701, + 0.88555914 -0.46452105 -0.0023068802, + 0.7845729 -0.62002891 -0.0030791694, + 0.76981491 -0.63824993 0.0046976698, + 0.62995923 -0.77660728 0.0057160119, + 0.58960676 -0.80737168 0.022689993, + 0.42671591 -0.90402877 0.025406394, + 0.35255197 -0.93426687 0.053408392, + 0.20027803 -0.97814214 0.055916607, + 0.10244895 -0.99040151 0.092785053, + -0.010282597 -0.99558765 0.093270972, + -0.095286444 -0.98718041 0.12804392, + -0.16713704 -0.97774327 0.12682003, + -0.18151602 -0.97427809 0.13354501, + -0.11821798 -0.98782688 0.10110699, + -0.21869007 -0.96344835 0.15473206, + -0.23864295 -0.95882076 0.15398797, + -0.048388794 -0.99695086 0.061216891, + -0.054876707 -0.99661613 0.061196309, + 0.10683703 -0.99398333 -0.024146508, + 0.092463143 -0.99542248 -0.024181511, + 0.26335102 -0.95708513 -0.12097301, + 0.24234003 -0.96253312 -0.12166101, + 0.4200719 -0.87801576 -0.22940794, + 0.34480596 -0.91851789 -0.19347797, + 0.51605624 -0.80199033 -0.30082816, + 0.47020912 -0.82633418 -0.30996007, + 0.5554651 -0.74472117 -0.3699311, + 0.51161987 -0.76950383 -0.3822419, + 0.61647612 -0.63578016 -0.46447912, + 0.58274901 -0.656192 -0.47939101, + 0.68472916 -0.45911112 -0.56600612, + 0.66034329 -0.49712124 -0.56286532, + 0.72537905 -0.29982904 -0.61961907, + 0.68803495 -0.31608796 -0.65321994, + 0.61701208 -0.52780104 -0.58371407, + 0.68785083 -0.3186489 -0.65216881, + 0.64888775 -0.33402789 -0.68364477, + 0.49134889 -0.6928488 -0.52776587, + 0.49302912 -0.69209319 -0.52719015, + 0.57406616 -0.5392732 -0.61614323, + 0.57348084 -0.55593079 -0.60171479, + 0.64865792 -0.33751398 -0.68214893, + 0.60835999 -0.35196301 -0.71135098, + 0.64387226 -0.13294704 -0.75349432, + 0.61307788 0.0020384595 -0.79001981, + 0.61162812 0.0028778408 -0.7911402, + 0.60474789 -0.14959697 -0.78224081, + 0.60619926 -0.14939506 -0.78115529, + 0.60417414 -0.13612004 -0.78514016, + 0.60891485 -0.12918296 -0.78264582, + 0.61405873 0.0020384693 -0.78925771, + 0.57325292 -0.0030341996 -0.81937289, + 0.5661183 -0.15731208 -0.80917436, + 0.56642503 -0.15727399 -0.80896699, + 0.57356071 -0.0029738387 -0.8191576, + 0.55822593 -0.015723998 -0.8295399, + 0.5301069 -0.099929675 -0.84202182, + 0.52487814 -0.037310407 -0.8503592, + 0.46988499 -0.015869699 -0.88258499, + 0.44460195 -0.10830098 -0.88915688, + 0.44723314 -0.00050209515 -0.89441729, + 0.44799486 -0.00090545067 -0.8940357, + 0.44536084 -0.10827097 -0.88878071, + 0.48138699 -0.0282462 -0.87605298, + 0.487847 -0.10322 -0.86680502, + 0.49046582 -0.0011323796 -0.87145972, + 0.49107412 -0.0010251602 -0.87111717, + 0.48845223 -0.10319305 -0.86646742, + 0.53186923 -0.01794401 -0.84663641, + 0.53195506 0.00094308011 -0.84677213, + 0.5327729 0.00094307779 -0.84625781, + 0.53274888 0.00095601875 -0.84627283, + 0.53008288 -0.099930875 -0.84203684, + 0.55255181 -0.064801477 -0.83095568, + 0.55449688 -0.21911295 -0.80282182, + 0.51172304 -0.22621202 -0.82883513, + 0.51174378 -0.2253149 -0.82906657, + 0.46856982 -0.23168491 -0.85250473, + 0.43374193 -0.43453795 -0.78933185, + 0.46861288 -0.22821794 -0.85341585, + 0.42467386 -0.23388691 -0.8746137, + 0.4365572 -0.024919512 -0.89933139, + 0.39420909 -0.12660703 -0.91025823, + 0.39740714 0.00043841015 -0.91764235, + 0.40336791 0.00043844187 -0.91503775, + 0.40077418 -0.11321805 -0.90915442, + 0.40041181 -0.11322995 -0.90931261, + 0.40300286 0.00038632084 -0.91519868, + 0.37664691 -0.015940497 -0.92621976, + 0.35507813 -0.11771805 -0.92739534, + 0.35756403 -0.0021829102 -0.93388611, + 0.35698217 -0.0018673509 -0.93410939, + 0.35449883 -0.11773594 -0.92761457, + 0.39109808 -0.024786705 -0.92001522, + 0.3800841 -0.23770106 -0.89388722, + 0.4246749 -0.23266195 -0.8749398, + 0.391334 -0.44472399 -0.80565399, + 0.30847406 -0.7746712 -0.5520221, + 0.23033898 -0.88300186 -0.40896395, + 0.25189897 -0.87814087 -0.40671295, + 0.17411506 -0.94505936 -0.27667108, + 0.15973693 -0.9473955 -0.27735487, + 0.2257521 -0.88924241 -0.39784917, + 0.19927692 -0.89449871 -0.40020084, + 0.27004007 -0.79257315 -0.54672313, + 0.28078705 -0.6755082 -0.68179721, + 0.30091402 -0.67120206 -0.67745006, + 0.23111092 -0.8237527 -0.5177058, + 0.24606006 -0.82064319 -0.51575112, + 0.32071289 -0.66375273 -0.67570376, + 0.30031496 -0.66842192 -0.68045795, + 0.36396703 -0.42905906 -0.82670212, + 0.38584405 -0.42498305 -0.81884915, + 0.32028303 -0.66148609 -0.67812604, + 0.34002501 -0.65666401 -0.67318302, + 0.2648159 -0.81094569 -0.52176583, + 0.28060496 -0.80718189 -0.51934391, + 0.36020902 -0.64913607 -0.66997904, + 0.33966291 -0.65447682 -0.67549181, + 0.4071641 -0.41880509 -0.81167716, + 0.42868301 -0.41426599 -0.80287898, + 0.35987613 -0.64679223 -0.67242026, + 0.38072193 -0.64103097 -0.66643095, + 0.30146995 -0.79575384 -0.52525389, + 0.31908187 -0.79095572 -0.52208781, + 0.25385612 -0.87475443 -0.4127492, + 0.26936203 -0.87095314 -0.41095605, + 0.2047739 -0.9345656 -0.29095486, + 0.19380005 -0.93669623 -0.29161906, + 0.19901404 -0.93114322 -0.30555806, + 0.100761 -0.984065 -0.146504, + 0.11512097 -0.98252279 -0.14627397, + 0.018937591 -0.99979055 -0.0077638063, + 0.024098685 -0.99967939 -0.0077629355, + -0.07858938 -0.98913574 0.12423397, + -0.083796091 -0.98871487 0.12418199, + -0.18885805 -0.95102823 0.24470006, + -0.20482197 -0.9479239 0.24390197, + -0.29065984 -0.89751059 0.33164984, + -0.31536013 -0.89014328 0.32892713, + -0.37384391 -0.84513384 0.38208592, + -0.40009391 -0.83509481 0.37754691, + -0.3869029 -0.8459698 0.36693493, + -0.38528576 -0.84659052 0.36720479, + -0.36332083 -0.8626036 0.35201281, + -0.35377303 -0.8659991 0.35339803, + -0.31968597 -0.88706589 0.33303896, + -0.29843602 -0.89353114 0.33546704, + -0.25812504 -0.91349614 0.31447804, + -0.21949904 -0.92248011 0.31757003, + -0.17399198 -0.93904889 0.29650298, + -0.11312498 -0.94747287 0.29916197, + -0.0650573 -0.958148 0.27878299, + 0.024183109 -0.95990133 0.27929309, + 0.068568297 -0.96281701 0.26130801, + 0.18918605 -0.94766027 0.25719407, + 0.2228919 -0.94396752 0.24340189, + 0.37143508 -0.89905226 0.23182106, + 0.38816807 -0.89384413 0.22442903, + 0.55072325 -0.80955935 0.2032671, + 0.55094892 -0.80943489 0.20315097, + 0.7082628 -0.68471283 0.17184895, + 0.69692218 -0.69443619 0.17904705, + 0.83226669 -0.53681982 0.13840796, + 0.81808281 -0.55505991 0.15049598, + 0.91918659 -0.38009882 0.10305795, + 0.90847272 -0.40134487 0.11661796, + 0.9723779 -0.22414197 0.065128289, + 0.96749812 -0.24115703 0.076097205, + 0.99711221 -0.072422117 0.022852806, + 0.99649853 -0.079026766 0.027302787, + 0.99720877 0.070570283 -0.024381094, + 0.99656576 0.077431187 -0.029344093, + 0.97525048 0.2067541 -0.07835374, + 0.9694221 0.22661804 -0.094154216, + 0.93364859 0.33077684 -0.13742994, + 0.91895866 0.35915387 -0.16285995, + 0.87617671 0.43896785 -0.19905193, + 0.85013586 0.47202095 -0.23337796, + 0.80639768 0.53011781 -0.2621029, + 0.78537917 0.54916012 -0.28566206, + 0.73143697 0.60495692 -0.31468597, + 0.74570626 0.59880126 -0.29216313, + 0.69692379 0.64451981 -0.3144699, + 0.68707174 0.65027177 -0.32415888, + 0.64227152 0.68596953 -0.34195477, + 0.64341897 0.68544292 -0.34085196, + 0.61618775 0.70521778 -0.35068589, + 0.63182521 0.69909126 -0.33476612, + 0.60648274 0.71711677 -0.34339789, + 0.61599469 0.71392167 -0.33296585, + 0.6249361 0.70751017 -0.32997608, + 0.63115698 0.70558298 -0.32216999, + 0.64505702 0.69510299 -0.31738499, + 0.64651293 0.69468796 -0.31532496, + 0.64538383 0.69555783 -0.3157199, + 0.6516698 0.69413179 -0.30578995, + 0.63639331 0.70590234 -0.31097513, + 0.64088917 0.70527416 -0.30306706, + 0.62327504 0.71847606 -0.30874002, + 0.62674117 0.71832716 -0.30199605, + 0.60698712 0.73260117 -0.30799705, + 0.60930026 0.73274821 -0.30304012, + 0.58670002 0.74833298 -0.30948499, + 0.5909577 0.74907762 -0.29941884, + 0.56562382 0.76575571 -0.30608487, + 0.57672215 0.7687732 -0.27636805, + 0.54953885 0.78620869 -0.2826359, + 0.55926812 0.78967917 -0.25224206, + 0.52996391 0.80780983 -0.25803393, + 0.53799218 0.8113873 -0.22850607, + 0.50638783 0.8300187 -0.23375291, + 0.51292211 0.83358318 -0.20506105, + 0.47861618 0.85260528 -0.20974007, + 0.48388475 0.85606056 -0.18170291, + 0.44765314 0.87472028 -0.18566406, + 0.45180395 0.87796187 -0.15829098, + 0.41354495 0.89603686 -0.16154999, + 0.41673899 0.89898902 -0.134712, + 0.37630492 0.91626579 -0.13730097, + 0.37867305 0.9188531 -0.11097602, + 0.3361201 0.93502426 -0.11292903, + 0.33779097 0.93719786 -0.086933896, + 0.29388893 0.95175374 -0.088283978, + 0.29498398 0.95346189 -0.062408391, + 0.25010908 0.96615034 -0.063238919, + 0.25072905 0.96732825 -0.037565406, + 0.20483008 0.97806036 -0.037982214, + 0.20509203 0.97867811 -0.011250001, + 0.21744205 0.97596127 -0.014784104, + 0.21746504 0.97606725 -0.0012925003, + 0.21734807 0.97609335 -0.0013022604, + 0.21732393 0.97598761 -0.014784395, + 0.26509202 0.96417612 -0.0095227007, + 0.26510388 0.96421951 0.00073161867, + 0.26501197 0.9642449 0.00073161797, + 0.26498312 0.96413946 -0.014806007, + 0.25160098 0.96774989 -0.012530598, + 0.25129592 0.96717262 -0.037783187, + 0.29699987 0.95414966 -0.037274484, + 0.29767707 0.95392823 -0.037541308, + 0.34333396 0.93848687 -0.036933597, + 0.34250808 0.93743622 -0.062463515, + 0.38709694 0.91999888 -0.061301693, + 0.38570395 0.91850686 -0.087049089, + 0.42842892 0.89954478 -0.085252076, + 0.42638114 0.89769131 -0.11112804, + 0.46714613 0.87748224 -0.10862602, + 0.46432918 0.8753323 -0.13487704, + 0.50327313 0.85404819 -0.13159703, + 0.49955082 0.8516677 -0.15846494, + 0.53662926 0.82958043 -0.15435508, + 0.53188717 0.8270703 -0.18179905, + 0.56640929 0.80490834 -0.17692709, + 0.56049812 0.80236417 -0.20507005, + 0.59274888 0.78030485 -0.19943196, + 0.58552009 0.77784312 -0.22831203, + 0.61582512 0.75599021 -0.22189707, + 0.60704774 0.75374973 -0.2517029, + 0.63557303 0.73229003 -0.244537, + 0.62503028 0.73044235 -0.27530211, + 0.65159595 0.70982397 -0.26753098, + 0.63959408 0.70861703 -0.29796204, + 0.6639868 0.68928784 -0.28983393, + 0.65853131 0.68922538 -0.30216715, + 0.68105096 0.67061794 -0.29400897, + 0.67730409 0.67096806 -0.30176303, + 0.6977458 0.65331382 -0.29382294, + 0.69269663 0.6543147 -0.30338684, + 0.71106195 0.63789392 -0.29577398, + 0.70473796 0.63975292 -0.30669296, + 0.72090083 0.62493789 -0.29959095, + 0.71237397 0.62818003 -0.312911, + 0.72639805 0.61517805 -0.30643404, + 0.71612191 0.61986792 -0.32083198, + 0.72809345 0.60876936 -0.31508717, + 0.70825696 0.61892694 -0.33956096, + 0.71450406 0.61338305 -0.33651903, + 0.70201105 0.62027007 -0.34992203, + 0.73617399 0.58946103 -0.33254099, + 0.71485275 0.60283577 -0.35436487, + 0.75444263 0.56584471 -0.33261985, + 0.76694798 0.55638897 -0.319722, + 0.81369531 0.50400418 -0.2896201, + 0.85016221 0.46547711 -0.24608006, + 0.89888126 0.38738909 -0.20479804, + 0.91892999 0.35443199 -0.173048, + 0.96146488 0.24705397 -0.12062199, + 0.96937913 0.22387902 -0.10090801, + 0.99563986 0.08504159 -0.038330495, + 0.99655026 0.076644018 -0.031833608, + 0.99559724 -0.086564422 0.035954006, + 0.99646026 -0.078488022 0.030108908, + 0.95980537 -0.26204708 0.10052404, + 0.9668259 -0.24066097 0.085614994, + 0.89029032 -0.42905214 0.15263505, + 0.90544522 -0.4026711 0.13425703, + 0.78970331 -0.58199215 0.19404608, + 0.80988097 -0.55914903 0.17732801, + 0.6622358 -0.71423781 0.22651294, + 0.680691 -0.70031601 0.214982, + 0.51692319 -0.81834131 0.2512131, + 0.52522093 -0.81433189 0.24699497, + 0.36172208 -0.89215124 0.27059805, + 0.35408789 -0.8941837 0.27396592, + 0.20798492 -0.93522066 0.2865389, + 0.18413794 -0.93718266 0.29627988, + 0.065226614 -0.95145625 0.30079305, + 0.030149685 -0.9486475 0.31489486, + -0.05902027 -0.94742453 0.31448886, + -0.09930636 -0.93828666 0.33129489, + -0.16197096 -0.93049675 0.3285439, + -0.20185509 -0.91606039 0.34653717, + -0.24280697 -0.9073239 0.34323198, + -0.27918309 -0.88957328 0.36154711, + -0.30356306 -0.88269323 0.35875109, + -0.33413196 -0.86415291 0.37629193, + -0.34673083 -0.85997057 0.37447083, + -0.37223697 -0.8416059 0.39132994, + -0.37548777 -0.8404175 0.39077777, + -0.39147395 -0.8272289 0.40303895, + -0.38867906 -0.82829314 0.40355805, + -0.39772001 -0.81998903 0.41162699, + -0.37062204 -0.8300671 0.41668707, + -0.31605503 -0.8771081 0.36165002, + -0.2908369 -0.8845337 0.36471087, + -0.21044193 -0.93856066 0.2735289, + -0.19343291 -0.94192755 0.27451089, + -0.094950825 -0.98425025 0.14911702, + -0.088069953 -0.9848755 0.14921093, + 0.0063878712 -0.99988025 0.014095704, + 0.0033107908 -0.99989522 0.014095903, + 0.091570444 -0.98753846 -0.12799506, + 0.079532266 -0.98856354 -0.12812795, + 0.15342602 -0.95266914 -0.26245403, + 0.13438396 -0.95533866 -0.26318991, + 0.19512703 -0.90056413 -0.38847107, + 0.17037393 -0.90478957 -0.39029282, + 0.23518004 -0.80586314 -0.54339206, + 0.21282403 -0.83247113 -0.51156408, + 0.19868092 -0.83500469 -0.51312083, + 0.24209297 -0.73994392 -0.62759393, + 0.22442603 -0.74317604 -0.63033503, + 0.25980398 -0.63070494 -0.73124093, + 0.24058194 -0.6339488 -0.73500282, + 0.27817294 -0.44474089 -0.85136682, + 0.29896313 -0.44184014 -0.84581232, + 0.25978684 -0.62780565 -0.73373759, + 0.27966207 -0.6241861 -0.72950721, + 0.24233194 -0.73710585 -0.63083285, + 0.26020601 -0.73358101 -0.62781501, + 0.26830804 -0.62529308 -0.73281604, + 0.27967602 -0.62319005 -0.73035306, + 0.32098103 -0.43806806 -0.83968312, + 0.34225884 -0.4346078 -0.83305156, + 0.3483901 -0.45446911 -0.81980616, + 0.3800371 -0.23375507 -0.89494723, + 0.33485499 -0.23812699 -0.91168398, + 0.34459612 -0.02491571 -0.93842036, + 0.30979499 -0.114713 -0.94385803, + 0.31185398 0.0014868598 -0.95012885, + 0.31121299 0.0014868299 -0.95033902, + 0.30912596 -0.11563499 -0.9439649, + 0.30900684 -0.11563795 -0.94400352, + 0.31109312 0.0014759806 -0.95037836, + 0.26431203 -0.023533804 -0.96415013, + 0.26259005 -0.11633203 -0.95786923, + 0.26249194 -0.11633397 -0.95789576, + 0.26428393 -0.0039990884 -0.96443665, + 0.2795369 -0.012949395 -0.96004766, + 0.64049977 -0.015263194 -0.76780671, + 0.65118468 -0.0048747975 -0.75890362, + 0.64463896 -0.14150998 -0.7512759, + 0.68082708 -0.13582602 -0.71974003, + 0.68719226 0.0028012509 -0.72647023, + 0.6875 0.00280127 -0.726179, + 0.72249722 -0.018503608 -0.69112623, + 0.71583593 -0.13670999 -0.68475497, + 0.71566302 -0.13674299 -0.68492901, + 0.72243077 -0.0071969973 -0.69140577, + 0.7544353 0.0030964313 -0.65636724, + 0.74740726 -0.13621004 -0.65025324, + 0.748559 -0.13596199 -0.64897901, + 0.75557113 0.0033589303 -0.65505809, + 0.75536633 0.003358931 -0.65529424, + 0.7863791 -0.014793701 -0.61756706, + 0.7794137 -0.13360596 -0.61209774, + 0.77952319 -0.13358003 -0.61196411, + 0.78653318 -0.009995603 -0.61746711, + 0.81611013 0.0036205905 -0.57788503, + 0.80900699 -0.13169999 -0.572855, + 0.80874264 -0.13177094 -0.57321173, + 0.81585139 0.0035541474 -0.57825059, + 0.8159743 0.0035541612 -0.5780772, + 0.8432591 -0.011790502 -0.53737807, + 0.836357 -0.128216 -0.53298002, + 0.83631343 -0.12822907 -0.53304523, + 0.84320509 -0.012866502 -0.53743804, + 0.8687641 0.0036193104 -0.49521306, + 0.86219972 -0.12275196 -0.49147081, + 0.86202401 -0.122812 -0.49176401, + 0.86859381 0.0035659291 -0.49551189, + 0.86860985 0.0035659291 -0.49548388, + 0.891846 -0.0089352699 -0.45225099, + 0.89443868 -0.011573796 -0.44704086, + 0.93560863 -0.014747594 -0.35273087, + 0.94856638 0.0025759109 -0.31656811, + 0.94454837 -0.091980331 -0.31522712, + 0.94453597 -0.091987997 -0.31526199, + 0.94855434 0.002567501 -0.31660411, + 0.94862211 0.0025675101 -0.31640103, + 0.96300113 -0.0041911504 -0.26946503, + 0.96291673 -0.0040769191 -0.26976794, + 0.95968211 -0.081997804 -0.26886204, + 0.96714765 -0.033428587 -0.2520079, + 0.96233076 -0.10553297 -0.25056395, + 0.97510147 -0.086077444 -0.20437211, + 0.97134167 -0.12300896 -0.20338193, + 0.98298335 -0.09506654 -0.15718205, + 0.9791435 -0.12985495 -0.15625493, + 0.98957151 -0.092064053 -0.11078095, + 0.98662049 -0.12027406 -0.11006505, + 0.99529314 -0.071492806 -0.065424509, + 0.99379188 -0.09032739 -0.064950891, + 0.99934101 -0.0294696 -0.021190399, + 0.99917352 -0.034779087 -0.02103889, + 0.99922955 0.033581484 0.02031449, + 0.99918586 0.034892395 0.020250898, + 0.99348789 0.098543085 0.057192493, + 0.99351001 0.0983072 0.057215001, + 0.98403126 0.15383802 0.089534223, + 0.98384237 0.15515307 0.089340933, + 0.97162426 0.20497605 0.11803003, + 0.97077227 0.20948805 0.11711503, + 0.95625561 0.25533891 0.14274895, + 0.95426112 0.26391003 0.14048901, + 0.93794626 0.30610907 0.16295405, + 0.9344849 0.31860796 0.15882999, + 0.91653889 0.35793498 0.17843498, + 0.91124874 0.3742919 0.17184696, + 0.89164674 0.41143891 0.18890196, + 0.88782698 0.421839 0.183889, + 0.8624478 0.46397787 0.20225796, + 0.86119068 0.46702582 0.20059292, + 0.83449018 0.50629711 0.21746105, + 0.83237559 0.51098573 0.2145799, + 0.80440128 0.54775017 0.23001809, + 0.8014558 0.5537619 0.22586794, + 0.77212912 0.58840305 0.23999703, + 0.76817697 0.59586102 0.234209, + 0.73752183 0.62851483 0.24704394, + 0.73270226 0.63694423 0.23968609, + 0.7013492 0.66714519 0.25105107, + 0.69553393 0.67659795 0.24175997, + 0.66350603 0.70454508 0.25174603, + 0.65688616 0.7145592 0.24063607, + 0.62404275 0.74052674 0.24938092, + 0.61676115 0.75078219 0.23649906, + 0.58317888 0.7748118 0.24406794, + 0.57512283 0.78536773 0.22897893, + 0.54139709 0.8071602 0.23533306, + 0.5328601 0.81755418 0.21832405, + 0.49927694 0.8371079 0.22354597, + 0.49040306 0.84712315 0.20466404, + 0.45666012 0.86476117 0.20892504, + 0.44760385 0.87419868 0.18822193, + 0.41368994 0.89002186 0.19162896, + 0.40459207 0.89872414 0.16911602, + 0.37119803 0.91253811 0.17171602, + 0.36229911 0.92028534 0.14769706, + 0.3294881 0.93223023 0.14961404, + 0.3208769 0.93896174 0.12405197, + 0.28852016 0.94922549 0.12540805, + 0.28039095 0.95481378 0.09854728, + 0.24843197 0.9635309 0.099446982, + 0.24091688 0.96791452 0.071417265, + 0.20976907 0.97510034 0.071947522, + 0.20297498 0.97824585 0.042850696, + 0.17273204 0.98402524 0.04310381, + 0.16679692 0.9859035 0.013157194, + 0.13727805 0.99044436 0.013217805, + 0.13231301 0.99105811 -0.017239701, + 0.10342102 0.99448723 -0.017299304, + 0.099477097 0.99386603 -0.048317902, + 0.071553208 0.99626011 -0.048434306, + 0.068688177 0.99443066 -0.079934873, + 0.041536186 0.99592465 -0.080054969, + 0.039777711 0.99291623 -0.11196103, + 0.013496002 0.99361211 -0.11204001, + 0.012583497 0.98684776 -0.16116196, + -0.012400598 0.9868499 -0.16116299, + -0.013308702 0.99359512 -0.11221302, + -0.039550886 0.99290562 -0.11213496, + -0.041314714 0.99592835 -0.080124229, + -0.068328783 0.99444973 -0.080005176, + -0.071196593 0.99627787 -0.048595991, + -0.099102162 0.99389565 -0.048479781, + -0.10304604 0.99452335 -0.017459206, + -0.13193803 0.99110526 -0.017399203, + -0.13691305 0.99049634 0.013109005, + -0.16640194 0.98597163 0.013049196, + -0.17233302 0.98410112 0.042970203, + -0.20255704 0.97833824 0.042718612, + -0.20936297 0.97519088 0.071902491, + -0.24051 0.96801901 0.071373798, + -0.24804209 0.96363038 0.099457234, + -0.28000799 0.954925 0.098558702, + -0.28814206 0.94933826 0.12542403, + -0.32052612 0.93907934 0.12406904, + -0.329117 0.93236601 0.14958499, + -0.36197898 0.92041588 0.14766799, + -0.37091982 0.91263759 0.17178793, + -0.404241 0.89886701 0.16919599, + -0.4133361 0.89016926 0.19170804, + -0.4472858 0.87434459 0.18829991, + -0.45631599 0.86493701 0.208949, + -0.49013287 0.84727484 0.20468296, + -0.49906111 0.8372032 0.22367106, + -0.53267676 0.81764156 0.2184439, + -0.54118019 0.80729228 0.23537908, + -0.57493693 0.78549087 0.22902296, + -0.58297265 0.77496755 0.24406585, + -0.61651695 0.75097889 0.23651098, + -0.62392288 0.74054885 0.24961494, + -0.65676004 0.71459705 0.24086803, + -0.6633783 0.70458233 0.25197813, + -0.69545609 0.67660207 0.24197203, + -0.70127153 0.66714555 0.25126681, + -0.732651 0.63692802 0.239886, + -0.73750722 0.62842923 0.2473051, + -0.76821434 0.59572428 0.23443411, + -0.77211362 0.58836371 0.24014288, + -0.80140072 0.5537768 0.22602692, + -0.80441719 0.54761714 0.23027906, + -0.83240771 0.51083583 0.21481192, + -0.83454013 0.50610405 0.21771903, + -0.86123902 0.46683601 0.200827, + -0.862499 0.463779 0.20249601, + -0.88792974 0.4215489 0.18405795, + -0.89170057 0.41127378 0.18900791, + -0.89087123 0.40985209 0.19588204, + -0.86564916 0.45171213 0.21588804, + -0.86459202 0.454386 0.214509, + -0.83829528 0.49303716 0.23275609, + -0.83641499 0.497401 0.230222, + -0.80880988 0.53367692 0.24701297, + -0.80599588 0.53970796 0.24307597, + -0.77705437 0.57391131 0.25848112, + -0.77334511 0.58128303 0.25307602, + -0.74292183 0.61373389 0.26720393, + -0.7383498 0.62218589 0.26023895, + -0.70714176 0.65231079 0.27283892, + -0.70171279 0.66167879 0.26415992, + -0.66983932 0.68958336 0.27530012, + -0.66340256 0.69996357 0.26447687, + -0.63063967 0.72598165 0.27430689, + -0.62354326 0.73668325 0.26170909, + -0.58983588 0.7609328 0.27032393, + -0.5821901 0.7717222 0.25592905, + -0.54837108 0.79372615 0.26322603, + -0.54004568 0.80471754 0.24653685, + -0.50620598 0.82458299 0.25262299, + -0.49761277 0.83518261 0.23420389, + -0.46346599 0.853203 0.23925699, + -0.45459184 0.86341071 0.21878792, + -0.42028809 0.87959021 0.22288805, + -0.41141316 0.88907433 0.20071408, + -0.37762195 0.90322888 0.20390996, + -0.36884689 0.91189373 0.18000494, + -0.33547708 0.92421424 0.18243705, + -0.32697588 0.93191063 0.15693694, + -0.29403296 0.9425239 0.15872398, + -0.28599784 0.94910854 0.13190193, + -0.25337207 0.95816022 0.13316002, + -0.24593703 0.9635691 0.10511702, + -0.21407904 0.97105521 0.10593402, + -0.20735997 0.97524887 0.076756194, + -0.17645195 0.98127478 0.077230483, + -0.17052299 0.98423386 0.046964094, + -0.14027995 0.98898667 0.047190882, + -0.13531302 0.99066812 0.016343102, + -0.10567505 0.9942655 0.016402507, + -0.10172702 0.99469924 -0.015002703, + -0.073074408 0.99721313 -0.015040602, + -0.070202768 0.99643052 -0.046880677, + -0.042434014 0.99799538 -0.046954319, + -0.040688284 0.99603462 -0.079117373, + -0.013355803 0.99677122 -0.079175919, + -0.013958698 0.99884886 -0.045892797, + -0.041745815 0.99807537 -0.045857314, + -0.043497179 0.99896455 -0.013331394, + -0.072060935 0.99731147 -0.013309306, + -0.074919738 0.99701047 0.018899109, + -0.10434704 0.99436235 0.018848907, + -0.10828996 0.99282867 0.05063998, + -0.13864702 0.98905611 0.050447609, + -0.14362505 0.98625535 0.081684232, + -0.17459105 0.98128122 0.081272222, + -0.18042795 0.97725779 0.11141297, + -0.212079 0.970963 0.110695, + -0.21874908 0.96569133 0.13996105, + -0.25122103 0.95792115 0.13883501, + -0.25856796 0.95147389 0.16685298, + -0.29183707 0.94209224 0.16520704, + -0.29979011 0.93448037 0.19202207, + -0.33328292 0.92353076 0.18977195, + -0.34164298 0.91488385 0.21509898, + -0.37548906 0.90222609 0.21212304, + -0.38404185 0.89273769 0.23565091, + -0.41831106 0.87822312 0.23181903, + -0.4270139 0.86791283 0.25374493, + -0.46169817 0.85139632 0.24891609, + -0.47033313 0.84049618 0.26898506, + -0.50467074 0.82223159 0.26313987, + -0.51308674 0.81092966 0.28130984, + -0.54715425 0.79080135 0.27432713, + -0.55507195 0.77950388 0.29029098, + -0.58896476 0.75734669 0.28203991, + -0.59646493 0.74597496 0.29622796, + -0.63015527 0.72165221 0.2865701, + -0.63694984 0.71069682 0.29867193, + -0.66976583 0.68457681 0.28769493, + -0.67581123 0.67420524 0.29787013, + -0.70747763 0.64645368 0.28560984, + -0.71272516 0.63686121 0.29399106, + -0.74367279 0.60699075 0.28020191, + -0.74798805 0.59856808 0.28675804, + -0.7781893 0.56638819 0.27134109, + -0.78158945 0.55928236 0.27626318, + -0.81027597 0.52544099 0.259547, + -0.81285989 0.51963896 0.26312396, + -0.84007043 0.48396924 0.24506211, + -0.84171402 0.479987 0.247245, + -0.86764759 0.44198778 0.22767189, + -0.86860961 0.43945578 0.22890189, + -0.89316225 0.3988691 0.20776105, + -0.89640999 0.389328 0.211832, + -0.91539621 0.35360208 0.19239405, + -0.91991389 0.33866096 0.19765396, + -0.93737537 0.30083311 0.17557606, + -0.94026738 0.28976309 0.17870305, + -0.9560495 0.24956188 0.15390992, + -0.95759636 0.24258809 0.15543605, + -0.9717344 0.19877388 0.12736192, + -0.97237664 0.19523993 0.12792596, + -0.98430365 0.14761794 0.09672296, + -0.98444122 0.14662904 0.096826725, + -0.99369174 0.093582481 0.061797585, + -0.99351102 0.095551699 0.0616914, + -0.99924374 0.032667693 0.021091394, + -0.99938035 0.028082609 0.021222007, + -0.99936324 -0.028467407 -0.021512806, + -0.99950254 -0.02295859 -0.021624988, + -0.99534434 -0.070160724 -0.066085219, + -0.99632865 -0.05407488 -0.066370279, + -0.98959488 -0.090881296 -0.11154599, + -0.99156022 -0.065308318 -0.11199703, + -0.9831661 -0.092040405 -0.15783902, + -0.98564851 -0.058302574 -0.15842293, + -0.97586238 -0.075424828 -0.20494807, + -0.97831112 -0.025267603 -0.20559403, + -0.98419076 -0.051980089 -0.16931196, + -0.98423266 -0.05193368 -0.16908294, + -0.98692852 -0.026331186 -0.15899293, + -0.98565876 -0.057345886 -0.15870796, + -0.99279898 -0.040708698 -0.112663, + -0.9916085 -0.06386333 -0.11240205, + -0.99702567 -0.038072985 -0.067010075, + -0.99639761 -0.052192982 -0.066841178, + -0.99961334 -0.017112806 -0.021915507, + -0.99952048 -0.021943912 -0.021848012, + -0.99952942 0.021736788 0.021641687, + -0.99941999 0.026372001 0.021547601, + -0.99480724 0.078814119 0.064396016, + -0.994008 0.088560097 0.064071499, + -0.98428452 0.14307192 0.10350995, + -0.98464465 0.14044996 0.10367596, + -0.97292876 0.18593496 0.13725097, + -0.97245824 0.18860905 0.13693704, + -0.95862752 0.23035289 0.16724493, + -0.95739353 0.23614588 0.16623093, + -0.94197488 0.27449396 0.19322596, + -0.93964362 0.2838769 0.19100693, + -0.92262465 0.32000488 0.21531492, + -0.91875857 0.33358386 0.2111979, + -0.90026975 0.3678129 0.23286894, + -0.89464432 0.38521114 0.22632708, + -0.87458873 0.41804886 0.24562091, + -0.870525 0.42936701 0.24047901, + -0.84491742 0.46668521 0.26138011, + -0.84340411 0.47051007 0.25940302, + -0.81658202 0.50549501 0.27869099, + -0.81423283 0.51101387 0.27548093, + -0.78579217 0.54442114 0.29349005, + -0.78262091 0.55137897 0.28893897, + -0.75275409 0.58309203 0.30555704, + -0.74862242 0.59158534 0.29931816, + -0.71790391 0.62116092 0.31428197, + -0.71295983 0.63071382 0.30641195, + -0.68138719 0.65834415 0.3198351, + -0.67564303 0.66880298 0.31017601, + -0.64288652 0.69486851 0.32226476, + -0.63638008 0.70605206 0.31066203, + -0.60271287 0.73038381 0.32136691, + -0.59551895 0.74206895 0.30771896, + -0.56156021 0.76432538 0.31694916, + -0.55378622 0.77626836 0.30121115, + -0.51951903 0.79659212 0.30909702, + -0.51149195 0.80827188 0.29167196, + -0.47688395 0.82678187 0.29835096, + -0.46847978 0.83836961 0.27868089, + -0.43347284 0.85515869 0.28426191, + -0.42497009 0.86625916 0.26267007, + -0.39031395 0.88106787 0.26715997, + -0.38187394 0.8914929 0.24374697, + -0.34756482 0.90445858 0.24729188, + -0.33941311 0.91397429 0.22237307, + -0.30526096 0.92527586 0.22512297, + -0.29749697 0.93382889 0.19864297, + -0.26365396 0.9435069 0.20070197, + -0.2563591 0.95105338 0.17256206, + -0.22323997 0.95910388 0.17402199, + -0.21666393 0.96544164 0.14484195, + -0.18434706 0.97198337 0.14582404, + -0.17853704 0.97713625 0.11545303, + -0.14688702 0.98232013 0.11606602, + -0.14198904 0.98622036 0.084903233, + -0.11088695 0.99017054 0.085243262, + -0.10694998 0.99284679 0.053075589, + -0.076789282 0.99562573 0.053224187, + -0.073914684 0.99705178 0.020598894, + -0.044630572 0.99879038 0.020634787, + -0.042879198 0.99900389 -0.012354798, + -0.014359406 0.99982047 -0.012364905, + -0.013761598 0.99886489 -0.045600895, + 0.014097704 0.99886024 -0.045600712, + 0.014696804 0.99981624 -0.012311803, + 0.043217 0.99899 -0.0123016, + 0.044959415 0.99877334 0.020750608, + 0.074277759 0.99702239 0.020714186, + 0.077138901 0.99559301 0.053330801, + 0.10733593 0.9927994 0.053181067, + 0.11127003 0.99012727 0.085246719, + 0.14237003 0.98616523 0.084905624, + 0.14727207 0.98225737 0.11611004, + 0.17899394 0.97704762 0.11549495, + 0.18477695 0.97192264 0.14568396, + 0.21703196 0.96537977 0.14470297, + 0.22365198 0.95899487 0.17409399, + 0.25673106 0.95094025 0.17263204, + 0.26398706 0.94342726 0.20063904, + 0.29791915 0.93370944 0.19857208, + 0.30568606 0.92515421 0.22504605, + 0.33972612 0.91387528 0.22230208, + 0.347911 0.90431398 0.247334, + 0.38218608 0.89134824 0.24378707, + 0.39058015 0.88097233 0.26708609, + 0.42522693 0.86615586 0.26259497, + 0.433745 0.85502899 0.284237, + 0.46880475 0.83820057 0.27864289, + 0.47715095 0.82669288 0.29817098, + 0.51168078 0.80821264 0.29150486, + 0.51982117 0.7963593 0.30918911, + 0.55396986 0.77609479 0.30132094, + 0.56165093 0.76428288 0.31689098, + 0.59576315 0.74191517 0.30761707, + 0.60294211 0.73025221 0.3212361, + 0.63651019 0.70598018 0.31055906, + 0.64301604 0.69479305 0.32216904, + 0.67574483 0.66874081 0.31008795, + 0.68139106 0.65846103 0.31958604, + 0.71293998 0.63084698 0.30618399, + 0.71795106 0.62116808 0.31416002, + 0.74872404 0.59153104 0.29917103, + 0.7527892 0.58317709 0.30530807, + 0.78263485 0.55147797 0.28871197, + 0.7858572 0.54441011 0.29333606, + 0.81417459 0.51114374 0.27541187, + 0.8165108 0.5056569 0.27860594, + 0.84344018 0.47052911 0.25925106, + 0.84487784 0.46689788 0.26112795, + 0.87042791 0.42966294 0.24030197, + 0.87452179 0.4182719 0.24547994, + 0.89457214 0.38544506 0.22621404, + 0.90018272 0.3681109 0.2327349, + 0.91871125 0.33380908 0.21104805, + 0.92256826 0.32027808 0.21515104, + 0.93956238 0.28420508 0.19091907, + 0.94185221 0.27500606 0.19309604, + 0.95729309 0.23661603 0.16614102, + 0.95841545 0.23136811 0.16705908, + 0.97231537 0.18944907 0.13679205, + 0.97275698 0.18695401 0.13708401, + 0.98452646 0.14131707 0.10362105, + 0.98509926 0.13706502 0.10388802, + 0.99433637 0.08469943 0.064197719, + 0.99498814 0.076433711 0.064471409, + 0.99944013 0.025574304 0.021571802, + 0.99954253 0.02110409 0.021662589, + 0.99953437 -0.021293508 -0.021857008, + 0.99962038 -0.016689006 -0.021921307, + 0.99646324 -0.050900713 -0.066859014, + 0.99702448 -0.038102619 -0.06701123, + 0.99159914 -0.063935407 -0.11244301, + 0.99256402 -0.046117298 -0.112649, + 0.98521346 -0.064912431 -0.15855907, + 0.98711723 -0.017958203 -0.15898804, + 0.98475635 -0.0022355006 -0.17392506, + 0.98474878 -0.0022237096 -0.17396796, + 0.98293674 -0.060679886 -0.17364696, + 0.98294455 -0.060670469 -0.1736059, + 0.97494423 -0.0070122117 -0.22233906, + 0.97496688 0.0016680597 -0.22234397, + 0.97503775 0.0016680496 -0.22203293, + 0.97256035 -0.071259022 -0.22146907, + 0.97255498 -0.071263798 -0.22149099, + 0.97503275 0.0016615296 -0.22205494, + 0.96691543 -0.01544659 -0.25462884, + 0.98796374 -0.015808497 -0.15387598, + 0.99209648 0.00049358222 -0.12547706, + 0.99093902 -0.048291299 -0.125331, + 0.99093312 -0.048301209 -0.12537402, + 0.99209088 0.00047609294 -0.12552099, + 0.99209636 0.00047609617 -0.12547804, + 0.99705648 -0.00053005322 -0.076669641, + 0.99646151 -0.034544285 -0.076623864, + 0.99646109 -0.034545403 -0.07662861, + 0.99705613 -0.00052931008 -0.076674409, + 0.99854773 -0.015906896 -0.05147329, + 0.7840538 -0.013696096 0.62054187, + -0.61421674 -0.0032584588 0.78913069, + -0.60049456 0.21022186 0.77150047, + -0.59172899 0.26256999 0.76217699, + -0.5844509 0.30430594 0.7522068, + -0.5477398 0.31376389 0.77558571, + -0.545138 0.328123 0.77146602, + -0.50673795 0.33741996 0.79332489, + -0.50420791 0.35200191 0.7885868, + -0.46500212 0.36085808 0.80842716, + -0.46158719 0.38145214 0.80089432, + -0.42179686 0.38987786 0.81858569, + -0.41836721 0.4114992 0.80971438, + -0.37776691 0.41948292 0.82542485, + -0.3743861 0.44200513 0.81514817, + -0.33243999 0.449561 0.82908303, + -0.32911488 0.47334382 0.81708568, + -0.28740984 0.48011976 0.82878256, + -0.28425503 0.50470406 0.81515211, + -0.24207303 0.51076204 0.82493812, + -0.23917894 0.53594589 0.80966383, + -0.19657695 0.54119587 0.81759679, + -0.19397596 0.56733686 0.80031383, + -0.15167198 0.5716309 0.80637079, + -0.14950404 0.59803814 0.78740019, + -0.10699899 0.60136294 0.79177886, + -0.10535604 0.62786424 0.77115929, + -0.063411802 0.630108 0.77391398, + -0.062360015 0.65675515 0.75152117, + -0.020663602 0.65789509 0.75282609, + -0.020297892 0.68438774 0.72883576, + 0.0207243 0.68438202 0.72882903, + 0.021092908 0.65791428 0.75279737, + 0.062777378 0.65676278 0.75147969, + 0.063819103 0.630445 0.773606, + 0.10599905 0.62817329 0.77081937, + 0.10765495 0.60164768 0.79147363, + 0.14981897 0.59833491 0.7871148, + 0.15198998 0.57197195 0.8060689, + 0.19458504 0.56763411 0.79995519, + 0.19719303 0.54153305 0.8172251, + 0.23945588 0.53630877 0.80934167, + 0.24239591 0.51076782 0.82483971, + 0.28429994 0.50474387 0.81511182, + 0.28744999 0.48018301 0.82873201, + 0.32941484 0.47335976 0.81695557, + 0.33273003 0.44966707 0.8289091, + 0.37440321 0.44215426 0.81505948, + 0.37775218 0.41984922 0.82524544, + 0.4185501 0.4118171 0.8094582, + 0.42196095 0.39036095 0.81827086, + 0.461712 0.38192901 0.80059499, + 0.46485993 0.36305496 0.80752486, + 0.50404024 0.35415518 0.78772938, + 0.50738597 0.33486998 0.79399091, + 0.54571211 0.32564208 0.77211118, + 0.54892606 0.30758104 0.7772221, + 0.58588004 0.29820803 0.75353611, + 0.59147877 0.26586393 0.76122868, + 0.60072404 0.22398204 0.76743913, + 0.58589697 0.21882597 0.7802819, + 0.58076882 0.25456792 0.7732417, + 0.55995286 0.25908795 0.78697282, + 0.55098206 0.26889202 0.79001009, + 0.54609412 0.29900306 0.78254616, + 0.5076859 0.30750394 0.8047958, + 0.50449979 0.32687089 0.79914671, + 0.465242 0.33511299 0.81929803, + 0.46194595 0.35584897 0.81238991, + 0.4220888 0.36373183 0.83038557, + 0.41903493 0.38390595 0.8228159, + 0.3781479 0.39142191 0.83892381, + 0.37489983 0.4142198 0.82938057, + 0.33346909 0.42123309 0.84342217, + 0.330273 0.445301 0.83224201, + 0.28830695 0.45174187 0.84427983, + 0.28527209 0.47667819 0.83150327, + 0.24286588 0.48245376 0.8415786, + 0.24014799 0.50746399 0.82753199, + 0.19763309 0.51245123 0.83566439, + 0.19515903 0.53878707 0.81952512, + 0.15238002 0.54293507 0.8258341, + 0.15030201 0.56986606 0.8078751, + 0.10791002 0.57304811 0.81238616, + 0.10632798 0.60010791 0.79282081, + 0.064254515 0.60228211 0.79569316, + 0.063228063 0.62980264 0.77417755, + 0.021435812 0.63092035 0.7755515, + 0.021077601 0.65789908 0.75281113, + -0.0206724 0.65790403 0.75281799, + -0.021030892 0.63061875 0.77580768, + -0.062862568 0.6295107 0.77444464, + -0.063861653 0.6026206 0.79546839, + -0.10620099 0.60043794 0.79258788, + -0.107811 0.57298201 0.812446, + -0.15020701 0.56980306 0.80793715, + -0.15225899 0.54328692 0.82562488, + -0.19505195 0.5391379 0.81931984, + -0.19753499 0.512775 0.83548898, + -0.24004892 0.50778681 0.82736272, + -0.242855 0.481989 0.84184802, + -0.28501004 0.47625607 0.83183509, + -0.28804797 0.45123193 0.84464085, + -0.32978302 0.44484305 0.83268112, + -0.33293784 0.4210178 0.84373957, + -0.37494409 0.41391808 0.82951117, + -0.3781499 0.3914049 0.83893085, + -0.41907191 0.38388291 0.82280785, + -0.42238915 0.36188313 0.83104032, + -0.46224773 0.35403278 0.81301153, + -0.46483013 0.33781609 0.81842119, + -0.50394505 0.32955003 0.79839611, + -0.5066691 0.31327808 0.80320817, + -0.54477191 0.30471894 0.7812618, + -0.55117792 0.26552698 0.79101086, + -0.58986604 0.25697103 0.76552212, + -0.5975281 0.20282805 0.7757712, + -0.60227996 0.20191596 0.77232689, + -0.61494327 -0.0031112412 0.78856528, + -0.63952309 0.19602904 0.74335909, + -0.65217501 0.00230434 0.75806499, + -0.65294003 0.0023042501 0.75740612, + -0.63967085 0.20058696 0.74201483, + -0.63709706 0.19964904 0.74447805, + -0.62915182 0.25317195 0.73489583, + -0.67596895 0.18983696 0.71205896, + -0.66699278 0.24885891 0.70227474, + -0.63095295 0.25913298 0.73126495, + -0.62286204 0.30302003 0.72126406, + -0.58714128 0.31353715 0.74629736, + -0.58456421 0.32680711 0.74261826, + -0.54790592 0.33695397 0.76567686, + -0.54548401 0.34987101 0.76160198, + -0.50703192 0.35980797 0.78323489, + -0.50357825 0.37892017 0.77642035, + -0.46445999 0.38841301 0.79587197, + -0.46100178 0.4082478 0.78791565, + -0.42105815 0.41728014 0.80534929, + -0.41751516 0.43853515 0.79584432, + -0.37699208 0.44700313 0.81121218, + -0.37338081 0.46985975 0.79988664, + -0.33171085 0.47781277 0.81342655, + -0.32826799 0.501136 0.80068898, + -0.28655496 0.50828695 0.81211489, + -0.28320193 0.53300589 0.7973088, + -0.24154103 0.53930306 0.80672812, + -0.23848991 0.5642978 0.79037368, + -0.19587097 0.56980896 0.7980929, + -0.19316605 0.59540313 0.7798602, + -0.15102598 0.59987193 0.7857129, + -0.14874394 0.62596476 0.7655347, + -0.10672098 0.62939197 0.76972491, + -0.10499494 0.65537357 0.74797159, + -0.06325943 0.65769631 0.75062233, + -0.062166594 0.68350595 0.72729295, + -0.0206 0.68468499 0.72854799, + -0.020219093 0.71031475 0.70359379, + 0.020637807 0.71030819 0.70358819, + 0.021022305 0.68467516 0.72854519, + 0.062288936 0.68349642 0.72729141, + 0.063388214 0.65740216 0.75086915, + 0.105132 0.65507603 0.74821299, + 0.10684902 0.62912518 0.76992518, + 0.14887498 0.62569594 0.76572889, + 0.15112403 0.5999071 0.78566718, + 0.19353104 0.59540409 0.77976912, + 0.19624007 0.56979215 0.79801428, + 0.23854503 0.56431603 0.79034412, + 0.24159095 0.53934389 0.80668581, + 0.28351116 0.53300226 0.79720134, + 0.2868171 0.50866717 0.81178433, + 0.32850787 0.50150782 0.8003577, + 0.33200788 0.47782582 0.81329769, + 0.37339789 0.46992081 0.79984272, + 0.37699792 0.44713488 0.81113684, + 0.41776115 0.43861115 0.79567331, + 0.42126009 0.41765109 0.80505121, + 0.46093687 0.40866792 0.78773582, + 0.46444505 0.38857007 0.79580414, + 0.50374705 0.37902606 0.77625912, + 0.50685394 0.36191696 0.7823779, + 0.54486579 0.35204682 0.76104164, + 0.54829615 0.33371511 0.7668153, + 0.58549577 0.32349589 0.74333376, + 0.58856905 0.30736902 0.74773705, + 0.62432885 0.29699495 0.7225008, + 0.63065451 0.26243982 0.73034245, + 0.63622397 0.20135599 0.74476498, + 0.62722296 0.20335597 0.75182289, + 0.62025195 0.25089598 0.74319494, + 0.60025996 0.25582296 0.75778788, + 0.60660887 0.21256596 0.76605582, + 0.60012263 0.21389987 0.77077854, + 0.63867182 0.21455096 0.73896283, + 0.65389621 -0.0032734813 0.75657731, + 0.65351897 -0.0035061301 0.75690198, + 0.64137495 0.19191897 0.74283594, + 0.64014101 0.19218101 0.74383199, + 0.65229601 -0.0037603099 0.75795501, + 0.68945599 0.00227774 0.72432399, + 0.6764158 0.19358195 0.71062481, + 0.67535985 0.19246696 0.71193081, + 0.67221683 0.21463996 0.70855784, + 0.64368778 0.22186893 0.73242074, + 0.63881397 0.25265399 0.72669297, + 0.66811395 0.24434496 0.70279396, + 0.67243296 0.21745098 0.70749491, + 0.70949435 0.20703711 0.6736123, + 0.71308863 0.18179691 0.67709273, + 0.7573157 0.0030624089 0.65304178, + 0.74688643 0.16541611 0.64404833, + 0.74849224 0.16495806 0.64229923, + 0.75888389 0.0034265495 0.65121692, + 0.72457308 -0.0057330206 0.68917406, + 0.71284896 0.17925198 0.67802292, + 0.677683 0.18671 0.71125603, + 0.68981093 0.0022777799 0.72398597, + 0.71607339 -0.015062209 0.69786245, + 0.64049584 -0.015667096 0.76780182, + 0.61433989 0.0020756896 0.78903884, + 0.61562508 0.0013295701 0.78803813, + 0.60211998 0.208317 0.77074999, + 0.60224575 0.20829092 0.77065873, + 0.61575091 0.0013059396 0.78793985, + 0.61638379 0.0013059695 0.78744471, + 0.57567888 -0.0018390996 0.8176738, + 0.56171501 0.21892001 0.79784101, + 0.56566793 0.21818997 0.79524386, + 0.56276894 0.21556097 0.79801285, + 0.57631719 -0.0017136306 0.81722432, + 0.57627207 -0.0017394002 0.81725609, + 0.56272417 0.21556908 0.7980423, + 0.54400313 0.22862406 0.80733615, + 0.5399881 0.25783107 0.80120915, + 0.518269 0.26198 0.81410301, + 0.52340525 0.2229341 0.82240343, + 0.52098715 0.22333308 0.82382929, + 0.53448719 0.00069202826 0.84517628, + 0.55822408 -0.015941802 0.82953709, + -0.48008794 0.21819498 0.84965086, + -0.49194199 -0.000186755 0.870628, + -0.53518879 -0.0011767695 0.84473169, + -0.5229789 0.21239296 0.82545882, + -0.52191126 0.2125601 0.82609141, + -0.53411609 -0.0013783601 0.84541011, + -0.51471525 -0.015918007 0.85721344, + -0.49198219 -0.00020836707 0.87060529, + -0.48012894 0.21818997 0.84962887, + -0.51189208 0.22638303 0.82868409, + -0.5071891 0.26255107 0.82086921, + -0.46646178 0.26946789 0.84249657, + -0.46149021 0.30515113 0.8330124, + -0.42183009 0.31186906 0.85135019, + -0.41919786 0.33085388 0.84546369, + -0.37837684 0.33732387 0.86199969, + -0.37585291 0.3568649 0.85520881, + -0.33403814 0.36298019 0.8698644, + -0.33108899 0.38771901 0.860264, + -0.28878295 0.3933869 0.87284082, + -0.28605506 0.4184421 0.86202019, + -0.24363388 0.42353079 0.87250459, + -0.24112189 0.44938979 0.8601796, + -0.19841404 0.45384613 0.86870921, + -0.19614892 0.48085976 0.85457557, + -0.15321101 0.48459607 0.86121613, + -0.15129998 0.51233292 0.8453539, + -0.108568 0.51523602 0.85014403, + -0.10712193 0.54303467 0.8328495, + -0.064455971 0.54504174 0.83592761, + -0.063536197 0.57301402 0.81707901, + -0.021430194 0.57404286 0.81854481, + -0.021091798 0.60278893 0.79762191, + 0.021481305 0.6027841 0.79761517, + 0.021819288 0.57438469 0.81829458, + 0.063904583 0.57334685 0.81681681, + 0.064838618 0.54504609 0.83589518, + 0.10749498 0.54303086 0.83280385, + 0.10894299 0.51523793 0.85009485, + 0.15165198 0.51232797 0.84529388, + 0.15353702 0.48501506 0.8609221, + 0.19645104 0.4812701 0.85427517, + 0.19871596 0.45432687 0.86838883, + 0.24139188 0.44986278 0.85985661, + 0.24393812 0.4237082 0.87233341, + 0.28631106 0.4186171 0.8618502, + 0.28907594 0.39326292 0.87279981, + 0.33107609 0.3876341 0.86030716, + 0.33378798 0.36497596 0.86912489, + 0.37585285 0.35879287 0.85440171, + 0.37890881 0.33514285 0.8626166, + 0.41961601 0.32872099 0.84608799, + 0.42264509 0.30650905 0.85289121, + 0.46263474 0.29983082 0.83430851, + 0.46628106 0.27352902 0.84128714, + 0.45035499 -0.00170895 0.89284801, + 0.4500652 -0.0015550407 0.8929944, + 0.43766016 0.23316509 0.86838228, + 0.43794686 0.23312791 0.86824769, + 0.45727485 0.24042991 0.85620868, + 0.45459986 0.26272491 0.85106671, + 0.42411086 0.26712391 0.8653177, + 0.41997778 0.30039585 0.85637659, + 0.37905285 0.30630088 0.87321168, + 0.37621993 0.32949996 0.8659609, + 0.33418691 0.33518192 0.88089275, + 0.33132887 0.36026689 0.87202573, + 0.28930604 0.36550704 0.88470709, + 0.28683209 0.38932416 0.87530231, + 0.24419409 0.39409715 0.88603431, + 0.24178395 0.4202359 0.87460983, + 0.19885109 0.4244372 0.8833524, + 0.19671592 0.45135286 0.87039268, + 0.15358993 0.45488486 0.87720573, + 0.15178999 0.48260799 0.86258298, + 0.10886798 0.48536387 0.86750782, + 0.10749904 0.51338416 0.8513993, + 0.064673871 0.51529574 0.8545686, + 0.063797593 0.54379296 0.83679086, + 0.021560894 0.54477686 0.8383038, + 0.021245299 0.57373291 0.81876689, + -0.021158608 0.57373416 0.81876832, + -0.021475106 0.54511511 0.83808619, + -0.063701376 0.54413384 0.8365767, + -0.064581513 0.51568115 0.85434318, + -0.10742503 0.51376915 0.85117632, + -0.10881795 0.48532176 0.86753756, + -0.15173793 0.48256776 0.86261457, + -0.15354206 0.45481715 0.8772493, + -0.19669104 0.45128405 0.87043411, + -0.19880304 0.42469308 0.88324022, + -0.2417459 0.42048886 0.87449872, + -0.24416712 0.39424619 0.88597542, + -0.28656504 0.38950107 0.87531114, + -0.2892521 0.3634901 0.88555533, + -0.33157 0.35824201 0.87276798, + -0.33398396 0.33704698 0.8802579, + -0.37557885 0.33140087 0.86551368, + -0.37814492 0.31068495 0.87205583, + -0.4187378 0.30476484 0.8554396, + -0.42302084 0.27092692 0.86466873, + -0.4644748 0.26478687 0.84507459, + -0.46828994 0.23339197 0.85219288, + -0.42928979 0.2207429 0.87577558, + -0.44014812 0.00021337604 0.89792526, + -0.44919887 0.00021320996 0.89343178, + -0.43785116 0.22335407 0.87086129, + -0.4370451 0.22345506 0.8712402, + -0.44838285 8.1058672e-005 0.89384168, + -0.42376885 -0.015795493 0.90563267, + -0.32857913 -0.012604205 0.94439238, + -0.22968695 -0.012921398 0.97317874, + 0.24355806 0.26236406 0.93372625, + 0.21267892 0.24892291 0.94488364, + 0.2195901 0.0030685815 0.97558749, + 0.22031406 0.0030685707 0.97542423, + 0.21338101 0.248909 0.94472897, + 0.21296105 0.24893406 0.94481725, + 0.21988192 0.0030621488 0.97552162, + 0.17188808 -0.017308008 0.98496449, + 0.17918591 -0.012979894 0.98372954, + 0.151458 0.26635501 0.95190102, + 0.07278429 -0.014800498 0.99723786, + 0.077213027 -0.012737105 0.99693334, + -0.070734978 0.26215592 0.96242964, + 0.021781389 0.33328485 0.9425745, + -0.021632193 0.33328587 0.94257766, + -0.021853801 0.30265701 0.95284897, + -0.064272009 0.30210304 0.95110613, + -0.065013394 0.26340196 0.96249288, + -0.069861174 0.26582888 0.96148551, + -0.072468191 0.0034151895 0.99736488, + -0.073298216 0.0034152006 0.99730426, + -0.11739501 0.26070604 0.9582541, + -0.12159596 -0.0083419476 0.99254465, + -0.072574385 0.003526069 0.99735677, + -0.070036314 0.26216906 0.96247727, + -0.10934001 0.26579404 0.95780909, + -0.10815902 0.30241105 0.94702125, + -0.065232873 0.30354786 0.95058054, + -0.064610019 0.33298111 0.94071734, + -0.021853803 0.33359802 0.94246215, + -0.021628695 0.36400491 0.93114579, + 0.021628695 0.36400491 0.93114579, + 0.0218552 0.33338901 0.942536, + 0.064773768 0.33276784 0.94078153, + 0.10993095 0.26266789 0.9586035, + 0.10871202 0.30129305 0.94731426, + 0.065399595 0.30244097 0.95092189, + 0.065450825 0.2663801 0.96164334, + 0.064789921 0.30152512 0.95125437, + 0.021992892 0.30208689 0.95302665, + 0.022136308 0.26427108 0.96419436, + 0.021903798 0.30195698 0.95306987, + -0.021375598 0.30195996 0.95308089, + -0.021628898 0.26364997 0.96437585, + -0.021935906 0.26364905 0.96436924, + -0.022738298 -0.013895499 0.99964488, + -0.025736194 -0.012721797 0.99958777, + -0.02116769 -0.010335496 0.99972254, + -0.023914712 -0.011184006 0.99965149, + -0.023063511 0.26465112 0.96406847, + -0.020414 0.26466599 0.96412402, + 0.024466494 0.26520094 0.96388274, + 0.025374889 0.0036021783 0.99967152, + 0.025635496 0.0036021795 0.9996649, + 0.02472979 0.26348791 0.96434563, + 0.024559695 0.26348895 0.96434975, + 0.025459206 0.003642071 0.99966925, + 0.074337088 -0.010513397 0.99717778, + 0.071737401 0.26234099 0.96230501, + 0.070242174 0.26236892 0.96240765, + 0.11894903 0.26802307 0.95604122, + 0.123465 0.00342598 0.99234301, + 0.12213299 0.0034259695 0.99250787, + 0.11788396 0.26149991 0.95797765, + 0.11940003 0.26145107 0.95780325, + 0.123702 0.0032862399 0.99231398, + 0.17142595 -0.0078470977 0.98516577, + 0.16594495 0.25096595 0.95366573, + 0.16641295 0.25094494 0.95358974, + 0.19873004 0.26360804 0.94393712, + 0.19843605 0.26888207 0.94251025, + 0.15434207 0.27105111 0.9501105, + 0.15299799 0.30073696 0.94135487, + 0.10948101 0.30249003 0.9468441, + 0.10843902 0.33250308 0.93684721, + 0.065455213 0.3337591 0.94038326, + 0.064794824 0.36353013 0.92932636, + 0.021777106 0.3642101 0.93106222, + 0.021536907 0.39478216 0.91852236, + -0.021566095 0.39478192 0.91852176, + -0.021803811 0.36424619 0.93104744, + -0.0647939 0.36356699 0.92931199, + -0.065446012 0.3341971 0.94022822, + -0.10826695 0.33294684 0.93670958, + -0.10928503 0.30416411 0.94633037, + -0.15243499 0.30241996 0.94090688, + -0.19342496 0.26377493 0.94499177, + -0.24330693 0.25613394 0.93551975, + -0.24235606 0.27025905 0.93178523, + -0.19888391 0.27299887 0.94123155, + -0.19712305 0.30260405 0.93250924, + -0.15401398 0.30497694 0.93982375, + -0.15263405 0.33272311 0.93059033, + -0.10939405 0.33464715 0.93597239, + -0.108364 0.362486 0.925668, + -0.065001205 0.36386204 0.92918211, + -0.064309292 0.39382994 0.91693085, + -0.021398894 0.3945559 0.91862273, + -0.021154791 0.4248628 0.90501058, + 0.021495298 0.42485994 0.90500391, + 0.021740707 0.39505714 0.91839933, + 0.06493938 0.39431584 0.91667765, + 0.065635405 0.36472502 0.92879909, + 0.10833 0.363363 0.92532802, + 0.10941795 0.33397785 0.93620861, + 0.15280902 0.3320491 0.93080223, + 0.15424603 0.30275705 0.94050324, + 0.19774991 0.30037284 0.9330976, + 0.19948696 0.27066493 0.94177777, + 0.24318098 0.26792598 0.93224388, + 0.28856802 0.26004103 0.92147011, + 0.28801307 0.26697806 0.91965824, + 0.24453406 0.27032706 0.93119621, + 0.24235697 0.30064297 0.92242986, + 0.19968109 0.30364114 0.93162739, + 0.19788696 0.33179191 0.92236376, + 0.15432794 0.33442989 0.92969865, + 0.15283802 0.36287802 0.91921711, + 0.10943396 0.36498687 0.92455864, + 0.10832996 0.39315885 0.91306669, + 0.065176688 0.3946459 0.91651875, + 0.064447276 0.42435884 0.90319771, + 0.021710694 0.42514291 0.90486574, + 0.021448202 0.45552605 0.8899641, + -0.021413798 0.45552593 0.88996488, + -0.021675194 0.42554691 0.90467674, + -0.064421475 0.42476285 0.90300971, + -0.065154105 0.39500406 0.9163661, + -0.10835804 0.39351416 0.91291028, + -0.10950299 0.36416396 0.9248749, + -0.15288301 0.36206004 0.91953212, + -0.15428406 0.33531711 0.92938638, + -0.19736397 0.33270496 0.92214686, + -0.19908997 0.30593297 0.93100387, + -0.24171491 0.30292487 0.92185163, + -0.24389912 0.27298412 0.93058741, + -0.25707293 0.24026693 0.93604773, + -0.28847 0.25312299 0.92342502, + -0.28716284 0.26962888 0.91915059, + -0.39343214 0.22823708 0.89057231, + -0.35091498 0.23263498 0.90704989, + -0.37955201 0.244186 0.89236403, + -0.37716609 0.26766905 0.88662225, + 0.36024004 -0.0032117004 0.93285412, + 0.36055997 -0.0033856495 0.9327299, + 0.35000104 0.24025203 0.90541613, + 0.34968704 0.24028303 0.90552914, + 0.37893015 0.25361109 0.88999629, + 0.37781385 0.2644549 0.88731068, + 0.33494511 0.2691271 0.90298527, + 0.33186412 0.30047113 0.8941943, + 0.28937095 0.30489495 0.90736073, + 0.28698903 0.33057204 0.89908814, + 0.244478 0.33461699 0.91008902, + 0.24223091 0.36167887 0.90028471, + 0.19938107 0.36529711 0.90928829, + 0.197485 0.39182499 0.89859498, + 0.15423404 0.39491409 0.90567923, + 0.15260202 0.42291605 0.8932271, + 0.10930406 0.4253642 0.89839745, + 0.10804998 0.45408788 0.88438076, + 0.065233015 0.45578912 0.88769424, + 0.064419508 0.48524305 0.87200314, + 0.021954088 0.48613569 0.87360746, + 0.021664202 0.51543105 0.85665715, + -0.021284508 0.51543516 0.8566643, + -0.021575306 0.48570913 0.87385416, + -0.064057112 0.4848251 0.87226218, + -0.064856067 0.45577979 0.8877266, + -0.10801804 0.45406914 0.88439429, + -0.10927798 0.4252539 0.89845276, + -0.15229194 0.42282584 0.89332271, + -0.15392391 0.39473376 0.90581048, + -0.19721603 0.39164805 0.89873111, + -0.19917397 0.36410198 0.90981287, + -0.24233595 0.36047092 0.90074074, + -0.24433203 0.33646104 0.90944815, + -0.28666884 0.33241487 0.89851058, + -0.28894496 0.30822796 0.90636986, + -0.33079204 0.30383602 0.89345413, + -0.333931 0.27242401 0.902372, + -0.33398303 0.24886203 0.90913314, + -0.33216003 0.26896703 0.90406114, + -0.28897801 0.272991 0.917588, + -0.28635204 0.30336502 0.90883011, + -0.24403597 0.30705097 0.91987288, + -0.24202494 0.3324579 0.91153479, + -0.19922891 0.33577585 0.92063159, + -0.19749504 0.36140209 0.91125423, + -0.15430902 0.36424804 0.91842914, + -0.15272799 0.39294094 0.90679187, + -0.10953801 0.39521307 0.91203511, + -0.10834903 0.42395008 0.89918125, + -0.065008476 0.42555887 0.90259272, + -0.064244024 0.45497215 0.88818532, + -0.021633394 0.45580688 0.88981575, + -0.021360498 0.48544195 0.87400788, + 0.021396499 0.48544201 0.87400699, + 0.021667108 0.45580614 0.88981527, + 0.064604983 0.45496088 0.88816476, + 0.065370992 0.42561093 0.90254188, + 0.10834105 0.4240132 0.8991524, + 0.109545 0.39490899 0.912166, + 0.15271701 0.39264005 0.90692413, + 0.15424192 0.36503083 0.91812956, + 0.19743992 0.36217889 0.91095769, + 0.19933191 0.33416384 0.92119557, + 0.24229509 0.33084613 0.91204929, + 0.2443741 0.30422613 0.92072135, + 0.28704515 0.30053514 0.90955144, + 0.28964296 0.27001396 0.91825891, + 0.33334112 0.26597208 0.90451229, + 0.33416191 0.25701594 0.90679574, + 0.30547315 0.24360812 0.92051142, + 0.31496108 0.0021205305 0.94910222, + 0.31359816 0.0021204809 0.94955349, + 0.30416703 0.24341403 0.92099512, + 0.30475587 0.24336392 0.92081362, + 0.31420189 0.0021752494 0.94935364, + 0.26719192 -0.021127593 0.96341163, + 0.25900894 0.24643195 0.93390876, + 0.25918013 0.24642012 0.93386441, + 0.267423 -0.00542454 0.96356398, + 0.27953911 -0.012537706 0.96005249, + -0.12836005 -0.013161205 0.99164033, + -0.12170202 -0.016708503 0.9924261, + -0.11751001 0.26070204 0.95824111, + -0.15411498 0.26536593 0.95175076, + -0.16402905 0.25931305 0.95176226, + -0.16983804 0.0030476006 0.98546726, + -0.17112106 0.0030476011 0.98524535, + -0.16527294 0.25920391 0.95157665, + -0.16390395 0.25926495 0.95179677, + -0.16970599 0.0030946196 0.9854899, + -0.21848097 -0.005975639 0.97582287, + -0.2118839 0.24395189 0.94635755, + -0.211714 0.243962 0.94639301, + -0.21826503 -0.020309802 0.97567815, + -0.26576799 0.0024167399 0.96403402, + -0.25796694 0.24051194 0.93573874, + -0.25921592 0.24042591 0.93541563, + -0.267048 0.0024883801 0.96368003, + -0.26482996 0.0024884297 0.96429187, + -0.3127681 -0.0037149009 0.94982225, + -0.30389386 0.23653989 0.92287457, + -0.30425987 0.2365099 0.92276162, + -0.3130531 -0.024086706 0.94943023, + -0.358978 0.0013712 0.93334502, + -0.34917608 0.23209406 0.90785927, + -0.34864098 0.23214497 0.90805191, + -0.35843283 0.0013060094 0.93355459, + -0.36081398 0.0013061499 0.93263686, + -0.40409681 -0.0017560492 0.91471457, + -0.40480116 -0.0021311706 0.91440231, + -0.39412516 0.22816108 0.89028531, + -0.42397505 0.23928003 0.87349313, + -0.42094493 0.26635796 0.86709785, + -0.37912384 0.2717199 0.88455272, + -0.37537086 0.30477187 0.87533468, + -0.33386001 0.30994999 0.89020699, + -0.33144587 0.33206087 0.88310772, + -0.289121 0.33692399 0.89604199, + -0.28691801 0.35929799 0.88802201, + -0.24424689 0.36370781 0.89892161, + -0.24191099 0.390517 0.88824302, + -0.19898407 0.39442316 0.89712632, + -0.19692691 0.4218238 0.88503361, + -0.15386695 0.42512485 0.89196068, + -0.15216003 0.45285511 0.87850422, + -0.10903598 0.45545793 0.88355488, + -0.10772198 0.48386994 0.86848485, + -0.064725727 0.48568124 0.87173641, + -0.063876912 0.51480514 0.8549242, + -0.021536199 0.51573902 0.856475, + -0.021234194 0.54483289 0.83827585, + 0.021605497 0.54482895 0.83826888, + 0.021911012 0.51572925 0.85647142, + 0.064264305 0.51478708 0.85490614, + 0.06510222 0.48611718 0.87146533, + 0.10806298 0.48429793 0.86820388, + 0.10938003 0.45590413 0.88328224, + 0.15246902 0.45329413 0.87822425, + 0.15419897 0.4252499 0.89184374, + 0.19722192 0.42194384 0.8849107, + 0.19927795 0.39463991 0.89696574, + 0.24215905 0.3907311 0.88808125, + 0.24438497 0.36532298 0.89822888, + 0.28675097 0.36092496 0.88741589, + 0.289318 0.33482999 0.89676303, + 0.3315329 0.33000687 0.88384467, + 0.33420208 0.30512506 0.89174426, + 0.37608001 0.29997301 0.87668699, + 0.37961382 0.26820588 0.8854146, + 0.42216679 0.26280588 0.86758757, + 0.42368516 0.24944009 0.87078732, + 0.39468718 0.23709811 0.8876974, + 0.40627179 0.0011150294 0.9137516, + 0.40508717 0.0011149705 0.91427743, + 0.39356595 0.23680598 0.88827288, + 0.39422783 0.23672988 0.88799959, + 0.40576118 0.0012114305 0.9139784, + 0.37664905 -0.015638402 0.92622411, + 0.46988511 -0.015909504 0.88258421, + 0.49338505 -7.5152304e-005 0.86981112, + 0.48030683 0.22871792 0.84675473, + 0.48061511 0.22867206 0.84659219, + 0.49369699 8.9267e-005 0.86963397, + 0.49246082 -0.00012900896 0.87033468, + 0.47945875 0.2282749 0.84735459, + 0.48004106 0.22818904 0.8470481, + 0.47562829 0.26412815 0.83905548, + 0.49733913 0.26049805 0.82752317, + 0.50898123 0.27170312 0.81677139, + 0.50477731 0.29956719 0.80960447, + 0.46556383 0.30711988 0.83001667, + 0.46241206 0.32805103 0.82374614, + 0.42252186 0.33533487 0.84203672, + 0.41932186 0.35751387 0.83447772, + 0.37861115 0.36449111 0.85076427, + 0.37564006 0.38634405 0.84239709, + 0.33390689 0.39294684 0.85679573, + 0.33092716 0.41658321 0.84672642, + 0.2886771 0.42266214 0.85908228, + 0.28580803 0.44759205 0.84733415, + 0.243412 0.45302701 0.85762298, + 0.24072094 0.47919887 0.84405082, + 0.19828591 0.48391375 0.8523556, + 0.19595605 0.51010913 0.8374902, + 0.15295997 0.5140729 0.84399784, + 0.15098701 0.54113507 0.82727009, + 0.10842295 0.54418379 0.83193058, + 0.10689797 0.57183284 0.81337571, + 0.064408585 0.5739339 0.81636482, + 0.063451611 0.60137808 0.79644114, + 0.021183206 0.60245711 0.79787016, + 0.0208463 0.63029599 0.77607501, + -0.020727707 0.63029724 0.77607727, + -0.021066295 0.60276085 0.79764384, + -0.063039877 0.60169578 0.79623371, + -0.064018101 0.57357597 0.81664699, + -0.10656402 0.57148206 0.81366611, + -0.10806305 0.54420525 0.83196342, + -0.15061703 0.54116613 0.82731718, + -0.15259095 0.51405483 0.84407568, + -0.19561698 0.51009697 0.83757687, + -0.19797805 0.48349613 0.85266417, + -0.24072503 0.47875407 0.84430212, + -0.24337997 0.45292693 0.85768491, + -0.2857959 0.44749084 0.84739172, + -0.28863394 0.42284691 0.85900581, + -0.33063012 0.41680515 0.84673327, + -0.33368108 0.39257509 0.85705417, + -0.37546185 0.38597485 0.8426457, + -0.37862286 0.36259788 0.85156769, + -0.41960293 0.35560697 0.8351509, + -0.4221848 0.33772886 0.84124857, + -0.46191093 0.33043298 0.82307488, + -0.46459717 0.31290713 0.82839531, + -0.50374085 0.30525088 0.80812567, + -0.50938219 0.26811609 0.81770629, + -0.54929888 0.26035395 0.7940318, + -0.55521214 0.21728905 0.80282319, + -0.55960387 0.21882294 0.79934984, + -0.57350284 0.0011984796 0.81920272, + -0.57503682 0.0011984195 0.81812668, + -0.56255811 0.20720205 0.80037218, + -0.56221914 0.20726104 0.80059516, + -0.57469815 0.0013878505 0.81836432, + -0.60016102 -0.0155575 0.79972798, + -0.67918408 -0.015077402 0.73381305, + -0.65155917 0.0026777808 0.7585932, + -0.63890219 0.19616105 0.74385816, + -0.67609197 0.19017898 0.71185094, + -0.68865067 -0.0053217676 0.72507364, + -0.72638702 0.0036903501 0.68727601, + -0.71476305 0.17822202 0.67627704, + -0.71186507 0.17897801 0.67912805, + -0.72354478 0.0030528789 0.69027078, + -0.72341192 0.0030529096 0.69040996, + -0.71174055 0.17893289 0.67927057, + -0.71319091 0.18291798 0.67668295, + -0.70378661 0.24336985 0.66742456, + -0.66859621 0.25474805 0.6986292, + -0.6596092 0.30129707 0.68857521, + -0.62535292 0.31281498 0.71489894, + -0.62268198 0.325737 0.71145099, + -0.58731395 0.33692896 0.73589492, + -0.58523196 0.34728396 0.73273295, + -0.54814291 0.35821292 0.7557928, + -0.54470384 0.37585586 0.74968678, + -0.50636995 0.38647294 0.77086186, + -0.50286794 0.40493795 0.76364189, + -0.4638648 0.41502979 0.78267467, + -0.46022594 0.43489093 0.77399087, + -0.42035279 0.44447178 0.79104263, + -0.41657707 0.46596906 0.78060013, + -0.3761051 0.47492713 0.7956062, + -0.37243003 0.49697405 0.78378111, + -0.33079597 0.50535095 0.79699087, + -0.32713699 0.52883399 0.78314501, + -0.28541991 0.53634679 0.79427171, + -0.28195617 0.56050038 0.77867848, + -0.24050006 0.56705612 0.78778619, + -0.23725009 0.59217823 0.77008927, + -0.195124 0.597866 0.77748501, + -0.19230597 0.62290597 0.7582919, + -0.15011908 0.62756032 0.76395833, + -0.14777394 0.65280277 0.74297476, + -0.105891 0.65633798 0.74699903, + -0.10409695 0.68176669 0.72412562, + -0.06279517 0.6841377 0.72664464, + -0.061653115 0.70940816 0.70209616, + -0.020532507 0.71061021 0.70328623, + -0.020134391 0.73544365 0.67728668, + 0.020578295 0.7354368 0.67728084, + 0.020979101 0.71063101 0.70325202, + 0.061814591 0.70942795 0.70206195, + 0.062951013 0.6841622 0.72660816, + 0.10450498 0.68176782 0.72406584, + 0.10630204 0.65633625 0.74694222, + 0.14815101 0.65279204 0.74290907, + 0.15049706 0.62757826 0.76386929, + 0.19267397 0.62291396 0.75819188, + 0.19549395 0.59787285 0.77738684, + 0.23732603 0.59221804 0.77003515, + 0.24057303 0.56709903 0.78773314, + 0.28227606 0.56049812 0.77856416, + 0.285739 0.53636003 0.79414803, + 0.327447 0.52883899 0.78301197, + 0.33104897 0.50574493 0.79663587, + 0.37264198 0.49736395 0.7834329, + 0.37631807 0.47535306 0.79525113, + 0.41676685 0.46638581 0.78024971, + 0.42060506 0.44456506 0.79085612, + 0.46020612 0.4350431 0.7739172, + 0.46379805 0.41545606 0.78248811, + 0.50300598 0.40529999 0.76335901, + 0.50654995 0.38663995 0.77065986, + 0.54463804 0.37608406 0.74962008, + 0.54764605 0.36073703 0.75495213, + 0.58472294 0.34975198 0.73196495, + 0.58810806 0.33287403 0.73710507, + 0.62341213 0.32180709 0.71259916, + 0.62662482 0.30592394 0.71676481, + 0.66127682 0.29446995 0.68992782, + 0.66964304 0.25005102 0.69932306, + 0.70491308 0.23880903 0.66788304, + 0.70966774 0.20985493 0.67255676, + 0.74462605 0.19881803 0.63718408, + 0.74898463 0.16776192 0.64099771, + 0.74549484 0.17725995 0.64250779, + 0.75748652 0.0030624082 0.65284359, + 0.78796935 -0.016691407 0.61548829, + 0.77887511 0.15238501 0.60838509, + 0.77941167 0.15221594 0.60773975, + 0.78857535 -0.008142774 0.61488432, + 0.81731981 0.0033081493 0.57617486, + 0.80945146 0.1384621 0.57062835, + 0.8101095 0.1382331 0.56974936, + 0.80993301 0.138015 0.57005298, + 0.81775367 0.0034726288 0.57555783, + 0.84459019 -0.013535103 0.53524214, + 0.838117 0.124299 0.53114003, + 0.81198281 0.15895596 0.56161988, + 0.80912089 0.17940699 0.55958593, + 0.77798462 0.19181491 0.59828669, + 0.77228671 0.22601293 0.59370977, + 0.74072284 0.23901194 0.62785584, + 0.73084176 0.28810892 0.61875975, + 0.69893342 0.30188617 0.64834934, + 0.69570082 0.31638291 0.64490479, + 0.662341 0.32997999 0.67262, + 0.65935391 0.34329596 0.66887993, + 0.62501007 0.35643902 0.69448805, + 0.62230241 0.36864325 0.69053745, + 0.58669496 0.38137394 0.71438295, + 0.58334213 0.39675209 0.70873117, + 0.54649204 0.40908006 0.73075306, + 0.54283029 0.42618826 0.72367042, + 0.50471902 0.43808401 0.74386901, + 0.50081909 0.45674607 0.73523009, + 0.46199313 0.46800211 0.7533502, + 0.45799807 0.48770005 0.74322706, + 0.41830108 0.49831912 0.75940919, + 0.41423985 0.5191468 0.74759078, + 0.37408897 0.52897197 0.7617389, + 0.3699348 0.55131263 0.74779856, + 0.32885703 0.56040508 0.76013112, + 0.3248761 0.58316612 0.74456215, + 0.28343081 0.59132767 0.75498253, + 0.27960399 0.61501801 0.737275, + 0.23834798 0.62210494 0.74577194, + 0.23488912 0.6457743 0.72650033, + 0.19322009 0.6518423 0.73332638, + 0.19016191 0.67583472 0.71209967, + 0.14866598 0.68074596 0.71727496, + 0.14607802 0.70518506 0.69381207, + 0.10487495 0.70890063 0.69746763, + 0.10297198 0.73243785 0.67300183, + 0.062034771 0.73493361 0.67529571, + 0.06081517 0.75855166 0.64876872, + 0.02058289 0.75979763 0.64983368, + 0.020157102 0.78279114 0.62195808, + -0.019688806 0.78279817 0.6219641, + -0.02011141 0.75977737 0.6498723, + -0.060593806 0.75853413 0.64881009, + -0.06180983 0.73512834 0.67510432, + -0.10277701 0.73263603 0.67281604, + -0.10470496 0.70886374 0.69753075, + -0.14590903 0.70515317 0.6938802, + -0.14847592 0.68098056 0.71709156, + -0.18999691 0.67606968 0.71192062, + -0.19305997 0.65209496 0.73314393, + -0.234743 0.64602798 0.726322, + -0.23825309 0.62204623 0.74585122, + -0.27925295 0.6150099 0.73741484, + -0.28308314 0.59129131 0.75514138, + -0.3245779 0.5831309 0.7447198, + -0.32855085 0.56040078 0.76026666, + -0.36964697 0.55131394 0.74793994, + -0.37380004 0.52896708 0.76188409, + -0.4141919 0.51908988 0.74765682, + -0.41832986 0.49785781 0.75969571, + -0.45783111 0.48730311 0.74359018, + -0.46183118 0.46754318 0.75373429, + -0.50067097 0.45629993 0.73560792, + -0.50458318 0.43754014 0.74428123, + -0.54294115 0.42558315 0.72394323, + -0.54649889 0.40894091 0.73082584, + -0.58336073 0.39661282 0.70879364, + -0.58666992 0.38143295 0.71437192, + -0.62212813 0.36875808 0.69063318, + -0.62544006 0.35375202 0.69547409, + -0.65997583 0.34061092 0.66963881, + -0.66150922 0.33378911 0.67155826, + -0.69477004 0.32012302 0.64406204, + -0.69720197 0.30945697 0.64664197, + -0.72898793 0.29549298 0.61746293, + -0.73974741 0.24337316 0.62733036, + -0.7712751 0.23021303 0.59341109, + -0.7812351 0.16719702 0.60142905, + -0.77767497 0.157626 0.608585, + -0.78751481 0.003482349 0.61628586, + -0.78762901 0.0034823399 0.61614001, + -0.77778286 0.15766498 0.60843694, + -0.77770281 0.15768996 0.60853291, + -0.7875517 0.0034635989 0.61623877, + -0.75637269 -0.0076799071 0.65409577, + -0.74557436 0.16854407 0.64475727, + -0.74491417 0.16873404 0.6454702, + -0.7556392 -0.017130204 0.65476418, + -0.75105089 -0.013849298 0.66009897, + -0.99457777 -0.015670497 -0.10280798, + -0.99741054 0.0010972095 -0.071909361, + -0.99707186 -0.026079597 -0.071884893, + -0.99350226 -0.013831904 -0.11296903, + -0.99187547 -0.04008292 -0.12073306, + -0.99266863 -0.0030732388 -0.12082896, + -0.99267924 -0.0030928208 -0.12074103, + -0.99188685 -0.040064596 -0.12064499, + -0.98551124 -0.013712004 -0.16905504, + -0.98560154 0.0021237291 -0.16907093, + -0.98556024 0.0021237005 -0.16931204, + -0.98552126 0.0020443304 -0.16954005, + -0.9787451 -0.015125101 -0.20452203, + -0.95253688 -0.014363798 -0.30408397, + -0.964261 0.00294053 -0.264938, + -0.96177924 -0.071756117 -0.26425707, + -0.95364237 -0.038588915 -0.29845813, + -0.94695026 -0.080954425 -0.31101707, + -0.95004123 -0.0075976318 -0.31203207, + -0.94998038 -0.0075200428 -0.31221911, + -0.94688636 -0.080990627 -0.31120211, + -0.93313611 -0.033235203 -0.35798404, + -0.93364638 0.0033985111 -0.35818011, + -0.93358886 0.0033985095 -0.35832998, + -0.9336459 0.0034300496 -0.35818097, + -0.9148643 -0.014466505 -0.40350214, + -0.91074777 -0.095847979 -0.40168592, + -0.91062558 -0.095898554 -0.40195081, + -0.91479522 -0.010130903 -0.4037911, + -0.9162659 -0.011756798 -0.40039793, + -0.87021083 -0.012501597 -0.49252087, + -0.87107301 -0.0133211 -0.490973, + -0.86613011 -0.10719702 -0.48818806, + -0.84349459 -0.072613366 -0.53220677, + -0.84572184 0.003586919 -0.53361189, + -0.84587461 0.0035868983 -0.53336978, + -0.84580386 0.0035668795 -0.53348196, + -0.81873149 -0.0085272444 -0.57411337, + -0.81349087 -0.11328299 -0.57043797, + -0.81299883 -0.11340497 -0.5711149, + -0.81817132 -0.016095005 -0.57474917, + -0.81496912 -0.013465302 -0.57934809, + -0.67918003 -0.0154055 -0.73381001, + -0.65527523 0.0012269205 -0.75538927, + -0.64906824 -0.13731705 -0.74823421, + -0.64849603 -0.13740002 -0.74871504, + -0.65470439 0.0015743909 -0.75588346, + -0.65396941 0.0015744109 -0.7565195, + -0.61762476 -0.0018248193 -0.78647071, + -0.61680412 -0.0019916105 -0.7871142, + -0.61030525 -0.14479305 -0.77882129, + -0.61112666 -0.14468691 -0.77819651, + -0.65005904 -0.10920201 -0.7519961, + -0.64539433 -0.11631705 -0.75494134, + -0.61409098 -0.32821399 -0.71775198, + -0.65424728 -0.31450915 -0.68778235, + -0.57560706 -0.55168104 -0.60359305, + -0.5141269 -0.6797598 -0.52306789, + -0.51602405 -0.67885607 -0.52237308, + -0.60039186 -0.51681989 -0.61026788, + -0.62012696 -0.50699395 -0.59866494, + -0.50518888 -0.71384984 -0.48497689, + -0.52830487 -0.70230782 -0.47713488, + -0.40095392 -0.8433218 -0.35783291, + -0.41556308 -0.82709718 -0.3784411, + -0.36546791 -0.86546582 -0.34263992, + -0.46290919 -0.77035332 -0.43848714, + -0.44217595 -0.77949786 -0.44369295, + -0.51367998 -0.68400502 -0.51794797, + -0.49227619 -0.69393623 -0.52546817, + -0.57596886 -0.53586286 -0.61734188, + -0.55612576 -0.54479474 -0.62763268, + -0.46864021 -0.70927036 -0.52660424, + -0.48944601 -0.70015299 -0.519835, + -0.4182609 -0.7935248 -0.44201389, + -0.43842494 -0.78517389 -0.43736193, + -0.34919187 -0.8712557 -0.34493288, + -0.36159492 -0.85816681 -0.36441591, + -0.31778201 -0.88899899 -0.32969001, + -0.41409501 -0.79978502 -0.434591, + -0.39414883 -0.80752861 -0.43879879, + -0.46647605 -0.71404606 -0.52205205, + -0.44637686 -0.72236979 -0.5281378, + -0.53275579 -0.56157583 -0.63309073, + -0.51293093 -0.56964594 -0.64218795, + -0.4244639 -0.7348268 -0.52901787, + -0.444267 -0.72707599 -0.52343798, + -0.3712571 -0.82033116 -0.43500009, + -0.39020118 -0.81343943 -0.43134621, + -0.30302805 -0.89351624 -0.33136508, + -0.31327608 -0.88303721 -0.34943309, + -0.18864508 -0.96078837 -0.20322107, + -0.21176307 -0.95616639 -0.20224307, + -0.098227397 -0.99171197 -0.082817502, + -0.11297503 -0.99015123 -0.082687125, + 0.014121798 -0.99921089 0.037124995, + 0.010787704 -0.99925238 0.037126515, + 0.148432 -0.97700799 0.153047, + 0.15893096 -0.97539479 0.15279397, + 0.26811093 -0.93439174 0.23458195, + 0.29032296 -0.92812687 0.23300897, + 0.36241683 -0.88872457 0.28075388, + 0.386917 -0.87928301 0.277771, + 0.31812984 -0.91776556 0.23769689, + 0.2911649 -0.92611563 0.23985991, + 0.23240492 -0.94962466 0.21023993, + 0.18204105 -0.96004426 0.21254705, + 0.11299197 -0.97681361 0.18184593, + 0.030845501 -0.98264199 0.18292999, + -0.044997901 -0.98734301 0.152082, + -0.16536696 -0.97473675 0.15013997, + -0.23355509 -0.96450037 0.12325204, + -0.38554186 -0.91524768 0.11695796, + -0.43293709 -0.89615321 0.097339921, + -0.59368795 -0.79998988 0.086894691, + -0.61649531 -0.78367835 0.076038741, + -0.75920337 -0.64781129 0.062855832, + -0.76423889 -0.64215195 0.059831392, + -0.8735016 -0.48472175 0.045163076, + -0.87086111 -0.48924205 0.047362007, + -0.94358522 -0.3295891 0.031906508, + -0.94002974 -0.33913592 0.036480993, + -0.981911 -0.18825699 0.020250799, + -0.98007548 -0.19709209 0.02463451, + -0.9981935 -0.05961797 0.0074516363, + -0.99795848 -0.063180529 0.0093361847, + -0.99831134 0.057467122 -0.0084919231, + -0.99805367 0.061422877 -0.010772496, + -0.98523664 0.16862394 -0.02957359, + -0.98281455 0.18078192 -0.03733008, + -0.96042877 0.27277094 -0.056325085, + -0.95364326 0.29256305 -0.070509411, + -0.92458814 0.37036404 -0.089259811, + -0.91169846 0.39583477 -0.11009394, + -0.87858188 0.46012595 -0.12797599, + -0.85828018 0.48905313 -0.15550603, + -0.82422781 0.53963488 -0.17158896, + -0.80927187 0.55589992 -0.18987997, + -0.76543182 0.60897189 -0.20800796, + -0.76026881 0.61340487 -0.21383595, + -0.71799165 0.6572597 -0.22912389, + -0.71120608 0.66200006 -0.23652004, + -0.67062956 0.69854659 -0.24957685, + -0.66250908 0.70312005 -0.25827104, + -0.62438095 0.73321992 -0.26932698, + -0.6145829 0.73757482 -0.27976993, + -0.57902902 0.76231003 -0.289152, + -0.56763017 0.76614028 -0.30137211, + -0.53419477 0.78668565 -0.30945385, + -0.52723312 0.78834915 -0.3170661, + -0.50627297 0.80008799 -0.321787, + -0.51619303 0.7983591 -0.31010902, + -0.50529581 0.80439371 -0.31245288, + -0.50305504 0.8046881 -0.31529802, + -0.51984596 0.79538286 -0.31165096, + -0.52244025 0.79511833 -0.30796614, + -0.53394479 0.78844464 -0.30538186, + -0.53307277 0.78849864 -0.30676284, + -0.54082882 0.7838977 -0.30497289, + -0.53978407 0.7839061 -0.30679703, + -0.53510702 0.78668201 -0.30788299, + -0.53686923 0.78681034 -0.30446815, + -0.51898605 0.79717809 -0.30848104, + -0.52016884 0.79739571 -0.30591589, + -0.499749 0.80869901 -0.31025299, + -0.50011504 0.80881214 -0.30936703, + -0.477148 0.82082701 -0.313963, + -0.4793857 0.82181555 -0.30790982, + -0.45348421 0.83460742 -0.31270215, + -0.46256882 0.83972371 -0.28441891, + -0.43394506 0.85332114 -0.28902403, + -0.441937 0.85873097 -0.25937, + -0.41080385 0.87278169 -0.26361391, + -0.41723484 0.87793672 -0.23482391, + -0.38385901 0.89203399 -0.23859499, + -0.38895494 0.89686185 -0.21060097, + -0.353071 0.91082197 -0.213879, + -0.35706297 0.9152959 -0.18638499, + -0.31866398 0.92880589 -0.18913697, + -0.32169387 0.93284565 -0.16220994, + -0.28149214 0.94537747 -0.16438907, + -0.28371799 0.94893998 -0.13790201, + -0.24189106 0.96021724 -0.13954103, + -0.24345709 0.96327436 -0.11327504, + -0.20012605 0.97306526 -0.11442703, + -0.201148 0.97556502 -0.0883881, + -0.15652095 0.98364562 -0.089120172, + -0.157112 0.98554403 -0.063394099, + -0.11201403 0.99165726 -0.063787311, + -0.11229496 0.99293965 -0.038218085, + -0.067367531 0.99765849 -0.011797305, + -0.067278802 0.99699599 -0.038374301, + -0.022526098 0.99966788 -0.012520798, + -0.0224967 0.99901003 -0.038379099, + -0.06707523 0.9970125 -0.038302317, + -0.066907577 0.99571264 -0.063872777, + -0.11153602 0.99172211 -0.063616805, + -0.11111603 0.98978722 -0.089300819, + -0.15552692 0.98383552 -0.088763855, + -0.15473497 0.98127174 -0.11472997, + -0.19843492 0.97348267 -0.11381996, + -0.19715695 0.97033077 -0.13995497, + -0.23929197 0.96100289 -0.13860999, + -0.23740809 0.95730335 -0.16494806, + -0.27790704 0.94665813 -0.16311401, + -0.27528098 0.94243187 -0.18984897, + -0.31398287 0.93073165 -0.18749194, + -0.31046596 0.92601585 -0.21472196, + -0.3471489 0.91357172 -0.21183592, + -0.3425869 0.90843779 -0.23953094, + -0.37668186 0.89572871 -0.2361799, + -0.3708739 0.89019775 -0.26457593, + -0.40225101 0.87758899 -0.260829, + -0.39496514 0.87171429 -0.29002908, + -0.4239901 0.85935116 -0.28591606, + -0.41567487 0.85370469 -0.31369188, + -0.442182 0.84188902 -0.309351, + -0.44046614 0.84095931 -0.31428811, + -0.46400911 0.82977617 -0.31010807, + -0.46416107 0.82983613 -0.30972004, + -0.48479199 0.819417 -0.30583099, + -0.48426929 0.81927949 -0.30702516, + -0.50211728 0.80980349 -0.30347419, + -0.50109392 0.80965489 -0.30555496, + -0.50667483 0.80660868 -0.30440587, + -0.51012081 0.80680072 -0.29807588, + -0.48090929 0.8224355 -0.30385217, + -0.48297393 0.8226679 -0.29992297, + -0.46752393 0.83050889 -0.30278096, + -0.46789321 0.83059043 -0.30198616, + -0.44969222 0.83942342 -0.30519715, + -0.44964999 0.83940899 -0.30529901, + -0.42850792 0.84911984 -0.30883095, + -0.42789605 0.84881812 -0.31050402, + -0.40357494 0.8592599 -0.31432396, + -0.40483785 0.86008769 -0.31041187, + -0.37813401 0.87077498 -0.31426999, + -0.38563886 0.87684971 -0.28708392, + -0.35634208 0.88797426 -0.29072705, + -0.36289597 0.89424789 -0.26196796, + -0.3307659 0.90565175 -0.26530895, + -0.33593512 0.91150331 -0.23729609, + -0.30103707 0.92285222 -0.24025106, + -0.30504385 0.92824459 -0.2128619, + -0.26801494 0.93904078 -0.21533796, + -0.27104995 0.94395274 -0.18837495, + -0.232081 0.953888 -0.190358, + -0.23429289 0.95825851 -0.16385193, + -0.19341391 0.96708155 -0.16536093, + -0.19494903 0.97088909 -0.13917401, + -0.15239002 0.97832012 -0.14023902, + -0.15337892 0.9815405 -0.11424994, + -0.10987201 0.98728013 -0.11491802, + -0.11043403 0.98988521 -0.089060023, + -0.066343583 0.99378276 -0.089410678, + -0.066594079 0.99574065 -0.063762575, + -0.02227411 0.9977085 -0.063888729, + -0.0223301 0.99901599 -0.0383211, + 0.022103701 0.99902099 -0.038321301, + 0.022046989 0.99771255 -0.063902669, + 0.066332318 0.99575722 -0.063777417, + 0.066078819 0.99379337 -0.089489833, + 0.11006895 0.98991853 -0.089140855, + 0.109506 0.98731703 -0.11495, + 0.15302092 0.98159254 -0.11428295, + 0.15203293 0.97837853 -0.14021894, + 0.194593 0.970963 -0.139156, + 0.19305505 0.96715623 -0.16534404, + 0.23397709 0.95833838 -0.16383606, + 0.23176093 0.95396578 -0.19035795, + 0.27076206 0.94403523 -0.18837604, + 0.26772308 0.93912536 -0.21533208, + 0.30480394 0.92832476 -0.21285595, + 0.30080599 0.92294103 -0.240199, + 0.33566812 0.91161329 -0.23725109, + 0.33050811 0.90578532 -0.26517409, + 0.36265001 0.89438599 -0.26183701, + 0.3561579 0.88818777 -0.29029995, + 0.38558707 0.87701511 -0.28664804, + 0.37807709 0.87095219 -0.31384709, + 0.404982 0.86018097 -0.30996501, + 0.40358007 0.85926312 -0.31430903, + 0.42780009 0.84886616 -0.31050506, + 0.42842993 0.84917587 -0.30878496, + 0.44970301 0.839405 -0.30523199, + 0.44974694 0.8394199 -0.30512598, + 0.46788222 0.83061844 -0.30192614, + 0.4674978 0.83053356 -0.30275387, + 0.48302317 0.82265431 -0.29988113, + 0.48176381 0.82251471 -0.30227989, + 0.48439777 0.8211506 -0.30177885, + 0.48816401 0.82125598 -0.29535499, + 0.45968482 0.83568168 -0.30054289, + 0.46228194 0.83589488 -0.29593098, + 0.44924489 0.84218782 -0.29815894, + 0.44978687 0.84228581 -0.29706293, + 0.43408716 0.84958029 -0.29963613, + 0.43388274 0.84951955 -0.30010381, + 0.41506594 0.85783786 -0.30304196, + 0.41452619 0.8576014 -0.30444714, + 0.39257005 0.86672813 -0.30768704, + 0.39157394 0.8661319 -0.31062096, + 0.36695603 0.87563109 -0.31402802, + 0.36793789 0.87639672 -0.31072587, + 0.34082508 0.88608223 -0.31416008, + 0.34752217 0.89249343 -0.28754815, + 0.31736201 0.902614 -0.29080799, + 0.32312986 0.90914661 -0.26275387, + 0.29020202 0.91934013 -0.26570004, + 0.29471713 0.92543137 -0.23815709, + 0.25948504 0.93527311 -0.24069002, + 0.26292512 0.94085348 -0.21369411, + 0.22555092 0.95003462 -0.21577993, + 0.22810701 0.95509702 -0.18909501, + 0.18865103 0.96334511 -0.19072802, + 0.1904529 0.96782655 -0.16443692, + 0.14915898 0.97484291 -0.16562898, + 0.15034498 0.97872388 -0.13962798, + 0.10777895 0.98420954 -0.14041094, + 0.10847902 0.98747212 -0.11459102, + 0.065209493 0.99121988 -0.11502598, + 0.065545127 0.99384546 -0.089303643, + 0.021858405 0.99574924 -0.089474723, + 0.021942105 0.99771726 -0.063866317, + -0.022208607 0.99771136 -0.063866019, + -0.022126393 0.99574566 -0.089448571, + -0.065956675 0.99382067 -0.089275673, + -0.065622672 0.99119455 -0.11500895, + -0.10888299 0.98742986 -0.11457199, + -0.10818294 0.9841615 -0.14043695, + -0.15071297 0.97866374 -0.13965297, + -0.14953005 0.97478235 -0.16565105, + -0.19081903 0.96775115 -0.16445601, + -0.18902092 0.96326953 -0.19074291, + -0.22846194 0.95500976 -0.18910696, + -0.22590996 0.94994587 -0.21579497, + -0.26324302 0.94076115 -0.21370903, + -0.25980192 0.93516463 -0.24076991, + -0.29502299 0.92531401 -0.238234, + -0.29050601 0.91920799 -0.265825, + -0.32336211 0.90902728 -0.2628811, + -0.31755412 0.90243328 -0.29115909, + -0.34751582 0.89237756 -0.28791484, + -0.34081197 0.8859539 -0.31453598, + -0.36785182 0.87629759 -0.31110686, + -0.36697999 0.87561703 -0.31403899, + -0.39156708 0.86612916 -0.31063706, + -0.39256409 0.86672717 -0.30769706, + -0.41449395 0.85761189 -0.30446097, + -0.41501099 0.85783798 -0.30311701, + -0.433826 0.84952199 -0.300179, + -0.43404499 0.84958702 -0.299678, + -0.44981313 0.8422612 -0.29709306, + -0.44845301 0.842013 -0.29984, + -0.47419989 0.82939982 -0.29534793, + -0.47083917 0.82908529 -0.30154312, + -0.48559582 0.82103968 -0.30015087, + -0.48648924 0.82106644 -0.29862714, + -0.50041515 0.81099117 -0.30311406, + -0.50087893 0.81073987 -0.30301997, + -0.50234914 0.81073821 -0.30058107, + -0.49204889 0.8162728 -0.30263293, + -0.49054405 0.81634313 -0.30487803, + -0.47558177 0.82407659 -0.30776584, + -0.47791883 0.82388669 -0.30463788, + -0.46463713 0.8330512 -0.30023006, + -0.46186018 0.8332063 -0.30406013, + -0.47621289 0.82604581 -0.30144593, + -0.47857806 0.82599813 -0.29780903, + -0.46217018 0.83552128 -0.29715812, + -0.46158788 0.83580685 -0.29725993, + -0.46410093 0.83599788 -0.29277596, + -0.42690316 0.85347229 -0.29889613, + -0.43063906 0.85403413 -0.29184902, + -0.44113612 0.8492232 -0.29020506, + -0.43603286 0.84893572 -0.29863587, + -0.46421081 0.83553469 -0.29392189, + -0.451994 0.84018499 -0.299651, + -0.44799986 0.84208071 -0.30032688, + -0.45038801 0.84200901 -0.29693699, + -0.4371489 0.85055584 -0.29232794, + -0.43599895 0.85056388 -0.29401696, + -0.42435586 0.85580772 -0.29582989, + -0.4289071 0.85601616 -0.28857407, + -0.4072901 0.8654452 -0.29175207, + -0.41113186 0.8658917 -0.28495991, + -0.39993593 0.87060988 -0.28651297, + -0.39965305 0.8705501 -0.28708902, + -0.38541305 0.87632209 -0.28899202, + -0.38451207 0.8760221 -0.29109403, + -0.36696112 0.88277531 -0.29333812, + -0.36586803 0.88225311 -0.29626003, + -0.34557196 0.88957685 -0.29871896, + -0.34437811 0.88880229 -0.30238113, + -0.32160512 0.89641631 -0.30497211, + -0.32013789 0.8951627 -0.31015387, + -0.29440212 0.90301532 -0.31287512, + -0.29464796 0.90328586 -0.31186098, + -0.26623392 0.91113371 -0.31457087, + -0.27134606 0.91805124 -0.28905606, + -0.24021205 0.92590922 -0.29153106, + -0.24454004 0.93296313 -0.26415902, + -0.21091589 0.94053054 -0.26630187, + -0.21415003 0.94697809 -0.23952504, + -0.17814991 0.95396054 -0.24129188, + -0.18047805 0.95980924 -0.21492805, + -0.14209607 0.96593148 -0.2162991, + -0.14368308 0.97117847 -0.1901781, + -0.10365698 0.97607476 -0.19113696, + -0.10463396 0.98067462 -0.16531494, + -0.063344412 0.98410726 -0.16589305, + -0.063841581 0.98805565 -0.14025095, + -0.021589989 0.9898445 -0.14050494, + -0.021726808 0.99313134 -0.11497004, + 0.021342792 0.99313951 -0.11497094, + 0.021204306 0.98985225 -0.14051002, + 0.063500077 0.98807663 -0.14025795, + 0.063001595 0.98412991 -0.16588898, + 0.10428698 0.98071188 -0.16531299, + 0.103307 0.97611201 -0.191136, + 0.14333297 0.97122973 -0.19017996, + 0.14174397 0.96599078 -0.21626495, + 0.18014398 0.95987886 -0.21489698, + 0.17780699 0.95402986 -0.24127097, + 0.21384592 0.94705164 -0.23950592, + 0.2106099 0.9406175 -0.26623687, + 0.24436589 0.93302858 -0.26408887, + 0.24007598 0.92603791 -0.29123396, + 0.27121705 0.91818124 -0.28876406, + 0.26610094 0.91127676 -0.31426892, + 0.29472303 0.9033711 -0.31154302, + 0.29440102 0.90301812 -0.31286803, + 0.32010791 0.89517474 -0.31014994, + 0.32158884 0.89643961 -0.30492085, + 0.3444249 0.88880378 -0.30232295, + 0.34561804 0.88957709 -0.29866502, + 0.36591783 0.88225061 -0.29620585, + 0.36700103 0.88276809 -0.29331002, + 0.38448209 0.87604123 -0.29107606, + 0.38511214 0.87625128 -0.28960708, + 0.39922482 0.87053859 -0.28771886, + 0.39813814 0.8703053 -0.28992209, + 0.421942 0.86015099 -0.28654, + 0.41956493 0.85984987 -0.29090098, + 0.44273788 0.84935981 -0.28735194, + 0.43817106 0.84913009 -0.29493102, + 0.4442398 0.84631157 -0.29395184, + 0.44110894 0.8463679 -0.29846996, + 0.46150911 0.8366372 -0.29503807, + 0.45609713 0.83706421 -0.30215707, + 0.47580093 0.82730389 -0.29863298, + 0.48498088 0.82593381 -0.28744894, + 0.51546896 0.80929589 -0.28165898, + 0.52800024 0.80622333 -0.26687011, + 0.56074512 0.78604418 -0.26019105, + 0.57139564 0.78233951 -0.24789485, + 0.60569072 0.75853163 -0.24035089, + 0.61506605 0.75427812 -0.22969203, + 0.65090507 0.72623307 -0.22115202, + 0.6589632 0.7216652 -0.21205404, + 0.69665337 0.68830836 -0.20225209, + 0.70331323 0.68369621 -0.19470507, + 0.74282181 0.64388782 -0.18336895, + 0.7483902 0.63922119 -0.17694205, + 0.78883314 0.59233308 -0.16396302, + 0.79317009 0.58793908 -0.15877302, + 0.8339718 0.5327239 -0.14386196, + 0.84636945 0.51703525 -0.12780206, + 0.8779881 0.46469706 -0.11486401, + 0.89424109 0.43810707 -0.091625407, + 0.92420512 0.37380904 -0.078178011, + 0.93447036 0.35080811 -0.060817823, + 0.96029067 0.27490091 -0.047658082, + 0.96553934 0.25771609 -0.03628001, + 0.985219 0.169627 -0.023879301, + 0.98709667 0.15914294 -0.017711695, + 0.99831623 0.057651114 -0.0064162412, + 0.99851036 0.054361317 -0.0046756119, + 0.99821299 -0.059537299 0.0051207999, + 0.99838966 -0.056607481 0.0037072685, + 0.98230636 -0.18688107 0.012239004, + 0.98360479 -0.18010296 0.009197358, + 0.94570512 -0.32460302 0.016576502, + 0.94790101 -0.31826401 0.0138479, + 0.88032699 -0.473919 0.020620599, + 0.88024026 -0.47407711 0.020689206, + 0.77559131 -0.63063526 0.027521608, + 0.7655738 -0.6424908 0.033200793, + 0.62466407 -0.77985311 0.040299002, + 0.59344602 -0.80303699 0.054345801, + 0.43170914 -0.89995432 0.060904723, + 0.37249589 -0.92419064 0.084370874, + 0.22003694 -0.97145176 0.088685378, + 0.13818999 -0.98308086 0.12023099, + 0.020736894 -0.99239075 0.12136997, + -0.067152217 -0.98529625 0.15710504, + -0.14367692 -0.97727954 0.15582593, + -0.21208204 -0.95922226 0.18685305, + -0.25725102 -0.94851613 0.18476802, + -0.30199504 -0.9303081 0.20814903, + -0.28580907 -0.93516523 0.20923504, + -0.20789699 -0.96450698 0.16280399, + 0.1929509 -0.97044951 -0.14490592, + 0.21836403 -0.96516711 -0.14411701, + 0.085801631 -0.99541837 -0.042195816, + 0.10179102 -0.99391323 -0.042132013, + -0.033104114 -0.99818546 0.050299123, + -0.028638404 -0.99832314 0.050306007, + -0.21732897 -0.96158886 0.16767499, + -0.20053495 -0.96512377 0.16829096, + -0.093542293 -0.99097687 0.095993288, + -0.090044476 -0.99129778 0.096024379, + 0.041816011 -0.99911624 -0.0042741508, + 0.032607205 -0.99945915 -0.0042756204, + 0.16173695 -0.98019874 -0.11424397, + 0.14199592 -0.98321152 -0.11459595, + 0.36695004 -0.85316211 -0.37075904, + 0.23471195 -0.94429374 -0.23069394, + 0.26246893 -0.93737274 -0.22900294, + 0.42217085 -0.82061368 -0.38518184, + 0.28384092 -0.92491263 -0.25292492, + 0.31571499 -0.91525 -0.250283, + 0.48011005 -0.78281415 -0.39584905, + 0.33947191 -0.89974278 -0.27426594, + 0.37602484 -0.88634473 -0.27018192, + 0.25372589 -0.95124352 -0.17538191, + 0.28577292 -0.94241363 -0.17375395, + 0.15364803 -0.98469722 -0.082241625, + 0.17341805 -0.98143125 -0.081968822, + 0.00268208 -0.999659 0.0259769, + 0.010682096 -0.99960554 0.025975486, + -0.14432801 -0.9825421 0.11739001, + -0.15262192 -0.98130554 0.11724294, + 0.055654019 -0.99844939 0.0012132805, + 0.044527173 -0.9990074 0.0012139493, + 0.2159321 -0.97112846 -0.10140505, + 0.19788991 -0.97492355 -0.10180195, + 0.35534111 -0.91253829 -0.20250107, + 0.32486591 -0.92329979 -0.20488895, + 0.44298813 -0.84920216 -0.28743204, + 0.40168309 -0.86743718 -0.29360405, + 0.49453899 -0.78833002 -0.36601499, + 0.46251681 -0.80416173 -0.37336588, + 0.5809691 -0.66193718 -0.47361812, + 0.55744296 -0.67518497 -0.48309693, + 0.66143918 -0.48030412 -0.57602614, + 0.64197594 -0.49101493 -0.58887297, + 0.53184003 -0.69395798 -0.48535401, + 0.55552077 -0.6813857 -0.47656077, + 0.42533207 -0.83002311 -0.36076903, + 0.40717208 -0.83764815 -0.36408308, + 0.53013802 -0.69949299 -0.47923201, + 0.50677186 -0.71118182 -0.48723987, + 0.6178779 -0.51149386 -0.59716088, + 0.59811926 -0.52133816 -0.60865426, + 0.48235071 -0.72735059 -0.4881587, + 0.50513494 -0.71660793 -0.48094895, + 0.37028208 -0.86124319 -0.34806809, + 0.35397896 -0.86711586 -0.35044098, + 0.44042799 -0.78260398 -0.43994799, + 0.41994494 -0.7911129 -0.44473195, + 0.490125 -0.698452 -0.52148098, + 0.46969581 -0.70740777 -0.52816683, + 0.55461413 -0.5480321 -0.62615019, + 0.53005379 -0.58119082 -0.61746275, + 0.6082117 -0.35456482 -0.71018463, + 0.56739992 -0.36781698 -0.73672795, + 0.48704088 -0.6048969 -0.62999284, + 0.56728685 -0.37030688 -0.73556674, + 0.52527404 -0.38263306 -0.76005214, + 0.4445588 -0.62628472 -0.6404177, + 0.52516919 -0.38599414 -0.75842327, + 0.48221406 -0.39735907 -0.78075314, + 0.40283105 -0.64472103 -0.64966303, + 0.48217994 -0.39965793 -0.77959991, + 0.45024699 -0.40733701 -0.79457802, + 0.3803429 -0.63785583 -0.66968584, + 0.40162092 -0.63162184 -0.66313982, + 0.32039312 -0.78744531 -0.52657217, + 0.3385109 -0.78218985 -0.52305788, + 0.2714529 -0.86748171 -0.41687986, + 0.28776196 -0.8632009 -0.41482195, + 0.30730203 -0.85393012 -0.41996306, + 0.29061204 -0.85862213 -0.42227107, + 0.35929298 -0.7714299 -0.52517092, + 0.34044889 -0.77724773 -0.52913183, + 0.42370287 -0.61879379 -0.66149074, + 0.44382712 -0.61217511 -0.65441519, + 0.36090392 -0.76748681 -0.52982289, + 0.37990275 -0.76125151 -0.52551872, + 0.30986196 -0.84991789 -0.42617494, + 0.32730296 -0.84467787 -0.42354694, + 0.23928604 -0.92159212 -0.30563104, + 0.2271381 -0.92435741 -0.30654815, + 0.23368008 -0.91761535 -0.32152113, + 0.12632594 -0.97798949 -0.16606693, + 0.14324901 -0.97571999 -0.165681, + 0.03955809 -0.99871874 -0.031558994, + 0.047307406 -0.99838209 -0.031548403, + -0.063096419 -0.99335438 0.096259736, + -0.065976903 -0.99316901 0.096241698, + -0.17902701 -0.96045101 0.213268, + -0.19363198 -0.95774686 0.21266797, + -0.28427604 -0.91182309 0.29625303, + -0.30794799 -0.90484297 0.29398501, + -0.36951208 -0.8630302 0.34444109, + -0.39474109 -0.85334021 0.3405731, + -0.37629315 -0.86679929 0.32720411, + -0.36903092 -0.86952782 0.3282339, + -0.33906099 -0.88837302 0.30956599, + -0.32087889 -0.89437473 0.31165788, + -0.27683508 -0.91677535 0.28789809, + -0.24185494 -0.92573875 0.29071295, + -0.19003105 -0.94503224 0.26608706, + -0.13183494 -0.95417053 0.26865989, + -0.07616806 -0.9666025 0.24469988, + 0.011902998 -0.96934986 0.24539597, + 0.066266522 -0.97249633 0.22329308, + 0.18776396 -0.95730376 0.21980494, + 0.23183508 -0.95157439 0.20188807, + 0.38183185 -0.90410769 0.19181693, + 0.40854695 -0.89478189 0.18015198, + 0.57015306 -0.80537713 0.16215202, + 0.57787907 -0.80063415 0.15824302, + 0.72966295 -0.67082995 0.13258699, + 0.72452897 -0.67572594 0.13583899, + 0.84960771 -0.51707083 0.10394496, + 0.8400076 -0.53084475 0.11220995, + 0.92942435 -0.36103511 0.076315828, + 0.92192602 -0.377693 0.086025901, + 0.9764685 -0.21027489 0.047893576, + 0.97295755 -0.22407089 0.056086875, + 0.99757862 -0.067465581 0.016887194, + 0.99714386 -0.072773196 0.020202698, + 0.99768865 0.065474674 -0.018176595, + 0.99722087 0.071174391 -0.022015398, + 0.97954375 0.19224496 -0.059464484, + 0.97527134 0.20899507 -0.071881823, + 0.94501173 0.30925593 -0.10636498, + 0.93361986 0.33476698 -0.12761298, + 0.89613378 0.4146769 -0.15807396, + 0.87599844 0.44466621 -0.18681209, + 0.83584458 0.50611573 -0.2126279, + 0.80598629 0.53741717 -0.2481311, + 0.76780999 0.581671 -0.26856399, + 0.76747221 0.58472711 -0.26283205, + 0.71719599 0.63561201 -0.285705, + 0.7097078 0.64049983 -0.29338494, + 0.66500401 0.67899698 -0.311019, + 0.65503001 0.68408501 -0.32087901, + 0.61378288 0.71475083 -0.33526391, + 0.61247313 0.71527117 -0.33654708, + 0.58786231 0.73198336 -0.34441018, + 0.60155278 0.72743177 -0.33011687, + 0.57789898 0.74316299 -0.33725601, + 0.58622205 0.74084508 -0.32786003, + 0.59482402 0.735089 -0.325313, + 0.59952694 0.73392391 -0.31925398, + 0.61273229 0.72469538 -0.31523916, + 0.61328727 0.72457439 -0.31443715, + 0.6120131 0.7254802 -0.31483108, + 0.61720109 0.72466719 -0.30646405, + 0.60244113 0.73512816 -0.31088805, + 0.60599005 0.73488605 -0.30449703, + 0.58878291 0.74672884 -0.30940393, + 0.59145397 0.74681193 -0.30406296, + 0.57135302 0.76011699 -0.30948001, + 0.57295805 0.7603451 -0.30593202, + 0.55005902 0.77476299 -0.31173301, + 0.5536778 0.7757017 -0.30286589, + 0.52836376 0.79087365 -0.30878887, + 0.53886521 0.79468036 -0.27947712, + 0.51138794 0.81067789 -0.28510296, + 0.52057177 0.81483656 -0.25504187, + 0.49063611 0.83158219 -0.26028305, + 0.49817488 0.83574384 -0.23098494, + 0.46551901 0.85305601 -0.23577, + 0.47161913 0.85709417 -0.20728004, + 0.43696707 0.87427419 -0.21143405, + 0.44183889 0.87811476 -0.18355596, + 0.40503895 0.89495587 -0.18707599, + 0.40884399 0.89850301 -0.15980899, + 0.36975408 0.91477323 -0.16270204, + 0.37264791 0.91796374 -0.13592698, + 0.33131692 0.93334275 -0.13820396, + 0.3334271 0.93611026 -0.11191103, + 0.29058984 0.95008254 -0.11358095, + 0.29205087 0.95238364 -0.087588273, + 0.24805807 0.96467423 -0.088718526, + 0.24899299 0.96646601 -0.062817499, + 0.203844 0.976942 -0.0634984, + 0.20435397 0.97816688 -0.037803598, + 0.15834993 0.98664653 -0.038131282, + 0.53343213 0.78865117 -0.30574405, + 0.53349996 0.78864688 -0.30563697, + 0.52201992 0.79529786 -0.30821496, + 0.51803303 0.79569697 -0.31386, + 0.56565106 0.76460314 -0.30890304, + 0.56489509 0.76469719 -0.31005105, + 0.5524689 0.7724548 -0.31319591, + 0.546996 0.77330798 -0.320609, + 0.79859012 0.56334704 -0.21188203, + 0.75148064 0.6175217 -0.2322579, + 0.74620926 0.62169325 -0.23805308, + 0.70292425 0.66423422 -0.25434309, + 0.69584405 0.66875404 -0.26185703, + 0.65482503 0.70375407 -0.27556202, + 0.64575708 0.70835406 -0.28501302, + 0.60770589 0.73675984 -0.29644293, + 0.59640735 0.74117345 -0.30815619, + 0.56127763 0.76420754 -0.31773281, + 0.55605626 0.76572537 -0.32321215, + 0.53411603 0.77886897 -0.32876, + 0.54411125 0.77660936 -0.31752315, + 0.52227092 0.78935188 -0.32273299, + 0.52840823 0.78830338 -0.31521815, + 0.53515106 0.78437209 -0.31364602, + 0.53723675 0.78409863 -0.31075084, + 0.54909986 0.77696383 -0.30792293, + 0.54815906 0.77705014 -0.30937803, + 0.54679513 0.77787918 -0.30970806, + 0.54985923 0.77780634 -0.30442116, + 0.53512907 0.78666514 -0.30788803, + 0.53694624 0.78679734 -0.30436614, + 0.5190317 0.79718554 -0.30838484, + 0.52018291 0.79739684 -0.30588895, + 0.49975982 0.80870271 -0.31022587, + 0.50012892 0.80881691 -0.30933198, + 0.47703689 0.82089585 -0.31395191, + 0.47945276 0.82195956 -0.30742085, + 0.4535751 0.83474517 -0.31220207, + 0.46265295 0.83984989 -0.28390896, + 0.43381485 0.85355067 -0.2885409, + 0.44173205 0.85889411 -0.25917903, + 0.410584 0.872944 -0.263419, + 0.41698107 0.87806213 -0.23480603, + 0.38359892 0.89215177 -0.23857294, + 0.38870484 0.8969807 -0.21055692, + 0.35280201 0.91093701 -0.213833, + 0.35679308 0.91540122 -0.18638505, + 0.31835899 0.92891097 -0.189135, + 0.32139492 0.93295175 -0.16219196, + 0.28113008 0.94548833 -0.16437106, + 0.28336 0.949054 -0.13785399, + 0.24155694 0.96030879 -0.13948897, + 0.24311803 0.96335214 -0.11334202, + 0.19978492 0.97312766 -0.11449196, + 0.20080504 0.97562224 -0.088536419, + 0.15623693 0.98367751 -0.089267358, + 0.15683194 0.98558664 -0.063425675, + 0.11179895 0.99167955 -0.063817769, + 0 0.99999255 -0.003865018, + 0.022946892 0.99973667 -0.00032012688, + 0.022944907 0.99964738 -0.013363904, + 0.022568099 0.99965602 -0.013364, + 0.022570105 0.99974525 -0.0003279291, + 0.071931086 0.99731177 -0.013969896, + 0.071938105 0.99740911 0.00027063003, + 0.072125964 0.99739552 0.00027062988, + 0.072120607 0.99732113 -0.012215102, + 0.067038111 0.99767226 -0.012494903, + 0.066954374 0.99702066 -0.038300283, + 0.11208096 0.99296665 -0.038144585, + 0.11232202 0.99293613 -0.038231205, + 0.15796995 0.98671275 -0.037991591, + 0.15757301 0.9854511 -0.06369441, + 0.20292391 0.97715551 -0.063158169, + 0.20215797 0.97529787 -0.089029595, + 0.24640194 0.96515477 -0.088103674, + 0.24515709 0.96274734 -0.11408604, + 0.28817394 0.95092475 -0.11268497, + 0.28633285 0.94800353 -0.13893394, + 0.32800698 0.93469089 -0.13698299, + 0.32543904 0.93129414 -0.16364801, + 0.36537397 0.91681391 -0.16110298, + 0.36194396 0.91300189 -0.18821298, + 0.39950114 0.89785331 -0.18509007, + 0.39505899 0.89367801 -0.212763, + 0.43021005 0.87818414 -0.20907404, + 0.4245891 0.87371618 -0.23736906, + 0.45762873 0.85804147 -0.23311086, + 0.45064887 0.85336781 -0.26206693, + 0.48139611 0.83788317 -0.25731206, + 0.47281283 0.83310068 -0.28703892, + 0.50091881 0.81828672 -0.28193492, + 0.49108994 0.81378186 -0.31078896, + 0.51657903 0.79989111 -0.30548403, + 0.51358813 0.79884917 -0.31315708, + 0.53642207 0.78573412 -0.30801502, + 0.53545719 0.7855193 -0.31023413, + 0.55598181 0.77308571 -0.30532387, + 0.5541001 0.77288616 -0.30922505, + 0.57154363 0.76185751 -0.30481282, + 0.56888092 0.76185191 -0.30976796, + 0.58337229 0.75238937 -0.30592015, + 0.5793069 0.75275183 -0.3126789, + 0.58034235 0.7520715 -0.31239617, + 0.5805788 0.75203472 -0.31204489, + 0.56794417 0.7602213 -0.31544113, + 0.5646472 0.76084232 -0.31983212, + 0.55720103 0.76549298 -0.32178801, + 0.54993713 0.76711917 -0.33029908, + 0.5725261 0.75304818 -0.3242411, + 0.56080395 0.75630689 -0.33689597, + 0.58360726 0.74177122 -0.33042112, + 0.58687872 0.74065363 -0.32711685, + 0.62479687 0.71422881 -0.3154459, + 0.63547015 0.70946318 -0.30469605, + 0.67662877 0.67656773 -0.2905679, + 0.68514377 0.67167777 -0.2818279, + 0.72913235 0.63107228 -0.26479012, + 0.73537284 0.62656581 -0.25815094, + 0.78168815 0.57664412 -0.23758206, + 0.79898989 0.56056696 -0.21766897, + 0.83528709 0.51253104 -0.19901603, + 0.8592962 0.48297611 -0.16835704, + 0.89588672 0.41952485 -0.14623894, + 0.91203761 0.39167282 -0.12157194, + 0.94494814 0.31251204 -0.097001217, + 0.95366198 0.29013401 -0.079694197, + 0.979554 0.193996 -0.053286999, + 0.98277652 0.1796319 -0.043390378, + 0.9976989 0.06590569 -0.015919598, + 0.99804038 0.061210923 -0.012986705, + 0.99760675 -0.067636788 0.014350097, + 0.99792647 -0.063268028 0.011831606, + 0.97699153 -0.2096439 0.039204881, + 0.97950053 -0.19868091 0.033236586, + 0.93198287 -0.35753396 0.059810393, + 0.93734187 -0.34438097 0.052838091, + 0.85711986 -0.50915897 0.078119993, + 0.86273819 -0.50030613 0.073325314, + 0.74616683 -0.6587218 0.09654288, + 0.74588275 -0.65901774 0.096719161, + 0.59889603 -0.79233903 0.116286, + 0.58364367 -0.80251461 0.12381594, + 0.42240015 -0.89581031 0.13821004, + 0.38584495 -0.90965188 0.15380898, + 0.23470902 -0.95846111 0.16206202, + 0.17936905 -0.96637225 0.18425904, + 0.057917174 -0.98065454 0.18698192, + -0.0067144111 -0.97697109 0.21326603, + -0.092299253 -0.97282255 0.21236089, + -0.15644601 -0.95798612 0.24039003, + -0.21097107 -0.94809836 0.23790909, + -0.26813692 -0.92598063 0.2658239, + -0.29880893 -0.91726476 0.26332194, + -0.33915192 -0.89622474 0.28593194, + -0.35434401 -0.89087403 0.28422499, + -0.37985286 -0.87475771 0.30084988, + -0.35612991 -0.88363677 0.30390394, + -0.29171705 -0.92152226 0.25631607, + -0.26959097 -0.92775589 0.25804996, + -0.17266691 -0.96887654 0.17738192, + -0.16062704 -0.97087824 0.17774804, + -0.0402245 -0.99705303 0.065324299, + -0.040265515 -0.99705136 0.065324225, + 0.077268519 -0.99535125 -0.057494514, + 0.066299222 -0.99613935 -0.057540022, + 0.17696202 -0.96636713 -0.18659902, + 0.157042 -0.96968001 -0.18723901, + 0.27285701 -0.90073597 -0.33796999, + 0.27720508 -0.90605229 -0.31972912, + 0.264312 -0.90947199 -0.32093599, + 0.34870601 -0.83367902 -0.428233, + 0.33069187 -0.83946669 -0.43120584, + 0.40087819 -0.75038034 -0.52557224, + 0.38167295 -0.75706887 -0.53025693, + 0.46690401 -0.59796 -0.65149403, + 0.48679975 -0.59066069 -0.64354169, + 0.40272084 -0.74614674 -0.5301708, + 0.42230293 -0.73891795 -0.52503395, + 0.35215402 -0.82843512 -0.43552607, + 0.37029988 -0.8222127 -0.43225485, + 0.39196613 -0.81125629 -0.43385014, + 0.37296808 -0.81819117 -0.43755913, + 0.44447985 -0.72644877 -0.52412784, + 0.42434606 -0.73432404 -0.52981007, + 0.51040411 -0.5744431 -0.63992417, + 0.53022927 -0.56637335 -0.63093436, + 0.44712478 -0.72058463 -0.52994078, + 0.46754918 -0.71212226 -0.52371716, + 0.39600283 -0.80519563 -0.44140878, + 0.41569287 -0.79752773 -0.43720585, + 0.32193792 -0.88550079 -0.33502892, + 0.30727515 -0.89004642 -0.33674815, + 0.31787008 -0.87902021 -0.35536209, + 0.19278193 -0.95880562 -0.20863092, + 0.21619 -0.954027 -0.207592, + 0.099956088 -0.99133587 -0.085216589, + 0.11499502 -0.98971611 -0.085077405, + -0.0092042191 -0.9994449 0.032017995, + -0.0051452103 -0.99947411 0.032018904, + -0.13190895 -0.98148865 0.13885295, + -0.14050199 -0.9803189 0.13868698, + -0.24298006 -0.94577026 0.21559104, + -0.26249495 -0.94079977 0.21445796, + -0.3302249 -0.90753776 0.25947395, + -0.35160103 -0.90008414 0.25734302, + -0.31685001 -0.91837901 0.237036, + -0.28961098 -0.92677289 0.23920196, + -0.23653391 -0.94811267 0.21244793, + -0.18729301 -0.95853513 0.21478303, + -0.11459795 -0.9765045 0.18249992, + -0.032722 -0.982454 0.183612, + 0.043130316 -0.98731738 0.15278806, + 0.16337502 -0.97495914 0.15087502, + 0.23096009 -0.96499538 0.12426405, + 0.38284716 -0.91624629 0.11798605, + 0.43026695 -0.89732188 0.098405786, + 0.59141195 -0.80156386 0.087904491, + 0.61444306 -0.78519714 0.076975107, + 0.75777131 -0.64940727 0.063663222, + 0.76295727 -0.64360625 0.060558621, + 0.8727898 -0.48594987 0.045724388, + 0.87018597 -0.49039099 0.047885701, + 0.94331849 -0.33031815 0.032254815, + 0.93977588 -0.33980396 0.036802698, + 0.98183125 -0.18865305 0.020432206, + 0.9799931 -0.19747902 0.024809703, + 0.9981879 -0.059705593 0.0075009293, + 0.99795252 -0.06326697 0.0093856556, + 0.99830675 0.057539385 -0.0085359784, + 0.99804986 0.061479792 -0.010807799, + 0.98521078 0.16875896 -0.029666992, + 0.98278362 0.18092895 -0.037431184, + 0.960374 0.272935 -0.056465801, + 0.953583 0.292725 -0.0706513, + 0.92450345 0.37053418 -0.089431047, + 0.91175002 0.39572999 -0.110044, + 0.87864202 0.460026 -0.127923, + 0.85867703 0.488509 -0.15502501, + 0.82475227 0.53900421 -0.17105006, + 0.81011009 0.55497605 -0.18900603, + 0.76637435 0.6080963 -0.2070971, + 0.7615512 0.61225611 -0.21256104, + 0.7190758 0.65649283 -0.22791894, + 0.71291602 0.660824 -0.23465399, + 0.67246777 0.69745976 -0.24766292, + 0.66422975 0.70213777 -0.25651792, + 0.62619996 0.73232096 -0.26754397, + 0.61642414 0.73670518 -0.27800506, + 0.58075094 0.76165485 -0.28741997, + 0.56933194 0.76553088 -0.29970598, + 0.53568608 0.78630513 -0.30783904, + 0.52886611 0.78795719 -0.31531608, + 0.50777406 0.7998271 -0.32006603, + 0.51605314 0.79837215 -0.31030807, + 0.49515983 0.80978572 -0.31474388, + 0.50020504 0.80918211 -0.30825204, + 0.50602418 0.80601633 -0.30704612, + 0.50704074 0.80593961 -0.30556685, + 0.51792097 0.79986799 -0.30326399, + 0.51638979 0.79991466 -0.30574185, + 0.51431382 0.8010807 -0.30618787, + 0.51645088 0.80117184 -0.30232793, + 0.50115907 0.80962813 -0.30551904, + 0.50220692 0.8097809 -0.30338597, + 0.48423001 0.81932598 -0.306963, + 0.48474631 0.81946146 -0.30578417, + 0.46421093 0.82983285 -0.30965397, + 0.46402395 0.82975888 -0.31013197, + 0.44045612 0.84095418 -0.31431609, + 0.44234774 0.84197855 -0.30886981, + 0.41574091 0.85384482 -0.31322291, + 0.42403615 0.85947132 -0.2854861, + 0.39494008 0.87186718 -0.28960305, + 0.40215391 0.87767977 -0.26067293, + 0.37060001 0.89035314 -0.26443702, + 0.37639406 0.89585811 -0.23614803, + 0.34233588 0.90854269 -0.23949191, + 0.34689698 0.91367686 -0.21179497, + 0.31013104 0.92613709 -0.21468303, + 0.31364885 0.93084657 -0.18748091, + 0.27494708 0.94253236 -0.18983407, + 0.27757496 0.9467569 -0.16310598, + 0.23710394 0.95738077 -0.16493596, + 0.23899092 0.96108365 -0.13856995, + 0.19674 0.97042102 -0.139916, + 0.19801709 0.97356349 -0.11385705, + 0.15437992 0.98132354 -0.11476495, + 0.15517098 0.98388076 -0.088884875, + 0.11085903 0.98980522 -0.089420125, + 0.11128305 0.99174947 -0.063633829, + 0.066650383 0.99572879 -0.063889183, + 0.066818975 0.99703163 -0.038252484, + 0.022125205 0.99902022 -0.038328808, + 0.022152798 0.9996689 -0.013087398, + 0.023181792 0.99964565 -0.013087096, + 0.023183189 0.99970353 -0.0074441661, + -0.026116196 0.99965888 -6.4459993e-005, + -0.026113791 0.99956465 -0.013728796, + -0.025918294 0.99956977 -0.013728896, + -0.075920366 0.99704951 -0.011326094, + -0.075925261 0.99711353 6.0097969e-005, + -0.10280804 0.99469334 -0.0039622113, + -0.12401196 0.99228066 -0.00046628484, + -0.12390795 0.99229366 -0.00047202283, + -0.12389603 0.99219126 -0.014363304, + -0.12399904 0.99217838 -0.014363206, + -0.17240407 0.98498136 -0.0094158435, + -0.17241198 0.98502487 0.00037551695, + -0.17241894 0.98502362 0.00037551686, + -0.17242008 0.9850235 0.00037541517, + -0.20454797 0.97884887 -0.0038764095, + 0.69157004 -0.72229505 -0.0045597306, + 0.8190878 -0.57362288 0.007205788, + 0.81910872 -0.57363784 -0.00071152375, + 0.81906313 -0.57370305 -0.00070836005, + 0.81904221 -0.57368809 0.0072068521, + 0.75899518 -0.65109515 -0.0012353504, + 0.75894785 -0.6510548 0.011219197, + 0.78998601 -0.61305499 0.0092536304, + 0.7898733 -0.61320025 0.0092560537, + 0.75976235 -0.6500783 0.012627506, + 0.75941086 -0.64997196 0.028838497, + 0.72443181 -0.68866885 0.030555392, + 0.72357023 -0.68834424 0.051268317, + 0.6860767 -0.72551966 0.054037172, + 0.68458992 -0.72478694 0.077592395, + 0.64516521 -0.75970221 0.081330322, + 0.64294398 -0.75832999 0.107511, + 0.60175574 -0.79077268 0.11210996, + 0.59877479 -0.7885347 0.14029196, + 0.55579519 -0.81846631 0.14561805, + 0.55204505 -0.81510913 0.17562301, + 0.5074352 -0.8423593 0.18149506, + 0.50294197 -0.83760989 0.21321097, + 0.45768413 -0.86163819 0.21932806, + 0.45251989 -0.8552348 0.25258493, + 0.40703094 -0.87600785 0.25871998, + 0.40135193 -0.86775887 0.29310596, + 0.3558771 -0.88538921 0.29906106, + 0.34985998 -0.87511688 0.33431798, + 0.30477396 -0.8897109 0.33989298, + 0.29864895 -0.87730473 0.3756929, + 0.25495598 -0.88887787 0.38064894, + 0.24895798 -0.87429887 0.41667894, + 0.20708697 -0.8831529 0.42089894, + 0.20151204 -0.86658818 0.45652813, + 0.16164199 -0.8731029 0.45995995, + 0.15672207 -0.85467744 0.49493924, + 0.11912102 -0.85920912 0.49756405, + 0.11504395 -0.8390227 0.53179485, + 0.080283336 -0.8419044 0.53362125, + 0.0772231 -0.82020199 0.56683803, + 0.045256205 -0.82181513 0.56795406, + 0.043355297 -0.7988919 0.59990996, + 0.0141168 -0.799564 0.60041499, + 0.013473895 -0.77570671 0.63094974, + -0.013079198 -0.77571088 0.63095295, + -0.013723302 -0.79958212 0.60040003, + -0.042985722 -0.79891837 0.59990132, + -0.044884689 -0.82181281 0.56798691, + -0.076829769 -0.8202107 0.5668788, + -0.079895593 -0.84195286 0.53360295, + -0.11463395 -0.83908457 0.53178579, + -0.11871206 -0.85927141 0.49755424, + -0.15632394 -0.85475171 0.49493682, + -0.16124095 -0.87316179 0.45998889, + -0.20113698 -0.8666569 0.45656294, + -0.20671192 -0.88322371 0.42093486, + -0.248592 -0.87438297 0.41672099, + -0.25458395 -0.88894373 0.38074392, + -0.29829088 -0.87738371 0.37579286, + -0.30442393 -0.88980174 0.33996892, + -0.34951612 -0.87522328 0.33439913, + -0.35554719 -0.88552243 0.29905915, + -0.40103894 -0.86790287 0.29310796, + -0.40675291 -0.87620276 0.25849694, + -0.45228478 -0.85542357 0.25236687, + -0.45748201 -0.86186302 0.21886601, + -0.50277996 -0.8378219 0.21275997, + -0.50728476 -0.84257561 0.18090992, + -0.55195916 -0.81529027 0.17505106, + -0.55568188 -0.81861681 0.14520396, + -0.59871304 -0.78865314 0.13988902, + -0.60163808 -0.79084611 0.11222401, + -0.64284307 -0.75840014 0.10762002, + -0.64501804 -0.75974911 0.082055308, + -0.68443894 -0.72485495 0.078286596, + -0.68594623 -0.72560424 0.054556318, + -0.72344005 -0.68844408 0.051762309, + -0.72435302 -0.68878698 0.0297524, + -0.72466493 -0.68843496 0.030299697, + -0.72508407 -0.68858904 0.0099073714, + -0.72400337 -0.68979633 0.00058712129, + -0.72396415 -0.68975919 0.010407602, + -0.75687701 -0.65352499 0.0065037501, + -0.75689316 -0.65353817 -0.00088712922, + -0.75690609 -0.65352309 -0.00088794914, + -0.75689089 -0.65350896 0.0065035592, + -0.75970513 -0.65017408 0.011043901, + -0.75935102 -0.65007502 0.028080201, + -0.79209602 -0.61030602 0.0105091, + -0.79178602 -0.61025101 0.025857801, + -0.75906783 -0.65042782 0.027560193, + -0.75823909 -0.65020609 0.048016608, + -0.72294122 -0.68903321 0.050883919, + -0.72154921 -0.68849623 0.073073827, + -0.68369192 -0.72569495 0.077021889, + -0.68164283 -0.72466481 0.10111398, + -0.64183182 -0.75948781 0.10597298, + -0.63901508 -0.75772512 0.13233502, + -0.59748071 -0.78992665 0.13795894, + -0.59382564 -0.78715855 0.1665909, + -0.5504961 -0.81674719 0.17285304, + -0.54598397 -0.81267589 0.20361596, + -0.50108683 -0.8394497 0.21032393, + -0.49575695 -0.83377188 0.24300097, + -0.45042706 -0.85715109 0.24981503, + -0.44444293 -0.84966987 0.28378096, + -0.39902601 -0.86971402 0.29047501, + -0.39255276 -0.86023647 0.32541579, + -0.34740609 -0.87705827 0.33178008, + -0.34065396 -0.86543387 0.36739498, + -0.29612106 -0.87920624 0.3732411, + -0.28932804 -0.86534011 0.40923807, + -0.246445 -0.876122 0.41433701, + -0.239914 -0.86012203 0.45014599, + -0.19908105 -0.86826319 0.45440713, + -0.19306493 -0.85024869 0.48969683, + -0.15446205 -0.8561523 0.49309719, + -0.14917503 -0.8362022 0.5277431, + -0.11302999 -0.84024489 0.53029495, + -0.10868798 -0.81857085 0.56402892, + -0.075557433 -0.82109529 0.56576818, + -0.07234218 -0.79809368 0.59817475, + -0.042146515 -0.79947931 0.59921324, + -0.040161487 -0.77532369 0.63028574, + -0.012808902 -0.77588612 0.63074309, + -0.012136894 -0.75076866 0.66045368, + 0.0125086 -0.75076503 0.66045099, + 0.013181802 -0.77589613 0.63072306, + 0.040529717 -0.77532631 0.63025922, + 0.042512886 -0.7994557 0.59921879, + 0.072729886 -0.79805982 0.5981729, + 0.075949408 -0.82108814 0.56572604, + 0.10905205 -0.81855541 0.56398129, + 0.11339295 -0.84021759 0.53026074, + 0.14954901 -0.83616197 0.52770102, + 0.15483207 -0.85609931 0.49307317, + 0.19341204 -0.85018712 0.48966706, + 0.19943203 -0.86821413 0.45434707, + 0.24027006 -0.86005819 0.45007813, + 0.24679907 -0.87604922 0.41428009, + 0.28967002 -0.86525512 0.40917605, + 0.29647005 -0.87913525 0.3731311, + 0.34098202 -0.86535311 0.36728102, + 0.34773096 -0.87696987 0.33167297, + 0.39290115 -0.86012131 0.32530013, + 0.39934891 -0.8695628 0.29048395, + 0.44470516 -0.84952933 0.2837911, + 0.45065713 -0.85696918 0.25002405, + 0.49599418 -0.83357328 0.2431981, + 0.5012809 -0.83920884 0.21082196, + 0.54609388 -0.81247884 0.20410696, + 0.55060011 -0.8165502 0.17345105, + 0.59387726 -0.7869963 0.16717306, + 0.59755969 -0.78979164 0.13838895, + 0.63908607 -0.7575931 0.13274701, + 0.64195591 -0.75939286 0.10590099, + 0.68173879 -0.7245838 0.10104698, + 0.68383503 -0.72563499 0.076311998, + 0.72170275 -0.68840677 0.072396778, + 0.72307444 -0.68892944 0.050394531, + 0.75835633 -0.65010327 0.047554422, + 0.75913686 -0.65031391 0.028336497, + 0.791839 -0.61015099 0.026586501, + 0.79214215 -0.6102131 0.012279603, + 0.78996891 -0.61300093 0.013381698, + 0.79003954 -0.61305565 0.00051308068, + 0.79001987 -0.61308092 0.00051308091, + 0.78990668 -0.61322677 0.0004920268, + 0.76786703 -0.640598 -0.0038019801, + 0.69793826 -0.71614921 -0.0035350011, + 0.69156498 -0.72231197 -0.00182327, + 0.69152522 -0.72227126 0.010826604, + 0.69153696 -0.72225994 0.010826399, + 0.72606808 -0.68749309 0.013359101, + 0.72613198 -0.68755502 0.00071084697, + 0.72609794 -0.68759096 0.00071084691, + 0.72604775 -0.68754375 0.011758995, + 0.72514439 -0.68848938 0.012166806, + 0.72473407 -0.68832707 0.031084804, + 0.68756884 -0.72537982 0.032758094, + 0.68663281 -0.72492284 0.054975484, + 0.64752793 -0.75985986 0.057624992, + 0.64594895 -0.7588979 0.082606293, + 0.60508889 -0.79148281 0.086153179, + 0.60277587 -0.78976685 0.11370897, + 0.56008607 -0.81997913 0.11805902, + 0.55704284 -0.81728071 0.14749794, + 0.51263475 -0.84495658 0.15249293, + 0.5088858 -0.84102869 0.18359195, + 0.46373188 -0.86559182 0.18895395, + 0.45933017 -0.86017829 0.22160608, + 0.41379207 -0.88158512 0.22712103, + 0.40884301 -0.87445199 0.26111501, + 0.36310989 -0.89279372 0.26659092, + 0.35779917 -0.88379341 0.30147815, + 0.31221405 -0.89913821 0.30671307, + 0.30674005 -0.88813424 0.3422401, + 0.26235992 -0.90042973 0.34697789, + 0.25693497 -0.88734591 0.38288593, + 0.21410698 -0.89687788 0.38699895, + 0.20897405 -0.88174325 0.4229171, + 0.167946 -0.88884401 0.42632201, + 0.16337401 -0.87185699 0.46170801, + 0.12443695 -0.87686169 0.46435881, + 0.12062898 -0.85816586 0.49899894, + 0.084356323 -0.86139721 0.5008781, + 0.081474476 -0.84111279 0.53468788, + 0.04785981 -0.84295118 0.53585714, + 0.046050511 -0.8213082 0.56862313, + 0.015004296 -0.82208782 0.56916291, + 0.0143865 -0.79939699 0.600631, + -0.014015404 -0.79940116 0.6006341, + -0.014632902 -0.82207513 0.56919104, + -0.045680489 -0.8213048 0.56865788, + -0.047492612 -0.84297121 0.53585809, + -0.08111506 -0.84114259 0.53469574, + -0.08399681 -0.8614161 0.50090605, + -0.12026698 -0.85819685 0.49903294, + -0.12407398 -0.87689388 0.46439493, + -0.16298793 -0.87190557 0.4617528, + -0.16756094 -0.88889468 0.42636785, + -0.20861411 -0.88180441 0.4229672, + -0.21374205 -0.89692825 0.3870841, + -0.25655994 -0.88741475 0.3829779, + -0.26198605 -0.90050226 0.34707209, + -0.30640596 -0.88821286 0.34233496, + -0.31189597 -0.8992489 0.30671197, + -0.3574768 -0.88392144 0.30148482, + -0.36281604 -0.89297014 0.26640004, + -0.40859213 -0.87462533 0.26092708, + -0.413573 -0.8818 0.226685, + -0.45915407 -0.86038214 0.22117902, + -0.46356207 -0.86579913 0.18842003, + -0.50877804 -0.8412081 0.18306802, + -0.51250523 -0.84510744 0.15209207, + -0.55694586 -0.81741685 0.14710897, + -0.55993867 -0.82006651 0.11815093, + -0.60264313 -0.78985518 0.11379803, + -0.6049149 -0.79154283 0.086820975, + -0.64575374 -0.75899369 0.083250768, + -0.64735103 -0.75997299 0.0581186, + -0.68647468 -0.72503662 0.055446874, + -0.68746197 -0.72551799 0.031931899, + -0.61493808 -0.78853214 0.0082697207, + -0.61495811 -0.78855717 -0.0020398605, + -0.57556707 -0.81771815 0.0077169011, + 0.52349985 -0.84927368 0.068426579, + 0.47895813 -0.87500226 0.070499517, + 0.47727001 -0.87299198 0.100491, + 0.43191892 -0.89599574 0.10313898, + 0.42964908 -0.89281726 0.13520002, + 0.38354009 -0.91311425 0.13827303, + 0.38080299 -0.90859902 0.171572, + 0.33415109 -0.92615223 0.17488605, + 0.33107492 -0.92013079 0.20916195, + 0.28482208 -0.93473434 0.21248108, + 0.28155297 -0.92705989 0.24756397, + 0.23611094 -0.93882775 0.25070694, + 0.23282091 -0.92938763 0.28641391, + 0.18835291 -0.93854451 0.28923586, + 0.18525895 -0.92736578 0.3250719, + 0.142014 -0.93413699 0.327445, + 0.13931805 -0.92126936 0.36311612, + 0.098050654 -0.92585957 0.36492482, + 0.095921434 -0.91130829 0.40039515, + 0.05675612 -0.91405427 0.40160114, + 0.055367991 -0.89794987 0.43660095, + 0.018168204 -0.89918125 0.43719909, + 0.017678505 -0.88182729 0.47124118, + -0.017281195 -0.88183367 0.47124383, + -0.017770005 -0.89920229 0.43717214, + -0.054974016 -0.89798427 0.43658009, + -0.056358282 -0.91405272 0.40166086, + -0.095564976 -0.91131777 0.4004589, + -0.097695053 -0.92587161 0.36498982, + -0.13892995 -0.92129964 0.36318788, + -0.14163205 -0.93420434 0.32741812, + -0.18485509 -0.9274534 0.32505214, + -0.18795598 -0.93866289 0.28910998, + -0.23247106 -0.92951322 0.28629106, + -0.23576991 -0.93898267 0.2504479, + -0.28129706 -0.92720622 0.24730706, + -0.28457606 -0.93490326 0.21206704, + -0.33086708 -0.92029822 0.20875405, + -0.33393204 -0.92629111 0.17456901, + -0.380629 -0.90873098 0.171259, + -0.38333294 -0.91318989 0.13834798, + -0.42945307 -0.89290023 0.13527504, + -0.43169105 -0.8960371 0.10373201, + -0.47703788 -0.87305182 0.10107098, + -0.47873983 -0.87508768 0.07092078, + -0.52324587 -0.84939682 0.068838686, + -0.52437818 -0.85054529 0.040004015, + -0.56789392 -0.82219291 0.038670495, + -0.56844705 -0.82265514 0.010326301, + -0.57546693 -0.81761986 0.018315999, + -0.57556301 -0.81775701 0.000868381, + -0.57558411 -0.81774217 0.00086838123, + -0.57564992 -0.81769586 0.00086539291, + -0.57563287 -0.81767184 0.0077162683, + -0.6098907 -0.79234564 0.014887293, + -0.60942096 -0.7919969 0.036701098, + -0.56752294 -0.8224749 0.038113497, + -0.56640106 -0.82150412 0.065734506, + -0.52267063 -0.84981841 0.068000048, + -0.52094883 -0.84805572 0.097024366, + -0.47624099 -0.87361598 0.099948697, + -0.47393113 -0.87083817 0.13050003, + -0.4284482 -0.89358842 0.13391006, + -0.42558715 -0.88955528 0.16603306, + -0.37947693 -0.90949488 0.16975398, + -0.37614793 -0.90397388 0.20333198, + -0.32961491 -0.92110175 0.20718496, + -0.32595396 -0.91389686 0.24196397, + -0.27996087 -0.92803556 0.24570689, + -0.27614284 -0.91901249 0.28135583, + -0.23117392 -0.93029165 0.2848089, + -0.22743507 -0.91948837 0.32064712, + -0.18359399 -0.92818385 0.32367897, + -0.18012995 -0.91558069 0.35953489, + -0.13780798 -0.92192489 0.36202696, + -0.13481899 -0.90755987 0.39769194, + -0.094643682 -0.91181087 0.39955395, + -0.0923144 -0.89577901 0.43480799, + -0.054380007 -0.89828914 0.43602705, + -0.052885011 -0.88082021 0.47048813, + -0.017095698 -0.88192588 0.47107795, + -0.016573504 -0.86323917 0.5045231, + 0.016956892 -0.86323357 0.50451976, + 0.017479306 -0.8819263 0.47106317, + 0.05323118 -0.88081068 0.47046682, + 0.054725114 -0.89828026 0.43600208, + 0.092702255 -0.89575458 0.4347758, + 0.095032156 -0.91178459 0.39952183, + 0.13519801 -0.90752012 0.39765406, + 0.13818897 -0.92189878 0.36194792, + 0.1805229 -0.91553658 0.35944983, + 0.18397895 -0.92810762 0.32367888, + 0.22776604 -0.91940713 0.32064503, + 0.23149709 -0.93018335 0.2849001, + 0.2764909 -0.91888267 0.2814379, + 0.28028506 -0.92784822 0.24604505, + 0.32616499 -0.91373199 0.242302, + 0.32982191 -0.92093575 0.20759295, + 0.37632 -0.90381199 0.203733, + 0.37965995 -0.90935791 0.17007798, + 0.42572093 -0.88943189 0.16635099, + 0.42862207 -0.89352113 0.13380301, + 0.47409487 -0.87076479 0.13039497, + 0.47643894 -0.87357986 0.099318586, + 0.52117503 -0.847987 0.096408799, + 0.5228821 -0.8497262 0.067525618, + 0.56659311 -0.82140815 0.065275215, + 0.60815769 -0.79139167 0.061995771, + 0.56600308 -0.82188511 0.064384609, + 0.56431198 -0.82041597 0.092030801, + 0.52034289 -0.84863484 0.09519618, + 0.51796389 -0.8461858 0.12523197, + 0.47308895 -0.87152189 0.12898198, + 0.47008789 -0.86788684 0.16059196, + 0.42452899 -0.89030099 0.16474, + 0.42098799 -0.88527101 0.19764701, + 0.37498209 -0.90475726 0.20199704, + 0.37100199 -0.89810401 0.23615, + 0.3247261 -0.91471529 0.24051809, + 0.32047704 -0.90629309 0.27554902, + 0.27500108 -0.91986734 0.27967608, + 0.27067298 -0.90957487 0.31529298, + 0.22632296 -0.9203279 0.31902096, + 0.22213803 -0.90816009 0.35482404, + 0.17919095 -0.91635579 0.35802591, + 0.17535105 -0.90229428 0.39384913, + 0.13400094 -0.90822858 0.39643982, + 0.13072397 -0.89236873 0.4319599, + 0.091750599 -0.89629602 0.43386099, + 0.08923661 -0.8788721 0.46863705, + 0.052568607 -0.88117212 0.46986407, + 0.05097051 -0.86236715 0.5037111, + 0.016700406 -0.86336929 0.50429618, + 0.016143 -0.84324503 0.537287, + -0.015771301 -0.8432501 0.53729004, + -0.016329896 -0.8633678 0.50431091, + -0.050610606 -0.86237609 0.50373209, + -0.052208018 -0.88118929 0.46987218, + -0.088834129 -0.87890428 0.46865317, + -0.091347896 -0.89632785 0.43387994, + -0.13034604 -0.8924123 0.43198416, + -0.13362204 -0.90826821 0.3964771, + -0.17491798 -0.90235788 0.39389595, + -0.178758 -0.91642398 0.35806799, + -0.22177994 -0.90823078 0.35486692, + -0.22597297 -0.92042089 0.31900096, + -0.27031606 -0.90968525 0.31528109, + -0.27465102 -0.9199971 0.27959302, + -0.32021001 -0.90641302 0.27546501, + -0.32449001 -0.91489601 0.24014901, + -0.37077412 -0.8982923 0.23579109, + -0.37476182 -0.90495157 0.20153491, + -0.42084375 -0.88544148 0.19718988, + -0.4243688 -0.89044261 0.16438693, + -0.46995994 -0.86801988 0.16024698, + -0.47291893 -0.87159985 0.12907898, + -0.51781112 -0.8462652 0.12532704, + -0.52015185 -0.8486768 0.095863678, + -0.56410992 -0.8204819 0.092678793, + -0.56582099 -0.82197303 0.064861797, + -0.60795391 -0.79151183 0.062458184, + -0.60904878 -0.7923097 0.036122087, + -0.6493212 -0.75972515 0.034636509, + -0.64982516 -0.76001918 0.009911323, + -0.65288776 -0.75740469 0.0086937277, + -0.65296996 -0.75733387 0.0086928187, + -0.68825704 -0.72538608 0.010832801, + -0.68780363 -0.72516865 0.032505784, + -0.64896995 -0.76005089 0.034069397, + -0.64791995 -0.75941688 0.059040394, + -0.60738772 -0.79201567 0.061574772, + -0.60572088 -0.7907868 0.088082775, + -0.56330711 -0.8211692 0.09146712, + -0.5609808 -0.81912571 0.11972295, + -0.51677108 -0.84712315 0.12381501, + -0.5137701 -0.84400618 0.15392803, + -0.46870399 -0.869021 0.15849, + -0.46504018 -0.8645553 0.19047807, + -0.41944891 -0.88651776 0.19531696, + -0.41521394 -0.88046288 0.22887197, + -0.36923009 -0.89944625 0.23380706, + -0.36456108 -0.89159322 0.26862007, + -0.31855989 -0.90760571 0.27344391, + -0.31368798 -0.89788288 0.30887896, + -0.2686511 -0.91084832 0.31334013, + -0.26378006 -0.89918125 0.34913209, + -0.22015792 -0.90932471 0.35307088, + -0.2154981 -0.89568043 0.38899517, + -0.17341605 -0.90333426 0.39231908, + -0.16919704 -0.88777423 0.42805308, + -0.12903805 -0.89323032 0.43068415, + -0.12549399 -0.87595886 0.46577594, + -0.087793373 -0.87952971 0.46767482, + -0.08509881 -0.86071914 0.50191706, + -0.049918178 -0.86277556 0.50311679, + -0.048213489 -0.84253281 0.53648287, + -0.015480299 -0.84341288 0.53704292, + -0.0148906 -0.82192302 0.56940401, + 0.015291805 -0.82191831 0.56940019, + 0.015881091 -0.84339154 0.53706473, + 0.048599508 -0.8425011 0.53649807, + 0.050307199 -0.86274999 0.50312197, + 0.085487023 -0.86068118 0.50191611, + 0.088182367 -0.87950569 0.46764681, + 0.12585902 -0.87592411 0.46574306, + 0.12940103 -0.89319623 0.43064609, + 0.16958198 -0.88772291 0.42800695, + 0.17380504 -0.90330023 0.39222509, + 0.21585092 -0.89563769 0.38889784, + 0.22050507 -0.9092623 0.35301512, + 0.26417804 -0.89909011 0.34906602, + 0.26903397 -0.91072088 0.31338197, + 0.31403592 -0.89774776 0.30891794, + 0.31889197 -0.90743989 0.27360696, + 0.36483109 -0.89143425 0.26878107, + 0.36947396 -0.89924687 0.23418798, + 0.4153879 -0.88028276 0.22924894, + 0.4196161 -0.88633126 0.19580404, + 0.46516812 -0.86438119 0.19095504, + 0.46884993 -0.86887491 0.15885898, + 0.51387215 -0.84387815 0.15428904, + 0.51692176 -0.8470456 0.12371594, + 0.56112504 -0.81904113 0.11962602, + 0.56349099 -0.821118 0.090791598, + 0.60590506 -0.79071814 0.087430306, + 0.60755485 -0.79192781 0.061053883, + 0.64809191 -0.75930887 0.058539193, + 0.64908969 -0.75991166 0.034884587, + 0.68788201 -0.72505897 0.033284601, + 0.68828595 -0.72527194 0.015589398, + 0.6552918 -0.7553038 0.010428997, + 0.65532696 -0.75534487 0.00083642389, + 0.65518296 -0.75523287 0.018933497, + 0.6553002 -0.75536817 0.00084023719, + 0.65525085 -0.75541085 0.00084023684, + 0.65521574 -0.75536972 0.010430097, + 0.64991891 -0.75989985 0.012554999, + 0.64942604 -0.75959909 0.035427704, + 0.6092031 -0.79215318 0.036946107, + 0.60996211 -0.79219717 0.019231904, + 0.6095401 -0.79186916 0.037471708, + 0.56766999 -0.82233602 0.038913399, + 0.56856406 -0.82253313 0.013201102, + 0.56802297 -0.8220669 0.039445296, + 0.52458793 -0.85037786 0.040803798, + 0.52533793 -0.8506189 0.021624798, + 0.52490795 -0.85015786 0.041270696, + 0.48062488 -0.87589478 0.042520087, + 0.47954413 -0.87461418 0.071326315, + 0.43435714 -0.89776027 0.073213927, + 0.43271908 -0.89548326 0.10423102, + 0.38661405 -0.91605711 0.10662601, + 0.38446501 -0.91254002 0.13948999, + 0.33771586 -0.9304406 0.14222592, + 0.3351911 -0.92552722 0.17620005, + 0.28870398 -0.94052589 0.17905599, + 0.2859441 -0.93408138 0.21384108, + 0.240087 -0.946271 0.21663199, + 0.23725297 -0.93818486 0.25203198, + 0.19216697 -0.94775987 0.25460398, + 0.18943807 -0.93795538 0.29043609, + 0.14540601 -0.94510013 0.29264802, + 0.14298907 -0.93362743 0.32847214, + 0.10081396 -0.93851465 0.33019188, + 0.098889776 -0.92543876 0.36576492, + 0.058583487 -0.92839974 0.36693591, + 0.057315007 -0.9137851 0.40213406, + 0.0188176 -0.91512799 0.402724, + 0.018363604 -0.89909023 0.43737808, + -0.017998094 -0.89909673 0.43737984, + -0.018451603 -0.91512626 0.4027451, + -0.056883916 -0.91380024 0.40216109, + -0.058152884 -0.92842877 0.3669309, + -0.098470964 -0.92548263 0.36576688, + -0.100396 -0.93856299 0.33018199, + -0.14262602 -0.93368512 0.32846603, + -0.14504805 -0.94517833 0.29257312, + -0.18909107 -0.93804735 0.2903651, + -0.19182892 -0.94788063 0.2544089, + -0.23697001 -0.938308 0.25184, + -0.23981509 -0.94642234 0.21627207, + -0.28574592 -0.93422365 0.21348393, + -0.2884959 -0.94063962 0.17879394, + -0.33501887 -0.92563862 0.17594194, + -0.33752012 -0.93049937 0.14230704, + -0.38426283 -0.91261256 0.13957193, + -0.38638505 -0.91609114 0.10716201, + -0.43244416 -0.8955543 0.10475904, + -0.43409595 -0.89785385 0.073615089, + -0.47930512 -0.87471318 0.071717717, + -0.48042294 -0.87603891 0.041826997, + -0.5247851 -0.85026616 0.040596411, + -0.52525681 -0.85075772 0.017793894, + -0.53475302 -0.84500402 -0.00272795, + -0.53474092 -0.84498489 0.0072599989, + -0.53465891 -0.8450368 0.0072607282, + -0.53467 -0.84505397 -0.00344828, + -0.53669024 -0.84377342 -0.0031686414, + -0.29751298 -0.95353091 0.047589593, + -0.29665184 -0.95156151 0.080798365, + -0.24997795 -0.96477973 0.08192078, + -0.24883488 -0.96158451 0.11591595, + -0.20233607 -0.97227734 0.11720505, + -0.20104004 -0.96772724 0.15194403, + -0.15492003 -0.97597021 0.15323803, + -0.15362903 -0.96998227 0.18850105, + -0.10867795 -0.9758215 0.1896349, + -0.10755005 -0.96834147 0.2252731, + -0.063803628 -0.9720065 0.22612511, + -0.063008308 -0.96305615 0.26182604, + -0.020484801 -0.96477109 0.26229203, + -0.020183891 -0.95437151 0.29793885, + 0.020560507 -0.95436436 0.29793611, + 0.020862095 -0.96474373 0.26236293, + 0.063345782 -0.96301574 0.26189294, + 0.064140819 -0.97195935 0.22623208, + 0.10784198 -0.96828479 0.22537693, + 0.10896904 -0.97575939 0.18978807, + 0.15386704 -0.96991521 0.18865204, + 0.15516493 -0.97593552 0.15321092, + 0.20128404 -0.96768111 0.15191501, + 0.20258804 -0.9722631 0.11688702, + 0.24910305 -0.96155322 0.11559903, + 0.25024495 -0.96473575 0.081623577, + 0.29693505 -0.95149821 0.08050362, + 0.36261618 -0.93188941 0.0095746145, + 0.36263201 -0.93193102 -0.00160814, + 0.36270192 -0.93190378 -0.0016002797, + 0.3626861 -0.93186224 0.009574132, + 0.34483203 -0.93836111 0.023861405, + 0.34445289 -0.93761164 0.047292583, + 0.29777893 -0.95342278 0.048090089, + 0.26954398 -0.9629339 0.010218899, + 0.31636214 -0.94807047 0.032826714, + 0.29842788 -0.95424867 0.018715793, + 0.29802799 -0.95332903 0.048405498, + 0.25142699 -0.966631 0.049080901, + 0.25068608 -0.96457535 0.08216463, + 0.20402411 -0.97543347 0.083089538, + 0.20306696 -0.97209477 0.11745397, + 0.15665695 -0.98052174 0.11847197, + 0.15562993 -0.97577852 0.15373893, + 0.11026897 -0.98179066 0.15468594, + 0.10933796 -0.97563964 0.19019093, + 0.065055601 -0.97944498 0.190933, + 0.064381287 -0.97188479 0.22648394, + 0.021262705 -0.97368526 0.22690307, + 0.021000592 -0.96470267 0.26250291, + -0.020694895 -0.96470875 0.26250494, + -0.020957194 -0.97369975 0.22686894, + -0.064115785 -0.97190976 0.22645193, + -0.064791478 -0.97947663 0.19085993, + -0.10912198 -0.97567779 0.19011895, + -0.11004995 -0.98181152 0.15470992, + -0.15538298 -0.97581375 0.15376496, + -0.15640505 -0.98053122 0.11872703, + -0.20276308 -0.97212738 0.11771005, + -0.203721 -0.97548097 0.083274998, + -0.25032902 -0.96465212 0.082350604, + -0.25108188 -0.96674454 0.048608977, + -0.29778907 -0.95342726 0.047939312, + -0.29820493 -0.95437074 0.015819496, + -0.31354997 -0.94953489 0.0083604995, + -0.31353316 -0.9495405 0.0083605833, + -0.34462798 -0.93850189 0.021113098, + -0.34422889 -0.93771863 0.046800487, + 0.43669409 -0.89930826 0.023301706, + 0.43627694 -0.89870787 0.044569798, + 0.39046985 -0.91948563 0.045600284, + 0.38946885 -0.91786367 0.07642097, + 0.34275308 -0.93618625 0.077946514, + 0.34130913 -0.93341237 0.11067703, + 0.29449594 -0.94900477 0.11252597, + 0.29270789 -0.94488162 0.14669994, + 0.24627097 -0.9577269 0.14869398, + 0.24429494 -0.95215279 0.18364395, + 0.19834104 -0.96239626 0.18561904, + 0.19634308 -0.95530033 0.22102207, + 0.15105103 -0.96308523 0.22282407, + 0.14920004 -0.95441025 0.25853506, + 0.10545103 -0.95983225 0.26000407, + 0.10391898 -0.94955873 0.29586995, + 0.061675508 -0.95291013 0.29691502, + 0.060642909 -0.9411611 0.33247304, + 0.019964807 -0.94270837 0.33302012, + 0.019587198 -0.92956287 0.36814296, + -0.019201001 -0.92957014 0.36814502, + -0.019577209 -0.94270349 0.33305714, + -0.060270313 -0.94117022 0.33251509, + -0.061303269 -0.9529435 0.29688486, + -0.103567 -0.94960499 0.295845, + -0.10510202 -0.95990413 0.25988004, + -0.14889507 -0.95449048 0.25841513, + -0.15075105 -0.96318936 0.22257708, + -0.19607991 -0.95541054 0.2207789, + -0.19807291 -0.96248651 0.1854369, + -0.24410889 -0.95223552 0.1834619, + -0.246071 -0.95776999 0.148747, + -0.29251984 -0.94493151 0.14675292, + -0.29428807 -0.94901526 0.11298103, + -0.34102008 -0.93346423 0.11113003, + -0.34247303 -0.93625909 0.07830181, + -0.38920316 -0.91794735 0.076770432, + -0.39023283 -0.91961557 0.045007177, + -0.43610579 -0.89881957 0.043989379, + -0.43655407 -0.89945614 0.019980501, + -0.44938707 -0.89330512 0.007570561, + -0.44939715 -0.89332527 -0.0034834212, + -0.40507707 -0.91428214 0.00086408114, + -0.40500176 -0.91431546 0.0008640805, + -0.40510982 -0.9142676 0.00085881958, + -0.4050979 -0.91424078 0.0077053881, + -0.40498984 -0.9142887 0.0077061071, + -0.40506491 -0.91425574 0.0076759681, + -0.39101282 -0.92015558 0.02056309, + -0.39058414 -0.91944337 0.045475516, + -0.34390888 -0.93785661 0.046386287, + -0.34295601 -0.93602997 0.078924499, + -0.296215 -0.95174402 0.080249503, + -0.29490405 -0.94873226 0.11374903, + -0.248339 -0.96178502 0.115314, + -0.24679388 -0.95744854 0.14961593, + -0.20045404 -0.96795624 0.15125804, + -0.19881396 -0.96216875 0.18629095, + -0.15304603 -0.97020125 0.18784705, + -0.15147702 -0.96288925 0.22338106, + -0.10701005 -0.9685365 0.22469111, + -0.105682 -0.959674 0.26049399, + -0.062639728 -0.96318346 0.26144612, + -0.061720692 -0.9527849 0.29730698, + -0.020059697 -0.95441288 0.29781497, + -0.019719495 -0.94265175 0.33319491, + 0.020141898 -0.94264388 0.33319196, + 0.020482501 -0.95439011 0.29785904, + 0.0621025 -0.952748 0.297346, + 0.063019767 -0.96312851 0.26155689, + 0.10601602 -0.95960814 0.26060104, + 0.10734203 -0.96846533 0.22483908, + 0.15168793 -0.96282166 0.22352892, + 0.15325806 -0.97014433 0.18796808, + 0.19902597 -0.96210188 0.18640998, + 0.20067203 -0.96792012 0.15120001, + 0.24698888 -0.95740753 0.14955692, + 0.24854791 -0.96177763 0.11492495, + 0.29516602 -0.94869709 0.11336201, + 0.29647306 -0.95169121 0.079923019, + 0.3432599 -0.93594575 0.078600675, + 0.34419098 -0.93772489 0.046953093, + 0.39079419 -0.91932642 0.046031922, + 0.3911981 -0.92000425 0.023588806, + 0.40790391 -0.91297376 0.0096538486, + 0.40792301 -0.91301602 0.00079902902, + 0.40794101 -0.91300797 0.00079902902, + 0.40792194 -0.91296589 0.0096465787, + 0.40793586 -0.91295969 0.0096464762, + 0.4079549 -0.91300178 0.00079832383, + 0.45225286 -0.89188069 -0.0040174085, + 0.45223594 -0.8918469 0.0095785093, + 0.45217094 -0.89187986 0.0095790988, + 0.45218995 -0.8919189 -0.0022392597, + 0.44708893 -0.89448488 -0.0028866297, + 0.53741723 -0.84331143 -0.0029418613, + 0.53669071 -0.84377354 -0.0030425582, + 0.35275099 -0.93571001 -0.00369044, + 0.31648988 -0.94859564 0.00064875977, + 0.31647512 -0.94854933 0.0098900236, + 0.31656387 -0.94851965 0.0098894965, + 0.31657898 -0.9485659 0.00064350793, + 0.31653312 -0.94858134 0.00064350822, + 0.26955789 -0.96298355 -0.0010472095, + 0.26964295 -0.96295977 -0.0010392098, + 0.26962903 -0.96291012 0.010218501, + 0.25193688 -0.96744555 0.024018388, + 0.25162894 -0.96656579 0.04932959, + 0.20496596 -0.97749686 0.049887493, + 0.20434304 -0.97533411 0.083471105, + 0.15778694 -0.98387665 0.08420217, + 0.15703095 -0.98040974 0.11890297, + 0.11133499 -0.98655391 0.11964899, + 0.11059597 -0.98169678 0.15504797, + 0.065857992 -0.98561186 0.15566598, + 0.065298617 -0.97937822 0.19119205, + 0.021572892 -0.98124462 0.19155593, + 0.021349907 -0.97366238 0.22699307, + -0.021079002 -0.9736681 0.22699402, + -0.02130289 -0.9812575 0.19151992, + -0.065071017 -0.97940022 0.19115704, + -0.065630622 -0.98562235 0.15569606, + -0.11038397 -0.98171574 0.15507898, + -0.11111894 -0.9865514 0.11986993, + -0.15675093 -0.9804275 0.11912594, + -0.15750694 -0.98390561 0.084387973, + -0.20404108 -0.97538137 0.083656929, + -0.20467097 -0.97757685 0.049529694, + -0.25137991 -0.96664864 0.048975982, + -0.21894702 -0.97569013 0.0095411111, + -0.21904907 -0.97566724 0.0095407516, + -0.25170007 -0.96756023 0.021778205, + -0.26654088 -0.96378154 0.009006625, + -0.26655096 -0.96381986 -0.0014030599, + -0.26655796 -0.96381789 -0.0014024499, + -0.26654696 -0.96377987 0.009006599, + -0.31340891 -0.94921178 0.027782392, + -0.31353 -0.94957799 0.00075268501, + -0.3135609 -0.94956774 0.00075268483, + -0.31354412 -0.94957334 0.00075365527, + -0.35970801 -0.93305498 -0.0043090298, + -0.35970098 -0.9330349 0.0078160195, + -0.35968 -0.933043 0.0078161499, + -0.35968992 -0.93306977 -0.0020112596, + -0.35275191 -0.93571275 -0.0027916294, + -0.44708878 -0.89448458 -0.0029784087, + -0.44929716 -0.89337832 -0.002698411, + -0.44928595 -0.89335591 0.0075713089, + -0.49257189 -0.86996084 0.023261795, + -0.49270499 -0.87019598 0.00090223999, + -0.49269405 -0.87020212 0.00090224011, + -0.49264812 -0.87022817 0.00090428925, + -0.49263513 -0.87020516 0.0073235319, + -0.49268112 -0.87017918 0.0073231617, + -0.48134983 -0.8764537 0.011454796, + -0.48079413 -0.87581027 0.042350911, + -0.43572995 -0.89902687 0.043473598, + -0.43464506 -0.89752614 0.074367106, + -0.38868505 -0.9182241 0.07608211, + -0.38711792 -0.91566777 0.10813098, + -0.34035304 -0.9338091 0.11027402, + -0.33838999 -0.930013 0.143416, + -0.29172993 -0.94532675 0.14577697, + -0.28948003 -0.94010711 0.18000002, + -0.24322006 -0.95266622 0.18240404, + -0.24083006 -0.94589126 0.21746404, + -0.19517691 -0.95583254 0.2197499, + -0.19280905 -0.94738525 0.25551105, + -0.14808008 -0.95485747 0.25752613, + -0.14593597 -0.94474673 0.29352394, + -0.10287598 -0.94990379 0.29512593, + -0.10114396 -0.93821353 0.33094585, + -0.059807878 -0.94136167 0.33205587, + -0.058658723 -0.92820233 0.36742312, + -0.019038698 -0.92963487 0.36798996, + -0.018623507 -0.91505229 0.40290514, + 0.019008197 -0.91504574 0.40290192, + 0.019424893 -0.92962766 0.36798787, + 0.059075922 -0.92817938 0.36741412, + 0.060225978 -0.94133365 0.33205989, + 0.10155102 -0.93817025 0.33094409, + 0.10327902 -0.94983524 0.29520607, + 0.14629397 -0.94466776 0.29359993, + 0.14843298 -0.9547559 0.25769898, + 0.19312507 -0.94727534 0.25568008, + 0.19548407 -0.95570236 0.22004308, + 0.24104509 -0.94576937 0.21775608, + 0.243441 -0.95256698 0.18262701, + 0.289655 -0.94001102 0.18021999, + 0.29192293 -0.94527477 0.14572798, + 0.33860788 -0.92994165 0.14336395, + 0.34059486 -0.93378156 0.10975995, + 0.3873691 -0.91562122 0.10762502, + 0.38892505 -0.91815412 0.075698905, + 0.4349241 -0.89742225 0.073989712, + 0.43597493 -0.89887488 0.044155195, + 0.48097593 -0.87567788 0.043015696, + 0.48140213 -0.87620723 0.022649106, + 0.49539882 -0.86861467 0.0094062863, + 0.49542081 -0.8686527 0.00088685669, + 0.49534687 -0.86869484 0.00088685675, + 0.49532482 -0.86865669 0.0094335964, + 0.49547887 -0.86856884 0.0094320485, + 0.49550095 -0.86860687 0.00087998086, + 0.53741723 -0.84331042 -0.0032080116, + 0.57797492 -0.81570387 0.023918996, + 0.57814008 -0.8159371 0.00090023311, + 0.57818872 -0.81590259 0.00090023258, + 0.57816195 -0.81586486 0.0096586589, + 0.57808292 -0.81592089 0.0096596386, + 0.57810909 -0.8159591 0.0009038311, + 0.61745578 -0.78660172 -0.0024770291, + 0.61742586 -0.78656381 0.010132197, + 0.61740905 -0.78657711 0.010132501, + 0.61743623 -0.78661227 -0.0037215315, + 0.62061208 -0.78411114 -0.0032478406, + 0.2546649 -0.96702164 -0.0038567185, + 0.22211507 -0.97502035 0.00041317815, + 0.2221029 -0.97496754 0.010419595, + 0.2220809 -0.97497255 0.010419696, + 0.22209311 -0.97502548 0.00041480121, + 0.22195707 -0.97505635 0.00041480115, + 0.221854 -0.974603 0.0304926, + 0.20543292 -0.97844863 0.020871492, + 0.20514904 -0.97744721 0.050108112, + 0.15859808 -0.98604846 0.050549023, + 0.15810402 -0.98379409 0.084571704, + 0.11220101 -0.9900341 0.085108109, + 0.11165395 -0.98647451 0.12000594, + 0.066565 -0.99048001 0.120493, + 0.066120461 -0.98554939 0.15594991, + 0.0218064 -0.98747599 0.15625501, + 0.021622607 -0.98123336 0.19160807, + -0.021388305 -0.98123825 0.19160904, + -0.021573406 -0.98748326 0.15624203, + -0.065855093 -0.98556888 0.15593898, + -0.066299073 -0.99047953 0.12064294, + -0.11137397 -0.98648775 0.12015697, + -0.11191905 -0.99005646 0.085220136, + -0.15776205 -0.98383921 0.084684923, + -0.15825906 -0.98611933 0.050227419, + -0.20488593 -0.97751862 0.04978938, + -0.20518197 -0.9785549 0.018181099, + -0.21891697 -0.97539085 0.026230097, + -0.21899305 -0.97572625 0.0005737741, + -0.21895708 -0.97573435 0.00057377422, + -0.21905793 -0.97571164 0.00056614081, + -0.25466502 -0.96702212 -0.0037548405, + -0.15389703 -0.98807925 -0.003899331, + -0.12233499 -0.99248886 0.00032403597, + -0.12232704 -0.99242735 0.011140903, + -0.12234304 -0.99242538 0.011140903, + -0.12235 -0.99248701 0.000322482, + -0.12227194 -0.99249655 0.00032248185, + -0.12224196 -0.99225062 0.022260392, + -0.11272798 -0.99344087 0.019174699, + -0.11256104 -0.99233836 0.050937019, + -0.06708128 -0.99643564 0.051147383, + -0.066867433 -0.99406147 0.085852534, + -0.021904506 -0.99605227 0.086024426, + -0.021796808 -0.99241036 0.12102304, + 0.022087902 -0.9924041 0.12102202, + 0.022198098 -0.99604887 0.085987195, + 0.067190103 -0.99404299 0.085813999, + 0.067406371 -0.99640751 0.051267873, + 0.11284303 -0.99230021 0.051056612, + 0.11300405 -0.99336046 0.021568011, + 0.12533402 -0.99178523 0.025565905, + 0.12537506 -0.99210948 0.00012096906, + 0.12552199 -0.99209088 0.00012096899, + 0.12551394 -0.99202955 0.011114795, + 0.12544897 -0.99203777 0.011114897, + 0.12545702 -0.99209911 0.00012746002, + 0.153897 -0.98807901 -0.0039516301, + 0.10280795 0.99469352 -0.003915648, + 0.071956687 0.99740773 0.00026847795, + 0.071949735 0.99731046 -0.013969907, + 0.11246701 0.99358511 -0.011831002, + 0.12076703 0.99257624 -0.014413704, + 0.12077902 0.99267912 -0.00077198411, + 0.12076104 0.99268138 -0.0007729893, + 0.12074892 0.99257839 -0.014413692, + 0.169328 0.985502 -0.0106694, + 0.16933702 0.98555809 0.00053772307, + 0.169314 0.98556203 0.00053772301, + 0.16929598 0.98545587 -0.014681998, + 0.16930895 0.98545367 -0.014681994, + 0.16932696 0.98555976 0.0005366499, + 0.20454805 0.97884923 -0.003782881, + 0.30412212 0.95262635 -0.0035832615, + 0.26509103 0.96422315 0.00072643004, + 0.26506191 0.96411765 -0.014805694, + 0.29805011 0.95448834 -0.010873504, + 0.31202102 0.9499591 -0.014852902, + 0.31205505 0.95006222 -0.0018901405, + 0.31202111 0.95007336 -0.0018937207, + 0.31198707 0.94997025 -0.014853003, + 0.35822588 0.93359065 -0.009092167, + 0.3582409 0.93362874 0.0008514768, + 0.35819808 0.93364525 0.00085147715, + 0.3581591 0.93354326 -0.014806003, + 0.358183 0.93353403 -0.0148058, + 0.35822204 0.93363613 0.00085023814, + 0.40361205 0.91492313 -0.0036278705, + 0.40357095 0.91483188 -0.014598298, + 0.40352708 0.91485125 -0.014598603, + 0.40356886 0.91494572 -0.0025678691, + 0.40045491 0.91631174 -0.0029416992, + 0.49254277 0.87028259 -0.0031348085, + 0.49130005 0.87098414 -0.0032999006, + 0.49125287 0.87090284 -0.014106196, + 0.53340304 0.84580511 -0.009741311, + 0.53342801 0.84584498 0.00088085898, + 0.53342992 0.84584385 0.00088085886, + 0.53337985 0.8457638 -0.013767396, + 0.53335404 0.84578013 -0.013767602, + 0.53340483 0.84585971 0.00088199071, + 0.57425892 0.81867087 -0.0021583198, + 0.574211 0.81860101 -0.0131964, + 0.57408881 0.81868672 -0.013197695, + 0.57413399 0.81875098 -0.0041251499, + 0.57941306 0.81502712 -0.0033671104, + 0.6601578 0.75111783 -0.0036883592, + 0.65191603 0.75827497 -0.0049608299, + 0.65187782 0.75823081 -0.011883497, + 0.68805903 0.72557008 -0.011086201, + 0.68810183 0.72561383 0.00061903783, + 0.68819636 0.72552437 0.00061903731, + 0.68815362 0.72547966 -0.011123095, + 0.72248602 0.69129199 -0.011373, + 0.72253293 0.69133592 -0.00096510287, + 0.72287405 0.69097906 -0.00098419411, + 0.72282773 0.69093478 -0.011367396, + 0.72486776 0.68881273 -0.010185896, + 0.72429985 0.68877482 -0.031288791, + 0.75808489 0.65148395 -0.029594796, + 0.75951946 0.65041441 -0.0095625259, + 0.75896698 0.65043098 -0.0301452, + 0.79058534 0.61169529 -0.028349914, + 0.79194212 0.61053705 -0.0084982505, + 0.7914049 0.61060894 -0.028895896, + 0.82103282 0.57024288 -0.026985694, + 0.82227618 0.5690341 -0.0078788018, + 0.82177186 0.56915194 -0.027513897, + 0.84936887 0.52718395 -0.025485096, + 0.84841514 0.52747709 -0.044270005, + 0.87331015 0.48545805 -0.040743504, + 0.87195581 0.48599789 -0.059153285, + 0.89439768 0.44399586 -0.05404098, + 0.8927204 0.4448362 -0.071909934, + 0.9131214 0.40246317 -0.065060027, + 0.91117239 0.40366417 -0.082584634, + 0.92974102 0.360742 -0.073803298, + 0.92758697 0.362358 -0.090989798, + 0.94431835 0.31912613 -0.080134131, + 0.94206876 0.32117191 -0.096721679, + 0.95715714 0.27726904 -0.083500206, + 0.95491225 0.27975807 -0.099388123, + 0.96852887 0.23453997 -0.083323695, + 0.96642452 0.23743288 -0.098230056, + 0.97865498 0.1899 -0.078565001, + 0.97684664 0.19309393 -0.092116073, + 0.98738915 0.14288601 -0.068164304, + 0.98604089 0.14614998 -0.079772092, + 0.99453902 0.091607898 -0.0500018, + 0.99381965 0.094384462 -0.058429476, + 0.99924988 0.032926697 -0.020383498, + 0.99916399 0.033876799 -0.0228847, + 0.99904388 -0.036227796 0.024472896, + 0.99892133 -0.037487917 0.027401209, + 0.98833275 -0.12296397 0.089878574, + 0.98635089 -0.12893699 0.10240699, + 0.953852 -0.235136 0.186755, + 0.94482189 -0.24863698 0.21328697, + 0.88384122 -0.3550511 0.30457106, + 0.86084998 -0.374291 0.34473699, + 0.76247698 -0.475912 0.43833399, + 0.71065009 -0.49883005 0.49613005, + 0.58261681 -0.5762558 0.57313782, + 0.49383211 -0.59067911 0.6381442, + 0.36016998 -0.63369793 0.68461996, + 0.24583894 -0.62691981 0.73927981, + 0.137631 -0.64061397 0.75542802, + 0.019276703 -0.61122108 0.79122514, + -0.051097024 -0.61053628 0.79033834, + -0.168171 -0.56103599 0.81052899, + -0.263313 -0.54905701 0.79322302, + -0.27772492 -0.54040384 0.79424971, + -0.29611787 -0.53730482 0.78969473, + -0.31900114 -0.52142525 0.79142535, + -0.32691601 -0.51993901 0.78917003, + -0.33837 -0.51093698 0.79022098, + -0.34061912 -0.5104962 0.78953928, + -0.32718086 -0.52202678 0.78768063, + -0.33000779 -0.52148372 0.78686053, + -0.31996989 -0.53072083 0.78482771, + -0.32183504 -0.53036708 0.78430414, + -0.31402299 -0.538104 0.78219801, + -0.31505689 -0.53790981 0.78191572, + -0.30846199 -0.544963 0.77965802, + -0.30760506 -0.54512215 0.77988517, + -0.30217907 -0.55140513 0.77758616, + -0.300161 -0.55177402 0.77810597, + -0.29500899 -0.55824798 0.77545398, + -0.29142895 -0.55888987 0.77634484, + -0.28666502 -0.56540406 0.77339613, + -0.28103 -0.56638801 0.77474302, + -0.27678013 -0.5727393 0.77159739, + -0.26901096 -0.57405293 0.77336687, + -0.26494995 -0.58072287 0.76978081, + -0.25490606 -0.58235115 0.77193916, + -0.25049299 -0.59036702 0.767281, + -0.23916806 -0.5921101 0.76954818, + -0.23447008 -0.60159922 0.76361132, + -0.22047794 -0.6036219 0.76617885, + -0.21590704 -0.61398911 0.75921118, + -0.199646 -0.61616099 0.76189703, + -0.19490796 -0.62838393 0.7530899, + -0.1768461 -0.63057333 0.75571346, + -0.172186 -0.64446098 0.74499798, + -0.15241601 -0.64658898 0.74745703, + -0.14818794 -0.66145974 0.73519474, + -0.12643898 -0.66347682 0.73743582, + -0.12266502 -0.67967504 0.72318405, + -0.099605039 -0.68144125 0.72506326, + -0.096460022 -0.6987192 0.7088632, + -0.071693443 -0.70018643 0.71035141, + -0.069367625 -0.71798426 0.69259423, + -0.043469697 -0.71903795 0.69360995, + -0.041994613 -0.73763621 0.67389119, + -0.0145046 -0.73821002 0.67441499, + -0.014185509 -0.75031847 0.66092443, + 0.014185509 -0.75031847 0.66092443, + 0.014509207 -0.73803234 0.6746093, + 0.041985918 -0.73745936 0.67408532, + 0.04344099 -0.71911985 0.6935268, + 0.069506191 -0.71805894 0.69250292, + 0.071846783 -0.70021784 0.7103048, + 0.096607476 -0.69874883 0.70881385, + 0.099723175 -0.6816808 0.72482181, + 0.12299501 -0.67989403 0.72292209, + 0.12676795 -0.66376078 0.73712379, + 0.14823693 -0.66176671 0.73490864, + 0.15253094 -0.64669275 0.74734378, + 0.17224805 -0.64456916 0.74489015, + 0.17690901 -0.63070107 0.75559211, + 0.19470103 -0.62854505 0.75300914, + 0.19944297 -0.61632097 0.76182085, + 0.21567497 -0.61415493 0.75914288, + 0.22025102 -0.60378706 0.76611412, + 0.23418695 -0.60177487 0.76355982, + 0.23876111 -0.59254932 0.76933634, + 0.25034896 -0.59076595 0.76702088, + 0.25476596 -0.58275592 0.77167988, + 0.26450506 -0.58117813 0.7695902, + 0.26859397 -0.57446891 0.7732029, + 0.27630687 -0.57316673 0.77144963, + 0.28057602 -0.56679606 0.77460915, + 0.28617594 -0.56581891 0.77327383, + 0.29075891 -0.55956084 0.77611268, + 0.29427594 -0.55893189 0.77523983, + 0.29946715 -0.55241925 0.77791536, + 0.30141997 -0.55206293 0.7774139, + 0.30721185 -0.54536474 0.77987063, + 0.30773115 -0.54526824 0.77973336, + 0.31484798 -0.53766096 0.78217089, + 0.31419292 -0.53778386 0.78234982, + 0.3220771 -0.52997309 0.78447115, + 0.32029596 -0.53031093 0.78497189, + 0.33043596 -0.52097493 0.78701788, + 0.32775185 -0.52149177 0.78779763, + 0.342875 -0.50848597 0.78986001, + 0.34092912 -0.50886917 0.79045528, + 0.33423102 -0.51417506 0.78988212, + 0.32727596 -0.51550496 0.79192489, + 0.290941 -0.540784 0.789244, + 0.27190396 -0.54393995 0.79384989, + 0.25689495 -0.55286288 0.79268384, + 0.22751793 -0.55705881 0.79869968, + 0.17326009 -0.58352929 0.79339439, + 0.120239 -0.58819199 0.79973298, + -0.023696491 -0.63550776 0.77173072, + -0.11833603 -0.63122016 0.76652318, + -0.25312003 -0.64886206 0.71757108, + -0.38760483 -0.61827171 0.68374169, + -0.49692017 -0.60836124 0.61884326, + -0.64184594 -0.53758192 0.54684496, + -0.7106728 -0.51235491 0.48211688, + -0.82798415 -0.40837908 0.38427708, + -0.86311501 -0.38163799 0.33073401, + -0.8860181 -0.34100202 0.31414902, + -0.76265419 -0.47570813 0.43824711, + -0.71152502 -0.49834999 0.49535799, + -0.58272856 -0.57636958 0.57290959, + -0.49493012 -0.59070909 0.63726521, + -0.36192602 -0.63372308 0.68367004, + -0.24715009 -0.62705225 0.73873025, + -0.13937797 -0.6408118 0.75493979, + -0.014961404 -0.60978311 0.79242718, + 0.055409681 -0.60891378 0.79129869, + 0.18025805 -0.55533612 0.8118552, + 0.21680093 -0.55115581 0.80574471, + 0.26092702 -0.52569908 0.80966514, + 0.28240615 -0.52239722 0.80457938, + 0.29322982 -0.51504272 0.80544853, + 0.30578011 -0.5129202 0.80212927, + 0.33543086 -0.48983976 0.80470061, + 0.33853889 -0.48926082 0.80375069, + 0.34323999 -0.48514599 0.80425102, + 0.34248301 -0.48528799 0.804488, + 0.32970297 -0.49740195 0.80242586, + 0.32967684 -0.49740675 0.80243367, + 0.32026002 -0.50696707 0.80026114, + 0.31939796 -0.50712293 0.80050689, + 0.31193218 -0.51528031 0.79823846, + 0.31000805 -0.51562214 0.79876715, + 0.30318296 -0.52367592 0.79614288, + 0.30033687 -0.52417082 0.79689568, + 0.29440886 -0.53174675 0.79408365, + 0.29016501 -0.53246897 0.79516101, + 0.28474092 -0.53999883 0.79203773, + 0.27886608 -0.54097116 0.79346329, + 0.27377608 -0.54868215 0.78993332, + 0.26600203 -0.54992509 0.79172313, + 0.261186 -0.55793101 0.78771502, + 0.25153992 -0.5594098 0.78980273, + 0.24694704 -0.56784105 0.78522211, + 0.23539194 -0.56952387 0.78754884, + 0.23067003 -0.57916707 0.78189313, + 0.21714699 -0.581016 0.78438997, + 0.21226603 -0.59220809 0.77732414, + 0.19665597 -0.59418392 0.7799179, + 0.19189003 -0.60661209 0.77149212, + 0.17460991 -0.6086027 0.77402467, + 0.16993693 -0.62267369 0.76380563, + 0.15038998 -0.62467796 0.7662639, + 0.14608808 -0.63998729 0.75437033, + 0.12518798 -0.64183897 0.75655186, + 0.12132298 -0.65859497 0.74265295, + 0.098247513 -0.66028607 0.74456006, + 0.095124848 -0.6776703 0.72918737, + 0.0709773 -0.67904001 0.73066199, + 0.0685836 -0.69758302 0.71321398, + 0.042981595 -0.69858396 0.71423596, + 0.04149279 -0.71765083 0.69516581, + 0.014313896 -0.7181958 0.69569385, + 0.013808802 -0.73753005 0.67517304, + -0.0135597 -0.73753297 0.67517501, + -0.014063506 -0.71795136 0.69595134, + -0.04131091 -0.71740919 0.69542617, + -0.04277442 -0.69855338 0.71427834, + -0.068432294 -0.69755393 0.71325696, + -0.070817314 -0.6790092 0.73070616, + -0.095228985 -0.67762393 0.72921693, + -0.098316826 -0.66042221 0.74443018, + -0.12142994 -0.65872669 0.74251866, + -0.12529494 -0.64195973 0.75643164, + -0.14618403 -0.64010817 0.75424916, + -0.15055299 -0.62454796 0.76633787, + -0.16988498 -0.62256593 0.76390487, + -0.17454205 -0.60851723 0.77410728, + -0.19211809 -0.60649133 0.77153033, + -0.1969839 -0.59378672 0.78013766, + -0.21234804 -0.5918411 0.77758116, + -0.21723203 -0.58062208 0.78465813, + -0.23107398 -0.57872796 0.78209889, + -0.23577188 -0.56912071 0.78772664, + -0.24709688 -0.56747073 0.78544265, + -0.25182706 -0.55877411 0.79016119, + -0.26149902 -0.55729103 0.78806412, + -0.2663089 -0.54927981 0.79206771, + -0.27413312 -0.54802823 0.79026335, + -0.27919289 -0.54034978 0.79377162, + -0.28541014 -0.53932023 0.79225934, + -0.29081681 -0.5318017 0.79536951, + -0.29509702 -0.53107303 0.7942791, + -0.30071297 -0.52388793 0.79693991, + -0.30356905 -0.52339113 0.79618317, + -0.31019995 -0.51555985 0.79873282, + -0.31211603 -0.51521903 0.79820609, + -0.31923598 -0.50743794 0.80037189, + -0.32004997 -0.50729096 0.8001399, + -0.3290709 -0.49813789 0.80222881, + -0.32935309 -0.49808612 0.80214518, + -0.34094399 -0.48711899 0.80403501, + -0.34102803 -0.48710304 0.80400914, + -0.33233896 -0.49465895 0.80303389, + -0.32802215 -0.49545124 0.80431938, + -0.31004679 -0.50941265 0.80272639, + -0.298585 -0.51137501 0.80581802, + -0.288625 -0.51820397 0.80508399, + -0.21127395 -0.52901989 0.8218888, + -0.11104195 -0.58086067 0.80639362, + -0.058687091 -0.58346796 0.81001288, + 0.048698813 -0.62152511 0.78187919, + 0.13194899 -0.616822 0.77596402, + 0.2441631 -0.63742423 0.73080426, + 0.35741702 -0.61389905 0.70383304, + 0.456377 -0.61326998 0.64468598, + 0.58277404 -0.56009406 0.58878607, + 0.65170157 -0.54427969 0.5282467, + 0.7640661 -0.46294907 0.44931206, + 0.80285311 -0.44309205 0.39886907, + 0.88532901 -0.34557199 0.31108299, + 0.90495813 -0.32748902 0.27166504, + 0.95942122 -0.21702504 0.18003105, + 0.96579051 -0.2065199 0.15683793, + 0.98952425 -0.11497103 0.087312624, + 0.99082136 -0.11080704 0.077426128, + 0.99912566 -0.034271687 0.02394739, + 0.99922264 -0.033232089 0.021207493, + 0.99930322 0.031463809 -0.020079006, + 0.99938887 0.030474596 -0.017124798, + 0.99486691 0.088217795 -0.049572792, + 0.99539024 0.086097024 -0.042255811, + 0.98803413 0.13845901 -0.067954406, + 0.98902547 0.13596006 -0.057823427, + 0.97957885 0.18502198 -0.07868959, + 0.98093945 0.18253408 -0.066627227, + 0.96968573 0.22954194 -0.083785675, + 0.97129446 0.22726111 -0.070282228, + 0.95848215 0.27242303 -0.084248707, + 0.96020621 0.27045506 -0.069700912, + 0.94574189 0.31463796 -0.081087492, + 0.94747323 0.31301808 -0.065682717, + 0.93118662 0.35677287 -0.074864171, + 0.93281078 0.35551891 -0.058909483, + 0.91451627 0.39910716 -0.06613192, + 0.91595775 0.3981919 -0.049644988, + 0.8956539 0.44133493 -0.055023994, + 0.89684826 0.44071612 -0.037850909, + 0.87431711 0.48357505 -0.041531805, + 0.87517476 0.48321688 -0.023887094, + 0.850043 0.52607101 -0.026005501, + 0.85051203 0.52590901 -0.0069983201, + 0.8690576 0.49471077 -0.00029469185, + 0.86900687 0.49468094 -0.010853199, + 0.86897612 0.49473506 -0.010854101, + 0.8690272 0.49476412 -0.00030181807, + 0.85730779 0.51478887 -0.0039761988, + 0.84373617 0.53675812 -8.762232e-005, + 0.84368271 0.53672481 -0.011229296, + 0.84369785 0.5367009 -0.011228898, + 0.81645954 0.57736164 -0.0068739858, + 0.81647915 0.57737505 7.9093908e-005, + 0.81638509 0.57750803 7.9093807e-005, + 0.81633216 0.57747114 -0.011356803, + 0.81635779 0.5774349 -0.011356197, + 0.81641042 0.57747227 8.4107647e-005, + 0.79983413 0.60020804 -0.0039601303, + 0.78703821 0.61690414 -0.0004964621, + 0.78709567 0.61683071 -0.00050021178, + 0.7870447 0.61679077 -0.011390496, + 0.78698719 0.61686414 -0.011391703, + 0.75593531 0.65458423 -0.0090157026, + 0.75596589 0.65461093 0.00038610093, + 0.75588518 0.65470415 0.0003861021, + 0.75583613 0.65466106 -0.011431001, + 0.75585186 0.65464294 -0.011430699, + 0.75590086 0.65468591 0.00038891894, + 0.73387474 0.67927378 -0.0038729587, + 0.97472966 -0.19173293 0.11463196, + 0.95106465 -0.2652069 0.15855993, + 0.94691676 -0.26928493 0.17559695, + 0.9181841 -0.33183601 0.21638604, + 0.91048026 -0.33698109 0.23972806, + 0.87218183 -0.3986069 0.28356895, + 0.8591451 -0.40422606 0.31380102, + 0.8105095 -0.46267474 0.35917479, + 0.7907328 -0.46742988 0.3952859, + 0.73235899 -0.51993102 0.439684, + 0.70694506 -0.52198905 0.47723806, + 0.64178431 -0.5659883 0.51746523, + 0.60845876 -0.56401581 0.55826885, + 0.54011989 -0.5981319 0.59203786, + 0.49765924 -0.59003532 0.63576227, + 0.4296791 -0.61425811 0.66186321, + 0.38005009 -0.59842014 0.70530516, + 0.31759 -0.61347002 0.72304302, + 0.2640889 -0.58950877 0.76337171, + 0.21028903 -0.59754103 0.77377212, + 0.15537998 -0.56575292 0.80980289, + 0.11219399 -0.56909192 0.8145839, + 0.058188684 -0.53042287 0.84573382, + 0.025793999 -0.531147 0.84688699, + -0.024416389 -0.48782375 0.87260056, + -0.047348693 -0.48742193 0.8718819, + -0.093159527 -0.44055414 0.89287931, + -0.10730204 -0.43992415 0.89160132, + -0.14747994 -0.39171785 0.9081887, + -0.15439194 -0.39129984 0.90721971, + -0.18996397 -0.34154698 0.9204669, + -0.19017491 -0.34153286 0.92042857, + -0.2214631 -0.29056314 0.93087441, + -0.21622097 -0.29091296 0.93199688, + -0.23403503 -0.25729203 0.93756515, + -0.23978899 -0.25692099 0.936212, + -0.23099893 -0.27591395 0.93301177, + -0.21882606 -0.27671105 0.93570626, + -0.21349095 -0.28949293 0.93306774, + -0.19938888 -0.29037482 0.93590945, + -0.19461598 -0.30321598 0.93283689, + -0.17841506 -0.30416611 0.93576235, + -0.17249493 -0.32227787 0.93079662, + -0.15620998 -0.32316592 0.93336076, + -0.150775 -0.34234199 0.92739898, + -0.133066 -0.34322101 0.92978102, + -0.128258 -0.36324099 0.92282498, + -0.11010299 -0.36403897 0.92485291, + -0.10590898 -0.38532093 0.91668487, + -0.086355075 -0.38605291 0.91842574, + -0.082832664 -0.40897679 0.90877759, + -0.062353514 -0.4095881 0.91013724, + -0.059741929 -0.4332442 0.89929444, + -0.037461605 -0.43371505 0.90027112, + -0.035797808 -0.45874012 0.88784921, + -0.0126372 -0.45899701 0.88834798, + -0.012074198 -0.48448589 0.87471581, + 0.011876203 -0.48448813 0.87471718, + 0.012449998 -0.45898294 0.88835788, + 0.035939891 -0.45872188 0.88785279, + 0.037595794 -0.43403792 0.90010977, + 0.059532192 -0.43357494 0.89914888, + 0.062188402 -0.40960699 0.91013998, + 0.082669631 -0.40899715 0.90878332, + 0.086155728 -0.38637215 0.91831034, + 0.10571002 -0.3856411 0.91657323, + 0.10991903 -0.36432713 0.92476135, + 0.12838596 -0.36351389 0.92269963, + 0.13322599 -0.34340298 0.9296909, + 0.15062501 -0.342538 0.927351, + 0.15609202 -0.32326803 0.93334514, + 0.17240894 -0.32237887 0.93077767, + 0.17866695 -0.30323693 0.93601578, + 0.19460797 -0.30230296 0.93313485, + 0.200212 -0.28719699 0.93671399, + 0.214807 -0.28628901 0.93375403, + 0.21783911 -0.27902111 0.9352504, + 0.22991011 -0.27822813 0.93259341, + 0.23552004 -0.26617503 0.93470913, + 0.24637906 -0.26543707 0.93211621, + 0.24620488 -0.26577288 0.93206656, + 0.25444493 -0.26518795 0.93001777, + 0.228035 -0.310022 0.92297697, + 0.2314899 -0.30976287 0.9222036, + 0.19587597 -0.36180198 0.9114449, + 0.19343004 -0.36198103 0.91189611, + 0.15326303 -0.4123041 0.89806223, + 0.14378904 -0.41289815 0.89935529, + 0.097816117 -0.46204805 0.8814441, + 0.079662271 -0.46279883 0.88287669, + 0.029223192 -0.50838691 0.86063284, + 0.0010220601 -0.50860399 0.861, + -0.05465319 -0.55053091 0.83302385, + -0.093559608 -0.54893708 0.83061111, + -0.15196407 -0.58470029 0.79688936, + -0.20249096 -0.5793159 0.78955084, + -0.26035097 -0.60698295 0.7508589, + -0.321621 -0.59526199 0.73635799, + -0.37701985 -0.61448175 0.69301379, + -0.44567186 -0.59390974 0.66981179, + -0.49404183 -0.60436875 0.62502879, + -0.56576085 -0.57317984 0.59277278, + -0.60535663 -0.57644862 0.5488627, + -0.6751616 -0.53423768 0.5086717, + -0.70432293 -0.53251594 0.46942094, + -0.76762301 -0.48077199 0.42380801, + -0.78802389 -0.47637993 0.38997495, + -0.84181386 -0.41766694 0.34191197, + -0.85666984 -0.41174492 0.31077793, + -0.97471499 -0.19172201 0.114775, + -0.95097589 -0.26534998 0.15885298, + -0.94675934 -0.26949108 0.17612906, + -0.91799301 -0.33198199 0.21697199, + -0.9101783 -0.33718312 0.24058908, + -0.87176281 -0.3988139 0.28456494, + -0.85844857 -0.40451583 0.31532985, + -0.80962384 -0.46291789 0.36085492, + -0.7903831 -0.46751007 0.39589006, + -0.73194325 -0.51997817 0.44032013, + -0.70717919 -0.52197814 0.47690311, + -0.64205301 -0.56599802 0.51712102, + -0.60860598 -0.56402701 0.558097, + -0.5399912 -0.59828824 0.59199727, + -0.49747211 -0.59019113 0.63576418, + -0.42982891 -0.6142959 0.66173083, + -0.38051373 -0.5985716 0.70492655, + -0.31767511 -0.61373323 0.72278225, + -0.26382595 -0.58963287 0.76336682, + -0.21043493 -0.59760278 0.77368468, + -0.15555391 -0.56583863 0.80970955, + -0.11236803 -0.56918311 0.81449616, + -0.058443975 -0.53058475 0.84561461, + -0.025245389 -0.53132379 0.84679258, + 0.025120895 -0.48787695 0.8725509, + 0.04725052 -0.48748618 0.87185133, + 0.093107931 -0.44057715 0.89287329, + 0.10764501 -0.43992805 0.89155811, + 0.14814493 -0.39132783 0.9082486, + 0.15469906 -0.39093116 0.90732628, + 0.19024505 -0.3411901 0.92054123, + 0.19048205 -0.3411741 0.92049825, + 0.22192089 -0.28991485 0.93096757, + 0.21662095 -0.29026893 0.93210477, + 0.23923397 -0.24736796 0.93892288, + 0.22925597 -0.24797997 0.94124788, + 0.22823989 -0.25017989 0.94091254, + 0.21660995 -0.25086194 0.94347674, + 0.21074601 -0.26506501 0.94091803, + 0.19749704 -0.26581407 0.94357723, + 0.19381496 -0.27584597 0.94145888, + 0.17788202 -0.27669302 0.94435114, + 0.17251594 -0.29334989 0.94031066, + 0.15545906 -0.29419512 0.94301736, + 0.14988007 -0.31418112 0.93745738, + 0.13214695 -0.31498289 0.93985265, + 0.12729804 -0.33546212 0.93341339, + 0.10923104 -0.3361901 0.93543833, + 0.10495004 -0.35820311 0.92772633, + 0.085613191 -0.35886997 0.9294529, + 0.082132228 -0.38179314 0.92059135, + 0.061661277 -0.38235787 0.92195463, + 0.059047509 -0.40629506 0.91183209, + 0.037260294 -0.40672192 0.91279179, + 0.035585605 -0.43206307 0.90114111, + 0.012403196 -0.43230385 0.90164268, + 0.011823105 -0.45840219 0.88866627, + -0.011993496 -0.45840082 0.88866472, + -0.012564202 -0.43228805 0.9016481, + -0.035761606 -0.43204609 0.90114224, + -0.037445687 -0.40639985 0.91292769, + -0.058929201 -0.40597799 0.91198099, + -0.061527301 -0.38204801 0.92209202, + -0.082330793 -0.38147393 0.92070585, + -0.085746706 -0.35891804 0.92942214, + -0.10539503 -0.35823813 0.92766237, + -0.10959203 -0.33664009 0.93523425, + -0.12760904 -0.33591112 0.93320936, + -0.13251497 -0.3151769 0.93973577, + -0.15020494 -0.31437388 0.93734062, + -0.15559398 -0.29507294 0.94272077, + -0.17224506 -0.29424611 0.94008034, + -0.17710601 -0.27917904 0.9437651, + -0.19259605 -0.27835205 0.94097126, + -0.19805293 -0.26347792 0.94411564, + -0.21173193 -0.26270792 0.94135761, + -0.22056103 -0.24120203 0.94507915, + -0.21729904 -0.24138306 0.94578826, + -0.20247905 -0.27278706 0.94052625, + -0.20970395 -0.27236295 0.93906474, + -0.18234405 -0.32229009 0.92891324, + -0.18392906 -0.32219312 0.92863435, + -0.15255599 -0.37128198 0.9159019, + -0.14860706 -0.37150812 0.91645932, + -0.11280899 -0.41962594 0.90065986, + -0.10206604 -0.42011616 0.9017123, + -0.061083384 -0.46732888 0.88197076, + -0.042596973 -0.46777874 0.88281846, + 0.002597901 -0.51210117 0.85892129, + 0.030150989 -0.51186985 0.85853368, + 0.079007372 -0.55219084 0.82996571, + 0.11634401 -0.55016106 0.82691413, + 0.16754998 -0.58511895 0.79344988, + 0.21423292 -0.57972884 0.78614169, + 0.26567611 -0.60797131 0.74818933, + 0.32137504 -0.59718108 0.73491007, + 0.37067702 -0.61790907 0.69338804, + 0.43333679 -0.5995937 0.67283469, + 0.47742519 -0.61254925 0.62995923, + 0.54359305 -0.58513606 0.60176605, + 0.57997084 -0.59124374 0.56041485, + 0.64494503 -0.55465901 0.52573699, + 0.67440975 -0.5557788 0.48608783, + 0.73504609 -0.51035905 0.44636405, + 0.75909215 -0.50785112 0.40726709, + 0.81267619 -0.45459312 0.3645581, + 0.82967985 -0.45004287 0.3302919, + 0.87378889 -0.39205095 0.28773096, + 0.8845787 -0.38708284 0.2601679, + 0.91930026 -0.32663408 0.21953906, + 0.92566788 -0.32218298 0.19833598, + 0.95176667 -0.26128292 0.16084594, + 0.95522022 -0.25776806 0.14529303, + 0.97394621 -0.19755705 0.11135503, + 0.99964386 0.025071196 -0.009146289, + 0.99964386 -0.025071597 0.0091464389, + 0.99962914 -0.025268104 0.010155201, + 0.99650002 -0.0775626 0.0311723, + 0.9963339 -0.078260891 0.034554597, + 0.98945564 -0.13249595 0.058501378, + 0.98865753 -0.13434695 0.067135073, + 0.97614026 -0.19423905 0.097064219, + 0.97841775 -0.18256995 0.096783079, + 0.9587521 -0.25113803 0.13313201, + 0.95585352 -0.25418189 0.14742993, + 0.93198961 -0.31355885 0.18186891, + 0.9266786 -0.31742486 0.20126691, + 0.89504242 -0.37664917 0.23881912, + 0.88605702 -0.38102701 0.26404801, + 0.84577614 -0.43853107 0.30389702, + 0.83166611 -0.44267505 0.33521703, + 0.78260988 -0.49627694 0.37580693, + 0.76163 -0.49898201 0.413445, + 0.70523465 -0.54592377 0.4523398, + 0.6774298 -0.54547387 0.49350488, + 0.61573911 -0.58430314 0.52863514, + 0.58333975 -0.57953984 0.56907684, + 0.51974809 -0.60957313 0.59856713, + 0.48113912 -0.59909314 0.6399942, + 0.41909593 -0.62048197 0.66284293, + 0.3746179 -0.60288686 0.7044068, + 0.3171781 -0.6166631 0.72050315, + 0.26971591 -0.59191877 0.75952971, + 0.22029097 -0.59959894 0.76938486, + 0.17179894 -0.56798381 0.80490971, + 0.13126101 -0.57156801 0.80998802, + 0.083626807 -0.53387004 0.84142113, + 0.052164018 -0.53501719 0.84322929, + 0.0076411199 -0.49303499 0.86997598, + -0.015037904 -0.49299312 0.86990321, + -0.055598907 -0.44800606 0.89230013, + -0.070963182 -0.44756788 0.89142978, + -0.10702295 -0.40088081 0.90985757, + -0.114802 -0.40053099 0.90906298, + -0.14635907 -0.35297018 0.92411643, + -0.14821994 -0.35287088 0.92385763, + -0.17576009 -0.30450514 0.93615443, + -0.17191498 -0.30471498 0.93679988, + -0.19571789 -0.25585586 0.94669545, + -0.18746591 -0.25627589 0.94825053, + -0.19968092 -0.22702792 0.95319766, + -0.19978003 -0.22702304 0.95317811, + -0.191128 -0.251017 0.94892597, + -0.17606306 -0.25173607 0.95164633, + -0.17066301 -0.26870802 0.94798213, + -0.15441002 -0.26943803 0.95055813, + -0.14974307 -0.28638309 0.94634134, + -0.132085 -0.28711101 0.94874698, + -0.12721999 -0.30797297 0.94285089, + -0.10865398 -0.30865797 0.94494689, + -0.104517 -0.33028999 0.93807501, + -0.084714927 -0.33091512 0.93985033, + -0.081307396 -0.35378799 0.93178499, + -0.061139524 -0.35429913 0.93313134, + -0.058515623 -0.37882316 0.92361736, + -0.037158892 -0.37921092 0.92456377, + -0.035524111 -0.40448314 0.91385531, + -0.012229303 -0.40470809 0.91436422, + -0.011657997 -0.4314349 0.90206873, + 0.011481394 -0.43143579 0.90207058, + 0.0120637 -0.40470901 0.91436601, + 0.035023585 -0.40448982 0.91387159, + 0.036685709 -0.3788901 0.92471427, + 0.058065116 -0.37850508 0.92377621, + 0.060663808 -0.35427102 0.93317312, + 0.081186578 -0.35375291 0.93180877, + 0.084610879 -0.33082092 0.93989277, + 0.10444205 -0.33019614 0.93811649, + 0.10853304 -0.30884013 0.94490135, + 0.12712404 -0.30815512 0.94280434, + 0.13215205 -0.2866061 0.94889033, + 0.14985606 -0.28587708 0.94647634, + 0.15497003 -0.26729405 0.95107222, + 0.17165096 -0.26654693 0.94841379, + 0.17572494 -0.2537469 0.95117462, + 0.19038101 -0.253043 0.94853801, + 0.19617091 -0.23707688 0.95147854, + 0.20934305 -0.23641706 0.94883221, + 0.21110596 -0.23211394 0.94950378, + 0.22223794 -0.23152694 0.94710374, + 0.20316011 -0.27215511 0.94056249, + 0.21009797 -0.27174798 0.93915486, + 0.18268098 -0.32182598 0.92900789, + 0.18424909 -0.32173014 0.92873144, + 0.152891 -0.370823 0.91603202, + 0.14893495 -0.37104988 0.9165917, + 0.11281195 -0.4196128 0.90066558, + 0.10242803 -0.42008814 0.90168428, + 0.061655872 -0.46705979 0.88207358, + 0.042427599 -0.467529 0.88295901, + -0.0029067702 -0.51199406 0.85898411, + -0.029663989 -0.51177084 0.85860968, + -0.079120837 -0.55257457 0.8296994, + -0.11646795 -0.55053973 0.8266446, + -0.16732402 -0.58523905 0.79340911, + -0.21438999 -0.57980603 0.78604198, + -0.26582196 -0.60803592 0.74808496, + -0.32152101 -0.597238 0.73479998, + -0.37083691 -0.61796588 0.69325185, + -0.43349406 -0.59963906 0.67269307, + -0.47759894 -0.61259294 0.62978494, + -0.54346782 -0.58529675 0.60172278, + -0.58001602 -0.59141898 0.56018299, + -0.64522207 -0.55467504 0.52538007, + -0.67394918 -0.55577111 0.48673511, + -0.73463303 -0.51039898 0.446998, + -0.75814289 -0.50798094 0.40886995, + -0.81176531 -0.45492715 0.36616713, + -0.82897115 -0.45035806 0.33163902, + -0.87339514 -0.39215705 0.28878003, + -0.88435924 -0.3871381 0.26083106, + -0.91911626 -0.32674608 0.22014207, + -0.92556489 -0.32225096 0.19870597, + -0.95168722 -0.26137406 0.16116804, + -0.95518267 -0.2578209 0.14544596, + -0.97392488 -0.19759697 0.11147098, + -0.97560751 -0.19508791 0.10065096, + -0.98803079 -0.13708697 0.070726983, + -0.98871237 -0.13551804 0.063895725, + -0.99111563 -0.12531595 0.044560384, + -0.99076086 -0.12619798 0.049667694, + -0.98129326 -0.17914404 0.070505716, + -0.98043346 -0.18054709 0.078441635, + -0.96652412 -0.23532502 0.10224102, + -0.96477824 -0.23730806 0.11352503, + -0.94582754 -0.29288086 0.14011094, + -0.9426555 -0.29543185 0.15530792, + -0.91783237 -0.35137412 0.18471606, + -0.91248775 -0.35435691 0.20444396, + -0.88099241 -0.40981522 0.23644012, + -0.87250686 -0.41288295 0.26126498, + -0.83387828 -0.46641317 0.29513711, + -0.82120073 -0.46888882 0.32522687, + -0.77583271 -0.51843584 0.35959387, + -0.75793135 -0.51932025 0.39477417, + -0.70668083 -0.56326288 0.42817891, + -0.6827442 -0.5612511 0.4678221, + -0.62697518 -0.59841514 0.49880013, + -0.59699804 -0.59209704 0.54130805, + -0.53919387 -0.62157387 0.56825686, + -0.50532186 -0.61026889 0.61009985, + -0.44891989 -0.6319378 0.63176382, + -0.4132379 -0.61572587 0.67090684, + -0.36033902 -0.63073605 0.68726104, + -0.32169396 -0.60842693 0.72548592, + -0.27376911 -0.6180343 0.73694235, + -0.23365003 -0.58965105 0.77312315, + -0.19230397 -0.59511793 0.7802909, + -0.15235102 -0.56122708 0.81351912, + -0.11860497 -0.5638479 0.81731784, + -0.0807686 -0.52594799 0.84667301, + -0.054369673 -0.52689177 0.84819156, + -0.019166891 -0.48564577 0.87394559, + 0.00019979003 -0.48573506 0.87410611, + 0.032359887 -0.44182879 0.89651561, + 0.044588104 -0.44162107 0.89609313, + 0.07293921 -0.39652205 0.91512311, + 0.079823695 -0.39631295 0.91463888, + 0.10412596 -0.35123688 0.93047863, + 0.10533604 -0.35119212 0.93035936, + 0.12621097 -0.30584493 0.94367874, + 0.122341 -0.305994 0.94414002, + 0.13999394 -0.26067889 0.95522153, + 0.13169703 -0.26097807 0.95631921, + 0.14653894 -0.21534492 0.96548063, + 0.13378203 -0.21573804 0.96724325, + 0.14260508 -0.18285508 0.9727425, + 0.12681098 -0.18325098 0.97485286, + 0.12375597 -0.19705196 0.97255075, + 0.10618796 -0.19745593 0.97454363, + 0.10212796 -0.21993592 0.97015363, + 0.083156422 -0.22032607 0.97187525, + 0.080005422 -0.24272206 0.96679121, + 0.059932087 -0.24306494 0.96815675, + 0.057405572 -0.26806289 0.96168953, + 0.035856389 -0.2683329 0.96265864, + 0.034256112 -0.29452613 0.95502937, + 0.011921103 -0.29467806 0.95552224, + 0.011363696 -0.32177889 0.94674665, + -0.011459497 -0.32177791 0.94674575, + -0.012015197 -0.29435793 0.95561975, + -0.034330212 -0.29420611 0.95512533, + -0.035902988 -0.26838091 0.96264362, + -0.057078019 -0.26811609 0.96169436, + -0.059533093 -0.24378698 0.96799988, + -0.079585381 -0.24344595 0.96664375, + -0.082978271 -0.21929492 0.97212362, + -0.10232396 -0.21889792 0.97036767, + -0.10816102 -0.18640502 0.97650111, + -0.11837196 -0.18618694 0.97535765, + -0.11384704 -0.20631808 0.97183937, + -0.12785895 -0.20596392 0.97017062, + -0.115561 -0.25034201 0.961236, + -0.12480004 -0.25006109 0.96015334, + -0.11021895 -0.29340085 0.94961452, + -0.11559004 -0.29322112 0.94903135, + -0.097759813 -0.33758703 0.93620414, + -0.098489821 -0.3375631 0.93613625, + -0.077351294 -0.38213894 0.9208619, + -0.072735086 -0.38227192 0.92118275, + -0.048077177 -0.42669979 0.90311456, + -0.0385199 -0.42687699 0.90348899, + -0.010164397 -0.47068688 0.88224179, + 0.0060075712 -0.47070313 0.88227123, + 0.037562899 -0.512559 0.85782999, + 0.060240608 -0.51198906 0.85687715, + 0.09450464 -0.55098718 0.82914531, + 0.12379602 -0.54920703 0.82646614, + 0.16045998 -0.58484596 0.79511487, + 0.19718395 -0.58089089 0.78973681, + 0.23485506 -0.61186212 0.75529319, + 0.27825594 -0.60460889 0.74633884, + 0.31525815 -0.62993532 0.70978433, + 0.36459216 -0.61809433 0.69644237, + 0.40042886 -0.63805377 0.65768075, + 0.45345113 -0.6206131 0.63970417, + 0.48852113 -0.6358422 0.59753811, + 0.54423314 -0.6113441 0.57451612, + 0.57544363 -0.62109667 0.53207469, + 0.63126218 -0.58899415 0.50457311, + 0.65716779 -0.59390187 0.46412387, + 0.71007097 -0.55480891 0.43357393, + 0.73039192 -0.55609792 0.39658895, + 0.7784971 -0.51100904 0.36443403, + 0.79364181 -0.50995886 0.33177492, + 0.83589828 -0.46008417 0.29932711, + 0.8466081 -0.45778006 0.27146304, + 0.88248873 -0.40455186 0.23989891, + 0.88963044 -0.40182519 0.21701211, + 0.91889066 -0.34712389 0.18746994, + 0.92340022 -0.34451208 0.16924405, + 0.94653189 -0.28955698 0.14224699, + 0.94922012 -0.28733402 0.12814201, + 0.96695662 -0.2328359 0.10383796, + 0.96844202 -0.23111001 0.093317598, + 0.98153067 -0.17738993 0.071626179, + 0.98226136 -0.17617406 0.064230122, + 0.99122602 -0.124182 0.045274802, + 0.99152851 -0.12341794 0.040486481, + 0.99703336 -0.073135629 0.02399181, + 0.99712199 -0.072738603 0.021372801, + 0.99969274 -0.023783294 0.0069882381, + 0.99970347 -0.023628511 0.0058903326, + 0.99971187 0.023290697 -0.0058061094, + 0.99972177 0.023143895 -0.0045457189, + 0.9974941 0.069424011 -0.013635602, + 0.99755722 0.069107614 -0.010189103, + 0.99325699 0.114694 -0.016910199, + 0.99337488 0.11433399 -0.011581899, + 0.98698676 0.15998295 -0.016205996, + 0.98712552 0.15967892 -0.0092715053, + 0.97851288 0.20583896 -0.011951698, + 0.97862887 0.20562497 -0.0019518498, + -0.99008989 -0.12982799 0.053541694, + -0.98960066 -0.13100095 0.059407476, + -0.97887754 -0.18619591 0.084437862, + -0.97768879 -0.18805696 0.093589976, + -0.96173745 -0.24527712 0.12206706, + -0.95929825 -0.24791206 0.13522802, + -0.93731976 -0.30591893 0.16686895, + -0.93283826 -0.30930007 0.18478705, + -0.90379912 -0.36738503 0.21948902, + -0.89622313 -0.37126303 0.24279203, + -0.85923427 -0.42815614 0.27999809, + -0.84723341 -0.4319602 0.30920213, + -0.8020153 -0.48569518 0.34766611, + -0.78420311 -0.48839405 0.38274905, + -0.73157936 -0.53660524 0.42053121, + -0.70692939 -0.53675222 0.46059522, + -0.64886618 -0.57744312 0.49551213, + -0.61848521 -0.57359219 0.53709215, + -0.55768615 -0.60589623 0.56734121, + -0.52352989 -0.5973109 0.60756588, + -0.46245313 -0.62159312 0.63226515, + -0.42295107 -0.60685104 0.67293704, + -0.36559692 -0.62333989 0.69122082, + -0.32190186 -0.60163867 0.73103362, + -0.2705211 -0.61176831 0.74334234, + -0.22497196 -0.58331597 0.78046787, + -0.18075098 -0.58880192 0.78780788, + -0.13581493 -0.55463278 0.82093656, + -0.10043605 -0.55698925 0.82442445, + -0.057040885 -0.51759589 0.8537218, + -0.030723415 -0.51819521 0.8547104, + 0.0096457535 -0.47501418 0.87992531, + 0.028825887 -0.47483876 0.87960058, + 0.065015592 -0.42960793 0.9006719, + 0.076680094 -0.42925194 0.89992386, + 0.10859496 -0.38280186 0.91742563, + 0.114339 -0.38255399 0.91683102, + 0.14211196 -0.33546588 0.93127161, + 0.14178397 -0.33548191 0.93131578, + 0.16565093 -0.28823191 0.94312364, + 0.16025905 -0.28849208 0.94397533, + 0.18109499 -0.24003597 0.95372289, + 0.17103806 -0.24047509 0.95546734, + 0.1843821 -0.20383111 0.96148646, + 0.17054392 -0.20434889 0.96392751, + 0.16769393 -0.2135019 0.96244252, + 0.152044 -0.21405099 0.964917, + 0.14683206 -0.23350109 0.96120638, + 0.13048495 -0.23404092 0.96343064, + 0.12649195 -0.25164992 0.95951664, + 0.10778696 -0.2522099 0.96165067, + 0.10360897 -0.27470291 0.95593065, + 0.084158763 -0.27520987 0.95769352, + 0.080726504 -0.29888004 0.9508701, + 0.060111176 -0.29931587 0.95225865, + 0.057589285 -0.3235299 0.94446379, + 0.035992607 -0.3238571 0.94542122, + 0.034367889 -0.34967187 0.93624163, + 0.012116903 -0.3498531 0.93672621, + 0.011545697 -0.37669891 0.92626375, + -0.011699903 -0.37669808 0.92626226, + -0.012259898 -0.34986496 0.93671989, + -0.034828201 -0.34967899 0.93622202, + -0.036446203 -0.32388803 0.94539315, + -0.057682287 -0.32356292 0.94444674, + -0.060226414 -0.29906505 0.95233023, + -0.080476172 -0.29863688 0.95096767, + -0.083851911 -0.27531204 0.95769113, + -0.10361498 -0.27479795 0.95590276, + -0.10747795 -0.25400987 0.9612115, + -0.12577096 -0.25346091 0.95913464, + -0.13056105 -0.2323211 0.96383649, + -0.14730494 -0.23177092 0.96155262, + -0.154801 -0.203646 0.96672899, + -0.16053601 -0.203457 0.96583301, + -0.15282106 -0.22781408 0.96163738, + -0.16403802 -0.22739904 0.95988613, + -0.14631103 -0.27444705 0.95040625, + -0.15329102 -0.27415404 0.94939011, + -0.13274404 -0.32023913 0.93799037, + -0.13455406 -0.32016015 0.93775946, + -0.11058702 -0.36603203 0.92400813, + -0.10735399 -0.36616197 0.92433786, + -0.079430297 -0.41198501 0.907722, + -0.070471622 -0.41226315 0.90833527, + -0.038145881 -0.45779979 0.88823658, + -0.022586601 -0.45801601 0.88865697, + 0.013196696 -0.50128484 0.86518168, + 0.035729107 -0.50100911 0.86470419, + 0.075325318 -0.54195011 0.83702821, + 0.105755 -0.54044598 0.83470601, + 0.14699 -0.57659501 0.80369902, + 0.18576795 -0.57277989 0.79838181, + 0.22865114 -0.60421133 0.76331347, + 0.27485204 -0.59675008 0.75388712, + 0.31702298 -0.62204796 0.71592796, + 0.36963809 -0.60942709 0.7014032, + 0.40924409 -0.62822318 0.66170615, + 0.46620813 -0.60911709 0.64158118, + 0.50207782 -0.62177879 0.60108978, + 0.56150925 -0.59492427 0.57512832, + 0.59483498 -0.60260302 0.53201598, + 0.65337354 -0.5675106 0.50103366, + 0.68069869 -0.57034969 0.45972878, + 0.73511821 -0.52782118 0.42544815, + 0.7559275 -0.52720368 0.38811076, + 0.80461615 -0.47819212 0.3520301, + 0.81943285 -0.47559494 0.31990498, + 0.86111981 -0.42184892 0.28375393, + 0.87109941 -0.41844922 0.25707212, + 0.90511113 -0.36227202 0.22256003, + 0.91143769 -0.35887989 0.20121293, + 0.93818748 -0.30191216 0.16927308, + 0.94193649 -0.29898581 0.15284991, + 0.96227252 -0.24226488 0.12385194, + 0.96432376 -0.23998994 0.11173397, + 0.97917187 -0.18406199 0.085695595, + 0.98017889 -0.18245098 0.077207394, + 0.99022573 -0.12844697 0.05435469, + 0.99064213 -0.12743002 0.048886906, + 0.99673414 -0.075395711 0.028924603, + 0.99685514 -0.074869707 0.025968704, + 0.99966538 -0.024438109 0.0084764129, + 0.99967623 -0.024290005 0.0075888718, + 0.99967623 0.024290105 -0.007588902, + 0.99969727 0.023616906 -0.0069059818, + 0.99717426 0.072103612 -0.021084305, + 0.99729311 0.071536005 -0.017005103, + 0.99261975 0.11798097 -0.028045792, + 0.99285334 0.11730004 -0.021977007, + 0.9861201 0.16319402 -0.030575404, + 0.98643899 0.16252799 -0.022864301, + 0.97759533 0.20844108 -0.029323312, + 0.9779501 0.20787004 -0.020094302, + 0.96701938 0.25352108 -0.02450731, + 0.96733552 0.25311089 -0.014031493, + 0.95412922 0.29893607 -0.016571803, + 0.95434463 0.29868889 -0.0033646689, + 0.96314526 0.26886806 -0.0078302622, + 0.96317452 0.26887587 0.00072052167, + 0.96317345 0.26888013 0.00072052237, + 0.96314412 0.26887202 -0.0078301607, + 0.96315026 0.26885006 -0.0078297118, + 0.96317953 0.26885787 0.00072021165, + 0.97518313 0.22135402 -0.0045073302, + 0.97325897 0.229689 -0.00315552, + 0.99976212 -0.021793703 0.00085362012, + 0.99320436 -0.11482804 0.018966708, + 0.99975246 -0.02225141 -1.0057805e-005, + 0.99975061 -0.022285992 0.0014473496, + 0.99768698 -0.067833103 0.00440537, + 0.99765652 -0.067986071 0.0077052764, + 0.99334735 -0.11442403 0.012968404, + 0.9867785 -0.16099708 0.018662909, + 0.99341822 -0.11378203 0.013189703, + 0.99350649 -0.11352605 0.0075379037, + 0.99770164 -0.067611881 0.0044892984, + 0.9977141 -0.067550905 0.0018942202, + 0.99746567 -0.071147777 0.00044307485, + 0.99746335 -0.071147725 -0.0021972808, + 0.99975187 -0.022257898 0.00087705691, + 0.99975234 -0.022257907 1.5353306e-005, + 0.99975538 -0.022115188 1.2031192e-005, + 0.99975502 -0.0221151 0.00088522403, + 0.99975312 -0.022202702 0.00088522414, + 0.99975353 -0.022202689 -2.322979e-005, + 0.99976254 -0.02179369 -3.2552285e-005, + 0.99963814 0.026899103 -3.0869705e-005, + 0.99963289 0.026898896 -0.0032539996, + 0.99963897 0.0267101 -0.0029139, + 0.99966425 0.025738705 -0.0030083808, + 0.9917171 0.12840201 -0.0031744705, + 0.99219501 0.124642 -0.0036758599, + 0.984864 0.173223 -0.0060543702, + 0.98488152 0.17322691 0.0008475316, + 0.98493534 0.17292106 0.0008475323, + 0.98491776 0.17291796 -0.0060401387, + 0.98487073 0.17318496 -0.0060457285, + 0.98488849 0.17318809 0.00084531243, + 0.97519875 0.22132294 -0.0018602995, + 0.97517687 0.22131798 -0.0069625489, + 0.97516936 0.22135107 -0.0069632223, + 0.96768588 0.25214496 -0.0026268398, + 0.96752214 0.25238004 -0.014323601, + 0.97838914 0.20644003 -0.011716301, + 0.97816813 0.20680504 -0.020468501, + 0.98685473 0.16082396 -0.015917595, + 0.98663187 0.16129999 -0.023233298, + 0.99315751 0.11558995 -0.016649393, + 0.99298847 0.11609405 -0.022274811, + 0.99744499 0.070159703 -0.0134614, + 0.99735755 0.07058806 -0.017185593, + 0.99970478 0.023608595 -0.0057478184, + 0.99969453 0.023759089 -0.0068154265, + 0.99968922 -0.023962306 0.006873732, + 0.9996801 -0.024091205 0.0077121309, + 0.99699789 -0.07374239 0.023606597, + 0.99689448 -0.07419914 0.026381413, + 0.991117 -0.12530801 0.044553202, + 0.99076235 -0.12619005 0.049658619, + 0.98129612 -0.17913301 0.070493005, + 0.98043752 -0.18053491 0.07841786, + 0.96653253 -0.23530488 0.10220795, + 0.96479023 -0.23728406 0.11347303, + 0.94585025 -0.29284105 0.14004102, + 0.94268554 -0.29538685 0.15521093, + 0.91787934 -0.35131413 0.18459706, + 0.9125461 -0.35429204 0.20429602, + 0.8810783 -0.40973216 0.23626409, + 0.87263769 -0.41278684 0.26097992, + 0.83403015 -0.46633312 0.29483405, + 0.82144952 -0.46879774 0.32472983, + 0.77615154 -0.51833868 0.3590458, + 0.75844085 -0.51922792 0.39391595, + 0.70725638 -0.56321627 0.42728922, + 0.68366402 -0.561261 0.466465, + 0.62799805 -0.59849703 0.49741307, + 0.59825701 -0.59226698 0.53973001, + 0.54059482 -0.62181675 0.56665784, + 0.50589693 -0.61025792 0.60963392, + 0.44948927 -0.63197136 0.63132536, + 0.41340223 -0.61557037 0.67094845, + 0.36020708 -0.6306622 0.6873982, + 0.32150301 -0.60831302 0.72566599, + 0.27358297 -0.61791092 0.73711497, + 0.2334699 -0.58952475 0.77327371, + 0.19213608 -0.59498423 0.78043431, + 0.15218702 -0.56108904 0.81364512, + 0.11843898 -0.56370592 0.81743985, + 0.080859378 -0.52605987 0.84659481, + 0.054442398 -0.52700597 0.84811598, + 0.018983092 -0.48545483 0.87405568, + -3.150191e-005 -0.48554218 0.87421328, + -0.031979907 -0.44191211 0.89648825, + -0.044917785 -0.44169185 0.89604169, + -0.073134489 -0.39681393 0.91498089, + -0.079344325 -0.3966251 0.91454524, + -0.10391295 -0.35104582 0.9305746, + -0.10509702 -0.35100204 0.93045813, + -0.12586999 -0.30586496 0.9437179, + -0.12230797 -0.30600193 0.94414175, + -0.13966398 -0.26147297 0.95505285, + -0.13136801 -0.26177302 0.95614713, + -0.14632106 -0.21585707 0.96539938, + -0.13394302 -0.21623904 0.96710914, + -0.13988295 -0.19422293 0.97093266, + -0.13180596 -0.19443993 0.97201866, + -0.12510306 -0.22457311 0.96639347, + -0.10696802 -0.22505206 0.96845722, + -0.10278802 -0.24788903 0.96332014, + -0.08358369 -0.24833697 0.96506089, + -0.080338307 -0.27107003 0.9592011, + -0.060023684 -0.27145794 0.96057677, + -0.057507526 -0.29602215 0.95344847, + -0.036328182 -0.29631686 0.95439851, + -0.034733389 -0.32210189 0.94606763, + -0.011956798 -0.32227397 0.94657087, + -0.011409099 -0.34902796 0.93704289, + 0.0112793 -0.349029 0.93704402, + 0.011837503 -0.32225108 0.94658023, + 0.034291398 -0.32208398 0.94608986, + 0.035893295 -0.29625598 0.95443386, + 0.05711472 -0.29596311 0.95349038, + 0.059706185 -0.27067393 0.96081775, + 0.080081262 -0.27028689 0.95944351, + 0.083417021 -0.24689905 0.96544427, + 0.103369 -0.246435 0.96363097, + 0.10703298 -0.22642997 0.96812886, + 0.12478394 -0.2259589 0.96611154, + 0.12943293 -0.20517288 0.97012943, + 0.14596498 -0.20469697 0.9678809, + 0.14901605 -0.19320507 0.96977633, + 0.16391802 -0.19274303 0.96746111, + 0.15303394 -0.22728093 0.96172965, + 0.16429199 -0.22686499 0.95996898, + 0.14665706 -0.27372408 0.95056134, + 0.15329301 -0.27344504 0.94959414, + 0.13275103 -0.31956208 0.93822026, + 0.13490096 -0.31946787 0.93794566, + 0.11064597 -0.36590391 0.92405176, + 0.10775194 -0.3660208 0.92434746, + 0.079507023 -0.4123551 0.90754724, + 0.070533007 -0.41263404 0.90816212, + 0.038522504 -0.45771107 0.88826615, + 0.022984302 -0.45793006 0.88869113, + -0.013271297 -0.5017519 0.86490983, + -0.036188889 -0.50146681 0.8644197, + -0.075234383 -0.54182887 0.83711481, + -0.10564496 -0.5403288 0.83479571, + -0.14715202 -0.57671404 0.8035841, + -0.18557404 -0.57293409 0.79831618, + -0.22874995 -0.6045599 0.76300782, + -0.27496192 -0.59708875 0.75357872, + -0.31713897 -0.62236494 0.71560097, + -0.36976102 -0.60973108 0.70107406, + -0.40907815 -0.62837225 0.66166723, + -0.46633404 -0.60916609 0.64144307, + -0.50156194 -0.62160891 0.60169595, + -0.56124181 -0.59468573 0.57563585, + -0.59365499 -0.60220301 0.53378397, + -0.65204793 -0.56737393 0.50291193, + -0.67979181 -0.57030588 0.46112287, + -0.73427218 -0.52788711 0.42682508, + -0.75542098 -0.52728897 0.38898, + -0.80418581 -0.47831187 0.3528499, + -0.81918085 -0.47569788 0.3203969, + -0.86091256 -0.42196679 0.28420684, + -0.87096798 -0.418547 0.25735801, + -0.90501773 -0.36235392 0.22280595, + -0.91137826 -0.35894608 0.20136404, + -0.93814623 -0.30196905 0.16940005, + -0.94190514 -0.29903603 0.15294501, + -0.96225345 -0.24230212 0.12392806, + -0.96431035 -0.24002109 0.11178304, + -0.97916436 -0.18408506 0.085732333, + -0.98017377 -0.18246995 0.077228285, + -0.99022365 -0.12845695 0.054367881, + -0.99064046 -0.12743907 0.048896324, + -0.99665552 -0.07629396 0.029272787, + -0.99654776 -0.076750785 0.031652492, + -0.99667412 -0.074543908 0.032924604, + -0.98945236 -0.13250904 0.058526523, + -0.98887688 -0.13386199 0.06483379, + -0.9773711 -0.19037803 0.092206605, + -0.97596079 -0.19253495 0.10213098, + -0.95872778 -0.25117493 0.13323697, + -0.95581686 -0.25422996 0.14758499, + -0.93192559 -0.31363285 0.18206891, + -0.92656809 -0.31752703 0.20161404, + -0.89488614 -0.37676305 0.23922503, + -0.88581598 -0.381172 0.26464701, + -0.84539402 -0.438759 0.30463001, + -0.83095998 -0.44297799 0.33656499, + -0.78187388 -0.49640995 0.37716094, + -0.76068372 -0.49909881 0.41504285, + -0.70415878 -0.54593885 0.45399484, + -0.67697018 -0.54546314 0.49414712, + -0.615242 -0.58424401 0.52927899, + -0.58343691 -0.57955986 0.56895685, + -0.51985496 -0.60959995 0.59844697, + -0.48131806 -0.59914505 0.63981104, + -0.418962 -0.62064701 0.66277301, + -0.37472981 -0.60316771 0.70410663, + -0.31762701 -0.61688298 0.72011697, + -0.26987007 -0.5919981 0.75941318, + -0.22045 -0.599684 0.76927298, + -0.17164001 -0.56786108 0.80503011, + -0.13112803 -0.57143813 0.81010115, + -0.083816819 -0.53399915 0.84132016, + -0.051971424 -0.53516024 0.84315044, + -0.0077991718 -0.49353111 0.86969316, + 0.015273398 -0.49348894 0.86961788, + 0.056270592 -0.44803995 0.89224088, + 0.070888981 -0.44762185 0.89140868, + 0.10703396 -0.40082985 0.90987873, + 0.11483005 -0.40047914 0.90908229, + 0.14670493 -0.35242781 0.9242686, + 0.14856994 -0.35232788 0.92400867, + 0.17610106 -0.3039481 0.93627137, + 0.17226806 -0.30415711 0.93691635, + 0.19624799 -0.25487599 0.94685, + 0.18792599 -0.255299 0.94842303, + 0.203885 -0.216887 0.95466799, + 0.19148991 -0.21744089 0.95710552, + 0.18906392 -0.22419192 0.95602965, + 0.17448609 -0.2248071 0.95865345, + 0.16891804 -0.24252506 0.95532626, + 0.15316705 -0.24315809 0.95781738, + 0.14903702 -0.25836402 0.95448214, + 0.13174699 -0.25900397 0.95684886, + 0.12702805 -0.27953508 0.95169538, + 0.10785598 -0.28017396 0.95387089, + 0.10362605 -0.30261016 0.94746447, + 0.084326379 -0.30316493 0.94919974, + 0.080897607 -0.32646504 0.94174111, + 0.060674809 -0.32693502 0.94309711, + 0.058078878 -0.35145989 0.93439966, + 0.03645812 -0.35182017 0.93535739, + 0.034844894 -0.37702391 0.92554778, + 0.012089104 -0.37722614 0.92604238, + 0.011509495 -0.40417883 0.91460758, + -0.011674899 -0.40417793 0.91460586, + -0.012243497 -0.37722492 0.92604077, + -0.034997895 -0.37702194 0.92554289, + -0.036619496 -0.35151997 0.93546391, + -0.058251224 -0.35115817 0.93450242, + -0.060798217 -0.32700109 0.94306624, + -0.080978125 -0.32653108 0.94171125, + -0.084390879 -0.30329695 0.94915175, + -0.10399003 -0.30273306 0.94738525, + -0.10815199 -0.28064498 0.95369887, + -0.12694596 -0.2800169 0.95156467, + -0.13128296 -0.26116291 0.95632565, + -0.14847702 -0.26052403 0.95398211, + -0.153653 -0.241464 0.95816803, + -0.16946094 -0.24083091 0.95565861, + -0.17767005 -0.21456905 0.96041322, + -0.18084805 -0.21444204 0.95984823, + -0.17097393 -0.24141188 0.95524251, + -0.18063401 -0.240989 0.95357001, + -0.16007295 -0.28875393 0.94392675, + -0.16515006 -0.28851008 0.94312638, + -0.14128096 -0.33574691 0.93129677, + -0.14162198 -0.33573091 0.93125075, + -0.11394299 -0.38265795 0.91683686, + -0.10856296 -0.38288984 0.91739267, + -0.076742597 -0.429207 0.89994001, + -0.065089181 -0.42956385 0.90068769, + -0.028539503 -0.47524205 0.87939215, + -0.0096857734 -0.47541317 0.8797093, + 0.030176096 -0.51804495 0.85482091, + 0.057233814 -0.51743209 0.85380816, + 0.10063402 -0.55684304 0.82449913, + 0.13602096 -0.55448282 0.82100368, + 0.18094695 -0.58865774 0.78787071, + 0.224806 -0.58321798 0.78058898, + 0.27034813 -0.61167228 0.74348438, + 0.32138103 -0.60162604 0.73127306, + 0.36535203 -0.62346005 0.69124204, + 0.423026 -0.60688198 0.67286199, + 0.46233121 -0.62155229 0.63239431, + 0.52341783 -0.59727675 0.60769576, + 0.55800939 -0.60596734 0.56694734, + 0.61902809 -0.57349712 0.53656811, + 0.65023559 -0.57742667 0.49373269, + 0.70800358 -0.53674668 0.45894873, + 0.73241884 -0.53655487 0.4191319, + 0.78494102 -0.48826 0.381405, + 0.80244428 -0.48557919 0.34683713, + 0.84759629 -0.43180314 0.30842611, + 0.85944211 -0.42803505 0.27954504, + 0.89638078 -0.37114492 0.24238995, + 0.90389472 -0.36729389 0.21924792, + 0.93290091 -0.30922997 0.18458799, + 0.93736136 -0.30586213 0.16674006, + 0.95932311 -0.24787103 0.13512701, + 0.96175635 -0.24524209 0.12198804, + 0.97769934 -0.18803208 0.093531132, + 0.97888476 -0.18617596 0.084398679, + 0.98960352 -0.13099094 0.059381869, + 0.99009174 -0.12981997 0.05352689, + 0.99654847 -0.076745838 0.031643614, + 0.99669045 -0.076138839 0.028481513, + 0.99964863 -0.02482859 0.0092877364, + 0.99966115 -0.024658304 0.0083441613, + 0.99966812 0.024401704 -0.0082573313, + 0.99967039 0.024285208 -0.0083270427, + 0.99693227 0.074037418 -0.025386306, + 0.99709052 0.073300764 -0.02091429, + 0.99212575 0.12043897 -0.034363993, + 0.99244201 0.11954 -0.027731299, + 0.9854185 0.16574708 -0.038450819, + 0.98585767 0.16485094 -0.030147988, + 0.97677147 0.2107881 -0.03854892, + 0.97727764 0.20999193 -0.028842188, + 0.96619487 0.25541496 -0.035081096, + 0.96670085 0.25477597 -0.024055297, + 0.95345575 0.30019793 -0.028343892, + 0.9538765 0.29976016 -0.016235208, + 0.9382351 0.34549204 -0.018712003, + 0.93850386 0.34524396 -0.0041392795, + 0.93220741 0.36192417 0.00052094721, + 0.93216664 0.36190787 -0.0093818661, + 0.93217009 0.36189902 -0.0093816807, + 0.93221134 0.36191413 0.0005206542, + 0.948798 0.315837 -0.00542052, + 0.94877636 0.31583011 -0.0086545032, + 0.94880462 0.31574488 -0.008652837, + 0.94883925 0.3157571 -0.0012636804, + 0.94448376 0.3285439 -0.0030595392, + 0.90569532 0.42391115 -0.0039236615, + 0.89225191 0.45153794 0.00025345996, + 0.89220411 0.45151305 -0.010390301, + 0.89221269 0.45149586 -0.010389997, + 0.89226103 0.45152 0.00025274901, + 0.89218402 0.45167199 0.00025275, + 0.89213586 0.45164794 -0.010374899, + 0.87617958 0.48194477 -0.0062189871, + 0.875754 0.482142 -0.024374301, + 0.89846271 0.43848985 -0.022167493, + 0.89770931 0.43889514 -0.038588416, + 0.91801798 0.395015 -0.034730501, + 0.91699523 0.39568409 -0.050536811, + 0.93512809 0.35145503 -0.044887803, + 0.93393159 0.35240382 -0.059860971, + 0.94989198 0.308164 -0.0523462, + 0.94859314 0.30941302 -0.066594407, + 0.96257025 0.26496506 -0.057027914, + 0.96125138 0.2665121 -0.070478924, + 0.97343248 0.22136511 -0.058539625, + 0.97220463 0.22315593 -0.070849277, + 0.982692 0.176562 -0.056056298, + 0.98165923 0.17851004 -0.066927418, + 0.99025053 0.13043194 -0.048901979, + 0.98951238 0.13235992 -0.057844367, + 0.9960115 0.081758834 -0.035730518, + 0.99563015 0.083371408 -0.042069305, + 0.99948752 0.028577486 -0.014420194, + 0.99942613 0.029325703 -0.016958402, + 0.99937135 -0.030692011 0.017748505, + 0.99927813 -0.031740405 0.020875702, + 0.99261099 -0.101379 0.066677101, + 0.99160951 -0.10475395 0.075743563, + 0.97339666 -0.18567394 0.13425395, + 0.96928537 -0.19298407 0.15245706, + 0.92998725 -0.28844306 0.22786906, + 0.93914223 -0.26382306 0.22002105, + 0.87771928 -0.36799711 0.30689913, + 0.86010158 -0.37999582 0.34033585, + 0.78680682 -0.45975888 0.41177291, + 0.75369215 -0.47278312 0.45653513, + 0.66044122 -0.54015118 0.52158821, + 0.60692197 -0.54924297 0.57443702, + 0.50335014 -0.59714913 0.6245411, + 0.42837593 -0.59578192 0.67936593, + 0.33064198 -0.62225795 0.70955694, + 0.24243405 -0.60589111 0.75770819, + 0.16115496 -0.61635888 0.7707988, + 0.069416553 -0.58505464 0.80801755, + 0.010843297 -0.5864349 0.80992383, + -0.076056272 -0.54371184 0.83581871, + -0.11394896 -0.54173982 0.83278668, + -0.19210492 -0.49152881 0.84940869, + -0.21240905 -0.48942813 0.84577918, + -0.2766529 -0.43830785 0.85518968, + -0.31993791 -0.43213591 0.84314781, + -0.32030714 -0.4317832 0.84318841, + -0.32172301 -0.43156499 0.84276098, + -0.32786196 -0.42511493 0.84367287, + -0.32482296 -0.42558694 0.84460986, + -0.32778388 -0.42216784 0.8451817, + -0.32101604 -0.42320505 0.84725809, + -0.31253296 -0.43383995 0.84504789, + -0.30625811 -0.43477216 0.84686428, + -0.29846781 -0.44530874 0.84416652, + -0.29179001 -0.446271 0.84599102, + -0.28515503 -0.45599106 0.84306514, + -0.27711096 -0.45711195 0.84513789, + -0.27064598 -0.46741894 0.8415879, + -0.26194292 -0.46858683 0.84368968, + -0.25567496 -0.47952494 0.8394559, + -0.24555802 -0.48082405 0.84173012, + -0.23938514 -0.49268231 0.83663547, + -0.22811297 -0.49405694 0.8389709, + -0.22244492 -0.50613379 0.83327472, + -0.20912801 -0.507662 0.83578998, + -0.20369093 -0.52065384 0.82911372, + -0.189046 -0.52221298 0.83159798, + -0.18377596 -0.5365169 0.82363582, + -0.16745895 -0.53810591 0.82607484, + -0.16261604 -0.55328614 0.81696415, + -0.14480393 -0.55483979 0.81925857, + -0.14027701 -0.57159108 0.8084591, + -0.12028705 -0.57310718 0.81060427, + -0.11639094 -0.59071362 0.79844254, + -0.094948441 -0.59206921 0.80027431, + -0.091688804 -0.61097008 0.78632611, + -0.068304926 -0.61212128 0.78780836, + -0.06581001 -0.63234204 0.77188909, + -0.0416766 -0.633165 0.77289402, + -0.040103991 -0.65419281 0.75526381, + -0.014008402 -0.65465605 0.75579715, + -0.013476798 -0.67590892 0.73686194, + 0.013376098 -0.67590994 0.73686296, + 0.013915898 -0.65445495 0.75597286, + 0.039999019 -0.65399432 0.75544137, + 0.041557197 -0.63320595 0.7728669, + 0.0662046 -0.63236302 0.77183801, + 0.068686783 -0.61238289 0.78757185, + 0.091465592 -0.61125994 0.78612685, + 0.094767526 -0.59215111 0.80023515, + 0.11648701 -0.59077907 0.79838014, + 0.12039202 -0.57317305 0.81054211, + 0.140076 -0.57168001 0.80843103, + 0.14453197 -0.5552159 0.8190518, + 0.16260906 -0.55363917 0.81672633, + 0.16746596 -0.53844589 0.8258518, + 0.18372504 -0.53686213 0.82342219, + 0.18890508 -0.52283317 0.8312403, + 0.20349595 -0.52127886 0.82876885, + 0.20907095 -0.5079869 0.83560681, + 0.222091 -0.50649297 0.83315098, + 0.22776502 -0.49441907 0.83885211, + 0.23903206 -0.4930461 0.83652216, + 0.24521898 -0.48117393 0.84162891, + 0.25500998 -0.47991893 0.8394329, + 0.26132116 -0.46891627 0.84369946, + 0.27061498 -0.46767095 0.8414579, + 0.27718312 -0.45720622 0.84506339, + 0.28460607 -0.45617312 0.84315217, + 0.29164594 -0.44586289 0.84625584, + 0.29872188 -0.44484386 0.84432173, + 0.30622107 -0.43470109 0.84691417, + 0.31255409 -0.43376008 0.84508115, + 0.32228008 -0.42155409 0.84760118, + 0.32884809 -0.4205471 0.84557617, + 0.32887504 -0.42051607 0.84558111, + 0.33311188 -0.41985384 0.84425068, + 0.31866103 -0.43505606 0.84212911, + 0.31652704 -0.43538406 0.84276414, + 0.31384099 -0.437931 0.84244901, + 0.30906007 -0.43865412 0.84383917, + 0.28510582 -0.45891172 0.84149551, + 0.27225396 -0.46069694 0.8447699, + 0.19096304 -0.51815414 0.83369619, + 0.16315001 -0.52079606 0.83794612, + 0.073410332 -0.5700652 0.8183133, + 0.024094991 -0.57144183 0.82028872, + -0.072491139 -0.60953832 0.78943539, + -0.14678401 -0.60452706 0.78294414, + -0.24344203 -0.62739706 0.73966807, + -0.3408851 -0.60811412 0.7169342, + -0.42877901 -0.61408299 0.66260898, + -0.53839409 -0.57281214 0.61807615, + -0.60482627 -0.56477928 0.56143522, + -0.70918661 -0.50000274 0.49704278, + -0.75145137 -0.48543724 0.44684622, + -0.86116081 -0.37400392 0.3442719, + -0.89437973 0.44721788 -0.0089961179, + -0.87624025 0.48184612 -0.0052343812, + -0.87578702 0.48206201 -0.024764, + -0.8984679 0.43846095 -0.022524199, + -0.89773375 0.43885389 -0.038487893, + -0.91803944 0.39497319 -0.034639515, + -0.91703737 0.39563215 -0.05017722, + -0.93516457 0.35139883 -0.044567179, + -0.93395263 0.35236287 -0.059772577, + -0.94990897 0.30812499 -0.052268401, + -0.94859725 0.30938604 -0.066659816, + -0.96257377 0.26493993 -0.057083584, + -0.96125722 0.26648307 -0.070508212, + -0.97343665 0.22133993 -0.058563877, + -0.97221065 0.22312793 -0.070855379, + -0.98269254 0.17655592 -0.056065973, + -0.98165911 0.17850402 -0.066946708, + -0.99025035 0.13042805 -0.048916217, + -0.98951024 0.13236003 -0.057881813, + -0.99601048 0.081760138 -0.035754118, + -0.99562651 0.083382465 -0.04213218, + -0.9994871 0.028584205 -0.014443302, + -0.99942464 0.029342389 -0.017015094, + -0.99936962 -0.030712489 0.017809594, + -0.99927586 -0.031764496 0.020947399, + -0.99258524 -0.10147303 0.066917017, + -0.99161077 -0.10475298 0.075728782, + -0.97340089 -0.18567099 0.13422698, + -0.96929437 -0.19297408 0.15241206, + -0.93001813 -0.28840902 0.22778603, + -0.91609347 -0.30288082 0.26274684, + -0.83828413 -0.41185907 0.35728404, + -0.80450612 -0.43152106 0.40811706, + -0.70726097 -0.51362497 0.48576894, + -0.65320122 -0.52929717 0.5414542, + -0.53757691 -0.58943492 0.60297394, + -0.45626813 -0.59485114 0.66179419, + -0.34211603 -0.62815207 0.69884306, + -0.24221 -0.615897 0.74967003, + -0.14996897 -0.6276198 0.76393884, + -0.044560988 -0.59675688 0.80118382, + 0.019800706 -0.59723312 0.8018232, + 0.12011997 -0.55168587 0.82535684, + 0.15873906 -0.5486632 0.82083529, + 0.25248393 -0.49099889 0.8337698, + 0.27029011 -0.48855224 0.8296144, + 0.29970986 -0.4663828 0.83226258, + 0.30942699 -0.46486399 0.82955199, + 0.31428704 -0.46071005 0.83004212, + 0.31820908 -0.46007511 0.8288992, + 0.33727798 -0.44186395 0.8312639, + 0.3355979 -0.44214588 0.83179384, + 0.33676904 -0.44090706 0.83197814, + 0.33208886 -0.44168478 0.83344561, + 0.32166889 -0.45359585 0.8311317, + 0.31677192 -0.45438588 0.83257979, + 0.30905184 -0.4638758 0.8302446, + 0.30381781 -0.46469772 0.83171552, + 0.29660904 -0.47426906 0.82891011, + 0.29054603 -0.47519407 0.83052611, + 0.28405502 -0.48453405 0.82736909, + 0.2772471 -0.48553917 0.82908732, + 0.27081895 -0.49560887 0.82524484, + 0.26235497 -0.49681395 0.82725185, + 0.25639787 -0.50702876 0.82291061, + 0.24670388 -0.50835079 0.8250556, + 0.24104895 -0.51903188 0.8200618, + 0.23006691 -0.52045584 0.82231069, + 0.22459406 -0.53192914 0.81646121, + 0.211411 -0.53353602 0.81892902, + 0.20625789 -0.54565477 0.81223065, + 0.19131003 -0.54734606 0.8147471, + 0.18637209 -0.56055123 0.80687535, + 0.16955896 -0.5622859 0.80937284, + 0.16471599 -0.57724994 0.79978186, + 0.14650099 -0.57892895 0.80210888, + 0.14209791 -0.59499067 0.79107153, + 0.12212303 -0.59659111 0.79319918, + 0.11818504 -0.61410624 0.78032428, + 0.096026488 -0.61558294 0.78219986, + 0.092812449 -0.63393939 0.76779348, + 0.069384933 -0.63515329 0.76926339, + 0.066894293 -0.65496796 0.7526899, + 0.042270269 -0.65585154 0.75370544, + 0.040741514 -0.67589027 0.73587525, + 0.013990194 -0.6763857 0.73641467, + 0.013462502 -0.69712007 0.71682805, + -0.013565402 -0.69711906 0.71682703, + -0.014090004 -0.67638421 0.73641425, + -0.040322986 -0.67590076 0.73588878, + -0.041852783 -0.65562278 0.75392771, + -0.066768974 -0.65473378 0.75290471, + -0.069200307 -0.63531303 0.76914811, + -0.092919409 -0.63408506 0.76766014, + -0.096211463 -0.61525679 0.78243369, + -0.11785898 -0.61381596 0.78060186, + -0.12178796 -0.59627575 0.79348773, + -0.142084 -0.59465301 0.79132801, + -0.14647794 -0.5785858 0.80236071, + -0.16501307 -0.57687628 0.79999036, + -0.16976398 -0.56217492 0.80940688, + -0.18631995 -0.56046581 0.80694669, + -0.19135295 -0.54698288 0.8149808, + -0.20660892 -0.54525679 0.81240869, + -0.21175487 -0.53313768 0.81909955, + -0.22467703 -0.53156108 0.81667811, + -0.23026697 -0.51982296 0.8226549, + -0.24159791 -0.51835281 0.82032973, + -0.24706897 -0.50800395 0.82515991, + -0.2567699 -0.50667977 0.82300961, + -0.26290098 -0.49615195 0.82747591, + -0.27141398 -0.49493793 0.82545191, + -0.27738896 -0.48556995 0.82902187, + -0.28481692 -0.48446983 0.82714468, + -0.29117697 -0.47531494 0.8302359, + -0.29657003 -0.47449106 0.8287971, + -0.30355796 -0.46521395 0.83152187, + -0.30873486 -0.46440178 0.83006859, + -0.31672803 -0.45457706 0.83249211, + -0.32157391 -0.45379487 0.83105981, + -0.33096212 -0.44307414 0.83315629, + -0.33545816 -0.44232821 0.83175343, + -0.33043915 -0.4476082 0.83093745, + -0.33157298 -0.44741994 0.83058691, + -0.32189816 -0.45664522 0.82937139, + -0.31793302 -0.45729107 0.83054411, + -0.31509003 -0.45973906 0.83027613, + -0.26372898 -0.46726394 0.84386688, + -0.189218 -0.51952797 0.83323902, + -0.16008107 -0.52226222 0.83762544, + -0.073199227 -0.56985819 0.81847632, + -0.024568001 -0.57121903 0.82042998, + 0.07186041 -0.60929203 0.7896831, + 0.14597499 -0.60432798 0.78324902, + 0.24366511 -0.62746233 0.73953938, + 0.34112313 -0.60815626 0.71678525, + 0.42795879 -0.61407471 0.66314667, + 0.53816891 -0.5726549 0.61841786, + 0.60516202 -0.56457102 0.56128299, + 0.70912397 -0.50002396 0.49711093, + 0.75147033 -0.48543116 0.44682115, + 0.83586419 -0.40388608 0.3717621, + 0.85825342 -0.38975617 0.33390316, + 0.91820437 -0.30081311 0.25770608, + 0.91891313 -0.29636404 0.26032102, + 0.83394915 -0.41460705 0.36418402, + 0.80469728 -0.43143016 0.40783614, + 0.7071898 -0.51379287 0.48569489, + 0.65298498 -0.52951503 0.541502, + 0.53732705 -0.58964407 0.60299206, + 0.45574421 -0.59507132 0.66195732, + 0.3422499 -0.6281628 0.69876784, + 0.24100401 -0.61570299 0.75021797, + 0.14895397 -0.62732583 0.76437885, + 0.043628115 -0.59641427 0.80149031, + -0.020529199 -0.59685701 0.80208498, + -0.11713795 -0.5530808 0.82485169, + -0.15562497 -0.55012989 0.82044983, + -0.24204005 -0.49749613 0.8330152, + -0.30540502 -0.48824406 0.81752414, + -0.31107995 -0.48386487 0.8179878, + -0.31825116 -0.48265523 0.81594139, + -0.3321121 -0.47069311 0.81740415, + -0.33302203 -0.47053307 0.8171261, + -0.33999702 -0.46385005 0.81807411, + -0.337587 -0.46427801 0.818829, + -0.32706299 -0.47522601 0.81681699, + -0.32474977 -0.47562668 0.81750643, + -0.31616002 -0.48522106 0.8152321, + -0.31296399 -0.48576301 0.81614202, + -0.30606806 -0.49407011 0.81376719, + -0.30170706 -0.49479213 0.81495619, + -0.29548413 -0.50290418 0.81226629, + -0.29077798 -0.50366396 0.81349289, + -0.28475192 -0.51219183 0.81029367, + -0.27822295 -0.51321489 0.81191283, + -0.27240297 -0.52218992 0.80815488, + -0.2641241 -0.5234412 0.81009132, + -0.25882694 -0.5323959 0.80595481, + -0.24942397 -0.53375691 0.8080169, + -0.24406809 -0.54374015 0.8029803, + -0.23267689 -0.54530776 0.80529565, + -0.2277299 -0.55555278 0.79968762, + -0.21451892 -0.55726182 0.80214769, + -0.20944311 -0.56906033 0.79517537, + -0.19405091 -0.57090569 0.79775363, + -0.18925293 -0.58359075 0.78968668, + -0.17208806 -0.58546525 0.79222232, + -0.1673339 -0.59999263 0.78230953, + -0.148597 -0.60181701 0.784688, + -0.14418608 -0.6177333 0.77305633, + -0.12349906 -0.61947727 0.77523935, + -0.11964506 -0.6364423 0.76198834, + -0.09717562 -0.63801318 0.76386917, + -0.09390898 -0.6564678 0.7484858, + -0.070302114 -0.65775019 0.7499482, + -0.067904361 -0.67658859 0.73322356, + -0.042385597 -0.67754394 0.73425996, + -0.040887795 -0.69708997 0.71581692, + -0.014205996 -0.69760281 0.71634382, + -0.013690796 -0.71767676 0.69624174, + 0.013610402 -0.71767706 0.69624305, + 0.014127309 -0.69762242 0.71632642, + 0.041073617 -0.69710326 0.71579325, + 0.042594805 -0.67736804 0.73441005, + 0.067827471 -0.6764217 0.73338467, + 0.070201099 -0.65779197 0.74992102, + 0.094027035 -0.65649724 0.74844521, + 0.097296312 -0.63808107 0.7637971, + 0.11973704 -0.63651025 0.76191729, + 0.1236 -0.61954498 0.77516901, + 0.14399204 -0.6178261 0.77301818, + 0.14840299 -0.60192895 0.78463888, + 0.16740905 -0.60007912 0.78222716, + 0.17199706 -0.58608824 0.79178131, + 0.18910095 -0.58421987 0.78925782, + 0.19410703 -0.57100904 0.79766613, + 0.20919293 -0.56920081 0.79514068, + 0.21416497 -0.55765796 0.80196691, + 0.22735205 -0.5559541 0.7995162, + 0.23244096 -0.54542696 0.80528289, + 0.24354003 -0.54390204 0.80303115, + 0.24875391 -0.53419381 0.8079347, + 0.25841594 -0.53279686 0.80582184, + 0.26375014 -0.5237903 0.80998749, + 0.27198091 -0.52254784 0.80806571, + 0.27762091 -0.51386184 0.8117097, + 0.2840949 -0.51284879 0.81010872, + 0.29018307 -0.50424713 0.81334418, + 0.29517201 -0.503443 0.81204599, + 0.30180803 -0.49480006 0.81491411, + 0.30586287 -0.49412882 0.81380868, + 0.313292 -0.48517999 0.81636298, + 0.31625596 -0.48467794 0.8155179, + 0.32484785 -0.47507775 0.81778657, + 0.32761896 -0.47459695 0.81695986, + 0.338927 -0.462818 0.81910199, + 0.34150898 -0.46235794 0.81828886, + 0.33865902 -0.46510407 0.81791711, + 0.33839488 -0.46515083 0.81799972, + 0.31470901 -0.48563501 0.81554699, + 0.30669215 -0.48697624 0.81779844, + 0.29869193 -0.49309987 0.8170898, + 0.28491703 -0.49527106 0.82068813, + 0.24889506 -0.51923114 0.81758815, + 0.22208394 -0.5227139 0.82307285, + 0.11414903 -0.57918411 0.80716521, + 0.06294816 -0.58183867 0.81086451, + -0.049918909 -0.62196404 0.78145313, + -0.13343199 -0.61717194 0.77543187, + -0.24558499 -0.63764602 0.73013401, + -0.35896111 -0.61395127 0.70300126, + -0.45699188 -0.61323988 0.64427882, + -0.58279908 -0.56025308 0.58861005, + -0.65189558 -0.54436868 0.52791572, + -0.7642079 -0.46300593 0.44901195, + -0.80263549 -0.44332027 0.39905325, + -0.88534498 -0.34555799 0.31105301, + -0.90493339 -0.32751316 0.27171811, + -0.9594571 -0.21692003 0.17996602, + -0.96582299 -0.206422 0.156767, + -0.98952514 -0.11496501 0.087310307, + -0.9908241 -0.11079501 0.07740891, + -0.9991259 -0.034268297 0.023942295, + -0.99922013 -0.033259105 0.021282302, + -0.99930114 0.031486902 -0.020148301, + -0.99938726 0.030494208 -0.017183604, + -0.99485213 0.088285506 -0.049749307, + -0.99538463 0.08612977 -0.042321585, + -0.98802215 0.13849601 -0.068052605, + -0.98902047 0.13598005 -0.057861827, + -0.97957587 0.18502098 -0.078729391, + -0.98093897 0.182529 -0.066647403, + -0.96968663 0.22952992 -0.083808772, + -0.97129762 0.22724593 -0.070287079, + -0.95848447 0.27241212 -0.084257036, + -0.96020621 0.27044806 -0.069727115, + -0.94575047 0.31460616 -0.081112236, + -0.94747752 0.31299084 -0.065749072, + -0.93120039 0.35672212 -0.074935429, + -0.93283999 0.35545599 -0.058827501, + -0.91454774 0.39904991 -0.066042386, + -0.91600823 0.39812008 -0.049290013, + -0.89570427 0.44128114 -0.054633718, + -0.89687401 0.44067201 -0.037751898, + -0.87435532 0.48351517 -0.041422315, + -0.87519085 0.48316893 -0.024263296, + -0.85007417 0.52600014 -0.026414106, + -0.85057282 0.52582288 -0.0060115084, + -0.84539145 0.53406328 -0.0094758756, + -0.8454293 0.53408718 -0.00034629513, + -0.84549081 0.53398991 -0.00035087491, + -0.8454529 0.53396595 -0.0094743995, + -0.81808984 0.5750559 -0.0063147885, + -0.81810617 0.5750671 0.00028712105, + -0.81820971 0.57491982 0.00028712087, + -0.81817281 0.57489389 -0.0095091183, + -0.81821573 0.5748328 -0.0095082158, + -0.81825256 0.57485873 0.00029569786, + -0.79983467 0.60020769 -0.0039106482, + -0.62061214 -0.78411019 -0.0034188309, + -0.61491162 -0.78858453 -0.0042678178, + -0.61489594 -0.78856486 0.0082701594, + -0.65283495 -0.75737888 0.013557798, + -0.65289503 -0.75744814 0.00076249411, + -0.65291226 -0.7574333 0.00076249329, + -0.65299493 -0.75736189 0.00075838389, + -0.68925422 -0.72451824 -0.0014307605, + -0.68922526 -0.72448725 0.0093136234, + -0.72393823 -0.68981326 0.0084278332, + -0.72396374 -0.68983775 0.00058712077, + -0.69793767 -0.71614861 -0.0037448981, + -0.76786673 -0.64059776 -0.0038917686, + -0.78819531 -0.61542523 0.00036907016, + -0.78818613 -0.61541808 0.0048143403, + -0.7880401 -0.61560506 0.0048165405, + -0.78804964 -0.61561167 0.00034196384, + -0.78806669 -0.61558974 0.00034196489, + -0.78800488 -0.61554092 0.012556798, + -0.81730014 -0.57620406 0.0030864205, + -0.81730384 -0.57620686 -0.00041751491, + -0.81731129 -0.57619619 -0.00041802015, + -0.81730711 -0.57619405 0.0030863006, + -0.82240182 -0.56879687 0.011197797, + -0.8221541 -0.56877506 0.023612304, + -0.79152238 -0.6106143 0.025349211, + -0.79078418 -0.61049414 0.04424021, + -0.75777614 -0.65080804 0.047161609, + -0.75650984 -0.65045685 0.067814589, + -0.72086757 -0.6893366 0.071868055, + -0.71896958 -0.68859255 0.09446194, + -0.68072605 -0.72574109 0.099558316, + -0.67806798 -0.72438699 0.124448, + -0.63783008 -0.7590571 0.13040401, + -0.63431007 -0.75682813 0.15767701, + -0.59237611 -0.78872615 0.16432205, + -0.58793086 -0.78532183 0.19392495, + -0.54431099 -0.81441998 0.201111, + -0.53894788 -0.80952984 0.23280194, + -0.49387982 -0.83566171 0.24031691, + -0.48772717 -0.82904631 0.27350408, + -0.44237888 -0.85167885 0.28096995, + -0.43557301 -0.843095 0.315384, + -0.39035293 -0.86230689 0.32256997, + -0.38308382 -0.85157257 0.35786983, + -0.33835301 -0.86752701 0.36457399, + -0.33083591 -0.85448384 0.4005059, + -0.28700602 -0.86737812 0.40655005, + -0.27957693 -0.8520878 0.44247389, + -0.23762709 -0.86205727 0.44765013, + -0.23055895 -0.84459984 0.48321187, + -0.19088709 -0.85202444 0.48745924, + -0.18441501 -0.83247411 0.52247304, + -0.14716598 -0.83777887 0.52580297, + -0.14152403 -0.81630516 0.56001514, + -0.106962 -0.81987399 0.562464, + -0.10239405 -0.79687536 0.59540331, + -0.071005486 -0.7990638 0.59703887, + -0.067638725 -0.77477127 0.62861323, + -0.039262999 -0.77595103 0.62957001, + -0.037191499 -0.75052202 0.65979803, + -0.0118116 -0.75098902 0.660209, + -0.011113599 -0.72466391 0.68901294, + 0.011480699 -0.72466093 0.68900996, + 0.012178203 -0.7509892 0.66020221, + 0.037608191 -0.75051379 0.65978384, + 0.039676595 -0.77592188 0.62957996, + 0.068023175 -0.77473468 0.62861675, + 0.071389705 -0.79903311 0.59703404, + 0.10279401 -0.7968331 0.59539104, + 0.10736198 -0.8198328 0.56244791, + 0.14191808 -0.81625241 0.55999225, + 0.14755906 -0.83772528 0.52577817, + 0.18476099 -0.83241487 0.52244496, + 0.19123399 -0.851964 0.48742899, + 0.23088004 -0.84453213 0.48317707, + 0.23795903 -0.86201411 0.44755706, + 0.27990198 -0.8520329 0.44237393, + 0.28732607 -0.86731321 0.4064621, + 0.33114696 -0.85440689 0.40041295, + 0.3386679 -0.86745882 0.3644439, + 0.38340318 -0.85148644 0.35773319, + 0.39067405 -0.8622191 0.32241604, + 0.435844 -0.84301102 0.31523401, + 0.44262207 -0.85155815 0.28095302, + 0.48798981 -0.82890069 0.2734769, + 0.494104 -0.83547801 0.240495, + 0.53910297 -0.80937499 0.232981, + 0.54441988 -0.81422681 0.20159796, + 0.5880239 -0.78513581 0.19439596, + 0.59245515 -0.78853619 0.16494705, + 0.63434201 -0.756675 0.158282, + 0.63789672 -0.75893164 0.13080694, + 0.67809224 -0.72429723 0.12483805, + 0.68080479 -0.72568077 0.099459864, + 0.71905524 -0.68851626 0.094366238, + 0.72099835 -0.68927437 0.071149334, + 0.75664002 -0.65037602 0.067134097, + 0.75788403 -0.65071702 0.0466826, + 0.79087549 -0.61040837 0.043790925, + 0.79157048 -0.61052155 0.026068982, + 0.8221789 -0.56871092 0.024283797, + 0.82241631 -0.56873918 0.012930404, + 0.84636617 -0.53257513 0.0053028315, + 0.84624481 -0.53276789 0.0053059687, + 0.85303515 -0.52160311 0.016161004, + 0.84619069 -0.53256685 0.018274892, + 0.84633183 -0.53265589 0.00023593094, + 0.8462562 -0.53277612 0.00023593106, + 0.84637833 -0.53258216 0.00026217208, + 0.82967287 -0.55823594 -0.0039262897, + 0.88268244 -0.46996972 -0.00021701786, + 0.89437222 -0.44725212 -0.0079981219, + 0.89436924 -0.44725811 -0.0079968022, + 0.8943491 -0.44724807 0.010434701, + 0.87603033 -0.48198819 0.016073005, + 0.87551522 -0.48209611 0.032504607, + 0.84938085 -0.52658486 0.035504192, + 0.84855288 -0.52662891 0.051184591, + 0.81948328 -0.5704152 0.055440418, + 0.81809968 -0.57031983 0.073812373, + 0.78644687 -0.61254895 0.079277791, + 0.78438997 -0.612167 0.099919498, + 0.75013685 -0.65264595 0.10652699, + 0.74727893 -0.65178794 0.12940899, + 0.71023899 -0.69048297 0.137091, + 0.70643795 -0.68890494 0.16234398, + 0.66672772 -0.72543067 0.17095193, + 0.66187805 -0.72283506 0.19856203, + 0.62026811 -0.7563712 0.20777404, + 0.614326 -0.75244701 0.237544, + 0.5711593 -0.78275937 0.24711312, + 0.56411582 -0.77716571 0.27890292, + 0.519665 -0.80415499 0.28858799, + 0.51158303 -0.79654312 0.32218304, + 0.46617305 -0.82014513 0.33173004, + 0.45722988 -0.81023782 0.3666819, + 0.4121511 -0.83006817 0.37565708, + 0.40262505 -0.81771111 0.41139007, + 0.35852808 -0.83392817 0.41954908, + 0.34872919 -0.81905842 0.45555621, + 0.30588397 -0.83203191 0.46277195, + 0.29611403 -0.81461513 0.49871707, + 0.25499597 -0.8246699 0.50487292, + 0.24557514 -0.80476147 0.54041833, + 0.20716807 -0.81217331 0.5453952, + 0.19846398 -0.79009587 0.57996595, + 0.16308106 -0.79533929 0.58381522, + 0.15535595 -0.77137071 0.61713177, + 0.12296701 -0.77492511 0.61997604, + 0.11640905 -0.74926937 0.65195429, + 0.087229267 -0.75152272 0.65391475, + 0.081999376 -0.72443581 0.68444782, + 0.056324568 -0.72572958 0.68567055, + 0.052552491 -0.69769895 0.71446097, + 0.030240381 -0.69834459 0.71512258, + 0.027972804 -0.66964304 0.74215609, + 0.0089155892 -0.66987896 0.74241692, + 0.0081639662 -0.64058769 0.76784164, + -0.007903262 -0.64058918 0.76784319, + -0.0086525399 -0.669819 0.74247402, + -0.027685309 -0.66958725 0.74221724, + -0.029953388 -0.69831276 0.71516573, + -0.052214209 -0.69767308 0.71451104, + -0.055983275 -0.72568965 0.68574071, + -0.081634209 -0.72440404 0.68452507, + -0.086868532 -0.75151032 0.65397722, + -0.11605102 -0.74926507 0.65202308, + -0.122613 -0.77493799 0.62002999, + -0.15498498 -0.77139491 0.61719495, + -0.16271505 -0.79537821 0.58386409, + -0.19809704 -0.79014611 0.58002305, + -0.20680304 -0.81222618 0.5454551, + -0.24524197 -0.8048209 0.54048091, + -0.2546699 -0.82474071 0.50492179, + -0.29576895 -0.81470382 0.49877688, + -0.30554703 -0.83213013 0.46281806, + -0.3484202 -0.81916249 0.45560527, + -0.35821298 -0.83402288 0.41962993, + -0.4023599 -0.81780183 0.41146892, + -0.41187775 -0.83014655 0.37578377, + -0.4569422 -0.81033838 0.36681819, + -0.46588787 -0.82024884 0.33187392, + -0.51128894 -0.79667085 0.32233396, + -0.51938087 -0.80428982 0.28872395, + -0.56388706 -0.77728611 0.27903003, + -0.57095885 -0.78290284 0.24712195, + -0.61413378 -0.75259972 0.2375569, + -0.62012792 -0.75655389 0.20752697, + -0.66176873 -0.72300076 0.19832292, + -0.66666681 -0.72561485 0.17040695, + -0.70640874 -0.68905777 0.16182093, + -0.71021318 -0.69063216 0.13647203, + -0.74728304 -0.65190005 0.12881902, + -0.7501111 -0.65274304 0.10611302, + -0.78437084 -0.61225486 0.099531077, + -0.78638071 -0.61262679 0.079333872, + -0.81804103 -0.57039702 0.073865198, + -0.81938583 -0.57049286 0.056078684, + -0.8484726 -0.52670074 0.051773973, + -0.8493166 -0.52666074 0.035914782, + -0.89937621 -0.4370501 0.010478803, + -0.89926475 -0.4370749 0.016985996, + -0.8759169 -0.48209795 0.018735798, + -0.8754549 -0.48217994 0.032881495, + -0.87781668 -0.47745082 0.038454086, + -0.8985101 -0.43753606 0.035239402, + -0.89911878 -0.4373889 0.016620496, + -0.92005575 -0.39150491 0.014876996, + -0.92013586 -0.39147794 0.0097453687, + -0.91397828 -0.40576115 -0.0012531505, + -0.91393578 -0.40585691 -0.0012521796, + -0.9140237 -0.40565884 -0.0013045896, + -0.91402441 -0.40565917 0.00030664416, + -0.91393667 -0.40585685 0.00030664389, + -0.91397923 -0.40576109 0.00030320705, + -0.92631412 -0.37673205 -0.0039039005, + -0.88267571 -0.46996582 -0.0039692684, + -0.89294428 -0.45016715 -0.00037987615, + -0.89297813 -0.45010006 -0.00037107407, + -0.89297813 -0.45010006 -0.00032445503, + -0.89294428 -0.45016715 -0.00032375913, + -0.87624991 -0.48173195 0.010967999, + -0.87610024 -0.48174813 0.019160604, + -0.85019809 -0.52604705 0.020922503, + -0.84964627 -0.52607918 0.036632616, + -0.82089484 -0.56969988 0.039669991, + -0.81990743 -0.56963629 0.057152227, + -0.7886579 -0.61176091 0.061378691, + -0.78712016 -0.61148709 0.080779821, + -0.75333816 -0.65196919 0.086127721, + -0.75109065 -0.65131569 0.10793895, + -0.71455199 -0.69016898 0.114378, + -0.71145475 -0.68891174 0.13868195, + -0.67225993 -0.72575593 0.14609899, + -0.66817892 -0.72361296 0.17297798, + -0.62703526 -0.7576443 0.18111306, + -0.62189889 -0.7543028 0.21040195, + -0.57914698 -0.78524703 0.219034, + -0.57299107 -0.78041512 0.25026703, + -0.52877182 -0.80822271 0.25918391, + -0.52165908 -0.80159914 0.29208001, + -0.47632581 -0.82613569 0.30102089, + -0.46837479 -0.8174156 0.33534586, + -0.42312184 -0.83827168 0.34390187, + -0.41452593 -0.82723188 0.37928295, + -0.36993909 -0.84452015 0.38720909, + -0.3609899 -0.83107179 0.4230909, + -0.31740108 -0.84508216 0.43022409, + -0.30840713 -0.82919931 0.46616918, + -0.26629496 -0.84021491 0.47236195, + -0.257548 -0.82190001 0.508084, + -0.21780595 -0.83017385 0.5131979, + -0.20960502 -0.8095631 0.54833704, + -0.17265691 -0.81552058 0.55237275, + -0.16532601 -0.79298913 0.58637506, + -0.13119496 -0.79710382 0.58941787, + -0.12494504 -0.77288431 0.62212425, + -0.093866885 -0.77554888 0.62426996, + -0.088851452 -0.74983066 0.65563673, + -0.061189406 -0.75139713 0.65700704, + -0.057524193 -0.72443491 0.68693894, + -0.03317719 -0.72523677 0.68769974, + -0.030964199 -0.69752002 0.71589601, + -0.009724102 -0.69782215 0.71620518, + -0.0089896088 -0.66956192 0.74270195, + 0.0093336217 -0.66956019 0.74269921, + 0.010067504 -0.69781822 0.71620423, + 0.031302482 -0.69751155 0.71588957, + 0.03351751 -0.72526622 0.68765223, + 0.057886008 -0.72445709 0.68688506, + 0.061547872 -0.75139964 0.65697068, + 0.089234255 -0.74982363 0.65559268, + 0.094245866 -0.77552468 0.62424278, + 0.12532201 -0.7728501 0.62209105, + 0.13157201 -0.79706812 0.58938205, + 0.16569805 -0.79294318 0.58633214, + 0.17302506 -0.81546128 0.55234516, + 0.20999099 -0.809488 0.54830003, + 0.21818805 -0.8300882 0.51317412, + 0.25789213 -0.82180941 0.50805622, + 0.26664406 -0.84013617 0.47230512, + 0.30873013 -0.8291133 0.46610817, + 0.31771904 -0.84498709 0.43017605, + 0.36132318 -0.8309564 0.42303321, + 0.3702729 -0.84440881 0.38713291, + 0.4148351 -0.82711315 0.37920409, + 0.42344192 -0.83816785 0.34376091, + 0.46866018 -0.81730932 0.33520612, + 0.47660682 -0.82602173 0.30088887, + 0.52194107 -0.80146509 0.29194403, + 0.52901989 -0.80805784 0.25919193, + 0.57320005 -0.78025913 0.25027502, + 0.57931727 -0.78506035 0.21925311, + 0.62201971 -0.75414264 0.2106189, + 0.62710571 -0.75745666 0.1816529, + 0.66822398 -0.72344702 0.17349701, + 0.67229903 -0.72559297 0.146727, + 0.71146798 -0.68877703 0.139282, + 0.71459919 -0.69005215 0.11478703, + 0.75110418 -0.65123516 0.10833002, + 0.75340289 -0.65190494 0.086046994, + 0.7871753 -0.61142623 0.080704033, + 0.7887553 -0.61170423 0.060688321, + 0.82000089 -0.56956595 0.056507692, + 0.82096988 -0.56962293 0.039219797, + 0.8497076 -0.52600878 0.036216781, + 0.85021073 -0.52598083 0.022041593, + 0.82196403 -0.56904 0.023846099, + 0.82135856 -0.56900668 0.040017582, + 0.79045331 -0.61101323 0.042971916, + 0.78934485 -0.61082786 0.061838284, + 0.75599152 -0.65125257 0.065930761, + 0.75422317 -0.65075219 0.087573819, + 0.71817744 -0.68964344 0.092807651, + 0.71565825 -0.68863726 0.11667105, + 0.67697918 -0.72566116 0.12294403, + 0.67361331 -0.72391635 0.14896408, + 0.63296533 -0.75829238 0.15603708, + 0.62867701 -0.75553399 0.184211, + 0.58640796 -0.78696287 0.19187297, + 0.58115906 -0.78289014 0.22212003, + 0.5372439 -0.81140184 0.23020893, + 0.53107917 -0.8057183 0.2622461, + 0.48590001 -0.83109999 0.27050701, + 0.478903 -0.82350397 0.30412701, + 0.43358192 -0.84531081 0.31217995, + 0.42591193 -0.83555186 0.34706196, + 0.38100284 -0.85384572 0.35466087, + 0.37287796 -0.84174287 0.39042395, + 0.32865098 -0.85677588 0.39739594, + 0.32040286 -0.8423366 0.43337178, + 0.27740797 -0.85431486 0.43953493, + 0.26934087 -0.83756959 0.47532377, + 0.22839794 -0.84672183 0.48051688, + 0.220769 -0.82772201 0.515885, + 0.18239401 -0.83442611 0.52006304, + 0.17546104 -0.81331021 0.55474311, + 0.13975902 -0.81801814 0.55795509, + 0.13380799 -0.79516786 0.59144193, + 0.10094997 -0.79828471 0.59375978, + 0.096161276 -0.77395982 0.62589079, + 0.066563509 -0.77583814 0.62741107, + 0.063047372 -0.75022167 0.65817368, + 0.036647897 -0.75121188 0.65904295, + 0.034495194 -0.72452682 0.6883828, + 0.011123196 -0.72491378 0.68874979, + 0.010404201 -0.69757104 0.71644008, + -0.010062501 -0.69757307 0.71644306, + -0.010780199 -0.72489995 0.68876994, + -0.03412601 -0.72451925 0.68840921, + -0.036275998 -0.75118786 0.65909094, + -0.062710598 -0.75020301 0.65822703, + -0.066229083 -0.77583683 0.62744784, + -0.09580338 -0.7739678 0.62593579, + -0.10059097 -0.79829282 0.5938099, + -0.13345298 -0.79518586 0.59149796, + -0.13940509 -0.81803745 0.55801535, + -0.17513189 -0.81333643 0.55480856, + -0.182069 -0.83446598 0.52011299, + -0.2204209 -0.82777756 0.51594478, + -0.22806098 -0.84680188 0.48053595, + -0.26897004 -0.8376711 0.47535506, + -0.27703598 -0.8544119 0.43958095, + -0.32008517 -0.84243345 0.43341827, + -0.32832909 -0.85686219 0.39747608, + -0.37255281 -0.84184659 0.39051083, + -0.38067293 -0.8539409 0.35478598, + -0.42558521 -0.83566439 0.34719217, + -0.43326807 -0.84543711 0.31227404, + -0.47859895 -0.82364488 0.30422398, + -0.48561817 -0.83126432 0.27050808, + -0.53083795 -0.80587685 0.26224697, + -0.53704792 -0.8115989 0.22997098, + -0.58098465 -0.78308451 0.22189087, + -0.58627862 -0.78718752 0.19134589, + -0.62862027 -0.75570732 0.18369307, + -0.63291681 -0.75846285 0.15540397, + -0.67358726 -0.72406524 0.14835706, + -0.67692327 -0.72578835 0.12250006, + -0.71560574 -0.68876278 0.11625095, + -0.71807277 -0.68974376 0.092870772, + -0.75414681 -0.65083283 0.087631576, + -0.75586981 -0.65132284 0.066628188, + -0.78922981 -0.61090988 0.062493984, + -0.79035884 -0.61110389 0.043416288, + -0.82126731 -0.5691092 0.040432815, + -0.82191283 -0.56914389 0.023120595, + -0.85039818 -0.52570611 0.021356005, + -0.85059512 -0.52570504 0.011055901, + -0.84354019 -0.53686011 0.014869804, + -0.84363389 -0.53691894 2.4934696e-005, + -0.84458411 -0.53542304 2.4931303e-005, + -0.84458327 -0.53542221 0.0015009906, + -0.84460688 -0.53538495 0.0015005697, + -0.84460813 -0.53538507 3.0058503e-005, + -0.82967281 -0.55823588 -0.003963999, + -0.98379791 -0.17927998 0.00060023996, + -0.97547567 -0.21977893 -0.012016496, + -0.98515451 -0.17165892 -0.0019690092, + -0.98516077 -0.17162296 -0.0019631195, + -0.99237537 -0.12324905 0.00085794629, + -0.96634954 -0.25351387 0.043581378, + -0.97729045 -0.2088411 0.035901718, + -0.97778553 -0.2081569 0.024621189, + -0.98691899 -0.160101 0.0189371, + -0.987095 -0.159757 0.0110123, + -0.99354589 -0.11316199 0.0078004091, + -0.99357921 -0.11307203 0.0038968909, + -0.99239051 -0.12312994 0.00036209784, + -0.99239022 -0.12313003 0.00086142024, + -0.99239463 -0.12309396 0.00086141971, + -0.99239498 -0.123094 0.000364026, + -0.99237567 -0.12324896 0.00036727285, + -0.98724735 -0.15910307 0.0053783921, + -0.98717755 -0.15923093 0.011225294, + -0.97832537 -0.20656107 0.014561906, + -0.97802198 -0.206991 0.025054101, + -0.96640122 -0.25517607 0.030886507, + -0.96584123 -0.25577807 0.041572612, + -0.95143312 -0.30386803 0.049388908, + -0.95070624 -0.30442405 0.059022516, + -0.93315089 -0.35291296 0.068423592, + -0.93194264 -0.3535789 0.08040487, + -0.91098028 -0.40218216 0.091457427, + -0.90909868 -0.40288785 0.10592896, + -0.88470358 -0.4508318 0.11853394, + -0.8819167 -0.45145586 0.13568595, + -0.85394228 -0.49834618 0.14977907, + -0.8499679 -0.49870294 0.16985299, + -0.81812018 -0.54434115 0.18539704, + -0.81264973 -0.54414982 0.20856993, + -0.77688485 -0.58793396 0.22535197, + -0.76964271 -0.58681774 0.25158492, + -0.73058134 -0.62758029 0.26906112, + -0.72132182 -0.62508285 0.29827195, + -0.67937493 -0.66225892 0.31601098, + -0.66789305 -0.65783906 0.34809002, + -0.62336707 -0.69113708 0.36570904, + -0.60964376 -0.68422878 0.40020686, + -0.56332392 -0.71319795 0.41715094, + -0.5475719 -0.70331085 0.45334187, + -0.5010379 -0.72740585 0.46887287, + -0.48360506 -0.71416909 0.50605208, + -0.43790412 -0.73353517 0.51977509, + -0.41918486 -0.71665776 0.55739182, + -0.37512499 -0.73171401 0.56910098, + -0.355701 -0.71113098 0.60644001, + -0.31409702 -0.72238505 0.61603808, + -0.29470587 -0.69835079 0.65226877, + -0.25677514 -0.70630443 0.65969741, + -0.23800804 -0.67917603 0.69431406, + -0.20422712 -0.6845324 0.69979042, + -0.18656209 -0.65472227 0.73248434, + -0.15699102 -0.65815908 0.73632908, + -0.14082408 -0.62613231 0.76689434, + -0.11562797 -0.62819284 0.76941782, + -0.10148799 -0.59498596 0.7973029, + -0.080646954 -0.59612566 0.79883051, + -0.068527997 -0.56195098 0.82432699, + -0.051926889 -0.5625149 0.82515484, + -0.041709598 -0.52720797 0.84871203, + -0.029252307 -0.5274421 0.84908718, + -0.021038998 -0.49153996 0.87060088, + -0.012550402 -0.49161005 0.8707251, + -0.0063563292 -0.45559993 0.89016187, + -0.0019992895 -0.45560887 0.89017779, + 0.0022259601 -0.42012805 0.90746212, + 0.0030371107 -0.42012709 0.90746021, + 0.0054998016 -0.3847051 0.92302322, + 0.0021870907 -0.38470915 0.92303538, + 0.0029551401 -0.35039601 0.93659699, + -0.0029812411 -0.35039511 0.93659735, + -0.0022078706 -0.38505915 0.92288935, + -0.0055067982 -0.38505384 0.92287767, + -0.0030697007 -0.42014208 0.90745324, + -0.0022217103 -0.42014307 0.90745515, + 0.0020014807 -0.45560616 0.89017928, + 0.0064513716 -0.45559812 0.89016223, + 0.012639398 -0.49158493 0.87073791, + 0.021080101 -0.49151501 0.87061399, + 0.0292808 -0.52737498 0.84912801, + 0.041780688 -0.5271399 0.84875083, + 0.051989876 -0.56242877 0.82520956, + 0.068606384 -0.5618639 0.8243798, + 0.080807306 -0.59627205 0.7987051, + 0.10160198 -0.59513289 0.7971788, + 0.11593699 -0.62878692 0.76888591, + 0.14126605 -0.62670726 0.7663433, + 0.15740702 -0.65866905 0.73578405, + 0.18708201 -0.65520704 0.73191804, + 0.20466596 -0.68486685 0.6993348, + 0.23854189 -0.67947972 0.69383365, + 0.25720099 -0.70644403 0.65938199, + 0.29516089 -0.69846779 0.65193778, + 0.31449798 -0.72242892 0.61578196, + 0.35610399 -0.71115702 0.60617298, + 0.375453 -0.73166001 0.56895399, + 0.41954824 -0.71657544 0.55722433, + 0.4382531 -0.73344016 0.51961511, + 0.48388389 -0.71408582 0.50590289, + 0.50130922 -0.72731733 0.4687202, + 0.54782999 -0.70321101 0.45318499, + 0.56354904 -0.71307904 0.41705006, + 0.60983068 -0.68411767 0.40011182, + 0.62354004 -0.69101906 0.36563703, + 0.66806096 -0.65770996 0.34801197, + 0.67952925 -0.66212624 0.31595713, + 0.72146004 -0.62495005 0.29821602, + 0.73071998 -0.62744898 0.26899099, + 0.76974601 -0.58670801 0.25152501, + 0.77700031 -0.58782625 0.22523507, + 0.81273758 -0.54405874 0.20846489, + 0.81821501 -0.54425102 0.185243, + 0.85005456 -0.49860477 0.16970693, + 0.8540197 -0.49824882 0.14966094, + 0.88197076 -0.45138088 0.13558297, + 0.88474023 -0.45076013 0.11853303, + 0.90912187 -0.40283495 0.10593098, + 0.91098177 -0.40213892 0.091632478, + 0.93193966 -0.35355088 0.080561273, + 0.93313324 -0.35289609 0.068751417, + 0.95069045 -0.30441815 0.059307031, + 0.95141548 -0.30386716 0.049734522, + 0.96582979 -0.25577393 0.041862987, + 0.96640241 -0.25516185 0.030962382, + 0.9780215 -0.20698589 0.025116589, + 0.97833186 -0.20654497 0.014347398, + 0.98718178 -0.15921596 0.011059797, + 0.98724788 -0.15909499 0.0055141198, + 0.99279678 -0.11980497 0.0011398698, + 0.99275434 -0.12015604 0.0011483805, + 0.99277222 -0.12000803 0.0011557002, + 0.99277264 -0.12000795 0.00079577271, + 0.99275476 -0.12015597 0.00079577282, + 0.99279714 -0.11980502 0.00080359512, + 0.98568839 -0.16856989 -0.0015709291, + 0.98568749 -0.16856992 0.002069769, + 0.98570955 -0.16844092 0.0020665792, + 0.98569965 -0.16843894 -0.004949098, + 0.98379266 -0.17927894 -0.0033397188, + 0.9970125 -0.07716734 -0.0033618517, + 0.99746197 -0.071084902 -0.004069, + 0.99747014 -0.071085505 0.00044159405, + 0.99358034 -0.11306503 0.0037894915, + 0.99354774 -0.11315397 0.0076836781, + 0.98709965 -0.15973894 0.010846997, + 0.98691934 -0.16009305 0.018986108, + 0.97778577 -0.20814796 0.024685195, + 0.97741467 -0.20867793 0.033378389, + 0.96562326 -0.25668305 0.041056912, + 0.96511787 -0.25719497 0.048970893, + 0.95036203 -0.305655 0.058197901, + 0.94948554 -0.30630887 0.068205468, + 0.93144798 -0.355176 0.0790869, + 0.93002212 -0.35594103 0.091459811, + 0.90842414 -0.40489706 0.10403901, + 0.90621811 -0.40569606 0.11907802, + 0.88102603 -0.45391899 0.133232, + 0.87775868 -0.45461285 0.15121794, + 0.84882385 -0.50165188 0.16686395, + 0.84417248 -0.50201732 0.18802013, + 0.81118464 -0.54764074 0.2051079, + 0.8048529 -0.54734993 0.22938997, + 0.76783085 -0.59086186 0.24762493, + 0.75949585 -0.58948696 0.27508396, + 0.71917939 -0.62964237 0.29382217, + 0.70856982 -0.62666184 0.32438192, + 0.66540402 -0.66293299 0.34315801, + 0.65237021 -0.65776324 0.37651116, + 0.60680163 -0.68983358 0.39486876, + 0.59143579 -0.68190974 0.43035185, + 0.54445672 -0.70934057 0.44766372, + 0.52698576 -0.69814563 0.48464277, + 0.48019117 -0.72056323 0.50020516, + 0.4610132 -0.70573235 0.53796726, + 0.41553575 -0.72337461 0.55141562, + 0.39516425 -0.70469344 0.58928138, + 0.351877 -0.71806902 0.60046601, + 0.33110502 -0.69570208 0.63747007, + 0.2907331 -0.70544225 0.64639425, + 0.27026299 -0.67968303 0.68190098, + 0.2340059 -0.68635368 0.68859261, + 0.21435714 -0.65753043 0.72229141, + 0.18250896 -0.66187185 0.72705984, + 0.164112 -0.63037801 0.75874299, + 0.13673897 -0.63303983 0.7619468, + 0.12008799 -0.59957993 0.79125386, + 0.097157061 -0.60109377 0.79325068, + 0.0827002 -0.56665701 0.81979299, + 0.064278089 -0.56742889 0.8209098, + 0.05182948 -0.53179485 0.84528571, + 0.037732605 -0.53213209 0.84582013, + 0.027359514 -0.49570423 0.86806041, + 0.017444599 -0.49581501 0.86825299, + 0.0091997506 -0.45915005 0.88831115, + 0.0033045895 -0.45916694 0.88834387, + -0.0028286593 -0.4228639 0.90618879, + -0.0047207209 -0.4228611 0.90618223, + -0.0089528281 -0.38665292 0.92218179, + -0.007042319 -0.38665894 0.92219585, + -0.0094802761 -0.35081789 0.93639565, + -0.0034111007 -0.35083207 0.93643224, + -0.0041623912 -0.31631112 0.94864637, + 0.0044915196 -0.31631097 0.94864488, + 0.0037254286 -0.35117689 0.93630165, + 0.0097764032 -0.35116309 0.93626326, + 0.0073549082 -0.38664392 0.92219979, + 0.0089402189 -0.38663894 0.92218786, + 0.0047089611 -0.42282909 0.90619725, + 0.0031428004 -0.42283106 0.90620309, + -0.0030372282 -0.45936474 0.88824248, + -0.0091174664 -0.45934781 0.8882097, + -0.017342903 -0.49591106 0.86820012, + -0.027294403 -0.49580106 0.86800712, + -0.037661903 -0.53219908 0.84578115, + -0.051802807 -0.53186208 0.84524512, + -0.06424021 -0.56746304 0.82088912, + -0.08268448 -0.56668991 0.81977183, + -0.097057216 -0.60092604 0.7933901, + -0.119899 -0.59942102 0.791403, + -0.13632296 -0.63242978 0.7625277, + -0.16356298 -0.62979192 0.75934786, + -0.18199989 -0.66137159 0.7276426, + -0.21374211 -0.65706128 0.72290033, + -0.23348497 -0.68603295 0.68908894, + -0.26972106 -0.67938519 0.68241221, + -0.29030114 -0.70528835 0.64675629, + -0.33064288 -0.69557476 0.63784873, + -0.35148582 -0.71802163 0.6007517, + -0.39477393 -0.70466495 0.58957696, + -0.41520315 -0.72340125 0.55163115, + -0.46068093 -0.70577794 0.53819191, + -0.47990894 -0.72064793 0.50035393, + -0.52672273 -0.69823861 0.48479471, + -0.54419911 -0.70943516 0.44782713, + -0.59120727 -0.68200624 0.43051314, + -0.60661095 -0.68994796 0.39496195, + -0.65219384 -0.65788382 0.3766059, + -0.66523826 -0.66305524 0.34324312, + -0.7084378 -0.62677079 0.32445991, + -0.71905094 -0.62975192 0.29390198, + -0.75940287 -0.58957493 0.27515197, + -0.76773614 -0.59095007 0.24770802, + -0.80477214 -0.54743606 0.22946803, + -0.8110978 -0.54772687 0.20522095, + -0.84408897 -0.50211602 0.188131, + -0.84873617 -0.50175112 0.16701104, + -0.87770188 -0.45468095 0.15134299, + -0.88097459 -0.45398578 0.13334394, + -0.90617073 -0.40577084 0.11918295, + -0.90839559 -0.40496483 0.10402395, + -0.93000078 -0.35599992 0.091446474, + -0.93144441 -0.35522419 0.078911841, + -0.94948685 -0.30633897 0.068052091, + -0.95037389 -0.30567497 0.057899393, + -0.96480709 -0.25836504 0.048938207, + -0.96426922 -0.25889805 0.056184314, + -0.94911098 -0.307778 0.0667919, + -0.94804937 -0.30855611 0.077431828, + -0.92944837 -0.35785612 0.089803733, + -0.9277426 -0.35874882 0.10292195, + -0.90539026 -0.40811709 0.11708503, + -0.90277588 -0.40903193 0.13299799, + -0.87665814 -0.45753506 0.14876902, + -0.87282181 -0.45830387 0.16774896, + -0.84273732 -0.50552619 0.18503305, + -0.83734429 -0.50588816 0.20720008, + -0.8030839 -0.55140793 0.22584397, + -0.79577017 -0.55099112 0.25131407, + -0.75734729 -0.59412926 0.2709901, + -0.74774933 -0.59243733 0.29981515, + -0.70600098 -0.63190103 0.319787, + -0.69385266 -0.62834769 0.35177782, + -0.64938074 -0.66355276 0.37148687, + -0.63466316 -0.65753615 0.40601608, + -0.58799404 -0.68823206 0.42497006, + -0.57080418 -0.67914921 0.46145317, + -0.52314687 -0.70491982 0.47896287, + -0.50371587 -0.69220585 0.51683789, + -0.45679101 -0.71280301 0.53221601, + -0.43566778 -0.69614965 0.57058668, + -0.39058924 -0.7119714 0.58355534, + -0.36852202 -0.69137007 0.62144905, + -0.32622096 -0.70302796 0.63192695, + -0.30394688 -0.67863274 0.66863579, + -0.26512706 -0.6868422 0.6767242, + -0.24330904 -0.65893304 0.71176404, + -0.20908608 -0.66433221 0.71759725, + -0.18839508 -0.63348728 0.75046736, + -0.15886199 -0.63684702 0.75444603, + -0.14011905 -0.60424823 0.7843793, + -0.11518299 -0.60620695 0.78692186, + -0.098479159 -0.57212782 0.81423068, + -0.077981092 -0.57317096 0.81571686, + -0.063197695 -0.53741294 0.84094787, + -0.047237013 -0.53788912 0.8416912, + -0.034558009 -0.50100815 0.86475229, + -0.0230466 -0.50117499 0.86503899, + -0.012608803 -0.46390313 0.88579625, + -0.0053348215 -0.46393311 0.88585424, + 0.0029626694 -0.42637691 0.90454078, + 0.0061893212 -0.4263711 0.90452725, + 0.012318404 -0.38941213 0.92098135, + 0.0114347 -0.38941601 0.920991, + 0.015672395 -0.35242289 0.93570966, + 0.010974803 -0.3524451 0.93576825, + 0.013355005 -0.3167161 0.94842637, + 0.0049054688 -0.31673992 0.94849974, + 0.0056425179 -0.2823509 0.95929462, + -0.0056635626 -0.28235114 0.9592945, + -0.0049213399 -0.31709799 0.94837999, + -0.013366495 -0.31707388 0.94830662, + -0.011013003 -0.35245708 0.93576324, + -0.015683698 -0.35243496 0.93570489, + -0.0114471 -0.38942999 0.92098498, + -0.012012595 -0.38942784 0.92097867, + -0.0058867899 -0.42641601 0.90450799, + -0.0029682487 -0.42642179 0.90451956, + 0.0053045494 -0.46387294 0.88588589, + 0.012672203 -0.46384212 0.88582724, + 0.023100402 -0.50109303 0.86508512, + 0.034622792 -0.50092685 0.86479682, + 0.047291812 -0.53778714 0.84175318, + 0.063227415 -0.53731209 0.84101015, + 0.078020789 -0.57310587 0.81575882, + 0.098527484 -0.57206094 0.81427187, + 0.115354 -0.60639101 0.78675503, + 0.14030299 -0.60442793 0.78420788, + 0.15934299 -0.63753295 0.75376487, + 0.18897009 -0.63414931 0.74976337, + 0.20962299 -0.664922 0.71689397, + 0.24400584 -0.65947556 0.71102256, + 0.26565784 -0.68715757 0.67619556, + 0.30452096 -0.67891693 0.66808593, + 0.32667416 -0.70317036 0.63153428, + 0.36900604 -0.69148207 0.62103707, + 0.39098316 -0.71199536 0.58326232, + 0.4360348 -0.69616163 0.5702917, + 0.45711306 -0.71277708 0.53197408, + 0.50406504 -0.69214708 0.51657605, + 0.52341896 -0.70481294 0.47882295, + 0.57106769 -0.67902768 0.4613058, + 0.58824134 -0.68810344 0.42483625, + 0.63484877 -0.65742975 0.40589786, + 0.64955419 -0.66344219 0.3713811, + 0.69401902 -0.62822598 0.35166699, + 0.70614308 -0.63177407 0.31972402, + 0.74786884 -0.59231687 0.29975495, + 0.75745589 -0.59400892 0.27094996, + 0.79585189 -0.55088794 0.25128096, + 0.80317181 -0.55130786 0.22577594, + 0.83742452 -0.50578272 0.20713288, + 0.84282386 -0.50542092 0.18492599, + 0.87287372 -0.45823684 0.16766194, + 0.87671626 -0.45746511 0.14864203, + 0.90282673 -0.40895784 0.13288096, + 0.90543723 -0.4080441 0.11697703, + 0.92777038 -0.35870311 0.10283203, + 0.92946422 -0.3578161 0.089799821, + 0.94805688 -0.30853298 0.077431493, + 0.94910514 -0.30776602 0.066929705, + 0.96426851 -0.25887588 0.056297574, + 0.96487778 -0.25826895 0.048041388, + 0.97694898 -0.20987301 0.039039198, + 0.97727579 -0.20942895 0.032735493, + 0.98656291 -0.16142198 0.025231596, + 0.98676687 -0.15997799 0.026424397, + 0.98616278 -0.16310796 0.029645393, + 0.97678876 -0.21075195 0.038304791, + 0.97639453 -0.2112799 0.044883978, + 0.96399713 -0.26010802 0.055256907, + 0.96326715 -0.26082402 0.063932508, + 0.94763452 -0.31017485 0.076029263, + 0.94638997 -0.311068 0.087078497, + 0.92715067 -0.36081788 0.10100497, + 0.9251439 -0.36184096 0.11480398, + 0.90196675 -0.4115859 0.13058697, + 0.89889568 -0.41262186 0.14740995, + 0.87172514 -0.46143305 0.16484801, + 0.86725301 -0.46227601 0.18486001, + 0.83595014 -0.50957209 0.20377403, + 0.82969218 -0.50991911 0.22714207, + 0.79401553 -0.55529666 0.24735585, + 0.78555787 -0.55471396 0.27420998, + 0.74565184 -0.5973379 0.29528093, + 0.73462218 -0.5952611 0.32556808, + 0.69141108 -0.63385105 0.34667504, + 0.67763495 -0.62965095 0.37993494, + 0.6318478 -0.6636368 0.4004429, + 0.61531007 -0.65666407 0.43610305, + 0.56767201 -0.68579501 0.45544899, + 0.54847282 -0.67538977 0.49297681, + 0.50031829 -0.69935739 0.51047128, + 0.47885224 -0.68499732 0.54907125, + 0.43197894 -0.70371497 0.56407392, + 0.40908378 -0.68530267 0.60250372, + 0.36466381 -0.69930363 0.61481273, + 0.34107497 -0.67687792 0.65230691, + 0.29992494 -0.6869058 0.66197079, + 0.27634606 -0.66064119 0.6979872, + 0.23924206 -0.66744715 0.70517915, + 0.216351 -0.63768297 0.73929203, + 0.18409809 -0.64198929 0.74428338, + 0.16264996 -0.60950387 0.77591884, + 0.13537201 -0.61204404 0.77915114, + 0.11612499 -0.57803792 0.80770487, + 0.093553595 -0.57942295 0.80963987, + 0.076283604 -0.54362106 0.83585709, + 0.058306377 -0.54428184 0.83687371, + 0.043206822 -0.50713426 0.8607834, + 0.029860392 -0.50738186 0.86120385, + 0.017082393 -0.46955377 0.88273859, + 0.0082288021 -0.46960711 0.88283724, + -0.0022641795 -0.43143591 0.90214074, + -0.0069971182 -0.43142691 0.90212077, + -0.015239499 -0.39339593 0.91924286, + -0.015348606 -0.39339516 0.91924137, + -0.021532692 -0.35526988 0.93451566, + -0.0181915 -0.35529301 0.934578, + -0.022287706 -0.3187041 0.94759226, + -0.014898405 -0.31874812 0.94772238, + -0.017210295 -0.28312793 0.95892775, + -0.006432049 -0.28316396 0.95904988, + -0.0071462076 -0.24896692 0.96848565, + 0.0071406378 -0.24896692 0.96848565, + 0.0064254012 -0.28318006 0.95904523, + 0.017542094 -0.28314191 0.95891762, + 0.015223598 -0.31875798 0.94771385, + 0.022608006 -0.31871408 0.94758123, + 0.018469699 -0.35560998 0.93445188, + 0.021781994 -0.3555859 0.93438977, + 0.0156438 -0.39336801 0.91924798, + 0.0152336 -0.39337 0.919254, + 0.0069936425 -0.43138415 0.90214127, + 0.0022605294 -0.43139392 0.90216076, + -0.0082365815 -0.46957511 0.88285422, + -0.017071797 -0.46952188 0.88275576, + -0.029858693 -0.50737691 0.86120683, + -0.043130904 -0.50713104 0.86078912, + -0.058276687 -0.54438186 0.83681083, + -0.076267704 -0.54372007 0.83579409, + -0.09351591 -0.57947206 0.80960912, + -0.11611105 -0.5780862 0.80767232, + -0.13521108 -0.61182839 0.77934849, + -0.16245902 -0.60929608 0.77612209, + -0.18356 -0.64126998 0.74503601, + -0.21566901 -0.63700199 0.74007797, + -0.23859194 -0.66682881 0.70598382, + -0.27558091 -0.66007078 0.69882876, + -0.29937011 -0.68658924 0.66255021, + -0.34043297 -0.67660993 0.65291995, + -0.36417803 -0.69919407 0.61522508, + -0.4085981 -0.68521917 0.6029281, + -0.4316009 -0.70372081 0.56435591, + -0.47848013 -0.6850242 0.54936212, + -0.49997419 -0.69940424 0.51074415, + -0.54819769 -0.67542559 0.49323371, + -0.56743729 -0.68585432 0.45565221, + -0.61506873 -0.65674877 0.43631586, + -0.63166028 -0.66374332 0.40056217, + -0.67743409 -0.62978607 0.38006905, + -0.69123363 -0.63399273 0.34676981, + -0.73448765 -0.59538168 0.32565084, + -0.74552995 -0.59745991 0.29534197, + -0.78547215 -0.55481112 0.27425906, + -0.7939353 -0.55539316 0.24739709, + -0.82962412 -0.51001203 0.22718203, + -0.83587372 -0.50966483 0.20385492, + -0.86720115 -0.46234611 0.18492804, + -0.87167168 -0.46150282 0.16493493, + -0.89884877 -0.4126949 0.14749198, + -0.90191501 -0.41166201 0.130705, + -0.92511243 -0.36189017 0.11490205, + -0.92712212 -0.36086604 0.10109601, + -0.94636726 -0.31111506 0.087158121, + -0.94762248 -0.31021515 0.076015934, + -0.96326035 -0.2608521 0.06391982, + -0.96399838 -0.2601271 0.055145618, + -0.97639745 -0.2112861 0.044791523, + -0.9769485 -0.2105259 0.035361581, + -0.98649138 -0.16155006 0.027135309, + -0.98677862 -0.16100094 0.018615492, + -0.99341863 -0.11378197 0.013155895, + -0.99350464 -0.11353397 0.0076548574, + -0.99770111 -0.067614809 0.0045588403, + -0.99771255 -0.067560866 0.0022567788, + -0.99967486 -0.025490396 -0.00064394396, + -0.99967462 -0.02549039 0.0008920707, + -0.99723238 -0.074301228 -0.002641781, + -0.99723577 -0.074301489 -0.00027734195, + -0.99723625 -0.074295014 -0.00027747406, + -0.99723011 -0.074294508 -0.0035303705, + -0.99701309 -0.07716731 -0.0031963105, + -0.99966449 0.025738712 -0.0029279315, + -0.9973501 0.072750106 -0.00059389707, + -0.99734986 0.072750092 0.00087720086, + -0.99735725 0.072648816 0.00087720121, + -0.97863567 0.20559593 -0.0016118694, + -0.97851402 0.20582201 -0.012152, + -0.99717897 -0.071754001 0.022032401, + -0.99968934 -0.023829509 0.0073169428, + -0.99970347 -0.023629311 0.0058961329, + -0.99971187 0.023291398 -0.0058118193, + -0.99972188 0.023143299 -0.0045398497, + -0.99749452 0.06942077 -0.013617793, + -0.99755841 0.069099553 -0.010117995, + -0.99326038 0.11468204 -0.016792506, + -0.99337578 0.11432897 -0.011550097, + -0.98698938 0.15997106 -0.016161105, + -0.9871245 0.15967593 -0.0094274655, + -0.98720133 0.15918906 -0.0096139042, + -0.9935149 0.11349498 -0.006854279, + -0.99344367 0.11371696 -0.011754495, + -0.99763751 0.068334267 -0.0070634866, + -0.99759448 0.068555832 -0.010272005, + -0.99973452 0.02278729 -0.0034143084, + -0.99972725 0.022897106 -0.004596781, + -0.99972111 -0.023155902 0.0046487306, + -0.99971062 -0.023307893 0.0059543676, + -0.99725652 -0.071720064 0.018321991, + -0.99715346 -0.072196037 0.021743411, + -0.99188399 -0.121745 0.0366663, + -0.99162567 -0.12240796 0.041169386, + -0.98309302 -0.173554 0.058371, + -0.98247063 -0.17460795 0.065296374, + -0.97008109 -0.22740103 0.085038811, + -0.96881789 -0.22889997 0.094851382, + -0.95212078 -0.28243393 0.11703497, + -0.94982302 -0.28438401 0.130238, + -0.92813677 -0.3384369 0.15499197, + -0.92428964 -0.34074089 0.17200094, + -0.89693189 -0.39472893 0.19925398, + -0.89085931 -0.39716014 0.22053008, + -0.85733658 -0.4500328 0.24988888, + -0.84821641 -0.45216021 0.27582613, + -0.80867851 -0.50218773 0.30634382, + -0.79562652 -0.5033257 0.33710778, + -0.75037247 -0.54921228 0.36784121, + -0.73270178 -0.54840285 0.40299186, + -0.68240106 -0.58903909 0.43285307, + -0.65960795 -0.58512992 0.47174194, + -0.60585737 -0.61935538 0.49933529, + -0.57793486 -0.61114186 0.5408299, + -0.52342403 -0.63809299 0.56468099, + -0.49112105 -0.62466908 0.60711503, + -0.43825305 -0.64457607 0.62646306, + -0.40421224 -0.62626237 0.66663939, + -0.35439891 -0.64024985 0.68152881, + -0.32029685 -0.61759871 0.71831864, + -0.27509502 -0.62679106 0.72901005, + -0.23983888 -0.59862667 0.76427966, + -0.20092295 -0.60404986 0.7712028, + -0.16606605 -0.57109314 0.80391216, + -0.13351396 -0.5739488 0.80793369, + -0.10010296 -0.53694582 0.83765668, + -0.074331887 -0.53816289 0.83955681, + -0.04372881 -0.49865612 0.86569619, + -0.024066892 -0.49898782 0.86627471, + 0.0039953594 -0.45680493 0.8895579, + 0.017231796 -0.45674089 0.88943279, + 0.04204781 -0.41325909 0.90964222, + 0.049441099 -0.41311899 0.909334, + 0.070803404 -0.36932504 0.92659914, + 0.073658116 -0.36924809 0.92640722, + 0.091764733 -0.32549512 0.94108033, + 0.089112192 -0.32557398 0.9413079, + 0.10405095 -0.28248286 0.95361251, + 0.097667724 -0.28266606 0.95423323, + 0.10983295 -0.24012887 0.96450752, + 0.098557301 -0.24041399 0.96565402, + 0.1085 -0.197258 0.97432899, + 0.094096154 -0.19754891 0.97576654, + 0.099319465 -0.16859594 0.98066866, + 0.080675922 -0.16888104 0.98232925, + 0.078331336 -0.18598409 0.97942549, + 0.058849324 -0.18623406 0.98074138, + 0.056318399 -0.21206699 0.975631, + 0.035487708 -0.21227105 0.97656626, + 0.033945207 -0.23831207 0.97059524, + 0.011797004 -0.23843309 0.97108734, + 0.011250996 -0.2659629 0.96391761, + -0.011276803 -0.26596305 0.96391726, + -0.011813103 -0.23879506 0.97099823, + -0.033951603 -0.23867403 0.97050613, + -0.035532389 -0.21193492 0.97663766, + -0.056356985 -0.21173096 0.97570175, + 0.99771202 0.067564301 -0.0024045401, + 0.98528862 -0.16508694 0.044189084, + 0.99246246 -0.11838206 0.031687416, + 0.99275154 -0.11760694 0.024756189, + 0.99747378 -0.069512889 0.014632496, + 0.997545 -0.069172204 0.0109172, + 0.99973798 -0.0226129 0.0035689001, + 0.9997431 -0.022534302 0.0024426903, + 0.99974602 0.022406099 -0.0024287901, + 0.99974912 0.022357302 -0.0013893901, + 0.99770325 0.067606516 -0.0042014108, + 0.99359488 0.11299898 -0.00073947886, + 0.99355525 0.11314003 -0.006876362, + 0.99768901 0.067820899 -0.0041219699, + 0.99766177 0.067963883 -0.0072049582, + 0.99974334 0.022530608 -0.0023885109, + 0.99973834 0.022607507 -0.0034884713, + 0.99973398 -0.022796899 0.0035176999, + 0.99972653 -0.022907889 0.0047118575, + 0.99742323 -0.070270918 0.014453904, + 0.99732387 -0.070734195 0.018486299, + 0.99227512 -0.12002601 0.031368505, + 0.99197435 -0.12082305 0.037264913, + 0.98382074 -0.17119795 0.052801788, + 0.98328847 -0.17211509 0.05933243, + 0.97151154 -0.22405289 0.077236861, + 0.97043514 -0.22535603 0.086431809, + 0.95464498 -0.27800101 0.106623, + 0.95269448 -0.27969712 0.11892406, + 0.93228066 -0.33289388 0.14154296, + 0.92900109 -0.33492103 0.15743202, + 0.90333879 -0.38818091 0.18246795, + 0.89816856 -0.39034182 0.20230292, + 0.86676282 -0.44278589 0.22948395, + 0.8590048 -0.44472989 0.25362593, + 0.82193798 -0.494773 0.282166, + 0.81083786 -0.49593195 0.31079498, + 0.76827949 -0.54240429 0.3399182, + 0.75308597 -0.54197299 0.37299699, + 0.70542216 -0.58387411 0.4018341, + 0.68577147 -0.58085543 0.43854833, + 0.63418704 -0.61705804 0.46588206, + 0.60991007 -0.61037809 0.50541908, + 0.55681717 -0.63977325 0.52975917, + 0.52826697 -0.62848693 0.57090992, + 0.47563124 -0.65111232 0.59146231, + 0.44354612 -0.63451916 0.63297117, + 0.39321607 -0.65094006 0.64935207, + 0.35938904 -0.62915605 0.68920404, + 0.31296813 -0.64033127 0.70144635, + 0.27982205 -0.61455512 0.73757815, + 0.23879109 -0.62160826 0.74604422, + 0.20591411 -0.59131831 0.77970636, + 0.17111999 -0.59535491 0.78502887, + 0.13918196 -0.5608688 0.8161217, + 0.11017799 -0.56293297 0.81912589, + 0.079984419 -0.52492315 0.8473832, + 0.057690207 -0.52573305 0.84869111, + 0.030387396 -0.48569694 0.87359887, + 0.013851793 -0.48587477 0.87391859, + -0.010773701 -0.44380406 0.8960591, + -0.021641301 -0.44372606 0.89590114, + -0.043061987 -0.40093786 0.91509271, + -0.048864193 -0.40083095 0.91484791, + -0.067104399 -0.35791701 0.93133903, + -0.067553096 -0.35790598 0.93131089, + -0.082794935 -0.31514716 0.9454245, + -0.079290681 -0.3152369 0.94569474, + -0.091552801 -0.27361199 0.95747298, + -0.08335232 -0.27381006 0.95816523, + -0.093181342 -0.23252511 0.96811646, + -0.081469692 -0.23276398 0.9691149, + -0.089217223 -0.19113305 0.97750121, + -0.072979994 -0.19138597 0.97879785, + -0.075259402 -0.175005 0.98168701, + -0.059919491 -0.17518799 0.98270988, + -0.044665489 -0.17175396 0.98412675, + -0.053658992 -0.17167698 0.98369086, + -0.052211672 -0.18638991 0.98108751, + -0.069137581 -0.18619794 0.98007667, + -0.063425094 -0.22622997 0.97200686, + -0.076696411 -0.22601803 0.97109914, + -0.069010928 -0.26607311 0.96147949, + -0.07803563 -0.2658951 0.96083838, + -0.068136379 -0.30631489 0.94948864, + -0.073541515 -0.30619705 0.94912326, + -0.060947798 -0.34781 0.93558198, + -0.061471116 -0.34779808 0.93555224, + -0.046143387 -0.38969886 0.91978562, + -0.042567987 -0.38976091 0.91993177, + -0.0240041 -0.43236101 0.90138102, + -0.015555498 -0.43243295 0.90153188, + 0.0057262317 -0.47390518 0.8805573, + 0.020020995 -0.47381687 0.88039577, + 0.0440467 -0.513901 0.856718, + 0.063712403 -0.51335502 0.85580802, + 0.090563796 -0.55182803 0.82902598, + 0.11601503 -0.55036414 0.8268252, + 0.14503008 -0.58606029 0.79718238, + 0.17662804 -0.58301014 0.79303318, + 0.20706607 -0.61512822 0.76075029, + 0.24390598 -0.60976595 0.75411886, + 0.27514207 -0.63787019 0.71931815, + 0.31769103 -0.62910604 0.70943505, + 0.35017097 -0.65370792 0.67085493, + 0.39756 -0.64037102 0.65716898, + 0.42907193 -0.66003692 0.61664295, + 0.47963393 -0.64118296 0.59902894, + 0.5085578 -0.65559977 0.55817384, + 0.560444 -0.63059801 0.536888, + 0.58587188 -0.64020282 0.49688488, + 0.63740724 -0.60870123 0.47243518, + 0.65879077 -0.61422575 0.43442085, + 0.70819479 -0.57641691 0.4076809, + 0.72535276 -0.57877183 0.37267488, + 0.77060372 -0.5358398 0.34502989, + 0.78365082 -0.53600186 0.3139959, + 0.82381761 -0.48910877 0.28652585, + 0.83333403 -0.487966 0.25969899, + 0.86822331 -0.43800515 0.23310909, + 0.87486786 -0.43623495 0.21048798, + 0.90442288 -0.38424593 0.18540299, + 0.90884769 -0.38232285 0.16680893, + 0.93304765 -0.32973489 0.14386396, + 0.93583834 -0.32796013 0.12903005, + 0.95515752 -0.27553988 0.10840595, + 0.95682091 -0.27406096 0.096872784, + 0.97182733 -0.22222008 0.078548729, + 0.97274715 -0.22108603 0.069885209, + 0.98399413 -0.16991402 0.053709906, + 0.9843629 -0.16927399 0.048743393, + 0.97381812 -0.21845204 0.06290441, + 0.97303236 -0.21943907 0.071096219, + 0.95870697 -0.27055001 0.087655999, + 0.95728534 -0.27184209 0.098523036, + 0.93892062 -0.32353988 0.11725996, + 0.93653727 -0.32509708 0.13118704, + 0.91361713 -0.37703505 0.15214601, + 0.90984225 -0.37873608 0.16954705, + 0.88191211 -0.43026805 0.19261503, + 0.87621123 -0.4318741 0.21386604, + 0.84325755 -0.4816837 0.23853186, + 0.83507186 -0.48278895 0.26376098, + 0.7970739 -0.52995092 0.28952596, + 0.78581583 -0.52997988 0.31877092, + 0.74284142 -0.57368934 0.34506121, + 0.72797036 -0.57187527 0.37817717, + 0.68067795 -0.61105692 0.40408793, + 0.66185123 -0.60648823 0.44059616, + 0.61197066 -0.63985765 0.46483773, + 0.58934903 -0.63168305 0.50363106, + 0.5384649 -0.65886885 0.52530688, + 0.51243013 -0.64634418 0.5653801, + 0.46200779 -0.6675297 0.58391172, + 0.43330306 -0.65015107 0.62414104, + 0.38505885 -0.66576475 0.63912976, + 0.35470098 -0.64337993 0.67841697, + 0.31066781 -0.65407258 0.6896916, + 0.27999198 -0.62712091 0.72685891, + 0.24108188 -0.6339817 0.73481065, + 0.21217699 -0.604155 0.76810002, + 0.17829691 -0.60832572 0.77340162, + 0.15045998 -0.57482886 0.80432183, + 0.12245005 -0.5770722 0.80746132, + 0.096314996 -0.54044098 0.83585101, + 0.073632896 -0.54149091 0.8374759, + 0.049920812 -0.50280315 0.86295819, + 0.032956198 -0.50315791 0.86356586, + 0.011836695 -0.46291682 0.88632268, + 0.00046064911 -0.46295011 0.88638425, + -0.01786159 -0.42187178 0.9064796, + -0.02496 -0.42180699 0.90634203, + -0.040454581 -0.38048083 0.92390358, + -0.042285915 -0.38045216 0.92383337, + -0.055170182 -0.33892688 0.93919367, + -0.052622691 -0.33897397 0.93932289, + -0.062791385 -0.29851595 0.95233679, + -0.05648018 -0.29862887 0.95269662, + -0.064211294 -0.25942296 0.96362686, + -0.05392319 -0.25958094 0.96421474, + -0.059574109 -0.22115202 0.97341812, + -0.045226905 -0.22131903 0.97415215, + -0.049138691 -0.18251199 0.9819749, + -0.031269897 -0.18264298 0.98268187, + -0.032705303 -0.15802002 0.98689413, + -0.011344497 -0.15809496 0.98735875, + -0.010922994 -0.1803299 0.98354554, + 0.010919695 -0.1803299 0.98354554, + 0.011342197 -0.15805794 0.98736465, + 0.032738894 -0.15798396 0.98689878, + 0.031307787 -0.1826169 0.98268551, + 0.049187619 -0.18248606 0.98197734, + 0.045311913 -0.22103706 0.97421223, + 0.059634522 -0.22087008 0.97347838, + 0.05398339 -0.25933394 0.96427774, + 0.064251177 -0.2591759 0.96369064, + 0.056454226 -0.29871416 0.95267147, + 0.063426293 -0.29858896 0.95227188, + 0.053170875 -0.33934087 0.93915951, + 0.055364672 -0.33929986 0.93904752, + 0.042601611 -0.3804051 0.92383826, + 0.040445313 -0.3804391 0.92392123, + 0.024831394 -0.42207292 0.90622175, + 0.018389508 -0.42213115 0.90634829, + 5.91809e-005 -0.46318999 0.88625902, + -0.011980303 -0.46315712 0.88619524, + -0.033091698 -0.50337195 0.86343586, + -0.0500522 -0.50301701 0.86282599, + -0.073604017 -0.54144013 0.83751118, + -0.096300378 -0.5403899 0.83588582, + -0.12251894 -0.5771367 0.80740464, + -0.15066898 -0.57487893 0.8042469, + -0.17836998 -0.60821992 0.7734679, + -0.21204096 -0.60407591 0.7681998, + -0.24079497 -0.63375193 0.73510295, + -0.27968806 -0.62690616 0.72716117, + -0.30971888 -0.65331274 0.69083774, + -0.35363212 -0.64270127 0.67961723, + -0.38415316 -0.66523725 0.64022326, + -0.43227974 -0.64972466 0.62529367, + -0.46128887 -0.66730982 0.58473086, + -0.51171678 -0.64617872 0.56621468, + -0.53798604 -0.65883005 0.52584606, + -0.58891225 -0.63166523 0.50416416, + -0.6116721 -0.63989717 0.46517611, + -0.66152722 -0.60658026 0.44095615, + -0.68042505 -0.61116707 0.40434706, + -0.72776484 -0.5719769 0.37841892, + -0.74267894 -0.57379693 0.34523198, + -0.78569615 -0.53006709 0.31892103, + -0.79696721 -0.53003812 0.28966007, + -0.83497584 -0.48288387 0.26389095, + -0.84318787 -0.48177394 0.23859598, + -0.87615991 -0.43195093 0.21392097, + -0.88186723 -0.43034208 0.19265504, + -0.90980679 -0.37880492 0.16958295, + -0.91358727 -0.37710014 0.15216406, + -0.93652236 -0.32513613 0.13119605, + -0.93890214 -0.32358202 0.11729202, + -0.95727187 -0.27187896 0.098550983, + -0.95869088 -0.27058998 0.08770939, + -0.97302413 -0.21946204 0.071136907, + -0.97380823 -0.21847804 0.062968314, + -0.98435724 -0.16929305 0.048792712, + -0.98398936 -0.16993205 0.053741317, + -0.97273874 -0.22110994 0.069926582, + -0.97182024 -0.22224306 0.078572124, + -0.95680797 -0.274095 0.096904099, + -0.95514667 -0.27557191 0.10841996, + -0.9358241 -0.32799503 0.12904501, + -0.93302822 -0.3297731 0.14390303, + -0.90881586 -0.38237694 0.16685799, + -0.90438509 -0.38430306 0.18546902, + -0.87482113 -0.43629405 0.21056002, + -0.86816561 -0.43806779 0.2332059, + -0.83323413 -0.48807007 0.25982404, + -0.82369888 -0.48921493 0.28668597, + -0.78353131 -0.53608519 0.31415212, + -0.77043515 -0.5359211 0.34528008, + -0.72515506 -0.57885003 0.37293804, + -0.70793027 -0.57648116 0.40804914, + -0.65847778 -0.61428678 0.43480885, + -0.63697779 -0.60872287 0.47298589, + -0.58543831 -0.64017832 0.49742723, + -0.55974597 -0.63045794 0.53777993, + -0.50786501 -0.65539098 0.55904901, + -0.47862712 -0.64079219 0.60025114, + -0.42806971 -0.65956855 0.61783957, + -0.396393 -0.63976598 0.65846199, + -0.34911492 -0.65300483 0.6720888, + -0.3173449 -0.62891883 0.70975584, + -0.27483404 -0.63766009 0.71962208, + -0.24393797 -0.60986197 0.75403088, + -0.20682988 -0.61526161 0.76070654, + -0.17666405 -0.58344924 0.79270232, + -0.14504308 -0.58650428 0.79685336, + -0.11583202 -0.55058604 0.82670313, + -0.090411678 -0.5520469 0.82889682, + -0.063723594 -0.51383191 0.8555209, + -0.04403251 -0.5143801 0.85643119, + -0.019671008 -0.47375616 0.8804363, + -0.0060363091 -0.47383896 0.88059086, + 0.015245502 -0.43235606 0.90157413, + 0.024332091 -0.43227884 0.90141171, + 0.042743985 -0.39005086 0.91980064, + 0.04633861 -0.38998809 0.91965324, + 0.061775185 -0.34781492 0.93552577, + 0.060914516 -0.34783408 0.93557525, + 0.073596716 -0.30593607 0.94920325, + 0.068533182 -0.30604595 0.94954675, + 0.078421101 -0.26568499 0.96086502, + 0.069077007 -0.26586902 0.9615311, + 0.076763213 -0.22578406 0.97114825, + 0.063518219 -0.22599508 0.97205538, + 0.06924817 -0.18575691 0.98015255, + 0.051935606 -0.18595302 0.98118514, + 0.0544772 -0.15993001 0.98562402, + 0.034556106 -0.16007204 0.98650026, + 0.033346195 -0.18105298 0.98290789, + 0.011688794 -0.18114191 0.98338753, + 0.0111435 -0.20952401 0.97773999, + -0.0111497 -0.20952401 0.97773999, + -0.011694201 -0.18114401 0.98338711, + -0.035329912 -0.18104306 0.98284036, + -0.033651687 -0.20986693 0.97715062, + -0.011576999 -0.20997196 0.9776389, + -0.011034103 -0.23798905 0.97120523, + 0.011367694 -0.23798788 0.97120154, + 0.011909395 -0.21032692 0.97755861, + 0.033624604 -0.21022303 0.9770751, + 0.035205282 -0.18311191 0.98246151, + 0.0560432 -0.182937 0.98152602, + 0.057872087 -0.16407496 0.98474878, + 0.076825872 -0.16386494 0.98348665, + 0.073081538 -0.19093008 0.97887945, + 0.089350104 -0.19067703 0.9775781, + 0.081565276 -0.23257694 0.96915174, + 0.093248978 -0.23233794 0.96815479, + 0.083510421 -0.27327105 0.95830524, + 0.091704533 -0.27307308 0.95761234, + 0.079356022 -0.31500009 0.94576824, + 0.082855806 -0.31491002 0.94549811, + 0.067646511 -0.35757804 0.9314301, + 0.067210183 -0.3575879 0.93145776, + 0.048849318 -0.40078413 0.91486931, + 0.043056298 -0.40088993 0.91511387, + 0.021495894 -0.44394788 0.89579475, + 0.0109486 -0.444024 0.89594799, + -0.013512105 -0.48579517 0.8739683, + -0.030332897 -0.48561594 0.8736459, + -0.057829607 -0.52593404 0.84855711, + -0.080141805 -0.52512205 0.8472451, + -0.110126 -0.56286597 0.819179, + -0.13912193 -0.56080377 0.81617659, + -0.17127298 -0.59551793 0.78487188, + -0.20610598 -0.59147096 0.77953988, + -0.23885015 -0.62163335 0.7460044, + -0.28000882 -0.61455363 0.73750859, + -0.3126891 -0.63998115 0.70189017, + -0.35886881 -0.62888569 0.68972164, + -0.39206919 -0.65029329 0.65069228, + -0.44235107 -0.63396907 0.63435704, + -0.47463495 -0.65070295 0.59271193, + -0.52719086 -0.62820184 0.57221687, + -0.55610996 -0.63966095 0.53063697, + -0.60923594 -0.61032194 0.50629896, + -0.63375598 -0.61708403 0.466434, + -0.68534684 -0.58093286 0.43910888, + -0.7051422 -0.58397812 0.40217409, + -0.75286049 -0.54206932 0.37331221, + -0.76810384 -0.54250389 0.3401559, + -0.81070411 -0.49601707 0.31100804, + -0.82182455 -0.49485871 0.28234583, + -0.85892516 -0.44479513 0.25378105, + -0.86670488 -0.44284794 0.22958297, + -0.89811474 -0.39041492 0.20240095, + -0.9032979 -0.38824794 0.18252799, + -0.92897624 -0.33496809 0.15747905, + -0.9322589 -0.33293998 0.14157799, + -0.95268387 -0.27972296 0.11894798, + -0.95463562 -0.27802593 0.10664196, + -0.97042876 -0.22537693 0.086447679, + -0.97150451 -0.2240749 0.077261761, + -0.98328489 -0.17212899 0.059350591, + -0.98381639 -0.17121306 0.052835118, + -0.99197251 -0.12083094 0.037287481, + -0.99227321 -0.12003403 0.031398207, + -0.99732333 -0.070738621 0.018503608, + -0.99742341 -0.070271157 0.014436391, + -0.99972653 -0.022907488 0.0047060675, + -0.9997341 -0.022794902 0.0034938205, + -0.99973845 0.022605911 -0.0034648515, + -0.99974334 0.022530207 -0.0023819609, + -0.99766201 0.067961998 -0.0071851602, + -0.99768853 0.067822874 -0.004189088, + -0.99355465 0.11313897 -0.0069880178, + -0.99359512 0.11299601 -0.00080707314, + -0.99257463 0.12156796 -0.0040900288, + -0.99258077 0.12156897 -0.0020793595, + -0.99734312 0.07284271 0.00086972211, + -0.99733943 0.072842352 -0.0028202084, + -0.99735361 0.072648481 -0.0028166091, + -0.99771327 0.067555614 -0.0021043005, + -0.9977029 0.067606494 -0.0042689797, + -0.999749 0.0223582 -0.0014118, + -0.99974602 0.0224056 -0.0024222799, + -0.9997431 -0.022534002 0.0024361603, + -0.9997381 -0.022611402 0.0035450605, + -0.99754614 -0.069167905 0.010844301, + -0.9974739 -0.069513895 0.014614898, + -0.99275225 -0.11760803 0.024726506, + -0.99246055 -0.11838994 0.031716585, + -0.98528486 -0.16509798 0.044229798, + -0.9851259 -0.16627598 0.043351095, + -0.97473276 -0.21614896 0.056353785, + -0.97406566 -0.21700093 0.064082377, + -0.96032637 -0.26746008 0.078983627, + -0.95911354 -0.26858488 0.089238256, + -0.94157702 -0.31961799 0.106194, + -0.93954223 -0.3209801 0.11929903, + -0.91772467 -0.37233189 0.13838495, + -0.91449988 -0.37383598 0.15471499, + -0.88797611 -0.42493606 0.17586301, + -0.88309902 -0.42638299 0.19578999, + -0.85186583 -0.47597787 0.21856296, + -0.84479868 -0.47703382 0.24239191, + -0.8087281 -0.52437204 0.26644504, + -0.7989769 -0.52453494 0.29410696, + -0.75805509 -0.56887007 0.31896603, + -0.74512517 -0.56747812 0.3503671, + -0.69981974 -0.60780579 0.37526584, + -0.68331224 -0.60404426 0.41014016, + -0.63514316 -0.63901317 0.43388408, + -0.61497521 -0.63203526 0.47152618, + -0.5652281 -0.66120118 0.49328512, + -0.54169309 -0.65025717 0.5326671, + -0.49165189 -0.67363185 0.5518139, + -0.46535179 -0.65815473 0.59184468, + -0.41678208 -0.67591119 0.60781312, + -0.38854501 -0.65560102 0.64747202, + -0.34337792 -0.66824281 0.65995681, + -0.31439304 -0.64334404 0.69804406, + -0.27380505 -0.65181017 0.70723015, + -0.24577515 -0.62347639 0.74220741, + -0.21002993 -0.62885875 0.74861479, + -0.18364196 -0.5977329 0.78037882, + -0.15294001 -0.60092002 0.78454101, + -0.12800002 -0.56667805 0.81393611, + -0.10270004 -0.56835717 0.8163473, + -0.079320095 -0.53099895 0.84365189, + -0.059762191 -0.53172493 0.8448059, + -0.039025806 -0.49303412 0.86913419, + -0.024113791 -0.49326682 0.86954373, + -0.0058922493 -0.45331693 0.89132988, + 0.0033712084 -0.45332178 0.89134055, + 0.018924501 -0.412756 0.91064501, + 0.024111805 -0.4127101 0.91054326, + 0.037034299 -0.372049 0.92747402, + 0.037399415 -0.37204412 0.92746139, + 0.04780532 -0.33167613 0.94218135, + 0.044288978 -0.33172885 0.94233453, + 0.052157789 -0.29287294 0.95472777, + 0.044588715 -0.2929801 0.95507836, + 0.050381221 -0.25467113 0.96571445, + 0.038662206 -0.25480506 0.96621925, + 0.042522717 -0.2175951 0.9751125, + 0.027257986 -0.2177109 0.97563255, + 0.029484097 -0.18045698 0.98314089, + 0.0105184 -0.180526 0.98351401, + 0.010955296 -0.15763494 0.98743665, + -0.0109242 -0.157635 0.98743701, + -0.0104826 -0.180539 0.98351198, + -0.029436097 -0.18046999 0.98313987, + -0.027181691 -0.21802893 0.97556365, + -0.042465303 -0.21791203 0.97504413, + -0.038644403 -0.25470203 0.96624714, + -0.050051622 -0.25457311 0.96575749, + -0.044258583 -0.29291487 0.95511365, + -0.052193612 -0.29280305 0.95474726, + -0.044242822 -0.33207616 0.94221449, + -0.047754899 -0.33202201 0.94206202, + -0.037431005 -0.37208402 0.9274441, + -0.036716782 -0.37209383 0.9274686, + -0.023796989 -0.41277179 0.91052359, + -0.019258892 -0.41281185 0.9106127, + -0.0036997686 -0.45338386 0.89130771, + 0.0062297378 -0.45337784 0.89129668, + 0.024309603 -0.49303806 0.86966813, + 0.038891498 -0.49281093 0.86926687, + 0.059772208 -0.53177607 0.84477311, + 0.079348378 -0.53104889 0.8436178, + 0.10261102 -0.56822109 0.81645316, + 0.12796694 -0.5665397 0.81403756, + 0.15295707 -0.60085523 0.78458732, + 0.18365298 -0.59766793 0.78042591, + 0.21030295 -0.62910181 0.74833381, + 0.246061 -0.62370801 0.74191803, + 0.27461994 -0.65255785 0.70622385, + 0.31538588 -0.64401376 0.69697773, + 0.3442581 -0.66878921 0.65894419, + 0.38947394 -0.65608293 0.64642495, + 0.41746005 -0.67619008 0.60703707, + 0.46607572 -0.65836757 0.59103763, + 0.49214381 -0.67369676 0.55129582, + 0.54217607 -0.65028703 0.53213906, + 0.56555527 -0.66115332 0.49297425, + 0.61528409 -0.63196808 0.47121307, + 0.63541996 -0.63893294 0.43359694, + 0.68355393 -0.60395896 0.40986294, + 0.70000023 -0.60770524 0.37509215, + 0.74528503 -0.56737304 0.35019702, + 0.75819117 -0.56876212 0.31883508, + 0.79908711 -0.52443504 0.29398602, + 0.80882168 -0.5242728 0.2663559, + 0.84486216 -0.47695911 0.24231806, + 0.8519187 -0.47590482 0.21851593, + 0.88314211 -0.42631406 0.19574603, + 0.88801575 -0.42486891 0.17582496, + 0.91452497 -0.37378699 0.15468501, + 0.91775274 -0.37228191 0.13833296, + 0.93955725 -0.3209511 0.11925903, + 0.94159645 -0.31958514 0.10612106, + 0.95912677 -0.26855794 0.089176975, + 0.96034074 -0.26743194 0.078903876, + 0.97407538 -0.21697707 0.064017721, + 0.97474051 -0.21612689 0.056304574, + 0.98513025 -0.16626005 0.04331341, + 0.98540264 -0.16577195 0.038746987, + 0.97553223 -0.21408604 0.050039813, + 0.974971 -0.214816 0.057321198, + 0.96175122 -0.26466405 0.070622616, + 0.96072227 -0.26563707 0.080309823, + 0.94391614 -0.31605703 0.095553212, + 0.94217545 -0.31725115 0.10796905, + 0.9213466 -0.36801383 0.12524495, + 0.91858178 -0.36934391 0.14068598, + 0.89332741 -0.4199712 0.15997007, + 0.88914812 -0.42126805 0.17874302, + 0.85944968 -0.47061083 0.19967893, + 0.85340083 -0.47159588 0.22204594, + 0.81911188 -0.51898396 0.24435897, + 0.8106873 -0.51923817 0.2705141, + 0.77169609 -0.56403506 0.29385304, + 0.76047069 -0.56297785 0.32363588, + 0.71709716 -0.60424614 0.34735909, + 0.70270908 -0.60116804 0.38052207, + 0.65629381 -0.63752484 0.40353492, + 0.63856179 -0.63164878 0.43961185, + 0.59007126 -0.66265821 0.46119419, + 0.56908804 -0.65322703 0.49943307, + 0.51976508 -0.67867404 0.51888907, + 0.49607795 -0.66512895 0.55813092, + 0.44733912 -0.68511218 0.57489914, + 0.421727 -0.66716099 0.61403799, + 0.37560791 -0.68191785 0.6276198, + 0.34880883 -0.65943772 0.66593868, + 0.30654496 -0.66975492 0.67635691, + 0.27944598 -0.64295292 0.71310693, + 0.24162506 -0.64978915 0.72068816, + 0.21535701 -0.61940402 0.75495702, + 0.18247494 -0.62363774 0.76011771, + 0.15828404 -0.5910331 0.7909652, + 0.13065597 -0.59344786 0.79419684, + 0.10823205 -0.55828625 0.8225584, + 0.085717008 -0.55951905 0.82437313, + 0.065376475 -0.52230382 0.85024971, + 0.047932081 -0.5228228 0.8510927, + 0.029888492 -0.48404089 0.87453485, + 0.017490597 -0.48418295 0.87479186, + 0.0020045002 -0.44462207 0.89571613, + -0.0058779302 -0.44461599 0.895702, + -0.018661097 -0.40525591 0.91401279, + -0.021989405 -0.40522808 0.91395122, + -0.032534286 -0.36524782 0.9303416, + -0.031852003 -0.36525604 0.93036211, + -0.039928183 -0.32633185 0.94441152, + -0.034748707 -0.32639608 0.94459426, + -0.040649902 -0.28833604 0.95666611, + -0.031913295 -0.28842697 0.95696986, + -0.035870194 -0.25134397 0.96723288, + -0.023159308 -0.25143808 0.96759635, + -0.025353797 -0.21591097 0.97608387, + -0.0089923106 -0.21597204 0.97635812, + -0.0097125359 -0.17967194 0.98367864, + 0.0097593218 -0.17967205 0.98367822, + 0.0090555679 -0.21561795 0.97643578, + 0.025398497 -0.21555696 0.97616088, + 0.023182098 -0.25150296 0.96757889, + 0.035857882 -0.25140887 0.96721655, + 0.031941611 -0.2881071 0.95706534, + 0.040678311 -0.28801605 0.95676124, + 0.034779295 -0.32605198 0.94471186, + 0.039978012 -0.32598808 0.94452822, + 0.031761497 -0.36557496 0.93023986, + 0.032756999 -0.36556301 0.93020999, + 0.022298401 -0.40518206 0.91396409, + 0.018987091 -0.40520981 0.91402656, + 0.0060950071 -0.4448798 0.89556956, + -0.0021226106 -0.44488713 0.89558423, + -0.017488502 -0.48413405 0.8748191, + -0.029866088 -0.48399183 0.87456268, + -0.047972407 -0.52290803 0.8510381, + -0.065284319 -0.52239418 0.85020131, + -0.085692674 -0.55971783 0.82424068, + -0.10829202 -0.5584811 0.82241815, + -0.13063706 -0.59351432 0.79415035, + -0.158269 -0.59109902 0.79091901, + -0.182238 -0.62340301 0.76036698, + -0.21507397 -0.61918294 0.75521886, + -0.240878 -0.64904302 0.72161001, + -0.27860507 -0.6422562 0.71406317, + -0.30576816 -0.66914928 0.67730731, + -0.34792289 -0.65889978 0.66693377, + -0.37497309 -0.68161219 0.62833118, + -0.42103386 -0.66691375 0.61478174, + -0.44686407 -0.68503106 0.57536507, + -0.49557081 -0.66509575 0.55862081, + -0.51937497 -0.67871195 0.51922995, + -0.56876999 -0.65325701 0.49975601, + -0.5898149 -0.66271883 0.46143487, + -0.63827527 -0.63175523 0.43987516, + -0.65604895 -0.63764393 0.40374494, + -0.70253557 -0.60125566 0.38070375, + -0.71695483 -0.60434085 0.3474879, + -0.76033682 -0.56308389 0.3237659, + -0.77158511 -0.56414205 0.29393902, + -0.81059229 -0.5193432 0.2705971, + -0.81903017 -0.51908809 0.24441206, + -0.853347 -0.471674 0.222087, + -0.85939801 -0.470687 0.19972201, + -0.88910913 -0.42133406 0.17878102, + -0.89328772 -0.42003685 0.16001894, + -0.91855091 -0.36940396 0.14072998, + -0.92131037 -0.36807713 0.12532604, + -0.94215387 -0.31729296 0.10803398, + -0.94389302 -0.3161 0.095638499, + -0.96070611 -0.26567402 0.080381811, + -0.96173686 -0.26469898 0.070686489, + -0.97496367 -0.21483593 0.057370678, + -0.97552925 -0.21410105 0.050034411, + -0.98540097 -0.165783 0.0387429, + -0.98615003 -0.16214301 0.034896102, + -0.99289387 -0.11633898 0.025038097, + -0.9931035 -0.11576094 0.01856699, + -0.99758309 -0.068607807 0.011004101, + -0.99763149 -0.068370029 0.0075576338, + -0.99974579 -0.022408394 0.0024770193, + -0.999749 -0.0223598 0.00144309, + -0.99975061 0.022285892 -0.0014383196, + -0.99975097 0.022281401 -0.00124971, + -0.99971879 0.023680795 -0.0012763196, + -0.99971378 0.023680694 -0.0033936293, + -0.99971187 0.023764296 -0.0033854996, + -0.99971735 0.023764409 -0.00063859223, + -0.99973321 0.023092305 -0.00062551815, + -0.99967939 -0.025311409 0.00068562821, + -0.99967927 -0.025311405 0.0009001682, + -0.99967825 -0.025348905 0.0009001682, + -0.99967849 -0.025348911 -0.00064676028, + -0.99975246 -0.022248711 -0.00013333106, + -0.99975049 -0.022286789 0.0014700793, + -0.99768639 -0.067837521 0.0044746813, + -0.99765664 -0.067986377 0.007685137, + -0.99334764 -0.11442497 0.012934595, + -0.99320722 -0.11482303 0.018844604, + -0.98628587 -0.16286698 0.026729597, + -0.98596627 -0.16347805 0.033846106, + -0.97621322 -0.21231005 0.04395631, + -0.97573549 -0.21294111 0.050955925, + -0.96295387 -0.26226196 0.062758096, + -0.96207923 -0.26310506 0.071967117, + -0.9458949 -0.31297597 0.085608594, + -0.94441611 -0.31401402 0.097331315, + -0.92442709 -0.36426204 0.11290602, + -0.92206538 -0.36543211 0.12749505, + -0.89790511 -0.41562006 0.14500502, + -0.8943246 -0.41677979 0.16272092, + -0.86594927 -0.46588317 0.18189205, + -0.86075419 -0.46679813 0.20298204, + -0.82803118 -0.5141741 0.22358306, + -0.82076252 -0.51448768 0.24829686, + -0.78350371 -0.55962384 0.27007991, + -0.77371883 -0.55882889 0.29844493, + -0.73211825 -0.60085922 0.32089111, + -0.71950281 -0.59832591 0.35259292, + -0.674649 -0.63593102 0.37475401, + -0.659006 -0.630961 0.40938899, + -0.61187565 -0.66352355 0.43051672, + -0.59317791 -0.65538794 0.46755394, + -0.54462391 -0.68274796 0.48707294, + -0.52313101 -0.67078501 0.52572, + -0.47455895 -0.69280094 0.54297394, + -0.45096189 -0.67664284 0.58205485, + -0.40435886 -0.69336474 0.59643877, + -0.37938508 -0.67285216 0.63508821, + -0.33594498 -0.68495494 0.64651191, + -0.31042314 -0.6602003 0.68393928, + -0.27085802 -0.66854906 0.69258803, + -0.24573906 -0.64002419 0.7279982, + -0.21078596 -0.64543581 0.73415381, + -0.18731394 -0.61435574 0.7664727, + -0.15743504 -0.61762613 0.77055317, + -0.135919 -0.58447897 0.79994398, + -0.110939 -0.586312 0.80245298, + -0.091153704 -0.55076802 0.82966602, + -0.071044318 -0.55167311 0.83102918, + -0.053386107 -0.51442808 0.85587013, + -0.037865106 -0.51479411 0.8564772, + -0.022577398 -0.47652695 0.87886989, + -0.011971602 -0.47661406 0.87903112, + 0.00097576733 -0.43757516 0.89918131, + 0.006901152 -0.43756512 0.89916027, + 0.017421303 -0.39853609 0.91698724, + 0.019283701 -0.39852199 0.91695601, + 0.027463503 -0.35997903 0.93255609, + 0.025407391 -0.35999888 0.93260664, + 0.031459093 -0.3219209 0.94624376, + 0.025410613 -0.32197714 0.94640648, + 0.029447308 -0.28514406 0.95803225, + 0.019399691 -0.28521386 0.95826751, + 0.021651398 -0.24976297 0.9680649, + 0.0079257041 -0.24981412 0.96826148, + 0.0086301789 -0.21514997 0.97654289, + -0.0082455399 -0.215151 0.97654599, + -0.007549149 -0.24940097 0.96837085, + -0.021324102 -0.24935202 0.96817809, + -0.019052692 -0.28518292 0.95828366, + -0.029123204 -0.28511402 0.95805115, + -0.02509111 -0.32196712 0.94641834, + -0.031143697 -0.32191297 0.94625688, + -0.025150308 -0.35967311 0.93273938, + -0.027547704 -0.35965103 0.93268013, + -0.019293807 -0.39855316 0.91694236, + -0.017102297 -0.39856893 0.9169789, + -0.0066710589 -0.43729794 0.89929187, + -0.00075776101 -0.437307 0.89931202, + 0.012185602 -0.47636506 0.87916315, + 0.022778705 -0.47627711 0.87900025, + 0.038077801 -0.51459903 0.85658503, + 0.053411119 -0.51423717 0.85598332, + 0.071089737 -0.55153126 0.83111942, + 0.091139093 -0.55062896 0.8297599, + 0.11096399 -0.58624995 0.80249488, + 0.135932 -0.58441699 0.79998702, + 0.15762696 -0.61783588 0.77034581, + 0.18757109 -0.61455232 0.76625234, + 0.21144705 -0.6461522 0.73333317, + 0.246528 -0.64069599 0.72714001, + 0.27160493 -0.66914976 0.69171476, + 0.31122696 -0.66075593 0.68303692, + 0.33654702 -0.68529606 0.64583707, + 0.38002601 -0.67314899 0.63439, + 0.40481606 -0.69350106 0.59597003, + 0.45142588 -0.6767478 0.58157289, + 0.47490799 -0.69282103 0.54264301, + 0.52351207 -0.67076409 0.52536708, + 0.54491818 -0.68267626 0.48684418, + 0.59344065 -0.65531057 0.46732873, + 0.61211908 -0.66343707 0.43030405, + 0.65924394 -0.63085395 0.40917093, + 0.67484492 -0.63581091 0.37460497, + 0.71964294 -0.59823292 0.35246497, + 0.73224294 -0.60076392 0.32078496, + 0.77382118 -0.55874014 0.29834607, + 0.78358763 -0.55953377 0.27002287, + 0.82083958 -0.51439273 0.24823888, + 0.82810056 -0.51407975 0.2235429, + 0.86080819 -0.46671411 0.20294605, + 0.86600679 -0.46579888 0.18183395, + 0.89436311 -0.41671607 0.16267301, + 0.89794999 -0.41555399 0.144916, + 0.92210042 -0.36537117 0.12741606, + 0.92446202 -0.36420101 0.112817, + 0.94444102 -0.313963 0.097254701, + 0.94591886 -0.31292498 0.085530795, + 0.96209377 -0.26306894 0.071903989, + 0.96296066 -0.26223391 0.062770374, + 0.97573924 -0.21292104 0.050966512, + 0.97621149 -0.21229811 0.044054322, + 0.98596424 -0.16347404 0.033922706, + 0.98614311 -0.16217501 0.034944404, + 0.99289346 -0.11633705 0.025067711, + 0.9931004 -0.11576793 0.01868929, + 0.9975819 -0.068611592 0.011076499, + 0.99763125 -0.068370111 0.0075776516, + 0.99974579 -0.022408495 0.0024835893, + 0.999749 -0.0223586 0.00142043, + 0.99975061 0.022285592 -0.0014157995, + 0.99974954 0.022297289 -0.0019106991, + 0.99964124 0.026710106 -0.0020092004, + 0.99711353 0.075925462 -2.2801789e-006, + 0.99711311 0.07592541 0.00090249011, + 0.99711555 0.075892366 0.00090248958, + 0.99710953 0.075891964 -0.0035960083, + 0.99711412 0.075832106 -0.0035947005, + 0.99712014 0.075832605 0.00090480014, + 0.99218589 0.12474298 -0.0025230597, + 0.99217701 0.124742 -0.0049237702, + 0.99218953 0.12464194 -0.0049216175, + 0.98727626 0.15900904 -0.0013064704, + 0.98720253 0.15919092 -0.0094589051, + 0.99351591 0.11349299 -0.0067435591, + 0.99344277 0.11372097 -0.011786797, + 0.99763709 0.068337508 -0.007082921, + 0.99759322 0.068562716 -0.010342803, + 0.99973434 0.022789808 -0.0034378811, + 0.99972725 0.022897905 -0.004602591, + 0.99972099 -0.023156401 0.00465453, + 0.99971062 -0.023307092 0.0059487275, + 0.99725711 -0.071715906 0.018304203, + 0.997154 -0.072192401 0.021730199, + 0.99188578 -0.12173697 0.036643293, + 0.99162686 -0.12240198 0.041157298, + 0.98309654 -0.17353991 0.058352172, + 0.98247355 -0.17459491 0.065286271, + 0.97008777 -0.22737794 0.085023478, + 0.96882534 -0.22887607 0.094832838, + 0.95213246 -0.28240415 0.11701205, + 0.94983864 -0.2843509 0.13019596, + 0.92816103 -0.33839399 0.15494099, + 0.92432213 -0.34069303 0.17192101, + 0.89698571 -0.39465785 0.19915293, + 0.89092422 -0.3970851 0.22040306, + 0.85742241 -0.4499492 0.24974512, + 0.84832668 -0.45207185 0.2756319, + 0.80881548 -0.5020963 0.30613217, + 0.7958225 -0.50323272 0.3367838, + 0.7505905 -0.54913872 0.36750579, + 0.73304385 -0.54834288 0.40245092, + 0.68281782 -0.5889799 0.43227592, + 0.66027552 -0.58512861 0.47080868, + 0.60651708 -0.61944604 0.49842107, + 0.57895994 -0.61136997 0.53947395, + 0.5244838 -0.63841176 0.56333584, + 0.49243507 -0.62513608 0.60556805, + 0.43941614 -0.64520025 0.62500423, + 0.40467885 -0.62654674 0.66608876, + 0.35490596 -0.64055294 0.68097997, + 0.31995404 -0.61734205 0.71869206, + 0.275047 -0.62646198 0.72931099, + 0.23996703 -0.59841907 0.76440209, + 0.20074108 -0.60388231 0.77138138, + 0.16589901 -0.57093203 0.80406111, + 0.13368498 -0.57375795 0.80804086, + 0.10028594 -0.5367527 0.83775854, + 0.074170731 -0.53798616 0.83968431, + 0.043567277 -0.49846977 0.86581159, + 0.024252288 -0.49879676 0.86637956, + -0.0038182205 -0.45658207 0.88967311, + -0.017052904 -0.45651913 0.88955021, + -0.041699 -0.41331899 0.90963101, + -0.049449299 -0.41317299 0.90930903, + -0.070848577 -0.36929488 0.92660767, + -0.073362671 -0.36922789 0.92643863, + -0.091362432 -0.3257181 0.94104236, + -0.089043967 -0.32578689 0.94124067, + -0.10401804 -0.28259709 0.95358235, + -0.097267516 -0.28279102 0.9542371, + -0.10942899 -0.24027596 0.96451688, + -0.098463982 -0.24055298 0.96562886, + -0.10834298 -0.19772997 0.97425085, + -0.093971282 -0.19802096 0.97568285, + -0.097259037 -0.17989805 0.97886539, + -0.084085003 -0.180115 0.98004502, + -0.079309478 -0.21473995 0.97344577, + -0.059196223 -0.21504107 0.97480935, + -0.05666782 -0.24049309 0.96899533, + -0.035843004 -0.24072602 0.96993113, + -0.034285001 -0.26664799 0.963184, + -0.0120819 -0.26678601 0.96368003, + -0.011538397 -0.29387689 0.95577365, + 0.011128401 -0.29387802 0.95577812, + 0.011681699 -0.26640296 0.96379089, + 0.033927791 -0.26626793 0.96330178, + 0.035505507 -0.24000506 0.97012222, + 0.057063375 -0.23976488 0.96915251, + 0.05945627 -0.2157239 0.97464252, + 0.079207227 -0.21542707 0.97330236, + 0.082556173 -0.19126892 0.97805965, + 0.10130596 -0.19093692 0.97636062, + 0.10410599 -0.17526898 0.97900087, + 0.12124903 -0.17492604 0.97708726, + 0.11424895 -0.20622189 0.97181255, + 0.12793604 -0.20587504 0.97017926, + 0.11575696 -0.24987191 0.96133465, + 0.12532096 -0.24957991 0.96021062, + 0.11047903 -0.29370207 0.94949126, + 0.11580005 -0.29352313 0.94891238, + 0.098166354 -0.33738986 0.93623257, + 0.098552361 -0.33737689 0.93619663, + 0.07730671 -0.38217404 0.92085111, + 0.073372774 -0.38228786 0.92112565, + 0.048571613 -0.42694709 0.90297127, + 0.038329303 -0.42713705 0.90337414, + 0.010200301 -0.47059005 0.88229311, + -0.0059602484 -0.47060689 0.88232279, + -0.03772312 -0.51273227 0.85771942, + -0.060056977 -0.5121718 0.85678071, + -0.09432552 -0.55115813 0.82905215, + -0.12396596 -0.5493558 0.82634169, + -0.16062801 -0.58498597 0.79497802, + -0.19735996 -0.58102393 0.78959489, + -0.23482101 -0.61181998 0.75533801, + -0.27852502 -0.60451305 0.74631608, + -0.31568 -0.62995201 0.70958197, + -0.36473212 -0.61816525 0.69630623, + -0.39995581 -0.63778973 0.6582247, + -0.45294613 -0.62039512 0.64027315, + -0.48723093 -0.63531792 0.59914696, + -0.54287094 -0.61097795 0.57619196, + -0.57441789 -0.62087786 0.53343689, + -0.63024098 -0.588898 0.50595999, + -0.65650272 -0.59390068 0.46506578, + -0.70950174 -0.55483383 0.43447286, + -0.73005193 -0.55615395 0.39713594, + -0.77817512 -0.51111406 0.36497402, + -0.79344219 -0.51006114 0.33209509, + -0.83574188 -0.46017894 0.29961798, + -0.84649754 -0.45786774 0.27165985, + -0.88240373 -0.40463284 0.24007492, + -0.88956475 -0.4018999 0.21714295, + -0.91884261 -0.34718987 0.18758292, + -0.92336488 -0.34456998 0.16931899, + -0.94650787 -0.28960496 0.14230898, + -0.94920212 -0.28737703 0.12817901, + -0.96694738 -0.23286308 0.10386404, + -0.9684341 -0.23113602 0.093336307, + -0.98152786 -0.17740099 0.071637489, + -0.98225838 -0.17618605 0.064241819, + -0.99122477 -0.12418897 0.045282289, + -0.99152714 -0.12342501 0.040498804, + -0.99697524 -0.073846914 0.024231106, + -0.99689424 -0.074201316 0.026384905, + -0.99691552 -0.07383246 0.026611688, + -0.99966091 -0.024497597 0.0088297389, + -0.99967986 -0.024236197 0.0072639389, + -0.99969125 0.023804206 -0.0071344618, + -0.99970466 0.023609491 -0.005753628, + -0.99735737 0.070586622 -0.017202005, + -0.99744552 0.070154473 -0.013443894, + -0.99299026 0.11608403 -0.022245506, + -0.99316138 0.11557304 -0.016532606, + -0.98663813 0.16128501 -0.023071703, + -0.98685664 0.16081694 -0.015870994, + -0.97816974 0.20680295 -0.020409495, + -0.97838485 0.20644897 -0.011907298, + -0.96769452 0.25211689 -0.0021014791, + -0.96752191 0.25236797 -0.014555798, + -0.96733624 0.25309506 -0.014266504, + -0.96702862 0.25349191 -0.024441591, + -0.97795498 0.20785201 -0.020041, + -0.97760749 0.20841311 -0.029116113, + -0.98644602 0.162508 -0.022702999, + -0.98612303 0.163184 -0.030535899, + -0.99285525 0.11728903 -0.021947706, + -0.99261963 0.11797596 -0.028071191, + -0.99729276 0.071536787 -0.017021496, + -0.99717414 0.072103307 -0.021093402, + -0.99968189 0.024204995 -0.0070810192, + -0.99966389 0.024458297 -0.0085993391, + -0.99964875 -0.025001995 0.0087905079, + -0.99962324 -0.025343705 0.010544903, + -0.99634278 -0.078890078 0.032824393, + -0.99608362 -0.079972267 0.037706286, + -0.99622035 -0.077630527 0.038968515, + -0.98784763 -0.13890696 0.069727875, + -0.98672646 -0.14139408 0.079867139, + -0.97180438 -0.20530108 0.11596505, + -0.96864253 -0.2098019 0.13309693, + -0.94598067 -0.2737779 0.17368394, + -0.94087178 -0.27859694 0.19272795, + -0.9089433 -0.34287313 0.23719209, + -0.89940578 -0.3488889 0.26333594, + -0.90137178 -0.3394869 0.26884493, + -0.83987588 -0.42551193 0.33696896, + -0.82416487 -0.43136495 0.36698297, + -0.76511401 -0.490428 0.41723001, + -0.74113518 -0.49503812 0.45349312, + -0.67215395 -0.54595792 0.50013894, + -0.63705385 -0.54717588 0.54291886, + -0.56248885 -0.58691788 0.58235186, + -0.51659685 -0.58191991 0.62808985, + -0.44237205 -0.60951406 0.65787506, + -0.38741884 -0.59607273 0.70328075, + -0.31836799 -0.61292499 0.72316301, + -0.25745296 -0.58992195 0.7653169, + -0.19936493 -0.59824574 0.77611572, + -0.13704604 -0.56635916 0.8126843, + -0.090349704 -0.56941503 0.81707013, + -0.029520715 -0.52992523 0.84753042, + 0.0044841277 -0.53015077 0.84789157, + 0.060949776 -0.48533782 0.87219971, + 0.083480589 -0.48454493 0.87077385, + 0.13488603 -0.4357461 0.88990521, + 0.14814906 -0.43491215 0.88820231, + 0.19315204 -0.38448209 0.90269923, + 0.19841991 -0.38406983 0.90173161, + 0.23864709 -0.33129111 0.91284931, + 0.23703609 -0.33142513 0.91322029, + 0.26772204 -0.28461304 0.9205001, + 0.26104704 -0.28515404 0.92224813, + 0.26272887 -0.28224084 0.92266661, + 0.25350901 -0.28296199 0.92502201, + 0.24816889 -0.29321086 0.9232766, + 0.2371821 -0.29404211 0.92589635, + 0.23506588 -0.29854485 0.92499459, + 0.22159907 -0.29951513 0.92800033, + 0.21601599 -0.312758 0.92494297, + 0.201152 -0.31377399 0.92794597, + 0.19452293 -0.33138388 0.92322564, + 0.17873505 -0.33239809 0.92604822, + 0.17284602 -0.35013703 0.92061311, + 0.15656598 -0.35110396 0.92315388, + 0.15112397 -0.37000492 0.91665578, + 0.13400394 -0.37092781 0.91894257, + 0.12918103 -0.3906731 0.91142023, + 0.11058699 -0.39155793 0.91348386, + 0.10631498 -0.41288292 0.90455776, + 0.086840525 -0.41366708 0.90627724, + 0.08334861 -0.43599305 0.8960821, + 0.062506631 -0.4366602 0.89745241, + 0.059855808 -0.46025807 0.88576514, + 0.038039695 -0.46075094 0.88671386, + 0.036401987 -0.48480082 0.87386668, + 0.012530297 -0.48508388 0.87437785, + 0.011956397 -0.51027387 0.85992885, + -0.012146103 -0.51027215 0.85992718, + -0.012710895 -0.48506683 0.8743847, + -0.036260106 -0.48478711 0.87388021, + -0.037883084 -0.46075282 0.8867197, + -0.060360909 -0.46024406 0.88573813, + -0.063008003 -0.43663201 0.89743102, + -0.083522305 -0.43597206 0.89607614, + -0.087005354 -0.41364679 0.90627056, + -0.10679902 -0.4128471 0.90451723, + -0.11105698 -0.39156494 0.9134239, + -0.12933902 -0.3906931 0.91138923, + -0.13414101 -0.37100103 0.9188931, + -0.15156502 -0.37005904 0.91656113, + -0.15696906 -0.35127512 0.92302036, + -0.17321105 -0.35030812 0.92047936, + -0.17905894 -0.33268487 0.92588264, + -0.19446203 -0.33169404 0.92312711, + -0.20097995 -0.3143779 0.92777878, + -0.21579005 -0.3133651 0.92479026, + -0.22029503 -0.30270004 0.92727715, + -0.2332629 -0.30176285 0.92440659, + -0.23811297 -0.29144296 0.92647886, + -0.24954906 -0.29058006 0.92373621, + -0.258075 -0.27412301 0.92641997, + -0.24916688 -0.27478588 0.92865956, + -0.2276791 -0.31106916 0.92271245, + -0.23105302 -0.31081504 0.9219591, + -0.19571392 -0.36239389 0.91124469, + -0.19291696 -0.36259791 0.91175973, + -0.15271394 -0.41292685 0.89786971, + -0.14322701 -0.41352007 0.89915913, + -0.097885348 -0.46198121 0.8814714, + -0.079357922 -0.46274713 0.88293123, + -0.028593607 -0.50862509 0.86051315, + -0.0011948305 -0.50883317 0.86086428, + 0.054354288 -0.55065888 0.83295882, + 0.093693569 -0.54904783 0.83052272, + 0.15180102 -0.58463109 0.79697114, + 0.20233591 -0.57925171 0.78963763, + 0.260573 -0.607099 0.75068802, + 0.32186097 -0.59535992 0.73617393, + 0.37657225 -0.61434734 0.69337642, + 0.44523105 -0.59380805 0.67019504, + 0.49418807 -0.60440105 0.62488204, + 0.56590414 -0.57319611 0.59262013, + 0.60521495 -0.57644194 0.54902595, + 0.67480093 -0.53439796 0.50898194, + 0.70405781 -0.5326699 0.46964389, + 0.76773912 -0.48062906 0.42376006, + 0.78840691 -0.47617894 0.38944593, + 0.84200513 -0.41759306 0.34153104, + 0.8573696 -0.41143879 0.30924985, + 0.89991575 -0.34857792 0.26200193, + 0.90924788 -0.34266096 0.23632997, + 0.94107389 -0.27840698 0.19201396, + 0.94612879 -0.27362293 0.17312096, + 0.96872765 -0.20968193 0.13266596, + 0.97183323 -0.20525205 0.11580903, + 0.98673999 -0.14136 0.079758897, + 0.98810548 -0.13829106 0.067255132, + 0.99600875 -0.080266275 0.039035793, + 0.99628001 -0.0791618 0.034051701, + 0.99960667 -0.025760891 0.011081097, + 0.99962389 -0.025535395 0.010004899, + 0.99963325 0.025213905 -0.0098789632, + 0.99963498 0.025127299 -0.0099275997, + 0.99661362 0.076474868 -0.03021469, + 0.9968245 0.075520866 -0.025249489, + 0.99147749 0.12355606 -0.04130942, + 0.99189711 0.12239301 -0.034061305, + 0.98448187 0.16906199 -0.047048792, + 0.98507488 0.16788098 -0.037993997, + 0.97564542 0.21394287 -0.04841847, + 0.97634077 0.21287495 -0.037987694, + 0.96500647 0.25814813 -0.046066921, + 0.96572626 0.25726107 -0.034489706, + 0.95234478 0.30231893 -0.040530588, + 0.95301586 0.30164096 -0.027809996, + 0.93737721 0.34684509 -0.031977706, + 0.93790811 0.34639904 -0.018333301, + 0.91978425 0.3918761 -0.020740105, + 0.92010748 0.39163578 -0.0048517771, + 0.93215466 0.36193889 -0.0093797464, + 0.93219548 0.36195478 0.00052094669, + 0.91333514 0.40720806 -0.0007456431, + 0.91329068 0.40718785 -0.0099143367, + 0.91329587 0.40717593 -0.0099141095, + 0.89934021 0.43721509 -0.0055010812, + 0.89896286 0.43743995 -0.022629898, + 0.91937846 0.39284876 -0.020323087, + 0.91873491 0.39328393 -0.035409696, + 0.9368071 0.34843704 -0.031371903, + 0.93596137 0.34912613 -0.045686416, + 0.95170552 0.30441687 -0.039835781, + 0.95075285 0.30535597 -0.053167392, + 0.96437699 0.260611 -0.045376498, + 0.96339124 0.26179805 -0.057786215, + 0.97508562 0.21661493 -0.04781308, + 0.97415125 0.21801504 -0.059152015, + 0.98403966 0.17173994 -0.046596684, + 0.98325664 0.17325895 -0.056460381, + 0.99118388 0.12597299 -0.041051295, + 0.99062753 0.12747194 -0.049070876, + 0.99647439 0.078296632 -0.03014061, + 0.99619287 0.079530396 -0.035702296, + 0.99955922 0.027085006 -0.012158803, + 0.99951476 0.027648892 -0.014342196, + 0.99947655 -0.028717887 0.014896693, + 0.99941045 -0.029503815 0.017562607, + 0.99407101 -0.093432099 0.055617101, + 0.99314737 -0.096714839 0.065610126, + 0.97874534 -0.16971307 0.11513104, + 0.97566551 -0.17551191 0.13142394, + 0.94586051 -0.25980788 0.19454491, + 0.93842137 -0.26837009 0.21758407, + 0.89329278 -0.34914091 0.28306994, + 0.87943077 -0.35920691 0.31236494, + 0.81535381 -0.4368819 0.37991092, + 0.78905016 -0.44838911 0.4199371, + 0.70632637 -0.51667523 0.48389024, + 0.66272575 -0.52599984 0.53302783, + 0.56738913 -0.57839012 0.5861181, + 0.5049032 -0.5800662 0.63921523, + 0.4082621 -0.61345714 0.67601216, + 0.33090121 -0.60271734 0.7261104, + 0.245932 -0.61908197 0.74582499, + 0.16020693 -0.5940327 0.78832662, + 0.09403538 -0.59913886 0.79510385, + 0.0092703421 -0.56184113 0.8271932, + -0.036973603 -0.56148106 0.82666314, + -0.11554096 -0.51533282 0.84916568, + -0.14418992 -0.51338577 0.84595758, + -0.2137101 -0.46204621 0.86072141, + -0.22905494 -0.46039888 0.85765183, + -0.28457105 -0.41077009 0.86619121, + -0.32063699 -0.40586299 0.85584301, + -0.31898391 -0.4076069 0.85563183, + -0.31735599 -0.40784201 0.856125, + -0.32115504 -0.40345007 0.85678911, + -0.31569591 -0.40423191 0.85844785, + -0.31680691 -0.40282291 0.85870081, + -0.30945903 -0.40385205 0.86089414, + -0.30121988 -0.41520584 0.85841173, + -0.29321316 -0.41629121 0.86065543, + -0.28585407 -0.42726108 0.85775018, + -0.27757812 -0.42834422 0.85992539, + -0.27063295 -0.43960187 0.8564508, + -0.26116508 -0.44079414 0.8587743, + -0.25481692 -0.45205086 0.85482073, + -0.2442831 -0.45332015 0.85722029, + -0.23800702 -0.46557105 0.85240614, + -0.22642694 -0.46689588 0.85483283, + -0.22029606 -0.48016113 0.84906715, + -0.20739408 -0.48155218 0.85152531, + -0.20155093 -0.49570781 0.84477872, + -0.18691911 -0.49717429 0.84727746, + -0.18162394 -0.5117408 0.83972269, + -0.165482 -0.51322103 0.842152, + -0.16045302 -0.52919507 0.8331911, + -0.14269198 -0.53065592 0.83548987, + -0.13826203 -0.54728013 0.82545018, + -0.11873996 -0.5486778 0.8275587, + -0.11469504 -0.56720316 0.81555229, + -0.093654253 -0.56846172 0.81736159, + -0.090391092 -0.58764094 0.80405688, + -0.067844182 -0.5886969 0.80550182, + -0.065312222 -0.60943127 0.79014432, + -0.041054618 -0.61022031 0.79116738, + -0.03949992 -0.63134032 0.77449936, + -0.013703907 -0.63177431 0.77503133, + -0.013161398 -0.65398395 0.75639391, + 0.0133211 -0.653983 0.756392, + 0.013868395 -0.63202274 0.77482569, + 0.039626021 -0.63158739 0.77429146, + 0.041225296 -0.61001092 0.79131991, + 0.065182574 -0.60923177 0.79030871, + 0.067657478 -0.58900976 0.80528867, + 0.090437993 -0.58794296 0.80383086, + 0.093759023 -0.56849414 0.8173272, + 0.11477395 -0.56723571 0.81551856, + 0.11876702 -0.54899704 0.82734311, + 0.13796298 -0.54762292 0.82527286, + 0.14247398 -0.53072393 0.83548391, + 0.16025095 -0.52926481 0.83318567, + 0.165281 -0.51330698 0.84213901, + 0.181128 -0.51185697 0.83975899, + 0.18643409 -0.49727124 0.84732741, + 0.20133898 -0.49577993 0.84478688, + 0.20707804 -0.48189312 0.8514092, + 0.21994308 -0.48050818 0.84896231, + 0.22608703 -0.46723205 0.85473913, + 0.23766406 -0.46590912 0.85231715, + 0.243981 -0.45359299 0.857162, + 0.25418502 -0.45236605 0.85484213, + 0.2607879 -0.44066584 0.85895473, + 0.27060601 -0.43943101 0.856547, + 0.27748808 -0.42828014 0.85998631, + 0.28579798 -0.42719293 0.85780287, + 0.29312286 -0.4162778 0.86069256, + 0.30115789 -0.41518885 0.85844171, + 0.31029788 -0.40258685 0.86118472, + 0.31811708 -0.40149108 0.85884017, + 0.31948704 -0.39974707 0.8591451, + 0.32535011 -0.39890516 0.85733432, + 0.31484616 -0.41106021 0.85551244, + 0.31581697 -0.41091993 0.85522187, + 0.31452715 -0.41227221 0.85504639, + 0.31218603 -0.41260806 0.8557421, + 0.29357603 -0.43012905 0.85369915, + 0.28556505 -0.43122008 0.85586315, + 0.21430792 -0.48833382 0.84593272, + 0.193757 -0.49047601 0.84964198, + 0.11446795 -0.54149675 0.83287358, + 0.076530069 -0.54348081 0.8359257, + -0.011203403 -0.58661813 0.8097862, + -0.069863692 -0.58522195 0.80785787, + -0.16196495 -0.6166079 0.77042985, + -0.24213903 -0.60626304 0.75750512, + -0.33038101 -0.62261301 0.70936698, + -0.42920393 -0.59580493 0.67882293, + -0.50301594 -0.59713596 0.62482291, + -0.60661513 -0.54926914 0.57473612, + -0.66043305 -0.54013807 0.52161205, + -0.7536878 -0.47277087 0.45655489, + -0.78699988 -0.45966193 0.41151193, + -0.8600657 -0.38011286 0.34029588, + -0.88073373 -0.36586389 0.30075189, + -0.93695325 -0.26995307 0.22191006, + -0.94589603 -0.259758 0.19443899, + -0.9756605 -0.17555191 0.13140795, + -0.97866374 -0.16990095 0.11554597, + -0.99312174 -0.096818179 0.065844089, + -0.99405098 -0.093522303 0.055822801, + -0.99940878 -0.029522393 0.017621696, + -0.9994759 -0.028726296 0.014921199, + -0.99951434 0.02765481 -0.014364606, + -0.9995591 0.027087204 -0.012167102, + -0.99619174 0.079533778 -0.035725094, + -0.99647415 0.07829681 -0.030150004, + -0.99062747 0.12746806 -0.049084522, + -0.99118435 0.12596804 -0.041056514, + -0.98325664 0.17325594 -0.056468982, + -0.98403901 0.171739 -0.046615802, + -0.97415274 0.21800196 -0.059173286, + -0.97508538 0.21660608 -0.047856919, + -0.96339214 0.26178303 -0.057838406, + -0.96438664 0.2605859 -0.045314386, + -0.95077151 0.30531085 -0.053091872, + -0.95173675 0.30435595 -0.039553788, + -0.93599534 0.34907711 -0.045365617, + -0.93682444 0.34839818 -0.031284817, + -0.91875023 0.39325708 -0.035312906, + -0.91937715 0.39283505 -0.020651402, + -0.89897698 0.437392 -0.022993701, + -0.89937788 0.43714795 -0.0045811594, + -0.91459101 0.404291 -0.0084906304, + -0.91457868 0.40431884 -0.0084910775, + -0.91461128 0.40433416 -0.00044759116, + -0.91462409 0.40430507 -0.00044379907, + -0.90569514 0.42391106 -0.0039659906, + -0.89367586 0.44871294 4.2840496e-005, + -0.8936407 0.44869584 -0.0088527976, + -0.89367175 0.44863388 -0.0088518383, + -0.89370668 0.44865185 4.0349987e-005, + -0.89441597 0.447236 4.03466e-005, + -0.87059081 0.49200788 -4.6319688e-005, + -0.87055385 0.49198693 -0.009213239, + -0.8705759 0.49194795 -0.0092126494, + -0.8706128 0.49196887 -4.1197491e-005, + -0.85730779 0.51478887 -0.0039736889, + -0.97325873 0.22968894 -0.0032380894, + -0.99171674 0.12840196 -0.0032956293, + -0.99258125 0.12151003 -0.0042145108, + -0.99258178 0.12150997 -0.004088969, + -0.98727787 0.15899998 -0.0011424399, + -0.98541778 0.17007495 -0.0051361485, + -0.98543054 0.17007692 0.00077111163, + -0.98536724 0.17044304 0.00077111216, + -0.98535448 0.17044108 -0.0051520225, + -0.98541075 0.17011495 -0.0051462385, + -0.98542339 0.17011806 0.0007738173, + -0.97589946 0.21821611 -0.0014623808, + -0.97588313 0.21821202 -0.0059757307, + -0.9758901 0.21818103 -0.005975191, + -0.97589475 0.21818195 -0.0051036286, + -0.96402335 0.26581708 0.00059989822, + -0.96400166 0.26581091 -0.0067318575, + -0.96396637 0.26593909 -0.0067340424, + -0.96398801 0.26594499 0.00060169498, + -0.96404099 0.265753 0.00060169498, + -0.96401924 0.26574707 -0.0067389016, + -0.95436049 0.29864514 -0.0026957213, + -0.95413226 0.29891106 -0.016849104, + -0.93852466 0.34519589 -0.0033612689, + -0.93823874 0.34546492 -0.019024497, + -0.95387465 0.29975089 -0.016507095, + -0.95346534 0.30017513 -0.02826331, + -0.96670812 0.25475502 -0.023986705, + -0.96621209 0.25538403 -0.034830105, + -0.97729075 0.20995896 -0.028634893, + -0.97677773 0.21076795 -0.038497191, + -0.98586053 0.16484092 -0.030108485, + -0.98541713 0.16574602 -0.038488105, + -0.99244189 0.11953498 -0.027757397, + -0.99212623 0.12043203 -0.034377806, + -0.99709046 0.073300138 -0.02092381, + -0.99693239 0.074035533 -0.025388809, + -0.99965191 0.024956897 -0.008558399, + -0.99962765 0.025287291 -0.010254596, + -0.99960738 -0.02596771 0.010530604, + -0.99957275 -0.026414094 0.012513597, + -0.99581134 -0.082628533 0.039145015, + -0.99534667 -0.08446537 0.046373986, + -0.98597288 -0.14630498 0.080325693, + -0.98401535 -0.15047206 0.095246941, + -0.96565187 -0.21955197 0.13897298, + -0.95987564 -0.22709793 0.16451494, + -0.92678022 -0.30417606 0.22035307, + -0.91542757 -0.31362286 0.25225589, + -0.8608371 -0.39653006 0.31894103, + -0.84056729 -0.40704814 0.35743311, + -0.77517718 -0.47470313 0.4168421, + -0.74675906 -0.48292506 0.45731205, + -0.66763705 -0.54057205 0.51190108, + -0.62436992 -0.54508597 0.55950296, + -0.5371151 -0.58861613 0.60418409, + -0.47950524 -0.5852493 0.65387928, + -0.39433074 -0.61287957 0.68474954, + -0.32482296 -0.59844595 0.73236096, + -0.25018811 -0.6126343 0.74972337, + -0.1749721 -0.58629435 0.79097646, + -0.11481693 -0.59154266 0.79805654, + -0.040362619 -0.55497026 0.83089042, + 0.0034242601 -0.55541998 0.831563, + 0.073717199 -0.51079702 0.85653502, + 0.102414 -0.50949699 0.85435599, + 0.16599604 -0.45964211 0.87245315, + 0.18273593 -0.45825985 0.86983073, + 0.23942401 -0.40476701 0.88251901, + 0.24560197 -0.40412393 0.8811149, + 0.29266995 -0.35159391 0.88922775, + 0.29169303 -0.35170403 0.88950515, + 0.30021095 -0.3408359 0.89090079, + 0.29532394 -0.34137991 0.89232475, + 0.29195204 -0.34612504 0.89160609, + 0.28582308 -0.34679413 0.89333028, + 0.28846097 -0.34271598 0.8940559, + 0.27832991 -0.3437869 0.89685172, + 0.27388698 -0.35134298 0.8952899, + 0.26232198 -0.35251898 0.89828587, + 0.25444701 -0.36718401 0.894669, + 0.24210607 -0.36838508 0.89759523, + 0.23539397 -0.38211495 0.89363188, + 0.22286896 -0.38327393 0.89634287, + 0.21618907 -0.39840513 0.89136732, + 0.20294091 -0.39956382 0.89395958, + 0.19669196 -0.41539592 0.88812077, + 0.18170996 -0.41661891 0.89073575, + 0.17604105 -0.43291909 0.88407624, + 0.15994595 -0.43412492 0.88653976, + 0.15448597 -0.45222887 0.87842077, + 0.13756998 -0.45337194 0.88064086, + 0.13280503 -0.47200012 0.87153816, + 0.11436097 -0.47309282 0.8735587, + 0.11020499 -0.49288693 0.86308587, + 0.089825295 -0.49390295 0.86486489, + 0.086473681 -0.51439089 0.85318482, + 0.064809702 -0.51524001 0.85459203, + 0.062272672 -0.53686374 0.8413676, + 0.039427098 -0.53748995 0.84234786, + 0.037805792 -0.5603379 0.8274008, + 0.013023297 -0.56069088 0.82792282, + 0.012469797 -0.58405989 0.81161481, + -0.012643805 -0.58405823 0.81161332, + -0.013190798 -0.56067193 0.82793289, + -0.037688177 -0.56032264 0.82741654, + -0.039296284 -0.53747481 0.84236372, + -0.062469508 -0.53684008 0.84136814, + -0.065000378 -0.51519984 0.85460168, + -0.086663194 -0.51434892 0.8531909, + -0.090053923 -0.49357012 0.86503118, + -0.11014304 -0.49256918 0.86327529, + -0.11422601 -0.47307107 0.87358814, + -0.13301401 -0.47195607 0.87153012, + -0.13784102 -0.45305207 0.88076311, + -0.15476894 -0.45190686 0.8785367, + -0.16022104 -0.43379608 0.88665122, + -0.176318 -0.43258801 0.88418299, + -0.18196996 -0.4163129 0.89082575, + -0.19696908 -0.41508815 0.88820332, + -0.2030471 -0.39966917 0.89388841, + -0.21658887 -0.39848277 0.89123547, + -0.22318397 -0.38353494 0.89615285, + -0.23566906 -0.38237709 0.89344722, + -0.24229909 -0.36881313 0.8973673, + -0.25424513 -0.36764917 0.89453542, + -0.26179799 -0.35359201 0.89801699, + -0.27359498 -0.35239196 0.8949669, + -0.27622402 -0.34793404 0.89590311, + -0.28544185 -0.34695783 0.89338857, + -0.28733405 -0.34403509 0.89391226, + -0.29431194 -0.34327292 0.89193279, + -0.30086195 -0.33400092 0.89326674, + -0.28077802 -0.33613902 0.89898515, + -0.24547599 -0.379639 0.89197302, + -0.24203213 -0.37997818 0.8927694, + -0.19203509 -0.43269122 0.8808524, + -0.17960502 -0.43372807 0.88296211, + -0.12306005 -0.48392418 0.86641431, + -0.10056198 -0.48515788 0.86862481, + -0.037669603 -0.53136808 0.84630311, + -0.0025760198 -0.53174293 0.84690189, + 0.066685095 -0.57259494 0.81712186, + 0.11636097 -0.56997389 0.81338185, + 0.18663998 -0.60157591 0.77670586, + 0.2516619 -0.59262776 0.76515269, + 0.32042897 -0.61405593 0.72129095, + 0.39654186 -0.59509176 0.69901377, + 0.4574382 -0.60553628 0.65121132, + 0.54014713 -0.5730741 0.61630112, + 0.5892719 -0.57426888 0.56830788, + 0.67011899 -0.52758402 0.52210701, + 0.70585275 -0.5226928 0.47808382, + 0.77761817 -0.46394011 0.42434609, + 0.80086988 -0.45648393 0.38759494, + 0.85933429 -0.38984215 0.33101013, + 0.87291682 -0.38248092 0.30286095, + 0.91732514 -0.31213403 0.24715804, + 0.92702711 -0.30395603 0.21961702, + 0.96001053 -0.22692789 0.16396193, + 0.96575922 -0.21939506 0.13847403, + 0.98406363 -0.15036994 0.094908066, + 0.98598778 -0.14626597 0.080214076, + 0.99535137 -0.084445633 0.046311215, + 0.99581325 -0.082618125 0.03911791, + 0.99957287 -0.026411897 0.012505498, + 0.99960089 -0.026055297 0.010921099, + 0.99960089 0.026055695 -0.010921199, + 0.99957955 0.026329787 -0.012139094, + 0.99955201 -0.0271807 0.0125314, + 0.99950475 -0.027768692 0.014807996, + 0.99508548 -0.087373547 0.046592921, + 0.99443614 -0.08982081 0.055036407, + 0.98301864 -0.15646894 0.095874265, + 0.98025626 -0.16199905 0.11337603, + 0.95699221 -0.23768605 0.16634704, + 0.95038736 -0.24575509 0.19070508, + 0.90799928 -0.33100113 0.2568571, + 0.89485979 -0.3411659 0.28780493, + 0.83848518 -0.41651309 0.3513681, + 0.81753731 -0.42650214 0.38694814, + 0.74418634 -0.49471024 0.44883022, + 0.70884961 -0.50367171 0.49380872, + 0.62137407 -0.55947906 0.54852307, + 0.56961995 -0.56297594 0.59882492, + 0.47722393 -0.60193193 0.64026195, + 0.40964484 -0.59540278 0.69114876, + 0.32371491 -0.61753488 0.71683985, + 0.24629997 -0.59835297 0.76243687, + 0.17452998 -0.60789591 0.77459788, + 0.093657345 -0.57612562 0.81197751, + 0.039496489 -0.57821786 0.81492585, + -0.037533514 -0.53685015 0.84284228, + -0.073967114 -0.53575712 0.8411262, + -0.14447297 -0.48752388 0.86107379, + -0.16646707 -0.48581824 0.85806143, + -0.22890793 -0.43350786 0.87159169, + -0.23952392 -0.43236884 0.86930168, + -0.28744107 -0.38456514 0.8772043, + -0.31739989 -0.38074785 0.86849773, + -0.31362599 -0.38514 0.86793202, + -0.30969515 -0.38566318 0.86911041, + -0.31124389 -0.38369384 0.86942869, + -0.30477706 -0.3845391 0.87134415, + -0.30453807 -0.38487309 0.87128019, + -0.29559886 -0.38600883 0.87385261, + -0.28756806 -0.39819008 0.87106216, + -0.27815893 -0.39934391 0.87358582, + -0.27115503 -0.41088706 0.8704291, + -0.26086593 -0.41209891 0.87299681, + -0.25410706 -0.42428109 0.86914617, + -0.24318206 -0.42551208 0.87166619, + -0.23683488 -0.4380978 0.86716759, + -0.22493806 -0.43937111 0.8696872, + -0.21873197 -0.45301193 0.86425489, + -0.20561288 -0.45433474 0.86677748, + -0.19962405 -0.46907413 0.86030215, + -0.18490095 -0.47045487 0.86283481, + -0.17927401 -0.48617607 0.85527414, + -0.16349608 -0.48753223 0.85766041, + -0.15838593 -0.50400078 0.8490566, + -0.14083703 -0.50535613 0.85134017, + -0.13620299 -0.52298993 0.8413859, + -0.11712001 -0.52427703 0.84345514, + -0.11316304 -0.5426482 0.83230227, + -0.092415169 -0.54381883 0.8340987, + -0.089049004 -0.56388104 0.82104111, + -0.066989996 -0.56485891 0.82246387, + -0.064490117 -0.58560914 0.80802417, + -0.040569488 -0.58634788 0.80904281, + -0.038966477 -0.60842967 0.79265052, + -0.013696096 -0.60883486 0.7931788, + -0.013151298 -0.63132495 0.7754069, + 0.013010696 -0.63132674 0.77540773, + 0.0135658 -0.608612 0.79335201, + 0.039117794 -0.60820192 0.79281789, + 0.04069509 -0.58663291 0.80882984, + 0.064284399 -0.58590502 0.80782598, + 0.066852704 -0.56463897 0.82262599, + 0.088907033 -0.5636642 0.82120532, + 0.092184156 -0.54417074 0.83389461, + 0.11320802 -0.54298407 0.83207715, + 0.11723602 -0.52433807 0.84340113, + 0.13600101 -0.52307302 0.84136701, + 0.14064701 -0.50542104 0.85133314, + 0.15817605 -0.50406909 0.84905517, + 0.16321295 -0.48786187 0.85752684, + 0.17895605 -0.48651111 0.85515016, + 0.18459004 -0.47079611 0.86271518, + 0.19931093 -0.46941683 0.86018771, + 0.20530604 -0.45468211 0.86666816, + 0.218403 -0.453363 0.86415398, + 0.22464511 -0.43965921 0.8696174, + 0.23654209 -0.43838716 0.86710131, + 0.24294794 -0.4256959 0.87164181, + 0.25386006 -0.4244681 0.86912715, + 0.26075202 -0.41205606 0.87305111, + 0.27105686 -0.41084278 0.87048048, + 0.27819988 -0.39907482 0.87369561, + 0.28737295 -0.39795092 0.87123585, + 0.29622707 -0.38451108 0.87430018, + 0.30529213 -0.38336015 0.8716833, + 0.30786201 -0.379767 0.872352, + 0.31500703 -0.37883207 0.8702051, + 0.30758184 -0.38828683 0.86869258, + 0.31095713 -0.38783914 0.86769032, + 0.31144512 -0.38727516 0.86776727, + 0.31164089 -0.38724884 0.86770868, + 0.29676893 -0.4027679 0.86585581, + 0.29261813 -0.40330815 0.86701632, + 0.23067406 -0.45905513 0.85793817, + 0.21557602 -0.46068606 0.8609851, + 0.14443493 -0.51330376 0.84596556, + 0.11623393 -0.51522672 0.84913552, + 0.036818016 -0.56187516 0.82640231, + -0.0094900085 -0.56223089 0.82692581, + -0.094100341 -0.59943432 0.79487336, + -0.16095498 -0.59425592 0.78800589, + -0.24566916 -0.61899436 0.74598444, + -0.33062488 -0.60265279 0.72628975, + -0.40839076 -0.61345363 0.67593759, + -0.5045628 -0.5802328 0.63933277, + -0.56740594 -0.57853794 0.58595592, + -0.6627062 -0.5261541 0.53290009, + -0.70628136 -0.51681924 0.48380223, + -0.78925413 -0.44829407 0.41965505, + -0.82017303 -0.43454099 0.372143, + -0.89214826 -0.34311408 0.29384407, + -0.90802479 -0.33097991 0.25679395, + -0.95044178 -0.24563994 0.19058196, + -0.95686424 -0.23780806 0.16690804, + -0.98020053 -0.16207193 0.11375195, + -0.98297375 -0.15653996 0.096217677, + -0.99442297 -0.089850202 0.055226602, + -0.99508286 -0.087369293 0.046654996, + -0.99950415 -0.027774904 0.014831702, + -0.99955177 -0.027182894 0.012539697, + -0.99957943 0.026331484 -0.012146993, + -0.99961209 0.025901604 -0.010236901, + -0.9966135 0.076472461 -0.030223684, + -0.99682462 0.075517572 -0.025252391, + -0.99147791 0.12354998 -0.041314196, + -0.99189699 0.12239 -0.0340751, + -0.98448199 0.169056 -0.047067799, + -0.98507375 0.16787896 -0.038032293, + -0.97564763 0.21392293 -0.048463583, + -0.976349 0.212846 -0.037937999, + -0.96501786 0.25811598 -0.046007097, + -0.96574765 0.25721392 -0.034241788, + -0.95236778 0.30228493 -0.04024189, + -0.95302612 0.30161604 -0.027730104, + -0.93738991 0.34681898 -0.031885996, + -0.9379065 0.34638682 -0.018640291, + -0.91980022 0.3918201 -0.021085206, + -0.92014438 0.39155915 -0.0039868616, + -0.93332422 0.35894409 -0.0080649517, + -0.93335485 0.35895497 0.00035463896, + -0.93337214 0.35891002 0.00035463902, + -0.93334186 0.35889798 -0.0080682291, + -0.93331534 0.35896713 -0.0080693429, + -0.93334597 0.358978 0.000356687, + -0.94978851 0.31283385 -0.0060510873, + -0.94977963 0.3128309 -0.007452657, + -0.94980264 0.31276089 -0.0074515073, + -0.94982851 0.31276986 -0.00091967254, + -0.94448346 0.32854414 -0.0031339014, + -0.4508118 0.8926186 0.0008744126, + -0.45077094 0.89253789 -0.013473498, + -0.27682602 0.9609201 0, + -0.16750504 0.98587126 0, + -0.57866585 0.81556481 0, + -0.48371601 0.87522501 0, + -0.74563295 0.66635692 0, + -0.66635692 0.74563295 0, + -0.38269693 0.9238739 0, + -0.056072284 0.99842674 0, + 0.056072284 0.99842674 0, + -0.48371601 -0.87522501 0, + -0.57866585 -0.81556481 0, + 0.81556481 -0.57866585 0, + 0.87522501 -0.48371601 0, + 0.74563295 -0.66635692 0, + -0.38269693 -0.9238739 0, + 0.38269693 -0.9238739 0, + 0.48371601 -0.87522501 0, + 0 0 -1, + 0.57866585 -0.81556481 0, + 0.66635692 -0.74563295 0, + 0.27682602 -0.9609201 0, + -0.27682602 -0.9609201 0, + -0.16750504 -0.98587126 0, + 0.16750504 -0.98587126 0, + -0.056072284 -0.99842674 0, + 0.056072284 -0.99842674 0, + 0.16750504 0.98587126 0, + 0.27682602 0.9609201 0, + 0.38269693 0.9238739 0, + 0.48371601 0.87522501 0, + 0.57866585 0.81556481 0, + 0.66635692 0.74563295 0, + 0.74563295 0.66635692 0, + 0.81556481 0.57866585 0, + 0.9609201 0.27682602 0, + 0.98587126 0.16750504 0, + 0.9238739 0.38269693 0, + 0.99842674 -0.056072284 0, + 0.99842674 0.056072284 0, + 0.87522501 0.48371601 0, + -0.81556481 0.57866585 0, + -0.66635692 -0.74563295 0, + -0.74563295 -0.66635692 0, + -0.81556481 -0.57866585 0, + 0.9238739 -0.38269693 0, + 0.9609201 -0.27682602 0, + -0.87522501 -0.48371601 0, + -0.9238739 -0.38269693 0, + -0.9609201 -0.27682602 0, + 0.98587126 -0.16750504 0, + -0.98587126 -0.16750504 0, + -0.99842674 -0.056072284 0, + -0.9609201 0.27682602 0, + -0.9238739 0.38269693 0, + -0.87522501 0.48371601 0, + -0.98587126 0.16750504 0, + -0.99842674 0.056072284 0, + -0.075101294 0.99717587 6.0073791e-005, + -0.075093836 0.99707645 -0.014126707, + -0.17240191 0.9849205 -0.014466394, + 0.53739715 -0.84327817 0.0092843818, + 0 -1 0 ] + + } + coordIndex [ 0, 1, 2, -1, 2, 3, 0, -1, + 3, 2, 4, -1, 4, 5, 3, -1, + 5, 4, 6, -1, 6, 7, 5, -1, + 7, 6, 8, -1, 8, 9, 7, -1, + 9, 8, 10, -1, 10, 11, 9, -1, + 11, 10, 12, -1, 12, 13, 11, -1, + 13, 12, 14, -1, 14, 15, 13, -1, + 15, 14, 16, -1, 16, 17, 15, -1, + 17, 16, 18, -1, 18, 19, 17, -1, + 19, 18, 20, -1, 20, 21, 19, -1, + 21, 20, 22, -1, 22, 23, 21, -1, + 23, 22, 24, -1, 24, 25, 23, -1, + 25, 24, 26, -1, 26, 27, 25, -1, + 27, 26, 28, -1, 28, 29, 27, -1, + 29, 28, 30, -1, 30, 31, 29, -1, + 31, 30, 32, -1, 32, 33, 31, -1, + 33, 32, 34, -1, 34, 35, 33, -1, + 35, 34, 36, -1, 36, 37, 35, -1, + 37, 36, 38, -1, 38, 39, 37, -1, + 39, 38, 40, -1, 40, 41, 39, -1, + 41, 40, 42, -1, 42, 43, 41, -1, + 43, 42, 44, -1, 44, 45, 43, -1, + 45, 44, 46, -1, 46, 47, 45, -1, + 47, 46, 48, -1, 48, 49, 47, -1, + 49, 48, 50, -1, 50, 51, 49, -1, + 51, 50, 52, -1, 52, 53, 51, -1, + 53, 52, 54, -1, 54, 55, 53, -1, + 55, 54, 56, -1, 55, 56, 57, -1, + 57, 58, 55, -1, 58, 57, 59, -1, + 59, 60, 58, -1, 60, 59, 61, -1, + 61, 62, 60, -1, 62, 61, 63, -1, + 63, 64, 62, -1, 64, 63, 65, -1, + 65, 66, 64, -1, 66, 65, 67, -1, + 67, 68, 66, -1, 68, 67, 69, -1, + 69, 70, 68, -1, 70, 69, 71, -1, + 71, 72, 70, -1, 72, 71, 73, -1, + 73, 74, 72, -1, 74, 73, 75, -1, + 75, 76, 74, -1, 76, 75, 77, -1, + 77, 78, 76, -1, 78, 77, 79, -1, + 79, 80, 78, -1, 80, 79, 81, -1, + 81, 82, 80, -1, 82, 81, 83, -1, + 83, 84, 82, -1, 84, 83, 85, -1, + 85, 86, 84, -1, 86, 85, 87, -1, + 87, 88, 86, -1, 88, 87, 89, -1, + 89, 90, 88, -1, 90, 89, 91, -1, + 91, 92, 90, -1, 92, 91, 93, -1, + 93, 94, 92, -1, 94, 93, 95, -1, + 95, 96, 94, -1, 96, 95, 97, -1, + 97, 98, 96, -1, 98, 97, 99, -1, + 99, 100, 98, -1, 100, 99, 101, -1, + 101, 102, 100, -1, 102, 101, 103, -1, + 103, 104, 102, -1, 104, 103, 105, -1, + 105, 106, 104, -1, 106, 105, 107, -1, + 107, 108, 106, -1, 108, 107, 109, -1, + 110, 111, 112, -1, 111, 110, 113, -1, + 113, 114, 111, -1, 114, 113, 115, -1, + 115, 116, 114, -1, 116, 115, 117, -1, + 117, 118, 116, -1, 118, 117, 119, -1, + 119, 120, 118, -1, 120, 119, 121, -1, + 121, 122, 120, -1, 122, 121, 123, -1, + 123, 124, 122, -1, 124, 123, 125, -1, + 125, 126, 124, -1, 126, 125, 127, -1, + 127, 128, 126, -1, 128, 127, 129, -1, + 129, 130, 128, -1, 130, 129, 131, -1, + 131, 132, 130, -1, 132, 131, 133, -1, + 133, 134, 132, -1, 134, 133, 135, -1, + 135, 136, 134, -1, 136, 135, 137, -1, + 137, 138, 136, -1, 138, 137, 139, -1, + 139, 140, 138, -1, 140, 139, 141, -1, + 141, 142, 140, -1, 142, 141, 143, -1, + 143, 144, 142, -1, 144, 143, 145, -1, + 145, 146, 144, -1, 146, 145, 147, -1, + 147, 148, 146, -1, 148, 147, 149, -1, + 149, 150, 148, -1, 150, 149, 151, -1, + 151, 152, 150, -1, 152, 151, 153, -1, + 153, 154, 152, -1, 154, 153, 155, -1, + 155, 156, 154, -1, 156, 155, 157, -1, + 157, 158, 156, -1, 158, 157, 159, -1, + 159, 160, 158, -1, 160, 159, 161, -1, + 161, 162, 160, -1, 162, 161, 163, -1, + 163, 164, 162, -1, 163, 165, 164, -1, + 165, 163, 166, -1, 166, 167, 165, -1, + 167, 166, 168, -1, 168, 169, 167, -1, + 169, 168, 170, -1, 170, 171, 169, -1, + 171, 170, 172, -1, 172, 173, 171, -1, + 173, 172, 174, -1, 174, 175, 173, -1, + 175, 174, 176, -1, 176, 177, 175, -1, + 177, 176, 178, -1, 178, 179, 177, -1, + 179, 178, 180, -1, 180, 181, 179, -1, + 181, 180, 182, -1, 182, 183, 181, -1, + 183, 182, 184, -1, 184, 185, 183, -1, + 185, 184, 186, -1, 186, 187, 185, -1, + 187, 186, 188, -1, 188, 189, 187, -1, + 189, 188, 190, -1, 190, 191, 189, -1, + 191, 190, 192, -1, 192, 193, 191, -1, + 193, 192, 194, -1, 194, 195, 193, -1, + 195, 194, 196, -1, 196, 197, 195, -1, + 197, 196, 198, -1, 198, 199, 197, -1, + 199, 198, 200, -1, 200, 201, 199, -1, + 201, 200, 202, -1, 202, 203, 201, -1, + 203, 202, 204, -1, 204, 205, 203, -1, + 205, 204, 206, -1, 206, 207, 205, -1, + 207, 206, 208, -1, 208, 209, 207, -1, + 209, 208, 210, -1, 210, 211, 209, -1, + 211, 210, 212, -1, 212, 213, 211, -1, + 213, 212, 214, -1, 214, 215, 213, -1, + 215, 214, 216, -1, 216, 217, 215, -1, + 217, 216, 218, -1, 218, 219, 217, -1, + 220, 221, 219, -1, 219, 222, 220, -1, + 222, 219, 218, -1, 218, 223, 222, -1, + 223, 218, 216, -1, 216, 224, 223, -1, + 224, 216, 214, -1, 214, 225, 224, -1, + 225, 214, 212, -1, 212, 226, 225, -1, + 226, 212, 210, -1, 210, 227, 226, -1, + 227, 210, 208, -1, 208, 228, 227, -1, + 228, 208, 206, -1, 206, 229, 228, -1, + 229, 206, 204, -1, 204, 230, 229, -1, + 230, 204, 202, -1, 202, 231, 230, -1, + 231, 202, 200, -1, 200, 232, 231, -1, + 232, 200, 198, -1, 198, 233, 232, -1, + 233, 198, 196, -1, 196, 234, 233, -1, + 234, 196, 194, -1, 194, 235, 234, -1, + 235, 194, 192, -1, 192, 236, 235, -1, + 236, 192, 190, -1, 190, 237, 236, -1, + 237, 190, 188, -1, 188, 238, 237, -1, + 238, 188, 186, -1, 186, 239, 238, -1, + 239, 186, 184, -1, 184, 240, 239, -1, + 240, 184, 182, -1, 182, 241, 240, -1, + 241, 182, 180, -1, 180, 242, 241, -1, + 242, 180, 178, -1, 178, 243, 242, -1, + 243, 178, 176, -1, 176, 244, 243, -1, + 244, 176, 174, -1, 174, 245, 244, -1, + 245, 174, 172, -1, 172, 246, 245, -1, + 246, 172, 170, -1, 170, 247, 246, -1, + 247, 170, 168, -1, 168, 248, 247, -1, + 248, 168, 166, -1, 166, 249, 248, -1, + 249, 166, 163, -1, 249, 163, 161, -1, + 161, 250, 249, -1, 250, 161, 159, -1, + 159, 251, 250, -1, 251, 159, 157, -1, + 157, 252, 251, -1, 252, 157, 155, -1, + 155, 253, 252, -1, 253, 155, 153, -1, + 153, 254, 253, -1, 254, 153, 151, -1, + 151, 255, 254, -1, 255, 151, 149, -1, + 149, 256, 255, -1, 256, 149, 147, -1, + 147, 257, 256, -1, 257, 147, 145, -1, + 145, 258, 257, -1, 258, 145, 143, -1, + 143, 259, 258, -1, 259, 143, 141, -1, + 141, 260, 259, -1, 260, 141, 139, -1, + 139, 261, 260, -1, 261, 139, 137, -1, + 137, 262, 261, -1, 262, 137, 135, -1, + 135, 263, 262, -1, 263, 135, 133, -1, + 133, 264, 263, -1, 264, 133, 131, -1, + 131, 265, 264, -1, 265, 131, 129, -1, + 129, 266, 265, -1, 266, 129, 127, -1, + 127, 267, 266, -1, 267, 127, 125, -1, + 125, 268, 267, -1, 268, 125, 123, -1, + 123, 269, 268, -1, 269, 123, 121, -1, + 121, 270, 269, -1, 270, 121, 119, -1, + 119, 271, 270, -1, 271, 119, 117, -1, + 117, 272, 271, -1, 272, 117, 115, -1, + 115, 273, 272, -1, 273, 115, 113, -1, + 113, 274, 273, -1, 274, 113, 110, -1, + 110, 275, 274, -1, 275, 110, 112, -1, + 112, 276, 275, -1, 276, 112, 277, -1, + 277, 278, 276, -1, 278, 277, 279, -1, + 280, 281, 282, -1, 283, 284, 285, -1, + 283, 286, 284, -1, 283, 287, 286, -1, + 283, 285, 287, -1, 288, 289, 290, -1, + 288, 291, 289, -1, 288, 292, 291, -1, + 288, 290, 292, -1, 293, 294, 295, -1, + 296, 297, 298, -1, 297, 296, 299, -1, + 299, 300, 297, -1, 299, 301, 300, -1, + 302, 303, 304, -1, 303, 302, 305, -1, + 305, 306, 303, -1, 307, 308, 309, -1, + 307, 310, 308, -1, 310, 307, 311, -1, + 312, 310, 311, -1, 312, 313, 310, -1, + 314, 303, 313, -1, 303, 310, 313, -1, + 310, 303, 306, -1, 306, 308, 310, -1, + 308, 306, 315, -1, 315, 316, 308, -1, + 316, 315, 317, -1, 317, 318, 316, -1, + 318, 317, 319, -1, 319, 320, 318, -1, + 320, 319, 321, -1, 321, 322, 320, -1, + 322, 321, 323, -1, 323, 324, 322, -1, + 324, 323, 325, -1, 325, 326, 324, -1, + 326, 325, 327, -1, 327, 328, 326, -1, + 328, 327, 329, -1, 329, 330, 328, -1, + 330, 329, 331, -1, 331, 332, 330, -1, + 332, 331, 333, -1, 333, 334, 332, -1, + 334, 333, 335, -1, 335, 336, 334, -1, + 336, 335, 337, -1, 337, 338, 336, -1, + 338, 337, 339, -1, 339, 340, 338, -1, + 340, 339, 341, -1, 341, 342, 340, -1, + 342, 341, 343, -1, 343, 344, 342, -1, + 344, 343, 345, -1, 345, 346, 344, -1, + 346, 345, 347, -1, 347, 348, 346, -1, + 348, 347, 349, -1, 349, 350, 348, -1, + 350, 349, 351, -1, 351, 352, 350, -1, + 352, 351, 353, -1, 353, 354, 352, -1, + 354, 353, 355, -1, 355, 356, 354, -1, + 356, 355, 357, -1, 357, 358, 356, -1, + 358, 357, 359, -1, 359, 360, 358, -1, + 360, 359, 361, -1, 360, 361, 362, -1, + 362, 363, 360, -1, 363, 362, 364, -1, + 364, 365, 363, -1, 365, 364, 366, -1, + 366, 367, 365, -1, 367, 366, 368, -1, + 368, 369, 367, -1, 369, 368, 370, -1, + 370, 371, 369, -1, 371, 370, 372, -1, + 372, 373, 371, -1, 373, 372, 374, -1, + 374, 375, 373, -1, 375, 374, 376, -1, + 376, 377, 375, -1, 377, 376, 378, -1, + 378, 379, 377, -1, 379, 378, 380, -1, + 380, 381, 379, -1, 381, 380, 382, -1, + 382, 383, 381, -1, 383, 382, 384, -1, + 384, 385, 383, -1, 385, 384, 386, -1, + 386, 387, 385, -1, 387, 386, 388, -1, + 388, 389, 387, -1, 389, 388, 390, -1, + 390, 391, 389, -1, 391, 390, 392, -1, + 392, 393, 391, -1, 393, 392, 394, -1, + 394, 395, 393, -1, 395, 394, 396, -1, + 396, 397, 395, -1, 397, 396, 398, -1, + 398, 399, 397, -1, 399, 398, 400, -1, + 400, 401, 399, -1, 401, 400, 402, -1, + 402, 403, 401, -1, 403, 402, 404, -1, + 404, 301, 403, -1, 404, 300, 301, -1, + 404, 405, 300, -1, 405, 404, 402, -1, + 402, 406, 405, -1, 406, 402, 400, -1, + 400, 407, 406, -1, 407, 400, 398, -1, + 398, 408, 407, -1, 408, 398, 396, -1, + 396, 409, 408, -1, 409, 396, 394, -1, + 394, 410, 409, -1, 410, 394, 392, -1, + 392, 411, 410, -1, 411, 392, 390, -1, + 390, 412, 411, -1, 412, 390, 388, -1, + 388, 413, 412, -1, 413, 388, 386, -1, + 386, 414, 413, -1, 414, 386, 384, -1, + 384, 415, 414, -1, 415, 384, 382, -1, + 382, 416, 415, -1, 416, 382, 380, -1, + 380, 417, 416, -1, 417, 380, 378, -1, + 378, 418, 417, -1, 418, 378, 376, -1, + 376, 419, 418, -1, 419, 376, 374, -1, + 374, 420, 419, -1, 420, 374, 372, -1, + 372, 421, 420, -1, 421, 372, 370, -1, + 370, 422, 421, -1, 422, 370, 368, -1, + 368, 423, 422, -1, 423, 368, 366, -1, + 366, 424, 423, -1, 424, 366, 364, -1, + 364, 425, 424, -1, 425, 364, 362, -1, + 362, 426, 425, -1, 426, 362, 361, -1, + 361, 427, 426, -1, 361, 428, 427, -1, + 428, 361, 359, -1, 359, 429, 428, -1, + 429, 359, 357, -1, 357, 430, 429, -1, + 430, 357, 355, -1, 355, 431, 430, -1, + 431, 355, 353, -1, 353, 432, 431, -1, + 432, 353, 351, -1, 351, 433, 432, -1, + 433, 351, 349, -1, 349, 434, 433, -1, + 434, 349, 347, -1, 347, 435, 434, -1, + 435, 347, 345, -1, 345, 436, 435, -1, + 436, 345, 343, -1, 343, 437, 436, -1, + 437, 343, 341, -1, 341, 438, 437, -1, + 438, 341, 339, -1, 339, 439, 438, -1, + 439, 339, 337, -1, 337, 440, 439, -1, + 440, 337, 335, -1, 335, 441, 440, -1, + 441, 335, 333, -1, 333, 442, 441, -1, + 442, 333, 331, -1, 331, 443, 442, -1, + 443, 331, 329, -1, 329, 444, 443, -1, + 444, 329, 327, -1, 327, 445, 444, -1, + 445, 327, 325, -1, 325, 446, 445, -1, + 446, 325, 323, -1, 323, 447, 446, -1, + 447, 323, 321, -1, 321, 448, 447, -1, + 448, 321, 319, -1, 319, 449, 448, -1, + 449, 319, 317, -1, 317, 450, 449, -1, + 450, 317, 315, -1, 315, 451, 450, -1, + 451, 315, 306, -1, 306, 305, 451, -1, + 305, 452, 451, -1, 305, 453, 452, -1, + 453, 305, 302, -1, 302, 454, 453, -1, + 455, 454, 456, -1, 454, 302, 456, -1, + 457, 456, 302, -1, 457, 302, 304, -1, + 304, 458, 457, -1, 459, 458, 304, -1, + 459, 304, 303, -1, 459, 303, 314, -1, + 314, 458, 459, -1, 314, 313, 458, -1, + 313, 312, 458, -1, 312, 311, 458, -1, + 460, 458, 311, -1, 461, 460, 311, -1, + 461, 311, 307, -1, 461, 307, 462, -1, + 462, 460, 461, -1, 462, 294, 460, -1, + 462, 307, 294, -1, 307, 295, 294, -1, + 295, 307, 309, -1, 309, 463, 295, -1, + 463, 309, 464, -1, 464, 465, 463, -1, + 465, 464, 466, -1, 466, 467, 465, -1, + 467, 466, 468, -1, 468, 469, 467, -1, + 469, 468, 470, -1, 470, 471, 469, -1, + 471, 470, 472, -1, 472, 473, 471, -1, + 473, 472, 474, -1, 474, 475, 473, -1, + 475, 474, 476, -1, 476, 477, 475, -1, + 477, 476, 478, -1, 478, 479, 477, -1, + 479, 478, 480, -1, 480, 481, 479, -1, + 481, 480, 482, -1, 482, 483, 481, -1, + 483, 482, 484, -1, 484, 485, 483, -1, + 485, 484, 486, -1, 486, 487, 485, -1, + 487, 486, 488, -1, 488, 489, 487, -1, + 489, 488, 490, -1, 490, 491, 489, -1, + 491, 490, 492, -1, 492, 493, 491, -1, + 493, 492, 494, -1, 494, 495, 493, -1, + 495, 494, 496, -1, 496, 497, 495, -1, + 497, 496, 498, -1, 498, 499, 497, -1, + 499, 498, 500, -1, 500, 501, 499, -1, + 501, 500, 502, -1, 502, 503, 501, -1, + 503, 502, 504, -1, 504, 505, 503, -1, + 505, 504, 506, -1, 505, 506, 507, -1, + 507, 508, 505, -1, 508, 507, 509, -1, + 509, 510, 508, -1, 510, 509, 511, -1, + 511, 512, 510, -1, 512, 511, 513, -1, + 513, 514, 512, -1, 514, 513, 515, -1, + 515, 516, 514, -1, 516, 515, 517, -1, + 517, 518, 516, -1, 518, 517, 519, -1, + 519, 520, 518, -1, 520, 519, 521, -1, + 521, 522, 520, -1, 522, 521, 523, -1, + 523, 524, 522, -1, 524, 523, 525, -1, + 525, 526, 524, -1, 526, 525, 527, -1, + 527, 528, 526, -1, 528, 527, 529, -1, + 529, 530, 528, -1, 530, 529, 531, -1, + 531, 532, 530, -1, 532, 531, 533, -1, + 533, 534, 532, -1, 534, 533, 535, -1, + 535, 536, 534, -1, 536, 535, 537, -1, + 537, 538, 536, -1, 538, 537, 539, -1, + 539, 540, 538, -1, 540, 539, 541, -1, + 541, 542, 540, -1, 542, 541, 543, -1, + 543, 544, 542, -1, 544, 543, 545, -1, + 545, 546, 544, -1, 546, 545, 547, -1, + 547, 548, 546, -1, 547, 549, 548, -1, + 547, 550, 549, -1, 550, 547, 545, -1, + 545, 551, 550, -1, 551, 545, 543, -1, + 543, 552, 551, -1, 552, 543, 541, -1, + 541, 553, 552, -1, 553, 541, 539, -1, + 539, 554, 553, -1, 554, 539, 537, -1, + 537, 555, 554, -1, 555, 537, 535, -1, + 535, 556, 555, -1, 556, 535, 533, -1, + 533, 557, 556, -1, 557, 533, 531, -1, + 531, 558, 557, -1, 558, 531, 529, -1, + 529, 559, 558, -1, 559, 529, 527, -1, + 527, 560, 559, -1, 560, 527, 525, -1, + 525, 561, 560, -1, 561, 525, 523, -1, + 523, 562, 561, -1, 562, 523, 521, -1, + 521, 563, 562, -1, 563, 521, 519, -1, + 519, 564, 563, -1, 564, 519, 517, -1, + 517, 565, 564, -1, 565, 517, 515, -1, + 515, 566, 565, -1, 566, 515, 513, -1, + 513, 567, 566, -1, 567, 513, 511, -1, + 511, 568, 567, -1, 568, 511, 509, -1, + 509, 569, 568, -1, 569, 509, 507, -1, + 507, 570, 569, -1, 570, 507, 506, -1, + 506, 571, 570, -1, 506, 572, 571, -1, + 572, 506, 504, -1, 504, 573, 572, -1, + 573, 504, 502, -1, 502, 574, 573, -1, + 574, 502, 500, -1, 500, 575, 574, -1, + 575, 500, 498, -1, 498, 576, 575, -1, + 576, 498, 496, -1, 496, 577, 576, -1, + 577, 496, 494, -1, 494, 578, 577, -1, + 578, 494, 492, -1, 492, 579, 578, -1, + 579, 492, 490, -1, 490, 580, 579, -1, + 580, 490, 488, -1, 488, 581, 580, -1, + 581, 488, 486, -1, 486, 582, 581, -1, + 582, 486, 484, -1, 484, 583, 582, -1, + 583, 484, 482, -1, 482, 584, 583, -1, + 584, 482, 480, -1, 480, 585, 584, -1, + 585, 480, 478, -1, 478, 586, 585, -1, + 586, 478, 476, -1, 476, 587, 586, -1, + 587, 476, 474, -1, 474, 588, 587, -1, + 588, 474, 472, -1, 472, 589, 588, -1, + 589, 472, 470, -1, 470, 590, 589, -1, + 590, 470, 468, -1, 468, 591, 590, -1, + 591, 468, 466, -1, 466, 592, 591, -1, + 592, 466, 464, -1, 464, 593, 592, -1, + 593, 464, 309, -1, 593, 309, 308, -1, + 593, 308, 316, -1, 316, 592, 593, -1, + 592, 316, 318, -1, 318, 591, 592, -1, + 591, 318, 320, -1, 320, 590, 591, -1, + 590, 320, 322, -1, 322, 589, 590, -1, + 589, 322, 324, -1, 324, 588, 589, -1, + 588, 324, 326, -1, 326, 587, 588, -1, + 587, 326, 328, -1, 328, 586, 587, -1, + 586, 328, 330, -1, 330, 585, 586, -1, + 585, 330, 332, -1, 332, 584, 585, -1, + 584, 332, 334, -1, 334, 583, 584, -1, + 583, 334, 336, -1, 336, 582, 583, -1, + 582, 336, 338, -1, 338, 581, 582, -1, + 581, 338, 340, -1, 340, 580, 581, -1, + 580, 340, 342, -1, 342, 579, 580, -1, + 579, 342, 344, -1, 344, 578, 579, -1, + 578, 344, 346, -1, 346, 577, 578, -1, + 577, 346, 348, -1, 348, 576, 577, -1, + 576, 348, 350, -1, 350, 575, 576, -1, + 575, 350, 352, -1, 352, 574, 575, -1, + 574, 352, 354, -1, 354, 573, 574, -1, + 573, 354, 356, -1, 356, 572, 573, -1, + 572, 356, 358, -1, 358, 571, 572, -1, + 571, 358, 360, -1, 571, 360, 363, -1, + 363, 570, 571, -1, 570, 363, 365, -1, + 365, 569, 570, -1, 569, 365, 367, -1, + 367, 568, 569, -1, 568, 367, 369, -1, + 369, 567, 568, -1, 567, 369, 371, -1, + 371, 566, 567, -1, 566, 371, 373, -1, + 373, 565, 566, -1, 565, 373, 375, -1, + 375, 564, 565, -1, 564, 375, 377, -1, + 377, 563, 564, -1, 563, 377, 379, -1, + 379, 562, 563, -1, 562, 379, 381, -1, + 381, 561, 562, -1, 561, 381, 383, -1, + 383, 560, 561, -1, 560, 383, 385, -1, + 385, 559, 560, -1, 559, 385, 387, -1, + 387, 558, 559, -1, 558, 387, 389, -1, + 389, 557, 558, -1, 557, 389, 391, -1, + 391, 556, 557, -1, 556, 391, 393, -1, + 393, 555, 556, -1, 555, 393, 395, -1, + 395, 554, 555, -1, 554, 395, 397, -1, + 397, 553, 554, -1, 553, 397, 399, -1, + 399, 552, 553, -1, 552, 399, 401, -1, + 401, 551, 552, -1, 551, 401, 403, -1, + 403, 550, 551, -1, 550, 403, 301, -1, + 301, 549, 550, -1, 549, 301, 299, -1, + 299, 594, 549, -1, 594, 299, 296, -1, + 296, 290, 594, -1, 296, 298, 290, -1, + 298, 292, 290, -1, 595, 298, 596, -1, + 595, 597, 298, -1, 597, 292, 298, -1, + 597, 291, 292, -1, 597, 595, 291, -1, + 595, 596, 291, -1, 596, 598, 291, -1, + 599, 291, 598, -1, 598, 600, 599, -1, + 598, 601, 600, -1, 598, 596, 601, -1, + 601, 596, 298, -1, 298, 602, 601, -1, + 602, 298, 297, -1, 297, 603, 602, -1, + 603, 297, 300, -1, 300, 604, 603, -1, + 604, 300, 405, -1, 405, 605, 604, -1, + 605, 405, 406, -1, 406, 606, 605, -1, + 606, 406, 407, -1, 407, 607, 606, -1, + 607, 407, 408, -1, 408, 608, 607, -1, + 608, 408, 409, -1, 409, 609, 608, -1, + 609, 409, 410, -1, 410, 610, 609, -1, + 610, 410, 411, -1, 411, 611, 610, -1, + 611, 411, 412, -1, 412, 612, 611, -1, + 612, 412, 413, -1, 413, 613, 612, -1, + 613, 413, 414, -1, 414, 614, 613, -1, + 614, 414, 415, -1, 415, 615, 614, -1, + 615, 415, 416, -1, 416, 616, 615, -1, + 616, 416, 417, -1, 417, 617, 616, -1, + 617, 417, 418, -1, 418, 618, 617, -1, + 618, 418, 419, -1, 419, 619, 618, -1, + 619, 419, 420, -1, 420, 620, 619, -1, + 620, 420, 421, -1, 421, 621, 620, -1, + 621, 421, 422, -1, 422, 622, 621, -1, + 622, 422, 423, -1, 423, 623, 622, -1, + 623, 423, 424, -1, 424, 624, 623, -1, + 624, 424, 425, -1, 425, 625, 624, -1, + 625, 425, 426, -1, 426, 626, 625, -1, + 626, 426, 427, -1, 427, 627, 626, -1, + 427, 628, 627, -1, 628, 427, 428, -1, + 428, 629, 628, -1, 629, 428, 429, -1, + 429, 630, 629, -1, 630, 429, 430, -1, + 430, 631, 630, -1, 631, 430, 431, -1, + 431, 632, 631, -1, 632, 431, 432, -1, + 432, 633, 632, -1, 633, 432, 433, -1, + 433, 634, 633, -1, 634, 433, 434, -1, + 434, 635, 634, -1, 635, 434, 435, -1, + 435, 636, 635, -1, 636, 435, 436, -1, + 436, 637, 636, -1, 637, 436, 437, -1, + 437, 638, 637, -1, 638, 437, 438, -1, + 438, 639, 638, -1, 639, 438, 439, -1, + 439, 640, 639, -1, 640, 439, 440, -1, + 440, 641, 640, -1, 641, 440, 441, -1, + 441, 642, 641, -1, 642, 441, 442, -1, + 442, 643, 642, -1, 643, 442, 443, -1, + 443, 644, 643, -1, 644, 443, 444, -1, + 444, 645, 644, -1, 645, 444, 445, -1, + 445, 646, 645, -1, 646, 445, 446, -1, + 446, 647, 646, -1, 647, 446, 447, -1, + 447, 648, 647, -1, 648, 447, 448, -1, + 448, 649, 648, -1, 649, 448, 449, -1, + 449, 650, 649, -1, 650, 449, 450, -1, + 450, 651, 650, -1, 651, 450, 451, -1, + 651, 451, 452, -1, 651, 452, 652, -1, + 652, 650, 651, -1, 650, 652, 653, -1, + 653, 649, 650, -1, 649, 653, 654, -1, + 654, 648, 649, -1, 648, 654, 655, -1, + 655, 647, 648, -1, 647, 655, 656, -1, + 656, 646, 647, -1, 646, 656, 657, -1, + 657, 645, 646, -1, 645, 657, 658, -1, + 658, 644, 645, -1, 644, 658, 659, -1, + 659, 643, 644, -1, 643, 659, 660, -1, + 660, 642, 643, -1, 642, 660, 661, -1, + 661, 641, 642, -1, 641, 661, 662, -1, + 662, 640, 641, -1, 640, 662, 663, -1, + 663, 639, 640, -1, 639, 663, 664, -1, + 664, 638, 639, -1, 638, 664, 665, -1, + 665, 637, 638, -1, 637, 665, 666, -1, + 666, 636, 637, -1, 636, 666, 667, -1, + 667, 635, 636, -1, 635, 667, 668, -1, + 668, 634, 635, -1, 634, 668, 669, -1, + 669, 633, 634, -1, 633, 669, 670, -1, + 670, 632, 633, -1, 632, 670, 671, -1, + 671, 631, 632, -1, 631, 671, 672, -1, + 672, 630, 631, -1, 630, 672, 673, -1, + 673, 629, 630, -1, 629, 673, 674, -1, + 674, 628, 629, -1, 628, 674, 675, -1, + 675, 627, 628, -1, 627, 675, 676, -1, + 627, 676, 677, -1, 677, 626, 627, -1, + 626, 677, 678, -1, 678, 625, 626, -1, + 625, 678, 679, -1, 679, 624, 625, -1, + 624, 679, 680, -1, 680, 623, 624, -1, + 623, 680, 681, -1, 681, 622, 623, -1, + 622, 681, 682, -1, 682, 621, 622, -1, + 621, 682, 683, -1, 683, 620, 621, -1, + 620, 683, 684, -1, 684, 619, 620, -1, + 619, 684, 685, -1, 685, 618, 619, -1, + 618, 685, 686, -1, 686, 617, 618, -1, + 617, 686, 687, -1, 687, 616, 617, -1, + 616, 687, 688, -1, 688, 615, 616, -1, + 615, 688, 689, -1, 689, 614, 615, -1, + 614, 689, 690, -1, 690, 613, 614, -1, + 613, 690, 691, -1, 691, 612, 613, -1, + 612, 691, 692, -1, 692, 611, 612, -1, + 611, 692, 693, -1, 693, 610, 611, -1, + 610, 693, 694, -1, 694, 609, 610, -1, + 609, 694, 695, -1, 695, 608, 609, -1, + 608, 695, 696, -1, 696, 607, 608, -1, + 607, 696, 697, -1, 697, 606, 607, -1, + 606, 697, 698, -1, 698, 605, 606, -1, + 605, 698, 699, -1, 699, 604, 605, -1, + 604, 699, 700, -1, 700, 603, 604, -1, + 603, 700, 701, -1, 701, 602, 603, -1, + 602, 701, 702, -1, 702, 601, 602, -1, + 601, 702, 703, -1, 703, 600, 601, -1, + 704, 600, 703, -1, 704, 599, 600, -1, + 704, 705, 599, -1, 705, 704, 703, -1, + 705, 703, 706, -1, 707, 708, 709, -1, + 707, 706, 708, -1, 708, 706, 703, -1, + 703, 710, 708, -1, 710, 703, 702, -1, + 702, 711, 710, -1, 711, 702, 701, -1, + 701, 712, 711, -1, 712, 701, 700, -1, + 700, 713, 712, -1, 713, 700, 699, -1, + 699, 714, 713, -1, 714, 699, 698, -1, + 698, 715, 714, -1, 715, 698, 697, -1, + 697, 716, 715, -1, 716, 697, 696, -1, + 696, 717, 716, -1, 717, 696, 695, -1, + 695, 718, 717, -1, 718, 695, 694, -1, + 694, 719, 718, -1, 719, 694, 693, -1, + 693, 720, 719, -1, 720, 693, 692, -1, + 692, 721, 720, -1, 721, 692, 691, -1, + 691, 722, 721, -1, 722, 691, 690, -1, + 690, 723, 722, -1, 723, 690, 689, -1, + 689, 724, 723, -1, 724, 689, 688, -1, + 688, 725, 724, -1, 725, 688, 687, -1, + 687, 726, 725, -1, 726, 687, 686, -1, + 686, 727, 726, -1, 727, 686, 685, -1, + 685, 728, 727, -1, 728, 685, 684, -1, + 684, 729, 728, -1, 729, 684, 683, -1, + 683, 730, 729, -1, 730, 683, 682, -1, + 682, 731, 730, -1, 731, 682, 681, -1, + 681, 732, 731, -1, 732, 681, 680, -1, + 680, 733, 732, -1, 733, 680, 679, -1, + 679, 734, 733, -1, 734, 679, 678, -1, + 678, 735, 734, -1, 735, 678, 677, -1, + 677, 736, 735, -1, 736, 677, 676, -1, + 676, 737, 736, -1, 676, 738, 737, -1, + 738, 676, 675, -1, 675, 739, 738, -1, + 739, 675, 674, -1, 674, 740, 739, -1, + 740, 674, 673, -1, 673, 741, 740, -1, + 741, 673, 672, -1, 672, 742, 741, -1, + 742, 672, 671, -1, 671, 743, 742, -1, + 743, 671, 670, -1, 670, 744, 743, -1, + 744, 670, 669, -1, 669, 745, 744, -1, + 745, 669, 668, -1, 668, 746, 745, -1, + 746, 668, 667, -1, 667, 747, 746, -1, + 747, 667, 666, -1, 666, 748, 747, -1, + 748, 666, 665, -1, 665, 749, 748, -1, + 749, 665, 664, -1, 664, 750, 749, -1, + 750, 664, 663, -1, 663, 751, 750, -1, + 751, 663, 662, -1, 662, 752, 751, -1, + 752, 662, 661, -1, 661, 753, 752, -1, + 753, 661, 660, -1, 660, 754, 753, -1, + 754, 660, 659, -1, 659, 755, 754, -1, + 755, 659, 658, -1, 658, 756, 755, -1, + 756, 658, 657, -1, 657, 757, 756, -1, + 757, 657, 656, -1, 656, 758, 757, -1, + 758, 656, 655, -1, 655, 759, 758, -1, + 759, 655, 654, -1, 654, 760, 759, -1, + 760, 654, 653, -1, 653, 761, 760, -1, + 761, 653, 652, -1, 652, 762, 761, -1, + 762, 652, 452, -1, 452, 763, 762, -1, + 763, 452, 453, -1, 453, 764, 763, -1, + 764, 453, 454, -1, 454, 765, 764, -1, + 765, 454, 766, -1, 767, 768, 766, -1, + 767, 766, 454, -1, 767, 454, 455, -1, + 455, 768, 767, -1, 455, 456, 768, -1, + 456, 457, 768, -1, 768, 457, 458, -1, + 769, 770, 771, -1, 770, 769, 772, -1, + 769, 773, 772, -1, 769, 771, 773, -1, + 774, 775, 776, -1, 777, 778, 779, -1, + 780, 781, 782, -1, 780, 783, 781, -1, + 780, 784, 783, -1, 780, 782, 784, -1, + 785, 784, 782, -1, 786, 787, 788, -1, + 786, 785, 787, -1, 786, 789, 785, -1, + 786, 788, 789, -1, 790, 789, 788, -1, + 790, 788, 791, -1, 790, 791, 792, -1, + 792, 793, 790, -1, 794, 790, 793, -1, + 794, 789, 790, -1, 794, 785, 789, -1, + 794, 793, 785, -1, 793, 784, 785, -1, + 793, 792, 784, -1, 792, 783, 784, -1, + 792, 795, 783, -1, 795, 792, 791, -1, + 791, 796, 795, -1, 791, 797, 796, -1, + 797, 791, 788, -1, 788, 798, 797, -1, + 788, 787, 798, -1, 799, 798, 787, -1, + 799, 800, 798, -1, 799, 801, 800, -1, + 799, 787, 801, -1, 801, 787, 785, -1, + 802, 803, 804, -1, 802, 805, 803, -1, + 802, 806, 805, -1, 802, 804, 806, -1, + 807, 806, 804, -1, 807, 808, 806, -1, + 808, 807, 809, -1, 809, 810, 808, -1, + 810, 809, 811, -1, 811, 812, 810, -1, + 812, 811, 813, -1, 813, 814, 812, -1, + 813, 815, 814, -1, 815, 813, 816, -1, + 816, 817, 815, -1, 817, 816, 818, -1, + 818, 819, 817, -1, 819, 818, 820, -1, + 820, 821, 819, -1, 820, 822, 821, -1, + 823, 822, 824, -1, 823, 821, 822, -1, + 823, 825, 821, -1, 825, 823, 824, -1, + 826, 827, 828, -1, 829, 830, 831, -1, + 832, 833, 834, -1, 833, 832, 835, -1, + 835, 836, 833, -1, 836, 835, 837, -1, + 838, 839, 840, -1, 840, 841, 838, -1, + 841, 840, 842, -1, 842, 843, 841, -1, + 843, 842, 844, -1, 844, 845, 843, -1, + 845, 844, 846, -1, 846, 847, 845, -1, + 847, 846, 848, -1, 848, 849, 847, -1, + 849, 848, 850, -1, 850, 851, 849, -1, + 851, 850, 852, -1, 852, 853, 851, -1, + 853, 852, 854, -1, 854, 855, 853, -1, + 855, 854, 856, -1, 856, 857, 855, -1, + 858, 859, 857, -1, 860, 861, 862, -1, + 860, 862, 863, -1, 863, 864, 860, -1, + 864, 863, 865, -1, 865, 866, 864, -1, + 866, 865, 867, -1, 867, 868, 866, -1, + 868, 867, 869, -1, 869, 870, 868, -1, + 870, 869, 871, -1, 871, 872, 870, -1, + 872, 871, 873, -1, 873, 874, 872, -1, + 874, 873, 875, -1, 875, 876, 874, -1, + 876, 875, 877, -1, 877, 878, 876, -1, + 878, 877, 879, -1, 879, 880, 878, -1, + 880, 879, 881, -1, 881, 882, 880, -1, + 882, 881, 883, -1, 883, 884, 882, -1, + 884, 883, 885, -1, 885, 886, 884, -1, + 886, 885, 887, -1, 887, 888, 886, -1, + 888, 887, 889, -1, 889, 890, 888, -1, + 889, 891, 890, -1, 891, 889, 892, -1, + 892, 893, 891, -1, 893, 892, 894, -1, + 894, 895, 893, -1, 895, 894, 896, -1, + 896, 897, 895, -1, 897, 896, 898, -1, + 898, 899, 897, -1, 899, 898, 900, -1, + 900, 901, 899, -1, 901, 900, 902, -1, + 902, 903, 901, -1, 903, 902, 904, -1, + 904, 905, 903, -1, 905, 904, 906, -1, + 906, 907, 905, -1, 907, 906, 908, -1, + 908, 909, 907, -1, 909, 908, 910, -1, + 910, 911, 909, -1, 911, 910, 912, -1, + 912, 913, 911, -1, 913, 912, 914, -1, + 914, 915, 913, -1, 915, 914, 916, -1, + 916, 917, 915, -1, 917, 916, 918, -1, + 918, 919, 917, -1, 919, 918, 920, -1, + 920, 921, 919, -1, 921, 920, 859, -1, + 859, 858, 921, -1, 858, 922, 921, -1, + 858, 923, 922, -1, 923, 858, 857, -1, + 857, 856, 923, -1, 924, 923, 856, -1, + 923, 924, 925, -1, 925, 922, 923, -1, + 922, 925, 926, -1, 927, 928, 929, -1, + 930, 931, 932, -1, 932, 933, 930, -1, + 934, 935, 936, -1, 935, 934, 937, -1, + 937, 938, 935, -1, 938, 937, 939, -1, + 939, 940, 938, -1, 940, 939, 941, -1, + 941, 942, 940, -1, 942, 941, 943, -1, + 943, 944, 942, -1, 944, 943, 945, -1, + 945, 946, 944, -1, 946, 945, 947, -1, + 947, 948, 946, -1, 948, 947, 949, -1, + 949, 950, 948, -1, 950, 949, 951, -1, + 951, 952, 950, -1, 952, 951, 953, -1, + 953, 954, 952, -1, 954, 953, 955, -1, + 955, 956, 954, -1, 956, 955, 957, -1, + 957, 958, 956, -1, 958, 957, 959, -1, + 959, 960, 958, -1, 960, 959, 961, -1, + 961, 962, 960, -1, 962, 961, 963, -1, + 963, 964, 962, -1, 964, 963, 965, -1, + 965, 966, 964, -1, 966, 965, 967, -1, + 967, 968, 966, -1, 968, 967, 969, -1, + 969, 970, 968, -1, 970, 969, 971, -1, + 971, 972, 970, -1, 972, 971, 973, -1, + 972, 973, 974, -1, 974, 975, 972, -1, + 975, 974, 976, -1, 976, 977, 975, -1, + 977, 976, 978, -1, 978, 979, 977, -1, + 979, 978, 980, -1, 980, 981, 979, -1, + 981, 980, 982, -1, 982, 983, 981, -1, + 983, 982, 984, -1, 984, 985, 983, -1, + 985, 984, 986, -1, 986, 987, 985, -1, + 987, 986, 988, -1, 988, 989, 987, -1, + 989, 988, 990, -1, 990, 991, 989, -1, + 991, 990, 992, -1, 992, 993, 991, -1, + 993, 992, 994, -1, 994, 995, 993, -1, + 995, 994, 996, -1, 996, 997, 995, -1, + 997, 996, 998, -1, 998, 999, 997, -1, + 999, 998, 1000, -1, 1000, 1001, 999, -1, + 1001, 1000, 1002, -1, 1002, 1003, 1001, -1, + 1003, 1002, 1004, -1, 1004, 1005, 1003, -1, + 1005, 1004, 933, -1, 933, 932, 1005, -1, + 1006, 1007, 1008, -1, 1009, 1010, 1011, -1, + 1010, 1009, 1012, -1, 1010, 1012, 1008, -1, + 1010, 1008, 1007, -1, 1007, 1011, 1010, -1, + 1007, 1006, 1011, -1, 1013, 1014, 1015, -1, + 1014, 1013, 1016, -1, 1016, 1017, 1014, -1, + 1017, 1016, 1018, -1, 1018, 1019, 1017, -1, + 1019, 1018, 1020, -1, 1020, 1021, 1019, -1, + 1021, 1020, 1022, -1, 1022, 1023, 1021, -1, + 1023, 1022, 1024, -1, 1024, 1025, 1023, -1, + 1025, 1024, 1026, -1, 1026, 1027, 1025, -1, + 1027, 1026, 1028, -1, 1028, 1029, 1027, -1, + 1030, 1031, 1032, -1, 1031, 1030, 1033, -1, + 1033, 1034, 1031, -1, 1034, 1033, 1035, -1, + 1035, 1036, 1034, -1, 1036, 1035, 1037, -1, + 1037, 1038, 1036, -1, 1038, 1037, 1039, -1, + 1039, 1040, 1038, -1, 1040, 1039, 1041, -1, + 1041, 1042, 1040, -1, 1042, 1041, 1043, -1, + 1043, 1044, 1042, -1, 1044, 1043, 1045, -1, + 1045, 1046, 1044, -1, 1046, 1045, 1047, -1, + 1047, 1048, 1046, -1, 1048, 1047, 1049, -1, + 1049, 1050, 1048, -1, 1050, 1049, 1051, -1, + 1051, 1052, 1050, -1, 1052, 1051, 1053, -1, + 1053, 1054, 1052, -1, 1054, 1053, 1055, -1, + 1055, 1056, 1054, -1, 1056, 1055, 1057, -1, + 1057, 1058, 1056, -1, 1058, 1057, 1059, -1, + 1059, 1060, 1058, -1, 1060, 1059, 1061, -1, + 1061, 1062, 1060, -1, 1062, 1061, 1063, -1, + 1063, 1064, 1062, -1, 1064, 1063, 1065, -1, + 1065, 1066, 1064, -1, 1066, 1065, 1067, -1, + 1067, 1068, 1066, -1, 1068, 1067, 1069, -1, + 1069, 1070, 1068, -1, 1070, 1069, 1071, -1, + 1071, 1072, 1070, -1, 1072, 1071, 1073, -1, + 1073, 1074, 1072, -1, 1074, 1073, 1075, -1, + 1075, 1076, 1074, -1, 1075, 1077, 1076, -1, + 1077, 1075, 1078, -1, 1078, 1079, 1077, -1, + 1079, 1078, 1080, -1, 1080, 1081, 1079, -1, + 1081, 1080, 1082, -1, 1082, 1083, 1081, -1, + 1083, 1082, 1084, -1, 1084, 1085, 1083, -1, + 1085, 1084, 1086, -1, 1086, 1087, 1085, -1, + 1087, 1086, 1088, -1, 1088, 1089, 1087, -1, + 1089, 1088, 1090, -1, 1090, 1091, 1089, -1, + 1091, 1090, 1092, -1, 1092, 1093, 1091, -1, + 1093, 1092, 1094, -1, 1094, 1095, 1093, -1, + 1095, 1094, 1096, -1, 1096, 1097, 1095, -1, + 1097, 1096, 1098, -1, 1098, 1099, 1097, -1, + 1099, 1098, 1100, -1, 1100, 1101, 1099, -1, + 1101, 1100, 1102, -1, 1102, 1103, 1101, -1, + 1103, 1102, 1104, -1, 1104, 1105, 1103, -1, + 1105, 1104, 1106, -1, 1106, 1107, 1105, -1, + 1107, 1106, 1108, -1, 1108, 1109, 1107, -1, + 1109, 1108, 1110, -1, 1110, 1111, 1109, -1, + 1111, 1110, 1112, -1, 1112, 1113, 1111, -1, + 1113, 1112, 1114, -1, 1114, 1115, 1113, -1, + 1115, 1114, 1116, -1, 1116, 1117, 1115, -1, + 1117, 1116, 1118, -1, 1118, 1119, 1117, -1, + 1119, 1118, 1120, -1, 1120, 1029, 1119, -1, + 1121, 1119, 1029, -1, 1029, 1028, 1121, -1, + 1122, 1123, 1124, -1, 1124, 1123, 1125, -1, + 1124, 1125, 1126, -1, 1126, 1127, 1124, -1, + 1127, 1126, 1128, -1, 1128, 1129, 1127, -1, + 1129, 1128, 1130, -1, 1130, 1131, 1129, -1, + 1131, 1130, 1132, -1, 1132, 1133, 1131, -1, + 1134, 1135, 1136, -1, 1136, 1137, 1134, -1, + 1137, 1136, 1138, -1, 1138, 1139, 1137, -1, + 1139, 1138, 1140, -1, 1140, 1141, 1139, -1, + 1141, 1140, 1142, -1, 1142, 1143, 1141, -1, + 1143, 1142, 1144, -1, 1144, 1145, 1143, -1, + 1145, 1144, 1146, -1, 1146, 1147, 1145, -1, + 1147, 1146, 1148, -1, 1148, 1149, 1147, -1, + 1149, 1148, 1150, -1, 1150, 1151, 1149, -1, + 1151, 1150, 1152, -1, 1152, 1153, 1151, -1, + 1153, 1152, 1154, -1, 1154, 1155, 1153, -1, + 1155, 1154, 1156, -1, 1156, 1157, 1155, -1, + 1157, 1156, 1158, -1, 1158, 1159, 1157, -1, + 1159, 1158, 1160, -1, 1160, 1161, 1159, -1, + 1161, 1160, 1162, -1, 1162, 1163, 1161, -1, + 1163, 1162, 1164, -1, 1164, 1165, 1163, -1, + 1165, 1164, 1166, -1, 1166, 1167, 1165, -1, + 1167, 1166, 1168, -1, 1168, 1169, 1167, -1, + 1169, 1168, 1170, -1, 1170, 1171, 1169, -1, + 1171, 1170, 1172, -1, 1172, 1173, 1171, -1, + 1173, 1172, 1174, -1, 1174, 1175, 1173, -1, + 1175, 1174, 1176, -1, 1176, 1177, 1175, -1, + 1177, 1176, 1178, -1, 1178, 1179, 1177, -1, + 1179, 1178, 1180, -1, 1180, 1181, 1179, -1, + 1181, 1180, 1182, -1, 1181, 1182, 1183, -1, + 1183, 1184, 1181, -1, 1184, 1183, 1185, -1, + 1185, 1186, 1184, -1, 1186, 1185, 1187, -1, + 1187, 1188, 1186, -1, 1188, 1187, 1189, -1, + 1189, 1190, 1188, -1, 1190, 1189, 1191, -1, + 1191, 1192, 1190, -1, 1192, 1191, 1193, -1, + 1193, 1194, 1192, -1, 1194, 1193, 1195, -1, + 1195, 1196, 1194, -1, 1196, 1195, 1197, -1, + 1197, 1198, 1196, -1, 1198, 1197, 1199, -1, + 1199, 1200, 1198, -1, 1200, 1199, 1201, -1, + 1201, 1202, 1200, -1, 1202, 1201, 1203, -1, + 1203, 1204, 1202, -1, 1204, 1203, 1205, -1, + 1205, 1206, 1204, -1, 1206, 1205, 1207, -1, + 1207, 1208, 1206, -1, 1208, 1207, 1209, -1, + 1209, 1210, 1208, -1, 1210, 1209, 1211, -1, + 1211, 1212, 1210, -1, 1212, 1211, 1213, -1, + 1213, 1214, 1212, -1, 1214, 1213, 1215, -1, + 1215, 1216, 1214, -1, 1216, 1215, 1217, -1, + 1217, 1218, 1216, -1, 1218, 1217, 1219, -1, + 1219, 1220, 1218, -1, 1220, 1219, 1221, -1, + 1221, 1222, 1220, -1, 1222, 1221, 1223, -1, + 1223, 1224, 1222, -1, 1224, 1223, 1225, -1, + 1225, 1226, 1224, -1, 1226, 1225, 1227, -1, + 1227, 1228, 1226, -1, 1228, 1227, 1229, -1, + 1230, 1231, 1232, -1, 1232, 1233, 1230, -1, + 1233, 1232, 1234, -1, 1234, 1235, 1233, -1, + 1235, 1234, 1236, -1, 1236, 1237, 1235, -1, + 1237, 1236, 1238, -1, 1238, 1239, 1237, -1, + 1239, 1238, 1240, -1, 1240, 1241, 1239, -1, + 1241, 1240, 1242, -1, 1242, 1243, 1241, -1, + 1243, 1242, 1244, -1, 1244, 1245, 1243, -1, + 1245, 1244, 1246, -1, 1246, 1247, 1245, -1, + 1247, 1246, 1248, -1, 1248, 1249, 1247, -1, + 1249, 1248, 1250, -1, 1250, 1251, 1249, -1, + 1251, 1250, 1252, -1, 1252, 1253, 1251, -1, + 1253, 1252, 1254, -1, 1254, 1255, 1253, -1, + 1255, 1254, 1256, -1, 1256, 1257, 1255, -1, + 1257, 1256, 1258, -1, 1258, 1259, 1257, -1, + 1259, 1258, 1260, -1, 1260, 1261, 1259, -1, + 1261, 1260, 1262, -1, 1262, 1263, 1261, -1, + 1263, 1262, 1264, -1, 1264, 1265, 1263, -1, + 1265, 1264, 1266, -1, 1266, 1267, 1265, -1, + 1267, 1266, 1268, -1, 1268, 1269, 1267, -1, + 1269, 1268, 1270, -1, 1270, 1271, 1269, -1, + 1271, 1270, 1272, -1, 1272, 1273, 1271, -1, + 1273, 1272, 1274, -1, 1274, 1275, 1273, -1, + 1275, 1274, 1276, -1, 1276, 1277, 1275, -1, + 1277, 1276, 1278, -1, 1277, 1278, 1279, -1, + 1279, 1280, 1277, -1, 1280, 1279, 1281, -1, + 1281, 1282, 1280, -1, 1282, 1281, 1283, -1, + 1283, 1284, 1282, -1, 1284, 1283, 1285, -1, + 1285, 1286, 1284, -1, 1286, 1285, 1287, -1, + 1287, 1288, 1286, -1, 1288, 1287, 1289, -1, + 1289, 1290, 1288, -1, 1290, 1289, 1291, -1, + 1291, 1292, 1290, -1, 1292, 1291, 1293, -1, + 1293, 1294, 1292, -1, 1294, 1293, 1295, -1, + 1295, 1296, 1294, -1, 1296, 1295, 1297, -1, + 1297, 1298, 1296, -1, 1298, 1297, 1299, -1, + 1299, 1300, 1298, -1, 1300, 1299, 1301, -1, + 1301, 1302, 1300, -1, 1302, 1301, 1303, -1, + 1303, 1304, 1302, -1, 1304, 1303, 1305, -1, + 1305, 1306, 1304, -1, 1306, 1305, 1307, -1, + 1307, 1308, 1306, -1, 1308, 1307, 1309, -1, + 1309, 1310, 1308, -1, 1310, 1309, 1311, -1, + 1311, 1312, 1310, -1, 1312, 1311, 1313, -1, + 1313, 1314, 1312, -1, 1314, 1313, 1315, -1, + 1315, 1316, 1314, -1, 1316, 1315, 1317, -1, + 1317, 1318, 1316, -1, 1318, 1317, 1319, -1, + 1319, 1320, 1318, -1, 1320, 1319, 1321, -1, + 1321, 1322, 1320, -1, 1322, 1321, 1323, -1, + 1323, 1324, 1322, -1, 1324, 1323, 1325, -1, + 1326, 1325, 1327, -1, 1327, 1328, 1326, -1, + 1328, 1327, 1329, -1, 1329, 1330, 1328, -1, + 1330, 1329, 1331, -1, 1331, 1332, 1330, -1, + 1332, 1331, 1333, -1, 1333, 1334, 1332, -1, + 1334, 1333, 1335, -1, 1335, 1336, 1334, -1, + 1337, 1338, 1339, -1, 1337, 1339, 1340, -1, + 1340, 1341, 1342, -1, 1341, 1340, 1339, -1, + 1339, 1343, 1341, -1, 1343, 1339, 1344, -1, + 1344, 1345, 1343, -1, 1345, 1344, 1346, -1, + 1346, 1347, 1345, -1, 1347, 1346, 1336, -1, + 1336, 1335, 1347, -1, 1348, 1347, 1335, -1, + 1335, 1349, 1348, -1, 1349, 1335, 1333, -1, + 1333, 1350, 1349, -1, 1350, 1333, 1331, -1, + 1331, 1351, 1350, -1, 1351, 1331, 1329, -1, + 1329, 1352, 1351, -1, 1352, 1329, 1327, -1, + 1327, 1353, 1352, -1, 1353, 1327, 1325, -1, + 1325, 1229, 1353, -1, 1229, 1325, 1323, -1, + 1323, 1228, 1229, -1, 1228, 1323, 1321, -1, + 1321, 1226, 1228, -1, 1226, 1321, 1319, -1, + 1319, 1224, 1226, -1, 1224, 1319, 1317, -1, + 1317, 1222, 1224, -1, 1222, 1317, 1315, -1, + 1315, 1220, 1222, -1, 1220, 1315, 1313, -1, + 1313, 1218, 1220, -1, 1218, 1313, 1311, -1, + 1311, 1216, 1218, -1, 1216, 1311, 1309, -1, + 1309, 1214, 1216, -1, 1214, 1309, 1307, -1, + 1307, 1212, 1214, -1, 1212, 1307, 1305, -1, + 1305, 1210, 1212, -1, 1210, 1305, 1303, -1, + 1303, 1208, 1210, -1, 1208, 1303, 1301, -1, + 1301, 1206, 1208, -1, 1206, 1301, 1299, -1, + 1299, 1204, 1206, -1, 1204, 1299, 1297, -1, + 1297, 1202, 1204, -1, 1202, 1297, 1295, -1, + 1295, 1200, 1202, -1, 1200, 1295, 1293, -1, + 1293, 1198, 1200, -1, 1198, 1293, 1291, -1, + 1291, 1196, 1198, -1, 1196, 1291, 1289, -1, + 1289, 1194, 1196, -1, 1194, 1289, 1287, -1, + 1287, 1192, 1194, -1, 1192, 1287, 1285, -1, + 1285, 1190, 1192, -1, 1190, 1285, 1283, -1, + 1283, 1188, 1190, -1, 1188, 1283, 1281, -1, + 1281, 1186, 1188, -1, 1186, 1281, 1279, -1, + 1279, 1184, 1186, -1, 1184, 1279, 1278, -1, + 1278, 1181, 1184, -1, 1278, 1179, 1181, -1, + 1179, 1278, 1276, -1, 1276, 1177, 1179, -1, + 1177, 1276, 1274, -1, 1274, 1175, 1177, -1, + 1175, 1274, 1272, -1, 1272, 1173, 1175, -1, + 1173, 1272, 1270, -1, 1270, 1171, 1173, -1, + 1171, 1270, 1268, -1, 1268, 1169, 1171, -1, + 1169, 1268, 1266, -1, 1266, 1167, 1169, -1, + 1167, 1266, 1264, -1, 1264, 1165, 1167, -1, + 1165, 1264, 1262, -1, 1262, 1163, 1165, -1, + 1163, 1262, 1260, -1, 1260, 1161, 1163, -1, + 1161, 1260, 1258, -1, 1258, 1159, 1161, -1, + 1159, 1258, 1256, -1, 1256, 1157, 1159, -1, + 1157, 1256, 1254, -1, 1254, 1155, 1157, -1, + 1155, 1254, 1252, -1, 1252, 1153, 1155, -1, + 1153, 1252, 1250, -1, 1250, 1151, 1153, -1, + 1151, 1250, 1248, -1, 1248, 1149, 1151, -1, + 1149, 1248, 1246, -1, 1246, 1147, 1149, -1, + 1147, 1246, 1244, -1, 1244, 1145, 1147, -1, + 1145, 1244, 1242, -1, 1242, 1143, 1145, -1, + 1143, 1242, 1240, -1, 1240, 1141, 1143, -1, + 1141, 1240, 1238, -1, 1238, 1139, 1141, -1, + 1139, 1238, 1236, -1, 1236, 1137, 1139, -1, + 1137, 1236, 1234, -1, 1234, 1134, 1137, -1, + 1134, 1234, 1232, -1, 1232, 1135, 1134, -1, + 1135, 1232, 1231, -1, 1231, 1354, 1135, -1, + 1354, 1231, 1355, -1, 1355, 1356, 1354, -1, + 1356, 1355, 1357, -1, 1357, 1358, 1356, -1, + 1358, 1357, 1359, -1, 1359, 1360, 1358, -1, + 1360, 1359, 1361, -1, 1361, 1362, 1360, -1, + 1362, 1361, 1363, -1, 1363, 1133, 1362, -1, + 1133, 1363, 1364, -1, 1364, 1131, 1133, -1, + 1131, 1364, 1365, -1, 1365, 1129, 1131, -1, + 1129, 1365, 1366, -1, 1366, 1127, 1129, -1, + 1127, 1366, 1367, -1, 1367, 1124, 1127, -1, + 1367, 1368, 1124, -1, 1369, 1370, 1371, -1, + 1369, 1372, 1370, -1, 1370, 1372, 1368, -1, + 1370, 1368, 1367, -1, 1367, 1371, 1370, -1, + 1371, 1367, 1366, -1, 1366, 1373, 1371, -1, + 1373, 1366, 1365, -1, 1365, 1374, 1373, -1, + 1374, 1365, 1364, -1, 1364, 1375, 1374, -1, + 1375, 1364, 1363, -1, 1363, 1376, 1375, -1, + 1376, 1363, 1361, -1, 1361, 1377, 1376, -1, + 1377, 1361, 1359, -1, 1359, 1378, 1377, -1, + 1378, 1359, 1357, -1, 1357, 1379, 1378, -1, + 1379, 1357, 1355, -1, 1355, 1380, 1379, -1, + 1380, 1355, 1231, -1, 1231, 1381, 1380, -1, + 1381, 1231, 1230, -1, 1230, 1382, 1381, -1, + 1382, 1230, 1233, -1, 1233, 1383, 1382, -1, + 1383, 1233, 1235, -1, 1235, 1384, 1383, -1, + 1384, 1235, 1237, -1, 1237, 1385, 1384, -1, + 1385, 1237, 1239, -1, 1239, 1386, 1385, -1, + 1386, 1239, 1241, -1, 1241, 1387, 1386, -1, + 1387, 1241, 1243, -1, 1243, 1388, 1387, -1, + 1388, 1243, 1245, -1, 1245, 1389, 1388, -1, + 1389, 1245, 1247, -1, 1247, 1390, 1389, -1, + 1390, 1247, 1249, -1, 1249, 1391, 1390, -1, + 1391, 1249, 1251, -1, 1251, 1392, 1391, -1, + 1392, 1251, 1253, -1, 1253, 1393, 1392, -1, + 1393, 1253, 1255, -1, 1255, 1394, 1393, -1, + 1394, 1255, 1257, -1, 1257, 1395, 1394, -1, + 1395, 1257, 1259, -1, 1259, 1396, 1395, -1, + 1396, 1259, 1261, -1, 1261, 1397, 1396, -1, + 1397, 1261, 1263, -1, 1263, 1398, 1397, -1, + 1398, 1263, 1265, -1, 1265, 1399, 1398, -1, + 1399, 1265, 1267, -1, 1267, 1400, 1399, -1, + 1400, 1267, 1269, -1, 1269, 1401, 1400, -1, + 1401, 1269, 1271, -1, 1271, 1402, 1401, -1, + 1402, 1271, 1273, -1, 1273, 1403, 1402, -1, + 1403, 1273, 1275, -1, 1275, 1404, 1403, -1, + 1404, 1275, 1277, -1, 1404, 1277, 1280, -1, + 1280, 1405, 1404, -1, 1405, 1280, 1282, -1, + 1282, 1406, 1405, -1, 1406, 1282, 1284, -1, + 1284, 1407, 1406, -1, 1407, 1284, 1286, -1, + 1286, 1408, 1407, -1, 1408, 1286, 1288, -1, + 1288, 1409, 1408, -1, 1409, 1288, 1290, -1, + 1290, 1410, 1409, -1, 1410, 1290, 1292, -1, + 1292, 1411, 1410, -1, 1411, 1292, 1294, -1, + 1294, 1412, 1411, -1, 1412, 1294, 1296, -1, + 1296, 1413, 1412, -1, 1413, 1296, 1298, -1, + 1298, 1414, 1413, -1, 1414, 1298, 1300, -1, + 1300, 1415, 1414, -1, 1415, 1300, 1302, -1, + 1302, 1416, 1415, -1, 1416, 1302, 1304, -1, + 1304, 1417, 1416, -1, 1417, 1304, 1306, -1, + 1306, 1418, 1417, -1, 1418, 1306, 1308, -1, + 1308, 1419, 1418, -1, 1419, 1308, 1310, -1, + 1310, 1420, 1419, -1, 1420, 1310, 1312, -1, + 1312, 1421, 1420, -1, 1421, 1312, 1314, -1, + 1314, 1422, 1421, -1, 1422, 1314, 1316, -1, + 1316, 1423, 1422, -1, 1423, 1316, 1318, -1, + 1318, 1424, 1423, -1, 1424, 1318, 1320, -1, + 1320, 1425, 1424, -1, 1425, 1320, 1322, -1, + 1322, 1426, 1425, -1, 1426, 1322, 1324, -1, + 1324, 1427, 1426, -1, 1427, 1324, 1325, -1, + 1325, 1326, 1427, -1, 1428, 1427, 1326, -1, + 1427, 1428, 1429, -1, 1429, 1426, 1427, -1, + 1426, 1429, 1430, -1, 1430, 1425, 1426, -1, + 1425, 1430, 1431, -1, 1431, 1424, 1425, -1, + 1424, 1431, 1432, -1, 1432, 1423, 1424, -1, + 1423, 1432, 1433, -1, 1433, 1422, 1423, -1, + 1422, 1433, 1434, -1, 1434, 1421, 1422, -1, + 1421, 1434, 1435, -1, 1435, 1420, 1421, -1, + 1420, 1435, 1436, -1, 1436, 1419, 1420, -1, + 1419, 1436, 1437, -1, 1437, 1418, 1419, -1, + 1418, 1437, 1438, -1, 1438, 1417, 1418, -1, + 1417, 1438, 1439, -1, 1439, 1416, 1417, -1, + 1416, 1439, 1440, -1, 1440, 1415, 1416, -1, + 1415, 1440, 1441, -1, 1441, 1414, 1415, -1, + 1414, 1441, 1442, -1, 1442, 1413, 1414, -1, + 1413, 1442, 1443, -1, 1443, 1412, 1413, -1, + 1412, 1443, 1444, -1, 1444, 1411, 1412, -1, + 1411, 1444, 1445, -1, 1445, 1410, 1411, -1, + 1410, 1445, 1446, -1, 1446, 1409, 1410, -1, + 1409, 1446, 1447, -1, 1447, 1408, 1409, -1, + 1408, 1447, 1448, -1, 1448, 1407, 1408, -1, + 1407, 1448, 1449, -1, 1449, 1406, 1407, -1, + 1406, 1449, 1450, -1, 1450, 1405, 1406, -1, + 1405, 1450, 1451, -1, 1451, 1404, 1405, -1, + 1451, 1403, 1404, -1, 1403, 1451, 1452, -1, + 1452, 1402, 1403, -1, 1402, 1452, 1453, -1, + 1453, 1401, 1402, -1, 1401, 1453, 1454, -1, + 1454, 1400, 1401, -1, 1400, 1454, 1455, -1, + 1455, 1399, 1400, -1, 1399, 1455, 1456, -1, + 1456, 1398, 1399, -1, 1398, 1456, 1457, -1, + 1457, 1397, 1398, -1, 1397, 1457, 1458, -1, + 1458, 1396, 1397, -1, 1396, 1458, 1459, -1, + 1459, 1395, 1396, -1, 1395, 1459, 1460, -1, + 1460, 1394, 1395, -1, 1394, 1460, 1461, -1, + 1461, 1393, 1394, -1, 1393, 1461, 1462, -1, + 1462, 1392, 1393, -1, 1392, 1462, 1463, -1, + 1463, 1391, 1392, -1, 1391, 1463, 1464, -1, + 1464, 1390, 1391, -1, 1390, 1464, 1465, -1, + 1465, 1389, 1390, -1, 1389, 1465, 1466, -1, + 1466, 1388, 1389, -1, 1388, 1466, 1467, -1, + 1467, 1387, 1388, -1, 1387, 1467, 1468, -1, + 1468, 1386, 1387, -1, 1386, 1468, 1469, -1, + 1469, 1385, 1386, -1, 1385, 1469, 1470, -1, + 1470, 1384, 1385, -1, 1384, 1470, 1471, -1, + 1471, 1383, 1384, -1, 1383, 1471, 1472, -1, + 1472, 1382, 1383, -1, 1382, 1472, 1473, -1, + 1473, 1381, 1382, -1, 1381, 1473, 1121, -1, + 1121, 1380, 1381, -1, 1380, 1121, 1028, -1, + 1028, 1379, 1380, -1, 1379, 1028, 1026, -1, + 1026, 1378, 1379, -1, 1378, 1026, 1024, -1, + 1024, 1377, 1378, -1, 1377, 1024, 1022, -1, + 1022, 1376, 1377, -1, 1376, 1022, 1020, -1, + 1020, 1375, 1376, -1, 1375, 1020, 1018, -1, + 1018, 1374, 1375, -1, 1374, 1018, 1016, -1, + 1016, 1373, 1374, -1, 1373, 1016, 1013, -1, + 1013, 1371, 1373, -1, 1371, 1013, 1474, -1, + 1474, 1369, 1371, -1, 1474, 1372, 1369, -1, + 1474, 1475, 1372, -1, 1475, 1474, 1013, -1, + 1475, 1013, 1015, -1, 1015, 1372, 1475, -1, + 1372, 1015, 1476, -1, 1477, 1476, 1015, -1, + 1477, 1015, 1014, -1, 1477, 1014, 1478, -1, + 1478, 1476, 1477, -1, 1479, 1480, 1481, -1, + 1480, 1479, 1482, -1, 1482, 1483, 1480, -1, + 1483, 1482, 1484, -1, 1484, 1485, 1483, -1, + 1486, 1487, 1488, -1, 1489, 1490, 1491, -1, + 1492, 1491, 1490, -1, 1493, 1491, 1494, -1, + 1494, 1495, 1493, -1, 1495, 1494, 1496, -1, + 1496, 1497, 1495, -1, 1497, 1496, 1498, -1, + 1498, 1499, 1497, -1, 1499, 1498, 1500, -1, + 1500, 1501, 1499, -1, 1501, 1500, 1502, -1, + 1502, 1503, 1501, -1, 1503, 1502, 1504, -1, + 1504, 1505, 1503, -1, 1505, 1504, 1506, -1, + 1506, 1507, 1505, -1, 1507, 1506, 1508, -1, + 1508, 1509, 1507, -1, 1509, 1508, 1510, -1, + 1510, 1511, 1509, -1, 1511, 1510, 1512, -1, + 1512, 1513, 1511, -1, 1513, 1512, 1514, -1, + 1514, 1515, 1513, -1, 1515, 1514, 1516, -1, + 1516, 1517, 1515, -1, 1517, 1516, 1518, -1, + 1518, 1519, 1517, -1, 1519, 1518, 1520, -1, + 1520, 1521, 1519, -1, 1521, 1520, 1522, -1, + 1522, 1523, 1521, -1, 1523, 1522, 1524, -1, + 1524, 1525, 1523, -1, 1525, 1524, 1526, -1, + 1526, 1527, 1525, -1, 1527, 1526, 1528, -1, + 1528, 1529, 1527, -1, 1529, 1528, 1530, -1, + 1530, 1531, 1529, -1, 1531, 1530, 1532, -1, + 1532, 1533, 1531, -1, 1533, 1532, 1534, -1, + 1534, 1535, 1533, -1, 1535, 1534, 1536, -1, + 1535, 1536, 1537, -1, 1537, 1538, 1535, -1, + 1538, 1537, 1539, -1, 1539, 1540, 1538, -1, + 1540, 1539, 1541, -1, 1541, 1542, 1540, -1, + 1542, 1541, 1543, -1, 1543, 1544, 1542, -1, + 1544, 1543, 1545, -1, 1545, 1546, 1544, -1, + 1546, 1545, 1547, -1, 1547, 1548, 1546, -1, + 1548, 1547, 1549, -1, 1549, 1550, 1548, -1, + 1550, 1549, 1551, -1, 1551, 1552, 1550, -1, + 1552, 1551, 1553, -1, 1553, 1554, 1552, -1, + 1554, 1553, 1555, -1, 1555, 1556, 1554, -1, + 1556, 1555, 1557, -1, 1557, 1558, 1556, -1, + 1558, 1557, 1559, -1, 1559, 1560, 1558, -1, + 1560, 1559, 1561, -1, 1561, 1562, 1560, -1, + 1562, 1561, 1563, -1, 1563, 1564, 1562, -1, + 1564, 1563, 1565, -1, 1565, 1566, 1564, -1, + 1566, 1565, 1567, -1, 1567, 1568, 1566, -1, + 1568, 1567, 1569, -1, 1569, 1570, 1568, -1, + 1570, 1569, 1571, -1, 1571, 1572, 1570, -1, + 1572, 1571, 1573, -1, 1573, 1574, 1572, -1, + 1574, 1573, 1575, -1, 1575, 1576, 1574, -1, + 1577, 1576, 1578, -1, 1579, 1578, 1576, -1, + 1576, 1575, 1579, -1, 1580, 1581, 1579, -1, + 1579, 1582, 1580, -1, 1582, 1579, 1575, -1, + 1575, 1583, 1582, -1, 1583, 1575, 1573, -1, + 1573, 1584, 1583, -1, 1584, 1573, 1571, -1, + 1571, 1585, 1584, -1, 1585, 1571, 1569, -1, + 1569, 1586, 1585, -1, 1586, 1569, 1567, -1, + 1567, 1587, 1586, -1, 1587, 1567, 1565, -1, + 1565, 1588, 1587, -1, 1588, 1565, 1563, -1, + 1563, 1589, 1588, -1, 1589, 1563, 1561, -1, + 1561, 1590, 1589, -1, 1590, 1561, 1559, -1, + 1559, 1591, 1590, -1, 1591, 1559, 1557, -1, + 1557, 1592, 1591, -1, 1592, 1557, 1555, -1, + 1555, 1593, 1592, -1, 1593, 1555, 1553, -1, + 1553, 1594, 1593, -1, 1594, 1553, 1551, -1, + 1551, 1595, 1594, -1, 1595, 1551, 1549, -1, + 1549, 1596, 1595, -1, 1596, 1549, 1547, -1, + 1547, 1597, 1596, -1, 1597, 1547, 1545, -1, + 1545, 1598, 1597, -1, 1598, 1545, 1543, -1, + 1543, 1599, 1598, -1, 1599, 1543, 1541, -1, + 1541, 1600, 1599, -1, 1600, 1541, 1539, -1, + 1539, 1601, 1600, -1, 1601, 1539, 1537, -1, + 1537, 1602, 1601, -1, 1602, 1537, 1536, -1, + 1536, 1603, 1602, -1, 1536, 1604, 1603, -1, + 1604, 1536, 1534, -1, 1534, 1605, 1604, -1, + 1605, 1534, 1532, -1, 1532, 1606, 1605, -1, + 1606, 1532, 1530, -1, 1530, 1607, 1606, -1, + 1607, 1530, 1528, -1, 1528, 1608, 1607, -1, + 1608, 1528, 1526, -1, 1526, 1609, 1608, -1, + 1609, 1526, 1524, -1, 1524, 1610, 1609, -1, + 1610, 1524, 1522, -1, 1522, 1611, 1610, -1, + 1611, 1522, 1520, -1, 1520, 1612, 1611, -1, + 1612, 1520, 1518, -1, 1518, 1613, 1612, -1, + 1613, 1518, 1516, -1, 1516, 1614, 1613, -1, + 1614, 1516, 1514, -1, 1514, 1615, 1614, -1, + 1615, 1514, 1512, -1, 1512, 1616, 1615, -1, + 1616, 1512, 1510, -1, 1510, 1617, 1616, -1, + 1617, 1510, 1508, -1, 1508, 1618, 1617, -1, + 1618, 1508, 1506, -1, 1506, 1619, 1618, -1, + 1619, 1506, 1504, -1, 1504, 1620, 1619, -1, + 1620, 1504, 1502, -1, 1502, 1621, 1620, -1, + 1621, 1502, 1500, -1, 1500, 1622, 1621, -1, + 1622, 1500, 1498, -1, 1498, 1623, 1622, -1, + 1623, 1498, 1496, -1, 1496, 1624, 1623, -1, + 1624, 1496, 1494, -1, 1494, 1625, 1624, -1, + 1625, 1494, 1491, -1, 1491, 1492, 1625, -1, + 1492, 1488, 1626, -1, 1626, 1625, 1492, -1, + 1625, 1626, 1627, -1, 1627, 1624, 1625, -1, + 1624, 1627, 1628, -1, 1628, 1623, 1624, -1, + 1623, 1628, 1629, -1, 1629, 1622, 1623, -1, + 1622, 1629, 1630, -1, 1630, 1621, 1622, -1, + 1621, 1630, 1631, -1, 1631, 1620, 1621, -1, + 1620, 1631, 1632, -1, 1632, 1619, 1620, -1, + 1619, 1632, 1633, -1, 1633, 1618, 1619, -1, + 1618, 1633, 1634, -1, 1634, 1617, 1618, -1, + 1617, 1634, 1635, -1, 1635, 1616, 1617, -1, + 1616, 1635, 1636, -1, 1636, 1615, 1616, -1, + 1615, 1636, 1637, -1, 1637, 1614, 1615, -1, + 1614, 1637, 1638, -1, 1638, 1613, 1614, -1, + 1613, 1638, 1639, -1, 1639, 1612, 1613, -1, + 1612, 1639, 1640, -1, 1640, 1611, 1612, -1, + 1611, 1640, 1641, -1, 1641, 1610, 1611, -1, + 1610, 1641, 1642, -1, 1642, 1609, 1610, -1, + 1609, 1642, 1643, -1, 1643, 1608, 1609, -1, + 1608, 1643, 1644, -1, 1644, 1607, 1608, -1, + 1607, 1644, 1645, -1, 1645, 1606, 1607, -1, + 1606, 1645, 1646, -1, 1646, 1605, 1606, -1, + 1605, 1646, 1647, -1, 1647, 1604, 1605, -1, + 1604, 1647, 1648, -1, 1648, 1603, 1604, -1, + 1603, 1648, 1649, -1, 1603, 1649, 1650, -1, + 1650, 1602, 1603, -1, 1602, 1650, 1651, -1, + 1651, 1601, 1602, -1, 1601, 1651, 1652, -1, + 1652, 1600, 1601, -1, 1600, 1652, 1653, -1, + 1653, 1599, 1600, -1, 1599, 1653, 1654, -1, + 1654, 1598, 1599, -1, 1598, 1654, 1655, -1, + 1655, 1597, 1598, -1, 1597, 1655, 1656, -1, + 1656, 1596, 1597, -1, 1596, 1656, 1657, -1, + 1657, 1595, 1596, -1, 1595, 1657, 1658, -1, + 1658, 1594, 1595, -1, 1594, 1658, 1659, -1, + 1659, 1593, 1594, -1, 1593, 1659, 1660, -1, + 1660, 1592, 1593, -1, 1592, 1660, 1661, -1, + 1661, 1591, 1592, -1, 1591, 1661, 1662, -1, + 1662, 1590, 1591, -1, 1590, 1662, 1663, -1, + 1663, 1589, 1590, -1, 1589, 1663, 1664, -1, + 1664, 1588, 1589, -1, 1588, 1664, 1665, -1, + 1665, 1587, 1588, -1, 1587, 1665, 1666, -1, + 1666, 1586, 1587, -1, 1586, 1666, 1667, -1, + 1667, 1585, 1586, -1, 1585, 1667, 1668, -1, + 1668, 1584, 1585, -1, 1584, 1668, 1669, -1, + 1669, 1583, 1584, -1, 1583, 1669, 1670, -1, + 1670, 1582, 1583, -1, 1582, 1670, 1671, -1, + 1671, 1580, 1582, -1, 1672, 1580, 1673, -1, + 1674, 1673, 1580, -1, 1580, 1671, 1674, -1, + 1674, 1675, 1676, -1, 1677, 1675, 1678, -1, + 1679, 1680, 1681, -1, 1681, 1682, 1679, -1, + 1682, 1681, 1683, -1, 1683, 1684, 1682, -1, + 1684, 1683, 1685, -1, 1685, 1686, 1684, -1, + 1686, 1685, 1687, -1, 1687, 1688, 1686, -1, + 1688, 1687, 1689, -1, 1689, 1690, 1688, -1, + 1690, 1689, 1691, -1, 1691, 1692, 1690, -1, + 1692, 1691, 1693, -1, 1693, 1694, 1692, -1, + 1694, 1693, 1695, -1, 1695, 1696, 1694, -1, + 1696, 1695, 1697, -1, 1697, 1698, 1696, -1, + 1698, 1697, 1699, -1, 1699, 1700, 1698, -1, + 1700, 1699, 1701, -1, 1701, 1702, 1700, -1, + 1702, 1701, 1703, -1, 1703, 1704, 1702, -1, + 1704, 1703, 1705, -1, 1705, 1706, 1704, -1, + 1706, 1705, 1707, -1, 1707, 1708, 1706, -1, + 1708, 1707, 1709, -1, 1709, 1710, 1708, -1, + 1710, 1709, 1711, -1, 1711, 1712, 1710, -1, + 1712, 1711, 1713, -1, 1713, 1714, 1712, -1, + 1714, 1713, 1715, -1, 1715, 1716, 1714, -1, + 1716, 1715, 1717, -1, 1717, 1718, 1716, -1, + 1718, 1717, 1719, -1, 1719, 1720, 1718, -1, + 1720, 1719, 1721, -1, 1721, 1722, 1720, -1, + 1722, 1721, 1723, -1, 1722, 1723, 1724, -1, + 1724, 1725, 1722, -1, 1725, 1724, 1726, -1, + 1726, 1727, 1725, -1, 1727, 1726, 1728, -1, + 1728, 1729, 1727, -1, 1729, 1728, 1730, -1, + 1730, 1731, 1729, -1, 1731, 1730, 1732, -1, + 1732, 1733, 1731, -1, 1733, 1732, 1734, -1, + 1734, 1735, 1733, -1, 1735, 1734, 1736, -1, + 1736, 1737, 1735, -1, 1737, 1736, 1738, -1, + 1738, 1739, 1737, -1, 1739, 1738, 1740, -1, + 1740, 1741, 1739, -1, 1741, 1740, 1742, -1, + 1742, 1743, 1741, -1, 1743, 1742, 1744, -1, + 1744, 1745, 1743, -1, 1745, 1744, 1746, -1, + 1746, 1747, 1745, -1, 1747, 1746, 1748, -1, + 1748, 1749, 1747, -1, 1749, 1748, 1750, -1, + 1750, 1751, 1749, -1, 1751, 1750, 1752, -1, + 1752, 1753, 1751, -1, 1753, 1752, 1754, -1, + 1754, 1755, 1753, -1, 1755, 1754, 1756, -1, + 1756, 1757, 1755, -1, 1757, 1756, 1758, -1, + 1758, 1759, 1757, -1, 1759, 1758, 1760, -1, + 1760, 1761, 1759, -1, 1761, 1760, 1762, -1, + 1762, 1763, 1761, -1, 1763, 1762, 1764, -1, + 1764, 1765, 1763, -1, 1765, 1764, 1766, -1, + 1766, 1767, 1765, -1, 1768, 1769, 1770, -1, + 1770, 1771, 1768, -1, 1771, 1770, 1772, -1, + 1772, 1773, 1771, -1, 1773, 1772, 1774, -1, + 1774, 1775, 1773, -1, 1775, 1774, 1776, -1, + 1776, 1777, 1775, -1, 1777, 1776, 1778, -1, + 1778, 1779, 1777, -1, 1779, 1778, 1780, -1, + 1780, 1781, 1779, -1, 1781, 1780, 1782, -1, + 1782, 1783, 1781, -1, 1783, 1782, 1784, -1, + 1784, 1785, 1783, -1, 1785, 1784, 1786, -1, + 1786, 1787, 1785, -1, 1787, 1786, 1788, -1, + 1788, 1789, 1787, -1, 1789, 1788, 1790, -1, + 1790, 1791, 1789, -1, 1791, 1790, 1792, -1, + 1792, 1793, 1791, -1, 1793, 1792, 1794, -1, + 1794, 1795, 1793, -1, 1795, 1794, 1796, -1, + 1796, 1797, 1795, -1, 1797, 1796, 1798, -1, + 1798, 1799, 1797, -1, 1799, 1798, 1800, -1, + 1800, 1801, 1799, -1, 1801, 1800, 1802, -1, + 1802, 1803, 1801, -1, 1803, 1802, 1804, -1, + 1804, 1805, 1803, -1, 1805, 1804, 1806, -1, + 1806, 1807, 1805, -1, 1807, 1806, 1808, -1, + 1808, 1809, 1807, -1, 1809, 1808, 1810, -1, + 1810, 1811, 1809, -1, 1811, 1810, 1812, -1, + 1811, 1812, 1813, -1, 1813, 1814, 1811, -1, + 1814, 1813, 1815, -1, 1815, 1816, 1814, -1, + 1816, 1815, 1817, -1, 1817, 1818, 1816, -1, + 1818, 1817, 1819, -1, 1819, 1820, 1818, -1, + 1820, 1819, 1821, -1, 1821, 1822, 1820, -1, + 1822, 1821, 1823, -1, 1823, 1824, 1822, -1, + 1824, 1823, 1825, -1, 1825, 1826, 1824, -1, + 1826, 1825, 1827, -1, 1827, 1828, 1826, -1, + 1828, 1827, 1829, -1, 1829, 1830, 1828, -1, + 1830, 1829, 1831, -1, 1831, 1832, 1830, -1, + 1832, 1831, 1833, -1, 1833, 1834, 1832, -1, + 1834, 1833, 1835, -1, 1835, 1836, 1834, -1, + 1836, 1835, 1837, -1, 1837, 1838, 1836, -1, + 1838, 1837, 1839, -1, 1839, 1840, 1838, -1, + 1840, 1839, 1841, -1, 1841, 1842, 1840, -1, + 1842, 1841, 1843, -1, 1843, 1844, 1842, -1, + 1844, 1843, 1845, -1, 1845, 1846, 1844, -1, + 1846, 1845, 1847, -1, 1847, 1848, 1846, -1, + 1848, 1847, 1849, -1, 1849, 1850, 1848, -1, + 1850, 1849, 1851, -1, 1851, 1852, 1850, -1, + 1852, 1851, 1853, -1, 1853, 1854, 1852, -1, + 1854, 1853, 1855, -1, 1855, 1856, 1854, -1, + 1857, 1858, 1859, -1, 1860, 1861, 1862, -1, + 1861, 1860, 1863, -1, 1863, 1858, 1861, -1, + 1858, 1863, 1864, -1, 1864, 1859, 1858, -1, + 1865, 1859, 1864, -1, 1865, 1864, 1866, -1, + 1867, 1866, 1864, -1, 1864, 1868, 1867, -1, + 1868, 1864, 1863, -1, 1863, 1869, 1868, -1, + 1869, 1863, 1860, -1, 1860, 1870, 1869, -1, + 1870, 1860, 1862, -1, 1862, 1871, 1870, -1, + 1871, 1862, 1872, -1, 1872, 1873, 1871, -1, + 1873, 1872, 1856, -1, 1856, 1855, 1873, -1, + 1855, 1767, 1873, -1, 1767, 1855, 1853, -1, + 1853, 1765, 1767, -1, 1765, 1853, 1851, -1, + 1851, 1763, 1765, -1, 1763, 1851, 1849, -1, + 1849, 1761, 1763, -1, 1761, 1849, 1847, -1, + 1847, 1759, 1761, -1, 1759, 1847, 1845, -1, + 1845, 1757, 1759, -1, 1757, 1845, 1843, -1, + 1843, 1755, 1757, -1, 1755, 1843, 1841, -1, + 1841, 1753, 1755, -1, 1753, 1841, 1839, -1, + 1839, 1751, 1753, -1, 1751, 1839, 1837, -1, + 1837, 1749, 1751, -1, 1749, 1837, 1835, -1, + 1835, 1747, 1749, -1, 1747, 1835, 1833, -1, + 1833, 1745, 1747, -1, 1745, 1833, 1831, -1, + 1831, 1743, 1745, -1, 1743, 1831, 1829, -1, + 1829, 1741, 1743, -1, 1741, 1829, 1827, -1, + 1827, 1739, 1741, -1, 1739, 1827, 1825, -1, + 1825, 1737, 1739, -1, 1737, 1825, 1823, -1, + 1823, 1735, 1737, -1, 1735, 1823, 1821, -1, + 1821, 1733, 1735, -1, 1733, 1821, 1819, -1, + 1819, 1731, 1733, -1, 1731, 1819, 1817, -1, + 1817, 1729, 1731, -1, 1729, 1817, 1815, -1, + 1815, 1727, 1729, -1, 1727, 1815, 1813, -1, + 1813, 1725, 1727, -1, 1725, 1813, 1812, -1, + 1812, 1722, 1725, -1, 1812, 1720, 1722, -1, + 1720, 1812, 1810, -1, 1810, 1718, 1720, -1, + 1718, 1810, 1808, -1, 1808, 1716, 1718, -1, + 1716, 1808, 1806, -1, 1806, 1714, 1716, -1, + 1714, 1806, 1804, -1, 1804, 1712, 1714, -1, + 1712, 1804, 1802, -1, 1802, 1710, 1712, -1, + 1710, 1802, 1800, -1, 1800, 1708, 1710, -1, + 1708, 1800, 1798, -1, 1798, 1706, 1708, -1, + 1706, 1798, 1796, -1, 1796, 1704, 1706, -1, + 1704, 1796, 1794, -1, 1794, 1702, 1704, -1, + 1702, 1794, 1792, -1, 1792, 1700, 1702, -1, + 1700, 1792, 1790, -1, 1790, 1698, 1700, -1, + 1698, 1790, 1788, -1, 1788, 1696, 1698, -1, + 1696, 1788, 1786, -1, 1786, 1694, 1696, -1, + 1694, 1786, 1784, -1, 1784, 1692, 1694, -1, + 1692, 1784, 1782, -1, 1782, 1690, 1692, -1, + 1690, 1782, 1780, -1, 1780, 1688, 1690, -1, + 1688, 1780, 1778, -1, 1778, 1686, 1688, -1, + 1686, 1778, 1776, -1, 1776, 1684, 1686, -1, + 1684, 1776, 1774, -1, 1774, 1682, 1684, -1, + 1682, 1774, 1772, -1, 1772, 1679, 1682, -1, + 1679, 1772, 1770, -1, 1770, 1680, 1679, -1, + 1680, 1770, 1769, -1, 1769, 1874, 1680, -1, + 1874, 1769, 1875, -1, 1875, 1876, 1874, -1, + 1876, 1875, 1877, -1, 1877, 1878, 1876, -1, + 1878, 1877, 1879, -1, 1879, 1880, 1878, -1, + 1880, 1879, 1881, -1, 1881, 1882, 1880, -1, + 1883, 1884, 1882, -1, 1884, 1883, 1885, -1, + 1885, 1886, 1887, -1, 1886, 1885, 1883, -1, + 1883, 1882, 1886, -1, 1882, 1881, 1886, -1, + 1888, 1886, 1881, -1, 1888, 1887, 1886, -1, + 1889, 1887, 1888, -1, 1888, 1881, 1889, -1, + 1881, 1890, 1889, -1, 1890, 1881, 1879, -1, + 1879, 1891, 1890, -1, 1891, 1879, 1877, -1, + 1877, 1892, 1891, -1, 1892, 1877, 1875, -1, + 1875, 1893, 1892, -1, 1893, 1875, 1769, -1, + 1769, 1894, 1893, -1, 1894, 1769, 1768, -1, + 1768, 1895, 1894, -1, 1895, 1768, 1771, -1, + 1771, 1896, 1895, -1, 1896, 1771, 1773, -1, + 1773, 1897, 1896, -1, 1897, 1773, 1775, -1, + 1775, 1898, 1897, -1, 1898, 1775, 1777, -1, + 1777, 1899, 1898, -1, 1899, 1777, 1779, -1, + 1779, 1900, 1899, -1, 1900, 1779, 1781, -1, + 1781, 1901, 1900, -1, 1901, 1781, 1783, -1, + 1783, 1902, 1901, -1, 1902, 1783, 1785, -1, + 1785, 1903, 1902, -1, 1903, 1785, 1787, -1, + 1787, 1904, 1903, -1, 1904, 1787, 1789, -1, + 1789, 1905, 1904, -1, 1905, 1789, 1791, -1, + 1791, 1906, 1905, -1, 1906, 1791, 1793, -1, + 1793, 1907, 1906, -1, 1907, 1793, 1795, -1, + 1795, 1908, 1907, -1, 1908, 1795, 1797, -1, + 1797, 1909, 1908, -1, 1909, 1797, 1799, -1, + 1799, 1910, 1909, -1, 1910, 1799, 1801, -1, + 1801, 1911, 1910, -1, 1911, 1801, 1803, -1, + 1803, 1912, 1911, -1, 1912, 1803, 1805, -1, + 1805, 1913, 1912, -1, 1913, 1805, 1807, -1, + 1807, 1914, 1913, -1, 1914, 1807, 1809, -1, + 1809, 1915, 1914, -1, 1915, 1809, 1811, -1, + 1915, 1811, 1814, -1, 1814, 1916, 1915, -1, + 1916, 1814, 1816, -1, 1816, 1917, 1916, -1, + 1917, 1816, 1818, -1, 1818, 1918, 1917, -1, + 1918, 1818, 1820, -1, 1820, 1919, 1918, -1, + 1919, 1820, 1822, -1, 1822, 1920, 1919, -1, + 1920, 1822, 1824, -1, 1824, 1921, 1920, -1, + 1921, 1824, 1826, -1, 1826, 1922, 1921, -1, + 1922, 1826, 1828, -1, 1828, 1923, 1922, -1, + 1923, 1828, 1830, -1, 1830, 1924, 1923, -1, + 1924, 1830, 1832, -1, 1832, 1925, 1924, -1, + 1925, 1832, 1834, -1, 1834, 1926, 1925, -1, + 1926, 1834, 1836, -1, 1836, 1927, 1926, -1, + 1927, 1836, 1838, -1, 1838, 1928, 1927, -1, + 1928, 1838, 1840, -1, 1840, 1929, 1928, -1, + 1929, 1840, 1842, -1, 1842, 1930, 1929, -1, + 1930, 1842, 1844, -1, 1844, 1931, 1930, -1, + 1931, 1844, 1846, -1, 1846, 1932, 1931, -1, + 1932, 1846, 1848, -1, 1848, 1933, 1932, -1, + 1933, 1848, 1850, -1, 1850, 1934, 1933, -1, + 1934, 1850, 1852, -1, 1852, 1935, 1934, -1, + 1935, 1852, 1854, -1, 1854, 1936, 1935, -1, + 1936, 1854, 1856, -1, 1856, 1937, 1936, -1, + 1937, 1856, 1872, -1, 1872, 1938, 1937, -1, + 1938, 1872, 1862, -1, 1862, 1939, 1938, -1, + 1939, 1862, 1861, -1, 1861, 1940, 1939, -1, + 1940, 1861, 1858, -1, 1858, 1941, 1940, -1, + 1942, 1940, 1941, -1, 1942, 1678, 1940, -1, + 1940, 1678, 1675, -1, 1675, 1939, 1940, -1, + 1939, 1675, 1674, -1, 1674, 1938, 1939, -1, + 1938, 1674, 1671, -1, 1671, 1937, 1938, -1, + 1937, 1671, 1670, -1, 1670, 1936, 1937, -1, + 1936, 1670, 1669, -1, 1669, 1935, 1936, -1, + 1935, 1669, 1668, -1, 1668, 1934, 1935, -1, + 1934, 1668, 1667, -1, 1667, 1933, 1934, -1, + 1933, 1667, 1666, -1, 1666, 1932, 1933, -1, + 1932, 1666, 1665, -1, 1665, 1931, 1932, -1, + 1931, 1665, 1664, -1, 1664, 1930, 1931, -1, + 1930, 1664, 1663, -1, 1663, 1929, 1930, -1, + 1929, 1663, 1662, -1, 1662, 1928, 1929, -1, + 1928, 1662, 1661, -1, 1661, 1927, 1928, -1, + 1927, 1661, 1660, -1, 1660, 1926, 1927, -1, + 1926, 1660, 1659, -1, 1659, 1925, 1926, -1, + 1925, 1659, 1658, -1, 1658, 1924, 1925, -1, + 1924, 1658, 1657, -1, 1657, 1923, 1924, -1, + 1923, 1657, 1656, -1, 1656, 1922, 1923, -1, + 1922, 1656, 1655, -1, 1655, 1921, 1922, -1, + 1921, 1655, 1654, -1, 1654, 1920, 1921, -1, + 1920, 1654, 1653, -1, 1653, 1919, 1920, -1, + 1919, 1653, 1652, -1, 1652, 1918, 1919, -1, + 1918, 1652, 1651, -1, 1651, 1917, 1918, -1, + 1917, 1651, 1650, -1, 1650, 1916, 1917, -1, + 1916, 1650, 1649, -1, 1649, 1915, 1916, -1, + 1649, 1914, 1915, -1, 1914, 1649, 1648, -1, + 1648, 1913, 1914, -1, 1913, 1648, 1647, -1, + 1647, 1912, 1913, -1, 1912, 1647, 1646, -1, + 1646, 1911, 1912, -1, 1911, 1646, 1645, -1, + 1645, 1910, 1911, -1, 1910, 1645, 1644, -1, + 1644, 1909, 1910, -1, 1909, 1644, 1643, -1, + 1643, 1908, 1909, -1, 1908, 1643, 1642, -1, + 1642, 1907, 1908, -1, 1907, 1642, 1641, -1, + 1641, 1906, 1907, -1, 1906, 1641, 1640, -1, + 1640, 1905, 1906, -1, 1905, 1640, 1639, -1, + 1639, 1904, 1905, -1, 1904, 1639, 1638, -1, + 1638, 1903, 1904, -1, 1903, 1638, 1637, -1, + 1637, 1902, 1903, -1, 1902, 1637, 1636, -1, + 1636, 1901, 1902, -1, 1901, 1636, 1635, -1, + 1635, 1900, 1901, -1, 1900, 1635, 1634, -1, + 1634, 1899, 1900, -1, 1899, 1634, 1633, -1, + 1633, 1898, 1899, -1, 1898, 1633, 1632, -1, + 1632, 1897, 1898, -1, 1897, 1632, 1631, -1, + 1631, 1896, 1897, -1, 1896, 1631, 1630, -1, + 1630, 1895, 1896, -1, 1895, 1630, 1629, -1, + 1629, 1894, 1895, -1, 1894, 1629, 1628, -1, + 1628, 1893, 1894, -1, 1893, 1628, 1627, -1, + 1627, 1892, 1893, -1, 1892, 1627, 1626, -1, + 1626, 1891, 1892, -1, 1891, 1626, 1488, -1, + 1488, 1890, 1891, -1, 1890, 1488, 1487, -1, + 1943, 1890, 1487, -1, 1943, 1944, 1890, -1, + 1944, 1889, 1890, -1, 1944, 1887, 1889, -1, + 1944, 1943, 1887, -1, 1943, 1487, 1887, -1, + 1487, 1486, 1887, -1, 1945, 1887, 1486, -1, + 1946, 1945, 1486, -1, 1486, 1488, 1946, -1, + 1488, 1492, 1946, -1, 1947, 1946, 1492, -1, + 1947, 1945, 1946, -1, 1947, 1948, 1945, -1, + 1948, 1947, 1492, -1, 1948, 1492, 1490, -1, + 1490, 1945, 1948, -1, 1490, 1489, 1945, -1, + 1949, 1945, 1489, -1, 1950, 1949, 1489, -1, + 1489, 1491, 1950, -1, 1491, 1493, 1950, -1, + 1951, 1952, 1493, -1, 1952, 1950, 1493, -1, + 1952, 1949, 1950, -1, 1952, 1951, 1949, -1, + 929, 1949, 1953, -1, 1953, 1954, 1955, -1, + 1954, 1953, 1949, -1, 1954, 1949, 1951, -1, + 1951, 1493, 1954, -1, 1493, 1955, 1954, -1, + 1955, 1493, 1495, -1, 1495, 1956, 1955, -1, + 1956, 1495, 1497, -1, 1497, 1957, 1956, -1, + 1957, 1497, 1499, -1, 1499, 1958, 1957, -1, + 1958, 1499, 1501, -1, 1501, 1959, 1958, -1, + 1959, 1501, 1503, -1, 1503, 1960, 1959, -1, + 1960, 1503, 1505, -1, 1505, 1961, 1960, -1, + 1961, 1505, 1507, -1, 1507, 1962, 1961, -1, + 1962, 1507, 1509, -1, 1509, 1963, 1962, -1, + 1963, 1509, 1511, -1, 1511, 1964, 1963, -1, + 1964, 1511, 1513, -1, 1513, 1965, 1964, -1, + 1965, 1513, 1515, -1, 1515, 1966, 1965, -1, + 1966, 1515, 1517, -1, 1517, 1967, 1966, -1, + 1967, 1517, 1519, -1, 1519, 1968, 1967, -1, + 1968, 1519, 1521, -1, 1521, 1969, 1968, -1, + 1969, 1521, 1523, -1, 1523, 1970, 1969, -1, + 1970, 1523, 1525, -1, 1525, 1971, 1970, -1, + 1971, 1525, 1527, -1, 1527, 1972, 1971, -1, + 1972, 1527, 1529, -1, 1529, 1973, 1972, -1, + 1973, 1529, 1531, -1, 1531, 1974, 1973, -1, + 1974, 1531, 1533, -1, 1533, 1975, 1974, -1, + 1975, 1533, 1535, -1, 1975, 1535, 1538, -1, + 1538, 1976, 1975, -1, 1976, 1538, 1540, -1, + 1540, 1977, 1976, -1, 1977, 1540, 1542, -1, + 1542, 1978, 1977, -1, 1978, 1542, 1544, -1, + 1544, 1979, 1978, -1, 1979, 1544, 1546, -1, + 1546, 1980, 1979, -1, 1980, 1546, 1548, -1, + 1548, 1981, 1980, -1, 1981, 1548, 1550, -1, + 1550, 1982, 1981, -1, 1982, 1550, 1552, -1, + 1552, 1983, 1982, -1, 1983, 1552, 1554, -1, + 1554, 1984, 1983, -1, 1984, 1554, 1556, -1, + 1556, 1985, 1984, -1, 1985, 1556, 1558, -1, + 1558, 1986, 1985, -1, 1986, 1558, 1560, -1, + 1560, 1987, 1986, -1, 1987, 1560, 1562, -1, + 1562, 1988, 1987, -1, 1988, 1562, 1564, -1, + 1564, 1989, 1988, -1, 1989, 1564, 1566, -1, + 1566, 1990, 1989, -1, 1990, 1566, 1568, -1, + 1568, 1991, 1990, -1, 1991, 1568, 1570, -1, + 1570, 1992, 1991, -1, 1992, 1570, 1572, -1, + 1572, 1993, 1992, -1, 1993, 1572, 1574, -1, + 1574, 1994, 1993, -1, 1994, 1574, 1576, -1, + 1576, 1995, 1994, -1, 1996, 1997, 1998, -1, + 1997, 1996, 1999, -1, 1997, 1999, 1994, -1, + 1997, 1994, 1995, -1, 1995, 1998, 1997, -1, + 2000, 1998, 1995, -1, 2000, 1995, 1576, -1, + 2000, 1576, 1577, -1, 1577, 1998, 2000, -1, + 1577, 1578, 1998, -1, 1998, 2001, 2002, -1, + 2001, 1998, 1578, -1, 2001, 1578, 1579, -1, + 2001, 1579, 1581, -1, 1581, 2002, 2001, -1, + 2003, 2002, 1581, -1, 2003, 1581, 1580, -1, + 2003, 1580, 1672, -1, 1672, 2002, 2003, -1, + 1672, 1673, 2002, -1, 2002, 2004, 2005, -1, + 2004, 2002, 1673, -1, 2004, 1673, 1674, -1, + 2004, 1674, 1676, -1, 1676, 2005, 2004, -1, + 2006, 2005, 1676, -1, 2006, 1676, 1675, -1, + 2006, 1675, 1677, -1, 1677, 2005, 2006, -1, + 1677, 1678, 2005, -1, 1678, 1942, 2005, -1, + 1942, 1941, 2005, -1, 2007, 2005, 1941, -1, + 2008, 2007, 1941, -1, 2008, 1941, 1858, -1, + 2008, 1858, 1857, -1, 1857, 2007, 2008, -1, + 1857, 1859, 2007, -1, 1859, 1865, 2007, -1, + 1865, 1866, 2007, -1, 2009, 2007, 1866, -1, + 1866, 2010, 2009, -1, 2010, 1866, 1867, -1, + 2010, 1867, 2011, -1, 2011, 2009, 2010, -1, + 2011, 2012, 2009, -1, 2011, 2013, 2012, -1, + 2013, 2011, 1867, -1, 1867, 2014, 2013, -1, + 2014, 1867, 1868, -1, 1868, 2015, 2014, -1, + 2015, 1868, 1869, -1, 1869, 2016, 2015, -1, + 2016, 1869, 1870, -1, 1870, 2017, 2016, -1, + 2017, 1870, 1871, -1, 1871, 2018, 2017, -1, + 2018, 1871, 1873, -1, 1873, 2019, 2018, -1, + 2019, 1873, 1767, -1, 1767, 1766, 2019, -1, + 1766, 2020, 2019, -1, 2020, 1766, 1764, -1, + 1764, 2021, 2020, -1, 2021, 1764, 1762, -1, + 1762, 2022, 2021, -1, 2022, 1762, 1760, -1, + 1760, 2023, 2022, -1, 2023, 1760, 1758, -1, + 1758, 2024, 2023, -1, 2024, 1758, 1756, -1, + 1756, 2025, 2024, -1, 2025, 1756, 1754, -1, + 1754, 2026, 2025, -1, 2026, 1754, 1752, -1, + 1752, 2027, 2026, -1, 2027, 1752, 1750, -1, + 1750, 2028, 2027, -1, 2028, 1750, 1748, -1, + 1748, 2029, 2028, -1, 2029, 1748, 1746, -1, + 1746, 2030, 2029, -1, 2030, 1746, 1744, -1, + 1744, 2031, 2030, -1, 2031, 1744, 1742, -1, + 1742, 2032, 2031, -1, 2032, 1742, 1740, -1, + 1740, 2033, 2032, -1, 2033, 1740, 1738, -1, + 1738, 2034, 2033, -1, 2034, 1738, 1736, -1, + 1736, 2035, 2034, -1, 2035, 1736, 1734, -1, + 1734, 2036, 2035, -1, 2036, 1734, 1732, -1, + 1732, 2037, 2036, -1, 2037, 1732, 1730, -1, + 1730, 2038, 2037, -1, 2038, 1730, 1728, -1, + 1728, 2039, 2038, -1, 2039, 1728, 1726, -1, + 1726, 2040, 2039, -1, 2040, 1726, 1724, -1, + 1724, 2041, 2040, -1, 2041, 1724, 1723, -1, + 1723, 2042, 2041, -1, 1723, 2043, 2042, -1, + 2043, 1723, 1721, -1, 1721, 2044, 2043, -1, + 2044, 1721, 1719, -1, 1719, 2045, 2044, -1, + 2045, 1719, 1717, -1, 1717, 2046, 2045, -1, + 2046, 1717, 1715, -1, 1715, 2047, 2046, -1, + 2047, 1715, 1713, -1, 1713, 2048, 2047, -1, + 2048, 1713, 1711, -1, 1711, 2049, 2048, -1, + 2049, 1711, 1709, -1, 1709, 2050, 2049, -1, + 2050, 1709, 1707, -1, 1707, 2051, 2050, -1, + 2051, 1707, 1705, -1, 1705, 2052, 2051, -1, + 2052, 1705, 1703, -1, 1703, 2053, 2052, -1, + 2053, 1703, 1701, -1, 1701, 2054, 2053, -1, + 2054, 1701, 1699, -1, 1699, 2055, 2054, -1, + 2055, 1699, 1697, -1, 1697, 2056, 2055, -1, + 2056, 1697, 1695, -1, 1695, 2057, 2056, -1, + 2057, 1695, 1693, -1, 1693, 2058, 2057, -1, + 2058, 1693, 1691, -1, 1691, 2059, 2058, -1, + 2059, 1691, 1689, -1, 1689, 2060, 2059, -1, + 2060, 1689, 1687, -1, 1687, 2061, 2060, -1, + 2061, 1687, 1685, -1, 1685, 2062, 2061, -1, + 2062, 1685, 1683, -1, 1683, 2063, 2062, -1, + 2063, 1683, 1681, -1, 1681, 2064, 2063, -1, + 2064, 1681, 1680, -1, 1680, 2065, 2064, -1, + 2065, 1680, 1874, -1, 1874, 2066, 2065, -1, + 2066, 1874, 1876, -1, 1876, 2067, 2066, -1, + 2067, 1876, 1878, -1, 1878, 1485, 2067, -1, + 1485, 1878, 1880, -1, 1880, 1483, 1485, -1, + 1483, 1880, 1882, -1, 1882, 1480, 1483, -1, + 1882, 1884, 1480, -1, 2068, 1480, 1884, -1, + 1884, 1885, 2068, -1, 2068, 1885, 2069, -1, + 2069, 1480, 2068, -1, 2069, 1481, 1480, -1, + 2069, 1885, 1481, -1, 1476, 1481, 1885, -1, + 2070, 1481, 1476, -1, 2070, 1479, 1481, -1, + 2070, 2071, 1479, -1, 2071, 2070, 1476, -1, + 2071, 1476, 1478, -1, 2071, 1478, 1014, -1, + 1014, 1479, 2071, -1, 1479, 1014, 1017, -1, + 1017, 1482, 1479, -1, 1482, 1017, 1019, -1, + 1019, 1484, 1482, -1, 1484, 1019, 1021, -1, + 1021, 1485, 1484, -1, 1485, 1021, 1023, -1, + 1023, 2067, 1485, -1, 2067, 1023, 1025, -1, + 1025, 2066, 2067, -1, 2066, 1025, 1027, -1, + 1027, 2065, 2066, -1, 2065, 1027, 1029, -1, + 1029, 2064, 2065, -1, 2064, 1029, 1120, -1, + 1120, 2063, 2064, -1, 2063, 1120, 1118, -1, + 1118, 2062, 2063, -1, 2062, 1118, 1116, -1, + 1116, 2061, 2062, -1, 2061, 1116, 1114, -1, + 1114, 2060, 2061, -1, 2060, 1114, 1112, -1, + 1112, 2059, 2060, -1, 2059, 1112, 1110, -1, + 1110, 2058, 2059, -1, 2058, 1110, 1108, -1, + 1108, 2057, 2058, -1, 2057, 1108, 1106, -1, + 1106, 2056, 2057, -1, 2056, 1106, 1104, -1, + 1104, 2055, 2056, -1, 2055, 1104, 1102, -1, + 1102, 2054, 2055, -1, 2054, 1102, 1100, -1, + 1100, 2053, 2054, -1, 2053, 1100, 1098, -1, + 1098, 2052, 2053, -1, 2052, 1098, 1096, -1, + 1096, 2051, 2052, -1, 2051, 1096, 1094, -1, + 1094, 2050, 2051, -1, 2050, 1094, 1092, -1, + 1092, 2049, 2050, -1, 2049, 1092, 1090, -1, + 1090, 2048, 2049, -1, 2048, 1090, 1088, -1, + 1088, 2047, 2048, -1, 2047, 1088, 1086, -1, + 1086, 2046, 2047, -1, 2046, 1086, 1084, -1, + 1084, 2045, 2046, -1, 2045, 1084, 1082, -1, + 1082, 2044, 2045, -1, 2044, 1082, 1080, -1, + 1080, 2043, 2044, -1, 2043, 1080, 1078, -1, + 1078, 2042, 2043, -1, 2042, 1078, 1075, -1, + 2042, 1075, 1073, -1, 1073, 2041, 2042, -1, + 2041, 1073, 1071, -1, 1071, 2040, 2041, -1, + 2040, 1071, 1069, -1, 1069, 2039, 2040, -1, + 2039, 1069, 1067, -1, 1067, 2038, 2039, -1, + 2038, 1067, 1065, -1, 1065, 2037, 2038, -1, + 2037, 1065, 1063, -1, 1063, 2036, 2037, -1, + 2036, 1063, 1061, -1, 1061, 2035, 2036, -1, + 2035, 1061, 1059, -1, 1059, 2034, 2035, -1, + 2034, 1059, 1057, -1, 1057, 2033, 2034, -1, + 2033, 1057, 1055, -1, 1055, 2032, 2033, -1, + 2032, 1055, 1053, -1, 1053, 2031, 2032, -1, + 2031, 1053, 1051, -1, 1051, 2030, 2031, -1, + 2030, 1051, 1049, -1, 1049, 2029, 2030, -1, + 2029, 1049, 1047, -1, 1047, 2028, 2029, -1, + 2028, 1047, 1045, -1, 1045, 2027, 2028, -1, + 2027, 1045, 1043, -1, 1043, 2026, 2027, -1, + 2026, 1043, 1041, -1, 1041, 2025, 2026, -1, + 2025, 1041, 1039, -1, 1039, 2024, 2025, -1, + 2024, 1039, 1037, -1, 1037, 2023, 2024, -1, + 2023, 1037, 1035, -1, 1035, 2022, 2023, -1, + 2022, 1035, 1033, -1, 1033, 2021, 2022, -1, + 2021, 1033, 1030, -1, 1030, 2020, 2021, -1, + 2020, 1030, 1032, -1, 1032, 2019, 2020, -1, + 2019, 1032, 2072, -1, 2072, 2018, 2019, -1, + 2018, 2072, 2073, -1, 2073, 2017, 2018, -1, + 2017, 2073, 2074, -1, 2074, 2016, 2017, -1, + 2016, 2074, 2075, -1, 2075, 2015, 2016, -1, + 2015, 2075, 2076, -1, 2076, 2014, 2015, -1, + 2014, 2076, 2077, -1, 2077, 2013, 2014, -1, + 2013, 2077, 2078, -1, 2078, 2079, 2013, -1, + 2080, 2013, 2079, -1, 2080, 2012, 2013, -1, + 2080, 2009, 2012, -1, 2080, 2079, 2009, -1, + 2081, 2009, 2079, -1, 2082, 2081, 2079, -1, + 2082, 2079, 2078, -1, 2082, 2078, 2083, -1, + 2083, 2081, 2082, -1, 2083, 2084, 2081, -1, + 2083, 2085, 2084, -1, 2085, 2083, 2078, -1, + 2078, 2086, 2085, -1, 2086, 2078, 2077, -1, + 2077, 2087, 2086, -1, 2087, 2077, 2076, -1, + 2076, 2088, 2087, -1, 2088, 2076, 2075, -1, + 2075, 2089, 2088, -1, 2089, 2075, 2074, -1, + 2074, 2090, 2089, -1, 2090, 2074, 2073, -1, + 2073, 2091, 2090, -1, 2091, 2073, 2072, -1, + 2072, 2092, 2091, -1, 2092, 2072, 1032, -1, + 1032, 2093, 2092, -1, 2093, 1032, 1031, -1, + 1031, 2094, 2093, -1, 2094, 1031, 1034, -1, + 1034, 2095, 2094, -1, 2095, 1034, 1036, -1, + 1036, 2096, 2095, -1, 2096, 1036, 1038, -1, + 1038, 2097, 2096, -1, 2097, 1038, 1040, -1, + 1040, 2098, 2097, -1, 2098, 1040, 1042, -1, + 1042, 2099, 2098, -1, 2099, 1042, 1044, -1, + 1044, 2100, 2099, -1, 2100, 1044, 1046, -1, + 1046, 2101, 2100, -1, 2101, 1046, 1048, -1, + 1048, 2102, 2101, -1, 2102, 1048, 1050, -1, + 1050, 2103, 2102, -1, 2103, 1050, 1052, -1, + 1052, 2104, 2103, -1, 2104, 1052, 1054, -1, + 1054, 2105, 2104, -1, 2105, 1054, 1056, -1, + 1056, 2106, 2105, -1, 2106, 1056, 1058, -1, + 1058, 2107, 2106, -1, 2107, 1058, 1060, -1, + 1060, 2108, 2107, -1, 2108, 1060, 1062, -1, + 1062, 2109, 2108, -1, 2109, 1062, 1064, -1, + 1064, 2110, 2109, -1, 2110, 1064, 1066, -1, + 1066, 2111, 2110, -1, 2111, 1066, 1068, -1, + 1068, 2112, 2111, -1, 2112, 1068, 1070, -1, + 1070, 2113, 2112, -1, 2113, 1070, 1072, -1, + 1072, 2114, 2113, -1, 2114, 1072, 1074, -1, + 1074, 2115, 2114, -1, 2115, 1074, 1076, -1, + 1076, 2116, 2115, -1, 1076, 2117, 2116, -1, + 2117, 1076, 1077, -1, 1077, 2118, 2117, -1, + 2118, 1077, 1079, -1, 1079, 2119, 2118, -1, + 2119, 1079, 1081, -1, 1081, 2120, 2119, -1, + 2120, 1081, 1083, -1, 1083, 2121, 2120, -1, + 2121, 1083, 1085, -1, 1085, 2122, 2121, -1, + 2122, 1085, 1087, -1, 1087, 2123, 2122, -1, + 2123, 1087, 1089, -1, 1089, 2124, 2123, -1, + 2124, 1089, 1091, -1, 1091, 2125, 2124, -1, + 2125, 1091, 1093, -1, 1093, 2126, 2125, -1, + 2126, 1093, 1095, -1, 1095, 2127, 2126, -1, + 2127, 1095, 1097, -1, 1097, 2128, 2127, -1, + 2128, 1097, 1099, -1, 1099, 2129, 2128, -1, + 2129, 1099, 1101, -1, 1101, 2130, 2129, -1, + 2130, 1101, 1103, -1, 1103, 2131, 2130, -1, + 2131, 1103, 1105, -1, 1105, 2132, 2131, -1, + 2132, 1105, 1107, -1, 1107, 2133, 2132, -1, + 2133, 1107, 1109, -1, 1109, 2134, 2133, -1, + 2134, 1109, 1111, -1, 1111, 2135, 2134, -1, + 2135, 1111, 1113, -1, 1113, 2136, 2135, -1, + 2136, 1113, 1115, -1, 1115, 2137, 2136, -1, + 2137, 1115, 1117, -1, 1117, 2138, 2137, -1, + 2138, 1117, 1119, -1, 1119, 1121, 2138, -1, + 2138, 1121, 1473, -1, 1473, 2137, 2138, -1, + 2137, 1473, 1472, -1, 1472, 2136, 2137, -1, + 2136, 1472, 1471, -1, 1471, 2135, 2136, -1, + 2135, 1471, 1470, -1, 1470, 2134, 2135, -1, + 2134, 1470, 1469, -1, 1469, 2133, 2134, -1, + 2133, 1469, 1468, -1, 1468, 2132, 2133, -1, + 2132, 1468, 1467, -1, 1467, 2131, 2132, -1, + 2131, 1467, 1466, -1, 1466, 2130, 2131, -1, + 2130, 1466, 1465, -1, 1465, 2129, 2130, -1, + 2129, 1465, 1464, -1, 1464, 2128, 2129, -1, + 2128, 1464, 1463, -1, 1463, 2127, 2128, -1, + 2127, 1463, 1462, -1, 1462, 2126, 2127, -1, + 2126, 1462, 1461, -1, 1461, 2125, 2126, -1, + 2125, 1461, 1460, -1, 1460, 2124, 2125, -1, + 2124, 1460, 1459, -1, 1459, 2123, 2124, -1, + 2123, 1459, 1458, -1, 1458, 2122, 2123, -1, + 2122, 1458, 1457, -1, 1457, 2121, 2122, -1, + 2121, 1457, 1456, -1, 1456, 2120, 2121, -1, + 2120, 1456, 1455, -1, 1455, 2119, 2120, -1, + 2119, 1455, 1454, -1, 1454, 2118, 2119, -1, + 2118, 1454, 1453, -1, 1453, 2117, 2118, -1, + 2117, 1453, 1452, -1, 1452, 2116, 2117, -1, + 2116, 1452, 1451, -1, 2116, 1451, 1450, -1, + 1450, 2115, 2116, -1, 2115, 1450, 1449, -1, + 1449, 2114, 2115, -1, 2114, 1449, 1448, -1, + 1448, 2113, 2114, -1, 2113, 1448, 1447, -1, + 1447, 2112, 2113, -1, 2112, 1447, 1446, -1, + 1446, 2111, 2112, -1, 2111, 1446, 1445, -1, + 1445, 2110, 2111, -1, 2110, 1445, 1444, -1, + 1444, 2109, 2110, -1, 2109, 1444, 1443, -1, + 1443, 2108, 2109, -1, 2108, 1443, 1442, -1, + 1442, 2107, 2108, -1, 2107, 1442, 1441, -1, + 1441, 2106, 2107, -1, 2106, 1441, 1440, -1, + 1440, 2105, 2106, -1, 2105, 1440, 1439, -1, + 1439, 2104, 2105, -1, 2104, 1439, 1438, -1, + 1438, 2103, 2104, -1, 2103, 1438, 1437, -1, + 1437, 2102, 2103, -1, 2102, 1437, 1436, -1, + 1436, 2101, 2102, -1, 2101, 1436, 1435, -1, + 1435, 2100, 2101, -1, 2100, 1435, 1434, -1, + 1434, 2099, 2100, -1, 2099, 1434, 1433, -1, + 1433, 2098, 2099, -1, 2098, 1433, 1432, -1, + 1432, 2097, 2098, -1, 2097, 1432, 1431, -1, + 1431, 2096, 2097, -1, 2096, 1431, 1430, -1, + 1430, 2095, 2096, -1, 2095, 1430, 1429, -1, + 1429, 2094, 2095, -1, 2094, 1429, 1428, -1, + 1428, 2093, 2094, -1, 2093, 1428, 1326, -1, + 1326, 2092, 2093, -1, 2092, 1326, 1328, -1, + 1328, 2091, 2092, -1, 2091, 1328, 1330, -1, + 1330, 2090, 2091, -1, 2090, 1330, 1332, -1, + 1332, 2089, 2090, -1, 2089, 1332, 1334, -1, + 1334, 2088, 2089, -1, 2088, 1334, 1336, -1, + 1336, 2087, 2088, -1, 2087, 1336, 1346, -1, + 1346, 2086, 2087, -1, 2086, 1346, 1344, -1, + 1344, 2085, 2086, -1, 2085, 1344, 1339, -1, + 1339, 1338, 2085, -1, 2139, 2085, 1338, -1, + 2139, 2084, 2085, -1, 2139, 2081, 2084, -1, + 2139, 1338, 2081, -1, 1338, 1337, 2081, -1, + 2140, 2081, 1337, -1, 1337, 1340, 2140, -1, + 1340, 1342, 2140, -1, 2141, 2142, 2143, -1, + 2142, 2141, 2140, -1, 2142, 2140, 1342, -1, + 1342, 1341, 2142, -1, 1341, 2143, 2142, -1, + 1341, 2144, 2143, -1, 2144, 1341, 1343, -1, + 1343, 2145, 2144, -1, 2145, 1343, 1345, -1, + 1345, 2146, 2145, -1, 2146, 1345, 1347, -1, + 1347, 1348, 2146, -1, 2147, 2146, 1348, -1, + 2146, 2147, 2148, -1, 2148, 2145, 2146, -1, + 2145, 2148, 2149, -1, 2149, 2144, 2145, -1, + 2144, 2149, 2150, -1, 2150, 2143, 2144, -1, + 2143, 2150, 2151, -1, 2152, 2153, 2154, -1, + 2155, 2156, 2157, -1, 2155, 2157, 2158, -1, + 2159, 2160, 2161, -1, 2161, 2162, 2159, -1, + 2162, 2161, 2163, -1, 2163, 2164, 2162, -1, + 2164, 2163, 2165, -1, 2165, 2166, 2164, -1, + 2166, 2165, 2167, -1, 2167, 2168, 2166, -1, + 2168, 2167, 2169, -1, 2169, 2170, 2168, -1, + 2170, 2169, 2171, -1, 2171, 2172, 2170, -1, + 2172, 2171, 2173, -1, 2173, 2174, 2172, -1, + 2174, 2173, 2175, -1, 2175, 2176, 2174, -1, + 2176, 2175, 2177, -1, 2177, 2178, 2176, -1, + 2178, 2177, 2179, -1, 2179, 2180, 2178, -1, + 2180, 2179, 2181, -1, 2181, 2182, 2180, -1, + 2182, 2181, 2183, -1, 2183, 2184, 2182, -1, + 2184, 2183, 2185, -1, 2185, 2186, 2184, -1, + 2186, 2185, 2187, -1, 2187, 2188, 2186, -1, + 2188, 2187, 2189, -1, 2189, 2190, 2188, -1, + 2190, 2189, 2191, -1, 2191, 2192, 2190, -1, + 2192, 2191, 2193, -1, 2193, 2194, 2192, -1, + 2194, 2193, 2195, -1, 2195, 2196, 2194, -1, + 2196, 2195, 2197, -1, 2197, 2198, 2196, -1, + 2198, 2197, 2199, -1, 2199, 2200, 2198, -1, + 2200, 2199, 2201, -1, 2201, 2202, 2200, -1, + 2202, 2201, 2203, -1, 2203, 2204, 2202, -1, + 2204, 2203, 2205, -1, 2205, 2157, 2204, -1, + 2205, 2158, 2157, -1, 2205, 2206, 2158, -1, + 2206, 2205, 2203, -1, 2203, 2207, 2206, -1, + 2207, 2203, 2201, -1, 2201, 2208, 2207, -1, + 2208, 2201, 2199, -1, 2199, 2209, 2208, -1, + 2209, 2199, 2197, -1, 2197, 2210, 2209, -1, + 2210, 2197, 2195, -1, 2195, 2211, 2210, -1, + 2211, 2195, 2193, -1, 2193, 2212, 2211, -1, + 2212, 2193, 2191, -1, 2191, 2213, 2212, -1, + 2213, 2191, 2189, -1, 2189, 2214, 2213, -1, + 2214, 2189, 2187, -1, 2187, 2215, 2214, -1, + 2215, 2187, 2185, -1, 2185, 2216, 2215, -1, + 2216, 2185, 2183, -1, 2183, 2217, 2216, -1, + 2217, 2183, 2181, -1, 2181, 2218, 2217, -1, + 2218, 2181, 2179, -1, 2179, 2219, 2218, -1, + 2219, 2179, 2177, -1, 2177, 2220, 2219, -1, + 2220, 2177, 2175, -1, 2175, 2221, 2220, -1, + 2221, 2175, 2173, -1, 2173, 2222, 2221, -1, + 2222, 2173, 2171, -1, 2171, 2223, 2222, -1, + 2223, 2171, 2169, -1, 2169, 2224, 2223, -1, + 2224, 2169, 2167, -1, 2167, 2225, 2224, -1, + 2225, 2167, 2165, -1, 2165, 2226, 2225, -1, + 2226, 2165, 2163, -1, 2163, 2227, 2226, -1, + 2227, 2163, 2161, -1, 2161, 2228, 2227, -1, + 2228, 2161, 2160, -1, 2160, 2229, 2228, -1, + 2229, 2160, 2230, -1, 2230, 2231, 2229, -1, + 2231, 2230, 2232, -1, 2232, 2233, 2231, -1, + 2233, 2232, 2234, -1, 2234, 2235, 2233, -1, + 2235, 2234, 2236, -1, 2236, 2237, 2235, -1, + 2237, 2236, 2238, -1, 2238, 2239, 2237, -1, + 2239, 2238, 2240, -1, 2240, 2241, 2239, -1, + 2241, 2240, 2242, -1, 2242, 2243, 2241, -1, + 2243, 2242, 2244, -1, 2244, 2245, 2243, -1, + 2245, 2244, 2246, -1, 2246, 2247, 2245, -1, + 2247, 2246, 2248, -1, 2248, 2249, 2247, -1, + 2249, 2248, 2250, -1, 2250, 2251, 2249, -1, + 2251, 2250, 2152, -1, 2152, 2154, 2251, -1, + 2252, 2253, 2254, -1, 2255, 2256, 2252, -1, + 2257, 2258, 2255, -1, 2259, 2260, 2261, -1, + 2262, 2263, 2264, -1, 2264, 2265, 2262, -1, + 2265, 2264, 2266, -1, 2266, 2267, 2265, -1, + 2268, 2269, 2270, -1, 2270, 2271, 2268, -1, + 2270, 2272, 2271, -1, 2273, 2274, 2275, -1, + 2276, 2277, 2278, -1, 2276, 2278, 2279, -1, + 2274, 2279, 2278, -1, 2278, 2280, 2274, -1, + 2280, 2278, 2281, -1, 2281, 2282, 2280, -1, + 2282, 2281, 2283, -1, 2284, 2283, 2281, -1, + 2281, 2285, 2284, -1, 2285, 2281, 2278, -1, + 2278, 2277, 2285, -1, 2286, 2287, 2285, -1, + 2286, 2288, 2287, -1, 2286, 2289, 2288, -1, + 2289, 2286, 2285, -1, 2289, 2285, 2277, -1, + 2277, 2288, 2289, -1, 2277, 2276, 2288, -1, + 2290, 2288, 2276, -1, 2276, 2279, 2290, -1, + 2279, 2291, 2290, -1, 2291, 2279, 2274, -1, + 2291, 2274, 2273, -1, 2273, 2290, 2291, -1, + 2273, 2275, 2290, -1, 2275, 2292, 2290, -1, + 2290, 2292, 2293, -1, 2294, 2295, 2296, -1, + 2294, 2296, 2297, -1, 2297, 2298, 2294, -1, + 2297, 2299, 2298, -1, 2299, 2297, 2293, -1, + 2293, 2297, 2296, -1, 2300, 2301, 2302, -1, + 2302, 2303, 2300, -1, 2303, 2302, 2304, -1, + 2304, 2305, 2303, -1, 2305, 2304, 2306, -1, + 2307, 2308, 2309, -1, 2308, 2307, 2310, -1, + 2310, 2311, 2308, -1, 2311, 2310, 2312, -1, + 2312, 2313, 2311, -1, 2314, 2311, 2313, -1, + 2313, 2315, 2314, -1, 2315, 2313, 2316, -1, + 2316, 2317, 2315, -1, 2318, 2319, 2320, -1, + 2319, 2318, 2321, -1, 2321, 2322, 2319, -1, + 2322, 2321, 2323, -1, 2323, 2324, 2322, -1, + 2324, 2323, 2325, -1, 2325, 2326, 2324, -1, + 2326, 2325, 2327, -1, 2327, 2328, 2326, -1, + 2328, 2327, 2329, -1, 2329, 2330, 2328, -1, + 2330, 2329, 2331, -1, 2331, 2332, 2330, -1, + 2332, 2331, 2333, -1, 2333, 2334, 2332, -1, + 2334, 2333, 2335, -1, 2335, 2336, 2334, -1, + 2336, 2335, 2337, -1, 2337, 2338, 2336, -1, + 2338, 2337, 2339, -1, 2339, 2340, 2338, -1, + 2341, 2342, 2343, -1, 2341, 2343, 2344, -1, + 2344, 2345, 2341, -1, 2345, 2344, 2346, -1, + 2346, 2347, 2345, -1, 2347, 2346, 2348, -1, + 2348, 2349, 2347, -1, 2349, 2348, 2350, -1, + 2350, 2351, 2349, -1, 2350, 2352, 2351, -1, + 2353, 2354, 2355, -1, 2355, 2356, 2353, -1, + 2356, 2355, 2357, -1, 2357, 2358, 2356, -1, + 2358, 2357, 2359, -1, 2359, 2360, 2358, -1, + 2360, 2361, 2362, -1, 2362, 2358, 2360, -1, + 2358, 2362, 2363, -1, 2363, 2356, 2358, -1, + 2356, 2363, 2364, -1, 2364, 2353, 2356, -1, + 2364, 2365, 2353, -1, 2364, 2366, 2365, -1, + 2366, 2364, 2363, -1, 2363, 2367, 2366, -1, + 2367, 2363, 2362, -1, 2362, 2368, 2367, -1, + 2368, 2362, 2361, -1, 2361, 2369, 2368, -1, + 2361, 2370, 2369, -1, 2361, 2360, 2370, -1, + 2371, 2372, 2370, -1, 2371, 2370, 2373, -1, + 2370, 2374, 2373, -1, 2374, 2370, 2360, -1, + 2360, 2359, 2374, -1, 2375, 2376, 2377, -1, + 2378, 2379, 2380, -1, 2381, 2382, 2383, -1, + 2381, 2383, 2379, -1, 2379, 2378, 2381, -1, + 2384, 2385, 2381, -1, 2384, 2381, 2378, -1, + 2378, 2386, 2384, -1, 2386, 2378, 2387, -1, + 2387, 2388, 2386, -1, 2388, 2387, 2376, -1, + 2388, 2376, 2375, -1, 2375, 2386, 2388, -1, + 2375, 2377, 2386, -1, 2374, 2386, 2377, -1, + 2386, 2374, 2359, -1, 2359, 2384, 2386, -1, + 2384, 2359, 2357, -1, 2357, 2385, 2384, -1, + 2385, 2357, 2355, -1, 2355, 2389, 2385, -1, + 2389, 2355, 2354, -1, 2354, 2352, 2389, -1, + 2354, 2351, 2352, -1, 2354, 2353, 2351, -1, + 2351, 2353, 2365, -1, 2351, 2365, 2390, -1, + 2390, 2349, 2351, -1, 2349, 2390, 2391, -1, + 2391, 2347, 2349, -1, 2347, 2391, 2392, -1, + 2392, 2345, 2347, -1, 2345, 2392, 2393, -1, + 2393, 2341, 2345, -1, 2341, 2393, 2340, -1, + 2340, 2342, 2341, -1, 2342, 2340, 2339, -1, + 2339, 2394, 2342, -1, 2394, 2339, 2337, -1, + 2337, 2395, 2394, -1, 2395, 2337, 2335, -1, + 2335, 2396, 2395, -1, 2396, 2335, 2333, -1, + 2333, 2397, 2396, -1, 2397, 2333, 2331, -1, + 2331, 2398, 2397, -1, 2398, 2331, 2329, -1, + 2329, 2399, 2398, -1, 2399, 2329, 2327, -1, + 2327, 2400, 2399, -1, 2400, 2327, 2325, -1, + 2325, 2401, 2400, -1, 2401, 2325, 2323, -1, + 2323, 2402, 2401, -1, 2402, 2323, 2321, -1, + 2321, 2403, 2402, -1, 2403, 2321, 2318, -1, + 2318, 2404, 2403, -1, 2404, 2318, 2320, -1, + 2320, 2405, 2404, -1, 2405, 2320, 2406, -1, + 2406, 2407, 2405, -1, 2407, 2406, 2408, -1, + 2408, 2409, 2407, -1, 2409, 2410, 2317, -1, + 2317, 2407, 2409, -1, 2407, 2317, 2316, -1, + 2316, 2405, 2407, -1, 2405, 2316, 2313, -1, + 2313, 2312, 2405, -1, 2312, 2404, 2405, -1, + 2404, 2312, 2310, -1, 2310, 2403, 2404, -1, + 2403, 2310, 2307, -1, 2307, 2402, 2403, -1, + 2402, 2307, 2309, -1, 2309, 2401, 2402, -1, + 2401, 2309, 2411, -1, 2411, 2400, 2401, -1, + 2400, 2411, 2412, -1, 2412, 2399, 2400, -1, + 2399, 2412, 2413, -1, 2413, 2398, 2399, -1, + 2398, 2413, 2414, -1, 2414, 2397, 2398, -1, + 2397, 2414, 2415, -1, 2415, 2396, 2397, -1, + 2396, 2415, 2416, -1, 2416, 2395, 2396, -1, + 2395, 2416, 2417, -1, 2417, 2394, 2395, -1, + 2394, 2417, 2418, -1, 2418, 2342, 2394, -1, + 2418, 2343, 2342, -1, 2418, 2419, 2343, -1, + 2419, 2418, 2417, -1, 2417, 2420, 2419, -1, + 2420, 2417, 2416, -1, 2416, 2421, 2420, -1, + 2421, 2416, 2415, -1, 2415, 2422, 2421, -1, + 2422, 2415, 2414, -1, 2414, 2423, 2422, -1, + 2423, 2414, 2413, -1, 2413, 2424, 2423, -1, + 2424, 2413, 2412, -1, 2412, 2425, 2424, -1, + 2425, 2412, 2411, -1, 2411, 2426, 2425, -1, + 2426, 2411, 2309, -1, 2309, 2306, 2426, -1, + 2306, 2309, 2308, -1, 2308, 2305, 2306, -1, + 2305, 2308, 2311, -1, 2311, 2303, 2305, -1, + 2303, 2311, 2314, -1, 2314, 2300, 2303, -1, + 2300, 2314, 2315, -1, 2315, 2301, 2300, -1, + 2301, 2315, 2317, -1, 2317, 2427, 2301, -1, + 2427, 2317, 2410, -1, 2410, 2428, 2427, -1, + 2428, 2410, 2429, -1, 2429, 2430, 2428, -1, + 2430, 2429, 2431, -1, 2431, 2432, 2430, -1, + 2432, 2431, 2433, -1, 2433, 2434, 2432, -1, + 2434, 2433, 2435, -1, 2435, 2436, 2434, -1, + 2437, 2438, 2436, -1, 2436, 2439, 2437, -1, + 2439, 2436, 2435, -1, 2435, 2440, 2439, -1, + 2440, 2435, 2433, -1, 2433, 2441, 2440, -1, + 2441, 2433, 2431, -1, 2431, 2442, 2441, -1, + 2442, 2431, 2429, -1, 2429, 2443, 2442, -1, + 2443, 2429, 2410, -1, 2410, 2409, 2443, -1, + 2444, 2443, 2409, -1, 2409, 2445, 2444, -1, + 2445, 2409, 2408, -1, 2408, 2446, 2445, -1, + 2446, 2408, 2406, -1, 2406, 2447, 2446, -1, + 2447, 2406, 2320, -1, 2320, 2448, 2447, -1, + 2448, 2320, 2319, -1, 2319, 2449, 2448, -1, + 2449, 2319, 2322, -1, 2322, 2450, 2449, -1, + 2450, 2322, 2324, -1, 2324, 2451, 2450, -1, + 2451, 2324, 2326, -1, 2326, 2452, 2451, -1, + 2452, 2326, 2328, -1, 2328, 2453, 2452, -1, + 2453, 2328, 2330, -1, 2330, 2454, 2453, -1, + 2454, 2330, 2332, -1, 2332, 2455, 2454, -1, + 2455, 2332, 2334, -1, 2334, 2456, 2455, -1, + 2456, 2334, 2336, -1, 2336, 2457, 2456, -1, + 2336, 2338, 2457, -1, 2458, 2459, 2460, -1, + 2458, 2460, 2461, -1, 2461, 2462, 2458, -1, + 2462, 2461, 2463, -1, 2463, 2464, 2462, -1, + 2464, 2463, 2465, -1, 2465, 2466, 2464, -1, + 2466, 2465, 2467, -1, 2467, 2468, 2466, -1, + 2468, 2467, 2469, -1, 2469, 2470, 2468, -1, + 2470, 2469, 2471, -1, 2471, 2472, 2470, -1, + 2472, 2471, 2473, -1, 2473, 2474, 2472, -1, + 2474, 2473, 2475, -1, 2475, 2476, 2474, -1, + 2476, 2475, 2457, -1, 2476, 2457, 2338, -1, + 2476, 2338, 2340, -1, 2340, 2474, 2476, -1, + 2474, 2340, 2393, -1, 2393, 2472, 2474, -1, + 2472, 2393, 2392, -1, 2392, 2470, 2472, -1, + 2470, 2392, 2391, -1, 2391, 2468, 2470, -1, + 2468, 2391, 2390, -1, 2390, 2466, 2468, -1, + 2466, 2390, 2365, -1, 2365, 2464, 2466, -1, + 2464, 2365, 2366, -1, 2366, 2462, 2464, -1, + 2462, 2366, 2367, -1, 2367, 2458, 2462, -1, + 2458, 2367, 2368, -1, 2368, 2459, 2458, -1, + 2459, 2368, 2369, -1, 2459, 2369, 2477, -1, + 2478, 2477, 2369, -1, 2478, 2479, 2477, -1, + 2480, 2481, 2482, -1, 2480, 2482, 2479, -1, + 2479, 2478, 2480, -1, 2480, 2483, 2484, -1, + 2483, 2480, 2478, -1, 2478, 2369, 2483, -1, + 2483, 2369, 2370, -1, 2370, 2372, 2483, -1, + 2485, 2483, 2372, -1, 2372, 2486, 2485, -1, + 2372, 2371, 2486, -1, 2371, 2373, 2486, -1, + 2373, 2487, 2486, -1, 2487, 2373, 2374, -1, + 2487, 2374, 2377, -1, 2487, 2377, 2376, -1, + 2376, 2486, 2487, -1, 2486, 2296, 2488, -1, + 2488, 2485, 2486, -1, 2488, 2483, 2485, -1, + 2488, 2484, 2483, -1, 2484, 2488, 2296, -1, + 2489, 2484, 2296, -1, 2489, 2480, 2484, -1, + 2489, 2481, 2480, -1, 2481, 2489, 2296, -1, + 2481, 2296, 2295, -1, 2295, 2482, 2481, -1, + 2295, 2294, 2482, -1, 2482, 2294, 2298, -1, + 2298, 2490, 2482, -1, 2491, 2492, 2493, -1, + 2492, 2491, 2494, -1, 2494, 2495, 2492, -1, + 2495, 2494, 2496, -1, 2496, 2497, 2495, -1, + 2497, 2496, 2498, -1, 2498, 2499, 2497, -1, + 2499, 2498, 2500, -1, 2500, 2501, 2499, -1, + 2501, 2500, 2502, -1, 2502, 2503, 2501, -1, + 2503, 2502, 2504, -1, 2504, 2505, 2503, -1, + 2505, 2504, 2506, -1, 2506, 2507, 2505, -1, + 2507, 2506, 2508, -1, 2508, 2509, 2507, -1, + 2509, 2508, 2510, -1, 2510, 2511, 2509, -1, + 2511, 2510, 2512, -1, 2512, 2513, 2511, -1, + 2513, 2512, 2514, -1, 2515, 2516, 2517, -1, + 2517, 2518, 2515, -1, 2518, 2517, 2519, -1, + 2519, 2520, 2518, -1, 2520, 2519, 2521, -1, + 2521, 2522, 2520, -1, 2522, 2521, 2523, -1, + 2523, 2524, 2522, -1, 2524, 2523, 2525, -1, + 2525, 2526, 2524, -1, 2526, 2525, 2527, -1, + 2527, 2528, 2526, -1, 2528, 2527, 2529, -1, + 2529, 2530, 2528, -1, 2530, 2529, 2531, -1, + 2531, 2532, 2530, -1, 2532, 2531, 2533, -1, + 2533, 2534, 2532, -1, 2534, 2533, 2535, -1, + 2535, 2536, 2534, -1, 2536, 2535, 2537, -1, + 2537, 2538, 2536, -1, 2538, 2537, 2539, -1, + 2539, 2540, 2538, -1, 2540, 2539, 2541, -1, + 2541, 2542, 2540, -1, 2542, 2541, 2543, -1, + 2543, 2544, 2542, -1, 2544, 2543, 2545, -1, + 2545, 2546, 2544, -1, 2546, 2545, 2547, -1, + 2547, 2548, 2546, -1, 2548, 2547, 2549, -1, + 2549, 2550, 2548, -1, 2550, 2549, 2551, -1, + 2551, 2552, 2550, -1, 2552, 2551, 2553, -1, + 2553, 2554, 2552, -1, 2554, 2553, 2555, -1, + 2555, 2556, 2554, -1, 2556, 2555, 2557, -1, + 2557, 2558, 2556, -1, 2558, 2557, 2559, -1, + 2559, 2560, 2558, -1, 2560, 2559, 2561, -1, + 2561, 2562, 2560, -1, 2562, 2561, 2563, -1, + 2563, 2564, 2562, -1, 2564, 2563, 2565, -1, + 2565, 2566, 2564, -1, 2566, 2565, 2567, -1, + 2567, 2568, 2566, -1, 2568, 2567, 2569, -1, + 2569, 2570, 2568, -1, 2570, 2569, 2571, -1, + 2572, 2571, 2573, -1, 2571, 2572, 2574, -1, + 2574, 2570, 2571, -1, 2570, 2574, 2575, -1, + 2575, 2568, 2570, -1, 2568, 2575, 2576, -1, + 2576, 2566, 2568, -1, 2566, 2576, 2577, -1, + 2577, 2564, 2566, -1, 2564, 2577, 2578, -1, + 2578, 2562, 2564, -1, 2562, 2578, 2579, -1, + 2579, 2560, 2562, -1, 2560, 2579, 2580, -1, + 2580, 2558, 2560, -1, 2558, 2580, 2514, -1, + 2514, 2556, 2558, -1, 2556, 2514, 2512, -1, + 2512, 2554, 2556, -1, 2554, 2512, 2510, -1, + 2510, 2552, 2554, -1, 2552, 2510, 2508, -1, + 2508, 2550, 2552, -1, 2550, 2508, 2506, -1, + 2506, 2548, 2550, -1, 2548, 2506, 2504, -1, + 2504, 2546, 2548, -1, 2546, 2504, 2502, -1, + 2502, 2544, 2546, -1, 2544, 2502, 2500, -1, + 2500, 2542, 2544, -1, 2542, 2500, 2498, -1, + 2498, 2540, 2542, -1, 2540, 2498, 2496, -1, + 2496, 2538, 2540, -1, 2538, 2496, 2494, -1, + 2494, 2536, 2538, -1, 2536, 2494, 2491, -1, + 2491, 2534, 2536, -1, 2491, 2493, 2534, -1, + 2581, 2534, 2493, -1, 2581, 2532, 2534, -1, + 2532, 2581, 2582, -1, 2582, 2530, 2532, -1, + 2530, 2582, 2583, -1, 2583, 2528, 2530, -1, + 2528, 2583, 2584, -1, 2584, 2526, 2528, -1, + 2526, 2584, 2585, -1, 2585, 2524, 2526, -1, + 2524, 2585, 2586, -1, 2586, 2522, 2524, -1, + 2522, 2586, 2587, -1, 2587, 2520, 2522, -1, + 2520, 2587, 2588, -1, 2588, 2518, 2520, -1, + 2518, 2588, 2589, -1, 2589, 2515, 2518, -1, + 2515, 2589, 2490, -1, 2490, 2298, 2515, -1, + 2298, 2299, 2515, -1, 2590, 2515, 2299, -1, + 2590, 2299, 2293, -1, 2590, 2293, 2591, -1, + 2591, 2515, 2590, -1, 2591, 2516, 2515, -1, + 2516, 2591, 2293, -1, 2516, 2293, 2292, -1, + 2292, 2517, 2516, -1, 2292, 2275, 2517, -1, + 2517, 2275, 2274, -1, 2274, 2519, 2517, -1, + 2519, 2274, 2280, -1, 2280, 2521, 2519, -1, + 2521, 2280, 2282, -1, 2282, 2523, 2521, -1, + 2282, 2283, 2523, -1, 2592, 2523, 2283, -1, + 2592, 2525, 2523, -1, 2525, 2592, 2593, -1, + 2593, 2527, 2525, -1, 2593, 2594, 2527, -1, + 2593, 2595, 2594, -1, 2595, 2593, 2592, -1, + 2595, 2592, 2596, -1, 2597, 2598, 2599, -1, + 2598, 2597, 2600, -1, 2600, 2601, 2598, -1, + 2600, 2602, 2601, -1, 2602, 2600, 2596, -1, + 2602, 2596, 2592, -1, 2602, 2592, 2283, -1, + 2283, 2284, 2602, -1, 2284, 2601, 2602, -1, + 2601, 2284, 2285, -1, 2601, 2285, 2287, -1, + 2287, 2598, 2601, -1, 2598, 2287, 2288, -1, + 2288, 2599, 2598, -1, 2603, 2604, 2605, -1, + 2606, 2605, 2604, -1, 2604, 2607, 2606, -1, + 2604, 2603, 2607, -1, 2608, 2609, 2610, -1, + 2610, 2611, 2608, -1, 2611, 2610, 2612, -1, + 2612, 2613, 2611, -1, 2614, 2615, 2616, -1, + 2616, 2617, 2614, -1, 2617, 2616, 2618, -1, + 2618, 2619, 2617, -1, 2620, 2617, 2619, -1, + 2619, 2621, 2620, -1, 2621, 2619, 2622, -1, + 2622, 2623, 2621, -1, 2624, 2625, 2626, -1, + 2626, 2627, 2624, -1, 2627, 2626, 2628, -1, + 2628, 2629, 2627, -1, 2630, 2627, 2629, -1, + 2629, 2631, 2630, -1, 2631, 2629, 2632, -1, + 2632, 2633, 2631, -1, 2634, 2635, 2636, -1, + 2636, 2637, 2634, -1, 2637, 2636, 2638, -1, + 2638, 2639, 2637, -1, 2640, 2641, 2642, -1, + 2642, 2643, 2640, -1, 2643, 2642, 2644, -1, + 2644, 2645, 2643, -1, 2646, 2647, 2648, -1, + 2648, 2649, 2646, -1, 2649, 2648, 2650, -1, + 2650, 2651, 2649, -1, 2652, 2653, 2654, -1, + 2653, 2655, 2654, -1, 2656, 2654, 2655, -1, + 2656, 2657, 2654, -1, 2657, 2656, 2658, -1, + 2658, 2659, 2657, -1, 2659, 2658, 2660, -1, + 2660, 2661, 2659, -1, 2661, 2660, 2662, -1, + 2662, 2663, 2661, -1, 2663, 2662, 2664, -1, + 2664, 2665, 2663, -1, 2665, 2664, 2666, -1, + 2666, 2667, 2665, -1, 2667, 2666, 2668, -1, + 2668, 2669, 2667, -1, 2669, 2668, 2670, -1, + 2670, 2671, 2669, -1, 2671, 2670, 2672, -1, + 2672, 2673, 2671, -1, 2673, 2672, 2674, -1, + 2674, 2675, 2673, -1, 2675, 2674, 2676, -1, + 2676, 2677, 2675, -1, 2677, 2676, 2678, -1, + 2678, 2679, 2677, -1, 2679, 2678, 2680, -1, + 2680, 2681, 2679, -1, 2681, 2680, 2682, -1, + 2682, 2683, 2681, -1, 2683, 2682, 2684, -1, + 2684, 2685, 2683, -1, 2685, 2684, 2686, -1, + 2686, 2687, 2685, -1, 2687, 2686, 2688, -1, + 2688, 2651, 2687, -1, 2651, 2688, 2645, -1, + 2645, 2649, 2651, -1, 2649, 2645, 2644, -1, + 2644, 2646, 2649, -1, 2646, 2644, 2642, -1, + 2642, 2647, 2646, -1, 2647, 2642, 2641, -1, + 2641, 2689, 2647, -1, 2689, 2641, 2690, -1, + 2690, 2691, 2689, -1, 2691, 2690, 2692, -1, + 2692, 2693, 2691, -1, 2694, 2695, 2696, -1, + 2696, 2697, 2698, -1, 2697, 2696, 2695, -1, + 2695, 2699, 2697, -1, 2699, 2695, 2700, -1, + 2700, 2701, 2699, -1, 2701, 2700, 2702, -1, + 2702, 2703, 2701, -1, 2703, 2702, 2704, -1, + 2704, 2705, 2703, -1, 2705, 2704, 2706, -1, + 2706, 2707, 2705, -1, 2707, 2706, 2708, -1, + 2708, 2709, 2707, -1, 2709, 2708, 2710, -1, + 2710, 2711, 2709, -1, 2711, 2710, 2712, -1, + 2712, 2713, 2711, -1, 2713, 2712, 2714, -1, + 2714, 2715, 2713, -1, 2715, 2714, 2716, -1, + 2716, 2717, 2715, -1, 2717, 2716, 2718, -1, + 2718, 2719, 2717, -1, 2719, 2718, 2720, -1, + 2720, 2721, 2719, -1, 2721, 2720, 2722, -1, + 2722, 2723, 2721, -1, 2723, 2722, 2724, -1, + 2724, 2725, 2723, -1, 2725, 2724, 2726, -1, + 2726, 2727, 2725, -1, 2727, 2726, 2728, -1, + 2728, 2729, 2727, -1, 2729, 2728, 2730, -1, + 2730, 2731, 2729, -1, 2731, 2730, 2732, -1, + 2732, 2733, 2731, -1, 2733, 2732, 2734, -1, + 2734, 2735, 2733, -1, 2735, 2734, 2736, -1, + 2736, 2737, 2735, -1, 2737, 2736, 2738, -1, + 2738, 2739, 2737, -1, 2739, 2738, 2740, -1, + 2740, 2741, 2739, -1, 2741, 2740, 2742, -1, + 2742, 2743, 2741, -1, 2743, 2742, 2744, -1, + 2744, 2745, 2743, -1, 2745, 2744, 2746, -1, + 2746, 2747, 2745, -1, 2747, 2746, 2748, -1, + 2748, 2749, 2747, -1, 2749, 2748, 2693, -1, + 2693, 2692, 2749, -1, 2692, 2750, 2749, -1, + 2750, 2692, 2690, -1, 2690, 2639, 2750, -1, + 2639, 2690, 2641, -1, 2641, 2637, 2639, -1, + 2637, 2641, 2640, -1, 2640, 2634, 2637, -1, + 2634, 2640, 2643, -1, 2643, 2635, 2634, -1, + 2635, 2643, 2645, -1, 2645, 2751, 2635, -1, + 2751, 2645, 2688, -1, 2688, 2752, 2751, -1, + 2752, 2688, 2686, -1, 2686, 2753, 2752, -1, + 2753, 2686, 2684, -1, 2684, 2754, 2753, -1, + 2754, 2684, 2682, -1, 2682, 2755, 2754, -1, + 2755, 2682, 2680, -1, 2680, 2756, 2755, -1, + 2756, 2680, 2678, -1, 2678, 2757, 2756, -1, + 2757, 2678, 2676, -1, 2676, 2758, 2757, -1, + 2758, 2676, 2674, -1, 2674, 2759, 2758, -1, + 2759, 2674, 2672, -1, 2672, 2760, 2759, -1, + 2760, 2672, 2670, -1, 2670, 2761, 2760, -1, + 2761, 2670, 2668, -1, 2668, 2762, 2761, -1, + 2762, 2668, 2666, -1, 2666, 2763, 2762, -1, + 2763, 2666, 2664, -1, 2664, 2764, 2763, -1, + 2764, 2664, 2662, -1, 2662, 2765, 2764, -1, + 2765, 2662, 2660, -1, 2660, 2766, 2765, -1, + 2766, 2660, 2658, -1, 2658, 2767, 2766, -1, + 2767, 2658, 2656, -1, 2656, 2768, 2767, -1, + 2769, 2767, 2768, -1, 2769, 2770, 2767, -1, + 2769, 2771, 2770, -1, 2769, 2768, 2771, -1, + 2772, 2773, 2774, -1, 2774, 2773, 2771, -1, + 2775, 2771, 2776, -1, 2776, 2771, 2773, -1, + 2773, 2777, 2776, -1, 2773, 2772, 2777, -1, + 2778, 2779, 2780, -1, 2780, 2781, 2778, -1, + 2781, 2780, 2782, -1, 2782, 2783, 2781, -1, + 2784, 2785, 2786, -1, 2784, 2787, 2785, -1, + 2787, 2784, 2788, -1, 2788, 2789, 2787, -1, + 2789, 2788, 2790, -1, 2790, 2791, 2789, -1, + 2791, 2790, 2792, -1, 2792, 2793, 2791, -1, + 2793, 2792, 2794, -1, 2794, 2795, 2793, -1, + 2795, 2794, 2796, -1, 2796, 2797, 2795, -1, + 2797, 2796, 2798, -1, 2798, 2799, 2797, -1, + 2799, 2798, 2800, -1, 2800, 2801, 2799, -1, + 2801, 2800, 2802, -1, 2802, 2803, 2801, -1, + 2803, 2802, 2804, -1, 2804, 2805, 2803, -1, + 2805, 2804, 2806, -1, 2806, 2807, 2805, -1, + 2807, 2806, 2808, -1, 2808, 2809, 2807, -1, + 2809, 2808, 2810, -1, 2810, 2811, 2809, -1, + 2811, 2810, 2812, -1, 2812, 2813, 2811, -1, + 2813, 2812, 2814, -1, 2814, 2815, 2813, -1, + 2815, 2814, 2816, -1, 2816, 2817, 2815, -1, + 2818, 2819, 2820, -1, 2820, 2821, 2818, -1, + 2821, 2820, 2822, -1, 2823, 2824, 2825, -1, + 2824, 2823, 2822, -1, 2822, 2826, 2824, -1, + 2826, 2822, 2820, -1, 2820, 2827, 2826, -1, + 2827, 2820, 2819, -1, 2819, 2828, 2827, -1, + 2828, 2819, 2829, -1, 2829, 2830, 2828, -1, + 2830, 2829, 2831, -1, 2831, 2832, 2830, -1, + 2832, 2831, 2833, -1, 2833, 2834, 2832, -1, + 2834, 2833, 2835, -1, 2835, 2836, 2834, -1, + 2836, 2835, 2837, -1, 2837, 2838, 2836, -1, + 2838, 2837, 2839, -1, 2839, 2840, 2838, -1, + 2840, 2839, 2841, -1, 2841, 2842, 2840, -1, + 2842, 2841, 2843, -1, 2843, 2844, 2842, -1, + 2844, 2843, 2845, -1, 2845, 2846, 2844, -1, + 2846, 2845, 2847, -1, 2847, 2848, 2846, -1, + 2848, 2847, 2849, -1, 2849, 2850, 2848, -1, + 2850, 2849, 2851, -1, 2851, 2852, 2850, -1, + 2852, 2851, 2853, -1, 2853, 2854, 2852, -1, + 2854, 2853, 2855, -1, 2855, 2856, 2854, -1, + 2856, 2855, 2857, -1, 2857, 2858, 2856, -1, + 2858, 2857, 2859, -1, 2859, 2860, 2858, -1, + 2860, 2859, 2861, -1, 2861, 2862, 2860, -1, + 2862, 2861, 2863, -1, 2863, 2864, 2862, -1, + 2864, 2863, 2865, -1, 2865, 2866, 2864, -1, + 2866, 2865, 2867, -1, 2867, 2868, 2866, -1, + 2868, 2867, 2869, -1, 2869, 2870, 2868, -1, + 2870, 2869, 2871, -1, 2871, 2872, 2870, -1, + 2872, 2871, 2873, -1, 2873, 2874, 2872, -1, + 2874, 2873, 2875, -1, 2875, 2876, 2874, -1, + 2876, 2875, 2877, -1, 2876, 2877, 2878, -1, + 2878, 2879, 2876, -1, 2879, 2878, 2880, -1, + 2880, 2881, 2879, -1, 2881, 2880, 2882, -1, + 2882, 2883, 2881, -1, 2883, 2882, 2884, -1, + 2884, 2885, 2883, -1, 2885, 2884, 2886, -1, + 2886, 2887, 2885, -1, 2887, 2886, 2888, -1, + 2888, 2889, 2887, -1, 2889, 2888, 2890, -1, + 2890, 2891, 2889, -1, 2891, 2890, 2892, -1, + 2892, 2893, 2891, -1, 2893, 2892, 2894, -1, + 2894, 2895, 2893, -1, 2895, 2894, 2896, -1, + 2896, 2897, 2895, -1, 2897, 2896, 2898, -1, + 2898, 2899, 2897, -1, 2899, 2898, 2900, -1, + 2900, 2901, 2899, -1, 2901, 2900, 2902, -1, + 2902, 2903, 2901, -1, 2903, 2902, 2904, -1, + 2904, 2905, 2903, -1, 2905, 2904, 2906, -1, + 2906, 2907, 2905, -1, 2907, 2906, 2908, -1, + 2908, 2909, 2907, -1, 2909, 2908, 2910, -1, + 2910, 2911, 2909, -1, 2911, 2910, 2912, -1, + 2912, 2913, 2911, -1, 2913, 2912, 2914, -1, + 2914, 2915, 2913, -1, 2915, 2914, 2916, -1, + 2916, 2917, 2915, -1, 2917, 2916, 2918, -1, + 2918, 2919, 2917, -1, 2919, 2918, 2920, -1, + 2920, 2921, 2919, -1, 2921, 2920, 2922, -1, + 2922, 2923, 2921, -1, 2923, 2922, 2924, -1, + 2924, 2925, 2923, -1, 2925, 2924, 2926, -1, + 2926, 2927, 2925, -1, 2927, 2926, 2928, -1, + 2928, 2929, 2927, -1, 2929, 2928, 2930, -1, + 2930, 2931, 2929, -1, 2932, 2933, 2934, -1, + 2934, 2931, 2932, -1, 2931, 2934, 2935, -1, + 2935, 2929, 2931, -1, 2929, 2935, 2936, -1, + 2936, 2927, 2929, -1, 2927, 2936, 2937, -1, + 2937, 2925, 2927, -1, 2925, 2937, 2938, -1, + 2938, 2923, 2925, -1, 2923, 2938, 2939, -1, + 2939, 2921, 2923, -1, 2921, 2939, 2940, -1, + 2940, 2919, 2921, -1, 2919, 2940, 2941, -1, + 2941, 2917, 2919, -1, 2917, 2941, 2942, -1, + 2942, 2915, 2917, -1, 2915, 2942, 2943, -1, + 2943, 2913, 2915, -1, 2913, 2943, 2944, -1, + 2944, 2911, 2913, -1, 2911, 2944, 2945, -1, + 2945, 2909, 2911, -1, 2909, 2945, 2946, -1, + 2946, 2907, 2909, -1, 2907, 2946, 2947, -1, + 2947, 2905, 2907, -1, 2905, 2947, 2948, -1, + 2948, 2903, 2905, -1, 2903, 2948, 2949, -1, + 2949, 2901, 2903, -1, 2901, 2949, 2950, -1, + 2950, 2899, 2901, -1, 2899, 2950, 2951, -1, + 2951, 2897, 2899, -1, 2897, 2951, 2952, -1, + 2952, 2895, 2897, -1, 2895, 2952, 2953, -1, + 2953, 2893, 2895, -1, 2893, 2953, 2954, -1, + 2954, 2891, 2893, -1, 2891, 2954, 2955, -1, + 2955, 2889, 2891, -1, 2889, 2955, 2956, -1, + 2956, 2887, 2889, -1, 2887, 2956, 2957, -1, + 2957, 2885, 2887, -1, 2885, 2957, 2958, -1, + 2958, 2883, 2885, -1, 2883, 2958, 2959, -1, + 2959, 2881, 2883, -1, 2881, 2959, 2960, -1, + 2960, 2879, 2881, -1, 2879, 2960, 2961, -1, + 2961, 2876, 2879, -1, 2961, 2874, 2876, -1, + 2874, 2961, 2962, -1, 2962, 2872, 2874, -1, + 2872, 2962, 2963, -1, 2963, 2870, 2872, -1, + 2870, 2963, 2964, -1, 2964, 2868, 2870, -1, + 2868, 2964, 2965, -1, 2965, 2866, 2868, -1, + 2866, 2965, 2966, -1, 2966, 2864, 2866, -1, + 2864, 2966, 2967, -1, 2967, 2862, 2864, -1, + 2862, 2967, 2968, -1, 2968, 2860, 2862, -1, + 2860, 2968, 2969, -1, 2969, 2858, 2860, -1, + 2858, 2969, 2970, -1, 2970, 2856, 2858, -1, + 2856, 2970, 2971, -1, 2971, 2854, 2856, -1, + 2854, 2971, 2972, -1, 2972, 2852, 2854, -1, + 2852, 2972, 2973, -1, 2973, 2850, 2852, -1, + 2850, 2973, 2974, -1, 2974, 2848, 2850, -1, + 2848, 2974, 2975, -1, 2975, 2846, 2848, -1, + 2846, 2975, 2976, -1, 2976, 2844, 2846, -1, + 2844, 2976, 2977, -1, 2977, 2842, 2844, -1, + 2842, 2977, 2978, -1, 2978, 2840, 2842, -1, + 2840, 2978, 2979, -1, 2979, 2838, 2840, -1, + 2838, 2979, 2980, -1, 2980, 2836, 2838, -1, + 2836, 2980, 2981, -1, 2981, 2834, 2836, -1, + 2834, 2981, 2982, -1, 2982, 2832, 2834, -1, + 2832, 2982, 2983, -1, 2983, 2830, 2832, -1, + 2830, 2983, 2984, -1, 2984, 2828, 2830, -1, + 2828, 2984, 2985, -1, 2985, 2827, 2828, -1, + 2827, 2985, 2986, -1, 2986, 2826, 2827, -1, + 2826, 2986, 2987, -1, 2987, 2824, 2826, -1, + 2824, 2987, 2988, -1, 2988, 2825, 2824, -1, + 2825, 2988, 2989, -1, 2989, 2990, 2825, -1, + 2990, 2989, 2991, -1, 2991, 2992, 2990, -1, + 2993, 2994, 2995, -1, 2996, 2997, 2998, -1, + 2997, 2996, 2999, -1, 2997, 2999, 3000, -1, + 3001, 3002, 3003, -1, 3003, 3004, 3001, -1, + 3004, 3003, 3005, -1, 3005, 3006, 3004, -1, + 3006, 3005, 3007, -1, 3007, 3008, 3006, -1, + 3008, 3007, 3009, -1, 3009, 3010, 3008, -1, + 3010, 3009, 3011, -1, 3011, 3012, 3010, -1, + 3012, 3011, 3013, -1, 3013, 3014, 3012, -1, + 3014, 3013, 3015, -1, 3015, 3016, 3014, -1, + 3016, 3015, 3017, -1, 3017, 3018, 3016, -1, + 3018, 3017, 3019, -1, 3019, 3020, 3018, -1, + 3020, 3019, 3021, -1, 3021, 3022, 3020, -1, + 3022, 3021, 3023, -1, 3023, 3024, 3022, -1, + 3024, 3023, 3025, -1, 3025, 3026, 3024, -1, + 3026, 3025, 3027, -1, 3027, 3028, 3026, -1, + 3028, 3027, 3029, -1, 3029, 2999, 3028, -1, + 3029, 3000, 2999, -1, 3029, 3030, 3000, -1, + 3030, 3029, 3027, -1, 3027, 3031, 3030, -1, + 3031, 3027, 3025, -1, 3025, 3032, 3031, -1, + 3032, 3025, 3023, -1, 3023, 3033, 3032, -1, + 3033, 3023, 3021, -1, 3021, 3034, 3033, -1, + 3034, 3021, 3019, -1, 3019, 3035, 3034, -1, + 3035, 3019, 3017, -1, 3017, 3036, 3035, -1, + 3036, 3017, 3015, -1, 3015, 3037, 3036, -1, + 3037, 3015, 3013, -1, 3013, 3038, 3037, -1, + 3038, 3013, 3011, -1, 3011, 3039, 3038, -1, + 3039, 3011, 3009, -1, 3009, 3040, 3039, -1, + 3040, 3009, 3007, -1, 3007, 3041, 3040, -1, + 3041, 3007, 3005, -1, 3005, 3042, 3041, -1, + 3042, 3005, 3003, -1, 3003, 3043, 3042, -1, + 3043, 3003, 3002, -1, 3002, 3044, 3043, -1, + 3045, 3046, 3047, -1, 3048, 3049, 3046, -1, + 3049, 3047, 3046, -1, 3049, 3050, 3047, -1, + 3049, 3048, 3050, -1, 3051, 3052, 3053, -1, + 3052, 3051, 3050, -1, 3052, 3050, 3048, -1, + 3048, 3046, 3052, -1, 3046, 3053, 3052, -1, + 3053, 3046, 3044, -1, 3044, 3002, 3053, -1, + 3054, 3055, 3053, -1, 3054, 3053, 3002, -1, + 3002, 3001, 3054, -1, 3054, 3056, 3057, -1, + 3056, 3054, 3001, -1, 3001, 3058, 3056, -1, + 3058, 3001, 3004, -1, 3004, 3059, 3058, -1, + 3059, 3004, 3006, -1, 3006, 3060, 3059, -1, + 3060, 3006, 3008, -1, 3008, 3061, 3060, -1, + 3061, 3008, 3010, -1, 3010, 3062, 3061, -1, + 3062, 3010, 3012, -1, 3012, 3063, 3062, -1, + 3063, 3012, 3014, -1, 3014, 3064, 3063, -1, + 3064, 3014, 3016, -1, 3016, 3065, 3064, -1, + 3065, 3016, 3018, -1, 3018, 3066, 3065, -1, + 3066, 3018, 3020, -1, 3020, 3067, 3066, -1, + 3067, 3020, 3022, -1, 3022, 3068, 3067, -1, + 3068, 3022, 3024, -1, 3024, 3069, 3068, -1, + 3069, 3024, 3026, -1, 3026, 3070, 3069, -1, + 3070, 3026, 3028, -1, 3028, 3071, 3070, -1, + 3071, 3028, 2999, -1, 2999, 3072, 3071, -1, + 3072, 2999, 2996, -1, 2996, 3073, 3072, -1, + 2996, 2998, 3073, -1, 3074, 3073, 2998, -1, + 3074, 3075, 3073, -1, 3076, 3077, 3078, -1, + 3077, 3076, 3079, -1, 3079, 3080, 3077, -1, + 3080, 3079, 3081, -1, 3081, 3082, 3080, -1, + 3082, 3081, 3075, -1, 3075, 3074, 3082, -1, + 3083, 3082, 3074, -1, 3074, 3084, 3083, -1, + 3084, 3074, 2998, -1, 2998, 3085, 3084, -1, + 3085, 2998, 2997, -1, 2997, 3086, 3085, -1, + 3086, 2997, 3000, -1, 3000, 3087, 3086, -1, + 3087, 3000, 3030, -1, 3030, 3088, 3087, -1, + 3088, 3030, 3031, -1, 3031, 3089, 3088, -1, + 3089, 3031, 3032, -1, 3032, 3090, 3089, -1, + 3090, 3032, 3033, -1, 3033, 3091, 3090, -1, + 3091, 3033, 3034, -1, 3034, 3092, 3091, -1, + 3092, 3034, 3035, -1, 3035, 3093, 3092, -1, + 3093, 3035, 3036, -1, 3036, 3094, 3093, -1, + 3094, 3036, 3037, -1, 3037, 3095, 3094, -1, + 3095, 3037, 3038, -1, 3038, 3096, 3095, -1, + 3096, 3038, 3039, -1, 3039, 3097, 3096, -1, + 3097, 3039, 3040, -1, 3040, 3098, 3097, -1, + 3098, 3040, 3041, -1, 3041, 3099, 3098, -1, + 3099, 3041, 3042, -1, 3042, 3100, 3099, -1, + 3100, 3042, 3043, -1, 3043, 3101, 3100, -1, + 3101, 3043, 3044, -1, 3044, 3102, 3101, -1, + 3102, 3044, 3046, -1, 3046, 3045, 3102, -1, + 2259, 3045, 3103, -1, 3045, 2259, 3104, -1, + 3104, 3102, 3045, -1, 3102, 3104, 3105, -1, + 3105, 3101, 3102, -1, 3101, 3105, 3106, -1, + 3106, 3100, 3101, -1, 3100, 3106, 3107, -1, + 3107, 3099, 3100, -1, 3099, 3107, 3108, -1, + 3108, 3098, 3099, -1, 3098, 3108, 3109, -1, + 3109, 3097, 3098, -1, 3097, 3109, 3110, -1, + 3110, 3096, 3097, -1, 3096, 3110, 3111, -1, + 3111, 3095, 3096, -1, 3095, 3111, 3112, -1, + 3112, 3094, 3095, -1, 3094, 3112, 3113, -1, + 3113, 3093, 3094, -1, 3093, 3113, 3114, -1, + 3114, 3092, 3093, -1, 3092, 3114, 3115, -1, + 3115, 3091, 3092, -1, 3091, 3115, 3116, -1, + 3116, 3090, 3091, -1, 3090, 3116, 3117, -1, + 3117, 3089, 3090, -1, 3089, 3117, 3118, -1, + 3118, 3088, 3089, -1, 3088, 3118, 3119, -1, + 3119, 3087, 3088, -1, 3087, 3119, 3120, -1, + 3120, 3086, 3087, -1, 3086, 3120, 3121, -1, + 3121, 3085, 3086, -1, 3085, 3121, 3122, -1, + 3122, 3084, 3085, -1, 3084, 3122, 3123, -1, + 3123, 3083, 3084, -1, 3083, 3123, 3124, -1, + 3124, 3082, 3083, -1, 3082, 3124, 3125, -1, + 3125, 3080, 3082, -1, 3080, 3125, 3126, -1, + 3126, 3077, 3080, -1, 3077, 3126, 3127, -1, + 3127, 3078, 3077, -1, 3128, 3129, 3130, -1, + 3129, 3128, 3078, -1, 3078, 3127, 3129, -1, + 3129, 3127, 3131, -1, 3131, 3130, 3129, -1, + 3132, 3133, 3134, -1, 3133, 3132, 3130, -1, + 3130, 3131, 3133, -1, 3133, 3131, 3135, -1, + 3135, 3134, 3133, -1, 3134, 3135, 3136, -1, + 3136, 3137, 3134, -1, 3137, 3136, 3138, -1, + 3138, 3139, 3137, -1, 3139, 3138, 3140, -1, + 3140, 3141, 3139, -1, 3142, 3143, 3144, -1, + 3144, 3145, 3142, -1, 3145, 3144, 3146, -1, + 3146, 3147, 3145, -1, 3147, 3146, 3148, -1, + 3148, 3149, 3147, -1, 3149, 3148, 3150, -1, + 3150, 3151, 3149, -1, 3151, 3150, 3152, -1, + 3152, 3153, 3151, -1, 3153, 3152, 3154, -1, + 3154, 3155, 3153, -1, 3156, 3157, 3158, -1, + 3158, 3159, 3156, -1, 3158, 3160, 3159, -1, + 3161, 3159, 3160, -1, 3161, 3162, 3159, -1, + 3161, 3163, 3162, -1, 3161, 3160, 3163, -1, + 3164, 3165, 3166, -1, 3165, 3164, 3167, -1, + 3167, 3168, 3165, -1, 3169, 3170, 3171, -1, + 3170, 3169, 3172, -1, 3172, 3173, 3170, -1, + 3173, 3172, 3174, -1, 3174, 3175, 3173, -1, + 3175, 3174, 3176, -1, 3176, 3177, 3175, -1, + 3177, 3176, 3178, -1, 3179, 3180, 3181, -1, + 3180, 3179, 3182, -1, 3182, 3183, 3180, -1, + 3183, 3182, 3184, -1, 3184, 3185, 3183, -1, + 3185, 3184, 3186, -1, 3186, 3187, 3185, -1, + 3187, 3186, 3188, -1, 3189, 3190, 3191, -1, + 3190, 3189, 3192, -1, 3192, 3193, 3190, -1, + 3193, 3192, 3194, -1, 3194, 3195, 3193, -1, + 3196, 3197, 3198, -1, 3198, 3199, 3196, -1, + 3199, 3198, 3200, -1, 3200, 3201, 3199, -1, + 3201, 3200, 3202, -1, 3202, 3203, 3201, -1, + 3203, 3202, 3204, -1, 3204, 3205, 3203, -1, + 3205, 3204, 3206, -1, 3206, 3207, 3205, -1, + 3207, 3206, 3208, -1, 3208, 3209, 3207, -1, + 3209, 3208, 3195, -1, 3195, 3194, 3209, -1, + 3194, 3210, 3209, -1, 3210, 3194, 3192, -1, + 3192, 3211, 3210, -1, 3211, 3192, 3189, -1, + 3189, 3212, 3211, -1, 3212, 3189, 3191, -1, + 3191, 3213, 3212, -1, 3213, 3191, 3214, -1, + 3215, 3216, 3217, -1, 3216, 3215, 3218, -1, + 3218, 3219, 3216, -1, 3219, 3218, 3220, -1, + 3220, 3221, 3219, -1, 3222, 3223, 3224, -1, + 3224, 3225, 3222, -1, 3226, 3227, 3228, -1, + 3227, 3226, 3225, -1, 3225, 3224, 3227, -1, + 3229, 3227, 3224, -1, 3224, 3230, 3229, -1, + 3230, 3224, 3223, -1, 3223, 3231, 3230, -1, + 3232, 3233, 3231, -1, 3231, 3234, 3232, -1, + 3234, 3231, 3223, -1, 3223, 3222, 3234, -1, + 3222, 3221, 3234, -1, 3221, 3222, 3225, -1, + 3225, 3219, 3221, -1, 3219, 3225, 3226, -1, + 3226, 3216, 3219, -1, 3216, 3226, 3228, -1, + 3228, 3217, 3216, -1, 3217, 3228, 3235, -1, + 3235, 3236, 3217, -1, 3236, 3235, 3237, -1, + 3237, 3238, 3236, -1, 3238, 3237, 3239, -1, + 3239, 3240, 3238, -1, 3240, 3239, 3241, -1, + 3241, 3242, 3240, -1, 3242, 3241, 3243, -1, + 3243, 3244, 3242, -1, 3245, 3246, 3247, -1, + 3247, 3248, 3245, -1, 3248, 3247, 3249, -1, + 3249, 3250, 3248, -1, 3251, 3252, 3253, -1, + 3253, 3250, 3251, -1, 3250, 3253, 3254, -1, + 3254, 3248, 3250, -1, 3248, 3254, 3255, -1, + 3255, 3245, 3248, -1, 3245, 3255, 3256, -1, + 3256, 3246, 3245, -1, 3257, 3246, 3258, -1, + 3258, 3259, 3257, -1, 3259, 3258, 3260, -1, + 3260, 3261, 3259, -1, 3262, 3263, 3261, -1, + 3261, 3264, 3262, -1, 3264, 3261, 3260, -1, + 3260, 3265, 3264, -1, 3265, 3260, 3258, -1, + 3258, 3266, 3265, -1, 3266, 3258, 3246, -1, + 3246, 3256, 3266, -1, 3267, 3266, 3256, -1, + 3256, 3268, 3267, -1, 3268, 3256, 3255, -1, + 3255, 3269, 3268, -1, 3269, 3255, 3254, -1, + 3254, 3270, 3269, -1, 3270, 3254, 3253, -1, + 3253, 3252, 3270, -1, 3271, 3272, 3273, -1, + 3272, 3271, 3274, -1, 3274, 3275, 3272, -1, + 3275, 3274, 3276, -1, 3276, 3277, 3275, -1, + 3277, 3276, 3278, -1, 3278, 3279, 3277, -1, + 3279, 3278, 3280, -1, 3281, 3282, 3283, -1, + 3282, 3281, 3284, -1, 3284, 3285, 3282, -1, + 3285, 3284, 3286, -1, 3286, 3287, 3285, -1, + 3287, 3286, 3288, -1, 3288, 3289, 3287, -1, + 3289, 3288, 3290, -1, 3291, 3292, 3293, -1, + 3292, 3291, 3294, -1, 3294, 3295, 3292, -1, + 3295, 3294, 3296, -1, 3296, 3297, 3295, -1, + 3297, 3296, 3298, -1, 3298, 3299, 3297, -1, + 3300, 3301, 3302, -1, 3301, 3300, 3303, -1, + 3303, 3304, 3301, -1, 3304, 3303, 3305, -1, + 3305, 3306, 3304, -1, 3306, 3305, 3307, -1, + 3307, 3308, 3306, -1, 3308, 3307, 3299, -1, + 3299, 3298, 3308, -1, 3309, 3310, 3311, -1, + 3312, 3313, 3314, -1, 3314, 3315, 3312, -1, + 3315, 3314, 3316, -1, 3316, 3317, 3315, -1, + 3317, 3316, 3318, -1, 3318, 3319, 3317, -1, + 3317, 3319, 3320, -1, 3320, 3315, 3317, -1, + 3315, 3320, 3310, -1, 3310, 3312, 3315, -1, + 3312, 3310, 3309, -1, 3309, 3313, 3312, -1, + 3313, 3309, 3321, -1, 3321, 3322, 3313, -1, + 3323, 3313, 3322, -1, 3322, 3324, 3323, -1, + 3324, 3322, 3325, -1, 3325, 3326, 3324, -1, + 3327, 3328, 3329, -1, 3328, 3327, 3326, -1, + 3326, 3325, 3328, -1, 3325, 3330, 3328, -1, + 3330, 3325, 3322, -1, 3322, 3321, 3330, -1, + 3331, 3330, 3321, -1, 3321, 3332, 3331, -1, + 3332, 3321, 3309, -1, 3309, 3311, 3332, -1, + 3333, 3332, 3311, -1, 3311, 3334, 3333, -1, + 3335, 3336, 3334, -1, 3334, 3311, 3335, -1, + 3335, 3311, 3310, -1, 3335, 3310, 3320, -1, + 3320, 3336, 3335, -1, 3336, 3320, 3319, -1, + 3319, 3337, 3336, -1, 3337, 3319, 3338, -1, + 3338, 3339, 3337, -1, 3340, 3341, 3339, -1, + 3339, 3338, 3340, -1, 3338, 3342, 3340, -1, + 3342, 3338, 3319, -1, 3319, 3318, 3342, -1, + 3343, 3342, 3318, -1, 3318, 3344, 3343, -1, + 3344, 3318, 3316, -1, 3316, 3345, 3344, -1, + 3345, 3316, 3314, -1, 3314, 3346, 3345, -1, + 3346, 3314, 3313, -1, 3313, 3323, 3346, -1, + 3298, 3346, 3323, -1, 3323, 3308, 3298, -1, + 3308, 3323, 3324, -1, 3324, 3306, 3308, -1, + 3306, 3324, 3326, -1, 3326, 3304, 3306, -1, + 3304, 3326, 3327, -1, 3327, 3301, 3304, -1, + 3301, 3327, 3329, -1, 3329, 3302, 3301, -1, + 3302, 3329, 3347, -1, 3347, 3348, 3302, -1, + 3348, 3347, 3349, -1, 3349, 3350, 3348, -1, + 3350, 3349, 3290, -1, 3290, 3280, 3350, -1, + 3280, 3290, 3288, -1, 3288, 3279, 3280, -1, + 3279, 3288, 3286, -1, 3286, 3277, 3279, -1, + 3277, 3286, 3284, -1, 3284, 3275, 3277, -1, + 3275, 3284, 3281, -1, 3281, 3272, 3275, -1, + 3272, 3281, 3283, -1, 3283, 3273, 3272, -1, + 3273, 3283, 3351, -1, 3351, 3352, 3273, -1, + 3352, 3351, 3353, -1, 3353, 3354, 3352, -1, + 3354, 3353, 3355, -1, 3355, 3356, 3354, -1, + 3356, 3355, 3357, -1, 3357, 3358, 3356, -1, + 3358, 3357, 3359, -1, 3359, 3360, 3358, -1, + 3360, 3359, 3361, -1, 3361, 3362, 3360, -1, + 3362, 3361, 3363, -1, 3363, 3364, 3362, -1, + 3364, 3363, 3365, -1, 3365, 3366, 3364, -1, + 3366, 3365, 3367, -1, 3367, 3368, 3366, -1, + 3368, 3367, 3369, -1, 3369, 3370, 3368, -1, + 3370, 3369, 3371, -1, 3371, 3372, 3370, -1, + 3372, 3371, 3373, -1, 3373, 3374, 3372, -1, + 3374, 3373, 3375, -1, 3375, 3376, 3374, -1, + 3376, 3375, 3377, -1, 3377, 3378, 3376, -1, + 3378, 3377, 3379, -1, 3379, 3380, 3378, -1, + 3380, 3379, 3381, -1, 3381, 3382, 3380, -1, + 3382, 3381, 3383, -1, 3383, 3384, 3382, -1, + 3384, 3383, 3385, -1, 3385, 3386, 3384, -1, + 3385, 3387, 3386, -1, 3387, 3385, 3388, -1, + 3388, 3389, 3387, -1, 3389, 3388, 3390, -1, + 3390, 3391, 3389, -1, 3391, 3390, 3392, -1, + 3392, 3393, 3391, -1, 3393, 3392, 3394, -1, + 3394, 3395, 3393, -1, 3395, 3394, 3396, -1, + 3396, 3397, 3395, -1, 3397, 3396, 3398, -1, + 3398, 3399, 3397, -1, 3399, 3398, 3400, -1, + 3400, 3401, 3399, -1, 3401, 3400, 3402, -1, + 3402, 3403, 3401, -1, 3403, 3402, 3404, -1, + 3404, 3405, 3403, -1, 3405, 3404, 3406, -1, + 3406, 3407, 3405, -1, 3407, 3406, 3408, -1, + 3408, 3409, 3407, -1, 3409, 3408, 3410, -1, + 3410, 3411, 3409, -1, 3411, 3410, 3412, -1, + 3412, 3413, 3411, -1, 3413, 3412, 3414, -1, + 3414, 3415, 3413, -1, 3415, 3414, 3416, -1, + 3416, 3417, 3415, -1, 3417, 3416, 3418, -1, + 3418, 3419, 3417, -1, 3419, 3418, 3420, -1, + 3420, 3421, 3419, -1, 3421, 3420, 3422, -1, + 3422, 3423, 3421, -1, 3424, 3252, 3425, -1, + 3425, 3426, 3424, -1, 3426, 3425, 3427, -1, + 3427, 3428, 3426, -1, 3428, 3427, 3429, -1, + 3429, 3430, 3428, -1, 3430, 3429, 3431, -1, + 3431, 3432, 3430, -1, 3432, 3431, 3433, -1, + 3433, 3434, 3432, -1, 3434, 3433, 3435, -1, + 3435, 3436, 3434, -1, 3436, 3435, 3423, -1, + 3423, 3422, 3436, -1, 3436, 3422, 3437, -1, + 3437, 3434, 3436, -1, 3434, 3437, 3438, -1, + 3438, 3432, 3434, -1, 3432, 3438, 3439, -1, + 3439, 3430, 3432, -1, 3430, 3439, 3440, -1, + 3440, 3428, 3430, -1, 3428, 3440, 3441, -1, + 3441, 3426, 3428, -1, 3426, 3441, 3442, -1, + 3442, 3424, 3426, -1, 3424, 3442, 3443, -1, + 3443, 3252, 3424, -1, 3252, 3443, 3244, -1, + 3244, 3270, 3252, -1, 3270, 3244, 3243, -1, + 3243, 3269, 3270, -1, 3269, 3243, 3241, -1, + 3241, 3268, 3269, -1, 3268, 3241, 3239, -1, + 3239, 3267, 3268, -1, 3267, 3239, 3237, -1, + 3237, 3266, 3267, -1, 3266, 3237, 3235, -1, + 3235, 3265, 3266, -1, 3265, 3235, 3228, -1, + 3228, 3264, 3265, -1, 3264, 3228, 3227, -1, + 3227, 3229, 3264, -1, 3229, 3262, 3264, -1, + 3262, 3229, 3230, -1, 3230, 3263, 3262, -1, + 3263, 3230, 3231, -1, 3231, 3444, 3263, -1, + 3444, 3231, 3233, -1, 3233, 3445, 3444, -1, + 3446, 3447, 3448, -1, 3448, 3449, 3446, -1, + 3450, 3451, 3452, -1, 3451, 3450, 3453, -1, + 3453, 3454, 3451, -1, 3454, 3453, 3455, -1, + 3456, 3457, 3458, -1, 3457, 3456, 3459, -1, + 3459, 3460, 3457, -1, 3460, 3459, 3461, -1, + 3462, 3449, 3461, -1, 3463, 3464, 3465, -1, + 3466, 3467, 3468, -1, 3468, 3469, 3466, -1, + 3469, 3468, 3464, -1, 3464, 3463, 3469, -1, + 3463, 3462, 3469, -1, 3463, 3470, 3462, -1, + 3470, 3463, 3465, -1, 3465, 3471, 3470, -1, + 3471, 3465, 3472, -1, 3472, 3473, 3471, -1, + 3473, 3472, 3474, -1, 3474, 3475, 3473, -1, + 3476, 3477, 3475, -1, 3475, 3478, 3476, -1, + 3478, 3475, 3474, -1, 3474, 3479, 3478, -1, + 3479, 3474, 3472, -1, 3472, 3480, 3479, -1, + 3480, 3472, 3465, -1, 3465, 3481, 3480, -1, + 3481, 3465, 3464, -1, 3464, 3482, 3481, -1, + 3482, 3464, 3468, -1, 3468, 3483, 3482, -1, + 3483, 3468, 3467, -1, 3467, 3484, 3483, -1, + 3484, 3467, 3485, -1, 3486, 3487, 3485, -1, + 3485, 3488, 3486, -1, 3488, 3485, 3467, -1, + 3467, 3466, 3488, -1, 3466, 3489, 3488, -1, + 3489, 3466, 3469, -1, 3489, 3469, 3462, -1, + 3489, 3462, 3461, -1, 3461, 3488, 3489, -1, + 3488, 3461, 3459, -1, 3459, 3486, 3488, -1, + 3486, 3459, 3456, -1, 3456, 3487, 3486, -1, + 3487, 3456, 3458, -1, 3458, 3490, 3487, -1, + 3491, 3492, 3490, -1, 3490, 3493, 3491, -1, + 3493, 3490, 3458, -1, 3458, 3455, 3493, -1, + 3455, 3458, 3457, -1, 3457, 3454, 3455, -1, + 3454, 3457, 3460, -1, 3460, 3451, 3454, -1, + 3451, 3460, 3461, -1, 3461, 3452, 3451, -1, + 3452, 3461, 3449, -1, 3449, 3448, 3452, -1, + 3448, 3494, 3452, -1, 3494, 3448, 3447, -1, + 3447, 3495, 3494, -1, 3496, 3497, 3498, -1, + 3498, 3499, 3496, -1, 3499, 3498, 3500, -1, + 3500, 3501, 3499, -1, 3502, 3503, 3504, -1, + 3505, 3506, 3507, -1, 3506, 3505, 3508, -1, + 3508, 3509, 3506, -1, 3509, 3508, 3510, -1, + 3510, 3511, 3509, -1, 3511, 3510, 3503, -1, + 3503, 3502, 3511, -1, 3501, 3511, 3502, -1, + 3511, 3501, 3500, -1, 3500, 3509, 3511, -1, + 3509, 3500, 3498, -1, 3498, 3506, 3509, -1, + 3506, 3498, 3497, -1, 3497, 3507, 3506, -1, + 3507, 3497, 3512, -1, 3512, 3513, 3507, -1, + 3513, 3512, 3514, -1, 3514, 3515, 3513, -1, + 3515, 3514, 3516, -1, 3516, 3517, 3515, -1, + 3517, 3516, 3518, -1, 3518, 3519, 3517, -1, + 3519, 3518, 3520, -1, 3520, 3521, 3519, -1, + 3521, 3520, 3522, -1, 3522, 3523, 3521, -1, + 3523, 3522, 3524, -1, 3524, 3525, 3523, -1, + 3526, 3527, 3525, -1, 3525, 3528, 3526, -1, + 3528, 3525, 3524, -1, 3524, 3529, 3528, -1, + 3529, 3524, 3522, -1, 3522, 3530, 3529, -1, + 3530, 3522, 3520, -1, 3520, 3531, 3530, -1, + 3531, 3520, 3518, -1, 3518, 3532, 3531, -1, + 3532, 3518, 3516, -1, 3516, 3533, 3532, -1, + 3533, 3516, 3514, -1, 3514, 3495, 3533, -1, + 3495, 3514, 3512, -1, 3512, 3494, 3495, -1, + 3494, 3512, 3497, -1, 3497, 3496, 3494, -1, + 3496, 3452, 3494, -1, 3452, 3496, 3499, -1, + 3499, 3450, 3452, -1, 3450, 3499, 3501, -1, + 3501, 3453, 3450, -1, 3453, 3501, 3502, -1, + 3502, 3455, 3453, -1, 3455, 3502, 3504, -1, + 3504, 3493, 3455, -1, 3493, 3504, 3534, -1, + 3534, 3491, 3493, -1, 3491, 3534, 3535, -1, + 3535, 3492, 3491, -1, 3492, 3535, 3536, -1, + 3536, 3537, 3492, -1, 3537, 3536, 3538, -1, + 3538, 3539, 3537, -1, 3539, 3538, 3540, -1, + 3540, 3541, 3539, -1, 3541, 3540, 3542, -1, + 3542, 3543, 3541, -1, 3543, 3542, 3544, -1, + 3544, 3545, 3543, -1, 3545, 3544, 3546, -1, + 3546, 3547, 3545, -1, 3547, 3546, 3548, -1, + 3548, 3549, 3547, -1, 3549, 3548, 3550, -1, + 3550, 3551, 3549, -1, 3551, 3550, 3552, -1, + 3552, 3553, 3551, -1, 3553, 3552, 3554, -1, + 3554, 3555, 3553, -1, 3555, 3554, 3556, -1, + 3556, 3557, 3555, -1, 3557, 3556, 3558, -1, + 3558, 3559, 3557, -1, 3559, 3560, 3561, -1, + 3561, 3557, 3559, -1, 3557, 3561, 3562, -1, + 3562, 3555, 3557, -1, 3555, 3562, 3563, -1, + 3563, 3553, 3555, -1, 3553, 3563, 3564, -1, + 3564, 3551, 3553, -1, 3551, 3564, 3565, -1, + 3565, 3549, 3551, -1, 3549, 3565, 3566, -1, + 3566, 3547, 3549, -1, 3547, 3566, 3567, -1, + 3567, 3545, 3547, -1, 3545, 3567, 3568, -1, + 3568, 3543, 3545, -1, 3543, 3568, 3569, -1, + 3569, 3541, 3543, -1, 3541, 3569, 3570, -1, + 3570, 3539, 3541, -1, 3539, 3570, 3571, -1, + 3571, 3537, 3539, -1, 3537, 3571, 3572, -1, + 3572, 3492, 3537, -1, 3492, 3572, 3445, -1, + 3445, 3490, 3492, -1, 3490, 3445, 3233, -1, + 3233, 3232, 3490, -1, 3232, 3487, 3490, -1, + 3487, 3232, 3234, -1, 3234, 3485, 3487, -1, + 3485, 3234, 3221, -1, 3221, 3484, 3485, -1, + 3484, 3221, 3220, -1, 3220, 3483, 3484, -1, + 3483, 3220, 3218, -1, 3218, 3482, 3483, -1, + 3482, 3218, 3215, -1, 3215, 3481, 3482, -1, + 3481, 3215, 3217, -1, 3217, 3480, 3481, -1, + 3480, 3217, 3236, -1, 3236, 3479, 3480, -1, + 3479, 3236, 3238, -1, 3238, 3478, 3479, -1, + 3478, 3238, 3240, -1, 3240, 3476, 3478, -1, + 3476, 3240, 3242, -1, 3242, 3477, 3476, -1, + 3477, 3242, 3244, -1, 3244, 3573, 3477, -1, + 3574, 3575, 3576, -1, 3576, 3577, 3574, -1, + 3577, 3576, 3578, -1, 3578, 3579, 3577, -1, + 3579, 3578, 3580, -1, 3580, 3581, 3579, -1, + 3581, 3580, 3582, -1, 3582, 3583, 3581, -1, + 3583, 3582, 3584, -1, 3584, 3585, 3583, -1, + 3585, 3584, 3586, -1, 3586, 3587, 3585, -1, + 3587, 3586, 3573, -1, 3573, 3244, 3587, -1, + 3587, 3244, 3443, -1, 3443, 3585, 3587, -1, + 3585, 3443, 3442, -1, 3442, 3583, 3585, -1, + 3583, 3442, 3441, -1, 3441, 3581, 3583, -1, + 3581, 3441, 3440, -1, 3440, 3579, 3581, -1, + 3579, 3440, 3439, -1, 3439, 3577, 3579, -1, + 3577, 3439, 3438, -1, 3438, 3574, 3577, -1, + 3574, 3438, 3437, -1, 3437, 3575, 3574, -1, + 3575, 3437, 3422, -1, 3422, 3588, 3575, -1, + 3588, 3422, 3420, -1, 3420, 3589, 3588, -1, + 3589, 3420, 3418, -1, 3418, 3590, 3589, -1, + 3590, 3418, 3416, -1, 3416, 3591, 3590, -1, + 3591, 3416, 3414, -1, 3414, 3592, 3591, -1, + 3592, 3414, 3412, -1, 3412, 3593, 3592, -1, + 3593, 3412, 3410, -1, 3410, 3594, 3593, -1, + 3594, 3410, 3408, -1, 3408, 3595, 3594, -1, + 3595, 3408, 3406, -1, 3406, 3596, 3595, -1, + 3596, 3406, 3404, -1, 3404, 3597, 3596, -1, + 3597, 3404, 3402, -1, 3402, 3598, 3597, -1, + 3598, 3402, 3400, -1, 3400, 3599, 3598, -1, + 3599, 3400, 3398, -1, 3398, 3600, 3599, -1, + 3600, 3398, 3396, -1, 3396, 3601, 3600, -1, + 3601, 3396, 3394, -1, 3394, 3602, 3601, -1, + 3602, 3394, 3392, -1, 3392, 3603, 3602, -1, + 3603, 3392, 3390, -1, 3390, 3604, 3603, -1, + 3604, 3390, 3388, -1, 3388, 3605, 3604, -1, + 3605, 3388, 3385, -1, 3605, 3385, 3383, -1, + 3383, 3606, 3605, -1, 3606, 3383, 3381, -1, + 3381, 3607, 3606, -1, 3607, 3381, 3379, -1, + 3379, 3608, 3607, -1, 3608, 3379, 3377, -1, + 3377, 3609, 3608, -1, 3609, 3377, 3375, -1, + 3375, 3610, 3609, -1, 3610, 3375, 3373, -1, + 3373, 3611, 3610, -1, 3611, 3373, 3371, -1, + 3371, 3612, 3611, -1, 3612, 3371, 3369, -1, + 3369, 3613, 3612, -1, 3613, 3369, 3367, -1, + 3367, 3614, 3613, -1, 3614, 3367, 3365, -1, + 3365, 3615, 3614, -1, 3615, 3365, 3363, -1, + 3363, 3616, 3615, -1, 3616, 3363, 3361, -1, + 3361, 3617, 3616, -1, 3617, 3361, 3359, -1, + 3359, 3618, 3617, -1, 3618, 3359, 3357, -1, + 3357, 3619, 3618, -1, 3619, 3357, 3355, -1, + 3355, 3620, 3619, -1, 3620, 3355, 3353, -1, + 3353, 3621, 3620, -1, 3621, 3353, 3351, -1, + 3351, 3622, 3621, -1, 3622, 3351, 3283, -1, + 3283, 3214, 3622, -1, 3214, 3283, 3282, -1, + 3282, 3213, 3214, -1, 3213, 3282, 3285, -1, + 3285, 3212, 3213, -1, 3212, 3285, 3287, -1, + 3287, 3211, 3212, -1, 3211, 3287, 3289, -1, + 3289, 3210, 3211, -1, 3210, 3289, 3290, -1, + 3290, 3209, 3210, -1, 3209, 3290, 3349, -1, + 3349, 3207, 3209, -1, 3207, 3349, 3347, -1, + 3347, 3205, 3207, -1, 3205, 3347, 3329, -1, + 3329, 3203, 3205, -1, 3203, 3329, 3328, -1, + 3328, 3201, 3203, -1, 3201, 3328, 3330, -1, + 3330, 3331, 3201, -1, 3331, 3199, 3201, -1, + 3199, 3331, 3332, -1, 3332, 3333, 3199, -1, + 3333, 3196, 3199, -1, 3196, 3333, 3334, -1, + 3334, 3197, 3196, -1, 3197, 3334, 3336, -1, + 3336, 3623, 3197, -1, 3624, 3197, 3623, -1, + 3623, 3625, 3624, -1, 3625, 3623, 3626, -1, + 3626, 3627, 3625, -1, 3628, 3629, 3627, -1, + 3627, 3630, 3628, -1, 3630, 3627, 3626, -1, + 3626, 3631, 3630, -1, 3631, 3626, 3623, -1, + 3623, 3336, 3631, -1, 3631, 3336, 3337, -1, + 3337, 3630, 3631, -1, 3630, 3337, 3339, -1, + 3339, 3628, 3630, -1, 3628, 3339, 3341, -1, + 3341, 3629, 3628, -1, 3632, 3633, 3634, -1, + 3633, 3632, 3629, -1, 3629, 3341, 3633, -1, + 3341, 3340, 3633, -1, 3635, 3633, 3340, -1, + 3340, 3636, 3635, -1, 3636, 3340, 3342, -1, + 3342, 3637, 3636, -1, 3637, 3342, 3343, -1, + 3343, 3638, 3637, -1, 3638, 3343, 3344, -1, + 3344, 3639, 3638, -1, 3639, 3344, 3345, -1, + 3345, 3640, 3639, -1, 3640, 3345, 3346, -1, + 3346, 3298, 3640, -1, 3640, 3298, 3296, -1, + 3296, 3639, 3640, -1, 3639, 3296, 3294, -1, + 3294, 3638, 3639, -1, 3638, 3294, 3291, -1, + 3291, 3637, 3638, -1, 3637, 3291, 3293, -1, + 3293, 3636, 3637, -1, 3641, 3636, 3293, -1, + 3293, 3642, 3641, -1, 3642, 3293, 3292, -1, + 3292, 3643, 3642, -1, 3643, 3292, 3295, -1, + 3295, 3297, 3643, -1, 3644, 3643, 3297, -1, + 3297, 3645, 3644, -1, 3645, 3297, 3299, -1, + 3299, 3188, 3645, -1, 3188, 3299, 3307, -1, + 3307, 3187, 3188, -1, 3187, 3307, 3305, -1, + 3305, 3185, 3187, -1, 3185, 3305, 3303, -1, + 3303, 3183, 3185, -1, 3183, 3303, 3300, -1, + 3300, 3180, 3183, -1, 3180, 3300, 3302, -1, + 3302, 3181, 3180, -1, 3181, 3302, 3348, -1, + 3348, 3646, 3181, -1, 3646, 3348, 3350, -1, + 3350, 3647, 3646, -1, 3647, 3350, 3280, -1, + 3280, 3178, 3647, -1, 3178, 3280, 3278, -1, + 3278, 3177, 3178, -1, 3177, 3278, 3276, -1, + 3276, 3175, 3177, -1, 3175, 3276, 3274, -1, + 3274, 3173, 3175, -1, 3173, 3274, 3271, -1, + 3271, 3170, 3173, -1, 3170, 3271, 3273, -1, + 3273, 3171, 3170, -1, 3171, 3273, 3352, -1, + 3352, 3648, 3171, -1, 3648, 3352, 3354, -1, + 3354, 3649, 3648, -1, 3649, 3354, 3356, -1, + 3356, 3650, 3649, -1, 3650, 3356, 3358, -1, + 3358, 3651, 3650, -1, 3651, 3358, 3360, -1, + 3360, 3652, 3651, -1, 3652, 3360, 3362, -1, + 3362, 3653, 3652, -1, 3653, 3362, 3364, -1, + 3364, 3654, 3653, -1, 3654, 3364, 3366, -1, + 3366, 3655, 3654, -1, 3655, 3366, 3368, -1, + 3368, 3656, 3655, -1, 3656, 3368, 3370, -1, + 3370, 3657, 3656, -1, 3657, 3370, 3372, -1, + 3372, 3658, 3657, -1, 3658, 3372, 3374, -1, + 3374, 3659, 3658, -1, 3659, 3374, 3376, -1, + 3376, 3660, 3659, -1, 3660, 3376, 3378, -1, + 3378, 3661, 3660, -1, 3661, 3378, 3380, -1, + 3380, 3662, 3661, -1, 3662, 3380, 3382, -1, + 3382, 3663, 3662, -1, 3663, 3382, 3384, -1, + 3384, 3664, 3663, -1, 3664, 3384, 3386, -1, + 3386, 3665, 3664, -1, 3386, 3666, 3665, -1, + 3666, 3386, 3387, -1, 3387, 3667, 3666, -1, + 3667, 3387, 3389, -1, 3389, 3668, 3667, -1, + 3668, 3389, 3391, -1, 3391, 3669, 3668, -1, + 3669, 3391, 3393, -1, 3393, 3670, 3669, -1, + 3670, 3393, 3395, -1, 3395, 3671, 3670, -1, + 3671, 3395, 3397, -1, 3397, 3672, 3671, -1, + 3672, 3397, 3399, -1, 3399, 3673, 3672, -1, + 3673, 3399, 3401, -1, 3401, 3674, 3673, -1, + 3674, 3401, 3403, -1, 3403, 3675, 3674, -1, + 3675, 3403, 3405, -1, 3405, 3676, 3675, -1, + 3676, 3405, 3407, -1, 3407, 3677, 3676, -1, + 3677, 3407, 3409, -1, 3409, 3678, 3677, -1, + 3678, 3409, 3411, -1, 3411, 3679, 3678, -1, + 3679, 3411, 3413, -1, 3413, 3680, 3679, -1, + 3680, 3413, 3415, -1, 3415, 3681, 3680, -1, + 3681, 3415, 3417, -1, 3417, 3682, 3681, -1, + 3682, 3417, 3419, -1, 3419, 3683, 3682, -1, + 3683, 3419, 3421, -1, 3421, 3684, 3683, -1, + 3685, 3683, 3684, -1, 3684, 3686, 3685, -1, + 3686, 3684, 3687, -1, 3687, 3688, 3686, -1, + 3688, 3687, 3689, -1, 3689, 3690, 3688, -1, + 3690, 3689, 3691, -1, 3691, 3692, 3690, -1, + 3692, 3691, 3693, -1, 3693, 3694, 3692, -1, + 3694, 3693, 3695, -1, 3695, 3696, 3694, -1, + 3697, 3698, 3696, -1, 3696, 3699, 3697, -1, + 3699, 3696, 3695, -1, 3695, 3700, 3699, -1, + 3700, 3695, 3693, -1, 3693, 3701, 3700, -1, + 3701, 3693, 3691, -1, 3691, 3702, 3701, -1, + 3702, 3691, 3689, -1, 3689, 3703, 3702, -1, + 3703, 3689, 3687, -1, 3687, 3704, 3703, -1, + 3704, 3687, 3684, -1, 3684, 3421, 3704, -1, + 3704, 3421, 3423, -1, 3423, 3703, 3704, -1, + 3703, 3423, 3435, -1, 3435, 3702, 3703, -1, + 3702, 3435, 3433, -1, 3433, 3701, 3702, -1, + 3701, 3433, 3431, -1, 3431, 3700, 3701, -1, + 3700, 3431, 3429, -1, 3429, 3699, 3700, -1, + 3699, 3429, 3427, -1, 3427, 3697, 3699, -1, + 3697, 3427, 3425, -1, 3425, 3698, 3697, -1, + 3698, 3425, 3252, -1, 3252, 3251, 3698, -1, + 3705, 3698, 3251, -1, 3251, 3706, 3705, -1, + 3706, 3251, 3250, -1, 3250, 3249, 3706, -1, + 3707, 3706, 3249, -1, 3249, 3708, 3707, -1, + 3708, 3249, 3247, -1, 3247, 3709, 3708, -1, + 3709, 3247, 3246, -1, 3246, 3257, 3709, -1, + 3710, 3709, 3257, -1, 3257, 3711, 3710, -1, + 3711, 3257, 3259, -1, 3259, 3712, 3711, -1, + 3712, 3259, 3261, -1, 3261, 3713, 3712, -1, + 3713, 3261, 3263, -1, 3263, 3714, 3713, -1, + 3714, 3263, 3444, -1, 3444, 3715, 3714, -1, + 3715, 3444, 3445, -1, 3445, 3716, 3715, -1, + 3716, 3445, 3572, -1, 3572, 3717, 3716, -1, + 3717, 3572, 3571, -1, 3571, 3718, 3717, -1, + 3718, 3571, 3570, -1, 3570, 3719, 3718, -1, + 3719, 3570, 3569, -1, 3569, 3720, 3719, -1, + 3720, 3569, 3568, -1, 3568, 3721, 3720, -1, + 3721, 3568, 3567, -1, 3567, 3722, 3721, -1, + 3722, 3567, 3566, -1, 3566, 3723, 3722, -1, + 3723, 3566, 3565, -1, 3565, 3724, 3723, -1, + 3724, 3565, 3564, -1, 3564, 3725, 3724, -1, + 3725, 3564, 3563, -1, 3563, 3726, 3725, -1, + 3726, 3563, 3562, -1, 3562, 3727, 3726, -1, + 3727, 3562, 3561, -1, 3561, 3728, 3727, -1, + 3728, 3561, 3560, -1, 3560, 3729, 3728, -1, + 3730, 3731, 3732, -1, 3732, 3733, 3730, -1, + 3733, 3732, 3729, -1, 3729, 3560, 3733, -1, + 3734, 3733, 3560, -1, 3560, 3559, 3734, -1, + 3735, 3734, 3559, -1, 3559, 3558, 3735, -1, + 3736, 3735, 3558, -1, 3558, 3737, 3736, -1, + 3737, 3558, 3556, -1, 3556, 3738, 3737, -1, + 3738, 3556, 3554, -1, 3554, 3739, 3738, -1, + 3739, 3554, 3552, -1, 3552, 3740, 3739, -1, + 3740, 3552, 3550, -1, 3550, 3741, 3740, -1, + 3741, 3550, 3548, -1, 3548, 3742, 3741, -1, + 3742, 3548, 3546, -1, 3546, 3743, 3742, -1, + 3743, 3546, 3544, -1, 3544, 3744, 3743, -1, + 3744, 3544, 3542, -1, 3542, 3745, 3744, -1, + 3745, 3542, 3540, -1, 3540, 3746, 3745, -1, + 3746, 3540, 3538, -1, 3538, 3747, 3746, -1, + 3747, 3538, 3536, -1, 3536, 3748, 3747, -1, + 3748, 3536, 3535, -1, 3535, 3749, 3748, -1, + 3749, 3535, 3534, -1, 3534, 3750, 3749, -1, + 3751, 3752, 3753, -1, 3752, 3751, 3754, -1, + 3754, 3755, 3752, -1, 3755, 3754, 3756, -1, + 3756, 3757, 3755, -1, 3758, 3759, 3760, -1, + 3759, 3758, 3757, -1, 3757, 3756, 3759, -1, + 3761, 3759, 3756, -1, 3756, 3762, 3761, -1, + 3762, 3756, 3754, -1, 3754, 3763, 3762, -1, + 3763, 3754, 3751, -1, 3751, 3764, 3763, -1, + 3764, 3751, 3753, -1, 3753, 3765, 3764, -1, + 3765, 3753, 3750, -1, 3750, 3534, 3765, -1, + 3765, 3534, 3504, -1, 3504, 3764, 3765, -1, + 3764, 3504, 3503, -1, 3503, 3763, 3764, -1, + 3763, 3503, 3510, -1, 3510, 3762, 3763, -1, + 3762, 3510, 3508, -1, 3508, 3761, 3762, -1, + 3761, 3508, 3505, -1, 3505, 3759, 3761, -1, + 3759, 3505, 3507, -1, 3507, 3760, 3759, -1, + 3760, 3507, 3513, -1, 3513, 3766, 3760, -1, + 3766, 3513, 3515, -1, 3515, 3767, 3766, -1, + 3767, 3515, 3517, -1, 3517, 3768, 3767, -1, + 3768, 3517, 3519, -1, 3519, 3769, 3768, -1, + 3769, 3519, 3521, -1, 3521, 3770, 3769, -1, + 3770, 3521, 3523, -1, 3523, 3771, 3770, -1, + 3771, 3523, 3525, -1, 3525, 3772, 3771, -1, + 3772, 3525, 3527, -1, 3527, 3773, 3772, -1, + 3774, 3775, 3776, -1, 3776, 3777, 3774, -1, + 3777, 3776, 3778, -1, 3778, 3779, 3780, -1, + 3780, 3777, 3778, -1, 3777, 3780, 3781, -1, + 3781, 3774, 3777, -1, 3774, 3781, 3782, -1, + 3782, 3775, 3774, -1, 3783, 3784, 3785, -1, + 3784, 3783, 3786, -1, 3786, 3787, 3784, -1, + 3787, 3786, 3788, -1, 3788, 3789, 3787, -1, + 3789, 3788, 3790, -1, 3790, 3791, 3789, -1, + 3791, 3790, 3792, -1, 3792, 3793, 3791, -1, + 3793, 3792, 3794, -1, 3794, 3795, 3793, -1, + 3795, 3794, 3796, -1, 3796, 3797, 3795, -1, + 3797, 3796, 3798, -1, 3798, 3799, 3797, -1, + 3799, 3798, 3775, -1, 3775, 3782, 3799, -1, + 3800, 3799, 3782, -1, 3782, 3801, 3800, -1, + 3801, 3782, 3781, -1, 3781, 3802, 3801, -1, + 3802, 3781, 3780, -1, 3780, 3803, 3802, -1, + 3803, 3780, 3779, -1, 3779, 3804, 3803, -1, + 3805, 3806, 3807, -1, 3807, 3808, 3805, -1, + 3809, 3810, 3811, -1, 3811, 3812, 3809, -1, + 3812, 3811, 3813, -1, 3813, 3814, 3812, -1, + 3814, 3813, 3808, -1, 3808, 3807, 3814, -1, + 3815, 3814, 3807, -1, 3814, 3815, 3816, -1, + 3816, 3812, 3814, -1, 3812, 3816, 3817, -1, + 3817, 3809, 3812, -1, 3809, 3817, 3818, -1, + 3818, 3810, 3809, -1, 3810, 3818, 3819, -1, + 3820, 3821, 3822, -1, 3823, 3822, 3821, -1, + 3823, 3824, 3822, -1, 3824, 3823, 3825, -1, + 3825, 3826, 3824, -1, 3826, 3825, 3827, -1, + 3827, 3828, 3826, -1, 3828, 3827, 3829, -1, + 3829, 3830, 3828, -1, 3830, 3829, 3831, -1, + 3831, 3832, 3830, -1, 3832, 3831, 3833, -1, + 3833, 3834, 3832, -1, 3834, 3833, 3835, -1, + 3835, 3836, 3834, -1, 3836, 3835, 3837, -1, + 3837, 3838, 3836, -1, 3838, 3837, 3839, -1, + 3839, 3840, 3838, -1, 3840, 3839, 3841, -1, + 3841, 3842, 3840, -1, 3842, 3841, 3843, -1, + 3843, 3844, 3842, -1, 3844, 3843, 3845, -1, + 3845, 3846, 3844, -1, 3846, 3845, 3847, -1, + 3847, 3848, 3846, -1, 3848, 3847, 3849, -1, + 3849, 3850, 3848, -1, 3850, 3849, 3851, -1, + 3851, 3852, 3850, -1, 3852, 3851, 3853, -1, + 3853, 3854, 3852, -1, 3854, 3853, 3819, -1, + 3819, 3804, 3854, -1, 3804, 3819, 3818, -1, + 3818, 3803, 3804, -1, 3803, 3818, 3817, -1, + 3817, 3802, 3803, -1, 3802, 3817, 3816, -1, + 3816, 3801, 3802, -1, 3801, 3816, 3815, -1, + 3815, 3800, 3801, -1, 3800, 3815, 3807, -1, + 3807, 3799, 3800, -1, 3799, 3807, 3806, -1, + 3806, 3797, 3799, -1, 3797, 3806, 3855, -1, + 3855, 3795, 3797, -1, 3795, 3855, 3856, -1, + 3856, 3793, 3795, -1, 3793, 3856, 3857, -1, + 3857, 3791, 3793, -1, 3791, 3857, 3858, -1, + 3858, 3789, 3791, -1, 3789, 3858, 3859, -1, + 3859, 3787, 3789, -1, 3787, 3859, 3860, -1, + 3860, 3784, 3787, -1, 3784, 3860, 3861, -1, + 3861, 3785, 3784, -1, 3785, 3861, 3862, -1, + 3862, 3863, 3785, -1, 3863, 3862, 3864, -1, + 3864, 3865, 3863, -1, 3865, 3864, 3866, -1, + 3866, 3867, 3865, -1, 3867, 3866, 3868, -1, + 3868, 3869, 3867, -1, 3869, 3868, 3870, -1, + 3870, 3871, 3869, -1, 3871, 3870, 3872, -1, + 3872, 3873, 3871, -1, 3873, 3872, 3874, -1, + 3874, 3875, 3873, -1, 3875, 3874, 3876, -1, + 3876, 3877, 3875, -1, 3877, 3876, 3878, -1, + 3878, 3879, 3877, -1, 3879, 3878, 3880, -1, + 3880, 3881, 3879, -1, 3881, 3880, 3882, -1, + 3882, 3883, 3881, -1, 3883, 3882, 3884, -1, + 3884, 3885, 3883, -1, 3885, 3884, 3886, -1, + 3886, 3887, 3885, -1, 3887, 3886, 3888, -1, + 3888, 3889, 3887, -1, 3889, 3888, 3890, -1, + 3890, 3891, 3889, -1, 3891, 3890, 3892, -1, + 3892, 3893, 3891, -1, 3893, 3892, 3894, -1, + 3894, 3895, 3893, -1, 3895, 3894, 3896, -1, + 3896, 3897, 3895, -1, 3897, 3896, 3898, -1, + 3898, 3899, 3897, -1, 3898, 3900, 3899, -1, + 3900, 3898, 3901, -1, 3901, 3902, 3900, -1, + 3902, 3901, 3903, -1, 3903, 3904, 3902, -1, + 3904, 3903, 3905, -1, 3905, 3906, 3904, -1, + 3906, 3905, 3907, -1, 3907, 3908, 3906, -1, + 3908, 3907, 3909, -1, 3909, 3910, 3908, -1, + 3910, 3909, 3911, -1, 3911, 3912, 3910, -1, + 3912, 3911, 3913, -1, 3913, 3914, 3912, -1, + 3914, 3913, 3915, -1, 3915, 3916, 3914, -1, + 3916, 3915, 3917, -1, 3917, 3918, 3916, -1, + 3918, 3917, 3919, -1, 3919, 3920, 3918, -1, + 3920, 3919, 3921, -1, 3921, 3922, 3920, -1, + 3922, 3921, 3923, -1, 3923, 3924, 3922, -1, + 3924, 3923, 3925, -1, 3925, 3926, 3924, -1, + 3926, 3925, 3927, -1, 3927, 3928, 3926, -1, + 3928, 3927, 3929, -1, 3929, 3930, 3928, -1, + 3930, 3929, 3931, -1, 3931, 3932, 3930, -1, + 3932, 3931, 3933, -1, 3933, 3934, 3932, -1, + 3934, 3933, 3773, -1, 3773, 3527, 3934, -1, + 3935, 3934, 3527, -1, 3527, 3936, 3935, -1, + 3936, 3527, 3526, -1, 3526, 3937, 3936, -1, + 3937, 3526, 3528, -1, 3528, 3938, 3937, -1, + 3938, 3528, 3529, -1, 3529, 3939, 3938, -1, + 3939, 3529, 3530, -1, 3530, 3940, 3939, -1, + 3940, 3530, 3531, -1, 3531, 3941, 3940, -1, + 3941, 3531, 3532, -1, 3532, 3942, 3941, -1, + 3942, 3532, 3533, -1, 3533, 3943, 3942, -1, + 3943, 3533, 3495, -1, 3495, 3447, 3943, -1, + 3944, 3943, 3447, -1, 3447, 3945, 3944, -1, + 3945, 3447, 3446, -1, 3446, 3946, 3945, -1, + 3946, 3446, 3449, -1, 3449, 3462, 3946, -1, + 3946, 3462, 3470, -1, 3470, 3945, 3946, -1, + 3945, 3470, 3471, -1, 3471, 3944, 3945, -1, + 3944, 3471, 3473, -1, 3473, 3943, 3944, -1, + 3943, 3473, 3475, -1, 3475, 3942, 3943, -1, + 3942, 3475, 3477, -1, 3477, 3941, 3942, -1, + 3941, 3477, 3573, -1, 3573, 3940, 3941, -1, + 3940, 3573, 3586, -1, 3586, 3939, 3940, -1, + 3939, 3586, 3584, -1, 3584, 3938, 3939, -1, + 3938, 3584, 3582, -1, 3582, 3937, 3938, -1, + 3937, 3582, 3580, -1, 3580, 3936, 3937, -1, + 3936, 3580, 3578, -1, 3578, 3935, 3936, -1, + 3935, 3578, 3576, -1, 3576, 3934, 3935, -1, + 3934, 3576, 3575, -1, 3575, 3932, 3934, -1, + 3932, 3575, 3588, -1, 3588, 3930, 3932, -1, + 3930, 3588, 3589, -1, 3589, 3928, 3930, -1, + 3928, 3589, 3590, -1, 3590, 3926, 3928, -1, + 3926, 3590, 3591, -1, 3591, 3924, 3926, -1, + 3924, 3591, 3592, -1, 3592, 3922, 3924, -1, + 3922, 3592, 3593, -1, 3593, 3920, 3922, -1, + 3920, 3593, 3594, -1, 3594, 3918, 3920, -1, + 3918, 3594, 3595, -1, 3595, 3916, 3918, -1, + 3916, 3595, 3596, -1, 3596, 3914, 3916, -1, + 3914, 3596, 3597, -1, 3597, 3912, 3914, -1, + 3912, 3597, 3598, -1, 3598, 3910, 3912, -1, + 3910, 3598, 3599, -1, 3599, 3908, 3910, -1, + 3908, 3599, 3600, -1, 3600, 3906, 3908, -1, + 3906, 3600, 3601, -1, 3601, 3904, 3906, -1, + 3904, 3601, 3602, -1, 3602, 3902, 3904, -1, + 3902, 3602, 3603, -1, 3603, 3900, 3902, -1, + 3900, 3603, 3604, -1, 3604, 3899, 3900, -1, + 3899, 3604, 3605, -1, 3899, 3605, 3606, -1, + 3606, 3897, 3899, -1, 3897, 3606, 3607, -1, + 3607, 3895, 3897, -1, 3895, 3607, 3608, -1, + 3608, 3893, 3895, -1, 3893, 3608, 3609, -1, + 3609, 3891, 3893, -1, 3891, 3609, 3610, -1, + 3610, 3889, 3891, -1, 3889, 3610, 3611, -1, + 3611, 3887, 3889, -1, 3887, 3611, 3612, -1, + 3612, 3885, 3887, -1, 3885, 3612, 3613, -1, + 3613, 3883, 3885, -1, 3883, 3613, 3614, -1, + 3614, 3881, 3883, -1, 3881, 3614, 3615, -1, + 3615, 3879, 3881, -1, 3879, 3615, 3616, -1, + 3616, 3877, 3879, -1, 3877, 3616, 3617, -1, + 3617, 3875, 3877, -1, 3875, 3617, 3618, -1, + 3618, 3873, 3875, -1, 3873, 3618, 3619, -1, + 3619, 3871, 3873, -1, 3871, 3619, 3620, -1, + 3620, 3869, 3871, -1, 3869, 3620, 3621, -1, + 3621, 3867, 3869, -1, 3867, 3621, 3622, -1, + 3622, 3865, 3867, -1, 3865, 3622, 3214, -1, + 3214, 3863, 3865, -1, 3863, 3214, 3191, -1, + 3191, 3785, 3863, -1, 3785, 3191, 3190, -1, + 3190, 3783, 3785, -1, 3783, 3190, 3193, -1, + 3193, 3786, 3783, -1, 3786, 3193, 3195, -1, + 3195, 3788, 3786, -1, 3788, 3195, 3208, -1, + 3208, 3790, 3788, -1, 3790, 3208, 3206, -1, + 3206, 3792, 3790, -1, 3792, 3206, 3204, -1, + 3204, 3794, 3792, -1, 3794, 3204, 3202, -1, + 3202, 3796, 3794, -1, 3796, 3202, 3200, -1, + 3200, 3798, 3796, -1, 3798, 3200, 3198, -1, + 3198, 3775, 3798, -1, 3775, 3198, 3197, -1, + 3197, 3776, 3775, -1, 3776, 3197, 3624, -1, + 3624, 3778, 3776, -1, 3778, 3624, 3625, -1, + 3625, 3779, 3778, -1, 3779, 3625, 3627, -1, + 3627, 3804, 3779, -1, 3804, 3627, 3629, -1, + 3629, 3854, 3804, -1, 3854, 3629, 3632, -1, + 3632, 3852, 3854, -1, 3852, 3632, 3634, -1, + 3634, 3850, 3852, -1, 3850, 3634, 3947, -1, + 3947, 3848, 3850, -1, 3848, 3947, 3948, -1, + 3948, 3846, 3848, -1, 3846, 3948, 3949, -1, + 3949, 3844, 3846, -1, 3844, 3949, 3950, -1, + 3950, 3842, 3844, -1, 3842, 3950, 3951, -1, + 3951, 3840, 3842, -1, 3840, 3951, 3952, -1, + 3952, 3838, 3840, -1, 3838, 3952, 3953, -1, + 3953, 3836, 3838, -1, 3836, 3953, 3954, -1, + 3954, 3834, 3836, -1, 3834, 3954, 3955, -1, + 3955, 3832, 3834, -1, 3832, 3955, 3956, -1, + 3956, 3830, 3832, -1, 3830, 3956, 3957, -1, + 3957, 3828, 3830, -1, 3828, 3957, 3958, -1, + 3958, 3826, 3828, -1, 3826, 3958, 3959, -1, + 3959, 3824, 3826, -1, 3824, 3959, 3960, -1, + 3960, 3822, 3824, -1, 3961, 3962, 3822, -1, + 3822, 3960, 3961, -1, 3963, 3964, 3965, -1, + 3961, 3965, 3964, -1, 3961, 3966, 3965, -1, + 3966, 3961, 3960, -1, 3960, 3967, 3966, -1, + 3967, 3960, 3959, -1, 3959, 3968, 3967, -1, + 3968, 3959, 3958, -1, 3958, 3969, 3968, -1, + 3969, 3958, 3957, -1, 3957, 3970, 3969, -1, + 3970, 3957, 3956, -1, 3956, 3971, 3970, -1, + 3971, 3956, 3955, -1, 3955, 3972, 3971, -1, + 3972, 3955, 3954, -1, 3954, 3973, 3972, -1, + 3973, 3954, 3953, -1, 3953, 3974, 3973, -1, + 3974, 3953, 3952, -1, 3952, 3975, 3974, -1, + 3975, 3952, 3951, -1, 3951, 3976, 3975, -1, + 3976, 3951, 3950, -1, 3950, 3977, 3976, -1, + 3977, 3950, 3949, -1, 3949, 3978, 3977, -1, + 3978, 3949, 3948, -1, 3948, 3979, 3978, -1, + 3979, 3948, 3947, -1, 3947, 3980, 3979, -1, + 3980, 3947, 3634, -1, 3634, 3981, 3980, -1, + 3981, 3634, 3633, -1, 3633, 3982, 3981, -1, + 3982, 3633, 3635, -1, 3635, 3983, 3982, -1, + 3983, 3635, 3636, -1, 3636, 3641, 3983, -1, + 3984, 3983, 3641, -1, 3641, 3985, 3984, -1, + 3985, 3641, 3642, -1, 3642, 3986, 3985, -1, + 3986, 3642, 3643, -1, 3643, 3644, 3986, -1, + 3986, 3644, 3168, -1, 3168, 3985, 3986, -1, + 3985, 3168, 3167, -1, 3167, 3984, 3985, -1, + 3984, 3167, 3164, -1, 3164, 3983, 3984, -1, + 3983, 3164, 3166, -1, 3166, 3982, 3983, -1, + 3982, 3166, 3987, -1, 3987, 3981, 3982, -1, + 3981, 3987, 3988, -1, 3988, 3980, 3981, -1, + 3980, 3988, 3163, -1, 3163, 3979, 3980, -1, + 3979, 3163, 3160, -1, 3160, 3978, 3979, -1, + 3978, 3160, 3158, -1, 3158, 3977, 3978, -1, + 3977, 3158, 3157, -1, 3157, 3976, 3977, -1, + 3976, 3157, 3989, -1, 3989, 3975, 3976, -1, + 3975, 3989, 3990, -1, 3990, 3974, 3975, -1, + 3974, 3990, 3991, -1, 3991, 3973, 3974, -1, + 3973, 3991, 3992, -1, 3992, 3972, 3973, -1, + 3972, 3992, 3993, -1, 3993, 3971, 3972, -1, + 3971, 3993, 3994, -1, 3994, 3970, 3971, -1, + 3970, 3994, 3995, -1, 3995, 3969, 3970, -1, + 3969, 3995, 3996, -1, 3996, 3968, 3969, -1, + 3968, 3996, 3997, -1, 3997, 3967, 3968, -1, + 3967, 3997, 3998, -1, 3998, 3966, 3967, -1, + 3966, 3998, 3999, -1, 3999, 3965, 3966, -1, + 4000, 4001, 3965, -1, 3965, 3999, 4000, -1, + 4002, 4003, 4004, -1, 4000, 4004, 4003, -1, + 4000, 4005, 4004, -1, 4005, 4000, 3999, -1, + 3999, 4006, 4005, -1, 4006, 3999, 3998, -1, + 3998, 4007, 4006, -1, 4007, 3998, 3997, -1, + 3997, 4008, 4007, -1, 4008, 3997, 3996, -1, + 3996, 4009, 4008, -1, 4009, 3996, 3995, -1, + 3995, 4010, 4009, -1, 4010, 3995, 3994, -1, + 3994, 4011, 4010, -1, 4011, 3994, 3993, -1, + 3993, 4012, 4011, -1, 4012, 3993, 3992, -1, + 3992, 4013, 4012, -1, 4013, 3992, 3991, -1, + 3991, 4014, 4013, -1, 4014, 3991, 3990, -1, + 3990, 4015, 4014, -1, 4015, 3990, 3989, -1, + 3989, 4016, 4015, -1, 4016, 3989, 3157, -1, + 3157, 3156, 4016, -1, 4017, 4016, 3156, -1, + 4016, 4017, 4018, -1, 4018, 4015, 4016, -1, + 4015, 4018, 4019, -1, 4019, 4014, 4015, -1, + 4014, 4019, 4020, -1, 4020, 4013, 4014, -1, + 4013, 4020, 4021, -1, 4021, 4012, 4013, -1, + 4012, 4021, 4022, -1, 4022, 4011, 4012, -1, + 4011, 4022, 4023, -1, 4023, 4010, 4011, -1, + 4010, 4023, 4024, -1, 4024, 4009, 4010, -1, + 4009, 4024, 4025, -1, 4025, 4008, 4009, -1, + 4008, 4025, 4026, -1, 4026, 4007, 4008, -1, + 4007, 4026, 4027, -1, 4027, 4006, 4007, -1, + 4006, 4027, 4028, -1, 4028, 4005, 4006, -1, + 4005, 4028, 4029, -1, 4029, 4004, 4005, -1, + 4030, 4031, 4004, -1, 4004, 4029, 4030, -1, + 4032, 4030, 4029, -1, 4029, 4033, 4032, -1, + 4033, 4029, 4028, -1, 4028, 4034, 4033, -1, + 4034, 4028, 4027, -1, 4027, 4035, 4034, -1, + 4035, 4027, 4026, -1, 4026, 4036, 4035, -1, + 4036, 4026, 4025, -1, 4025, 4037, 4036, -1, + 4037, 4025, 4024, -1, 4024, 4038, 4037, -1, + 4038, 4024, 4023, -1, 4023, 4039, 4038, -1, + 4039, 4023, 4022, -1, 4022, 4040, 4039, -1, + 4040, 4022, 4021, -1, 4021, 4041, 4040, -1, + 4041, 4021, 4020, -1, 4020, 4042, 4041, -1, + 4042, 4020, 4019, -1, 4019, 4043, 4042, -1, + 4043, 4019, 4018, -1, 4018, 4044, 4043, -1, + 4044, 4018, 4017, -1, 4017, 4045, 4044, -1, + 4017, 3156, 4045, -1, 4046, 4045, 3156, -1, + 4046, 3156, 3159, -1, 3159, 4047, 4046, -1, + 4047, 3159, 3162, -1, 3162, 4048, 4047, -1, + 4049, 4050, 4051, -1, 4051, 4052, 4049, -1, + 4053, 4054, 4055, -1, 4055, 4056, 4053, -1, + 4057, 4056, 4058, -1, 4058, 4059, 4057, -1, + 4060, 4059, 4061, -1, 4061, 4062, 4060, -1, + 4062, 4061, 4063, -1, 4063, 4064, 4062, -1, + 4064, 4063, 4065, -1, 4065, 4066, 4064, -1, + 4066, 4065, 4067, -1, 4067, 4068, 4066, -1, + 4068, 4067, 4069, -1, 4069, 4048, 4068, -1, + 4070, 4048, 4069, -1, 4069, 4071, 4070, -1, + 4071, 4069, 4067, -1, 4067, 4072, 4071, -1, + 4072, 4067, 4065, -1, 4065, 4073, 4072, -1, + 4073, 4065, 4063, -1, 4063, 4074, 4073, -1, + 4074, 4063, 4061, -1, 4061, 4075, 4074, -1, + 4075, 4061, 4059, -1, 4059, 4058, 4075, -1, + 4058, 4076, 4075, -1, 4076, 4058, 4056, -1, + 4056, 4055, 4076, -1, 4055, 4077, 4076, -1, + 4077, 4055, 4054, -1, 4054, 4078, 4077, -1, + 4078, 4054, 4049, -1, 4049, 4079, 4078, -1, + 4079, 4049, 4052, -1, 4052, 4080, 4079, -1, + 4080, 4052, 4081, -1, 4082, 4083, 4084, -1, + 4083, 4082, 4085, -1, 4085, 4086, 4083, -1, + 4086, 4085, 4087, -1, 4087, 4088, 4086, -1, + 4088, 4087, 4089, -1, 4089, 4090, 4088, -1, + 4090, 4089, 4091, -1, 4092, 4093, 4094, -1, + 4093, 4092, 4095, -1, 4095, 4096, 4093, -1, + 4096, 4095, 4097, -1, 4098, 4097, 4099, -1, + 4097, 4098, 4100, -1, 4100, 4096, 4097, -1, + 4096, 4100, 4101, -1, 4101, 4093, 4096, -1, + 4093, 4101, 4102, -1, 4102, 4094, 4093, -1, + 4094, 4102, 4103, -1, 4103, 4104, 4094, -1, + 4104, 4103, 4105, -1, 4105, 4106, 4104, -1, + 4106, 4105, 4107, -1, 4107, 4108, 4106, -1, + 4108, 4107, 4109, -1, 4109, 4110, 4108, -1, + 4110, 4109, 4111, -1, 4111, 4112, 4110, -1, + 4112, 4111, 4113, -1, 4113, 4114, 4112, -1, + 4114, 4113, 4115, -1, 4115, 4116, 4114, -1, + 4116, 4115, 4117, -1, 4117, 4118, 4116, -1, + 4119, 4120, 4121, -1, 4120, 4119, 4118, -1, + 4118, 4117, 4120, -1, 4117, 4122, 4120, -1, + 4117, 4123, 4122, -1, 4123, 4117, 4115, -1, + 4115, 4124, 4123, -1, 4124, 4115, 4113, -1, + 4113, 4125, 4124, -1, 4125, 4113, 4111, -1, + 4111, 4126, 4125, -1, 4126, 4111, 4109, -1, + 4109, 4127, 4126, -1, 4127, 4109, 4107, -1, + 4107, 4128, 4127, -1, 4128, 4107, 4105, -1, + 4105, 4129, 4128, -1, 4129, 4105, 4103, -1, + 4103, 4091, 4129, -1, 4091, 4103, 4102, -1, + 4102, 4090, 4091, -1, 4090, 4102, 4101, -1, + 4101, 4088, 4090, -1, 4088, 4101, 4100, -1, + 4100, 4086, 4088, -1, 4086, 4100, 4098, -1, + 4098, 4083, 4086, -1, 4083, 4098, 4099, -1, + 4099, 4084, 4083, -1, 4084, 4099, 4130, -1, + 4130, 4131, 4084, -1, 4131, 4130, 4132, -1, + 4132, 4133, 4131, -1, 4133, 4132, 4081, -1, + 4081, 4134, 4133, -1, 4134, 4081, 4052, -1, + 4052, 4051, 4134, -1, 4051, 4135, 4134, -1, + 4135, 4051, 4050, -1, 4050, 4136, 4135, -1, + 4136, 4050, 4137, -1, 4137, 4138, 4136, -1, + 4138, 4137, 4139, -1, 4139, 4140, 4138, -1, + 4140, 4139, 4141, -1, 4142, 4143, 4144, -1, + 4143, 4142, 4145, -1, 4145, 4146, 4143, -1, + 4147, 4148, 4149, -1, 4148, 4147, 4150, -1, + 4150, 4151, 4148, -1, 4151, 4150, 4146, -1, + 4146, 4145, 4151, -1, 4152, 4151, 4145, -1, + 4151, 4152, 4153, -1, 4153, 4148, 4151, -1, + 4148, 4153, 4141, -1, 4141, 4149, 4148, -1, + 4149, 4141, 4139, -1, 4139, 4154, 4149, -1, + 4154, 4139, 4137, -1, 4137, 4155, 4154, -1, + 4155, 4137, 4050, -1, 4050, 4049, 4155, -1, + 4155, 4049, 4054, -1, 4054, 4154, 4155, -1, + 4154, 4054, 4053, -1, 4053, 4149, 4154, -1, + 4149, 4053, 4056, -1, 4056, 4147, 4149, -1, + 4147, 4056, 4057, -1, 4057, 4150, 4147, -1, + 4150, 4057, 4059, -1, 4059, 4146, 4150, -1, + 4146, 4059, 4060, -1, 4060, 4143, 4146, -1, + 4143, 4060, 4062, -1, 4062, 4144, 4143, -1, + 4144, 4062, 4064, -1, 4064, 4156, 4144, -1, + 4156, 4064, 4066, -1, 4066, 4157, 4156, -1, + 4157, 4066, 4068, -1, 4068, 4158, 4157, -1, + 4158, 4068, 4048, -1, 4048, 3162, 4158, -1, + 4158, 3162, 3163, -1, 4158, 3163, 3988, -1, + 3988, 4157, 4158, -1, 4157, 3988, 3987, -1, + 3987, 4156, 4157, -1, 4156, 3987, 3166, -1, + 3166, 4144, 4156, -1, 4144, 3166, 3165, -1, + 3165, 4142, 4144, -1, 4142, 3165, 3168, -1, + 3168, 4145, 4142, -1, 4145, 3168, 3644, -1, + 3644, 4152, 4145, -1, 4152, 3644, 3645, -1, + 3645, 4153, 4152, -1, 4153, 3645, 3188, -1, + 3188, 4141, 4153, -1, 4141, 3188, 3186, -1, + 3186, 4140, 4141, -1, 4140, 3186, 3184, -1, + 3184, 4138, 4140, -1, 4138, 3184, 3182, -1, + 3182, 4136, 4138, -1, 4136, 3182, 3179, -1, + 3179, 4135, 4136, -1, 4135, 3179, 3181, -1, + 3181, 4134, 4135, -1, 4134, 3181, 3646, -1, + 3646, 4133, 4134, -1, 4133, 3646, 3647, -1, + 3647, 4131, 4133, -1, 4131, 3647, 3178, -1, + 3178, 4084, 4131, -1, 4084, 3178, 3176, -1, + 3176, 4082, 4084, -1, 4082, 3176, 3174, -1, + 3174, 4085, 4082, -1, 4085, 3174, 3172, -1, + 3172, 4087, 4085, -1, 4087, 3172, 3169, -1, + 3169, 4089, 4087, -1, 4089, 3169, 3171, -1, + 3171, 4091, 4089, -1, 4091, 3171, 3648, -1, + 3648, 4129, 4091, -1, 4129, 3648, 3649, -1, + 3649, 4128, 4129, -1, 4128, 3649, 3650, -1, + 3650, 4127, 4128, -1, 4127, 3650, 3651, -1, + 3651, 4126, 4127, -1, 4126, 3651, 3652, -1, + 3652, 4125, 4126, -1, 4125, 3652, 3653, -1, + 3653, 4124, 4125, -1, 4124, 3653, 3654, -1, + 3654, 4123, 4124, -1, 4123, 3654, 3655, -1, + 3655, 4122, 4123, -1, 4122, 3655, 3656, -1, + 3656, 4159, 4122, -1, 4159, 3656, 3657, -1, + 3657, 4160, 4159, -1, 4160, 3657, 3658, -1, + 3658, 4161, 4160, -1, 4161, 3658, 3659, -1, + 3659, 4162, 4161, -1, 4162, 3659, 3660, -1, + 3660, 4163, 4162, -1, 4163, 3660, 3661, -1, + 3661, 4164, 4163, -1, 4164, 3661, 3662, -1, + 3662, 4165, 4164, -1, 4165, 3662, 3663, -1, + 3663, 4166, 4165, -1, 4166, 3663, 3664, -1, + 3664, 4167, 4166, -1, 4167, 3664, 3665, -1, + 3665, 4168, 4167, -1, 3665, 4169, 4168, -1, + 4169, 3665, 3666, -1, 3666, 4170, 4169, -1, + 4170, 3666, 3667, -1, 3667, 4171, 4170, -1, + 4171, 3667, 3668, -1, 3668, 4172, 4171, -1, + 4172, 3668, 3669, -1, 3669, 4173, 4172, -1, + 4173, 3669, 3670, -1, 3670, 4174, 4173, -1, + 4174, 3670, 3671, -1, 3671, 4175, 4174, -1, + 4175, 3671, 3672, -1, 3672, 4176, 4175, -1, + 4176, 3672, 3673, -1, 3673, 4177, 4176, -1, + 4177, 3673, 3674, -1, 3674, 4178, 4177, -1, + 4178, 3674, 3675, -1, 3675, 4179, 4178, -1, + 4179, 3675, 3676, -1, 3676, 4180, 4179, -1, + 4180, 3676, 3677, -1, 3677, 4181, 4180, -1, + 4181, 3677, 3678, -1, 3678, 4182, 4181, -1, + 4182, 3678, 3679, -1, 3679, 4183, 4182, -1, + 4183, 3679, 3680, -1, 3680, 4184, 4183, -1, + 4184, 3680, 3681, -1, 3681, 4185, 4184, -1, + 4185, 3681, 3682, -1, 3682, 3155, 4185, -1, + 3155, 3682, 3683, -1, 3683, 3153, 3155, -1, + 3153, 3683, 3685, -1, 3685, 3151, 3153, -1, + 3151, 3685, 3686, -1, 3686, 3149, 3151, -1, + 3149, 3686, 3688, -1, 3688, 3147, 3149, -1, + 3147, 3688, 3690, -1, 3690, 3145, 3147, -1, + 3145, 3690, 3692, -1, 3692, 3142, 3145, -1, + 3142, 3692, 3694, -1, 3694, 3143, 3142, -1, + 3143, 3694, 3696, -1, 3696, 3141, 3143, -1, + 3141, 3696, 3698, -1, 3698, 3139, 3141, -1, + 3139, 3698, 3705, -1, 3705, 3137, 3139, -1, + 3137, 3705, 3706, -1, 3706, 3707, 3137, -1, + 3707, 3134, 3137, -1, 3134, 3707, 3708, -1, + 3708, 3132, 3134, -1, 3132, 3708, 3709, -1, + 3709, 3130, 3132, -1, 3130, 3709, 3710, -1, + 3710, 3128, 3130, -1, 3128, 3710, 3711, -1, + 3711, 3078, 3128, -1, 3078, 3711, 3712, -1, + 3712, 3076, 3078, -1, 3076, 3712, 3713, -1, + 3713, 3079, 3076, -1, 3079, 3713, 3714, -1, + 3714, 3081, 3079, -1, 3081, 3714, 3715, -1, + 3715, 3075, 3081, -1, 3075, 3715, 3716, -1, + 3716, 3073, 3075, -1, 3073, 3716, 3717, -1, + 3717, 3072, 3073, -1, 3072, 3717, 3718, -1, + 3718, 3071, 3072, -1, 3071, 3718, 3719, -1, + 3719, 3070, 3071, -1, 3070, 3719, 3720, -1, + 3720, 3069, 3070, -1, 3069, 3720, 3721, -1, + 3721, 3068, 3069, -1, 3068, 3721, 3722, -1, + 3722, 3067, 3068, -1, 3067, 3722, 3723, -1, + 3723, 3066, 3067, -1, 3066, 3723, 3724, -1, + 3724, 3065, 3066, -1, 3065, 3724, 3725, -1, + 3725, 3064, 3065, -1, 3064, 3725, 3726, -1, + 3726, 3063, 3064, -1, 3063, 3726, 3727, -1, + 3727, 3062, 3063, -1, 3062, 3727, 3728, -1, + 3728, 3061, 3062, -1, 3061, 3728, 3729, -1, + 3729, 3060, 3061, -1, 3060, 3729, 3732, -1, + 3732, 3059, 3060, -1, 3059, 3732, 3731, -1, + 3731, 3058, 3059, -1, 3058, 3731, 2995, -1, + 2995, 3056, 3058, -1, 2995, 2994, 3056, -1, + 4186, 3056, 2994, -1, 2994, 4187, 4186, -1, + 2994, 2993, 4187, -1, 4188, 4189, 4190, -1, + 4189, 4188, 4187, -1, 4189, 4187, 2993, -1, + 2993, 2995, 4189, -1, 2995, 4190, 4189, -1, + 4190, 2995, 3731, -1, 3731, 3730, 4190, -1, + 4191, 4192, 4190, -1, 4191, 4190, 3730, -1, + 3730, 4193, 4191, -1, 4193, 3730, 3733, -1, + 3733, 3734, 4193, -1, 4194, 4193, 3734, -1, + 3734, 3735, 4194, -1, 4195, 4194, 3735, -1, + 3735, 3736, 4195, -1, 4196, 4195, 3736, -1, + 3736, 4197, 4196, -1, 4197, 3736, 3737, -1, + 3737, 4198, 4197, -1, 4198, 3737, 3738, -1, + 3738, 4199, 4198, -1, 4199, 3738, 3739, -1, + 3739, 4200, 4199, -1, 4200, 3739, 3740, -1, + 3740, 4201, 4200, -1, 4201, 3740, 3741, -1, + 3741, 4202, 4201, -1, 4202, 3741, 3742, -1, + 3742, 4203, 4202, -1, 4203, 3742, 3743, -1, + 3743, 4204, 4203, -1, 4204, 3743, 3744, -1, + 3744, 4205, 4204, -1, 4205, 3744, 3745, -1, + 3745, 4206, 4205, -1, 4206, 3745, 3746, -1, + 3746, 4207, 4206, -1, 4207, 3746, 3747, -1, + 3747, 4208, 4207, -1, 4208, 3747, 3748, -1, + 3748, 4209, 4208, -1, 4209, 3748, 3749, -1, + 3749, 2992, 4209, -1, 2992, 3749, 3750, -1, + 3750, 2990, 2992, -1, 2990, 3750, 3753, -1, + 3753, 2825, 2990, -1, 2825, 3753, 3752, -1, + 3752, 2823, 2825, -1, 2823, 3752, 3755, -1, + 3755, 2822, 2823, -1, 2822, 3755, 3757, -1, + 3757, 2821, 2822, -1, 2821, 3757, 3758, -1, + 3758, 2818, 2821, -1, 2818, 3758, 3760, -1, + 3760, 2819, 2818, -1, 2819, 3760, 3766, -1, + 3766, 2829, 2819, -1, 2829, 3766, 3767, -1, + 3767, 2831, 2829, -1, 2831, 3767, 3768, -1, + 3768, 2833, 2831, -1, 2833, 3768, 3769, -1, + 3769, 2835, 2833, -1, 2835, 3769, 3770, -1, + 3770, 2837, 2835, -1, 2837, 3770, 3771, -1, + 3771, 2839, 2837, -1, 2839, 3771, 3772, -1, + 3772, 2841, 2839, -1, 2841, 3772, 3773, -1, + 3773, 2843, 2841, -1, 2843, 3773, 3933, -1, + 3933, 2845, 2843, -1, 2845, 3933, 3931, -1, + 3931, 2847, 2845, -1, 2847, 3931, 3929, -1, + 3929, 2849, 2847, -1, 2849, 3929, 3927, -1, + 3927, 2851, 2849, -1, 2851, 3927, 3925, -1, + 3925, 2853, 2851, -1, 2853, 3925, 3923, -1, + 3923, 2855, 2853, -1, 2855, 3923, 3921, -1, + 3921, 2857, 2855, -1, 2857, 3921, 3919, -1, + 3919, 2859, 2857, -1, 2859, 3919, 3917, -1, + 3917, 2861, 2859, -1, 2861, 3917, 3915, -1, + 3915, 2863, 2861, -1, 2863, 3915, 3913, -1, + 3913, 2865, 2863, -1, 2865, 3913, 3911, -1, + 3911, 2867, 2865, -1, 2867, 3911, 3909, -1, + 3909, 2869, 2867, -1, 2869, 3909, 3907, -1, + 3907, 2871, 2869, -1, 2871, 3907, 3905, -1, + 3905, 2873, 2871, -1, 2873, 3905, 3903, -1, + 3903, 2875, 2873, -1, 2875, 3903, 3901, -1, + 3901, 2877, 2875, -1, 2877, 3901, 3898, -1, + 2877, 3898, 3896, -1, 3896, 2878, 2877, -1, + 2878, 3896, 3894, -1, 3894, 2880, 2878, -1, + 2880, 3894, 3892, -1, 3892, 2882, 2880, -1, + 2882, 3892, 3890, -1, 3890, 2884, 2882, -1, + 2884, 3890, 3888, -1, 3888, 2886, 2884, -1, + 2886, 3888, 3886, -1, 3886, 2888, 2886, -1, + 2888, 3886, 3884, -1, 3884, 2890, 2888, -1, + 2890, 3884, 3882, -1, 3882, 2892, 2890, -1, + 2892, 3882, 3880, -1, 3880, 2894, 2892, -1, + 2894, 3880, 3878, -1, 3878, 2896, 2894, -1, + 2896, 3878, 3876, -1, 3876, 2898, 2896, -1, + 2898, 3876, 3874, -1, 3874, 2900, 2898, -1, + 2900, 3874, 3872, -1, 3872, 2902, 2900, -1, + 2902, 3872, 3870, -1, 3870, 2904, 2902, -1, + 2904, 3870, 3868, -1, 3868, 2906, 2904, -1, + 2906, 3868, 3866, -1, 3866, 2908, 2906, -1, + 2908, 3866, 3864, -1, 3864, 2910, 2908, -1, + 2910, 3864, 3862, -1, 3862, 2912, 2910, -1, + 2912, 3862, 3861, -1, 3861, 2914, 2912, -1, + 2914, 3861, 3860, -1, 3860, 2916, 2914, -1, + 2916, 3860, 3859, -1, 3859, 2918, 2916, -1, + 2918, 3859, 3858, -1, 3858, 2920, 2918, -1, + 2920, 3858, 3857, -1, 3857, 2922, 2920, -1, + 2922, 3857, 3856, -1, 3856, 2924, 2922, -1, + 2924, 3856, 3855, -1, 3855, 2926, 2924, -1, + 2926, 3855, 3806, -1, 3806, 2928, 2926, -1, + 2928, 3806, 3805, -1, 3805, 2930, 2928, -1, + 2930, 3805, 3808, -1, 3808, 2931, 2930, -1, + 2931, 3808, 3813, -1, 3813, 2932, 2931, -1, + 2932, 3813, 3811, -1, 3811, 2933, 2932, -1, + 2933, 3811, 3810, -1, 3810, 2817, 2933, -1, + 2817, 3810, 3819, -1, 3819, 2815, 2817, -1, + 2815, 3819, 3853, -1, 3853, 2813, 2815, -1, + 2813, 3853, 3851, -1, 3851, 2811, 2813, -1, + 2811, 3851, 3849, -1, 3849, 2809, 2811, -1, + 2809, 3849, 3847, -1, 3847, 2807, 2809, -1, + 2807, 3847, 3845, -1, 3845, 2805, 2807, -1, + 2805, 3845, 3843, -1, 3843, 2803, 2805, -1, + 2803, 3843, 3841, -1, 3841, 2801, 2803, -1, + 2801, 3841, 3839, -1, 3839, 2799, 2801, -1, + 2799, 3839, 3837, -1, 3837, 2797, 2799, -1, + 2797, 3837, 3835, -1, 3835, 2795, 2797, -1, + 2795, 3835, 3833, -1, 3833, 2793, 2795, -1, + 2793, 3833, 3831, -1, 3831, 2791, 2793, -1, + 2791, 3831, 3829, -1, 3829, 2789, 2791, -1, + 2789, 3829, 3827, -1, 3827, 2787, 2789, -1, + 2787, 3827, 3825, -1, 3825, 2785, 2787, -1, + 2785, 3825, 3823, -1, 2785, 3823, 4210, -1, + 4211, 4210, 3823, -1, 4211, 4212, 4210, -1, + 4213, 4212, 4211, -1, 4211, 3823, 4213, -1, + 4213, 3823, 3821, -1, 3821, 4212, 4213, -1, + 3821, 3820, 4212, -1, 4214, 4215, 4216, -1, + 4217, 4218, 4214, -1, 4212, 4219, 4217, -1, + 4219, 4212, 3820, -1, 3820, 3822, 4219, -1, + 4219, 3822, 3962, -1, 3962, 4217, 4219, -1, + 4220, 4217, 3962, -1, 4220, 3962, 3961, -1, + 4220, 3961, 3964, -1, 3964, 4217, 4220, -1, + 3964, 3963, 4217, -1, 3963, 4218, 4217, -1, + 4218, 3963, 3965, -1, 4218, 3965, 4001, -1, + 4001, 4214, 4218, -1, 4001, 4221, 4214, -1, + 4221, 4001, 4000, -1, 4221, 4000, 4003, -1, + 4003, 4214, 4221, -1, 4003, 4002, 4214, -1, + 4002, 4215, 4214, -1, 4215, 4002, 4004, -1, + 4215, 4004, 4031, -1, 4031, 4216, 4215, -1, + 4031, 4222, 4216, -1, 4222, 4031, 4030, -1, + 4222, 4030, 4223, -1, 4223, 4216, 4222, -1, + 4223, 4224, 4216, -1, 4223, 4030, 4224, -1, + 4225, 4224, 4030, -1, 4030, 4032, 4225, -1, + 4226, 4227, 4225, -1, 4225, 4228, 4226, -1, + 4228, 4225, 4032, -1, 4032, 4229, 4228, -1, + 4229, 4032, 4033, -1, 4033, 4230, 4229, -1, + 4230, 4033, 4034, -1, 4034, 4231, 4230, -1, + 4231, 4034, 4035, -1, 4035, 4232, 4231, -1, + 4232, 4035, 4036, -1, 4036, 4233, 4232, -1, + 4233, 4036, 4037, -1, 4037, 4234, 4233, -1, + 4234, 4037, 4038, -1, 4038, 4235, 4234, -1, + 4235, 4038, 4039, -1, 4039, 4236, 4235, -1, + 4236, 4039, 4040, -1, 4040, 4237, 4236, -1, + 4237, 4040, 4041, -1, 4041, 4238, 4237, -1, + 4238, 4041, 4042, -1, 4042, 4239, 4238, -1, + 4239, 4042, 4043, -1, 4043, 4240, 4239, -1, + 4240, 4043, 4044, -1, 4044, 4241, 4240, -1, + 4241, 4044, 4045, -1, 4045, 4242, 4241, -1, + 4242, 4045, 4046, -1, 4046, 4243, 4242, -1, + 4243, 4046, 4047, -1, 4047, 4244, 4243, -1, + 4244, 4047, 4048, -1, 4048, 4070, 4244, -1, + 4245, 4244, 4070, -1, 4070, 4246, 4245, -1, + 4246, 4070, 4071, -1, 4071, 4072, 4246, -1, + 2783, 4246, 4072, -1, 4246, 2783, 2782, -1, + 2782, 4245, 4246, -1, 4245, 2782, 2780, -1, + 2780, 4244, 4245, -1, 4244, 2780, 2779, -1, + 2779, 4243, 4244, -1, 4243, 2779, 4247, -1, + 4247, 4242, 4243, -1, 4242, 4247, 4248, -1, + 4248, 4241, 4242, -1, 4241, 4248, 4249, -1, + 4249, 4240, 4241, -1, 4240, 4249, 4250, -1, + 4250, 4239, 4240, -1, 4239, 4250, 4251, -1, + 4251, 4238, 4239, -1, 4238, 4251, 4252, -1, + 4252, 4237, 4238, -1, 4237, 4252, 4253, -1, + 4253, 4236, 4237, -1, 4236, 4253, 4254, -1, + 4254, 4235, 4236, -1, 4235, 4254, 4255, -1, + 4255, 4234, 4235, -1, 4234, 4255, 4256, -1, + 4256, 4233, 4234, -1, 4233, 4256, 4257, -1, + 4257, 4232, 4233, -1, 4232, 4257, 4258, -1, + 4258, 4231, 4232, -1, 4231, 4258, 4259, -1, + 4259, 4230, 4231, -1, 4230, 4259, 4260, -1, + 4260, 4229, 4230, -1, 4229, 4260, 4261, -1, + 4261, 4228, 4229, -1, 4228, 4261, 4262, -1, + 4262, 4226, 4228, -1, 4226, 4262, 2777, -1, + 2777, 2772, 4226, -1, 4263, 4227, 4226, -1, + 4227, 4263, 2774, -1, 4227, 2774, 4264, -1, + 4264, 4225, 4227, -1, 4264, 4224, 4225, -1, + 4264, 4216, 4224, -1, 4216, 4264, 2774, -1, + 4265, 2771, 2768, -1, 2768, 4266, 4265, -1, + 4266, 2768, 2656, -1, 4266, 2656, 2655, -1, + 2655, 4265, 4266, -1, 2655, 2653, 4265, -1, + 2653, 2652, 4265, -1, 2652, 4267, 4265, -1, + 2652, 2654, 4267, -1, 4268, 4267, 2654, -1, + 2654, 4269, 4268, -1, 4269, 2654, 2657, -1, + 2657, 4270, 4269, -1, 4270, 2657, 2659, -1, + 2659, 4271, 4270, -1, 4271, 2659, 2661, -1, + 2661, 4272, 4271, -1, 4272, 2661, 2663, -1, + 2663, 4273, 4272, -1, 4273, 2663, 2665, -1, + 2665, 4274, 4273, -1, 4274, 2665, 2667, -1, + 2667, 4275, 4274, -1, 4275, 2667, 2669, -1, + 2669, 4276, 4275, -1, 4276, 2669, 2671, -1, + 2671, 4277, 4276, -1, 4277, 2671, 2673, -1, + 2673, 4278, 4277, -1, 4278, 2673, 2675, -1, + 2675, 4279, 4278, -1, 4279, 2675, 2677, -1, + 2677, 4280, 4279, -1, 4280, 2677, 2679, -1, + 2679, 4281, 4280, -1, 4281, 2679, 2681, -1, + 2681, 4282, 4281, -1, 4282, 2681, 2683, -1, + 2683, 4283, 4282, -1, 4283, 2683, 2685, -1, + 2685, 4284, 4283, -1, 4285, 4283, 4284, -1, + 4284, 4286, 4285, -1, 4286, 4284, 4287, -1, + 4287, 4288, 4286, -1, 4289, 4286, 4288, -1, + 4288, 4290, 4289, -1, 4290, 4288, 4291, -1, + 4291, 4292, 4290, -1, 4293, 4294, 4295, -1, + 4295, 4296, 4293, -1, 4296, 4295, 4297, -1, + 4297, 4298, 4296, -1, 4298, 4297, 4299, -1, + 4299, 4300, 4298, -1, 4300, 4299, 4301, -1, + 4301, 4292, 4300, -1, 4292, 4301, 2633, -1, + 2633, 4290, 4292, -1, 4290, 2633, 2632, -1, + 2632, 4289, 4290, -1, 4289, 2632, 2629, -1, + 2629, 4286, 4289, -1, 4286, 2629, 2628, -1, + 2628, 4285, 4286, -1, 4285, 2628, 2626, -1, + 2626, 4283, 4285, -1, 4283, 2626, 2625, -1, + 2625, 4282, 4283, -1, 4282, 2625, 4302, -1, + 4302, 4281, 4282, -1, 4281, 4302, 4303, -1, + 4303, 4280, 4281, -1, 4280, 4303, 4304, -1, + 4304, 4279, 4280, -1, 4279, 4304, 4305, -1, + 4305, 4278, 4279, -1, 4278, 4305, 4306, -1, + 4306, 4277, 4278, -1, 4277, 4306, 4307, -1, + 4307, 4276, 4277, -1, 4276, 4307, 4308, -1, + 4308, 4275, 4276, -1, 4275, 4308, 4309, -1, + 4309, 4274, 4275, -1, 4274, 4309, 4310, -1, + 4310, 4273, 4274, -1, 4273, 4310, 4311, -1, + 4311, 4272, 4273, -1, 4272, 4311, 4312, -1, + 4312, 4271, 4272, -1, 4271, 4312, 4313, -1, + 4313, 4270, 4271, -1, 4270, 4313, 4314, -1, + 4314, 4269, 4270, -1, 4269, 4314, 4315, -1, + 4315, 4268, 4269, -1, 4316, 4317, 4268, -1, + 4268, 4315, 4316, -1, 4318, 4319, 4316, -1, + 4316, 4320, 4318, -1, 4320, 4316, 4315, -1, + 4315, 4321, 4320, -1, 4321, 4315, 4314, -1, + 4314, 4322, 4321, -1, 4322, 4314, 4313, -1, + 4313, 4323, 4322, -1, 4323, 4313, 4312, -1, + 4312, 4324, 4323, -1, 4324, 4312, 4311, -1, + 4311, 4325, 4324, -1, 4325, 4311, 4310, -1, + 4310, 4326, 4325, -1, 4326, 4310, 4309, -1, + 4309, 4327, 4326, -1, 4327, 4309, 4308, -1, + 4308, 4328, 4327, -1, 4328, 4308, 4307, -1, + 4307, 4329, 4328, -1, 4329, 4307, 4306, -1, + 4306, 4330, 4329, -1, 4330, 4306, 4305, -1, + 4305, 4331, 4330, -1, 4331, 4305, 4304, -1, + 4304, 4332, 4331, -1, 4332, 4304, 4303, -1, + 4303, 4333, 4332, -1, 4333, 4303, 4302, -1, + 4302, 2623, 4333, -1, 2623, 4302, 2625, -1, + 2625, 2621, 2623, -1, 2621, 2625, 2624, -1, + 2624, 2620, 2621, -1, 2620, 2624, 2627, -1, + 2627, 2617, 2620, -1, 2617, 2627, 2630, -1, + 2630, 2614, 2617, -1, 2614, 2630, 2631, -1, + 2631, 2615, 2614, -1, 2615, 2631, 2633, -1, + 2633, 4334, 2615, -1, 4334, 2633, 4301, -1, + 4301, 4335, 4334, -1, 4335, 4301, 4299, -1, + 4299, 4336, 4335, -1, 4336, 4299, 4297, -1, + 4297, 4337, 4336, -1, 4337, 4297, 4295, -1, + 4295, 4338, 4337, -1, 4338, 4295, 4294, -1, + 4294, 4339, 4338, -1, 4339, 4294, 4340, -1, + 4341, 4342, 4343, -1, 4341, 4343, 4344, -1, + 4345, 4346, 4347, -1, 4345, 4348, 4346, -1, + 4349, 4350, 4348, -1, 4348, 4345, 4349, -1, + 4343, 4351, 4349, -1, 4349, 4352, 4343, -1, + 4352, 4349, 4345, -1, 4352, 4345, 4353, -1, + 4354, 4355, 4356, -1, 4354, 4357, 4355, -1, + 4357, 4354, 4358, -1, 4358, 4353, 4357, -1, + 4353, 4358, 4359, -1, 4359, 4352, 4353, -1, + 4352, 4359, 4360, -1, 4360, 4343, 4352, -1, + 4360, 4344, 4343, -1, 4360, 4361, 4344, -1, + 4361, 4360, 4359, -1, 4359, 4362, 4361, -1, + 4362, 4359, 4358, -1, 4358, 4363, 4362, -1, + 4363, 4358, 4354, -1, 4354, 4356, 4363, -1, + 4356, 4364, 4363, -1, 4356, 4365, 4364, -1, + 4365, 4356, 4366, -1, 4366, 4367, 4365, -1, + 4367, 4366, 4368, -1, 4368, 4369, 4367, -1, + 4369, 4368, 4370, -1, 4370, 4371, 4369, -1, + 4371, 4370, 4372, -1, 4372, 4373, 4371, -1, + 4373, 4372, 4374, -1, 4374, 4375, 4373, -1, + 4375, 4374, 4376, -1, 4376, 4377, 4375, -1, + 4377, 4376, 4378, -1, 4378, 4379, 4377, -1, + 4379, 4378, 4380, -1, 4380, 4381, 4379, -1, + 4381, 4380, 4382, -1, 4382, 4383, 4381, -1, + 4383, 4382, 4384, -1, 4384, 4385, 4383, -1, + 4385, 4384, 4386, -1, 4386, 4387, 4385, -1, + 4387, 4386, 4388, -1, 4388, 4389, 4387, -1, + 4389, 4388, 4390, -1, 4390, 4391, 4389, -1, + 4391, 4390, 4392, -1, 4392, 4393, 4391, -1, + 4393, 4392, 4394, -1, 4394, 4395, 4393, -1, + 4395, 4394, 4396, -1, 4396, 4397, 4395, -1, + 4397, 4396, 4398, -1, 4398, 4399, 4397, -1, + 4399, 4398, 4400, -1, 4400, 4401, 4399, -1, + 4401, 4400, 4402, -1, 4402, 4403, 4401, -1, + 4403, 4402, 4404, -1, 4404, 4405, 4403, -1, + 4405, 4404, 4406, -1, 4406, 4407, 4405, -1, + 4407, 4406, 4408, -1, 4408, 4409, 4407, -1, + 4409, 4408, 4340, -1, 4340, 4410, 4409, -1, + 4410, 4340, 4294, -1, 4294, 4293, 4410, -1, + 4293, 4411, 4410, -1, 4411, 4293, 4296, -1, + 4296, 4412, 4411, -1, 4412, 4296, 4298, -1, + 4298, 4413, 4412, -1, 4413, 4298, 4300, -1, + 4300, 2613, 4413, -1, 2613, 4300, 4292, -1, + 4292, 2611, 2613, -1, 2611, 4292, 4291, -1, + 4291, 2608, 2611, -1, 2608, 4291, 4288, -1, + 4288, 2609, 2608, -1, 2609, 4288, 4287, -1, + 4287, 4414, 2609, -1, 4414, 4287, 4284, -1, + 4284, 2685, 4414, -1, 4414, 2685, 2687, -1, + 2687, 2609, 4414, -1, 2609, 2687, 2651, -1, + 2651, 2610, 2609, -1, 2610, 2651, 2650, -1, + 2650, 2612, 2610, -1, 2612, 2650, 2648, -1, + 2648, 2613, 2612, -1, 2613, 2648, 2647, -1, + 2647, 4413, 2613, -1, 4413, 2647, 2689, -1, + 2689, 4412, 4413, -1, 4412, 2689, 2691, -1, + 2691, 4411, 4412, -1, 4411, 2691, 2693, -1, + 2693, 4410, 4411, -1, 4410, 2693, 2748, -1, + 2748, 4409, 4410, -1, 4409, 2748, 2746, -1, + 2746, 4407, 4409, -1, 4407, 2746, 2744, -1, + 2744, 4405, 4407, -1, 4405, 2744, 2742, -1, + 2742, 4403, 4405, -1, 4403, 2742, 2740, -1, + 2740, 4401, 4403, -1, 4401, 2740, 2738, -1, + 2738, 4399, 4401, -1, 4399, 2738, 2736, -1, + 2736, 4397, 4399, -1, 4397, 2736, 2734, -1, + 2734, 4395, 4397, -1, 4395, 2734, 2732, -1, + 2732, 4393, 4395, -1, 4393, 2732, 2730, -1, + 2730, 4391, 4393, -1, 4391, 2730, 2728, -1, + 2728, 4389, 4391, -1, 4389, 2728, 2726, -1, + 2726, 4387, 4389, -1, 4387, 2726, 2724, -1, + 2724, 4385, 4387, -1, 4385, 2724, 2722, -1, + 2722, 4383, 4385, -1, 4383, 2722, 2720, -1, + 2720, 4381, 4383, -1, 4381, 2720, 2718, -1, + 2718, 4379, 4381, -1, 4379, 2718, 2716, -1, + 2716, 4377, 4379, -1, 4377, 2716, 2714, -1, + 2714, 4375, 4377, -1, 4375, 2714, 2712, -1, + 2712, 4373, 4375, -1, 4373, 2712, 2710, -1, + 2710, 4371, 4373, -1, 4371, 2710, 2708, -1, + 2708, 4369, 4371, -1, 4369, 2708, 2706, -1, + 2706, 4367, 4369, -1, 4367, 2706, 2704, -1, + 2704, 4365, 4367, -1, 4365, 2704, 2702, -1, + 2702, 4364, 4365, -1, 4364, 2702, 2700, -1, + 2700, 4415, 4364, -1, 4415, 2700, 2695, -1, + 2695, 2694, 4415, -1, 4416, 4417, 4418, -1, + 4417, 4416, 4419, -1, 4417, 4419, 2694, -1, + 4420, 2694, 4419, -1, 4420, 4415, 2694, -1, + 4415, 4420, 4421, -1, 4421, 4364, 4415, -1, + 4421, 4363, 4364, -1, 4421, 4362, 4363, -1, + 4362, 4421, 4420, -1, 4420, 4361, 4362, -1, + 4361, 4420, 4419, -1, 4419, 4344, 4361, -1, + 4344, 4419, 4416, -1, 4416, 4341, 4344, -1, + 4416, 4418, 4341, -1, 2607, 4341, 4418, -1, + 2607, 4422, 4341, -1, 4422, 2607, 2603, -1, + 2603, 2605, 4422, -1, 4423, 4422, 2605, -1, + 4423, 4341, 4422, -1, 4423, 4342, 4341, -1, + 4423, 2605, 4342, -1, 4424, 4342, 2605, -1, + 4425, 4424, 4426, -1, 4425, 4342, 4424, -1, + 4425, 4343, 4342, -1, 4425, 4426, 4343, -1, + 4426, 4351, 4343, -1, 4351, 4426, 4424, -1, + 4351, 4424, 4427, -1, 4427, 4349, 4351, -1, + 4427, 4350, 4349, -1, 4427, 4424, 4350, -1, + 4424, 4428, 4350, -1, 2605, 2606, 2599, -1, + 4429, 2599, 2606, -1, 4429, 4430, 2599, -1, + 4429, 4431, 4430, -1, 4429, 2606, 4431, -1, + 4431, 2606, 2607, -1, 4431, 2607, 4432, -1, + 4433, 4434, 4435, -1, 4434, 4433, 4432, -1, + 4434, 4432, 2607, -1, 4434, 2607, 4418, -1, + 4418, 4435, 4434, -1, 4435, 4418, 4417, -1, + 4417, 2694, 4435, -1, 2694, 2696, 4435, -1, + 4436, 4435, 2696, -1, 4436, 4433, 4435, -1, + 4433, 4436, 4437, -1, 4437, 4432, 4433, -1, + 4432, 4437, 4438, -1, 4438, 4431, 4432, -1, + 4438, 4439, 4431, -1, 4438, 4440, 4439, -1, + 4440, 4438, 4437, -1, 4437, 4441, 4440, -1, + 4441, 4437, 4436, -1, 4436, 2696, 4441, -1, + 2696, 2698, 4441, -1, 4442, 4441, 2698, -1, + 4442, 4440, 4441, -1, 4440, 4442, 4443, -1, + 4443, 4439, 4440, -1, 4439, 4443, 2272, -1, + 2272, 2270, 4439, -1, 2270, 4431, 4439, -1, + 2270, 4430, 4431, -1, 4430, 2270, 2269, -1, + 2269, 2599, 4430, -1, 2269, 2268, 2599, -1, + 2268, 2597, 2599, -1, 2597, 2268, 2271, -1, + 2271, 2600, 2597, -1, 2271, 2596, 2600, -1, + 2596, 2271, 2272, -1, 2272, 2595, 2596, -1, + 2595, 2272, 4443, -1, 4443, 2594, 2595, -1, + 2594, 4443, 4442, -1, 4442, 2698, 2594, -1, + 2698, 2527, 2594, -1, 2698, 2529, 2527, -1, + 2529, 2698, 2697, -1, 2697, 2531, 2529, -1, + 2531, 2697, 2699, -1, 2699, 2533, 2531, -1, + 2533, 2699, 2701, -1, 2701, 2535, 2533, -1, + 2535, 2701, 2703, -1, 2703, 2537, 2535, -1, + 2537, 2703, 2705, -1, 2705, 2539, 2537, -1, + 2539, 2705, 2707, -1, 2707, 2541, 2539, -1, + 2541, 2707, 2709, -1, 2709, 2543, 2541, -1, + 2543, 2709, 2711, -1, 2711, 2545, 2543, -1, + 2545, 2711, 2713, -1, 2713, 2547, 2545, -1, + 2547, 2713, 2715, -1, 2715, 2549, 2547, -1, + 2549, 2715, 2717, -1, 2717, 2551, 2549, -1, + 2551, 2717, 2719, -1, 2719, 2553, 2551, -1, + 2553, 2719, 2721, -1, 2721, 2555, 2553, -1, + 2555, 2721, 2723, -1, 2723, 2557, 2555, -1, + 2557, 2723, 2725, -1, 2725, 2559, 2557, -1, + 2559, 2725, 2727, -1, 2727, 2561, 2559, -1, + 2561, 2727, 2729, -1, 2729, 2563, 2561, -1, + 2563, 2729, 2731, -1, 2731, 2565, 2563, -1, + 2565, 2731, 2733, -1, 2733, 2567, 2565, -1, + 2567, 2733, 2735, -1, 2735, 2569, 2567, -1, + 2569, 2735, 2737, -1, 2737, 2571, 2569, -1, + 2571, 2737, 2739, -1, 2739, 2573, 2571, -1, + 2573, 2739, 2741, -1, 2741, 4444, 2573, -1, + 4444, 2741, 2743, -1, 2743, 4445, 4444, -1, + 4445, 2743, 2745, -1, 2745, 4446, 4445, -1, + 4446, 2745, 2747, -1, 2747, 4447, 4446, -1, + 4447, 2747, 2749, -1, 2749, 4448, 4447, -1, + 4448, 2749, 2750, -1, 2750, 2267, 4448, -1, + 2267, 2750, 2639, -1, 2639, 2265, 2267, -1, + 2265, 2639, 2638, -1, 2638, 2262, 2265, -1, + 2262, 2638, 2636, -1, 2636, 2263, 2262, -1, + 2263, 2636, 2635, -1, 2635, 4449, 2263, -1, + 4449, 2635, 2751, -1, 2751, 4450, 4449, -1, + 4450, 2751, 2752, -1, 2752, 4451, 4450, -1, + 4451, 2752, 2753, -1, 2753, 4452, 4451, -1, + 4452, 2753, 2754, -1, 2754, 4453, 4452, -1, + 4453, 2754, 2755, -1, 2755, 4454, 4453, -1, + 4454, 2755, 2756, -1, 2756, 4455, 4454, -1, + 4455, 2756, 2757, -1, 2757, 4456, 4455, -1, + 4456, 2757, 2758, -1, 2758, 4457, 4456, -1, + 4457, 2758, 2759, -1, 2759, 4458, 4457, -1, + 4458, 2759, 2760, -1, 2760, 4459, 4458, -1, + 4459, 2760, 2761, -1, 2761, 4460, 4459, -1, + 4460, 2761, 2762, -1, 2762, 4461, 4460, -1, + 4461, 2762, 2763, -1, 2763, 4462, 4461, -1, + 4462, 2763, 2764, -1, 2764, 4463, 4462, -1, + 4463, 2764, 2765, -1, 2765, 4464, 4463, -1, + 4464, 2765, 2766, -1, 2766, 4465, 4464, -1, + 4465, 2766, 2767, -1, 2767, 2770, 4465, -1, + 4466, 4465, 2770, -1, 4466, 2770, 2771, -1, + 4466, 2771, 2775, -1, 2775, 4465, 4466, -1, + 2775, 2776, 4465, -1, 4465, 2776, 2777, -1, + 2777, 4464, 4465, -1, 4464, 2777, 4262, -1, + 4262, 4463, 4464, -1, 4463, 4262, 4261, -1, + 4261, 4462, 4463, -1, 4462, 4261, 4260, -1, + 4260, 4461, 4462, -1, 4461, 4260, 4259, -1, + 4259, 4460, 4461, -1, 4460, 4259, 4258, -1, + 4258, 4459, 4460, -1, 4459, 4258, 4257, -1, + 4257, 4458, 4459, -1, 4458, 4257, 4256, -1, + 4256, 4457, 4458, -1, 4457, 4256, 4255, -1, + 4255, 4456, 4457, -1, 4456, 4255, 4254, -1, + 4254, 4455, 4456, -1, 4455, 4254, 4253, -1, + 4253, 4454, 4455, -1, 4454, 4253, 4252, -1, + 4252, 4453, 4454, -1, 4453, 4252, 4251, -1, + 4251, 4452, 4453, -1, 4452, 4251, 4250, -1, + 4250, 4451, 4452, -1, 4451, 4250, 4249, -1, + 4249, 4450, 4451, -1, 4450, 4249, 4248, -1, + 4248, 4449, 4450, -1, 4449, 4248, 4247, -1, + 4247, 2263, 4449, -1, 2263, 4247, 2779, -1, + 2779, 2264, 2263, -1, 2264, 2779, 2778, -1, + 2778, 2266, 2264, -1, 2266, 2778, 2781, -1, + 2781, 2267, 2266, -1, 2267, 2781, 2783, -1, + 2783, 4448, 2267, -1, 4448, 2783, 4072, -1, + 4072, 4447, 4448, -1, 4447, 4072, 4073, -1, + 4073, 4446, 4447, -1, 4446, 4073, 4074, -1, + 4074, 4445, 4446, -1, 4445, 4074, 4075, -1, + 4075, 4444, 4445, -1, 4444, 4075, 4076, -1, + 4076, 2573, 4444, -1, 2573, 4076, 4077, -1, + 4077, 2572, 2573, -1, 2572, 4077, 4078, -1, + 4078, 2574, 2572, -1, 2574, 4078, 4079, -1, + 4079, 2575, 2574, -1, 2575, 4079, 4080, -1, + 4080, 2576, 2575, -1, 2576, 4080, 4081, -1, + 4081, 2577, 2576, -1, 2577, 4081, 4132, -1, + 4132, 2578, 2577, -1, 2578, 4132, 4130, -1, + 4130, 2579, 2578, -1, 2579, 4130, 4099, -1, + 4099, 2580, 2579, -1, 2580, 4099, 4097, -1, + 4097, 2514, 2580, -1, 2514, 4097, 4095, -1, + 4095, 2513, 2514, -1, 2513, 4095, 4092, -1, + 4092, 2511, 2513, -1, 2511, 4092, 4094, -1, + 4094, 2509, 2511, -1, 2509, 4094, 4104, -1, + 4104, 2507, 2509, -1, 2507, 4104, 4106, -1, + 4106, 2505, 2507, -1, 2505, 4106, 4108, -1, + 4108, 2503, 2505, -1, 2503, 4108, 4110, -1, + 4110, 2501, 2503, -1, 2501, 4110, 4112, -1, + 4112, 2499, 2501, -1, 2499, 4112, 4114, -1, + 4114, 2497, 2499, -1, 2497, 4114, 4116, -1, + 4116, 2495, 2497, -1, 2495, 4116, 4118, -1, + 4118, 2492, 2495, -1, 2492, 4118, 4119, -1, + 4119, 2493, 2492, -1, 2493, 4119, 4121, -1, + 4121, 2581, 2493, -1, 2581, 4121, 4467, -1, + 4467, 2582, 2581, -1, 2582, 4467, 4468, -1, + 4468, 2583, 2582, -1, 2583, 4468, 4469, -1, + 4469, 2584, 2583, -1, 2584, 4469, 4470, -1, + 4470, 2585, 2584, -1, 2585, 4470, 4471, -1, + 4471, 2586, 2585, -1, 2586, 4471, 4472, -1, + 4472, 2587, 2586, -1, 2587, 4472, 4473, -1, + 4473, 2588, 2587, -1, 2588, 4473, 4474, -1, + 4474, 2589, 2588, -1, 2589, 4474, 4475, -1, + 4475, 2490, 2589, -1, 2490, 4475, 4476, -1, + 4476, 2482, 2490, -1, 4476, 2479, 2482, -1, + 2479, 4476, 4477, -1, 4477, 2477, 2479, -1, + 2477, 4477, 4478, -1, 4478, 2459, 2477, -1, + 4478, 2460, 2459, -1, 4478, 4479, 2460, -1, + 4479, 4478, 4477, -1, 4477, 4480, 4479, -1, + 4480, 4477, 4476, -1, 4480, 4476, 4475, -1, + 4475, 4481, 4480, -1, 4481, 4475, 4474, -1, + 4474, 4482, 4481, -1, 4482, 4474, 4473, -1, + 4473, 4483, 4482, -1, 4483, 4473, 4472, -1, + 4472, 4484, 4483, -1, 4484, 4472, 4471, -1, + 4471, 4485, 4484, -1, 4485, 4471, 4470, -1, + 4470, 4486, 4485, -1, 4486, 4470, 4469, -1, + 4469, 4487, 4486, -1, 4487, 4469, 4468, -1, + 4468, 4488, 4487, -1, 4488, 4468, 4467, -1, + 4467, 4489, 4488, -1, 4489, 4467, 4121, -1, + 4121, 4490, 4489, -1, 4490, 4121, 4120, -1, + 4490, 4120, 4122, -1, 4490, 4122, 4159, -1, + 4159, 4489, 4490, -1, 4489, 4159, 4160, -1, + 4160, 4488, 4489, -1, 4488, 4160, 4161, -1, + 4161, 4487, 4488, -1, 4487, 4161, 4162, -1, + 4162, 4486, 4487, -1, 4486, 4162, 4163, -1, + 4163, 4485, 4486, -1, 4485, 4163, 4164, -1, + 4164, 4484, 4485, -1, 4484, 4164, 4165, -1, + 4165, 4483, 4484, -1, 4483, 4165, 4166, -1, + 4166, 4482, 4483, -1, 4482, 4166, 4167, -1, + 4167, 4481, 4482, -1, 4481, 4167, 4168, -1, + 4168, 4480, 4481, -1, 4168, 4479, 4480, -1, + 4479, 4168, 4169, -1, 4169, 2460, 4479, -1, + 2460, 4169, 4170, -1, 4170, 2461, 2460, -1, + 2461, 4170, 4171, -1, 4171, 2463, 2461, -1, + 2463, 4171, 4172, -1, 4172, 2465, 2463, -1, + 2465, 4172, 4173, -1, 4173, 2467, 2465, -1, + 2467, 4173, 4174, -1, 4174, 2469, 2467, -1, + 2469, 4174, 4175, -1, 4175, 2471, 2469, -1, + 2471, 4175, 4176, -1, 4176, 2473, 2471, -1, + 2473, 4176, 4177, -1, 4177, 2475, 2473, -1, + 2475, 4177, 4178, -1, 4178, 2457, 2475, -1, + 2457, 4178, 4179, -1, 4179, 2456, 2457, -1, + 2456, 4179, 4180, -1, 4180, 2455, 2456, -1, + 2455, 4180, 4181, -1, 4181, 2454, 2455, -1, + 2454, 4181, 4182, -1, 4182, 2453, 2454, -1, + 2453, 4182, 4183, -1, 4183, 2452, 2453, -1, + 2452, 4183, 4184, -1, 4184, 2451, 2452, -1, + 2451, 4184, 4185, -1, 4185, 2450, 2451, -1, + 2450, 4185, 3155, -1, 3155, 2449, 2450, -1, + 2449, 3155, 3154, -1, 3154, 2448, 2449, -1, + 2448, 3154, 3152, -1, 3152, 2447, 2448, -1, + 2447, 3152, 3150, -1, 3150, 2446, 2447, -1, + 2446, 3150, 3148, -1, 3148, 2445, 2446, -1, + 2445, 3148, 3146, -1, 3146, 2444, 2445, -1, + 2444, 3146, 3144, -1, 3144, 2443, 2444, -1, + 2443, 3144, 3143, -1, 3143, 2442, 2443, -1, + 2442, 3143, 3141, -1, 3141, 2441, 2442, -1, + 2441, 3141, 3140, -1, 3140, 2440, 2441, -1, + 2440, 3140, 3138, -1, 3138, 2439, 2440, -1, + 2439, 3138, 3136, -1, 3136, 2437, 2439, -1, + 2437, 3136, 3135, -1, 3135, 2438, 2437, -1, + 2438, 3135, 3131, -1, 3131, 4491, 2438, -1, + 4491, 3131, 3127, -1, 3127, 4492, 4491, -1, + 4492, 3127, 3126, -1, 3126, 4493, 4492, -1, + 4493, 3126, 3125, -1, 3125, 4494, 4493, -1, + 4494, 3125, 3124, -1, 3124, 4495, 4494, -1, + 4495, 3124, 3123, -1, 3123, 4496, 4495, -1, + 4496, 3123, 3122, -1, 3122, 4497, 4496, -1, + 4497, 3122, 3121, -1, 3121, 4498, 4497, -1, + 4498, 3121, 3120, -1, 3120, 4499, 4498, -1, + 4499, 3120, 3119, -1, 3119, 4500, 4499, -1, + 4500, 3119, 3118, -1, 3118, 4501, 4500, -1, + 4501, 3118, 3117, -1, 3117, 4502, 4501, -1, + 4502, 3117, 3116, -1, 3116, 4503, 4502, -1, + 4503, 3116, 3115, -1, 3115, 4504, 4503, -1, + 4504, 3115, 3114, -1, 3114, 4505, 4504, -1, + 4505, 3114, 3113, -1, 3113, 4506, 4505, -1, + 4506, 3113, 3112, -1, 3112, 4507, 4506, -1, + 4507, 3112, 3111, -1, 3111, 4508, 4507, -1, + 4508, 3111, 3110, -1, 3110, 4509, 4508, -1, + 4509, 3110, 3109, -1, 3109, 4510, 4509, -1, + 4510, 3109, 3108, -1, 3108, 4511, 4510, -1, + 4511, 3108, 3107, -1, 3107, 4512, 4511, -1, + 4512, 3107, 3106, -1, 3106, 4513, 4512, -1, + 4513, 3106, 3105, -1, 3105, 4514, 4513, -1, + 4514, 3105, 3104, -1, 3104, 4515, 4514, -1, + 4515, 3104, 2259, -1, 2259, 2261, 4515, -1, + 4516, 4517, 4518, -1, 4517, 4516, 4519, -1, + 4519, 4520, 4517, -1, 4520, 4519, 4521, -1, + 4522, 4523, 4524, -1, 4524, 4525, 4522, -1, + 4526, 4527, 4528, -1, 4528, 4529, 4526, -1, + 4529, 4528, 4530, -1, 4530, 4531, 4529, -1, + 4531, 4530, 4532, -1, 4532, 4533, 4531, -1, + 4533, 4532, 4525, -1, 4525, 4524, 4533, -1, + 4524, 4534, 4533, -1, 4534, 4524, 4523, -1, + 4523, 4535, 4534, -1, 4535, 4523, 4536, -1, + 4537, 4538, 4539, -1, 4539, 4540, 4537, -1, + 4540, 4539, 4541, -1, 4541, 4542, 4540, -1, + 4542, 4541, 4543, -1, 4543, 4544, 4542, -1, + 4544, 4543, 4545, -1, 4545, 4546, 4544, -1, + 4546, 4545, 4547, -1, 4547, 4548, 4546, -1, + 4548, 4547, 4549, -1, 4549, 4550, 4548, -1, + 4550, 4549, 4551, -1, 4551, 4552, 4550, -1, + 4552, 4551, 4553, -1, 4553, 4554, 4552, -1, + 4554, 4553, 4555, -1, 4555, 4556, 4554, -1, + 4556, 4555, 4557, -1, 4557, 4558, 4556, -1, + 4558, 4557, 4559, -1, 4559, 4560, 4558, -1, + 4560, 4559, 4561, -1, 4561, 4562, 4560, -1, + 4562, 4561, 4563, -1, 4563, 4564, 4562, -1, + 4564, 4563, 4565, -1, 4565, 4566, 4564, -1, + 4566, 4565, 4536, -1, 4536, 4567, 4566, -1, + 4567, 4536, 4523, -1, 4523, 4522, 4567, -1, + 4522, 4568, 4567, -1, 4568, 4522, 4525, -1, + 4525, 4569, 4568, -1, 4569, 4525, 4532, -1, + 4532, 4570, 4569, -1, 4570, 4532, 4530, -1, + 4530, 4571, 4570, -1, 4571, 4530, 4528, -1, + 4528, 4572, 4571, -1, 4572, 4528, 4527, -1, + 4527, 4573, 4572, -1, 4574, 4575, 4576, -1, + 4577, 4576, 4575, -1, 4578, 4579, 4576, -1, + 4580, 4581, 4582, -1, 4580, 4583, 4581, -1, + 4584, 4585, 4586, -1, 4585, 4584, 4583, -1, + 4583, 4580, 4585, -1, 4580, 4587, 4585, -1, + 4580, 4582, 4587, -1, 4588, 4589, 4590, -1, + 4589, 4588, 4591, -1, 4591, 4592, 4589, -1, + 4592, 4591, 4593, -1, 4593, 4594, 4592, -1, + 4594, 4593, 4595, -1, 4595, 4596, 4594, -1, + 4596, 4595, 4597, -1, 4597, 4598, 4596, -1, + 4598, 4597, 4599, -1, 4599, 4600, 4598, -1, + 4600, 4599, 4601, -1, 4601, 4602, 4600, -1, + 4602, 4601, 4603, -1, 4603, 4604, 4602, -1, + 4605, 4606, 4607, -1, 4607, 4608, 4605, -1, + 4608, 4607, 4609, -1, 4609, 4610, 4608, -1, + 4611, 4608, 4610, -1, 4610, 4612, 4611, -1, + 4612, 4610, 4613, -1, 4613, 4604, 4612, -1, + 4614, 4612, 4604, -1, 4604, 4603, 4614, -1, + 4615, 4616, 4614, -1, 4614, 4617, 4615, -1, + 4617, 4614, 4603, -1, 4603, 4618, 4617, -1, + 4618, 4603, 4601, -1, 4601, 4619, 4618, -1, + 4619, 4601, 4599, -1, 4599, 4620, 4619, -1, + 4620, 4599, 4597, -1, 4597, 4621, 4620, -1, + 4621, 4597, 4595, -1, 4595, 4622, 4621, -1, + 4622, 4595, 4593, -1, 4593, 4623, 4622, -1, + 4623, 4593, 4591, -1, 4591, 4624, 4623, -1, + 4624, 4591, 4588, -1, 4588, 4625, 4624, -1, + 4625, 4588, 4590, -1, 4590, 4626, 4625, -1, + 4626, 4590, 4627, -1, 4627, 4628, 4626, -1, + 4628, 4627, 4629, -1, 4629, 4630, 4628, -1, + 4630, 4629, 4631, -1, 4631, 4632, 4630, -1, + 4632, 4631, 4633, -1, 4633, 4634, 4632, -1, + 4634, 4633, 4635, -1, 4635, 4636, 4634, -1, + 4636, 4635, 4637, -1, 4637, 4638, 4636, -1, + 4638, 4637, 4639, -1, 4639, 4640, 4638, -1, + 4640, 4639, 4641, -1, 4641, 4642, 4640, -1, + 4642, 4641, 4643, -1, 4643, 4644, 4642, -1, + 4644, 4643, 4645, -1, 4645, 4646, 4644, -1, + 4646, 4645, 4647, -1, 4647, 4648, 4646, -1, + 4648, 4647, 4649, -1, 4649, 4650, 4648, -1, + 4650, 4649, 4651, -1, 4651, 4652, 4650, -1, + 4652, 4651, 4653, -1, 4653, 4654, 4652, -1, + 4654, 4653, 4655, -1, 4655, 4582, 4654, -1, + 4582, 4655, 4656, -1, 4656, 4587, 4582, -1, + 4587, 4656, 4657, -1, 4587, 4657, 4658, -1, + 4659, 4660, 4661, -1, 4660, 4659, 4662, -1, + 4662, 4663, 4660, -1, 4664, 4665, 4666, -1, + 4666, 4667, 4664, -1, 4667, 4666, 4668, -1, + 4668, 4669, 4667, -1, 4670, 4671, 4672, -1, + 4671, 4673, 4672, -1, 4672, 4673, 4674, -1, + 4674, 4675, 4672, -1, 4675, 4676, 4677, -1, + 4675, 4674, 4676, -1, 4678, 4679, 4674, -1, + 4680, 4681, 4682, -1, 4680, 4682, 4679, -1, + 4682, 4674, 4679, -1, 4682, 4676, 4674, -1, + 4676, 4682, 4683, -1, 4683, 4684, 4676, -1, + 4684, 4683, 4685, -1, 4685, 4686, 4684, -1, + 4686, 4685, 4687, -1, 4687, 4688, 4686, -1, + 4688, 4687, 4689, -1, 4689, 4690, 4688, -1, + 4690, 4689, 4691, -1, 4691, 4692, 4690, -1, + 4692, 4691, 4693, -1, 4693, 4694, 4692, -1, + 4694, 4693, 4695, -1, 4695, 4696, 4694, -1, + 4696, 4695, 4697, -1, 4697, 4698, 4696, -1, + 4698, 4697, 4699, -1, 4699, 4700, 4698, -1, + 4700, 4699, 4669, -1, 4669, 4668, 4700, -1, + 4701, 4700, 4668, -1, 4668, 4666, 4701, -1, + 4701, 4702, 4703, -1, 4702, 4701, 4666, -1, + 4666, 4704, 4702, -1, 4704, 4666, 4665, -1, + 4665, 4705, 4704, -1, 4705, 4665, 4706, -1, + 4706, 4707, 4705, -1, 4708, 4709, 4710, -1, + 4710, 4711, 4708, -1, 4712, 4711, 4710, -1, + 4712, 4710, 4713, -1, 4710, 4714, 4713, -1, + 4710, 4715, 4714, -1, 4715, 4710, 4709, -1, + 4709, 4716, 4715, -1, 4716, 4709, 4717, -1, + 4716, 4717, 4718, -1, 4719, 4718, 4717, -1, + 4719, 4720, 4718, -1, 4720, 4719, 4721, -1, + 4721, 4722, 4720, -1, 4723, 4724, 4725, -1, + 4725, 4726, 4723, -1, 4726, 4725, 4727, -1, + 4727, 4728, 4726, -1, 4728, 4727, 4729, -1, + 4729, 4730, 4728, -1, 4730, 4729, 4731, -1, + 4731, 4732, 4730, -1, 4732, 4731, 4733, -1, + 4733, 4734, 4732, -1, 4734, 4733, 4735, -1, + 4735, 4736, 4734, -1, 4736, 4735, 4737, -1, + 4737, 4738, 4736, -1, 4738, 4737, 4722, -1, + 4722, 4721, 4738, -1, 4721, 4739, 4738, -1, + 4739, 4721, 4719, -1, 4719, 4717, 4739, -1, + 4717, 4740, 4739, -1, 4717, 4741, 4740, -1, + 4741, 4717, 4709, -1, 4709, 4708, 4741, -1, + 4742, 4743, 4708, -1, 4743, 4742, 4744, -1, + 4745, 4746, 4747, -1, 4748, 4749, 4750, -1, + 4749, 4748, 4751, -1, 4752, 4753, 4754, -1, + 4752, 4755, 4753, -1, 4752, 4756, 4755, -1, + 4752, 4754, 4756, -1, 4756, 4754, 4757, -1, + 4757, 4755, 4756, -1, 4757, 4758, 4755, -1, + 4758, 4757, 4759, -1, 4759, 4757, 4754, -1, + 4754, 4760, 4759, -1, 4760, 4754, 4761, -1, + 4761, 4762, 4760, -1, 4762, 4761, 4763, -1, + 4763, 4764, 4762, -1, 4764, 4763, 4765, -1, + 4765, 4766, 4764, -1, 4766, 4765, 4767, -1, + 4767, 4768, 4766, -1, 4768, 4767, 4769, -1, + 4769, 4770, 4768, -1, 4770, 4769, 4771, -1, + 4771, 4772, 4770, -1, 4772, 4771, 4773, -1, + 4773, 4774, 4772, -1, 4774, 4773, 4775, -1, + 4775, 4776, 4774, -1, 4776, 4775, 4777, -1, + 4777, 4778, 4776, -1, 4778, 4777, 4779, -1, + 4779, 4780, 4778, -1, 4780, 4779, 4781, -1, + 4781, 4782, 4780, -1, 4782, 4781, 4783, -1, + 4783, 4784, 4782, -1, 4785, 4786, 4787, -1, + 4785, 4788, 4786, -1, 4788, 4785, 4789, -1, + 4789, 4790, 4788, -1, 4790, 4789, 4791, -1, + 4791, 4792, 4790, -1, 4792, 4791, 4793, -1, + 4793, 4794, 4792, -1, 4794, 4793, 4795, -1, + 4796, 4797, 4798, -1, 4797, 4796, 4799, -1, + 4799, 4800, 4797, -1, 4800, 4799, 4801, -1, + 4801, 4802, 4800, -1, 4802, 4801, 4795, -1, + 4795, 4803, 4802, -1, 4803, 4795, 4793, -1, + 4793, 4804, 4803, -1, 4804, 4793, 4791, -1, + 4791, 4805, 4804, -1, 4805, 4791, 4789, -1, + 4789, 4806, 4805, -1, 4806, 4789, 4785, -1, + 4785, 4787, 4806, -1, 4807, 4808, 4809, -1, + 4807, 4809, 4810, -1, 4810, 4811, 4807, -1, + 4811, 4812, 4813, -1, 4813, 4807, 4811, -1, + 4807, 4813, 4814, -1, 4814, 4808, 4807, -1, + 4808, 4814, 4815, -1, 4815, 4816, 4808, -1, + 4816, 4815, 4817, -1, 4817, 4818, 4816, -1, + 4818, 4817, 4819, -1, 4819, 4820, 4818, -1, + 4820, 4819, 4821, -1, 4821, 4822, 4820, -1, + 4822, 4821, 4823, -1, 4823, 4824, 4822, -1, + 4825, 4826, 4827, -1, 4827, 4828, 4825, -1, + 4828, 4827, 4824, -1, 4824, 4823, 4828, -1, + 4787, 4828, 4823, -1, 4823, 4806, 4787, -1, + 4806, 4823, 4821, -1, 4821, 4805, 4806, -1, + 4805, 4821, 4819, -1, 4819, 4804, 4805, -1, + 4804, 4819, 4817, -1, 4817, 4803, 4804, -1, + 4803, 4817, 4815, -1, 4815, 4802, 4803, -1, + 4802, 4815, 4814, -1, 4814, 4800, 4802, -1, + 4800, 4814, 4813, -1, 4813, 4797, 4800, -1, + 4797, 4813, 4812, -1, 4812, 4798, 4797, -1, + 4829, 4830, 4831, -1, 4578, 4831, 4830, -1, + 4831, 4578, 4798, -1, 4798, 4812, 4831, -1, + 4832, 4833, 4831, -1, 4832, 4831, 4812, -1, + 4812, 4811, 4832, -1, 4834, 4835, 4836, -1, + 4832, 4836, 4835, -1, 4836, 4832, 4811, -1, + 4811, 4810, 4836, -1, 4837, 4838, 4836, -1, + 4837, 4836, 4810, -1, 4810, 4839, 4837, -1, + 4839, 4810, 4809, -1, 4809, 4840, 4839, -1, + 4809, 4841, 4840, -1, 4842, 4843, 4841, -1, + 4841, 4844, 4842, -1, 4844, 4841, 4809, -1, + 4844, 4809, 4808, -1, 4844, 4808, 4816, -1, + 4816, 4842, 4844, -1, 4842, 4816, 4818, -1, + 4818, 4843, 4842, -1, 4843, 4818, 4820, -1, + 4820, 4845, 4843, -1, 4845, 4820, 4822, -1, + 4822, 4846, 4845, -1, 4846, 4822, 4824, -1, + 4824, 4847, 4846, -1, 4847, 4824, 4827, -1, + 4827, 4848, 4847, -1, 4848, 4827, 4826, -1, + 4826, 4849, 4848, -1, 4849, 4826, 4850, -1, + 4851, 4852, 4853, -1, 4853, 4854, 4851, -1, + 4854, 4853, 4855, -1, 4855, 4856, 4854, -1, + 4856, 4855, 4857, -1, 4857, 4858, 4856, -1, + 4858, 4857, 4859, -1, 4859, 4860, 4858, -1, + 4860, 4859, 4861, -1, 4861, 4862, 4860, -1, + 4862, 4861, 4863, -1, 4863, 4864, 4862, -1, + 4864, 4863, 4865, -1, 4865, 4866, 4864, -1, + 4866, 4865, 4867, -1, 4867, 4868, 4866, -1, + 4868, 4867, 4869, -1, 4869, 4870, 4868, -1, + 4870, 4869, 4871, -1, 4871, 4872, 4870, -1, + 4872, 4871, 4873, -1, 4873, 4874, 4872, -1, + 4874, 4873, 4875, -1, 4875, 4876, 4874, -1, + 4876, 4875, 4877, -1, 4877, 4878, 4876, -1, + 4878, 4877, 4879, -1, 4879, 4880, 4878, -1, + 4880, 4879, 4881, -1, 4881, 4882, 4880, -1, + 4882, 4881, 4883, -1, 4883, 4884, 4882, -1, + 4884, 4883, 4885, -1, 4885, 4886, 4884, -1, + 4886, 4885, 4887, -1, 4887, 4888, 4886, -1, + 4888, 4887, 4889, -1, 4889, 4890, 4888, -1, + 4890, 4889, 4891, -1, 4891, 4892, 4890, -1, + 4892, 4891, 4893, -1, 4893, 4894, 4892, -1, + 4894, 4893, 4895, -1, 4894, 4895, 4896, -1, + 4897, 4898, 4899, -1, 4899, 4900, 4897, -1, + 4900, 4899, 4901, -1, 4901, 4902, 4900, -1, + 4902, 4901, 4903, -1, 4903, 4904, 4902, -1, + 4904, 4903, 4905, -1, 4905, 4906, 4904, -1, + 4906, 4905, 4907, -1, 4907, 4908, 4906, -1, + 4908, 4907, 4909, -1, 4909, 4910, 4908, -1, + 4910, 4909, 4911, -1, 4911, 4912, 4910, -1, + 4912, 4911, 4913, -1, 4913, 4914, 4912, -1, + 4914, 4913, 4915, -1, 4915, 4916, 4914, -1, + 4916, 4915, 4917, -1, 4917, 4918, 4916, -1, + 4918, 4917, 4919, -1, 4919, 4920, 4918, -1, + 4920, 4919, 4921, -1, 4921, 4922, 4920, -1, + 4921, 4923, 4922, -1, 4923, 4921, 4924, -1, + 4924, 4925, 4923, -1, 4925, 4924, 4926, -1, + 4926, 4927, 4925, -1, 4927, 4926, 4928, -1, + 4928, 4895, 4927, -1, 4928, 4896, 4895, -1, + 4928, 4929, 4896, -1, 4929, 4928, 4926, -1, + 4926, 4930, 4929, -1, 4930, 4926, 4924, -1, + 4924, 4931, 4930, -1, 4931, 4924, 4921, -1, + 4931, 4921, 4919, -1, 4919, 4932, 4931, -1, + 4932, 4919, 4917, -1, 4917, 4933, 4932, -1, + 4933, 4917, 4915, -1, 4915, 4934, 4933, -1, + 4934, 4915, 4913, -1, 4913, 4935, 4934, -1, + 4935, 4913, 4911, -1, 4911, 4936, 4935, -1, + 4936, 4911, 4909, -1, 4909, 4937, 4936, -1, + 4937, 4909, 4907, -1, 4907, 4938, 4937, -1, + 4938, 4907, 4905, -1, 4905, 4939, 4938, -1, + 4939, 4905, 4903, -1, 4903, 4940, 4939, -1, + 4940, 4903, 4901, -1, 4901, 4941, 4940, -1, + 4941, 4901, 4899, -1, 4899, 4942, 4941, -1, + 4942, 4899, 4898, -1, 4898, 4943, 4942, -1, + 4943, 4898, 4944, -1, 4944, 4945, 4943, -1, + 4945, 4944, 4946, -1, 4946, 4947, 4945, -1, + 4947, 4946, 4948, -1, 4948, 4949, 4947, -1, + 4949, 4948, 4950, -1, 4950, 4951, 4949, -1, + 4951, 4950, 4952, -1, 4952, 4953, 4951, -1, + 4953, 4952, 4954, -1, 4954, 4955, 4953, -1, + 4955, 4954, 4956, -1, 4956, 4957, 4955, -1, + 4957, 4956, 4958, -1, 4958, 4959, 4957, -1, + 4959, 4958, 4960, -1, 4960, 4961, 4959, -1, + 4961, 4960, 4962, -1, 4962, 4963, 4961, -1, + 4963, 4962, 4964, -1, 4964, 4965, 4963, -1, + 4965, 4964, 4966, -1, 4966, 4967, 4965, -1, + 4967, 4966, 4968, -1, 4968, 4969, 4967, -1, + 4969, 4968, 4970, -1, 4971, 4972, 4973, -1, + 4973, 4974, 4971, -1, 4974, 4973, 4975, -1, + 4975, 4976, 4974, -1, 4976, 4975, 4977, -1, + 4977, 4978, 4976, -1, 4978, 4977, 4979, -1, + 4980, 4981, 4982, -1, 4982, 4983, 4980, -1, + 4983, 4982, 4984, -1, 4984, 4985, 4983, -1, + 4985, 4984, 4986, -1, 4986, 4987, 4985, -1, + 4987, 4986, 4988, -1, 4988, 4989, 4987, -1, + 4989, 4988, 4990, -1, 4990, 4991, 4989, -1, + 4991, 4990, 4992, -1, 4992, 4993, 4991, -1, + 4993, 4992, 4994, -1, 4994, 4995, 4993, -1, + 4995, 4994, 4996, -1, 4996, 4997, 4995, -1, + 4997, 4996, 4998, -1, 4998, 4999, 4997, -1, + 4999, 4998, 5000, -1, 5000, 5001, 4999, -1, + 5001, 5000, 5002, -1, 5002, 5003, 5001, -1, + 5003, 5002, 5004, -1, 5004, 5005, 5003, -1, + 5005, 5004, 5006, -1, 5006, 5007, 5005, -1, + 5007, 5006, 5008, -1, 5008, 5009, 5007, -1, + 5009, 5008, 5010, -1, 5010, 5011, 5009, -1, + 5011, 5010, 5012, -1, 5012, 5013, 5011, -1, + 5013, 5012, 5014, -1, 5014, 5015, 5013, -1, + 5015, 5014, 5016, -1, 5016, 5017, 5015, -1, + 5017, 5016, 5018, -1, 5018, 5019, 5017, -1, + 5019, 5018, 5020, -1, 5020, 5021, 5019, -1, + 5021, 5020, 5022, -1, 5022, 5023, 5021, -1, + 5023, 5022, 5024, -1, 5024, 5025, 5023, -1, + 5025, 5024, 5026, -1, 5026, 5027, 5025, -1, + 5027, 5026, 5028, -1, 5028, 5029, 5027, -1, + 5028, 5030, 5029, -1, 5030, 5028, 5031, -1, + 5031, 5032, 5030, -1, 5033, 5034, 5035, -1, + 5035, 5036, 5033, -1, 5036, 5035, 5037, -1, + 5037, 5038, 5036, -1, 5038, 5037, 5039, -1, + 5039, 5040, 5038, -1, 5040, 5039, 5041, -1, + 5041, 5042, 5040, -1, 5042, 5041, 5043, -1, + 5043, 5044, 5042, -1, 5044, 5043, 5045, -1, + 5045, 5046, 5044, -1, 5046, 5045, 5047, -1, + 5047, 5048, 5046, -1, 5048, 5047, 5049, -1, + 5049, 5050, 5048, -1, 5050, 5049, 5051, -1, + 5051, 5052, 5050, -1, 5052, 5051, 5053, -1, + 5053, 5054, 5052, -1, 5054, 5053, 5055, -1, + 5054, 5055, 5056, -1, 5057, 5056, 5058, -1, + 5058, 5056, 5055, -1, 5058, 5055, 5059, -1, + 5059, 5060, 5058, -1, 5060, 5059, 5061, -1, + 5061, 5062, 5060, -1, 5063, 5064, 5065, -1, + 5065, 5066, 5063, -1, 5067, 5068, 5069, -1, + 5069, 5070, 5067, -1, 5070, 5069, 5071, -1, + 5071, 5072, 5070, -1, 5072, 5071, 5073, -1, + 5073, 5074, 5072, -1, 5074, 5073, 5075, -1, + 5075, 5076, 5074, -1, 5076, 5075, 5077, -1, + 5077, 5078, 5076, -1, 5078, 5077, 5079, -1, + 5079, 5080, 5078, -1, 5080, 5079, 5081, -1, + 5081, 5082, 5080, -1, 5082, 5081, 5083, -1, + 5083, 5084, 5082, -1, 5084, 5083, 5085, -1, + 5085, 5086, 5084, -1, 5086, 5085, 5087, -1, + 5087, 5088, 5086, -1, 5088, 5087, 5089, -1, + 5089, 5090, 5088, -1, 5090, 5089, 5091, -1, + 5091, 5092, 5090, -1, 5092, 5091, 5093, -1, + 5093, 5094, 5092, -1, 5094, 5093, 5095, -1, + 5095, 5096, 5094, -1, 5096, 5095, 5097, -1, + 5097, 5098, 5096, -1, 5098, 5097, 5099, -1, + 5099, 5100, 5098, -1, 5100, 5099, 5101, -1, + 5101, 5102, 5100, -1, 5102, 5101, 5103, -1, + 5103, 5104, 5102, -1, 5104, 5103, 5105, -1, + 5105, 5106, 5104, -1, 5106, 5105, 5107, -1, + 5107, 5108, 5106, -1, 5108, 5107, 5109, -1, + 5109, 5110, 5108, -1, 5110, 5109, 5111, -1, + 5111, 5112, 5110, -1, 5112, 5111, 5113, -1, + 5113, 5114, 5112, -1, 5114, 5113, 5115, -1, + 5115, 5116, 5114, -1, 5116, 5115, 5117, -1, + 5117, 5118, 5116, -1, 5118, 5117, 5119, -1, + 5118, 5119, 5120, -1, 5120, 5121, 5118, -1, + 5121, 5120, 5122, -1, 5122, 5123, 5121, -1, + 5123, 5122, 5124, -1, 5124, 5125, 5123, -1, + 5125, 5124, 5126, -1, 5126, 5127, 5125, -1, + 5127, 5126, 5128, -1, 5128, 5129, 5127, -1, + 5129, 5128, 5130, -1, 5130, 5131, 5129, -1, + 5131, 5130, 5132, -1, 5132, 5133, 5131, -1, + 5133, 5132, 5134, -1, 5134, 5135, 5133, -1, + 5135, 5134, 5136, -1, 5136, 5137, 5135, -1, + 5137, 5136, 5138, -1, 5138, 5139, 5137, -1, + 5139, 5138, 5140, -1, 5140, 5141, 5139, -1, + 5141, 5140, 5142, -1, 5142, 5143, 5141, -1, + 5143, 5142, 5144, -1, 5144, 5145, 5143, -1, + 5145, 5144, 5146, -1, 5146, 5147, 5145, -1, + 5147, 5146, 5148, -1, 5148, 5149, 5147, -1, + 5149, 5148, 5150, -1, 5150, 5151, 5149, -1, + 5151, 5150, 5152, -1, 5152, 5153, 5151, -1, + 5153, 5152, 5154, -1, 5154, 5155, 5153, -1, + 5155, 5154, 5156, -1, 5156, 5157, 5155, -1, + 5157, 5156, 5158, -1, 5158, 5159, 5157, -1, + 5159, 5158, 5160, -1, 5160, 5161, 5159, -1, + 5161, 5160, 5162, -1, 5162, 5163, 5161, -1, + 5163, 5162, 5164, -1, 5164, 5165, 5163, -1, + 5165, 5164, 5166, -1, 5166, 5167, 5165, -1, + 5167, 5166, 5168, -1, 5168, 5169, 5167, -1, + 5169, 5168, 5170, -1, 5171, 5172, 5173, -1, + 5173, 5174, 5171, -1, 5174, 5173, 5175, -1, + 5175, 5176, 5174, -1, 5176, 5175, 5177, -1, + 5177, 5178, 5176, -1, 5178, 5177, 5179, -1, + 5179, 5180, 5178, -1, 5180, 5179, 5181, -1, + 5181, 5182, 5180, -1, 5182, 5181, 5183, -1, + 5183, 5184, 5182, -1, 5184, 5183, 5185, -1, + 5185, 5186, 5184, -1, 5186, 5185, 5187, -1, + 5187, 5188, 5186, -1, 5188, 5187, 5189, -1, + 5189, 5190, 5188, -1, 5190, 5189, 5191, -1, + 5191, 5192, 5190, -1, 5192, 5191, 5193, -1, + 5193, 5194, 5192, -1, 5194, 5193, 5195, -1, + 5195, 5196, 5194, -1, 5196, 5195, 5197, -1, + 5197, 5198, 5196, -1, 5198, 5197, 5199, -1, + 5199, 5200, 5198, -1, 5200, 5199, 5201, -1, + 5201, 5202, 5200, -1, 5202, 5201, 5203, -1, + 5203, 5204, 5202, -1, 5204, 5203, 5205, -1, + 5205, 5206, 5204, -1, 5206, 5205, 5207, -1, + 5207, 5208, 5206, -1, 5208, 5207, 5209, -1, + 5209, 5210, 5208, -1, 5210, 5209, 5211, -1, + 5211, 5212, 5210, -1, 5212, 5211, 5213, -1, + 5213, 5214, 5212, -1, 5214, 5213, 5215, -1, + 5215, 5216, 5214, -1, 5216, 5215, 5217, -1, + 5217, 5218, 5216, -1, 5218, 5217, 5219, -1, + 5219, 5220, 5218, -1, 5220, 5219, 5221, -1, + 5221, 5222, 5220, -1, 5222, 5221, 5223, -1, + 5222, 5223, 5224, -1, 5224, 5225, 5222, -1, + 5225, 5224, 5226, -1, 5226, 5227, 5225, -1, + 5227, 5226, 5228, -1, 5228, 5229, 5227, -1, + 5229, 5228, 5230, -1, 5230, 5231, 5229, -1, + 5231, 5230, 5232, -1, 5232, 5233, 5231, -1, + 5233, 5232, 5234, -1, 5234, 5235, 5233, -1, + 5235, 5234, 5236, -1, 5236, 5237, 5235, -1, + 5237, 5236, 5238, -1, 5238, 5239, 5237, -1, + 5239, 5238, 5240, -1, 5240, 5241, 5239, -1, + 5241, 5240, 5242, -1, 5242, 5243, 5241, -1, + 5243, 5242, 5244, -1, 5244, 5245, 5243, -1, + 5245, 5244, 5246, -1, 5246, 5247, 5245, -1, + 5247, 5246, 5248, -1, 5248, 5249, 5247, -1, + 5249, 5248, 5250, -1, 5250, 5251, 5249, -1, + 5251, 5250, 5252, -1, 5252, 5253, 5251, -1, + 5253, 5252, 5254, -1, 5254, 5255, 5253, -1, + 5255, 5254, 5256, -1, 5256, 5257, 5255, -1, + 5257, 5256, 5258, -1, 5258, 5259, 5257, -1, + 5259, 5258, 5260, -1, 5260, 5261, 5259, -1, + 5261, 5260, 5262, -1, 5262, 5263, 5261, -1, + 5263, 5262, 5264, -1, 5264, 5265, 5263, -1, + 5265, 5264, 5266, -1, 5266, 5267, 5265, -1, + 5267, 5266, 5268, -1, 5268, 5269, 5267, -1, + 5269, 5268, 5270, -1, 5270, 5271, 5269, -1, + 5271, 5270, 5272, -1, 5272, 5273, 5271, -1, + 5273, 5272, 5274, -1, 5275, 5276, 5277, -1, + 5277, 5278, 5275, -1, 5278, 5277, 5279, -1, + 5279, 5280, 5278, -1, 5280, 5279, 5281, -1, + 5281, 5282, 5280, -1, 5282, 5281, 5283, -1, + 5283, 5284, 5282, -1, 5284, 5283, 5285, -1, + 5285, 5286, 5284, -1, 5286, 5285, 5287, -1, + 5287, 5288, 5286, -1, 5288, 5287, 5289, -1, + 5289, 5290, 5288, -1, 5290, 5289, 5291, -1, + 5291, 5292, 5290, -1, 5292, 5291, 5274, -1, + 5274, 5170, 5292, -1, 5170, 5274, 5272, -1, + 5272, 5169, 5170, -1, 5169, 5272, 5270, -1, + 5270, 5167, 5169, -1, 5167, 5270, 5268, -1, + 5268, 5165, 5167, -1, 5165, 5268, 5266, -1, + 5266, 5163, 5165, -1, 5163, 5266, 5264, -1, + 5264, 5161, 5163, -1, 5161, 5264, 5262, -1, + 5262, 5159, 5161, -1, 5159, 5262, 5260, -1, + 5260, 5157, 5159, -1, 5157, 5260, 5258, -1, + 5258, 5155, 5157, -1, 5155, 5258, 5256, -1, + 5256, 5153, 5155, -1, 5153, 5256, 5254, -1, + 5254, 5151, 5153, -1, 5151, 5254, 5252, -1, + 5252, 5149, 5151, -1, 5149, 5252, 5250, -1, + 5250, 5147, 5149, -1, 5147, 5250, 5248, -1, + 5248, 5145, 5147, -1, 5145, 5248, 5246, -1, + 5246, 5143, 5145, -1, 5143, 5246, 5244, -1, + 5244, 5141, 5143, -1, 5141, 5244, 5242, -1, + 5242, 5139, 5141, -1, 5139, 5242, 5240, -1, + 5240, 5137, 5139, -1, 5137, 5240, 5238, -1, + 5238, 5135, 5137, -1, 5135, 5238, 5236, -1, + 5236, 5133, 5135, -1, 5133, 5236, 5234, -1, + 5234, 5131, 5133, -1, 5131, 5234, 5232, -1, + 5232, 5129, 5131, -1, 5129, 5232, 5230, -1, + 5230, 5127, 5129, -1, 5127, 5230, 5228, -1, + 5228, 5125, 5127, -1, 5125, 5228, 5226, -1, + 5226, 5123, 5125, -1, 5123, 5226, 5224, -1, + 5224, 5121, 5123, -1, 5121, 5224, 5223, -1, + 5223, 5118, 5121, -1, 5223, 5116, 5118, -1, + 5116, 5223, 5221, -1, 5221, 5114, 5116, -1, + 5114, 5221, 5219, -1, 5219, 5112, 5114, -1, + 5112, 5219, 5217, -1, 5217, 5110, 5112, -1, + 5110, 5217, 5215, -1, 5215, 5108, 5110, -1, + 5108, 5215, 5213, -1, 5213, 5106, 5108, -1, + 5106, 5213, 5211, -1, 5211, 5104, 5106, -1, + 5104, 5211, 5209, -1, 5209, 5102, 5104, -1, + 5102, 5209, 5207, -1, 5207, 5100, 5102, -1, + 5100, 5207, 5205, -1, 5205, 5098, 5100, -1, + 5098, 5205, 5203, -1, 5203, 5096, 5098, -1, + 5096, 5203, 5201, -1, 5201, 5094, 5096, -1, + 5094, 5201, 5199, -1, 5199, 5092, 5094, -1, + 5092, 5199, 5197, -1, 5197, 5090, 5092, -1, + 5090, 5197, 5195, -1, 5195, 5088, 5090, -1, + 5088, 5195, 5193, -1, 5193, 5086, 5088, -1, + 5086, 5193, 5191, -1, 5191, 5084, 5086, -1, + 5084, 5191, 5189, -1, 5189, 5082, 5084, -1, + 5082, 5189, 5187, -1, 5187, 5080, 5082, -1, + 5080, 5187, 5185, -1, 5185, 5078, 5080, -1, + 5078, 5185, 5183, -1, 5183, 5076, 5078, -1, + 5076, 5183, 5181, -1, 5181, 5074, 5076, -1, + 5074, 5181, 5179, -1, 5179, 5072, 5074, -1, + 5072, 5179, 5177, -1, 5177, 5070, 5072, -1, + 5070, 5177, 5175, -1, 5175, 5067, 5070, -1, + 5067, 5175, 5173, -1, 5173, 5068, 5067, -1, + 5068, 5173, 5172, -1, 5172, 5293, 5068, -1, + 5293, 5172, 5294, -1, 5294, 5295, 5293, -1, + 5295, 5294, 5296, -1, 5296, 5297, 5295, -1, + 5297, 5296, 5298, -1, 5298, 5299, 5297, -1, + 5299, 5298, 5300, -1, 5300, 5301, 5299, -1, + 5301, 5300, 5302, -1, 5302, 5303, 5301, -1, + 5303, 5302, 5304, -1, 5304, 5305, 5303, -1, + 5305, 5304, 5306, -1, 5306, 5307, 5305, -1, + 5307, 5306, 5308, -1, 5308, 5309, 5307, -1, + 5309, 5308, 5310, -1, 5310, 5311, 5309, -1, + 5311, 5310, 5312, -1, 5312, 5313, 5311, -1, + 5314, 5315, 5316, -1, 5316, 5317, 5314, -1, + 5317, 5316, 5318, -1, 5318, 5319, 5317, -1, + 5318, 5320, 5319, -1, 5321, 5322, 5313, -1, + 5322, 5321, 5323, -1, 5323, 5324, 5322, -1, + 5324, 5323, 5325, -1, 5325, 5326, 5324, -1, + 5326, 5325, 5327, -1, 5327, 5320, 5326, -1, + 5327, 5319, 5320, -1, 5327, 5328, 5319, -1, + 5328, 5327, 5325, -1, 5325, 5329, 5328, -1, + 5329, 5325, 5323, -1, 5323, 5330, 5329, -1, + 5330, 5323, 5321, -1, 5321, 5331, 5330, -1, + 5331, 5321, 5313, -1, 5313, 5312, 5331, -1, + 5332, 5331, 5312, -1, 5331, 5332, 5333, -1, + 5333, 5330, 5331, -1, 5330, 5333, 5334, -1, + 5334, 5329, 5330, -1, 5329, 5334, 5066, -1, + 5066, 5328, 5329, -1, 5328, 5066, 5065, -1, + 5065, 5319, 5328, -1, 5319, 5065, 5064, -1, + 5064, 5317, 5319, -1, 5317, 5064, 5335, -1, + 5335, 5314, 5317, -1, 5335, 5336, 5314, -1, + 5335, 5337, 5336, -1, 5337, 5335, 5064, -1, + 5064, 5063, 5337, -1, 5337, 5063, 5060, -1, + 5337, 5060, 5062, -1, 5062, 5336, 5337, -1, + 5336, 5062, 5338, -1, 5338, 5339, 5336, -1, + 5340, 5341, 5342, -1, 5340, 5342, 5339, -1, + 5339, 5338, 5340, -1, 5343, 5344, 5345, -1, + 5344, 5346, 5345, -1, 5340, 5345, 5346, -1, + 5345, 5340, 5338, -1, 5338, 5347, 5345, -1, + 5347, 5338, 5062, -1, 5062, 5061, 5347, -1, + 5348, 5347, 5061, -1, 5061, 5349, 5348, -1, + 5349, 5061, 5059, -1, 5059, 5350, 5349, -1, + 5350, 5059, 5055, -1, 5055, 5351, 5350, -1, + 5351, 5055, 5053, -1, 5053, 5352, 5351, -1, + 5352, 5053, 5051, -1, 5051, 5353, 5352, -1, + 5353, 5051, 5049, -1, 5049, 5354, 5353, -1, + 5354, 5049, 5047, -1, 5047, 5355, 5354, -1, + 5355, 5047, 5045, -1, 5045, 5356, 5355, -1, + 5356, 5045, 5043, -1, 5043, 5357, 5356, -1, + 5357, 5043, 5041, -1, 5041, 5358, 5357, -1, + 5358, 5041, 5039, -1, 5039, 5359, 5358, -1, + 5359, 5039, 5037, -1, 5037, 5360, 5359, -1, + 5360, 5037, 5035, -1, 5035, 5361, 5360, -1, + 5361, 5035, 5034, -1, 5034, 5362, 5361, -1, + 5362, 5034, 5363, -1, 5363, 5364, 5362, -1, + 5364, 5363, 5365, -1, 5365, 5366, 5364, -1, + 5366, 5365, 5367, -1, 5367, 5368, 5366, -1, + 5368, 5367, 5369, -1, 5369, 5370, 5368, -1, + 5370, 5369, 5371, -1, 5371, 5372, 5370, -1, + 5372, 5371, 5373, -1, 5373, 5374, 5372, -1, + 5374, 5373, 5375, -1, 5375, 5376, 5374, -1, + 5376, 5375, 5377, -1, 5377, 5378, 5376, -1, + 5378, 5377, 5379, -1, 5379, 5380, 5378, -1, + 5380, 5379, 5381, -1, 5381, 5382, 5380, -1, + 5382, 5381, 5383, -1, 5383, 5384, 5382, -1, + 5384, 5383, 5385, -1, 5385, 5386, 5384, -1, + 5386, 5385, 5387, -1, 5387, 5388, 5386, -1, + 5388, 5387, 5389, -1, 5389, 5390, 5388, -1, + 5390, 5389, 5391, -1, 5391, 5392, 5390, -1, + 5392, 5391, 5393, -1, 5393, 5394, 5392, -1, + 5394, 5393, 5395, -1, 5395, 5396, 5394, -1, + 5396, 5395, 5397, -1, 5397, 5398, 5396, -1, + 5398, 5397, 5399, -1, 5399, 5400, 5398, -1, + 5400, 5399, 5401, -1, 5401, 5402, 5400, -1, + 5402, 5401, 5403, -1, 5403, 5404, 5402, -1, + 5404, 5403, 5405, -1, 5405, 5406, 5404, -1, + 5406, 5405, 5032, -1, 5032, 5031, 5406, -1, + 5407, 5406, 5031, -1, 5031, 5408, 5407, -1, + 5408, 5031, 5028, -1, 5408, 5028, 5026, -1, + 5026, 5409, 5408, -1, 5409, 5026, 5024, -1, + 5024, 5410, 5409, -1, 5410, 5024, 5022, -1, + 5022, 5411, 5410, -1, 5411, 5022, 5020, -1, + 5020, 5412, 5411, -1, 5412, 5020, 5018, -1, + 5018, 5413, 5412, -1, 5413, 5018, 5016, -1, + 5016, 5414, 5413, -1, 5414, 5016, 5014, -1, + 5014, 5415, 5414, -1, 5415, 5014, 5012, -1, + 5012, 5416, 5415, -1, 5416, 5012, 5010, -1, + 5010, 5417, 5416, -1, 5417, 5010, 5008, -1, + 5008, 5418, 5417, -1, 5418, 5008, 5006, -1, + 5006, 5419, 5418, -1, 5419, 5006, 5004, -1, + 5004, 5420, 5419, -1, 5420, 5004, 5002, -1, + 5002, 5421, 5420, -1, 5421, 5002, 5000, -1, + 5000, 5422, 5421, -1, 5422, 5000, 4998, -1, + 4998, 5423, 5422, -1, 5423, 4998, 4996, -1, + 4996, 5424, 5423, -1, 5424, 4996, 4994, -1, + 4994, 5425, 5424, -1, 5425, 4994, 4992, -1, + 4992, 5426, 5425, -1, 5426, 4992, 4990, -1, + 4990, 5427, 5426, -1, 5427, 4990, 4988, -1, + 4988, 5428, 5427, -1, 5428, 4988, 4986, -1, + 4986, 5429, 5428, -1, 5429, 4986, 4984, -1, + 4984, 5430, 5429, -1, 5430, 4984, 4982, -1, + 4982, 5431, 5430, -1, 5431, 4982, 4981, -1, + 4981, 5432, 5431, -1, 5432, 4981, 5433, -1, + 5434, 5435, 5436, -1, 5436, 5437, 5434, -1, + 5437, 5436, 5438, -1, 5438, 5439, 5437, -1, + 5439, 5438, 5440, -1, 5440, 5441, 5439, -1, + 5441, 5440, 5442, -1, 5442, 5443, 5441, -1, + 5443, 5442, 5444, -1, 5444, 5445, 5443, -1, + 5445, 5444, 5446, -1, 5446, 5447, 5445, -1, + 5447, 5446, 5448, -1, 5448, 5449, 5447, -1, + 5449, 5448, 5450, -1, 5450, 5451, 5449, -1, + 5451, 5450, 5433, -1, 5433, 5452, 5451, -1, + 5452, 5433, 4981, -1, 4981, 4980, 5452, -1, + 5453, 5452, 4980, -1, 4980, 5454, 5453, -1, + 5454, 4980, 4983, -1, 4983, 5455, 5454, -1, + 5455, 4983, 4985, -1, 4985, 5456, 5455, -1, + 5456, 4985, 4987, -1, 4987, 5457, 5456, -1, + 5457, 4987, 4989, -1, 4989, 5458, 5457, -1, + 5458, 4989, 4991, -1, 4991, 5459, 5458, -1, + 5459, 4991, 4993, -1, 4993, 5460, 5459, -1, + 5460, 4993, 4995, -1, 4995, 5461, 5460, -1, + 5461, 4995, 4997, -1, 4997, 5462, 5461, -1, + 5462, 4997, 4999, -1, 4999, 5463, 5462, -1, + 5463, 4999, 5001, -1, 5001, 5464, 5463, -1, + 5464, 5001, 5003, -1, 5003, 5465, 5464, -1, + 5465, 5003, 5005, -1, 5005, 5466, 5465, -1, + 5466, 5005, 5007, -1, 5007, 5467, 5466, -1, + 5467, 5007, 5009, -1, 5009, 5468, 5467, -1, + 5468, 5009, 5011, -1, 5011, 5469, 5468, -1, + 5469, 5011, 5013, -1, 5013, 5470, 5469, -1, + 5470, 5013, 5015, -1, 5015, 5471, 5470, -1, + 5471, 5015, 5017, -1, 5017, 5472, 5471, -1, + 5472, 5017, 5019, -1, 5019, 5473, 5472, -1, + 5473, 5019, 5021, -1, 5021, 5474, 5473, -1, + 5474, 5021, 5023, -1, 5023, 5475, 5474, -1, + 5475, 5023, 5025, -1, 5025, 5476, 5475, -1, + 5476, 5025, 5027, -1, 5027, 5477, 5476, -1, + 5477, 5027, 5029, -1, 5029, 5478, 5477, -1, + 5029, 5479, 5478, -1, 5479, 5029, 5030, -1, + 5030, 5480, 5479, -1, 5480, 5030, 5032, -1, + 5032, 5481, 5480, -1, 5481, 5032, 5405, -1, + 5405, 5482, 5481, -1, 5482, 5405, 5403, -1, + 5403, 5483, 5482, -1, 5483, 5403, 5401, -1, + 5401, 5484, 5483, -1, 5484, 5401, 5399, -1, + 5399, 5485, 5484, -1, 5485, 5399, 5397, -1, + 5397, 5486, 5485, -1, 5486, 5397, 5395, -1, + 5395, 5487, 5486, -1, 5487, 5395, 5393, -1, + 5393, 5488, 5487, -1, 5488, 5393, 5391, -1, + 5391, 5489, 5488, -1, 5489, 5391, 5389, -1, + 5389, 5490, 5489, -1, 5490, 5389, 5387, -1, + 5387, 5491, 5490, -1, 5491, 5387, 5385, -1, + 5385, 5492, 5491, -1, 5492, 5385, 5383, -1, + 5383, 5493, 5492, -1, 5493, 5383, 5381, -1, + 5381, 5494, 5493, -1, 5494, 5381, 5379, -1, + 5379, 5495, 5494, -1, 5495, 5379, 5377, -1, + 5377, 5496, 5495, -1, 5496, 5377, 5375, -1, + 5375, 5497, 5496, -1, 5497, 5375, 5373, -1, + 5373, 5498, 5497, -1, 5498, 5373, 5371, -1, + 5371, 5499, 5498, -1, 5499, 5371, 5369, -1, + 5369, 5500, 5499, -1, 5500, 5369, 5367, -1, + 5367, 5501, 5500, -1, 5501, 5367, 5365, -1, + 5365, 5502, 5501, -1, 5502, 5365, 5363, -1, + 5363, 5034, 5502, -1, 5503, 5502, 5034, -1, + 5034, 5033, 5503, -1, 5504, 5505, 5506, -1, + 5505, 5504, 5507, -1, 5507, 5508, 5505, -1, + 5508, 5507, 5509, -1, 5509, 5510, 5508, -1, + 5510, 5509, 5511, -1, 5511, 5512, 5510, -1, + 5512, 5511, 5513, -1, 5513, 5514, 5512, -1, + 5514, 5513, 5515, -1, 5515, 5516, 5514, -1, + 5516, 5515, 5517, -1, 5517, 5518, 5516, -1, + 5518, 5517, 5519, -1, 5519, 5520, 5518, -1, + 5520, 5519, 5521, -1, 5521, 5522, 5520, -1, + 5522, 5521, 5523, -1, 5523, 5524, 5522, -1, + 5524, 5523, 5525, -1, 5525, 5526, 5524, -1, + 5526, 5525, 5527, -1, 5527, 5528, 5526, -1, + 5528, 5527, 5529, -1, 5529, 5530, 5528, -1, + 5530, 5529, 5531, -1, 5531, 5532, 5530, -1, + 5532, 5531, 5533, -1, 5533, 5534, 5532, -1, + 5534, 5533, 5535, -1, 5535, 5536, 5534, -1, + 5536, 5535, 5537, -1, 5537, 5538, 5536, -1, + 5538, 5537, 5539, -1, 5539, 5540, 5538, -1, + 5540, 5539, 5541, -1, 5541, 5542, 5540, -1, + 5542, 5541, 5543, -1, 5543, 5544, 5542, -1, + 5544, 5543, 5545, -1, 5545, 5546, 5544, -1, + 5546, 5545, 5547, -1, 5547, 5548, 5546, -1, + 5548, 5547, 5549, -1, 5549, 5550, 5548, -1, + 5550, 5549, 5551, -1, 5551, 5552, 5550, -1, + 5552, 5551, 5553, -1, 5553, 5554, 5552, -1, + 5554, 5553, 5555, -1, 5555, 5556, 5554, -1, + 5555, 5557, 5556, -1, 5557, 5555, 5558, -1, + 5558, 5559, 5557, -1, 5559, 5558, 5560, -1, + 5560, 5561, 5559, -1, 5561, 5560, 5562, -1, + 5562, 5563, 5561, -1, 5563, 5562, 5564, -1, + 5564, 5565, 5563, -1, 5565, 5564, 5566, -1, + 5566, 5567, 5565, -1, 5567, 5566, 5568, -1, + 5568, 5569, 5567, -1, 5569, 5568, 5570, -1, + 5570, 5571, 5569, -1, 5571, 5570, 5572, -1, + 5572, 5573, 5571, -1, 5573, 5572, 5574, -1, + 5574, 5575, 5573, -1, 5575, 5574, 5576, -1, + 5576, 5577, 5575, -1, 5577, 5576, 5578, -1, + 5578, 5579, 5577, -1, 5579, 5578, 5580, -1, + 5580, 5581, 5579, -1, 5581, 5580, 5582, -1, + 5582, 5583, 5581, -1, 5583, 5582, 5584, -1, + 5584, 5585, 5583, -1, 5585, 5584, 5586, -1, + 5586, 5587, 5585, -1, 5587, 5586, 5588, -1, + 5588, 5589, 5587, -1, 5589, 5588, 5590, -1, + 5590, 5591, 5589, -1, 5591, 5590, 5592, -1, + 5592, 5593, 5591, -1, 5593, 5592, 5594, -1, + 5594, 5595, 5593, -1, 5595, 5594, 5596, -1, + 5596, 5597, 5595, -1, 5597, 5596, 5598, -1, + 5598, 5599, 5597, -1, 5599, 5598, 5600, -1, + 5600, 5601, 5599, -1, 5601, 5600, 5602, -1, + 5602, 5603, 5601, -1, 5603, 5602, 5604, -1, + 5604, 5605, 5603, -1, 5605, 5604, 5503, -1, + 5503, 5606, 5605, -1, 5606, 5503, 5033, -1, + 5033, 5607, 5606, -1, 5607, 5033, 5036, -1, + 5036, 5608, 5607, -1, 5608, 5036, 5038, -1, + 5038, 5609, 5608, -1, 5609, 5038, 5040, -1, + 5040, 5610, 5609, -1, 5610, 5040, 5042, -1, + 5042, 5611, 5610, -1, 5611, 5042, 5044, -1, + 5044, 5612, 5611, -1, 5612, 5044, 5046, -1, + 5046, 5613, 5612, -1, 5613, 5046, 5048, -1, + 5048, 5614, 5613, -1, 5614, 5048, 5050, -1, + 5050, 5615, 5614, -1, 5615, 5050, 5052, -1, + 5052, 5616, 5615, -1, 5616, 5052, 5054, -1, + 5054, 5056, 5616, -1, 5617, 5616, 5056, -1, + 5056, 5057, 5617, -1, 5618, 5617, 5057, -1, + 5057, 5619, 5618, -1, 5057, 5058, 5619, -1, + 5620, 5619, 5058, -1, 5620, 5058, 5060, -1, + 5620, 5060, 5063, -1, 5620, 5063, 5066, -1, + 5066, 5619, 5620, -1, 5619, 5066, 5334, -1, + 5334, 5618, 5619, -1, 5618, 5334, 5333, -1, + 5333, 5617, 5618, -1, 5617, 5333, 5332, -1, + 5332, 5616, 5617, -1, 5616, 5332, 5312, -1, + 5312, 5615, 5616, -1, 5615, 5312, 5310, -1, + 5310, 5614, 5615, -1, 5614, 5310, 5308, -1, + 5308, 5613, 5614, -1, 5613, 5308, 5306, -1, + 5306, 5612, 5613, -1, 5612, 5306, 5304, -1, + 5304, 5611, 5612, -1, 5611, 5304, 5302, -1, + 5302, 5610, 5611, -1, 5610, 5302, 5300, -1, + 5300, 5609, 5610, -1, 5609, 5300, 5298, -1, + 5298, 5608, 5609, -1, 5608, 5298, 5296, -1, + 5296, 5607, 5608, -1, 5607, 5296, 5294, -1, + 5294, 5606, 5607, -1, 5606, 5294, 5172, -1, + 5172, 5605, 5606, -1, 5605, 5172, 5171, -1, + 5171, 5603, 5605, -1, 5603, 5171, 5174, -1, + 5174, 5601, 5603, -1, 5601, 5174, 5176, -1, + 5176, 5599, 5601, -1, 5599, 5176, 5178, -1, + 5178, 5597, 5599, -1, 5597, 5178, 5180, -1, + 5180, 5595, 5597, -1, 5595, 5180, 5182, -1, + 5182, 5593, 5595, -1, 5593, 5182, 5184, -1, + 5184, 5591, 5593, -1, 5591, 5184, 5186, -1, + 5186, 5589, 5591, -1, 5589, 5186, 5188, -1, + 5188, 5587, 5589, -1, 5587, 5188, 5190, -1, + 5190, 5585, 5587, -1, 5585, 5190, 5192, -1, + 5192, 5583, 5585, -1, 5583, 5192, 5194, -1, + 5194, 5581, 5583, -1, 5581, 5194, 5196, -1, + 5196, 5579, 5581, -1, 5579, 5196, 5198, -1, + 5198, 5577, 5579, -1, 5577, 5198, 5200, -1, + 5200, 5575, 5577, -1, 5575, 5200, 5202, -1, + 5202, 5573, 5575, -1, 5573, 5202, 5204, -1, + 5204, 5571, 5573, -1, 5571, 5204, 5206, -1, + 5206, 5569, 5571, -1, 5569, 5206, 5208, -1, + 5208, 5567, 5569, -1, 5567, 5208, 5210, -1, + 5210, 5565, 5567, -1, 5565, 5210, 5212, -1, + 5212, 5563, 5565, -1, 5563, 5212, 5214, -1, + 5214, 5561, 5563, -1, 5561, 5214, 5216, -1, + 5216, 5559, 5561, -1, 5559, 5216, 5218, -1, + 5218, 5557, 5559, -1, 5557, 5218, 5220, -1, + 5220, 5556, 5557, -1, 5556, 5220, 5222, -1, + 5556, 5222, 5225, -1, 5225, 5554, 5556, -1, + 5554, 5225, 5227, -1, 5227, 5552, 5554, -1, + 5552, 5227, 5229, -1, 5229, 5550, 5552, -1, + 5550, 5229, 5231, -1, 5231, 5548, 5550, -1, + 5548, 5231, 5233, -1, 5233, 5546, 5548, -1, + 5546, 5233, 5235, -1, 5235, 5544, 5546, -1, + 5544, 5235, 5237, -1, 5237, 5542, 5544, -1, + 5542, 5237, 5239, -1, 5239, 5540, 5542, -1, + 5540, 5239, 5241, -1, 5241, 5538, 5540, -1, + 5538, 5241, 5243, -1, 5243, 5536, 5538, -1, + 5536, 5243, 5245, -1, 5245, 5534, 5536, -1, + 5534, 5245, 5247, -1, 5247, 5532, 5534, -1, + 5532, 5247, 5249, -1, 5249, 5530, 5532, -1, + 5530, 5249, 5251, -1, 5251, 5528, 5530, -1, + 5528, 5251, 5253, -1, 5253, 5526, 5528, -1, + 5526, 5253, 5255, -1, 5255, 5524, 5526, -1, + 5524, 5255, 5257, -1, 5257, 5522, 5524, -1, + 5522, 5257, 5259, -1, 5259, 5520, 5522, -1, + 5520, 5259, 5261, -1, 5261, 5518, 5520, -1, + 5518, 5261, 5263, -1, 5263, 5516, 5518, -1, + 5516, 5263, 5265, -1, 5265, 5514, 5516, -1, + 5514, 5265, 5267, -1, 5267, 5512, 5514, -1, + 5512, 5267, 5269, -1, 5269, 5510, 5512, -1, + 5510, 5269, 5271, -1, 5271, 5508, 5510, -1, + 5508, 5271, 5273, -1, 5273, 5505, 5508, -1, + 5505, 5273, 5274, -1, 5274, 5506, 5505, -1, + 5506, 5274, 5291, -1, 5291, 5621, 5506, -1, + 5621, 5291, 5289, -1, 5289, 5622, 5621, -1, + 5622, 5289, 5287, -1, 5287, 5623, 5622, -1, + 5623, 5287, 5285, -1, 5285, 5624, 5623, -1, + 5624, 5285, 5283, -1, 5283, 5625, 5624, -1, + 5625, 5283, 5281, -1, 5281, 5626, 5625, -1, + 5626, 5281, 5279, -1, 5279, 5627, 5626, -1, + 5627, 5279, 5277, -1, 5277, 5628, 5627, -1, + 5628, 5277, 5276, -1, 5276, 5629, 5628, -1, + 5629, 5276, 5630, -1, 5630, 5631, 5629, -1, + 5631, 4977, 5632, -1, 5631, 5630, 4977, -1, + 5630, 4979, 4977, -1, 4979, 5630, 5276, -1, + 5276, 5275, 4979, -1, 5633, 4979, 5275, -1, + 5275, 5634, 5633, -1, 5634, 5275, 5278, -1, + 5278, 5635, 5634, -1, 5635, 5278, 5280, -1, + 5280, 5636, 5635, -1, 5636, 5280, 5282, -1, + 5282, 5637, 5636, -1, 5637, 5282, 5284, -1, + 5284, 5638, 5637, -1, 5638, 5284, 5286, -1, + 5286, 5639, 5638, -1, 5639, 5286, 5288, -1, + 5288, 5640, 5639, -1, 5640, 5288, 5290, -1, + 5290, 5641, 5640, -1, 5641, 5290, 5292, -1, + 5292, 5642, 5641, -1, 5642, 5292, 5170, -1, + 5170, 4970, 5642, -1, 4970, 5170, 5168, -1, + 5168, 4969, 4970, -1, 4969, 5168, 5166, -1, + 5166, 4967, 4969, -1, 4967, 5166, 5164, -1, + 5164, 4965, 4967, -1, 4965, 5164, 5162, -1, + 5162, 4963, 4965, -1, 4963, 5162, 5160, -1, + 5160, 4961, 4963, -1, 4961, 5160, 5158, -1, + 5158, 4959, 4961, -1, 4959, 5158, 5156, -1, + 5156, 4957, 4959, -1, 4957, 5156, 5154, -1, + 5154, 4955, 4957, -1, 4955, 5154, 5152, -1, + 5152, 4953, 4955, -1, 4953, 5152, 5150, -1, + 5150, 4951, 4953, -1, 4951, 5150, 5148, -1, + 5148, 4949, 4951, -1, 4949, 5148, 5146, -1, + 5146, 4947, 4949, -1, 4947, 5146, 5144, -1, + 5144, 4945, 4947, -1, 4945, 5144, 5142, -1, + 5142, 4943, 4945, -1, 4943, 5142, 5140, -1, + 5140, 4942, 4943, -1, 4942, 5140, 5138, -1, + 5138, 4941, 4942, -1, 4941, 5138, 5136, -1, + 5136, 4940, 4941, -1, 4940, 5136, 5134, -1, + 5134, 4939, 4940, -1, 4939, 5134, 5132, -1, + 5132, 4938, 4939, -1, 4938, 5132, 5130, -1, + 5130, 4937, 4938, -1, 4937, 5130, 5128, -1, + 5128, 4936, 4937, -1, 4936, 5128, 5126, -1, + 5126, 4935, 4936, -1, 4935, 5126, 5124, -1, + 5124, 4934, 4935, -1, 4934, 5124, 5122, -1, + 5122, 4933, 4934, -1, 4933, 5122, 5120, -1, + 5120, 4932, 4933, -1, 4932, 5120, 5119, -1, + 5119, 4931, 4932, -1, 5119, 4930, 4931, -1, + 4930, 5119, 5117, -1, 5117, 4929, 4930, -1, + 4929, 5117, 5115, -1, 5115, 4896, 4929, -1, + 4896, 5115, 5113, -1, 5113, 4894, 4896, -1, + 4894, 5113, 5111, -1, 5111, 4892, 4894, -1, + 4892, 5111, 5109, -1, 5109, 4890, 4892, -1, + 4890, 5109, 5107, -1, 5107, 4888, 4890, -1, + 4888, 5107, 5105, -1, 5105, 4886, 4888, -1, + 4886, 5105, 5103, -1, 5103, 4884, 4886, -1, + 4884, 5103, 5101, -1, 5101, 4882, 4884, -1, + 4882, 5101, 5099, -1, 5099, 4880, 4882, -1, + 4880, 5099, 5097, -1, 5097, 4878, 4880, -1, + 4878, 5097, 5095, -1, 5095, 4876, 4878, -1, + 4876, 5095, 5093, -1, 5093, 4874, 4876, -1, + 4874, 5093, 5091, -1, 5091, 4872, 4874, -1, + 4872, 5091, 5089, -1, 5089, 4870, 4872, -1, + 4870, 5089, 5087, -1, 5087, 4868, 4870, -1, + 4868, 5087, 5085, -1, 5085, 4866, 4868, -1, + 4866, 5085, 5083, -1, 5083, 4864, 4866, -1, + 4864, 5083, 5081, -1, 5081, 4862, 4864, -1, + 4862, 5081, 5079, -1, 5079, 4860, 4862, -1, + 4860, 5079, 5077, -1, 5077, 4858, 4860, -1, + 4858, 5077, 5075, -1, 5075, 4856, 4858, -1, + 4856, 5075, 5073, -1, 5073, 4854, 4856, -1, + 4854, 5073, 5071, -1, 5071, 4851, 4854, -1, + 4851, 5071, 5069, -1, 5069, 4852, 4851, -1, + 4852, 5069, 5068, -1, 5068, 5643, 4852, -1, + 5643, 5068, 5293, -1, 5293, 5644, 5643, -1, + 5644, 5293, 5295, -1, 5295, 5645, 5644, -1, + 5645, 5295, 5297, -1, 5297, 5646, 5645, -1, + 5646, 5297, 5299, -1, 5299, 5647, 5646, -1, + 5647, 5299, 5301, -1, 5301, 5648, 5647, -1, + 5648, 5301, 5303, -1, 5303, 5649, 5648, -1, + 5649, 5303, 5305, -1, 5305, 5650, 5649, -1, + 5650, 5305, 5307, -1, 5307, 5651, 5650, -1, + 5651, 5307, 5309, -1, 5309, 5652, 5651, -1, + 5652, 5309, 5311, -1, 5311, 5653, 5652, -1, + 5653, 5311, 5313, -1, 5313, 4850, 5653, -1, + 4850, 5313, 5322, -1, 5322, 4849, 4850, -1, + 4849, 5322, 5324, -1, 5324, 4848, 4849, -1, + 4848, 5324, 5326, -1, 5326, 4847, 4848, -1, + 4847, 5326, 5320, -1, 5320, 4846, 4847, -1, + 4846, 5320, 5318, -1, 5318, 4845, 4846, -1, + 4845, 5318, 5316, -1, 5316, 4843, 4845, -1, + 4843, 5316, 5315, -1, 5315, 4841, 4843, -1, + 5315, 4840, 4841, -1, 5315, 5314, 4840, -1, + 4840, 5314, 5336, -1, 4840, 5336, 5339, -1, + 5339, 4839, 4840, -1, 4839, 5339, 5342, -1, + 5342, 4837, 4839, -1, 4837, 5342, 5654, -1, + 5655, 5654, 5342, -1, 5656, 5655, 5342, -1, + 5656, 5342, 5341, -1, 5341, 5657, 5656, -1, + 5341, 5658, 5657, -1, 5658, 5341, 5340, -1, + 5658, 5340, 5346, -1, 5346, 5657, 5658, -1, + 5346, 5344, 5657, -1, 5344, 5343, 5657, -1, + 5343, 5659, 5657, -1, 5343, 5345, 5659, -1, + 5660, 5659, 5345, -1, 5660, 5345, 5347, -1, + 5347, 5348, 5660, -1, 5661, 5662, 5663, -1, + 5662, 5664, 5663, -1, 5660, 5663, 5664, -1, + 5663, 5660, 5348, -1, 5348, 5665, 5663, -1, + 5665, 5348, 5349, -1, 5349, 5666, 5665, -1, + 5666, 5349, 5350, -1, 5350, 5667, 5666, -1, + 5667, 5350, 5351, -1, 5351, 5668, 5667, -1, + 5668, 5351, 5352, -1, 5352, 5669, 5668, -1, + 5669, 5352, 5353, -1, 5353, 5670, 5669, -1, + 5670, 5353, 5354, -1, 5354, 5671, 5670, -1, + 5671, 5354, 5355, -1, 5355, 5672, 5671, -1, + 5672, 5355, 5356, -1, 5356, 5673, 5672, -1, + 5673, 5356, 5357, -1, 5357, 5674, 5673, -1, + 5674, 5357, 5358, -1, 5358, 5675, 5674, -1, + 5675, 5358, 5359, -1, 5359, 5676, 5675, -1, + 5676, 5359, 5360, -1, 5360, 5677, 5676, -1, + 5677, 5360, 5361, -1, 5361, 5678, 5677, -1, + 5679, 5677, 5678, -1, 5678, 5680, 5679, -1, + 5680, 5678, 5681, -1, 5681, 5682, 5680, -1, + 5682, 5681, 5683, -1, 5683, 5684, 5682, -1, + 5684, 5683, 5685, -1, 5685, 5686, 5684, -1, + 5686, 5685, 5687, -1, 5687, 5688, 5686, -1, + 5688, 5687, 5689, -1, 5689, 5690, 5688, -1, + 5690, 5689, 5691, -1, 5691, 5692, 5690, -1, + 5692, 5691, 5693, -1, 5693, 5694, 5692, -1, + 5694, 5693, 5695, -1, 5695, 5696, 5694, -1, + 5696, 5695, 5697, -1, 5697, 5698, 5696, -1, + 5698, 5697, 5699, -1, 5699, 5700, 5698, -1, + 5700, 5699, 5701, -1, 5701, 5702, 5700, -1, + 5702, 5701, 5703, -1, 5703, 5704, 5702, -1, + 5704, 5703, 5705, -1, 5705, 5706, 5704, -1, + 5706, 5705, 5707, -1, 5707, 5708, 5706, -1, + 5708, 5707, 5709, -1, 5709, 5710, 5708, -1, + 5710, 5709, 5711, -1, 5711, 5712, 5710, -1, + 5712, 5711, 5713, -1, 5713, 5714, 5712, -1, + 5714, 5713, 5715, -1, 5715, 5716, 5714, -1, + 5716, 5715, 5717, -1, 5717, 5718, 5716, -1, + 5718, 5717, 5719, -1, 5719, 5720, 5718, -1, + 5720, 5719, 5721, -1, 5721, 5722, 5720, -1, + 5722, 5721, 5723, -1, 5723, 5724, 5722, -1, + 5723, 5725, 5724, -1, 5723, 5726, 5725, -1, + 5726, 5723, 5721, -1, 5721, 5727, 5726, -1, + 5727, 5721, 5719, -1, 5719, 5728, 5727, -1, + 5728, 5719, 5717, -1, 5717, 5729, 5728, -1, + 5729, 5717, 5715, -1, 5715, 5730, 5729, -1, + 5730, 5715, 5713, -1, 5713, 5731, 5730, -1, + 5731, 5713, 5711, -1, 5711, 5732, 5731, -1, + 5732, 5711, 5709, -1, 5709, 5733, 5732, -1, + 5733, 5709, 5707, -1, 5707, 5734, 5733, -1, + 5734, 5707, 5705, -1, 5705, 5735, 5734, -1, + 5735, 5705, 5703, -1, 5703, 5736, 5735, -1, + 5736, 5703, 5701, -1, 5701, 5737, 5736, -1, + 5737, 5701, 5699, -1, 5699, 5738, 5737, -1, + 5738, 5699, 5697, -1, 5697, 5739, 5738, -1, + 5739, 5697, 5695, -1, 5695, 5740, 5739, -1, + 5740, 5695, 5693, -1, 5693, 5741, 5740, -1, + 5741, 5693, 5691, -1, 5691, 5742, 5741, -1, + 5742, 5691, 5689, -1, 5689, 5743, 5742, -1, + 5743, 5689, 5687, -1, 5687, 5744, 5743, -1, + 5744, 5687, 5685, -1, 5685, 5745, 5744, -1, + 5745, 5685, 5683, -1, 5683, 5746, 5745, -1, + 5746, 5683, 5681, -1, 5681, 5747, 5746, -1, + 5747, 5681, 5678, -1, 5678, 5361, 5747, -1, + 5747, 5361, 5362, -1, 5362, 5746, 5747, -1, + 5746, 5362, 5364, -1, 5364, 5745, 5746, -1, + 5745, 5364, 5366, -1, 5366, 5744, 5745, -1, + 5744, 5366, 5368, -1, 5368, 5743, 5744, -1, + 5743, 5368, 5370, -1, 5370, 5742, 5743, -1, + 5742, 5370, 5372, -1, 5372, 5741, 5742, -1, + 5741, 5372, 5374, -1, 5374, 5740, 5741, -1, + 5740, 5374, 5376, -1, 5376, 5739, 5740, -1, + 5739, 5376, 5378, -1, 5378, 5738, 5739, -1, + 5738, 5378, 5380, -1, 5380, 5737, 5738, -1, + 5737, 5380, 5382, -1, 5382, 5736, 5737, -1, + 5736, 5382, 5384, -1, 5384, 5735, 5736, -1, + 5735, 5384, 5386, -1, 5386, 5734, 5735, -1, + 5734, 5386, 5388, -1, 5388, 5733, 5734, -1, + 5733, 5388, 5390, -1, 5390, 5732, 5733, -1, + 5732, 5390, 5392, -1, 5392, 5731, 5732, -1, + 5731, 5392, 5394, -1, 5394, 5730, 5731, -1, + 5730, 5394, 5396, -1, 5396, 5729, 5730, -1, + 5729, 5396, 5398, -1, 5398, 5728, 5729, -1, + 5728, 5398, 5400, -1, 5400, 5727, 5728, -1, + 5727, 5400, 5402, -1, 5402, 5726, 5727, -1, + 5726, 5402, 5404, -1, 5404, 5725, 5726, -1, + 5725, 5404, 5406, -1, 5406, 5407, 5725, -1, + 5407, 5724, 5725, -1, 5407, 5748, 5724, -1, + 5748, 5407, 5408, -1, 5748, 5408, 5409, -1, + 5409, 5749, 5748, -1, 5409, 5410, 5749, -1, + 5750, 5751, 4784, -1, 5751, 5750, 5752, -1, + 5752, 5753, 5751, -1, 5753, 5752, 5754, -1, + 5754, 5755, 5753, -1, 5755, 5754, 5756, -1, + 5756, 5757, 5755, -1, 5757, 5756, 5758, -1, + 5758, 5759, 5757, -1, 5759, 5758, 5760, -1, + 5760, 5761, 5759, -1, 5761, 5760, 5762, -1, + 5762, 5763, 5761, -1, 5763, 5762, 5764, -1, + 5764, 5765, 5763, -1, 5765, 5764, 5766, -1, + 5766, 5767, 5765, -1, 5767, 5766, 5768, -1, + 5768, 5769, 5767, -1, 5769, 5768, 5770, -1, + 5770, 5771, 5769, -1, 5771, 5770, 5772, -1, + 5772, 5773, 5771, -1, 5773, 5772, 5774, -1, + 5774, 5775, 5773, -1, 5775, 5774, 5776, -1, + 5776, 5777, 5775, -1, 5777, 5776, 5778, -1, + 5778, 5779, 5777, -1, 5779, 5778, 5780, -1, + 5780, 5781, 5779, -1, 5781, 5780, 5782, -1, + 5782, 5783, 5781, -1, 5783, 5782, 5784, -1, + 5784, 5785, 5783, -1, 5785, 5784, 5786, -1, + 5786, 5787, 5785, -1, 5787, 5786, 5788, -1, + 5788, 5789, 5787, -1, 5789, 5788, 5790, -1, + 5790, 5791, 5789, -1, 5791, 5790, 5792, -1, + 5792, 5793, 5791, -1, 5793, 5792, 5794, -1, + 5794, 5795, 5793, -1, 5795, 5794, 5749, -1, + 5795, 5749, 5410, -1, 5795, 5410, 5411, -1, + 5411, 5793, 5795, -1, 5793, 5411, 5412, -1, + 5412, 5791, 5793, -1, 5791, 5412, 5413, -1, + 5413, 5789, 5791, -1, 5789, 5413, 5414, -1, + 5414, 5787, 5789, -1, 5787, 5414, 5415, -1, + 5415, 5785, 5787, -1, 5785, 5415, 5416, -1, + 5416, 5783, 5785, -1, 5783, 5416, 5417, -1, + 5417, 5781, 5783, -1, 5781, 5417, 5418, -1, + 5418, 5779, 5781, -1, 5779, 5418, 5419, -1, + 5419, 5777, 5779, -1, 5777, 5419, 5420, -1, + 5420, 5775, 5777, -1, 5775, 5420, 5421, -1, + 5421, 5773, 5775, -1, 5773, 5421, 5422, -1, + 5422, 5771, 5773, -1, 5771, 5422, 5423, -1, + 5423, 5769, 5771, -1, 5769, 5423, 5424, -1, + 5424, 5767, 5769, -1, 5767, 5424, 5425, -1, + 5425, 5765, 5767, -1, 5765, 5425, 5426, -1, + 5426, 5763, 5765, -1, 5763, 5426, 5427, -1, + 5427, 5761, 5763, -1, 5761, 5427, 5428, -1, + 5428, 5759, 5761, -1, 5759, 5428, 5429, -1, + 5429, 5757, 5759, -1, 5757, 5429, 5430, -1, + 5430, 5755, 5757, -1, 5755, 5430, 5431, -1, + 5431, 5753, 5755, -1, 5753, 5431, 5432, -1, + 5432, 5751, 5753, -1, 5751, 5432, 5433, -1, + 5433, 4784, 5751, -1, 4784, 5433, 5450, -1, + 5450, 4782, 4784, -1, 4782, 5450, 5448, -1, + 5448, 4780, 4782, -1, 4780, 5448, 5446, -1, + 5446, 4778, 4780, -1, 4778, 5446, 5444, -1, + 5444, 4776, 4778, -1, 4776, 5444, 5442, -1, + 5442, 4774, 4776, -1, 4774, 5442, 5440, -1, + 5440, 4772, 4774, -1, 4772, 5440, 5438, -1, + 5438, 4770, 4772, -1, 4770, 5438, 5436, -1, + 5436, 4768, 4770, -1, 4768, 5436, 5435, -1, + 5435, 4766, 4768, -1, 4766, 5435, 5796, -1, + 5796, 4764, 4766, -1, 4764, 5796, 5797, -1, + 5797, 4762, 4764, -1, 4762, 5797, 5798, -1, + 5798, 4760, 4762, -1, 4760, 5798, 5799, -1, + 5799, 4759, 4760, -1, 4759, 5799, 5800, -1, + 5801, 5802, 5803, -1, 5804, 5805, 5806, -1, + 5805, 5804, 5802, -1, 5802, 5801, 5805, -1, + 5801, 5807, 5805, -1, 5801, 5808, 5807, -1, + 5801, 5803, 5808, -1, 5809, 5808, 5803, -1, + 5809, 5810, 5808, -1, 5810, 5809, 5811, -1, + 5811, 5812, 5810, -1, 5812, 5811, 5813, -1, + 5813, 5814, 5812, -1, 5814, 5813, 5815, -1, + 5814, 5815, 5816, -1, 5817, 5814, 5816, -1, + 5817, 5818, 5814, -1, 5814, 5818, 5800, -1, + 5800, 5812, 5814, -1, 5812, 5800, 5799, -1, + 5799, 5810, 5812, -1, 5810, 5799, 5798, -1, + 5798, 5808, 5810, -1, 5808, 5798, 5797, -1, + 5797, 5807, 5808, -1, 5807, 5797, 5796, -1, + 5796, 5819, 5807, -1, 5819, 5796, 5435, -1, + 5435, 5434, 5819, -1, 5820, 5819, 5434, -1, + 5819, 5820, 5821, -1, 5821, 5807, 5819, -1, + 5821, 5805, 5807, -1, 5821, 5806, 5805, -1, + 5806, 5821, 5820, -1, 5820, 5822, 5806, -1, + 5822, 5820, 5434, -1, 5434, 5823, 5822, -1, + 5823, 5434, 5437, -1, 5437, 5824, 5823, -1, + 5824, 5437, 5439, -1, 5439, 5825, 5824, -1, + 5825, 5439, 5441, -1, 5441, 5826, 5825, -1, + 5826, 5441, 5443, -1, 5443, 5827, 5826, -1, + 5827, 5443, 5445, -1, 5445, 5828, 5827, -1, + 5828, 5445, 5447, -1, 5447, 5829, 5828, -1, + 5829, 5447, 5449, -1, 5449, 5830, 5829, -1, + 5830, 5449, 5451, -1, 5451, 5831, 5830, -1, + 5831, 5451, 5452, -1, 5452, 5453, 5831, -1, + 5453, 5832, 5831, -1, 5832, 5453, 5454, -1, + 5454, 5833, 5832, -1, 5833, 5454, 5455, -1, + 5455, 5834, 5833, -1, 5834, 5455, 5456, -1, + 5456, 5835, 5834, -1, 5835, 5456, 5457, -1, + 5457, 5836, 5835, -1, 5836, 5457, 5458, -1, + 5458, 5837, 5836, -1, 5837, 5458, 5459, -1, + 5459, 5838, 5837, -1, 5838, 5459, 5460, -1, + 5460, 5839, 5838, -1, 5839, 5460, 5461, -1, + 5461, 5840, 5839, -1, 5840, 5461, 5462, -1, + 5462, 5841, 5840, -1, 5841, 5462, 5463, -1, + 5463, 5842, 5841, -1, 5842, 5463, 5464, -1, + 5464, 5843, 5842, -1, 5843, 5464, 5465, -1, + 5465, 5844, 5843, -1, 5844, 5465, 5466, -1, + 5466, 5845, 5844, -1, 5845, 5466, 5467, -1, + 5467, 5846, 5845, -1, 5846, 5467, 5468, -1, + 5468, 5847, 5846, -1, 5847, 5468, 5469, -1, + 5469, 5848, 5847, -1, 5848, 5469, 5470, -1, + 5470, 5849, 5848, -1, 5849, 5470, 5471, -1, + 5471, 5850, 5849, -1, 5850, 5471, 5472, -1, + 5472, 5851, 5850, -1, 5851, 5472, 5473, -1, + 5473, 5852, 5851, -1, 5852, 5473, 5474, -1, + 5474, 5853, 5852, -1, 5853, 5474, 5475, -1, + 5475, 5854, 5853, -1, 5854, 5475, 5476, -1, + 5476, 5855, 5854, -1, 5855, 5476, 5477, -1, + 5477, 5856, 5855, -1, 5856, 5477, 5478, -1, + 5478, 5857, 5856, -1, 5478, 5858, 5857, -1, + 5858, 5478, 5479, -1, 5479, 5859, 5858, -1, + 5859, 5479, 5480, -1, 5480, 5860, 5859, -1, + 5860, 5480, 5481, -1, 5481, 5861, 5860, -1, + 5861, 5481, 5482, -1, 5482, 5862, 5861, -1, + 5862, 5482, 5483, -1, 5483, 5863, 5862, -1, + 5863, 5483, 5484, -1, 5484, 5864, 5863, -1, + 5864, 5484, 5485, -1, 5485, 5865, 5864, -1, + 5865, 5485, 5486, -1, 5486, 5866, 5865, -1, + 5866, 5486, 5487, -1, 5487, 5867, 5866, -1, + 5867, 5487, 5488, -1, 5488, 5868, 5867, -1, + 5868, 5488, 5489, -1, 5489, 5869, 5868, -1, + 5869, 5489, 5490, -1, 5490, 5870, 5869, -1, + 5870, 5490, 5491, -1, 5491, 5871, 5870, -1, + 5871, 5491, 5492, -1, 5492, 5872, 5871, -1, + 5872, 5492, 5493, -1, 5493, 5873, 5872, -1, + 5873, 5493, 5494, -1, 5494, 5874, 5873, -1, + 5874, 5494, 5495, -1, 5495, 5875, 5874, -1, + 5875, 5495, 5496, -1, 5496, 5876, 5875, -1, + 5876, 5496, 5497, -1, 5497, 5877, 5876, -1, + 5877, 5497, 5498, -1, 5498, 5878, 5877, -1, + 5878, 5498, 5499, -1, 5499, 5879, 5878, -1, + 5879, 5499, 5500, -1, 5500, 5880, 5879, -1, + 5880, 5500, 5501, -1, 5501, 5881, 5880, -1, + 5881, 5501, 5502, -1, 5502, 5503, 5881, -1, + 5881, 5503, 5604, -1, 5604, 5880, 5881, -1, + 5880, 5604, 5602, -1, 5602, 5879, 5880, -1, + 5879, 5602, 5600, -1, 5600, 5878, 5879, -1, + 5878, 5600, 5598, -1, 5598, 5877, 5878, -1, + 5877, 5598, 5596, -1, 5596, 5876, 5877, -1, + 5876, 5596, 5594, -1, 5594, 5875, 5876, -1, + 5875, 5594, 5592, -1, 5592, 5874, 5875, -1, + 5874, 5592, 5590, -1, 5590, 5873, 5874, -1, + 5873, 5590, 5588, -1, 5588, 5872, 5873, -1, + 5872, 5588, 5586, -1, 5586, 5871, 5872, -1, + 5871, 5586, 5584, -1, 5584, 5870, 5871, -1, + 5870, 5584, 5582, -1, 5582, 5869, 5870, -1, + 5869, 5582, 5580, -1, 5580, 5868, 5869, -1, + 5868, 5580, 5578, -1, 5578, 5867, 5868, -1, + 5867, 5578, 5576, -1, 5576, 5866, 5867, -1, + 5866, 5576, 5574, -1, 5574, 5865, 5866, -1, + 5865, 5574, 5572, -1, 5572, 5864, 5865, -1, + 5864, 5572, 5570, -1, 5570, 5863, 5864, -1, + 5863, 5570, 5568, -1, 5568, 5862, 5863, -1, + 5862, 5568, 5566, -1, 5566, 5861, 5862, -1, + 5861, 5566, 5564, -1, 5564, 5860, 5861, -1, + 5860, 5564, 5562, -1, 5562, 5859, 5860, -1, + 5859, 5562, 5560, -1, 5560, 5858, 5859, -1, + 5858, 5560, 5558, -1, 5558, 5857, 5858, -1, + 5857, 5558, 5555, -1, 5857, 5555, 5553, -1, + 5553, 5856, 5857, -1, 5856, 5553, 5551, -1, + 5551, 5855, 5856, -1, 5855, 5551, 5549, -1, + 5549, 5854, 5855, -1, 5854, 5549, 5547, -1, + 5547, 5853, 5854, -1, 5853, 5547, 5545, -1, + 5545, 5852, 5853, -1, 5852, 5545, 5543, -1, + 5543, 5851, 5852, -1, 5851, 5543, 5541, -1, + 5541, 5850, 5851, -1, 5850, 5541, 5539, -1, + 5539, 5849, 5850, -1, 5849, 5539, 5537, -1, + 5537, 5848, 5849, -1, 5848, 5537, 5535, -1, + 5535, 5847, 5848, -1, 5847, 5535, 5533, -1, + 5533, 5846, 5847, -1, 5846, 5533, 5531, -1, + 5531, 5845, 5846, -1, 5845, 5531, 5529, -1, + 5529, 5844, 5845, -1, 5844, 5529, 5527, -1, + 5527, 5843, 5844, -1, 5843, 5527, 5525, -1, + 5525, 5842, 5843, -1, 5842, 5525, 5523, -1, + 5523, 5841, 5842, -1, 5841, 5523, 5521, -1, + 5521, 5840, 5841, -1, 5840, 5521, 5519, -1, + 5519, 5839, 5840, -1, 5839, 5519, 5517, -1, + 5517, 5838, 5839, -1, 5838, 5517, 5515, -1, + 5515, 5837, 5838, -1, 5837, 5515, 5513, -1, + 5513, 5836, 5837, -1, 5836, 5513, 5511, -1, + 5511, 5835, 5836, -1, 5835, 5511, 5509, -1, + 5509, 5834, 5835, -1, 5834, 5509, 5507, -1, + 5507, 5833, 5834, -1, 5833, 5507, 5504, -1, + 5504, 5832, 5833, -1, 5832, 5504, 5506, -1, + 5506, 5831, 5832, -1, 5831, 5506, 5621, -1, + 5621, 5830, 5831, -1, 5830, 5621, 5622, -1, + 5622, 5829, 5830, -1, 5829, 5622, 5623, -1, + 5623, 5828, 5829, -1, 5828, 5623, 5624, -1, + 5624, 5827, 5828, -1, 5827, 5624, 5625, -1, + 5625, 5826, 5827, -1, 5826, 5625, 5626, -1, + 5626, 5825, 5826, -1, 5825, 5626, 5627, -1, + 5627, 5824, 5825, -1, 5824, 5627, 5628, -1, + 5628, 5823, 5824, -1, 5823, 5628, 5629, -1, + 5629, 5822, 5823, -1, 5822, 5629, 5631, -1, + 5631, 5806, 5822, -1, 5806, 5631, 5632, -1, + 5632, 5804, 5806, -1, 5804, 5632, 5882, -1, + 5882, 5802, 5804, -1, 5802, 5882, 4751, -1, + 4751, 5803, 5802, -1, 5803, 4751, 4748, -1, + 4748, 5809, 5803, -1, 4748, 4750, 5809, -1, + 5883, 5809, 4750, -1, 5883, 5811, 5809, -1, + 5811, 5883, 5884, -1, 5884, 5813, 5811, -1, + 5813, 5884, 5885, -1, 5885, 5815, 5813, -1, + 5815, 5885, 4747, -1, 4747, 4746, 5815, -1, + 5886, 5815, 4746, -1, 4746, 4744, 5886, -1, + 4746, 4745, 4744, -1, 4745, 4743, 4744, -1, + 4745, 4747, 4743, -1, 4747, 4708, 4743, -1, + 4747, 4741, 4708, -1, 4741, 4747, 5885, -1, + 5885, 4740, 4741, -1, 4740, 5885, 5884, -1, + 4740, 5884, 5887, -1, 5888, 5889, 5890, -1, + 5888, 5891, 5889, -1, 5891, 5888, 5887, -1, + 5891, 5887, 5884, -1, 5891, 5884, 5883, -1, + 5883, 5889, 5891, -1, 5889, 5883, 4750, -1, + 4750, 5892, 5889, -1, 5892, 4750, 4749, -1, + 4749, 5893, 5892, -1, 5893, 4749, 4751, -1, + 4751, 5894, 5893, -1, 5894, 4751, 5882, -1, + 5882, 5895, 5894, -1, 5895, 5882, 5632, -1, + 5895, 5632, 4977, -1, 5895, 4977, 4975, -1, + 4975, 5894, 5895, -1, 5894, 4975, 4973, -1, + 4973, 5893, 5894, -1, 5893, 4973, 4972, -1, + 4972, 5892, 5893, -1, 5892, 4972, 5896, -1, + 5896, 5889, 5892, -1, 5896, 5890, 5889, -1, + 5896, 5897, 5890, -1, 5897, 5896, 4972, -1, + 4972, 4971, 5897, -1, 5898, 5897, 4971, -1, + 5897, 5898, 5899, -1, 5899, 5890, 5897, -1, + 5890, 5899, 5900, -1, 5900, 5888, 5890, -1, + 5888, 5900, 5901, -1, 5901, 5887, 5888, -1, + 5887, 5901, 5902, -1, 5902, 4740, 5887, -1, + 5902, 4739, 4740, -1, 5902, 4738, 4739, -1, + 4738, 5902, 5901, -1, 5901, 4736, 4738, -1, + 4736, 5901, 5900, -1, 5900, 4734, 4736, -1, + 4734, 5900, 5899, -1, 5899, 4732, 4734, -1, + 4732, 5899, 5898, -1, 5898, 4730, 4732, -1, + 4730, 5898, 4971, -1, 4971, 4728, 4730, -1, + 4728, 4971, 4974, -1, 4974, 4726, 4728, -1, + 4726, 4974, 4976, -1, 4976, 4723, 4726, -1, + 4723, 4976, 4978, -1, 4978, 4724, 4723, -1, + 4724, 4978, 4979, -1, 4979, 5633, 4724, -1, + 5633, 5903, 4724, -1, 5903, 5633, 5634, -1, + 5634, 5904, 5903, -1, 5904, 5634, 5635, -1, + 5635, 5905, 5904, -1, 5905, 5635, 5636, -1, + 5636, 5906, 5905, -1, 5906, 5636, 5637, -1, + 5637, 5907, 5906, -1, 5907, 5637, 5638, -1, + 5638, 5908, 5907, -1, 5908, 5638, 5639, -1, + 5639, 5909, 5908, -1, 5909, 5639, 5640, -1, + 5640, 5910, 5909, -1, 5910, 5640, 5641, -1, + 5641, 5911, 5910, -1, 5911, 5641, 5642, -1, + 5642, 5912, 5911, -1, 5912, 5642, 4970, -1, + 4970, 5913, 5912, -1, 5913, 4970, 4968, -1, + 4968, 5914, 5913, -1, 5914, 4968, 4966, -1, + 4966, 5915, 5914, -1, 5915, 4966, 4964, -1, + 4964, 5916, 5915, -1, 5916, 4964, 4962, -1, + 4962, 5917, 5916, -1, 5917, 4962, 4960, -1, + 4960, 5918, 5917, -1, 5918, 4960, 4958, -1, + 4958, 5919, 5918, -1, 5919, 4958, 4956, -1, + 4956, 5920, 5919, -1, 5920, 4956, 4954, -1, + 4954, 5921, 5920, -1, 5921, 4954, 4952, -1, + 4952, 5922, 5921, -1, 5922, 4952, 4950, -1, + 4950, 5923, 5922, -1, 5923, 4950, 4948, -1, + 4948, 5924, 5923, -1, 5924, 4948, 4946, -1, + 4946, 5925, 5924, -1, 5925, 4946, 4944, -1, + 4944, 5926, 5925, -1, 5926, 4944, 4898, -1, + 4898, 4897, 5926, -1, 5927, 5928, 5929, -1, + 5929, 5930, 5927, -1, 5930, 5929, 5931, -1, + 5931, 5932, 5930, -1, 5932, 5931, 5933, -1, + 5933, 5934, 5932, -1, 5934, 5933, 5935, -1, + 5935, 5936, 5934, -1, 5936, 5935, 5937, -1, + 5937, 5938, 5936, -1, 5938, 5937, 5939, -1, + 5939, 5940, 5938, -1, 5940, 5939, 5941, -1, + 5941, 5942, 5940, -1, 5942, 5941, 5943, -1, + 5943, 5944, 5942, -1, 5944, 5943, 5945, -1, + 5945, 5946, 5944, -1, 5946, 5945, 5947, -1, + 5947, 5948, 5946, -1, 5948, 5947, 5949, -1, + 5949, 5950, 5948, -1, 5950, 5949, 5951, -1, + 5951, 5952, 5950, -1, 5952, 5951, 5953, -1, + 5953, 5954, 5952, -1, 5955, 5954, 5956, -1, + 5954, 5955, 5957, -1, 5957, 5952, 5954, -1, + 5952, 5957, 5958, -1, 5958, 5950, 5952, -1, + 5950, 5958, 5959, -1, 5959, 5948, 5950, -1, + 5948, 5959, 5960, -1, 5960, 5946, 5948, -1, + 5946, 5960, 5961, -1, 5961, 5944, 5946, -1, + 5944, 5961, 5962, -1, 5962, 5942, 5944, -1, + 5942, 5962, 5963, -1, 5963, 5940, 5942, -1, + 5940, 5963, 5964, -1, 5964, 5938, 5940, -1, + 5938, 5964, 5965, -1, 5965, 5936, 5938, -1, + 5936, 5965, 5966, -1, 5966, 5934, 5936, -1, + 5934, 5966, 5967, -1, 5967, 5932, 5934, -1, + 5932, 5967, 5968, -1, 5968, 5930, 5932, -1, + 5930, 5968, 5969, -1, 5969, 5927, 5930, -1, + 5969, 4897, 5927, -1, 5969, 5926, 4897, -1, + 5926, 5969, 5968, -1, 5968, 5925, 5926, -1, + 5925, 5968, 5967, -1, 5967, 5924, 5925, -1, + 5924, 5967, 5966, -1, 5966, 5923, 5924, -1, + 5923, 5966, 5965, -1, 5965, 5922, 5923, -1, + 5922, 5965, 5964, -1, 5964, 5921, 5922, -1, + 5921, 5964, 5963, -1, 5963, 5920, 5921, -1, + 5920, 5963, 5962, -1, 5962, 5919, 5920, -1, + 5919, 5962, 5961, -1, 5961, 5918, 5919, -1, + 5918, 5961, 5960, -1, 5960, 5917, 5918, -1, + 5917, 5960, 5959, -1, 5959, 5916, 5917, -1, + 5916, 5959, 5958, -1, 5958, 5915, 5916, -1, + 5915, 5958, 5957, -1, 5957, 5914, 5915, -1, + 5914, 5957, 5955, -1, 5955, 5913, 5914, -1, + 5913, 5955, 5956, -1, 5956, 5912, 5913, -1, + 5912, 5956, 5970, -1, 5970, 5911, 5912, -1, + 5911, 5970, 5971, -1, 5971, 5910, 5911, -1, + 5910, 5971, 5972, -1, 5972, 5909, 5910, -1, + 5909, 5972, 5973, -1, 5973, 5908, 5909, -1, + 5908, 5973, 5974, -1, 5974, 5907, 5908, -1, + 5907, 5974, 5975, -1, 5975, 5906, 5907, -1, + 5906, 5975, 5976, -1, 5976, 5905, 5906, -1, + 5905, 5976, 5977, -1, 5977, 5904, 5905, -1, + 5904, 5977, 5978, -1, 5978, 5903, 5904, -1, + 5903, 5978, 4707, -1, 4707, 4706, 5903, -1, + 4706, 4724, 5903, -1, 4724, 4706, 4665, -1, + 4665, 4725, 4724, -1, 4725, 4665, 4664, -1, + 4664, 4727, 4725, -1, 4727, 4664, 4667, -1, + 4667, 4729, 4727, -1, 4729, 4667, 4669, -1, + 4669, 4731, 4729, -1, 4731, 4669, 4699, -1, + 4699, 4733, 4731, -1, 4733, 4699, 4697, -1, + 4697, 4735, 4733, -1, 4735, 4697, 4695, -1, + 4695, 4737, 4735, -1, 4737, 4695, 4693, -1, + 4693, 4722, 4737, -1, 4722, 4693, 4691, -1, + 4691, 4720, 4722, -1, 4720, 4691, 4689, -1, + 4689, 4718, 4720, -1, 4718, 4689, 4687, -1, + 4687, 4716, 4718, -1, 4716, 4687, 4685, -1, + 4685, 4715, 4716, -1, 4715, 4685, 4683, -1, + 4683, 4714, 4715, -1, 4714, 4683, 4682, -1, + 4682, 4681, 4714, -1, 5979, 4714, 4681, -1, + 4681, 5980, 5979, -1, 4681, 4680, 5980, -1, + 4680, 4679, 5980, -1, 4679, 4678, 5980, -1, + 5981, 5980, 4678, -1, 4678, 5982, 5981, -1, + 4678, 4674, 5982, -1, 5982, 4674, 4673, -1, + 4673, 5981, 5982, -1, 4673, 4671, 5981, -1, + 4671, 4670, 5981, -1, 4670, 5983, 5981, -1, + 4670, 4672, 5983, -1, 5984, 5983, 4672, -1, + 4672, 5985, 5984, -1, 5985, 4672, 4675, -1, + 5985, 4675, 5986, -1, 5987, 5988, 5989, -1, + 5987, 5990, 5988, -1, 5990, 5987, 5986, -1, + 5990, 5986, 4675, -1, 5990, 4675, 4677, -1, + 4677, 5988, 5990, -1, 5988, 4677, 4663, -1, + 4663, 4662, 5988, -1, 4662, 5989, 5988, -1, + 4662, 5991, 5989, -1, 5991, 4662, 4659, -1, + 4659, 5992, 5991, -1, 5993, 5992, 5994, -1, + 5992, 5993, 5995, -1, 5995, 5991, 5992, -1, + 5991, 5995, 5996, -1, 5996, 5989, 5991, -1, + 5989, 5996, 5997, -1, 5997, 5998, 5999, -1, + 5998, 5997, 5996, -1, 5996, 6000, 5998, -1, + 6000, 5996, 5995, -1, 5995, 6001, 6000, -1, + 6001, 5995, 5993, -1, 5993, 6002, 6001, -1, + 5993, 5994, 6002, -1, 6003, 6002, 5994, -1, + 6003, 4657, 6002, -1, 6003, 4658, 4657, -1, + 6003, 6004, 4658, -1, 6004, 6003, 5994, -1, + 5994, 6005, 6004, -1, 6005, 5994, 5992, -1, + 5992, 4659, 6005, -1, 4659, 4661, 6005, -1, + 6006, 6005, 4661, -1, 6006, 6004, 6005, -1, + 6004, 6006, 6007, -1, 6007, 4658, 6004, -1, + 4658, 6007, 6008, -1, 6008, 4587, 4658, -1, + 6008, 4585, 4587, -1, 6008, 4586, 4585, -1, + 4586, 6008, 6007, -1, 6007, 6009, 4586, -1, + 6009, 6007, 6006, -1, 6006, 4661, 6009, -1, + 4661, 6010, 6009, -1, 4661, 6011, 6010, -1, + 6011, 4661, 4660, -1, 4660, 6012, 6011, -1, + 6012, 4660, 4663, -1, 4663, 6013, 6012, -1, + 6013, 4663, 4677, -1, 6013, 4677, 4676, -1, + 6013, 4676, 4684, -1, 4684, 6012, 6013, -1, + 6012, 4684, 4686, -1, 4686, 6011, 6012, -1, + 6011, 4686, 4688, -1, 4688, 6010, 6011, -1, + 6010, 4688, 4690, -1, 4690, 6014, 6010, -1, + 6014, 4690, 4692, -1, 4692, 6015, 6014, -1, + 6015, 4692, 4694, -1, 4694, 6016, 6015, -1, + 6016, 4694, 4696, -1, 4696, 6017, 6016, -1, + 6017, 4696, 4698, -1, 4698, 6018, 6017, -1, + 6018, 4698, 4700, -1, 4700, 4701, 6018, -1, + 4701, 4703, 6018, -1, 6019, 6018, 4703, -1, + 6019, 6017, 6018, -1, 6017, 6019, 6020, -1, + 6020, 6016, 6017, -1, 6016, 6020, 6021, -1, + 6021, 6015, 6016, -1, 6015, 6021, 6022, -1, + 6022, 6014, 6015, -1, 6014, 6022, 6023, -1, + 6023, 6010, 6014, -1, 6023, 6009, 6010, -1, + 6023, 4586, 6009, -1, 4586, 6023, 6022, -1, + 6022, 4584, 4586, -1, 4584, 6022, 6021, -1, + 6021, 4583, 4584, -1, 4583, 6021, 6020, -1, + 6020, 4581, 4583, -1, 4581, 6020, 6019, -1, + 6019, 4703, 4581, -1, 4703, 4582, 4581, -1, + 4703, 4654, 4582, -1, 4654, 4703, 4702, -1, + 4702, 4652, 4654, -1, 4652, 4702, 4704, -1, + 4704, 4650, 4652, -1, 4650, 4704, 4705, -1, + 4705, 4648, 4650, -1, 4648, 4705, 4707, -1, + 4707, 4646, 4648, -1, 4646, 4707, 5978, -1, + 5978, 4644, 4646, -1, 4644, 5978, 5977, -1, + 5977, 4642, 4644, -1, 4642, 5977, 5976, -1, + 5976, 4640, 4642, -1, 4640, 5976, 5975, -1, + 5975, 4638, 4640, -1, 4638, 5975, 5974, -1, + 5974, 4636, 4638, -1, 4636, 5974, 5973, -1, + 5973, 4634, 4636, -1, 4634, 5973, 5972, -1, + 5972, 4632, 4634, -1, 4632, 5972, 5971, -1, + 5971, 4630, 4632, -1, 4630, 5971, 5970, -1, + 5970, 4628, 4630, -1, 4628, 5970, 5956, -1, + 5956, 4626, 4628, -1, 4626, 5956, 5954, -1, + 5954, 5953, 4626, -1, 5953, 4625, 4626, -1, + 4625, 5953, 5951, -1, 5951, 4624, 4625, -1, + 4624, 5951, 5949, -1, 5949, 4623, 4624, -1, + 4623, 5949, 5947, -1, 5947, 4622, 4623, -1, + 4622, 5947, 5945, -1, 5945, 4621, 4622, -1, + 4621, 5945, 5943, -1, 5943, 4620, 4621, -1, + 4620, 5943, 5941, -1, 5941, 4619, 4620, -1, + 4619, 5941, 5939, -1, 5939, 4618, 4619, -1, + 4618, 5939, 5937, -1, 5937, 4617, 4618, -1, + 4617, 5937, 5935, -1, 5935, 4615, 4617, -1, + 4615, 5935, 5933, -1, 5933, 6024, 4615, -1, + 6024, 5933, 5931, -1, 5931, 6025, 6024, -1, + 6025, 5931, 5929, -1, 5929, 6026, 6025, -1, + 6026, 5929, 5928, -1, 5928, 6027, 6026, -1, + 6027, 5928, 6028, -1, 6028, 6029, 6027, -1, + 6029, 6028, 6030, -1, 6030, 6031, 6029, -1, + 6031, 6030, 6032, -1, 6032, 6033, 6031, -1, + 6033, 6032, 6034, -1, 6034, 6035, 6033, -1, + 6035, 6034, 6036, -1, 6036, 6037, 6035, -1, + 6037, 6036, 6038, -1, 6038, 6039, 6037, -1, + 6039, 6038, 6040, -1, 6040, 6041, 6039, -1, + 6041, 6040, 6042, -1, 6042, 6043, 6041, -1, + 6043, 6042, 6044, -1, 6044, 6045, 6043, -1, + 6045, 6044, 6046, -1, 6046, 6047, 6045, -1, + 6047, 6046, 6048, -1, 6048, 6049, 6047, -1, + 6049, 6048, 6050, -1, 6050, 6051, 6049, -1, + 6051, 6050, 6052, -1, 6052, 6053, 6051, -1, + 6052, 6054, 6053, -1, 6054, 6052, 6055, -1, + 6055, 6056, 6054, -1, 6056, 6055, 6057, -1, + 6057, 6058, 6056, -1, 6058, 6057, 6059, -1, + 6059, 6060, 6058, -1, 6060, 6059, 6061, -1, + 6061, 6062, 6060, -1, 6062, 6061, 6063, -1, + 6063, 6064, 6062, -1, 6064, 6063, 6065, -1, + 6065, 6066, 6064, -1, 6066, 6067, 6068, -1, + 6066, 6065, 6067, -1, 6069, 6070, 6071, -1, + 6071, 6072, 6069, -1, 6072, 6071, 6073, -1, + 6073, 6074, 6072, -1, 6074, 6073, 6075, -1, + 6075, 6076, 6074, -1, 6076, 6075, 6077, -1, + 6077, 6078, 6076, -1, 6078, 6077, 6079, -1, + 6079, 6080, 6078, -1, 6080, 6079, 6081, -1, + 6081, 6082, 6080, -1, 6082, 6081, 6083, -1, + 6083, 6084, 6082, -1, 6084, 6083, 6085, -1, + 6085, 6086, 6084, -1, 6086, 6085, 6087, -1, + 6087, 6088, 6086, -1, 6088, 6087, 6089, -1, + 6089, 6090, 6088, -1, 6090, 6089, 6091, -1, + 6091, 6092, 6090, -1, 6092, 6091, 6093, -1, + 6093, 6094, 6092, -1, 6094, 6093, 6095, -1, + 6095, 6096, 6094, -1, 6096, 6095, 6097, -1, + 6097, 6098, 6096, -1, 6098, 6097, 6099, -1, + 6099, 6100, 6098, -1, 6100, 6099, 6101, -1, + 6101, 6102, 6100, -1, 6102, 6101, 6103, -1, + 6103, 6104, 6102, -1, 6104, 6103, 6105, -1, + 6105, 6106, 6104, -1, 6106, 6105, 6067, -1, + 6067, 6107, 6106, -1, 6107, 6067, 6065, -1, + 6065, 6108, 6107, -1, 6108, 6065, 6063, -1, + 6063, 6109, 6108, -1, 6109, 6063, 6061, -1, + 6061, 6110, 6109, -1, 6110, 6061, 6059, -1, + 6059, 6111, 6110, -1, 6111, 6059, 6057, -1, + 6057, 6112, 6111, -1, 6112, 6057, 6055, -1, + 6055, 6113, 6112, -1, 6113, 6055, 6052, -1, + 6113, 6052, 6050, -1, 6050, 6114, 6113, -1, + 6114, 6050, 6048, -1, 6048, 6115, 6114, -1, + 6115, 6048, 6046, -1, 6046, 6116, 6115, -1, + 6116, 6046, 6044, -1, 6044, 6117, 6116, -1, + 6117, 6044, 6042, -1, 6042, 6118, 6117, -1, + 6118, 6042, 6040, -1, 6040, 6119, 6118, -1, + 6119, 6040, 6038, -1, 6038, 6120, 6119, -1, + 6120, 6038, 6036, -1, 6036, 6121, 6120, -1, + 6121, 6036, 6034, -1, 6034, 6122, 6121, -1, + 6122, 6034, 6032, -1, 6032, 6123, 6122, -1, + 6123, 6032, 6030, -1, 6030, 6124, 6123, -1, + 6124, 6030, 6028, -1, 6028, 6125, 6124, -1, + 6125, 6028, 5928, -1, 5928, 5927, 6125, -1, + 6125, 5927, 4897, -1, 6125, 4897, 4900, -1, + 4900, 6124, 6125, -1, 6124, 4900, 4902, -1, + 4902, 6123, 6124, -1, 6123, 4902, 4904, -1, + 4904, 6122, 6123, -1, 6122, 4904, 4906, -1, + 4906, 6121, 6122, -1, 6121, 4906, 4908, -1, + 4908, 6120, 6121, -1, 6120, 4908, 4910, -1, + 4910, 6119, 6120, -1, 6119, 4910, 4912, -1, + 4912, 6118, 6119, -1, 6118, 4912, 4914, -1, + 4914, 6117, 6118, -1, 6117, 4914, 4916, -1, + 4916, 6116, 6117, -1, 6116, 4916, 4918, -1, + 4918, 6115, 6116, -1, 6115, 4918, 4920, -1, + 4920, 6114, 6115, -1, 6114, 4920, 4922, -1, + 4922, 6113, 6114, -1, 4922, 6112, 6113, -1, + 6112, 4922, 4923, -1, 4923, 6111, 6112, -1, + 6111, 4923, 4925, -1, 4925, 6110, 6111, -1, + 6110, 4925, 4927, -1, 4927, 6109, 6110, -1, + 6109, 4927, 4895, -1, 4895, 6108, 6109, -1, + 6108, 4895, 4893, -1, 4893, 6107, 6108, -1, + 6107, 4893, 4891, -1, 4891, 6106, 6107, -1, + 6106, 4891, 4889, -1, 4889, 6104, 6106, -1, + 6104, 4889, 4887, -1, 4887, 6102, 6104, -1, + 6102, 4887, 4885, -1, 4885, 6100, 6102, -1, + 6100, 4885, 4883, -1, 4883, 6098, 6100, -1, + 6098, 4883, 4881, -1, 4881, 6096, 6098, -1, + 6096, 4881, 4879, -1, 4879, 6094, 6096, -1, + 6094, 4879, 4877, -1, 4877, 6092, 6094, -1, + 6092, 4877, 4875, -1, 4875, 6090, 6092, -1, + 6090, 4875, 4873, -1, 4873, 6088, 6090, -1, + 6088, 4873, 4871, -1, 4871, 6086, 6088, -1, + 6086, 4871, 4869, -1, 4869, 6084, 6086, -1, + 6084, 4869, 4867, -1, 4867, 6082, 6084, -1, + 6082, 4867, 4865, -1, 4865, 6080, 6082, -1, + 6080, 4865, 4863, -1, 4863, 6078, 6080, -1, + 6078, 4863, 4861, -1, 4861, 6076, 6078, -1, + 6076, 4861, 4859, -1, 4859, 6074, 6076, -1, + 6074, 4859, 4857, -1, 4857, 6072, 6074, -1, + 6072, 4857, 4855, -1, 4855, 6069, 6072, -1, + 6069, 4855, 4853, -1, 4853, 6070, 6069, -1, + 6070, 4853, 4852, -1, 4852, 6126, 6070, -1, + 6126, 4852, 5643, -1, 5643, 6127, 6126, -1, + 6127, 5643, 5644, -1, 5644, 6128, 6127, -1, + 6128, 5644, 5645, -1, 5645, 6129, 6128, -1, + 6129, 5645, 5646, -1, 5646, 6130, 6129, -1, + 6130, 5646, 5647, -1, 5647, 6131, 6130, -1, + 6131, 5647, 5648, -1, 5648, 6132, 6131, -1, + 6132, 5648, 5649, -1, 5649, 6133, 6132, -1, + 6133, 5649, 5650, -1, 5650, 6134, 6133, -1, + 6134, 5650, 5651, -1, 5651, 6135, 6134, -1, + 6135, 5651, 5652, -1, 5652, 6136, 6135, -1, + 6136, 5652, 5653, -1, 5653, 6137, 6136, -1, + 6137, 5653, 4850, -1, 4850, 6138, 6137, -1, + 6138, 4850, 4826, -1, 4826, 4825, 6138, -1, + 4825, 6139, 6138, -1, 6139, 4825, 4828, -1, + 4828, 4787, 6139, -1, 6139, 4787, 4786, -1, + 6139, 4786, 6140, -1, 6140, 6138, 6139, -1, + 6138, 6140, 6141, -1, 6141, 6137, 6138, -1, + 6137, 6141, 6142, -1, 6142, 6136, 6137, -1, + 6136, 6142, 6143, -1, 6143, 6135, 6136, -1, + 6135, 6143, 6144, -1, 6144, 6134, 6135, -1, + 6134, 6144, 6145, -1, 6145, 6133, 6134, -1, + 6133, 6145, 6146, -1, 6146, 6132, 6133, -1, + 6132, 6146, 6147, -1, 6147, 6131, 6132, -1, + 6131, 6147, 6148, -1, 6148, 6130, 6131, -1, + 6130, 6148, 6149, -1, 6149, 6129, 6130, -1, + 6129, 6149, 6150, -1, 6150, 6128, 6129, -1, + 6128, 6150, 6151, -1, 6151, 6127, 6128, -1, + 6127, 6151, 6152, -1, 6152, 6126, 6127, -1, + 6126, 6152, 6153, -1, 6153, 6070, 6126, -1, + 6070, 6153, 6154, -1, 6154, 6071, 6070, -1, + 6071, 6154, 6155, -1, 6155, 6073, 6071, -1, + 6073, 6155, 6156, -1, 6156, 6075, 6073, -1, + 6075, 6156, 6157, -1, 6157, 6077, 6075, -1, + 6077, 6157, 6158, -1, 6158, 6079, 6077, -1, + 6079, 6158, 6159, -1, 6159, 6081, 6079, -1, + 6081, 6159, 6160, -1, 6160, 6083, 6081, -1, + 6083, 6160, 6161, -1, 6161, 6085, 6083, -1, + 6085, 6161, 6162, -1, 6162, 6087, 6085, -1, + 6087, 6162, 6163, -1, 6163, 6089, 6087, -1, + 6089, 6163, 6164, -1, 6164, 6091, 6089, -1, + 6091, 6164, 6165, -1, 6165, 6093, 6091, -1, + 6093, 6165, 6166, -1, 6166, 6095, 6093, -1, + 6095, 6166, 6167, -1, 6167, 6097, 6095, -1, + 6097, 6167, 6168, -1, 6168, 6099, 6097, -1, + 6099, 6168, 6169, -1, 6169, 6101, 6099, -1, + 6101, 6169, 6170, -1, 6170, 6103, 6101, -1, + 6103, 6170, 6171, -1, 6171, 6105, 6103, -1, + 6105, 6171, 6172, -1, 6172, 6067, 6105, -1, + 6172, 6068, 6067, -1, 6172, 6173, 6068, -1, + 6173, 6172, 6171, -1, 6171, 6174, 6173, -1, + 6174, 6171, 6170, -1, 6170, 6175, 6174, -1, + 6175, 6170, 6169, -1, 6169, 6176, 6175, -1, + 6176, 6169, 6168, -1, 6168, 6177, 6176, -1, + 6177, 6168, 6167, -1, 6177, 6167, 6178, -1, + 6179, 6180, 6181, -1, 6181, 6182, 6179, -1, + 6182, 6181, 6183, -1, 6183, 6184, 6182, -1, + 6184, 6183, 6185, -1, 6185, 6186, 6184, -1, + 6186, 6185, 6187, -1, 6187, 6188, 6186, -1, + 6188, 6187, 6189, -1, 6189, 6190, 6188, -1, + 6190, 6189, 6191, -1, 6191, 6192, 6190, -1, + 6192, 6191, 6193, -1, 6193, 6194, 6192, -1, + 6194, 6193, 6195, -1, 6195, 6196, 6194, -1, + 6196, 6195, 6197, -1, 6197, 6198, 6196, -1, + 6198, 6197, 6199, -1, 6199, 6200, 6198, -1, + 6200, 6199, 6201, -1, 6201, 6202, 6200, -1, + 6202, 6201, 6203, -1, 6203, 6204, 6202, -1, + 6204, 6203, 6178, -1, 6204, 6178, 6167, -1, + 6204, 6167, 6166, -1, 6166, 6202, 6204, -1, + 6202, 6166, 6165, -1, 6165, 6200, 6202, -1, + 6200, 6165, 6164, -1, 6164, 6198, 6200, -1, + 6198, 6164, 6163, -1, 6163, 6196, 6198, -1, + 6196, 6163, 6162, -1, 6162, 6194, 6196, -1, + 6194, 6162, 6161, -1, 6161, 6192, 6194, -1, + 6192, 6161, 6160, -1, 6160, 6190, 6192, -1, + 6190, 6160, 6159, -1, 6159, 6188, 6190, -1, + 6188, 6159, 6158, -1, 6158, 6186, 6188, -1, + 6186, 6158, 6157, -1, 6157, 6184, 6186, -1, + 6184, 6157, 6156, -1, 6156, 6182, 6184, -1, + 6182, 6156, 6155, -1, 6155, 6179, 6182, -1, + 6179, 6155, 6154, -1, 6154, 6180, 6179, -1, + 6180, 6154, 6153, -1, 6153, 6205, 6180, -1, + 6205, 6153, 6152, -1, 6152, 6206, 6205, -1, + 6206, 6152, 6151, -1, 6151, 6207, 6206, -1, + 6207, 6151, 6150, -1, 6150, 6208, 6207, -1, + 6208, 6150, 6149, -1, 6149, 6209, 6208, -1, + 6209, 6149, 6148, -1, 6148, 6210, 6209, -1, + 6210, 6148, 6147, -1, 6147, 6211, 6210, -1, + 6211, 6147, 6146, -1, 6146, 6212, 6211, -1, + 6212, 6146, 6145, -1, 6145, 6213, 6212, -1, + 6213, 6145, 6144, -1, 6144, 6214, 6213, -1, + 6214, 6144, 6143, -1, 6143, 6215, 6214, -1, + 6215, 6143, 6142, -1, 6142, 6216, 6215, -1, + 6216, 6142, 6141, -1, 6141, 6217, 6216, -1, + 6217, 6141, 6140, -1, 6140, 6218, 6217, -1, + 6218, 6140, 4786, -1, 4786, 6219, 6218, -1, + 4786, 4788, 6219, -1, 6220, 6221, 6222, -1, + 6220, 6222, 6219, -1, 6220, 6219, 4788, -1, + 6220, 4788, 4790, -1, 4790, 6221, 6220, -1, + 6221, 4790, 4792, -1, 4792, 6223, 6221, -1, + 6223, 4792, 4794, -1, 4794, 6224, 6223, -1, + 4794, 4795, 6224, -1, 6225, 6224, 4795, -1, + 6225, 4795, 4801, -1, 4801, 6226, 6225, -1, + 6226, 4801, 4799, -1, 4799, 6227, 6226, -1, + 6227, 4799, 4796, -1, 4796, 6228, 6227, -1, + 4796, 4798, 6228, -1, 6229, 6228, 4798, -1, + 6229, 4798, 4578, -1, 4578, 4576, 6229, -1, + 6230, 6231, 6229, -1, 6230, 6229, 4576, -1, + 4576, 4577, 6230, -1, 6232, 6233, 6234, -1, + 6234, 6235, 6232, -1, 6235, 6234, 6236, -1, + 6236, 6234, 6230, -1, 6236, 6230, 4577, -1, + 4577, 6237, 6236, -1, 6237, 4577, 6238, -1, + 6239, 6240, 6241, -1, 6240, 6238, 6241, -1, + 6240, 6237, 6238, -1, 6240, 6239, 6237, -1, + 6242, 6237, 6239, -1, 6243, 6242, 6239, -1, + 6239, 6241, 6243, -1, 6244, 6243, 6241, -1, + 6244, 6242, 6243, -1, 6244, 6245, 6242, -1, + 6244, 6241, 6245, -1, 6246, 6245, 6241, -1, + 6247, 6248, 6249, -1, 6250, 6249, 6248, -1, + 6251, 6252, 6246, -1, 6253, 6254, 6255, -1, + 6253, 6251, 6254, -1, 6253, 6252, 6251, -1, + 6253, 6255, 6252, -1, 6255, 6250, 6252, -1, + 6256, 6252, 6250, -1, 6256, 6246, 6252, -1, + 6256, 6257, 6246, -1, 6256, 6250, 6257, -1, + 6257, 6250, 6248, -1, 6248, 6246, 6257, -1, + 6248, 6247, 6246, -1, 6247, 6245, 6246, -1, + 6247, 6249, 6245, -1, 6249, 6242, 6245, -1, + 6258, 6242, 6249, -1, 6249, 6250, 6258, -1, + 6259, 6258, 6250, -1, 6250, 6255, 6259, -1, + 6260, 6261, 6259, -1, 6260, 6259, 6255, -1, + 6255, 6262, 6260, -1, 6262, 6255, 6254, -1, + 6254, 6263, 6262, -1, 6263, 6254, 6251, -1, + 6263, 6251, 6264, -1, 6264, 6262, 6263, -1, + 6264, 6265, 6262, -1, 6264, 6251, 6265, -1, + 6251, 6266, 6265, -1, 6267, 6268, 6269, -1, + 6268, 6267, 6266, -1, 6267, 6265, 6266, -1, + 6267, 6269, 6265, -1, 6269, 6262, 6265, -1, + 6262, 6269, 6270, -1, 6270, 6260, 6262, -1, + 6270, 6271, 6260, -1, 6272, 6273, 6274, -1, + 6272, 6274, 6275, -1, 6275, 6276, 6272, -1, + 6275, 6277, 6276, -1, 6275, 6278, 6277, -1, + 6278, 6275, 6274, -1, 6274, 6279, 6278, -1, + 6274, 6280, 6279, -1, 6281, 6282, 6283, -1, + 6283, 6284, 6281, -1, 6284, 6283, 6279, -1, + 6284, 6279, 6280, -1, 6284, 6280, 6285, -1, + 6285, 6281, 6284, -1, 6285, 6270, 6281, -1, + 6285, 6271, 6270, -1, 6271, 6285, 6280, -1, + 6280, 6286, 6271, -1, 6286, 6280, 6274, -1, + 6286, 6274, 6273, -1, 6286, 6273, 6287, -1, + 6287, 6271, 6286, -1, 6287, 6260, 6271, -1, + 6287, 6261, 6260, -1, 6261, 6287, 6273, -1, + 6273, 6288, 6261, -1, 6288, 6273, 6272, -1, + 6272, 6289, 6288, -1, 6289, 6272, 6276, -1, + 6276, 6290, 6289, -1, 6290, 6291, 6292, -1, + 6290, 6276, 6291, -1, 6291, 6276, 6277, -1, + 6291, 6277, 6293, -1, 6293, 6294, 6291, -1, + 6294, 6293, 6295, -1, 6295, 6296, 6294, -1, + 6296, 6295, 6297, -1, 6297, 6298, 6296, -1, + 6298, 6297, 6299, -1, 6299, 6300, 6298, -1, + 6300, 6299, 6301, -1, 6301, 6302, 6300, -1, + 6302, 6301, 6303, -1, 6303, 6304, 6302, -1, + 6304, 6303, 6305, -1, 6305, 6306, 6304, -1, + 6306, 6305, 6307, -1, 6307, 6308, 6306, -1, + 6308, 6307, 6309, -1, 6309, 6310, 6308, -1, + 6310, 6309, 6311, -1, 6311, 6312, 6310, -1, + 6312, 6311, 6313, -1, 6313, 6314, 6312, -1, + 6314, 6313, 6315, -1, 6315, 6316, 6314, -1, + 6316, 6315, 6317, -1, 6317, 6318, 6316, -1, + 6318, 6317, 6319, -1, 6319, 6320, 6318, -1, + 6320, 6319, 6321, -1, 6321, 6322, 6320, -1, + 6322, 6321, 6323, -1, 6323, 6324, 6322, -1, + 6324, 6323, 6325, -1, 6325, 6326, 6324, -1, + 6326, 6325, 6327, -1, 6327, 6328, 6326, -1, + 6328, 6327, 6329, -1, 6329, 6330, 6328, -1, + 6330, 6329, 6331, -1, 6331, 6332, 6330, -1, + 6332, 6331, 6333, -1, 6333, 6334, 6332, -1, + 6334, 6333, 6335, -1, 6335, 6336, 6334, -1, + 6336, 6335, 6337, -1, 6337, 6338, 6336, -1, + 6338, 6337, 6339, -1, 6339, 6340, 6338, -1, + 6340, 6339, 4573, -1, 4573, 6341, 6340, -1, + 6341, 4573, 4527, -1, 4527, 4526, 6341, -1, + 6342, 6341, 4526, -1, 4526, 6343, 6342, -1, + 6343, 4526, 4529, -1, 4529, 6344, 6343, -1, + 6344, 4529, 4531, -1, 4531, 6345, 6344, -1, + 6345, 4531, 4533, -1, 4533, 4521, 6345, -1, + 4521, 4533, 4534, -1, 4534, 4520, 4521, -1, + 4520, 4534, 4535, -1, 4535, 4517, 4520, -1, + 4517, 4535, 4536, -1, 4536, 4518, 4517, -1, + 4518, 4536, 4565, -1, 4565, 6346, 4518, -1, + 6346, 4565, 4563, -1, 4563, 6347, 6346, -1, + 6347, 4563, 4561, -1, 4561, 6348, 6347, -1, + 6348, 4561, 4559, -1, 4559, 6349, 6348, -1, + 6349, 4559, 4557, -1, 4557, 6350, 6349, -1, + 6350, 4557, 4555, -1, 4555, 6351, 6350, -1, + 6351, 4555, 4553, -1, 4553, 6352, 6351, -1, + 6352, 4553, 4551, -1, 4551, 6353, 6352, -1, + 6353, 4551, 4549, -1, 4549, 6354, 6353, -1, + 6354, 4549, 4547, -1, 4547, 6355, 6354, -1, + 6355, 4547, 4545, -1, 4545, 6356, 6355, -1, + 6356, 4545, 4543, -1, 4543, 6357, 6356, -1, + 6357, 4543, 4541, -1, 4541, 6358, 6357, -1, + 6358, 4541, 4539, -1, 4539, 6359, 6358, -1, + 6359, 4539, 4538, -1, 4538, 6360, 6359, -1, + 6360, 4538, 6361, -1, 6361, 830, 6360, -1, + 830, 6361, 6362, -1, 6363, 6362, 6361, -1, + 6363, 6364, 6362, -1, 6365, 6364, 6363, -1, + 6363, 6361, 6365, -1, 6365, 6361, 6366, -1, + 6366, 6364, 6365, -1, 6366, 6367, 6364, -1, + 6367, 6366, 6368, -1, 6368, 6366, 6361, -1, + 6368, 6361, 4538, -1, 4538, 4537, 6368, -1, + 2261, 6368, 4537, -1, 4537, 4515, 2261, -1, + 4515, 4537, 4540, -1, 4540, 4514, 4515, -1, + 4514, 4540, 4542, -1, 4542, 4513, 4514, -1, + 4513, 4542, 4544, -1, 4544, 4512, 4513, -1, + 4512, 4544, 4546, -1, 4546, 4511, 4512, -1, + 4511, 4546, 4548, -1, 4548, 4510, 4511, -1, + 4510, 4548, 4550, -1, 4550, 4509, 4510, -1, + 4509, 4550, 4552, -1, 4552, 4508, 4509, -1, + 4508, 4552, 4554, -1, 4554, 4507, 4508, -1, + 4507, 4554, 4556, -1, 4556, 4506, 4507, -1, + 4506, 4556, 4558, -1, 4558, 4505, 4506, -1, + 4505, 4558, 4560, -1, 4560, 4504, 4505, -1, + 4504, 4560, 4562, -1, 4562, 4503, 4504, -1, + 4503, 4562, 4564, -1, 4564, 4502, 4503, -1, + 4502, 4564, 4566, -1, 4566, 4501, 4502, -1, + 4501, 4566, 4567, -1, 4567, 4500, 4501, -1, + 4500, 4567, 4568, -1, 4568, 4499, 4500, -1, + 4499, 4568, 4569, -1, 4569, 4498, 4499, -1, + 4498, 4569, 4570, -1, 4570, 4497, 4498, -1, + 4497, 4570, 4571, -1, 4571, 4496, 4497, -1, + 4496, 4571, 4572, -1, 4572, 4495, 4496, -1, + 4495, 4572, 4573, -1, 4573, 4494, 4495, -1, + 4494, 4573, 6339, -1, 6339, 4493, 4494, -1, + 4493, 6339, 6337, -1, 6337, 4492, 4493, -1, + 4492, 6337, 6335, -1, 6335, 4491, 4492, -1, + 4491, 6335, 6333, -1, 6333, 2438, 4491, -1, + 2438, 6333, 6331, -1, 6331, 2436, 2438, -1, + 2436, 6331, 6329, -1, 6329, 2434, 2436, -1, + 2434, 6329, 6327, -1, 6327, 2432, 2434, -1, + 2432, 6327, 6325, -1, 6325, 2430, 2432, -1, + 2430, 6325, 6323, -1, 6323, 2428, 2430, -1, + 2428, 6323, 6321, -1, 6321, 2427, 2428, -1, + 2427, 6321, 6319, -1, 6319, 2301, 2427, -1, + 2301, 6319, 6317, -1, 6317, 2302, 2301, -1, + 2302, 6317, 6315, -1, 6315, 2304, 2302, -1, + 2304, 6315, 6313, -1, 6313, 2306, 2304, -1, + 2306, 6313, 6311, -1, 6311, 2426, 2306, -1, + 2426, 6311, 6309, -1, 6309, 2425, 2426, -1, + 2425, 6309, 6307, -1, 6307, 2424, 2425, -1, + 2424, 6307, 6305, -1, 6305, 2423, 2424, -1, + 2423, 6305, 6303, -1, 6303, 2422, 2423, -1, + 2422, 6303, 6301, -1, 6301, 2421, 2422, -1, + 2421, 6301, 6299, -1, 6299, 2420, 2421, -1, + 2420, 6299, 6297, -1, 6297, 2419, 2420, -1, + 2419, 6297, 6295, -1, 6295, 2343, 2419, -1, + 2343, 6295, 6293, -1, 6293, 2344, 2343, -1, + 2344, 6293, 6277, -1, 6277, 2346, 2344, -1, + 2346, 6277, 6278, -1, 6278, 2348, 2346, -1, + 2348, 6278, 6279, -1, 6279, 2350, 2348, -1, + 6279, 6283, 2350, -1, 6369, 2350, 6283, -1, + 6369, 2352, 2350, -1, 2352, 6369, 6370, -1, + 6370, 2389, 2352, -1, 2389, 6370, 6371, -1, + 6371, 2385, 2389, -1, 6371, 2381, 2385, -1, + 6371, 2382, 2381, -1, 2382, 6371, 6370, -1, + 6370, 6372, 2382, -1, 6372, 6370, 6369, -1, + 6369, 6283, 6372, -1, 6372, 6283, 6282, -1, + 6282, 2382, 6372, -1, 6282, 2383, 2382, -1, + 6282, 6281, 2383, -1, 2383, 6281, 6270, -1, + 2383, 6270, 6269, -1, 6269, 2379, 2383, -1, + 2379, 6269, 6268, -1, 6268, 6373, 2379, -1, + 6373, 6268, 6266, -1, 6373, 6266, 6374, -1, + 6374, 2379, 6373, -1, 6374, 2380, 2379, -1, + 6374, 6266, 2380, -1, 2380, 6266, 6375, -1, + 6375, 2378, 2380, -1, 6375, 2387, 2378, -1, + 6375, 2376, 2387, -1, 2376, 6375, 6266, -1, + 6241, 6238, 2257, -1, 6376, 2257, 6238, -1, + 6376, 6238, 4577, -1, 6376, 4577, 4575, -1, + 4575, 2257, 6376, -1, 4575, 4574, 2257, -1, + 4574, 2258, 2257, -1, 2258, 4574, 4576, -1, + 2258, 4576, 4579, -1, 4579, 2255, 2258, -1, + 4579, 6377, 2255, -1, 6377, 4579, 4578, -1, + 6377, 4578, 4830, -1, 4830, 2255, 6377, -1, + 4830, 4829, 2255, -1, 4829, 2256, 2255, -1, + 2256, 4829, 4831, -1, 2256, 4831, 4833, -1, + 4833, 2252, 2256, -1, 4833, 6378, 2252, -1, + 6378, 4833, 4832, -1, 6378, 4832, 4835, -1, + 4835, 2252, 6378, -1, 4835, 4834, 2252, -1, + 4834, 2253, 2252, -1, 2253, 4834, 4836, -1, + 2253, 4836, 4838, -1, 4838, 2254, 2253, -1, + 4838, 6379, 2254, -1, 6379, 4838, 4837, -1, + 6379, 4837, 5654, -1, 5654, 2254, 6379, -1, + 5654, 5655, 2254, -1, 5655, 5656, 2254, -1, + 2254, 5656, 5657, -1, 6380, 5657, 5659, -1, + 5659, 6381, 6380, -1, 6381, 5659, 5660, -1, + 6381, 5660, 5664, -1, 5664, 6380, 6381, -1, + 5664, 5662, 6380, -1, 5662, 5661, 6380, -1, + 5661, 6382, 6380, -1, 5661, 5663, 6382, -1, + 2154, 6382, 5663, -1, 2154, 5663, 5665, -1, + 5665, 2251, 2154, -1, 2251, 5665, 5666, -1, + 5666, 2249, 2251, -1, 2249, 5666, 5667, -1, + 5667, 2247, 2249, -1, 2247, 5667, 5668, -1, + 5668, 2245, 2247, -1, 2245, 5668, 5669, -1, + 5669, 2243, 2245, -1, 2243, 5669, 5670, -1, + 5670, 2241, 2243, -1, 2241, 5670, 5671, -1, + 5671, 2239, 2241, -1, 2239, 5671, 5672, -1, + 5672, 2237, 2239, -1, 2237, 5672, 5673, -1, + 5673, 2235, 2237, -1, 2235, 5673, 5674, -1, + 5674, 2233, 2235, -1, 2233, 5674, 5675, -1, + 5675, 2231, 2233, -1, 2231, 5675, 5676, -1, + 5676, 2229, 2231, -1, 2229, 5676, 5677, -1, + 5677, 2228, 2229, -1, 2228, 5677, 5679, -1, + 5679, 2227, 2228, -1, 2227, 5679, 5680, -1, + 5680, 2226, 2227, -1, 2226, 5680, 5682, -1, + 5682, 2225, 2226, -1, 2225, 5682, 5684, -1, + 5684, 2224, 2225, -1, 2224, 5684, 5686, -1, + 5686, 2223, 2224, -1, 2223, 5686, 5688, -1, + 5688, 2222, 2223, -1, 2222, 5688, 5690, -1, + 5690, 2221, 2222, -1, 2221, 5690, 5692, -1, + 5692, 2220, 2221, -1, 2220, 5692, 5694, -1, + 5694, 2219, 2220, -1, 2219, 5694, 5696, -1, + 5696, 2218, 2219, -1, 2218, 5696, 5698, -1, + 5698, 2217, 2218, -1, 2217, 5698, 5700, -1, + 5700, 2216, 2217, -1, 2216, 5700, 5702, -1, + 5702, 2215, 2216, -1, 2215, 5702, 5704, -1, + 5704, 2214, 2215, -1, 2214, 5704, 5706, -1, + 5706, 2213, 2214, -1, 2213, 5706, 5708, -1, + 5708, 2212, 2213, -1, 2212, 5708, 5710, -1, + 5710, 2211, 2212, -1, 2211, 5710, 5712, -1, + 5712, 2210, 2211, -1, 2210, 5712, 5714, -1, + 5714, 2209, 2210, -1, 2209, 5714, 5716, -1, + 5716, 2208, 2209, -1, 2208, 5716, 5718, -1, + 5718, 2207, 2208, -1, 2207, 5718, 5720, -1, + 5720, 2206, 2207, -1, 2206, 5720, 5722, -1, + 5722, 2158, 2206, -1, 2158, 5722, 5724, -1, + 5724, 2155, 2158, -1, 2155, 5724, 5748, -1, + 2155, 5748, 5749, -1, 5749, 2156, 2155, -1, + 2156, 5749, 5794, -1, 5794, 6383, 2156, -1, + 6383, 5794, 5792, -1, 5792, 6384, 6383, -1, + 6384, 5792, 5790, -1, 5790, 6385, 6384, -1, + 6385, 5790, 5788, -1, 5788, 6386, 6385, -1, + 6386, 5788, 5786, -1, 5786, 6387, 6386, -1, + 6387, 5786, 5784, -1, 5784, 6388, 6387, -1, + 6388, 5784, 5782, -1, 5782, 6389, 6388, -1, + 6389, 5782, 5780, -1, 5780, 6390, 6389, -1, + 6390, 5780, 5778, -1, 5778, 6391, 6390, -1, + 6391, 5778, 5776, -1, 5776, 6392, 6391, -1, + 6392, 5776, 5774, -1, 5774, 6393, 6392, -1, + 6393, 5774, 5772, -1, 5772, 6394, 6393, -1, + 6394, 5772, 5770, -1, 5770, 6395, 6394, -1, + 6395, 5770, 5768, -1, 5768, 6396, 6395, -1, + 6396, 5768, 5766, -1, 5766, 6397, 6396, -1, + 6397, 5766, 5764, -1, 5764, 6398, 6397, -1, + 6398, 5764, 5762, -1, 5762, 6399, 6398, -1, + 6399, 5762, 5760, -1, 5760, 6400, 6399, -1, + 6400, 5760, 5758, -1, 5758, 6401, 6400, -1, + 6401, 5758, 5756, -1, 5756, 6402, 6401, -1, + 6402, 5756, 5754, -1, 5754, 6403, 6402, -1, + 6403, 5754, 5752, -1, 5752, 6404, 6403, -1, + 6404, 5752, 5750, -1, 5750, 6405, 6404, -1, + 6405, 5750, 4784, -1, 4784, 4783, 6405, -1, + 6406, 6405, 4783, -1, 6405, 6406, 6407, -1, + 6407, 6404, 6405, -1, 6404, 6407, 6408, -1, + 6408, 6403, 6404, -1, 6403, 6408, 6409, -1, + 6409, 6402, 6403, -1, 6402, 6409, 6410, -1, + 6410, 6401, 6402, -1, 6401, 6410, 6411, -1, + 6411, 6400, 6401, -1, 6400, 6411, 6412, -1, + 6412, 6399, 6400, -1, 6399, 6412, 6413, -1, + 6413, 6398, 6399, -1, 6398, 6413, 6414, -1, + 6414, 6397, 6398, -1, 6397, 6414, 6415, -1, + 6415, 6396, 6397, -1, 6396, 6415, 6416, -1, + 6416, 6395, 6396, -1, 6395, 6416, 6417, -1, + 6417, 6394, 6395, -1, 6394, 6417, 6418, -1, + 6418, 6393, 6394, -1, 6393, 6418, 6419, -1, + 6419, 6392, 6393, -1, 6392, 6419, 6420, -1, + 6420, 6391, 6392, -1, 6391, 6420, 6421, -1, + 6421, 6390, 6391, -1, 6390, 6421, 6422, -1, + 6422, 6389, 6390, -1, 6389, 6422, 6423, -1, + 6423, 6388, 6389, -1, 6388, 6423, 6424, -1, + 6424, 6387, 6388, -1, 6387, 6424, 6425, -1, + 6425, 6386, 6387, -1, 6386, 6425, 6426, -1, + 6426, 6385, 6386, -1, 6385, 6426, 6427, -1, + 6427, 6384, 6385, -1, 6384, 6427, 6428, -1, + 6428, 6383, 6384, -1, 6383, 6428, 6429, -1, + 6429, 2156, 6383, -1, 6429, 2157, 2156, -1, + 6429, 6430, 2157, -1, 6430, 6429, 6428, -1, + 6428, 6431, 6430, -1, 6431, 6428, 6427, -1, + 6427, 6432, 6431, -1, 6432, 6427, 6426, -1, + 6426, 6433, 6432, -1, 6433, 6426, 6425, -1, + 6425, 6434, 6433, -1, 6434, 6425, 6424, -1, + 6424, 6435, 6434, -1, 6435, 6424, 6423, -1, + 6423, 6436, 6435, -1, 6436, 6423, 6422, -1, + 6422, 6437, 6436, -1, 6437, 6422, 6421, -1, + 6421, 6438, 6437, -1, 6438, 6421, 6420, -1, + 6420, 6439, 6438, -1, 6439, 6420, 6419, -1, + 6419, 6440, 6439, -1, 6440, 6419, 6418, -1, + 6418, 6441, 6440, -1, 6441, 6418, 6417, -1, + 6417, 6442, 6441, -1, 6442, 6417, 6416, -1, + 6416, 6443, 6442, -1, 6443, 6416, 6415, -1, + 6415, 6444, 6443, -1, 6444, 6415, 6414, -1, + 6414, 6445, 6444, -1, 6445, 6414, 6413, -1, + 6413, 6446, 6445, -1, 6446, 6413, 6412, -1, + 6412, 6447, 6446, -1, 6447, 6412, 6411, -1, + 6411, 6448, 6447, -1, 6448, 6411, 6410, -1, + 6410, 6449, 6448, -1, 6449, 6410, 6409, -1, + 6409, 6450, 6449, -1, 6450, 6409, 6408, -1, + 6408, 6451, 6450, -1, 6451, 6408, 6407, -1, + 6407, 6452, 6451, -1, 6452, 6407, 6406, -1, + 6406, 6453, 6452, -1, 6453, 6406, 4783, -1, + 4783, 6454, 6453, -1, 6454, 4783, 4781, -1, + 4781, 6455, 6454, -1, 6455, 4781, 4779, -1, + 4779, 6456, 6455, -1, 6456, 4779, 4777, -1, + 4777, 6457, 6456, -1, 6457, 4777, 4775, -1, + 4775, 6458, 6457, -1, 6458, 4775, 4773, -1, + 4773, 6459, 6458, -1, 6459, 4773, 4771, -1, + 4771, 6460, 6459, -1, 6460, 4771, 4769, -1, + 4769, 6461, 6460, -1, 6461, 4769, 4767, -1, + 4767, 6462, 6461, -1, 6462, 4767, 4765, -1, + 4765, 6463, 6462, -1, 6463, 4765, 4763, -1, + 4763, 6464, 6463, -1, 6464, 4763, 4761, -1, + 4761, 6465, 6464, -1, 6465, 4761, 4754, -1, + 6465, 4754, 4753, -1, 6466, 6465, 4753, -1, + 6466, 6467, 6465, -1, 2151, 6465, 6467, -1, + 2151, 6464, 6465, -1, 6464, 2151, 2150, -1, + 2150, 6463, 6464, -1, 6463, 2150, 2149, -1, + 2149, 6462, 6463, -1, 6462, 2149, 2148, -1, + 2148, 6461, 6462, -1, 6461, 2148, 2147, -1, + 2147, 6460, 6461, -1, 6460, 2147, 1348, -1, + 1348, 6459, 6460, -1, 6459, 1348, 1349, -1, + 1349, 6458, 6459, -1, 6458, 1349, 1350, -1, + 1350, 6457, 6458, -1, 6457, 1350, 1351, -1, + 1351, 6456, 6457, -1, 6456, 1351, 1352, -1, + 1352, 6455, 6456, -1, 6455, 1352, 1353, -1, + 1353, 6454, 6455, -1, 6454, 1353, 1229, -1, + 1229, 6453, 6454, -1, 6453, 1229, 1227, -1, + 1227, 6452, 6453, -1, 6452, 1227, 1225, -1, + 1225, 6451, 6452, -1, 6451, 1225, 1223, -1, + 1223, 6450, 6451, -1, 6450, 1223, 1221, -1, + 1221, 6449, 6450, -1, 6449, 1221, 1219, -1, + 1219, 6448, 6449, -1, 6448, 1219, 1217, -1, + 1217, 6447, 6448, -1, 6447, 1217, 1215, -1, + 1215, 6446, 6447, -1, 6446, 1215, 1213, -1, + 1213, 6445, 6446, -1, 6445, 1213, 1211, -1, + 1211, 6444, 6445, -1, 6444, 1211, 1209, -1, + 1209, 6443, 6444, -1, 6443, 1209, 1207, -1, + 1207, 6442, 6443, -1, 6442, 1207, 1205, -1, + 1205, 6441, 6442, -1, 6441, 1205, 1203, -1, + 1203, 6440, 6441, -1, 6440, 1203, 1201, -1, + 1201, 6439, 6440, -1, 6439, 1201, 1199, -1, + 1199, 6438, 6439, -1, 6438, 1199, 1197, -1, + 1197, 6437, 6438, -1, 6437, 1197, 1195, -1, + 1195, 6436, 6437, -1, 6436, 1195, 1193, -1, + 1193, 6435, 6436, -1, 6435, 1193, 1191, -1, + 1191, 6434, 6435, -1, 6434, 1191, 1189, -1, + 1189, 6433, 6434, -1, 6433, 1189, 1187, -1, + 1187, 6432, 6433, -1, 6432, 1187, 1185, -1, + 1185, 6431, 6432, -1, 6431, 1185, 1183, -1, + 1183, 6430, 6431, -1, 6430, 1183, 1182, -1, + 1182, 2157, 6430, -1, 1182, 2204, 2157, -1, + 2204, 1182, 1180, -1, 1180, 2202, 2204, -1, + 2202, 1180, 1178, -1, 1178, 2200, 2202, -1, + 2200, 1178, 1176, -1, 1176, 2198, 2200, -1, + 2198, 1176, 1174, -1, 1174, 2196, 2198, -1, + 2196, 1174, 1172, -1, 1172, 2194, 2196, -1, + 2194, 1172, 1170, -1, 1170, 2192, 2194, -1, + 2192, 1170, 1168, -1, 1168, 2190, 2192, -1, + 2190, 1168, 1166, -1, 1166, 2188, 2190, -1, + 2188, 1166, 1164, -1, 1164, 2186, 2188, -1, + 2186, 1164, 1162, -1, 1162, 2184, 2186, -1, + 2184, 1162, 1160, -1, 1160, 2182, 2184, -1, + 2182, 1160, 1158, -1, 1158, 2180, 2182, -1, + 2180, 1158, 1156, -1, 1156, 2178, 2180, -1, + 2178, 1156, 1154, -1, 1154, 2176, 2178, -1, + 2176, 1154, 1152, -1, 1152, 2174, 2176, -1, + 2174, 1152, 1150, -1, 1150, 2172, 2174, -1, + 2172, 1150, 1148, -1, 1148, 2170, 2172, -1, + 2170, 1148, 1146, -1, 1146, 2168, 2170, -1, + 2168, 1146, 1144, -1, 1144, 2166, 2168, -1, + 2166, 1144, 1142, -1, 1142, 2164, 2166, -1, + 2164, 1142, 1140, -1, 1140, 2162, 2164, -1, + 2162, 1140, 1138, -1, 1138, 2159, 2162, -1, + 2159, 1138, 1136, -1, 1136, 2160, 2159, -1, + 2160, 1136, 1135, -1, 1135, 2230, 2160, -1, + 2230, 1135, 1354, -1, 1354, 2232, 2230, -1, + 2232, 1354, 1356, -1, 1356, 2234, 2232, -1, + 2234, 1356, 1358, -1, 1358, 2236, 2234, -1, + 2236, 1358, 1360, -1, 1360, 2238, 2236, -1, + 2238, 1360, 1362, -1, 1362, 2240, 2238, -1, + 2240, 1362, 1133, -1, 1133, 2242, 2240, -1, + 2242, 1133, 1132, -1, 1132, 2244, 2242, -1, + 2244, 1132, 1130, -1, 1130, 2246, 2244, -1, + 2246, 1130, 1128, -1, 1128, 2248, 2246, -1, + 2248, 1128, 1126, -1, 1126, 2250, 2248, -1, + 2250, 1126, 1125, -1, 1125, 2152, 2250, -1, + 1125, 6468, 2152, -1, 6469, 6470, 6471, -1, + 6469, 6468, 6470, -1, 6469, 2152, 6468, -1, + 6469, 6471, 2152, -1, 6471, 2153, 2152, -1, + 2153, 6471, 6470, -1, 2153, 6470, 6472, -1, + 6472, 2154, 2153, -1, 6472, 6382, 2154, -1, + 6382, 6472, 6470, -1, 6470, 6380, 6382, -1, + 6473, 6470, 6468, -1, 6468, 6474, 6473, -1, + 6474, 6468, 1125, -1, 6474, 1125, 1123, -1, + 1123, 6473, 6474, -1, 1123, 1122, 6473, -1, + 6475, 6473, 1122, -1, 6475, 1122, 1124, -1, + 6475, 1124, 1368, -1, 1368, 6473, 6475, -1, + 6473, 1368, 1372, -1, 6476, 929, 6477, -1, + 6478, 6479, 6480, -1, 6480, 6481, 6478, -1, + 6482, 6483, 6484, -1, 6484, 6485, 6482, -1, + 6485, 6484, 6486, -1, 6486, 6487, 6485, -1, + 6487, 6486, 6488, -1, 6488, 6489, 6487, -1, + 6489, 6488, 6490, -1, 6490, 6491, 6489, -1, + 6491, 6490, 6492, -1, 6492, 6493, 6491, -1, + 6493, 6492, 6494, -1, 6494, 6495, 6493, -1, + 6495, 6494, 6496, -1, 6496, 6497, 6495, -1, + 6497, 6496, 6498, -1, 6498, 6499, 6497, -1, + 6499, 6498, 6500, -1, 6500, 6501, 6499, -1, + 6501, 6500, 6502, -1, 6502, 6503, 6501, -1, + 6503, 6502, 6504, -1, 6504, 6505, 6503, -1, + 6505, 6504, 6506, -1, 6506, 6507, 6505, -1, + 6507, 6506, 6508, -1, 6508, 6509, 6507, -1, + 6509, 6508, 6510, -1, 6510, 6511, 6509, -1, + 6510, 6512, 6511, -1, 6512, 6510, 6513, -1, + 6513, 6514, 6512, -1, 6514, 6513, 6515, -1, + 6515, 6516, 6514, -1, 6516, 6515, 6517, -1, + 6517, 6518, 6516, -1, 6518, 6517, 6519, -1, + 6519, 6520, 6518, -1, 6520, 6519, 6521, -1, + 6521, 6522, 6520, -1, 6522, 6521, 6523, -1, + 6523, 6524, 6522, -1, 6524, 6523, 6525, -1, + 6525, 6526, 6524, -1, 6526, 6525, 6527, -1, + 6527, 6528, 6526, -1, 6528, 6527, 6529, -1, + 6529, 6530, 6528, -1, 6530, 6529, 6531, -1, + 6531, 6532, 6530, -1, 6532, 6531, 6533, -1, + 6533, 6534, 6532, -1, 6534, 6533, 6535, -1, + 6535, 6536, 6534, -1, 6536, 6535, 6537, -1, + 6537, 6538, 6536, -1, 6537, 6539, 6538, -1, + 6540, 6541, 6542, -1, 6541, 6540, 6539, -1, + 6541, 6539, 6537, -1, 6541, 6537, 6543, -1, + 6544, 6543, 6537, -1, 6544, 6537, 6535, -1, + 6535, 6545, 6544, -1, 6545, 6535, 6533, -1, + 6533, 6546, 6545, -1, 6546, 6533, 6531, -1, + 6531, 6547, 6546, -1, 6547, 6531, 6529, -1, + 6529, 6548, 6547, -1, 6548, 6529, 6527, -1, + 6527, 6549, 6548, -1, 6549, 6527, 6525, -1, + 6525, 6550, 6549, -1, 6550, 6525, 6523, -1, + 6523, 6551, 6550, -1, 6551, 6523, 6521, -1, + 6521, 6552, 6551, -1, 6552, 6521, 6519, -1, + 6519, 6553, 6552, -1, 6553, 6519, 6517, -1, + 6517, 6554, 6553, -1, 6554, 6517, 6515, -1, + 6515, 6555, 6554, -1, 6555, 6515, 6513, -1, + 6513, 6556, 6555, -1, 6556, 6513, 6510, -1, + 6556, 6510, 6508, -1, 6508, 6557, 6556, -1, + 6557, 6508, 6506, -1, 6506, 6558, 6557, -1, + 6558, 6506, 6504, -1, 6504, 6559, 6558, -1, + 6559, 6504, 6502, -1, 6502, 6560, 6559, -1, + 6560, 6502, 6500, -1, 6500, 6561, 6560, -1, + 6561, 6500, 6498, -1, 6498, 6562, 6561, -1, + 6562, 6498, 6496, -1, 6496, 6563, 6562, -1, + 6563, 6496, 6494, -1, 6494, 6564, 6563, -1, + 6564, 6494, 6492, -1, 6492, 6565, 6564, -1, + 6565, 6492, 6490, -1, 6490, 6566, 6565, -1, + 6566, 6490, 6488, -1, 6488, 6567, 6566, -1, + 6567, 6488, 6486, -1, 6486, 6568, 6567, -1, + 6568, 6486, 6484, -1, 6484, 6481, 6568, -1, + 6481, 6484, 6483, -1, 6483, 6478, 6481, -1, + 6478, 6483, 6569, -1, 6569, 6479, 6478, -1, + 6570, 6571, 6572, -1, 6571, 6570, 6479, -1, + 6571, 6479, 6569, -1, 6571, 6569, 6483, -1, + 6483, 6572, 6571, -1, 6483, 6482, 6572, -1, + 6573, 6574, 6572, -1, 6572, 6575, 6573, -1, + 6575, 6572, 6482, -1, 6482, 6576, 6575, -1, + 6576, 6482, 6485, -1, 6485, 6577, 6576, -1, + 6577, 6485, 6487, -1, 6487, 6578, 6577, -1, + 6578, 6487, 6489, -1, 6489, 6579, 6578, -1, + 6579, 6489, 6491, -1, 6491, 6580, 6579, -1, + 6580, 6491, 6493, -1, 6493, 6581, 6580, -1, + 6581, 6493, 6495, -1, 6495, 6582, 6581, -1, + 6582, 6495, 6497, -1, 6497, 6583, 6582, -1, + 6583, 6497, 6499, -1, 6499, 6584, 6583, -1, + 6584, 6499, 6501, -1, 6501, 6585, 6584, -1, + 6585, 6501, 6503, -1, 6503, 6586, 6585, -1, + 6586, 6503, 6505, -1, 6505, 6587, 6586, -1, + 6587, 6505, 6507, -1, 6507, 6588, 6587, -1, + 6588, 6507, 6509, -1, 6509, 6589, 6588, -1, + 6589, 6509, 6511, -1, 6511, 6590, 6589, -1, + 6511, 6591, 6590, -1, 6591, 6511, 6512, -1, + 6512, 6592, 6591, -1, 6592, 6512, 6514, -1, + 6514, 6593, 6592, -1, 6593, 6514, 6516, -1, + 6516, 6594, 6593, -1, 6594, 6516, 6518, -1, + 6518, 6595, 6594, -1, 6595, 6518, 6520, -1, + 6520, 6596, 6595, -1, 6596, 6520, 6522, -1, + 6522, 6597, 6596, -1, 6597, 6522, 6524, -1, + 6524, 6598, 6597, -1, 6598, 6524, 6526, -1, + 6526, 6599, 6598, -1, 6599, 6526, 6528, -1, + 6528, 6600, 6599, -1, 6600, 6528, 6530, -1, + 6530, 6601, 6600, -1, 6601, 6530, 6532, -1, + 6532, 6602, 6601, -1, 6602, 6532, 6534, -1, + 6534, 6603, 6602, -1, 6603, 6534, 6536, -1, + 6536, 6604, 6603, -1, 6604, 6536, 6538, -1, + 6538, 6605, 6604, -1, 6538, 6606, 6605, -1, + 6606, 6607, 6608, -1, 6606, 6609, 6607, -1, + 6609, 6606, 6538, -1, 6609, 6538, 6539, -1, + 6609, 6539, 6610, -1, 6610, 6611, 6609, -1, + 6611, 6607, 6609, -1, 6607, 6611, 6612, -1, + 6607, 6612, 6613, -1, 6613, 6608, 6607, -1, + 6613, 6614, 6608, -1, 6614, 6613, 6612, -1, + 6615, 6614, 6612, -1, 6615, 6608, 6614, -1, + 6608, 6615, 6616, -1, 6608, 6616, 6617, -1, + 6617, 6606, 6608, -1, 6617, 6605, 6606, -1, + 6617, 6618, 6605, -1, 6618, 6617, 6616, -1, + 6616, 6619, 6618, -1, 6619, 6616, 6620, -1, + 6621, 6622, 6476, -1, 6622, 6621, 6619, -1, + 6622, 6619, 6620, -1, 6620, 6476, 6622, -1, + 6620, 6623, 6476, -1, 6623, 6620, 6616, -1, + 6623, 6616, 6615, -1, 6615, 6612, 6623, -1, + 6612, 6476, 6623, -1, 6624, 6612, 6611, -1, + 6611, 6610, 6624, -1, 6610, 6625, 6624, -1, + 6625, 6610, 6539, -1, 6625, 6539, 6540, -1, + 6540, 6624, 6625, -1, 6540, 6542, 6624, -1, + 6626, 6624, 6542, -1, 6626, 6542, 6541, -1, + 6541, 6543, 6626, -1, 6627, 6626, 6543, -1, + 6627, 6624, 6626, -1, 6627, 6628, 6624, -1, + 6627, 6543, 6628, -1, 6629, 6628, 6543, -1, + 6629, 6543, 6544, -1, 6629, 6544, 1011, -1, + 6629, 1011, 1006, -1, 1006, 6628, 6629, -1, + 6628, 1006, 1008, -1, 1008, 6624, 6628, -1, + 6630, 6631, 6632, -1, 6631, 6630, 6633, -1, + 6634, 6635, 6636, -1, 6636, 6637, 6634, -1, + 6636, 6638, 6637, -1, 6636, 6635, 6638, -1, + 6633, 6638, 6635, -1, 6638, 6633, 6630, -1, + 6630, 6632, 6638, -1, 6632, 6637, 6638, -1, + 6632, 6639, 6637, -1, 6639, 6632, 6640, -1, + 6640, 6641, 6639, -1, 6641, 6640, 6642, -1, + 6642, 6643, 6641, -1, 6643, 6642, 6644, -1, + 6644, 6645, 6643, -1, 6645, 6644, 6646, -1, + 6646, 6647, 6645, -1, 6647, 6646, 6648, -1, + 6648, 6649, 6647, -1, 6649, 6648, 6650, -1, + 6650, 6651, 6649, -1, 6651, 6650, 6652, -1, + 6652, 6653, 6651, -1, 6653, 6652, 6654, -1, + 6654, 6655, 6653, -1, 6655, 6654, 6656, -1, + 6656, 6657, 6655, -1, 6657, 6656, 6658, -1, + 6658, 6659, 6657, -1, 6659, 6658, 6660, -1, + 6660, 6661, 6659, -1, 6660, 6662, 6661, -1, + 6662, 6660, 6663, -1, 6663, 6664, 6662, -1, + 6664, 6663, 6665, -1, 6665, 6666, 6664, -1, + 6666, 6665, 6667, -1, 6667, 6668, 6666, -1, + 6668, 6667, 6669, -1, 6669, 6670, 6668, -1, + 6670, 6669, 6671, -1, 6671, 6672, 6670, -1, + 6672, 6671, 6673, -1, 6673, 6674, 6672, -1, + 6674, 6673, 6675, -1, 6675, 6676, 6674, -1, + 6676, 6675, 6677, -1, 6677, 6678, 6676, -1, + 6678, 6677, 6679, -1, 6679, 6680, 6678, -1, + 6680, 6679, 6681, -1, 6681, 6682, 6680, -1, + 6681, 6683, 6682, -1, 6684, 6685, 6686, -1, + 6684, 6687, 6685, -1, 6684, 6688, 6687, -1, + 6684, 6686, 6688, -1, 6688, 6686, 6683, -1, + 6688, 6683, 6681, -1, 6681, 6689, 6688, -1, + 6689, 6681, 6679, -1, 6679, 6690, 6689, -1, + 6690, 6679, 6677, -1, 6677, 6691, 6690, -1, + 6691, 6677, 6675, -1, 6675, 6692, 6691, -1, + 6692, 6675, 6673, -1, 6673, 6693, 6692, -1, + 6693, 6673, 6671, -1, 6671, 6694, 6693, -1, + 6694, 6671, 6669, -1, 6669, 6695, 6694, -1, + 6695, 6669, 6667, -1, 6667, 6696, 6695, -1, + 6696, 6667, 6665, -1, 6665, 6697, 6696, -1, + 6697, 6665, 6663, -1, 6663, 6698, 6697, -1, + 6698, 6663, 6660, -1, 6698, 6660, 6658, -1, + 6658, 6699, 6698, -1, 6699, 6658, 6656, -1, + 6656, 6700, 6699, -1, 6700, 6656, 6654, -1, + 6654, 6701, 6700, -1, 6701, 6654, 6652, -1, + 6652, 6702, 6701, -1, 6702, 6652, 6650, -1, + 6650, 6703, 6702, -1, 6703, 6650, 6648, -1, + 6648, 6704, 6703, -1, 6704, 6648, 6646, -1, + 6646, 6705, 6704, -1, 6705, 6646, 6644, -1, + 6644, 6706, 6705, -1, 6706, 6644, 6642, -1, + 6642, 6707, 6706, -1, 6707, 6642, 6640, -1, + 6640, 6708, 6707, -1, 6708, 6640, 6632, -1, + 6708, 6632, 6631, -1, 6709, 6708, 6631, -1, + 6709, 6631, 6633, -1, 6709, 6633, 6710, -1, + 6710, 6708, 6709, -1, 6710, 6711, 6708, -1, + 6711, 6710, 6633, -1, 6633, 6712, 6711, -1, + 6713, 6714, 6712, -1, 6715, 6716, 6713, -1, + 6717, 6718, 6719, -1, 6720, 6718, 6717, -1, + 6720, 6721, 6718, -1, 6720, 6722, 6721, -1, + 6722, 6720, 6717, -1, 6722, 6717, 6723, -1, + 6723, 6721, 6722, -1, 6724, 6721, 6723, -1, + 6721, 6724, 6725, -1, 6726, 6727, 6728, -1, + 6729, 6725, 6730, -1, 6725, 6729, 6731, -1, + 6732, 6733, 6734, -1, 6735, 6736, 6737, -1, + 6735, 6737, 6738, -1, 6738, 6739, 6735, -1, + 6739, 6738, 6734, -1, 6734, 6733, 6739, -1, + 6740, 6739, 6733, -1, 6733, 6741, 6740, -1, + 6733, 6732, 6741, -1, 6742, 6743, 6744, -1, + 6743, 6742, 6741, -1, 6743, 6741, 6732, -1, + 6732, 6734, 6743, -1, 6734, 6744, 6743, -1, + 6734, 6745, 6744, -1, 6745, 6734, 6738, -1, + 6738, 6746, 6745, -1, 6746, 6738, 6737, -1, + 6737, 6747, 6746, -1, 6737, 6748, 6747, -1, + 6748, 6737, 6736, -1, 6736, 6749, 6748, -1, + 6726, 6750, 6751, -1, 6750, 6726, 6749, -1, + 6749, 6736, 6750, -1, 6752, 6753, 6750, -1, + 6752, 6750, 6736, -1, 6736, 6735, 6752, -1, + 6752, 6754, 6755, -1, 6754, 6752, 6735, -1, + 6754, 6735, 6739, -1, 6739, 6756, 6754, -1, + 6756, 6739, 6740, -1, 6740, 6741, 6756, -1, + 6741, 6731, 6756, -1, 6757, 6731, 6758, -1, + 6757, 6756, 6731, -1, 6757, 6754, 6756, -1, + 6757, 6758, 6754, -1, 6758, 6755, 6754, -1, + 6755, 6758, 6731, -1, 6755, 6731, 6759, -1, + 6759, 6752, 6755, -1, 6759, 6753, 6752, -1, + 6759, 6731, 6753, -1, 6753, 6731, 6729, -1, + 6729, 6750, 6753, -1, 6729, 6730, 6750, -1, + 6730, 6751, 6750, -1, 6751, 6730, 6725, -1, + 6751, 6725, 6760, -1, 6760, 6726, 6751, -1, + 6760, 6727, 6726, -1, 6727, 6760, 6725, -1, + 6727, 6725, 6724, -1, 6724, 6728, 6727, -1, + 6724, 6723, 6728, -1, 6728, 6723, 6717, -1, + 6728, 6717, 6761, -1, 6761, 6726, 6728, -1, + 6726, 6761, 6762, -1, 6762, 6749, 6726, -1, + 6749, 6762, 6763, -1, 6763, 6748, 6749, -1, + 6748, 6763, 6764, -1, 6764, 6747, 6748, -1, + 6747, 6764, 6765, -1, 6747, 6765, 6766, -1, + 6766, 6746, 6747, -1, 6746, 6766, 6767, -1, + 6767, 6745, 6746, -1, 6745, 6767, 6768, -1, + 6768, 6744, 6745, -1, 6744, 6768, 6769, -1, + 6769, 6770, 6771, -1, 6770, 6772, 6773, -1, + 6770, 6774, 6772, -1, 6774, 6770, 6769, -1, + 6769, 6775, 6774, -1, 6775, 6769, 6768, -1, + 6768, 6776, 6775, -1, 6776, 6768, 6767, -1, + 6767, 6777, 6776, -1, 6777, 6767, 6766, -1, + 6766, 6778, 6777, -1, 6778, 6766, 6765, -1, + 6765, 6779, 6778, -1, 6765, 6780, 6779, -1, + 6780, 6765, 6764, -1, 6764, 6781, 6780, -1, + 6781, 6764, 6763, -1, 6763, 6782, 6781, -1, + 6782, 6763, 6762, -1, 6762, 6783, 6782, -1, + 6783, 6762, 6761, -1, 6761, 6784, 6783, -1, + 6784, 6761, 6717, -1, 6717, 6719, 6784, -1, + 6719, 6785, 6786, -1, 6719, 6786, 6787, -1, + 6787, 6784, 6719, -1, 6784, 6787, 6788, -1, + 6788, 6783, 6784, -1, 6783, 6788, 6789, -1, + 6789, 6782, 6783, -1, 6782, 6789, 6790, -1, + 6790, 6781, 6782, -1, 6781, 6790, 6791, -1, + 6791, 6780, 6781, -1, 6780, 6791, 6792, -1, + 6792, 6779, 6780, -1, 6779, 6792, 6793, -1, + 6779, 6793, 6794, -1, 6794, 6778, 6779, -1, + 6778, 6794, 6795, -1, 6795, 6777, 6778, -1, + 6777, 6795, 6796, -1, 6796, 6776, 6777, -1, + 6776, 6796, 6797, -1, 6797, 6775, 6776, -1, + 6775, 6797, 6798, -1, 6798, 6774, 6775, -1, + 6774, 6798, 6799, -1, 6799, 6772, 6774, -1, + 6800, 6772, 6801, -1, 6772, 6802, 6801, -1, + 6772, 6799, 6802, -1, 6803, 6804, 6805, -1, + 6806, 6807, 6804, -1, 6807, 6805, 6804, -1, + 6807, 6808, 6805, -1, 6809, 6810, 6811, -1, + 6812, 6810, 6809, -1, 6809, 6813, 6812, -1, + 6809, 6811, 6813, -1, 6813, 6811, 6814, -1, + 6813, 6814, 6815, -1, 6815, 6816, 6813, -1, + 6816, 6815, 6817, -1, 6817, 6818, 6816, -1, + 6818, 6817, 6819, -1, 6819, 6820, 6818, -1, + 6820, 6819, 6821, -1, 6821, 6822, 6820, -1, + 6822, 6821, 6823, -1, 6823, 6824, 6822, -1, + 6824, 6823, 6825, -1, 6825, 6826, 6824, -1, + 6826, 6825, 6827, -1, 6827, 6828, 6826, -1, + 6828, 6827, 6829, -1, 6829, 6830, 6828, -1, + 6830, 6829, 6831, -1, 6830, 6831, 6832, -1, + 6832, 6833, 6830, -1, 6833, 6832, 6834, -1, + 6834, 6835, 6833, -1, 6835, 6834, 6836, -1, + 6836, 6837, 6835, -1, 6837, 6836, 6838, -1, + 6838, 6839, 6837, -1, 6839, 6838, 6840, -1, + 6840, 6841, 6839, -1, 6841, 6840, 6842, -1, + 6842, 6843, 6841, -1, 6843, 6842, 6844, -1, + 6844, 6845, 6843, -1, 6845, 6844, 6808, -1, + 6808, 6807, 6845, -1, 6802, 6807, 6846, -1, + 6802, 6845, 6807, -1, 6845, 6802, 6799, -1, + 6799, 6843, 6845, -1, 6843, 6799, 6798, -1, + 6798, 6841, 6843, -1, 6841, 6798, 6797, -1, + 6797, 6839, 6841, -1, 6839, 6797, 6796, -1, + 6796, 6837, 6839, -1, 6837, 6796, 6795, -1, + 6795, 6835, 6837, -1, 6835, 6795, 6794, -1, + 6794, 6833, 6835, -1, 6833, 6794, 6793, -1, + 6793, 6830, 6833, -1, 6793, 6828, 6830, -1, + 6828, 6793, 6792, -1, 6792, 6826, 6828, -1, + 6826, 6792, 6791, -1, 6791, 6824, 6826, -1, + 6824, 6791, 6790, -1, 6790, 6822, 6824, -1, + 6822, 6790, 6789, -1, 6789, 6820, 6822, -1, + 6820, 6789, 6788, -1, 6788, 6818, 6820, -1, + 6818, 6788, 6787, -1, 6787, 6816, 6818, -1, + 6816, 6787, 6786, -1, 6786, 6813, 6816, -1, + 6786, 6812, 6813, -1, 6847, 6812, 6786, -1, + 6847, 6810, 6812, -1, 6847, 6848, 6810, -1, + 6848, 6847, 6786, -1, 6848, 6786, 6785, -1, + 6785, 6810, 6848, -1, 6785, 6849, 6810, -1, + 6849, 6785, 6719, -1, 6849, 6719, 6718, -1, + 6849, 6718, 6721, -1, 6721, 6810, 6849, -1, + 6715, 6741, 6742, -1, 6850, 6715, 6742, -1, + 6742, 6744, 6850, -1, 6744, 6769, 6850, -1, + 6851, 6850, 6769, -1, 6851, 6715, 6850, -1, + 6851, 6852, 6715, -1, 6852, 6851, 6769, -1, + 6852, 6769, 6771, -1, 6771, 6715, 6852, -1, + 6771, 6716, 6715, -1, 6716, 6771, 6770, -1, + 6716, 6770, 6773, -1, 6773, 6713, 6716, -1, + 6853, 6713, 6773, -1, 6853, 6773, 6772, -1, + 6853, 6772, 6800, -1, 6800, 6713, 6853, -1, + 6800, 6801, 6713, -1, 6801, 6714, 6713, -1, + 6714, 6801, 6802, -1, 6714, 6802, 6846, -1, + 6846, 6712, 6714, -1, 6854, 6712, 6846, -1, + 6854, 6846, 6807, -1, 6854, 6807, 6806, -1, + 6806, 6712, 6854, -1, 6806, 6804, 6712, -1, + 6804, 6803, 6712, -1, 6803, 6711, 6712, -1, + 6803, 6805, 6711, -1, 6805, 6708, 6711, -1, + 6805, 6707, 6708, -1, 6707, 6805, 6808, -1, + 6808, 6706, 6707, -1, 6706, 6808, 6844, -1, + 6844, 6705, 6706, -1, 6705, 6844, 6842, -1, + 6842, 6704, 6705, -1, 6704, 6842, 6840, -1, + 6840, 6703, 6704, -1, 6703, 6840, 6838, -1, + 6838, 6702, 6703, -1, 6702, 6838, 6836, -1, + 6836, 6701, 6702, -1, 6701, 6836, 6834, -1, + 6834, 6700, 6701, -1, 6700, 6834, 6832, -1, + 6832, 6699, 6700, -1, 6699, 6832, 6831, -1, + 6831, 6698, 6699, -1, 6831, 6697, 6698, -1, + 6697, 6831, 6829, -1, 6829, 6696, 6697, -1, + 6696, 6829, 6827, -1, 6827, 6695, 6696, -1, + 6695, 6827, 6825, -1, 6825, 6694, 6695, -1, + 6694, 6825, 6823, -1, 6823, 6693, 6694, -1, + 6693, 6823, 6821, -1, 6821, 6692, 6693, -1, + 6692, 6821, 6819, -1, 6819, 6691, 6692, -1, + 6691, 6819, 6817, -1, 6817, 6690, 6691, -1, + 6690, 6817, 6815, -1, 6815, 6689, 6690, -1, + 6689, 6815, 6814, -1, 6814, 6688, 6689, -1, + 6814, 6687, 6688, -1, 6855, 6687, 6814, -1, + 6855, 6685, 6687, -1, 6855, 6856, 6685, -1, + 6856, 6855, 6814, -1, 6856, 6814, 6811, -1, + 6811, 6685, 6856, -1, 6685, 6811, 6810, -1, + 1008, 6686, 6685, -1, 6686, 1008, 6857, -1, + 6857, 6683, 6686, -1, 6857, 6858, 6683, -1, + 6858, 6857, 1008, -1, 6858, 1008, 1012, -1, + 6858, 1012, 1009, -1, 1009, 6683, 6858, -1, + 1009, 6682, 6683, -1, 1009, 1011, 6682, -1, + 6682, 1011, 6544, -1, 6682, 6544, 6545, -1, + 6545, 6680, 6682, -1, 6680, 6545, 6546, -1, + 6546, 6678, 6680, -1, 6678, 6546, 6547, -1, + 6547, 6676, 6678, -1, 6676, 6547, 6548, -1, + 6548, 6674, 6676, -1, 6674, 6548, 6549, -1, + 6549, 6672, 6674, -1, 6672, 6549, 6550, -1, + 6550, 6670, 6672, -1, 6670, 6550, 6551, -1, + 6551, 6668, 6670, -1, 6668, 6551, 6552, -1, + 6552, 6666, 6668, -1, 6666, 6552, 6553, -1, + 6553, 6664, 6666, -1, 6664, 6553, 6554, -1, + 6554, 6662, 6664, -1, 6662, 6554, 6555, -1, + 6555, 6661, 6662, -1, 6661, 6555, 6556, -1, + 6661, 6556, 6557, -1, 6557, 6659, 6661, -1, + 6659, 6557, 6558, -1, 6558, 6657, 6659, -1, + 6657, 6558, 6559, -1, 6559, 6655, 6657, -1, + 6655, 6559, 6560, -1, 6560, 6653, 6655, -1, + 6653, 6560, 6561, -1, 6561, 6651, 6653, -1, + 6651, 6561, 6562, -1, 6562, 6649, 6651, -1, + 6649, 6562, 6563, -1, 6563, 6647, 6649, -1, + 6647, 6563, 6564, -1, 6564, 6645, 6647, -1, + 6645, 6564, 6565, -1, 6565, 6643, 6645, -1, + 6643, 6565, 6566, -1, 6566, 6641, 6643, -1, + 6641, 6566, 6567, -1, 6567, 6639, 6641, -1, + 6639, 6567, 6568, -1, 6568, 6637, 6639, -1, + 6637, 6568, 6481, -1, 6637, 6481, 6859, -1, + 6859, 6634, 6637, -1, 6859, 6635, 6634, -1, + 6859, 6860, 6635, -1, 6860, 6859, 6481, -1, + 6860, 6481, 6480, -1, 6480, 6635, 6860, -1, + 6635, 6480, 6479, -1, 6479, 6861, 6862, -1, + 6861, 6479, 6570, -1, 6570, 6572, 6861, -1, + 6861, 6572, 6574, -1, 6574, 6862, 6861, -1, + 6863, 6862, 6574, -1, 6863, 6574, 6573, -1, + 6863, 6573, 6864, -1, 6864, 6862, 6863, -1, + 6864, 6865, 6862, -1, 6864, 6573, 6865, -1, + 932, 6865, 6573, -1, 6573, 1005, 932, -1, + 1005, 6573, 6575, -1, 6575, 1003, 1005, -1, + 1003, 6575, 6576, -1, 6576, 1001, 1003, -1, + 1001, 6576, 6577, -1, 6577, 999, 1001, -1, + 999, 6577, 6578, -1, 6578, 997, 999, -1, + 997, 6578, 6579, -1, 6579, 995, 997, -1, + 995, 6579, 6580, -1, 6580, 993, 995, -1, + 993, 6580, 6581, -1, 6581, 991, 993, -1, + 991, 6581, 6582, -1, 6582, 989, 991, -1, + 989, 6582, 6583, -1, 6583, 987, 989, -1, + 987, 6583, 6584, -1, 6584, 985, 987, -1, + 985, 6584, 6585, -1, 6585, 983, 985, -1, + 983, 6585, 6586, -1, 6586, 981, 983, -1, + 981, 6586, 6587, -1, 6587, 979, 981, -1, + 979, 6587, 6588, -1, 6588, 977, 979, -1, + 977, 6588, 6589, -1, 6589, 975, 977, -1, + 975, 6589, 6590, -1, 6590, 972, 975, -1, + 6590, 970, 972, -1, 970, 6590, 6591, -1, + 6591, 968, 970, -1, 968, 6591, 6592, -1, + 6592, 966, 968, -1, 966, 6592, 6593, -1, + 6593, 964, 966, -1, 964, 6593, 6594, -1, + 6594, 962, 964, -1, 962, 6594, 6595, -1, + 6595, 960, 962, -1, 960, 6595, 6596, -1, + 6596, 958, 960, -1, 958, 6596, 6597, -1, + 6597, 956, 958, -1, 956, 6597, 6598, -1, + 6598, 954, 956, -1, 954, 6598, 6599, -1, + 6599, 952, 954, -1, 952, 6599, 6600, -1, + 6600, 950, 952, -1, 950, 6600, 6601, -1, + 6601, 948, 950, -1, 948, 6601, 6602, -1, + 6602, 946, 948, -1, 946, 6602, 6603, -1, + 6603, 944, 946, -1, 944, 6603, 6604, -1, + 6604, 942, 944, -1, 942, 6604, 6605, -1, + 6605, 940, 942, -1, 940, 6605, 6618, -1, + 6618, 938, 940, -1, 938, 6618, 6619, -1, + 6619, 935, 938, -1, 6619, 6621, 935, -1, + 6866, 935, 6621, -1, 6621, 6476, 6866, -1, + 6866, 6476, 6477, -1, 6477, 935, 6866, -1, + 6477, 936, 935, -1, 936, 6477, 929, -1, + 936, 929, 928, -1, 928, 934, 936, -1, + 928, 927, 934, -1, 927, 6867, 934, -1, + 927, 929, 6867, -1, 6867, 929, 1953, -1, + 1953, 1955, 6867, -1, 1955, 934, 6867, -1, + 934, 1955, 1956, -1, 1956, 937, 934, -1, + 937, 1956, 1957, -1, 1957, 939, 937, -1, + 939, 1957, 1958, -1, 1958, 941, 939, -1, + 941, 1958, 1959, -1, 1959, 943, 941, -1, + 943, 1959, 1960, -1, 1960, 945, 943, -1, + 945, 1960, 1961, -1, 1961, 947, 945, -1, + 947, 1961, 1962, -1, 1962, 949, 947, -1, + 949, 1962, 1963, -1, 1963, 951, 949, -1, + 951, 1963, 1964, -1, 1964, 953, 951, -1, + 953, 1964, 1965, -1, 1965, 955, 953, -1, + 955, 1965, 1966, -1, 1966, 957, 955, -1, + 957, 1966, 1967, -1, 1967, 959, 957, -1, + 959, 1967, 1968, -1, 1968, 961, 959, -1, + 961, 1968, 1969, -1, 1969, 963, 961, -1, + 963, 1969, 1970, -1, 1970, 965, 963, -1, + 965, 1970, 1971, -1, 1971, 967, 965, -1, + 967, 1971, 1972, -1, 1972, 969, 967, -1, + 969, 1972, 1973, -1, 1973, 971, 969, -1, + 971, 1973, 1974, -1, 1974, 973, 971, -1, + 973, 1974, 1975, -1, 973, 1975, 1976, -1, + 1976, 974, 973, -1, 974, 1976, 1977, -1, + 1977, 976, 974, -1, 976, 1977, 1978, -1, + 1978, 978, 976, -1, 978, 1978, 1979, -1, + 1979, 980, 978, -1, 980, 1979, 1980, -1, + 1980, 982, 980, -1, 982, 1980, 1981, -1, + 1981, 984, 982, -1, 984, 1981, 1982, -1, + 1982, 986, 984, -1, 986, 1982, 1983, -1, + 1983, 988, 986, -1, 988, 1983, 1984, -1, + 1984, 990, 988, -1, 990, 1984, 1985, -1, + 1985, 992, 990, -1, 992, 1985, 1986, -1, + 1986, 994, 992, -1, 994, 1986, 1987, -1, + 1987, 996, 994, -1, 996, 1987, 1988, -1, + 1988, 998, 996, -1, 998, 1988, 1989, -1, + 1989, 1000, 998, -1, 1000, 1989, 1990, -1, + 1990, 1002, 1000, -1, 1002, 1990, 1991, -1, + 1991, 1004, 1002, -1, 1004, 1991, 1992, -1, + 1992, 933, 1004, -1, 933, 1992, 1993, -1, + 1993, 930, 933, -1, 930, 1993, 1994, -1, + 1994, 1999, 930, -1, 6868, 930, 1999, -1, + 6868, 1999, 1996, -1, 6868, 1996, 6869, -1, + 6869, 930, 6868, -1, 6869, 931, 930, -1, + 6869, 1996, 931, -1, 931, 1996, 6870, -1, + 6870, 932, 931, -1, 6870, 6865, 932, -1, + 6870, 6862, 6865, -1, 6862, 6870, 1996, -1, + 2140, 6871, 6872, -1, 6871, 2140, 2141, -1, + 2141, 2143, 6871, -1, 2143, 2151, 6871, -1, + 6873, 6871, 2151, -1, 6873, 6872, 6871, -1, + 6874, 6872, 6873, -1, 6873, 2151, 6874, -1, + 6874, 2151, 6467, -1, 6467, 6872, 6874, -1, + 6467, 6466, 6872, -1, 6466, 4753, 6872, -1, + 6872, 4753, 4755, -1, 4755, 6875, 6876, -1, + 6875, 4755, 4758, -1, 4758, 4759, 6875, -1, + 4759, 5800, 6875, -1, 6877, 6875, 5800, -1, + 6877, 6876, 6875, -1, 6878, 6876, 6877, -1, + 6877, 5800, 6878, -1, 6878, 5800, 5818, -1, + 5818, 6876, 6878, -1, 5818, 5817, 6876, -1, + 5817, 5816, 6876, -1, 5816, 6879, 6876, -1, + 6879, 5816, 5815, -1, 6879, 5815, 5886, -1, + 6879, 5886, 4744, -1, 4744, 6876, 6879, -1, + 6880, 4744, 4742, -1, 4742, 6881, 6880, -1, + 4742, 4708, 6881, -1, 6881, 4708, 4711, -1, + 4711, 6880, 6881, -1, 4711, 4712, 6880, -1, + 4712, 4713, 6880, -1, 4713, 6882, 6880, -1, + 6882, 4713, 4714, -1, 6882, 4714, 5979, -1, + 6882, 5979, 5980, -1, 5980, 6880, 6882, -1, + 4428, 5981, 5983, -1, 6883, 4428, 5983, -1, + 6883, 5983, 5984, -1, 6883, 5984, 6884, -1, + 6884, 4428, 6883, -1, 6884, 6885, 4428, -1, + 6886, 4428, 6885, -1, 6886, 4350, 4428, -1, + 6886, 4348, 4350, -1, 6886, 6885, 4348, -1, + 6885, 6884, 4348, -1, 4348, 6884, 5984, -1, + 5984, 4346, 4348, -1, 4346, 5984, 5985, -1, + 4346, 5985, 6887, -1, 6888, 6889, 6890, -1, + 6889, 6888, 6887, -1, 6889, 6887, 5985, -1, + 6889, 5985, 5986, -1, 5986, 6890, 6889, -1, + 6890, 5986, 5987, -1, 5987, 5989, 6890, -1, + 5989, 5997, 6890, -1, 6891, 6890, 5997, -1, + 6891, 6888, 6890, -1, 6888, 6891, 6892, -1, + 6892, 6887, 6888, -1, 6887, 6892, 6893, -1, + 6893, 4346, 6887, -1, 6893, 4347, 4346, -1, + 6893, 6894, 4347, -1, 6894, 6893, 6892, -1, + 6892, 6895, 6894, -1, 6895, 6892, 6891, -1, + 6891, 5997, 6895, -1, 5997, 5999, 6895, -1, + 6896, 6895, 5999, -1, 6896, 6894, 6895, -1, + 6894, 6896, 6897, -1, 6897, 4347, 6894, -1, + 4347, 6897, 6898, -1, 6898, 4345, 4347, -1, + 6898, 4353, 4345, -1, 6898, 4357, 4353, -1, + 4357, 6898, 6897, -1, 6897, 4355, 4357, -1, + 4355, 6897, 6896, -1, 6896, 5999, 4355, -1, + 5999, 4356, 4355, -1, 5999, 4366, 4356, -1, + 4366, 5999, 5998, -1, 5998, 4368, 4366, -1, + 4368, 5998, 6000, -1, 6000, 4370, 4368, -1, + 4370, 6000, 6001, -1, 6001, 4372, 4370, -1, + 4372, 6001, 6002, -1, 6002, 4374, 4372, -1, + 4374, 6002, 4657, -1, 4657, 4376, 4374, -1, + 4376, 4657, 4656, -1, 4656, 4378, 4376, -1, + 4378, 4656, 4655, -1, 4655, 4380, 4378, -1, + 4380, 4655, 4653, -1, 4653, 4382, 4380, -1, + 4382, 4653, 4651, -1, 4651, 4384, 4382, -1, + 4384, 4651, 4649, -1, 4649, 4386, 4384, -1, + 4386, 4649, 4647, -1, 4647, 4388, 4386, -1, + 4388, 4647, 4645, -1, 4645, 4390, 4388, -1, + 4390, 4645, 4643, -1, 4643, 4392, 4390, -1, + 4392, 4643, 4641, -1, 4641, 4394, 4392, -1, + 4394, 4641, 4639, -1, 4639, 4396, 4394, -1, + 4396, 4639, 4637, -1, 4637, 4398, 4396, -1, + 4398, 4637, 4635, -1, 4635, 4400, 4398, -1, + 4400, 4635, 4633, -1, 4633, 4402, 4400, -1, + 4402, 4633, 4631, -1, 4631, 4404, 4402, -1, + 4404, 4631, 4629, -1, 4629, 4406, 4404, -1, + 4406, 4629, 4627, -1, 4627, 4408, 4406, -1, + 4408, 4627, 4590, -1, 4590, 4340, 4408, -1, + 4340, 4590, 4589, -1, 4589, 4339, 4340, -1, + 4339, 4589, 4592, -1, 4592, 4338, 4339, -1, + 4338, 4592, 4594, -1, 4594, 4337, 4338, -1, + 4337, 4594, 4596, -1, 4596, 4336, 4337, -1, + 4336, 4596, 4598, -1, 4598, 4335, 4336, -1, + 4335, 4598, 4600, -1, 4600, 4334, 4335, -1, + 4334, 4600, 4602, -1, 4602, 2615, 4334, -1, + 2615, 4602, 4604, -1, 4604, 2616, 2615, -1, + 2616, 4604, 4613, -1, 4613, 2618, 2616, -1, + 2618, 4613, 4610, -1, 4610, 2619, 2618, -1, + 2619, 4610, 4609, -1, 4609, 2622, 2619, -1, + 2622, 4609, 4607, -1, 4607, 2623, 2622, -1, + 2623, 4607, 4606, -1, 4606, 4333, 2623, -1, + 4333, 4606, 6899, -1, 6899, 4332, 4333, -1, + 4332, 6899, 6900, -1, 6900, 4331, 4332, -1, + 4331, 6900, 6901, -1, 6901, 4330, 4331, -1, + 4330, 6901, 6902, -1, 6902, 4329, 4330, -1, + 4329, 6902, 6903, -1, 6903, 4328, 4329, -1, + 4328, 6903, 6904, -1, 6904, 4327, 4328, -1, + 4327, 6904, 6905, -1, 6905, 4326, 4327, -1, + 4326, 6905, 6906, -1, 6906, 4325, 4326, -1, + 4325, 6906, 6907, -1, 6907, 4324, 4325, -1, + 4324, 6907, 6908, -1, 6908, 4323, 4324, -1, + 4323, 6908, 6909, -1, 6909, 4322, 4323, -1, + 4322, 6909, 6910, -1, 6910, 4321, 4322, -1, + 4321, 6910, 6911, -1, 6911, 4320, 4321, -1, + 4320, 6911, 6912, -1, 6912, 4318, 4320, -1, + 6913, 6914, 4318, -1, 4318, 6912, 6913, -1, + 6915, 6916, 6913, -1, 6913, 6917, 6915, -1, + 6917, 6913, 6912, -1, 6912, 6918, 6917, -1, + 6918, 6912, 6911, -1, 6911, 6919, 6918, -1, + 6919, 6911, 6910, -1, 6910, 6920, 6919, -1, + 6920, 6910, 6909, -1, 6909, 6921, 6920, -1, + 6921, 6909, 6908, -1, 6908, 6922, 6921, -1, + 6922, 6908, 6907, -1, 6907, 6923, 6922, -1, + 6923, 6907, 6906, -1, 6906, 6924, 6923, -1, + 6924, 6906, 6905, -1, 6905, 6925, 6924, -1, + 6925, 6905, 6904, -1, 6904, 6926, 6925, -1, + 6926, 6904, 6903, -1, 6903, 6927, 6926, -1, + 6927, 6903, 6902, -1, 6902, 6928, 6927, -1, + 6928, 6902, 6901, -1, 6901, 6929, 6928, -1, + 6929, 6901, 6900, -1, 6900, 6930, 6929, -1, + 6930, 6900, 6899, -1, 6899, 6931, 6930, -1, + 6931, 6899, 4606, -1, 4606, 6932, 6931, -1, + 6932, 4606, 4605, -1, 6932, 4605, 6933, -1, + 6932, 6933, 6934, -1, 6934, 6931, 6932, -1, + 6931, 6934, 6935, -1, 6935, 6930, 6931, -1, + 6930, 6935, 6936, -1, 6936, 6929, 6930, -1, + 6929, 6936, 6937, -1, 6937, 6928, 6929, -1, + 6928, 6937, 6938, -1, 6938, 6927, 6928, -1, + 6927, 6938, 6939, -1, 6939, 6926, 6927, -1, + 6926, 6939, 6940, -1, 6940, 6925, 6926, -1, + 6925, 6940, 6941, -1, 6941, 6924, 6925, -1, + 6924, 6941, 6942, -1, 6942, 6923, 6924, -1, + 6923, 6942, 6943, -1, 6943, 6922, 6923, -1, + 6922, 6943, 6944, -1, 6944, 6921, 6922, -1, + 6921, 6944, 6945, -1, 6945, 6920, 6921, -1, + 6920, 6945, 6946, -1, 6946, 6919, 6920, -1, + 6919, 6946, 6947, -1, 6947, 6918, 6919, -1, + 6918, 6947, 6948, -1, 6948, 6917, 6918, -1, + 6917, 6948, 6949, -1, 6949, 6915, 6917, -1, + 6949, 6950, 6915, -1, 6950, 6949, 6951, -1, + 6951, 6952, 6950, -1, 6952, 6951, 6953, -1, + 6953, 6954, 6952, -1, 6954, 6953, 6955, -1, + 6955, 6956, 6954, -1, 6956, 6955, 6957, -1, + 6957, 6958, 6956, -1, 6958, 6957, 6959, -1, + 6959, 6960, 6958, -1, 6960, 6959, 6961, -1, + 6961, 6962, 6960, -1, 6962, 6961, 6963, -1, + 6963, 6964, 6962, -1, 6964, 6963, 6965, -1, + 6965, 6966, 6964, -1, 6966, 6965, 6967, -1, + 6967, 6968, 6966, -1, 6968, 6967, 6969, -1, + 6969, 6970, 6968, -1, 6970, 6969, 6971, -1, + 6971, 6972, 6970, -1, 6972, 6971, 6973, -1, + 6973, 6974, 6972, -1, 6974, 6973, 6975, -1, + 6975, 6976, 6974, -1, 6976, 6975, 6977, -1, + 6977, 6978, 6976, -1, 6978, 6977, 6979, -1, + 6979, 926, 6978, -1, 926, 6979, 6980, -1, + 6980, 922, 926, -1, 6980, 921, 922, -1, + 6980, 919, 921, -1, 919, 6980, 6979, -1, + 6979, 917, 919, -1, 917, 6979, 6977, -1, + 6977, 915, 917, -1, 915, 6977, 6975, -1, + 6975, 913, 915, -1, 913, 6975, 6973, -1, + 6973, 911, 913, -1, 911, 6973, 6971, -1, + 6971, 909, 911, -1, 909, 6971, 6969, -1, + 6969, 907, 909, -1, 907, 6969, 6967, -1, + 6967, 905, 907, -1, 905, 6967, 6965, -1, + 6965, 903, 905, -1, 903, 6965, 6963, -1, + 6963, 901, 903, -1, 901, 6963, 6961, -1, + 6961, 899, 901, -1, 899, 6961, 6959, -1, + 6959, 897, 899, -1, 897, 6959, 6957, -1, + 6957, 895, 897, -1, 895, 6957, 6955, -1, + 6955, 893, 895, -1, 893, 6955, 6953, -1, + 6953, 891, 893, -1, 891, 6953, 6951, -1, + 6951, 890, 891, -1, 890, 6951, 6949, -1, + 890, 6949, 6948, -1, 6948, 888, 890, -1, + 888, 6948, 6947, -1, 6947, 886, 888, -1, + 886, 6947, 6946, -1, 6946, 884, 886, -1, + 884, 6946, 6945, -1, 6945, 882, 884, -1, + 882, 6945, 6944, -1, 6944, 880, 882, -1, + 880, 6944, 6943, -1, 6943, 878, 880, -1, + 878, 6943, 6942, -1, 6942, 876, 878, -1, + 876, 6942, 6941, -1, 6941, 874, 876, -1, + 874, 6941, 6940, -1, 6940, 872, 874, -1, + 872, 6940, 6939, -1, 6939, 870, 872, -1, + 870, 6939, 6938, -1, 6938, 868, 870, -1, + 868, 6938, 6937, -1, 6937, 866, 868, -1, + 866, 6937, 6936, -1, 6936, 864, 866, -1, + 864, 6936, 6935, -1, 6935, 860, 864, -1, + 860, 6935, 6934, -1, 6934, 861, 860, -1, + 861, 6934, 6933, -1, 6933, 6981, 861, -1, + 6982, 6983, 6981, -1, 6981, 6933, 6982, -1, + 6982, 6933, 4605, -1, 6982, 4605, 4608, -1, + 4608, 6983, 6982, -1, 6983, 4608, 4611, -1, + 4611, 6984, 6983, -1, 6984, 4611, 4612, -1, + 4612, 4614, 6984, -1, 6984, 4614, 4616, -1, + 4616, 6983, 6984, -1, 6983, 4616, 6985, -1, + 6985, 6981, 6983, -1, 6986, 6981, 6985, -1, + 6981, 6986, 6987, -1, 6987, 861, 6981, -1, + 6987, 862, 861, -1, 6987, 6988, 862, -1, + 6988, 6987, 6986, -1, 6986, 6989, 6988, -1, + 6986, 6985, 6989, -1, 6990, 6989, 6985, -1, + 6990, 6985, 4616, -1, 4616, 4615, 6990, -1, + 6990, 4615, 6024, -1, 6024, 6989, 6990, -1, + 6989, 6024, 6025, -1, 6025, 6988, 6989, -1, + 6988, 6025, 6026, -1, 6026, 862, 6988, -1, + 862, 6026, 6027, -1, 6027, 863, 862, -1, + 863, 6027, 6029, -1, 6029, 865, 863, -1, + 865, 6029, 6031, -1, 6031, 867, 865, -1, + 867, 6031, 6033, -1, 6033, 869, 867, -1, + 869, 6033, 6035, -1, 6035, 871, 869, -1, + 871, 6035, 6037, -1, 6037, 873, 871, -1, + 873, 6037, 6039, -1, 6039, 875, 873, -1, + 875, 6039, 6041, -1, 6041, 877, 875, -1, + 877, 6041, 6043, -1, 6043, 879, 877, -1, + 879, 6043, 6045, -1, 6045, 881, 879, -1, + 881, 6045, 6047, -1, 6047, 883, 881, -1, + 883, 6047, 6049, -1, 6049, 885, 883, -1, + 885, 6049, 6051, -1, 6051, 887, 885, -1, + 887, 6051, 6053, -1, 6053, 889, 887, -1, + 6053, 892, 889, -1, 892, 6053, 6054, -1, + 6054, 894, 892, -1, 894, 6054, 6056, -1, + 6056, 896, 894, -1, 896, 6056, 6058, -1, + 6058, 898, 896, -1, 898, 6058, 6060, -1, + 6060, 900, 898, -1, 900, 6060, 6062, -1, + 6062, 902, 900, -1, 902, 6062, 6064, -1, + 6064, 904, 902, -1, 904, 6064, 6066, -1, + 6066, 906, 904, -1, 906, 6066, 6068, -1, + 6068, 908, 906, -1, 908, 6068, 6173, -1, + 6173, 910, 908, -1, 910, 6173, 6174, -1, + 6174, 912, 910, -1, 912, 6174, 6175, -1, + 6175, 914, 912, -1, 914, 6175, 6176, -1, + 6176, 916, 914, -1, 916, 6176, 6177, -1, + 6177, 918, 916, -1, 918, 6177, 6178, -1, + 6178, 920, 918, -1, 920, 6178, 6203, -1, + 6203, 859, 920, -1, 859, 6203, 6201, -1, + 6201, 857, 859, -1, 857, 6201, 6199, -1, + 6199, 855, 857, -1, 855, 6199, 6197, -1, + 6197, 853, 855, -1, 853, 6197, 6195, -1, + 6195, 851, 853, -1, 851, 6195, 6193, -1, + 6193, 849, 851, -1, 849, 6193, 6191, -1, + 6191, 847, 849, -1, 847, 6191, 6189, -1, + 6189, 845, 847, -1, 845, 6189, 6187, -1, + 6187, 843, 845, -1, 843, 6187, 6185, -1, + 6185, 841, 843, -1, 841, 6185, 6183, -1, + 6183, 838, 841, -1, 838, 6183, 6181, -1, + 6181, 839, 838, -1, 839, 6181, 6180, -1, + 6180, 6991, 839, -1, 6991, 6180, 6205, -1, + 6205, 6992, 6991, -1, 6992, 6205, 6206, -1, + 6206, 6993, 6992, -1, 6993, 6206, 6207, -1, + 6207, 6994, 6993, -1, 6994, 6207, 6208, -1, + 6208, 6995, 6994, -1, 6995, 6208, 6209, -1, + 6209, 6996, 6995, -1, 6996, 6209, 6210, -1, + 6210, 6997, 6996, -1, 6997, 6210, 6211, -1, + 6211, 6998, 6997, -1, 6998, 6211, 6212, -1, + 6212, 6999, 6998, -1, 6999, 6212, 6213, -1, + 6213, 7000, 6999, -1, 7000, 6213, 6214, -1, + 6214, 7001, 7000, -1, 7001, 6214, 6215, -1, + 6215, 7002, 7001, -1, 7002, 6215, 6216, -1, + 6216, 7003, 7002, -1, 7003, 6216, 6217, -1, + 6217, 7004, 7003, -1, 7004, 6217, 6218, -1, + 6218, 7005, 7004, -1, 7005, 6218, 6219, -1, + 6219, 7006, 7005, -1, 7006, 6219, 6222, -1, + 6222, 7007, 7006, -1, 6222, 7008, 7007, -1, + 7009, 7010, 7011, -1, 7011, 7012, 7009, -1, + 7012, 7011, 7013, -1, 7013, 7014, 7012, -1, + 7014, 7013, 7015, -1, 7015, 7008, 7014, -1, + 7015, 7007, 7008, -1, 7015, 7016, 7007, -1, + 7016, 7015, 7013, -1, 7013, 7017, 7016, -1, + 7017, 7013, 7011, -1, 7011, 7018, 7017, -1, + 7018, 7011, 7010, -1, 7010, 7019, 7018, -1, + 7020, 7021, 7022, -1, 7020, 7022, 7019, -1, + 7019, 7010, 7020, -1, 7023, 7024, 7020, -1, + 7023, 7020, 7010, -1, 7010, 7009, 7023, -1, + 7025, 7026, 7023, -1, 7025, 7023, 7009, -1, + 7009, 7027, 7025, -1, 7027, 7009, 7012, -1, + 7012, 7028, 7027, -1, 7028, 7012, 7014, -1, + 7014, 7029, 7028, -1, 7029, 7014, 7008, -1, + 7008, 7030, 7029, -1, 7030, 7008, 6222, -1, + 7030, 6222, 6221, -1, 7030, 6221, 6223, -1, + 6223, 7029, 7030, -1, 7029, 6223, 6224, -1, + 6224, 7028, 7029, -1, 7028, 6224, 6225, -1, + 6225, 7027, 7028, -1, 7027, 6225, 6226, -1, + 6226, 7025, 7027, -1, 7025, 6226, 6227, -1, + 6227, 7026, 7025, -1, 7026, 6227, 6228, -1, + 6228, 7031, 7026, -1, 7031, 6228, 6229, -1, + 7031, 6229, 6231, -1, 7031, 6231, 7032, -1, + 7032, 7026, 7031, -1, 7032, 7023, 7026, -1, + 7032, 7024, 7023, -1, 7024, 7032, 6231, -1, + 6231, 7033, 7024, -1, 7033, 6231, 6230, -1, + 7033, 6230, 6234, -1, 7033, 6234, 6233, -1, + 6233, 7024, 7033, -1, 6233, 7020, 7024, -1, + 6233, 7021, 7020, -1, 7021, 6233, 6232, -1, + 6232, 7034, 7021, -1, 7034, 6232, 6235, -1, + 6235, 7035, 7034, -1, 6235, 6236, 7035, -1, + 7036, 7035, 6236, -1, 7036, 6236, 6237, -1, + 6237, 6242, 7036, -1, 7037, 7038, 7036, -1, + 7037, 7036, 6242, -1, 6242, 6258, 7037, -1, + 7039, 7040, 7037, -1, 7039, 7037, 6258, -1, + 6258, 6259, 7039, -1, 7041, 7042, 7039, -1, + 7041, 7039, 6259, -1, 7041, 6259, 6261, -1, + 7041, 6261, 6288, -1, 6288, 7042, 7041, -1, + 7042, 6288, 6289, -1, 6289, 7043, 7042, -1, + 7043, 6289, 6290, -1, 6290, 6292, 7043, -1, + 6292, 7044, 7045, -1, 7045, 7043, 6292, -1, + 7043, 7045, 7046, -1, 7046, 7042, 7043, -1, + 7046, 7039, 7042, -1, 7046, 7040, 7039, -1, + 7040, 7046, 7045, -1, 7045, 7047, 7040, -1, + 7047, 7045, 7044, -1, 7044, 7048, 7047, -1, + 7044, 7049, 7048, -1, 7044, 6292, 7049, -1, + 7049, 6292, 6291, -1, 7049, 6291, 6294, -1, + 6294, 7050, 7049, -1, 7050, 6294, 6296, -1, + 6296, 7051, 7050, -1, 7051, 6296, 6298, -1, + 6298, 7052, 7051, -1, 7052, 6298, 6300, -1, + 6300, 7053, 7052, -1, 7053, 6300, 6302, -1, + 6302, 7054, 7053, -1, 7054, 6302, 6304, -1, + 6304, 7055, 7054, -1, 7055, 6304, 6306, -1, + 6306, 7056, 7055, -1, 7056, 6306, 6308, -1, + 6308, 7057, 7056, -1, 7057, 6308, 6310, -1, + 6310, 7058, 7057, -1, 7058, 6310, 6312, -1, + 6312, 7059, 7058, -1, 7059, 6312, 6314, -1, + 6314, 7060, 7059, -1, 7060, 6314, 6316, -1, + 6316, 7061, 7060, -1, 7061, 6316, 6318, -1, + 6318, 7062, 7061, -1, 7062, 6318, 6320, -1, + 6320, 7063, 7062, -1, 7063, 6320, 6322, -1, + 6322, 7064, 7063, -1, 7064, 6322, 6324, -1, + 6324, 7065, 7064, -1, 7065, 6324, 6326, -1, + 6326, 7066, 7065, -1, 7066, 6326, 6328, -1, + 6328, 7067, 7066, -1, 7067, 6328, 6330, -1, + 6330, 7068, 7067, -1, 7068, 6330, 6332, -1, + 6332, 7069, 7068, -1, 7069, 6332, 6334, -1, + 6334, 7070, 7069, -1, 7070, 6334, 6336, -1, + 6336, 7071, 7070, -1, 7071, 6336, 6338, -1, + 6338, 7072, 7071, -1, 7072, 6338, 6340, -1, + 6340, 7073, 7072, -1, 7073, 6340, 6341, -1, + 6341, 6342, 7073, -1, 7074, 7073, 6342, -1, + 6342, 7075, 7074, -1, 7075, 6342, 6343, -1, + 6343, 7076, 7075, -1, 7076, 6343, 6344, -1, + 6344, 7077, 7076, -1, 7077, 6344, 6345, -1, + 6345, 7078, 7077, -1, 7078, 6345, 4521, -1, + 4521, 837, 7078, -1, 837, 4521, 4519, -1, + 4519, 836, 837, -1, 836, 4519, 4516, -1, + 4516, 833, 836, -1, 833, 4516, 4518, -1, + 4518, 834, 833, -1, 834, 4518, 6346, -1, + 6346, 7079, 834, -1, 7079, 6346, 6347, -1, + 6347, 7080, 7079, -1, 7080, 6347, 6348, -1, + 6348, 7081, 7080, -1, 7081, 6348, 6349, -1, + 6349, 7082, 7081, -1, 7082, 6349, 6350, -1, + 6350, 7083, 7082, -1, 7083, 6350, 6351, -1, + 6351, 7084, 7083, -1, 7084, 6351, 6352, -1, + 6352, 7085, 7084, -1, 7085, 6352, 6353, -1, + 6353, 7086, 7085, -1, 7086, 6353, 6354, -1, + 6354, 7087, 7086, -1, 7087, 6354, 6355, -1, + 6355, 7088, 7087, -1, 7088, 6355, 6356, -1, + 6356, 7089, 7088, -1, 7089, 6356, 6357, -1, + 6357, 7090, 7089, -1, 7090, 6357, 6358, -1, + 6358, 7091, 7090, -1, 7091, 6358, 6359, -1, + 6359, 7092, 7091, -1, 7092, 6359, 6360, -1, + 6360, 7093, 7092, -1, 7093, 6360, 830, -1, + 830, 829, 7093, -1, 7094, 7095, 7096, -1, + 7095, 7094, 7097, -1, 7097, 7098, 7095, -1, + 7098, 7097, 7099, -1, 7100, 7101, 7102, -1, + 7101, 7100, 7103, -1, 7103, 7104, 7101, -1, + 7104, 7103, 7105, -1, 7106, 7107, 7108, -1, + 7108, 7109, 7106, -1, 7109, 7108, 7110, -1, + 7110, 7111, 7109, -1, 7111, 7110, 7112, -1, + 7112, 7113, 7111, -1, 7113, 7112, 7114, -1, + 7114, 7115, 7113, -1, 7115, 7114, 7116, -1, + 7116, 7117, 7115, -1, 7117, 7116, 7118, -1, + 7118, 7119, 7117, -1, 7119, 7118, 7105, -1, + 7105, 7099, 7119, -1, 7099, 7105, 7103, -1, + 7103, 7098, 7099, -1, 7098, 7103, 7100, -1, + 7100, 7095, 7098, -1, 7095, 7100, 7102, -1, + 7102, 7096, 7095, -1, 7096, 7102, 7120, -1, + 7120, 7121, 7096, -1, 7121, 7120, 7122, -1, + 7122, 7123, 7121, -1, 7123, 7122, 7124, -1, + 7124, 7125, 7123, -1, 7125, 7124, 7126, -1, + 7126, 7127, 7125, -1, 7127, 7126, 7128, -1, + 7128, 7129, 7127, -1, 7129, 7128, 7130, -1, + 7130, 7131, 7129, -1, 7131, 7130, 7132, -1, + 7132, 7133, 7131, -1, 7133, 7132, 7134, -1, + 7134, 7135, 7133, -1, 7135, 7134, 7136, -1, + 7136, 7137, 7135, -1, 7137, 7136, 7138, -1, + 7138, 7139, 7137, -1, 7139, 7138, 7140, -1, + 7140, 7141, 7139, -1, 7141, 7140, 7142, -1, + 7142, 7143, 7141, -1, 7143, 7142, 7144, -1, + 7144, 7145, 7143, -1, 7145, 7144, 7146, -1, + 7146, 7147, 7145, -1, 7147, 7146, 7148, -1, + 7148, 7149, 7147, -1, 7150, 827, 7151, -1, + 7151, 7152, 7150, -1, 7152, 7151, 7153, -1, + 7152, 7153, 7154, -1, 7154, 7150, 7152, -1, + 7155, 7156, 7157, -1, 7156, 7155, 7150, -1, + 7156, 7150, 7154, -1, 7154, 7153, 7156, -1, + 7153, 7157, 7156, -1, 7157, 7153, 7149, -1, + 7149, 7148, 7157, -1, 829, 7157, 7148, -1, + 7148, 7093, 829, -1, 7093, 7148, 7146, -1, + 7146, 7092, 7093, -1, 7092, 7146, 7144, -1, + 7144, 7091, 7092, -1, 7091, 7144, 7142, -1, + 7142, 7090, 7091, -1, 7090, 7142, 7140, -1, + 7140, 7089, 7090, -1, 7089, 7140, 7138, -1, + 7138, 7088, 7089, -1, 7088, 7138, 7136, -1, + 7136, 7087, 7088, -1, 7087, 7136, 7134, -1, + 7134, 7086, 7087, -1, 7086, 7134, 7132, -1, + 7132, 7085, 7086, -1, 7085, 7132, 7130, -1, + 7130, 7084, 7085, -1, 7084, 7130, 7128, -1, + 7128, 7083, 7084, -1, 7083, 7128, 7126, -1, + 7126, 7082, 7083, -1, 7082, 7126, 7124, -1, + 7124, 7081, 7082, -1, 7081, 7124, 7122, -1, + 7122, 7080, 7081, -1, 7080, 7122, 7120, -1, + 7120, 7079, 7080, -1, 7079, 7120, 7102, -1, + 7102, 834, 7079, -1, 834, 7102, 7101, -1, + 7101, 832, 834, -1, 832, 7101, 7104, -1, + 7104, 835, 832, -1, 835, 7104, 7105, -1, + 7105, 837, 835, -1, 837, 7105, 7118, -1, + 7118, 7078, 837, -1, 7078, 7118, 7116, -1, + 7116, 7077, 7078, -1, 7077, 7116, 7114, -1, + 7114, 7076, 7077, -1, 7076, 7114, 7112, -1, + 7112, 7075, 7076, -1, 7075, 7112, 7110, -1, + 7110, 7074, 7075, -1, 7074, 7110, 7108, -1, + 7108, 7073, 7074, -1, 7073, 7108, 7107, -1, + 7107, 7072, 7073, -1, 7072, 7107, 7158, -1, + 7158, 7071, 7072, -1, 7071, 7158, 7159, -1, + 7159, 7070, 7071, -1, 7070, 7159, 7160, -1, + 7160, 7069, 7070, -1, 7069, 7160, 7161, -1, + 7161, 7068, 7069, -1, 7068, 7161, 7162, -1, + 7162, 7067, 7068, -1, 7067, 7162, 7163, -1, + 7163, 7066, 7067, -1, 7066, 7163, 7164, -1, + 7164, 7065, 7066, -1, 7065, 7164, 7165, -1, + 7165, 7064, 7065, -1, 7064, 7165, 7166, -1, + 7166, 7063, 7064, -1, 7063, 7166, 7167, -1, + 7167, 7062, 7063, -1, 7062, 7167, 7168, -1, + 7168, 7061, 7062, -1, 7061, 7168, 7169, -1, + 7169, 7060, 7061, -1, 7060, 7169, 7170, -1, + 7170, 7059, 7060, -1, 7059, 7170, 7171, -1, + 7171, 7058, 7059, -1, 7058, 7171, 7172, -1, + 7172, 7057, 7058, -1, 7057, 7172, 7173, -1, + 7173, 7056, 7057, -1, 7056, 7173, 7174, -1, + 7174, 7055, 7056, -1, 7055, 7174, 7175, -1, + 7175, 7054, 7055, -1, 7054, 7175, 7176, -1, + 7176, 7053, 7054, -1, 7053, 7176, 7177, -1, + 7177, 7052, 7053, -1, 7052, 7177, 7178, -1, + 7178, 7051, 7052, -1, 7051, 7178, 7179, -1, + 7179, 7050, 7051, -1, 7050, 7179, 7180, -1, + 7180, 7049, 7050, -1, 7180, 7048, 7049, -1, + 7181, 7180, 7182, -1, 7181, 7048, 7180, -1, + 7048, 7181, 7183, -1, 7183, 7047, 7048, -1, + 7047, 7183, 7184, -1, 7184, 7040, 7047, -1, + 7184, 7037, 7040, -1, 7184, 7038, 7037, -1, + 7038, 7184, 7183, -1, 7183, 7185, 7038, -1, + 7185, 7183, 7181, -1, 7181, 7182, 7185, -1, + 7182, 7186, 7187, -1, 7187, 7185, 7182, -1, + 7185, 7187, 7188, -1, 7188, 7038, 7185, -1, + 7188, 7036, 7038, -1, 7188, 7035, 7036, -1, + 7035, 7188, 7187, -1, 7187, 7034, 7035, -1, + 7034, 7187, 7186, -1, 7186, 7021, 7034, -1, + 7186, 7022, 7021, -1, 7186, 7182, 7022, -1, + 7022, 7182, 7180, -1, 7022, 7180, 7179, -1, + 7179, 7019, 7022, -1, 7019, 7179, 7178, -1, + 7178, 7018, 7019, -1, 7018, 7178, 7177, -1, + 7177, 7017, 7018, -1, 7017, 7177, 7176, -1, + 7176, 7016, 7017, -1, 7016, 7176, 7175, -1, + 7175, 7007, 7016, -1, 7007, 7175, 7174, -1, + 7174, 7006, 7007, -1, 7006, 7174, 7173, -1, + 7173, 7005, 7006, -1, 7005, 7173, 7172, -1, + 7172, 7004, 7005, -1, 7004, 7172, 7171, -1, + 7171, 7003, 7004, -1, 7003, 7171, 7170, -1, + 7170, 7002, 7003, -1, 7002, 7170, 7169, -1, + 7169, 7001, 7002, -1, 7001, 7169, 7168, -1, + 7168, 7000, 7001, -1, 7000, 7168, 7167, -1, + 7167, 6999, 7000, -1, 6999, 7167, 7166, -1, + 7166, 6998, 6999, -1, 6998, 7166, 7165, -1, + 7165, 6997, 6998, -1, 6997, 7165, 7164, -1, + 7164, 6996, 6997, -1, 6996, 7164, 7163, -1, + 7163, 6995, 6996, -1, 6995, 7163, 7162, -1, + 7162, 6994, 6995, -1, 6994, 7162, 7161, -1, + 7161, 6993, 6994, -1, 6993, 7161, 7160, -1, + 7160, 6992, 6993, -1, 6992, 7160, 7159, -1, + 7159, 6991, 6992, -1, 6991, 7159, 7158, -1, + 7158, 839, 6991, -1, 839, 7158, 7107, -1, + 7107, 840, 839, -1, 840, 7107, 7106, -1, + 7106, 842, 840, -1, 842, 7106, 7109, -1, + 7109, 844, 842, -1, 844, 7109, 7111, -1, + 7111, 846, 844, -1, 846, 7111, 7113, -1, + 7113, 848, 846, -1, 848, 7113, 7115, -1, + 7115, 850, 848, -1, 850, 7115, 7117, -1, + 7117, 852, 850, -1, 852, 7117, 7119, -1, + 7119, 854, 852, -1, 854, 7119, 7099, -1, + 7099, 856, 854, -1, 856, 7099, 7097, -1, + 7097, 924, 856, -1, 924, 7097, 7094, -1, + 7094, 925, 924, -1, 925, 7094, 7096, -1, + 7096, 926, 925, -1, 926, 7096, 7121, -1, + 7121, 6978, 926, -1, 6978, 7121, 7123, -1, + 7123, 6976, 6978, -1, 6976, 7123, 7125, -1, + 7125, 6974, 6976, -1, 6974, 7125, 7127, -1, + 7127, 6972, 6974, -1, 6972, 7127, 7129, -1, + 7129, 6970, 6972, -1, 6970, 7129, 7131, -1, + 7131, 6968, 6970, -1, 6968, 7131, 7133, -1, + 7133, 6966, 6968, -1, 6966, 7133, 7135, -1, + 7135, 6964, 6966, -1, 6964, 7135, 7137, -1, + 7137, 6962, 6964, -1, 6962, 7137, 7139, -1, + 7139, 6960, 6962, -1, 6960, 7139, 7141, -1, + 7141, 6958, 6960, -1, 6958, 7141, 7143, -1, + 7143, 6956, 6958, -1, 6956, 7143, 7145, -1, + 7145, 6954, 6956, -1, 6954, 7145, 7147, -1, + 7147, 6952, 6954, -1, 6952, 7147, 7149, -1, + 7149, 6950, 6952, -1, 6950, 7149, 7153, -1, + 7153, 6915, 6950, -1, 6915, 7153, 7151, -1, + 7151, 6916, 6915, -1, 6916, 7151, 827, -1, + 6916, 827, 826, -1, 826, 6913, 6916, -1, + 826, 828, 6913, -1, 828, 6914, 6913, -1, + 6914, 828, 827, -1, 827, 7189, 4319, -1, + 7190, 7189, 7191, -1, 7190, 4319, 7189, -1, + 7190, 4316, 4319, -1, 7190, 7191, 4316, -1, + 7191, 4317, 4316, -1, 4317, 7191, 7189, -1, + 4317, 7189, 7192, -1, 7192, 7189, 4267, -1, + 7189, 4265, 4267, -1, 7193, 7194, 7195, -1, + 7196, 7197, 7198, -1, 7196, 7199, 7197, -1, + 7196, 7200, 7199, -1, 7196, 7198, 7200, -1, + 7201, 7194, 7202, -1, 7201, 7202, 7203, -1, + 7204, 7205, 7206, -1, 7204, 7206, 7202, -1, + 7206, 7203, 7202, -1, 7203, 7206, 7207, -1, + 7207, 7208, 7203, -1, 7208, 7207, 7209, -1, + 7209, 7210, 7208, -1, 7210, 7209, 7211, -1, + 7211, 7212, 7210, -1, 7212, 7211, 7213, -1, + 7213, 7214, 7212, -1, 7214, 7213, 7215, -1, + 7215, 7216, 7214, -1, 7216, 7215, 7217, -1, + 7217, 7218, 7216, -1, 7218, 7217, 7219, -1, + 7219, 7220, 7218, -1, 7220, 7219, 7221, -1, + 7221, 7222, 7220, -1, 7222, 7221, 7223, -1, + 7223, 7224, 7222, -1, 7224, 7223, 7225, -1, + 7225, 7226, 7224, -1, 7226, 7225, 7227, -1, + 7227, 7228, 7226, -1, 7228, 7227, 7229, -1, + 7229, 7230, 7228, -1, 7230, 7229, 7231, -1, + 7231, 7232, 7230, -1, 7232, 7231, 7233, -1, + 7233, 7234, 7232, -1, 7234, 7233, 7235, -1, + 7235, 7236, 7234, -1, 7236, 7235, 7237, -1, + 7237, 7238, 7236, -1, 7238, 7237, 7239, -1, + 7239, 7240, 7238, -1, 7240, 7239, 7241, -1, + 7240, 7241, 7242, -1, 7242, 7243, 7240, -1, + 7243, 7242, 7244, -1, 7244, 7245, 7243, -1, + 7245, 7244, 7246, -1, 7246, 7247, 7245, -1, + 7247, 7246, 7248, -1, 7248, 7249, 7247, -1, + 7249, 7248, 7250, -1, 7250, 7251, 7249, -1, + 7251, 7250, 7252, -1, 7252, 7253, 7251, -1, + 7253, 7252, 7254, -1, 7254, 7255, 7253, -1, + 7255, 7254, 7256, -1, 7256, 7257, 7255, -1, + 7257, 7256, 7258, -1, 7258, 7259, 7257, -1, + 7259, 7258, 7260, -1, 7260, 7261, 7259, -1, + 7261, 7260, 7262, -1, 7262, 7263, 7261, -1, + 7263, 7262, 7264, -1, 7264, 7265, 7263, -1, + 7265, 7264, 7266, -1, 7266, 7267, 7265, -1, + 7267, 7266, 7268, -1, 7268, 7269, 7267, -1, + 7269, 7268, 7270, -1, 7270, 7271, 7269, -1, + 7271, 7270, 7272, -1, 7272, 7273, 7271, -1, + 7273, 7272, 7274, -1, 7274, 7275, 7273, -1, + 7276, 7273, 7275, -1, 7275, 7277, 7276, -1, + 7277, 7278, 7279, -1, 7277, 7275, 7278, -1, + 7280, 7278, 7275, -1, 7280, 7279, 7278, -1, + 7280, 7281, 7279, -1, 7280, 7275, 7281, -1, + 7282, 7281, 7275, -1, 7275, 7274, 7282, -1, + 7283, 7284, 7282, -1, 7282, 7285, 7283, -1, + 7285, 7282, 7274, -1, 7274, 7286, 7285, -1, + 7286, 7274, 7272, -1, 7272, 7287, 7286, -1, + 7287, 7272, 7270, -1, 7270, 7288, 7287, -1, + 7288, 7270, 7268, -1, 7268, 7289, 7288, -1, + 7289, 7268, 7266, -1, 7266, 7290, 7289, -1, + 7290, 7266, 7264, -1, 7264, 7291, 7290, -1, + 7291, 7264, 7262, -1, 7262, 7292, 7291, -1, + 7292, 7262, 7260, -1, 7260, 7293, 7292, -1, + 7293, 7260, 7258, -1, 7258, 7294, 7293, -1, + 7294, 7258, 7256, -1, 7256, 7295, 7294, -1, + 7295, 7256, 7254, -1, 7254, 7296, 7295, -1, + 7296, 7254, 7252, -1, 7252, 7297, 7296, -1, + 7297, 7252, 7250, -1, 7250, 7298, 7297, -1, + 7298, 7250, 7248, -1, 7248, 7299, 7298, -1, + 7299, 7248, 7246, -1, 7246, 7300, 7299, -1, + 7300, 7246, 7244, -1, 7244, 7301, 7300, -1, + 7301, 7244, 7242, -1, 7242, 7302, 7301, -1, + 7302, 7242, 7241, -1, 7241, 7303, 7302, -1, + 7241, 7304, 7303, -1, 7304, 7241, 7239, -1, + 7239, 7305, 7304, -1, 7305, 7239, 7237, -1, + 7237, 7306, 7305, -1, 7306, 7237, 7235, -1, + 7235, 7307, 7306, -1, 7307, 7235, 7233, -1, + 7233, 7308, 7307, -1, 7308, 7233, 7231, -1, + 7231, 7309, 7308, -1, 7309, 7231, 7229, -1, + 7229, 7310, 7309, -1, 7310, 7229, 7227, -1, + 7227, 7311, 7310, -1, 7311, 7227, 7225, -1, + 7225, 7312, 7311, -1, 7312, 7225, 7223, -1, + 7223, 7313, 7312, -1, 7313, 7223, 7221, -1, + 7221, 7314, 7313, -1, 7314, 7221, 7219, -1, + 7219, 7315, 7314, -1, 7315, 7219, 7217, -1, + 7217, 7316, 7315, -1, 7316, 7217, 7215, -1, + 7215, 7317, 7316, -1, 7317, 7215, 7213, -1, + 7213, 7318, 7317, -1, 7318, 7213, 7211, -1, + 7211, 7319, 7318, -1, 7319, 7211, 7209, -1, + 7209, 7320, 7319, -1, 7320, 7209, 7207, -1, + 7207, 7321, 7320, -1, 7321, 7207, 7206, -1, + 7206, 7198, 7321, -1, 7198, 7206, 7205, -1, + 7205, 7200, 7198, -1, 7205, 7199, 7200, -1, + 7205, 7204, 7199, -1, 7204, 7202, 7199, -1, + 7199, 7202, 7194, -1, 7194, 7193, 7322, -1, + 7323, 7322, 7193, -1, 7193, 7324, 7323, -1, + 7193, 7195, 7324, -1, 7195, 7325, 7324, -1, + 7325, 7195, 7194, -1, 7325, 7194, 7201, -1, + 7201, 7203, 7325, -1, 7203, 7324, 7325, -1, + 7324, 7203, 7208, -1, 7208, 7326, 7324, -1, + 7326, 7208, 7210, -1, 7210, 7327, 7326, -1, + 7327, 7210, 7212, -1, 7212, 7328, 7327, -1, + 7328, 7212, 7214, -1, 7214, 7329, 7328, -1, + 7329, 7214, 7216, -1, 7216, 7330, 7329, -1, + 7330, 7216, 7218, -1, 7218, 7331, 7330, -1, + 7331, 7218, 7220, -1, 7220, 7332, 7331, -1, + 7332, 7220, 7222, -1, 7222, 7333, 7332, -1, + 7333, 7222, 7224, -1, 7224, 7334, 7333, -1, + 7334, 7224, 7226, -1, 7226, 7335, 7334, -1, + 7335, 7226, 7228, -1, 7228, 7336, 7335, -1, + 7336, 7228, 7230, -1, 7230, 7337, 7336, -1, + 7337, 7230, 7232, -1, 7232, 7338, 7337, -1, + 7338, 7232, 7234, -1, 7234, 7339, 7338, -1, + 7339, 7234, 7236, -1, 7236, 7340, 7339, -1, + 7340, 7236, 7238, -1, 7238, 7341, 7340, -1, + 7341, 7238, 7240, -1, 7341, 7240, 7243, -1, + 7243, 7342, 7341, -1, 7342, 7243, 7245, -1, + 7245, 7343, 7342, -1, 7343, 7245, 7247, -1, + 7247, 7344, 7343, -1, 7344, 7247, 7249, -1, + 7249, 7345, 7344, -1, 7345, 7249, 7251, -1, + 7251, 7346, 7345, -1, 7346, 7251, 7253, -1, + 7253, 7347, 7346, -1, 7347, 7253, 7255, -1, + 7255, 7348, 7347, -1, 7348, 7255, 7257, -1, + 7257, 7349, 7348, -1, 7349, 7257, 7259, -1, + 7259, 7350, 7349, -1, 7350, 7259, 7261, -1, + 7261, 7351, 7350, -1, 7351, 7261, 7263, -1, + 7263, 7352, 7351, -1, 7352, 7263, 7265, -1, + 7265, 7353, 7352, -1, 7353, 7265, 7267, -1, + 7267, 7354, 7353, -1, 7354, 7267, 7269, -1, + 7269, 7355, 7354, -1, 7355, 7269, 7271, -1, + 7271, 7356, 7355, -1, 7356, 7271, 7273, -1, + 7273, 7276, 7356, -1, 7357, 7358, 7359, -1, + 7358, 7357, 7360, -1, 7361, 7362, 7363, -1, + 7364, 7365, 7366, -1, 7366, 7367, 7364, -1, + 7367, 7366, 7368, -1, 7368, 7369, 7367, -1, + 7369, 7368, 7370, -1, 7370, 7371, 7369, -1, + 7371, 7370, 7372, -1, 7372, 7373, 7371, -1, + 7373, 7372, 7374, -1, 7374, 7375, 7373, -1, + 7375, 7374, 7376, -1, 7376, 7377, 7375, -1, + 7377, 7376, 7378, -1, 7378, 7379, 7377, -1, + 7379, 7378, 7380, -1, 7380, 7381, 7379, -1, + 7381, 7380, 7382, -1, 7382, 7383, 7381, -1, + 7383, 7382, 7384, -1, 7384, 7385, 7383, -1, + 7385, 7384, 7386, -1, 7386, 7387, 7385, -1, + 7387, 7386, 7388, -1, 7387, 7388, 7389, -1, + 7389, 7390, 7387, -1, 7390, 7389, 7391, -1, + 7391, 7392, 7390, -1, 7392, 7391, 7393, -1, + 7393, 7394, 7392, -1, 7394, 7393, 7395, -1, + 7395, 7396, 7394, -1, 7396, 7395, 7397, -1, + 7397, 7398, 7396, -1, 7398, 7397, 7399, -1, + 7399, 7400, 7398, -1, 7400, 7399, 7401, -1, + 7401, 7402, 7400, -1, 7402, 7401, 7403, -1, + 7403, 7404, 7402, -1, 7404, 7403, 7405, -1, + 7405, 7406, 7404, -1, 7406, 7405, 7407, -1, + 7407, 7408, 7406, -1, 7408, 7407, 7409, -1, + 7409, 7410, 7408, -1, 7410, 7409, 7411, -1, + 7411, 7412, 7410, -1, 7412, 7411, 7363, -1, + 7363, 7362, 7412, -1, 7413, 7412, 7362, -1, + 7362, 7360, 7413, -1, 7362, 7361, 7360, -1, + 7361, 7358, 7360, -1, 7361, 7363, 7358, -1, + 7363, 7359, 7358, -1, 7363, 7414, 7359, -1, + 7414, 7363, 7411, -1, 7411, 7415, 7414, -1, + 7415, 7411, 7409, -1, 7409, 7416, 7415, -1, + 7416, 7409, 7407, -1, 7407, 7417, 7416, -1, + 7417, 7407, 7405, -1, 7405, 7418, 7417, -1, + 7418, 7405, 7403, -1, 7403, 7419, 7418, -1, + 7419, 7403, 7401, -1, 7401, 7420, 7419, -1, + 7420, 7401, 7399, -1, 7399, 7421, 7420, -1, + 7421, 7399, 7397, -1, 7397, 7422, 7421, -1, + 7422, 7397, 7395, -1, 7395, 7423, 7422, -1, + 7423, 7395, 7393, -1, 7393, 7424, 7423, -1, + 7424, 7393, 7391, -1, 7391, 7425, 7424, -1, + 7425, 7391, 7389, -1, 7389, 7426, 7425, -1, + 7426, 7389, 7388, -1, 7388, 7427, 7426, -1, + 7388, 7428, 7427, -1, 7428, 7388, 7386, -1, + 7386, 7429, 7428, -1, 7429, 7386, 7384, -1, + 7384, 7430, 7429, -1, 7430, 7384, 7382, -1, + 7382, 7431, 7430, -1, 7431, 7382, 7380, -1, + 7380, 7432, 7431, -1, 7432, 7380, 7378, -1, + 7378, 7433, 7432, -1, 7433, 7378, 7376, -1, + 7376, 7434, 7433, -1, 7434, 7376, 7374, -1, + 7374, 7435, 7434, -1, 7435, 7374, 7372, -1, + 7372, 7436, 7435, -1, 7436, 7372, 7370, -1, + 7370, 7437, 7436, -1, 7437, 7370, 7368, -1, + 7368, 7438, 7437, -1, 7438, 7368, 7366, -1, + 7366, 7439, 7438, -1, 7439, 7366, 7365, -1, + 7365, 7440, 7439, -1, 7440, 7441, 7442, -1, + 7442, 7439, 7440, -1, 7439, 7442, 7443, -1, + 7443, 7438, 7439, -1, 7438, 7443, 7444, -1, + 7444, 7437, 7438, -1, 7437, 7444, 7445, -1, + 7445, 7436, 7437, -1, 7436, 7445, 7446, -1, + 7446, 7435, 7436, -1, 7435, 7446, 7447, -1, + 7447, 7434, 7435, -1, 7434, 7447, 7448, -1, + 7448, 7433, 7434, -1, 7433, 7448, 7449, -1, + 7449, 7432, 7433, -1, 7432, 7449, 7450, -1, + 7450, 7431, 7432, -1, 7431, 7450, 7451, -1, + 7451, 7430, 7431, -1, 7430, 7451, 7452, -1, + 7452, 7429, 7430, -1, 7429, 7452, 7453, -1, + 7453, 7428, 7429, -1, 7428, 7453, 7454, -1, + 7454, 7427, 7428, -1, 7427, 7454, 7455, -1, + 7427, 7455, 7456, -1, 7456, 7426, 7427, -1, + 7426, 7456, 7457, -1, 7457, 7425, 7426, -1, + 7425, 7457, 7458, -1, 7458, 7424, 7425, -1, + 7424, 7458, 7459, -1, 7459, 7423, 7424, -1, + 7423, 7459, 7460, -1, 7460, 7422, 7423, -1, + 7422, 7460, 7461, -1, 7461, 7421, 7422, -1, + 7421, 7461, 7462, -1, 7462, 7420, 7421, -1, + 7420, 7462, 7463, -1, 7463, 7419, 7420, -1, + 7419, 7463, 7464, -1, 7464, 7418, 7419, -1, + 7418, 7464, 7465, -1, 7465, 7417, 7418, -1, + 7417, 7465, 7466, -1, 7466, 7416, 7417, -1, + 7416, 7466, 7467, -1, 7467, 7415, 7416, -1, + 7415, 7467, 7468, -1, 7468, 7414, 7415, -1, + 7414, 7468, 7469, -1, 7469, 7359, 7414, -1, + 7359, 7469, 7470, -1, 7470, 7471, 7359, -1, + 7472, 7471, 7470, -1, 7472, 7470, 7473, -1, + 7470, 7276, 7473, -1, 7470, 7356, 7276, -1, + 7356, 7470, 7469, -1, 7469, 7355, 7356, -1, + 7355, 7469, 7468, -1, 7468, 7354, 7355, -1, + 7354, 7468, 7467, -1, 7467, 7353, 7354, -1, + 7353, 7467, 7466, -1, 7466, 7352, 7353, -1, + 7352, 7466, 7465, -1, 7465, 7351, 7352, -1, + 7351, 7465, 7464, -1, 7464, 7350, 7351, -1, + 7350, 7464, 7463, -1, 7463, 7349, 7350, -1, + 7349, 7463, 7462, -1, 7462, 7348, 7349, -1, + 7348, 7462, 7461, -1, 7461, 7347, 7348, -1, + 7347, 7461, 7460, -1, 7460, 7346, 7347, -1, + 7346, 7460, 7459, -1, 7459, 7345, 7346, -1, + 7345, 7459, 7458, -1, 7458, 7344, 7345, -1, + 7344, 7458, 7457, -1, 7457, 7343, 7344, -1, + 7343, 7457, 7456, -1, 7456, 7342, 7343, -1, + 7342, 7456, 7455, -1, 7455, 7341, 7342, -1, + 7455, 7340, 7341, -1, 7340, 7455, 7454, -1, + 7454, 7339, 7340, -1, 7339, 7454, 7453, -1, + 7453, 7338, 7339, -1, 7338, 7453, 7452, -1, + 7452, 7337, 7338, -1, 7337, 7452, 7451, -1, + 7451, 7336, 7337, -1, 7336, 7451, 7450, -1, + 7450, 7335, 7336, -1, 7335, 7450, 7449, -1, + 7449, 7334, 7335, -1, 7334, 7449, 7448, -1, + 7448, 7333, 7334, -1, 7333, 7448, 7447, -1, + 7447, 7332, 7333, -1, 7332, 7447, 7446, -1, + 7446, 7331, 7332, -1, 7331, 7446, 7445, -1, + 7445, 7330, 7331, -1, 7330, 7445, 7444, -1, + 7444, 7329, 7330, -1, 7329, 7444, 7443, -1, + 7443, 7328, 7329, -1, 7328, 7443, 7442, -1, + 7442, 7327, 7328, -1, 7327, 7442, 7441, -1, + 7441, 7326, 7327, -1, 7326, 7441, 7474, -1, + 7474, 7324, 7326, -1, 7474, 7323, 7324, -1, + 7475, 7323, 7474, -1, 7475, 7322, 7323, -1, + 7476, 7477, 7478, -1, 7477, 7476, 7322, -1, + 7477, 7322, 7475, -1, 7475, 7474, 7477, -1, + 7474, 7478, 7477, -1, 7478, 7474, 7441, -1, + 7441, 7440, 7478, -1, 7479, 7480, 7478, -1, + 7479, 7478, 7440, -1, 7440, 7365, 7479, -1, + 7479, 7481, 7482, -1, 7481, 7479, 7365, -1, + 7365, 7364, 7481, -1, 7483, 7484, 7481, -1, + 7483, 7481, 7364, -1, 7364, 7485, 7483, -1, + 7485, 7364, 7367, -1, 7367, 7486, 7485, -1, + 7486, 7367, 7369, -1, 7369, 7487, 7486, -1, + 7487, 7369, 7371, -1, 7371, 7488, 7487, -1, + 7488, 7371, 7373, -1, 7373, 7489, 7488, -1, + 7489, 7373, 7375, -1, 7375, 7490, 7489, -1, + 7490, 7375, 7377, -1, 7377, 7491, 7490, -1, + 7491, 7377, 7379, -1, 7379, 7492, 7491, -1, + 7492, 7379, 7381, -1, 7381, 7493, 7492, -1, + 7493, 7381, 7383, -1, 7383, 7494, 7493, -1, + 7494, 7383, 7385, -1, 7385, 7495, 7494, -1, + 7495, 7385, 7387, -1, 7495, 7387, 7390, -1, + 7390, 7496, 7495, -1, 7496, 7390, 7392, -1, + 7392, 7497, 7496, -1, 7497, 7392, 7394, -1, + 7394, 7498, 7497, -1, 7498, 7394, 7396, -1, + 7396, 7499, 7498, -1, 7499, 7396, 7398, -1, + 7398, 7500, 7499, -1, 7500, 7398, 7400, -1, + 7400, 7501, 7500, -1, 7501, 7400, 7402, -1, + 7402, 7502, 7501, -1, 7502, 7402, 7404, -1, + 7404, 7503, 7502, -1, 7503, 7404, 7406, -1, + 7406, 7504, 7503, -1, 7504, 7406, 7408, -1, + 7408, 7505, 7504, -1, 7505, 7408, 7410, -1, + 7410, 7506, 7505, -1, 7506, 7410, 7412, -1, + 7506, 7412, 7507, -1, 7507, 7508, 7509, -1, + 7508, 7507, 7412, -1, 7508, 7412, 7413, -1, + 7508, 7413, 7360, -1, 7360, 7509, 7508, -1, + 7510, 7511, 7512, -1, 7512, 7513, 7510, -1, + 7513, 7512, 7514, -1, 7514, 7515, 7513, -1, + 7515, 7514, 7516, -1, 7516, 7517, 7515, -1, + 7517, 7516, 7518, -1, 7518, 7519, 7517, -1, + 7519, 7518, 7520, -1, 7520, 7521, 7519, -1, + 7521, 7520, 7522, -1, 7522, 7523, 7521, -1, + 7523, 7522, 7524, -1, 7524, 7525, 7523, -1, + 7524, 7526, 7525, -1, 7526, 7524, 7527, -1, + 7527, 7528, 7526, -1, 7528, 7527, 7529, -1, + 7529, 7530, 7528, -1, 7530, 7529, 7531, -1, + 7531, 7532, 7530, -1, 7532, 7531, 7533, -1, + 7533, 7534, 7532, -1, 7534, 7533, 7535, -1, + 7535, 7536, 7534, -1, 7536, 7535, 7537, -1, + 7537, 7538, 7536, -1, 7539, 7540, 7541, -1, + 7539, 7542, 7540, -1, 7539, 7543, 7542, -1, + 7539, 7541, 7543, -1, 7544, 7543, 7541, -1, + 7544, 7541, 7538, -1, 7538, 7537, 7544, -1, + 7545, 7546, 7547, -1, 7546, 7548, 7547, -1, + 7544, 7547, 7548, -1, 7547, 7544, 7537, -1, + 7537, 7549, 7547, -1, 7549, 7537, 7535, -1, + 7535, 7550, 7549, -1, 7550, 7535, 7533, -1, + 7533, 7551, 7550, -1, 7551, 7533, 7531, -1, + 7531, 7552, 7551, -1, 7552, 7531, 7529, -1, + 7529, 7553, 7552, -1, 7553, 7529, 7527, -1, + 7527, 7554, 7553, -1, 7554, 7527, 7524, -1, + 7554, 7524, 7522, -1, 7522, 7555, 7554, -1, + 7555, 7522, 7520, -1, 7520, 7556, 7555, -1, + 7556, 7520, 7518, -1, 7518, 7557, 7556, -1, + 7557, 7518, 7516, -1, 7516, 7558, 7557, -1, + 7558, 7516, 7514, -1, 7514, 7559, 7558, -1, + 7559, 7514, 7512, -1, 7512, 7560, 7559, -1, + 7560, 7512, 7511, -1, 7511, 7561, 7560, -1, + 7562, 7561, 7511, -1, 7562, 7511, 7563, -1, + 7511, 7564, 7563, -1, 7511, 7510, 7564, -1, + 7565, 7566, 7567, -1, 7565, 7567, 7568, -1, + 7568, 7569, 7565, -1, 7569, 7568, 7570, -1, + 7570, 7571, 7569, -1, 7571, 7570, 7572, -1, + 7572, 7573, 7571, -1, 7573, 7572, 7574, -1, + 7574, 7575, 7573, -1, 7575, 7574, 7576, -1, + 7576, 7577, 7575, -1, 7577, 7576, 7578, -1, + 7578, 7579, 7577, -1, 7579, 7578, 7580, -1, + 7580, 7581, 7579, -1, 7581, 7580, 7582, -1, + 7582, 7583, 7581, -1, 7583, 7582, 7584, -1, + 7584, 7585, 7583, -1, 7585, 7584, 7586, -1, + 7585, 7586, 7587, -1, 7587, 7588, 7585, -1, + 7588, 7587, 7589, -1, 7589, 7590, 7588, -1, + 7590, 7589, 7591, -1, 7591, 7592, 7590, -1, + 7592, 7591, 7593, -1, 7593, 7594, 7592, -1, + 7594, 7593, 7595, -1, 7595, 7596, 7594, -1, + 7596, 7595, 7597, -1, 7597, 7598, 7596, -1, + 7598, 7597, 7599, -1, 7599, 7600, 7598, -1, + 7600, 7599, 7601, -1, 7601, 7602, 7600, -1, + 7602, 7601, 7603, -1, 7603, 7604, 7602, -1, + 7604, 7603, 7605, -1, 7604, 7605, 7606, -1, + 7607, 7606, 7605, -1, 7606, 7607, 7608, -1, + 7609, 7608, 7610, -1, 7609, 7611, 7608, -1, + 7611, 7606, 7608, -1, 7611, 7604, 7606, -1, + 7611, 7609, 7604, -1, 7609, 7610, 7604, -1, + 7564, 7604, 7610, -1, 7564, 7602, 7604, -1, + 7602, 7564, 7510, -1, 7510, 7600, 7602, -1, + 7600, 7510, 7513, -1, 7513, 7598, 7600, -1, + 7598, 7513, 7515, -1, 7515, 7596, 7598, -1, + 7596, 7515, 7517, -1, 7517, 7594, 7596, -1, + 7594, 7517, 7519, -1, 7519, 7592, 7594, -1, + 7592, 7519, 7521, -1, 7521, 7590, 7592, -1, + 7590, 7521, 7523, -1, 7523, 7588, 7590, -1, + 7588, 7523, 7525, -1, 7525, 7585, 7588, -1, + 7525, 7583, 7585, -1, 7583, 7525, 7526, -1, + 7526, 7581, 7583, -1, 7581, 7526, 7528, -1, + 7528, 7579, 7581, -1, 7579, 7528, 7530, -1, + 7530, 7577, 7579, -1, 7577, 7530, 7532, -1, + 7532, 7575, 7577, -1, 7575, 7532, 7534, -1, + 7534, 7573, 7575, -1, 7573, 7534, 7536, -1, + 7536, 7571, 7573, -1, 7571, 7536, 7538, -1, + 7538, 7569, 7571, -1, 7569, 7538, 7541, -1, + 7541, 7565, 7569, -1, 7541, 7540, 7565, -1, + 7612, 7565, 7540, -1, 7612, 7540, 7542, -1, + 7612, 7542, 7613, -1, 7613, 7565, 7612, -1, + 7613, 7566, 7565, -1, 7613, 7542, 7566, -1, + 7566, 7542, 7614, -1, 7614, 7567, 7566, -1, + 7614, 7615, 7567, -1, 7614, 7616, 7615, -1, + 7616, 7614, 7542, -1, 7617, 7618, 7619, -1, + 7618, 7617, 7616, -1, 7620, 7542, 7543, -1, + 7543, 7621, 7620, -1, 7621, 7543, 7544, -1, + 7621, 7544, 7548, -1, 7548, 7620, 7621, -1, + 7548, 7546, 7620, -1, 7546, 7545, 7620, -1, + 7545, 7622, 7620, -1, 7545, 7547, 7622, -1, + 7623, 7622, 7547, -1, 7623, 7547, 7549, -1, + 7549, 7624, 7623, -1, 7624, 7549, 7550, -1, + 7550, 7625, 7624, -1, 7625, 7550, 7551, -1, + 7551, 7626, 7625, -1, 7626, 7551, 7552, -1, + 7552, 7627, 7626, -1, 7627, 7552, 7553, -1, + 7553, 7628, 7627, -1, 7628, 7553, 7554, -1, + 7628, 7554, 7555, -1, 7555, 7629, 7628, -1, + 7629, 7555, 7556, -1, 7556, 7630, 7629, -1, + 7630, 7556, 7557, -1, 7557, 7631, 7630, -1, + 7631, 7557, 7558, -1, 7558, 7632, 7631, -1, + 7632, 7558, 7559, -1, 7559, 7633, 7632, -1, + 7633, 7559, 7560, -1, 7634, 7635, 7633, -1, + 7634, 7633, 7636, -1, 7633, 7560, 7636, -1, + 7637, 7636, 7560, -1, 7637, 7638, 7636, -1, + 7637, 7639, 7638, -1, 7637, 7560, 7639, -1, + 7639, 7560, 7561, -1, 7561, 7638, 7639, -1, + 7561, 7562, 7638, -1, 7562, 7563, 7638, -1, + 7563, 7640, 7638, -1, 7640, 7563, 7564, -1, + 7640, 7564, 7610, -1, 7640, 7610, 7608, -1, + 7608, 7638, 7640, -1, 7509, 7608, 7607, -1, + 7607, 7641, 7509, -1, 7607, 7605, 7641, -1, + 7641, 7605, 7642, -1, 7642, 7509, 7641, -1, + 7642, 7643, 7509, -1, 7643, 7507, 7509, -1, + 7643, 7506, 7507, -1, 7643, 7642, 7506, -1, + 7506, 7642, 7605, -1, 7605, 7505, 7506, -1, + 7505, 7605, 7603, -1, 7603, 7504, 7505, -1, + 7504, 7603, 7601, -1, 7601, 7503, 7504, -1, + 7503, 7601, 7599, -1, 7599, 7502, 7503, -1, + 7502, 7599, 7597, -1, 7597, 7501, 7502, -1, + 7501, 7597, 7595, -1, 7595, 7500, 7501, -1, + 7500, 7595, 7593, -1, 7593, 7499, 7500, -1, + 7499, 7593, 7591, -1, 7591, 7498, 7499, -1, + 7498, 7591, 7589, -1, 7589, 7497, 7498, -1, + 7497, 7589, 7587, -1, 7587, 7496, 7497, -1, + 7496, 7587, 7586, -1, 7586, 7495, 7496, -1, + 7586, 7494, 7495, -1, 7494, 7586, 7584, -1, + 7584, 7493, 7494, -1, 7493, 7584, 7582, -1, + 7582, 7492, 7493, -1, 7492, 7582, 7580, -1, + 7580, 7491, 7492, -1, 7491, 7580, 7578, -1, + 7578, 7490, 7491, -1, 7490, 7578, 7576, -1, + 7576, 7489, 7490, -1, 7489, 7576, 7574, -1, + 7574, 7488, 7489, -1, 7488, 7574, 7572, -1, + 7572, 7487, 7488, -1, 7487, 7572, 7570, -1, + 7570, 7486, 7487, -1, 7486, 7570, 7568, -1, + 7568, 7485, 7486, -1, 7485, 7568, 7567, -1, + 7567, 7483, 7485, -1, 7567, 7615, 7483, -1, + 7644, 7483, 7615, -1, 7644, 7615, 7616, -1, + 7644, 7616, 7645, -1, 7645, 7483, 7644, -1, + 7645, 7484, 7483, -1, 7645, 7616, 7484, -1, + 7484, 7616, 7617, -1, 7619, 7482, 7481, -1, + 7482, 7619, 7618, -1, 7482, 7618, 7646, -1, + 7646, 7479, 7482, -1, 7646, 7480, 7479, -1, + 7646, 7618, 7480, -1, 7480, 7618, 7647, -1, + 7647, 7478, 7480, -1, 7647, 7476, 7478, -1, + 7647, 7322, 7476, -1, 7322, 7647, 7618, -1, + 824, 7620, 7622, -1, 7622, 7648, 824, -1, + 7648, 7622, 7623, -1, 7648, 7623, 7649, -1, + 7649, 824, 7648, -1, 7649, 825, 824, -1, + 7649, 821, 825, -1, 821, 7649, 7623, -1, + 821, 7623, 7624, -1, 7624, 819, 821, -1, + 819, 7624, 7625, -1, 7625, 817, 819, -1, + 817, 7625, 7626, -1, 7626, 815, 817, -1, + 815, 7626, 7627, -1, 7627, 814, 815, -1, + 814, 7627, 7628, -1, 814, 7628, 7629, -1, + 7629, 812, 814, -1, 812, 7629, 7630, -1, + 7630, 810, 812, -1, 810, 7630, 7631, -1, + 7631, 808, 810, -1, 808, 7631, 7632, -1, + 7632, 806, 808, -1, 806, 7632, 7633, -1, + 806, 7633, 7635, -1, 7635, 805, 806, -1, + 7635, 803, 805, -1, 7635, 7634, 803, -1, + 7634, 7636, 803, -1, 803, 7636, 7638, -1, + 782, 804, 803, -1, 7650, 804, 782, -1, + 7650, 807, 804, -1, 7650, 7651, 807, -1, + 7651, 7650, 782, -1, 7651, 782, 781, -1, + 7651, 781, 783, -1, 783, 807, 7651, -1, + 783, 809, 807, -1, 809, 783, 795, -1, + 795, 811, 809, -1, 811, 795, 796, -1, + 796, 813, 811, -1, 796, 816, 813, -1, + 816, 796, 797, -1, 797, 818, 816, -1, + 818, 797, 798, -1, 798, 820, 818, -1, + 798, 7652, 820, -1, 7652, 798, 800, -1, + 7652, 800, 801, -1, 7652, 801, 7653, -1, + 7653, 820, 7652, -1, 7653, 822, 820, -1, + 7653, 801, 822, -1, 801, 824, 822, -1, + 7150, 7654, 7655, -1, 7654, 7150, 7155, -1, + 7155, 7157, 7654, -1, 7157, 829, 7654, -1, + 7656, 7654, 829, -1, 7656, 7655, 7654, -1, + 7657, 7655, 7656, -1, 7656, 829, 7657, -1, + 7657, 829, 831, -1, 831, 7655, 7657, -1, + 831, 7658, 7655, -1, 7658, 831, 830, -1, + 7658, 830, 6362, -1, 6362, 7655, 7658, -1, + 7655, 6362, 6364, -1, 6364, 7659, 7660, -1, + 7659, 6364, 6367, -1, 6367, 6368, 7659, -1, + 6368, 2261, 7659, -1, 7661, 7659, 2261, -1, + 7661, 7660, 7659, -1, 7662, 7660, 7661, -1, + 7661, 2261, 7662, -1, 7662, 2261, 2260, -1, + 2260, 7660, 7662, -1, 2260, 7663, 7660, -1, + 7663, 2260, 2259, -1, 7663, 2259, 3103, -1, + 3103, 7660, 7663, -1, 3103, 7664, 7660, -1, + 7664, 3103, 3045, -1, 7664, 3045, 3047, -1, + 3047, 3050, 7664, -1, 3050, 7660, 7664, -1, + 7665, 3050, 3051, -1, 7666, 7665, 3051, -1, + 3051, 3053, 7666, -1, 7666, 3053, 3055, -1, + 3055, 7665, 7666, -1, 3055, 7667, 7665, -1, + 7667, 3055, 3054, -1, 7667, 3054, 3057, -1, + 3057, 7665, 7667, -1, 3057, 7668, 7665, -1, + 7668, 3057, 3056, -1, 7668, 3056, 4186, -1, + 4186, 4187, 7668, -1, 4187, 7665, 7668, -1, + 7669, 4187, 4188, -1, 7670, 7669, 4188, -1, + 4188, 4190, 7670, -1, 7670, 4190, 4192, -1, + 4192, 7669, 7670, -1, 4192, 7671, 7669, -1, + 7671, 4192, 4191, -1, 7672, 7671, 4191, -1, + 7672, 7669, 7671, -1, 7672, 7673, 7669, -1, + 7672, 4191, 7673, -1, 7674, 7673, 4191, -1, + 7674, 4191, 4193, -1, 4193, 4194, 7674, -1, + 7675, 7676, 7674, -1, 7675, 7674, 4194, -1, + 4194, 4195, 7675, -1, 7677, 7678, 7675, -1, + 7677, 7675, 4195, -1, 4195, 4196, 7677, -1, + 7679, 7680, 7677, -1, 7679, 7677, 4196, -1, + 4196, 7681, 7679, -1, 7681, 4196, 4197, -1, + 4197, 7682, 7681, -1, 7682, 4197, 4198, -1, + 4198, 7683, 7682, -1, 7683, 4198, 4199, -1, + 4199, 7684, 7683, -1, 7684, 4199, 4200, -1, + 4200, 7685, 7684, -1, 7685, 4200, 4201, -1, + 4201, 7686, 7685, -1, 7686, 4201, 4202, -1, + 4202, 7687, 7686, -1, 7687, 4202, 4203, -1, + 4203, 7688, 7687, -1, 7688, 4203, 4204, -1, + 4204, 7689, 7688, -1, 7689, 4204, 4205, -1, + 4205, 7690, 7689, -1, 7690, 4205, 4206, -1, + 4206, 7691, 7690, -1, 7691, 4206, 4207, -1, + 4207, 7692, 7691, -1, 7692, 4207, 4208, -1, + 4208, 7693, 7692, -1, 7693, 4208, 4209, -1, + 4209, 7694, 7693, -1, 7694, 4209, 2992, -1, + 2992, 7695, 7694, -1, 7695, 2992, 2991, -1, + 2991, 7696, 7695, -1, 7696, 2991, 2989, -1, + 2989, 7697, 7696, -1, 7697, 2989, 2988, -1, + 2988, 7698, 7697, -1, 7698, 2988, 2987, -1, + 2987, 7699, 7698, -1, 7699, 2987, 2986, -1, + 2986, 7700, 7699, -1, 7700, 2986, 2985, -1, + 2985, 7701, 7700, -1, 7701, 2985, 2984, -1, + 2984, 7702, 7701, -1, 7702, 2984, 2983, -1, + 2983, 7703, 7702, -1, 7703, 2983, 2982, -1, + 2982, 7704, 7703, -1, 7704, 2982, 2981, -1, + 2981, 7705, 7704, -1, 7705, 2981, 2980, -1, + 2980, 7706, 7705, -1, 7706, 2980, 2979, -1, + 2979, 7707, 7706, -1, 7707, 2979, 2978, -1, + 2978, 7708, 7707, -1, 7708, 2978, 2977, -1, + 2977, 7709, 7708, -1, 7709, 2977, 2976, -1, + 2976, 7710, 7709, -1, 7710, 2976, 2975, -1, + 2975, 7711, 7710, -1, 7711, 2975, 2974, -1, + 2974, 7712, 7711, -1, 7712, 2974, 2973, -1, + 2973, 7713, 7712, -1, 7713, 2973, 2972, -1, + 2972, 7714, 7713, -1, 7714, 2972, 2971, -1, + 2971, 7715, 7714, -1, 7715, 2971, 2970, -1, + 2970, 7716, 7715, -1, 7716, 2970, 2969, -1, + 2969, 7717, 7716, -1, 7717, 2969, 2968, -1, + 2968, 7718, 7717, -1, 7718, 2968, 2967, -1, + 2967, 7719, 7718, -1, 7719, 2967, 2966, -1, + 2966, 7720, 7719, -1, 7720, 2966, 2965, -1, + 2965, 7721, 7720, -1, 7721, 2965, 2964, -1, + 2964, 7722, 7721, -1, 7722, 2964, 2963, -1, + 2963, 7723, 7722, -1, 7723, 2963, 2962, -1, + 2962, 7724, 7723, -1, 7724, 2962, 2961, -1, + 7724, 2961, 2960, -1, 2960, 7725, 7724, -1, + 7725, 2960, 2959, -1, 2959, 7726, 7725, -1, + 7726, 2959, 2958, -1, 2958, 7727, 7726, -1, + 7727, 2958, 2957, -1, 2957, 7728, 7727, -1, + 7728, 2957, 2956, -1, 2956, 7729, 7728, -1, + 7729, 2956, 2955, -1, 2955, 7730, 7729, -1, + 7730, 2955, 2954, -1, 2954, 7731, 7730, -1, + 7731, 2954, 2953, -1, 2953, 7732, 7731, -1, + 7732, 2953, 2952, -1, 2952, 7733, 7732, -1, + 7733, 2952, 2951, -1, 2951, 7734, 7733, -1, + 7734, 2951, 2950, -1, 2950, 7735, 7734, -1, + 7735, 2950, 2949, -1, 2949, 7736, 7735, -1, + 7736, 2949, 2948, -1, 2948, 7737, 7736, -1, + 7737, 2948, 2947, -1, 2947, 7738, 7737, -1, + 7738, 2947, 2946, -1, 2946, 7739, 7738, -1, + 7739, 2946, 2945, -1, 2945, 7740, 7739, -1, + 7740, 2945, 2944, -1, 2944, 7741, 7740, -1, + 7741, 2944, 2943, -1, 2943, 7742, 7741, -1, + 7742, 2943, 2942, -1, 2942, 7743, 7742, -1, + 7743, 2942, 2941, -1, 2941, 7744, 7743, -1, + 7744, 2941, 2940, -1, 2940, 7745, 7744, -1, + 7745, 2940, 2939, -1, 2939, 7746, 7745, -1, + 7746, 2939, 2938, -1, 2938, 7747, 7746, -1, + 7747, 2938, 2937, -1, 2937, 7748, 7747, -1, + 7748, 2937, 2936, -1, 2936, 7749, 7748, -1, + 7749, 2936, 2935, -1, 2935, 7750, 7749, -1, + 7750, 2935, 2934, -1, 2934, 7751, 7750, -1, + 7751, 2934, 2933, -1, 2933, 7752, 7751, -1, + 7752, 2933, 2817, -1, 2817, 2816, 7752, -1, + 7753, 7752, 2816, -1, 7752, 7753, 7754, -1, + 7754, 7751, 7752, -1, 7751, 7754, 7755, -1, + 7755, 7750, 7751, -1, 7750, 7755, 7756, -1, + 7756, 7749, 7750, -1, 7749, 7756, 7757, -1, + 7757, 7748, 7749, -1, 7748, 7757, 7758, -1, + 7758, 7747, 7748, -1, 7747, 7758, 7759, -1, + 7759, 7746, 7747, -1, 7746, 7759, 7760, -1, + 7760, 7745, 7746, -1, 7745, 7760, 7761, -1, + 7761, 7744, 7745, -1, 7744, 7761, 7762, -1, + 7762, 7743, 7744, -1, 7743, 7762, 7763, -1, + 7763, 7742, 7743, -1, 7742, 7763, 7764, -1, + 7764, 7741, 7742, -1, 7741, 7764, 7765, -1, + 7765, 7740, 7741, -1, 7740, 7765, 7766, -1, + 7766, 7739, 7740, -1, 7739, 7766, 7767, -1, + 7767, 7738, 7739, -1, 7738, 7767, 7768, -1, + 7768, 7737, 7738, -1, 7737, 7768, 7769, -1, + 7769, 7736, 7737, -1, 7736, 7769, 7770, -1, + 7770, 7735, 7736, -1, 7735, 7770, 7771, -1, + 7771, 7734, 7735, -1, 7734, 7771, 7772, -1, + 7772, 7733, 7734, -1, 7733, 7772, 7773, -1, + 7773, 7732, 7733, -1, 7732, 7773, 7774, -1, + 7774, 7731, 7732, -1, 7731, 7774, 7775, -1, + 7775, 7730, 7731, -1, 7730, 7775, 7776, -1, + 7776, 7729, 7730, -1, 7729, 7776, 7777, -1, + 7777, 7728, 7729, -1, 7728, 7777, 7778, -1, + 7778, 7727, 7728, -1, 7727, 7778, 7779, -1, + 7779, 7726, 7727, -1, 7726, 7779, 7780, -1, + 7780, 7725, 7726, -1, 7725, 7780, 7781, -1, + 7781, 7724, 7725, -1, 7781, 7723, 7724, -1, + 7723, 7781, 7782, -1, 7782, 7722, 7723, -1, + 7722, 7782, 7783, -1, 7783, 7721, 7722, -1, + 7721, 7783, 7784, -1, 7784, 7720, 7721, -1, + 7720, 7784, 7785, -1, 7785, 7719, 7720, -1, + 7719, 7785, 7786, -1, 7786, 7718, 7719, -1, + 7718, 7786, 7787, -1, 7787, 7717, 7718, -1, + 7717, 7787, 7788, -1, 7788, 7716, 7717, -1, + 7716, 7788, 7789, -1, 7789, 7715, 7716, -1, + 7715, 7789, 7790, -1, 7790, 7714, 7715, -1, + 7714, 7790, 7791, -1, 7791, 7713, 7714, -1, + 7713, 7791, 7792, -1, 7792, 7712, 7713, -1, + 7712, 7792, 7793, -1, 7793, 7711, 7712, -1, + 7711, 7793, 7794, -1, 7794, 7710, 7711, -1, + 7710, 7794, 7795, -1, 7795, 7709, 7710, -1, + 7709, 7795, 7796, -1, 7796, 7708, 7709, -1, + 7708, 7796, 7797, -1, 7797, 7707, 7708, -1, + 7707, 7797, 7798, -1, 7798, 7706, 7707, -1, + 7706, 7798, 7799, -1, 7799, 7705, 7706, -1, + 7705, 7799, 7800, -1, 7800, 7704, 7705, -1, + 7704, 7800, 7801, -1, 7801, 7703, 7704, -1, + 7703, 7801, 7802, -1, 7802, 7702, 7703, -1, + 7702, 7802, 7803, -1, 7803, 7701, 7702, -1, + 7701, 7803, 7804, -1, 7804, 7700, 7701, -1, + 7700, 7804, 7805, -1, 7805, 7699, 7700, -1, + 7699, 7805, 7806, -1, 7806, 7698, 7699, -1, + 7698, 7806, 7807, -1, 7807, 7697, 7698, -1, + 7697, 7807, 7808, -1, 7808, 7696, 7697, -1, + 7696, 7808, 7809, -1, 7809, 7695, 7696, -1, + 7695, 7809, 7810, -1, 7810, 7694, 7695, -1, + 7694, 7810, 7811, -1, 7811, 7693, 7694, -1, + 7693, 7811, 7812, -1, 7812, 7692, 7693, -1, + 7692, 7812, 7813, -1, 7813, 7691, 7692, -1, + 7691, 7813, 7814, -1, 7814, 7690, 7691, -1, + 7690, 7814, 7815, -1, 7815, 7689, 7690, -1, + 7689, 7815, 7816, -1, 7816, 7688, 7689, -1, + 7688, 7816, 7817, -1, 7817, 7687, 7688, -1, + 7687, 7817, 7818, -1, 7818, 7686, 7687, -1, + 7686, 7818, 7819, -1, 7819, 7685, 7686, -1, + 7685, 7819, 7820, -1, 7820, 7684, 7685, -1, + 7684, 7820, 7821, -1, 7821, 7683, 7684, -1, + 7683, 7821, 7822, -1, 7822, 7682, 7683, -1, + 7682, 7822, 7823, -1, 7823, 7681, 7682, -1, + 7681, 7823, 7824, -1, 7824, 7679, 7681, -1, + 7824, 7825, 7679, -1, 7826, 7827, 7828, -1, + 7828, 7824, 7826, -1, 7828, 7825, 7824, -1, + 7828, 7827, 7825, -1, 778, 7825, 7827, -1, + 7825, 778, 777, -1, 777, 7679, 7825, -1, + 777, 779, 7679, -1, 779, 7680, 7679, -1, + 7680, 779, 778, -1, 7680, 778, 7829, -1, + 7829, 7677, 7680, -1, 7829, 7678, 7677, -1, + 7829, 778, 7678, -1, 778, 7830, 7678, -1, + 7831, 7830, 7832, -1, 7831, 7678, 7830, -1, + 7831, 7675, 7678, -1, 7831, 7832, 7675, -1, + 7832, 7676, 7675, -1, 7676, 7832, 7830, -1, + 7676, 7830, 7833, -1, 7833, 7674, 7676, -1, + 7833, 7673, 7674, -1, 7673, 7833, 7830, -1, + 7830, 7669, 7673, -1, 7834, 7835, 7836, -1, + 7836, 7837, 7834, -1, 7837, 7836, 7838, -1, + 7838, 7839, 7837, -1, 7839, 7838, 7840, -1, + 7840, 7841, 7839, -1, 7841, 7840, 7842, -1, + 7842, 7843, 7841, -1, 7843, 7842, 7844, -1, + 7844, 7845, 7843, -1, 7845, 7844, 7846, -1, + 7846, 7847, 7845, -1, 7847, 7846, 7848, -1, + 7848, 7849, 7847, -1, 7849, 7848, 7850, -1, + 7850, 7851, 7849, -1, 7851, 7850, 7852, -1, + 7852, 7853, 7851, -1, 7853, 7852, 7854, -1, + 7854, 7855, 7853, -1, 7855, 7854, 7856, -1, + 7856, 7857, 7855, -1, 7857, 7856, 7858, -1, + 7858, 7859, 7857, -1, 7859, 7858, 7860, -1, + 7860, 7861, 7859, -1, 7861, 7860, 7862, -1, + 7862, 7863, 7861, -1, 7863, 7862, 7864, -1, + 7864, 7865, 7863, -1, 7865, 7864, 7866, -1, + 7866, 7867, 7865, -1, 7867, 7866, 7868, -1, + 7868, 7869, 7867, -1, 7869, 7868, 7870, -1, + 7870, 7871, 7869, -1, 7871, 7870, 7872, -1, + 7872, 7873, 7871, -1, 7873, 7872, 7874, -1, + 7874, 7875, 7873, -1, 7875, 7874, 7876, -1, + 7876, 7877, 7875, -1, 7877, 7876, 7878, -1, + 7878, 7879, 7877, -1, 7879, 7878, 7880, -1, + 7880, 7881, 7879, -1, 7881, 7880, 7882, -1, + 7882, 7883, 7881, -1, 7883, 7882, 7884, -1, + 7884, 7885, 7883, -1, 7885, 7884, 7886, -1, + 7886, 7887, 7885, -1, 7887, 7886, 7888, -1, + 7888, 7889, 7887, -1, 7889, 7888, 7890, -1, + 7890, 7891, 7889, -1, 7891, 7890, 7892, -1, + 7891, 7892, 7893, -1, 7893, 7894, 7891, -1, + 7894, 7893, 7895, -1, 7895, 7896, 7894, -1, + 7896, 7895, 7897, -1, 7897, 7898, 7896, -1, + 7898, 7897, 7899, -1, 7899, 7900, 7898, -1, + 7900, 7899, 7901, -1, 7901, 7902, 7900, -1, + 7902, 7901, 7903, -1, 7903, 7904, 7902, -1, + 7904, 7903, 7905, -1, 7905, 7906, 7904, -1, + 7906, 7905, 7907, -1, 7907, 7908, 7906, -1, + 7908, 7907, 7909, -1, 7909, 7910, 7908, -1, + 7910, 7909, 7911, -1, 7911, 7912, 7910, -1, + 7912, 7911, 7913, -1, 7913, 7914, 7912, -1, + 7914, 7913, 7915, -1, 7915, 7916, 7914, -1, + 7916, 7915, 7917, -1, 7917, 7918, 7916, -1, + 7918, 7917, 7919, -1, 7919, 7920, 7918, -1, + 7920, 7919, 7921, -1, 7921, 7922, 7920, -1, + 7922, 7921, 7923, -1, 7923, 7924, 7922, -1, + 7924, 7923, 7925, -1, 7925, 7926, 7924, -1, + 7926, 7925, 7927, -1, 7927, 7928, 7926, -1, + 7928, 7927, 7929, -1, 7929, 7930, 7928, -1, + 7930, 7929, 7931, -1, 7931, 7932, 7930, -1, + 7932, 7931, 7933, -1, 7933, 7934, 7932, -1, + 7934, 7933, 7935, -1, 7935, 7936, 7934, -1, + 7936, 7935, 7937, -1, 7937, 7938, 7936, -1, + 7938, 7937, 7939, -1, 7939, 7940, 7938, -1, + 7940, 7939, 7941, -1, 7941, 7942, 7940, -1, + 7942, 7941, 7943, -1, 7943, 7944, 7942, -1, + 7945, 7946, 7947, -1, 7946, 7945, 7948, -1, + 7948, 7949, 7946, -1, 7949, 7948, 7950, -1, + 7950, 7944, 7949, -1, 7944, 7950, 7951, -1, + 7951, 7942, 7944, -1, 7942, 7951, 7952, -1, + 7952, 7940, 7942, -1, 7940, 7952, 7953, -1, + 7953, 7938, 7940, -1, 7938, 7953, 7954, -1, + 7954, 7936, 7938, -1, 7936, 7954, 7955, -1, + 7955, 7934, 7936, -1, 7934, 7955, 7956, -1, + 7956, 7932, 7934, -1, 7932, 7956, 7957, -1, + 7957, 7930, 7932, -1, 7930, 7957, 7958, -1, + 7958, 7928, 7930, -1, 7928, 7958, 7959, -1, + 7959, 7926, 7928, -1, 7926, 7959, 7960, -1, + 7960, 7924, 7926, -1, 7924, 7960, 7961, -1, + 7961, 7922, 7924, -1, 7922, 7961, 7962, -1, + 7962, 7920, 7922, -1, 7920, 7962, 7963, -1, + 7963, 7918, 7920, -1, 7918, 7963, 7964, -1, + 7964, 7916, 7918, -1, 7916, 7964, 7965, -1, + 7965, 7914, 7916, -1, 7914, 7965, 7966, -1, + 7966, 7912, 7914, -1, 7912, 7966, 7967, -1, + 7967, 7910, 7912, -1, 7910, 7967, 7968, -1, + 7968, 7908, 7910, -1, 7908, 7968, 7969, -1, + 7969, 7906, 7908, -1, 7906, 7969, 7970, -1, + 7970, 7904, 7906, -1, 7904, 7970, 7971, -1, + 7971, 7902, 7904, -1, 7902, 7971, 7972, -1, + 7972, 7900, 7902, -1, 7900, 7972, 7973, -1, + 7973, 7898, 7900, -1, 7898, 7973, 7974, -1, + 7974, 7896, 7898, -1, 7896, 7974, 7975, -1, + 7975, 7894, 7896, -1, 7894, 7975, 7976, -1, + 7976, 7891, 7894, -1, 7976, 7889, 7891, -1, + 7889, 7976, 7977, -1, 7977, 7887, 7889, -1, + 7887, 7977, 7978, -1, 7978, 7885, 7887, -1, + 7885, 7978, 7979, -1, 7979, 7883, 7885, -1, + 7883, 7979, 7980, -1, 7980, 7881, 7883, -1, + 7881, 7980, 7981, -1, 7981, 7879, 7881, -1, + 7879, 7981, 7982, -1, 7982, 7877, 7879, -1, + 7877, 7982, 7983, -1, 7983, 7875, 7877, -1, + 7875, 7983, 7984, -1, 7984, 7873, 7875, -1, + 7873, 7984, 7985, -1, 7985, 7871, 7873, -1, + 7871, 7985, 7986, -1, 7986, 7869, 7871, -1, + 7869, 7986, 7987, -1, 7987, 7867, 7869, -1, + 7867, 7987, 7988, -1, 7988, 7865, 7867, -1, + 7865, 7988, 7989, -1, 7989, 7863, 7865, -1, + 7863, 7989, 7990, -1, 7990, 7861, 7863, -1, + 7861, 7990, 7991, -1, 7991, 7859, 7861, -1, + 7859, 7991, 7992, -1, 7992, 7857, 7859, -1, + 7857, 7992, 7993, -1, 7993, 7855, 7857, -1, + 7855, 7993, 7994, -1, 7994, 7853, 7855, -1, + 7853, 7994, 7995, -1, 7995, 7851, 7853, -1, + 7851, 7995, 7996, -1, 7996, 7849, 7851, -1, + 7849, 7996, 7997, -1, 7997, 7847, 7849, -1, + 7847, 7997, 7998, -1, 7998, 7845, 7847, -1, + 7845, 7998, 7999, -1, 7999, 7843, 7845, -1, + 7843, 7999, 8000, -1, 8000, 7841, 7843, -1, + 7841, 8000, 8001, -1, 8001, 7839, 7841, -1, + 7839, 8001, 8002, -1, 8002, 7837, 7839, -1, + 7837, 8002, 8003, -1, 8003, 7834, 7837, -1, + 7834, 8003, 8004, -1, 8004, 7835, 7834, -1, + 8005, 8006, 8007, -1, 8005, 8008, 8006, -1, + 8008, 8005, 8009, -1, 8009, 8010, 8008, -1, + 8010, 8009, 8011, -1, 8011, 8012, 8010, -1, + 8012, 8011, 7835, -1, 7835, 8004, 8012, -1, + 8013, 8012, 8004, -1, 8004, 8014, 8013, -1, + 8014, 8004, 8003, -1, 8003, 8015, 8014, -1, + 8015, 8003, 8002, -1, 8002, 8016, 8015, -1, + 8016, 8002, 8001, -1, 8001, 8017, 8016, -1, + 8017, 8001, 8000, -1, 8000, 8018, 8017, -1, + 8018, 8000, 7999, -1, 7999, 8019, 8018, -1, + 8019, 7999, 7998, -1, 7998, 8020, 8019, -1, + 8020, 7998, 7997, -1, 7997, 8021, 8020, -1, + 8021, 7997, 7996, -1, 7996, 8022, 8021, -1, + 8022, 7996, 7995, -1, 7995, 8023, 8022, -1, + 8023, 7995, 7994, -1, 7994, 8024, 8023, -1, + 8024, 7994, 7993, -1, 7993, 8025, 8024, -1, + 8025, 7993, 7992, -1, 7992, 8026, 8025, -1, + 8026, 7992, 7991, -1, 7991, 8027, 8026, -1, + 8027, 7991, 7990, -1, 7990, 8028, 8027, -1, + 8028, 7990, 7989, -1, 7989, 8029, 8028, -1, + 8029, 7989, 7988, -1, 7988, 8030, 8029, -1, + 8030, 7988, 7987, -1, 7987, 8031, 8030, -1, + 8031, 7987, 7986, -1, 7986, 8032, 8031, -1, + 8032, 7986, 7985, -1, 7985, 8033, 8032, -1, + 8033, 7985, 7984, -1, 7984, 8034, 8033, -1, + 8034, 7984, 7983, -1, 7983, 8035, 8034, -1, + 8035, 7983, 7982, -1, 7982, 8036, 8035, -1, + 8036, 7982, 7981, -1, 7981, 8037, 8036, -1, + 8037, 7981, 7980, -1, 7980, 8038, 8037, -1, + 8038, 7980, 7979, -1, 7979, 8039, 8038, -1, + 8039, 7979, 7978, -1, 7978, 8040, 8039, -1, + 8040, 7978, 7977, -1, 7977, 8041, 8040, -1, + 8041, 7977, 7976, -1, 8041, 7976, 7975, -1, + 7975, 8042, 8041, -1, 8042, 7975, 7974, -1, + 7974, 8043, 8042, -1, 8043, 7974, 7973, -1, + 7973, 8044, 8043, -1, 8044, 7973, 7972, -1, + 7972, 8045, 8044, -1, 8045, 7972, 7971, -1, + 7971, 8046, 8045, -1, 8046, 7971, 7970, -1, + 7970, 8047, 8046, -1, 8047, 7970, 7969, -1, + 7969, 8048, 8047, -1, 8048, 7969, 7968, -1, + 7968, 8049, 8048, -1, 8049, 7968, 7967, -1, + 7967, 8050, 8049, -1, 8050, 7967, 7966, -1, + 7966, 8051, 8050, -1, 8051, 7966, 7965, -1, + 7965, 8052, 8051, -1, 8052, 7965, 7964, -1, + 7964, 8053, 8052, -1, 8053, 7964, 7963, -1, + 7963, 8054, 8053, -1, 8054, 7963, 7962, -1, + 7962, 8055, 8054, -1, 8055, 7962, 7961, -1, + 7961, 8056, 8055, -1, 8056, 7961, 7960, -1, + 7960, 8057, 8056, -1, 8057, 7960, 7959, -1, + 7959, 8058, 8057, -1, 8058, 7959, 7958, -1, + 7958, 8059, 8058, -1, 8059, 7958, 7957, -1, + 7957, 8060, 8059, -1, 8060, 7957, 7956, -1, + 7956, 8061, 8060, -1, 8061, 7956, 7955, -1, + 7955, 8062, 8061, -1, 8062, 7955, 7954, -1, + 7954, 8063, 8062, -1, 8063, 7954, 7953, -1, + 7953, 8064, 8063, -1, 8064, 7953, 7952, -1, + 7952, 8065, 8064, -1, 8065, 7952, 7951, -1, + 7951, 8066, 8065, -1, 8066, 7951, 7950, -1, + 7950, 8067, 8066, -1, 8067, 7950, 7948, -1, + 7948, 8068, 8067, -1, 8068, 7948, 7945, -1, + 7945, 8069, 8068, -1, 8069, 7945, 7947, -1, + 7947, 8070, 8069, -1, 8070, 7947, 8071, -1, + 8071, 8072, 8070, -1, 8073, 8074, 8075, -1, + 8075, 8076, 8073, -1, 8076, 8075, 8077, -1, + 8077, 8078, 8076, -1, 8078, 8077, 8079, -1, + 8079, 8080, 8078, -1, 8080, 8079, 8081, -1, + 8081, 8082, 8080, -1, 8082, 8081, 8083, -1, + 8083, 8084, 8082, -1, 8084, 8083, 8085, -1, + 8085, 8086, 8084, -1, 8086, 8085, 8087, -1, + 8087, 8088, 8086, -1, 8088, 8087, 8089, -1, + 8089, 8090, 8088, -1, 8090, 8089, 8091, -1, + 8091, 8092, 8090, -1, 8092, 8091, 8093, -1, + 8093, 8094, 8092, -1, 8094, 8093, 8095, -1, + 8095, 8096, 8094, -1, 8096, 8095, 8097, -1, + 8097, 8098, 8096, -1, 8098, 8097, 8099, -1, + 8099, 8100, 8098, -1, 8100, 8099, 8101, -1, + 8101, 8102, 8100, -1, 8102, 8101, 8103, -1, + 8103, 8104, 8102, -1, 8104, 8103, 8105, -1, + 8105, 8106, 8104, -1, 8106, 8105, 8107, -1, + 8107, 8108, 8106, -1, 8108, 8107, 8109, -1, + 8109, 8110, 8108, -1, 8110, 8109, 8111, -1, + 8111, 8112, 8110, -1, 8112, 8111, 8113, -1, + 8113, 8114, 8112, -1, 8114, 8113, 8115, -1, + 8115, 8116, 8114, -1, 8116, 8115, 8117, -1, + 8117, 8118, 8116, -1, 8118, 8117, 8119, -1, + 8119, 8120, 8118, -1, 8120, 8119, 8121, -1, + 8121, 8122, 8120, -1, 8122, 8121, 8123, -1, + 8123, 8124, 8122, -1, 8124, 8123, 8125, -1, + 8125, 8126, 8124, -1, 8126, 8125, 8127, -1, + 8127, 8128, 8126, -1, 8128, 8127, 8129, -1, + 8129, 8130, 8128, -1, 8130, 8129, 8131, -1, + 8131, 8132, 8130, -1, 8132, 8131, 8133, -1, + 8133, 8134, 8132, -1, 8133, 8135, 8134, -1, + 8135, 8133, 8136, -1, 8136, 8137, 8135, -1, + 8137, 8136, 8138, -1, 8138, 8139, 8137, -1, + 8139, 8138, 8140, -1, 8140, 8141, 8139, -1, + 8141, 8140, 8142, -1, 8142, 8143, 8141, -1, + 8143, 8142, 8144, -1, 8144, 8145, 8143, -1, + 8145, 8144, 8146, -1, 8146, 8147, 8145, -1, + 8147, 8146, 8148, -1, 8148, 8149, 8147, -1, + 8149, 8148, 8150, -1, 8150, 8151, 8149, -1, + 8151, 8150, 8152, -1, 8152, 8153, 8151, -1, + 8153, 8152, 8154, -1, 8154, 8155, 8153, -1, + 8155, 8154, 8156, -1, 8156, 8157, 8155, -1, + 8157, 8156, 8158, -1, 8158, 8159, 8157, -1, + 8159, 8158, 8160, -1, 8160, 8161, 8159, -1, + 8161, 8160, 8162, -1, 8162, 8163, 8161, -1, + 8163, 8162, 8164, -1, 8164, 8165, 8163, -1, + 8165, 8164, 8166, -1, 8166, 8167, 8165, -1, + 8167, 8166, 8168, -1, 8168, 8169, 8167, -1, + 8169, 8168, 8170, -1, 8170, 8171, 8169, -1, + 8171, 8170, 8172, -1, 8172, 8173, 8171, -1, + 8173, 8172, 8174, -1, 8174, 8175, 8173, -1, + 8175, 8174, 8176, -1, 8176, 8177, 8175, -1, + 8177, 8176, 8178, -1, 8178, 8179, 8177, -1, + 8179, 8178, 8180, -1, 8180, 8181, 8179, -1, + 8181, 8180, 8182, -1, 8182, 8183, 8181, -1, + 8183, 8182, 8184, -1, 8184, 8185, 8183, -1, + 8185, 8184, 8186, -1, 8186, 8187, 8185, -1, + 8187, 8186, 8188, -1, 8188, 8189, 8187, -1, + 8189, 8188, 8190, -1, 8190, 8191, 8189, -1, + 8191, 8190, 8192, -1, 8192, 8193, 8191, -1, + 8193, 8192, 8194, -1, 8194, 8195, 8193, -1, + 8195, 8194, 8196, -1, 8196, 8197, 8195, -1, + 8197, 8196, 8198, -1, 8198, 8199, 8197, -1, + 8199, 8198, 8200, -1, 8200, 8201, 8199, -1, + 8201, 8200, 8202, -1, 8202, 8203, 8201, -1, + 8203, 8202, 8204, -1, 8204, 8205, 8203, -1, + 8205, 8204, 8206, -1, 8206, 8207, 8205, -1, + 8206, 8208, 8207, -1, 8209, 8210, 8211, -1, + 8211, 8212, 8209, -1, 8212, 8211, 8213, -1, + 8213, 8214, 8212, -1, 8214, 8213, 8215, -1, + 8215, 8216, 8214, -1, 8216, 8215, 8217, -1, + 8217, 8218, 8216, -1, 8218, 8217, 8219, -1, + 8219, 8220, 8218, -1, 8220, 8219, 8221, -1, + 8221, 8222, 8220, -1, 8222, 8221, 8223, -1, + 8223, 8224, 8222, -1, 8224, 8223, 8225, -1, + 8225, 8226, 8224, -1, 8226, 8225, 8227, -1, + 8227, 8228, 8226, -1, 8228, 8227, 8229, -1, + 8229, 8230, 8228, -1, 8230, 8229, 8231, -1, + 8231, 8232, 8230, -1, 8232, 8231, 8233, -1, + 8233, 8234, 8232, -1, 8234, 8233, 8235, -1, + 8235, 8236, 8234, -1, 8236, 8235, 8237, -1, + 8237, 8238, 8236, -1, 8238, 8237, 8239, -1, + 8239, 8240, 8238, -1, 8240, 8239, 8241, -1, + 8241, 8242, 8240, -1, 8242, 8241, 8243, -1, + 8243, 8244, 8242, -1, 8244, 8243, 8245, -1, + 8245, 8246, 8244, -1, 8246, 8245, 8247, -1, + 8247, 8248, 8246, -1, 8248, 8247, 8249, -1, + 8249, 8250, 8248, -1, 8250, 8249, 8251, -1, + 8251, 8252, 8250, -1, 8252, 8251, 8253, -1, + 8253, 8254, 8252, -1, 8254, 8253, 8255, -1, + 8255, 8256, 8254, -1, 8256, 8255, 8257, -1, + 8257, 8258, 8256, -1, 8258, 8257, 8259, -1, + 8259, 8260, 8258, -1, 8260, 8259, 8261, -1, + 8261, 8262, 8260, -1, 8262, 8261, 8263, -1, + 8263, 8264, 8262, -1, 8264, 8263, 8265, -1, + 8265, 8266, 8264, -1, 8266, 8265, 8267, -1, + 8267, 8268, 8266, -1, 8268, 8267, 8269, -1, + 8269, 8270, 8268, -1, 8269, 8271, 8270, -1, + 8271, 8269, 8272, -1, 8272, 8273, 8271, -1, + 8273, 8272, 8274, -1, 8274, 8275, 8273, -1, + 8275, 8274, 8276, -1, 8276, 8277, 8275, -1, + 8277, 8276, 8278, -1, 8278, 8279, 8277, -1, + 8279, 8278, 8280, -1, 8280, 8281, 8279, -1, + 8281, 8280, 8282, -1, 8282, 8283, 8281, -1, + 8283, 8282, 8284, -1, 8284, 8285, 8283, -1, + 8285, 8284, 8286, -1, 8286, 8287, 8285, -1, + 8287, 8286, 8288, -1, 8288, 8289, 8287, -1, + 8289, 8288, 8290, -1, 8290, 8291, 8289, -1, + 8291, 8290, 8292, -1, 8292, 8293, 8291, -1, + 8293, 8292, 8294, -1, 8294, 8295, 8293, -1, + 8295, 8294, 8296, -1, 8296, 8297, 8295, -1, + 8297, 8296, 8298, -1, 8298, 8299, 8297, -1, + 8299, 8298, 8300, -1, 8300, 8301, 8299, -1, + 8301, 8300, 8302, -1, 8302, 8303, 8301, -1, + 8303, 8302, 8304, -1, 8304, 8305, 8303, -1, + 8305, 8304, 8306, -1, 8306, 8307, 8305, -1, + 8307, 8306, 8308, -1, 8308, 8309, 8307, -1, + 8309, 8308, 8310, -1, 8310, 8311, 8309, -1, + 8311, 8310, 8312, -1, 8312, 8313, 8311, -1, + 8313, 8312, 8314, -1, 8314, 8315, 8313, -1, + 8315, 8314, 8316, -1, 8316, 8317, 8315, -1, + 8317, 8316, 8318, -1, 8318, 8319, 8317, -1, + 8319, 8318, 8320, -1, 8320, 8321, 8319, -1, + 8321, 8320, 8322, -1, 8322, 8323, 8321, -1, + 8323, 8322, 8324, -1, 8324, 8325, 8323, -1, + 8325, 8324, 8326, -1, 8326, 8327, 8325, -1, + 8327, 8326, 8328, -1, 8328, 8329, 8327, -1, + 8329, 8328, 8330, -1, 8330, 8331, 8329, -1, + 8331, 8330, 8332, -1, 8332, 8333, 8331, -1, + 8333, 8332, 8334, -1, 8333, 8334, 8335, -1, + 8336, 8335, 8334, -1, 8336, 8337, 8335, -1, + 8337, 8336, 8338, -1, 8338, 8339, 8337, -1, + 8339, 8338, 8340, -1, 8340, 8341, 8339, -1, + 8341, 8340, 8342, -1, 8342, 8343, 8341, -1, + 8343, 8342, 8344, -1, 8344, 8345, 8343, -1, + 8345, 8344, 8346, -1, 8346, 8347, 8345, -1, + 8346, 8348, 8347, -1, 8348, 8346, 8349, -1, + 8349, 8350, 8348, -1, 8349, 8351, 8350, -1, + 8351, 8349, 8346, -1, 8351, 8346, 8352, -1, + 8352, 8350, 8351, -1, 8352, 8353, 8350, -1, + 8354, 8350, 8353, -1, 8355, 8356, 8357, -1, + 8358, 8359, 8360, -1, 8361, 8362, 8363, -1, + 8361, 8363, 8364, -1, 8364, 8365, 8361, -1, + 8365, 8364, 8359, -1, 8359, 8358, 8365, -1, + 8358, 8366, 8367, -1, 8367, 8365, 8358, -1, + 8365, 8367, 8368, -1, 8368, 8361, 8365, -1, + 8361, 8368, 8369, -1, 8370, 8369, 8368, -1, + 8369, 8370, 8356, -1, 8371, 8369, 8356, -1, + 8371, 8361, 8369, -1, 8371, 8362, 8361, -1, + 8362, 8371, 8356, -1, 8362, 8356, 8355, -1, + 8355, 8363, 8362, -1, 8355, 8357, 8363, -1, + 8357, 8372, 8363, -1, 8357, 8356, 8372, -1, + 8373, 8372, 8374, -1, 8374, 8372, 8356, -1, + 8354, 8375, 8374, -1, 8375, 8354, 8376, -1, + 8377, 8206, 8376, -1, 8377, 8376, 8354, -1, + 8377, 8354, 8378, -1, 8378, 8206, 8377, -1, + 8378, 8208, 8206, -1, 8378, 8354, 8208, -1, + 8208, 8354, 8353, -1, 8353, 8207, 8208, -1, + 8353, 8352, 8207, -1, 8207, 8352, 8346, -1, + 8207, 8346, 8344, -1, 8344, 8205, 8207, -1, + 8205, 8344, 8342, -1, 8342, 8203, 8205, -1, + 8203, 8342, 8340, -1, 8340, 8201, 8203, -1, + 8201, 8340, 8338, -1, 8338, 8199, 8201, -1, + 8199, 8338, 8336, -1, 8336, 8197, 8199, -1, + 8197, 8336, 8334, -1, 8334, 8195, 8197, -1, + 8195, 8334, 8332, -1, 8332, 8193, 8195, -1, + 8193, 8332, 8330, -1, 8330, 8191, 8193, -1, + 8191, 8330, 8328, -1, 8328, 8189, 8191, -1, + 8189, 8328, 8326, -1, 8326, 8187, 8189, -1, + 8187, 8326, 8324, -1, 8324, 8185, 8187, -1, + 8185, 8324, 8322, -1, 8322, 8183, 8185, -1, + 8183, 8322, 8320, -1, 8320, 8181, 8183, -1, + 8181, 8320, 8318, -1, 8318, 8179, 8181, -1, + 8179, 8318, 8316, -1, 8316, 8177, 8179, -1, + 8177, 8316, 8314, -1, 8314, 8175, 8177, -1, + 8175, 8314, 8312, -1, 8312, 8173, 8175, -1, + 8173, 8312, 8310, -1, 8310, 8171, 8173, -1, + 8171, 8310, 8308, -1, 8308, 8169, 8171, -1, + 8169, 8308, 8306, -1, 8306, 8167, 8169, -1, + 8167, 8306, 8304, -1, 8304, 8165, 8167, -1, + 8165, 8304, 8302, -1, 8302, 8163, 8165, -1, + 8163, 8302, 8300, -1, 8300, 8161, 8163, -1, + 8161, 8300, 8298, -1, 8298, 8159, 8161, -1, + 8159, 8298, 8296, -1, 8296, 8157, 8159, -1, + 8157, 8296, 8294, -1, 8294, 8155, 8157, -1, + 8155, 8294, 8292, -1, 8292, 8153, 8155, -1, + 8153, 8292, 8290, -1, 8290, 8151, 8153, -1, + 8151, 8290, 8288, -1, 8288, 8149, 8151, -1, + 8149, 8288, 8286, -1, 8286, 8147, 8149, -1, + 8147, 8286, 8284, -1, 8284, 8145, 8147, -1, + 8145, 8284, 8282, -1, 8282, 8143, 8145, -1, + 8143, 8282, 8280, -1, 8280, 8141, 8143, -1, + 8141, 8280, 8278, -1, 8278, 8139, 8141, -1, + 8139, 8278, 8276, -1, 8276, 8137, 8139, -1, + 8137, 8276, 8274, -1, 8274, 8135, 8137, -1, + 8135, 8274, 8272, -1, 8272, 8134, 8135, -1, + 8134, 8272, 8269, -1, 8134, 8269, 8267, -1, + 8267, 8132, 8134, -1, 8132, 8267, 8265, -1, + 8265, 8130, 8132, -1, 8130, 8265, 8263, -1, + 8263, 8128, 8130, -1, 8128, 8263, 8261, -1, + 8261, 8126, 8128, -1, 8126, 8261, 8259, -1, + 8259, 8124, 8126, -1, 8124, 8259, 8257, -1, + 8257, 8122, 8124, -1, 8122, 8257, 8255, -1, + 8255, 8120, 8122, -1, 8120, 8255, 8253, -1, + 8253, 8118, 8120, -1, 8118, 8253, 8251, -1, + 8251, 8116, 8118, -1, 8116, 8251, 8249, -1, + 8249, 8114, 8116, -1, 8114, 8249, 8247, -1, + 8247, 8112, 8114, -1, 8112, 8247, 8245, -1, + 8245, 8110, 8112, -1, 8110, 8245, 8243, -1, + 8243, 8108, 8110, -1, 8108, 8243, 8241, -1, + 8241, 8106, 8108, -1, 8106, 8241, 8239, -1, + 8239, 8104, 8106, -1, 8104, 8239, 8237, -1, + 8237, 8102, 8104, -1, 8102, 8237, 8235, -1, + 8235, 8100, 8102, -1, 8100, 8235, 8233, -1, + 8233, 8098, 8100, -1, 8098, 8233, 8231, -1, + 8231, 8096, 8098, -1, 8096, 8231, 8229, -1, + 8229, 8094, 8096, -1, 8094, 8229, 8227, -1, + 8227, 8092, 8094, -1, 8092, 8227, 8225, -1, + 8225, 8090, 8092, -1, 8090, 8225, 8223, -1, + 8223, 8088, 8090, -1, 8088, 8223, 8221, -1, + 8221, 8086, 8088, -1, 8086, 8221, 8219, -1, + 8219, 8084, 8086, -1, 8084, 8219, 8217, -1, + 8217, 8082, 8084, -1, 8082, 8217, 8215, -1, + 8215, 8080, 8082, -1, 8080, 8215, 8213, -1, + 8213, 8078, 8080, -1, 8078, 8213, 8211, -1, + 8211, 8076, 8078, -1, 8076, 8211, 8210, -1, + 8210, 8073, 8076, -1, 8210, 8379, 8073, -1, + 8210, 8209, 8379, -1, 8209, 8072, 8379, -1, + 8072, 8209, 8212, -1, 8212, 8070, 8072, -1, + 8070, 8212, 8214, -1, 8214, 8069, 8070, -1, + 8069, 8214, 8216, -1, 8216, 8068, 8069, -1, + 8068, 8216, 8218, -1, 8218, 8067, 8068, -1, + 8067, 8218, 8220, -1, 8220, 8066, 8067, -1, + 8066, 8220, 8222, -1, 8222, 8065, 8066, -1, + 8065, 8222, 8224, -1, 8224, 8064, 8065, -1, + 8064, 8224, 8226, -1, 8226, 8063, 8064, -1, + 8063, 8226, 8228, -1, 8228, 8062, 8063, -1, + 8062, 8228, 8230, -1, 8230, 8061, 8062, -1, + 8061, 8230, 8232, -1, 8232, 8060, 8061, -1, + 8060, 8232, 8234, -1, 8234, 8059, 8060, -1, + 8059, 8234, 8236, -1, 8236, 8058, 8059, -1, + 8058, 8236, 8238, -1, 8238, 8057, 8058, -1, + 8057, 8238, 8240, -1, 8240, 8056, 8057, -1, + 8056, 8240, 8242, -1, 8242, 8055, 8056, -1, + 8055, 8242, 8244, -1, 8244, 8054, 8055, -1, + 8054, 8244, 8246, -1, 8246, 8053, 8054, -1, + 8053, 8246, 8248, -1, 8248, 8052, 8053, -1, + 8052, 8248, 8250, -1, 8250, 8051, 8052, -1, + 8051, 8250, 8252, -1, 8252, 8050, 8051, -1, + 8050, 8252, 8254, -1, 8254, 8049, 8050, -1, + 8049, 8254, 8256, -1, 8256, 8048, 8049, -1, + 8048, 8256, 8258, -1, 8258, 8047, 8048, -1, + 8047, 8258, 8260, -1, 8260, 8046, 8047, -1, + 8046, 8260, 8262, -1, 8262, 8045, 8046, -1, + 8045, 8262, 8264, -1, 8264, 8044, 8045, -1, + 8044, 8264, 8266, -1, 8266, 8043, 8044, -1, + 8043, 8266, 8268, -1, 8268, 8042, 8043, -1, + 8042, 8268, 8270, -1, 8270, 8041, 8042, -1, + 8270, 8040, 8041, -1, 8040, 8270, 8271, -1, + 8271, 8039, 8040, -1, 8039, 8271, 8273, -1, + 8273, 8038, 8039, -1, 8038, 8273, 8275, -1, + 8275, 8037, 8038, -1, 8037, 8275, 8277, -1, + 8277, 8036, 8037, -1, 8036, 8277, 8279, -1, + 8279, 8035, 8036, -1, 8035, 8279, 8281, -1, + 8281, 8034, 8035, -1, 8034, 8281, 8283, -1, + 8283, 8033, 8034, -1, 8033, 8283, 8285, -1, + 8285, 8032, 8033, -1, 8032, 8285, 8287, -1, + 8287, 8031, 8032, -1, 8031, 8287, 8289, -1, + 8289, 8030, 8031, -1, 8030, 8289, 8291, -1, + 8291, 8029, 8030, -1, 8029, 8291, 8293, -1, + 8293, 8028, 8029, -1, 8028, 8293, 8295, -1, + 8295, 8027, 8028, -1, 8027, 8295, 8297, -1, + 8297, 8026, 8027, -1, 8026, 8297, 8299, -1, + 8299, 8025, 8026, -1, 8025, 8299, 8301, -1, + 8301, 8024, 8025, -1, 8024, 8301, 8303, -1, + 8303, 8023, 8024, -1, 8023, 8303, 8305, -1, + 8305, 8022, 8023, -1, 8022, 8305, 8307, -1, + 8307, 8021, 8022, -1, 8021, 8307, 8309, -1, + 8309, 8020, 8021, -1, 8020, 8309, 8311, -1, + 8311, 8019, 8020, -1, 8019, 8311, 8313, -1, + 8313, 8018, 8019, -1, 8018, 8313, 8315, -1, + 8315, 8017, 8018, -1, 8017, 8315, 8317, -1, + 8317, 8016, 8017, -1, 8016, 8317, 8319, -1, + 8319, 8015, 8016, -1, 8015, 8319, 8321, -1, + 8321, 8014, 8015, -1, 8014, 8321, 8323, -1, + 8323, 8013, 8014, -1, 8013, 8323, 8325, -1, + 8325, 8012, 8013, -1, 8012, 8325, 8327, -1, + 8327, 8010, 8012, -1, 8010, 8327, 8329, -1, + 8329, 8008, 8010, -1, 8008, 8329, 8331, -1, + 8331, 8006, 8008, -1, 8006, 8331, 8333, -1, + 8333, 8335, 8006, -1, 8335, 8007, 8006, -1, + 8335, 8380, 8007, -1, 8380, 8335, 8337, -1, + 8337, 8381, 8380, -1, 8381, 8337, 8339, -1, + 8339, 8382, 8381, -1, 8382, 8339, 8341, -1, + 8341, 8383, 8382, -1, 8383, 8341, 8343, -1, + 8343, 8384, 8383, -1, 8384, 8343, 8345, -1, + 8345, 8385, 8384, -1, 8385, 8345, 8347, -1, + 8347, 8386, 8385, -1, 8347, 8387, 8386, -1, + 8388, 8389, 775, -1, 8389, 8388, 8386, -1, + 8389, 8386, 8387, -1, 8387, 775, 8389, -1, + 8387, 8390, 775, -1, 8390, 8387, 8347, -1, + 8390, 8347, 8348, -1, 8348, 8350, 8390, -1, + 8350, 775, 8390, -1, 7827, 776, 775, -1, + 776, 7827, 8391, -1, 8391, 8392, 776, -1, + 8391, 8393, 8392, -1, 8393, 8391, 7827, -1, + 8393, 7827, 7826, -1, 7826, 8392, 8393, -1, + 8392, 7826, 7824, -1, 8392, 7824, 7823, -1, + 7823, 8394, 8392, -1, 8394, 7823, 7822, -1, + 7822, 8395, 8394, -1, 8395, 7822, 7821, -1, + 7821, 8396, 8395, -1, 8396, 7821, 7820, -1, + 7820, 8397, 8396, -1, 8397, 7820, 7819, -1, + 7819, 8398, 8397, -1, 8398, 7819, 7818, -1, + 7818, 8399, 8398, -1, 8399, 7818, 7817, -1, + 7817, 8400, 8399, -1, 8400, 7817, 7816, -1, + 7816, 8401, 8400, -1, 8401, 7816, 7815, -1, + 7815, 8402, 8401, -1, 8402, 7815, 7814, -1, + 7814, 8403, 8402, -1, 8403, 7814, 7813, -1, + 7813, 8404, 8403, -1, 8404, 7813, 7812, -1, + 7812, 8405, 8404, -1, 8405, 7812, 7811, -1, + 7811, 8406, 8405, -1, 8406, 7811, 7810, -1, + 7810, 8407, 8406, -1, 8408, 8406, 8407, -1, + 8407, 8409, 8408, -1, 8409, 8407, 8410, -1, + 8410, 8411, 8409, -1, 8411, 8410, 8412, -1, + 8412, 8413, 8411, -1, 8413, 8412, 8414, -1, + 8414, 8415, 8413, -1, 8415, 8414, 8416, -1, + 8416, 8417, 8415, -1, 8417, 8416, 8418, -1, + 8418, 8419, 8417, -1, 8419, 8418, 8420, -1, + 8420, 8421, 8419, -1, 8421, 8420, 8422, -1, + 8422, 8423, 8421, -1, 8423, 8422, 8424, -1, + 8424, 8425, 8423, -1, 8425, 8424, 8426, -1, + 8426, 8427, 8425, -1, 8427, 8426, 8428, -1, + 8428, 8429, 8427, -1, 8429, 8428, 8430, -1, + 8430, 8431, 8429, -1, 8431, 8430, 8432, -1, + 8432, 8433, 8431, -1, 8433, 8432, 8434, -1, + 8434, 8435, 8433, -1, 8435, 8434, 8436, -1, + 8436, 8437, 8435, -1, 8437, 8436, 8438, -1, + 8438, 8439, 8437, -1, 8439, 8438, 8440, -1, + 8440, 8441, 8439, -1, 8441, 8440, 8442, -1, + 8442, 8443, 8441, -1, 8443, 8442, 8444, -1, + 8444, 8445, 8443, -1, 8445, 8444, 8446, -1, + 8446, 8447, 8445, -1, 8447, 8446, 8448, -1, + 8448, 8449, 8447, -1, 8449, 8448, 8450, -1, + 8450, 8451, 8449, -1, 8451, 8450, 8452, -1, + 8452, 8453, 8451, -1, 8453, 8452, 8454, -1, + 8454, 8455, 8453, -1, 8455, 8454, 8456, -1, + 8456, 8457, 8455, -1, 8457, 8456, 8458, -1, + 8458, 8459, 8457, -1, 8459, 8458, 8460, -1, + 8460, 8461, 8459, -1, 8461, 8460, 8462, -1, + 8462, 8463, 8461, -1, 8463, 8462, 8464, -1, + 8463, 8464, 8465, -1, 8465, 8466, 8463, -1, + 8466, 8465, 8467, -1, 8467, 8468, 8466, -1, + 8468, 8467, 8469, -1, 8469, 8470, 8468, -1, + 8470, 8469, 8471, -1, 8471, 8472, 8470, -1, + 8472, 8471, 8473, -1, 8473, 8474, 8472, -1, + 8474, 8473, 8475, -1, 8475, 8476, 8474, -1, + 8476, 8475, 8477, -1, 8477, 8478, 8476, -1, + 8478, 8477, 8479, -1, 8479, 8480, 8478, -1, + 8480, 8479, 8481, -1, 8481, 8482, 8480, -1, + 8482, 8481, 8483, -1, 8483, 8484, 8482, -1, + 8484, 8483, 8485, -1, 8485, 8486, 8484, -1, + 8486, 8485, 8487, -1, 8487, 8488, 8486, -1, + 8488, 8487, 8489, -1, 8489, 8490, 8488, -1, + 8490, 8489, 8491, -1, 8491, 8492, 8490, -1, + 8492, 8491, 8493, -1, 8493, 8494, 8492, -1, + 8494, 8493, 8495, -1, 8495, 8496, 8494, -1, + 8496, 8495, 8497, -1, 8497, 8498, 8496, -1, + 8498, 8497, 8499, -1, 8499, 8500, 8498, -1, + 8500, 8499, 8501, -1, 8501, 8502, 8500, -1, + 8502, 8501, 8503, -1, 8503, 8504, 8502, -1, + 8504, 8503, 8505, -1, 8505, 8506, 8504, -1, + 8506, 8505, 8507, -1, 8507, 8508, 8506, -1, + 8508, 8507, 8509, -1, 8509, 8510, 8508, -1, + 8510, 8509, 8511, -1, 8511, 8512, 8510, -1, + 8512, 8511, 8513, -1, 8513, 8514, 8512, -1, + 8514, 8513, 8515, -1, 8515, 8516, 8514, -1, + 8516, 8515, 8517, -1, 8517, 8518, 8516, -1, + 8518, 8517, 8519, -1, 8520, 8521, 8522, -1, + 8522, 8523, 8520, -1, 8522, 8524, 8523, -1, + 8524, 8522, 8525, -1, 8525, 8526, 8524, -1, + 8526, 8525, 8527, -1, 8527, 8528, 8526, -1, + 8528, 8527, 8529, -1, 8529, 8530, 8528, -1, + 8530, 8529, 8531, -1, 8531, 8532, 8530, -1, + 8532, 8531, 8533, -1, 8533, 8534, 8532, -1, + 8534, 8533, 8535, -1, 8535, 8536, 8534, -1, + 8536, 8535, 8537, -1, 8537, 8538, 8536, -1, + 8538, 8537, 8539, -1, 8539, 8540, 8538, -1, + 8540, 8539, 8541, -1, 8541, 8542, 8540, -1, + 8542, 8541, 8543, -1, 8543, 8544, 8542, -1, + 8544, 8543, 8545, -1, 8545, 8546, 8544, -1, + 8546, 8545, 8547, -1, 8547, 8548, 8546, -1, + 8548, 8547, 8549, -1, 8549, 8550, 8548, -1, + 8550, 8549, 8519, -1, 8519, 8551, 8550, -1, + 8551, 8519, 8517, -1, 8517, 8552, 8551, -1, + 8552, 8517, 8515, -1, 8515, 8553, 8552, -1, + 8553, 8515, 8513, -1, 8513, 8554, 8553, -1, + 8554, 8513, 8511, -1, 8511, 8555, 8554, -1, + 8555, 8511, 8509, -1, 8509, 8556, 8555, -1, + 8556, 8509, 8507, -1, 8507, 8557, 8556, -1, + 8557, 8507, 8505, -1, 8505, 8558, 8557, -1, + 8558, 8505, 8503, -1, 8503, 8559, 8558, -1, + 8559, 8503, 8501, -1, 8501, 8560, 8559, -1, + 8560, 8501, 8499, -1, 8499, 8561, 8560, -1, + 8561, 8499, 8497, -1, 8497, 8562, 8561, -1, + 8562, 8497, 8495, -1, 8495, 8563, 8562, -1, + 8563, 8495, 8493, -1, 8493, 8564, 8563, -1, + 8564, 8493, 8491, -1, 8491, 8565, 8564, -1, + 8565, 8491, 8489, -1, 8489, 8566, 8565, -1, + 8566, 8489, 8487, -1, 8487, 8567, 8566, -1, + 8567, 8487, 8485, -1, 8485, 8568, 8567, -1, + 8568, 8485, 8483, -1, 8483, 8569, 8568, -1, + 8569, 8483, 8481, -1, 8481, 8570, 8569, -1, + 8570, 8481, 8479, -1, 8479, 8571, 8570, -1, + 8571, 8479, 8477, -1, 8477, 8572, 8571, -1, + 8572, 8477, 8475, -1, 8475, 8573, 8572, -1, + 8573, 8475, 8473, -1, 8473, 8574, 8573, -1, + 8574, 8473, 8471, -1, 8471, 8575, 8574, -1, + 8575, 8471, 8469, -1, 8469, 8576, 8575, -1, + 8576, 8469, 8467, -1, 8467, 8577, 8576, -1, + 8577, 8467, 8465, -1, 8465, 8578, 8577, -1, + 8578, 8465, 8464, -1, 8464, 8579, 8578, -1, + 8464, 8580, 8579, -1, 8580, 8464, 8462, -1, + 8462, 8581, 8580, -1, 8581, 8462, 8460, -1, + 8460, 8582, 8581, -1, 8582, 8460, 8458, -1, + 8458, 8583, 8582, -1, 8583, 8458, 8456, -1, + 8456, 8584, 8583, -1, 8584, 8456, 8454, -1, + 8454, 8585, 8584, -1, 8585, 8454, 8452, -1, + 8452, 8586, 8585, -1, 8586, 8452, 8450, -1, + 8450, 8587, 8586, -1, 8587, 8450, 8448, -1, + 8448, 8588, 8587, -1, 8588, 8448, 8446, -1, + 8446, 8589, 8588, -1, 8589, 8446, 8444, -1, + 8444, 8590, 8589, -1, 8590, 8444, 8442, -1, + 8442, 8591, 8590, -1, 8591, 8442, 8440, -1, + 8440, 8592, 8591, -1, 8592, 8440, 8438, -1, + 8438, 8593, 8592, -1, 8593, 8438, 8436, -1, + 8436, 8594, 8593, -1, 8594, 8436, 8434, -1, + 8434, 8595, 8594, -1, 8595, 8434, 8432, -1, + 8432, 8596, 8595, -1, 8596, 8432, 8430, -1, + 8430, 8597, 8596, -1, 8597, 8430, 8428, -1, + 8428, 8598, 8597, -1, 8598, 8428, 8426, -1, + 8426, 8599, 8598, -1, 8599, 8426, 8424, -1, + 8424, 8600, 8599, -1, 8600, 8424, 8422, -1, + 8422, 8601, 8600, -1, 8601, 8422, 8420, -1, + 8420, 8602, 8601, -1, 8602, 8420, 8418, -1, + 8418, 8603, 8602, -1, 8603, 8418, 8416, -1, + 8416, 8604, 8603, -1, 8604, 8416, 8414, -1, + 8414, 8605, 8604, -1, 8605, 8414, 8412, -1, + 8412, 8606, 8605, -1, 8606, 8412, 8410, -1, + 8410, 8607, 8606, -1, 8607, 8410, 8407, -1, + 8407, 7810, 8607, -1, 8607, 7810, 7809, -1, + 7809, 8606, 8607, -1, 8606, 7809, 7808, -1, + 7808, 8605, 8606, -1, 8605, 7808, 7807, -1, + 7807, 8604, 8605, -1, 8604, 7807, 7806, -1, + 7806, 8603, 8604, -1, 8603, 7806, 7805, -1, + 7805, 8602, 8603, -1, 8602, 7805, 7804, -1, + 7804, 8601, 8602, -1, 8601, 7804, 7803, -1, + 7803, 8600, 8601, -1, 8600, 7803, 7802, -1, + 7802, 8599, 8600, -1, 8599, 7802, 7801, -1, + 7801, 8598, 8599, -1, 8598, 7801, 7800, -1, + 7800, 8597, 8598, -1, 8597, 7800, 7799, -1, + 7799, 8596, 8597, -1, 8596, 7799, 7798, -1, + 7798, 8595, 8596, -1, 8595, 7798, 7797, -1, + 7797, 8594, 8595, -1, 8594, 7797, 7796, -1, + 7796, 8593, 8594, -1, 8593, 7796, 7795, -1, + 7795, 8592, 8593, -1, 8592, 7795, 7794, -1, + 7794, 8591, 8592, -1, 8591, 7794, 7793, -1, + 7793, 8590, 8591, -1, 8590, 7793, 7792, -1, + 7792, 8589, 8590, -1, 8589, 7792, 7791, -1, + 7791, 8588, 8589, -1, 8588, 7791, 7790, -1, + 7790, 8587, 8588, -1, 8587, 7790, 7789, -1, + 7789, 8586, 8587, -1, 8586, 7789, 7788, -1, + 7788, 8585, 8586, -1, 8585, 7788, 7787, -1, + 7787, 8584, 8585, -1, 8584, 7787, 7786, -1, + 7786, 8583, 8584, -1, 8583, 7786, 7785, -1, + 7785, 8582, 8583, -1, 8582, 7785, 7784, -1, + 7784, 8581, 8582, -1, 8581, 7784, 7783, -1, + 7783, 8580, 8581, -1, 8580, 7783, 7782, -1, + 7782, 8579, 8580, -1, 8579, 7782, 7781, -1, + 8579, 7781, 7780, -1, 7780, 8578, 8579, -1, + 8578, 7780, 7779, -1, 7779, 8577, 8578, -1, + 8577, 7779, 7778, -1, 7778, 8576, 8577, -1, + 8576, 7778, 7777, -1, 7777, 8575, 8576, -1, + 8575, 7777, 7776, -1, 7776, 8574, 8575, -1, + 8574, 7776, 7775, -1, 7775, 8573, 8574, -1, + 8573, 7775, 7774, -1, 7774, 8572, 8573, -1, + 8572, 7774, 7773, -1, 7773, 8571, 8572, -1, + 8571, 7773, 7772, -1, 7772, 8570, 8571, -1, + 8570, 7772, 7771, -1, 7771, 8569, 8570, -1, + 8569, 7771, 7770, -1, 7770, 8568, 8569, -1, + 8568, 7770, 7769, -1, 7769, 8567, 8568, -1, + 8567, 7769, 7768, -1, 7768, 8566, 8567, -1, + 8566, 7768, 7767, -1, 7767, 8565, 8566, -1, + 8565, 7767, 7766, -1, 7766, 8564, 8565, -1, + 8564, 7766, 7765, -1, 7765, 8563, 8564, -1, + 8563, 7765, 7764, -1, 7764, 8562, 8563, -1, + 8562, 7764, 7763, -1, 7763, 8561, 8562, -1, + 8561, 7763, 7762, -1, 7762, 8560, 8561, -1, + 8560, 7762, 7761, -1, 7761, 8559, 8560, -1, + 8559, 7761, 7760, -1, 7760, 8558, 8559, -1, + 8558, 7760, 7759, -1, 7759, 8557, 8558, -1, + 8557, 7759, 7758, -1, 7758, 8556, 8557, -1, + 8556, 7758, 7757, -1, 7757, 8555, 8556, -1, + 8555, 7757, 7756, -1, 7756, 8554, 8555, -1, + 8554, 7756, 7755, -1, 7755, 8553, 8554, -1, + 8553, 7755, 7754, -1, 7754, 8552, 8553, -1, + 8552, 7754, 7753, -1, 7753, 8551, 8552, -1, + 8551, 7753, 2816, -1, 2816, 8550, 8551, -1, + 8550, 2816, 2814, -1, 2814, 8548, 8550, -1, + 8548, 2814, 2812, -1, 2812, 8546, 8548, -1, + 8546, 2812, 2810, -1, 2810, 8544, 8546, -1, + 8544, 2810, 2808, -1, 2808, 8542, 8544, -1, + 8542, 2808, 2806, -1, 2806, 8540, 8542, -1, + 8540, 2806, 2804, -1, 2804, 8538, 8540, -1, + 8538, 2804, 2802, -1, 2802, 8536, 8538, -1, + 8536, 2802, 2800, -1, 2800, 8534, 8536, -1, + 8534, 2800, 2798, -1, 2798, 8532, 8534, -1, + 8532, 2798, 2796, -1, 2796, 8530, 8532, -1, + 8530, 2796, 2794, -1, 2794, 8528, 8530, -1, + 8528, 2794, 2792, -1, 2792, 8526, 8528, -1, + 8526, 2792, 2790, -1, 2790, 8524, 8526, -1, + 8524, 2790, 2788, -1, 2788, 8523, 8524, -1, + 8523, 2788, 2784, -1, 8523, 2784, 8608, -1, + 8609, 8608, 2784, -1, 8609, 8610, 8608, -1, + 8611, 8610, 8609, -1, 8609, 2784, 8611, -1, + 8611, 2784, 2786, -1, 2786, 8610, 8611, -1, + 2786, 8612, 8610, -1, 8612, 2786, 2785, -1, + 8612, 2785, 4210, -1, 4210, 8610, 8612, -1, + 8610, 4210, 4212, -1, 8613, 7360, 7357, -1, + 7357, 8614, 8613, -1, 7357, 7359, 8614, -1, + 8614, 7359, 7471, -1, 7471, 8613, 8614, -1, + 7471, 7472, 8613, -1, 7472, 7473, 8613, -1, + 7473, 8615, 8613, -1, 8615, 7473, 7276, -1, + 8615, 7276, 7277, -1, 7277, 7279, 8615, -1, + 7279, 8613, 8615, -1, 8616, 7279, 7281, -1, + 8617, 8616, 7281, -1, 8617, 7281, 7282, -1, + 8617, 7282, 7284, -1, 7284, 8616, 8617, -1, + 7284, 8618, 8616, -1, 7284, 7283, 8618, -1, + 8619, 8618, 7283, -1, 8619, 8616, 8618, -1, + 8619, 8620, 8616, -1, 8619, 7283, 8620, -1, + 8621, 8620, 7283, -1, 7283, 8622, 8621, -1, + 8622, 7283, 7285, -1, 7285, 8623, 8622, -1, + 8623, 7285, 7286, -1, 7286, 8624, 8623, -1, + 8624, 7286, 7287, -1, 7287, 8625, 8624, -1, + 8625, 7287, 7288, -1, 7288, 8626, 8625, -1, + 8626, 7288, 7289, -1, 7289, 8627, 8626, -1, + 8627, 7289, 7290, -1, 7290, 8628, 8627, -1, + 8628, 7290, 7291, -1, 7291, 8629, 8628, -1, + 8629, 7291, 7292, -1, 7292, 8630, 8629, -1, + 8630, 7292, 7293, -1, 7293, 8631, 8630, -1, + 8631, 7293, 7294, -1, 7294, 8632, 8631, -1, + 8632, 7294, 7295, -1, 7295, 8633, 8632, -1, + 8633, 7295, 7296, -1, 7296, 8634, 8633, -1, + 8634, 7296, 7297, -1, 7297, 8635, 8634, -1, + 8635, 7297, 7298, -1, 7298, 8636, 8635, -1, + 8636, 7298, 7299, -1, 7299, 8637, 8636, -1, + 8637, 7299, 7300, -1, 7300, 8638, 8637, -1, + 8638, 7300, 7301, -1, 7301, 8639, 8638, -1, + 8639, 7301, 7302, -1, 7302, 8640, 8639, -1, + 8640, 7302, 7303, -1, 7303, 8641, 8640, -1, + 7303, 8642, 8641, -1, 8642, 7303, 7304, -1, + 7304, 8643, 8642, -1, 8643, 7304, 7305, -1, + 7305, 8644, 8643, -1, 8644, 7305, 7306, -1, + 7306, 8645, 8644, -1, 8645, 7306, 7307, -1, + 7307, 8646, 8645, -1, 8646, 7307, 7308, -1, + 7308, 8647, 8646, -1, 8647, 7308, 7309, -1, + 7309, 8648, 8647, -1, 8648, 7309, 7310, -1, + 7310, 8649, 8648, -1, 8649, 7310, 7311, -1, + 7311, 8650, 8649, -1, 8650, 7311, 7312, -1, + 7312, 8651, 8650, -1, 8651, 7312, 7313, -1, + 7313, 8652, 8651, -1, 8652, 7313, 7314, -1, + 7314, 8653, 8652, -1, 8653, 7314, 7315, -1, + 7315, 8654, 8653, -1, 8654, 7315, 7316, -1, + 7316, 8655, 8654, -1, 8655, 7316, 7317, -1, + 7317, 8656, 8655, -1, 8656, 7317, 7318, -1, + 7318, 8657, 8656, -1, 8657, 7318, 7319, -1, + 7319, 8658, 8657, -1, 8658, 7319, 7320, -1, + 7320, 8659, 8658, -1, 8659, 7320, 7321, -1, + 7321, 8660, 8659, -1, 8660, 7321, 7198, -1, + 7198, 8661, 8660, -1, 8661, 7198, 7197, -1, + 8662, 8661, 7197, -1, 8662, 8663, 8661, -1, + 771, 8661, 8663, -1, 8663, 773, 771, -1, + 8663, 772, 773, -1, 8663, 8662, 772, -1, + 8662, 7197, 772, -1, 772, 7197, 7199, -1, + 772, 460, 294, -1, 294, 293, 772, -1, + 293, 770, 772, -1, 293, 295, 770, -1, + 295, 771, 770, -1, 771, 295, 463, -1, + 463, 8664, 771, -1, 8664, 463, 465, -1, + 465, 8665, 8664, -1, 8665, 465, 467, -1, + 467, 8666, 8665, -1, 8666, 467, 469, -1, + 469, 8667, 8666, -1, 8667, 469, 471, -1, + 471, 8668, 8667, -1, 8668, 471, 473, -1, + 473, 8669, 8668, -1, 8669, 473, 475, -1, + 475, 8670, 8669, -1, 8670, 475, 477, -1, + 477, 8671, 8670, -1, 8671, 477, 479, -1, + 479, 8672, 8671, -1, 8672, 479, 481, -1, + 481, 8673, 8672, -1, 8673, 481, 483, -1, + 483, 8674, 8673, -1, 8674, 483, 485, -1, + 485, 8675, 8674, -1, 8675, 485, 487, -1, + 487, 8676, 8675, -1, 8676, 487, 489, -1, + 489, 8677, 8676, -1, 8677, 489, 491, -1, + 491, 8678, 8677, -1, 8678, 491, 493, -1, + 493, 8679, 8678, -1, 8679, 493, 495, -1, + 495, 8680, 8679, -1, 8680, 495, 497, -1, + 497, 8681, 8680, -1, 8681, 497, 499, -1, + 499, 8682, 8681, -1, 8682, 499, 501, -1, + 501, 8683, 8682, -1, 8683, 501, 503, -1, + 503, 8684, 8683, -1, 8684, 503, 505, -1, + 8684, 505, 508, -1, 508, 8685, 8684, -1, + 8685, 508, 510, -1, 510, 8686, 8685, -1, + 8686, 510, 512, -1, 512, 8687, 8686, -1, + 8687, 512, 514, -1, 514, 8688, 8687, -1, + 8688, 514, 516, -1, 516, 8689, 8688, -1, + 8689, 516, 518, -1, 518, 8690, 8689, -1, + 8690, 518, 520, -1, 520, 8691, 8690, -1, + 8691, 520, 522, -1, 522, 8692, 8691, -1, + 8692, 522, 524, -1, 524, 8693, 8692, -1, + 8693, 524, 526, -1, 526, 8694, 8693, -1, + 8694, 526, 528, -1, 528, 8695, 8694, -1, + 8695, 528, 530, -1, 530, 8696, 8695, -1, + 8696, 530, 532, -1, 532, 8697, 8696, -1, + 8697, 532, 534, -1, 534, 8698, 8697, -1, + 8698, 534, 536, -1, 536, 8699, 8698, -1, + 8699, 536, 538, -1, 538, 8700, 8699, -1, + 8700, 538, 540, -1, 540, 8701, 8700, -1, + 8701, 540, 542, -1, 542, 8702, 8701, -1, + 8702, 542, 544, -1, 544, 8703, 8702, -1, + 8703, 544, 546, -1, 546, 8704, 8703, -1, + 8704, 546, 548, -1, 548, 8705, 8704, -1, + 8706, 8707, 8708, -1, 8708, 8709, 8706, -1, + 8709, 8708, 8705, -1, 8705, 548, 8709, -1, + 8709, 548, 549, -1, 8709, 549, 594, -1, + 594, 8706, 8709, -1, 8706, 594, 290, -1, + 290, 289, 8706, -1, 8710, 8706, 289, -1, + 8710, 8711, 8706, -1, 8711, 8707, 8706, -1, + 8711, 8712, 8707, -1, 8711, 8710, 8712, -1, + 8710, 289, 8712, -1, 8712, 289, 291, -1, + 287, 285, 8712, -1, 8713, 8712, 285, -1, + 8713, 8707, 8712, -1, 8713, 8708, 8707, -1, + 8713, 285, 8708, -1, 8708, 285, 284, -1, + 284, 8705, 8708, -1, 8705, 284, 8714, -1, + 8714, 8704, 8705, -1, 8704, 8714, 8715, -1, + 8715, 8703, 8704, -1, 8703, 8715, 8716, -1, + 8716, 8702, 8703, -1, 8702, 8716, 8717, -1, + 8717, 8701, 8702, -1, 8701, 8717, 8718, -1, + 8718, 8700, 8701, -1, 8700, 8718, 8719, -1, + 8719, 8699, 8700, -1, 8699, 8719, 8720, -1, + 8720, 8698, 8699, -1, 8698, 8720, 8721, -1, + 8721, 8697, 8698, -1, 8697, 8721, 8722, -1, + 8722, 8696, 8697, -1, 8696, 8722, 8723, -1, + 8723, 8695, 8696, -1, 8695, 8723, 8724, -1, + 8724, 8694, 8695, -1, 8694, 8724, 8725, -1, + 8725, 8693, 8694, -1, 8693, 8725, 8726, -1, + 8726, 8692, 8693, -1, 8692, 8726, 8727, -1, + 8727, 8691, 8692, -1, 8691, 8727, 8728, -1, + 8728, 8690, 8691, -1, 8690, 8728, 8729, -1, + 8729, 8689, 8690, -1, 8689, 8729, 8730, -1, + 8730, 8688, 8689, -1, 8688, 8730, 8731, -1, + 8731, 8687, 8688, -1, 8687, 8731, 8732, -1, + 8732, 8686, 8687, -1, 8686, 8732, 8733, -1, + 8733, 8685, 8686, -1, 8685, 8733, 8734, -1, + 8734, 8684, 8685, -1, 8734, 8683, 8684, -1, + 8683, 8734, 8735, -1, 8735, 8682, 8683, -1, + 8682, 8735, 8736, -1, 8736, 8681, 8682, -1, + 8681, 8736, 8737, -1, 8737, 8680, 8681, -1, + 8680, 8737, 8738, -1, 8738, 8679, 8680, -1, + 8679, 8738, 8739, -1, 8739, 8678, 8679, -1, + 8678, 8739, 8740, -1, 8740, 8677, 8678, -1, + 8677, 8740, 8741, -1, 8741, 8676, 8677, -1, + 8676, 8741, 8742, -1, 8742, 8675, 8676, -1, + 8675, 8742, 8743, -1, 8743, 8674, 8675, -1, + 8674, 8743, 8744, -1, 8744, 8673, 8674, -1, + 8673, 8744, 8745, -1, 8745, 8672, 8673, -1, + 8672, 8745, 8746, -1, 8746, 8671, 8672, -1, + 8671, 8746, 8747, -1, 8747, 8670, 8671, -1, + 8670, 8747, 8748, -1, 8748, 8669, 8670, -1, + 8669, 8748, 8749, -1, 8749, 8668, 8669, -1, + 8668, 8749, 8750, -1, 8750, 8667, 8668, -1, + 8667, 8750, 8751, -1, 8751, 8666, 8667, -1, + 8666, 8751, 8752, -1, 8752, 8665, 8666, -1, + 8665, 8752, 8753, -1, 8753, 8664, 8665, -1, + 8664, 8753, 8754, -1, 8754, 771, 8664, -1, + 8754, 8661, 771, -1, 8754, 8660, 8661, -1, + 8660, 8754, 8753, -1, 8753, 8659, 8660, -1, + 8659, 8753, 8752, -1, 8752, 8658, 8659, -1, + 8658, 8752, 8751, -1, 8751, 8657, 8658, -1, + 8657, 8751, 8750, -1, 8750, 8656, 8657, -1, + 8656, 8750, 8749, -1, 8749, 8655, 8656, -1, + 8655, 8749, 8748, -1, 8748, 8654, 8655, -1, + 8654, 8748, 8747, -1, 8747, 8653, 8654, -1, + 8653, 8747, 8746, -1, 8746, 8652, 8653, -1, + 8652, 8746, 8745, -1, 8745, 8651, 8652, -1, + 8651, 8745, 8744, -1, 8744, 8650, 8651, -1, + 8650, 8744, 8743, -1, 8743, 8649, 8650, -1, + 8649, 8743, 8742, -1, 8742, 8648, 8649, -1, + 8648, 8742, 8741, -1, 8741, 8647, 8648, -1, + 8647, 8741, 8740, -1, 8740, 8646, 8647, -1, + 8646, 8740, 8739, -1, 8739, 8645, 8646, -1, + 8645, 8739, 8738, -1, 8738, 8644, 8645, -1, + 8644, 8738, 8737, -1, 8737, 8643, 8644, -1, + 8643, 8737, 8736, -1, 8736, 8642, 8643, -1, + 8642, 8736, 8735, -1, 8735, 8641, 8642, -1, + 8641, 8735, 8734, -1, 8641, 8734, 8733, -1, + 8733, 8640, 8641, -1, 8640, 8733, 8732, -1, + 8732, 8639, 8640, -1, 8639, 8732, 8731, -1, + 8731, 8638, 8639, -1, 8638, 8731, 8730, -1, + 8730, 8637, 8638, -1, 8637, 8730, 8729, -1, + 8729, 8636, 8637, -1, 8636, 8729, 8728, -1, + 8728, 8635, 8636, -1, 8635, 8728, 8727, -1, + 8727, 8634, 8635, -1, 8634, 8727, 8726, -1, + 8726, 8633, 8634, -1, 8633, 8726, 8725, -1, + 8725, 8632, 8633, -1, 8632, 8725, 8724, -1, + 8724, 8631, 8632, -1, 8631, 8724, 8723, -1, + 8723, 8630, 8631, -1, 8630, 8723, 8722, -1, + 8722, 8629, 8630, -1, 8629, 8722, 8721, -1, + 8721, 8628, 8629, -1, 8628, 8721, 8720, -1, + 8720, 8627, 8628, -1, 8627, 8720, 8719, -1, + 8719, 8626, 8627, -1, 8626, 8719, 8718, -1, + 8718, 8625, 8626, -1, 8625, 8718, 8717, -1, + 8717, 8624, 8625, -1, 8624, 8717, 8716, -1, + 8716, 8623, 8624, -1, 8623, 8716, 8715, -1, + 8715, 8622, 8623, -1, 8622, 8715, 8714, -1, + 8714, 8621, 8622, -1, 8621, 8714, 284, -1, + 284, 8755, 8621, -1, 8755, 284, 286, -1, + 8755, 286, 287, -1, 8755, 287, 8756, -1, + 8756, 8621, 8755, -1, 8756, 8620, 8621, -1, + 8620, 8756, 287, -1, 287, 8616, 8620, -1, + 8757, 599, 705, -1, 705, 706, 8757, -1, + 706, 707, 8757, -1, 707, 709, 8757, -1, + 709, 8758, 8757, -1, 8759, 8760, 8761, -1, + 8759, 8761, 8762, -1, 8762, 8763, 8759, -1, + 8763, 8762, 8764, -1, 8764, 8765, 8763, -1, + 8765, 8764, 8766, -1, 8766, 8767, 8765, -1, + 8768, 8765, 8767, -1, 8768, 8767, 8757, -1, + 8768, 8757, 8758, -1, 8758, 8765, 8768, -1, + 8758, 709, 8765, -1, 8765, 709, 708, -1, + 708, 8763, 8765, -1, 8763, 708, 710, -1, + 710, 8759, 8763, -1, 8759, 710, 711, -1, + 711, 8760, 8759, -1, 8760, 711, 712, -1, + 712, 8769, 8760, -1, 8769, 712, 713, -1, + 713, 8770, 8769, -1, 8770, 713, 714, -1, + 714, 8771, 8770, -1, 8771, 714, 715, -1, + 715, 8772, 8771, -1, 8772, 715, 716, -1, + 716, 8773, 8772, -1, 8773, 716, 717, -1, + 717, 8774, 8773, -1, 8774, 717, 718, -1, + 718, 8775, 8774, -1, 8775, 718, 719, -1, + 719, 8776, 8775, -1, 8776, 719, 720, -1, + 720, 8777, 8776, -1, 8777, 720, 721, -1, + 721, 8778, 8777, -1, 8778, 721, 722, -1, + 722, 8779, 8778, -1, 8779, 722, 723, -1, + 723, 8780, 8779, -1, 8780, 723, 724, -1, + 724, 8781, 8780, -1, 8781, 724, 725, -1, + 725, 8782, 8781, -1, 8782, 725, 726, -1, + 726, 8783, 8782, -1, 8783, 726, 727, -1, + 727, 8784, 8783, -1, 8784, 727, 728, -1, + 728, 8785, 8784, -1, 8785, 728, 729, -1, + 729, 8786, 8785, -1, 8786, 729, 730, -1, + 730, 8787, 8786, -1, 8787, 730, 731, -1, + 731, 8788, 8787, -1, 8788, 731, 732, -1, + 732, 8789, 8788, -1, 8789, 732, 733, -1, + 733, 8790, 8789, -1, 8790, 733, 734, -1, + 734, 8791, 8790, -1, 8791, 734, 735, -1, + 735, 8792, 8791, -1, 8792, 735, 736, -1, + 736, 8793, 8792, -1, 8793, 736, 737, -1, + 737, 8794, 8793, -1, 737, 8795, 8794, -1, + 8795, 737, 738, -1, 738, 8796, 8795, -1, + 8796, 738, 739, -1, 739, 8797, 8796, -1, + 8797, 739, 740, -1, 740, 8798, 8797, -1, + 8798, 740, 741, -1, 741, 8799, 8798, -1, + 8799, 741, 742, -1, 742, 8800, 8799, -1, + 8800, 742, 743, -1, 743, 8801, 8800, -1, + 8801, 743, 744, -1, 744, 8802, 8801, -1, + 8802, 744, 745, -1, 745, 8803, 8802, -1, + 8803, 745, 746, -1, 746, 8804, 8803, -1, + 8804, 746, 747, -1, 747, 8805, 8804, -1, + 8805, 747, 748, -1, 748, 8806, 8805, -1, + 8806, 748, 749, -1, 749, 8807, 8806, -1, + 8807, 749, 750, -1, 750, 8808, 8807, -1, + 8808, 750, 751, -1, 751, 8809, 8808, -1, + 8809, 751, 752, -1, 752, 8810, 8809, -1, + 8810, 752, 753, -1, 753, 8811, 8810, -1, + 8811, 753, 754, -1, 754, 8812, 8811, -1, + 8812, 754, 755, -1, 755, 8813, 8812, -1, + 8813, 755, 756, -1, 756, 8814, 8813, -1, + 8814, 756, 757, -1, 757, 8815, 8814, -1, + 8815, 757, 758, -1, 758, 8816, 8815, -1, + 8816, 758, 759, -1, 759, 8817, 8816, -1, + 8817, 759, 760, -1, 760, 8818, 8817, -1, + 8818, 760, 761, -1, 761, 8819, 8818, -1, + 8819, 761, 762, -1, 762, 8820, 8819, -1, + 8820, 762, 763, -1, 763, 8821, 8820, -1, + 8821, 763, 764, -1, 764, 8822, 8821, -1, + 8822, 764, 765, -1, 765, 8823, 8822, -1, + 8823, 765, 8824, -1, 8825, 8823, 8824, -1, + 8825, 8826, 8823, -1, 8826, 8827, 8823, -1, + 8826, 8828, 8827, -1, 8826, 8825, 8828, -1, + 8825, 8824, 8828, -1, 8824, 8829, 8828, -1, + 8829, 8824, 765, -1, 8829, 765, 766, -1, + 8829, 766, 768, -1, 768, 8828, 8829, -1, + 8828, 8356, 8370, -1, 8370, 8827, 8828, -1, + 8370, 8368, 8827, -1, 8368, 8823, 8827, -1, + 8823, 8368, 8367, -1, 8367, 8822, 8823, -1, + 8822, 8367, 8366, -1, 8366, 8821, 8822, -1, + 8821, 8366, 8830, -1, 8830, 8820, 8821, -1, + 8820, 8830, 8831, -1, 8831, 8819, 8820, -1, + 8819, 8831, 8832, -1, 8832, 8818, 8819, -1, + 8818, 8832, 8833, -1, 8833, 8817, 8818, -1, + 8817, 8833, 8834, -1, 8834, 8816, 8817, -1, + 8816, 8834, 8835, -1, 8835, 8815, 8816, -1, + 8815, 8835, 8836, -1, 8836, 8814, 8815, -1, + 8814, 8836, 8837, -1, 8837, 8813, 8814, -1, + 8813, 8837, 8838, -1, 8838, 8812, 8813, -1, + 8812, 8838, 8839, -1, 8839, 8811, 8812, -1, + 8811, 8839, 8840, -1, 8840, 8810, 8811, -1, + 8810, 8840, 8841, -1, 8841, 8809, 8810, -1, + 8809, 8841, 8842, -1, 8842, 8808, 8809, -1, + 8808, 8842, 8843, -1, 8843, 8807, 8808, -1, + 8807, 8843, 8844, -1, 8844, 8806, 8807, -1, + 8806, 8844, 8845, -1, 8845, 8805, 8806, -1, + 8805, 8845, 8846, -1, 8846, 8804, 8805, -1, + 8804, 8846, 8847, -1, 8847, 8803, 8804, -1, + 8803, 8847, 8848, -1, 8848, 8802, 8803, -1, + 8802, 8848, 8849, -1, 8849, 8801, 8802, -1, + 8801, 8849, 8850, -1, 8850, 8800, 8801, -1, + 8800, 8850, 8851, -1, 8851, 8799, 8800, -1, + 8799, 8851, 8852, -1, 8852, 8798, 8799, -1, + 8798, 8852, 8853, -1, 8853, 8797, 8798, -1, + 8797, 8853, 8854, -1, 8854, 8796, 8797, -1, + 8796, 8854, 8855, -1, 8855, 8795, 8796, -1, + 8795, 8855, 8856, -1, 8856, 8794, 8795, -1, + 8794, 8856, 8857, -1, 8794, 8857, 8858, -1, + 8858, 8793, 8794, -1, 8793, 8858, 8859, -1, + 8859, 8792, 8793, -1, 8792, 8859, 8860, -1, + 8860, 8791, 8792, -1, 8791, 8860, 8861, -1, + 8861, 8790, 8791, -1, 8790, 8861, 8862, -1, + 8862, 8789, 8790, -1, 8789, 8862, 8863, -1, + 8863, 8788, 8789, -1, 8788, 8863, 8864, -1, + 8864, 8787, 8788, -1, 8787, 8864, 8865, -1, + 8865, 8786, 8787, -1, 8786, 8865, 8866, -1, + 8866, 8785, 8786, -1, 8785, 8866, 8867, -1, + 8867, 8784, 8785, -1, 8784, 8867, 8868, -1, + 8868, 8783, 8784, -1, 8783, 8868, 8869, -1, + 8869, 8782, 8783, -1, 8782, 8869, 8870, -1, + 8870, 8781, 8782, -1, 8781, 8870, 8871, -1, + 8871, 8780, 8781, -1, 8780, 8871, 8872, -1, + 8872, 8779, 8780, -1, 8779, 8872, 8873, -1, + 8873, 8778, 8779, -1, 8778, 8873, 8874, -1, + 8874, 8777, 8778, -1, 8777, 8874, 8875, -1, + 8875, 8776, 8777, -1, 8776, 8875, 8876, -1, + 8876, 8775, 8776, -1, 8775, 8876, 8877, -1, + 8877, 8774, 8775, -1, 8774, 8877, 8878, -1, + 8878, 8773, 8774, -1, 8773, 8878, 8879, -1, + 8879, 8772, 8773, -1, 8772, 8879, 8880, -1, + 8880, 8771, 8772, -1, 8771, 8880, 8881, -1, + 8881, 8770, 8771, -1, 8770, 8881, 8882, -1, + 8882, 8769, 8770, -1, 8769, 8882, 8883, -1, + 8883, 8760, 8769, -1, 8883, 8761, 8760, -1, + 8883, 8884, 8761, -1, 8884, 8883, 8882, -1, + 8882, 8885, 8884, -1, 8885, 8882, 8881, -1, + 8881, 8886, 8885, -1, 8886, 8881, 8880, -1, + 8880, 8887, 8886, -1, 8887, 8880, 8879, -1, + 8879, 8888, 8887, -1, 8888, 8879, 8878, -1, + 8878, 8889, 8888, -1, 8889, 8878, 8877, -1, + 8877, 8890, 8889, -1, 8890, 8877, 8876, -1, + 8876, 8891, 8890, -1, 8891, 8876, 8875, -1, + 8875, 8892, 8891, -1, 8892, 8875, 8874, -1, + 8874, 8893, 8892, -1, 8893, 8874, 8873, -1, + 8873, 8894, 8893, -1, 8894, 8873, 8872, -1, + 8872, 8895, 8894, -1, 8895, 8872, 8871, -1, + 8871, 8896, 8895, -1, 8896, 8871, 8870, -1, + 8870, 8897, 8896, -1, 8897, 8870, 8869, -1, + 8869, 8898, 8897, -1, 8898, 8869, 8868, -1, + 8868, 8899, 8898, -1, 8899, 8868, 8867, -1, + 8867, 8900, 8899, -1, 8900, 8867, 8866, -1, + 8866, 8901, 8900, -1, 8901, 8866, 8865, -1, + 8865, 8902, 8901, -1, 8902, 8865, 8864, -1, + 8864, 8903, 8902, -1, 8903, 8864, 8863, -1, + 8863, 8904, 8903, -1, 8904, 8863, 8862, -1, + 8862, 8905, 8904, -1, 8905, 8862, 8861, -1, + 8861, 8906, 8905, -1, 8906, 8861, 8860, -1, + 8860, 8907, 8906, -1, 8907, 8860, 8859, -1, + 8859, 8908, 8907, -1, 8908, 8859, 8858, -1, + 8858, 8909, 8908, -1, 8909, 8858, 8857, -1, + 8857, 8910, 8909, -1, 8857, 8911, 8910, -1, + 8911, 8857, 8856, -1, 8856, 8912, 8911, -1, + 8912, 8856, 8855, -1, 8855, 8913, 8912, -1, + 8913, 8855, 8854, -1, 8854, 8914, 8913, -1, + 8914, 8854, 8853, -1, 8853, 8915, 8914, -1, + 8915, 8853, 8852, -1, 8852, 8916, 8915, -1, + 8916, 8852, 8851, -1, 8851, 8917, 8916, -1, + 8917, 8851, 8850, -1, 8850, 8918, 8917, -1, + 8918, 8850, 8849, -1, 8849, 8919, 8918, -1, + 8919, 8849, 8848, -1, 8848, 8920, 8919, -1, + 8920, 8848, 8847, -1, 8847, 8921, 8920, -1, + 8921, 8847, 8846, -1, 8846, 8922, 8921, -1, + 8922, 8846, 8845, -1, 8845, 8923, 8922, -1, + 8923, 8845, 8844, -1, 8844, 8924, 8923, -1, + 8924, 8844, 8843, -1, 8843, 8925, 8924, -1, + 8925, 8843, 8842, -1, 8842, 8926, 8925, -1, + 8926, 8842, 8841, -1, 8841, 8927, 8926, -1, + 8927, 8841, 8840, -1, 8840, 8928, 8927, -1, + 8928, 8840, 8839, -1, 8839, 8929, 8928, -1, + 8929, 8839, 8838, -1, 8838, 8930, 8929, -1, + 8930, 8838, 8837, -1, 8837, 8931, 8930, -1, + 8931, 8837, 8836, -1, 8836, 8932, 8931, -1, + 8932, 8836, 8835, -1, 8835, 8933, 8932, -1, + 8933, 8835, 8834, -1, 8834, 8934, 8933, -1, + 8934, 8834, 8833, -1, 8833, 8935, 8934, -1, + 8935, 8833, 8832, -1, 8832, 8936, 8935, -1, + 8936, 8832, 8831, -1, 8831, 8937, 8936, -1, + 8937, 8831, 8830, -1, 8830, 8938, 8937, -1, + 8938, 8830, 8366, -1, 8366, 8358, 8938, -1, + 8358, 8360, 8938, -1, 8939, 8938, 8360, -1, + 8939, 8937, 8938, -1, 8937, 8939, 8940, -1, + 8940, 8936, 8937, -1, 8936, 8940, 8941, -1, + 8941, 8935, 8936, -1, 8935, 8941, 8942, -1, + 8942, 8934, 8935, -1, 8934, 8942, 8943, -1, + 8943, 8933, 8934, -1, 8933, 8943, 8944, -1, + 8944, 8932, 8933, -1, 8932, 8944, 8945, -1, + 8945, 8931, 8932, -1, 8931, 8945, 8946, -1, + 8946, 8930, 8931, -1, 8930, 8946, 8947, -1, + 8947, 8929, 8930, -1, 8929, 8947, 8948, -1, + 8948, 8928, 8929, -1, 8928, 8948, 8949, -1, + 8949, 8927, 8928, -1, 8927, 8949, 8950, -1, + 8950, 8926, 8927, -1, 8926, 8950, 8951, -1, + 8951, 8925, 8926, -1, 8925, 8951, 8952, -1, + 8952, 8924, 8925, -1, 8924, 8952, 8953, -1, + 8953, 8923, 8924, -1, 8923, 8953, 8954, -1, + 8954, 8922, 8923, -1, 8922, 8954, 8955, -1, + 8955, 8921, 8922, -1, 8921, 8955, 8956, -1, + 8956, 8920, 8921, -1, 8920, 8956, 8957, -1, + 8957, 8919, 8920, -1, 8919, 8957, 8958, -1, + 8958, 8918, 8919, -1, 8918, 8958, 8959, -1, + 8959, 8917, 8918, -1, 8917, 8959, 8960, -1, + 8960, 8916, 8917, -1, 8916, 8960, 8961, -1, + 8961, 8915, 8916, -1, 8915, 8961, 8962, -1, + 8962, 8914, 8915, -1, 8914, 8962, 8963, -1, + 8963, 8913, 8914, -1, 8913, 8963, 8964, -1, + 8964, 8912, 8913, -1, 8912, 8964, 8965, -1, + 8965, 8911, 8912, -1, 8911, 8965, 8966, -1, + 8966, 8910, 8911, -1, 8910, 8966, 8967, -1, + 8910, 8967, 8968, -1, 8968, 8909, 8910, -1, + 8909, 8968, 8969, -1, 8969, 8908, 8909, -1, + 8908, 8969, 8970, -1, 8970, 8907, 8908, -1, + 8907, 8970, 8971, -1, 8971, 8906, 8907, -1, + 8906, 8971, 8972, -1, 8972, 8905, 8906, -1, + 8905, 8972, 8973, -1, 8973, 8904, 8905, -1, + 8904, 8973, 8974, -1, 8974, 8903, 8904, -1, + 8903, 8974, 8975, -1, 8975, 8902, 8903, -1, + 8902, 8975, 8976, -1, 8976, 8901, 8902, -1, + 8901, 8976, 8977, -1, 8977, 8900, 8901, -1, + 8900, 8977, 8978, -1, 8978, 8899, 8900, -1, + 8899, 8978, 8979, -1, 8979, 8898, 8899, -1, + 8898, 8979, 8980, -1, 8980, 8897, 8898, -1, + 8897, 8980, 8981, -1, 8981, 8896, 8897, -1, + 8896, 8981, 8982, -1, 8982, 8895, 8896, -1, + 8895, 8982, 8983, -1, 8983, 8894, 8895, -1, + 8894, 8983, 8984, -1, 8984, 8893, 8894, -1, + 8893, 8984, 8985, -1, 8985, 8892, 8893, -1, + 8892, 8985, 8986, -1, 8986, 8891, 8892, -1, + 8891, 8986, 8987, -1, 8987, 8890, 8891, -1, + 8890, 8987, 8988, -1, 8988, 8889, 8890, -1, + 8889, 8988, 8989, -1, 8989, 8888, 8889, -1, + 8888, 8989, 8990, -1, 8990, 8887, 8888, -1, + 8887, 8990, 8991, -1, 8991, 8886, 8887, -1, + 8886, 8991, 8992, -1, 8992, 8885, 8886, -1, + 8885, 8992, 8993, -1, 8993, 8884, 8885, -1, + 8884, 8993, 8994, -1, 8994, 8761, 8884, -1, + 8761, 8994, 8995, -1, 8995, 8762, 8761, -1, + 8762, 8995, 8996, -1, 8996, 8764, 8762, -1, + 8764, 8996, 8997, -1, 8997, 8766, 8764, -1, + 8766, 8997, 8998, -1, 8998, 8999, 8766, -1, + 9000, 8999, 8998, -1, 9000, 282, 8999, -1, + 8999, 282, 9001, -1, 9001, 8766, 8999, -1, + 9001, 8767, 8766, -1, 9001, 8757, 8767, -1, + 8757, 9001, 282, -1, 9002, 282, 281, -1, + 9003, 9004, 9005, -1, 9005, 9002, 9003, -1, + 9005, 9006, 9002, -1, 9007, 9008, 9009, -1, + 9007, 9010, 9008, -1, 9011, 9012, 9013, -1, + 9011, 9013, 9014, -1, 9014, 9015, 9011, -1, + 9015, 9014, 9016, -1, 9016, 9017, 9015, -1, + 9017, 9016, 9018, -1, 9018, 9019, 9017, -1, + 9019, 9018, 9020, -1, 9020, 9021, 9019, -1, + 9021, 9020, 9010, -1, 9010, 9007, 9021, -1, + 9022, 9021, 9007, -1, 9021, 9022, 9023, -1, + 9023, 9019, 9021, -1, 9019, 9023, 9024, -1, + 9024, 9017, 9019, -1, 9017, 9024, 9025, -1, + 9025, 9015, 9017, -1, 9015, 9025, 9026, -1, + 9026, 9011, 9015, -1, 9011, 9026, 9027, -1, + 9027, 9012, 9011, -1, 9012, 9027, 9028, -1, + 9028, 9029, 9012, -1, 9029, 9028, 9030, -1, + 9030, 9031, 9029, -1, 9031, 9030, 9032, -1, + 9032, 9033, 9031, -1, 9033, 9032, 9034, -1, + 9034, 9035, 9033, -1, 9035, 9034, 9036, -1, + 9036, 9037, 9035, -1, 9037, 9036, 9038, -1, + 9038, 9039, 9037, -1, 9039, 9038, 9040, -1, + 9040, 9041, 9039, -1, 9041, 9040, 9042, -1, + 9042, 9043, 9041, -1, 9043, 9042, 9044, -1, + 9044, 9045, 9043, -1, 9045, 9044, 9046, -1, + 9046, 9047, 9045, -1, 9047, 9046, 9048, -1, + 9048, 9049, 9047, -1, 9049, 9048, 9050, -1, + 9050, 9051, 9049, -1, 9051, 9050, 9052, -1, + 9052, 9053, 9051, -1, 9053, 9052, 9054, -1, + 9054, 9055, 9053, -1, 9055, 9054, 9056, -1, + 9056, 9057, 9055, -1, 9057, 9056, 9058, -1, + 9058, 9059, 9057, -1, 9059, 9058, 9060, -1, + 9060, 9061, 9059, -1, 9061, 9060, 9062, -1, + 9062, 9063, 9061, -1, 9063, 9062, 9064, -1, + 9064, 9065, 9063, -1, 9065, 9064, 9066, -1, + 9066, 9067, 9065, -1, 9067, 9066, 9068, -1, + 9068, 9069, 9067, -1, 9069, 9068, 9070, -1, + 9070, 9071, 9069, -1, 9071, 9070, 9072, -1, + 9072, 9073, 9071, -1, 9073, 9072, 9074, -1, + 9074, 9075, 9073, -1, 9075, 9074, 9076, -1, + 9076, 9077, 9075, -1, 9077, 9076, 9078, -1, + 9078, 9079, 9077, -1, 9079, 9078, 9080, -1, + 9080, 9081, 9079, -1, 9081, 9080, 9082, -1, + 9082, 9083, 9081, -1, 9083, 9082, 9084, -1, + 9084, 9085, 9083, -1, 9085, 9084, 9086, -1, + 9086, 9087, 9085, -1, 9086, 9088, 9087, -1, + 9088, 9086, 9089, -1, 9089, 9090, 9088, -1, + 9090, 9089, 9091, -1, 9091, 9092, 9090, -1, + 9093, 9094, 9095, -1, 9096, 9097, 9098, -1, + 9096, 9099, 9097, -1, 9099, 9096, 9100, -1, + 9100, 9101, 9099, -1, 9101, 9100, 9102, -1, + 9102, 9103, 9101, -1, 9103, 9102, 9104, -1, + 9104, 9105, 9103, -1, 9105, 9104, 9094, -1, + 9094, 9093, 9105, -1, 9093, 9106, 9107, -1, + 9093, 9107, 9108, -1, 9108, 9105, 9093, -1, + 9105, 9108, 9109, -1, 9109, 9103, 9105, -1, + 9103, 9109, 9110, -1, 9110, 9101, 9103, -1, + 9101, 9110, 9111, -1, 9111, 9099, 9101, -1, + 9099, 9111, 9112, -1, 9112, 9097, 9099, -1, + 9097, 9112, 9113, -1, 9113, 9114, 9097, -1, + 9114, 9113, 9115, -1, 9115, 9116, 9114, -1, + 9116, 9115, 9117, -1, 9117, 9118, 9116, -1, + 9118, 9117, 9119, -1, 9119, 9120, 9118, -1, + 9120, 9119, 9121, -1, 9121, 9122, 9120, -1, + 9122, 9121, 9123, -1, 9123, 9124, 9122, -1, + 9124, 9123, 9125, -1, 9125, 9126, 9124, -1, + 9126, 9125, 9127, -1, 9127, 9128, 9126, -1, + 9128, 9127, 9129, -1, 9129, 9130, 9128, -1, + 9130, 9129, 9131, -1, 9131, 9132, 9130, -1, + 9132, 9131, 9133, -1, 9133, 9134, 9132, -1, + 9134, 9133, 9135, -1, 9135, 9136, 9134, -1, + 9136, 9135, 9137, -1, 9137, 9138, 9136, -1, + 9138, 9137, 9139, -1, 9139, 9140, 9138, -1, + 9140, 9139, 9141, -1, 9141, 9142, 9140, -1, + 9142, 9141, 9143, -1, 9143, 9144, 9142, -1, + 9144, 9143, 9145, -1, 9145, 9146, 9144, -1, + 9146, 9145, 9147, -1, 9147, 9148, 9146, -1, + 9148, 9147, 9149, -1, 9149, 9150, 9148, -1, + 9150, 9149, 9151, -1, 9151, 9152, 9150, -1, + 9152, 9151, 9153, -1, 9153, 9154, 9152, -1, + 9154, 9153, 9155, -1, 9155, 9156, 9154, -1, + 9156, 9155, 9157, -1, 9157, 9158, 9156, -1, + 9158, 9157, 9159, -1, 9159, 9160, 9158, -1, + 9160, 9159, 9161, -1, 9161, 9162, 9160, -1, + 9162, 9161, 9163, -1, 9163, 9164, 9162, -1, + 9164, 9163, 9092, -1, 9092, 9091, 9164, -1, + 9165, 9091, 9166, -1, 9165, 9164, 9091, -1, + 9164, 9165, 9167, -1, 9167, 9162, 9164, -1, + 9162, 9167, 9168, -1, 9168, 9160, 9162, -1, + 9160, 9168, 9169, -1, 9169, 9158, 9160, -1, + 9158, 9169, 9170, -1, 9170, 9156, 9158, -1, + 9156, 9170, 9171, -1, 9171, 9154, 9156, -1, + 9154, 9171, 9172, -1, 9172, 9152, 9154, -1, + 9152, 9172, 9173, -1, 9173, 9150, 9152, -1, + 9150, 9173, 9174, -1, 9174, 9148, 9150, -1, + 9148, 9174, 9175, -1, 9175, 9146, 9148, -1, + 9146, 9175, 9176, -1, 9176, 9144, 9146, -1, + 9144, 9176, 9177, -1, 9177, 9142, 9144, -1, + 9142, 9177, 9178, -1, 9178, 9140, 9142, -1, + 9140, 9178, 9179, -1, 9179, 9138, 9140, -1, + 9138, 9179, 9180, -1, 9180, 9136, 9138, -1, + 9136, 9180, 9181, -1, 9181, 9134, 9136, -1, + 9134, 9181, 9182, -1, 9182, 9132, 9134, -1, + 9132, 9182, 9183, -1, 9183, 9130, 9132, -1, + 9130, 9183, 9184, -1, 9184, 9128, 9130, -1, + 9128, 9184, 9185, -1, 9185, 9126, 9128, -1, + 9126, 9185, 9186, -1, 9186, 9124, 9126, -1, + 9124, 9186, 9187, -1, 9187, 9122, 9124, -1, + 9122, 9187, 9188, -1, 9188, 9120, 9122, -1, + 9120, 9188, 9189, -1, 9189, 9118, 9120, -1, + 9118, 9189, 9190, -1, 9190, 9116, 9118, -1, + 9116, 9190, 9191, -1, 9191, 9114, 9116, -1, + 9114, 9191, 9192, -1, 9192, 9097, 9114, -1, + 9192, 9098, 9097, -1, 9192, 9193, 9098, -1, + 9193, 9192, 9191, -1, 9191, 9194, 9193, -1, + 9194, 9191, 9190, -1, 9190, 9195, 9194, -1, + 9195, 9190, 9189, -1, 9189, 9196, 9195, -1, + 9196, 9189, 9188, -1, 9188, 9197, 9196, -1, + 9197, 9188, 9187, -1, 9187, 9198, 9197, -1, + 9198, 9187, 9186, -1, 9186, 9199, 9198, -1, + 9199, 9186, 9185, -1, 9185, 9200, 9199, -1, + 9200, 9185, 9184, -1, 9184, 9201, 9200, -1, + 9201, 9184, 9183, -1, 9183, 9202, 9201, -1, + 9202, 9183, 9182, -1, 9182, 9203, 9202, -1, + 9203, 9182, 9181, -1, 9181, 9204, 9203, -1, + 9204, 9181, 9180, -1, 9180, 9205, 9204, -1, + 9205, 9180, 9179, -1, 9179, 9206, 9205, -1, + 9206, 9179, 9178, -1, 9178, 9207, 9206, -1, + 9207, 9178, 9177, -1, 9177, 9208, 9207, -1, + 9208, 9177, 9176, -1, 9176, 9209, 9208, -1, + 9209, 9176, 9175, -1, 9175, 9210, 9209, -1, + 9210, 9175, 9174, -1, 9174, 9211, 9210, -1, + 9211, 9174, 9173, -1, 9173, 9212, 9211, -1, + 9212, 9173, 9172, -1, 9172, 9213, 9212, -1, + 9213, 9172, 9171, -1, 9171, 9214, 9213, -1, + 9214, 9171, 9170, -1, 9170, 9215, 9214, -1, + 9215, 9170, 9169, -1, 9169, 9216, 9215, -1, + 9216, 9169, 9168, -1, 9168, 9217, 9216, -1, + 9217, 9168, 9167, -1, 9167, 9218, 9217, -1, + 9218, 9167, 9165, -1, 9165, 9219, 9218, -1, + 9219, 9165, 9166, -1, 9166, 9220, 9219, -1, + 9220, 9166, 9221, -1, 9220, 9221, 9222, -1, + 9222, 9223, 9220, -1, 9223, 9222, 9224, -1, + 9224, 9225, 9223, -1, 9225, 9224, 9226, -1, + 9226, 9227, 9225, -1, 9227, 9226, 9228, -1, + 9228, 9229, 9227, -1, 9229, 9228, 9230, -1, + 9230, 9231, 9229, -1, 9231, 9230, 9232, -1, + 9232, 9233, 9231, -1, 9233, 9232, 9234, -1, + 9234, 9235, 9233, -1, 9235, 9234, 9236, -1, + 9236, 9237, 9235, -1, 9237, 9236, 9238, -1, + 9238, 9239, 9237, -1, 9239, 9238, 9240, -1, + 9240, 9241, 9239, -1, 9241, 9240, 9242, -1, + 9242, 9243, 9241, -1, 9243, 9242, 9244, -1, + 9244, 9245, 9243, -1, 9245, 9244, 9246, -1, + 9246, 9247, 9245, -1, 9247, 9246, 9248, -1, + 9248, 9249, 9247, -1, 9249, 9248, 9250, -1, + 9250, 9251, 9249, -1, 9251, 9250, 9252, -1, + 9252, 9253, 9251, -1, 9253, 9252, 9254, -1, + 9254, 9255, 9253, -1, 9255, 9254, 9256, -1, + 9256, 9257, 9255, -1, 9257, 9256, 9258, -1, + 9258, 9259, 9257, -1, 9259, 9258, 9260, -1, + 9260, 9261, 9259, -1, 9261, 9260, 9262, -1, + 9262, 9263, 9261, -1, 9263, 9262, 9264, -1, + 9264, 9265, 9263, -1, 9265, 9264, 9266, -1, + 9266, 9267, 9265, -1, 9267, 9266, 9268, -1, + 9268, 9269, 9267, -1, 9269, 9268, 9270, -1, + 9270, 9271, 9269, -1, 9271, 9270, 9272, -1, + 9272, 9273, 9271, -1, 9273, 9272, 9274, -1, + 9274, 9275, 9273, -1, 9275, 9274, 9276, -1, + 9276, 9277, 9275, -1, 9276, 9278, 9277, -1, + 9276, 9279, 9278, -1, 9279, 9276, 9274, -1, + 9274, 9280, 9279, -1, 9280, 9274, 9272, -1, + 9272, 9281, 9280, -1, 9281, 9272, 9270, -1, + 9270, 9282, 9281, -1, 9282, 9270, 9268, -1, + 9268, 9283, 9282, -1, 9283, 9268, 9266, -1, + 9266, 9284, 9283, -1, 9284, 9266, 9264, -1, + 9264, 9285, 9284, -1, 9285, 9264, 9262, -1, + 9262, 9286, 9285, -1, 9286, 9262, 9260, -1, + 9260, 9287, 9286, -1, 9287, 9260, 9258, -1, + 9258, 9288, 9287, -1, 9288, 9258, 9256, -1, + 9256, 9289, 9288, -1, 9289, 9256, 9254, -1, + 9254, 9290, 9289, -1, 9290, 9254, 9252, -1, + 9252, 9291, 9290, -1, 9291, 9252, 9250, -1, + 9250, 9292, 9291, -1, 9292, 9250, 9248, -1, + 9248, 9293, 9292, -1, 9293, 9248, 9246, -1, + 9246, 9294, 9293, -1, 9294, 9246, 9244, -1, + 9244, 9295, 9294, -1, 9295, 9244, 9242, -1, + 9242, 9296, 9295, -1, 9296, 9242, 9240, -1, + 9240, 9297, 9296, -1, 9297, 9240, 9238, -1, + 9238, 9298, 9297, -1, 9298, 9238, 9236, -1, + 9236, 9299, 9298, -1, 9299, 9236, 9234, -1, + 9234, 9300, 9299, -1, 9300, 9234, 9232, -1, + 9232, 9301, 9300, -1, 9301, 9232, 9230, -1, + 9230, 9302, 9301, -1, 9302, 9230, 9228, -1, + 9228, 9303, 9302, -1, 9303, 9228, 9226, -1, + 9226, 9304, 9303, -1, 9304, 9226, 9224, -1, + 9224, 9305, 9304, -1, 9305, 9224, 9222, -1, + 9222, 9306, 9305, -1, 9306, 9222, 9221, -1, + 9221, 9307, 9306, -1, 9221, 9308, 9307, -1, + 9308, 9221, 9166, -1, 9308, 9166, 9091, -1, + 9308, 9091, 9089, -1, 9089, 9307, 9308, -1, + 9307, 9089, 9086, -1, 9307, 9086, 9084, -1, + 9084, 9306, 9307, -1, 9306, 9084, 9082, -1, + 9082, 9305, 9306, -1, 9305, 9082, 9080, -1, + 9080, 9304, 9305, -1, 9304, 9080, 9078, -1, + 9078, 9303, 9304, -1, 9303, 9078, 9076, -1, + 9076, 9302, 9303, -1, 9302, 9076, 9074, -1, + 9074, 9301, 9302, -1, 9301, 9074, 9072, -1, + 9072, 9300, 9301, -1, 9300, 9072, 9070, -1, + 9070, 9299, 9300, -1, 9299, 9070, 9068, -1, + 9068, 9298, 9299, -1, 9298, 9068, 9066, -1, + 9066, 9297, 9298, -1, 9297, 9066, 9064, -1, + 9064, 9296, 9297, -1, 9296, 9064, 9062, -1, + 9062, 9295, 9296, -1, 9295, 9062, 9060, -1, + 9060, 9294, 9295, -1, 9294, 9060, 9058, -1, + 9058, 9293, 9294, -1, 9293, 9058, 9056, -1, + 9056, 9292, 9293, -1, 9292, 9056, 9054, -1, + 9054, 9291, 9292, -1, 9291, 9054, 9052, -1, + 9052, 9290, 9291, -1, 9290, 9052, 9050, -1, + 9050, 9289, 9290, -1, 9289, 9050, 9048, -1, + 9048, 9288, 9289, -1, 9288, 9048, 9046, -1, + 9046, 9287, 9288, -1, 9287, 9046, 9044, -1, + 9044, 9286, 9287, -1, 9286, 9044, 9042, -1, + 9042, 9285, 9286, -1, 9285, 9042, 9040, -1, + 9040, 9284, 9285, -1, 9284, 9040, 9038, -1, + 9038, 9283, 9284, -1, 9283, 9038, 9036, -1, + 9036, 9282, 9283, -1, 9282, 9036, 9034, -1, + 9034, 9281, 9282, -1, 9281, 9034, 9032, -1, + 9032, 9280, 9281, -1, 9280, 9032, 9030, -1, + 9030, 9279, 9280, -1, 9279, 9030, 9028, -1, + 9028, 9278, 9279, -1, 9278, 9028, 9027, -1, + 9027, 9309, 9278, -1, 9309, 9027, 9026, -1, + 9026, 9310, 9309, -1, 9310, 9026, 9025, -1, + 9025, 9311, 9310, -1, 9311, 9025, 9024, -1, + 9024, 9312, 9311, -1, 9312, 9024, 9023, -1, + 9023, 9313, 9312, -1, 9313, 9023, 9022, -1, + 9313, 9022, 9314, -1, 9315, 9314, 9022, -1, + 9314, 9315, 9002, -1, 9314, 9002, 9006, -1, + 9006, 9313, 9314, -1, 9006, 9005, 9313, -1, + 9313, 9005, 9004, -1, 9004, 9312, 9313, -1, + 9312, 9004, 9316, -1, 9316, 9311, 9312, -1, + 9311, 9316, 9317, -1, 9317, 9310, 9311, -1, + 9310, 9317, 9318, -1, 9318, 9309, 9310, -1, + 9309, 9318, 9319, -1, 9319, 9278, 9309, -1, + 9319, 9277, 9278, -1, 9320, 9277, 9319, -1, + 9277, 9320, 9321, -1, 9321, 9275, 9277, -1, + 9275, 9321, 9322, -1, 9322, 9273, 9275, -1, + 9273, 9322, 9323, -1, 9323, 9271, 9273, -1, + 9271, 9323, 9324, -1, 9324, 9269, 9271, -1, + 9269, 9324, 9325, -1, 9325, 9267, 9269, -1, + 9267, 9325, 9326, -1, 9326, 9265, 9267, -1, + 9265, 9326, 9327, -1, 9327, 9263, 9265, -1, + 9263, 9327, 9328, -1, 9328, 9261, 9263, -1, + 9261, 9328, 9329, -1, 9329, 9259, 9261, -1, + 9259, 9329, 9330, -1, 9330, 9257, 9259, -1, + 9257, 9330, 9331, -1, 9331, 9255, 9257, -1, + 9255, 9331, 9332, -1, 9332, 9253, 9255, -1, + 9253, 9332, 9333, -1, 9333, 9251, 9253, -1, + 9251, 9333, 9334, -1, 9334, 9249, 9251, -1, + 9249, 9334, 9335, -1, 9335, 9247, 9249, -1, + 9247, 9335, 9336, -1, 9336, 9245, 9247, -1, + 9245, 9336, 9337, -1, 9337, 9243, 9245, -1, + 9243, 9337, 9338, -1, 9338, 9241, 9243, -1, + 9241, 9338, 9339, -1, 9339, 9239, 9241, -1, + 9239, 9339, 9340, -1, 9340, 9237, 9239, -1, + 9237, 9340, 9341, -1, 9341, 9235, 9237, -1, + 9235, 9341, 9342, -1, 9342, 9233, 9235, -1, + 9233, 9342, 9343, -1, 9343, 9231, 9233, -1, + 9231, 9343, 9344, -1, 9344, 9229, 9231, -1, + 9229, 9344, 9345, -1, 9345, 9227, 9229, -1, + 9227, 9345, 9346, -1, 9346, 9225, 9227, -1, + 9225, 9346, 9347, -1, 9347, 9223, 9225, -1, + 9223, 9347, 9348, -1, 9348, 9220, 9223, -1, + 9348, 9219, 9220, -1, 9219, 9348, 9349, -1, + 9349, 9218, 9219, -1, 9218, 9349, 9350, -1, + 9350, 9217, 9218, -1, 9217, 9350, 9351, -1, + 9351, 9216, 9217, -1, 9216, 9351, 9352, -1, + 9352, 9215, 9216, -1, 9215, 9352, 9353, -1, + 9353, 9214, 9215, -1, 9214, 9353, 9354, -1, + 9354, 9213, 9214, -1, 9213, 9354, 9355, -1, + 9355, 9212, 9213, -1, 9212, 9355, 9356, -1, + 9356, 9211, 9212, -1, 9211, 9356, 9357, -1, + 9357, 9210, 9211, -1, 9210, 9357, 9358, -1, + 9358, 9209, 9210, -1, 9209, 9358, 9359, -1, + 9359, 9208, 9209, -1, 9208, 9359, 9360, -1, + 9360, 9207, 9208, -1, 9207, 9360, 9361, -1, + 9361, 9206, 9207, -1, 9206, 9361, 9362, -1, + 9362, 9205, 9206, -1, 9205, 9362, 9363, -1, + 9363, 9204, 9205, -1, 9204, 9363, 9364, -1, + 9364, 9203, 9204, -1, 9203, 9364, 9365, -1, + 9365, 9202, 9203, -1, 9202, 9365, 9366, -1, + 9366, 9201, 9202, -1, 9201, 9366, 9367, -1, + 9367, 9200, 9201, -1, 9200, 9367, 9368, -1, + 9368, 9199, 9200, -1, 9199, 9368, 9369, -1, + 9369, 9198, 9199, -1, 9198, 9369, 9370, -1, + 9370, 9197, 9198, -1, 9197, 9370, 9371, -1, + 9371, 9196, 9197, -1, 9196, 9371, 9372, -1, + 9372, 9195, 9196, -1, 9195, 9372, 9373, -1, + 9373, 9194, 9195, -1, 9194, 9373, 9374, -1, + 9374, 9193, 9194, -1, 9193, 9374, 9375, -1, + 9375, 9098, 9193, -1, 9098, 9375, 9376, -1, + 9376, 9096, 9098, -1, 9376, 9377, 9096, -1, + 9376, 9378, 9377, -1, 9378, 9376, 9375, -1, + 9375, 9379, 9378, -1, 9379, 9375, 9374, -1, + 9374, 9380, 9379, -1, 9380, 9374, 9373, -1, + 9373, 9381, 9380, -1, 9381, 9373, 9372, -1, + 9372, 9382, 9381, -1, 9382, 9372, 9371, -1, + 9371, 9383, 9382, -1, 9383, 9371, 9370, -1, + 9370, 9384, 9383, -1, 9384, 9370, 9369, -1, + 9369, 9385, 9384, -1, 9385, 9369, 9368, -1, + 9368, 9386, 9385, -1, 9386, 9368, 9367, -1, + 9367, 9387, 9386, -1, 9387, 9367, 9366, -1, + 9366, 9388, 9387, -1, 9388, 9366, 9365, -1, + 9365, 9389, 9388, -1, 9389, 9365, 9364, -1, + 9364, 9390, 9389, -1, 9390, 9364, 9363, -1, + 9363, 9391, 9390, -1, 9391, 9363, 9362, -1, + 9362, 9392, 9391, -1, 9392, 9362, 9361, -1, + 9361, 9393, 9392, -1, 9393, 9361, 9360, -1, + 9360, 9394, 9393, -1, 9394, 9360, 9359, -1, + 9359, 9395, 9394, -1, 9395, 9359, 9358, -1, + 9358, 9396, 9395, -1, 9396, 9358, 9357, -1, + 9357, 9397, 9396, -1, 9397, 9357, 9356, -1, + 9356, 9398, 9397, -1, 9398, 9356, 9355, -1, + 9355, 9399, 9398, -1, 9399, 9355, 9354, -1, + 9354, 9400, 9399, -1, 9400, 9354, 9353, -1, + 9353, 9401, 9400, -1, 9401, 9353, 9352, -1, + 9352, 9402, 9401, -1, 9402, 9352, 9351, -1, + 9351, 9403, 9402, -1, 9403, 9351, 9350, -1, + 9350, 9404, 9403, -1, 9404, 9350, 9349, -1, + 9349, 9405, 9404, -1, 9405, 9349, 9348, -1, + 9405, 9348, 9347, -1, 9347, 9406, 9405, -1, + 9406, 9347, 9346, -1, 9346, 9407, 9406, -1, + 9407, 9346, 9345, -1, 9345, 9408, 9407, -1, + 9408, 9345, 9344, -1, 9344, 9409, 9408, -1, + 9409, 9344, 9343, -1, 9343, 9410, 9409, -1, + 9410, 9343, 9342, -1, 9342, 9411, 9410, -1, + 9411, 9342, 9341, -1, 9341, 9412, 9411, -1, + 9412, 9341, 9340, -1, 9340, 9413, 9412, -1, + 9413, 9340, 9339, -1, 9339, 9414, 9413, -1, + 9414, 9339, 9338, -1, 9338, 9415, 9414, -1, + 9415, 9338, 9337, -1, 9337, 9416, 9415, -1, + 9416, 9337, 9336, -1, 9336, 9417, 9416, -1, + 9417, 9336, 9335, -1, 9335, 9418, 9417, -1, + 9418, 9335, 9334, -1, 9334, 9419, 9418, -1, + 9419, 9334, 9333, -1, 9333, 9420, 9419, -1, + 9420, 9333, 9332, -1, 9332, 9421, 9420, -1, + 9421, 9332, 9331, -1, 9331, 9422, 9421, -1, + 9422, 9331, 9330, -1, 9330, 9423, 9422, -1, + 9423, 9330, 9329, -1, 9329, 9424, 9423, -1, + 9424, 9329, 9328, -1, 9328, 9425, 9424, -1, + 9425, 9328, 9327, -1, 9327, 9426, 9425, -1, + 9426, 9327, 9326, -1, 9326, 9427, 9426, -1, + 9427, 9326, 9325, -1, 9325, 9428, 9427, -1, + 9428, 9325, 9324, -1, 9324, 9429, 9428, -1, + 9429, 9324, 9323, -1, 9323, 9430, 9429, -1, + 9430, 9323, 9322, -1, 9322, 9431, 9430, -1, + 9431, 9322, 9321, -1, 9321, 9432, 9431, -1, + 9432, 9321, 9320, -1, 9320, 9433, 9432, -1, + 9320, 9319, 9433, -1, 9434, 9433, 9319, -1, + 9434, 9319, 9318, -1, 9318, 9435, 9434, -1, + 9435, 9318, 9317, -1, 9317, 9436, 9435, -1, + 9436, 9317, 9316, -1, 9316, 9437, 9436, -1, + 9437, 9316, 9004, -1, 9004, 9438, 9437, -1, + 9438, 9004, 9003, -1, 9003, 9002, 9438, -1, + 9438, 9002, 281, -1, 281, 9437, 9438, -1, + 281, 280, 9437, -1, 280, 9439, 9437, -1, + 9439, 280, 282, -1, 9439, 282, 9000, -1, + 9000, 8998, 9439, -1, 8998, 9437, 9439, -1, + 8998, 9436, 9437, -1, 9436, 8998, 8997, -1, + 8997, 9435, 9436, -1, 9435, 8997, 8996, -1, + 8996, 9434, 9435, -1, 9434, 8996, 8995, -1, + 8995, 9433, 9434, -1, 9433, 8995, 8994, -1, + 8994, 9432, 9433, -1, 9432, 8994, 8993, -1, + 8993, 9431, 9432, -1, 9431, 8993, 8992, -1, + 8992, 9430, 9431, -1, 9430, 8992, 8991, -1, + 8991, 9429, 9430, -1, 9429, 8991, 8990, -1, + 8990, 9428, 9429, -1, 9428, 8990, 8989, -1, + 8989, 9427, 9428, -1, 9427, 8989, 8988, -1, + 8988, 9426, 9427, -1, 9426, 8988, 8987, -1, + 8987, 9425, 9426, -1, 9425, 8987, 8986, -1, + 8986, 9424, 9425, -1, 9424, 8986, 8985, -1, + 8985, 9423, 9424, -1, 9423, 8985, 8984, -1, + 8984, 9422, 9423, -1, 9422, 8984, 8983, -1, + 8983, 9421, 9422, -1, 9421, 8983, 8982, -1, + 8982, 9420, 9421, -1, 9420, 8982, 8981, -1, + 8981, 9419, 9420, -1, 9419, 8981, 8980, -1, + 8980, 9418, 9419, -1, 9418, 8980, 8979, -1, + 8979, 9417, 9418, -1, 9417, 8979, 8978, -1, + 8978, 9416, 9417, -1, 9416, 8978, 8977, -1, + 8977, 9415, 9416, -1, 9415, 8977, 8976, -1, + 8976, 9414, 9415, -1, 9414, 8976, 8975, -1, + 8975, 9413, 9414, -1, 9413, 8975, 8974, -1, + 8974, 9412, 9413, -1, 9412, 8974, 8973, -1, + 8973, 9411, 9412, -1, 9411, 8973, 8972, -1, + 8972, 9410, 9411, -1, 9410, 8972, 8971, -1, + 8971, 9409, 9410, -1, 9409, 8971, 8970, -1, + 8970, 9408, 9409, -1, 9408, 8970, 8969, -1, + 8969, 9407, 9408, -1, 9407, 8969, 8968, -1, + 8968, 9406, 9407, -1, 9406, 8968, 8967, -1, + 8967, 9405, 9406, -1, 8967, 9404, 9405, -1, + 9404, 8967, 8966, -1, 8966, 9403, 9404, -1, + 9403, 8966, 8965, -1, 8965, 9402, 9403, -1, + 9402, 8965, 8964, -1, 8964, 9401, 9402, -1, + 9401, 8964, 8963, -1, 8963, 9400, 9401, -1, + 9400, 8963, 8962, -1, 8962, 9399, 9400, -1, + 9399, 8962, 8961, -1, 8961, 9398, 9399, -1, + 9398, 8961, 8960, -1, 8960, 9397, 9398, -1, + 9397, 8960, 8959, -1, 8959, 9396, 9397, -1, + 9396, 8959, 8958, -1, 8958, 9395, 9396, -1, + 9395, 8958, 8957, -1, 8957, 9394, 9395, -1, + 9394, 8957, 8956, -1, 8956, 9393, 9394, -1, + 9393, 8956, 8955, -1, 8955, 9392, 9393, -1, + 9392, 8955, 8954, -1, 8954, 9391, 9392, -1, + 9391, 8954, 8953, -1, 8953, 9390, 9391, -1, + 9390, 8953, 8952, -1, 8952, 9389, 9390, -1, + 9389, 8952, 8951, -1, 8951, 9388, 9389, -1, + 9388, 8951, 8950, -1, 8950, 9387, 9388, -1, + 9387, 8950, 8949, -1, 8949, 9386, 9387, -1, + 9386, 8949, 8948, -1, 8948, 9385, 9386, -1, + 9385, 8948, 8947, -1, 8947, 9384, 9385, -1, + 9384, 8947, 8946, -1, 8946, 9383, 9384, -1, + 9383, 8946, 8945, -1, 8945, 9382, 9383, -1, + 9382, 8945, 8944, -1, 8944, 9381, 9382, -1, + 9381, 8944, 8943, -1, 8943, 9380, 9381, -1, + 9380, 8943, 8942, -1, 8942, 9379, 9380, -1, + 9379, 8942, 8941, -1, 8941, 9378, 9379, -1, + 9378, 8941, 8940, -1, 8940, 9377, 9378, -1, + 9377, 8940, 8939, -1, 8939, 8360, 9377, -1, + 8360, 9096, 9377, -1, 8360, 9100, 9096, -1, + 9100, 8360, 8359, -1, 8359, 9102, 9100, -1, + 9102, 8359, 8364, -1, 8364, 9104, 9102, -1, + 9104, 8364, 8363, -1, 8363, 9094, 9104, -1, + 9094, 8363, 8372, -1, 8372, 8373, 9094, -1, + 8373, 9095, 9094, -1, 9095, 8373, 8374, -1, + 9095, 8374, 9440, -1, 9440, 9093, 9095, -1, + 9440, 9106, 9093, -1, 9106, 9440, 8374, -1, + 9106, 8374, 8375, -1, 8375, 9107, 9106, -1, + 8375, 8376, 9107, -1, 9107, 8376, 8206, -1, + 9107, 8206, 8204, -1, 8204, 9108, 9107, -1, + 9108, 8204, 8202, -1, 8202, 9109, 9108, -1, + 9109, 8202, 8200, -1, 8200, 9110, 9109, -1, + 9110, 8200, 8198, -1, 8198, 9111, 9110, -1, + 9111, 8198, 8196, -1, 8196, 9112, 9111, -1, + 9112, 8196, 8194, -1, 8194, 9113, 9112, -1, + 9113, 8194, 8192, -1, 8192, 9115, 9113, -1, + 9115, 8192, 8190, -1, 8190, 9117, 9115, -1, + 9117, 8190, 8188, -1, 8188, 9119, 9117, -1, + 9119, 8188, 8186, -1, 8186, 9121, 9119, -1, + 9121, 8186, 8184, -1, 8184, 9123, 9121, -1, + 9123, 8184, 8182, -1, 8182, 9125, 9123, -1, + 9125, 8182, 8180, -1, 8180, 9127, 9125, -1, + 9127, 8180, 8178, -1, 8178, 9129, 9127, -1, + 9129, 8178, 8176, -1, 8176, 9131, 9129, -1, + 9131, 8176, 8174, -1, 8174, 9133, 9131, -1, + 9133, 8174, 8172, -1, 8172, 9135, 9133, -1, + 9135, 8172, 8170, -1, 8170, 9137, 9135, -1, + 9137, 8170, 8168, -1, 8168, 9139, 9137, -1, + 9139, 8168, 8166, -1, 8166, 9141, 9139, -1, + 9141, 8166, 8164, -1, 8164, 9143, 9141, -1, + 9143, 8164, 8162, -1, 8162, 9145, 9143, -1, + 9145, 8162, 8160, -1, 8160, 9147, 9145, -1, + 9147, 8160, 8158, -1, 8158, 9149, 9147, -1, + 9149, 8158, 8156, -1, 8156, 9151, 9149, -1, + 9151, 8156, 8154, -1, 8154, 9153, 9151, -1, + 9153, 8154, 8152, -1, 8152, 9155, 9153, -1, + 9155, 8152, 8150, -1, 8150, 9157, 9155, -1, + 9157, 8150, 8148, -1, 8148, 9159, 9157, -1, + 9159, 8148, 8146, -1, 8146, 9161, 9159, -1, + 9161, 8146, 8144, -1, 8144, 9163, 9161, -1, + 9163, 8144, 8142, -1, 8142, 9092, 9163, -1, + 9092, 8142, 8140, -1, 8140, 9090, 9092, -1, + 9090, 8140, 8138, -1, 8138, 9088, 9090, -1, + 9088, 8138, 8136, -1, 8136, 9087, 9088, -1, + 9087, 8136, 8133, -1, 9087, 8133, 8131, -1, + 8131, 9085, 9087, -1, 9085, 8131, 8129, -1, + 8129, 9083, 9085, -1, 9083, 8129, 8127, -1, + 8127, 9081, 9083, -1, 9081, 8127, 8125, -1, + 8125, 9079, 9081, -1, 9079, 8125, 8123, -1, + 8123, 9077, 9079, -1, 9077, 8123, 8121, -1, + 8121, 9075, 9077, -1, 9075, 8121, 8119, -1, + 8119, 9073, 9075, -1, 9073, 8119, 8117, -1, + 8117, 9071, 9073, -1, 9071, 8117, 8115, -1, + 8115, 9069, 9071, -1, 9069, 8115, 8113, -1, + 8113, 9067, 9069, -1, 9067, 8113, 8111, -1, + 8111, 9065, 9067, -1, 9065, 8111, 8109, -1, + 8109, 9063, 9065, -1, 9063, 8109, 8107, -1, + 8107, 9061, 9063, -1, 9061, 8107, 8105, -1, + 8105, 9059, 9061, -1, 9059, 8105, 8103, -1, + 8103, 9057, 9059, -1, 9057, 8103, 8101, -1, + 8101, 9055, 9057, -1, 9055, 8101, 8099, -1, + 8099, 9053, 9055, -1, 9053, 8099, 8097, -1, + 8097, 9051, 9053, -1, 9051, 8097, 8095, -1, + 8095, 9049, 9051, -1, 9049, 8095, 8093, -1, + 8093, 9047, 9049, -1, 9047, 8093, 8091, -1, + 8091, 9045, 9047, -1, 9045, 8091, 8089, -1, + 8089, 9043, 9045, -1, 9043, 8089, 8087, -1, + 8087, 9041, 9043, -1, 9041, 8087, 8085, -1, + 8085, 9039, 9041, -1, 9039, 8085, 8083, -1, + 8083, 9037, 9039, -1, 9037, 8083, 8081, -1, + 8081, 9035, 9037, -1, 9035, 8081, 8079, -1, + 8079, 9033, 9035, -1, 9033, 8079, 8077, -1, + 8077, 9031, 9033, -1, 9031, 8077, 8075, -1, + 8075, 9029, 9031, -1, 9029, 8075, 8074, -1, + 8074, 9012, 9029, -1, 8074, 9013, 9012, -1, + 8074, 8073, 9013, -1, 9013, 8073, 8379, -1, + 9013, 8379, 9441, -1, 9441, 9014, 9013, -1, + 9014, 9441, 9442, -1, 9442, 9016, 9014, -1, + 9016, 9442, 9443, -1, 9443, 9018, 9016, -1, + 9018, 9443, 9444, -1, 9444, 9020, 9018, -1, + 9020, 9444, 9445, -1, 9445, 9010, 9020, -1, + 9010, 9445, 9446, -1, 9446, 9008, 9010, -1, + 9008, 9447, 9448, -1, 9008, 9446, 9447, -1, + 9449, 9447, 9446, -1, 9446, 9450, 9449, -1, + 9450, 9446, 9445, -1, 9445, 9451, 9450, -1, + 9451, 9445, 9444, -1, 9444, 9452, 9451, -1, + 9452, 9444, 9443, -1, 9443, 9453, 9452, -1, + 9453, 9443, 9442, -1, 9442, 9454, 9453, -1, + 9454, 9442, 9441, -1, 9441, 9455, 9454, -1, + 9455, 9441, 8379, -1, 8379, 9456, 9455, -1, + 9456, 8379, 8072, -1, 8072, 8071, 9456, -1, + 8071, 9457, 9456, -1, 9457, 8071, 7947, -1, + 7947, 279, 9457, -1, 279, 7947, 7946, -1, + 7946, 278, 279, -1, 278, 7946, 7949, -1, + 7949, 276, 278, -1, 276, 7949, 7944, -1, + 7944, 7943, 276, -1, 7943, 275, 276, -1, + 275, 7943, 7941, -1, 7941, 274, 275, -1, + 274, 7941, 7939, -1, 7939, 273, 274, -1, + 273, 7939, 7937, -1, 7937, 272, 273, -1, + 272, 7937, 7935, -1, 7935, 271, 272, -1, + 271, 7935, 7933, -1, 7933, 270, 271, -1, + 270, 7933, 7931, -1, 7931, 269, 270, -1, + 269, 7931, 7929, -1, 7929, 268, 269, -1, + 268, 7929, 7927, -1, 7927, 267, 268, -1, + 267, 7927, 7925, -1, 7925, 266, 267, -1, + 266, 7925, 7923, -1, 7923, 265, 266, -1, + 265, 7923, 7921, -1, 7921, 264, 265, -1, + 264, 7921, 7919, -1, 7919, 263, 264, -1, + 263, 7919, 7917, -1, 7917, 262, 263, -1, + 262, 7917, 7915, -1, 7915, 261, 262, -1, + 261, 7915, 7913, -1, 7913, 260, 261, -1, + 260, 7913, 7911, -1, 7911, 259, 260, -1, + 259, 7911, 7909, -1, 7909, 258, 259, -1, + 258, 7909, 7907, -1, 7907, 257, 258, -1, + 257, 7907, 7905, -1, 7905, 256, 257, -1, + 256, 7905, 7903, -1, 7903, 255, 256, -1, + 255, 7903, 7901, -1, 7901, 254, 255, -1, + 254, 7901, 7899, -1, 7899, 253, 254, -1, + 253, 7899, 7897, -1, 7897, 252, 253, -1, + 252, 7897, 7895, -1, 7895, 251, 252, -1, + 251, 7895, 7893, -1, 7893, 250, 251, -1, + 250, 7893, 7892, -1, 7892, 249, 250, -1, + 7892, 248, 249, -1, 248, 7892, 7890, -1, + 7890, 247, 248, -1, 247, 7890, 7888, -1, + 7888, 246, 247, -1, 246, 7888, 7886, -1, + 7886, 245, 246, -1, 245, 7886, 7884, -1, + 7884, 244, 245, -1, 244, 7884, 7882, -1, + 7882, 243, 244, -1, 243, 7882, 7880, -1, + 7880, 242, 243, -1, 242, 7880, 7878, -1, + 7878, 241, 242, -1, 241, 7878, 7876, -1, + 7876, 240, 241, -1, 240, 7876, 7874, -1, + 7874, 239, 240, -1, 239, 7874, 7872, -1, + 7872, 238, 239, -1, 238, 7872, 7870, -1, + 7870, 237, 238, -1, 237, 7870, 7868, -1, + 7868, 236, 237, -1, 236, 7868, 7866, -1, + 7866, 235, 236, -1, 235, 7866, 7864, -1, + 7864, 234, 235, -1, 234, 7864, 7862, -1, + 7862, 233, 234, -1, 233, 7862, 7860, -1, + 7860, 232, 233, -1, 232, 7860, 7858, -1, + 7858, 231, 232, -1, 231, 7858, 7856, -1, + 7856, 230, 231, -1, 230, 7856, 7854, -1, + 7854, 229, 230, -1, 229, 7854, 7852, -1, + 7852, 228, 229, -1, 228, 7852, 7850, -1, + 7850, 227, 228, -1, 227, 7850, 7848, -1, + 7848, 226, 227, -1, 226, 7848, 7846, -1, + 7846, 225, 226, -1, 225, 7846, 7844, -1, + 7844, 224, 225, -1, 224, 7844, 7842, -1, + 7842, 223, 224, -1, 223, 7842, 7840, -1, + 7840, 222, 223, -1, 222, 7840, 7838, -1, + 7838, 220, 222, -1, 220, 7838, 7836, -1, + 7836, 221, 220, -1, 221, 7836, 7835, -1, + 7835, 9458, 221, -1, 9458, 7835, 8011, -1, + 8011, 9459, 9458, -1, 9459, 8011, 8009, -1, + 8009, 9460, 9459, -1, 9460, 8009, 8005, -1, + 8005, 8007, 9460, -1, 8007, 9461, 9460, -1, + 8007, 9462, 9461, -1, 9462, 8007, 8380, -1, + 8380, 9463, 9462, -1, 9463, 8380, 8381, -1, + 8381, 9464, 9463, -1, 9464, 8381, 8382, -1, + 8382, 9465, 9464, -1, 9465, 8382, 8383, -1, + 8383, 9466, 9465, -1, 9466, 8383, 8384, -1, + 8384, 9467, 9466, -1, 9467, 8384, 8385, -1, + 8385, 9468, 9467, -1, 9468, 8385, 8386, -1, + 8386, 9469, 9468, -1, 8386, 9470, 9469, -1, + 9470, 8386, 8388, -1, 8388, 775, 9470, -1, + 9470, 775, 774, -1, 774, 9469, 9470, -1, + 774, 776, 9469, -1, 9469, 776, 8392, -1, + 9469, 8392, 8394, -1, 8394, 9468, 9469, -1, + 9468, 8394, 8395, -1, 8395, 9467, 9468, -1, + 9467, 8395, 8396, -1, 8396, 9466, 9467, -1, + 9466, 8396, 8397, -1, 8397, 9465, 9466, -1, + 9465, 8397, 8398, -1, 8398, 9464, 9465, -1, + 9464, 8398, 8399, -1, 8399, 9463, 9464, -1, + 9463, 8399, 8400, -1, 8400, 9462, 9463, -1, + 9462, 8400, 8401, -1, 8401, 9461, 9462, -1, + 9461, 8401, 8402, -1, 8402, 9471, 9461, -1, + 9471, 8402, 8403, -1, 8403, 9472, 9471, -1, + 9472, 8403, 8404, -1, 8404, 9473, 9472, -1, + 9473, 8404, 8405, -1, 8405, 9474, 9473, -1, + 9474, 8405, 8406, -1, 8406, 9475, 9474, -1, + 9475, 8406, 8408, -1, 8408, 9476, 9475, -1, + 9476, 8408, 8409, -1, 8409, 9477, 9476, -1, + 9477, 8409, 8411, -1, 8411, 9478, 9477, -1, + 9478, 8411, 8413, -1, 8413, 9479, 9478, -1, + 9479, 8413, 8415, -1, 8415, 9480, 9479, -1, + 9480, 8415, 8417, -1, 8417, 9481, 9480, -1, + 9481, 8417, 8419, -1, 8419, 9482, 9481, -1, + 9482, 8419, 8421, -1, 8421, 9483, 9482, -1, + 9483, 8421, 8423, -1, 8423, 9484, 9483, -1, + 9484, 8423, 8425, -1, 8425, 9485, 9484, -1, + 9485, 8425, 8427, -1, 8427, 9486, 9485, -1, + 9486, 8427, 8429, -1, 8429, 9487, 9486, -1, + 9487, 8429, 8431, -1, 8431, 9488, 9487, -1, + 9488, 8431, 8433, -1, 8433, 9489, 9488, -1, + 9489, 8433, 8435, -1, 8435, 9490, 9489, -1, + 9490, 8435, 8437, -1, 8437, 9491, 9490, -1, + 9491, 8437, 8439, -1, 8439, 9492, 9491, -1, + 9492, 8439, 8441, -1, 8441, 9493, 9492, -1, + 9493, 8441, 8443, -1, 8443, 9494, 9493, -1, + 9494, 8443, 8445, -1, 8445, 9495, 9494, -1, + 9495, 8445, 8447, -1, 8447, 9496, 9495, -1, + 9496, 8447, 8449, -1, 8449, 9497, 9496, -1, + 9497, 8449, 8451, -1, 8451, 9498, 9497, -1, + 9498, 8451, 8453, -1, 8453, 9499, 9498, -1, + 9499, 8453, 8455, -1, 8455, 9500, 9499, -1, + 9500, 8455, 8457, -1, 8457, 9501, 9500, -1, + 9501, 8457, 8459, -1, 8459, 9502, 9501, -1, + 9502, 8459, 8461, -1, 8461, 9503, 9502, -1, + 9503, 8461, 8463, -1, 9503, 8463, 8466, -1, + 8466, 9504, 9503, -1, 9504, 8466, 8468, -1, + 8468, 9505, 9504, -1, 9505, 8468, 8470, -1, + 8470, 9506, 9505, -1, 9506, 8470, 8472, -1, + 8472, 9507, 9506, -1, 9507, 8472, 8474, -1, + 8474, 9508, 9507, -1, 9508, 8474, 8476, -1, + 8476, 9509, 9508, -1, 9509, 8476, 8478, -1, + 8478, 9510, 9509, -1, 9510, 8478, 8480, -1, + 8480, 9511, 9510, -1, 9511, 8480, 8482, -1, + 8482, 9512, 9511, -1, 9512, 8482, 8484, -1, + 8484, 9513, 9512, -1, 9513, 8484, 8486, -1, + 8486, 9514, 9513, -1, 9514, 8486, 8488, -1, + 8488, 9515, 9514, -1, 9515, 8488, 8490, -1, + 8490, 9516, 9515, -1, 9516, 8490, 8492, -1, + 8492, 9517, 9516, -1, 9517, 8492, 8494, -1, + 8494, 9518, 9517, -1, 9518, 8494, 8496, -1, + 8496, 9519, 9518, -1, 9519, 8496, 8498, -1, + 8498, 9520, 9519, -1, 9520, 8498, 8500, -1, + 8500, 9521, 9520, -1, 9521, 8500, 8502, -1, + 8502, 9522, 9521, -1, 9522, 8502, 8504, -1, + 8504, 9523, 9522, -1, 9523, 8504, 8506, -1, + 8506, 9524, 9523, -1, 9524, 8506, 8508, -1, + 8508, 9525, 9524, -1, 9525, 8508, 8510, -1, + 8510, 9526, 9525, -1, 9526, 8510, 8512, -1, + 8512, 9527, 9526, -1, 9527, 8512, 8514, -1, + 8514, 9528, 9527, -1, 9528, 8514, 8516, -1, + 8516, 9529, 9528, -1, 9529, 8516, 8518, -1, + 8518, 9530, 9529, -1, 9530, 8518, 8519, -1, + 8519, 9531, 9530, -1, 9531, 8519, 8549, -1, + 8549, 9532, 9531, -1, 9532, 8549, 8547, -1, + 8547, 9533, 9532, -1, 9533, 8547, 8545, -1, + 8545, 9534, 9533, -1, 9534, 8545, 8543, -1, + 8543, 9535, 9534, -1, 9535, 8543, 8541, -1, + 8541, 9536, 9535, -1, 9536, 8541, 8539, -1, + 8539, 9537, 9536, -1, 9537, 8539, 8537, -1, + 8537, 9538, 9537, -1, 9538, 8537, 8535, -1, + 8535, 9539, 9538, -1, 9539, 8535, 8533, -1, + 8533, 9540, 9539, -1, 9540, 8533, 8531, -1, + 8531, 9541, 9540, -1, 9541, 8531, 8529, -1, + 8529, 9542, 9541, -1, 9542, 8529, 8527, -1, + 8527, 9543, 9542, -1, 9543, 8527, 8525, -1, + 8525, 9544, 9543, -1, 9544, 8525, 8522, -1, + 9544, 8522, 9545, -1, 9546, 9544, 9545, -1, + 9546, 9547, 9544, -1, 9547, 9546, 9548, -1, + 9546, 9545, 9548, -1, 9549, 9548, 9545, -1, + 9550, 9549, 9545, -1, 9550, 9545, 8522, -1, + 9550, 8522, 8521, -1, 8521, 9549, 9550, -1, + 8521, 8520, 9549, -1, 9551, 9549, 8520, -1, + 9551, 8520, 8523, -1, 9551, 8523, 8608, -1, + 8608, 9549, 9551, -1, 9549, 8608, 8610, -1, + 9552, 9553, 9554, -1, 9552, 9002, 9315, -1, + 9555, 9552, 9315, -1, 9315, 9022, 9555, -1, + 9022, 9007, 9555, -1, 9556, 9555, 9007, -1, + 9556, 9552, 9555, -1, 9556, 9557, 9552, -1, + 9557, 9556, 9007, -1, 9557, 9007, 9009, -1, + 9009, 9552, 9557, -1, 9009, 9553, 9552, -1, + 9553, 9009, 9008, -1, 9553, 9008, 9448, -1, + 9448, 9554, 9553, -1, 9558, 9554, 9448, -1, + 9558, 9448, 9447, -1, 9558, 9447, 9559, -1, + 9559, 9554, 9558, -1, 9559, 9560, 9554, -1, + 9560, 9559, 9447, -1, 9447, 9561, 9560, -1, + 9447, 9449, 9561, -1, 9561, 9562, 9563, -1, + 9561, 9564, 9562, -1, 9564, 9561, 9449, -1, + 9449, 9565, 9564, -1, 9565, 9449, 9450, -1, + 9450, 9566, 9565, -1, 9566, 9450, 9451, -1, + 9451, 9567, 9566, -1, 9567, 9451, 9452, -1, + 9452, 9568, 9567, -1, 9568, 9452, 9453, -1, + 9453, 9569, 9568, -1, 9569, 9453, 9454, -1, + 9454, 9570, 9569, -1, 9570, 9454, 9455, -1, + 9455, 9571, 9570, -1, 9571, 9455, 9456, -1, + 9456, 9572, 9571, -1, 9572, 9456, 9457, -1, + 9457, 9573, 9572, -1, 9573, 9457, 279, -1, + 279, 9574, 9573, -1, 9574, 279, 277, -1, + 277, 9575, 9574, -1, 9575, 277, 112, -1, + 112, 109, 9575, -1, 109, 112, 111, -1, + 111, 108, 109, -1, 108, 111, 114, -1, + 114, 106, 108, -1, 106, 114, 116, -1, + 116, 104, 106, -1, 104, 116, 118, -1, + 118, 102, 104, -1, 102, 118, 120, -1, + 120, 100, 102, -1, 100, 120, 122, -1, + 122, 98, 100, -1, 98, 122, 124, -1, + 124, 96, 98, -1, 96, 124, 126, -1, + 126, 94, 96, -1, 94, 126, 128, -1, + 128, 92, 94, -1, 92, 128, 130, -1, + 130, 90, 92, -1, 90, 130, 132, -1, + 132, 88, 90, -1, 88, 132, 134, -1, + 134, 86, 88, -1, 86, 134, 136, -1, + 136, 84, 86, -1, 84, 136, 138, -1, + 138, 82, 84, -1, 82, 138, 140, -1, + 140, 80, 82, -1, 80, 140, 142, -1, + 142, 78, 80, -1, 78, 142, 144, -1, + 144, 76, 78, -1, 76, 144, 146, -1, + 146, 74, 76, -1, 74, 146, 148, -1, + 148, 72, 74, -1, 72, 148, 150, -1, + 150, 70, 72, -1, 70, 150, 152, -1, + 152, 68, 70, -1, 68, 152, 154, -1, + 154, 66, 68, -1, 66, 154, 156, -1, + 156, 64, 66, -1, 64, 156, 158, -1, + 158, 62, 64, -1, 62, 158, 160, -1, + 160, 60, 62, -1, 60, 160, 162, -1, + 162, 58, 60, -1, 58, 162, 164, -1, + 164, 55, 58, -1, 164, 53, 55, -1, + 53, 164, 165, -1, 165, 51, 53, -1, + 51, 165, 167, -1, 167, 49, 51, -1, + 49, 167, 169, -1, 169, 47, 49, -1, + 47, 169, 171, -1, 171, 45, 47, -1, + 45, 171, 173, -1, 173, 43, 45, -1, + 43, 173, 175, -1, 175, 41, 43, -1, + 41, 175, 177, -1, 177, 39, 41, -1, + 39, 177, 179, -1, 179, 37, 39, -1, + 37, 179, 181, -1, 181, 35, 37, -1, + 35, 181, 183, -1, 183, 33, 35, -1, + 33, 183, 185, -1, 185, 31, 33, -1, + 31, 185, 187, -1, 187, 29, 31, -1, + 29, 187, 189, -1, 189, 27, 29, -1, + 27, 189, 191, -1, 191, 25, 27, -1, + 25, 191, 193, -1, 193, 23, 25, -1, + 23, 193, 195, -1, 195, 21, 23, -1, + 21, 195, 197, -1, 197, 19, 21, -1, + 19, 197, 199, -1, 199, 17, 19, -1, + 17, 199, 201, -1, 201, 15, 17, -1, + 15, 201, 203, -1, 203, 13, 15, -1, + 13, 203, 205, -1, 205, 11, 13, -1, + 11, 205, 207, -1, 207, 9, 11, -1, + 9, 207, 209, -1, 209, 7, 9, -1, + 7, 209, 211, -1, 211, 5, 7, -1, + 5, 211, 213, -1, 213, 3, 5, -1, + 3, 213, 215, -1, 215, 0, 3, -1, + 0, 215, 217, -1, 217, 1, 0, -1, + 1, 217, 219, -1, 219, 9576, 1, -1, + 9576, 219, 221, -1, 221, 9577, 9576, -1, + 9577, 221, 9458, -1, 9458, 9578, 9577, -1, + 9578, 9458, 9459, -1, 9459, 9579, 9578, -1, + 9579, 9459, 9460, -1, 9579, 9460, 9461, -1, + 9579, 9461, 9471, -1, 9471, 9578, 9579, -1, + 9578, 9471, 9472, -1, 9472, 9577, 9578, -1, + 9577, 9472, 9473, -1, 9473, 9576, 9577, -1, + 9576, 9473, 9474, -1, 9474, 1, 9576, -1, + 1, 9474, 9475, -1, 9475, 2, 1, -1, + 2, 9475, 9476, -1, 9476, 4, 2, -1, + 4, 9476, 9477, -1, 9477, 6, 4, -1, + 6, 9477, 9478, -1, 9478, 8, 6, -1, + 8, 9478, 9479, -1, 9479, 10, 8, -1, + 10, 9479, 9480, -1, 9480, 12, 10, -1, + 12, 9480, 9481, -1, 9481, 14, 12, -1, + 14, 9481, 9482, -1, 9482, 16, 14, -1, + 16, 9482, 9483, -1, 9483, 18, 16, -1, + 18, 9483, 9484, -1, 9484, 20, 18, -1, + 20, 9484, 9485, -1, 9485, 22, 20, -1, + 22, 9485, 9486, -1, 9486, 24, 22, -1, + 24, 9486, 9487, -1, 9487, 26, 24, -1, + 26, 9487, 9488, -1, 9488, 28, 26, -1, + 28, 9488, 9489, -1, 9489, 30, 28, -1, + 30, 9489, 9490, -1, 9490, 32, 30, -1, + 32, 9490, 9491, -1, 9491, 34, 32, -1, + 34, 9491, 9492, -1, 9492, 36, 34, -1, + 36, 9492, 9493, -1, 9493, 38, 36, -1, + 38, 9493, 9494, -1, 9494, 40, 38, -1, + 40, 9494, 9495, -1, 9495, 42, 40, -1, + 42, 9495, 9496, -1, 9496, 44, 42, -1, + 44, 9496, 9497, -1, 9497, 46, 44, -1, + 46, 9497, 9498, -1, 9498, 48, 46, -1, + 48, 9498, 9499, -1, 9499, 50, 48, -1, + 50, 9499, 9500, -1, 9500, 52, 50, -1, + 52, 9500, 9501, -1, 9501, 54, 52, -1, + 54, 9501, 9502, -1, 9502, 56, 54, -1, + 56, 9502, 9503, -1, 56, 9503, 9504, -1, + 9504, 57, 56, -1, 57, 9504, 9505, -1, + 9505, 59, 57, -1, 59, 9505, 9506, -1, + 9506, 61, 59, -1, 61, 9506, 9507, -1, + 9507, 63, 61, -1, 63, 9507, 9508, -1, + 9508, 65, 63, -1, 65, 9508, 9509, -1, + 9509, 67, 65, -1, 67, 9509, 9510, -1, + 9510, 69, 67, -1, 69, 9510, 9511, -1, + 9511, 71, 69, -1, 71, 9511, 9512, -1, + 9512, 73, 71, -1, 73, 9512, 9513, -1, + 9513, 75, 73, -1, 75, 9513, 9514, -1, + 9514, 77, 75, -1, 77, 9514, 9515, -1, + 9515, 79, 77, -1, 79, 9515, 9516, -1, + 9516, 81, 79, -1, 81, 9516, 9517, -1, + 9517, 83, 81, -1, 83, 9517, 9518, -1, + 9518, 85, 83, -1, 85, 9518, 9519, -1, + 9519, 87, 85, -1, 87, 9519, 9520, -1, + 9520, 89, 87, -1, 89, 9520, 9521, -1, + 9521, 91, 89, -1, 91, 9521, 9522, -1, + 9522, 93, 91, -1, 93, 9522, 9523, -1, + 9523, 95, 93, -1, 95, 9523, 9524, -1, + 9524, 97, 95, -1, 97, 9524, 9525, -1, + 9525, 99, 97, -1, 99, 9525, 9526, -1, + 9526, 101, 99, -1, 101, 9526, 9527, -1, + 9527, 103, 101, -1, 103, 9527, 9528, -1, + 9528, 105, 103, -1, 105, 9528, 9529, -1, + 9529, 107, 105, -1, 107, 9529, 9530, -1, + 9530, 109, 107, -1, 109, 9530, 9531, -1, + 9531, 9575, 109, -1, 9575, 9531, 9532, -1, + 9532, 9574, 9575, -1, 9574, 9532, 9533, -1, + 9533, 9573, 9574, -1, 9573, 9533, 9534, -1, + 9534, 9572, 9573, -1, 9572, 9534, 9535, -1, + 9535, 9571, 9572, -1, 9571, 9535, 9536, -1, + 9536, 9570, 9571, -1, 9570, 9536, 9537, -1, + 9537, 9569, 9570, -1, 9569, 9537, 9538, -1, + 9538, 9568, 9569, -1, 9568, 9538, 9539, -1, + 9539, 9567, 9568, -1, 9567, 9539, 9540, -1, + 9540, 9566, 9567, -1, 9566, 9540, 9541, -1, + 9541, 9565, 9566, -1, 9565, 9541, 9542, -1, + 9542, 9564, 9565, -1, 9564, 9542, 9543, -1, + 9543, 9562, 9564, -1, 9562, 9543, 9544, -1, + 9562, 9544, 9547, -1, 9547, 9580, 9562, -1, + 9580, 9547, 9548, -1, 9580, 9548, 9581, -1, + 9581, 9562, 9580, -1, 9581, 9563, 9562, -1, + 9581, 9548, 9563, -1, 9563, 9548, 9582, -1, + 9582, 9561, 9563, -1, 9582, 9560, 9561, -1, + 9582, 9554, 9560, -1, 9554, 9582, 9548, -1, + 2772, 2774, 9583, -1, 9583, 2774, 4263, -1, + 2772, 9583, 4226, -1, 4226, 9583, 4263, -1, + 9584, 9585, 9586, -1, 9586, 9585, 9587, -1, + 9586, 9588, 9584, -1, 9584, 9588, 9589, -1, + 9590, 9591, 9592, -1, 9592, 9591, 9593, -1, + 9592, 9594, 9590, -1, 9590, 9594, 9595, -1, + 9596, 9597, 9598, -1, 9598, 9597, 9599, -1, + 9598, 9593, 9596, -1, 9596, 9593, 9591, -1, + 9594, 9587, 9595, -1, 9595, 9587, 9585, -1, + 9588, 9600, 9589, -1, 9589, 9600, 9601, -1, + 9600, 9602, 9601, -1, 9601, 9602, 9603, -1, + 9604, 9605, 9606, -1, 9606, 9605, 9607, -1, + 9606, 9608, 9604, -1, 9604, 9608, 9609, -1, + 9610, 9611, 9612, -1, 9612, 9611, 9613, -1, + 9612, 9614, 9610, -1, 9610, 9614, 9615, -1, + 9611, 9616, 9613, -1, 9613, 9616, 9617, -1, + 9605, 9618, 9607, -1, 9607, 9618, 9619, -1, + 9620, 9621, 9622, -1, 9622, 9621, 9623, -1, + 9622, 9624, 9620, -1, 9620, 9624, 9625, -1, + 9624, 9622, 9626, -1, 9626, 9622, 9617, -1, + 9622, 9623, 9617, -1, 9617, 9623, 9627, -1, + 9617, 9627, 9613, -1, 9613, 9627, 9612, -1, + 9612, 9627, 9614, -1, 9614, 9627, 9628, -1, + 9628, 9627, 9629, -1, 9629, 9627, 9630, -1, + 9630, 9627, 9631, -1, 9631, 9627, 9632, -1, + 9632, 9627, 9633, -1, 9633, 9627, 9634, -1, + 9634, 9627, 9635, -1, 9635, 9627, 9636, -1, + 9636, 9627, 9637, -1, 9637, 9627, 9638, -1, + 9638, 9627, 9639, -1, 9639, 9627, 9640, -1, + 9640, 9627, 9641, -1, 9641, 9627, 9642, -1, + 9642, 9627, 9643, -1, 9643, 9627, 9603, -1, + 9603, 9627, 9601, -1, 9601, 9627, 9644, -1, + 9601, 9644, 9645, -1, 9645, 9646, 9601, -1, + 9601, 9646, 9647, -1, 9601, 9647, 9618, -1, + 9618, 9605, 9601, -1, 9601, 9605, 9604, -1, + 9601, 9604, 9589, -1, 9589, 9604, 9584, -1, + 9584, 9604, 9585, -1, 9585, 9604, 9595, -1, + 9595, 9604, 9590, -1, 9590, 9604, 9591, -1, + 9591, 9604, 9596, -1, 9596, 9604, 9597, -1, + 9597, 9604, 9648, -1, 9648, 9604, 9609, -1, + 9648, 9609, 9649, -1, 9649, 9650, 9648, -1, + 9648, 9650, 9651, -1, 9648, 9651, 9652, -1, + 9652, 9653, 9648, -1, 9648, 9653, 9654, -1, + 9648, 9654, 9655, -1, 9655, 9656, 9648, -1, + 9648, 9656, 9657, -1, 9648, 9657, 9658, -1, + 9658, 9657, 9659, -1, 9657, 9660, 9659, -1, + 9624, 9626, 9625, -1, 9625, 9626, 9661, -1, + 9626, 9617, 9661, -1, 9661, 9617, 9616, -1, + 9621, 9662, 9623, -1, 9623, 9662, 9627, -1, + 9663, 9619, 9647, -1, 9647, 9619, 9618, -1, + 9647, 9646, 9663, -1, 9663, 9646, 9664, -1, + 9662, 9665, 9627, -1, 9627, 9665, 9644, -1, + 9646, 9645, 9664, -1, 9664, 9645, 9666, -1, + 9645, 9644, 9666, -1, 9666, 9644, 9665, -1, + 9602, 9667, 9603, -1, 9603, 9667, 9643, -1, + 9667, 9668, 9643, -1, 9643, 9668, 9642, -1, + 9668, 9669, 9642, -1, 9642, 9669, 9641, -1, + 9669, 9670, 9641, -1, 9641, 9670, 9640, -1, + 9670, 9671, 9640, -1, 9640, 9671, 9639, -1, + 9638, 9639, 9672, -1, 9672, 9639, 9671, -1, + 9672, 9673, 9638, -1, 9638, 9673, 9637, -1, + 9673, 9674, 9637, -1, 9637, 9674, 9636, -1, + 9633, 9634, 9675, -1, 9675, 9634, 9676, -1, + 9675, 9677, 9633, -1, 9633, 9677, 9632, -1, + 9634, 9635, 9676, -1, 9676, 9635, 9678, -1, + 9679, 9680, 9631, -1, 9631, 9680, 9630, -1, + 9631, 9632, 9679, -1, 9679, 9632, 9677, -1, + 9635, 9636, 9678, -1, 9678, 9636, 9674, -1, + 9597, 9648, 9599, -1, 9599, 9648, 9681, -1, + 9608, 9682, 9609, -1, 9609, 9682, 9649, -1, + 9682, 9683, 9649, -1, 9649, 9683, 9650, -1, + 9683, 9684, 9650, -1, 9650, 9684, 9651, -1, + 9614, 9628, 9615, -1, 9615, 9628, 9685, -1, + 9628, 9629, 9685, -1, 9685, 9629, 9686, -1, + 9652, 9651, 9687, -1, 9687, 9651, 9684, -1, + 9687, 9688, 9652, -1, 9652, 9688, 9653, -1, + 9688, 9689, 9653, -1, 9653, 9689, 9654, -1, + 9629, 9630, 9686, -1, 9686, 9630, 9680, -1, + 9689, 9690, 9654, -1, 9654, 9690, 9655, -1, + 9690, 9691, 9655, -1, 9655, 9691, 9656, -1, + 9659, 9660, 9692, -1, 9692, 9660, 9693, -1, + 9692, 9694, 9659, -1, 9659, 9694, 9658, -1, + 9694, 9681, 9658, -1, 9658, 9681, 9648, -1, + 9695, 9693, 9657, -1, 9657, 9693, 9660, -1, + 9657, 9656, 9695, -1, 9695, 9656, 9691, -1, + 6914, 827, 9696, -1, 9696, 827, 4319, -1, + 6914, 9696, 4318, -1, 4318, 9696, 4319, -1, + 4317, 7192, 4268, -1, 4268, 7192, 4267, -1, + 7484, 7617, 7481, -1, 7481, 7617, 7619, -1, + 9688, 9687, 8712, -1, 8712, 9687, 287, -1, + 9687, 9684, 287, -1, 287, 9684, 8616, -1, + 9684, 9683, 8616, -1, 8616, 9683, 7279, -1, + 9683, 9682, 7279, -1, 7279, 9682, 8613, -1, + 9682, 9608, 8613, -1, 8613, 9608, 7360, -1, + 9608, 9606, 7360, -1, 7360, 9606, 7509, -1, + 9606, 9607, 7509, -1, 7509, 9607, 7608, -1, + 9607, 9619, 7608, -1, 7608, 9619, 7638, -1, + 9619, 9663, 7638, -1, 7638, 9663, 803, -1, + 9663, 9664, 803, -1, 803, 9664, 782, -1, + 9664, 9666, 782, -1, 782, 9666, 785, -1, + 785, 9666, 801, -1, 801, 9666, 9665, -1, + 801, 9665, 824, -1, 824, 9665, 9662, -1, + 824, 9662, 7620, -1, 7620, 9662, 9621, -1, + 7620, 9621, 7542, -1, 7542, 9621, 9620, -1, + 7542, 9620, 7616, -1, 7616, 9620, 9625, -1, + 7616, 9625, 7618, -1, 7618, 9625, 9661, -1, + 7618, 9661, 7322, -1, 7322, 9661, 9616, -1, + 7322, 9616, 7194, -1, 7194, 9616, 9611, -1, + 7194, 9611, 7199, -1, 7199, 9611, 9610, -1, + 7199, 9610, 772, -1, 772, 9610, 9615, -1, + 772, 9615, 460, -1, 460, 9615, 9685, -1, + 460, 9685, 458, -1, 458, 9685, 768, -1, + 9685, 9686, 768, -1, 768, 9686, 8828, -1, + 9686, 9680, 8828, -1, 8828, 9680, 8356, -1, + 9680, 9679, 8356, -1, 8356, 9679, 8374, -1, + 9679, 9677, 8374, -1, 8374, 9677, 8354, -1, + 9677, 9675, 8354, -1, 8354, 9675, 8350, -1, + 9675, 9676, 8350, -1, 8350, 9676, 775, -1, + 9676, 9678, 775, -1, 775, 9678, 7827, -1, + 9678, 9674, 7827, -1, 7827, 9674, 778, -1, + 9674, 9673, 778, -1, 778, 9673, 7830, -1, + 9673, 9672, 7830, -1, 7830, 9672, 7669, -1, + 9672, 9671, 7669, -1, 7669, 9671, 4187, -1, + 4187, 9671, 7665, -1, 7665, 9671, 9670, -1, + 7665, 9670, 3050, -1, 3050, 9670, 9669, -1, + 3050, 9669, 7660, -1, 7660, 9669, 9668, -1, + 7660, 9668, 6364, -1, 6364, 9668, 9667, -1, + 6364, 9667, 7655, -1, 7655, 9667, 9602, -1, + 7655, 9602, 7150, -1, 7150, 9602, 9600, -1, + 7150, 9600, 827, -1, 827, 9600, 9588, -1, + 827, 9588, 7189, -1, 7189, 9588, 9586, -1, + 7189, 9586, 4265, -1, 4265, 9586, 9587, -1, + 4265, 9587, 2771, -1, 2771, 9587, 9594, -1, + 2771, 9594, 2774, -1, 2774, 9594, 9592, -1, + 2774, 9592, 4216, -1, 4216, 9592, 9593, -1, + 4216, 9593, 4214, -1, 4214, 9593, 4217, -1, + 9593, 9598, 4217, -1, 4217, 9598, 4212, -1, + 9598, 9599, 4212, -1, 4212, 9599, 8610, -1, + 9599, 9681, 8610, -1, 8610, 9681, 9549, -1, + 9681, 9694, 9549, -1, 9549, 9694, 9548, -1, + 9694, 9692, 9548, -1, 9548, 9692, 9554, -1, + 9692, 9693, 9554, -1, 9554, 9693, 9552, -1, + 9693, 9695, 9552, -1, 9552, 9695, 9002, -1, + 9695, 9691, 9002, -1, 9002, 9691, 282, -1, + 9691, 9690, 282, -1, 282, 9690, 8757, -1, + 9690, 9689, 8757, -1, 8757, 9689, 599, -1, + 9689, 9688, 599, -1, 599, 9688, 291, -1, + 9688, 8712, 291, -1, 9697, 9698, 2252, -1, + 2252, 9698, 2255, -1, 9698, 9699, 2255, -1, + 2255, 9699, 2257, -1, 9699, 9700, 2257, -1, + 2257, 9700, 6241, -1, 9700, 9701, 6241, -1, + 6241, 9701, 6246, -1, 9701, 9702, 6246, -1, + 6246, 9702, 6251, -1, 9702, 9703, 6251, -1, + 6251, 9703, 6266, -1, 6266, 9703, 2376, -1, + 2376, 9703, 9704, -1, 2376, 9704, 2486, -1, + 2486, 9704, 9705, -1, 2486, 9705, 2296, -1, + 2296, 9705, 9706, -1, 2296, 9706, 2293, -1, + 2293, 9706, 9707, -1, 2293, 9707, 2290, -1, + 2290, 9707, 9708, -1, 2290, 9708, 2288, -1, + 2288, 9708, 9709, -1, 2288, 9709, 2599, -1, + 2599, 9709, 9710, -1, 2599, 9710, 2605, -1, + 2605, 9710, 9711, -1, 2605, 9711, 4424, -1, + 4424, 9711, 9712, -1, 4424, 9712, 4428, -1, + 4428, 9712, 9713, -1, 4428, 9713, 5981, -1, + 5981, 9713, 9714, -1, 5981, 9714, 5980, -1, + 5980, 9714, 6880, -1, 9714, 9715, 6880, -1, + 6880, 9715, 4744, -1, 9715, 9716, 4744, -1, + 4744, 9716, 6876, -1, 9716, 9717, 6876, -1, + 6876, 9717, 4755, -1, 9717, 9718, 4755, -1, + 4755, 9718, 6872, -1, 9718, 9719, 6872, -1, + 6872, 9719, 2140, -1, 9719, 9720, 2140, -1, + 2140, 9720, 2081, -1, 9720, 9721, 2081, -1, + 2081, 9721, 2009, -1, 9721, 9722, 2009, -1, + 2009, 9722, 2007, -1, 9722, 9723, 2007, -1, + 2007, 9723, 2005, -1, 9723, 9724, 2005, -1, + 2005, 9724, 2002, -1, 9724, 9725, 2002, -1, + 2002, 9725, 1998, -1, 9725, 9726, 1998, -1, + 1998, 9726, 1996, -1, 1996, 9726, 6862, -1, + 6862, 9726, 9727, -1, 6862, 9727, 6479, -1, + 6479, 9727, 9728, -1, 6479, 9728, 6635, -1, + 6635, 9728, 9729, -1, 6635, 9729, 6633, -1, + 6633, 9729, 9730, -1, 6633, 9730, 6712, -1, + 6712, 9730, 9731, -1, 6712, 9731, 6713, -1, + 6713, 9731, 9732, -1, 6713, 9732, 6715, -1, + 6715, 9732, 9733, -1, 6715, 9733, 6741, -1, + 6741, 9733, 9734, -1, 6741, 9734, 6731, -1, + 6731, 9734, 9735, -1, 6731, 9735, 6725, -1, + 6725, 9735, 9736, -1, 6725, 9736, 6721, -1, + 6721, 9736, 9737, -1, 6721, 9737, 6810, -1, + 6810, 9737, 6685, -1, 9737, 9738, 6685, -1, + 6685, 9738, 1008, -1, 9738, 9739, 1008, -1, + 1008, 9739, 6624, -1, 9739, 9740, 6624, -1, + 6624, 9740, 6612, -1, 9740, 9741, 6612, -1, + 6612, 9741, 6476, -1, 9741, 9742, 6476, -1, + 6476, 9742, 929, -1, 9742, 9743, 929, -1, + 929, 9743, 1949, -1, 9743, 9744, 1949, -1, + 1949, 9744, 1945, -1, 9744, 9745, 1945, -1, + 1945, 9745, 1887, -1, 9745, 9746, 1887, -1, + 1887, 9746, 1885, -1, 9746, 9747, 1885, -1, + 1885, 9747, 1476, -1, 9747, 9748, 1476, -1, + 1476, 9748, 1372, -1, 1372, 9748, 6473, -1, + 6473, 9748, 9749, -1, 6473, 9749, 6470, -1, + 6470, 9749, 9750, -1, 6470, 9750, 6380, -1, + 6380, 9750, 9751, -1, 6380, 9751, 5657, -1, + 5657, 9751, 9752, -1, 5657, 9752, 2254, -1, + 2254, 9752, 9697, -1, 2254, 9697, 2252, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5712, 5712, 5712, -1, 5713, 5713, 5713, -1, + 5714, 5714, 5714, -1, 5715, 5715, 5715, -1, + 5716, 5716, 5716, -1, 5717, 5717, 5717, -1, + 5718, 5718, 5718, -1, 5719, 5719, 5719, -1, + 5720, 5720, 5720, -1, 5721, 5721, 5721, -1, + 5722, 5722, 5722, -1, 5723, 5723, 5723, -1, + 5724, 5724, 5724, -1, 5725, 5725, 5725, -1, + 5726, 5726, 5726, -1, 5727, 5727, 5727, -1, + 5728, 5728, 5728, -1, 5729, 5729, 5729, -1, + 5730, 5730, 5730, -1, 5731, 5731, 5731, -1, + 5732, 5732, 5732, -1, 5733, 5733, 5733, -1, + 5734, 5734, 5734, -1, 5735, 5735, 5735, -1, + 5736, 5736, 5736, -1, 5737, 5737, 5737, -1, + 5738, 5738, 5738, -1, 5739, 5739, 5739, -1, + 5740, 5740, 5740, -1, 5741, 5741, 5741, -1, + 5742, 5742, 5742, -1, 5743, 5743, 5743, -1, + 5744, 5744, 5744, -1, 5745, 5745, 5745, -1, + 5746, 5746, 5746, -1, 5747, 5747, 5747, -1, + 5748, 5748, 5748, -1, 5749, 5749, 5749, -1, + 5750, 5750, 5750, -1, 5751, 5751, 5751, -1, + 5752, 5752, 5752, -1, 5753, 5753, 5753, -1, + 5754, 5754, 5754, -1, 5755, 5755, 5755, -1, + 5756, 5756, 5756, -1, 5757, 5757, 5757, -1, + 5758, 5758, 5758, -1, 5759, 5759, 5759, -1, + 5760, 5760, 5760, -1, 5761, 5761, 5761, -1, + 5762, 5762, 5762, -1, 5763, 5763, 5763, -1, + 5764, 5764, 5764, -1, 5765, 5765, 5765, -1, + 5766, 5766, 5766, -1, 5767, 5767, 5767, -1, + 5768, 5768, 5768, -1, 5769, 5769, 5769, -1, + 5770, 5770, 5770, -1, 5771, 5771, 5771, -1, + 5772, 5772, 5772, -1, 5773, 5773, 5773, -1, + 5774, 5774, 5774, -1, 5775, 5775, 5775, -1, + 5776, 5776, 5776, -1, 5777, 5777, 5777, -1, + 5778, 5778, 5778, -1, 5779, 5779, 5779, -1, + 5780, 5780, 5780, -1, 5781, 5781, 5781, -1, + 5782, 5782, 5782, -1, 5783, 5783, 5783, -1, + 5784, 5784, 5784, -1, 5785, 5785, 5785, -1, + 5786, 5786, 5786, -1, 5787, 5787, 5787, -1, + 5788, 5788, 5788, -1, 5789, 5789, 5789, -1, + 5790, 5790, 5790, -1, 5791, 5791, 5791, -1, + 5792, 5792, 5792, -1, 5793, 5793, 5793, -1, + 5794, 5794, 5794, -1, 5795, 5795, 5795, -1, + 5796, 5796, 5796, -1, 5797, 5797, 5797, -1, + 5798, 5798, 5798, -1, 5799, 5799, 5799, -1, + 5800, 5800, 5800, -1, 5801, 5801, 5801, -1, + 5802, 5802, 5802, -1, 5803, 5803, 5803, -1, + 5804, 5804, 5804, -1, 5805, 5805, 5805, -1, + 5806, 5806, 5806, -1, 5807, 5807, 5807, -1, + 5808, 5808, 5808, -1, 5809, 5809, 5809, -1, + 5810, 5810, 5810, -1, 5811, 5811, 5811, -1, + 5812, 5812, 5812, -1, 5813, 5813, 5813, -1, + 5814, 5814, 5814, -1, 5815, 5815, 5815, -1, + 5816, 5816, 5816, -1, 5817, 5817, 5817, -1, + 5818, 5818, 5818, -1, 5819, 5819, 5819, -1, + 5820, 5820, 5820, -1, 5821, 5821, 5821, -1, + 5822, 5822, 5822, -1, 5823, 5823, 5823, -1, + 5824, 5824, 5824, -1, 5825, 5825, 5825, -1, + 5826, 5826, 5826, -1, 5827, 5827, 5827, -1, + 5828, 5828, 5828, -1, 5829, 5829, 5829, -1, + 5830, 5830, 5830, -1, 5831, 5831, 5831, -1, + 5832, 5832, 5832, -1, 5833, 5833, 5833, -1, + 5834, 5834, 5834, -1, 5835, 5835, 5835, -1, + 5836, 5836, 5836, -1, 5837, 5837, 5837, -1, + 5838, 5838, 5838, -1, 5839, 5839, 5839, -1, + 5840, 5840, 5840, -1, 5841, 5841, 5841, -1, + 5842, 5842, 5842, -1, 5843, 5843, 5843, -1, + 5844, 5844, 5844, -1, 5845, 5845, 5845, -1, + 5846, 5846, 5846, -1, 5847, 5847, 5847, -1, + 5848, 5848, 5848, -1, 5849, 5849, 5849, -1, + 5850, 5850, 5850, -1, 5851, 5851, 5851, -1, + 5852, 5852, 5852, -1, 5853, 5853, 5853, -1, + 5854, 5854, 5854, -1, 5855, 5855, 5855, -1, + 5856, 5856, 5856, -1, 5857, 5857, 5857, -1, + 5858, 5858, 5858, -1, 5859, 5859, 5859, -1, + 5860, 5860, 5860, -1, 5861, 5861, 5861, -1, + 5862, 5862, 5862, -1, 5863, 5863, 5863, -1, + 5864, 5864, 5864, -1, 5865, 5865, 5865, -1, + 5866, 5866, 5866, -1, 5867, 5867, 5867, -1, + 5868, 5868, 5868, -1, 5869, 5869, 5869, -1, + 5870, 5870, 5870, -1, 5871, 5871, 5871, -1, + 5872, 5872, 5872, -1, 5873, 5873, 5873, -1, + 5874, 5874, 5874, -1, 5875, 5875, 5875, -1, + 5876, 5876, 5876, -1, 5877, 5877, 5877, -1, + 5878, 5878, 5878, -1, 5879, 5879, 5879, -1, + 5880, 5880, 5880, -1, 5881, 5881, 5881, -1, + 5882, 5882, 5882, -1, 5883, 5883, 5883, -1, + 5884, 5884, 5884, -1, 5885, 5885, 5885, -1, + 5886, 5886, 5886, -1, 5887, 5887, 5887, -1, + 5888, 5888, 5888, -1, 5889, 5889, 5889, -1, + 5890, 5890, 5890, -1, 5891, 5891, 5891, -1, + 5892, 5892, 5892, -1, 5893, 5893, 5893, -1, + 5894, 5894, 5894, -1, 5895, 5895, 5895, -1, + 5896, 5896, 5896, -1, 5897, 5897, 5897, -1, + 5898, 5898, 5898, -1, 5899, 5899, 5899, -1, + 5900, 5900, 5900, -1, 5901, 5901, 5901, -1, + 5902, 5902, 5902, -1, 5903, 5903, 5903, -1, + 5904, 5904, 5904, -1, 5905, 5905, 5905, -1, + 5906, 5906, 5906, -1, 5907, 5907, 5907, -1, + 5908, 5908, 5908, -1, 5909, 5909, 5909, -1, + 5910, 5910, 5910, -1, 5911, 5911, 5911, -1, + 5912, 5912, 5912, -1, 5913, 5913, 5913, -1, + 5914, 5914, 5914, -1, 5915, 5915, 5915, -1, + 5916, 5916, 5916, -1, 5917, 5917, 5917, -1, + 5918, 5918, 5918, -1, 5919, 5919, 5919, -1, + 5920, 5920, 5920, -1, 5921, 5921, 5921, -1, + 5922, 5922, 5922, -1, 5923, 5923, 5923, -1, + 5924, 5924, 5924, -1, 5925, 5925, 5925, -1, + 5926, 5926, 5926, -1, 5927, 5927, 5927, -1, + 5928, 5928, 5928, -1, 5929, 5929, 5929, -1, + 5930, 5930, 5930, -1, 5931, 5931, 5931, -1, + 5932, 5932, 5932, -1, 5933, 5933, 5933, -1, + 5934, 5934, 5934, -1, 5935, 5935, 5935, -1, + 5936, 5936, 5936, -1, 5937, 5937, 5937, -1, + 5938, 5938, 5938, -1, 5939, 5939, 5939, -1, + 5940, 5940, 5940, -1, 5941, 5941, 5941, -1, + 5942, 5942, 5942, -1, 5943, 5943, 5943, -1, + 5944, 5944, 5944, -1, 5945, 5945, 5945, -1, + 5946, 5946, 5946, -1, 5947, 5947, 5947, -1, + 5948, 5948, 5948, -1, 5949, 5949, 5949, -1, + 5950, 5950, 5950, -1, 5951, 5951, 5951, -1, + 5952, 5952, 5952, -1, 5953, 5953, 5953, -1, + 5954, 5954, 5954, -1, 5955, 5955, 5955, -1, + 5956, 5956, 5956, -1, 5957, 5957, 5957, -1, + 5958, 5958, 5958, -1, 5959, 5959, 5959, -1, + 5960, 5960, 5960, -1, 5961, 5961, 5961, -1, + 5962, 5962, 5962, -1, 5963, 5963, 5963, -1, + 5964, 5964, 5964, -1, 5965, 5965, 5965, -1, + 5966, 5966, 5966, -1, 5967, 5967, 5967, -1, + 5968, 5968, 5968, -1, 5969, 5969, 5969, -1, + 5970, 5970, 5970, -1, 5971, 5971, 5971, -1, + 5972, 5972, 5972, -1, 5973, 5973, 5973, -1, + 5974, 5974, 5974, -1, 5975, 5975, 5975, -1, + 5976, 5976, 5976, -1, 5977, 5977, 5977, -1, + 5978, 5978, 5978, -1, 5979, 5979, 5979, -1, + 5980, 5980, 5980, -1, 5981, 5981, 5981, -1, + 5982, 5982, 5982, -1, 5983, 5983, 5983, -1, + 5984, 5984, 5984, -1, 5985, 5985, 5985, -1, + 5986, 5986, 5986, -1, 5987, 5987, 5987, -1, + 5988, 5988, 5988, -1, 5989, 5989, 5989, -1, + 5990, 5990, 5990, -1, 5991, 5991, 5991, -1, + 5992, 5992, 5992, -1, 5993, 5993, 5993, -1, + 5994, 5994, 5994, -1, 5995, 5995, 5995, -1, + 5996, 5996, 5996, -1, 5997, 5997, 5997, -1, + 5998, 5998, 5998, -1, 5999, 5999, 5999, -1, + 6000, 6000, 6000, -1, 6001, 6001, 6001, -1, + 6002, 6002, 6002, -1, 6003, 6003, 6003, -1, + 6004, 6004, 6004, -1, 6005, 6005, 6005, -1, + 6006, 6006, 6006, -1, 6007, 6007, 6007, -1, + 6008, 6008, 6008, -1, 6009, 6009, 6009, -1, + 6010, 6010, 6010, -1, 6011, 6011, 6011, -1, + 6012, 6012, 6012, -1, 6013, 6013, 6013, -1, + 6014, 6014, 6014, -1, 6015, 6015, 6015, -1, + 6016, 6016, 6016, -1, 6017, 6017, 6017, -1, + 6018, 6018, 6018, -1, 6019, 6019, 6019, -1, + 6020, 6020, 6020, -1, 6021, 6021, 6021, -1, + 6022, 6022, 6022, -1, 6023, 6023, 6023, -1, + 6024, 6024, 6024, -1, 6025, 6025, 6025, -1, + 6026, 6026, 6026, -1, 6027, 6027, 6027, -1, + 6028, 6028, 6028, -1, 6029, 6029, 6029, -1, + 6030, 6030, 6030, -1, 6031, 6031, 6031, -1, + 6032, 6032, 6032, -1, 6033, 6033, 6033, -1, + 6034, 6034, 6034, -1, 6035, 6035, 6035, -1, + 6036, 6036, 6036, -1, 6037, 6037, 6037, -1, + 6038, 6038, 6038, -1, 6039, 6039, 6039, -1, + 6040, 6040, 6040, -1, 6041, 6041, 6041, -1, + 6042, 6042, 6042, -1, 6043, 6043, 6043, -1, + 6044, 6044, 6044, -1, 6045, 6045, 6045, -1, + 6046, 6046, 6046, -1, 6047, 6047, 6047, -1, + 6048, 6048, 6048, -1, 6049, 6049, 6049, -1, + 6050, 6050, 6050, -1, 6051, 6051, 6051, -1, + 6052, 6052, 6052, -1, 6053, 6053, 6053, -1, + 6054, 6054, 6054, -1, 6055, 6055, 6055, -1, + 6056, 6056, 6056, -1, 6057, 6057, 6057, -1, + 6058, 6058, 6058, -1, 6059, 6059, 6059, -1, + 6060, 6060, 6060, -1, 6061, 6061, 6061, -1, + 6062, 6062, 6062, -1, 6063, 6063, 6063, -1, + 6064, 6064, 6064, -1, 6065, 6065, 6065, -1, + 6066, 6066, 6066, -1, 6067, 6067, 6067, -1, + 6068, 6068, 6068, -1, 6069, 6069, 6069, -1, + 6070, 6070, 6070, -1, 6071, 6071, 6071, -1, + 6072, 6072, 6072, -1, 6073, 6073, 6073, -1, + 6074, 6074, 6074, -1, 6075, 6075, 6075, -1, + 6076, 6076, 6076, -1, 6077, 6077, 6077, -1, + 6078, 6078, 6078, -1, 6079, 6079, 6079, -1, + 6080, 6080, 6080, -1, 6081, 6081, 6081, -1, + 6082, 6082, 6082, -1, 6083, 6083, 6083, -1, + 6084, 6084, 6084, -1, 6085, 6085, 6085, -1, + 6086, 6086, 6086, -1, 6087, 6087, 6087, -1, + 6088, 6088, 6088, -1, 6089, 6089, 6089, -1, + 6090, 6090, 6090, -1, 6091, 6091, 6091, -1, + 6092, 6092, 6092, -1, 6093, 6093, 6093, -1, + 6094, 6094, 6094, -1, 6095, 6095, 6095, -1, + 6096, 6096, 6096, -1, 6097, 6097, 6097, -1, + 6098, 6098, 6098, -1, 6099, 6099, 6099, -1, + 6100, 6100, 6100, -1, 6101, 6101, 6101, -1, + 6102, 6102, 6102, -1, 6103, 6103, 6103, -1, + 6104, 6104, 6104, -1, 6105, 6105, 6105, -1, + 6106, 6106, 6106, -1, 6107, 6107, 6107, -1, + 6108, 6108, 6108, -1, 6109, 6109, 6109, -1, + 6110, 6110, 6110, -1, 6111, 6111, 6111, -1, + 6112, 6112, 6112, -1, 6113, 6113, 6113, -1, + 6114, 6114, 6114, -1, 6115, 6115, 6115, -1, + 6116, 6116, 6116, -1, 6117, 6117, 6117, -1, + 6118, 6118, 6118, -1, 6119, 6119, 6119, -1, + 6120, 6120, 6120, -1, 6121, 6121, 6121, -1, + 6122, 6122, 6122, -1, 6123, 6123, 6123, -1, + 6124, 6124, 6124, -1, 6125, 6125, 6125, -1, + 6126, 6126, 6126, -1, 6127, 6127, 6127, -1, + 6128, 6128, 6128, -1, 6129, 6129, 6129, -1, + 6130, 6130, 6130, -1, 6131, 6131, 6131, -1, + 6132, 6132, 6132, -1, 6133, 6133, 6133, -1, + 6134, 6134, 6134, -1, 6135, 6135, 6135, -1, + 6136, 6136, 6136, -1, 6137, 6137, 6137, -1, + 6138, 6138, 6138, -1, 6139, 6139, 6139, -1, + 6140, 6140, 6140, -1, 6141, 6141, 6141, -1, + 6142, 6142, 6142, -1, 6143, 6143, 6143, -1, + 6144, 6144, 6144, -1, 6145, 6145, 6145, -1, + 6146, 6146, 6146, -1, 6147, 6147, 6147, -1, + 6148, 6148, 6148, -1, 6149, 6149, 6149, -1, + 6150, 6150, 6150, -1, 6151, 6151, 6151, -1, + 6152, 6152, 6152, -1, 6153, 6153, 6153, -1, + 6154, 6154, 6154, -1, 6155, 6155, 6155, -1, + 6156, 6156, 6156, -1, 6157, 6157, 6157, -1, + 6158, 6158, 6158, -1, 6159, 6159, 6159, -1, + 6160, 6160, 6160, -1, 6161, 6161, 6161, -1, + 6162, 6162, 6162, -1, 6163, 6163, 6163, -1, + 6164, 6164, 6164, -1, 6165, 6165, 6165, -1, + 6166, 6166, 6166, -1, 6167, 6167, 6167, -1, + 6168, 6168, 6168, -1, 6169, 6169, 6169, -1, + 6170, 6170, 6170, -1, 6171, 6171, 6171, -1, + 6172, 6172, 6172, -1, 6173, 6173, 6173, -1, + 6174, 6174, 6174, -1, 6175, 6175, 6175, -1, + 6176, 6176, 6176, -1, 6177, 6177, 6177, -1, + 6178, 6178, 6178, -1, 6179, 6179, 6179, -1, + 6180, 6180, 6180, -1, 6181, 6181, 6181, -1, + 6182, 6182, 6182, -1, 6183, 6183, 6183, -1, + 6184, 6184, 6184, -1, 6185, 6185, 6185, -1, + 6186, 6186, 6186, -1, 6187, 6187, 6187, -1, + 6188, 6188, 6188, -1, 6189, 6189, 6189, -1, + 6190, 6190, 6190, -1, 6191, 6191, 6191, -1, + 6192, 6192, 6192, -1, 6193, 6193, 6193, -1, + 6194, 6194, 6194, -1, 6195, 6195, 6195, -1, + 6196, 6196, 6196, -1, 6197, 6197, 6197, -1, + 6198, 6198, 6198, -1, 6199, 6199, 6199, -1, + 6200, 6200, 6200, -1, 6201, 6201, 6201, -1, + 6202, 6202, 6202, -1, 6203, 6203, 6203, -1, + 6204, 6204, 6204, -1, 6205, 6205, 6205, -1, + 6206, 6206, 6206, -1, 6207, 6207, 6207, -1, + 6208, 6208, 6208, -1, 6209, 6209, 6209, -1, + 6210, 6210, 6210, -1, 6211, 6211, 6211, -1, + 6212, 6212, 6212, -1, 6213, 6213, 6213, -1, + 6214, 6214, 6214, -1, 6215, 6215, 6215, -1, + 6216, 6216, 6216, -1, 6217, 6217, 6217, -1, + 6218, 6218, 6218, -1, 6219, 6219, 6219, -1, + 6220, 6220, 6220, -1, 6221, 6221, 6221, -1, + 6222, 6222, 6222, -1, 6223, 6223, 6223, -1, + 6224, 6224, 6224, -1, 6225, 6225, 6225, -1, + 6226, 6226, 6226, -1, 6227, 6227, 6227, -1, + 6228, 6228, 6228, -1, 6229, 6229, 6229, -1, + 6230, 6230, 6230, -1, 6231, 6231, 6231, -1, + 6232, 6232, 6232, -1, 6233, 6233, 6233, -1, + 6234, 6234, 6234, -1, 6235, 6235, 6235, -1, + 6236, 6236, 6236, -1, 6237, 6237, 6237, -1, + 6238, 6238, 6238, -1, 6239, 6239, 6239, -1, + 6240, 6240, 6240, -1, 6241, 6241, 6241, -1, + 6242, 6242, 6242, -1, 6243, 6243, 6243, -1, + 6244, 6244, 6244, -1, 6245, 6245, 6245, -1, + 6246, 6246, 6246, -1, 6247, 6247, 6247, -1, + 6248, 6248, 6248, -1, 6249, 6249, 6249, -1, + 6250, 6250, 6250, -1, 6251, 6251, 6251, -1, + 6252, 6252, 6252, -1, 6253, 6253, 6253, -1, + 6254, 6254, 6254, -1, 6255, 6255, 6255, -1, + 6256, 6256, 6256, -1, 6257, 6257, 6257, -1, + 6258, 6258, 6258, -1, 6259, 6259, 6259, -1, + 6260, 6260, 6260, -1, 6261, 6261, 6261, -1, + 6262, 6262, 6262, -1, 6263, 6263, 6263, -1, + 6264, 6264, 6264, -1, 6265, 6265, 6265, -1, + 6266, 6266, 6266, -1, 6267, 6267, 6267, -1, + 6268, 6268, 6268, -1, 6269, 6269, 6269, -1, + 6270, 6270, 6270, -1, 6271, 6271, 6271, -1, + 6272, 6272, 6272, -1, 6273, 6273, 6273, -1, + 6274, 6274, 6274, -1, 6275, 6275, 6275, -1, + 6276, 6276, 6276, -1, 6277, 6277, 6277, -1, + 6278, 6278, 6278, -1, 6279, 6279, 6279, -1, + 6280, 6280, 6280, -1, 6281, 6281, 6281, -1, + 6282, 6282, 6282, -1, 6283, 6283, 6283, -1, + 6284, 6284, 6284, -1, 6285, 6285, 6285, -1, + 6286, 6286, 6286, -1, 6287, 6287, 6287, -1, + 6288, 6288, 6288, -1, 6289, 6289, 6289, -1, + 6290, 6290, 6290, -1, 6291, 6291, 6291, -1, + 6292, 6292, 6292, -1, 6293, 6293, 6293, -1, + 6294, 6294, 6294, -1, 6295, 6295, 6295, -1, + 6296, 6296, 6296, -1, 6297, 6297, 6297, -1, + 6298, 6298, 6298, -1, 6299, 6299, 6299, -1, + 6300, 6300, 6300, -1, 6301, 6301, 6301, -1, + 6302, 6302, 6302, -1, 6303, 6303, 6303, -1, + 6304, 6304, 6304, -1, 6305, 6305, 6305, -1, + 6306, 6306, 6306, -1, 6307, 6307, 6307, -1, + 6308, 6308, 6308, -1, 6309, 6309, 6309, -1, + 6310, 6310, 6310, -1, 6311, 6311, 6311, -1, + 6312, 6312, 6312, -1, 6313, 6313, 6313, -1, + 6314, 6314, 6314, -1, 6315, 6315, 6315, -1, + 6316, 6316, 6316, -1, 6317, 6317, 6317, -1, + 6318, 6318, 6318, -1, 6319, 6319, 6319, -1, + 6320, 6320, 6320, -1, 6321, 6321, 6321, -1, + 6322, 6322, 6322, -1, 6323, 6323, 6323, -1, + 6324, 6324, 6324, -1, 6325, 6325, 6325, -1, + 6326, 6326, 6326, -1, 6327, 6327, 6327, -1, + 6328, 6328, 6328, -1, 6329, 6329, 6329, -1, + 6330, 6330, 6330, -1, 6331, 6331, 6331, -1, + 6332, 6332, 6332, -1, 6333, 6333, 6333, -1, + 6334, 6334, 6334, -1, 6335, 6335, 6335, -1, + 6336, 6336, 6336, -1, 6337, 6337, 6337, -1, + 6338, 6338, 6338, -1, 6339, 6339, 6339, -1, + 6340, 6340, 6340, -1, 6341, 6341, 6341, -1, + 6342, 6342, 6342, -1, 6343, 6343, 6343, -1, + 6344, 6344, 6344, -1, 6345, 6345, 6345, -1, + 6346, 6346, 6346, -1, 6347, 6347, 6347, -1, + 6348, 6348, 6348, -1, 6349, 6349, 6349, -1, + 6350, 6350, 6350, -1, 6351, 6351, 6351, -1, + 6352, 6352, 6352, -1, 6353, 6353, 6353, -1, + 6354, 6354, 6354, -1, 6355, 6355, 6355, -1, + 6356, 6356, 6356, -1, 6357, 6357, 6357, -1, + 6358, 6358, 6358, -1, 6359, 6359, 6359, -1, + 6360, 6360, 6360, -1, 6361, 6361, 6361, -1, + 6362, 6362, 6362, -1, 6363, 6363, 6363, -1, + 6364, 6364, 6364, -1, 6365, 6365, 6365, -1, + 6366, 6366, 6366, -1, 6367, 6367, 6367, -1, + 6368, 6368, 6368, -1, 6369, 6369, 6369, -1, + 6370, 6370, 6370, -1, 6371, 6371, 6371, -1, + 6372, 6372, 6372, -1, 6373, 6373, 6373, -1, + 6374, 6374, 6374, -1, 6375, 6375, 6375, -1, + 6376, 6376, 6376, -1, 6377, 6377, 6377, -1, + 6378, 6378, 6378, -1, 6379, 6379, 6379, -1, + 6380, 6380, 6380, -1, 6381, 6381, 6381, -1, + 6382, 6382, 6382, -1, 6383, 6383, 6383, -1, + 6384, 6384, 6384, -1, 6385, 6385, 6385, -1, + 6386, 6386, 6386, -1, 6387, 6387, 6387, -1, + 6388, 6388, 6388, -1, 6389, 6389, 6389, -1, + 6390, 6390, 6390, -1, 6391, 6391, 6391, -1, + 6392, 6392, 6392, -1, 6393, 6393, 6393, -1, + 6394, 6394, 6394, -1, 6395, 6395, 6395, -1, + 6396, 6396, 6396, -1, 6397, 6397, 6397, -1, + 6398, 6398, 6398, -1, 6399, 6399, 6399, -1, + 6400, 6400, 6400, -1, 6401, 6401, 6401, -1, + 6402, 6402, 6402, -1, 6403, 6403, 6403, -1, + 6404, 6404, 6404, -1, 6405, 6405, 6405, -1, + 6406, 6406, 6406, -1, 6407, 6407, 6407, -1, + 6408, 6408, 6408, -1, 6409, 6409, 6409, -1, + 6410, 6410, 6410, -1, 6411, 6411, 6411, -1, + 6412, 6412, 6412, -1, 6413, 6413, 6413, -1, + 6414, 6414, 6414, -1, 6415, 6415, 6415, -1, + 6416, 6416, 6416, -1, 6417, 6417, 6417, -1, + 6418, 6418, 6418, -1, 6419, 6419, 6419, -1, + 6420, 6420, 6420, -1, 6421, 6421, 6421, -1, + 6422, 6422, 6422, -1, 6423, 6423, 6423, -1, + 6424, 6424, 6424, -1, 6425, 6425, 6425, -1, + 6426, 6426, 6426, -1, 6427, 6427, 6427, -1, + 6428, 6428, 6428, -1, 6429, 6429, 6429, -1, + 6430, 6430, 6430, -1, 6431, 6431, 6431, -1, + 6432, 6432, 6432, -1, 6433, 6433, 6433, -1, + 6434, 6434, 6434, -1, 6435, 6435, 6435, -1, + 6436, 6436, 6436, -1, 6437, 6437, 6437, -1, + 6438, 6438, 6438, -1, 6439, 6439, 6439, -1, + 6440, 6440, 6440, -1, 6441, 6441, 6441, -1, + 6442, 6442, 6442, -1, 6443, 6443, 6443, -1, + 6444, 6444, 6444, -1, 6445, 6445, 6445, -1, + 6446, 6446, 6446, -1, 6447, 6447, 6447, -1, + 6448, 6448, 6448, -1, 6449, 6449, 6449, -1, + 6450, 6450, 6450, -1, 6451, 6451, 6451, -1, + 6452, 6452, 6452, -1, 6453, 6453, 6453, -1, + 6454, 6454, 6454, -1, 6455, 6455, 6455, -1, + 6456, 6456, 6456, -1, 6457, 6457, 6457, -1, + 6458, 6458, 6458, -1, 6459, 6459, 6459, -1, + 6460, 6460, 6460, -1, 6461, 6461, 6461, -1, + 6462, 6462, 6462, -1, 6463, 6463, 6463, -1, + 6464, 6464, 6464, -1, 6465, 6465, 6465, -1, + 6466, 6466, 6466, -1, 6467, 6467, 6467, -1, + 6468, 6468, 6468, -1, 6469, 6469, 6469, -1, + 6470, 6470, 6470, -1, 6471, 6471, 6471, -1, + 6472, 6472, 6472, -1, 6473, 6473, 6473, -1, + 6474, 6474, 6474, -1, 6475, 6475, 6475, -1, + 6476, 6476, 6476, -1, 6477, 6477, 6477, -1, + 6478, 6478, 6478, -1, 6479, 6479, 6479, -1, + 6480, 6480, 6480, -1, 6481, 6481, 6481, -1, + 6482, 6482, 6482, -1, 6483, 6483, 6483, -1, + 6484, 6484, 6484, -1, 6485, 6485, 6485, -1, + 6486, 6486, 6486, -1, 6487, 6487, 6487, -1, + 6488, 6488, 6488, -1, 6489, 6489, 6489, -1, + 6490, 6490, 6490, -1, 6491, 6491, 6491, -1, + 6492, 6492, 6492, -1, 6493, 6493, 6493, -1, + 6494, 6494, 6494, -1, 6495, 6495, 6495, -1, + 6496, 6496, 6496, -1, 6497, 6497, 6497, -1, + 6498, 6498, 6498, -1, 6499, 6499, 6499, -1, + 6500, 6500, 6500, -1, 6501, 6501, 6501, -1, + 6502, 6502, 6502, -1, 6503, 6503, 6503, -1, + 6504, 6504, 6504, -1, 6505, 6505, 6505, -1, + 6506, 6506, 6506, -1, 6507, 6507, 6507, -1, + 6508, 6508, 6508, -1, 6509, 6509, 6509, -1, + 6510, 6510, 6510, -1, 6511, 6511, 6511, -1, + 6512, 6512, 6512, -1, 6513, 6513, 6513, -1, + 6514, 6514, 6514, -1, 6515, 6515, 6515, -1, + 6516, 6516, 6516, -1, 6517, 6517, 6517, -1, + 6518, 6518, 6518, -1, 6519, 6519, 6519, -1, + 6520, 6520, 6520, -1, 6521, 6521, 6521, -1, + 6522, 6522, 6522, -1, 6523, 6523, 6523, -1, + 6524, 6524, 6524, -1, 6525, 6525, 6525, -1, + 6526, 6526, 6526, -1, 6527, 6527, 6527, -1, + 6528, 6528, 6528, -1, 6529, 6529, 6529, -1, + 6530, 6530, 6530, -1, 6531, 6531, 6531, -1, + 6532, 6532, 6532, -1, 6533, 6533, 6533, -1, + 6534, 6534, 6534, -1, 6535, 6535, 6535, -1, + 6536, 6536, 6536, -1, 6537, 6537, 6537, -1, + 6538, 6538, 6538, -1, 6539, 6539, 6539, -1, + 6540, 6540, 6540, -1, 6541, 6541, 6541, -1, + 6542, 6542, 6542, -1, 6543, 6543, 6543, -1, + 6544, 6544, 6544, -1, 6545, 6545, 6545, -1, + 6546, 6546, 6546, -1, 6547, 6547, 6547, -1, + 6548, 6548, 6548, -1, 6549, 6549, 6549, -1, + 6550, 6550, 6550, -1, 6551, 6551, 6551, -1, + 6552, 6552, 6552, -1, 6553, 6553, 6553, -1, + 6554, 6554, 6554, -1, 6555, 6555, 6555, -1, + 6556, 6556, 6556, -1, 6557, 6557, 6557, -1, + 6558, 6558, 6558, -1, 6559, 6559, 6559, -1, + 6560, 6560, 6560, -1, 6561, 6561, 6561, -1, + 6562, 6562, 6562, -1, 6563, 6563, 6563, -1, + 6564, 6564, 6564, -1, 6565, 6565, 6565, -1, + 6566, 6566, 6566, -1, 6567, 6567, 6567, -1, + 6568, 6568, 6568, -1, 6569, 6569, 6569, -1, + 6570, 6570, 6570, -1, 6571, 6571, 6571, -1, + 6572, 6572, 6572, -1, 6573, 6573, 6573, -1, + 6574, 6574, 6574, -1, 6575, 6575, 6575, -1, + 6576, 6576, 6576, -1, 6577, 6577, 6577, -1, + 6578, 6578, 6578, -1, 6579, 6579, 6579, -1, + 6580, 6580, 6580, -1, 6581, 6581, 6581, -1, + 6582, 6582, 6582, -1, 6583, 6583, 6583, -1, + 6584, 6584, 6584, -1, 6585, 6585, 6585, -1, + 6586, 6586, 6586, -1, 6587, 6587, 6587, -1, + 6588, 6588, 6588, -1, 6589, 6589, 6589, -1, + 6590, 6590, 6590, -1, 6591, 6591, 6591, -1, + 6592, 6592, 6592, -1, 6593, 6593, 6593, -1, + 6594, 6594, 6594, -1, 6595, 6595, 6595, -1, + 6596, 6596, 6596, -1, 6597, 6597, 6597, -1, + 6598, 6598, 6598, -1, 6599, 6599, 6599, -1, + 6600, 6600, 6600, -1, 6601, 6601, 6601, -1, + 6602, 6602, 6602, -1, 6603, 6603, 6603, -1, + 6604, 6604, 6604, -1, 6605, 6605, 6605, -1, + 6606, 6606, 6606, -1, 6607, 6607, 6607, -1, + 6608, 6608, 6608, -1, 6609, 6609, 6609, -1, + 6610, 6610, 6610, -1, 6611, 6611, 6611, -1, + 6612, 6612, 6612, -1, 6613, 6613, 6613, -1, + 6614, 6614, 6614, -1, 6615, 6615, 6615, -1, + 6616, 6616, 6616, -1, 6617, 6617, 6617, -1, + 6618, 6618, 6618, -1, 6619, 6619, 6619, -1, + 6620, 6620, 6620, -1, 6621, 6621, 6621, -1, + 6622, 6622, 6622, -1, 6623, 6623, 6623, -1, + 6624, 6624, 6624, -1, 6625, 6625, 6625, -1, + 6626, 6626, 6626, -1, 6627, 6627, 6627, -1, + 6628, 6628, 6628, -1, 6629, 6629, 6629, -1, + 6630, 6630, 6630, -1, 6631, 6631, 6631, -1, + 6632, 6632, 6632, -1, 6633, 6633, 6633, -1, + 6634, 6634, 6634, -1, 6635, 6635, 6635, -1, + 6636, 6636, 6636, -1, 6637, 6637, 6637, -1, + 6638, 6638, 6638, -1, 6639, 6639, 6639, -1, + 6640, 6640, 6640, -1, 6641, 6641, 6641, -1, + 6642, 6642, 6642, -1, 6643, 6643, 6643, -1, + 6644, 6644, 6644, -1, 6645, 6645, 6645, -1, + 6646, 6646, 6646, -1, 6647, 6647, 6647, -1, + 6648, 6648, 6648, -1, 6649, 6649, 6649, -1, + 6650, 6650, 6650, -1, 6651, 6651, 6651, -1, + 6652, 6652, 6652, -1, 6653, 6653, 6653, -1, + 6654, 6654, 6654, -1, 6655, 6655, 6655, -1, + 6656, 6656, 6656, -1, 6657, 6657, 6657, -1, + 6658, 6658, 6658, -1, 6659, 6659, 6659, -1, + 6660, 6660, 6660, -1, 6661, 6661, 6661, -1, + 6662, 6662, 6662, -1, 6663, 6663, 6663, -1, + 6664, 6664, 6664, -1, 6665, 6665, 6665, -1, + 6666, 6666, 6666, -1, 6667, 6667, 6667, -1, + 6668, 6668, 6668, -1, 6669, 6669, 6669, -1, + 6670, 6670, 6670, -1, 6671, 6671, 6671, -1, + 6672, 6672, 6672, -1, 6673, 6673, 6673, -1, + 6674, 6674, 6674, -1, 6675, 6675, 6675, -1, + 6676, 6676, 6676, -1, 6677, 6677, 6677, -1, + 6678, 6678, 6678, -1, 6679, 6679, 6679, -1, + 6680, 6680, 6680, -1, 6681, 6681, 6681, -1, + 6682, 6682, 6682, -1, 6683, 6683, 6683, -1, + 6684, 6684, 6684, -1, 6685, 6685, 6685, -1, + 6686, 6686, 6686, -1, 6687, 6687, 6687, -1, + 6688, 6688, 6688, -1, 6689, 6689, 6689, -1, + 6690, 6690, 6690, -1, 6691, 6691, 6691, -1, + 6692, 6692, 6692, -1, 6693, 6693, 6693, -1, + 6694, 6694, 6694, -1, 6695, 6695, 6695, -1, + 6696, 6696, 6696, -1, 6697, 6697, 6697, -1, + 6698, 6698, 6698, -1, 6699, 6699, 6699, -1, + 6700, 6700, 6700, -1, 6701, 6701, 6701, -1, + 6702, 6702, 6702, -1, 6703, 6703, 6703, -1, + 6704, 6704, 6704, -1, 6705, 6705, 6705, -1, + 6706, 6706, 6706, -1, 6707, 6707, 6707, -1, + 6708, 6708, 6708, -1, 6709, 6709, 6709, -1, + 6710, 6710, 6710, -1, 6711, 6711, 6711, -1, + 6712, 6712, 6712, -1, 6713, 6713, 6713, -1, + 6714, 6714, 6714, -1, 6715, 6715, 6715, -1, + 6716, 6716, 6716, -1, 6717, 6717, 6717, -1, + 6718, 6718, 6718, -1, 6719, 6719, 6719, -1, + 6720, 6720, 6720, -1, 6721, 6721, 6721, -1, + 6722, 6722, 6722, -1, 6723, 6723, 6723, -1, + 6724, 6724, 6724, -1, 6725, 6725, 6725, -1, + 6726, 6726, 6726, -1, 6727, 6727, 6727, -1, + 6728, 6728, 6728, -1, 6729, 6729, 6729, -1, + 6730, 6730, 6730, -1, 6731, 6731, 6731, -1, + 6732, 6732, 6732, -1, 6733, 6733, 6733, -1, + 6734, 6734, 6734, -1, 6735, 6735, 6735, -1, + 6736, 6736, 6736, -1, 6737, 6737, 6737, -1, + 6738, 6738, 6738, -1, 6739, 6739, 6739, -1, + 6740, 6740, 6740, -1, 6741, 6741, 6741, -1, + 6742, 6742, 6742, -1, 6743, 6743, 6743, -1, + 6744, 6744, 6744, -1, 6745, 6745, 6745, -1, + 6746, 6746, 6746, -1, 6747, 6747, 6747, -1, + 6748, 6748, 6748, -1, 6749, 6749, 6749, -1, + 6750, 6750, 6750, -1, 6751, 6751, 6751, -1, + 6752, 6752, 6752, -1, 6753, 6753, 6753, -1, + 6754, 6754, 6754, -1, 6755, 6755, 6755, -1, + 6756, 6756, 6756, -1, 6757, 6757, 6757, -1, + 6758, 6758, 6758, -1, 6759, 6759, 6759, -1, + 6760, 6760, 6760, -1, 6761, 6761, 6761, -1, + 6762, 6762, 6762, -1, 6763, 6763, 6763, -1, + 6764, 6764, 6764, -1, 6765, 6765, 6765, -1, + 6766, 6766, 6766, -1, 6767, 6767, 6767, -1, + 6768, 6768, 6768, -1, 6769, 6769, 6769, -1, + 6770, 6770, 6770, -1, 6771, 6771, 6771, -1, + 6772, 6772, 6772, -1, 6773, 6773, 6773, -1, + 6774, 6774, 6774, -1, 6775, 6775, 6775, -1, + 6776, 6776, 6776, -1, 6777, 6777, 6777, -1, + 6778, 6778, 6778, -1, 6779, 6779, 6779, -1, + 6780, 6780, 6780, -1, 6781, 6781, 6781, -1, + 6782, 6782, 6782, -1, 6783, 6783, 6783, -1, + 6784, 6784, 6784, -1, 6785, 6785, 6785, -1, + 6786, 6786, 6786, -1, 6787, 6787, 6787, -1, + 6788, 6788, 6788, -1, 6789, 6789, 6789, -1, + 6790, 6790, 6790, -1, 6791, 6791, 6791, -1, + 6792, 6792, 6792, -1, 6793, 6793, 6793, -1, + 6794, 6794, 6794, -1, 6795, 6795, 6795, -1, + 6796, 6796, 6796, -1, 6797, 6797, 6797, -1, + 6798, 6798, 6798, -1, 6799, 6799, 6799, -1, + 6800, 6800, 6800, -1, 6801, 6801, 6801, -1, + 6802, 6802, 6802, -1, 6803, 6803, 6803, -1, + 6804, 6804, 6804, -1, 6805, 6805, 6805, -1, + 6806, 6806, 6806, -1, 6807, 6807, 6807, -1, + 6808, 6808, 6808, -1, 6809, 6809, 6809, -1, + 6810, 6810, 6810, -1, 6811, 6811, 6811, -1, + 6812, 6812, 6812, -1, 6813, 6813, 6813, -1, + 6814, 6814, 6814, -1, 6815, 6815, 6815, -1, + 6816, 6816, 6816, -1, 6817, 6817, 6817, -1, + 6818, 6818, 6818, -1, 6819, 6819, 6819, -1, + 6820, 6820, 6820, -1, 6821, 6821, 6821, -1, + 6822, 6822, 6822, -1, 6823, 6823, 6823, -1, + 6824, 6824, 6824, -1, 6825, 6825, 6825, -1, + 6826, 6826, 6826, -1, 6827, 6827, 6827, -1, + 6828, 6828, 6828, -1, 6829, 6829, 6829, -1, + 6830, 6830, 6830, -1, 6831, 6831, 6831, -1, + 6832, 6832, 6832, -1, 6833, 6833, 6833, -1, + 6834, 6834, 6834, -1, 6835, 6835, 6835, -1, + 6836, 6836, 6836, -1, 6837, 6837, 6837, -1, + 6838, 6838, 6838, -1, 6839, 6839, 6839, -1, + 6840, 6840, 6840, -1, 6841, 6841, 6841, -1, + 6842, 6842, 6842, -1, 6843, 6843, 6843, -1, + 6844, 6844, 6844, -1, 6845, 6845, 6845, -1, + 6846, 6846, 6846, -1, 6847, 6847, 6847, -1, + 6848, 6848, 6848, -1, 6849, 6849, 6849, -1, + 6850, 6850, 6850, -1, 6851, 6851, 6851, -1, + 6852, 6852, 6852, -1, 6853, 6853, 6853, -1, + 6854, 6854, 6854, -1, 6855, 6855, 6855, -1, + 6856, 6856, 6856, -1, 6857, 6857, 6857, -1, + 6858, 6858, 6858, -1, 6859, 6859, 6859, -1, + 6860, 6860, 6860, -1, 6861, 6861, 6861, -1, + 6862, 6862, 6862, -1, 6863, 6863, 6863, -1, + 6864, 6864, 6864, -1, 6865, 6865, 6865, -1, + 6866, 6866, 6866, -1, 6867, 6867, 6867, -1, + 6868, 6868, 6868, -1, 6869, 6869, 6869, -1, + 6870, 6870, 6870, -1, 6871, 6871, 6871, -1, + 6872, 6872, 6872, -1, 6873, 6873, 6873, -1, + 6874, 6874, 6874, -1, 6875, 6875, 6875, -1, + 6876, 6876, 6876, -1, 6877, 6877, 6877, -1, + 6878, 6878, 6878, -1, 6879, 6879, 6879, -1, + 6880, 6880, 6880, -1, 6881, 6881, 6881, -1, + 6882, 6882, 6882, -1, 6883, 6883, 6883, -1, + 6884, 6884, 6884, -1, 6885, 6885, 6885, -1, + 6886, 6886, 6886, -1, 6887, 6887, 6887, -1, + 6888, 6888, 6888, -1, 6889, 6889, 6889, -1, + 6890, 6890, 6890, -1, 6891, 6891, 6891, -1, + 6892, 6892, 6892, -1, 6893, 6893, 6893, -1, + 6894, 6894, 6894, -1, 6895, 6895, 6895, -1, + 6896, 6896, 6896, -1, 6897, 6897, 6897, -1, + 6898, 6898, 6898, -1, 6899, 6899, 6899, -1, + 6900, 6900, 6900, -1, 6901, 6901, 6901, -1, + 6902, 6902, 6902, -1, 6903, 6903, 6903, -1, + 6904, 6904, 6904, -1, 6905, 6905, 6905, -1, + 6906, 6906, 6906, -1, 6907, 6907, 6907, -1, + 6908, 6908, 6908, -1, 6909, 6909, 6909, -1, + 6910, 6910, 6910, -1, 6911, 6911, 6911, -1, + 6912, 6912, 6912, -1, 6913, 6913, 6913, -1, + 6914, 6914, 6914, -1, 6915, 6915, 6915, -1, + 6916, 6916, 6916, -1, 6917, 6917, 6917, -1, + 6918, 6918, 6918, -1, 6919, 6919, 6919, -1, + 6920, 6920, 6920, -1, 6921, 6921, 6921, -1, + 6922, 6922, 6922, -1, 6923, 6923, 6923, -1, + 6924, 6924, 6924, -1, 6925, 6925, 6925, -1, + 6926, 6926, 6926, -1, 6927, 6927, 6927, -1, + 6928, 6928, 6928, -1, 6929, 6929, 6929, -1, + 6930, 6930, 6930, -1, 6931, 6931, 6931, -1, + 6932, 6932, 6932, -1, 6933, 6933, 6933, -1, + 6934, 6934, 6934, -1, 6935, 6935, 6935, -1, + 6936, 6936, 6936, -1, 6937, 6937, 6937, -1, + 6938, 6938, 6938, -1, 6939, 6939, 6939, -1, + 6940, 6940, 6940, -1, 6941, 6941, 6941, -1, + 6942, 6942, 6942, -1, 6943, 6943, 6943, -1, + 6944, 6944, 6944, -1, 6945, 6945, 6945, -1, + 6946, 6946, 6946, -1, 6947, 6947, 6947, -1, + 6948, 6948, 6948, -1, 6949, 6949, 6949, -1, + 6950, 6950, 6950, -1, 6951, 6951, 6951, -1, + 6952, 6952, 6952, -1, 6953, 6953, 6953, -1, + 6954, 6954, 6954, -1, 6955, 6955, 6955, -1, + 6956, 6956, 6956, -1, 6957, 6957, 6957, -1, + 6958, 6958, 6958, -1, 6959, 6959, 6959, -1, + 6960, 6960, 6960, -1, 6961, 6961, 6961, -1, + 6962, 6962, 6962, -1, 6963, 6963, 6963, -1, + 6964, 6964, 6964, -1, 6965, 6965, 6965, -1, + 6966, 6966, 6966, -1, 6967, 6967, 6967, -1, + 6968, 6968, 6968, -1, 6969, 6969, 6969, -1, + 6970, 6970, 6970, -1, 6971, 6971, 6971, -1, + 6972, 6972, 6972, -1, 6973, 6973, 6973, -1, + 6974, 6974, 6974, -1, 6975, 6975, 6975, -1, + 6976, 6976, 6976, -1, 6977, 6977, 6977, -1, + 6978, 6978, 6978, -1, 6979, 6979, 6979, -1, + 6980, 6980, 6980, -1, 6981, 6981, 6981, -1, + 6982, 6982, 6982, -1, 6983, 6983, 6983, -1, + 6984, 6984, 6984, -1, 6985, 6985, 6985, -1, + 6986, 6986, 6986, -1, 6987, 6987, 6987, -1, + 6988, 6988, 6988, -1, 6989, 6989, 6989, -1, + 6990, 6990, 6990, -1, 6991, 6991, 6991, -1, + 6992, 6992, 6992, -1, 6993, 6993, 6993, -1, + 6994, 6994, 6994, -1, 6995, 6995, 6995, -1, + 6996, 6996, 6996, -1, 6997, 6997, 6997, -1, + 6998, 6998, 6998, -1, 6999, 6999, 6999, -1, + 7000, 7000, 7000, -1, 7001, 7001, 7001, -1, + 7002, 7002, 7002, -1, 7003, 7003, 7003, -1, + 7004, 7004, 7004, -1, 7005, 7005, 7005, -1, + 7006, 7006, 7006, -1, 7007, 7007, 7007, -1, + 7008, 7008, 7008, -1, 7009, 7009, 7009, -1, + 7010, 7010, 7010, -1, 7011, 7011, 7011, -1, + 7012, 7012, 7012, -1, 7013, 7013, 7013, -1, + 7014, 7014, 7014, -1, 7015, 7015, 7015, -1, + 7016, 7016, 7016, -1, 7017, 7017, 7017, -1, + 7018, 7018, 7018, -1, 7019, 7019, 7019, -1, + 7020, 7020, 7020, -1, 7021, 7021, 7021, -1, + 7022, 7022, 7022, -1, 7023, 7023, 7023, -1, + 7024, 7024, 7024, -1, 7025, 7025, 7025, -1, + 7026, 7026, 7026, -1, 7027, 7027, 7027, -1, + 7028, 7028, 7028, -1, 7029, 7029, 7029, -1, + 7030, 7030, 7030, -1, 7031, 7031, 7031, -1, + 7032, 7032, 7032, -1, 7033, 7033, 7033, -1, + 7034, 7034, 7034, -1, 7035, 7035, 7035, -1, + 7036, 7036, 7036, -1, 7037, 7037, 7037, -1, + 7038, 7038, 7038, -1, 7039, 7039, 7039, -1, + 7040, 7040, 7040, -1, 7041, 7041, 7041, -1, + 7042, 7042, 7042, -1, 7043, 7043, 7043, -1, + 7044, 7044, 7044, -1, 7045, 7045, 7045, -1, + 7046, 7046, 7046, -1, 7047, 7047, 7047, -1, + 7048, 7048, 7048, -1, 7049, 7049, 7049, -1, + 7050, 7050, 7050, -1, 7051, 7051, 7051, -1, + 7052, 7052, 7052, -1, 7053, 7053, 7053, -1, + 7054, 7054, 7054, -1, 7055, 7055, 7055, -1, + 7056, 7056, 7056, -1, 7057, 7057, 7057, -1, + 7058, 7058, 7058, -1, 7059, 7059, 7059, -1, + 7060, 7060, 7060, -1, 7061, 7061, 7061, -1, + 7062, 7062, 7062, -1, 7063, 7063, 7063, -1, + 7064, 7064, 7064, -1, 7065, 7065, 7065, -1, + 7066, 7066, 7066, -1, 7067, 7067, 7067, -1, + 7068, 7068, 7068, -1, 7069, 7069, 7069, -1, + 7070, 7070, 7070, -1, 7071, 7071, 7071, -1, + 7072, 7072, 7072, -1, 7073, 7073, 7073, -1, + 7074, 7074, 7074, -1, 7075, 7075, 7075, -1, + 7076, 7076, 7076, -1, 7077, 7077, 7077, -1, + 7078, 7078, 7078, -1, 7079, 7079, 7079, -1, + 7080, 7080, 7080, -1, 7081, 7081, 7081, -1, + 7082, 7082, 7082, -1, 7083, 7083, 7083, -1, + 7084, 7084, 7084, -1, 7085, 7085, 7085, -1, + 7086, 7086, 7086, -1, 7087, 7087, 7087, -1, + 7088, 7088, 7088, -1, 7089, 7089, 7089, -1, + 7090, 7090, 7090, -1, 7091, 7091, 7091, -1, + 7092, 7092, 7092, -1, 7093, 7093, 7093, -1, + 7094, 7094, 7094, -1, 7095, 7095, 7095, -1, + 7096, 7096, 7096, -1, 7097, 7097, 7097, -1, + 7098, 7098, 7098, -1, 7099, 7099, 7099, -1, + 7100, 7100, 7100, -1, 7101, 7101, 7101, -1, + 7102, 7102, 7102, -1, 7103, 7103, 7103, -1, + 7104, 7104, 7104, -1, 7105, 7105, 7105, -1, + 7106, 7106, 7106, -1, 7107, 7107, 7107, -1, + 7108, 7108, 7108, -1, 7109, 7109, 7109, -1, + 7110, 7110, 7110, -1, 7111, 7111, 7111, -1, + 7112, 7112, 7112, -1, 7113, 7113, 7113, -1, + 7114, 7114, 7114, -1, 7115, 7115, 7115, -1, + 7116, 7116, 7116, -1, 7117, 7117, 7117, -1, + 7118, 7118, 7118, -1, 7119, 7119, 7119, -1, + 7120, 7120, 7120, -1, 7121, 7121, 7121, -1, + 7122, 7122, 7122, -1, 7123, 7123, 7123, -1, + 7124, 7124, 7124, -1, 7125, 7125, 7125, -1, + 7126, 7126, 7126, -1, 7127, 7127, 7127, -1, + 7128, 7128, 7128, -1, 7129, 7129, 7129, -1, + 7130, 7130, 7130, -1, 7131, 7131, 7131, -1, + 7132, 7132, 7132, -1, 7133, 7133, 7133, -1, + 7134, 7134, 7134, -1, 7135, 7135, 7135, -1, + 7136, 7136, 7136, -1, 7137, 7137, 7137, -1, + 7138, 7138, 7138, -1, 7139, 7139, 7139, -1, + 7140, 7140, 7140, -1, 7141, 7141, 7141, -1, + 7142, 7142, 7142, -1, 7143, 7143, 7143, -1, + 7144, 7144, 7144, -1, 7145, 7145, 7145, -1, + 7146, 7146, 7146, -1, 7147, 7147, 7147, -1, + 7148, 7148, 7148, -1, 7149, 7149, 7149, -1, + 7150, 7150, 7150, -1, 7151, 7151, 7151, -1, + 7152, 7152, 7152, -1, 7153, 7153, 7153, -1, + 7154, 7154, 7154, -1, 7155, 7155, 7155, -1, + 7156, 7156, 7156, -1, 7157, 7157, 7157, -1, + 7158, 7158, 7158, -1, 7159, 7159, 7159, -1, + 7160, 7160, 7160, -1, 7161, 7161, 7161, -1, + 7162, 7162, 7162, -1, 7163, 7163, 7163, -1, + 7164, 7164, 7164, -1, 7165, 7165, 7165, -1, + 7166, 7166, 7166, -1, 7167, 7167, 7167, -1, + 7168, 7168, 7168, -1, 7169, 7169, 7169, -1, + 7170, 7170, 7170, -1, 7171, 7171, 7171, -1, + 7172, 7172, 7172, -1, 7173, 7173, 7173, -1, + 7174, 7174, 7174, -1, 7175, 7175, 7175, -1, + 7176, 7176, 7176, -1, 7177, 7177, 7177, -1, + 7178, 7178, 7178, -1, 7179, 7179, 7179, -1, + 7180, 7180, 7180, -1, 7181, 7181, 7181, -1, + 7182, 7182, 7182, -1, 7183, 7183, 7183, -1, + 7184, 7184, 7184, -1, 7185, 7185, 7185, -1, + 7186, 7186, 7186, -1, 7187, 7187, 7187, -1, + 7188, 7188, 7188, -1, 7189, 7189, 7189, -1, + 7190, 7190, 7190, -1, 7191, 7191, 7191, -1, + 7192, 7192, 7192, -1, 7193, 7193, 7193, -1, + 7194, 7194, 7194, -1, 7195, 7195, 7195, -1, + 7196, 7196, 7196, -1, 7197, 7197, 7197, -1, + 7198, 7198, 7198, -1, 7199, 7199, 7199, -1, + 7200, 7200, 7200, -1, 7201, 7201, 7201, -1, + 7202, 7202, 7202, -1, 7203, 7203, 7203, -1, + 7204, 7204, 7204, -1, 7205, 7205, 7205, -1, + 7206, 7206, 7206, -1, 7207, 7207, 7207, -1, + 7208, 7208, 7208, -1, 7209, 7209, 7209, -1, + 7210, 7210, 7210, -1, 7211, 7211, 7211, -1, + 7212, 7212, 7212, -1, 7213, 7213, 7213, -1, + 7214, 7214, 7214, -1, 7215, 7215, 7215, -1, + 7216, 7216, 7216, -1, 7217, 7217, 7217, -1, + 7218, 7218, 7218, -1, 7219, 7219, 7219, -1, + 7220, 7220, 7220, -1, 7221, 7221, 7221, -1, + 7222, 7222, 7222, -1, 7223, 7223, 7223, -1, + 7224, 7224, 7224, -1, 7225, 7225, 7225, -1, + 7226, 7226, 7226, -1, 7227, 7227, 7227, -1, + 7228, 7228, 7228, -1, 7229, 7229, 7229, -1, + 7230, 7230, 7230, -1, 7231, 7231, 7231, -1, + 7232, 7232, 7232, -1, 7233, 7233, 7233, -1, + 7234, 7234, 7234, -1, 7235, 7235, 7235, -1, + 7236, 7236, 7236, -1, 7237, 7237, 7237, -1, + 7238, 7238, 7238, -1, 7239, 7239, 7239, -1, + 7240, 7240, 7240, -1, 7241, 7241, 7241, -1, + 7242, 7242, 7242, -1, 7243, 7243, 7243, -1, + 7244, 7244, 7244, -1, 7245, 7245, 7245, -1, + 7246, 7246, 7246, -1, 7247, 7247, 7247, -1, + 7248, 7248, 7248, -1, 7249, 7249, 7249, -1, + 7250, 7250, 7250, -1, 7251, 7251, 7251, -1, + 7252, 7252, 7252, -1, 7253, 7253, 7253, -1, + 7254, 7254, 7254, -1, 7255, 7255, 7255, -1, + 7256, 7256, 7256, -1, 7257, 7257, 7257, -1, + 7258, 7258, 7258, -1, 7259, 7259, 7259, -1, + 7260, 7260, 7260, -1, 7261, 7261, 7261, -1, + 7262, 7262, 7262, -1, 7263, 7263, 7263, -1, + 7264, 7264, 7264, -1, 7265, 7265, 7265, -1, + 7266, 7266, 7266, -1, 7267, 7267, 7267, -1, + 7268, 7268, 7268, -1, 7269, 7269, 7269, -1, + 7270, 7270, 7270, -1, 7271, 7271, 7271, -1, + 7272, 7272, 7272, -1, 7273, 7273, 7273, -1, + 7274, 7274, 7274, -1, 7275, 7275, 7275, -1, + 7276, 7276, 7276, -1, 7277, 7277, 7277, -1, + 7278, 7278, 7278, -1, 7279, 7279, 7279, -1, + 7280, 7280, 7280, -1, 7281, 7281, 7281, -1, + 7282, 7282, 7282, -1, 7283, 7283, 7283, -1, + 7284, 7284, 7284, -1, 7285, 7285, 7285, -1, + 7286, 7286, 7286, -1, 7287, 7287, 7287, -1, + 7288, 7288, 7288, -1, 7289, 7289, 7289, -1, + 7290, 7290, 7290, -1, 7291, 7291, 7291, -1, + 7292, 7292, 7292, -1, 7293, 7293, 7293, -1, + 7294, 7294, 7294, -1, 7295, 7295, 7295, -1, + 7296, 7296, 7296, -1, 7297, 7297, 7297, -1, + 7298, 7298, 7298, -1, 7299, 7299, 7299, -1, + 7300, 7300, 7300, -1, 7301, 7301, 7301, -1, + 7302, 7302, 7302, -1, 7303, 7303, 7303, -1, + 7304, 7304, 7304, -1, 7305, 7305, 7305, -1, + 7306, 7306, 7306, -1, 7307, 7307, 7307, -1, + 7308, 7308, 7308, -1, 7309, 7309, 7309, -1, + 7310, 7310, 7310, -1, 7311, 7311, 7311, -1, + 7312, 7312, 7312, -1, 7313, 7313, 7313, -1, + 7314, 7314, 7314, -1, 7315, 7315, 7315, -1, + 7316, 7316, 7316, -1, 7317, 7317, 7317, -1, + 7318, 7318, 7318, -1, 7319, 7319, 7319, -1, + 7320, 7320, 7320, -1, 7321, 7321, 7321, -1, + 7322, 7322, 7322, -1, 7323, 7323, 7323, -1, + 7324, 7324, 7324, -1, 7325, 7325, 7325, -1, + 7326, 7326, 7326, -1, 7327, 7327, 7327, -1, + 7328, 7328, 7328, -1, 7329, 7329, 7329, -1, + 7330, 7330, 7330, -1, 7331, 7331, 7331, -1, + 7332, 7332, 7332, -1, 7333, 7333, 7333, -1, + 7334, 7334, 7334, -1, 7335, 7335, 7335, -1, + 7336, 7336, 7336, -1, 7337, 7337, 7337, -1, + 7338, 7338, 7338, -1, 7339, 7339, 7339, -1, + 7340, 7340, 7340, -1, 7341, 7341, 7341, -1, + 7342, 7342, 7342, -1, 7343, 7343, 7343, -1, + 7344, 7344, 7344, -1, 7345, 7345, 7345, -1, + 7346, 7346, 7346, -1, 7347, 7347, 7347, -1, + 7348, 7348, 7348, -1, 7349, 7349, 7349, -1, + 7350, 7350, 7350, -1, 7351, 7351, 7351, -1, + 7352, 7352, 7352, -1, 7353, 7353, 7353, -1, + 7354, 7354, 7354, -1, 7355, 7355, 7355, -1, + 7356, 7356, 7356, -1, 7357, 7357, 7357, -1, + 7358, 7358, 7358, -1, 7359, 7359, 7359, -1, + 7360, 7360, 7360, -1, 7361, 7361, 7361, -1, + 7362, 7362, 7362, -1, 7363, 7363, 7363, -1, + 7364, 7364, 7364, -1, 7365, 7365, 7365, -1, + 7366, 7366, 7366, -1, 7367, 7367, 7367, -1, + 7368, 7368, 7368, -1, 7369, 7369, 7369, -1, + 7370, 7370, 7370, -1, 7371, 7371, 7371, -1, + 7372, 7372, 7372, -1, 7373, 7373, 7373, -1, + 7374, 7374, 7374, -1, 7375, 7375, 7375, -1, + 7376, 7376, 7376, -1, 7377, 7377, 7377, -1, + 7378, 7378, 7378, -1, 7379, 7379, 7379, -1, + 7380, 7380, 7380, -1, 7381, 7381, 7381, -1, + 7382, 7382, 7382, -1, 7383, 7383, 7383, -1, + 7384, 7384, 7384, -1, 7385, 7385, 7385, -1, + 7386, 7386, 7386, -1, 7387, 7387, 7387, -1, + 7388, 7388, 7388, -1, 7389, 7389, 7389, -1, + 7390, 7390, 7390, -1, 7391, 7391, 7391, -1, + 7392, 7392, 7392, -1, 7393, 7393, 7393, -1, + 7394, 7394, 7394, -1, 7395, 7395, 7395, -1, + 7396, 7396, 7396, -1, 7397, 7397, 7397, -1, + 7398, 7398, 7398, -1, 7399, 7399, 7399, -1, + 7400, 7400, 7400, -1, 7401, 7401, 7401, -1, + 7402, 7402, 7402, -1, 7403, 7403, 7403, -1, + 7404, 7404, 7404, -1, 7405, 7405, 7405, -1, + 7406, 7406, 7406, -1, 7407, 7407, 7407, -1, + 7408, 7408, 7408, -1, 7409, 7409, 7409, -1, + 7410, 7410, 7410, -1, 7411, 7411, 7411, -1, + 7412, 7412, 7412, -1, 7413, 7413, 7413, -1, + 7414, 7414, 7414, -1, 7415, 7415, 7415, -1, + 7416, 7416, 7416, -1, 7417, 7417, 7417, -1, + 7418, 7418, 7418, -1, 7419, 7419, 7419, -1, + 7420, 7420, 7420, -1, 7421, 7421, 7421, -1, + 7422, 7422, 7422, -1, 7423, 7423, 7423, -1, + 7424, 7424, 7424, -1, 7425, 7425, 7425, -1, + 7426, 7426, 7426, -1, 7427, 7427, 7427, -1, + 7428, 7428, 7428, -1, 7429, 7429, 7429, -1, + 7430, 7430, 7430, -1, 7431, 7431, 7431, -1, + 7432, 7432, 7432, -1, 7433, 7433, 7433, -1, + 7434, 7434, 7434, -1, 7435, 7435, 7435, -1, + 7436, 7436, 7436, -1, 7437, 7437, 7437, -1, + 7438, 7438, 7438, -1, 7439, 7439, 7439, -1, + 7440, 7440, 7440, -1, 7441, 7441, 7441, -1, + 7442, 7442, 7442, -1, 7443, 7443, 7443, -1, + 7444, 7444, 7444, -1, 7445, 7445, 7445, -1, + 7446, 7446, 7446, -1, 7447, 7447, 7447, -1, + 7448, 7448, 7448, -1, 7449, 7449, 7449, -1, + 7450, 7450, 7450, -1, 7451, 7451, 7451, -1, + 7452, 7452, 7452, -1, 7453, 7453, 7453, -1, + 7454, 7454, 7454, -1, 7455, 7455, 7455, -1, + 7456, 7456, 7456, -1, 7457, 7457, 7457, -1, + 7458, 7458, 7458, -1, 7459, 7459, 7459, -1, + 7460, 7460, 7460, -1, 7461, 7461, 7461, -1, + 7462, 7462, 7462, -1, 7463, 7463, 7463, -1, + 7464, 7464, 7464, -1, 7465, 7465, 7465, -1, + 7466, 7466, 7466, -1, 7467, 7467, 7467, -1, + 7468, 7468, 7468, -1, 7469, 7469, 7469, -1, + 7470, 7470, 7470, -1, 7471, 7471, 7471, -1, + 7472, 7472, 7472, -1, 7473, 7473, 7473, -1, + 7474, 7474, 7474, -1, 7475, 7475, 7475, -1, + 7476, 7476, 7476, -1, 7477, 7477, 7477, -1, + 7478, 7478, 7478, -1, 7479, 7479, 7479, -1, + 7480, 7480, 7480, -1, 7481, 7481, 7481, -1, + 7482, 7482, 7482, -1, 7483, 7483, 7483, -1, + 7484, 7484, 7484, -1, 7485, 7485, 7485, -1, + 7486, 7486, 7486, -1, 7487, 7487, 7487, -1, + 7488, 7488, 7488, -1, 7489, 7489, 7489, -1, + 7490, 7490, 7490, -1, 7491, 7491, 7491, -1, + 7492, 7492, 7492, -1, 7493, 7493, 7493, -1, + 7494, 7494, 7494, -1, 7495, 7495, 7495, -1, + 7496, 7496, 7496, -1, 7497, 7497, 7497, -1, + 7498, 7498, 7498, -1, 7499, 7499, 7499, -1, + 7500, 7500, 7500, -1, 7501, 7501, 7501, -1, + 7502, 7502, 7502, -1, 7503, 7503, 7503, -1, + 7504, 7504, 7504, -1, 7505, 7505, 7505, -1, + 7506, 7506, 7506, -1, 7507, 7507, 7507, -1, + 7508, 7508, 7508, -1, 7509, 7509, 7509, -1, + 7510, 7510, 7510, -1, 7511, 7511, 7511, -1, + 7512, 7512, 7512, -1, 7513, 7513, 7513, -1, + 7514, 7514, 7514, -1, 7515, 7515, 7515, -1, + 7516, 7516, 7516, -1, 7517, 7517, 7517, -1, + 7518, 7518, 7518, -1, 7519, 7519, 7519, -1, + 7520, 7520, 7520, -1, 7521, 7521, 7521, -1, + 7522, 7522, 7522, -1, 7523, 7523, 7523, -1, + 7524, 7524, 7524, -1, 7525, 7525, 7525, -1, + 7526, 7526, 7526, -1, 7527, 7527, 7527, -1, + 7528, 7528, 7528, -1, 7529, 7529, 7529, -1, + 7530, 7530, 7530, -1, 7531, 7531, 7531, -1, + 7532, 7532, 7532, -1, 7533, 7533, 7533, -1, + 7534, 7534, 7534, -1, 7535, 7535, 7535, -1, + 7536, 7536, 7536, -1, 7537, 7537, 7537, -1, + 7538, 7538, 7538, -1, 7539, 7539, 7539, -1, + 7540, 7540, 7540, -1, 7541, 7541, 7541, -1, + 7542, 7542, 7542, -1, 7543, 7543, 7543, -1, + 7544, 7544, 7544, -1, 7545, 7545, 7545, -1, + 7546, 7546, 7546, -1, 7547, 7547, 7547, -1, + 7548, 7548, 7548, -1, 7549, 7549, 7549, -1, + 7550, 7550, 7550, -1, 7551, 7551, 7551, -1, + 7552, 7552, 7552, -1, 7553, 7553, 7553, -1, + 7554, 7554, 7554, -1, 7555, 7555, 7555, -1, + 7556, 7556, 7556, -1, 7557, 7557, 7557, -1, + 7558, 7558, 7558, -1, 7559, 7559, 7559, -1, + 7560, 7560, 7560, -1, 7561, 7561, 7561, -1, + 7562, 7562, 7562, -1, 7563, 7563, 7563, -1, + 7564, 7564, 7564, -1, 7565, 7565, 7565, -1, + 7566, 7566, 7566, -1, 7567, 7567, 7567, -1, + 7568, 7568, 7568, -1, 7569, 7569, 7569, -1, + 7570, 7570, 7570, -1, 7571, 7571, 7571, -1, + 7572, 7572, 7572, -1, 7573, 7573, 7573, -1, + 7574, 7574, 7574, -1, 7575, 7575, 7575, -1, + 7576, 7576, 7576, -1, 7577, 7577, 7577, -1, + 7578, 7578, 7578, -1, 7579, 7579, 7579, -1, + 7580, 7580, 7580, -1, 7581, 7581, 7581, -1, + 7582, 7582, 7582, -1, 7583, 7583, 7583, -1, + 7584, 7584, 7584, -1, 7585, 7585, 7585, -1, + 7586, 7586, 7586, -1, 7587, 7587, 7587, -1, + 7588, 7588, 7588, -1, 7589, 7589, 7589, -1, + 7590, 7590, 7590, -1, 7591, 7591, 7591, -1, + 7592, 7592, 7592, -1, 7593, 7593, 7593, -1, + 7594, 7594, 7594, -1, 7595, 7595, 7595, -1, + 7596, 7596, 7596, -1, 7597, 7597, 7597, -1, + 7598, 7598, 7598, -1, 7599, 7599, 7599, -1, + 7600, 7600, 7600, -1, 7601, 7601, 7601, -1, + 7602, 7602, 7602, -1, 7603, 7603, 7603, -1, + 7604, 7604, 7604, -1, 7605, 7605, 7605, -1, + 7606, 7606, 7606, -1, 7607, 7607, 7607, -1, + 7608, 7608, 7608, -1, 7609, 7609, 7609, -1, + 7610, 7610, 7610, -1, 7611, 7611, 7611, -1, + 7612, 7612, 7612, -1, 7613, 7613, 7613, -1, + 7614, 7614, 7614, -1, 7615, 7615, 7615, -1, + 7616, 7616, 7616, -1, 7617, 7617, 7617, -1, + 7618, 7618, 7618, -1, 7619, 7619, 7619, -1, + 7620, 7620, 7620, -1, 7621, 7621, 7621, -1, + 7622, 7622, 7622, -1, 7623, 7623, 7623, -1, + 7624, 7624, 7624, -1, 7625, 7625, 7625, -1, + 7626, 7626, 7626, -1, 7627, 7627, 7627, -1, + 7628, 7628, 7628, -1, 7629, 7629, 7629, -1, + 7630, 7630, 7630, -1, 7631, 7631, 7631, -1, + 7632, 7632, 7632, -1, 7633, 7633, 7633, -1, + 7634, 7634, 7634, -1, 7635, 7635, 7635, -1, + 7636, 7636, 7636, -1, 7637, 7637, 7637, -1, + 7638, 7638, 7638, -1, 7639, 7639, 7639, -1, + 7640, 7640, 7640, -1, 7641, 7641, 7641, -1, + 7642, 7642, 7642, -1, 7643, 7643, 7643, -1, + 7644, 7644, 7644, -1, 7645, 7645, 7645, -1, + 7646, 7646, 7646, -1, 7647, 7647, 7647, -1, + 7648, 7648, 7648, -1, 7649, 7649, 7649, -1, + 7650, 7650, 7650, -1, 7651, 7651, 7651, -1, + 7652, 7652, 7652, -1, 7653, 7653, 7653, -1, + 7654, 7654, 7654, -1, 7655, 7655, 7655, -1, + 7656, 7656, 7656, -1, 7657, 7657, 7657, -1, + 7658, 7658, 7658, -1, 7659, 7659, 7659, -1, + 7660, 7660, 7660, -1, 7661, 7661, 7661, -1, + 7662, 7662, 7662, -1, 7663, 7663, 7663, -1, + 7664, 7664, 7664, -1, 7665, 7665, 7665, -1, + 7666, 7666, 7666, -1, 7667, 7667, 7667, -1, + 7668, 7668, 7668, -1, 7669, 7669, 7669, -1, + 7670, 7670, 7670, -1, 7671, 7671, 7671, -1, + 7672, 7672, 7672, -1, 7673, 7673, 7673, -1, + 7674, 7674, 7674, -1, 7675, 7675, 7675, -1, + 7676, 7676, 7676, -1, 7677, 7677, 7677, -1, + 7678, 7678, 7678, -1, 7679, 7679, 7679, -1, + 7680, 7680, 7680, -1, 7681, 7681, 7681, -1, + 7682, 7682, 7682, -1, 7683, 7683, 7683, -1, + 7684, 7684, 7684, -1, 7685, 7685, 7685, -1, + 7686, 7686, 7686, -1, 7687, 7687, 7687, -1, + 7688, 7688, 7688, -1, 7689, 7689, 7689, -1, + 7690, 7690, 7690, -1, 7691, 7691, 7691, -1, + 7692, 7692, 7692, -1, 7693, 7693, 7693, -1, + 7694, 7694, 7694, -1, 7695, 7695, 7695, -1, + 7696, 7696, 7696, -1, 7697, 7697, 7697, -1, + 7698, 7698, 7698, -1, 7699, 7699, 7699, -1, + 7700, 7700, 7700, -1, 7701, 7701, 7701, -1, + 7702, 7702, 7702, -1, 7703, 7703, 7703, -1, + 7704, 7704, 7704, -1, 7705, 7705, 7705, -1, + 7706, 7706, 7706, -1, 7707, 7707, 7707, -1, + 7708, 7708, 7708, -1, 7709, 7709, 7709, -1, + 7710, 7710, 7710, -1, 7711, 7711, 7711, -1, + 7712, 7712, 7712, -1, 7713, 7713, 7713, -1, + 7714, 7714, 7714, -1, 7715, 7715, 7715, -1, + 7716, 7716, 7716, -1, 7717, 7717, 7717, -1, + 7718, 7718, 7718, -1, 7719, 7719, 7719, -1, + 7720, 7720, 7720, -1, 7721, 7721, 7721, -1, + 7722, 7722, 7722, -1, 7723, 7723, 7723, -1, + 7724, 7724, 7724, -1, 7725, 7725, 7725, -1, + 7726, 7726, 7726, -1, 7727, 7727, 7727, -1, + 7728, 7728, 7728, -1, 7729, 7729, 7729, -1, + 7730, 7730, 7730, -1, 7731, 7731, 7731, -1, + 7732, 7732, 7732, -1, 7733, 7733, 7733, -1, + 7734, 7734, 7734, -1, 7735, 7735, 7735, -1, + 7736, 7736, 7736, -1, 7737, 7737, 7737, -1, + 7738, 7738, 7738, -1, 7739, 7739, 7739, -1, + 7740, 7740, 7740, -1, 7741, 7741, 7741, -1, + 7742, 7742, 7742, -1, 7743, 7743, 7743, -1, + 7744, 7744, 7744, -1, 7745, 7745, 7745, -1, + 7746, 7746, 7746, -1, 7747, 7747, 7747, -1, + 7748, 7748, 7748, -1, 7749, 7749, 7749, -1, + 7750, 7750, 7750, -1, 7751, 7751, 7751, -1, + 7752, 7752, 7752, -1, 7753, 7753, 7753, -1, + 7754, 7754, 7754, -1, 7755, 7755, 7755, -1, + 7756, 7756, 7756, -1, 7757, 7757, 7757, -1, + 7758, 7758, 7758, -1, 7759, 7759, 7759, -1, + 7760, 7760, 7760, -1, 7761, 7761, 7761, -1, + 7762, 7762, 7762, -1, 7763, 7763, 7763, -1, + 7764, 7764, 7764, -1, 7765, 7765, 7765, -1, + 7766, 7766, 7766, -1, 7767, 7767, 7767, -1, + 7768, 7768, 7768, -1, 7769, 7769, 7769, -1, + 7770, 7770, 7770, -1, 7771, 7771, 7771, -1, + 7772, 7772, 7772, -1, 7773, 7773, 7773, -1, + 7774, 7774, 7774, -1, 7775, 7775, 7775, -1, + 7776, 7776, 7776, -1, 7777, 7777, 7777, -1, + 7778, 7778, 7778, -1, 7779, 7779, 7779, -1, + 7780, 7780, 7780, -1, 7781, 7781, 7781, -1, + 7782, 7782, 7782, -1, 7783, 7783, 7783, -1, + 7784, 7784, 7784, -1, 7785, 7785, 7785, -1, + 7786, 7786, 7786, -1, 7787, 7787, 7787, -1, + 7788, 7788, 7788, -1, 7789, 7789, 7789, -1, + 7790, 7790, 7790, -1, 7791, 7791, 7791, -1, + 7792, 7792, 7792, -1, 7793, 7793, 7793, -1, + 7794, 7794, 7794, -1, 7795, 7795, 7795, -1, + 7796, 7796, 7796, -1, 7797, 7797, 7797, -1, + 7798, 7798, 7798, -1, 7799, 7799, 7799, -1, + 7800, 7800, 7800, -1, 7801, 7801, 7801, -1, + 7802, 7802, 7802, -1, 7803, 7803, 7803, -1, + 7804, 7804, 7804, -1, 7805, 7805, 7805, -1, + 7806, 7806, 7806, -1, 7807, 7807, 7807, -1, + 7808, 7808, 7808, -1, 7809, 7809, 7809, -1, + 7810, 7810, 7810, -1, 7811, 7811, 7811, -1, + 7812, 7812, 7812, -1, 7813, 7813, 7813, -1, + 7814, 7814, 7814, -1, 7815, 7815, 7815, -1, + 7816, 7816, 7816, -1, 7817, 7817, 7817, -1, + 7818, 7818, 7818, -1, 7819, 7819, 7819, -1, + 7820, 7820, 7820, -1, 7821, 7821, 7821, -1, + 7822, 7822, 7822, -1, 7823, 7823, 7823, -1, + 7824, 7824, 7824, -1, 7825, 7825, 7825, -1, + 7826, 7826, 7826, -1, 7827, 7827, 7827, -1, + 7828, 7828, 7828, -1, 7829, 7829, 7829, -1, + 7830, 7830, 7830, -1, 7831, 7831, 7831, -1, + 7832, 7832, 7832, -1, 7833, 7833, 7833, -1, + 7834, 7834, 7834, -1, 7835, 7835, 7835, -1, + 7836, 7836, 7836, -1, 7837, 7837, 7837, -1, + 7838, 7838, 7838, -1, 7839, 7839, 7839, -1, + 7840, 7840, 7840, -1, 7841, 7841, 7841, -1, + 7842, 7842, 7842, -1, 7843, 7843, 7843, -1, + 7844, 7844, 7844, -1, 7845, 7845, 7845, -1, + 7846, 7846, 7846, -1, 7847, 7847, 7847, -1, + 7848, 7848, 7848, -1, 7849, 7849, 7849, -1, + 7850, 7850, 7850, -1, 7851, 7851, 7851, -1, + 7852, 7852, 7852, -1, 7853, 7853, 7853, -1, + 7854, 7854, 7854, -1, 7855, 7855, 7855, -1, + 7856, 7856, 7856, -1, 7857, 7857, 7857, -1, + 7858, 7858, 7858, -1, 7859, 7859, 7859, -1, + 7860, 7860, 7860, -1, 7861, 7861, 7861, -1, + 7862, 7862, 7862, -1, 7863, 7863, 7863, -1, + 7864, 7864, 7864, -1, 7865, 7865, 7865, -1, + 7866, 7866, 7866, -1, 7867, 7867, 7867, -1, + 7868, 7868, 7868, -1, 7869, 7869, 7869, -1, + 7870, 7870, 7870, -1, 7871, 7871, 7871, -1, + 7872, 7872, 7872, -1, 7873, 7873, 7873, -1, + 7874, 7874, 7874, -1, 7875, 7875, 7875, -1, + 7876, 7876, 7876, -1, 7877, 7877, 7877, -1, + 7878, 7878, 7878, -1, 7879, 7879, 7879, -1, + 7880, 7880, 7880, -1, 7881, 7881, 7881, -1, + 7882, 7882, 7882, -1, 7883, 7883, 7883, -1, + 7884, 7884, 7884, -1, 7885, 7885, 7885, -1, + 7886, 7886, 7886, -1, 7887, 7887, 7887, -1, + 7888, 7888, 7888, -1, 7889, 7889, 7889, -1, + 7890, 7890, 7890, -1, 7891, 7891, 7891, -1, + 7892, 7892, 7892, -1, 7893, 7893, 7893, -1, + 7894, 7894, 7894, -1, 7895, 7895, 7895, -1, + 7896, 7896, 7896, -1, 7897, 7897, 7897, -1, + 7898, 7898, 7898, -1, 7899, 7899, 7899, -1, + 7900, 7900, 7900, -1, 7901, 7901, 7901, -1, + 7902, 7902, 7902, -1, 7903, 7903, 7903, -1, + 7904, 7904, 7904, -1, 7905, 7905, 7905, -1, + 7906, 7906, 7906, -1, 7907, 7907, 7907, -1, + 7908, 7908, 7908, -1, 7909, 7909, 7909, -1, + 7910, 7910, 7910, -1, 7911, 7911, 7911, -1, + 7912, 7912, 7912, -1, 7913, 7913, 7913, -1, + 7914, 7914, 7914, -1, 7915, 7915, 7915, -1, + 7916, 7916, 7916, -1, 7917, 7917, 7917, -1, + 7918, 7918, 7918, -1, 7919, 7919, 7919, -1, + 7920, 7920, 7920, -1, 7921, 7921, 7921, -1, + 7922, 7922, 7922, -1, 7923, 7923, 7923, -1, + 7924, 7924, 7924, -1, 7925, 7925, 7925, -1, + 7926, 7926, 7926, -1, 7927, 7927, 7927, -1, + 7928, 7928, 7928, -1, 7929, 7929, 7929, -1, + 7930, 7930, 7930, -1, 7931, 7931, 7931, -1, + 7932, 7932, 7932, -1, 7933, 7933, 7933, -1, + 7934, 7934, 7934, -1, 7935, 7935, 7935, -1, + 7936, 7936, 7936, -1, 7937, 7937, 7937, -1, + 7938, 7938, 7938, -1, 7939, 7939, 7939, -1, + 7940, 7940, 7940, -1, 7941, 7941, 7941, -1, + 7942, 7942, 7942, -1, 7943, 7943, 7943, -1, + 7944, 7944, 7944, -1, 7945, 7945, 7945, -1, + 7946, 7946, 7946, -1, 7947, 7947, 7947, -1, + 7948, 7948, 7948, -1, 7949, 7949, 7949, -1, + 7950, 7950, 7950, -1, 7951, 7951, 7951, -1, + 7952, 7952, 7952, -1, 7953, 7953, 7953, -1, + 7954, 7954, 7954, -1, 7955, 7955, 7955, -1, + 7956, 7956, 7956, -1, 7957, 7957, 7957, -1, + 7958, 7958, 7958, -1, 7959, 7959, 7959, -1, + 7960, 7960, 7960, -1, 7961, 7961, 7961, -1, + 7962, 7962, 7962, -1, 7963, 7963, 7963, -1, + 7964, 7964, 7964, -1, 7965, 7965, 7965, -1, + 7966, 7966, 7966, -1, 7967, 7967, 7967, -1, + 7968, 7968, 7968, -1, 7969, 7969, 7969, -1, + 7970, 7970, 7970, -1, 7971, 7971, 7971, -1, + 7972, 7972, 7972, -1, 7973, 7973, 7973, -1, + 7974, 7974, 7974, -1, 7975, 7975, 7975, -1, + 7976, 7976, 7976, -1, 7977, 7977, 7977, -1, + 7978, 7978, 7978, -1, 7979, 7979, 7979, -1, + 7980, 7980, 7980, -1, 7981, 7981, 7981, -1, + 7982, 7982, 7982, -1, 7983, 7983, 7983, -1, + 7984, 7984, 7984, -1, 7985, 7985, 7985, -1, + 7986, 7986, 7986, -1, 7987, 7987, 7987, -1, + 7988, 7988, 7988, -1, 7989, 7989, 7989, -1, + 7990, 7990, 7990, -1, 7991, 7991, 7991, -1, + 7992, 7992, 7992, -1, 7993, 7993, 7993, -1, + 7994, 7994, 7994, -1, 7995, 7995, 7995, -1, + 7996, 7996, 7996, -1, 7997, 7997, 7997, -1, + 7998, 7998, 7998, -1, 7999, 7999, 7999, -1, + 8000, 8000, 8000, -1, 8001, 8001, 8001, -1, + 8002, 8002, 8002, -1, 8003, 8003, 8003, -1, + 8004, 8004, 8004, -1, 8005, 8005, 8005, -1, + 8006, 8006, 8006, -1, 8007, 8007, 8007, -1, + 8008, 8008, 8008, -1, 8009, 8009, 8009, -1, + 8010, 8010, 8010, -1, 8011, 8011, 8011, -1, + 8012, 8012, 8012, -1, 8013, 8013, 8013, -1, + 8014, 8014, 8014, -1, 8015, 8015, 8015, -1, + 8016, 8016, 8016, -1, 8017, 8017, 8017, -1, + 8018, 8018, 8018, -1, 8019, 8019, 8019, -1, + 8020, 8020, 8020, -1, 8021, 8021, 8021, -1, + 8022, 8022, 8022, -1, 8023, 8023, 8023, -1, + 8024, 8024, 8024, -1, 8025, 8025, 8025, -1, + 8026, 8026, 8026, -1, 8027, 8027, 8027, -1, + 8028, 8028, 8028, -1, 8029, 8029, 8029, -1, + 8030, 8030, 8030, -1, 8031, 8031, 8031, -1, + 8032, 8032, 8032, -1, 8033, 8033, 8033, -1, + 8034, 8034, 8034, -1, 8035, 8035, 8035, -1, + 8036, 8036, 8036, -1, 8037, 8037, 8037, -1, + 8038, 8038, 8038, -1, 8039, 8039, 8039, -1, + 8040, 8040, 8040, -1, 8041, 8041, 8041, -1, + 8042, 8042, 8042, -1, 8043, 8043, 8043, -1, + 8044, 8044, 8044, -1, 8045, 8045, 8045, -1, + 8046, 8046, 8046, -1, 8047, 8047, 8047, -1, + 8048, 8048, 8048, -1, 8049, 8049, 8049, -1, + 8050, 8050, 8050, -1, 8051, 8051, 8051, -1, + 8052, 8052, 8052, -1, 8053, 8053, 8053, -1, + 8054, 8054, 8054, -1, 8055, 8055, 8055, -1, + 8056, 8056, 8056, -1, 8057, 8057, 8057, -1, + 8058, 8058, 8058, -1, 8059, 8059, 8059, -1, + 8060, 8060, 8060, -1, 8061, 8061, 8061, -1, + 8062, 8062, 8062, -1, 8063, 8063, 8063, -1, + 8064, 8064, 8064, -1, 8065, 8065, 8065, -1, + 8066, 8066, 8066, -1, 8067, 8067, 8067, -1, + 8068, 8068, 8068, -1, 8069, 8069, 8069, -1, + 8070, 8070, 8070, -1, 8071, 8071, 8071, -1, + 8072, 8072, 8072, -1, 8073, 8073, 8073, -1, + 8074, 8074, 8074, -1, 8075, 8075, 8075, -1, + 8076, 8076, 8076, -1, 8077, 8077, 8077, -1, + 8078, 8078, 8078, -1, 8079, 8079, 8079, -1, + 8080, 8080, 8080, -1, 8081, 8081, 8081, -1, + 8082, 8082, 8082, -1, 8083, 8083, 8083, -1, + 8084, 8084, 8084, -1, 8085, 8085, 8085, -1, + 8086, 8086, 8086, -1, 8087, 8087, 8087, -1, + 8088, 8088, 8088, -1, 8089, 8089, 8089, -1, + 8090, 8090, 8090, -1, 8091, 8091, 8091, -1, + 8092, 8092, 8092, -1, 8093, 8093, 8093, -1, + 8094, 8094, 8094, -1, 8095, 8095, 8095, -1, + 8096, 8096, 8096, -1, 8097, 8097, 8097, -1, + 8098, 8098, 8098, -1, 8099, 8099, 8099, -1, + 8100, 8100, 8100, -1, 8101, 8101, 8101, -1, + 8102, 8102, 8102, -1, 8103, 8103, 8103, -1, + 8104, 8104, 8104, -1, 8105, 8105, 8105, -1, + 8106, 8106, 8106, -1, 8107, 8107, 8107, -1, + 8108, 8108, 8108, -1, 8109, 8109, 8109, -1, + 8110, 8110, 8110, -1, 8111, 8111, 8111, -1, + 8112, 8112, 8112, -1, 8113, 8113, 8113, -1, + 8114, 8114, 8114, -1, 8115, 8115, 8115, -1, + 8116, 8116, 8116, -1, 8117, 8117, 8117, -1, + 8118, 8118, 8118, -1, 8119, 8119, 8119, -1, + 8120, 8120, 8120, -1, 8121, 8121, 8121, -1, + 8122, 8122, 8122, -1, 8123, 8123, 8123, -1, + 8124, 8124, 8124, -1, 8125, 8125, 8125, -1, + 8126, 8126, 8126, -1, 8127, 8127, 8127, -1, + 8128, 8128, 8128, -1, 8129, 8129, 8129, -1, + 8130, 8130, 8130, -1, 8131, 8131, 8131, -1, + 8132, 8132, 8132, -1, 8133, 8133, 8133, -1, + 8134, 8134, 8134, -1, 8135, 8135, 8135, -1, + 8136, 8136, 8136, -1, 8137, 8137, 8137, -1, + 8138, 8138, 8138, -1, 8139, 8139, 8139, -1, + 8140, 8140, 8140, -1, 8141, 8141, 8141, -1, + 8142, 8142, 8142, -1, 8143, 8143, 8143, -1, + 8144, 8144, 8144, -1, 8145, 8145, 8145, -1, + 8146, 8146, 8146, -1, 8147, 8147, 8147, -1, + 8148, 8148, 8148, -1, 8149, 8149, 8149, -1, + 8150, 8150, 8150, -1, 8151, 8151, 8151, -1, + 8152, 8152, 8152, -1, 8153, 8153, 8153, -1, + 8154, 8154, 8154, -1, 8155, 8155, 8155, -1, + 8156, 8156, 8156, -1, 8157, 8157, 8157, -1, + 8158, 8158, 8158, -1, 8159, 8159, 8159, -1, + 8160, 8160, 8160, -1, 8161, 8161, 8161, -1, + 8162, 8162, 8162, -1, 8163, 8163, 8163, -1, + 8164, 8164, 8164, -1, 8165, 8165, 8165, -1, + 8166, 8166, 8166, -1, 8167, 8167, 8167, -1, + 8168, 8168, 8168, -1, 8169, 8169, 8169, -1, + 8170, 8170, 8170, -1, 8171, 8171, 8171, -1, + 8172, 8172, 8172, -1, 8173, 8173, 8173, -1, + 8174, 8174, 8174, -1, 8175, 8175, 8175, -1, + 8176, 8176, 8176, -1, 8177, 8177, 8177, -1, + 8178, 8178, 8178, -1, 8179, 8179, 8179, -1, + 8180, 8180, 8180, -1, 8181, 8181, 8181, -1, + 8182, 8182, 8182, -1, 8183, 8183, 8183, -1, + 8184, 8184, 8184, -1, 8185, 8185, 8185, -1, + 8186, 8186, 8186, -1, 8187, 8187, 8187, -1, + 8188, 8188, 8188, -1, 8189, 8189, 8189, -1, + 8190, 8190, 8190, -1, 8191, 8191, 8191, -1, + 8192, 8192, 8192, -1, 8193, 8193, 8193, -1, + 8194, 8194, 8194, -1, 8195, 8195, 8195, -1, + 8196, 8196, 8196, -1, 8197, 8197, 8197, -1, + 8198, 8198, 8198, -1, 8199, 8199, 8199, -1, + 8200, 8200, 8200, -1, 8201, 8201, 8201, -1, + 8202, 8202, 8202, -1, 8203, 8203, 8203, -1, + 8204, 8204, 8204, -1, 8205, 8205, 8205, -1, + 8206, 8206, 8206, -1, 8207, 8207, 8207, -1, + 8208, 8208, 8208, -1, 8209, 8209, 8209, -1, + 8210, 8210, 8210, -1, 8211, 8211, 8211, -1, + 8212, 8212, 8212, -1, 8213, 8213, 8213, -1, + 8214, 8214, 8214, -1, 8215, 8215, 8215, -1, + 8216, 8216, 8216, -1, 8217, 8217, 8217, -1, + 8218, 8218, 8218, -1, 8219, 8219, 8219, -1, + 8220, 8220, 8220, -1, 8221, 8221, 8221, -1, + 8222, 8222, 8222, -1, 8223, 8223, 8223, -1, + 8224, 8224, 8224, -1, 8225, 8225, 8225, -1, + 8226, 8226, 8226, -1, 8227, 8227, 8227, -1, + 8228, 8228, 8228, -1, 8229, 8229, 8229, -1, + 8230, 8230, 8230, -1, 8231, 8231, 8231, -1, + 8232, 8232, 8232, -1, 8233, 8233, 8233, -1, + 8234, 8234, 8234, -1, 8235, 8235, 8235, -1, + 8236, 8236, 8236, -1, 8237, 8237, 8237, -1, + 8238, 8238, 8238, -1, 8239, 8239, 8239, -1, + 8240, 8240, 8240, -1, 8241, 8241, 8241, -1, + 8242, 8242, 8242, -1, 8243, 8243, 8243, -1, + 8244, 8244, 8244, -1, 8245, 8245, 8245, -1, + 8246, 8246, 8246, -1, 8247, 8247, 8247, -1, + 8248, 8248, 8248, -1, 8249, 8249, 8249, -1, + 8250, 8250, 8250, -1, 8251, 8251, 8251, -1, + 8252, 8252, 8252, -1, 8253, 8253, 8253, -1, + 8254, 8254, 8254, -1, 8255, 8255, 8255, -1, + 8256, 8256, 8256, -1, 8257, 8257, 8257, -1, + 8258, 8258, 8258, -1, 8259, 8259, 8259, -1, + 8260, 8260, 8260, -1, 8261, 8261, 8261, -1, + 8262, 8262, 8262, -1, 8263, 8263, 8263, -1, + 8264, 8264, 8264, -1, 8265, 8265, 8265, -1, + 8266, 8266, 8266, -1, 8267, 8267, 8267, -1, + 8268, 8268, 8268, -1, 8269, 8269, 8269, -1, + 8270, 8270, 8270, -1, 8271, 8271, 8271, -1, + 8272, 8272, 8272, -1, 8273, 8273, 8273, -1, + 8274, 8274, 8274, -1, 8275, 8275, 8275, -1, + 8276, 8276, 8276, -1, 8277, 8277, 8277, -1, + 8278, 8278, 8278, -1, 8279, 8279, 8279, -1, + 8280, 8280, 8280, -1, 8281, 8281, 8281, -1, + 8282, 8282, 8282, -1, 8283, 8283, 8283, -1, + 8284, 8284, 8284, -1, 8285, 8285, 8285, -1, + 8286, 8286, 8286, -1, 8287, 8287, 8287, -1, + 8288, 8288, 8288, -1, 8289, 8289, 8289, -1, + 8290, 8290, 8290, -1, 8291, 8291, 8291, -1, + 8292, 8292, 8292, -1, 8293, 8293, 8293, -1, + 8294, 8294, 8294, -1, 8295, 8295, 8295, -1, + 8296, 8296, 8296, -1, 8297, 8297, 8297, -1, + 8298, 8298, 8298, -1, 8299, 8299, 8299, -1, + 8300, 8300, 8300, -1, 8301, 8301, 8301, -1, + 8302, 8302, 8302, -1, 8303, 8303, 8303, -1, + 8304, 8304, 8304, -1, 8305, 8305, 8305, -1, + 8306, 8306, 8306, -1, 8307, 8307, 8307, -1, + 8308, 8308, 8308, -1, 8309, 8309, 8309, -1, + 8310, 8310, 8310, -1, 8311, 8311, 8311, -1, + 8312, 8312, 8312, -1, 8313, 8313, 8313, -1, + 8314, 8314, 8314, -1, 8315, 8315, 8315, -1, + 8316, 8316, 8316, -1, 8317, 8317, 8317, -1, + 8318, 8318, 8318, -1, 8319, 8319, 8319, -1, + 8320, 8320, 8320, -1, 8321, 8321, 8321, -1, + 8322, 8322, 8322, -1, 8323, 8323, 8323, -1, + 8324, 8324, 8324, -1, 8325, 8325, 8325, -1, + 8326, 8326, 8326, -1, 8327, 8327, 8327, -1, + 8328, 8328, 8328, -1, 8329, 8329, 8329, -1, + 8330, 8330, 8330, -1, 8331, 8331, 8331, -1, + 8332, 8332, 8332, -1, 8333, 8333, 8333, -1, + 8334, 8334, 8334, -1, 8335, 8335, 8335, -1, + 8336, 8336, 8336, -1, 8337, 8337, 8337, -1, + 8338, 8338, 8338, -1, 8339, 8339, 8339, -1, + 8340, 8340, 8340, -1, 8341, 8341, 8341, -1, + 8342, 8342, 8342, -1, 8343, 8343, 8343, -1, + 8344, 8344, 8344, -1, 8345, 8345, 8345, -1, + 8346, 8346, 8346, -1, 8347, 8347, 8347, -1, + 8348, 8348, 8348, -1, 8349, 8349, 8349, -1, + 8350, 8350, 8350, -1, 8351, 8351, 8351, -1, + 8352, 8352, 8352, -1, 8353, 8353, 8353, -1, + 8354, 8354, 8354, -1, 8355, 8355, 8355, -1, + 8356, 8356, 8356, -1, 8357, 8357, 8357, -1, + 8358, 8358, 8358, -1, 8359, 8359, 8359, -1, + 8360, 8360, 8360, -1, 8361, 8361, 8361, -1, + 8362, 8362, 8362, -1, 8363, 8363, 8363, -1, + 8364, 8364, 8364, -1, 8365, 8365, 8365, -1, + 8366, 8366, 8366, -1, 8367, 8367, 8367, -1, + 8368, 8368, 8368, -1, 8369, 8369, 8369, -1, + 8370, 8370, 8370, -1, 8371, 8371, 8371, -1, + 8372, 8372, 8372, -1, 8373, 8373, 8373, -1, + 8374, 8374, 8374, -1, 8375, 8375, 8375, -1, + 8376, 8376, 8376, -1, 8377, 8377, 8377, -1, + 8378, 8378, 8378, -1, 8379, 8379, 8379, -1, + 8380, 8380, 8380, -1, 8381, 8381, 8381, -1, + 8382, 8382, 8382, -1, 8383, 8383, 8383, -1, + 8384, 8384, 8384, -1, 8385, 8385, 8385, -1, + 8386, 8386, 8386, -1, 8387, 8387, 8387, -1, + 8388, 8388, 8388, -1, 8389, 8389, 8389, -1, + 8390, 8390, 8390, -1, 8391, 8391, 8391, -1, + 8392, 8392, 8392, -1, 8393, 8393, 8393, -1, + 8394, 8394, 8394, -1, 8395, 8395, 8395, -1, + 8396, 8396, 8396, -1, 8397, 8397, 8397, -1, + 8398, 8398, 8398, -1, 8399, 8399, 8399, -1, + 8400, 8400, 8400, -1, 8401, 8401, 8401, -1, + 8402, 8402, 8402, -1, 8403, 8403, 8403, -1, + 8404, 8404, 8404, -1, 8405, 8405, 8405, -1, + 8406, 8406, 8406, -1, 8407, 8407, 8407, -1, + 8408, 8408, 8408, -1, 8409, 8409, 8409, -1, + 8410, 8410, 8410, -1, 8411, 8411, 8411, -1, + 8412, 8412, 8412, -1, 8413, 8413, 8413, -1, + 8414, 8414, 8414, -1, 8415, 8415, 8415, -1, + 8416, 8416, 8416, -1, 8417, 8417, 8417, -1, + 8418, 8418, 8418, -1, 8419, 8419, 8419, -1, + 8420, 8420, 8420, -1, 8421, 8421, 8421, -1, + 8422, 8422, 8422, -1, 8423, 8423, 8423, -1, + 8424, 8424, 8424, -1, 8425, 8425, 8425, -1, + 8426, 8426, 8426, -1, 8427, 8427, 8427, -1, + 8428, 8428, 8428, -1, 8429, 8429, 8429, -1, + 8430, 8430, 8430, -1, 8431, 8431, 8431, -1, + 8432, 8432, 8432, -1, 8433, 8433, 8433, -1, + 8434, 8434, 8434, -1, 8435, 8435, 8435, -1, + 8436, 8436, 8436, -1, 8437, 8437, 8437, -1, + 8438, 8438, 8438, -1, 8439, 8439, 8439, -1, + 8440, 8440, 8440, -1, 8441, 8441, 8441, -1, + 8442, 8442, 8442, -1, 8443, 8443, 8443, -1, + 8444, 8444, 8444, -1, 8445, 8445, 8445, -1, + 8446, 8446, 8446, -1, 8447, 8447, 8447, -1, + 8448, 8448, 8448, -1, 8449, 8449, 8449, -1, + 8450, 8450, 8450, -1, 8451, 8451, 8451, -1, + 8452, 8452, 8452, -1, 8453, 8453, 8453, -1, + 8454, 8454, 8454, -1, 8455, 8455, 8455, -1, + 8456, 8456, 8456, -1, 8457, 8457, 8457, -1, + 8458, 8458, 8458, -1, 8459, 8459, 8459, -1, + 8460, 8460, 8460, -1, 8461, 8461, 8461, -1, + 8462, 8462, 8462, -1, 8463, 8463, 8463, -1, + 8464, 8464, 8464, -1, 8465, 8465, 8465, -1, + 8466, 8466, 8466, -1, 8467, 8467, 8467, -1, + 8468, 8468, 8468, -1, 8469, 8469, 8469, -1, + 8470, 8470, 8470, -1, 8471, 8471, 8471, -1, + 8472, 8472, 8472, -1, 8473, 8473, 8473, -1, + 8474, 8474, 8474, -1, 8475, 8475, 8475, -1, + 8476, 8476, 8476, -1, 8477, 8477, 8477, -1, + 8478, 8478, 8478, -1, 8479, 8479, 8479, -1, + 8480, 8480, 8480, -1, 8481, 8481, 8481, -1, + 8482, 8482, 8482, -1, 8483, 8483, 8483, -1, + 8484, 8484, 8484, -1, 8485, 8485, 8485, -1, + 8486, 8486, 8486, -1, 8487, 8487, 8487, -1, + 8488, 8488, 8488, -1, 8489, 8489, 8489, -1, + 8490, 8490, 8490, -1, 8491, 8491, 8491, -1, + 8492, 8492, 8492, -1, 8493, 8493, 8493, -1, + 8494, 8494, 8494, -1, 8495, 8495, 8495, -1, + 8496, 8496, 8496, -1, 8497, 8497, 8497, -1, + 8498, 8498, 8498, -1, 8499, 8499, 8499, -1, + 8500, 8500, 8500, -1, 8501, 8501, 8501, -1, + 8502, 8502, 8502, -1, 8503, 8503, 8503, -1, + 8504, 8504, 8504, -1, 8505, 8505, 8505, -1, + 8506, 8506, 8506, -1, 8507, 8507, 8507, -1, + 8508, 8508, 8508, -1, 8509, 8509, 8509, -1, + 8510, 8510, 8510, -1, 8511, 8511, 8511, -1, + 8512, 8512, 8512, -1, 8513, 8513, 8513, -1, + 8514, 8514, 8514, -1, 8515, 8515, 8515, -1, + 8516, 8516, 8516, -1, 8517, 8517, 8517, -1, + 8518, 8518, 8518, -1, 8519, 8519, 8519, -1, + 8520, 8520, 8520, -1, 8521, 8521, 8521, -1, + 8522, 8522, 8522, -1, 8523, 8523, 8523, -1, + 8524, 8524, 8524, -1, 8525, 8525, 8525, -1, + 8526, 8526, 8526, -1, 8527, 8527, 8527, -1, + 8528, 8528, 8528, -1, 8529, 8529, 8529, -1, + 8530, 8530, 8530, -1, 8531, 8531, 8531, -1, + 8532, 8532, 8532, -1, 8533, 8533, 8533, -1, + 8534, 8534, 8534, -1, 8535, 8535, 8535, -1, + 8536, 8536, 8536, -1, 8537, 8537, 8537, -1, + 8538, 8538, 8538, -1, 8539, 8539, 8539, -1, + 8540, 8540, 8540, -1, 8541, 8541, 8541, -1, + 8542, 8542, 8542, -1, 8543, 8543, 8543, -1, + 8544, 8544, 8544, -1, 8545, 8545, 8545, -1, + 8546, 8546, 8546, -1, 8547, 8547, 8547, -1, + 8548, 8548, 8548, -1, 8549, 8549, 8549, -1, + 8550, 8550, 8550, -1, 8551, 8551, 8551, -1, + 8552, 8552, 8552, -1, 8553, 8553, 8553, -1, + 8554, 8554, 8554, -1, 8555, 8555, 8555, -1, + 8556, 8556, 8556, -1, 8557, 8557, 8557, -1, + 8558, 8558, 8558, -1, 8559, 8559, 8559, -1, + 8560, 8560, 8560, -1, 8561, 8561, 8561, -1, + 8562, 8562, 8562, -1, 8563, 8563, 8563, -1, + 8564, 8564, 8564, -1, 8565, 8565, 8565, -1, + 8566, 8566, 8566, -1, 8567, 8567, 8567, -1, + 8568, 8568, 8568, -1, 8569, 8569, 8569, -1, + 8570, 8570, 8570, -1, 8571, 8571, 8571, -1, + 8572, 8572, 8572, -1, 8573, 8573, 8573, -1, + 8574, 8574, 8574, -1, 8575, 8575, 8575, -1, + 8576, 8576, 8576, -1, 8577, 8577, 8577, -1, + 8578, 8578, 8578, -1, 8579, 8579, 8579, -1, + 8580, 8580, 8580, -1, 8581, 8581, 8581, -1, + 8582, 8582, 8582, -1, 8583, 8583, 8583, -1, + 8584, 8584, 8584, -1, 8585, 8585, 8585, -1, + 8586, 8586, 8586, -1, 8587, 8587, 8587, -1, + 8588, 8588, 8588, -1, 8589, 8589, 8589, -1, + 8590, 8590, 8590, -1, 8591, 8591, 8591, -1, + 8592, 8592, 8592, -1, 8593, 8593, 8593, -1, + 8594, 8594, 8594, -1, 8595, 8595, 8595, -1, + 8596, 8596, 8596, -1, 8597, 8597, 8597, -1, + 8598, 8598, 8598, -1, 8599, 8599, 8599, -1, + 8600, 8600, 8600, -1, 8601, 8601, 8601, -1, + 8602, 8602, 8602, -1, 8603, 8603, 8603, -1, + 8604, 8604, 8604, -1, 8605, 8605, 8605, -1, + 8606, 8606, 8606, -1, 8607, 8607, 8607, -1, + 8608, 8608, 8608, -1, 8609, 8609, 8609, -1, + 8610, 8610, 8610, -1, 8611, 8611, 8611, -1, + 8612, 8612, 8612, -1, 8613, 8613, 8613, -1, + 8614, 8614, 8614, -1, 8615, 8615, 8615, -1, + 8616, 8616, 8616, -1, 8617, 8617, 8617, -1, + 8618, 8618, 8618, -1, 8619, 8619, 8619, -1, + 8620, 8620, 8620, -1, 8621, 8621, 8621, -1, + 8622, 8622, 8622, -1, 8623, 8623, 8623, -1, + 8624, 8624, 8624, -1, 8625, 8625, 8625, -1, + 8626, 8626, 8626, -1, 8627, 8627, 8627, -1, + 8628, 8628, 8628, -1, 8629, 8629, 8629, -1, + 8630, 8630, 8630, -1, 8631, 8631, 8631, -1, + 8632, 8632, 8632, -1, 8633, 8633, 8633, -1, + 8634, 8634, 8634, -1, 8635, 8635, 8635, -1, + 8636, 8636, 8636, -1, 8637, 8637, 8637, -1, + 8638, 8638, 8638, -1, 8639, 8639, 8639, -1, + 8640, 8640, 8640, -1, 8641, 8641, 8641, -1, + 8642, 8642, 8642, -1, 8643, 8643, 8643, -1, + 8644, 8644, 8644, -1, 8645, 8645, 8645, -1, + 8646, 8646, 8646, -1, 8647, 8647, 8647, -1, + 8648, 8648, 8648, -1, 8649, 8649, 8649, -1, + 8650, 8650, 8650, -1, 8651, 8651, 8651, -1, + 8652, 8652, 8652, -1, 8653, 8653, 8653, -1, + 8654, 8654, 8654, -1, 8655, 8655, 8655, -1, + 8656, 8656, 8656, -1, 8657, 8657, 8657, -1, + 8658, 8658, 8658, -1, 8659, 8659, 8659, -1, + 8660, 8660, 8660, -1, 8661, 8661, 8661, -1, + 8662, 8662, 8662, -1, 8663, 8663, 8663, -1, + 8664, 8664, 8664, -1, 8665, 8665, 8665, -1, + 8666, 8666, 8666, -1, 8667, 8667, 8667, -1, + 8668, 8668, 8668, -1, 8669, 8669, 8669, -1, + 8670, 8670, 8670, -1, 8671, 8671, 8671, -1, + 8672, 8672, 8672, -1, 8673, 8673, 8673, -1, + 8674, 8674, 8674, -1, 8675, 8675, 8675, -1, + 8676, 8676, 8676, -1, 8677, 8677, 8677, -1, + 8678, 8678, 8678, -1, 8679, 8679, 8679, -1, + 8680, 8680, 8680, -1, 8681, 8681, 8681, -1, + 8682, 8682, 8682, -1, 8683, 8683, 8683, -1, + 8684, 8684, 8684, -1, 8685, 8685, 8685, -1, + 8686, 8686, 8686, -1, 8687, 8687, 8687, -1, + 8688, 8688, 8688, -1, 8689, 8689, 8689, -1, + 8690, 8690, 8690, -1, 8691, 8691, 8691, -1, + 8692, 8692, 8692, -1, 8693, 8693, 8693, -1, + 8694, 8694, 8694, -1, 8695, 8695, 8695, -1, + 8696, 8696, 8696, -1, 8697, 8697, 8697, -1, + 8698, 8698, 8698, -1, 8699, 8699, 8699, -1, + 8700, 8700, 8700, -1, 8701, 8701, 8701, -1, + 8702, 8702, 8702, -1, 8703, 8703, 8703, -1, + 8704, 8704, 8704, -1, 8705, 8705, 8705, -1, + 8706, 8706, 8706, -1, 8707, 8707, 8707, -1, + 8708, 8708, 8708, -1, 8709, 8709, 8709, -1, + 8710, 8710, 8710, -1, 8711, 8711, 8711, -1, + 8712, 8712, 8712, -1, 8713, 8713, 8713, -1, + 8714, 8714, 8714, -1, 8715, 8715, 8715, -1, + 8716, 8716, 8716, -1, 8717, 8717, 8717, -1, + 8718, 8718, 8718, -1, 8719, 8719, 8719, -1, + 8720, 8720, 8720, -1, 8721, 8721, 8721, -1, + 8722, 8722, 8722, -1, 8723, 8723, 8723, -1, + 8724, 8724, 8724, -1, 8725, 8725, 8725, -1, + 8726, 8726, 8726, -1, 8727, 8727, 8727, -1, + 8728, 8728, 8728, -1, 8729, 8729, 8729, -1, + 8730, 8730, 8730, -1, 8731, 8731, 8731, -1, + 8732, 8732, 8732, -1, 8733, 8733, 8733, -1, + 8734, 8734, 8734, -1, 8735, 8735, 8735, -1, + 8736, 8736, 8736, -1, 8737, 8737, 8737, -1, + 8738, 8738, 8738, -1, 8739, 8739, 8739, -1, + 8740, 8740, 8740, -1, 8741, 8741, 8741, -1, + 8742, 8742, 8742, -1, 8743, 8743, 8743, -1, + 8744, 8744, 8744, -1, 8745, 8745, 8745, -1, + 8746, 8746, 8746, -1, 8747, 8747, 8747, -1, + 8748, 8748, 8748, -1, 8749, 8749, 8749, -1, + 8750, 8750, 8750, -1, 8751, 8751, 8751, -1, + 8752, 8752, 8752, -1, 8753, 8753, 8753, -1, + 8754, 8754, 8754, -1, 8755, 8755, 8755, -1, + 8756, 8756, 8756, -1, 8757, 8757, 8757, -1, + 8758, 8758, 8758, -1, 8759, 8759, 8759, -1, + 8760, 8760, 8760, -1, 8761, 8761, 8761, -1, + 8762, 8762, 8762, -1, 8763, 8763, 8763, -1, + 8764, 8764, 8764, -1, 8765, 8765, 8765, -1, + 8766, 8766, 8766, -1, 8767, 8767, 8767, -1, + 8768, 8768, 8768, -1, 8769, 8769, 8769, -1, + 8770, 8770, 8770, -1, 8771, 8771, 8771, -1, + 8772, 8772, 8772, -1, 8773, 8773, 8773, -1, + 8774, 8774, 8774, -1, 8775, 8775, 8775, -1, + 8776, 8776, 8776, -1, 8777, 8777, 8777, -1, + 8778, 8778, 8778, -1, 8779, 8779, 8779, -1, + 8780, 8780, 8780, -1, 8781, 8781, 8781, -1, + 8782, 8782, 8782, -1, 8783, 8783, 8783, -1, + 8784, 8784, 8784, -1, 8785, 8785, 8785, -1, + 8786, 8786, 8786, -1, 8787, 8787, 8787, -1, + 8788, 8788, 8788, -1, 8789, 8789, 8789, -1, + 8790, 8790, 8790, -1, 8791, 8791, 8791, -1, + 8792, 8792, 8792, -1, 8793, 8793, 8793, -1, + 8794, 8794, 8794, -1, 8795, 8795, 8795, -1, + 8796, 8796, 8796, -1, 8797, 8797, 8797, -1, + 8798, 8798, 8798, -1, 8799, 8799, 8799, -1, + 8800, 8800, 8800, -1, 8801, 8801, 8801, -1, + 8802, 8802, 8802, -1, 8803, 8803, 8803, -1, + 8804, 8804, 8804, -1, 8805, 8805, 8805, -1, + 8806, 8806, 8806, -1, 8807, 8807, 8807, -1, + 8808, 8808, 8808, -1, 8809, 8809, 8809, -1, + 8810, 8810, 8810, -1, 8811, 8811, 8811, -1, + 8812, 8812, 8812, -1, 8813, 8813, 8813, -1, + 8814, 8814, 8814, -1, 8815, 8815, 8815, -1, + 8816, 8816, 8816, -1, 8817, 8817, 8817, -1, + 8818, 8818, 8818, -1, 8819, 8819, 8819, -1, + 8820, 8820, 8820, -1, 8821, 8821, 8821, -1, + 8822, 8822, 8822, -1, 8823, 8823, 8823, -1, + 8824, 8824, 8824, -1, 8825, 8825, 8825, -1, + 8826, 8826, 8826, -1, 8827, 8827, 8827, -1, + 8828, 8828, 8828, -1, 8829, 8829, 8829, -1, + 8830, 8830, 8830, -1, 8831, 8831, 8831, -1, + 8832, 8832, 8832, -1, 8833, 8833, 8833, -1, + 8834, 8834, 8834, -1, 8835, 8835, 8835, -1, + 8836, 8836, 8836, -1, 8837, 8837, 8837, -1, + 8838, 8838, 8838, -1, 8839, 8839, 8839, -1, + 8840, 8840, 8840, -1, 8841, 8841, 8841, -1, + 8842, 8842, 8842, -1, 8843, 8843, 8843, -1, + 8844, 8844, 8844, -1, 8845, 8845, 8845, -1, + 8846, 8846, 8846, -1, 8847, 8847, 8847, -1, + 8848, 8848, 8848, -1, 8849, 8849, 8849, -1, + 8850, 8850, 8850, -1, 8851, 8851, 8851, -1, + 8852, 8852, 8852, -1, 8853, 8853, 8853, -1, + 8854, 8854, 8854, -1, 8855, 8855, 8855, -1, + 8856, 8856, 8856, -1, 8857, 8857, 8857, -1, + 8858, 8858, 8858, -1, 8859, 8859, 8859, -1, + 8860, 8860, 8860, -1, 8861, 8861, 8861, -1, + 8862, 8862, 8862, -1, 8863, 8863, 8863, -1, + 8864, 8864, 8864, -1, 8865, 8865, 8865, -1, + 8866, 8866, 8866, -1, 8867, 8867, 8867, -1, + 8868, 8868, 8868, -1, 8869, 8869, 8869, -1, + 8870, 8870, 8870, -1, 8871, 8871, 8871, -1, + 8872, 8872, 8872, -1, 8873, 8873, 8873, -1, + 8874, 8874, 8874, -1, 8875, 8875, 8875, -1, + 8876, 8876, 8876, -1, 8877, 8877, 8877, -1, + 8878, 8878, 8878, -1, 8879, 8879, 8879, -1, + 8880, 8880, 8880, -1, 8881, 8881, 8881, -1, + 8882, 8882, 8882, -1, 8883, 8883, 8883, -1, + 8884, 8884, 8884, -1, 8885, 8885, 8885, -1, + 8886, 8886, 8886, -1, 8887, 8887, 8887, -1, + 8888, 8888, 8888, -1, 8889, 8889, 8889, -1, + 8890, 8890, 8890, -1, 8891, 8891, 8891, -1, + 8892, 8892, 8892, -1, 8893, 8893, 8893, -1, + 8894, 8894, 8894, -1, 8895, 8895, 8895, -1, + 8896, 8896, 8896, -1, 8897, 8897, 8897, -1, + 8898, 8898, 8898, -1, 8899, 8899, 8899, -1, + 8900, 8900, 8900, -1, 8901, 8901, 8901, -1, + 8902, 8902, 8902, -1, 8903, 8903, 8903, -1, + 8904, 8904, 8904, -1, 8905, 8905, 8905, -1, + 8906, 8906, 8906, -1, 8907, 8907, 8907, -1, + 8908, 8908, 8908, -1, 8909, 8909, 8909, -1, + 8910, 8910, 8910, -1, 8911, 8911, 8911, -1, + 8912, 8912, 8912, -1, 8913, 8913, 8913, -1, + 8914, 8914, 8914, -1, 8915, 8915, 8915, -1, + 8916, 8916, 8916, -1, 8917, 8917, 8917, -1, + 8918, 8918, 8918, -1, 8919, 8919, 8919, -1, + 8920, 8920, 8920, -1, 8921, 8921, 8921, -1, + 8922, 8922, 8922, -1, 8923, 8923, 8923, -1, + 8924, 8924, 8924, -1, 8925, 8925, 8925, -1, + 8926, 8926, 8926, -1, 8927, 8927, 8927, -1, + 8928, 8928, 8928, -1, 8929, 8929, 8929, -1, + 8930, 8930, 8930, -1, 8931, 8931, 8931, -1, + 8932, 8932, 8932, -1, 8933, 8933, 8933, -1, + 8934, 8934, 8934, -1, 8935, 8935, 8935, -1, + 8936, 8936, 8936, -1, 8937, 8937, 8937, -1, + 8938, 8938, 8938, -1, 8939, 8939, 8939, -1, + 8940, 8940, 8940, -1, 8941, 8941, 8941, -1, + 8942, 8942, 8942, -1, 8943, 8943, 8943, -1, + 8944, 8944, 8944, -1, 8945, 8945, 8945, -1, + 8946, 8946, 8946, -1, 8947, 8947, 8947, -1, + 8948, 8948, 8948, -1, 8949, 8949, 8949, -1, + 8950, 8950, 8950, -1, 8951, 8951, 8951, -1, + 8952, 8952, 8952, -1, 8953, 8953, 8953, -1, + 8954, 8954, 8954, -1, 8955, 8955, 8955, -1, + 8956, 8956, 8956, -1, 8957, 8957, 8957, -1, + 8958, 8958, 8958, -1, 8959, 8959, 8959, -1, + 8960, 8960, 8960, -1, 8961, 8961, 8961, -1, + 8962, 8962, 8962, -1, 8963, 8963, 8963, -1, + 8964, 8964, 8964, -1, 8965, 8965, 8965, -1, + 8966, 8966, 8966, -1, 8967, 8967, 8967, -1, + 8968, 8968, 8968, -1, 8969, 8969, 8969, -1, + 8970, 8970, 8970, -1, 8971, 8971, 8971, -1, + 8972, 8972, 8972, -1, 8973, 8973, 8973, -1, + 8974, 8974, 8974, -1, 8975, 8975, 8975, -1, + 8976, 8976, 8976, -1, 8977, 8977, 8977, -1, + 8978, 8978, 8978, -1, 8979, 8979, 8979, -1, + 8980, 8980, 8980, -1, 8981, 8981, 8981, -1, + 8982, 8982, 8982, -1, 8983, 8983, 8983, -1, + 8984, 8984, 8984, -1, 8985, 8985, 8985, -1, + 8986, 8986, 8986, -1, 8987, 8987, 8987, -1, + 8988, 8988, 8988, -1, 8989, 8989, 8989, -1, + 8990, 8990, 8990, -1, 8991, 8991, 8991, -1, + 8992, 8992, 8992, -1, 8993, 8993, 8993, -1, + 8994, 8994, 8994, -1, 8995, 8995, 8995, -1, + 8996, 8996, 8996, -1, 8997, 8997, 8997, -1, + 8998, 8998, 8998, -1, 8999, 8999, 8999, -1, + 9000, 9000, 9000, -1, 9001, 9001, 9001, -1, + 9002, 9002, 9002, -1, 9003, 9003, 9003, -1, + 9004, 9004, 9004, -1, 9005, 9005, 9005, -1, + 9006, 9006, 9006, -1, 9007, 9007, 9007, -1, + 9008, 9008, 9008, -1, 9009, 9009, 9009, -1, + 9010, 9010, 9010, -1, 9011, 9011, 9011, -1, + 9012, 9012, 9012, -1, 9013, 9013, 9013, -1, + 9014, 9014, 9014, -1, 9015, 9015, 9015, -1, + 9016, 9016, 9016, -1, 9017, 9017, 9017, -1, + 9018, 9018, 9018, -1, 9019, 9019, 9019, -1, + 9020, 9020, 9020, -1, 9021, 9021, 9021, -1, + 9022, 9022, 9022, -1, 9023, 9023, 9023, -1, + 9024, 9024, 9024, -1, 9025, 9025, 9025, -1, + 9026, 9026, 9026, -1, 9027, 9027, 9027, -1, + 9028, 9028, 9028, -1, 9029, 9029, 9029, -1, + 9030, 9030, 9030, -1, 9031, 9031, 9031, -1, + 9032, 9032, 9032, -1, 9033, 9033, 9033, -1, + 9034, 9034, 9034, -1, 9035, 9035, 9035, -1, + 9036, 9036, 9036, -1, 9037, 9037, 9037, -1, + 9038, 9038, 9038, -1, 9039, 9039, 9039, -1, + 9040, 9040, 9040, -1, 9041, 9041, 9041, -1, + 9042, 9042, 9042, -1, 9043, 9043, 9043, -1, + 9044, 9044, 9044, -1, 9045, 9045, 9045, -1, + 9046, 9046, 9046, -1, 9047, 9047, 9047, -1, + 9048, 9048, 9048, -1, 9049, 9049, 9049, -1, + 9050, 9050, 9050, -1, 9051, 9051, 9051, -1, + 9052, 9052, 9052, -1, 9053, 9053, 9053, -1, + 9054, 9054, 9054, -1, 9055, 9055, 9055, -1, + 9056, 9056, 9056, -1, 9057, 9057, 9057, -1, + 9058, 9058, 9058, -1, 9059, 9059, 9059, -1, + 9060, 9060, 9060, -1, 9061, 9061, 9061, -1, + 9062, 9062, 9062, -1, 9063, 9063, 9063, -1, + 9064, 9064, 9064, -1, 9065, 9065, 9065, -1, + 9066, 9066, 9066, -1, 9067, 9067, 9067, -1, + 9068, 9068, 9068, -1, 9069, 9069, 9069, -1, + 9070, 9070, 9070, -1, 9071, 9071, 9071, -1, + 9072, 9072, 9072, -1, 9073, 9073, 9073, -1, + 9074, 9074, 9074, -1, 9075, 9075, 9075, -1, + 9076, 9076, 9076, -1, 9077, 9077, 9077, -1, + 9078, 9078, 9078, -1, 9079, 9079, 9079, -1, + 9080, 9080, 9080, -1, 9081, 9081, 9081, -1, + 9082, 9082, 9082, -1, 9083, 9083, 9083, -1, + 9084, 9084, 9084, -1, 9085, 9085, 9085, -1, + 9086, 9086, 9086, -1, 9087, 9087, 9087, -1, + 9088, 9088, 9088, -1, 9089, 9089, 9089, -1, + 9090, 9090, 9090, -1, 9091, 9091, 9091, -1, + 9092, 9092, 9092, -1, 9093, 9093, 9093, -1, + 9094, 9094, 9094, -1, 9095, 9095, 9095, -1, + 9096, 9096, 9096, -1, 9097, 9097, 9097, -1, + 9098, 9098, 9098, -1, 9099, 9099, 9099, -1, + 9100, 9100, 9100, -1, 9101, 9101, 9101, -1, + 9102, 9102, 9102, -1, 9103, 9103, 9103, -1, + 9104, 9104, 9104, -1, 9105, 9105, 9105, -1, + 9106, 9106, 9106, -1, 9107, 9107, 9107, -1, + 9108, 9108, 9108, -1, 9109, 9109, 9109, -1, + 9110, 9110, 9110, -1, 9111, 9111, 9111, -1, + 9112, 9112, 9112, -1, 9113, 9113, 9113, -1, + 9114, 9114, 9114, -1, 9115, 9115, 9115, -1, + 9116, 9116, 9116, -1, 9117, 9117, 9117, -1, + 9118, 9118, 9118, -1, 9119, 9119, 9119, -1, + 9120, 9120, 9120, -1, 9121, 9121, 9121, -1, + 9122, 9122, 9122, -1, 9123, 9123, 9123, -1, + 9124, 9124, 9124, -1, 9125, 9125, 9125, -1, + 9126, 9126, 9126, -1, 9127, 9127, 9127, -1, + 9128, 9128, 9128, -1, 9129, 9129, 9129, -1, + 9130, 9130, 9130, -1, 9131, 9131, 9131, -1, + 9132, 9132, 9132, -1, 9133, 9133, 9133, -1, + 9134, 9134, 9134, -1, 9135, 9135, 9135, -1, + 9136, 9136, 9136, -1, 9137, 9137, 9137, -1, + 9138, 9138, 9138, -1, 9139, 9139, 9139, -1, + 9140, 9140, 9140, -1, 9141, 9141, 9141, -1, + 9142, 9142, 9142, -1, 9143, 9143, 9143, -1, + 9144, 9144, 9144, -1, 9145, 9145, 9145, -1, + 9146, 9146, 9146, -1, 9147, 9147, 9147, -1, + 9148, 9148, 9148, -1, 9149, 9149, 9149, -1, + 9150, 9150, 9150, -1, 9151, 9151, 9151, -1, + 9152, 9152, 9152, -1, 9153, 9153, 9153, -1, + 9154, 9154, 9154, -1, 9155, 9155, 9155, -1, + 9156, 9156, 9156, -1, 9157, 9157, 9157, -1, + 9158, 9158, 9158, -1, 9159, 9159, 9159, -1, + 9160, 9160, 9160, -1, 9161, 9161, 9161, -1, + 9162, 9162, 9162, -1, 9163, 9163, 9163, -1, + 9164, 9164, 9164, -1, 9165, 9165, 9165, -1, + 9166, 9166, 9166, -1, 9167, 9167, 9167, -1, + 9168, 9168, 9168, -1, 9169, 9169, 9169, -1, + 9170, 9170, 9170, -1, 9171, 9171, 9171, -1, + 9172, 9172, 9172, -1, 9173, 9173, 9173, -1, + 9174, 9174, 9174, -1, 9175, 9175, 9175, -1, + 9176, 9176, 9176, -1, 9177, 9177, 9177, -1, + 9178, 9178, 9178, -1, 9179, 9179, 9179, -1, + 9180, 9180, 9180, -1, 9181, 9181, 9181, -1, + 9182, 9182, 9182, -1, 9183, 9183, 9183, -1, + 9184, 9184, 9184, -1, 9185, 9185, 9185, -1, + 9186, 9186, 9186, -1, 9187, 9187, 9187, -1, + 9188, 9188, 9188, -1, 9189, 9189, 9189, -1, + 9190, 9190, 9190, -1, 9191, 9191, 9191, -1, + 9192, 9192, 9192, -1, 9193, 9193, 9193, -1, + 9194, 9194, 9194, -1, 9195, 9195, 9195, -1, + 9196, 9196, 9196, -1, 9197, 9197, 9197, -1, + 9198, 9198, 9198, -1, 9199, 9199, 9199, -1, + 9200, 9200, 9200, -1, 9201, 9201, 9201, -1, + 9202, 9202, 9202, -1, 9203, 9203, 9203, -1, + 9204, 9204, 9204, -1, 9205, 9205, 9205, -1, + 9206, 9206, 9206, -1, 9207, 9207, 9207, -1, + 9208, 9208, 9208, -1, 9209, 9209, 9209, -1, + 9210, 9210, 9210, -1, 9211, 9211, 9211, -1, + 9212, 9212, 9212, -1, 9213, 9213, 9213, -1, + 9214, 9214, 9214, -1, 9215, 9215, 9215, -1, + 9216, 9216, 9216, -1, 9217, 9217, 9217, -1, + 9218, 9218, 9218, -1, 9219, 9219, 9219, -1, + 9220, 9220, 9220, -1, 9221, 9221, 9221, -1, + 9222, 9222, 9222, -1, 9223, 9223, 9223, -1, + 9224, 9224, 9224, -1, 9225, 9225, 9225, -1, + 9226, 9226, 9226, -1, 9227, 9227, 9227, -1, + 9228, 9228, 9228, -1, 9229, 9229, 9229, -1, + 9230, 9230, 9230, -1, 9231, 9231, 9231, -1, + 9232, 9232, 9232, -1, 9233, 9233, 9233, -1, + 9234, 9234, 9234, -1, 9235, 9235, 9235, -1, + 9236, 9236, 9236, -1, 9237, 9237, 9237, -1, + 9238, 9238, 9238, -1, 9239, 9239, 9239, -1, + 9240, 9240, 9240, -1, 9241, 9241, 9241, -1, + 9242, 9242, 9242, -1, 9243, 9243, 9243, -1, + 9244, 9244, 9244, -1, 9245, 9245, 9245, -1, + 9246, 9246, 9246, -1, 9247, 9247, 9247, -1, + 9248, 9248, 9248, -1, 9249, 9249, 9249, -1, + 9250, 9250, 9250, -1, 9251, 9251, 9251, -1, + 9252, 9252, 9252, -1, 9253, 9253, 9253, -1, + 9254, 9254, 9254, -1, 9255, 9255, 9255, -1, + 9256, 9256, 9256, -1, 9257, 9257, 9257, -1, + 9258, 9258, 9258, -1, 9259, 9259, 9259, -1, + 9260, 9260, 9260, -1, 9261, 9261, 9261, -1, + 9262, 9262, 9262, -1, 9263, 9263, 9263, -1, + 9264, 9264, 9264, -1, 9265, 9265, 9265, -1, + 9266, 9266, 9266, -1, 9267, 9267, 9267, -1, + 9268, 9268, 9268, -1, 9269, 9269, 9269, -1, + 9270, 9270, 9270, -1, 9271, 9271, 9271, -1, + 9272, 9272, 9272, -1, 9273, 9273, 9273, -1, + 9274, 9274, 9274, -1, 9275, 9275, 9275, -1, + 9276, 9276, 9276, -1, 9277, 9277, 9277, -1, + 9278, 9278, 9278, -1, 9279, 9279, 9279, -1, + 9280, 9280, 9280, -1, 9281, 9281, 9281, -1, + 9282, 9282, 9282, -1, 9283, 9283, 9283, -1, + 9284, 9284, 9284, -1, 9285, 9285, 9285, -1, + 9286, 9286, 9286, -1, 9287, 9287, 9287, -1, + 9288, 9288, 9288, -1, 9289, 9289, 9289, -1, + 9290, 9290, 9290, -1, 9291, 9291, 9291, -1, + 9292, 9292, 9292, -1, 9293, 9293, 9293, -1, + 9294, 9294, 9294, -1, 9295, 9295, 9295, -1, + 9296, 9296, 9296, -1, 9297, 9297, 9297, -1, + 9298, 9298, 9298, -1, 9299, 9299, 9299, -1, + 9300, 9300, 9300, -1, 9301, 9301, 9301, -1, + 9302, 9302, 9302, -1, 9303, 9303, 9303, -1, + 9304, 9304, 9304, -1, 9305, 9305, 9305, -1, + 9306, 9306, 9306, -1, 9307, 9307, 9307, -1, + 9308, 9308, 9308, -1, 9309, 9309, 9309, -1, + 9310, 9310, 9310, -1, 9311, 9311, 9311, -1, + 9312, 9312, 9312, -1, 9313, 9313, 9313, -1, + 9314, 9314, 9314, -1, 9315, 9315, 9315, -1, + 9316, 9316, 9316, -1, 9317, 9317, 9317, -1, + 9318, 9318, 9318, -1, 9319, 9319, 9319, -1, + 9320, 9320, 9320, -1, 9321, 9321, 9321, -1, + 9322, 9322, 9322, -1, 9323, 9323, 9323, -1, + 9324, 9324, 9324, -1, 9325, 9325, 9325, -1, + 9326, 9326, 9326, -1, 9327, 9327, 9327, -1, + 9328, 9328, 9328, -1, 9329, 9329, 9329, -1, + 9330, 9330, 9330, -1, 9331, 9331, 9331, -1, + 9332, 9332, 9332, -1, 9333, 9333, 9333, -1, + 9334, 9334, 9334, -1, 9335, 9335, 9335, -1, + 9336, 9336, 9336, -1, 9337, 9337, 9337, -1, + 9338, 9338, 9338, -1, 9339, 9339, 9339, -1, + 9340, 9340, 9340, -1, 9341, 9341, 9341, -1, + 9342, 9342, 9342, -1, 9343, 9343, 9343, -1, + 9344, 9344, 9344, -1, 9345, 9345, 9345, -1, + 9346, 9346, 9346, -1, 9347, 9347, 9347, -1, + 9348, 9348, 9348, -1, 9349, 9349, 9349, -1, + 9350, 9350, 9350, -1, 9351, 9351, 9351, -1, + 9352, 9352, 9352, -1, 9353, 9353, 9353, -1, + 9354, 9354, 9354, -1, 9355, 9355, 9355, -1, + 9356, 9356, 9356, -1, 9357, 9357, 9357, -1, + 9358, 9358, 9358, -1, 9359, 9359, 9359, -1, + 9360, 9360, 9360, -1, 9361, 9361, 9361, -1, + 9362, 9362, 9362, -1, 9363, 9363, 9363, -1, + 9364, 9364, 9364, -1, 9365, 9365, 9365, -1, + 9366, 9366, 9366, -1, 9367, 9367, 9367, -1, + 9368, 9368, 9368, -1, 9369, 9369, 9369, -1, + 9370, 9370, 9370, -1, 9371, 9371, 9371, -1, + 9372, 9372, 9372, -1, 9373, 9373, 9373, -1, + 9374, 9374, 9374, -1, 9375, 9375, 9375, -1, + 9376, 9376, 9376, -1, 9377, 9377, 9377, -1, + 9378, 9378, 9378, -1, 9379, 9379, 9379, -1, + 9380, 9380, 9380, -1, 9381, 9381, 9381, -1, + 9382, 9382, 9382, -1, 9383, 9383, 9383, -1, + 9384, 9384, 9384, -1, 9385, 9385, 9385, -1, + 9386, 9386, 9386, -1, 9387, 9387, 9387, -1, + 9388, 9388, 9388, -1, 9389, 9389, 9389, -1, + 9390, 9390, 9390, -1, 9391, 9391, 9391, -1, + 9392, 9392, 9392, -1, 9393, 9393, 9393, -1, + 9394, 9394, 9394, -1, 9395, 9395, 9395, -1, + 9396, 9396, 9396, -1, 9397, 9397, 9397, -1, + 9398, 9398, 9398, -1, 9399, 9399, 9399, -1, + 9400, 9400, 9400, -1, 9401, 9401, 9401, -1, + 9402, 9402, 9402, -1, 9403, 9403, 9403, -1, + 9404, 9404, 9404, -1, 9405, 9405, 9405, -1, + 9406, 9406, 9406, -1, 9407, 9407, 9407, -1, + 9408, 9408, 9408, -1, 9409, 9409, 9409, -1, + 9410, 9410, 9410, -1, 9411, 9411, 9411, -1, + 9412, 9412, 9412, -1, 9413, 9413, 9413, -1, + 9414, 9414, 9414, -1, 9415, 9415, 9415, -1, + 9416, 9416, 9416, -1, 9417, 9417, 9417, -1, + 9418, 9418, 9418, -1, 9419, 9419, 9419, -1, + 9420, 9420, 9420, -1, 9421, 9421, 9421, -1, + 9422, 9422, 9422, -1, 9423, 9423, 9423, -1, + 9424, 9424, 9424, -1, 9425, 9425, 9425, -1, + 9426, 9426, 9426, -1, 9427, 9427, 9427, -1, + 9428, 9428, 9428, -1, 9429, 9429, 9429, -1, + 9430, 9430, 9430, -1, 9431, 9431, 9431, -1, + 9432, 9432, 9432, -1, 9433, 9433, 9433, -1, + 9434, 9434, 9434, -1, 9435, 9435, 9435, -1, + 9436, 9436, 9436, -1, 9437, 9437, 9437, -1, + 9438, 9438, 9438, -1, 9439, 9439, 9439, -1, + 9440, 9440, 9440, -1, 9441, 9441, 9441, -1, + 9442, 9442, 9442, -1, 9443, 9443, 9443, -1, + 9444, 9444, 9444, -1, 9445, 9445, 9445, -1, + 9446, 9446, 9446, -1, 9447, 9447, 9447, -1, + 9448, 9448, 9448, -1, 9449, 9449, 9449, -1, + 9450, 9450, 9450, -1, 9451, 9451, 9451, -1, + 9452, 9452, 9452, -1, 9453, 9453, 9453, -1, + 9454, 9454, 9454, -1, 9455, 9455, 9455, -1, + 9456, 9456, 9456, -1, 9457, 9457, 9457, -1, + 9458, 9458, 9458, -1, 9459, 9459, 9459, -1, + 9460, 9460, 9460, -1, 9461, 9461, 9461, -1, + 9462, 9462, 9462, -1, 9463, 9463, 9463, -1, + 9464, 9464, 9464, -1, 9465, 9465, 9465, -1, + 9466, 9466, 9466, -1, 9467, 9467, 9467, -1, + 9468, 9468, 9468, -1, 9469, 9469, 9469, -1, + 9470, 9470, 9470, -1, 9471, 9471, 9471, -1, + 9472, 9472, 9472, -1, 9473, 9473, 9473, -1, + 9474, 9474, 9474, -1, 9475, 9475, 9475, -1, + 9476, 9476, 9476, -1, 9477, 9477, 9477, -1, + 9478, 9478, 9478, -1, 9479, 9479, 9479, -1, + 9480, 9480, 9480, -1, 9481, 9481, 9481, -1, + 9482, 9482, 9482, -1, 9483, 9483, 9483, -1, + 9484, 9484, 9484, -1, 9485, 9485, 9485, -1, + 9486, 9486, 9486, -1, 9487, 9487, 9487, -1, + 9488, 9488, 9488, -1, 9489, 9489, 9489, -1, + 9490, 9490, 9490, -1, 9491, 9491, 9491, -1, + 9492, 9492, 9492, -1, 9493, 9493, 9493, -1, + 9494, 9494, 9494, -1, 9495, 9495, 9495, -1, + 9496, 9496, 9496, -1, 9497, 9497, 9497, -1, + 9498, 9498, 9498, -1, 9499, 9499, 9499, -1, + 9500, 9500, 9500, -1, 9501, 9501, 9501, -1, + 9502, 9502, 9502, -1, 9503, 9503, 9503, -1, + 9504, 9504, 9504, -1, 9505, 9505, 9505, -1, + 9506, 9506, 9506, -1, 9507, 9507, 9507, -1, + 9508, 9508, 9508, -1, 9509, 9509, 9509, -1, + 9510, 9510, 9510, -1, 9511, 9511, 9511, -1, + 9512, 9512, 9512, -1, 9513, 9513, 9513, -1, + 9514, 9514, 9514, -1, 9515, 9515, 9515, -1, + 9516, 9516, 9516, -1, 9517, 9517, 9517, -1, + 9518, 9518, 9518, -1, 9519, 9519, 9519, -1, + 9520, 9520, 9520, -1, 9521, 9521, 9521, -1, + 9522, 9522, 9522, -1, 9523, 9523, 9523, -1, + 9524, 9524, 9524, -1, 9525, 9525, 9525, -1, + 9526, 9526, 9526, -1, 9527, 9527, 9527, -1, + 9528, 9528, 9528, -1, 9529, 9529, 9529, -1, + 9530, 9530, 9530, -1, 9531, 9531, 9531, -1, + 9532, 9532, 9532, -1, 9533, 9533, 9533, -1, + 9534, 9534, 9534, -1, 9535, 9535, 9535, -1, + 9536, 9536, 9536, -1, 9537, 9537, 9537, -1, + 9538, 9538, 9538, -1, 9539, 9539, 9539, -1, + 9540, 9540, 9540, -1, 9541, 9541, 9541, -1, + 9542, 9542, 9542, -1, 9543, 9543, 9543, -1, + 9544, 9544, 9544, -1, 9545, 9545, 9545, -1, + 9546, 9546, 9546, -1, 9547, 9547, 9547, -1, + 9548, 9548, 9548, -1, 9549, 9549, 9549, -1, + 9550, 9550, 9550, -1, 9551, 9551, 9551, -1, + 9552, 9552, 9552, -1, 9553, 9553, 9553, -1, + 9554, 9554, 9554, -1, 9555, 9555, 9555, -1, + 9556, 9556, 9556, -1, 9557, 9557, 9557, -1, + 9558, 9558, 9558, -1, 9559, 9559, 9559, -1, + 9560, 9560, 9560, -1, 9561, 9561, 9561, -1, + 9562, 9562, 9562, -1, 9563, 9563, 9563, -1, + 9564, 9564, 9564, -1, 9565, 9565, 9565, -1, + 9566, 9566, 9566, -1, 9567, 9567, 9567, -1, + 9568, 9568, 9568, -1, 9569, 9569, 9569, -1, + 9570, 9570, 9570, -1, 9571, 9571, 9571, -1, + 9572, 9572, 9572, -1, 9573, 9573, 9573, -1, + 9574, 9574, 9574, -1, 9575, 9575, 9575, -1, + 9576, 9576, 9576, -1, 9577, 9577, 9577, -1, + 9578, 9578, 9578, -1, 9579, 9579, 9579, -1, + 9580, 9580, 9580, -1, 9581, 9581, 9581, -1, + 9582, 9582, 9582, -1, 9583, 9583, 9583, -1, + 9584, 9584, 9584, -1, 9585, 9585, 9585, -1, + 9586, 9586, 9586, -1, 9587, 9587, 9587, -1, + 9588, 9588, 9588, -1, 9589, 9589, 9589, -1, + 9590, 9590, 9590, -1, 9591, 9591, 9591, -1, + 9592, 9592, 9592, -1, 9593, 9593, 9593, -1, + 9594, 9594, 9594, -1, 9595, 9595, 9595, -1, + 9596, 9596, 9596, -1, 9597, 9597, 9597, -1, + 9598, 9598, 9598, -1, 9599, 9599, 9599, -1, + 9600, 9600, 9600, -1, 9601, 9601, 9601, -1, + 9602, 9602, 9602, -1, 9603, 9603, 9603, -1, + 9604, 9604, 9604, -1, 9605, 9605, 9605, -1, + 9606, 9606, 9606, -1, 9607, 9607, 9607, -1, + 9608, 9608, 9608, -1, 9609, 9609, 9609, -1, + 9610, 9610, 9610, -1, 9611, 9611, 9611, -1, + 9612, 9612, 9612, -1, 9613, 9613, 9613, -1, + 9614, 9614, 9614, -1, 9615, 9615, 9615, -1, + 9616, 9616, 9616, -1, 9617, 9617, 9617, -1, + 9618, 9618, 9618, -1, 9619, 9619, 9619, -1, + 9620, 9620, 9620, -1, 9621, 9621, 9621, -1, + 9622, 9622, 9622, -1, 9623, 9623, 9623, -1, + 9624, 9624, 9624, -1, 9625, 9625, 9625, -1, + 9626, 9626, 9626, -1, 9627, 9627, 9627, -1, + 9628, 9628, 9628, -1, 9629, 9629, 9629, -1, + 9630, 9630, 9630, -1, 9631, 9631, 9631, -1, + 9632, 9632, 9632, -1, 9633, 9633, 9633, -1, + 9634, 9634, 9634, -1, 9635, 9635, 9635, -1, + 9636, 9636, 9636, -1, 9637, 9637, 9637, -1, + 9638, 9638, 9638, -1, 9639, 9639, 9639, -1, + 9640, 9640, 9640, -1, 9641, 9641, 9641, -1, + 9642, 9642, 9642, -1, 9643, 9643, 9643, -1, + 9644, 9644, 9644, -1, 9645, 9645, 9645, -1, + 9646, 9646, 9646, -1, 9647, 9647, 9647, -1, + 9648, 9648, 9648, -1, 9649, 9649, 9649, -1, + 9650, 9650, 9650, -1, 9651, 9651, 9651, -1, + 9652, 9652, 9652, -1, 9653, 9653, 9653, -1, + 9654, 9654, 9654, -1, 9655, 9655, 9655, -1, + 9656, 9656, 9656, -1, 9657, 9657, 9657, -1, + 9658, 9658, 9658, -1, 9659, 9659, 9659, -1, + 9660, 9660, 9660, -1, 9661, 9661, 9661, -1, + 9662, 9662, 9662, -1, 9663, 9663, 9663, -1, + 9664, 9664, 9664, -1, 9665, 9665, 9665, -1, + 9666, 9666, 9666, -1, 9667, 9667, 9667, -1, + 9668, 9668, 9668, -1, 9669, 9669, 9669, -1, + 9670, 9670, 9670, -1, 9671, 9671, 9671, -1, + 9672, 9672, 9672, -1, 9673, 9673, 9673, -1, + 9674, 9674, 9674, -1, 9675, 9675, 9675, -1, + 9676, 9676, 9676, -1, 9677, 9677, 9677, -1, + 9678, 9678, 9678, -1, 9679, 9679, 9679, -1, + 9680, 9680, 9680, -1, 9681, 9681, 9681, -1, + 9682, 9682, 9682, -1, 9683, 9683, 9683, -1, + 9684, 9684, 9684, -1, 9685, 9685, 9685, -1, + 9686, 9686, 9686, -1, 9687, 9687, 9687, -1, + 9688, 9688, 9688, -1, 9689, 9689, 9689, -1, + 9690, 9690, 9690, -1, 9691, 9691, 9691, -1, + 9692, 9692, 9692, -1, 9693, 9693, 9693, -1, + 9694, 9694, 9694, -1, 9695, 9695, 9695, -1, + 9696, 9696, 9696, -1, 9697, 9697, 9697, -1, + 9698, 9698, 9698, -1, 9699, 9699, 9699, -1, + 9700, 9700, 9700, -1, 9701, 9701, 9701, -1, + 9702, 9702, 9702, -1, 9703, 9703, 9703, -1, + 9704, 9704, 9704, -1, 9705, 9705, 9705, -1, + 9706, 9706, 9706, -1, 9707, 9707, 9707, -1, + 9708, 9708, 9708, -1, 9709, 9709, 9709, -1, + 9710, 9710, 9710, -1, 9711, 9711, 9711, -1, + 9712, 9712, 9712, -1, 9713, 9713, 9713, -1, + 9714, 9714, 9714, -1, 9715, 9715, 9715, -1, + 9716, 9716, 9716, -1, 9717, 9717, 9717, -1, + 9718, 9718, 9718, -1, 9719, 9719, 9719, -1, + 9720, 9720, 9720, -1, 9721, 9721, 9721, -1, + 9722, 9722, 9722, -1, 9723, 9723, 9723, -1, + 9724, 9724, 9724, -1, 9725, 9725, 9725, -1, + 9726, 9726, 9726, -1, 9727, 9727, 9727, -1, + 9728, 9728, 9728, -1, 9729, 9729, 9729, -1, + 9730, 9730, 9730, -1, 9731, 9731, 9731, -1, + 9732, 9732, 9732, -1, 9733, 9733, 9733, -1, + 9734, 9734, 9734, -1, 9735, 9735, 9735, -1, + 9736, 9736, 9736, -1, 9737, 9737, 9737, -1, + 9738, 9738, 9738, -1, 9739, 9739, 9739, -1, + 9740, 9740, 9740, -1, 9741, 9741, 9741, -1, + 9742, 9742, 9742, -1, 9743, 9743, 9743, -1, + 9744, 9744, 9744, -1, 9745, 9745, 9745, -1, + 9746, 9746, 9746, -1, 9747, 9747, 9747, -1, + 9748, 9748, 9748, -1, 9749, 9749, 9749, -1, + 9750, 9750, 9750, -1, 9751, 9751, 9751, -1, + 9752, 9752, 9752, -1, 9753, 9753, 9753, -1, + 9754, 9754, 9754, -1, 9755, 9755, 9755, -1, + 9756, 9756, 9756, -1, 9757, 9757, 9757, -1, + 9758, 9758, 9758, -1, 9759, 9759, 9759, -1, + 9760, 9760, 9760, -1, 9761, 9761, 9761, -1, + 9762, 9762, 9762, -1, 9763, 9763, 9763, -1, + 9764, 9764, 9764, -1, 9765, 9765, 9765, -1, + 9766, 9766, 9766, -1, 9767, 9767, 9767, -1, + 9768, 9768, 9768, -1, 9769, 9769, 9769, -1, + 9770, 9770, 9770, -1, 9771, 9771, 9771, -1, + 9772, 9772, 9772, -1, 9773, 9773, 9773, -1, + 9774, 9774, 9774, -1, 9775, 9775, 9775, -1, + 9776, 9776, 9776, -1, 9777, 9777, 9777, -1, + 9778, 9778, 9778, -1, 9779, 9779, 9779, -1, + 9780, 9780, 9780, -1, 9781, 9781, 9781, -1, + 9782, 9782, 9782, -1, 9783, 9783, 9783, -1, + 9784, 9784, 9784, -1, 9785, 9785, 9785, -1, + 9786, 9786, 9786, -1, 9787, 9787, 9787, -1, + 9788, 9788, 9788, -1, 9789, 9789, 9789, -1, + 9790, 9790, 9790, -1, 9791, 9791, 9791, -1, + 9792, 9792, 9792, -1, 9793, 9793, 9793, -1, + 9794, 9794, 9794, -1, 9795, 9795, 9795, -1, + 9796, 9796, 9796, -1, 9797, 9797, 9797, -1, + 9798, 9798, 9798, -1, 9799, 9799, 9799, -1, + 9800, 9800, 9800, -1, 9801, 9801, 9801, -1, + 9802, 9802, 9802, -1, 9803, 9803, 9803, -1, + 9804, 9804, 9804, -1, 9805, 9805, 9805, -1, + 9806, 9806, 9806, -1, 9807, 9807, 9807, -1, + 9808, 9808, 9808, -1, 9809, 9809, 9809, -1, + 9810, 9810, 9810, -1, 9811, 9811, 9811, -1, + 9812, 9812, 9812, -1, 9813, 9813, 9813, -1, + 9814, 9814, 9814, -1, 9815, 9815, 9815, -1, + 9816, 9816, 9816, -1, 9817, 9817, 9817, -1, + 9818, 9818, 9818, -1, 9819, 9819, 9819, -1, + 9820, 9820, 9820, -1, 9821, 9821, 9821, -1, + 9822, 9822, 9822, -1, 9823, 9823, 9823, -1, + 9824, 9824, 9824, -1, 9825, 9825, 9825, -1, + 9826, 9826, 9826, -1, 9827, 9827, 9827, -1, + 9828, 9828, 9828, -1, 9829, 9829, 9829, -1, + 9830, 9830, 9830, -1, 9831, 9831, 9831, -1, + 9832, 9832, 9832, -1, 9833, 9833, 9833, -1, + 9834, 9834, 9834, -1, 9835, 9835, 9835, -1, + 9836, 9836, 9836, -1, 9837, 9837, 9837, -1, + 9838, 9838, 9838, -1, 9839, 9839, 9839, -1, + 9840, 9840, 9840, -1, 9841, 9841, 9841, -1, + 9842, 9842, 9842, -1, 9843, 9843, 9843, -1, + 9844, 9844, 9844, -1, 9845, 9845, 9845, -1, + 9846, 9846, 9846, -1, 9847, 9847, 9847, -1, + 9848, 9848, 9848, -1, 9849, 9849, 9849, -1, + 9850, 9850, 9850, -1, 9851, 9851, 9851, -1, + 9852, 9852, 9852, -1, 9853, 9853, 9853, -1, + 9854, 9854, 9854, -1, 9855, 9855, 9855, -1, + 9856, 9856, 9856, -1, 9857, 9857, 9857, -1, + 9858, 9858, 9858, -1, 9859, 9859, 9859, -1, + 9860, 9860, 9860, -1, 9861, 9861, 9861, -1, + 9862, 9862, 9862, -1, 9863, 9863, 9863, -1, + 9864, 9864, 9864, -1, 9865, 9865, 9865, -1, + 9866, 9866, 9866, -1, 9867, 9867, 9867, -1, + 9868, 9868, 9868, -1, 9869, 9869, 9869, -1, + 9870, 9870, 9870, -1, 9871, 9871, 9871, -1, + 9872, 9872, 9872, -1, 9873, 9873, 9873, -1, + 9874, 9874, 9874, -1, 9875, 9875, 9875, -1, + 9876, 9876, 9876, -1, 9877, 9877, 9877, -1, + 9878, 9878, 9878, -1, 9879, 9879, 9879, -1, + 9880, 9880, 9880, -1, 9881, 9881, 9881, -1, + 9882, 9882, 9882, -1, 9883, 9883, 9883, -1, + 9884, 9884, 9884, -1, 9885, 9885, 9885, -1, + 9886, 9886, 9886, -1, 9887, 9887, 9887, -1, + 9888, 9888, 9888, -1, 9889, 9889, 9889, -1, + 9890, 9890, 9890, -1, 9891, 9891, 9891, -1, + 9892, 9892, 9892, -1, 9893, 9893, 9893, -1, + 9894, 9894, 9894, -1, 9895, 9895, 9895, -1, + 9896, 9896, 9896, -1, 9897, 9897, 9897, -1, + 9898, 9898, 9898, -1, 9899, 9899, 9899, -1, + 9900, 9900, 9900, -1, 9901, 9901, 9901, -1, + 9902, 9902, 9902, -1, 9903, 9903, 9903, -1, + 9904, 9904, 9904, -1, 9905, 9905, 9905, -1, + 9906, 9906, 9906, -1, 9907, 9907, 9907, -1, + 9908, 9908, 9908, -1, 9909, 9909, 9909, -1, + 9910, 9910, 9910, -1, 9911, 9911, 9911, -1, + 9912, 9912, 9912, -1, 9913, 9913, 9913, -1, + 9914, 9914, 9914, -1, 9915, 9915, 9915, -1, + 9916, 9916, 9916, -1, 9917, 9917, 9917, -1, + 9918, 9918, 9918, -1, 9919, 9919, 9919, -1, + 9920, 9920, 9920, -1, 9921, 9921, 9921, -1, + 9922, 9922, 9922, -1, 9923, 9923, 9923, -1, + 9924, 9924, 9924, -1, 9925, 9925, 9925, -1, + 9926, 9926, 9926, -1, 9927, 9927, 9927, -1, + 9928, 9928, 9928, -1, 9929, 9929, 9929, -1, + 9930, 9930, 9930, -1, 9931, 9931, 9931, -1, + 9932, 9932, 9932, -1, 9933, 9933, 9933, -1, + 9934, 9934, 9934, -1, 9935, 9935, 9935, -1, + 9936, 9936, 9936, -1, 9937, 9937, 9937, -1, + 9938, 9938, 9938, -1, 9939, 9939, 9939, -1, + 9940, 9940, 9940, -1, 9941, 9941, 9941, -1, + 9942, 9942, 9942, -1, 9943, 9943, 9943, -1, + 9944, 9944, 9944, -1, 9945, 9945, 9945, -1, + 9946, 9946, 9946, -1, 9947, 9947, 9947, -1, + 9948, 9948, 9948, -1, 9949, 9949, 9949, -1, + 9950, 9950, 9950, -1, 9951, 9951, 9951, -1, + 9952, 9952, 9952, -1, 9953, 9953, 9953, -1, + 9954, 9954, 9954, -1, 9955, 9955, 9955, -1, + 9956, 9956, 9956, -1, 9957, 9957, 9957, -1, + 9958, 9958, 9958, -1, 9959, 9959, 9959, -1, + 9960, 9960, 9960, -1, 9961, 9961, 9961, -1, + 9962, 9962, 9962, -1, 9963, 9963, 9963, -1, + 9964, 9964, 9964, -1, 9965, 9965, 9965, -1, + 9966, 9966, 9966, -1, 9967, 9967, 9967, -1, + 9968, 9968, 9968, -1, 9969, 9969, 9969, -1, + 9970, 9970, 9970, -1, 9971, 9971, 9971, -1, + 9972, 9972, 9972, -1, 9973, 9973, 9973, -1, + 9974, 9974, 9974, -1, 9975, 9975, 9975, -1, + 9976, 9976, 9976, -1, 9977, 9977, 9977, -1, + 9978, 9978, 9978, -1, 9979, 9979, 9979, -1, + 9980, 9980, 9980, -1, 9981, 9981, 9981, -1, + 9982, 9982, 9982, -1, 9983, 9983, 9983, -1, + 9984, 9984, 9984, -1, 9985, 9985, 9985, -1, + 9986, 9986, 9986, -1, 9987, 9987, 9987, -1, + 9988, 9988, 9988, -1, 9989, 9989, 9989, -1, + 9990, 9990, 9990, -1, 9991, 9991, 9991, -1, + 9992, 9992, 9992, -1, 9993, 9993, 9993, -1, + 9994, 9994, 9994, -1, 9995, 9995, 9995, -1, + 9996, 9996, 9996, -1, 9997, 9997, 9997, -1, + 9998, 9998, 9998, -1, 9999, 9999, 9999, -1, + 10000, 10000, 10000, -1, 10001, 10001, 10001, -1, + 10002, 10002, 10002, -1, 10003, 10003, 10003, -1, + 10004, 10004, 10004, -1, 10005, 10005, 10005, -1, + 10006, 10006, 10006, -1, 10007, 10007, 10007, -1, + 10008, 10008, 10008, -1, 10009, 10009, 10009, -1, + 10010, 10010, 10010, -1, 10011, 10011, 10011, -1, + 10012, 10012, 10012, -1, 10013, 10013, 10013, -1, + 10014, 10014, 10014, -1, 10015, 10015, 10015, -1, + 10016, 10016, 10016, -1, 10017, 10017, 10017, -1, + 10018, 10018, 10018, -1, 10019, 10019, 10019, -1, + 10020, 10020, 10020, -1, 10021, 10021, 10021, -1, + 10022, 10022, 10022, -1, 10023, 10023, 10023, -1, + 10024, 10024, 10024, -1, 10025, 10025, 10025, -1, + 10026, 10026, 10026, -1, 10027, 10027, 10027, -1, + 10028, 10028, 10028, -1, 10029, 10029, 10029, -1, + 10030, 10030, 10030, -1, 10031, 10031, 10031, -1, + 10032, 10032, 10032, -1, 10033, 10033, 10033, -1, + 10034, 10034, 10034, -1, 10035, 10035, 10035, -1, + 10036, 10036, 10036, -1, 10037, 10037, 10037, -1, + 10038, 10038, 10038, -1, 10039, 10039, 10039, -1, + 10040, 10040, 10040, -1, 10041, 10041, 10041, -1, + 10042, 10042, 10042, -1, 10043, 10043, 10043, -1, + 10044, 10044, 10044, -1, 10045, 10045, 10045, -1, + 10046, 10046, 10046, -1, 10047, 10047, 10047, -1, + 10048, 10048, 10048, -1, 10049, 10049, 10049, -1, + 10050, 10050, 10050, -1, 10051, 10051, 10051, -1, + 10052, 10052, 10052, -1, 10053, 10053, 10053, -1, + 10054, 10054, 10054, -1, 10055, 10055, 10055, -1, + 10056, 10056, 10056, -1, 10057, 10057, 10057, -1, + 10058, 10058, 10058, -1, 10059, 10059, 10059, -1, + 10060, 10060, 10060, -1, 10061, 10061, 10061, -1, + 10062, 10062, 10062, -1, 10063, 10063, 10063, -1, + 10064, 10064, 10064, -1, 10065, 10065, 10065, -1, + 10066, 10066, 10066, -1, 10067, 10067, 10067, -1, + 10068, 10068, 10068, -1, 10069, 10069, 10069, -1, + 10070, 10070, 10070, -1, 10071, 10071, 10071, -1, + 10072, 10072, 10072, -1, 10073, 10073, 10073, -1, + 10074, 10074, 10074, -1, 10075, 10075, 10075, -1, + 10076, 10076, 10076, -1, 10077, 10077, 10077, -1, + 10078, 10078, 10078, -1, 10079, 10079, 10079, -1, + 10080, 10080, 10080, -1, 10081, 10081, 10081, -1, + 10082, 10082, 10082, -1, 10083, 10083, 10083, -1, + 10084, 10084, 10084, -1, 10085, 10085, 10085, -1, + 10086, 10086, 10086, -1, 10087, 10087, 10087, -1, + 10088, 10088, 10088, -1, 10089, 10089, 10089, -1, + 10090, 10090, 10090, -1, 10091, 10091, 10091, -1, + 10092, 10092, 10092, -1, 10093, 10093, 10093, -1, + 10094, 10094, 10094, -1, 10095, 10095, 10095, -1, + 10096, 10096, 10096, -1, 10097, 10097, 10097, -1, + 10098, 10098, 10098, -1, 10099, 10099, 10099, -1, + 10100, 10100, 10100, -1, 10101, 10101, 10101, -1, + 10102, 10102, 10102, -1, 10103, 10103, 10103, -1, + 10104, 10104, 10104, -1, 10105, 10105, 10105, -1, + 10106, 10106, 10106, -1, 10107, 10107, 10107, -1, + 10108, 10108, 10108, -1, 10109, 10109, 10109, -1, + 10110, 10110, 10110, -1, 10111, 10111, 10111, -1, + 10112, 10112, 10112, -1, 10113, 10113, 10113, -1, + 10114, 10114, 10114, -1, 10115, 10115, 10115, -1, + 10116, 10116, 10116, -1, 10117, 10117, 10117, -1, + 10118, 10118, 10118, -1, 10119, 10119, 10119, -1, + 10120, 10120, 10120, -1, 10121, 10121, 10121, -1, + 10122, 10122, 10122, -1, 10123, 10123, 10123, -1, + 10124, 10124, 10124, -1, 10125, 10125, 10125, -1, + 10126, 10126, 10126, -1, 10127, 10127, 10127, -1, + 10128, 10128, 10128, -1, 10129, 10129, 10129, -1, + 10130, 10130, 10130, -1, 10131, 10131, 10131, -1, + 10132, 10132, 10132, -1, 10133, 10133, 10133, -1, + 10134, 10134, 10134, -1, 10135, 10135, 10135, -1, + 10136, 10136, 10136, -1, 10137, 10137, 10137, -1, + 10138, 10138, 10138, -1, 10139, 10139, 10139, -1, + 10140, 10140, 10140, -1, 10141, 10141, 10141, -1, + 10142, 10142, 10142, -1, 10143, 10143, 10143, -1, + 10144, 10144, 10144, -1, 10145, 10145, 10145, -1, + 10146, 10146, 10146, -1, 10147, 10147, 10147, -1, + 10148, 10148, 10148, -1, 10149, 10149, 10149, -1, + 10150, 10150, 10150, -1, 10151, 10151, 10151, -1, + 10152, 10152, 10152, -1, 10153, 10153, 10153, -1, + 10154, 10154, 10154, -1, 10155, 10155, 10155, -1, + 10156, 10156, 10156, -1, 10157, 10157, 10157, -1, + 10158, 10158, 10158, -1, 10159, 10159, 10159, -1, + 10160, 10160, 10160, -1, 10161, 10161, 10161, -1, + 10162, 10162, 10162, -1, 10163, 10163, 10163, -1, + 10164, 10164, 10164, -1, 10165, 10165, 10165, -1, + 10166, 10166, 10166, -1, 10167, 10167, 10167, -1, + 10168, 10168, 10168, -1, 10169, 10169, 10169, -1, + 10170, 10170, 10170, -1, 10171, 10171, 10171, -1, + 10172, 10172, 10172, -1, 10173, 10173, 10173, -1, + 10174, 10174, 10174, -1, 10175, 10175, 10175, -1, + 10176, 10176, 10176, -1, 10177, 10177, 10177, -1, + 10178, 10178, 10178, -1, 10179, 10179, 10179, -1, + 10180, 10180, 10180, -1, 10181, 10181, 10181, -1, + 10182, 10182, 10182, -1, 10183, 10183, 10183, -1, + 10184, 10184, 10184, -1, 10185, 10185, 10185, -1, + 10186, 10186, 10186, -1, 10187, 10187, 10187, -1, + 10188, 10188, 10188, -1, 10189, 10189, 10189, -1, + 10190, 10190, 10190, -1, 10191, 10191, 10191, -1, + 10192, 10192, 10192, -1, 10193, 10193, 10193, -1, + 10194, 10194, 10194, -1, 10195, 10195, 10195, -1, + 10196, 10196, 10196, -1, 10197, 10197, 10197, -1, + 10198, 10198, 10198, -1, 10199, 10199, 10199, -1, + 10200, 10200, 10200, -1, 10201, 10201, 10201, -1, + 10202, 10202, 10202, -1, 10203, 10203, 10203, -1, + 10204, 10204, 10204, -1, 10205, 10205, 10205, -1, + 10206, 10206, 10206, -1, 10207, 10207, 10207, -1, + 10208, 10208, 10208, -1, 10209, 10209, 10209, -1, + 10210, 10210, 10210, -1, 10211, 10211, 10211, -1, + 10212, 10212, 10212, -1, 10213, 10213, 10213, -1, + 10214, 10214, 10214, -1, 10215, 10215, 10215, -1, + 10216, 10216, 10216, -1, 10217, 10217, 10217, -1, + 10218, 10218, 10218, -1, 10219, 10219, 10219, -1, + 10220, 10220, 10220, -1, 10221, 10221, 10221, -1, + 10222, 10222, 10222, -1, 10223, 10223, 10223, -1, + 10224, 10224, 10224, -1, 10225, 10225, 10225, -1, + 10226, 10226, 10226, -1, 10227, 10227, 10227, -1, + 10228, 10228, 10228, -1, 10229, 10229, 10229, -1, + 10230, 10230, 10230, -1, 10231, 10231, 10231, -1, + 10232, 10232, 10232, -1, 10233, 10233, 10233, -1, + 10234, 10234, 10234, -1, 10235, 10235, 10235, -1, + 10236, 10236, 10236, -1, 10237, 10237, 10237, -1, + 10238, 10238, 10238, -1, 10239, 10239, 10239, -1, + 10240, 10240, 10240, -1, 10241, 10241, 10241, -1, + 10242, 10242, 10242, -1, 10243, 10243, 10243, -1, + 10244, 10244, 10244, -1, 10245, 10245, 10245, -1, + 10246, 10246, 10246, -1, 10247, 10247, 10247, -1, + 10248, 10248, 10248, -1, 10249, 10249, 10249, -1, + 10250, 10250, 10250, -1, 10251, 10251, 10251, -1, + 10252, 10252, 10252, -1, 10253, 10253, 10253, -1, + 10254, 10254, 10254, -1, 10255, 10255, 10255, -1, + 10256, 10256, 10256, -1, 10257, 10257, 10257, -1, + 10258, 10258, 10258, -1, 10259, 10259, 10259, -1, + 10260, 10260, 10260, -1, 10261, 10261, 10261, -1, + 10262, 10262, 10262, -1, 10263, 10263, 10263, -1, + 10264, 10264, 10264, -1, 10265, 10265, 10265, -1, + 10266, 10266, 10266, -1, 10267, 10267, 10267, -1, + 10268, 10268, 10268, -1, 10269, 10269, 10269, -1, + 10270, 10270, 10270, -1, 10271, 10271, 10271, -1, + 10272, 10272, 10272, -1, 10273, 10273, 10273, -1, + 10274, 10274, 10274, -1, 10275, 10275, 10275, -1, + 10276, 10276, 10276, -1, 10277, 10277, 10277, -1, + 10278, 10278, 10278, -1, 10279, 10279, 10279, -1, + 10280, 10280, 10280, -1, 10281, 10281, 10281, -1, + 10282, 10282, 10282, -1, 10283, 10283, 10283, -1, + 10284, 10284, 10284, -1, 10285, 10285, 10285, -1, + 10286, 10286, 10286, -1, 10287, 10287, 10287, -1, + 10288, 10288, 10288, -1, 10289, 10289, 10289, -1, + 10290, 10290, 10290, -1, 10291, 10291, 10291, -1, + 10292, 10292, 10292, -1, 10293, 10293, 10293, -1, + 10294, 10294, 10294, -1, 10295, 10295, 10295, -1, + 10296, 10296, 10296, -1, 10297, 10297, 10297, -1, + 10298, 10298, 10298, -1, 10299, 10299, 10299, -1, + 10300, 10300, 10300, -1, 10301, 10301, 10301, -1, + 10302, 10302, 10302, -1, 10303, 10303, 10303, -1, + 10304, 10304, 10304, -1, 10305, 10305, 10305, -1, + 10306, 10306, 10306, -1, 10307, 10307, 10307, -1, + 10308, 10308, 10308, -1, 10309, 10309, 10309, -1, + 10310, 10310, 10310, -1, 10311, 10311, 10311, -1, + 10312, 10312, 10312, -1, 10313, 10313, 10313, -1, + 10314, 10314, 10314, -1, 10315, 10315, 10315, -1, + 10316, 10316, 10316, -1, 10317, 10317, 10317, -1, + 10318, 10318, 10318, -1, 10319, 10319, 10319, -1, + 10320, 10320, 10320, -1, 10321, 10321, 10321, -1, + 10322, 10322, 10322, -1, 10323, 10323, 10323, -1, + 10324, 10324, 10324, -1, 10325, 10325, 10325, -1, + 10326, 10326, 10326, -1, 10327, 10327, 10327, -1, + 10328, 10328, 10328, -1, 10329, 10329, 10329, -1, + 10330, 10330, 10330, -1, 10331, 10331, 10331, -1, + 10332, 10332, 10332, -1, 10333, 10333, 10333, -1, + 10334, 10334, 10334, -1, 10335, 10335, 10335, -1, + 10336, 10336, 10336, -1, 10337, 10337, 10337, -1, + 10338, 10338, 10338, -1, 10339, 10339, 10339, -1, + 10340, 10340, 10340, -1, 10341, 10341, 10341, -1, + 10342, 10342, 10342, -1, 10343, 10343, 10343, -1, + 10344, 10344, 10344, -1, 10345, 10345, 10345, -1, + 10346, 10346, 10346, -1, 10347, 10347, 10347, -1, + 10348, 10348, 10348, -1, 10349, 10349, 10349, -1, + 10350, 10350, 10350, -1, 10351, 10351, 10351, -1, + 10352, 10352, 10352, -1, 10353, 10353, 10353, -1, + 10354, 10354, 10354, -1, 10355, 10355, 10355, -1, + 10356, 10356, 10356, -1, 10357, 10357, 10357, -1, + 10358, 10358, 10358, -1, 10359, 10359, 10359, -1, + 10360, 10360, 10360, -1, 10361, 10361, 10361, -1, + 10362, 10362, 10362, -1, 10363, 10363, 10363, -1, + 10364, 10364, 10364, -1, 10365, 10365, 10365, -1, + 10366, 10366, 10366, -1, 10367, 10367, 10367, -1, + 10368, 10368, 10368, -1, 10369, 10369, 10369, -1, + 10370, 10370, 10370, -1, 10371, 10371, 10371, -1, + 10372, 10372, 10372, -1, 10373, 10373, 10373, -1, + 10374, 10374, 10374, -1, 10375, 10375, 10375, -1, + 10376, 10376, 10376, -1, 10377, 10377, 10377, -1, + 10378, 10378, 10378, -1, 10379, 10379, 10379, -1, + 10380, 10380, 10380, -1, 10381, 10381, 10381, -1, + 10382, 10382, 10382, -1, 10383, 10383, 10383, -1, + 10384, 10384, 10384, -1, 10385, 10385, 10385, -1, + 10386, 10386, 10386, -1, 10387, 10387, 10387, -1, + 10388, 10388, 10388, -1, 10389, 10389, 10389, -1, + 10390, 10390, 10390, -1, 10391, 10391, 10391, -1, + 10392, 10392, 10392, -1, 10393, 10393, 10393, -1, + 10394, 10394, 10394, -1, 10395, 10395, 10395, -1, + 10396, 10396, 10396, -1, 10397, 10397, 10397, -1, + 10398, 10398, 10398, -1, 10399, 10399, 10399, -1, + 10400, 10400, 10400, -1, 10401, 10401, 10401, -1, + 10402, 10402, 10402, -1, 10403, 10403, 10403, -1, + 10404, 10404, 10404, -1, 10405, 10405, 10405, -1, + 10406, 10406, 10406, -1, 10407, 10407, 10407, -1, + 10408, 10408, 10408, -1, 10409, 10409, 10409, -1, + 10410, 10410, 10410, -1, 10411, 10411, 10411, -1, + 10412, 10412, 10412, -1, 10413, 10413, 10413, -1, + 10414, 10414, 10414, -1, 10415, 10415, 10415, -1, + 10416, 10416, 10416, -1, 10417, 10417, 10417, -1, + 10418, 10418, 10418, -1, 10419, 10419, 10419, -1, + 10420, 10420, 10420, -1, 10421, 10421, 10421, -1, + 10422, 10422, 10422, -1, 10423, 10423, 10423, -1, + 10424, 10424, 10424, -1, 10425, 10425, 10425, -1, + 10426, 10426, 10426, -1, 10427, 10427, 10427, -1, + 10428, 10428, 10428, -1, 10429, 10429, 10429, -1, + 10430, 10430, 10430, -1, 10431, 10431, 10431, -1, + 10432, 10432, 10432, -1, 10433, 10433, 10433, -1, + 10434, 10434, 10434, -1, 10435, 10435, 10435, -1, + 10436, 10436, 10436, -1, 10437, 10437, 10437, -1, + 10438, 10438, 10438, -1, 10439, 10439, 10439, -1, + 10440, 10440, 10440, -1, 10441, 10441, 10441, -1, + 10442, 10442, 10442, -1, 10443, 10443, 10443, -1, + 10444, 10444, 10444, -1, 10445, 10445, 10445, -1, + 10446, 10446, 10446, -1, 10447, 10447, 10447, -1, + 10448, 10448, 10448, -1, 10449, 10449, 10449, -1, + 10450, 10450, 10450, -1, 10451, 10451, 10451, -1, + 10452, 10452, 10452, -1, 10453, 10453, 10453, -1, + 10454, 10454, 10454, -1, 10455, 10455, 10455, -1, + 10456, 10456, 10456, -1, 10457, 10457, 10457, -1, + 10458, 10458, 10458, -1, 10459, 10459, 10459, -1, + 10460, 10460, 10460, -1, 10461, 10461, 10461, -1, + 10462, 10462, 10462, -1, 10463, 10463, 10463, -1, + 10464, 10464, 10464, -1, 10465, 10465, 10465, -1, + 10466, 10466, 10466, -1, 10467, 10467, 10467, -1, + 10468, 10468, 10468, -1, 10469, 10469, 10469, -1, + 10470, 10470, 10470, -1, 10471, 10471, 10471, -1, + 10472, 10472, 10472, -1, 10473, 10473, 10473, -1, + 10474, 10474, 10474, -1, 10475, 10475, 10475, -1, + 10476, 10476, 10476, -1, 10477, 10477, 10477, -1, + 10478, 10478, 10478, -1, 10479, 10479, 10479, -1, + 10480, 10480, 10480, -1, 10481, 10481, 10481, -1, + 10482, 10482, 10482, -1, 10483, 10483, 10483, -1, + 10484, 10484, 10484, -1, 10485, 10485, 10485, -1, + 10486, 10486, 10486, -1, 10487, 10487, 10487, -1, + 10488, 10488, 10488, -1, 10489, 10489, 10489, -1, + 10490, 10490, 10490, -1, 10491, 10491, 10491, -1, + 10492, 10492, 10492, -1, 10493, 10493, 10493, -1, + 10494, 10494, 10494, -1, 10495, 10495, 10495, -1, + 10496, 10496, 10496, -1, 10497, 10497, 10497, -1, + 10498, 10498, 10498, -1, 10499, 10499, 10499, -1, + 10500, 10500, 10500, -1, 10501, 10501, 10501, -1, + 10502, 10502, 10502, -1, 10503, 10503, 10503, -1, + 10504, 10504, 10504, -1, 10505, 10505, 10505, -1, + 10506, 10506, 10506, -1, 10507, 10507, 10507, -1, + 10508, 10508, 10508, -1, 10509, 10509, 10509, -1, + 10510, 10510, 10510, -1, 10511, 10511, 10511, -1, + 10512, 10512, 10512, -1, 10513, 10513, 10513, -1, + 10514, 10514, 10514, -1, 10515, 10515, 10515, -1, + 10516, 10516, 10516, -1, 10517, 10517, 10517, -1, + 10518, 10518, 10518, -1, 10519, 10519, 10519, -1, + 10520, 10520, 10520, -1, 10521, 10521, 10521, -1, + 10522, 10522, 10522, -1, 10523, 10523, 10523, -1, + 10524, 10524, 10524, -1, 10525, 10525, 10525, -1, + 10526, 10526, 10526, -1, 10527, 10527, 10527, -1, + 10528, 10528, 10528, -1, 10529, 10529, 10529, -1, + 10530, 10530, 10530, -1, 10531, 10531, 10531, -1, + 10532, 10532, 10532, -1, 10533, 10533, 10533, -1, + 10534, 10534, 10534, -1, 10535, 10535, 10535, -1, + 10536, 10536, 10536, -1, 10537, 10537, 10537, -1, + 10538, 10538, 10538, -1, 10539, 10539, 10539, -1, + 10540, 10540, 10540, -1, 10541, 10541, 10541, -1, + 10542, 10542, 10542, -1, 10543, 10543, 10543, -1, + 10544, 10544, 10544, -1, 10545, 10545, 10545, -1, + 10546, 10546, 10546, -1, 10547, 10547, 10547, -1, + 10548, 10548, 10548, -1, 10549, 10549, 10549, -1, + 10550, 10550, 10550, -1, 10551, 10551, 10551, -1, + 10552, 10552, 10552, -1, 10553, 10553, 10553, -1, + 10554, 10554, 10554, -1, 10555, 10555, 10555, -1, + 10556, 10556, 10556, -1, 10557, 10557, 10557, -1, + 10558, 10558, 10558, -1, 10559, 10559, 10559, -1, + 10560, 10560, 10560, -1, 10561, 10561, 10561, -1, + 10562, 10562, 10562, -1, 10563, 10563, 10563, -1, + 10564, 10564, 10564, -1, 10565, 10565, 10565, -1, + 10566, 10566, 10566, -1, 10567, 10567, 10567, -1, + 10568, 10568, 10568, -1, 10569, 10569, 10569, -1, + 10570, 10570, 10570, -1, 10571, 10571, 10571, -1, + 10572, 10572, 10572, -1, 10573, 10573, 10573, -1, + 10574, 10574, 10574, -1, 10575, 10575, 10575, -1, + 10576, 10576, 10576, -1, 10577, 10577, 10577, -1, + 10578, 10578, 10578, -1, 10579, 10579, 10579, -1, + 10580, 10580, 10580, -1, 10581, 10581, 10581, -1, + 10582, 10582, 10582, -1, 10583, 10583, 10583, -1, + 10584, 10584, 10584, -1, 10585, 10585, 10585, -1, + 10586, 10586, 10586, -1, 10587, 10587, 10587, -1, + 10588, 10588, 10588, -1, 10589, 10589, 10589, -1, + 10590, 10590, 10590, -1, 10591, 10591, 10591, -1, + 10592, 10592, 10592, -1, 10593, 10593, 10593, -1, + 10594, 10594, 10594, -1, 10595, 10595, 10595, -1, + 10596, 10596, 10596, -1, 10597, 10597, 10597, -1, + 10598, 10598, 10598, -1, 10599, 10599, 10599, -1, + 10600, 10600, 10600, -1, 10601, 10601, 10601, -1, + 10602, 10602, 10602, -1, 10603, 10603, 10603, -1, + 10604, 10604, 10604, -1, 10605, 10605, 10605, -1, + 10606, 10606, 10606, -1, 10607, 10607, 10607, -1, + 10608, 10608, 10608, -1, 10609, 10609, 10609, -1, + 10610, 10610, 10610, -1, 10611, 10611, 10611, -1, + 10612, 10612, 10612, -1, 10613, 10613, 10613, -1, + 10614, 10614, 10614, -1, 10615, 10615, 10615, -1, + 10616, 10616, 10616, -1, 10617, 10617, 10617, -1, + 10618, 10618, 10618, -1, 10619, 10619, 10619, -1, + 10620, 10620, 10620, -1, 10621, 10621, 10621, -1, + 10622, 10622, 10622, -1, 10623, 10623, 10623, -1, + 10624, 10624, 10624, -1, 10625, 10625, 10625, -1, + 10626, 10626, 10626, -1, 10627, 10627, 10627, -1, + 10628, 10628, 10628, -1, 10629, 10629, 10629, -1, + 10630, 10630, 10630, -1, 10631, 10631, 10631, -1, + 10632, 10632, 10632, -1, 10633, 10633, 10633, -1, + 10634, 10634, 10634, -1, 10635, 10635, 10635, -1, + 10636, 10636, 10636, -1, 10637, 10637, 10637, -1, + 10638, 10638, 10638, -1, 10639, 10639, 10639, -1, + 10640, 10640, 10640, -1, 10641, 10641, 10641, -1, + 10642, 10642, 10642, -1, 10643, 10643, 10643, -1, + 10644, 10644, 10644, -1, 10645, 10645, 10645, -1, + 10646, 10646, 10646, -1, 10647, 10647, 10647, -1, + 10648, 10648, 10648, -1, 10649, 10649, 10649, -1, + 10650, 10650, 10650, -1, 10651, 10651, 10651, -1, + 10652, 10652, 10652, -1, 10653, 10653, 10653, -1, + 10654, 10654, 10654, -1, 10655, 10655, 10655, -1, + 10656, 10656, 10656, -1, 10657, 10657, 10657, -1, + 10658, 10658, 10658, -1, 10659, 10659, 10659, -1, + 10660, 10660, 10660, -1, 10661, 10661, 10661, -1, + 10662, 10662, 10662, -1, 10663, 10663, 10663, -1, + 10664, 10664, 10664, -1, 10665, 10665, 10665, -1, + 10666, 10666, 10666, -1, 10667, 10667, 10667, -1, + 10668, 10668, 10668, -1, 10669, 10669, 10669, -1, + 10670, 10670, 10670, -1, 10671, 10671, 10671, -1, + 10672, 10672, 10672, -1, 10673, 10673, 10673, -1, + 10674, 10674, 10674, -1, 10675, 10675, 10675, -1, + 10676, 10676, 10676, -1, 10677, 10677, 10677, -1, + 10678, 10678, 10678, -1, 10679, 10679, 10679, -1, + 10680, 10680, 10680, -1, 10681, 10681, 10681, -1, + 10682, 10682, 10682, -1, 10683, 10683, 10683, -1, + 10684, 10684, 10684, -1, 10685, 10685, 10685, -1, + 10686, 10686, 10686, -1, 10687, 10687, 10687, -1, + 10688, 10688, 10688, -1, 10689, 10689, 10689, -1, + 10690, 10690, 10690, -1, 10691, 10691, 10691, -1, + 10692, 10692, 10692, -1, 10693, 10693, 10693, -1, + 10694, 10694, 10694, -1, 10695, 10695, 10695, -1, + 10696, 10696, 10696, -1, 10697, 10697, 10697, -1, + 10698, 10698, 10698, -1, 10699, 10699, 10699, -1, + 10700, 10700, 10700, -1, 10701, 10701, 10701, -1, + 10702, 10702, 10702, -1, 10703, 10703, 10703, -1, + 10704, 10704, 10704, -1, 10705, 10705, 10705, -1, + 10706, 10706, 10706, -1, 10707, 10707, 10707, -1, + 10708, 10708, 10708, -1, 10709, 10709, 10709, -1, + 10710, 10710, 10710, -1, 10711, 10711, 10711, -1, + 10712, 10712, 10712, -1, 10713, 10713, 10713, -1, + 10714, 10714, 10714, -1, 10715, 10715, 10715, -1, + 10716, 10716, 10716, -1, 10717, 10717, 10717, -1, + 10718, 10718, 10718, -1, 10719, 10719, 10719, -1, + 10720, 10720, 10720, -1, 10721, 10721, 10721, -1, + 10722, 10722, 10722, -1, 10723, 10723, 10723, -1, + 10724, 10724, 10724, -1, 10725, 10725, 10725, -1, + 10726, 10726, 10726, -1, 10727, 10727, 10727, -1, + 10728, 10728, 10728, -1, 10729, 10729, 10729, -1, + 10730, 10730, 10730, -1, 10731, 10731, 10731, -1, + 10732, 10732, 10732, -1, 10733, 10733, 10733, -1, + 10734, 10734, 10734, -1, 10735, 10735, 10735, -1, + 10736, 10736, 10736, -1, 10737, 10737, 10737, -1, + 10738, 10738, 10738, -1, 10739, 10739, 10739, -1, + 10740, 10740, 10740, -1, 10741, 10741, 10741, -1, + 10742, 10742, 10742, -1, 10743, 10743, 10743, -1, + 10744, 10744, 10744, -1, 10745, 10745, 10745, -1, + 10746, 10746, 10746, -1, 10747, 10747, 10747, -1, + 10748, 10748, 10748, -1, 10749, 10749, 10749, -1, + 10750, 10750, 10750, -1, 10751, 10751, 10751, -1, + 10752, 10752, 10752, -1, 10753, 10753, 10753, -1, + 10754, 10754, 10754, -1, 10755, 10755, 10755, -1, + 10756, 10756, 10756, -1, 10757, 10757, 10757, -1, + 10758, 10758, 10758, -1, 10759, 10759, 10759, -1, + 10760, 10760, 10760, -1, 10761, 10761, 10761, -1, + 10762, 10762, 10762, -1, 10763, 10763, 10763, -1, + 10764, 10764, 10764, -1, 10765, 10765, 10765, -1, + 10766, 10766, 10766, -1, 10767, 10767, 10767, -1, + 10768, 10768, 10768, -1, 10769, 10769, 10769, -1, + 10770, 10770, 10770, -1, 10771, 10771, 10771, -1, + 10772, 10772, 10772, -1, 10773, 10773, 10773, -1, + 10774, 10774, 10774, -1, 10775, 10775, 10775, -1, + 10776, 10776, 10776, -1, 10777, 10777, 10777, -1, + 10778, 10778, 10778, -1, 10779, 10779, 10779, -1, + 10780, 10780, 10780, -1, 10781, 10781, 10781, -1, + 10782, 10782, 10782, -1, 10783, 10783, 10783, -1, + 10784, 10784, 10784, -1, 10785, 10785, 10785, -1, + 10786, 10786, 10786, -1, 10787, 10787, 10787, -1, + 10788, 10788, 10788, -1, 10789, 10789, 10789, -1, + 10790, 10790, 10790, -1, 10791, 10791, 10791, -1, + 10792, 10792, 10792, -1, 10793, 10793, 10793, -1, + 10794, 10794, 10794, -1, 10795, 10795, 10795, -1, + 10796, 10796, 10796, -1, 10797, 10797, 10797, -1, + 10798, 10798, 10798, -1, 10799, 10799, 10799, -1, + 10800, 10800, 10800, -1, 10801, 10801, 10801, -1, + 10802, 10802, 10802, -1, 10803, 10803, 10803, -1, + 10804, 10804, 10804, -1, 10805, 10805, 10805, -1, + 10806, 10806, 10806, -1, 10807, 10807, 10807, -1, + 10808, 10808, 10808, -1, 10809, 10809, 10809, -1, + 10810, 10810, 10810, -1, 10811, 10811, 10811, -1, + 10812, 10812, 10812, -1, 10813, 10813, 10813, -1, + 10814, 10814, 10814, -1, 10815, 10815, 10815, -1, + 10816, 10816, 10816, -1, 10817, 10817, 10817, -1, + 10818, 10818, 10818, -1, 10819, 10819, 10819, -1, + 10820, 10820, 10820, -1, 10821, 10821, 10821, -1, + 10822, 10822, 10822, -1, 10823, 10823, 10823, -1, + 10824, 10824, 10824, -1, 10825, 10825, 10825, -1, + 10826, 10826, 10826, -1, 10827, 10827, 10827, -1, + 10828, 10828, 10828, -1, 10829, 10829, 10829, -1, + 10830, 10830, 10830, -1, 10831, 10831, 10831, -1, + 10832, 10832, 10832, -1, 10833, 10833, 10833, -1, + 10834, 10834, 10834, -1, 10835, 10835, 10835, -1, + 10836, 10836, 10836, -1, 10837, 10837, 10837, -1, + 10838, 10838, 10838, -1, 10839, 10839, 10839, -1, + 10840, 10840, 10840, -1, 10841, 10841, 10841, -1, + 10842, 10842, 10842, -1, 10843, 10843, 10843, -1, + 10844, 10844, 10844, -1, 10845, 10845, 10845, -1, + 10846, 10846, 10846, -1, 10847, 10847, 10847, -1, + 10848, 10848, 10848, -1, 10849, 10849, 10849, -1, + 10850, 10850, 10850, -1, 10851, 10851, 10851, -1, + 10852, 10852, 10852, -1, 10853, 10853, 10853, -1, + 10854, 10854, 10854, -1, 10855, 10855, 10855, -1, + 10856, 10856, 10856, -1, 10857, 10857, 10857, -1, + 10858, 10858, 10858, -1, 10859, 10859, 10859, -1, + 10860, 10860, 10860, -1, 10861, 10861, 10861, -1, + 10862, 10862, 10862, -1, 10863, 10863, 10863, -1, + 10864, 10864, 10864, -1, 10865, 10865, 10865, -1, + 10866, 10866, 10866, -1, 10867, 10867, 10867, -1, + 10868, 10868, 10868, -1, 10869, 10869, 10869, -1, + 10870, 10870, 10870, -1, 10871, 10871, 10871, -1, + 10872, 10872, 10872, -1, 10873, 10873, 10873, -1, + 10874, 10874, 10874, -1, 10875, 10875, 10875, -1, + 10876, 10876, 10876, -1, 10877, 10877, 10877, -1, + 10878, 10878, 10878, -1, 10879, 10879, 10879, -1, + 10880, 10880, 10880, -1, 10881, 10881, 10881, -1, + 10882, 10882, 10882, -1, 10883, 10883, 10883, -1, + 10884, 10884, 10884, -1, 10885, 10885, 10885, -1, + 10886, 10886, 10886, -1, 10887, 10887, 10887, -1, + 10888, 10888, 10888, -1, 10889, 10889, 10889, -1, + 10890, 10890, 10890, -1, 10891, 10891, 10891, -1, + 10892, 10892, 10892, -1, 10893, 10893, 10893, -1, + 10894, 10894, 10894, -1, 10895, 10895, 10895, -1, + 10896, 10896, 10896, -1, 10897, 10897, 10897, -1, + 10898, 10898, 10898, -1, 10899, 10899, 10899, -1, + 10900, 10900, 10900, -1, 10901, 10901, 10901, -1, + 10902, 10902, 10902, -1, 10903, 10903, 10903, -1, + 10904, 10904, 10904, -1, 10905, 10905, 10905, -1, + 10906, 10906, 10906, -1, 10907, 10907, 10907, -1, + 10908, 10908, 10908, -1, 10909, 10909, 10909, -1, + 10910, 10910, 10910, -1, 10911, 10911, 10911, -1, + 10912, 10912, 10912, -1, 10913, 10913, 10913, -1, + 10914, 10914, 10914, -1, 10915, 10915, 10915, -1, + 10916, 10916, 10916, -1, 10917, 10917, 10917, -1, + 10918, 10918, 10918, -1, 10919, 10919, 10919, -1, + 10920, 10920, 10920, -1, 10921, 10921, 10921, -1, + 10922, 10922, 10922, -1, 10923, 10923, 10923, -1, + 10924, 10924, 10924, -1, 10925, 10925, 10925, -1, + 10926, 10926, 10926, -1, 10927, 10927, 10927, -1, + 10928, 10928, 10928, -1, 10929, 10929, 10929, -1, + 10930, 10930, 10930, -1, 10931, 10931, 10931, -1, + 10932, 10932, 10932, -1, 10933, 10933, 10933, -1, + 10934, 10934, 10934, -1, 10935, 10935, 10935, -1, + 10936, 10936, 10936, -1, 10937, 10937, 10937, -1, + 10938, 10938, 10938, -1, 10939, 10939, 10939, -1, + 10940, 10940, 10940, -1, 10941, 10941, 10941, -1, + 10942, 10942, 10942, -1, 10943, 10943, 10943, -1, + 10944, 10944, 10944, -1, 10945, 10945, 10945, -1, + 10946, 10946, 10946, -1, 10947, 10947, 10947, -1, + 10948, 10948, 10948, -1, 10949, 10949, 10949, -1, + 10950, 10950, 10950, -1, 10951, 10951, 10951, -1, + 10952, 10952, 10952, -1, 10953, 10953, 10953, -1, + 10954, 10954, 10954, -1, 10955, 10955, 10955, -1, + 10956, 10956, 10956, -1, 10957, 10957, 10957, -1, + 10958, 10958, 10958, -1, 10959, 10959, 10959, -1, + 10960, 10960, 10960, -1, 10961, 10961, 10961, -1, + 10962, 10962, 10962, -1, 10963, 10963, 10963, -1, + 10964, 10964, 10964, -1, 10965, 10965, 10965, -1, + 10966, 10966, 10966, -1, 10967, 10967, 10967, -1, + 10968, 10968, 10968, -1, 10969, 10969, 10969, -1, + 10970, 10970, 10970, -1, 10971, 10971, 10971, -1, + 10972, 10972, 10972, -1, 10973, 10973, 10973, -1, + 10974, 10974, 10974, -1, 10975, 10975, 10975, -1, + 10976, 10976, 10976, -1, 10977, 10977, 10977, -1, + 10978, 10978, 10978, -1, 10979, 10979, 10979, -1, + 10980, 10980, 10980, -1, 10981, 10981, 10981, -1, + 10982, 10982, 10982, -1, 10983, 10983, 10983, -1, + 10984, 10984, 10984, -1, 10985, 10985, 10985, -1, + 10986, 10986, 10986, -1, 10987, 10987, 10987, -1, + 10988, 10988, 10988, -1, 10989, 10989, 10989, -1, + 10990, 10990, 10990, -1, 10991, 10991, 10991, -1, + 10992, 10992, 10992, -1, 10993, 10993, 10993, -1, + 10994, 10994, 10994, -1, 10995, 10995, 10995, -1, + 10996, 10996, 10996, -1, 10997, 10997, 10997, -1, + 10998, 10998, 10998, -1, 10999, 10999, 10999, -1, + 11000, 11000, 11000, -1, 11001, 11001, 11001, -1, + 11002, 11002, 11002, -1, 11003, 11003, 11003, -1, + 11004, 11004, 11004, -1, 11005, 11005, 11005, -1, + 11006, 11006, 11006, -1, 11007, 11007, 11007, -1, + 11008, 11008, 11008, -1, 11009, 11009, 11009, -1, + 11010, 11010, 11010, -1, 11011, 11011, 11011, -1, + 11012, 11012, 11012, -1, 11013, 11013, 11013, -1, + 11014, 11014, 11014, -1, 11015, 11015, 11015, -1, + 11016, 11016, 11016, -1, 11017, 11017, 11017, -1, + 11018, 11018, 11018, -1, 11019, 11019, 11019, -1, + 11020, 11020, 11020, -1, 11021, 11021, 11021, -1, + 11022, 11022, 11022, -1, 11023, 11023, 11023, -1, + 11024, 11024, 11024, -1, 11025, 11025, 11025, -1, + 11026, 11026, 11026, -1, 11027, 11027, 11027, -1, + 11028, 11028, 11028, -1, 11029, 11029, 11029, -1, + 11030, 11030, 11030, -1, 11031, 11031, 11031, -1, + 11032, 11032, 11032, -1, 11033, 11033, 11033, -1, + 11034, 11034, 11034, -1, 11035, 11035, 11035, -1, + 11036, 11036, 11036, -1, 11037, 11037, 11037, -1, + 11038, 11038, 11038, -1, 11039, 11039, 11039, -1, + 11040, 11040, 11040, -1, 11041, 11041, 11041, -1, + 11042, 11042, 11042, -1, 11043, 11043, 11043, -1, + 11044, 11044, 11044, -1, 11045, 11045, 11045, -1, + 11046, 11046, 11046, -1, 11047, 11047, 11047, -1, + 11048, 11048, 11048, -1, 11049, 11049, 11049, -1, + 11050, 11050, 11050, -1, 11051, 11051, 11051, -1, + 11052, 11052, 11052, -1, 11053, 11053, 11053, -1, + 11054, 11054, 11054, -1, 11055, 11055, 11055, -1, + 11056, 11056, 11056, -1, 11057, 11057, 11057, -1, + 11058, 11058, 11058, -1, 11059, 11059, 11059, -1, + 11060, 11060, 11060, -1, 11061, 11061, 11061, -1, + 11062, 11062, 11062, -1, 11063, 11063, 11063, -1, + 11064, 11064, 11064, -1, 11065, 11065, 11065, -1, + 11066, 11066, 11066, -1, 11067, 11067, 11067, -1, + 11068, 11068, 11068, -1, 11069, 11069, 11069, -1, + 11070, 11070, 11070, -1, 11071, 11071, 11071, -1, + 11072, 11072, 11072, -1, 11073, 11073, 11073, -1, + 11074, 11074, 11074, -1, 11075, 11075, 11075, -1, + 11076, 11076, 11076, -1, 11077, 11077, 11077, -1, + 11078, 11078, 11078, -1, 11079, 11079, 11079, -1, + 11080, 11080, 11080, -1, 11081, 11081, 11081, -1, + 11082, 11082, 11082, -1, 11083, 11083, 11083, -1, + 11084, 11084, 11084, -1, 11085, 11085, 11085, -1, + 11086, 11086, 11086, -1, 11087, 11087, 11087, -1, + 11088, 11088, 11088, -1, 11089, 11089, 11089, -1, + 11090, 11090, 11090, -1, 11091, 11091, 11091, -1, + 11092, 11092, 11092, -1, 11093, 11093, 11093, -1, + 11094, 11094, 11094, -1, 11095, 11095, 11095, -1, + 11096, 11096, 11096, -1, 11097, 11097, 11097, -1, + 11098, 11098, 11098, -1, 11099, 11099, 11099, -1, + 11100, 11100, 11100, -1, 11101, 11101, 11101, -1, + 11102, 11102, 11102, -1, 11103, 11103, 11103, -1, + 11104, 11104, 11104, -1, 11105, 11105, 11105, -1, + 11106, 11106, 11106, -1, 11107, 11107, 11107, -1, + 11108, 11108, 11108, -1, 11109, 11109, 11109, -1, + 11110, 11110, 11110, -1, 11111, 11111, 11111, -1, + 11112, 11112, 11112, -1, 11113, 11113, 11113, -1, + 11114, 11114, 11114, -1, 11115, 11115, 11115, -1, + 11116, 11116, 11116, -1, 11117, 11117, 11117, -1, + 11118, 11118, 11118, -1, 11119, 11119, 11119, -1, + 11120, 11120, 11120, -1, 11121, 11121, 11121, -1, + 11122, 11122, 11122, -1, 11123, 11123, 11123, -1, + 11124, 11124, 11124, -1, 11125, 11125, 11125, -1, + 11126, 11126, 11126, -1, 11127, 11127, 11127, -1, + 11128, 11128, 11128, -1, 11129, 11129, 11129, -1, + 11130, 11130, 11130, -1, 11131, 11131, 11131, -1, + 11132, 11132, 11132, -1, 11133, 11133, 11133, -1, + 11134, 11134, 11134, -1, 11135, 11135, 11135, -1, + 11136, 11136, 11136, -1, 11137, 11137, 11137, -1, + 11138, 11138, 11138, -1, 11139, 11139, 11139, -1, + 11140, 11140, 11140, -1, 11141, 11141, 11141, -1, + 11142, 11142, 11142, -1, 11143, 11143, 11143, -1, + 11144, 11144, 11144, -1, 11145, 11145, 11145, -1, + 11146, 11146, 11146, -1, 11147, 11147, 11147, -1, + 11148, 11148, 11148, -1, 11149, 11149, 11149, -1, + 11150, 11150, 11150, -1, 11151, 11151, 11151, -1, + 11152, 11152, 11152, -1, 11153, 11153, 11153, -1, + 11154, 11154, 11154, -1, 11155, 11155, 11155, -1, + 11156, 11156, 11156, -1, 11157, 11157, 11157, -1, + 11158, 11158, 11158, -1, 11159, 11159, 11159, -1, + 11160, 11160, 11160, -1, 11161, 11161, 11161, -1, + 11162, 11162, 11162, -1, 11163, 11163, 11163, -1, + 11164, 11164, 11164, -1, 11165, 11165, 11165, -1, + 11166, 11166, 11166, -1, 11167, 11167, 11167, -1, + 11168, 11168, 11168, -1, 11169, 11169, 11169, -1, + 11170, 11170, 11170, -1, 11171, 11171, 11171, -1, + 11172, 11172, 11172, -1, 11173, 11173, 11173, -1, + 11174, 11174, 11174, -1, 11175, 11175, 11175, -1, + 11176, 11176, 11176, -1, 11177, 11177, 11177, -1, + 11178, 11178, 11178, -1, 11179, 11179, 11179, -1, + 11180, 11180, 11180, -1, 11181, 11181, 11181, -1, + 11182, 11182, 11182, -1, 11183, 11183, 11183, -1, + 11184, 11184, 11184, -1, 11185, 11185, 11185, -1, + 11186, 11186, 11186, -1, 11187, 11187, 11187, -1, + 11188, 11188, 11188, -1, 11189, 11189, 11189, -1, + 11190, 11190, 11190, -1, 11191, 11191, 11191, -1, + 11192, 11192, 11192, -1, 11193, 11193, 11193, -1, + 11194, 11194, 11194, -1, 11195, 11195, 11195, -1, + 11196, 11196, 11196, -1, 11197, 11197, 11197, -1, + 11198, 11198, 11198, -1, 11199, 11199, 11199, -1, + 11200, 11200, 11200, -1, 11201, 11201, 11201, -1, + 11202, 11202, 11202, -1, 11203, 11203, 11203, -1, + 11204, 11204, 11204, -1, 11205, 11205, 11205, -1, + 11206, 11206, 11206, -1, 11207, 11207, 11207, -1, + 11208, 11208, 11208, -1, 11209, 11209, 11209, -1, + 11210, 11210, 11210, -1, 11211, 11211, 11211, -1, + 11212, 11212, 11212, -1, 11213, 11213, 11213, -1, + 11214, 11214, 11214, -1, 11215, 11215, 11215, -1, + 11216, 11216, 11216, -1, 11217, 11217, 11217, -1, + 11218, 11218, 11218, -1, 11219, 11219, 11219, -1, + 11220, 11220, 11220, -1, 11221, 11221, 11221, -1, + 11222, 11222, 11222, -1, 11223, 11223, 11223, -1, + 11224, 11224, 11224, -1, 11225, 11225, 11225, -1, + 11226, 11226, 11226, -1, 11227, 11227, 11227, -1, + 11228, 11228, 11228, -1, 11229, 11229, 11229, -1, + 11230, 11230, 11230, -1, 11231, 11231, 11231, -1, + 11232, 11232, 11232, -1, 11233, 11233, 11233, -1, + 11234, 11234, 11234, -1, 11235, 11235, 11235, -1, + 11236, 11236, 11236, -1, 11237, 11237, 11237, -1, + 11238, 11238, 11238, -1, 11239, 11239, 11239, -1, + 11240, 11240, 11240, -1, 11241, 11241, 11241, -1, + 11242, 11242, 11242, -1, 11243, 11243, 11243, -1, + 11244, 11244, 11244, -1, 11245, 11245, 11245, -1, + 11246, 11246, 11246, -1, 11247, 11247, 11247, -1, + 11248, 11248, 11248, -1, 11249, 11249, 11249, -1, + 11250, 11250, 11250, -1, 11251, 11251, 11251, -1, + 11252, 11252, 11252, -1, 11253, 11253, 11253, -1, + 11254, 11254, 11254, -1, 11255, 11255, 11255, -1, + 11256, 11256, 11256, -1, 11257, 11257, 11257, -1, + 11258, 11258, 11258, -1, 11259, 11259, 11259, -1, + 11260, 11260, 11260, -1, 11261, 11261, 11261, -1, + 11262, 11262, 11262, -1, 11263, 11263, 11263, -1, + 11264, 11264, 11264, -1, 11265, 11265, 11265, -1, + 11266, 11266, 11266, -1, 11267, 11267, 11267, -1, + 11268, 11268, 11268, -1, 11269, 11269, 11269, -1, + 11270, 11270, 11270, -1, 11271, 11271, 11271, -1, + 11272, 11272, 11272, -1, 11273, 11273, 11273, -1, + 11274, 11274, 11274, -1, 11275, 11275, 11275, -1, + 11276, 11276, 11276, -1, 11277, 11277, 11277, -1, + 11278, 11278, 11278, -1, 11279, 11279, 11279, -1, + 11280, 11280, 11280, -1, 11281, 11281, 11281, -1, + 11282, 11282, 11282, -1, 11283, 11283, 11283, -1, + 11284, 11284, 11284, -1, 11285, 11285, 11285, -1, + 11286, 11286, 11286, -1, 11287, 11287, 11287, -1, + 11288, 11288, 11288, -1, 11289, 11289, 11289, -1, + 11290, 11290, 11290, -1, 11291, 11291, 11291, -1, + 11292, 11292, 11292, -1, 11293, 11293, 11293, -1, + 11294, 11294, 11294, -1, 11295, 11295, 11295, -1, + 11296, 11296, 11296, -1, 11297, 11297, 11297, -1, + 11298, 11298, 11298, -1, 11299, 11299, 11299, -1, + 11300, 11300, 11300, -1, 11301, 11301, 11301, -1, + 11302, 11302, 11302, -1, 11303, 11303, 11303, -1, + 11304, 11304, 11304, -1, 11305, 11305, 11305, -1, + 11306, 11306, 11306, -1, 11307, 11307, 11307, -1, + 11308, 11308, 11308, -1, 11309, 11309, 11309, -1, + 11310, 11310, 11310, -1, 11311, 11311, 11311, -1, + 11312, 11312, 11312, -1, 11313, 11313, 11313, -1, + 11314, 11314, 11314, -1, 11315, 11315, 11315, -1, + 11316, 11316, 11316, -1, 11317, 11317, 11317, -1, + 11318, 11318, 11318, -1, 11319, 11319, 11319, -1, + 11320, 11320, 11320, -1, 11321, 11321, 11321, -1, + 11322, 11322, 11322, -1, 11323, 11323, 11323, -1, + 11324, 11324, 11324, -1, 11325, 11325, 11325, -1, + 11326, 11326, 11326, -1, 11327, 11327, 11327, -1, + 11328, 11328, 11328, -1, 11329, 11329, 11329, -1, + 11330, 11330, 11330, -1, 11331, 11331, 11331, -1, + 11332, 11332, 11332, -1, 11333, 11333, 11333, -1, + 11334, 11334, 11334, -1, 11335, 11335, 11335, -1, + 11336, 11336, 11336, -1, 11337, 11337, 11337, -1, + 11338, 11338, 11338, -1, 11339, 11339, 11339, -1, + 11340, 11340, 11340, -1, 11341, 11341, 11341, -1, + 11342, 11342, 11342, -1, 11343, 11343, 11343, -1, + 11344, 11344, 11344, -1, 11345, 11345, 11345, -1, + 11346, 11346, 11346, -1, 11347, 11347, 11347, -1, + 11348, 11348, 11348, -1, 11349, 11349, 11349, -1, + 11350, 11350, 11350, -1, 11351, 11351, 11351, -1, + 11352, 11352, 11352, -1, 11353, 11353, 11353, -1, + 11354, 11354, 11354, -1, 11355, 11355, 11355, -1, + 11356, 11356, 11356, -1, 11357, 11357, 11357, -1, + 11358, 11358, 11358, -1, 11359, 11359, 11359, -1, + 11360, 11360, 11360, -1, 11361, 11361, 11361, -1, + 11362, 11362, 11362, -1, 11363, 11363, 11363, -1, + 11364, 11364, 11364, -1, 11365, 11365, 11365, -1, + 11366, 11366, 11366, -1, 11367, 11367, 11367, -1, + 11368, 11368, 11368, -1, 11369, 11369, 11369, -1, + 11370, 11370, 11370, -1, 11371, 11371, 11371, -1, + 11372, 11372, 11372, -1, 11373, 11373, 11373, -1, + 11374, 11374, 11374, -1, 11375, 11375, 11375, -1, + 11376, 11376, 11376, -1, 11377, 11377, 11377, -1, + 11378, 11378, 11378, -1, 11379, 11379, 11379, -1, + 11380, 11380, 11380, -1, 11381, 11381, 11381, -1, + 11382, 11382, 11382, -1, 11383, 11383, 11383, -1, + 11384, 11384, 11384, -1, 11385, 11385, 11385, -1, + 11386, 11386, 11386, -1, 11387, 11387, 11387, -1, + 11388, 11388, 11388, -1, 11389, 11389, 11389, -1, + 11390, 11390, 11390, -1, 11391, 11391, 11391, -1, + 11392, 11392, 11392, -1, 11393, 11393, 11393, -1, + 11394, 11394, 11394, -1, 11395, 11395, 11395, -1, + 11396, 11396, 11396, -1, 11397, 11397, 11397, -1, + 11398, 11398, 11398, -1, 11399, 11399, 11399, -1, + 11400, 11400, 11400, -1, 11401, 11401, 11401, -1, + 11402, 11402, 11402, -1, 11403, 11403, 11403, -1, + 11404, 11404, 11404, -1, 11405, 11405, 11405, -1, + 11406, 11406, 11406, -1, 11407, 11407, 11407, -1, + 11408, 11408, 11408, -1, 11409, 11409, 11409, -1, + 11410, 11410, 11410, -1, 11411, 11411, 11411, -1, + 11412, 11412, 11412, -1, 11413, 11413, 11413, -1, + 11414, 11414, 11414, -1, 11415, 11415, 11415, -1, + 11416, 11416, 11416, -1, 11417, 11417, 11417, -1, + 11418, 11418, 11418, -1, 11419, 11419, 11419, -1, + 11420, 11420, 11420, -1, 11421, 11421, 11421, -1, + 11422, 11422, 11422, -1, 11423, 11423, 11423, -1, + 11424, 11424, 11424, -1, 11425, 11425, 11425, -1, + 11426, 11426, 11426, -1, 11427, 11427, 11427, -1, + 11428, 11428, 11428, -1, 11429, 11429, 11429, -1, + 11430, 11430, 11430, -1, 11431, 11431, 11431, -1, + 11432, 11432, 11432, -1, 11433, 11433, 11433, -1, + 11434, 11434, 11434, -1, 11435, 11435, 11435, -1, + 11436, 11436, 11436, -1, 11437, 11437, 11437, -1, + 11438, 11438, 11438, -1, 11439, 11439, 11439, -1, + 11440, 11440, 11440, -1, 11441, 11441, 11441, -1, + 11442, 11442, 11442, -1, 11443, 11443, 11443, -1, + 11444, 11444, 11444, -1, 11445, 11445, 11445, -1, + 11446, 11446, 11446, -1, 11447, 11447, 11447, -1, + 11448, 11448, 11448, -1, 11449, 11449, 11449, -1, + 11450, 11450, 11450, -1, 11451, 11451, 11451, -1, + 11452, 11452, 11452, -1, 11453, 11453, 11453, -1, + 11454, 11454, 11454, -1, 11455, 11455, 11455, -1, + 11456, 11456, 11456, -1, 11457, 11457, 11457, -1, + 11458, 11458, 11458, -1, 11459, 11459, 11459, -1, + 11460, 11460, 11460, -1, 11461, 11461, 11461, -1, + 11462, 11462, 11462, -1, 11463, 11463, 11463, -1, + 11464, 11464, 11464, -1, 11465, 11465, 11465, -1, + 11466, 11466, 11466, -1, 11467, 11467, 11467, -1, + 11468, 11468, 11468, -1, 11469, 11469, 11469, -1, + 11470, 11470, 11470, -1, 11471, 11471, 11471, -1, + 11472, 11472, 11472, -1, 11473, 11473, 11473, -1, + 11474, 11474, 11474, -1, 11475, 11475, 11475, -1, + 11476, 11476, 11476, -1, 11477, 11477, 11477, -1, + 11478, 11478, 11478, -1, 11479, 11479, 11479, -1, + 11480, 11480, 11480, -1, 11481, 11481, 11481, -1, + 11482, 11482, 11482, -1, 11483, 11483, 11483, -1, + 11484, 11484, 11484, -1, 11485, 11485, 11485, -1, + 11486, 11486, 11486, -1, 11487, 11487, 11487, -1, + 11488, 11488, 11488, -1, 11489, 11489, 11489, -1, + 11490, 11490, 11490, -1, 11491, 11491, 11491, -1, + 11492, 11492, 11492, -1, 11493, 11493, 11493, -1, + 11494, 11494, 11494, -1, 11495, 11495, 11495, -1, + 11496, 11496, 11496, -1, 11497, 11497, 11497, -1, + 11498, 11498, 11498, -1, 11499, 11499, 11499, -1, + 11500, 11500, 11500, -1, 11501, 11501, 11501, -1, + 11502, 11502, 11502, -1, 11503, 11503, 11503, -1, + 11504, 11504, 11504, -1, 11505, 11505, 11505, -1, + 11506, 11506, 11506, -1, 11507, 11507, 11507, -1, + 11508, 11508, 11508, -1, 11509, 11509, 11509, -1, + 11510, 11510, 11510, -1, 11511, 11511, 11511, -1, + 11512, 11512, 11512, -1, 11513, 11513, 11513, -1, + 11514, 11514, 11514, -1, 11515, 11515, 11515, -1, + 11516, 11516, 11516, -1, 11517, 11517, 11517, -1, + 11518, 11518, 11518, -1, 11519, 11519, 11519, -1, + 11520, 11520, 11520, -1, 11521, 11521, 11521, -1, + 11522, 11522, 11522, -1, 11523, 11523, 11523, -1, + 11524, 11524, 11524, -1, 11525, 11525, 11525, -1, + 11526, 11526, 11526, -1, 11527, 11527, 11527, -1, + 11528, 11528, 11528, -1, 11529, 11529, 11529, -1, + 11530, 11530, 11530, -1, 11531, 11531, 11531, -1, + 11532, 11532, 11532, -1, 11533, 11533, 11533, -1, + 11534, 11534, 11534, -1, 11535, 11535, 11535, -1, + 11536, 11536, 11536, -1, 11537, 11537, 11537, -1, + 11538, 11538, 11538, -1, 11539, 11539, 11539, -1, + 11540, 11540, 11540, -1, 11541, 11541, 11541, -1, + 11542, 11542, 11542, -1, 11543, 11543, 11543, -1, + 11544, 11544, 11544, -1, 11545, 11545, 11545, -1, + 11546, 11546, 11546, -1, 11547, 11547, 11547, -1, + 11548, 11548, 11548, -1, 11549, 11549, 11549, -1, + 11550, 11550, 11550, -1, 11551, 11551, 11551, -1, + 11552, 11552, 11552, -1, 11553, 11553, 11553, -1, + 11554, 11554, 11554, -1, 11555, 11555, 11555, -1, + 11556, 11556, 11556, -1, 11557, 11557, 11557, -1, + 11558, 11558, 11558, -1, 11559, 11559, 11559, -1, + 11560, 11560, 11560, -1, 11561, 11561, 11561, -1, + 11562, 11562, 11562, -1, 11563, 11563, 11563, -1, + 11564, 11564, 11564, -1, 11565, 11565, 11565, -1, + 11566, 11566, 11566, -1, 11567, 11567, 11567, -1, + 11568, 11568, 11568, -1, 11569, 11569, 11569, -1, + 11570, 11570, 11570, -1, 11571, 11571, 11571, -1, + 11572, 11572, 11572, -1, 11573, 11573, 11573, -1, + 11574, 11574, 11574, -1, 11575, 11575, 11575, -1, + 11576, 11576, 11576, -1, 11577, 11577, 11577, -1, + 11578, 11578, 11578, -1, 11579, 11579, 11579, -1, + 11580, 11580, 11580, -1, 11581, 11581, 11581, -1, + 11582, 11582, 11582, -1, 11583, 11583, 11583, -1, + 11584, 11584, 11584, -1, 11585, 11585, 11585, -1, + 11586, 11586, 11586, -1, 11587, 11587, 11587, -1, + 11588, 11588, 11588, -1, 11589, 11589, 11589, -1, + 11590, 11590, 11590, -1, 11591, 11591, 11591, -1, + 11592, 11592, 11592, -1, 11593, 11593, 11593, -1, + 11594, 11594, 11594, -1, 11595, 11595, 11595, -1, + 11596, 11596, 11596, -1, 11597, 11597, 11597, -1, + 11598, 11598, 11598, -1, 11599, 11599, 11599, -1, + 11600, 11600, 11600, -1, 11601, 11601, 11601, -1, + 11602, 11602, 11602, -1, 11603, 11603, 11603, -1, + 11604, 11604, 11604, -1, 11605, 11605, 11605, -1, + 11606, 11606, 11606, -1, 11607, 11607, 11607, -1, + 11608, 11608, 11608, -1, 11609, 11609, 11609, -1, + 11610, 11610, 11610, -1, 11611, 11611, 11611, -1, + 11612, 11612, 11612, -1, 11613, 11613, 11613, -1, + 11614, 11614, 11614, -1, 11615, 11615, 11615, -1, + 11616, 11616, 11616, -1, 11617, 11617, 11617, -1, + 11618, 11618, 11618, -1, 11619, 11619, 11619, -1, + 11620, 11620, 11620, -1, 11621, 11621, 11621, -1, + 11622, 11622, 11622, -1, 11623, 11623, 11623, -1, + 11624, 11624, 11624, -1, 11625, 11625, 11625, -1, + 11626, 11626, 11626, -1, 11627, 11627, 11627, -1, + 11628, 11628, 11628, -1, 11629, 11629, 11629, -1, + 11630, 11630, 11630, -1, 11631, 11631, 11631, -1, + 11632, 11632, 11632, -1, 11633, 11633, 11633, -1, + 11634, 11634, 11634, -1, 11635, 11635, 11635, -1, + 11636, 11636, 11636, -1, 11637, 11637, 11637, -1, + 11638, 11638, 11638, -1, 11639, 11639, 11639, -1, + 11640, 11640, 11640, -1, 11641, 11641, 11641, -1, + 11642, 11642, 11642, -1, 11643, 11643, 11643, -1, + 11644, 11644, 11644, -1, 11645, 11645, 11645, -1, + 11646, 11646, 11646, -1, 11647, 11647, 11647, -1, + 11648, 11648, 11648, -1, 11649, 11649, 11649, -1, + 11650, 11650, 11650, -1, 11651, 11651, 11651, -1, + 11652, 11652, 11652, -1, 11653, 11653, 11653, -1, + 11654, 11654, 11654, -1, 11655, 11655, 11655, -1, + 11656, 11656, 11656, -1, 11657, 11657, 11657, -1, + 11658, 11658, 11658, -1, 11659, 11659, 11659, -1, + 11660, 11660, 11660, -1, 11661, 11661, 11661, -1, + 11662, 11662, 11662, -1, 11663, 11663, 11663, -1, + 11664, 11664, 11664, -1, 11665, 11665, 11665, -1, + 11666, 11666, 11666, -1, 11667, 11667, 11667, -1, + 11668, 11668, 11668, -1, 11669, 11669, 11669, -1, + 11670, 11670, 11670, -1, 11671, 11671, 11671, -1, + 11672, 11672, 11672, -1, 11673, 11673, 11673, -1, + 11674, 11674, 11674, -1, 11675, 11675, 11675, -1, + 11676, 11676, 11676, -1, 11677, 11677, 11677, -1, + 11678, 11678, 11678, -1, 11679, 11679, 11679, -1, + 11680, 11680, 11680, -1, 11681, 11681, 11681, -1, + 11682, 11682, 11682, -1, 11683, 11683, 11683, -1, + 11684, 11684, 11684, -1, 11685, 11685, 11685, -1, + 11686, 11686, 11686, -1, 11687, 11687, 11687, -1, + 11688, 11688, 11688, -1, 11689, 11689, 11689, -1, + 11690, 11690, 11690, -1, 11691, 11691, 11691, -1, + 11692, 11692, 11692, -1, 11693, 11693, 11693, -1, + 11694, 11694, 11694, -1, 11695, 11695, 11695, -1, + 11696, 11696, 11696, -1, 11697, 11697, 11697, -1, + 11698, 11698, 11698, -1, 11699, 11699, 11699, -1, + 11700, 11700, 11700, -1, 11701, 11701, 11701, -1, + 11702, 11702, 11702, -1, 11703, 11703, 11703, -1, + 11704, 11704, 11704, -1, 11705, 11705, 11705, -1, + 11706, 11706, 11706, -1, 11707, 11707, 11707, -1, + 11708, 11708, 11708, -1, 11709, 11709, 11709, -1, + 11710, 11710, 11710, -1, 11711, 11711, 11711, -1, + 11712, 11712, 11712, -1, 11713, 11713, 11713, -1, + 11714, 11714, 11714, -1, 11715, 11715, 11715, -1, + 11716, 11716, 11716, -1, 11717, 11717, 11717, -1, + 11718, 11718, 11718, -1, 11719, 11719, 11719, -1, + 11720, 11720, 11720, -1, 11721, 11721, 11721, -1, + 11722, 11722, 11722, -1, 11723, 11723, 11723, -1, + 11724, 11724, 11724, -1, 11725, 11725, 11725, -1, + 11726, 11726, 11726, -1, 11727, 11727, 11727, -1, + 11728, 11728, 11728, -1, 11729, 11729, 11729, -1, + 11730, 11730, 11730, -1, 11731, 11731, 11731, -1, + 11732, 11732, 11732, -1, 11733, 11733, 11733, -1, + 11734, 11734, 11734, -1, 11735, 11735, 11735, -1, + 11736, 11736, 11736, -1, 11737, 11737, 11737, -1, + 11738, 11738, 11738, -1, 11739, 11739, 11739, -1, + 11740, 11740, 11740, -1, 11741, 11741, 11741, -1, + 11742, 11742, 11742, -1, 11743, 11743, 11743, -1, + 11744, 11744, 11744, -1, 11745, 11745, 11745, -1, + 11746, 11746, 11746, -1, 11747, 11747, 11747, -1, + 11748, 11748, 11748, -1, 11749, 11749, 11749, -1, + 11750, 11750, 11750, -1, 11751, 11751, 11751, -1, + 11752, 11752, 11752, -1, 11753, 11753, 11753, -1, + 11754, 11754, 11754, -1, 11755, 11755, 11755, -1, + 11756, 11756, 11756, -1, 11757, 11757, 11757, -1, + 11758, 11758, 11758, -1, 11759, 11759, 11759, -1, + 11760, 11760, 11760, -1, 11761, 11761, 11761, -1, + 11762, 11762, 11762, -1, 11763, 11763, 11763, -1, + 11764, 11764, 11764, -1, 11765, 11765, 11765, -1, + 11766, 11766, 11766, -1, 11767, 11767, 11767, -1, + 11768, 11768, 11768, -1, 11769, 11769, 11769, -1, + 11770, 11770, 11770, -1, 11771, 11771, 11771, -1, + 11772, 11772, 11772, -1, 11773, 11773, 11773, -1, + 11774, 11774, 11774, -1, 11775, 11775, 11775, -1, + 11776, 11776, 11776, -1, 11777, 11777, 11777, -1, + 11778, 11778, 11778, -1, 11779, 11779, 11779, -1, + 11780, 11780, 11780, -1, 11781, 11781, 11781, -1, + 11782, 11782, 11782, -1, 11783, 11783, 11783, -1, + 11784, 11784, 11784, -1, 11785, 11785, 11785, -1, + 11786, 11786, 11786, -1, 11787, 11787, 11787, -1, + 11788, 11788, 11788, -1, 11789, 11789, 11789, -1, + 11790, 11790, 11790, -1, 11791, 11791, 11791, -1, + 11792, 11792, 11792, -1, 11793, 11793, 11793, -1, + 11794, 11794, 11794, -1, 11795, 11795, 11795, -1, + 11796, 11796, 11796, -1, 11797, 11797, 11797, -1, + 11798, 11798, 11798, -1, 11799, 11799, 11799, -1, + 11800, 11800, 11800, -1, 11801, 11801, 11801, -1, + 11802, 11802, 11802, -1, 11803, 11803, 11803, -1, + 11804, 11804, 11804, -1, 11805, 11805, 11805, -1, + 11806, 11806, 11806, -1, 11807, 11807, 11807, -1, + 11808, 11808, 11808, -1, 11809, 11809, 11809, -1, + 11810, 11810, 11810, -1, 11811, 11811, 11811, -1, + 11812, 11812, 11812, -1, 11813, 11813, 11813, -1, + 11814, 11814, 11814, -1, 11815, 11815, 11815, -1, + 11816, 11816, 11816, -1, 11817, 11817, 11817, -1, + 11818, 11818, 11818, -1, 11819, 11819, 11819, -1, + 11820, 11820, 11820, -1, 11821, 11821, 11821, -1, + 11822, 11822, 11822, -1, 11823, 11823, 11823, -1, + 11824, 11824, 11824, -1, 11825, 11825, 11825, -1, + 11826, 11826, 11826, -1, 11827, 11827, 11827, -1, + 11828, 11828, 11828, -1, 11829, 11829, 11829, -1, + 11830, 11830, 11830, -1, 11831, 11831, 11831, -1, + 11832, 11832, 11832, -1, 11833, 11833, 11833, -1, + 11834, 11834, 11834, -1, 11835, 11835, 11835, -1, + 11836, 11836, 11836, -1, 11837, 11837, 11837, -1, + 11838, 11838, 11838, -1, 11839, 11839, 11839, -1, + 11840, 11840, 11840, -1, 11841, 11841, 11841, -1, + 11842, 11842, 11842, -1, 11843, 11843, 11843, -1, + 11844, 11844, 11844, -1, 11845, 11845, 11845, -1, + 11846, 11846, 11846, -1, 11847, 11847, 11847, -1, + 11848, 11848, 11848, -1, 11849, 11849, 11849, -1, + 11850, 11850, 11850, -1, 11851, 11851, 11851, -1, + 11852, 11852, 11852, -1, 11853, 11853, 11853, -1, + 11854, 11854, 11854, -1, 11855, 11855, 11855, -1, + 11856, 11856, 11856, -1, 11857, 11857, 11857, -1, + 11858, 11858, 11858, -1, 11859, 11859, 11859, -1, + 11860, 11860, 11860, -1, 11861, 11861, 11861, -1, + 11862, 11862, 11862, -1, 11863, 11863, 11863, -1, + 11864, 11864, 11864, -1, 11865, 11865, 11865, -1, + 11866, 11866, 11866, -1, 11867, 11867, 11867, -1, + 11868, 11868, 11868, -1, 11869, 11869, 11869, -1, + 11870, 11870, 11870, -1, 11871, 11871, 11871, -1, + 11872, 11872, 11872, -1, 11873, 11873, 11873, -1, + 11874, 11874, 11874, -1, 11875, 11875, 11875, -1, + 11876, 11876, 11876, -1, 11877, 11877, 11877, -1, + 11878, 11878, 11878, -1, 11879, 11879, 11879, -1, + 11880, 11880, 11880, -1, 11881, 11881, 11881, -1, + 11882, 11882, 11882, -1, 11883, 11883, 11883, -1, + 11884, 11884, 11884, -1, 11885, 11885, 11885, -1, + 11886, 11886, 11886, -1, 11887, 11887, 11887, -1, + 11888, 11888, 11888, -1, 11889, 11889, 11889, -1, + 11890, 11890, 11890, -1, 11891, 11891, 11891, -1, + 11892, 11892, 11892, -1, 11893, 11893, 11893, -1, + 11894, 11894, 11894, -1, 11895, 11895, 11895, -1, + 11896, 11896, 11896, -1, 11897, 11897, 11897, -1, + 11898, 11898, 11898, -1, 11899, 11899, 11899, -1, + 11900, 11900, 11900, -1, 11901, 11901, 11901, -1, + 11902, 11902, 11902, -1, 11903, 11903, 11903, -1, + 11904, 11904, 11904, -1, 11905, 11905, 11905, -1, + 11906, 11906, 11906, -1, 11907, 11907, 11907, -1, + 11908, 11908, 11908, -1, 11909, 11909, 11909, -1, + 11910, 11910, 11910, -1, 11911, 11911, 11911, -1, + 11912, 11912, 11912, -1, 11913, 11913, 11913, -1, + 11914, 11914, 11914, -1, 11915, 11915, 11915, -1, + 11916, 11916, 11916, -1, 11917, 11917, 11917, -1, + 11918, 11918, 11918, -1, 11919, 11919, 11919, -1, + 11920, 11920, 11920, -1, 11921, 11921, 11921, -1, + 11922, 11922, 11922, -1, 11923, 11923, 11923, -1, + 11924, 11924, 11924, -1, 11925, 11925, 11925, -1, + 11926, 11926, 11926, -1, 11927, 11927, 11927, -1, + 11928, 11928, 11928, -1, 11929, 11929, 11929, -1, + 11930, 11930, 11930, -1, 11931, 11931, 11931, -1, + 11932, 11932, 11932, -1, 11933, 11933, 11933, -1, + 11934, 11934, 11934, -1, 11935, 11935, 11935, -1, + 11936, 11936, 11936, -1, 11937, 11937, 11937, -1, + 11938, 11938, 11938, -1, 11939, 11939, 11939, -1, + 11940, 11940, 11940, -1, 11941, 11941, 11941, -1, + 11942, 11942, 11942, -1, 11943, 11943, 11943, -1, + 11944, 11944, 11944, -1, 11945, 11945, 11945, -1, + 11946, 11946, 11946, -1, 11947, 11947, 11947, -1, + 11948, 11948, 11948, -1, 11949, 11949, 11949, -1, + 11950, 11950, 11950, -1, 11951, 11951, 11951, -1, + 11952, 11952, 11952, -1, 11953, 11953, 11953, -1, + 11954, 11954, 11954, -1, 11955, 11955, 11955, -1, + 11956, 11956, 11956, -1, 11957, 11957, 11957, -1, + 11958, 11958, 11958, -1, 11959, 11959, 11959, -1, + 11960, 11960, 11960, -1, 11961, 11961, 11961, -1, + 11962, 11962, 11962, -1, 11963, 11963, 11963, -1, + 11964, 11964, 11964, -1, 11965, 11965, 11965, -1, + 11966, 11966, 11966, -1, 11967, 11967, 11967, -1, + 11968, 11968, 11968, -1, 11969, 11969, 11969, -1, + 11970, 11970, 11970, -1, 11971, 11971, 11971, -1, + 11972, 11972, 11972, -1, 11973, 11973, 11973, -1, + 11974, 11974, 11974, -1, 11975, 11975, 11975, -1, + 11976, 11976, 11976, -1, 11977, 11977, 11977, -1, + 11978, 11978, 11978, -1, 11979, 11979, 11979, -1, + 11980, 11980, 11980, -1, 11981, 11981, 11981, -1, + 11982, 11982, 11982, -1, 11983, 11983, 11983, -1, + 11984, 11984, 11984, -1, 11985, 11985, 11985, -1, + 11986, 11986, 11986, -1, 11987, 11987, 11987, -1, + 11988, 11988, 11988, -1, 11989, 11989, 11989, -1, + 11990, 11990, 11990, -1, 11991, 11991, 11991, -1, + 11992, 11992, 11992, -1, 11993, 11993, 11993, -1, + 11994, 11994, 11994, -1, 11995, 11995, 11995, -1, + 11996, 11996, 11996, -1, 11997, 11997, 11997, -1, + 11998, 11998, 11998, -1, 11999, 11999, 11999, -1, + 12000, 12000, 12000, -1, 12001, 12001, 12001, -1, + 12002, 12002, 12002, -1, 12003, 12003, 12003, -1, + 12004, 12004, 12004, -1, 12005, 12005, 12005, -1, + 12006, 12006, 12006, -1, 12007, 12007, 12007, -1, + 12008, 12008, 12008, -1, 12009, 12009, 12009, -1, + 12010, 12010, 12010, -1, 12011, 12011, 12011, -1, + 12012, 12012, 12012, -1, 12013, 12013, 12013, -1, + 12014, 12014, 12014, -1, 12015, 12015, 12015, -1, + 12016, 12016, 12016, -1, 12017, 12017, 12017, -1, + 12018, 12018, 12018, -1, 12019, 12019, 12019, -1, + 12020, 12020, 12020, -1, 12021, 12021, 12021, -1, + 12022, 12022, 12022, -1, 12023, 12023, 12023, -1, + 12024, 12024, 12024, -1, 12025, 12025, 12025, -1, + 12026, 12026, 12026, -1, 12027, 12027, 12027, -1, + 12028, 12028, 12028, -1, 12029, 12029, 12029, -1, + 12030, 12030, 12030, -1, 12031, 12031, 12031, -1, + 12032, 12032, 12032, -1, 12033, 12033, 12033, -1, + 12034, 12034, 12034, -1, 12035, 12035, 12035, -1, + 12036, 12036, 12036, -1, 12037, 12037, 12037, -1, + 12038, 12038, 12038, -1, 12039, 12039, 12039, -1, + 12040, 12040, 12040, -1, 12041, 12041, 12041, -1, + 12042, 12042, 12042, -1, 12043, 12043, 12043, -1, + 12044, 12044, 12044, -1, 12045, 12045, 12045, -1, + 12046, 12046, 12046, -1, 12047, 12047, 12047, -1, + 12048, 12048, 12048, -1, 12049, 12049, 12049, -1, + 12050, 12050, 12050, -1, 12051, 12051, 12051, -1, + 12052, 12052, 12052, -1, 12053, 12053, 12053, -1, + 12054, 12054, 12054, -1, 12055, 12055, 12055, -1, + 12056, 12056, 12056, -1, 12057, 12057, 12057, -1, + 12058, 12058, 12058, -1, 12059, 12059, 12059, -1, + 12060, 12060, 12060, -1, 12061, 12061, 12061, -1, + 12062, 12062, 12062, -1, 12063, 12063, 12063, -1, + 12064, 12064, 12064, -1, 12065, 12065, 12065, -1, + 12066, 12066, 12066, -1, 12067, 12067, 12067, -1, + 12068, 12068, 12068, -1, 12069, 12069, 12069, -1, + 12070, 12070, 12070, -1, 12071, 12071, 12071, -1, + 12072, 12072, 12072, -1, 12073, 12073, 12073, -1, + 12074, 12074, 12074, -1, 12075, 12075, 12075, -1, + 12076, 12076, 12076, -1, 12077, 12077, 12077, -1, + 12078, 12078, 12078, -1, 12079, 12079, 12079, -1, + 12080, 12080, 12080, -1, 12081, 12081, 12081, -1, + 12082, 12082, 12082, -1, 12083, 12083, 12083, -1, + 12084, 12084, 12084, -1, 12085, 12085, 12085, -1, + 12086, 12086, 12086, -1, 12087, 12087, 12087, -1, + 12088, 12088, 12088, -1, 12089, 12089, 12089, -1, + 12090, 12090, 12090, -1, 12091, 12091, 12091, -1, + 12092, 12092, 12092, -1, 12093, 12093, 12093, -1, + 12094, 12094, 12094, -1, 12095, 12095, 12095, -1, + 12096, 12096, 12096, -1, 12097, 12097, 12097, -1, + 12098, 12098, 12098, -1, 12099, 12099, 12099, -1, + 12100, 12100, 12100, -1, 12101, 12101, 12101, -1, + 12102, 12102, 12102, -1, 12103, 12103, 12103, -1, + 12104, 12104, 12104, -1, 12105, 12105, 12105, -1, + 12106, 12106, 12106, -1, 12107, 12107, 12107, -1, + 12108, 12108, 12108, -1, 12109, 12109, 12109, -1, + 12110, 12110, 12110, -1, 12111, 12111, 12111, -1, + 12112, 12112, 12112, -1, 12113, 12113, 12113, -1, + 12114, 12114, 12114, -1, 12115, 12115, 12115, -1, + 12116, 12116, 12116, -1, 12117, 12117, 12117, -1, + 12118, 12118, 12118, -1, 12119, 12119, 12119, -1, + 12120, 12120, 12120, -1, 12121, 12121, 12121, -1, + 12122, 12122, 12122, -1, 12123, 12123, 12123, -1, + 12124, 12124, 12124, -1, 12125, 12125, 12125, -1, + 12126, 12126, 12126, -1, 12127, 12127, 12127, -1, + 12128, 12128, 12128, -1, 12129, 12129, 12129, -1, + 12130, 12130, 12130, -1, 12131, 12131, 12131, -1, + 12132, 12132, 12132, -1, 12133, 12133, 12133, -1, + 12134, 12134, 12134, -1, 12135, 12135, 12135, -1, + 12136, 12136, 12136, -1, 12137, 12137, 12137, -1, + 12138, 12138, 12138, -1, 12139, 12139, 12139, -1, + 12140, 12140, 12140, -1, 12141, 12141, 12141, -1, + 12142, 12142, 12142, -1, 12143, 12143, 12143, -1, + 12144, 12144, 12144, -1, 12145, 12145, 12145, -1, + 12146, 12146, 12146, -1, 12147, 12147, 12147, -1, + 12148, 12148, 12148, -1, 12149, 12149, 12149, -1, + 12150, 12150, 12150, -1, 12151, 12151, 12151, -1, + 12152, 12152, 12152, -1, 12153, 12153, 12153, -1, + 12154, 12154, 12154, -1, 12155, 12155, 12155, -1, + 12156, 12156, 12156, -1, 12157, 12157, 12157, -1, + 12158, 12158, 12158, -1, 12159, 12159, 12159, -1, + 12160, 12160, 12160, -1, 12161, 12161, 12161, -1, + 12162, 12162, 12162, -1, 12163, 12163, 12163, -1, + 12164, 12164, 12164, -1, 12165, 12165, 12165, -1, + 12166, 12166, 12166, -1, 12167, 12167, 12167, -1, + 12168, 12168, 12168, -1, 12169, 12169, 12169, -1, + 12170, 12170, 12170, -1, 12171, 12171, 12171, -1, + 12172, 12172, 12172, -1, 12173, 12173, 12173, -1, + 12174, 12174, 12174, -1, 12175, 12175, 12175, -1, + 12176, 12176, 12176, -1, 12177, 12177, 12177, -1, + 12178, 12178, 12178, -1, 12179, 12179, 12179, -1, + 12180, 12180, 12180, -1, 12181, 12181, 12181, -1, + 12182, 12182, 12182, -1, 12183, 12183, 12183, -1, + 12184, 12184, 12184, -1, 12185, 12185, 12185, -1, + 12186, 12186, 12186, -1, 12187, 12187, 12187, -1, + 12188, 12188, 12188, -1, 12189, 12189, 12189, -1, + 12190, 12190, 12190, -1, 12191, 12191, 12191, -1, + 12192, 12192, 12192, -1, 12193, 12193, 12193, -1, + 12194, 12194, 12194, -1, 12195, 12195, 12195, -1, + 12196, 12196, 12196, -1, 12197, 12197, 12197, -1, + 12198, 12198, 12198, -1, 12199, 12199, 12199, -1, + 12200, 12200, 12200, -1, 12201, 12201, 12201, -1, + 12202, 12202, 12202, -1, 12203, 12203, 12203, -1, + 12204, 12204, 12204, -1, 12205, 12205, 12205, -1, + 12206, 12206, 12206, -1, 12207, 12207, 12207, -1, + 12208, 12208, 12208, -1, 12209, 12209, 12209, -1, + 12210, 12210, 12210, -1, 12211, 12211, 12211, -1, + 12212, 12212, 12212, -1, 12213, 12213, 12213, -1, + 12214, 12214, 12214, -1, 12215, 12215, 12215, -1, + 12216, 12216, 12216, -1, 12217, 12217, 12217, -1, + 12218, 12218, 12218, -1, 12219, 12219, 12219, -1, + 12220, 12220, 12220, -1, 12221, 12221, 12221, -1, + 12222, 12222, 12222, -1, 12223, 12223, 12223, -1, + 12224, 12224, 12224, -1, 12225, 12225, 12225, -1, + 12226, 12226, 12226, -1, 12227, 12227, 12227, -1, + 12228, 12228, 12228, -1, 12229, 12229, 12229, -1, + 12230, 12230, 12230, -1, 12231, 12231, 12231, -1, + 12232, 12232, 12232, -1, 12233, 12233, 12233, -1, + 12234, 12234, 12234, -1, 12235, 12235, 12235, -1, + 12236, 12236, 12236, -1, 12237, 12237, 12237, -1, + 12238, 12238, 12238, -1, 12239, 12239, 12239, -1, + 12240, 12240, 12240, -1, 12241, 12241, 12241, -1, + 12242, 12242, 12242, -1, 12243, 12243, 12243, -1, + 12244, 12244, 12244, -1, 12245, 12245, 12245, -1, + 12246, 12246, 12246, -1, 12247, 12247, 12247, -1, + 12248, 12248, 12248, -1, 12249, 12249, 12249, -1, + 12250, 12250, 12250, -1, 12251, 12251, 12251, -1, + 12252, 12252, 12252, -1, 12253, 12253, 12253, -1, + 12254, 12254, 12254, -1, 12255, 12255, 12255, -1, + 12256, 12256, 12256, -1, 12257, 12257, 12257, -1, + 12258, 12258, 12258, -1, 12259, 12259, 12259, -1, + 12260, 12260, 12260, -1, 12261, 12261, 12261, -1, + 12262, 12262, 12262, -1, 12263, 12263, 12263, -1, + 12264, 12264, 12264, -1, 12265, 12265, 12265, -1, + 12266, 12266, 12266, -1, 12267, 12267, 12267, -1, + 12268, 12268, 12268, -1, 12269, 12269, 12269, -1, + 12270, 12270, 12270, -1, 12271, 12271, 12271, -1, + 12272, 12272, 12272, -1, 12273, 12273, 12273, -1, + 12274, 12274, 12274, -1, 12275, 12275, 12275, -1, + 12276, 12276, 12276, -1, 12277, 12277, 12277, -1, + 12278, 12278, 12278, -1, 12279, 12279, 12279, -1, + 12280, 12280, 12280, -1, 12281, 12281, 12281, -1, + 12282, 12282, 12282, -1, 12283, 12283, 12283, -1, + 12284, 12284, 12284, -1, 12285, 12285, 12285, -1, + 12286, 12286, 12286, -1, 12287, 12287, 12287, -1, + 12288, 12288, 12288, -1, 12289, 12289, 12289, -1, + 12290, 12290, 12290, -1, 12291, 12291, 12291, -1, + 12292, 12292, 12292, -1, 12293, 12293, 12293, -1, + 12294, 12294, 12294, -1, 12295, 12295, 12295, -1, + 12296, 12296, 12296, -1, 12297, 12297, 12297, -1, + 12298, 12298, 12298, -1, 12299, 12299, 12299, -1, + 12300, 12300, 12300, -1, 12301, 12301, 12301, -1, + 12302, 12302, 12302, -1, 12303, 12303, 12303, -1, + 12304, 12304, 12304, -1, 12305, 12305, 12305, -1, + 12306, 12306, 12306, -1, 12307, 12307, 12307, -1, + 12308, 12308, 12308, -1, 12309, 12309, 12309, -1, + 12310, 12310, 12310, -1, 12311, 12311, 12311, -1, + 12312, 12312, 12312, -1, 12313, 12313, 12313, -1, + 12314, 12314, 12314, -1, 12315, 12315, 12315, -1, + 12316, 12316, 12316, -1, 12317, 12317, 12317, -1, + 12318, 12318, 12318, -1, 12319, 12319, 12319, -1, + 12320, 12320, 12320, -1, 12321, 12321, 12321, -1, + 12322, 12322, 12322, -1, 12323, 12323, 12323, -1, + 12324, 12324, 12324, -1, 12325, 12325, 12325, -1, + 12326, 12326, 12326, -1, 12327, 12327, 12327, -1, + 12328, 12328, 12328, -1, 12329, 12329, 12329, -1, + 12330, 12330, 12330, -1, 12331, 12331, 12331, -1, + 12332, 12332, 12332, -1, 12333, 12333, 12333, -1, + 12334, 12334, 12334, -1, 12335, 12335, 12335, -1, + 12336, 12336, 12336, -1, 12337, 12337, 12337, -1, + 12338, 12338, 12338, -1, 12339, 12339, 12339, -1, + 12340, 12340, 12340, -1, 12341, 12341, 12341, -1, + 12342, 12342, 12342, -1, 12343, 12343, 12343, -1, + 12344, 12344, 12344, -1, 12345, 12345, 12345, -1, + 12346, 12346, 12346, -1, 12347, 12347, 12347, -1, + 12348, 12348, 12348, -1, 12349, 12349, 12349, -1, + 12350, 12350, 12350, -1, 12351, 12351, 12351, -1, + 12352, 12352, 12352, -1, 12353, 12353, 12353, -1, + 12354, 12354, 12354, -1, 12355, 12355, 12355, -1, + 12356, 12356, 12356, -1, 12357, 12357, 12357, -1, + 12358, 12358, 12358, -1, 12359, 12359, 12359, -1, + 12360, 12360, 12360, -1, 12361, 12361, 12361, -1, + 12362, 12362, 12362, -1, 12363, 12363, 12363, -1, + 12364, 12364, 12364, -1, 12365, 12365, 12365, -1, + 12366, 12366, 12366, -1, 12367, 12367, 12367, -1, + 12368, 12368, 12368, -1, 12369, 12369, 12369, -1, + 12370, 12370, 12370, -1, 12371, 12371, 12371, -1, + 12372, 12372, 12372, -1, 12373, 12373, 12373, -1, + 12374, 12374, 12374, -1, 12375, 12375, 12375, -1, + 12376, 12376, 12376, -1, 12377, 12377, 12377, -1, + 12378, 12378, 12378, -1, 12379, 12379, 12379, -1, + 12380, 12380, 12380, -1, 12381, 12381, 12381, -1, + 12382, 12382, 12382, -1, 12383, 12383, 12383, -1, + 12384, 12384, 12384, -1, 12385, 12385, 12385, -1, + 12386, 12386, 12386, -1, 12387, 12387, 12387, -1, + 12388, 12388, 12388, -1, 12389, 12389, 12389, -1, + 12390, 12390, 12390, -1, 12391, 12391, 12391, -1, + 12392, 12392, 12392, -1, 12393, 12393, 12393, -1, + 12394, 12394, 12394, -1, 12395, 12395, 12395, -1, + 12396, 12396, 12396, -1, 12397, 12397, 12397, -1, + 12398, 12398, 12398, -1, 12399, 12399, 12399, -1, + 12400, 12400, 12400, -1, 12401, 12401, 12401, -1, + 12402, 12402, 12402, -1, 12403, 12403, 12403, -1, + 12404, 12404, 12404, -1, 12405, 12405, 12405, -1, + 12406, 12406, 12406, -1, 12407, 12407, 12407, -1, + 12408, 12408, 12408, -1, 12409, 12409, 12409, -1, + 12410, 12410, 12410, -1, 12411, 12411, 12411, -1, + 12412, 12412, 12412, -1, 12413, 12413, 12413, -1, + 12414, 12414, 12414, -1, 12415, 12415, 12415, -1, + 12416, 12416, 12416, -1, 12417, 12417, 12417, -1, + 12418, 12418, 12418, -1, 12419, 12419, 12419, -1, + 12420, 12420, 12420, -1, 12421, 12421, 12421, -1, + 12422, 12422, 12422, -1, 12423, 12423, 12423, -1, + 12424, 12424, 12424, -1, 12425, 12425, 12425, -1, + 12426, 12426, 12426, -1, 12427, 12427, 12427, -1, + 12428, 12428, 12428, -1, 12429, 12429, 12429, -1, + 12430, 12430, 12430, -1, 12431, 12431, 12431, -1, + 12432, 12432, 12432, -1, 12433, 12433, 12433, -1, + 12434, 12434, 12434, -1, 12435, 12435, 12435, -1, + 12436, 12436, 12436, -1, 12437, 12437, 12437, -1, + 12438, 12438, 12438, -1, 12439, 12439, 12439, -1, + 12440, 12440, 12440, -1, 12441, 12441, 12441, -1, + 12442, 12442, 12442, -1, 12443, 12443, 12443, -1, + 12444, 12444, 12444, -1, 12445, 12445, 12445, -1, + 12446, 12446, 12446, -1, 12447, 12447, 12447, -1, + 12448, 12448, 12448, -1, 12449, 12449, 12449, -1, + 12450, 12450, 12450, -1, 12451, 12451, 12451, -1, + 12452, 12452, 12452, -1, 12453, 12453, 12453, -1, + 12454, 12454, 12454, -1, 12455, 12455, 12455, -1, + 12456, 12456, 12456, -1, 12457, 12457, 12457, -1, + 12458, 12458, 12458, -1, 12459, 12459, 12459, -1, + 12460, 12460, 12460, -1, 12461, 12461, 12461, -1, + 12462, 12462, 12462, -1, 12463, 12463, 12463, -1, + 12464, 12464, 12464, -1, 12465, 12465, 12465, -1, + 12466, 12466, 12466, -1, 12467, 12467, 12467, -1, + 12468, 12468, 12468, -1, 12469, 12469, 12469, -1, + 12470, 12470, 12470, -1, 12471, 12471, 12471, -1, + 12472, 12472, 12472, -1, 12473, 12473, 12473, -1, + 12474, 12474, 12474, -1, 12475, 12475, 12475, -1, + 12476, 12476, 12476, -1, 12477, 12477, 12477, -1, + 12478, 12478, 12478, -1, 12479, 12479, 12479, -1, + 12480, 12480, 12480, -1, 12481, 12481, 12481, -1, + 12482, 12482, 12482, -1, 12483, 12483, 12483, -1, + 12484, 12484, 12484, -1, 12485, 12485, 12485, -1, + 12486, 12486, 12486, -1, 12487, 12487, 12487, -1, + 12488, 12488, 12488, -1, 12489, 12489, 12489, -1, + 12490, 12490, 12490, -1, 12491, 12491, 12491, -1, + 12492, 12492, 12492, -1, 12493, 12493, 12493, -1, + 12494, 12494, 12494, -1, 12495, 12495, 12495, -1, + 12496, 12496, 12496, -1, 12497, 12497, 12497, -1, + 12498, 12498, 12498, -1, 12499, 12499, 12499, -1, + 12500, 12500, 12500, -1, 12501, 12501, 12501, -1, + 12502, 12502, 12502, -1, 12503, 12503, 12503, -1, + 12504, 12504, 12504, -1, 12505, 12505, 12505, -1, + 12506, 12506, 12506, -1, 12507, 12507, 12507, -1, + 12508, 12508, 12508, -1, 12509, 12509, 12509, -1, + 12510, 12510, 12510, -1, 12511, 12511, 12511, -1, + 12512, 12512, 12512, -1, 12513, 12513, 12513, -1, + 12514, 12514, 12514, -1, 12515, 12515, 12515, -1, + 12516, 12516, 12516, -1, 12517, 12517, 12517, -1, + 12518, 12518, 12518, -1, 12519, 12519, 12519, -1, + 12520, 12520, 12520, -1, 12521, 12521, 12521, -1, + 12522, 12522, 12522, -1, 12523, 12523, 12523, -1, + 12524, 12524, 12524, -1, 12525, 12525, 12525, -1, + 12526, 12526, 12526, -1, 12527, 12527, 12527, -1, + 12528, 12528, 12528, -1, 12529, 12529, 12529, -1, + 12530, 12530, 12530, -1, 12531, 12531, 12531, -1, + 12532, 12532, 12532, -1, 12533, 12533, 12533, -1, + 12534, 12534, 12534, -1, 12535, 12535, 12535, -1, + 12536, 12536, 12536, -1, 12537, 12537, 12537, -1, + 12538, 12538, 12538, -1, 12539, 12539, 12539, -1, + 12540, 12540, 12540, -1, 12541, 12541, 12541, -1, + 12542, 12542, 12542, -1, 12543, 12543, 12543, -1, + 12544, 12544, 12544, -1, 12545, 12545, 12545, -1, + 12546, 12546, 12546, -1, 12547, 12547, 12547, -1, + 12548, 12548, 12548, -1, 12549, 12549, 12549, -1, + 12550, 12550, 12550, -1, 12551, 12551, 12551, -1, + 12552, 12552, 12552, -1, 12553, 12553, 12553, -1, + 12554, 12554, 12554, -1, 12555, 12555, 12555, -1, + 12556, 12556, 12556, -1, 12557, 12557, 12557, -1, + 12558, 12558, 12558, -1, 12559, 12559, 12559, -1, + 12560, 12560, 12560, -1, 12561, 12561, 12561, -1, + 12562, 12562, 12562, -1, 12563, 12563, 12563, -1, + 12564, 12564, 12564, -1, 12565, 12565, 12565, -1, + 12566, 12566, 12566, -1, 12567, 12567, 12567, -1, + 12568, 12568, 12568, -1, 12569, 12569, 12569, -1, + 12570, 12570, 12570, -1, 12571, 12571, 12571, -1, + 12572, 12572, 12572, -1, 12573, 12573, 12573, -1, + 12574, 12574, 12574, -1, 12575, 12575, 12575, -1, + 12576, 12576, 12576, -1, 12577, 12577, 12577, -1, + 12578, 12578, 12578, -1, 12579, 12579, 12579, -1, + 12580, 12580, 12580, -1, 12581, 12581, 12581, -1, + 12582, 12582, 12582, -1, 12583, 12583, 12583, -1, + 12584, 12584, 12584, -1, 12585, 12585, 12585, -1, + 12586, 12586, 12586, -1, 12587, 12587, 12587, -1, + 12588, 12588, 12588, -1, 12589, 12589, 12589, -1, + 12590, 12590, 12590, -1, 12591, 12591, 12591, -1, + 12592, 12592, 12592, -1, 12593, 12593, 12593, -1, + 12594, 12594, 12594, -1, 12595, 12595, 12595, -1, + 12596, 12596, 12596, -1, 12597, 12597, 12597, -1, + 12598, 12598, 12598, -1, 12599, 12599, 12599, -1, + 12600, 12600, 12600, -1, 12601, 12601, 12601, -1, + 12602, 12602, 12602, -1, 12603, 12603, 12603, -1, + 12604, 12604, 12604, -1, 12605, 12605, 12605, -1, + 12606, 12606, 12606, -1, 12607, 12607, 12607, -1, + 12608, 12608, 12608, -1, 12609, 12609, 12609, -1, + 12610, 12610, 12610, -1, 12611, 12611, 12611, -1, + 12612, 12612, 12612, -1, 12613, 12613, 12613, -1, + 12614, 12614, 12614, -1, 12615, 12615, 12615, -1, + 12616, 12616, 12616, -1, 12617, 12617, 12617, -1, + 12618, 12618, 12618, -1, 12619, 12619, 12619, -1, + 12620, 12620, 12620, -1, 12621, 12621, 12621, -1, + 12622, 12622, 12622, -1, 12623, 12623, 12623, -1, + 12624, 12624, 12624, -1, 12625, 12625, 12625, -1, + 12626, 12626, 12626, -1, 12627, 12627, 12627, -1, + 12628, 12628, 12628, -1, 12629, 12629, 12629, -1, + 12630, 12630, 12630, -1, 12631, 12631, 12631, -1, + 12632, 12632, 12632, -1, 12633, 12633, 12633, -1, + 12634, 12634, 12634, -1, 12635, 12635, 12635, -1, + 12636, 12636, 12636, -1, 12637, 12637, 12637, -1, + 12638, 12638, 12638, -1, 12639, 12639, 12639, -1, + 12640, 12640, 12640, -1, 12641, 12641, 12641, -1, + 12642, 12642, 12642, -1, 12643, 12643, 12643, -1, + 12644, 12644, 12644, -1, 12645, 12645, 12645, -1, + 12646, 12646, 12646, -1, 12647, 12647, 12647, -1, + 12648, 12648, 12648, -1, 12649, 12649, 12649, -1, + 12650, 12650, 12650, -1, 12651, 12651, 12651, -1, + 12652, 12652, 12652, -1, 12653, 12653, 12653, -1, + 12654, 12654, 12654, -1, 12655, 12655, 12655, -1, + 12656, 12656, 12656, -1, 12657, 12657, 12657, -1, + 12658, 12658, 12658, -1, 12659, 12659, 12659, -1, + 12660, 12660, 12660, -1, 12661, 12661, 12661, -1, + 12662, 12662, 12662, -1, 12663, 12663, 12663, -1, + 12664, 12664, 12664, -1, 12665, 12665, 12665, -1, + 12666, 12666, 12666, -1, 12667, 12667, 12667, -1, + 12668, 12668, 12668, -1, 12669, 12669, 12669, -1, + 12670, 12670, 12670, -1, 12671, 12671, 12671, -1, + 12672, 12672, 12672, -1, 12673, 12673, 12673, -1, + 12674, 12674, 12674, -1, 12675, 12675, 12675, -1, + 12676, 12676, 12676, -1, 12677, 12677, 12677, -1, + 12678, 12678, 12678, -1, 12679, 12679, 12679, -1, + 12680, 12680, 12680, -1, 12681, 12681, 12681, -1, + 12682, 12682, 12682, -1, 12683, 12683, 12683, -1, + 12684, 12684, 12684, -1, 12685, 12685, 12685, -1, + 12686, 12686, 12686, -1, 12687, 12687, 12687, -1, + 12688, 12688, 12688, -1, 12689, 12689, 12689, -1, + 12690, 12690, 12690, -1, 12691, 12691, 12691, -1, + 12692, 12692, 12692, -1, 12693, 12693, 12693, -1, + 12694, 12694, 12694, -1, 12695, 12695, 12695, -1, + 12696, 12696, 12696, -1, 12697, 12697, 12697, -1, + 12698, 12698, 12698, -1, 12699, 12699, 12699, -1, + 12700, 12700, 12700, -1, 12701, 12701, 12701, -1, + 12702, 12702, 12702, -1, 12703, 12703, 12703, -1, + 12704, 12704, 12704, -1, 12705, 12705, 12705, -1, + 12706, 12706, 12706, -1, 12707, 12707, 12707, -1, + 12708, 12708, 12708, -1, 12709, 12709, 12709, -1, + 12710, 12710, 12710, -1, 12711, 12711, 12711, -1, + 12712, 12712, 12712, -1, 12713, 12713, 12713, -1, + 12714, 12714, 12714, -1, 12715, 12715, 12715, -1, + 12716, 12716, 12716, -1, 12717, 12717, 12717, -1, + 12718, 12718, 12718, -1, 12719, 12719, 12719, -1, + 12720, 12720, 12720, -1, 12721, 12721, 12721, -1, + 12722, 12722, 12722, -1, 12723, 12723, 12723, -1, + 12724, 12724, 12724, -1, 12725, 12725, 12725, -1, + 12726, 12726, 12726, -1, 12727, 12727, 12727, -1, + 12728, 12728, 12728, -1, 12729, 12729, 12729, -1, + 12730, 12730, 12730, -1, 12731, 12731, 12731, -1, + 12732, 12732, 12732, -1, 12733, 12733, 12733, -1, + 12734, 12734, 12734, -1, 12735, 12735, 12735, -1, + 12736, 12736, 12736, -1, 12737, 12737, 12737, -1, + 12738, 12738, 12738, -1, 12739, 12739, 12739, -1, + 12740, 12740, 12740, -1, 12741, 12741, 12741, -1, + 12742, 12742, 12742, -1, 12743, 12743, 12743, -1, + 12744, 12744, 12744, -1, 12745, 12745, 12745, -1, + 12746, 12746, 12746, -1, 12747, 12747, 12747, -1, + 12748, 12748, 12748, -1, 12749, 12749, 12749, -1, + 12750, 12750, 12750, -1, 12751, 12751, 12751, -1, + 12752, 12752, 12752, -1, 12753, 12753, 12753, -1, + 12754, 12754, 12754, -1, 12755, 12755, 12755, -1, + 12756, 12756, 12756, -1, 12757, 12757, 12757, -1, + 12758, 12758, 12758, -1, 12759, 12759, 12759, -1, + 12760, 12760, 12760, -1, 12761, 12761, 12761, -1, + 12762, 12762, 12762, -1, 12763, 12763, 12763, -1, + 12764, 12764, 12764, -1, 12765, 12765, 12765, -1, + 12766, 12766, 12766, -1, 12767, 12767, 12767, -1, + 12768, 12768, 12768, -1, 12769, 12769, 12769, -1, + 12770, 12770, 12770, -1, 12771, 12771, 12771, -1, + 12772, 12772, 12772, -1, 12773, 12773, 12773, -1, + 12774, 12774, 12774, -1, 12775, 12775, 12775, -1, + 12776, 12776, 12776, -1, 12777, 12777, 12777, -1, + 12778, 12778, 12778, -1, 12779, 12779, 12779, -1, + 12780, 12780, 12780, -1, 12781, 12781, 12781, -1, + 12782, 12782, 12782, -1, 12783, 12783, 12783, -1, + 12784, 12784, 12784, -1, 12785, 12785, 12785, -1, + 12786, 12786, 12786, -1, 12787, 12787, 12787, -1, + 12788, 12788, 12788, -1, 12789, 12789, 12789, -1, + 12790, 12790, 12790, -1, 12791, 12791, 12791, -1, + 12792, 12792, 12792, -1, 12793, 12793, 12793, -1, + 12794, 12794, 12794, -1, 12795, 12795, 12795, -1, + 12796, 12796, 12796, -1, 12797, 12797, 12797, -1, + 12798, 12798, 12798, -1, 12799, 12799, 12799, -1, + 12800, 12800, 12800, -1, 12801, 12801, 12801, -1, + 12802, 12802, 12802, -1, 12803, 12803, 12803, -1, + 12804, 12804, 12804, -1, 12805, 12805, 12805, -1, + 12806, 12806, 12806, -1, 12807, 12807, 12807, -1, + 12808, 12808, 12808, -1, 12809, 12809, 12809, -1, + 12810, 12810, 12810, -1, 12811, 12811, 12811, -1, + 12812, 12812, 12812, -1, 12813, 12813, 12813, -1, + 12814, 12814, 12814, -1, 12815, 12815, 12815, -1, + 12816, 12816, 12816, -1, 12817, 12817, 12817, -1, + 12818, 12818, 12818, -1, 12819, 12819, 12819, -1, + 12820, 12820, 12820, -1, 12821, 12821, 12821, -1, + 12822, 12822, 12822, -1, 12823, 12823, 12823, -1, + 12824, 12824, 12824, -1, 12825, 12825, 12825, -1, + 12826, 12826, 12826, -1, 12827, 12827, 12827, -1, + 12828, 12828, 12828, -1, 12829, 12829, 12829, -1, + 12830, 12830, 12830, -1, 12831, 12831, 12831, -1, + 12832, 12832, 12832, -1, 12833, 12833, 12833, -1, + 12834, 12834, 12834, -1, 12835, 12835, 12835, -1, + 12836, 12836, 12836, -1, 12837, 12837, 12837, -1, + 12838, 12838, 12838, -1, 12839, 12839, 12839, -1, + 12840, 12840, 12840, -1, 12841, 12841, 12841, -1, + 12842, 12842, 12842, -1, 12843, 12843, 12843, -1, + 12844, 12844, 12844, -1, 12845, 12845, 12845, -1, + 12846, 12846, 12846, -1, 12847, 12847, 12847, -1, + 12848, 12848, 12848, -1, 12849, 12849, 12849, -1, + 12850, 12850, 12850, -1, 12851, 12851, 12851, -1, + 12852, 12852, 12852, -1, 12853, 12853, 12853, -1, + 12854, 12854, 12854, -1, 12855, 12855, 12855, -1, + 12856, 12856, 12856, -1, 12857, 12857, 12857, -1, + 12858, 12858, 12858, -1, 12859, 12859, 12859, -1, + 12860, 12860, 12860, -1, 12861, 12861, 12861, -1, + 12862, 12862, 12862, -1, 12863, 12863, 12863, -1, + 12864, 12864, 12864, -1, 12865, 12865, 12865, -1, + 12866, 12866, 12866, -1, 12867, 12867, 12867, -1, + 12868, 12868, 12868, -1, 12869, 12869, 12869, -1, + 12870, 12870, 12870, -1, 12871, 12871, 12871, -1, + 12872, 12872, 12872, -1, 12873, 12873, 12873, -1, + 12874, 12874, 12874, -1, 12875, 12875, 12875, -1, + 12876, 12876, 12876, -1, 12877, 12877, 12877, -1, + 12878, 12878, 12878, -1, 12879, 12879, 12879, -1, + 12880, 12880, 12880, -1, 12881, 12881, 12881, -1, + 12882, 12882, 12882, -1, 12883, 12883, 12883, -1, + 12884, 12884, 12884, -1, 12885, 12885, 12885, -1, + 12886, 12886, 12886, -1, 12887, 12887, 12887, -1, + 12888, 12888, 12888, -1, 12889, 12889, 12889, -1, + 12890, 12890, 12890, -1, 12891, 12891, 12891, -1, + 12892, 12892, 12892, -1, 12893, 12893, 12893, -1, + 12894, 12894, 12894, -1, 12895, 12895, 12895, -1, + 12896, 12896, 12896, -1, 12897, 12897, 12897, -1, + 12898, 12898, 12898, -1, 12899, 12899, 12899, -1, + 12900, 12900, 12900, -1, 12901, 12901, 12901, -1, + 12902, 12902, 12902, -1, 12903, 12903, 12903, -1, + 12904, 12904, 12904, -1, 12905, 12905, 12905, -1, + 12906, 12906, 12906, -1, 12907, 12907, 12907, -1, + 12908, 12908, 12908, -1, 12909, 12909, 12909, -1, + 12910, 12910, 12910, -1, 12911, 12911, 12911, -1, + 12912, 12912, 12912, -1, 12913, 12913, 12913, -1, + 12914, 12914, 12914, -1, 12915, 12915, 12915, -1, + 12916, 12916, 12916, -1, 12917, 12917, 12917, -1, + 12918, 12918, 12918, -1, 12919, 12919, 12919, -1, + 12920, 12920, 12920, -1, 12921, 12921, 12921, -1, + 12922, 12922, 12922, -1, 12923, 12923, 12923, -1, + 12924, 12924, 12924, -1, 12925, 12925, 12925, -1, + 12926, 12926, 12926, -1, 12927, 12927, 12927, -1, + 12928, 12928, 12928, -1, 12929, 12929, 12929, -1, + 12930, 12930, 12930, -1, 12931, 12931, 12931, -1, + 12932, 12932, 12932, -1, 12933, 12933, 12933, -1, + 12934, 12934, 12934, -1, 12935, 12935, 12935, -1, + 12936, 12936, 12936, -1, 12937, 12937, 12937, -1, + 12938, 12938, 12938, -1, 12939, 12939, 12939, -1, + 12940, 12940, 12940, -1, 12941, 12941, 12941, -1, + 12942, 12942, 12942, -1, 12943, 12943, 12943, -1, + 12944, 12944, 12944, -1, 12945, 12945, 12945, -1, + 12946, 12946, 12946, -1, 12947, 12947, 12947, -1, + 12948, 12948, 12948, -1, 12949, 12949, 12949, -1, + 12950, 12950, 12950, -1, 12951, 12951, 12951, -1, + 12952, 12952, 12952, -1, 12953, 12953, 12953, -1, + 12954, 12954, 12954, -1, 12955, 12955, 12955, -1, + 12956, 12956, 12956, -1, 12957, 12957, 12957, -1, + 12958, 12958, 12958, -1, 12959, 12959, 12959, -1, + 12960, 12960, 12960, -1, 12961, 12961, 12961, -1, + 12962, 12962, 12962, -1, 12963, 12963, 12963, -1, + 12964, 12964, 12964, -1, 12965, 12965, 12965, -1, + 12966, 12966, 12966, -1, 12967, 12967, 12967, -1, + 12968, 12968, 12968, -1, 12969, 12969, 12969, -1, + 12970, 12970, 12970, -1, 12971, 12971, 12971, -1, + 12972, 12972, 12972, -1, 12973, 12973, 12973, -1, + 12974, 12974, 12974, -1, 12975, 12975, 12975, -1, + 12976, 12976, 12976, -1, 12977, 12977, 12977, -1, + 12978, 12978, 12978, -1, 12979, 12979, 12979, -1, + 12980, 12980, 12980, -1, 12981, 12981, 12981, -1, + 12982, 12982, 12982, -1, 12983, 12983, 12983, -1, + 12984, 12984, 12984, -1, 12985, 12985, 12985, -1, + 12986, 12986, 12986, -1, 12987, 12987, 12987, -1, + 12988, 12988, 12988, -1, 12989, 12989, 12989, -1, + 12990, 12990, 12990, -1, 12991, 12991, 12991, -1, + 12992, 12992, 12992, -1, 12993, 12993, 12993, -1, + 12994, 12994, 12994, -1, 12995, 12995, 12995, -1, + 12996, 12996, 12996, -1, 12997, 12997, 12997, -1, + 12998, 12998, 12998, -1, 12999, 12999, 12999, -1, + 13000, 13000, 13000, -1, 13001, 13001, 13001, -1, + 13002, 13002, 13002, -1, 13003, 13003, 13003, -1, + 13004, 13004, 13004, -1, 13005, 13005, 13005, -1, + 13006, 13006, 13006, -1, 13007, 13007, 13007, -1, + 13008, 13008, 13008, -1, 13009, 13009, 13009, -1, + 13010, 13010, 13010, -1, 13011, 13011, 13011, -1, + 13012, 13012, 13012, -1, 13013, 13013, 13013, -1, + 13014, 13014, 13014, -1, 13015, 13015, 13015, -1, + 13016, 13016, 13016, -1, 13017, 13017, 13017, -1, + 13018, 13018, 13018, -1, 13019, 13019, 13019, -1, + 13020, 13020, 13020, -1, 13021, 13021, 13021, -1, + 13022, 13022, 13022, -1, 13023, 13023, 13023, -1, + 13024, 13024, 13024, -1, 13025, 13025, 13025, -1, + 13026, 13026, 13026, -1, 13027, 13027, 13027, -1, + 13028, 13028, 13028, -1, 13029, 13029, 13029, -1, + 13030, 13030, 13030, -1, 13031, 13031, 13031, -1, + 13032, 13032, 13032, -1, 13033, 13033, 13033, -1, + 13034, 13034, 13034, -1, 13035, 13035, 13035, -1, + 13036, 13036, 13036, -1, 13037, 13037, 13037, -1, + 13038, 13038, 13038, -1, 13039, 13039, 13039, -1, + 13040, 13040, 13040, -1, 13041, 13041, 13041, -1, + 13042, 13042, 13042, -1, 13043, 13043, 13043, -1, + 13044, 13044, 13044, -1, 13045, 13045, 13045, -1, + 13046, 13046, 13046, -1, 13047, 13047, 13047, -1, + 13048, 13048, 13048, -1, 13049, 13049, 13049, -1, + 13050, 13050, 13050, -1, 13051, 13051, 13051, -1, + 13052, 13052, 13052, -1, 13053, 13053, 13053, -1, + 13054, 13054, 13054, -1, 13055, 13055, 13055, -1, + 13056, 13056, 13056, -1, 13057, 13057, 13057, -1, + 13058, 13058, 13058, -1, 13059, 13059, 13059, -1, + 13060, 13060, 13060, -1, 13061, 13061, 13061, -1, + 13062, 13062, 13062, -1, 13063, 13063, 13063, -1, + 13064, 13064, 13064, -1, 13065, 13065, 13065, -1, + 13066, 13066, 13066, -1, 13067, 13067, 13067, -1, + 13068, 13068, 13068, -1, 13069, 13069, 13069, -1, + 13070, 13070, 13070, -1, 13071, 13071, 13071, -1, + 13072, 13072, 13072, -1, 13073, 13073, 13073, -1, + 13074, 13074, 13074, -1, 13075, 13075, 13075, -1, + 13076, 13076, 13076, -1, 13077, 13077, 13077, -1, + 13078, 13078, 13078, -1, 13079, 13079, 13079, -1, + 13080, 13080, 13080, -1, 13081, 13081, 13081, -1, + 13082, 13082, 13082, -1, 13083, 13083, 13083, -1, + 13084, 13084, 13084, -1, 13085, 13085, 13085, -1, + 13086, 13086, 13086, -1, 13087, 13087, 13087, -1, + 13088, 13088, 13088, -1, 13089, 13089, 13089, -1, + 13090, 13090, 13090, -1, 13091, 13091, 13091, -1, + 13092, 13092, 13092, -1, 13093, 13093, 13093, -1, + 13094, 13094, 13094, -1, 13095, 13095, 13095, -1, + 13096, 13096, 13096, -1, 13097, 13097, 13097, -1, + 13098, 13098, 13098, -1, 13099, 13099, 13099, -1, + 13100, 13100, 13100, -1, 13101, 13101, 13101, -1, + 13102, 13102, 13102, -1, 13103, 13103, 13103, -1, + 13104, 13104, 13104, -1, 13105, 13105, 13105, -1, + 13106, 13106, 13106, -1, 13107, 13107, 13107, -1, + 13108, 13108, 13108, -1, 13109, 13109, 13109, -1, + 13110, 13110, 13110, -1, 13111, 13111, 13111, -1, + 13112, 13112, 13112, -1, 13113, 13113, 13113, -1, + 13114, 13114, 13114, -1, 13115, 13115, 13115, -1, + 13116, 13116, 13116, -1, 13117, 13117, 13117, -1, + 13118, 13118, 13118, -1, 13119, 13119, 13119, -1, + 13120, 13120, 13120, -1, 13121, 13121, 13121, -1, + 13122, 13122, 13122, -1, 13123, 13123, 13123, -1, + 13124, 13124, 13124, -1, 13125, 13125, 13125, -1, + 13126, 13126, 13126, -1, 13127, 13127, 13127, -1, + 13128, 13128, 13128, -1, 13129, 13129, 13129, -1, + 13130, 13130, 13130, -1, 13131, 13131, 13131, -1, + 13132, 13132, 13132, -1, 13133, 13133, 13133, -1, + 13134, 13134, 13134, -1, 13135, 13135, 13135, -1, + 13136, 13136, 13136, -1, 13137, 13137, 13137, -1, + 13138, 13138, 13138, -1, 13139, 13139, 13139, -1, + 13140, 13140, 13140, -1, 13141, 13141, 13141, -1, + 13142, 13142, 13142, -1, 13143, 13143, 13143, -1, + 13144, 13144, 13144, -1, 13145, 13145, 13145, -1, + 13146, 13146, 13146, -1, 13147, 13147, 13147, -1, + 13148, 13148, 13148, -1, 13149, 13149, 13149, -1, + 13150, 13150, 13150, -1, 13151, 13151, 13151, -1, + 13152, 13152, 13152, -1, 13153, 13153, 13153, -1, + 13154, 13154, 13154, -1, 13155, 13155, 13155, -1, + 13156, 13156, 13156, -1, 13157, 13157, 13157, -1, + 13158, 13158, 13158, -1, 13159, 13159, 13159, -1, + 13160, 13160, 13160, -1, 13161, 13161, 13161, -1, + 13162, 13162, 13162, -1, 13163, 13163, 13163, -1, + 13164, 13164, 13164, -1, 13165, 13165, 13165, -1, + 13166, 13166, 13166, -1, 13167, 13167, 13167, -1, + 13168, 13168, 13168, -1, 13169, 13169, 13169, -1, + 13170, 13170, 13170, -1, 13171, 13171, 13171, -1, + 13172, 13172, 13172, -1, 13173, 13173, 13173, -1, + 13174, 13174, 13174, -1, 13175, 13175, 13175, -1, + 13176, 13176, 13176, -1, 13177, 13177, 13177, -1, + 13178, 13178, 13178, -1, 13179, 13179, 13179, -1, + 13180, 13180, 13180, -1, 13181, 13181, 13181, -1, + 13182, 13182, 13182, -1, 13183, 13183, 13183, -1, + 13184, 13184, 13184, -1, 13185, 13185, 13185, -1, + 13186, 13186, 13186, -1, 13187, 13187, 13187, -1, + 13188, 13188, 13188, -1, 13189, 13189, 13189, -1, + 13190, 13190, 13190, -1, 13191, 13191, 13191, -1, + 13192, 13192, 13192, -1, 13193, 13193, 13193, -1, + 13194, 13194, 13194, -1, 13195, 13195, 13195, -1, + 13196, 13196, 13196, -1, 13197, 13197, 13197, -1, + 13198, 13198, 13198, -1, 13199, 13199, 13199, -1, + 13200, 13200, 13200, -1, 13201, 13201, 13201, -1, + 13202, 13202, 13202, -1, 13203, 13203, 13203, -1, + 13204, 13204, 13204, -1, 13205, 13205, 13205, -1, + 13206, 13206, 13206, -1, 13207, 13207, 13207, -1, + 13208, 13208, 13208, -1, 13209, 13209, 13209, -1, + 13210, 13210, 13210, -1, 13211, 13211, 13211, -1, + 13212, 13212, 13212, -1, 13213, 13213, 13213, -1, + 13214, 13214, 13214, -1, 13215, 13215, 13215, -1, + 13216, 13216, 13216, -1, 13217, 13217, 13217, -1, + 13218, 13218, 13218, -1, 13219, 13219, 13219, -1, + 13220, 13220, 13220, -1, 13221, 13221, 13221, -1, + 13222, 13222, 13222, -1, 13223, 13223, 13223, -1, + 13224, 13224, 13224, -1, 13225, 13225, 13225, -1, + 13226, 13226, 13226, -1, 13227, 13227, 13227, -1, + 13228, 13228, 13228, -1, 13229, 13229, 13229, -1, + 13230, 13230, 13230, -1, 13231, 13231, 13231, -1, + 13232, 13232, 13232, -1, 13233, 13233, 13233, -1, + 13234, 13234, 13234, -1, 13235, 13235, 13235, -1, + 13236, 13236, 13236, -1, 13237, 13237, 13237, -1, + 13238, 13238, 13238, -1, 13239, 13239, 13239, -1, + 13240, 13240, 13240, -1, 13241, 13241, 13241, -1, + 13242, 13242, 13242, -1, 13243, 13243, 13243, -1, + 13244, 13244, 13244, -1, 13245, 13245, 13245, -1, + 13246, 13246, 13246, -1, 13247, 13247, 13247, -1, + 13248, 13248, 13248, -1, 13249, 13249, 13249, -1, + 13250, 13250, 13250, -1, 13251, 13251, 13251, -1, + 13252, 13252, 13252, -1, 13253, 13253, 13253, -1, + 13254, 13254, 13254, -1, 13255, 13255, 13255, -1, + 13256, 13256, 13256, -1, 13257, 13257, 13257, -1, + 13258, 13258, 13258, -1, 13259, 13259, 13259, -1, + 13260, 13260, 13260, -1, 13261, 13261, 13261, -1, + 13262, 13262, 13262, -1, 13263, 13263, 13263, -1, + 13264, 13264, 13264, -1, 13265, 13265, 13265, -1, + 13266, 13266, 13266, -1, 13267, 13267, 13267, -1, + 13268, 13268, 13268, -1, 13269, 13269, 13269, -1, + 13270, 13270, 13270, -1, 13271, 13271, 13271, -1, + 13272, 13272, 13272, -1, 13273, 13273, 13273, -1, + 13274, 13274, 13274, -1, 13275, 13275, 13275, -1, + 13276, 13276, 13276, -1, 13277, 13277, 13277, -1, + 13278, 13278, 13278, -1, 13279, 13279, 13279, -1, + 13280, 13280, 13280, -1, 13281, 13281, 13281, -1, + 13282, 13282, 13282, -1, 13283, 13283, 13283, -1, + 13284, 13284, 13284, -1, 13285, 13285, 13285, -1, + 13286, 13286, 13286, -1, 13287, 13287, 13287, -1, + 13288, 13288, 13288, -1, 13289, 13289, 13289, -1, + 13290, 13290, 13290, -1, 13291, 13291, 13291, -1, + 13292, 13292, 13292, -1, 13293, 13293, 13293, -1, + 13294, 13294, 13294, -1, 13295, 13295, 13295, -1, + 13296, 13296, 13296, -1, 13297, 13297, 13297, -1, + 13298, 13298, 13298, -1, 13299, 13299, 13299, -1, + 13300, 13300, 13300, -1, 13301, 13301, 13301, -1, + 13302, 13302, 13302, -1, 13303, 13303, 13303, -1, + 13304, 13304, 13304, -1, 13305, 13305, 13305, -1, + 13306, 13306, 13306, -1, 13307, 13307, 13307, -1, + 13308, 13308, 13308, -1, 13309, 13309, 13309, -1, + 13310, 13310, 13310, -1, 13311, 13311, 13311, -1, + 13312, 13312, 13312, -1, 13313, 13313, 13313, -1, + 13314, 13314, 13314, -1, 13315, 13315, 13315, -1, + 13316, 13316, 13316, -1, 13317, 13317, 13317, -1, + 13318, 13318, 13318, -1, 13319, 13319, 13319, -1, + 13320, 13320, 13320, -1, 13321, 13321, 13321, -1, + 13322, 13322, 13322, -1, 13323, 13323, 13323, -1, + 13324, 13324, 13324, -1, 13325, 13325, 13325, -1, + 13326, 13326, 13326, -1, 13327, 13327, 13327, -1, + 13328, 13328, 13328, -1, 13329, 13329, 13329, -1, + 13330, 13330, 13330, -1, 13331, 13331, 13331, -1, + 13332, 13332, 13332, -1, 13333, 13333, 13333, -1, + 13334, 13334, 13334, -1, 13335, 13335, 13335, -1, + 13336, 13336, 13336, -1, 13337, 13337, 13337, -1, + 13338, 13338, 13338, -1, 13339, 13339, 13339, -1, + 13340, 13340, 13340, -1, 13341, 13341, 13341, -1, + 13342, 13342, 13342, -1, 13343, 13343, 13343, -1, + 13344, 13344, 13344, -1, 13345, 13345, 13345, -1, + 13346, 13346, 13346, -1, 13347, 13347, 13347, -1, + 13348, 13348, 13348, -1, 13349, 13349, 13349, -1, + 13350, 13350, 13350, -1, 13351, 13351, 13351, -1, + 13352, 13352, 13352, -1, 13353, 13353, 13353, -1, + 13354, 13354, 13354, -1, 13355, 13355, 13355, -1, + 13356, 13356, 13356, -1, 13357, 13357, 13357, -1, + 13358, 13358, 13358, -1, 13359, 13359, 13359, -1, + 13360, 13360, 13360, -1, 13361, 13361, 13361, -1, + 13362, 13362, 13362, -1, 13363, 13363, 13363, -1, + 13364, 13364, 13364, -1, 13365, 13365, 13365, -1, + 13366, 13366, 13366, -1, 13367, 13367, 13367, -1, + 13368, 13368, 13368, -1, 13369, 13369, 13369, -1, + 13370, 13370, 13370, -1, 13371, 13371, 13371, -1, + 13372, 13372, 13372, -1, 13373, 13373, 13373, -1, + 13374, 13374, 13374, -1, 13375, 13375, 13375, -1, + 13376, 13376, 13376, -1, 13377, 13377, 13377, -1, + 13378, 13378, 13378, -1, 13379, 13379, 13379, -1, + 13380, 13380, 13380, -1, 13381, 13381, 13381, -1, + 13382, 13382, 13382, -1, 13383, 13383, 13383, -1, + 13384, 13384, 13384, -1, 13385, 13385, 13385, -1, + 13386, 13386, 13386, -1, 13387, 13387, 13387, -1, + 13388, 13388, 13388, -1, 13389, 13389, 13389, -1, + 13390, 13390, 13390, -1, 13391, 13391, 13391, -1, + 13392, 13392, 13392, -1, 13393, 13393, 13393, -1, + 13394, 13394, 13394, -1, 13395, 13395, 13395, -1, + 13396, 13396, 13396, -1, 13397, 13397, 13397, -1, + 13398, 13398, 13398, -1, 13399, 13399, 13399, -1, + 13400, 13400, 13400, -1, 13401, 13401, 13401, -1, + 13402, 13402, 13402, -1, 13403, 13403, 13403, -1, + 13404, 13404, 13404, -1, 13405, 13405, 13405, -1, + 13406, 13406, 13406, -1, 13407, 13407, 13407, -1, + 13408, 13408, 13408, -1, 13409, 13409, 13409, -1, + 13410, 13410, 13410, -1, 13411, 13411, 13411, -1, + 13412, 13412, 13412, -1, 13413, 13413, 13413, -1, + 13414, 13414, 13414, -1, 13415, 13415, 13415, -1, + 13416, 13416, 13416, -1, 13417, 13417, 13417, -1, + 13418, 13418, 13418, -1, 13419, 13419, 13419, -1, + 13420, 13420, 13420, -1, 13421, 13421, 13421, -1, + 13422, 13422, 13422, -1, 13423, 13423, 13423, -1, + 13424, 13424, 13424, -1, 13425, 13425, 13425, -1, + 13426, 13426, 13426, -1, 13427, 13427, 13427, -1, + 13428, 13428, 13428, -1, 13429, 13429, 13429, -1, + 13430, 13430, 13430, -1, 13431, 13431, 13431, -1, + 13432, 13432, 13432, -1, 13433, 13433, 13433, -1, + 13434, 13434, 13434, -1, 13435, 13435, 13435, -1, + 13436, 13436, 13436, -1, 13437, 13437, 13437, -1, + 13438, 13438, 13438, -1, 13439, 13439, 13439, -1, + 13440, 13440, 13440, -1, 13441, 13441, 13441, -1, + 13442, 13442, 13442, -1, 13443, 13443, 13443, -1, + 13444, 13444, 13444, -1, 13445, 13445, 13445, -1, + 13446, 13446, 13446, -1, 13447, 13447, 13447, -1, + 13448, 13448, 13448, -1, 13449, 13449, 13449, -1, + 13450, 13450, 13450, -1, 13451, 13451, 13451, -1, + 13452, 13452, 13452, -1, 13453, 13453, 13453, -1, + 13454, 13454, 13454, -1, 13455, 13455, 13455, -1, + 13456, 13456, 13456, -1, 13457, 13457, 13457, -1, + 13458, 13458, 13458, -1, 13459, 13459, 13459, -1, + 13460, 13460, 13460, -1, 13461, 13461, 13461, -1, + 13462, 13462, 13462, -1, 13463, 13463, 13463, -1, + 13464, 13464, 13464, -1, 13465, 13465, 13465, -1, + 13466, 13466, 13466, -1, 13467, 13467, 13467, -1, + 13468, 13468, 13468, -1, 13469, 13469, 13469, -1, + 13470, 13470, 13470, -1, 13471, 13471, 13471, -1, + 13472, 13472, 13472, -1, 13473, 13473, 13473, -1, + 13474, 13474, 13474, -1, 13475, 13475, 13475, -1, + 13476, 13476, 13476, -1, 13477, 13477, 13477, -1, + 13478, 13478, 13478, -1, 13479, 13479, 13479, -1, + 13480, 13480, 13480, -1, 13481, 13481, 13481, -1, + 13482, 13482, 13482, -1, 13483, 13483, 13483, -1, + 13484, 13484, 13484, -1, 13485, 13485, 13485, -1, + 13486, 13486, 13486, -1, 13487, 13487, 13487, -1, + 13488, 13488, 13488, -1, 13489, 13489, 13489, -1, + 13490, 13490, 13490, -1, 13491, 13491, 13491, -1, + 13492, 13492, 13492, -1, 13493, 13493, 13493, -1, + 13494, 13494, 13494, -1, 13495, 13495, 13495, -1, + 13496, 13496, 13496, -1, 13497, 13497, 13497, -1, + 13498, 13498, 13498, -1, 13499, 13499, 13499, -1, + 13500, 13500, 13500, -1, 13501, 13501, 13501, -1, + 13502, 13502, 13502, -1, 13503, 13503, 13503, -1, + 13504, 13504, 13504, -1, 13505, 13505, 13505, -1, + 13506, 13506, 13506, -1, 13507, 13507, 13507, -1, + 13508, 13508, 13508, -1, 13509, 13509, 13509, -1, + 13510, 13510, 13510, -1, 13511, 13511, 13511, -1, + 13512, 13512, 13512, -1, 13513, 13513, 13513, -1, + 13514, 13514, 13514, -1, 13515, 13515, 13515, -1, + 13516, 13516, 13516, -1, 13517, 13517, 13517, -1, + 13518, 13518, 13518, -1, 13519, 13519, 13519, -1, + 13520, 13520, 13520, -1, 13521, 13521, 13521, -1, + 13522, 13522, 13522, -1, 13523, 13523, 13523, -1, + 13524, 13524, 13524, -1, 13525, 13525, 13525, -1, + 13526, 13526, 13526, -1, 13527, 13527, 13527, -1, + 13528, 13528, 13528, -1, 13529, 13529, 13529, -1, + 13530, 13530, 13530, -1, 13531, 13531, 13531, -1, + 13532, 13532, 13532, -1, 13533, 13533, 13533, -1, + 13534, 13534, 13534, -1, 13535, 13535, 13535, -1, + 13536, 13536, 13536, -1, 13537, 13537, 13537, -1, + 13538, 13538, 13538, -1, 13539, 13539, 13539, -1, + 13540, 13540, 13540, -1, 13541, 13541, 13541, -1, + 13542, 13542, 13542, -1, 13543, 13543, 13543, -1, + 13544, 13544, 13544, -1, 13545, 13545, 13545, -1, + 13546, 13546, 13546, -1, 13547, 13547, 13547, -1, + 13548, 13548, 13548, -1, 13549, 13549, 13549, -1, + 13550, 13550, 13550, -1, 13551, 13551, 13551, -1, + 13552, 13552, 13552, -1, 13553, 13553, 13553, -1, + 13554, 13554, 13554, -1, 13555, 13555, 13555, -1, + 13556, 13556, 13556, -1, 13557, 13557, 13557, -1, + 13558, 13558, 13558, -1, 13559, 13559, 13559, -1, + 13560, 13560, 13560, -1, 13561, 13561, 13561, -1, + 13562, 13562, 13562, -1, 13563, 13563, 13563, -1, + 13564, 13564, 13564, -1, 13565, 13565, 13565, -1, + 13566, 13566, 13566, -1, 13567, 13567, 13567, -1, + 13568, 13568, 13568, -1, 13569, 13569, 13569, -1, + 13570, 13570, 13570, -1, 13571, 13571, 13571, -1, + 13572, 13572, 13572, -1, 13573, 13573, 13573, -1, + 13574, 13574, 13574, -1, 13575, 13575, 13575, -1, + 13576, 13576, 13576, -1, 13577, 13577, 13577, -1, + 13578, 13578, 13578, -1, 13579, 13579, 13579, -1, + 13580, 13580, 13580, -1, 13581, 13581, 13581, -1, + 13582, 13582, 13582, -1, 13583, 13583, 13583, -1, + 13584, 13584, 13584, -1, 13585, 13585, 13585, -1, + 13586, 13586, 13586, -1, 13587, 13587, 13587, -1, + 13588, 13588, 13588, -1, 13589, 13589, 13589, -1, + 13590, 13590, 13590, -1, 13591, 13591, 13591, -1, + 13592, 13592, 13592, -1, 13593, 13593, 13593, -1, + 13594, 13594, 13594, -1, 13595, 13595, 13595, -1, + 13596, 13596, 13596, -1, 13597, 13597, 13597, -1, + 13598, 13598, 13598, -1, 13599, 13599, 13599, -1, + 13600, 13600, 13600, -1, 13601, 13601, 13601, -1, + 13602, 13602, 13602, -1, 13603, 13603, 13603, -1, + 13604, 13604, 13604, -1, 13605, 13605, 13605, -1, + 13606, 13606, 13606, -1, 13607, 13607, 13607, -1, + 13608, 13608, 13608, -1, 13609, 13609, 13609, -1, + 13610, 13610, 13610, -1, 13611, 13611, 13611, -1, + 13612, 13612, 13612, -1, 13613, 13613, 13613, -1, + 13614, 13614, 13614, -1, 13615, 13615, 13615, -1, + 13616, 13616, 13616, -1, 13617, 13617, 13617, -1, + 13618, 13618, 13618, -1, 13619, 13619, 13619, -1, + 13620, 13620, 13620, -1, 13621, 13621, 13621, -1, + 13622, 13622, 13622, -1, 13623, 13623, 13623, -1, + 13624, 13624, 13624, -1, 13625, 13625, 13625, -1, + 13626, 13626, 13626, -1, 13627, 13627, 13627, -1, + 13628, 13628, 13628, -1, 13629, 13629, 13629, -1, + 13630, 13630, 13630, -1, 13631, 13631, 13631, -1, + 13632, 13632, 13632, -1, 13633, 13633, 13633, -1, + 13634, 13634, 13634, -1, 13635, 13635, 13635, -1, + 13636, 13636, 13636, -1, 13637, 13637, 13637, -1, + 13638, 13638, 13638, -1, 13639, 13639, 13639, -1, + 13640, 13640, 13640, -1, 13641, 13641, 13641, -1, + 13642, 13642, 13642, -1, 13643, 13643, 13643, -1, + 13644, 13644, 13644, -1, 13645, 13645, 13645, -1, + 13646, 13646, 13646, -1, 13647, 13647, 13647, -1, + 13648, 13648, 13648, -1, 13649, 13649, 13649, -1, + 13650, 13650, 13650, -1, 13651, 13651, 13651, -1, + 13652, 13652, 13652, -1, 13653, 13653, 13653, -1, + 13654, 13654, 13654, -1, 13655, 13655, 13655, -1, + 13656, 13656, 13656, -1, 13657, 13657, 13657, -1, + 13658, 13658, 13658, -1, 13659, 13659, 13659, -1, + 13660, 13660, 13660, -1, 13661, 13661, 13661, -1, + 13662, 13662, 13662, -1, 13663, 13663, 13663, -1, + 13664, 13664, 13664, -1, 13665, 13665, 13665, -1, + 13666, 13666, 13666, -1, 13667, 13667, 13667, -1, + 13668, 13668, 13668, -1, 13669, 13669, 13669, -1, + 13670, 13670, 13670, -1, 13671, 13671, 13671, -1, + 13672, 13672, 13672, -1, 13673, 13673, 13673, -1, + 13674, 13674, 13674, -1, 13675, 13675, 13675, -1, + 13676, 13676, 13676, -1, 13677, 13677, 13677, -1, + 13678, 13678, 13678, -1, 13679, 13679, 13679, -1, + 13680, 13680, 13680, -1, 13681, 13681, 13681, -1, + 13682, 13682, 13682, -1, 13683, 13683, 13683, -1, + 13684, 13684, 13684, -1, 13685, 13685, 13685, -1, + 13686, 13686, 13686, -1, 13687, 13687, 13687, -1, + 13688, 13688, 13688, -1, 13689, 13689, 13689, -1, + 13690, 13690, 13690, -1, 13691, 13691, 13691, -1, + 13692, 13692, 13692, -1, 13693, 13693, 13693, -1, + 13694, 13694, 13694, -1, 13695, 13695, 13695, -1, + 13696, 13696, 13696, -1, 13697, 13697, 13697, -1, + 13698, 13698, 13698, -1, 13699, 13699, 13699, -1, + 13700, 13700, 13700, -1, 13701, 13701, 13701, -1, + 13702, 13702, 13702, -1, 13703, 13703, 13703, -1, + 13704, 13704, 13704, -1, 13705, 13705, 13705, -1, + 13706, 13706, 13706, -1, 13707, 13707, 13707, -1, + 13708, 13708, 13708, -1, 13709, 13709, 13709, -1, + 13710, 13710, 13710, -1, 13711, 13711, 13711, -1, + 13712, 13712, 13712, -1, 13713, 13713, 13713, -1, + 13714, 13714, 13714, -1, 13715, 13715, 13715, -1, + 13716, 13716, 13716, -1, 13717, 13717, 13717, -1, + 13718, 13718, 13718, -1, 13719, 13719, 13719, -1, + 13720, 13720, 13720, -1, 13721, 13721, 13721, -1, + 13722, 13722, 13722, -1, 13723, 13723, 13723, -1, + 13724, 13724, 13724, -1, 13725, 13725, 13725, -1, + 13726, 13726, 13726, -1, 13727, 13727, 13727, -1, + 13728, 13728, 13728, -1, 13729, 13729, 13729, -1, + 13730, 13730, 13730, -1, 13731, 13731, 13731, -1, + 13732, 13732, 13732, -1, 13733, 13733, 13733, -1, + 13734, 13734, 13734, -1, 13735, 13735, 13735, -1, + 13736, 13736, 13736, -1, 13737, 13737, 13737, -1, + 13738, 13738, 13738, -1, 13739, 13739, 13739, -1, + 13740, 13740, 13740, -1, 13741, 13741, 13741, -1, + 13742, 13742, 13742, -1, 13743, 13743, 13743, -1, + 13744, 13744, 13744, -1, 13745, 13745, 13745, -1, + 13746, 13746, 13746, -1, 13747, 13747, 13747, -1, + 13748, 13748, 13748, -1, 13749, 13749, 13749, -1, + 13750, 13750, 13750, -1, 13751, 13751, 13751, -1, + 13752, 13752, 13752, -1, 13753, 13753, 13753, -1, + 13754, 13754, 13754, -1, 13755, 13755, 13755, -1, + 13756, 13756, 13756, -1, 13757, 13757, 13757, -1, + 13758, 13758, 13758, -1, 13759, 13759, 13759, -1, + 13760, 13760, 13760, -1, 13761, 13761, 13761, -1, + 13762, 13762, 13762, -1, 13763, 13763, 13763, -1, + 13764, 13764, 13764, -1, 13765, 13765, 13765, -1, + 13766, 13766, 13766, -1, 13767, 13767, 13767, -1, + 13768, 13768, 13768, -1, 13769, 13769, 13769, -1, + 13770, 13770, 13770, -1, 13771, 13771, 13771, -1, + 13772, 13772, 13772, -1, 13773, 13773, 13773, -1, + 13774, 13774, 13774, -1, 13775, 13775, 13775, -1, + 13776, 13776, 13776, -1, 13777, 13777, 13777, -1, + 13778, 13778, 13778, -1, 13779, 13779, 13779, -1, + 13780, 13780, 13780, -1, 13781, 13781, 13781, -1, + 13782, 13782, 13782, -1, 13783, 13783, 13783, -1, + 13784, 13784, 13784, -1, 13785, 13785, 13785, -1, + 13786, 13786, 13786, -1, 13787, 13787, 13787, -1, + 13788, 13788, 13788, -1, 13789, 13789, 13789, -1, + 13790, 13790, 13790, -1, 13791, 13791, 13791, -1, + 13792, 13792, 13792, -1, 13793, 13793, 13793, -1, + 13794, 13794, 13794, -1, 13795, 13795, 13795, -1, + 13796, 13796, 13796, -1, 13797, 13797, 13797, -1, + 13798, 13798, 13798, -1, 13799, 13799, 13799, -1, + 13800, 13800, 13800, -1, 13801, 13801, 13801, -1, + 13802, 13802, 13802, -1, 13803, 13803, 13803, -1, + 13804, 13804, 13804, -1, 13805, 13805, 13805, -1, + 13806, 13806, 13806, -1, 13807, 13807, 13807, -1, + 13808, 13808, 13808, -1, 13809, 13809, 13809, -1, + 13810, 13810, 13810, -1, 13811, 13811, 13811, -1, + 13812, 13812, 13812, -1, 13813, 13813, 13813, -1, + 13814, 13814, 13814, -1, 13815, 13815, 13815, -1, + 13816, 13816, 13816, -1, 13817, 13817, 13817, -1, + 13818, 13818, 13818, -1, 13819, 13819, 13819, -1, + 13820, 13820, 13820, -1, 13821, 13821, 13821, -1, + 13822, 13822, 13822, -1, 13823, 13823, 13823, -1, + 13824, 13824, 13824, -1, 13825, 13825, 13825, -1, + 13826, 13826, 13826, -1, 13827, 13827, 13827, -1, + 13828, 13828, 13828, -1, 13829, 13829, 13829, -1, + 13830, 13830, 13830, -1, 13831, 13831, 13831, -1, + 13832, 13832, 13832, -1, 13833, 13833, 13833, -1, + 13834, 13834, 13834, -1, 13835, 13835, 13835, -1, + 13836, 13836, 13836, -1, 13837, 13837, 13837, -1, + 13838, 13838, 13838, -1, 13839, 13839, 13839, -1, + 13840, 13840, 13840, -1, 13841, 13841, 13841, -1, + 13842, 13842, 13842, -1, 13843, 13843, 13843, -1, + 13844, 13844, 13844, -1, 13845, 13845, 13845, -1, + 13846, 13846, 13846, -1, 13847, 13847, 13847, -1, + 13848, 13848, 13848, -1, 13849, 13849, 13849, -1, + 13850, 13850, 13850, -1, 13851, 13851, 13851, -1, + 13852, 13852, 13852, -1, 13853, 13853, 13853, -1, + 13854, 13854, 13854, -1, 13855, 13855, 13855, -1, + 13856, 13856, 13856, -1, 13857, 13857, 13857, -1, + 13858, 13858, 13858, -1, 13859, 13859, 13859, -1, + 13860, 13860, 13860, -1, 13861, 13861, 13861, -1, + 13862, 13862, 13862, -1, 13863, 13863, 13863, -1, + 13864, 13864, 13864, -1, 13865, 13865, 13865, -1, + 13866, 13866, 13866, -1, 13867, 13867, 13867, -1, + 13868, 13868, 13868, -1, 13869, 13869, 13869, -1, + 13870, 13870, 13870, -1, 13871, 13871, 13871, -1, + 13872, 13872, 13872, -1, 13873, 13873, 13873, -1, + 13874, 13874, 13874, -1, 13875, 13875, 13875, -1, + 13876, 13876, 13876, -1, 13877, 13877, 13877, -1, + 13878, 13878, 13878, -1, 13879, 13879, 13879, -1, + 13880, 13880, 13880, -1, 13881, 13881, 13881, -1, + 13882, 13882, 13882, -1, 13883, 13883, 13883, -1, + 13884, 13884, 13884, -1, 13885, 13885, 13885, -1, + 13886, 13886, 13886, -1, 13887, 13887, 13887, -1, + 13888, 13888, 13888, -1, 13889, 13889, 13889, -1, + 13890, 13890, 13890, -1, 13891, 13891, 13891, -1, + 13892, 13892, 13892, -1, 13893, 13893, 13893, -1, + 13894, 13894, 13894, -1, 13895, 13895, 13895, -1, + 13896, 13896, 13896, -1, 13897, 13897, 13897, -1, + 13898, 13898, 13898, -1, 13899, 13899, 13899, -1, + 13900, 13900, 13900, -1, 13901, 13901, 13901, -1, + 13902, 13902, 13902, -1, 13903, 13903, 13903, -1, + 13904, 13904, 13904, -1, 13905, 13905, 13905, -1, + 13906, 13906, 13906, -1, 13907, 13907, 13907, -1, + 13908, 13908, 13908, -1, 13909, 13909, 13909, -1, + 13910, 13910, 13910, -1, 13911, 13911, 13911, -1, + 13912, 13912, 13912, -1, 13913, 13913, 13913, -1, + 13914, 13914, 13914, -1, 13915, 13915, 13915, -1, + 13916, 13916, 13916, -1, 13917, 13917, 13917, -1, + 13918, 13918, 13918, -1, 13919, 13919, 13919, -1, + 13920, 13920, 13920, -1, 13921, 13921, 13921, -1, + 13922, 13922, 13922, -1, 13923, 13923, 13923, -1, + 13924, 13924, 13924, -1, 13925, 13925, 13925, -1, + 13926, 13926, 13926, -1, 13927, 13927, 13927, -1, + 13928, 13928, 13928, -1, 13929, 13929, 13929, -1, + 13930, 13930, 13930, -1, 13931, 13931, 13931, -1, + 13932, 13932, 13932, -1, 13933, 13933, 13933, -1, + 13934, 13934, 13934, -1, 13935, 13935, 13935, -1, + 13936, 13936, 13936, -1, 13937, 13937, 13937, -1, + 13938, 13938, 13938, -1, 13939, 13939, 13939, -1, + 13940, 13940, 13940, -1, 13941, 13941, 13941, -1, + 13942, 13942, 13942, -1, 13943, 13943, 13943, -1, + 13944, 13944, 13944, -1, 13945, 13945, 13945, -1, + 13946, 13946, 13946, -1, 13947, 13947, 13947, -1, + 13948, 13948, 13948, -1, 13949, 13949, 13949, -1, + 13950, 13950, 13950, -1, 13951, 13951, 13951, -1, + 13952, 13952, 13952, -1, 13953, 13953, 13953, -1, + 13954, 13954, 13954, -1, 13955, 13955, 13955, -1, + 13956, 13956, 13956, -1, 13957, 13957, 13957, -1, + 13958, 13958, 13958, -1, 13959, 13959, 13959, -1, + 13960, 13960, 13960, -1, 13961, 13961, 13961, -1, + 13962, 13962, 13962, -1, 13963, 13963, 13963, -1, + 13964, 13964, 13964, -1, 13965, 13965, 13965, -1, + 13966, 13966, 13966, -1, 13967, 13967, 13967, -1, + 13968, 13968, 13968, -1, 13969, 13969, 13969, -1, + 13970, 13970, 13970, -1, 13971, 13971, 13971, -1, + 13972, 13972, 13972, -1, 13973, 13973, 13973, -1, + 13974, 13974, 13974, -1, 13975, 13975, 13975, -1, + 13976, 13976, 13976, -1, 13977, 13977, 13977, -1, + 13978, 13978, 13978, -1, 13979, 13979, 13979, -1, + 13980, 13980, 13980, -1, 13981, 13981, 13981, -1, + 13982, 13982, 13982, -1, 13983, 13983, 13983, -1, + 13984, 13984, 13984, -1, 13985, 13985, 13985, -1, + 13986, 13986, 13986, -1, 13987, 13987, 13987, -1, + 13988, 13988, 13988, -1, 13989, 13989, 13989, -1, + 13990, 13990, 13990, -1, 13991, 13991, 13991, -1, + 13992, 13992, 13992, -1, 13993, 13993, 13993, -1, + 13994, 13994, 13994, -1, 13995, 13995, 13995, -1, + 13996, 13996, 13996, -1, 13997, 13997, 13997, -1, + 13998, 13998, 13998, -1, 13999, 13999, 13999, -1, + 14000, 14000, 14000, -1, 14001, 14001, 14001, -1, + 14002, 14002, 14002, -1, 14003, 14003, 14003, -1, + 14004, 14004, 14004, -1, 14005, 14005, 14005, -1, + 14006, 14006, 14006, -1, 14007, 14007, 14007, -1, + 14008, 14008, 14008, -1, 14009, 14009, 14009, -1, + 14010, 14010, 14010, -1, 14011, 14011, 14011, -1, + 14012, 14012, 14012, -1, 14013, 14013, 14013, -1, + 14014, 14014, 14014, -1, 14015, 14015, 14015, -1, + 14016, 14016, 14016, -1, 14017, 14017, 14017, -1, + 14018, 14018, 14018, -1, 14019, 14019, 14019, -1, + 14020, 14020, 14020, -1, 14021, 14021, 14021, -1, + 14022, 14022, 14022, -1, 14023, 14023, 14023, -1, + 14024, 14024, 14024, -1, 14025, 14025, 14025, -1, + 14026, 14026, 14026, -1, 14027, 14027, 14027, -1, + 14028, 14028, 14028, -1, 14029, 14029, 14029, -1, + 14030, 14030, 14030, -1, 14031, 14031, 14031, -1, + 14032, 14032, 14032, -1, 14033, 14033, 14033, -1, + 14034, 14034, 14034, -1, 14035, 14035, 14035, -1, + 14036, 14036, 14036, -1, 14037, 14037, 14037, -1, + 14038, 14038, 14038, -1, 14039, 14039, 14039, -1, + 14040, 14040, 14040, -1, 14041, 14041, 14041, -1, + 14042, 14042, 14042, -1, 14043, 14043, 14043, -1, + 14044, 14044, 14044, -1, 14045, 14045, 14045, -1, + 14046, 14046, 14046, -1, 14047, 14047, 14047, -1, + 14048, 14048, 14048, -1, 14049, 14049, 14049, -1, + 14050, 14050, 14050, -1, 14051, 14051, 14051, -1, + 14052, 14052, 14052, -1, 14053, 14053, 14053, -1, + 14054, 14054, 14054, -1, 14055, 14055, 14055, -1, + 14056, 14056, 14056, -1, 14057, 14057, 14057, -1, + 14058, 14058, 14058, -1, 14059, 14059, 14059, -1, + 14060, 14060, 14060, -1, 14061, 14061, 14061, -1, + 14062, 14062, 14062, -1, 14063, 14063, 14063, -1, + 14064, 14064, 14064, -1, 14065, 14065, 14065, -1, + 14066, 14066, 14066, -1, 14067, 14067, 14067, -1, + 14068, 14068, 14068, -1, 14069, 14069, 14069, -1, + 14070, 14070, 14070, -1, 14071, 14071, 14071, -1, + 14072, 14072, 14072, -1, 14073, 14073, 14073, -1, + 14074, 14074, 14074, -1, 14075, 14075, 14075, -1, + 14076, 14076, 14076, -1, 14077, 14077, 14077, -1, + 14078, 14078, 14078, -1, 14079, 14079, 14079, -1, + 14080, 14080, 14080, -1, 14081, 14081, 14081, -1, + 14082, 14082, 14082, -1, 14083, 14083, 14083, -1, + 14084, 14084, 14084, -1, 14085, 14085, 14085, -1, + 14086, 14086, 14086, -1, 14087, 14087, 14087, -1, + 14088, 14088, 14088, -1, 14089, 14089, 14089, -1, + 14090, 14090, 14090, -1, 14091, 14091, 14091, -1, + 14092, 14092, 14092, -1, 14093, 14093, 14093, -1, + 14094, 14094, 14094, -1, 14095, 14095, 14095, -1, + 14096, 14096, 14096, -1, 14097, 14097, 14097, -1, + 14098, 14098, 14098, -1, 14099, 14099, 14099, -1, + 14100, 14100, 14100, -1, 14101, 14101, 14101, -1, + 14102, 14102, 14102, -1, 14103, 14103, 14103, -1, + 14104, 14104, 14104, -1, 14105, 14105, 14105, -1, + 14106, 14106, 14106, -1, 14107, 14107, 14107, -1, + 14108, 14108, 14108, -1, 14109, 14109, 14109, -1, + 14110, 14110, 14110, -1, 14111, 14111, 14111, -1, + 14112, 14112, 14112, -1, 14113, 14113, 14113, -1, + 14114, 14114, 14114, -1, 14115, 14115, 14115, -1, + 14116, 14116, 14116, -1, 14117, 14117, 14117, -1, + 14118, 14118, 14118, -1, 14119, 14119, 14119, -1, + 14120, 14120, 14120, -1, 14121, 14121, 14121, -1, + 14122, 14122, 14122, -1, 14123, 14123, 14123, -1, + 14124, 14124, 14124, -1, 14125, 14125, 14125, -1, + 14126, 14126, 14126, -1, 14127, 14127, 14127, -1, + 14128, 14128, 14128, -1, 14129, 14129, 14129, -1, + 14130, 14130, 14130, -1, 14131, 14131, 14131, -1, + 14132, 14132, 14132, -1, 14133, 14133, 14133, -1, + 14134, 14134, 14134, -1, 14135, 14135, 14135, -1, + 14136, 14136, 14136, -1, 14137, 14137, 14137, -1, + 14138, 14138, 14138, -1, 14139, 14139, 14139, -1, + 14140, 14140, 14140, -1, 14141, 14141, 14141, -1, + 14142, 14142, 14142, -1, 14143, 14143, 14143, -1, + 14144, 14144, 14144, -1, 14145, 14145, 14145, -1, + 14146, 14146, 14146, -1, 14147, 14147, 14147, -1, + 14148, 14148, 14148, -1, 14149, 14149, 14149, -1, + 14150, 14150, 14150, -1, 14151, 14151, 14151, -1, + 14152, 14152, 14152, -1, 14153, 14153, 14153, -1, + 14154, 14154, 14154, -1, 14155, 14155, 14155, -1, + 14156, 14156, 14156, -1, 14157, 14157, 14157, -1, + 14158, 14158, 14158, -1, 14159, 14159, 14159, -1, + 14160, 14160, 14160, -1, 14161, 14161, 14161, -1, + 14162, 14162, 14162, -1, 14163, 14163, 14163, -1, + 14164, 14164, 14164, -1, 14165, 14165, 14165, -1, + 14166, 14166, 14166, -1, 14167, 14167, 14167, -1, + 14168, 14168, 14168, -1, 14169, 14169, 14169, -1, + 14170, 14170, 14170, -1, 14171, 14171, 14171, -1, + 14172, 14172, 14172, -1, 14173, 14173, 14173, -1, + 14174, 14174, 14174, -1, 14175, 14175, 14175, -1, + 14176, 14176, 14176, -1, 14177, 14177, 14177, -1, + 14178, 14178, 14178, -1, 14179, 14179, 14179, -1, + 14180, 14180, 14180, -1, 14181, 14181, 14181, -1, + 14182, 14182, 14182, -1, 14183, 14183, 14183, -1, + 14184, 14184, 14184, -1, 14185, 14185, 14185, -1, + 14186, 14186, 14186, -1, 14187, 14187, 14187, -1, + 14188, 14188, 14188, -1, 14189, 14189, 14189, -1, + 14190, 14190, 14190, -1, 14191, 14191, 14191, -1, + 14192, 14192, 14192, -1, 14193, 14193, 14193, -1, + 14194, 14194, 14194, -1, 14195, 14195, 14195, -1, + 14196, 14196, 14196, -1, 14197, 14197, 14197, -1, + 14198, 14198, 14198, -1, 14199, 14199, 14199, -1, + 14200, 14200, 14200, -1, 14201, 14201, 14201, -1, + 14202, 14202, 14202, -1, 14203, 14203, 14203, -1, + 14204, 14204, 14204, -1, 14205, 14205, 14205, -1, + 14206, 14206, 14206, -1, 14207, 14207, 14207, -1, + 14208, 14208, 14208, -1, 14209, 14209, 14209, -1, + 14210, 14210, 14210, -1, 14211, 14211, 14211, -1, + 14212, 14212, 14212, -1, 14213, 14213, 14213, -1, + 14214, 14214, 14214, -1, 14215, 14215, 14215, -1, + 14216, 14216, 14216, -1, 14217, 14217, 14217, -1, + 14218, 14218, 14218, -1, 14219, 14219, 14219, -1, + 14220, 14220, 14220, -1, 14221, 14221, 14221, -1, + 14222, 14222, 14222, -1, 14223, 14223, 14223, -1, + 14224, 14224, 14224, -1, 14225, 14225, 14225, -1, + 14226, 14226, 14226, -1, 14227, 14227, 14227, -1, + 14228, 14228, 14228, -1, 14229, 14229, 14229, -1, + 14230, 14230, 14230, -1, 14231, 14231, 14231, -1, + 14232, 14232, 14232, -1, 14233, 14233, 14233, -1, + 14234, 14234, 14234, -1, 14235, 14235, 14235, -1, + 14236, 14236, 14236, -1, 14237, 14237, 14237, -1, + 14238, 14238, 14238, -1, 14239, 14239, 14239, -1, + 14240, 14240, 14240, -1, 14241, 14241, 14241, -1, + 14242, 14242, 14242, -1, 14243, 14243, 14243, -1, + 14244, 14244, 14244, -1, 14245, 14245, 14245, -1, + 14246, 14246, 14246, -1, 14247, 14247, 14247, -1, + 14248, 14248, 14248, -1, 14249, 14249, 14249, -1, + 14250, 14250, 14250, -1, 14251, 14251, 14251, -1, + 14252, 14252, 14252, -1, 14253, 14253, 14253, -1, + 14254, 14254, 14254, -1, 14255, 14255, 14255, -1, + 14256, 14256, 14256, -1, 14257, 14257, 14257, -1, + 14258, 14258, 14258, -1, 14259, 14259, 14259, -1, + 14260, 14260, 14260, -1, 14261, 14261, 14261, -1, + 14262, 14262, 14262, -1, 14263, 14263, 14263, -1, + 14264, 14264, 14264, -1, 14265, 14265, 14265, -1, + 14266, 14266, 14266, -1, 14267, 14267, 14267, -1, + 14268, 14268, 14268, -1, 14269, 14269, 14269, -1, + 14270, 14270, 14270, -1, 14271, 14271, 14271, -1, + 14272, 14272, 14272, -1, 14273, 14273, 14273, -1, + 14274, 14274, 14274, -1, 14275, 14275, 14275, -1, + 14276, 14276, 14276, -1, 14277, 14277, 14277, -1, + 14278, 14278, 14278, -1, 14279, 14279, 14279, -1, + 14280, 14280, 14280, -1, 14281, 14281, 14281, -1, + 14282, 14282, 14282, -1, 14283, 14283, 14283, -1, + 14284, 14284, 14284, -1, 14285, 14285, 14285, -1, + 14286, 14286, 14286, -1, 14287, 14287, 14287, -1, + 14288, 14288, 14288, -1, 14289, 14289, 14289, -1, + 14290, 14290, 14290, -1, 14291, 14291, 14291, -1, + 14292, 14292, 14292, -1, 14293, 14293, 14293, -1, + 14294, 14294, 14294, -1, 14295, 14295, 14295, -1, + 14296, 14296, 14296, -1, 14297, 14297, 14297, -1, + 14298, 14298, 14298, -1, 14299, 14299, 14299, -1, + 14300, 14300, 14300, -1, 14301, 14301, 14301, -1, + 14302, 14302, 14302, -1, 14303, 14303, 14303, -1, + 14304, 14304, 14304, -1, 14305, 14305, 14305, -1, + 14306, 14306, 14306, -1, 14307, 14307, 14307, -1, + 14308, 14308, 14308, -1, 14309, 14309, 14309, -1, + 14310, 14310, 14310, -1, 14311, 14311, 14311, -1, + 14312, 14312, 14312, -1, 14313, 14313, 14313, -1, + 14314, 14314, 14314, -1, 14315, 14315, 14315, -1, + 14316, 14316, 14316, -1, 14317, 14317, 14317, -1, + 14318, 14318, 14318, -1, 14319, 14319, 14319, -1, + 14320, 14320, 14320, -1, 14321, 14321, 14321, -1, + 14322, 14322, 14322, -1, 14323, 14323, 14323, -1, + 14324, 14324, 14324, -1, 14325, 14325, 14325, -1, + 14326, 14326, 14326, -1, 14327, 14327, 14327, -1, + 14328, 14328, 14328, -1, 14329, 14329, 14329, -1, + 14330, 14330, 14330, -1, 14331, 14331, 14331, -1, + 14332, 14332, 14332, -1, 14333, 14333, 14333, -1, + 14334, 14334, 14334, -1, 14335, 14335, 14335, -1, + 14336, 14336, 14336, -1, 14337, 14337, 14337, -1, + 14338, 14338, 14338, -1, 14339, 14339, 14339, -1, + 14340, 14340, 14340, -1, 14341, 14341, 14341, -1, + 14342, 14342, 14342, -1, 14343, 14343, 14343, -1, + 14344, 14344, 14344, -1, 14345, 14345, 14345, -1, + 14346, 14346, 14346, -1, 14347, 14347, 14347, -1, + 14348, 14348, 14348, -1, 14349, 14349, 14349, -1, + 14350, 14350, 14350, -1, 14351, 14351, 14351, -1, + 14352, 14352, 14352, -1, 14353, 14353, 14353, -1, + 14354, 14354, 14354, -1, 14355, 14355, 14355, -1, + 14356, 14356, 14356, -1, 14357, 14357, 14357, -1, + 14358, 14358, 14358, -1, 14359, 14359, 14359, -1, + 14360, 14360, 14360, -1, 14361, 14361, 14361, -1, + 14362, 14362, 14362, -1, 14363, 14363, 14363, -1, + 14364, 14364, 14364, -1, 14365, 14365, 14365, -1, + 14366, 14366, 14366, -1, 14367, 14367, 14367, -1, + 14368, 14368, 14368, -1, 14369, 14369, 14369, -1, + 14370, 14370, 14370, -1, 14371, 14371, 14371, -1, + 14372, 14372, 14372, -1, 14373, 14373, 14373, -1, + 14374, 14374, 14374, -1, 14375, 14375, 14375, -1, + 14376, 14376, 14376, -1, 14377, 14377, 14377, -1, + 14378, 14378, 14378, -1, 14379, 14379, 14379, -1, + 14380, 14380, 14380, -1, 14381, 14381, 14381, -1, + 14382, 14382, 14382, -1, 14383, 14383, 14383, -1, + 14384, 14384, 14384, -1, 14385, 14385, 14385, -1, + 14386, 14386, 14386, -1, 14387, 14387, 14387, -1, + 14388, 14388, 14388, -1, 14389, 14389, 14389, -1, + 14390, 14390, 14390, -1, 14391, 14391, 14391, -1, + 14392, 14392, 14392, -1, 14393, 14393, 14393, -1, + 14394, 14394, 14394, -1, 14395, 14395, 14395, -1, + 14396, 14396, 14396, -1, 14397, 14397, 14397, -1, + 14398, 14398, 14398, -1, 14399, 14399, 14399, -1, + 14400, 14400, 14400, -1, 14401, 14401, 14401, -1, + 14402, 14402, 14402, -1, 14403, 14403, 14403, -1, + 14404, 14404, 14404, -1, 14405, 14405, 14405, -1, + 14406, 14406, 14406, -1, 14407, 14407, 14407, -1, + 14408, 14408, 14408, -1, 14409, 14409, 14409, -1, + 14410, 14410, 14410, -1, 14411, 14411, 14411, -1, + 14412, 14412, 14412, -1, 14413, 14413, 14413, -1, + 14414, 14414, 14414, -1, 14415, 14415, 14415, -1, + 14416, 14416, 14416, -1, 14417, 14417, 14417, -1, + 14418, 14418, 14418, -1, 14419, 14419, 14419, -1, + 14420, 14420, 14420, -1, 14421, 14421, 14421, -1, + 14422, 14422, 14422, -1, 14423, 14423, 14423, -1, + 14424, 14424, 14424, -1, 14425, 14425, 14425, -1, + 14426, 14426, 14426, -1, 14427, 14427, 14427, -1, + 14428, 14428, 14428, -1, 14429, 14429, 14429, -1, + 14430, 14430, 14430, -1, 14431, 14431, 14431, -1, + 14432, 14432, 14432, -1, 14433, 14433, 14433, -1, + 14434, 14434, 14434, -1, 14435, 14435, 14435, -1, + 14436, 14436, 14436, -1, 14437, 14437, 14437, -1, + 14438, 14438, 14438, -1, 14439, 14439, 14439, -1, + 14440, 14440, 14440, -1, 14441, 14441, 14441, -1, + 14442, 14442, 14442, -1, 14443, 14443, 14443, -1, + 14444, 14444, 14444, -1, 14445, 14445, 14445, -1, + 14446, 14446, 14446, -1, 14447, 14447, 14447, -1, + 14448, 14448, 14448, -1, 14449, 14449, 14449, -1, + 14450, 14450, 14450, -1, 14451, 14451, 14451, -1, + 14452, 14452, 14452, -1, 14453, 14453, 14453, -1, + 14454, 14454, 14454, -1, 14455, 14455, 14455, -1, + 14456, 14456, 14456, -1, 14457, 14457, 14457, -1, + 14458, 14458, 14458, -1, 14459, 14459, 14459, -1, + 14460, 14460, 14460, -1, 14461, 14461, 14461, -1, + 14462, 14462, 14462, -1, 14463, 14463, 14463, -1, + 14464, 14464, 14464, -1, 14465, 14465, 14465, -1, + 14466, 14466, 14466, -1, 14467, 14467, 14467, -1, + 14468, 14468, 14468, -1, 14469, 14469, 14469, -1, + 14470, 14470, 14470, -1, 14471, 14471, 14471, -1, + 14472, 14472, 14472, -1, 14473, 14473, 14473, -1, + 14474, 14474, 14474, -1, 14475, 14475, 14475, -1, + 14476, 14476, 14476, -1, 14477, 14477, 14477, -1, + 14478, 14478, 14478, -1, 14479, 14479, 14479, -1, + 14480, 14480, 14480, -1, 14481, 14481, 14481, -1, + 14482, 14482, 14482, -1, 14483, 14483, 14483, -1, + 14484, 14484, 14484, -1, 14485, 14485, 14485, -1, + 14486, 14486, 14486, -1, 14487, 14487, 14487, -1, + 14488, 14488, 14488, -1, 14489, 14489, 14489, -1, + 14490, 14490, 14490, -1, 14491, 14491, 14491, -1, + 14492, 14492, 14492, -1, 14493, 14493, 14493, -1, + 14494, 14494, 14494, -1, 14495, 14495, 14495, -1, + 14496, 14496, 14496, -1, 14497, 14497, 14497, -1, + 14498, 14498, 14498, -1, 14499, 14499, 14499, -1, + 14500, 14500, 14500, -1, 14501, 14501, 14501, -1, + 14502, 14502, 14502, -1, 14503, 14503, 14503, -1, + 14504, 14504, 14504, -1, 14505, 14505, 14505, -1, + 14506, 14506, 14506, -1, 14507, 14507, 14507, -1, + 14508, 14508, 14508, -1, 14509, 14509, 14509, -1, + 14510, 14510, 14510, -1, 14511, 14511, 14511, -1, + 14512, 14512, 14512, -1, 14513, 14513, 14513, -1, + 14514, 14514, 14514, -1, 14515, 14515, 14515, -1, + 14516, 14516, 14516, -1, 14517, 14517, 14517, -1, + 14518, 14518, 14518, -1, 14519, 14519, 14519, -1, + 14520, 14520, 14520, -1, 14521, 14521, 14521, -1, + 14522, 14522, 14522, -1, 14523, 14523, 14523, -1, + 14524, 14524, 14524, -1, 14525, 14525, 14525, -1, + 14526, 14526, 14526, -1, 14527, 14527, 14527, -1, + 14528, 14528, 14528, -1, 14529, 14529, 14529, -1, + 14530, 14530, 14530, -1, 14531, 14531, 14531, -1, + 14532, 14532, 14532, -1, 14533, 14533, 14533, -1, + 14534, 14534, 14534, -1, 14535, 14535, 14535, -1, + 14536, 14536, 14536, -1, 14537, 14537, 14537, -1, + 14538, 14538, 14538, -1, 14539, 14539, 14539, -1, + 14540, 14540, 14540, -1, 14541, 14541, 14541, -1, + 14542, 14542, 14542, -1, 14543, 14543, 14543, -1, + 14544, 14544, 14544, -1, 14545, 14545, 14545, -1, + 14546, 14546, 14546, -1, 14547, 14547, 14547, -1, + 14548, 14548, 14548, -1, 14549, 14549, 14549, -1, + 14550, 14550, 14550, -1, 14551, 14551, 14551, -1, + 14552, 14552, 14552, -1, 14553, 14553, 14553, -1, + 14554, 14554, 14554, -1, 14555, 14555, 14555, -1, + 14556, 14556, 14556, -1, 14557, 14557, 14557, -1, + 14558, 14558, 14558, -1, 14559, 14559, 14559, -1, + 14560, 14560, 14560, -1, 14561, 14561, 14561, -1, + 14562, 14562, 14562, -1, 14563, 14563, 14563, -1, + 14564, 14564, 14564, -1, 14565, 14565, 14565, -1, + 14566, 14566, 14566, -1, 14567, 14567, 14567, -1, + 14568, 14568, 14568, -1, 14569, 14569, 14569, -1, + 14570, 14570, 14570, -1, 14571, 14571, 14571, -1, + 14572, 14572, 14572, -1, 14573, 14573, 14573, -1, + 14574, 14574, 14574, -1, 14575, 14575, 14575, -1, + 14576, 14576, 14576, -1, 14577, 14577, 14577, -1, + 14578, 14578, 14578, -1, 14579, 14579, 14579, -1, + 14580, 14580, 14580, -1, 14581, 14581, 14581, -1, + 14582, 14582, 14582, -1, 14583, 14583, 14583, -1, + 14584, 14584, 14584, -1, 14585, 14585, 14585, -1, + 14586, 14586, 14586, -1, 14587, 14587, 14587, -1, + 14588, 14588, 14588, -1, 14589, 14589, 14589, -1, + 14590, 14590, 14590, -1, 14591, 14591, 14591, -1, + 14592, 14592, 14592, -1, 14593, 14593, 14593, -1, + 14594, 14594, 14594, -1, 14595, 14595, 14595, -1, + 14596, 14596, 14596, -1, 14597, 14597, 14597, -1, + 14598, 14598, 14598, -1, 14599, 14599, 14599, -1, + 14600, 14600, 14600, -1, 14601, 14601, 14601, -1, + 14602, 14602, 14602, -1, 14603, 14603, 14603, -1, + 14604, 14604, 14604, -1, 14605, 14605, 14605, -1, + 14606, 14606, 14606, -1, 14607, 14607, 14607, -1, + 14608, 14608, 14608, -1, 14609, 14609, 14609, -1, + 14610, 14610, 14610, -1, 14611, 14611, 14611, -1, + 14612, 14612, 14612, -1, 14613, 14613, 14613, -1, + 14614, 14614, 14614, -1, 14615, 14615, 14615, -1, + 14616, 14616, 14616, -1, 14617, 14617, 14617, -1, + 14618, 14618, 14618, -1, 14619, 14619, 14619, -1, + 14620, 14620, 14620, -1, 14621, 14621, 14621, -1, + 14622, 14622, 14622, -1, 14623, 14623, 14623, -1, + 14624, 14624, 14624, -1, 14625, 14625, 14625, -1, + 14626, 14626, 14626, -1, 14627, 14627, 14627, -1, + 14628, 14628, 14628, -1, 14629, 14629, 14629, -1, + 14630, 14630, 14630, -1, 14631, 14631, 14631, -1, + 14632, 14632, 14632, -1, 14633, 14633, 14633, -1, + 14634, 14634, 14634, -1, 14635, 14635, 14635, -1, + 14636, 14636, 14636, -1, 14637, 14637, 14637, -1, + 14638, 14638, 14638, -1, 14639, 14639, 14639, -1, + 14640, 14640, 14640, -1, 14641, 14641, 14641, -1, + 14642, 14642, 14642, -1, 14643, 14643, 14643, -1, + 14644, 14644, 14644, -1, 14645, 14645, 14645, -1, + 14646, 14646, 14646, -1, 14647, 14647, 14647, -1, + 14648, 14648, 14648, -1, 14649, 14649, 14649, -1, + 14650, 14650, 14650, -1, 14651, 14651, 14651, -1, + 14652, 14652, 14652, -1, 14653, 14653, 14653, -1, + 14654, 14654, 14654, -1, 14655, 14655, 14655, -1, + 14656, 14656, 14656, -1, 14657, 14657, 14657, -1, + 14658, 14658, 14658, -1, 14659, 14659, 14659, -1, + 14660, 14660, 14660, -1, 14661, 14661, 14661, -1, + 14662, 14662, 14662, -1, 14663, 14663, 14663, -1, + 14664, 14664, 14664, -1, 14665, 14665, 14665, -1, + 14666, 14666, 14666, -1, 14667, 14667, 14667, -1, + 14668, 14668, 14668, -1, 14669, 14669, 14669, -1, + 14670, 14670, 14670, -1, 14671, 14671, 14671, -1, + 14672, 14672, 14672, -1, 14673, 14673, 14673, -1, + 14674, 14674, 14674, -1, 14675, 14675, 14675, -1, + 14676, 14676, 14676, -1, 14677, 14677, 14677, -1, + 14678, 14678, 14678, -1, 14679, 14679, 14679, -1, + 14680, 14680, 14680, -1, 14681, 14681, 14681, -1, + 14682, 14682, 14682, -1, 14683, 14683, 14683, -1, + 14684, 14684, 14684, -1, 14685, 14685, 14685, -1, + 14686, 14686, 14686, -1, 14687, 14687, 14687, -1, + 14688, 14688, 14688, -1, 14689, 14689, 14689, -1, + 14690, 14690, 14690, -1, 14691, 14691, 14691, -1, + 14692, 14692, 14692, -1, 14693, 14693, 14693, -1, + 14694, 14694, 14694, -1, 14695, 14695, 14695, -1, + 14696, 14696, 14696, -1, 14697, 14697, 14697, -1, + 14698, 14698, 14698, -1, 14699, 14699, 14699, -1, + 14700, 14700, 14700, -1, 14701, 14701, 14701, -1, + 14702, 14702, 14702, -1, 14703, 14703, 14703, -1, + 14704, 14704, 14704, -1, 14705, 14705, 14705, -1, + 14706, 14706, 14706, -1, 14707, 14707, 14707, -1, + 14708, 14708, 14708, -1, 14709, 14709, 14709, -1, + 14710, 14710, 14710, -1, 14711, 14711, 14711, -1, + 14712, 14712, 14712, -1, 14713, 14713, 14713, -1, + 14714, 14714, 14714, -1, 14715, 14715, 14715, -1, + 14716, 14716, 14716, -1, 14717, 14717, 14717, -1, + 14718, 14718, 14718, -1, 14719, 14719, 14719, -1, + 14720, 14720, 14720, -1, 14721, 14721, 14721, -1, + 14722, 14722, 14722, -1, 14723, 14723, 14723, -1, + 14724, 14724, 14724, -1, 14725, 14725, 14725, -1, + 14726, 14726, 14726, -1, 14727, 14727, 14727, -1, + 14728, 14728, 14728, -1, 14729, 14729, 14729, -1, + 14730, 14730, 14730, -1, 14731, 14731, 14731, -1, + 14732, 14732, 14732, -1, 14733, 14733, 14733, -1, + 14734, 14734, 14734, -1, 14735, 14735, 14735, -1, + 14736, 14736, 14736, -1, 14737, 14737, 14737, -1, + 14738, 14738, 14738, -1, 14739, 14739, 14739, -1, + 14740, 14740, 14740, -1, 14741, 14741, 14741, -1, + 14742, 14742, 14742, -1, 14743, 14743, 14743, -1, + 14744, 14744, 14744, -1, 14745, 14745, 14745, -1, + 14746, 14746, 14746, -1, 14747, 14747, 14747, -1, + 14748, 14748, 14748, -1, 14749, 14749, 14749, -1, + 14750, 14750, 14750, -1, 14751, 14751, 14751, -1, + 14752, 14752, 14752, -1, 14753, 14753, 14753, -1, + 14754, 14754, 14754, -1, 14755, 14755, 14755, -1, + 14756, 14756, 14756, -1, 14757, 14757, 14757, -1, + 14758, 14758, 14758, -1, 14759, 14759, 14759, -1, + 14760, 14760, 14760, -1, 14761, 14761, 14761, -1, + 14762, 14762, 14762, -1, 14763, 14763, 14763, -1, + 14764, 14764, 14764, -1, 14765, 14765, 14765, -1, + 14766, 14766, 14766, -1, 14767, 14767, 14767, -1, + 14768, 14768, 14768, -1, 14769, 14769, 14769, -1, + 14770, 14770, 14770, -1, 14771, 14771, 14771, -1, + 14772, 14772, 14772, -1, 14773, 14773, 14773, -1, + 14774, 14774, 14774, -1, 14775, 14775, 14775, -1, + 14776, 14776, 14776, -1, 14777, 14777, 14777, -1, + 14778, 14778, 14778, -1, 14779, 14779, 14779, -1, + 14780, 14780, 14780, -1, 14781, 14781, 14781, -1, + 14782, 14782, 14782, -1, 14783, 14783, 14783, -1, + 14784, 14784, 14784, -1, 14785, 14785, 14785, -1, + 14786, 14786, 14786, -1, 14787, 14787, 14787, -1, + 14788, 14788, 14788, -1, 14789, 14789, 14789, -1, + 14790, 14790, 14790, -1, 14791, 14791, 14791, -1, + 14792, 14792, 14792, -1, 14793, 14793, 14793, -1, + 14794, 14794, 14794, -1, 14795, 14795, 14795, -1, + 14796, 14796, 14796, -1, 14797, 14797, 14797, -1, + 14798, 14798, 14798, -1, 14799, 14799, 14799, -1, + 14800, 14800, 14800, -1, 14801, 14801, 14801, -1, + 14802, 14802, 14802, -1, 14803, 14803, 14803, -1, + 14804, 14804, 14804, -1, 14805, 14805, 14805, -1, + 14806, 14806, 14806, -1, 14807, 14807, 14807, -1, + 14808, 14808, 14808, -1, 14809, 14809, 14809, -1, + 14810, 14810, 14810, -1, 14811, 14811, 14811, -1, + 14812, 14812, 14812, -1, 14813, 14813, 14813, -1, + 14814, 14814, 14814, -1, 14815, 14815, 14815, -1, + 14816, 14816, 14816, -1, 14817, 14817, 14817, -1, + 14818, 14818, 14818, -1, 14819, 14819, 14819, -1, + 14820, 14820, 14820, -1, 14821, 14821, 14821, -1, + 14822, 14822, 14822, -1, 14823, 14823, 14823, -1, + 14824, 14824, 14824, -1, 14825, 14825, 14825, -1, + 14826, 14826, 14826, -1, 14827, 14827, 14827, -1, + 14828, 14828, 14828, -1, 14829, 14829, 14829, -1, + 14830, 14830, 14830, -1, 14831, 14831, 14831, -1, + 14832, 14832, 14832, -1, 14833, 14833, 14833, -1, + 14834, 14834, 14834, -1, 14835, 14835, 14835, -1, + 14836, 14836, 14836, -1, 14837, 14837, 14837, -1, + 14838, 14838, 14838, -1, 14839, 14839, 14839, -1, + 14840, 14840, 14840, -1, 14841, 14841, 14841, -1, + 14842, 14842, 14842, -1, 14843, 14843, 14843, -1, + 14844, 14844, 14844, -1, 14845, 14845, 14845, -1, + 14846, 14846, 14846, -1, 14847, 14847, 14847, -1, + 14848, 14848, 14848, -1, 14849, 14849, 14849, -1, + 14850, 14850, 14850, -1, 14851, 14851, 14851, -1, + 14852, 14852, 14852, -1, 14853, 14853, 14853, -1, + 14854, 14854, 14854, -1, 14855, 14855, 14855, -1, + 14856, 14856, 14856, -1, 14857, 14857, 14857, -1, + 14858, 14858, 14858, -1, 14859, 14859, 14859, -1, + 14860, 14860, 14860, -1, 14861, 14861, 14861, -1, + 14862, 14862, 14862, -1, 14863, 14863, 14863, -1, + 14864, 14864, 14864, -1, 14865, 14865, 14865, -1, + 14866, 14866, 14866, -1, 14867, 14867, 14867, -1, + 14868, 14868, 14868, -1, 14869, 14869, 14869, -1, + 14870, 14870, 14870, -1, 14871, 14871, 14871, -1, + 14872, 14872, 14872, -1, 14873, 14873, 14873, -1, + 14874, 14874, 14874, -1, 14875, 14875, 14875, -1, + 14876, 14876, 14876, -1, 14877, 14877, 14877, -1, + 14878, 14878, 14878, -1, 14879, 14879, 14879, -1, + 14880, 14880, 14880, -1, 14881, 14881, 14881, -1, + 14882, 14882, 14882, -1, 14883, 14883, 14883, -1, + 14884, 14884, 14884, -1, 14885, 14885, 14885, -1, + 14886, 14886, 14886, -1, 14887, 14887, 14887, -1, + 14888, 14888, 14888, -1, 14889, 14889, 14889, -1, + 14890, 14890, 14890, -1, 14891, 14891, 14891, -1, + 14892, 14892, 14892, -1, 14893, 14893, 14893, -1, + 14894, 14894, 14894, -1, 14895, 14895, 14895, -1, + 14896, 14896, 14896, -1, 14897, 14897, 14897, -1, + 14898, 14898, 14898, -1, 14899, 14899, 14899, -1, + 14900, 14900, 14900, -1, 14901, 14901, 14901, -1, + 14902, 14902, 14902, -1, 14903, 14903, 14903, -1, + 14904, 14904, 14904, -1, 14905, 14905, 14905, -1, + 14906, 14906, 14906, -1, 14907, 14907, 14907, -1, + 14908, 14908, 14908, -1, 14909, 14909, 14909, -1, + 14910, 14910, 14910, -1, 14911, 14911, 14911, -1, + 14912, 14912, 14912, -1, 14913, 14913, 14913, -1, + 14914, 14914, 14914, -1, 14915, 14915, 14915, -1, + 14916, 14916, 14916, -1, 14917, 14917, 14917, -1, + 14918, 14918, 14918, -1, 14919, 14919, 14919, -1, + 14920, 14920, 14920, -1, 14921, 14921, 14921, -1, + 14922, 14922, 14922, -1, 14923, 14923, 14923, -1, + 14924, 14924, 14924, -1, 14925, 14925, 14925, -1, + 14926, 14926, 14926, -1, 14927, 14927, 14927, -1, + 14928, 14928, 14928, -1, 14929, 14929, 14929, -1, + 14930, 14930, 14930, -1, 14931, 14931, 14931, -1, + 14932, 14932, 14932, -1, 14933, 14933, 14933, -1, + 14934, 14934, 14934, -1, 14935, 14935, 14935, -1, + 14936, 14936, 14936, -1, 14937, 14937, 14937, -1, + 14938, 14938, 14938, -1, 14939, 14939, 14939, -1, + 14940, 14940, 14940, -1, 14941, 14941, 14941, -1, + 14942, 14942, 14942, -1, 14943, 14943, 14943, -1, + 14944, 14944, 14944, -1, 14945, 14945, 14945, -1, + 14946, 14946, 14946, -1, 14947, 14947, 14947, -1, + 14948, 14948, 14948, -1, 14949, 14949, 14949, -1, + 14950, 14950, 14950, -1, 14951, 14951, 14951, -1, + 14952, 14952, 14952, -1, 14953, 14953, 14953, -1, + 14954, 14954, 14954, -1, 14955, 14955, 14955, -1, + 14956, 14956, 14956, -1, 14957, 14957, 14957, -1, + 14958, 14958, 14958, -1, 14959, 14959, 14959, -1, + 14960, 14960, 14960, -1, 14961, 14961, 14961, -1, + 14962, 14962, 14962, -1, 14963, 14963, 14963, -1, + 14964, 14964, 14964, -1, 14965, 14965, 14965, -1, + 14966, 14966, 14966, -1, 14967, 14967, 14967, -1, + 14968, 14968, 14968, -1, 14969, 14969, 14969, -1, + 14970, 14970, 14970, -1, 14971, 14971, 14971, -1, + 14972, 14972, 14972, -1, 14973, 14973, 14973, -1, + 14974, 14974, 14974, -1, 14975, 14975, 14975, -1, + 14976, 14976, 14976, -1, 14977, 14977, 14977, -1, + 14978, 14978, 14978, -1, 14979, 14979, 14979, -1, + 14980, 14980, 14980, -1, 14981, 14981, 14981, -1, + 14982, 14982, 14982, -1, 14983, 14983, 14983, -1, + 14984, 14984, 14984, -1, 14985, 14985, 14985, -1, + 14986, 14986, 14986, -1, 14987, 14987, 14987, -1, + 14988, 14988, 14988, -1, 14989, 14989, 14989, -1, + 14990, 14990, 14990, -1, 14991, 14991, 14991, -1, + 14992, 14992, 14992, -1, 14993, 14993, 14993, -1, + 14994, 14994, 14994, -1, 14995, 14995, 14995, -1, + 14996, 14996, 14996, -1, 14997, 14997, 14997, -1, + 14998, 14998, 14998, -1, 14999, 14999, 14999, -1, + 15000, 15000, 15000, -1, 15001, 15001, 15001, -1, + 15002, 15002, 15002, -1, 15003, 15003, 15003, -1, + 15004, 15004, 15004, -1, 15005, 15005, 15005, -1, + 15006, 15006, 15006, -1, 15007, 15007, 15007, -1, + 15008, 15008, 15008, -1, 15009, 15009, 15009, -1, + 15010, 15010, 15010, -1, 15011, 15011, 15011, -1, + 15012, 15012, 15012, -1, 15013, 15013, 15013, -1, + 15014, 15014, 15014, -1, 15015, 15015, 15015, -1, + 15016, 15016, 15016, -1, 15017, 15017, 15017, -1, + 15018, 15018, 15018, -1, 15019, 15019, 15019, -1, + 15020, 15020, 15020, -1, 15021, 15021, 15021, -1, + 15022, 15022, 15022, -1, 15023, 15023, 15023, -1, + 15024, 15024, 15024, -1, 15025, 15025, 15025, -1, + 15026, 15026, 15026, -1, 15027, 15027, 15027, -1, + 15028, 15028, 15028, -1, 15029, 15029, 15029, -1, + 15030, 15030, 15030, -1, 15031, 15031, 15031, -1, + 15032, 15032, 15032, -1, 15033, 15033, 15033, -1, + 15034, 15034, 15034, -1, 15035, 15035, 15035, -1, + 15036, 15036, 15036, -1, 15037, 15037, 15037, -1, + 15038, 15038, 15038, -1, 15039, 15039, 15039, -1, + 15040, 15040, 15040, -1, 15041, 15041, 15041, -1, + 15042, 15042, 15042, -1, 15043, 15043, 15043, -1, + 15044, 15044, 15044, -1, 15045, 15045, 15045, -1, + 15046, 15046, 15046, -1, 15047, 15047, 15047, -1, + 15048, 15048, 15048, -1, 15049, 15049, 15049, -1, + 15050, 15050, 15050, -1, 15051, 15051, 15051, -1, + 15052, 15052, 15052, -1, 15053, 15053, 15053, -1, + 15054, 15054, 15054, -1, 15055, 15055, 15055, -1, + 15056, 15056, 15056, -1, 15057, 15057, 15057, -1, + 15058, 15058, 15058, -1, 15059, 15059, 15059, -1, + 15060, 15060, 15060, -1, 15061, 15061, 15061, -1, + 15062, 15062, 15062, -1, 15063, 15063, 15063, -1, + 15064, 15064, 15064, -1, 15065, 15065, 15065, -1, + 15066, 15066, 15066, -1, 15067, 15067, 15067, -1, + 15068, 15068, 15068, -1, 15069, 15069, 15069, -1, + 15070, 15070, 15070, -1, 15071, 15071, 15071, -1, + 15072, 15072, 15072, -1, 15073, 15073, 15073, -1, + 15074, 15074, 15074, -1, 15075, 15075, 15075, -1, + 15076, 15076, 15076, -1, 15077, 15077, 15077, -1, + 15078, 15078, 15078, -1, 15079, 15079, 15079, -1, + 15080, 15080, 15080, -1, 15081, 15081, 15081, -1, + 15082, 15082, 15082, -1, 15083, 15083, 15083, -1, + 15084, 15084, 15084, -1, 15085, 15085, 15085, -1, + 15086, 15086, 15086, -1, 15087, 15087, 15087, -1, + 15088, 15088, 15088, -1, 15089, 15089, 15089, -1, + 15090, 15090, 15090, -1, 15091, 15091, 15091, -1, + 15092, 15092, 15092, -1, 15093, 15093, 15093, -1, + 15094, 15094, 15094, -1, 15095, 15095, 15095, -1, + 15096, 15096, 15096, -1, 15097, 15097, 15097, -1, + 15098, 15098, 15098, -1, 15099, 15099, 15099, -1, + 15100, 15100, 15100, -1, 15101, 15101, 15101, -1, + 15102, 15102, 15102, -1, 15103, 15103, 15103, -1, + 15104, 15104, 15104, -1, 15105, 15105, 15105, -1, + 15106, 15106, 15106, -1, 15107, 15107, 15107, -1, + 15108, 15108, 15108, -1, 15109, 15109, 15109, -1, + 15110, 15110, 15110, -1, 15111, 15111, 15111, -1, + 15112, 15112, 15112, -1, 15113, 15113, 15113, -1, + 15114, 15114, 15114, -1, 15115, 15115, 15115, -1, + 15116, 15116, 15116, -1, 15117, 15117, 15117, -1, + 15118, 15118, 15118, -1, 15119, 15119, 15119, -1, + 15120, 15120, 15120, -1, 15121, 15121, 15121, -1, + 15122, 15122, 15122, -1, 15123, 15123, 15123, -1, + 15124, 15124, 15124, -1, 15125, 15125, 15125, -1, + 15126, 15126, 15126, -1, 15127, 15127, 15127, -1, + 15128, 15128, 15128, -1, 15129, 15129, 15129, -1, + 15130, 15130, 15130, -1, 15131, 15131, 15131, -1, + 15132, 15132, 15132, -1, 15133, 15133, 15133, -1, + 15134, 15134, 15134, -1, 15135, 15135, 15135, -1, + 15136, 15136, 15136, -1, 15137, 15137, 15137, -1, + 15138, 15138, 15138, -1, 15139, 15139, 15139, -1, + 15140, 15140, 15140, -1, 15141, 15141, 15141, -1, + 15142, 15142, 15142, -1, 15143, 15143, 15143, -1, + 15144, 15144, 15144, -1, 15145, 15145, 15145, -1, + 15146, 15146, 15146, -1, 15147, 15147, 15147, -1, + 15148, 15148, 15148, -1, 15149, 15149, 15149, -1, + 15150, 15150, 15150, -1, 15151, 15151, 15151, -1, + 15152, 15152, 15152, -1, 15153, 15153, 15153, -1, + 15154, 15154, 15154, -1, 15155, 15155, 15155, -1, + 15156, 15156, 15156, -1, 15157, 15157, 15157, -1, + 15158, 15158, 15158, -1, 15159, 15159, 15159, -1, + 15160, 15160, 15160, -1, 15161, 15161, 15161, -1, + 15162, 15162, 15162, -1, 15163, 15163, 15163, -1, + 15164, 15164, 15164, -1, 15165, 15165, 15165, -1, + 15166, 15166, 15166, -1, 15167, 15167, 15167, -1, + 15168, 15168, 15168, -1, 15169, 15169, 15169, -1, + 15170, 15170, 15170, -1, 15171, 15171, 15171, -1, + 15172, 15172, 15172, -1, 15173, 15173, 15173, -1, + 15174, 15174, 15174, -1, 15175, 15175, 15175, -1, + 15176, 15176, 15176, -1, 15177, 15177, 15177, -1, + 15178, 15178, 15178, -1, 15179, 15179, 15179, -1, + 15180, 15180, 15180, -1, 15181, 15181, 15181, -1, + 15182, 15182, 15182, -1, 15183, 15183, 15183, -1, + 15184, 15184, 15184, -1, 15185, 15185, 15185, -1, + 15186, 15186, 15186, -1, 15187, 15187, 15187, -1, + 15188, 15188, 15188, -1, 15189, 15189, 15189, -1, + 15190, 15190, 15190, -1, 15191, 15191, 15191, -1, + 15192, 15192, 15192, -1, 15193, 15193, 15193, -1, + 15194, 15194, 15194, -1, 15195, 15195, 15195, -1, + 15196, 15196, 15196, -1, 15197, 15197, 15197, -1, + 15198, 15198, 15198, -1, 15199, 15199, 15199, -1, + 15200, 15200, 15200, -1, 15201, 15201, 15201, -1, + 15202, 15202, 15202, -1, 15203, 15203, 15203, -1, + 15204, 15204, 15204, -1, 15205, 15205, 15205, -1, + 15206, 15206, 15206, -1, 15207, 15207, 15207, -1, + 15208, 15208, 15208, -1, 15209, 15209, 15209, -1, + 15210, 15210, 15210, -1, 15211, 15211, 15211, -1, + 15212, 15212, 15212, -1, 15213, 15213, 15213, -1, + 15214, 15214, 15214, -1, 15215, 15215, 15215, -1, + 15216, 15216, 15216, -1, 15217, 15217, 15217, -1, + 15218, 15218, 15218, -1, 15219, 15219, 15219, -1, + 15220, 15220, 15220, -1, 15221, 15221, 15221, -1, + 15222, 15222, 15222, -1, 15223, 15223, 15223, -1, + 15224, 15224, 15224, -1, 15225, 15225, 15225, -1, + 15226, 15226, 15226, -1, 15227, 15227, 15227, -1, + 15228, 15228, 15228, -1, 15229, 15229, 15229, -1, + 15230, 15230, 15230, -1, 15231, 15231, 15231, -1, + 15232, 15232, 15232, -1, 15233, 15233, 15233, -1, + 15234, 15234, 15234, -1, 15235, 15235, 15235, -1, + 15236, 15236, 15236, -1, 15237, 15237, 15237, -1, + 15238, 15238, 15238, -1, 15239, 15239, 15239, -1, + 15240, 15240, 15240, -1, 15241, 15241, 15241, -1, + 15242, 15242, 15242, -1, 15243, 15243, 15243, -1, + 15244, 15244, 15244, -1, 15245, 15245, 15245, -1, + 15246, 15246, 15246, -1, 15247, 15247, 15247, -1, + 15248, 15248, 15248, -1, 15249, 15249, 15249, -1, + 15250, 15250, 15250, -1, 15251, 15251, 15251, -1, + 15252, 15252, 15252, -1, 15253, 15253, 15253, -1, + 15254, 15254, 15254, -1, 15255, 15255, 15255, -1, + 15256, 15256, 15256, -1, 15257, 15257, 15257, -1, + 15258, 15258, 15258, -1, 15259, 15259, 15259, -1, + 15260, 15260, 15260, -1, 15261, 15261, 15261, -1, + 15262, 15262, 15262, -1, 15263, 15263, 15263, -1, + 15264, 15264, 15264, -1, 15265, 15265, 15265, -1, + 15266, 15266, 15266, -1, 15267, 15267, 15267, -1, + 15268, 15268, 15268, -1, 15269, 15269, 15269, -1, + 15270, 15270, 15270, -1, 15271, 15271, 15271, -1, + 15272, 15272, 15272, -1, 15273, 15273, 15273, -1, + 15274, 15274, 15274, -1, 15275, 15275, 15275, -1, + 15276, 15276, 15276, -1, 15277, 15277, 15277, -1, + 15278, 15278, 15278, -1, 15279, 15279, 15279, -1, + 15280, 15280, 15280, -1, 15281, 15281, 15281, -1, + 15282, 15282, 15282, -1, 15283, 15283, 15283, -1, + 15284, 15284, 15284, -1, 15285, 15285, 15285, -1, + 15286, 15286, 15286, -1, 15287, 15287, 15287, -1, + 15288, 15288, 15288, -1, 15289, 15289, 15289, -1, + 15290, 15290, 15290, -1, 15291, 15291, 15291, -1, + 15292, 15292, 15292, -1, 15293, 15293, 15293, -1, + 15294, 15294, 15294, -1, 15295, 15295, 15295, -1, + 15296, 15296, 15296, -1, 15297, 15297, 15297, -1, + 15298, 15298, 15298, -1, 15299, 15299, 15299, -1, + 15300, 15300, 15300, -1, 15301, 15301, 15301, -1, + 15302, 15302, 15302, -1, 15303, 15303, 15303, -1, + 15304, 15304, 15304, -1, 15305, 15305, 15305, -1, + 15306, 15306, 15306, -1, 15307, 15307, 15307, -1, + 15308, 15308, 15308, -1, 15309, 15309, 15309, -1, + 15310, 15310, 15310, -1, 15311, 15311, 15311, -1, + 15312, 15312, 15312, -1, 15313, 15313, 15313, -1, + 15314, 15314, 15314, -1, 15315, 15315, 15315, -1, + 15316, 15316, 15316, -1, 15317, 15317, 15317, -1, + 15318, 15318, 15318, -1, 15319, 15319, 15319, -1, + 15320, 15320, 15320, -1, 15321, 15321, 15321, -1, + 15322, 15322, 15322, -1, 15323, 15323, 15323, -1, + 15324, 15324, 15324, -1, 15325, 15325, 15325, -1, + 15326, 15326, 15326, -1, 15327, 15327, 15327, -1, + 15328, 15328, 15328, -1, 15329, 15329, 15329, -1, + 15330, 15330, 15330, -1, 15331, 15331, 15331, -1, + 15332, 15332, 15332, -1, 15333, 15333, 15333, -1, + 15334, 15334, 15334, -1, 15335, 15335, 15335, -1, + 15336, 15336, 15336, -1, 15337, 15337, 15337, -1, + 15338, 15338, 15338, -1, 15339, 15339, 15339, -1, + 15340, 15340, 15340, -1, 15341, 15341, 15341, -1, + 15342, 15342, 15342, -1, 15343, 15343, 15343, -1, + 15344, 15344, 15344, -1, 15345, 15345, 15345, -1, + 15346, 15346, 15346, -1, 15347, 15347, 15347, -1, + 15348, 15348, 15348, -1, 15349, 15349, 15349, -1, + 15350, 15350, 15350, -1, 15351, 15351, 15351, -1, + 15352, 15352, 15352, -1, 15353, 15353, 15353, -1, + 15354, 15354, 15354, -1, 15355, 15355, 15355, -1, + 15356, 15356, 15356, -1, 15357, 15357, 15357, -1, + 15358, 15358, 15358, -1, 15359, 15359, 15359, -1, + 15360, 15360, 15360, -1, 15361, 15361, 15361, -1, + 15362, 15362, 15362, -1, 15363, 15363, 15363, -1, + 15364, 15364, 15364, -1, 15365, 15365, 15365, -1, + 15366, 15366, 15366, -1, 15367, 15367, 15367, -1, + 15368, 15368, 15368, -1, 15369, 15369, 15369, -1, + 15370, 15370, 15370, -1, 15371, 15371, 15371, -1, + 15372, 15372, 15372, -1, 15373, 15373, 15373, -1, + 15374, 15374, 15374, -1, 15375, 15375, 15375, -1, + 15376, 15376, 15376, -1, 15377, 15377, 15377, -1, + 15378, 15378, 15378, -1, 15379, 15379, 15379, -1, + 15380, 15380, 15380, -1, 15381, 15381, 15381, -1, + 15382, 15382, 15382, -1, 15383, 15383, 15383, -1, + 15384, 15384, 15384, -1, 15385, 15385, 15385, -1, + 15386, 15386, 15386, -1, 15387, 15387, 15387, -1, + 15388, 15388, 15388, -1, 15389, 15389, 15389, -1, + 15390, 15390, 15390, -1, 15391, 15391, 15391, -1, + 15392, 15392, 15392, -1, 15393, 15393, 15393, -1, + 15394, 15394, 15394, -1, 15395, 15395, 15395, -1, + 15396, 15396, 15396, -1, 15397, 15397, 15397, -1, + 15398, 15398, 15398, -1, 15399, 15399, 15399, -1, + 15400, 15400, 15400, -1, 15401, 15401, 15401, -1, + 15402, 15402, 15402, -1, 15403, 15403, 15403, -1, + 15404, 15404, 15404, -1, 15405, 15405, 15405, -1, + 15406, 15406, 15406, -1, 15407, 15407, 15407, -1, + 15408, 15408, 15408, -1, 15409, 15409, 15409, -1, + 15410, 15410, 15410, -1, 15411, 15411, 15411, -1, + 15412, 15412, 15412, -1, 15413, 15413, 15413, -1, + 15414, 15414, 15414, -1, 15415, 15415, 15415, -1, + 15416, 15416, 15416, -1, 15417, 15417, 15417, -1, + 15418, 15418, 15418, -1, 15419, 15419, 15419, -1, + 15420, 15420, 15420, -1, 15421, 15421, 15421, -1, + 15422, 15422, 15422, -1, 15423, 15423, 15423, -1, + 15424, 15424, 15424, -1, 15425, 15425, 15425, -1, + 15426, 15426, 15426, -1, 15427, 15427, 15427, -1, + 15428, 15428, 15428, -1, 15429, 15429, 15429, -1, + 15430, 15430, 15430, -1, 15431, 15431, 15431, -1, + 15432, 15432, 15432, -1, 15433, 15433, 15433, -1, + 15434, 15434, 15434, -1, 15435, 15435, 15435, -1, + 15436, 15436, 15436, -1, 15437, 15437, 15437, -1, + 15438, 15438, 15438, -1, 15439, 15439, 15439, -1, + 15440, 15440, 15440, -1, 15441, 15441, 15441, -1, + 15442, 15442, 15442, -1, 15443, 15443, 15443, -1, + 15444, 15444, 15444, -1, 15445, 15445, 15445, -1, + 15446, 15446, 15446, -1, 15447, 15447, 15447, -1, + 15448, 15448, 15448, -1, 15449, 15449, 15449, -1, + 15450, 15450, 15450, -1, 15451, 15451, 15451, -1, + 15452, 15452, 15452, -1, 15453, 15453, 15453, -1, + 15454, 15454, 15454, -1, 15455, 15455, 15455, -1, + 15456, 15456, 15456, -1, 15457, 15457, 15457, -1, + 15458, 15458, 15458, -1, 15459, 15459, 15459, -1, + 15460, 15460, 15460, -1, 15461, 15461, 15461, -1, + 15462, 15462, 15462, -1, 15463, 15463, 15463, -1, + 15464, 15464, 15464, -1, 15465, 15465, 15465, -1, + 15466, 15466, 15466, -1, 15467, 15467, 15467, -1, + 15468, 15468, 15468, -1, 15469, 15469, 15469, -1, + 15470, 15470, 15470, -1, 15471, 15471, 15471, -1, + 15472, 15472, 15472, -1, 15473, 15473, 15473, -1, + 15474, 15474, 15474, -1, 15475, 15475, 15475, -1, + 15476, 15476, 15476, -1, 15477, 15477, 15477, -1, + 15478, 15478, 15478, -1, 15479, 15479, 15479, -1, + 15480, 15480, 15480, -1, 15481, 15481, 15481, -1, + 15482, 15482, 15482, -1, 15483, 15483, 15483, -1, + 15484, 15484, 15484, -1, 15485, 15485, 15485, -1, + 15486, 15486, 15486, -1, 15487, 15487, 15487, -1, + 15488, 15488, 15488, -1, 15489, 15489, 15489, -1, + 15490, 15490, 15490, -1, 15491, 15491, 15491, -1, + 15492, 15492, 15492, -1, 15493, 15493, 15493, -1, + 15494, 15494, 15494, -1, 15495, 15495, 15495, -1, + 15496, 15496, 15496, -1, 15497, 15497, 15497, -1, + 15498, 15498, 15498, -1, 15499, 15499, 15499, -1, + 15500, 15500, 15500, -1, 15501, 15501, 15501, -1, + 15502, 15502, 15502, -1, 15503, 15503, 15503, -1, + 15504, 15504, 15504, -1, 15505, 15505, 15505, -1, + 15506, 15506, 15506, -1, 15507, 15507, 15507, -1, + 15508, 15508, 15508, -1, 15509, 15509, 15509, -1, + 15510, 15510, 15510, -1, 15511, 15511, 15511, -1, + 15512, 15512, 15512, -1, 15513, 15513, 15513, -1, + 15514, 15514, 15514, -1, 15515, 15515, 15515, -1, + 15516, 15516, 15516, -1, 15517, 15517, 15517, -1, + 15518, 15518, 15518, -1, 15519, 15519, 15519, -1, + 15520, 15520, 15520, -1, 15521, 15521, 15521, -1, + 15522, 15522, 15522, -1, 15523, 15523, 15523, -1, + 15524, 15524, 15524, -1, 15525, 15525, 15525, -1, + 15526, 15526, 15526, -1, 15527, 15527, 15527, -1, + 15528, 15528, 15528, -1, 15529, 15529, 15529, -1, + 15530, 15530, 15530, -1, 15531, 15531, 15531, -1, + 15532, 15532, 15532, -1, 15533, 15533, 15533, -1, + 15534, 15534, 15534, -1, 15535, 15535, 15535, -1, + 15536, 15536, 15536, -1, 15537, 15537, 15537, -1, + 15538, 15538, 15538, -1, 15539, 15539, 15539, -1, + 15540, 15540, 15540, -1, 15541, 15541, 15541, -1, + 15542, 15542, 15542, -1, 15543, 15543, 15543, -1, + 15544, 15544, 15544, -1, 15545, 15545, 15545, -1, + 15546, 15546, 15546, -1, 15547, 15547, 15547, -1, + 15548, 15548, 15548, -1, 15549, 15549, 15549, -1, + 15550, 15550, 15550, -1, 15551, 15551, 15551, -1, + 15552, 15552, 15552, -1, 15553, 15553, 15553, -1, + 15554, 15554, 15554, -1, 15555, 15555, 15555, -1, + 15556, 15556, 15556, -1, 15557, 15557, 15557, -1, + 15558, 15558, 15558, -1, 15559, 15559, 15559, -1, + 15560, 15560, 15560, -1, 15561, 15561, 15561, -1, + 15562, 15562, 15562, -1, 15563, 15563, 15563, -1, + 15564, 15564, 15564, -1, 15565, 15565, 15565, -1, + 15566, 15566, 15566, -1, 15567, 15567, 15567, -1, + 15568, 15568, 15568, -1, 15569, 15569, 15569, -1, + 15570, 15570, 15570, -1, 15571, 15571, 15571, -1, + 15572, 15572, 15572, -1, 15573, 15573, 15573, -1, + 15574, 15574, 15574, -1, 15575, 15575, 15575, -1, + 15576, 15576, 15576, -1, 15577, 15577, 15577, -1, + 15578, 15578, 15578, -1, 15579, 15579, 15579, -1, + 15580, 15580, 15580, -1, 15581, 15581, 15581, -1, + 15582, 15582, 15582, -1, 15583, 15583, 15583, -1, + 15584, 15584, 15584, -1, 15585, 15585, 15585, -1, + 15586, 15586, 15586, -1, 15587, 15587, 15587, -1, + 15588, 15588, 15588, -1, 15589, 15589, 15589, -1, + 15590, 15590, 15590, -1, 15591, 15591, 15591, -1, + 15592, 15592, 15592, -1, 15593, 15593, 15593, -1, + 15594, 15594, 15594, -1, 15595, 15595, 15595, -1, + 15596, 15596, 15596, -1, 15597, 15597, 15597, -1, + 15598, 15598, 15598, -1, 15599, 15599, 15599, -1, + 15600, 15600, 15600, -1, 15601, 15601, 15601, -1, + 15602, 15602, 15602, -1, 15603, 15603, 15603, -1, + 15604, 15604, 15604, -1, 15605, 15605, 15605, -1, + 15606, 15606, 15606, -1, 15607, 15607, 15607, -1, + 15608, 15608, 15608, -1, 15609, 15609, 15609, -1, + 15610, 15610, 15610, -1, 15611, 15611, 15611, -1, + 15612, 15612, 15612, -1, 15613, 15613, 15613, -1, + 15614, 15614, 15614, -1, 15615, 15615, 15615, -1, + 15616, 15616, 15616, -1, 15617, 15617, 15617, -1, + 15618, 15618, 15618, -1, 15619, 15619, 15619, -1, + 15620, 15620, 15620, -1, 15621, 15621, 15621, -1, + 15622, 15622, 15622, -1, 15623, 15623, 15623, -1, + 15624, 15624, 15624, -1, 15625, 15625, 15625, -1, + 15626, 15626, 15626, -1, 15627, 15627, 15627, -1, + 15628, 15628, 15628, -1, 15629, 15629, 15629, -1, + 15630, 15630, 15630, -1, 15631, 15631, 15631, -1, + 15632, 15632, 15632, -1, 15633, 15633, 15633, -1, + 15634, 15634, 15634, -1, 15635, 15635, 15635, -1, + 15636, 15636, 15636, -1, 15637, 15637, 15637, -1, + 15638, 15638, 15638, -1, 15639, 15639, 15639, -1, + 15640, 15640, 15640, -1, 15641, 15641, 15641, -1, + 15642, 15642, 15642, -1, 15643, 15643, 15643, -1, + 15644, 15644, 15644, -1, 15645, 15645, 15645, -1, + 15646, 15646, 15646, -1, 15647, 15647, 15647, -1, + 15648, 15648, 15648, -1, 15649, 15649, 15649, -1, + 15650, 15650, 15650, -1, 15651, 15651, 15651, -1, + 15652, 15652, 15652, -1, 15653, 15653, 15653, -1, + 15654, 15654, 15654, -1, 15655, 15655, 15655, -1, + 15656, 15656, 15656, -1, 15657, 15657, 15657, -1, + 15658, 15658, 15658, -1, 15659, 15659, 15659, -1, + 15660, 15660, 15660, -1, 15661, 15661, 15661, -1, + 15662, 15662, 15662, -1, 15663, 15663, 15663, -1, + 15664, 15664, 15664, -1, 15665, 15665, 15665, -1, + 15666, 15666, 15666, -1, 15667, 15667, 15667, -1, + 15668, 15668, 15668, -1, 15669, 15669, 15669, -1, + 15670, 15670, 15670, -1, 15671, 15671, 15671, -1, + 15672, 15672, 15672, -1, 15673, 15673, 15673, -1, + 15674, 15674, 15674, -1, 15675, 15675, 15675, -1, + 15676, 15676, 15676, -1, 15677, 15677, 15677, -1, + 15678, 15678, 15678, -1, 15679, 15679, 15679, -1, + 15680, 15680, 15680, -1, 15681, 15681, 15681, -1, + 15682, 15682, 15682, -1, 15683, 15683, 15683, -1, + 15684, 15684, 15684, -1, 15685, 15685, 15685, -1, + 15686, 15686, 15686, -1, 15687, 15687, 15687, -1, + 15688, 15688, 15688, -1, 15689, 15689, 15689, -1, + 15690, 15690, 15690, -1, 15691, 15691, 15691, -1, + 15692, 15692, 15692, -1, 15693, 15693, 15693, -1, + 15694, 15694, 15694, -1, 15695, 15695, 15695, -1, + 15696, 15696, 15696, -1, 15697, 15697, 15697, -1, + 15698, 15698, 15698, -1, 15699, 15699, 15699, -1, + 15700, 15700, 15700, -1, 15701, 15701, 15701, -1, + 15702, 15702, 15702, -1, 15703, 15703, 15703, -1, + 15704, 15704, 15704, -1, 15705, 15705, 15705, -1, + 15706, 15706, 15706, -1, 15707, 15707, 15707, -1, + 15708, 15708, 15708, -1, 15709, 15709, 15709, -1, + 15710, 15710, 15710, -1, 15711, 15711, 15711, -1, + 15712, 15712, 15712, -1, 15713, 15713, 15713, -1, + 15714, 15714, 15714, -1, 15715, 15715, 15715, -1, + 15716, 15716, 15716, -1, 15717, 15717, 15717, -1, + 15718, 15718, 15718, -1, 15719, 15719, 15719, -1, + 15720, 15720, 15720, -1, 15721, 15721, 15721, -1, + 15722, 15722, 15722, -1, 15723, 15723, 15723, -1, + 15724, 15724, 15724, -1, 15725, 15725, 15725, -1, + 15726, 15726, 15726, -1, 15727, 15727, 15727, -1, + 15728, 15728, 15728, -1, 15729, 15729, 15729, -1, + 15730, 15730, 15730, -1, 15731, 15731, 15731, -1, + 15732, 15732, 15732, -1, 15733, 15733, 15733, -1, + 15734, 15734, 15734, -1, 15735, 15735, 15735, -1, + 15736, 15736, 15736, -1, 15737, 15737, 15737, -1, + 15738, 15738, 15738, -1, 15739, 15739, 15739, -1, + 15740, 15740, 15740, -1, 15741, 15741, 15741, -1, + 15742, 15742, 15742, -1, 15743, 15743, 15743, -1, + 15744, 15744, 15744, -1, 15745, 15745, 15745, -1, + 15746, 15746, 15746, -1, 15747, 15747, 15747, -1, + 15748, 15748, 15748, -1, 15749, 15749, 15749, -1, + 15750, 15750, 15750, -1, 15751, 15751, 15751, -1, + 15752, 15752, 15752, -1, 15753, 15753, 15753, -1, + 15754, 15754, 15754, -1, 15755, 15755, 15755, -1, + 15756, 15756, 15756, -1, 15757, 15757, 15757, -1, + 15758, 15758, 15758, -1, 15759, 15759, 15759, -1, + 15760, 15760, 15760, -1, 15761, 15761, 15761, -1, + 15762, 15762, 15762, -1, 15763, 15763, 15763, -1, + 15764, 15764, 15764, -1, 15765, 15765, 15765, -1, + 15766, 15766, 15766, -1, 15767, 15767, 15767, -1, + 15768, 15768, 15768, -1, 15769, 15769, 15769, -1, + 15770, 15770, 15770, -1, 15771, 15771, 15771, -1, + 15772, 15772, 15772, -1, 15773, 15773, 15773, -1, + 15774, 15774, 15774, -1, 15775, 15775, 15775, -1, + 15776, 15776, 15776, -1, 15777, 15777, 15777, -1, + 15778, 15778, 15778, -1, 15779, 15779, 15779, -1, + 15780, 15780, 15780, -1, 15781, 15781, 15781, -1, + 15782, 15782, 15782, -1, 15783, 15783, 15783, -1, + 15784, 15784, 15784, -1, 15785, 15785, 15785, -1, + 15786, 15786, 15786, -1, 15787, 15787, 15787, -1, + 15788, 15788, 15788, -1, 15789, 15789, 15789, -1, + 15790, 15790, 15790, -1, 15791, 15791, 15791, -1, + 15792, 15792, 15792, -1, 15793, 15793, 15793, -1, + 15794, 15794, 15794, -1, 15795, 15795, 15795, -1, + 15796, 15796, 15796, -1, 15797, 15797, 15797, -1, + 15798, 15798, 15798, -1, 15799, 15799, 15799, -1, + 15800, 15800, 15800, -1, 15801, 15801, 15801, -1, + 15802, 15802, 15802, -1, 15803, 15803, 15803, -1, + 15804, 15804, 15804, -1, 15805, 15805, 15805, -1, + 15806, 15806, 15806, -1, 15807, 15807, 15807, -1, + 15808, 15808, 15808, -1, 15809, 15809, 15809, -1, + 15810, 15810, 15810, -1, 15811, 15811, 15811, -1, + 15812, 15812, 15812, -1, 15813, 15813, 15813, -1, + 15814, 15814, 15814, -1, 15815, 15815, 15815, -1, + 15816, 15816, 15816, -1, 15817, 15817, 15817, -1, + 15818, 15818, 15818, -1, 15819, 15819, 15819, -1, + 15820, 15820, 15820, -1, 15821, 15821, 15821, -1, + 15822, 15822, 15822, -1, 15823, 15823, 15823, -1, + 15824, 15824, 15824, -1, 15825, 15825, 15825, -1, + 15826, 15826, 15826, -1, 15827, 15827, 15827, -1, + 15828, 15828, 15828, -1, 15829, 15829, 15829, -1, + 15830, 15830, 15830, -1, 15831, 15831, 15831, -1, + 15832, 15832, 15832, -1, 15833, 15833, 15833, -1, + 15834, 15834, 15834, -1, 15835, 15835, 15835, -1, + 15836, 15836, 15836, -1, 15837, 15837, 15837, -1, + 15838, 15838, 15838, -1, 15839, 15839, 15839, -1, + 15840, 15840, 15840, -1, 15841, 15841, 15841, -1, + 15842, 15842, 15842, -1, 15843, 15843, 15843, -1, + 15844, 15844, 15844, -1, 15845, 15845, 15845, -1, + 15846, 15846, 15846, -1, 15847, 15847, 15847, -1, + 15848, 15848, 15848, -1, 15849, 15849, 15849, -1, + 15850, 15850, 15850, -1, 15851, 15851, 15851, -1, + 15852, 15852, 15852, -1, 15853, 15853, 15853, -1, + 15854, 15854, 15854, -1, 15855, 15855, 15855, -1, + 15856, 15856, 15856, -1, 15857, 15857, 15857, -1, + 15858, 15858, 15858, -1, 15859, 15859, 15859, -1, + 15860, 15860, 15860, -1, 15861, 15861, 15861, -1, + 15862, 15862, 15862, -1, 15863, 15863, 15863, -1, + 15864, 15864, 15864, -1, 15865, 15865, 15865, -1, + 15866, 15866, 15866, -1, 15867, 15867, 15867, -1, + 15868, 15868, 15868, -1, 15869, 15869, 15869, -1, + 15870, 15870, 15870, -1, 15871, 15871, 15871, -1, + 15872, 15872, 15872, -1, 15873, 15873, 15873, -1, + 15874, 15874, 15874, -1, 15875, 15875, 15875, -1, + 15876, 15876, 15876, -1, 15877, 15877, 15877, -1, + 15878, 15878, 15878, -1, 15879, 15879, 15879, -1, + 15880, 15880, 15880, -1, 15881, 15881, 15881, -1, + 15882, 15882, 15882, -1, 15883, 15883, 15883, -1, + 15884, 15884, 15884, -1, 15885, 15885, 15885, -1, + 15886, 15886, 15886, -1, 15887, 15887, 15887, -1, + 15888, 15888, 15888, -1, 15889, 15889, 15889, -1, + 15890, 15890, 15890, -1, 15891, 15891, 15891, -1, + 15892, 15892, 15892, -1, 15893, 15893, 15893, -1, + 15894, 15894, 15894, -1, 15895, 15895, 15895, -1, + 15896, 15896, 15896, -1, 15897, 15897, 15897, -1, + 15898, 15898, 15898, -1, 15899, 15899, 15899, -1, + 15900, 15900, 15900, -1, 15901, 15901, 15901, -1, + 15902, 15902, 15902, -1, 15903, 15903, 15903, -1, + 15904, 15904, 15904, -1, 15905, 15905, 15905, -1, + 15906, 15906, 15906, -1, 15907, 15907, 15907, -1, + 15908, 15908, 15908, -1, 15909, 15909, 15909, -1, + 15910, 15910, 15910, -1, 15911, 15911, 15911, -1, + 15912, 15912, 15912, -1, 15913, 15913, 15913, -1, + 15914, 15914, 15914, -1, 15915, 15915, 15915, -1, + 15916, 15916, 15916, -1, 15917, 15917, 15917, -1, + 15918, 15918, 15918, -1, 15919, 15919, 15919, -1, + 15920, 15920, 15920, -1, 15921, 15921, 15921, -1, + 15922, 15922, 15922, -1, 15923, 15923, 15923, -1, + 15924, 15924, 15924, -1, 15925, 15925, 15925, -1, + 15926, 15926, 15926, -1, 15927, 15927, 15927, -1, + 15928, 15928, 15928, -1, 15929, 15929, 15929, -1, + 15930, 15930, 15930, -1, 15931, 15931, 15931, -1, + 15932, 15932, 15932, -1, 15933, 15933, 15933, -1, + 15934, 15934, 15934, -1, 15935, 15935, 15935, -1, + 15936, 15936, 15936, -1, 15937, 15937, 15937, -1, + 15938, 15938, 15938, -1, 15939, 15939, 15939, -1, + 15940, 15940, 15940, -1, 15941, 15941, 15941, -1, + 15942, 15942, 15942, -1, 15943, 15943, 15943, -1, + 15944, 15944, 15944, -1, 15945, 15945, 15945, -1, + 15946, 15946, 15946, -1, 15947, 15947, 15947, -1, + 15948, 15948, 15948, -1, 15949, 15949, 15949, -1, + 15950, 15950, 15950, -1, 15951, 15951, 15951, -1, + 15952, 15952, 15952, -1, 15953, 15953, 15953, -1, + 15954, 15954, 15954, -1, 15955, 15955, 15955, -1, + 15956, 15956, 15956, -1, 15957, 15957, 15957, -1, + 15958, 15958, 15958, -1, 15959, 15959, 15959, -1, + 15960, 15960, 15960, -1, 15961, 15961, 15961, -1, + 15962, 15962, 15962, -1, 15963, 15963, 15963, -1, + 15964, 15964, 15964, -1, 15965, 15965, 15965, -1, + 15966, 15966, 15966, -1, 15967, 15967, 15967, -1, + 15968, 15968, 15968, -1, 15969, 15969, 15969, -1, + 15970, 15970, 15970, -1, 15971, 15971, 15971, -1, + 15972, 15972, 15972, -1, 15973, 15973, 15973, -1, + 15974, 15974, 15974, -1, 15975, 15975, 15975, -1, + 15976, 15976, 15976, -1, 15977, 15977, 15977, -1, + 15978, 15978, 15978, -1, 15979, 15979, 15979, -1, + 15980, 15980, 15980, -1, 15981, 15981, 15981, -1, + 15982, 15982, 15982, -1, 15983, 15983, 15983, -1, + 15984, 15984, 15984, -1, 15985, 15985, 15985, -1, + 15986, 15986, 15986, -1, 15987, 15987, 15987, -1, + 15988, 15988, 15988, -1, 15989, 15989, 15989, -1, + 15990, 15990, 15990, -1, 15991, 15991, 15991, -1, + 15992, 15992, 15992, -1, 15993, 15993, 15993, -1, + 15994, 15994, 15994, -1, 15995, 15995, 15995, -1, + 15996, 15996, 15996, -1, 15997, 15997, 15997, -1, + 15998, 15998, 15998, -1, 15999, 15999, 15999, -1, + 16000, 16000, 16000, -1, 16001, 16001, 16001, -1, + 16002, 16002, 16002, -1, 16003, 16003, 16003, -1, + 16004, 16004, 16004, -1, 16005, 16005, 16005, -1, + 16006, 16006, 16006, -1, 16007, 16007, 16007, -1, + 16008, 16008, 16008, -1, 16009, 16009, 16009, -1, + 16010, 16010, 16010, -1, 16011, 16011, 16011, -1, + 16012, 16012, 16012, -1, 16013, 16013, 16013, -1, + 16014, 16014, 16014, -1, 16015, 16015, 16015, -1, + 16016, 16016, 16016, -1, 16017, 16017, 16017, -1, + 16018, 16018, 16018, -1, 16019, 16019, 16019, -1, + 16020, 16020, 16020, -1, 16021, 16021, 16021, -1, + 16022, 16022, 16022, -1, 16023, 16023, 16023, -1, + 16024, 16024, 16024, -1, 16025, 16025, 16025, -1, + 16026, 16026, 16026, -1, 16027, 16027, 16027, -1, + 16028, 16028, 16028, -1, 16029, 16029, 16029, -1, + 16030, 16030, 16030, -1, 16031, 16031, 16031, -1, + 16032, 16032, 16032, -1, 16033, 16033, 16033, -1, + 16034, 16034, 16034, -1, 16035, 16035, 16035, -1, + 16036, 16036, 16036, -1, 16037, 16037, 16037, -1, + 16038, 16038, 16038, -1, 16039, 16039, 16039, -1, + 16040, 16040, 16040, -1, 16041, 16041, 16041, -1, + 16042, 16042, 16042, -1, 16043, 16043, 16043, -1, + 16044, 16044, 16044, -1, 16045, 16045, 16045, -1, + 16046, 16046, 16046, -1, 16047, 16047, 16047, -1, + 16048, 16048, 16048, -1, 16049, 16049, 16049, -1, + 16050, 16050, 16050, -1, 16051, 16051, 16051, -1, + 16052, 16052, 16052, -1, 16053, 16053, 16053, -1, + 16054, 16054, 16054, -1, 16055, 16055, 16055, -1, + 16056, 16056, 16056, -1, 16057, 16057, 16057, -1, + 16058, 16058, 16058, -1, 16059, 16059, 16059, -1, + 16060, 16060, 16060, -1, 16061, 16061, 16061, -1, + 16062, 16062, 16062, -1, 16063, 16063, 16063, -1, + 16064, 16064, 16064, -1, 16065, 16065, 16065, -1, + 16066, 16066, 16066, -1, 16067, 16067, 16067, -1, + 16068, 16068, 16068, -1, 16069, 16069, 16069, -1, + 16070, 16070, 16070, -1, 16071, 16071, 16071, -1, + 16072, 16072, 16072, -1, 16073, 16073, 16073, -1, + 16074, 16074, 16074, -1, 16075, 16075, 16075, -1, + 16076, 16076, 16076, -1, 16077, 16077, 16077, -1, + 16078, 16078, 16078, -1, 16079, 16079, 16079, -1, + 16080, 16080, 16080, -1, 16081, 16081, 16081, -1, + 16082, 16082, 16082, -1, 16083, 16083, 16083, -1, + 16084, 16084, 16084, -1, 16085, 16085, 16085, -1, + 16086, 16086, 16086, -1, 16087, 16087, 16087, -1, + 16088, 16088, 16088, -1, 16089, 16089, 16089, -1, + 16090, 16090, 16090, -1, 16091, 16091, 16091, -1, + 16092, 16092, 16092, -1, 16093, 16093, 16093, -1, + 16094, 16094, 16094, -1, 16095, 16095, 16095, -1, + 16096, 16096, 16096, -1, 16097, 16097, 16097, -1, + 16098, 16098, 16098, -1, 16099, 16099, 16099, -1, + 16100, 16100, 16100, -1, 16101, 16101, 16101, -1, + 16102, 16102, 16102, -1, 16103, 16103, 16103, -1, + 16104, 16104, 16104, -1, 16105, 16105, 16105, -1, + 16106, 16106, 16106, -1, 16107, 16107, 16107, -1, + 16108, 16108, 16108, -1, 16109, 16109, 16109, -1, + 16110, 16110, 16110, -1, 16111, 16111, 16111, -1, + 16112, 16112, 16112, -1, 16113, 16113, 16113, -1, + 16114, 16114, 16114, -1, 16115, 16115, 16115, -1, + 16116, 16116, 16116, -1, 16117, 16117, 16117, -1, + 16118, 16118, 16118, -1, 16119, 16119, 16119, -1, + 16120, 16120, 16120, -1, 16121, 16121, 16121, -1, + 16122, 16122, 16122, -1, 16123, 16123, 16123, -1, + 16124, 16124, 16124, -1, 16125, 16125, 16125, -1, + 16126, 16126, 16126, -1, 16127, 16127, 16127, -1, + 16128, 16128, 16128, -1, 16129, 16129, 16129, -1, + 16130, 16130, 16130, -1, 16131, 16131, 16131, -1, + 16132, 16132, 16132, -1, 16133, 16133, 16133, -1, + 16134, 16134, 16134, -1, 16135, 16135, 16135, -1, + 16136, 16136, 16136, -1, 16137, 16137, 16137, -1, + 16138, 16138, 16138, -1, 16139, 16139, 16139, -1, + 16140, 16140, 16140, -1, 16141, 16141, 16141, -1, + 16142, 16142, 16142, -1, 16143, 16143, 16143, -1, + 16144, 16144, 16144, -1, 16145, 16145, 16145, -1, + 16146, 16146, 16146, -1, 16147, 16147, 16147, -1, + 16148, 16148, 16148, -1, 16149, 16149, 16149, -1, + 16150, 16150, 16150, -1, 16151, 16151, 16151, -1, + 16152, 16152, 16152, -1, 16153, 16153, 16153, -1, + 16154, 16154, 16154, -1, 16155, 16155, 16155, -1, + 16156, 16156, 16156, -1, 16157, 16157, 16157, -1, + 16158, 16158, 16158, -1, 16159, 16159, 16159, -1, + 16160, 16160, 16160, -1, 16161, 16161, 16161, -1, + 16162, 16162, 16162, -1, 16163, 16163, 16163, -1, + 16164, 16164, 16164, -1, 16165, 16165, 16165, -1, + 16166, 16166, 16166, -1, 16167, 16167, 16167, -1, + 16168, 16168, 16168, -1, 16169, 16169, 16169, -1, + 16170, 16170, 16170, -1, 16171, 16171, 16171, -1, + 16172, 16172, 16172, -1, 16173, 16173, 16173, -1, + 16174, 16174, 16174, -1, 16175, 16175, 16175, -1, + 16176, 16176, 16176, -1, 16177, 16177, 16177, -1, + 16178, 16178, 16178, -1, 16179, 16179, 16179, -1, + 16180, 16180, 16180, -1, 16181, 16181, 16181, -1, + 16182, 16182, 16182, -1, 16183, 16183, 16183, -1, + 16184, 16184, 16184, -1, 16185, 16185, 16185, -1, + 16186, 16186, 16186, -1, 16187, 16187, 16187, -1, + 16188, 16188, 16188, -1, 16189, 16189, 16189, -1, + 16190, 16190, 16190, -1, 16191, 16191, 16191, -1, + 16192, 16192, 16192, -1, 16193, 16193, 16193, -1, + 16194, 16194, 16194, -1, 16195, 16195, 16195, -1, + 16196, 16196, 16196, -1, 16197, 16197, 16197, -1, + 16198, 16198, 16198, -1, 16199, 16199, 16199, -1, + 16200, 16200, 16200, -1, 16201, 16201, 16201, -1, + 16202, 16202, 16202, -1, 16203, 16203, 16203, -1, + 16204, 16204, 16204, -1, 16205, 16205, 16205, -1, + 16206, 16206, 16206, -1, 16207, 16207, 16207, -1, + 16208, 16208, 16208, -1, 16209, 16209, 16209, -1, + 16210, 16210, 16210, -1, 16211, 16211, 16211, -1, + 16212, 16212, 16212, -1, 16213, 16213, 16213, -1, + 16214, 16214, 16214, -1, 16215, 16215, 16215, -1, + 16216, 16216, 16216, -1, 16217, 16217, 16217, -1, + 16218, 16218, 16218, -1, 16219, 16219, 16219, -1, + 16220, 16220, 16220, -1, 16221, 16221, 16221, -1, + 16222, 16222, 16222, -1, 16223, 16223, 16223, -1, + 16224, 16224, 16224, -1, 16225, 16225, 16225, -1, + 16226, 16226, 16226, -1, 16227, 16227, 16227, -1, + 16228, 16228, 16228, -1, 16229, 16229, 16229, -1, + 16230, 16230, 16230, -1, 16231, 16231, 16231, -1, + 16232, 16232, 16232, -1, 16233, 16233, 16233, -1, + 16234, 16234, 16234, -1, 16235, 16235, 16235, -1, + 16236, 16236, 16236, -1, 16237, 16237, 16237, -1, + 16238, 16238, 16238, -1, 16239, 16239, 16239, -1, + 16240, 16240, 16240, -1, 16241, 16241, 16241, -1, + 16242, 16242, 16242, -1, 16243, 16243, 16243, -1, + 16244, 16244, 16244, -1, 16245, 16245, 16245, -1, + 16246, 16246, 16246, -1, 16247, 16247, 16247, -1, + 16248, 16248, 16248, -1, 16249, 16249, 16249, -1, + 16250, 16250, 16250, -1, 16251, 16251, 16251, -1, + 16252, 16252, 16252, -1, 16253, 16253, 16253, -1, + 16254, 16254, 16254, -1, 16255, 16255, 16255, -1, + 16256, 16256, 16256, -1, 16257, 16257, 16257, -1, + 16258, 16258, 16258, -1, 16259, 16259, 16259, -1, + 16260, 16260, 16260, -1, 16261, 16261, 16261, -1, + 16262, 16262, 16262, -1, 16263, 16263, 16263, -1, + 16264, 16264, 16264, -1, 16265, 16265, 16265, -1, + 16266, 16266, 16266, -1, 16267, 16267, 16267, -1, + 16268, 16268, 16268, -1, 16269, 16269, 16269, -1, + 16270, 16270, 16270, -1, 16271, 16271, 16271, -1, + 16272, 16272, 16272, -1, 16273, 16273, 16273, -1, + 16274, 16274, 16274, -1, 16275, 16275, 16275, -1, + 16276, 16276, 16276, -1, 16277, 16277, 16277, -1, + 16278, 16278, 16278, -1, 16279, 16279, 16279, -1, + 16280, 16280, 16280, -1, 16281, 16281, 16281, -1, + 16282, 16282, 16282, -1, 16283, 16283, 16283, -1, + 16284, 16284, 16284, -1, 16285, 16285, 16285, -1, + 16286, 16286, 16286, -1, 16287, 16287, 16287, -1, + 16288, 16288, 16288, -1, 16289, 16289, 16289, -1, + 16290, 16290, 16290, -1, 16291, 16291, 16291, -1, + 16292, 16292, 16292, -1, 16293, 16293, 16293, -1, + 16294, 16294, 16294, -1, 16295, 16295, 16295, -1, + 16296, 16296, 16296, -1, 16297, 16297, 16297, -1, + 16298, 16298, 16298, -1, 16299, 16299, 16299, -1, + 16300, 16300, 16300, -1, 16301, 16301, 16301, -1, + 16302, 16302, 16302, -1, 16303, 16303, 16303, -1, + 16304, 16304, 16304, -1, 16305, 16305, 16305, -1, + 16306, 16306, 16306, -1, 16307, 16307, 16307, -1, + 16308, 16308, 16308, -1, 16309, 16309, 16309, -1, + 16310, 16310, 16310, -1, 16311, 16311, 16311, -1, + 16312, 16312, 16312, -1, 16313, 16313, 16313, -1, + 16314, 16314, 16314, -1, 16315, 16315, 16315, -1, + 16316, 16316, 16316, -1, 16317, 16317, 16317, -1, + 16318, 16318, 16318, -1, 16319, 16319, 16319, -1, + 16320, 16320, 16320, -1, 16321, 16321, 16321, -1, + 16322, 16322, 16322, -1, 16323, 16323, 16323, -1, + 16324, 16324, 16324, -1, 16325, 16325, 16325, -1, + 16326, 16326, 16326, -1, 16327, 16327, 16327, -1, + 16328, 16328, 16328, -1, 16329, 16329, 16329, -1, + 16330, 16330, 16330, -1, 16331, 16331, 16331, -1, + 16332, 16332, 16332, -1, 16333, 16333, 16333, -1, + 16334, 16334, 16334, -1, 16335, 16335, 16335, -1, + 16336, 16336, 16336, -1, 16337, 16337, 16337, -1, + 16338, 16338, 16338, -1, 16339, 16339, 16339, -1, + 16340, 16340, 16340, -1, 16341, 16341, 16341, -1, + 16342, 16342, 16342, -1, 16343, 16343, 16343, -1, + 16344, 16344, 16344, -1, 16345, 16345, 16345, -1, + 16346, 16346, 16346, -1, 16347, 16347, 16347, -1, + 16348, 16348, 16348, -1, 16349, 16349, 16349, -1, + 16350, 16350, 16350, -1, 16351, 16351, 16351, -1, + 16352, 16352, 16352, -1, 16353, 16353, 16353, -1, + 16354, 16354, 16354, -1, 16355, 16355, 16355, -1, + 16356, 16356, 16356, -1, 16357, 16357, 16357, -1, + 16358, 16358, 16358, -1, 16359, 16359, 16359, -1, + 16360, 16360, 16360, -1, 16361, 16361, 16361, -1, + 16362, 16362, 16362, -1, 16363, 16363, 16363, -1, + 16364, 16364, 16364, -1, 16365, 16365, 16365, -1, + 16366, 16366, 16366, -1, 16367, 16367, 16367, -1, + 16368, 16368, 16368, -1, 16369, 16369, 16369, -1, + 16370, 16370, 16370, -1, 16371, 16371, 16371, -1, + 16372, 16372, 16372, -1, 16373, 16373, 16373, -1, + 16374, 16374, 16374, -1, 16375, 16375, 16375, -1, + 16376, 16376, 16376, -1, 16377, 16377, 16377, -1, + 16378, 16378, 16378, -1, 16379, 16379, 16379, -1, + 16380, 16380, 16380, -1, 16381, 16381, 16381, -1, + 16382, 16382, 16382, -1, 16383, 16383, 16383, -1, + 16384, 16384, 16384, -1, 16385, 16385, 16385, -1, + 16386, 16386, 16386, -1, 16387, 16387, 16387, -1, + 16388, 16388, 16388, -1, 16389, 16389, 16389, -1, + 16390, 16390, 16390, -1, 16391, 16391, 16391, -1, + 16392, 16392, 16392, -1, 16393, 16393, 16393, -1, + 16394, 16394, 16394, -1, 16395, 16395, 16395, -1, + 16396, 16396, 16396, -1, 16397, 16397, 16397, -1, + 16398, 16398, 16398, -1, 16399, 16399, 16399, -1, + 16400, 16400, 16400, -1, 16401, 16401, 16401, -1, + 16402, 16402, 16402, -1, 16403, 16403, 16403, -1, + 16404, 16404, 16404, -1, 16405, 16405, 16405, -1, + 16406, 16406, 16406, -1, 16407, 16407, 16407, -1, + 16408, 16408, 16408, -1, 16409, 16409, 16409, -1, + 16410, 16410, 16410, -1, 16411, 16411, 16411, -1, + 16412, 16412, 16412, -1, 16413, 16413, 16413, -1, + 16414, 16414, 16414, -1, 16415, 16415, 16415, -1, + 16416, 16416, 16416, -1, 16417, 16417, 16417, -1, + 16418, 16418, 16418, -1, 16419, 16419, 16419, -1, + 16420, 16420, 16420, -1, 16421, 16421, 16421, -1, + 16422, 16422, 16422, -1, 16423, 16423, 16423, -1, + 16424, 16424, 16424, -1, 16425, 16425, 16425, -1, + 16426, 16426, 16426, -1, 16427, 16427, 16427, -1, + 16428, 16428, 16428, -1, 16429, 16429, 16429, -1, + 16430, 16430, 16430, -1, 16431, 16431, 16431, -1, + 16432, 16432, 16432, -1, 16433, 16433, 16433, -1, + 16434, 16434, 16434, -1, 16435, 16435, 16435, -1, + 16436, 16436, 16436, -1, 16437, 16437, 16437, -1, + 16438, 16438, 16438, -1, 16439, 16439, 16439, -1, + 16440, 16440, 16440, -1, 16441, 16441, 16441, -1, + 16442, 16442, 16442, -1, 16443, 16443, 16443, -1, + 16444, 16444, 16444, -1, 16445, 16445, 16445, -1, + 16446, 16446, 16446, -1, 16447, 16447, 16447, -1, + 16448, 16448, 16448, -1, 16449, 16449, 16449, -1, + 16450, 16450, 16450, -1, 16451, 16451, 16451, -1, + 16452, 16452, 16452, -1, 16453, 16453, 16453, -1, + 16454, 16454, 16454, -1, 16455, 16455, 16455, -1, + 16456, 16456, 16456, -1, 16457, 16457, 16457, -1, + 16458, 16458, 16458, -1, 16459, 16459, 16459, -1, + 16460, 16460, 16460, -1, 16461, 16461, 16461, -1, + 16462, 16462, 16462, -1, 16463, 16463, 16463, -1, + 16464, 16464, 16464, -1, 16465, 16465, 16465, -1, + 16466, 16466, 16466, -1, 16467, 16467, 16467, -1, + 16468, 16468, 16468, -1, 16469, 16469, 16469, -1, + 16470, 16470, 16470, -1, 16471, 16471, 16471, -1, + 16472, 16472, 16472, -1, 16473, 16473, 16473, -1, + 16474, 16474, 16474, -1, 16475, 16475, 16475, -1, + 16476, 16476, 16476, -1, 16477, 16477, 16477, -1, + 16478, 16478, 16478, -1, 16479, 16479, 16479, -1, + 16480, 16480, 16480, -1, 16481, 16481, 16481, -1, + 16482, 16482, 16482, -1, 16483, 16483, 16483, -1, + 16484, 16484, 16484, -1, 16485, 16485, 16485, -1, + 16486, 16486, 16486, -1, 16487, 16487, 16487, -1, + 16488, 16488, 16488, -1, 16489, 16489, 16489, -1, + 16490, 16490, 16490, -1, 16491, 16491, 16491, -1, + 16492, 16492, 16492, -1, 16493, 16493, 16493, -1, + 16494, 16494, 16494, -1, 16495, 16495, 16495, -1, + 16496, 16496, 16496, -1, 16497, 16497, 16497, -1, + 16498, 16498, 16498, -1, 16499, 16499, 16499, -1, + 16500, 16500, 16500, -1, 16501, 16501, 16501, -1, + 16502, 16502, 16502, -1, 16503, 16503, 16503, -1, + 16504, 16504, 16504, -1, 16505, 16505, 16505, -1, + 16506, 16506, 16506, -1, 16507, 16507, 16507, -1, + 16508, 16508, 16508, -1, 16509, 16509, 16509, -1, + 16510, 16510, 16510, -1, 16511, 16511, 16511, -1, + 16512, 16512, 16512, -1, 16513, 16513, 16513, -1, + 16514, 16514, 16514, -1, 16515, 16515, 16515, -1, + 16516, 16516, 16516, -1, 16517, 16517, 16517, -1, + 16518, 16518, 16518, -1, 16519, 16519, 16519, -1, + 16520, 16520, 16520, -1, 16521, 16521, 16521, -1, + 16522, 16522, 16522, -1, 16523, 16523, 16523, -1, + 16524, 16524, 16524, -1, 16525, 16525, 16525, -1, + 16526, 16526, 16526, -1, 16527, 16527, 16527, -1, + 16528, 16528, 16528, -1, 16529, 16529, 16529, -1, + 16530, 16530, 16530, -1, 16531, 16531, 16531, -1, + 16532, 16532, 16532, -1, 16533, 16533, 16533, -1, + 16534, 16534, 16534, -1, 16535, 16535, 16535, -1, + 16536, 16536, 16536, -1, 16537, 16537, 16537, -1, + 16538, 16538, 16538, -1, 16539, 16539, 16539, -1, + 16540, 16540, 16540, -1, 16541, 16541, 16541, -1, + 16542, 16542, 16542, -1, 16543, 16543, 16543, -1, + 16544, 16544, 16544, -1, 16545, 16545, 16545, -1, + 16546, 16546, 16546, -1, 16547, 16547, 16547, -1, + 16548, 16548, 16548, -1, 16549, 16549, 16549, -1, + 16550, 16550, 16550, -1, 16551, 16551, 16551, -1, + 16552, 16552, 16552, -1, 16553, 16553, 16553, -1, + 16554, 16554, 16554, -1, 16555, 16555, 16555, -1, + 16556, 16556, 16556, -1, 16557, 16557, 16557, -1, + 16558, 16558, 16558, -1, 16559, 16559, 16559, -1, + 16560, 16560, 16560, -1, 16561, 16561, 16561, -1, + 16562, 16562, 16562, -1, 16563, 16563, 16563, -1, + 16564, 16564, 16564, -1, 16565, 16565, 16565, -1, + 16566, 16566, 16566, -1, 16567, 16567, 16567, -1, + 16568, 16568, 16568, -1, 16569, 16569, 16569, -1, + 16570, 16570, 16570, -1, 16571, 16571, 16571, -1, + 16572, 16572, 16572, -1, 16573, 16573, 16573, -1, + 16574, 16574, 16574, -1, 16575, 16575, 16575, -1, + 16576, 16576, 16576, -1, 16577, 16577, 16577, -1, + 16578, 16578, 16578, -1, 16579, 16579, 16579, -1, + 16580, 16580, 16580, -1, 16581, 16581, 16581, -1, + 16582, 16582, 16582, -1, 16583, 16583, 16583, -1, + 16584, 16584, 16584, -1, 16585, 16585, 16585, -1, + 16586, 16586, 16586, -1, 16587, 16587, 16587, -1, + 16588, 16588, 16588, -1, 16589, 16589, 16589, -1, + 16590, 16590, 16590, -1, 16591, 16591, 16591, -1, + 16592, 16592, 16592, -1, 16593, 16593, 16593, -1, + 16594, 16594, 16594, -1, 16595, 16595, 16595, -1, + 16596, 16596, 16596, -1, 16597, 16597, 16597, -1, + 16598, 16598, 16598, -1, 16599, 16599, 16599, -1, + 16600, 16600, 16600, -1, 16601, 16601, 16601, -1, + 16602, 16602, 16602, -1, 16603, 16603, 16603, -1, + 16604, 16604, 16604, -1, 16605, 16605, 16605, -1, + 16606, 16606, 16606, -1, 16607, 16607, 16607, -1, + 16608, 16608, 16608, -1, 16609, 16609, 16609, -1, + 16610, 16610, 16610, -1, 16611, 16611, 16611, -1, + 16612, 16612, 16612, -1, 16613, 16613, 16613, -1, + 16614, 16614, 16614, -1, 16615, 16615, 16615, -1, + 16616, 16616, 16616, -1, 16617, 16617, 16617, -1, + 16618, 16618, 16618, -1, 16619, 16619, 16619, -1, + 16620, 16620, 16620, -1, 16621, 16621, 16621, -1, + 16622, 16622, 16622, -1, 16623, 16623, 16623, -1, + 16624, 16624, 16624, -1, 16625, 16625, 16625, -1, + 16626, 16626, 16626, -1, 16627, 16627, 16627, -1, + 16628, 16628, 16628, -1, 16629, 16629, 16629, -1, + 16630, 16630, 16630, -1, 16631, 16631, 16631, -1, + 16632, 16632, 16632, -1, 16633, 16633, 16633, -1, + 16634, 16634, 16634, -1, 16635, 16635, 16635, -1, + 16636, 16636, 16636, -1, 16637, 16637, 16637, -1, + 16638, 16638, 16638, -1, 16639, 16639, 16639, -1, + 16640, 16640, 16640, -1, 16641, 16641, 16641, -1, + 16642, 16642, 16642, -1, 16643, 16643, 16643, -1, + 16644, 16644, 16644, -1, 16645, 16645, 16645, -1, + 16646, 16646, 16646, -1, 16647, 16647, 16647, -1, + 16648, 16648, 16648, -1, 16649, 16649, 16649, -1, + 16650, 16650, 16650, -1, 16651, 16651, 16651, -1, + 16652, 16652, 16652, -1, 16653, 16653, 16653, -1, + 16654, 16654, 16654, -1, 16655, 16655, 16655, -1, + 16656, 16656, 16656, -1, 16657, 16657, 16657, -1, + 16658, 16658, 16658, -1, 16659, 16659, 16659, -1, + 16660, 16660, 16660, -1, 16661, 16661, 16661, -1, + 16662, 16662, 16662, -1, 16663, 16663, 16663, -1, + 16664, 16664, 16664, -1, 16665, 16665, 16665, -1, + 16666, 16666, 16666, -1, 16667, 16667, 16667, -1, + 16668, 16668, 16668, -1, 16669, 16669, 16669, -1, + 16670, 16670, 16670, -1, 16671, 16671, 16671, -1, + 16672, 16672, 16672, -1, 16673, 16673, 16673, -1, + 16674, 16674, 16674, -1, 16675, 16675, 16675, -1, + 16676, 16676, 16676, -1, 16677, 16677, 16677, -1, + 16678, 16678, 16678, -1, 16679, 16679, 16679, -1, + 16680, 16680, 16680, -1, 16681, 16681, 16681, -1, + 16682, 16682, 16682, -1, 16683, 16683, 16683, -1, + 16684, 16684, 16684, -1, 16685, 16685, 16685, -1, + 16686, 16686, 16686, -1, 16687, 16687, 16687, -1, + 16688, 16688, 16688, -1, 16689, 16689, 16689, -1, + 16690, 16690, 16690, -1, 16691, 16691, 16691, -1, + 16692, 16692, 16692, -1, 16693, 16693, 16693, -1, + 16694, 16694, 16694, -1, 16695, 16695, 16695, -1, + 16696, 16696, 16696, -1, 16697, 16697, 16697, -1, + 16698, 16698, 16698, -1, 16699, 16699, 16699, -1, + 16700, 16700, 16700, -1, 16701, 16701, 16701, -1, + 16702, 16702, 16702, -1, 16703, 16703, 16703, -1, + 16704, 16704, 16704, -1, 16705, 16705, 16705, -1, + 16706, 16706, 16706, -1, 16707, 16707, 16707, -1, + 16708, 16708, 16708, -1, 16709, 16709, 16709, -1, + 16710, 16710, 16710, -1, 16711, 16711, 16711, -1, + 16712, 16712, 16712, -1, 16713, 16713, 16713, -1, + 16714, 16714, 16714, -1, 16715, 16715, 16715, -1, + 16716, 16716, 16716, -1, 16717, 16717, 16717, -1, + 16718, 16718, 16718, -1, 16719, 16719, 16719, -1, + 16720, 16720, 16720, -1, 16721, 16721, 16721, -1, + 16722, 16722, 16722, -1, 16723, 16723, 16723, -1, + 16724, 16724, 16724, -1, 16725, 16725, 16725, -1, + 16726, 16726, 16726, -1, 16727, 16727, 16727, -1, + 16728, 16728, 16728, -1, 16729, 16729, 16729, -1, + 16730, 16730, 16730, -1, 16731, 16731, 16731, -1, + 16732, 16732, 16732, -1, 16733, 16733, 16733, -1, + 16734, 16734, 16734, -1, 16735, 16735, 16735, -1, + 16736, 16736, 16736, -1, 16737, 16737, 16737, -1, + 16738, 16738, 16738, -1, 16739, 16739, 16739, -1, + 16740, 16740, 16740, -1, 16741, 16741, 16741, -1, + 16742, 16742, 16742, -1, 16743, 16743, 16743, -1, + 16744, 16744, 16744, -1, 16745, 16745, 16745, -1, + 16746, 16746, 16746, -1, 16747, 16747, 16747, -1, + 16748, 16748, 16748, -1, 16749, 16749, 16749, -1, + 16750, 16750, 16750, -1, 16751, 16751, 16751, -1, + 16752, 16752, 16752, -1, 16753, 16753, 16753, -1, + 16754, 16754, 16754, -1, 16755, 16755, 16755, -1, + 16756, 16756, 16756, -1, 16757, 16757, 16757, -1, + 16758, 16758, 16758, -1, 16759, 16759, 16759, -1, + 16760, 16760, 16760, -1, 16761, 16761, 16761, -1, + 16762, 16762, 16762, -1, 16763, 16763, 16763, -1, + 16764, 16764, 16764, -1, 16765, 16765, 16765, -1, + 16766, 16766, 16766, -1, 16767, 16767, 16767, -1, + 16768, 16768, 16768, -1, 16769, 16769, 16769, -1, + 16770, 16770, 16770, -1, 16771, 16771, 16771, -1, + 16772, 16772, 16772, -1, 16773, 16773, 16773, -1, + 16774, 16774, 16774, -1, 16775, 16775, 16775, -1, + 16776, 16776, 16776, -1, 16777, 16777, 16777, -1, + 16778, 16778, 16778, -1, 16779, 16779, 16779, -1, + 16780, 16780, 16780, -1, 16781, 16781, 16781, -1, + 16782, 16782, 16782, -1, 16783, 16783, 16783, -1, + 16784, 16784, 16784, -1, 16785, 16785, 16785, -1, + 16786, 16786, 16786, -1, 16787, 16787, 16787, -1, + 16788, 16788, 16788, -1, 16789, 16789, 16789, -1, + 16790, 16790, 16790, -1, 16791, 16791, 16791, -1, + 16792, 16792, 16792, -1, 16793, 16793, 16793, -1, + 16794, 16794, 16794, -1, 16795, 16795, 16795, -1, + 16796, 16796, 16796, -1, 16797, 16797, 16797, -1, + 16798, 16798, 16798, -1, 16799, 16799, 16799, -1, + 16800, 16800, 16800, -1, 16801, 16801, 16801, -1, + 16802, 16802, 16802, -1, 16803, 16803, 16803, -1, + 16804, 16804, 16804, -1, 16805, 16805, 16805, -1, + 16806, 16806, 16806, -1, 16807, 16807, 16807, -1, + 16808, 16808, 16808, -1, 16809, 16809, 16809, -1, + 16810, 16810, 16810, -1, 16811, 16811, 16811, -1, + 16812, 16812, 16812, -1, 16813, 16813, 16813, -1, + 16814, 16814, 16814, -1, 16815, 16815, 16815, -1, + 16816, 16816, 16816, -1, 16817, 16817, 16817, -1, + 16818, 16818, 16818, -1, 16819, 16819, 16819, -1, + 16820, 16820, 16820, -1, 16821, 16821, 16821, -1, + 16822, 16822, 16822, -1, 16823, 16823, 16823, -1, + 16824, 16824, 16824, -1, 16825, 16825, 16825, -1, + 16826, 16826, 16826, -1, 16827, 16827, 16827, -1, + 16828, 16828, 16828, -1, 16829, 16829, 16829, -1, + 16830, 16830, 16830, -1, 16831, 16831, 16831, -1, + 16832, 16832, 16832, -1, 16833, 16833, 16833, -1, + 16834, 16834, 16834, -1, 16835, 16835, 16835, -1, + 16836, 16836, 16836, -1, 16837, 16837, 16837, -1, + 16838, 16838, 16838, -1, 16839, 16839, 16839, -1, + 16840, 16840, 16840, -1, 16841, 16841, 16841, -1, + 16842, 16842, 16842, -1, 16843, 16843, 16843, -1, + 16844, 16844, 16844, -1, 16845, 16845, 16845, -1, + 16846, 16846, 16846, -1, 16847, 16847, 16847, -1, + 16848, 16848, 16848, -1, 16849, 16849, 16849, -1, + 16850, 16850, 16850, -1, 16851, 16851, 16851, -1, + 16852, 16852, 16852, -1, 16853, 16853, 16853, -1, + 16854, 16854, 16854, -1, 16855, 16855, 16855, -1, + 16856, 16856, 16856, -1, 16857, 16857, 16857, -1, + 16858, 16858, 16858, -1, 16859, 16859, 16859, -1, + 16860, 16860, 16860, -1, 16861, 16861, 16861, -1, + 16862, 16862, 16862, -1, 16863, 16863, 16863, -1, + 16864, 16864, 16864, -1, 16865, 16865, 16865, -1, + 16866, 16866, 16866, -1, 16867, 16867, 16867, -1, + 16868, 16868, 16868, -1, 16869, 16869, 16869, -1, + 16870, 16870, 16870, -1, 16871, 16871, 16871, -1, + 16872, 16872, 16872, -1, 16873, 16873, 16873, -1, + 16874, 16874, 16874, -1, 16875, 16875, 16875, -1, + 16876, 16876, 16876, -1, 16877, 16877, 16877, -1, + 16878, 16878, 16878, -1, 16879, 16879, 16879, -1, + 16880, 16880, 16880, -1, 16881, 16881, 16881, -1, + 16882, 16882, 16882, -1, 16883, 16883, 16883, -1, + 16884, 16884, 16884, -1, 16885, 16885, 16885, -1, + 16886, 16886, 16886, -1, 16887, 16887, 16887, -1, + 16888, 16888, 16888, -1, 16889, 16889, 16889, -1, + 16890, 16890, 16890, -1, 16891, 16891, 16891, -1, + 16892, 16892, 16892, -1, 16893, 16893, 16893, -1, + 16894, 16894, 16894, -1, 16895, 16895, 16895, -1, + 16896, 16896, 16896, -1, 16897, 16897, 16897, -1, + 16898, 16898, 16898, -1, 16899, 16899, 16899, -1, + 16900, 16900, 16900, -1, 16901, 16901, 16901, -1, + 16902, 16902, 16902, -1, 16903, 16903, 16903, -1, + 16904, 16904, 16904, -1, 16905, 16905, 16905, -1, + 16906, 16906, 16906, -1, 16907, 16907, 16907, -1, + 16908, 16908, 16908, -1, 16909, 16909, 16909, -1, + 16910, 16910, 16910, -1, 16911, 16911, 16911, -1, + 16912, 16912, 16912, -1, 16913, 16913, 16913, -1, + 16914, 16914, 16914, -1, 16915, 16915, 16915, -1, + 16916, 16916, 16916, -1, 16917, 16917, 16917, -1, + 16918, 16918, 16918, -1, 16919, 16919, 16919, -1, + 16920, 16920, 16920, -1, 16921, 16921, 16921, -1, + 16922, 16922, 16922, -1, 16923, 16923, 16923, -1, + 16924, 16924, 16924, -1, 16925, 16925, 16925, -1, + 16926, 16926, 16926, -1, 16927, 16927, 16927, -1, + 16928, 16928, 16928, -1, 16929, 16929, 16929, -1, + 16930, 16930, 16930, -1, 16931, 16931, 16931, -1, + 16932, 16932, 16932, -1, 16933, 16933, 16933, -1, + 16934, 16934, 16934, -1, 16935, 16935, 16935, -1, + 16936, 16936, 16936, -1, 16937, 16937, 16937, -1, + 16938, 16938, 16938, -1, 16939, 16939, 16939, -1, + 16940, 16940, 16940, -1, 16941, 16941, 16941, -1, + 16942, 16942, 16942, -1, 16943, 16943, 16943, -1, + 16944, 16944, 16944, -1, 16945, 16945, 16945, -1, + 16946, 16946, 16946, -1, 16947, 16947, 16947, -1, + 16948, 16948, 16948, -1, 16949, 16949, 16949, -1, + 16950, 16950, 16950, -1, 16951, 16951, 16951, -1, + 16952, 16952, 16952, -1, 16953, 16953, 16953, -1, + 16954, 16954, 16954, -1, 16955, 16955, 16955, -1, + 16956, 16956, 16956, -1, 16957, 16957, 16957, -1, + 16958, 16958, 16958, -1, 16959, 16959, 16959, -1, + 16960, 16960, 16960, -1, 16961, 16961, 16961, -1, + 16962, 16962, 16962, -1, 16963, 16963, 16963, -1, + 16964, 16964, 16964, -1, 16965, 16965, 16965, -1, + 16966, 16966, 16966, -1, 16967, 16967, 16967, -1, + 16968, 16968, 16968, -1, 16969, 16969, 16969, -1, + 16970, 16970, 16970, -1, 16971, 16971, 16971, -1, + 16972, 16972, 16972, -1, 16973, 16973, 16973, -1, + 16974, 16974, 16974, -1, 16975, 16975, 16975, -1, + 16976, 16976, 16976, -1, 16977, 16977, 16977, -1, + 16978, 16978, 16978, -1, 16979, 16979, 16979, -1, + 16980, 16980, 16980, -1, 16981, 16981, 16981, -1, + 16982, 16982, 16982, -1, 16983, 16983, 16983, -1, + 16984, 16984, 16984, -1, 16985, 16985, 16985, -1, + 16986, 16986, 16986, -1, 16987, 16987, 16987, -1, + 16988, 16988, 16988, -1, 16989, 16989, 16989, -1, + 16990, 16990, 16990, -1, 16991, 16991, 16991, -1, + 16992, 16992, 16992, -1, 16993, 16993, 16993, -1, + 16994, 16994, 16994, -1, 16995, 16995, 16995, -1, + 16996, 16996, 16996, -1, 16997, 16997, 16997, -1, + 16998, 16998, 16998, -1, 16999, 16999, 16999, -1, + 17000, 17000, 17000, -1, 17001, 17001, 17001, -1, + 17002, 17002, 17002, -1, 17003, 17003, 17003, -1, + 17004, 17004, 17004, -1, 17005, 17005, 17005, -1, + 17006, 17006, 17006, -1, 17007, 17007, 17007, -1, + 17008, 17008, 17008, -1, 17009, 17009, 17009, -1, + 17010, 17010, 17010, -1, 17011, 17011, 17011, -1, + 17012, 17012, 17012, -1, 17013, 17013, 17013, -1, + 17014, 17014, 17014, -1, 17015, 17015, 17015, -1, + 17016, 17016, 17016, -1, 17017, 17017, 17017, -1, + 17018, 17018, 17018, -1, 17019, 17019, 17019, -1, + 17020, 17020, 17020, -1, 17021, 17021, 17021, -1, + 17022, 17022, 17022, -1, 17023, 17023, 17023, -1, + 17024, 17024, 17024, -1, 17025, 17025, 17025, -1, + 17026, 17026, 17026, -1, 17027, 17027, 17027, -1, + 17028, 17028, 17028, -1, 17029, 17029, 17029, -1, + 17030, 17030, 17030, -1, 17031, 17031, 17031, -1, + 17032, 17032, 17032, -1, 17033, 17033, 17033, -1, + 17034, 17034, 17034, -1, 17035, 17035, 17035, -1, + 17036, 17036, 17036, -1, 17037, 17037, 17037, -1, + 17038, 17038, 17038, -1, 17039, 17039, 17039, -1, + 17040, 17040, 17040, -1, 17041, 17041, 17041, -1, + 17042, 17042, 17042, -1, 17043, 17043, 17043, -1, + 17044, 17044, 17044, -1, 17045, 17045, 17045, -1, + 17046, 17046, 17046, -1, 17047, 17047, 17047, -1, + 17048, 17048, 17048, -1, 17049, 17049, 17049, -1, + 17050, 17050, 17050, -1, 17051, 17051, 17051, -1, + 17052, 17052, 17052, -1, 17053, 17053, 17053, -1, + 17054, 17054, 17054, -1, 17055, 17055, 17055, -1, + 17056, 17056, 17056, -1, 17057, 17057, 17057, -1, + 17058, 17058, 17058, -1, 17059, 17059, 17059, -1, + 17060, 17060, 17060, -1, 17061, 17061, 17061, -1, + 17062, 17062, 17062, -1, 17063, 17063, 17063, -1, + 17064, 17064, 17064, -1, 17065, 17065, 17065, -1, + 17066, 17066, 17066, -1, 17067, 17067, 17067, -1, + 17068, 17068, 17068, -1, 17069, 17069, 17069, -1, + 17070, 17070, 17070, -1, 17071, 17071, 17071, -1, + 17072, 17072, 17072, -1, 17073, 17073, 17073, -1, + 17074, 17074, 17074, -1, 17075, 17075, 17075, -1, + 17076, 17076, 17076, -1, 17077, 17077, 17077, -1, + 17078, 17078, 17078, -1, 17079, 17079, 17079, -1, + 17080, 17080, 17080, -1, 17081, 17081, 17081, -1, + 17082, 17082, 17082, -1, 17083, 17083, 17083, -1, + 17084, 17084, 17084, -1, 17085, 17085, 17085, -1, + 17086, 17086, 17086, -1, 17087, 17087, 17087, -1, + 17088, 17088, 17088, -1, 17089, 17089, 17089, -1, + 17090, 17090, 17090, -1, 17091, 17091, 17091, -1, + 17092, 17092, 17092, -1, 17093, 17093, 17093, -1, + 17094, 17094, 17094, -1, 17095, 17095, 17095, -1, + 17096, 17096, 17096, -1, 17097, 17097, 17097, -1, + 17098, 17098, 17098, -1, 17099, 17099, 17099, -1, + 17100, 17100, 17100, -1, 17101, 17101, 17101, -1, + 17102, 17102, 17102, -1, 17103, 17103, 17103, -1, + 17104, 17104, 17104, -1, 17105, 17105, 17105, -1, + 17106, 17106, 17106, -1, 17107, 17107, 17107, -1, + 17108, 17108, 17108, -1, 17109, 17109, 17109, -1, + 17110, 17110, 17110, -1, 17111, 17111, 17111, -1, + 17112, 17112, 17112, -1, 17113, 17113, 17113, -1, + 17114, 17114, 17114, -1, 17115, 17115, 17115, -1, + 17116, 17116, 17116, -1, 17117, 17117, 17117, -1, + 17118, 17118, 17118, -1, 17119, 17119, 17119, -1, + 17120, 17120, 17120, -1, 17121, 17121, 17121, -1, + 17122, 17122, 17122, -1, 17123, 17123, 17123, -1, + 17124, 17124, 17124, -1, 17125, 17125, 17125, -1, + 17126, 17126, 17126, -1, 17127, 17127, 17127, -1, + 17128, 17128, 17128, -1, 17129, 17129, 17129, -1, + 17130, 17130, 17130, -1, 17131, 17131, 17131, -1, + 17132, 17132, 17132, -1, 17133, 17133, 17133, -1, + 17134, 17134, 17134, -1, 17135, 17135, 17135, -1, + 17136, 17136, 17136, -1, 17137, 17137, 17137, -1, + 17138, 17138, 17138, -1, 17139, 17139, 17139, -1, + 17140, 17140, 17140, -1, 17141, 17141, 17141, -1, + 17142, 17142, 17142, -1, 17143, 17143, 17143, -1, + 17144, 17144, 17144, -1, 17145, 17145, 17145, -1, + 17146, 17146, 17146, -1, 17147, 17147, 17147, -1, + 17148, 17148, 17148, -1, 17149, 17149, 17149, -1, + 17150, 17150, 17150, -1, 17151, 17151, 17151, -1, + 17152, 17152, 17152, -1, 17153, 17153, 17153, -1, + 17154, 17154, 17154, -1, 17155, 17155, 17155, -1, + 17156, 17156, 17156, -1, 17157, 17157, 17157, -1, + 17158, 17158, 17158, -1, 17159, 17159, 17159, -1, + 17160, 17160, 17160, -1, 17161, 17161, 17161, -1, + 17162, 17162, 17162, -1, 17163, 17163, 17163, -1, + 17164, 17164, 17164, -1, 17165, 17165, 17165, -1, + 17166, 17166, 17166, -1, 17167, 17167, 17167, -1, + 17168, 17168, 17168, -1, 17169, 17169, 17169, -1, + 17170, 17170, 17170, -1, 17171, 17171, 17171, -1, + 17172, 17172, 17172, -1, 17173, 17173, 17173, -1, + 17174, 17174, 17174, -1, 17175, 17175, 17175, -1, + 17176, 17176, 17176, -1, 17177, 17177, 17177, -1, + 17178, 17178, 17178, -1, 17179, 17179, 17179, -1, + 17180, 17180, 17180, -1, 17181, 17181, 17181, -1, + 17182, 17182, 17182, -1, 17183, 17183, 17183, -1, + 17184, 17184, 17184, -1, 17185, 17185, 17185, -1, + 17186, 17186, 17186, -1, 17187, 17187, 17187, -1, + 17188, 17188, 17188, -1, 17189, 17189, 17189, -1, + 17190, 17190, 17190, -1, 17191, 17191, 17191, -1, + 17192, 17192, 17192, -1, 17193, 17193, 17193, -1, + 17194, 17194, 17194, -1, 17195, 17195, 17195, -1, + 17196, 17196, 17196, -1, 17197, 17197, 17197, -1, + 17198, 17198, 17198, -1, 17199, 17199, 17199, -1, + 17200, 17200, 17200, -1, 17201, 17201, 17201, -1, + 17202, 17202, 17202, -1, 17203, 17203, 17203, -1, + 17204, 17204, 17204, -1, 17205, 17205, 17205, -1, + 17206, 17206, 17206, -1, 17207, 17207, 17207, -1, + 17208, 17208, 17208, -1, 17209, 17209, 17209, -1, + 17210, 17210, 17210, -1, 17211, 17211, 17211, -1, + 17212, 17212, 17212, -1, 17213, 17213, 17213, -1, + 17214, 17214, 17214, -1, 17215, 17215, 17215, -1, + 17216, 17216, 17216, -1, 17217, 17217, 17217, -1, + 17218, 17218, 17218, -1, 17219, 17219, 17219, -1, + 17220, 17220, 17220, -1, 17221, 17221, 17221, -1, + 17222, 17222, 17222, -1, 17223, 17223, 17223, -1, + 17224, 17224, 17224, -1, 17225, 17225, 17225, -1, + 17226, 17226, 17226, -1, 17227, 17227, 17227, -1, + 17228, 17228, 17228, -1, 17229, 17229, 17229, -1, + 17230, 17230, 17230, -1, 17231, 17231, 17231, -1, + 17232, 17232, 17232, -1, 17233, 17233, 17233, -1, + 17234, 17234, 17234, -1, 17235, 17235, 17235, -1, + 17236, 17236, 17236, -1, 17237, 17237, 17237, -1, + 17238, 17238, 17238, -1, 17239, 17239, 17239, -1, + 17240, 17240, 17240, -1, 17241, 17241, 17241, -1, + 17242, 17242, 17242, -1, 17243, 17243, 17243, -1, + 17244, 17244, 17244, -1, 17245, 17245, 17245, -1, + 17246, 17246, 17246, -1, 17247, 17247, 17247, -1, + 17248, 17248, 17248, -1, 17249, 17249, 17249, -1, + 17250, 17250, 17250, -1, 17251, 17251, 17251, -1, + 17252, 17252, 17252, -1, 17253, 17253, 17253, -1, + 17254, 17254, 17254, -1, 17255, 17255, 17255, -1, + 17256, 17256, 17256, -1, 17257, 17257, 17257, -1, + 17258, 17258, 17258, -1, 17259, 17259, 17259, -1, + 17260, 17260, 17260, -1, 17261, 17261, 17261, -1, + 17262, 17262, 17262, -1, 17263, 17263, 17263, -1, + 17264, 17264, 17264, -1, 17265, 17265, 17265, -1, + 17266, 17266, 17266, -1, 17267, 17267, 17267, -1, + 17268, 17268, 17268, -1, 17269, 17269, 17269, -1, + 17270, 17270, 17270, -1, 17271, 17271, 17271, -1, + 17272, 17272, 17272, -1, 17273, 17273, 17273, -1, + 17274, 17274, 17274, -1, 17275, 17275, 17275, -1, + 17276, 17276, 17276, -1, 17277, 17277, 17277, -1, + 17278, 17278, 17278, -1, 17279, 17279, 17279, -1, + 17280, 17280, 17280, -1, 17281, 17281, 17281, -1, + 17282, 17282, 17282, -1, 17283, 17283, 17283, -1, + 17284, 17284, 17284, -1, 17285, 17285, 17285, -1, + 17286, 17286, 17286, -1, 17287, 17287, 17287, -1, + 17288, 17288, 17288, -1, 17289, 17289, 17289, -1, + 17290, 17290, 17290, -1, 17291, 17291, 17291, -1, + 17292, 17292, 17292, -1, 17293, 17293, 17293, -1, + 17294, 17294, 17294, -1, 17295, 17295, 17295, -1, + 17296, 17296, 17296, -1, 17297, 17297, 17297, -1, + 17298, 17298, 17298, -1, 17299, 17299, 17299, -1, + 17300, 17300, 17300, -1, 17301, 17301, 17301, -1, + 17302, 17302, 17302, -1, 17303, 17303, 17303, -1, + 17304, 17304, 17304, -1, 17305, 17305, 17305, -1, + 17306, 17306, 17306, -1, 17307, 17307, 17307, -1, + 17308, 17308, 17308, -1, 17309, 17309, 17309, -1, + 17310, 17310, 17310, -1, 17311, 17311, 17311, -1, + 17312, 17312, 17312, -1, 17313, 17313, 17313, -1, + 17314, 17314, 17314, -1, 17315, 17315, 17315, -1, + 17316, 17316, 17316, -1, 17317, 17317, 17317, -1, + 17318, 17318, 17318, -1, 17319, 17319, 17319, -1, + 17320, 17320, 17320, -1, 17321, 17321, 17321, -1, + 17322, 17322, 17322, -1, 17323, 17323, 17323, -1, + 17324, 17324, 17324, -1, 17325, 17325, 17325, -1, + 17326, 17326, 17326, -1, 17327, 17327, 17327, -1, + 17328, 17328, 17328, -1, 17329, 17329, 17329, -1, + 17330, 17330, 17330, -1, 17331, 17331, 17331, -1, + 17332, 17332, 17332, -1, 17333, 17333, 17333, -1, + 17334, 17334, 17334, -1, 17335, 17335, 17335, -1, + 17336, 17336, 17336, -1, 17337, 17337, 17337, -1, + 17338, 17338, 17338, -1, 17339, 17339, 17339, -1, + 17340, 17340, 17340, -1, 17341, 17341, 17341, -1, + 17342, 17342, 17342, -1, 17343, 17343, 17343, -1, + 17344, 17344, 17344, -1, 17345, 17345, 17345, -1, + 17346, 17346, 17346, -1, 17347, 17347, 17347, -1, + 17348, 17348, 17348, -1, 17349, 17349, 17349, -1, + 17350, 17350, 17350, -1, 17351, 17351, 17351, -1, + 17352, 17352, 17352, -1, 17353, 17353, 17353, -1, + 17354, 17354, 17354, -1, 17355, 17355, 17355, -1, + 17356, 17356, 17356, -1, 17357, 17357, 17357, -1, + 17358, 17358, 17358, -1, 17359, 17359, 17359, -1, + 17360, 17360, 17360, -1, 17361, 17361, 17361, -1, + 17362, 17362, 17362, -1, 17363, 17363, 17363, -1, + 17364, 17364, 17364, -1, 17365, 17365, 17365, -1, + 17366, 17366, 17366, -1, 17367, 17367, 17367, -1, + 17368, 17368, 17368, -1, 17369, 17369, 17369, -1, + 17370, 17370, 17370, -1, 17371, 17371, 17371, -1, + 17372, 17372, 17372, -1, 17373, 17373, 17373, -1, + 17374, 17374, 17374, -1, 17375, 17375, 17375, -1, + 17376, 17376, 17376, -1, 17377, 17377, 17377, -1, + 17378, 17378, 17378, -1, 17379, 17379, 17379, -1, + 17380, 17380, 17380, -1, 17381, 17381, 17381, -1, + 17382, 17382, 17382, -1, 17383, 17383, 17383, -1, + 17384, 17384, 17384, -1, 17385, 17385, 17385, -1, + 17386, 17386, 17386, -1, 17387, 17387, 17387, -1, + 17388, 17388, 17388, -1, 17389, 17389, 17389, -1, + 17390, 17390, 17390, -1, 17391, 17391, 17391, -1, + 17392, 17392, 17392, -1, 17393, 17393, 17393, -1, + 17394, 17394, 17394, -1, 17395, 17395, 17395, -1, + 17396, 17396, 17396, -1, 17397, 17397, 17397, -1, + 17398, 17398, 17398, -1, 17399, 17399, 17399, -1, + 17400, 17400, 17400, -1, 17401, 17401, 17401, -1, + 17402, 17402, 17402, -1, 17403, 17403, 17403, -1, + 17404, 17404, 17404, -1, 17405, 17405, 17405, -1, + 17406, 17406, 17406, -1, 17407, 17407, 17407, -1, + 17408, 17408, 17408, -1, 17409, 17409, 17409, -1, + 17410, 17410, 17410, -1, 17411, 17411, 17411, -1, + 17412, 17412, 17412, -1, 17413, 17413, 17413, -1, + 17414, 17414, 17414, -1, 17415, 17415, 17415, -1, + 17416, 17416, 17416, -1, 17417, 17417, 17417, -1, + 17418, 17418, 17418, -1, 17419, 17419, 17419, -1, + 17420, 17420, 17420, -1, 17421, 17421, 17421, -1, + 17422, 17422, 17422, -1, 17423, 17423, 17423, -1, + 17424, 17424, 17424, -1, 17425, 17425, 17425, -1, + 17426, 17426, 17426, -1, 17427, 17427, 17427, -1, + 17428, 17428, 17428, -1, 17429, 17429, 17429, -1, + 17430, 17430, 17430, -1, 17431, 17431, 17431, -1, + 17432, 17432, 17432, -1, 17433, 17433, 17433, -1, + 17434, 17434, 17434, -1, 17435, 17435, 17435, -1, + 17436, 17436, 17436, -1, 17437, 17437, 17437, -1, + 17438, 17438, 17438, -1, 17439, 17439, 17439, -1, + 17440, 17440, 17440, -1, 17441, 17441, 17441, -1, + 17442, 17442, 17442, -1, 17443, 17443, 17443, -1, + 17444, 17444, 17444, -1, 17445, 17445, 17445, -1, + 17446, 17446, 17446, -1, 17447, 17447, 17447, -1, + 17448, 17448, 17448, -1, 17449, 17449, 17449, -1, + 17450, 17450, 17450, -1, 17451, 17451, 17451, -1, + 17452, 17452, 17452, -1, 17453, 17453, 17453, -1, + 17454, 17454, 17454, -1, 17455, 17455, 17455, -1, + 17456, 17456, 17456, -1, 17457, 17457, 17457, -1, + 17458, 17458, 17458, -1, 17459, 17459, 17459, -1, + 17460, 17460, 17460, -1, 17461, 17461, 17461, -1, + 17462, 17462, 17462, -1, 17463, 17463, 17463, -1, + 17464, 17464, 17464, -1, 17465, 17465, 17465, -1, + 17466, 17466, 17466, -1, 17467, 17467, 17467, -1, + 17468, 17468, 17468, -1, 17469, 17469, 17469, -1, + 17470, 17470, 17470, -1, 17471, 17471, 17471, -1, + 17472, 17472, 17472, -1, 17473, 17473, 17473, -1, + 17474, 17474, 17474, -1, 17475, 17475, 17475, -1, + 17476, 17476, 17476, -1, 17477, 17477, 17477, -1, + 17478, 17478, 17478, -1, 17479, 17479, 17479, -1, + 17480, 17480, 17480, -1, 17481, 17481, 17481, -1, + 17482, 17482, 17482, -1, 17483, 17483, 17483, -1, + 17484, 17484, 17484, -1, 17485, 17485, 17485, -1, + 17486, 17486, 17486, -1, 17487, 17487, 17487, -1, + 17488, 17488, 17488, -1, 17489, 17489, 17489, -1, + 17490, 17490, 17490, -1, 17491, 17491, 17491, -1, + 17492, 17492, 17492, -1, 17493, 17493, 17493, -1, + 17494, 17494, 17494, -1, 17495, 17495, 17495, -1, + 17496, 17496, 17496, -1, 17497, 17497, 17497, -1, + 17498, 17498, 17498, -1, 17499, 17499, 17499, -1, + 17500, 17500, 17500, -1, 17501, 17501, 17501, -1, + 17502, 17502, 17502, -1, 17503, 17503, 17503, -1, + 17504, 17504, 17504, -1, 17505, 17505, 17505, -1, + 17506, 17506, 17506, -1, 17507, 17507, 17507, -1, + 17508, 17508, 17508, -1, 17509, 17509, 17509, -1, + 17510, 17510, 17510, -1, 17511, 17511, 17511, -1, + 17512, 17512, 17512, -1, 17513, 17513, 17513, -1, + 17514, 17514, 17514, -1, 17515, 17515, 17515, -1, + 17516, 17516, 17516, -1, 17517, 17517, 17517, -1, + 17518, 17518, 17518, -1, 17519, 17519, 17519, -1, + 17520, 17520, 17520, -1, 17521, 17521, 17521, -1, + 17522, 17522, 17522, -1, 17523, 17523, 17523, -1, + 17524, 17524, 17524, -1, 17525, 17525, 17525, -1, + 17526, 17526, 17526, -1, 17527, 17527, 17527, -1, + 17528, 17528, 17528, -1, 17529, 17529, 17529, -1, + 17530, 17530, 17530, -1, 17531, 17531, 17531, -1, + 17532, 17532, 17532, -1, 17533, 17533, 17533, -1, + 17534, 17534, 17534, -1, 17535, 17535, 17535, -1, + 17536, 17536, 17536, -1, 17537, 17537, 17537, -1, + 17538, 17538, 17538, -1, 17539, 17539, 17539, -1, + 17540, 17540, 17540, -1, 17541, 17541, 17541, -1, + 17542, 17542, 17542, -1, 17543, 17543, 17543, -1, + 17544, 17544, 17544, -1, 17545, 17545, 17545, -1, + 17546, 17546, 17546, -1, 17547, 17547, 17547, -1, + 17548, 17548, 17548, -1, 17549, 17549, 17549, -1, + 17550, 17550, 17550, -1, 17551, 17551, 17551, -1, + 17552, 17552, 17552, -1, 17553, 17553, 17553, -1, + 17554, 17554, 17554, -1, 17555, 17555, 17555, -1, + 17556, 17556, 17556, -1, 17557, 17557, 17557, -1, + 17558, 17558, 17558, -1, 17559, 17559, 17559, -1, + 17560, 17560, 17560, -1, 17561, 17561, 17561, -1, + 17562, 17562, 17562, -1, 17563, 17563, 17563, -1, + 17564, 17564, 17564, -1, 17565, 17565, 17565, -1, + 17566, 17566, 17566, -1, 17567, 17567, 17567, -1, + 17568, 17568, 17568, -1, 17569, 17569, 17569, -1, + 17570, 17570, 17570, -1, 17571, 17571, 17571, -1, + 17572, 17572, 17572, -1, 17573, 17573, 17573, -1, + 17574, 17574, 17574, -1, 17575, 17575, 17575, -1, + 17576, 17576, 17576, -1, 17577, 17577, 17577, -1, + 17578, 17578, 17578, -1, 17579, 17579, 17579, -1, + 17580, 17580, 17580, -1, 17581, 17581, 17581, -1, + 17582, 17582, 17582, -1, 17583, 17583, 17583, -1, + 17584, 17584, 17584, -1, 17585, 17585, 17585, -1, + 17586, 17586, 17586, -1, 17587, 17587, 17587, -1, + 17588, 17588, 17588, -1, 17589, 17589, 17589, -1, + 17590, 17590, 17590, -1, 17591, 17591, 17591, -1, + 17592, 17592, 17592, -1, 17593, 17593, 17593, -1, + 17594, 17594, 17594, -1, 17595, 17595, 17595, -1, + 17596, 17596, 17596, -1, 17597, 17597, 17597, -1, + 17598, 17598, 17598, -1, 17599, 17599, 17599, -1, + 17600, 17600, 17600, -1, 17601, 17601, 17601, -1, + 17602, 17602, 17602, -1, 17603, 17603, 17603, -1, + 17604, 17604, 17604, -1, 17605, 17605, 17605, -1, + 17606, 17606, 17606, -1, 17607, 17607, 17607, -1, + 17608, 17608, 17608, -1, 17609, 17609, 17609, -1, + 17610, 17610, 17610, -1, 17611, 17611, 17611, -1, + 17612, 17612, 17612, -1, 17613, 17613, 17613, -1, + 17614, 17614, 17614, -1, 17615, 17615, 17615, -1, + 17616, 17616, 17616, -1, 17617, 17617, 17617, -1, + 17618, 17618, 17618, -1, 17619, 17619, 17619, -1, + 17620, 17620, 17620, -1, 17621, 17621, 17621, -1, + 17622, 17622, 17622, -1, 17623, 17623, 17623, -1, + 17624, 17624, 17624, -1, 17625, 17625, 17625, -1, + 17626, 17626, 17626, -1, 17627, 17627, 17627, -1, + 17628, 17628, 17628, -1, 17629, 17629, 17629, -1, + 17630, 17630, 17630, -1, 17631, 17631, 17631, -1, + 17632, 17632, 17632, -1, 17633, 17633, 17633, -1, + 17634, 17634, 17634, -1, 17635, 17635, 17635, -1, + 17636, 17636, 17636, -1, 17637, 17637, 17637, -1, + 17638, 17638, 17638, -1, 17639, 17639, 17639, -1, + 17640, 17640, 17640, -1, 17641, 17641, 17641, -1, + 17642, 17642, 17642, -1, 17643, 17643, 17643, -1, + 17644, 17644, 17644, -1, 17645, 17645, 17645, -1, + 17646, 17646, 17646, -1, 17647, 17647, 17647, -1, + 17648, 17648, 17648, -1, 17649, 17649, 17649, -1, + 17650, 17650, 17650, -1, 17651, 17651, 17651, -1, + 17652, 17652, 17652, -1, 17653, 17653, 17653, -1, + 17654, 17654, 17654, -1, 17655, 17655, 17655, -1, + 17656, 17656, 17656, -1, 17657, 17657, 17657, -1, + 17658, 17658, 17658, -1, 17659, 17659, 17659, -1, + 17660, 17660, 17660, -1, 17661, 17661, 17661, -1, + 17662, 17662, 17662, -1, 17663, 17663, 17663, -1, + 17664, 17664, 17664, -1, 17665, 17665, 17665, -1, + 17666, 17666, 17666, -1, 17667, 17667, 17667, -1, + 17668, 17668, 17668, -1, 17669, 17669, 17669, -1, + 17670, 17670, 17670, -1, 17671, 17671, 17671, -1, + 17672, 17672, 17672, -1, 17673, 17673, 17673, -1, + 17674, 17674, 17674, -1, 17675, 17675, 17675, -1, + 17676, 17676, 17676, -1, 17677, 17677, 17677, -1, + 17678, 17678, 17678, -1, 17679, 17679, 17679, -1, + 17680, 17680, 17680, -1, 17681, 17681, 17681, -1, + 17682, 17682, 17682, -1, 17683, 17683, 17683, -1, + 17684, 17684, 17684, -1, 17685, 17685, 17685, -1, + 17686, 17686, 17686, -1, 17687, 17687, 17687, -1, + 17688, 17688, 17688, -1, 17689, 17689, 17689, -1, + 17690, 17690, 17690, -1, 17691, 17691, 17691, -1, + 17692, 17692, 17692, -1, 17693, 17693, 17693, -1, + 17694, 17694, 17694, -1, 17695, 17695, 17695, -1, + 17696, 17696, 17696, -1, 17697, 17697, 17697, -1, + 17698, 17698, 17698, -1, 17699, 17699, 17699, -1, + 17700, 17700, 17700, -1, 17701, 17701, 17701, -1, + 17702, 17702, 17702, -1, 17703, 17703, 17703, -1, + 17704, 17704, 17704, -1, 17705, 17705, 17705, -1, + 17706, 17706, 17706, -1, 17707, 17707, 17707, -1, + 17708, 17708, 17708, -1, 17709, 17709, 17709, -1, + 17710, 17710, 17710, -1, 17711, 17711, 17711, -1, + 17712, 17712, 17712, -1, 17713, 17713, 17713, -1, + 17714, 17714, 17714, -1, 17715, 17715, 17715, -1, + 17716, 17716, 17716, -1, 17717, 17717, 17717, -1, + 17718, 17718, 17718, -1, 17719, 17719, 17719, -1, + 17720, 17720, 17720, -1, 17721, 17721, 17721, -1, + 17722, 17722, 17722, -1, 17723, 17723, 17723, -1, + 17724, 17724, 17724, -1, 17725, 17725, 17725, -1, + 17726, 17726, 17726, -1, 17727, 17727, 17727, -1, + 17728, 17728, 17728, -1, 17729, 17729, 17729, -1, + 17730, 17730, 17730, -1, 17731, 17731, 17731, -1, + 17732, 17732, 17732, -1, 17733, 17733, 17733, -1, + 17734, 17734, 17734, -1, 17735, 17735, 17735, -1, + 17736, 17736, 17736, -1, 17737, 17737, 17737, -1, + 17738, 17738, 17738, -1, 17739, 17739, 17739, -1, + 17740, 17740, 17740, -1, 17741, 17741, 17741, -1, + 17742, 17742, 17742, -1, 17743, 17743, 17743, -1, + 17744, 17744, 17744, -1, 17745, 17745, 17745, -1, + 17746, 17746, 17746, -1, 17747, 17747, 17747, -1, + 17748, 17748, 17748, -1, 17749, 17749, 17749, -1, + 17750, 17750, 17750, -1, 17751, 17751, 17751, -1, + 17752, 17752, 17752, -1, 17753, 17753, 17753, -1, + 17754, 17754, 17754, -1, 17755, 17755, 17755, -1, + 17756, 17756, 17756, -1, 17757, 17757, 17757, -1, + 17758, 17758, 17758, -1, 17759, 17759, 17759, -1, + 17760, 17760, 17760, -1, 17761, 17761, 17761, -1, + 17762, 17762, 17762, -1, 17763, 17763, 17763, -1, + 17764, 17764, 17764, -1, 17765, 17765, 17765, -1, + 17766, 17766, 17766, -1, 17767, 17767, 17767, -1, + 17768, 17768, 17768, -1, 17769, 17769, 17769, -1, + 17770, 17770, 17770, -1, 17771, 17771, 17771, -1, + 17772, 17772, 17772, -1, 17773, 17773, 17773, -1, + 17774, 17774, 17774, -1, 17775, 17775, 17775, -1, + 17776, 17776, 17776, -1, 17777, 17777, 17777, -1, + 17778, 17778, 17778, -1, 17779, 17779, 17779, -1, + 17780, 17780, 17780, -1, 17781, 17781, 17781, -1, + 17782, 17782, 17782, -1, 17783, 17783, 17783, -1, + 17784, 17784, 17784, -1, 17785, 17785, 17785, -1, + 17786, 17786, 17786, -1, 17787, 17787, 17787, -1, + 17788, 17788, 17788, -1, 17789, 17789, 17789, -1, + 17790, 17790, 17790, -1, 17791, 17791, 17791, -1, + 17792, 17792, 17792, -1, 17793, 17793, 17793, -1, + 17794, 17794, 17794, -1, 17795, 17795, 17795, -1, + 17796, 17796, 17796, -1, 17797, 17797, 17797, -1, + 17798, 17798, 17798, -1, 17799, 17799, 17799, -1, + 17800, 17800, 17800, -1, 17801, 17801, 17801, -1, + 17802, 17802, 17802, -1, 17803, 17803, 17803, -1, + 17804, 17804, 17804, -1, 17805, 17805, 17805, -1, + 17806, 17806, 17806, -1, 17807, 17807, 17807, -1, + 17808, 17808, 17808, -1, 17809, 17809, 17809, -1, + 17810, 17810, 17810, -1, 17811, 17811, 17811, -1, + 17812, 17812, 17812, -1, 17813, 17813, 17813, -1, + 17814, 17814, 17814, -1, 17815, 17815, 17815, -1, + 17816, 17816, 17816, -1, 17817, 17817, 17817, -1, + 17818, 17818, 17818, -1, 17819, 17819, 17819, -1, + 17820, 17820, 17820, -1, 17821, 17821, 17821, -1, + 17822, 17822, 17822, -1, 17823, 17823, 17823, -1, + 17824, 17824, 17824, -1, 17825, 17825, 17825, -1, + 17826, 17826, 17826, -1, 17827, 17827, 17827, -1, + 17828, 17828, 17828, -1, 17829, 17829, 17829, -1, + 17830, 17830, 17830, -1, 17831, 17831, 17831, -1, + 17832, 17832, 17832, -1, 17833, 17833, 17833, -1, + 17834, 17834, 17834, -1, 17835, 17835, 17835, -1, + 17836, 17836, 17836, -1, 17837, 17837, 17837, -1, + 17838, 17838, 17838, -1, 17839, 17839, 17839, -1, + 17840, 17840, 17840, -1, 17841, 17841, 17841, -1, + 17842, 17842, 17842, -1, 17843, 17843, 17843, -1, + 17844, 17844, 17844, -1, 17845, 17845, 17845, -1, + 17846, 17846, 17846, -1, 17847, 17847, 17847, -1, + 17848, 17848, 17848, -1, 17849, 17849, 17849, -1, + 17850, 17850, 17850, -1, 17851, 17851, 17851, -1, + 17852, 17852, 17852, -1, 17853, 17853, 17853, -1, + 17854, 17854, 17854, -1, 17855, 17855, 17855, -1, + 17856, 17856, 17856, -1, 17857, 17857, 17857, -1, + 17858, 17858, 17858, -1, 17859, 17859, 17859, -1, + 17860, 17860, 17860, -1, 17861, 17861, 17861, -1, + 17862, 17862, 17862, -1, 17863, 17863, 17863, -1, + 17864, 17864, 17864, -1, 17865, 17865, 17865, -1, + 17866, 17866, 17866, -1, 17867, 17867, 17867, -1, + 17868, 17868, 17868, -1, 17869, 17869, 17869, -1, + 17870, 17870, 17870, -1, 17871, 17871, 17871, -1, + 17872, 17872, 17872, -1, 17873, 17873, 17873, -1, + 17874, 17874, 17874, -1, 17875, 17875, 17875, -1, + 17876, 17876, 17876, -1, 17877, 17877, 17877, -1, + 17878, 17878, 17878, -1, 17879, 17879, 17879, -1, + 17880, 17880, 17880, -1, 17881, 17881, 17881, -1, + 17882, 17882, 17882, -1, 17883, 17883, 17883, -1, + 17884, 17884, 17884, -1, 17885, 17885, 17885, -1, + 17886, 17886, 17886, -1, 17887, 17887, 17887, -1, + 17888, 17888, 17888, -1, 17889, 17889, 17889, -1, + 17890, 17890, 17890, -1, 17891, 17891, 17891, -1, + 17892, 17892, 17892, -1, 17893, 17893, 17893, -1, + 17894, 17894, 17894, -1, 17895, 17895, 17895, -1, + 17896, 17896, 17896, -1, 17897, 17897, 17897, -1, + 17898, 17898, 17898, -1, 17899, 17899, 17899, -1, + 17900, 17900, 17900, -1, 17901, 17901, 17901, -1, + 17902, 17902, 17902, -1, 17903, 17903, 17903, -1, + 17904, 17904, 17904, -1, 17905, 17905, 17905, -1, + 17906, 17906, 17906, -1, 17907, 17907, 17907, -1, + 17908, 17908, 17908, -1, 17909, 17909, 17909, -1, + 17910, 17910, 17910, -1, 17911, 17911, 17911, -1, + 17912, 17912, 17912, -1, 17913, 17913, 17913, -1, + 17914, 17914, 17914, -1, 17915, 17915, 17915, -1, + 17916, 17916, 17916, -1, 17917, 17917, 17917, -1, + 17918, 17918, 17918, -1, 17919, 17919, 17919, -1, + 17920, 17920, 17920, -1, 17921, 17921, 17921, -1, + 17922, 17922, 17922, -1, 17923, 17923, 17923, -1, + 17924, 17924, 17924, -1, 17925, 17925, 17925, -1, + 17926, 17926, 17926, -1, 17927, 17927, 17927, -1, + 17928, 17928, 17928, -1, 17929, 17929, 17929, -1, + 17930, 17930, 17930, -1, 17931, 17931, 17931, -1, + 17932, 17932, 17932, -1, 17933, 17933, 17933, -1, + 17934, 17934, 17934, -1, 17935, 17935, 17935, -1, + 17936, 17936, 17936, -1, 17937, 17937, 17937, -1, + 17938, 17938, 17938, -1, 17939, 17939, 17939, -1, + 17940, 17940, 17940, -1, 17941, 17941, 17941, -1, + 17942, 17942, 17942, -1, 17943, 17943, 17943, -1, + 17944, 17944, 17944, -1, 17945, 17945, 17945, -1, + 17946, 17946, 17946, -1, 17947, 17947, 17947, -1, + 17948, 17948, 17948, -1, 17949, 17949, 17949, -1, + 17950, 17950, 17950, -1, 17951, 17951, 17951, -1, + 17952, 17952, 17952, -1, 17953, 17953, 17953, -1, + 17954, 17954, 17954, -1, 17955, 17955, 17955, -1, + 17956, 17956, 17956, -1, 17957, 17957, 17957, -1, + 17958, 17958, 17958, -1, 17959, 17959, 17959, -1, + 17960, 17960, 17960, -1, 17961, 17961, 17961, -1, + 17962, 17962, 17962, -1, 17963, 17963, 17963, -1, + 17964, 17964, 17964, -1, 17965, 17965, 17965, -1, + 17966, 17966, 17966, -1, 17967, 17967, 17967, -1, + 17968, 17968, 17968, -1, 17969, 17969, 17969, -1, + 17970, 17970, 17970, -1, 17971, 17971, 17971, -1, + 17972, 17972, 17972, -1, 17973, 17973, 17973, -1, + 17974, 17974, 17974, -1, 17975, 17975, 17975, -1, + 17976, 17976, 17976, -1, 17977, 17977, 17977, -1, + 17978, 17978, 17978, -1, 17979, 17979, 17979, -1, + 17980, 17980, 17980, -1, 17981, 17981, 17981, -1, + 17982, 17982, 17982, -1, 17983, 17983, 17983, -1, + 17984, 17984, 17984, -1, 17985, 17985, 17985, -1, + 17986, 17986, 17986, -1, 17987, 17987, 17987, -1, + 17988, 17988, 17988, -1, 17989, 17989, 17989, -1, + 17990, 17990, 17990, -1, 17991, 17991, 17991, -1, + 17992, 17992, 17992, -1, 17993, 17993, 17993, -1, + 17994, 17994, 17994, -1, 17995, 17995, 17995, -1, + 17996, 17996, 17996, -1, 17997, 17997, 17997, -1, + 17998, 17998, 17998, -1, 17999, 17999, 17999, -1, + 18000, 18000, 18000, -1, 18001, 18001, 18001, -1, + 18002, 18002, 18002, -1, 18003, 18003, 18003, -1, + 18004, 18004, 18004, -1, 18005, 18005, 18005, -1, + 18006, 18006, 18006, -1, 18007, 18007, 18007, -1, + 18008, 18008, 18008, -1, 18009, 18009, 18009, -1, + 18010, 18010, 18010, -1, 18011, 18011, 18011, -1, + 18012, 18012, 18012, -1, 18013, 18013, 18013, -1, + 18014, 18014, 18014, -1, 18015, 18015, 18015, -1, + 18016, 18016, 18016, -1, 18017, 18017, 18017, -1, + 18018, 18018, 18018, -1, 18019, 18019, 18019, -1, + 18020, 18020, 18020, -1, 18021, 18021, 18021, -1, + 18022, 18022, 18022, -1, 18023, 18023, 18023, -1, + 18024, 18024, 18024, -1, 18025, 18025, 18025, -1, + 18026, 18026, 18026, -1, 18027, 18027, 18027, -1, + 18028, 18028, 18028, -1, 18029, 18029, 18029, -1, + 18030, 18030, 18030, -1, 18031, 18031, 18031, -1, + 18032, 18032, 18032, -1, 18033, 18033, 18033, -1, + 18034, 18034, 18034, -1, 18035, 18035, 18035, -1, + 18036, 18036, 18036, -1, 18037, 18037, 18037, -1, + 18038, 18038, 18038, -1, 18039, 18039, 18039, -1, + 18040, 18040, 18040, -1, 18041, 18041, 18041, -1, + 18042, 18042, 18042, -1, 18043, 18043, 18043, -1, + 18044, 18044, 18044, -1, 18045, 18045, 18045, -1, + 18046, 18046, 18046, -1, 18047, 18047, 18047, -1, + 18048, 18048, 18048, -1, 18049, 18049, 18049, -1, + 18050, 18050, 18050, -1, 18051, 18051, 18051, -1, + 18052, 18052, 18052, -1, 18053, 18053, 18053, -1, + 18054, 18054, 18054, -1, 18055, 18055, 18055, -1, + 18056, 18056, 18056, -1, 18057, 18057, 18057, -1, + 18058, 18058, 18058, -1, 18059, 18059, 18059, -1, + 18060, 18060, 18060, -1, 18061, 18061, 18061, -1, + 18062, 18062, 18062, -1, 18063, 18063, 18063, -1, + 18064, 18064, 18064, -1, 18065, 18065, 18065, -1, + 18066, 18066, 18066, -1, 18067, 18067, 18067, -1, + 18068, 18068, 18068, -1, 18069, 18069, 18069, -1, + 18070, 18070, 18070, -1, 18071, 18071, 18071, -1, + 18072, 18072, 18072, -1, 18073, 18073, 18073, -1, + 18074, 18074, 18074, -1, 18075, 18075, 18075, -1, + 18076, 18076, 18076, -1, 18077, 18077, 18077, -1, + 18078, 18078, 18078, -1, 18079, 18079, 18079, -1, + 18080, 18080, 18080, -1, 18081, 18081, 18081, -1, + 18082, 18082, 18082, -1, 18083, 18083, 18083, -1, + 18084, 18084, 18084, -1, 18085, 18085, 18085, -1, + 18086, 18086, 18086, -1, 18087, 18087, 18087, -1, + 18088, 18088, 18088, -1, 18089, 18089, 18089, -1, + 18090, 18090, 18090, -1, 18091, 18091, 18091, -1, + 18092, 18092, 18092, -1, 18093, 18093, 18093, -1, + 18094, 18094, 18094, -1, 18095, 18095, 18095, -1, + 18096, 18096, 18096, -1, 18097, 18097, 18097, -1, + 18098, 18098, 18098, -1, 18099, 18099, 18099, -1, + 18100, 18100, 18100, -1, 18101, 18101, 18101, -1, + 18102, 18102, 18102, -1, 18103, 18103, 18103, -1, + 18104, 18104, 18104, -1, 18105, 18105, 18105, -1, + 18106, 18106, 18106, -1, 18107, 18107, 18107, -1, + 18108, 18108, 18108, -1, 18109, 18109, 18109, -1, + 18110, 18110, 18110, -1, 18111, 18111, 18111, -1, + 18112, 18112, 18112, -1, 18113, 18113, 18113, -1, + 18114, 18114, 18114, -1, 18115, 18115, 18115, -1, + 18116, 18116, 18116, -1, 18117, 18117, 18117, -1, + 18118, 18118, 18118, -1, 18119, 18119, 18119, -1, + 18120, 18120, 18120, -1, 18121, 18121, 18121, -1, + 18122, 18122, 18122, -1, 18123, 18123, 18123, -1, + 18124, 18124, 18124, -1, 18125, 18125, 18125, -1, + 18126, 18126, 18126, -1, 18127, 18127, 18127, -1, + 18128, 18128, 18128, -1, 18129, 18129, 18129, -1, + 18130, 18130, 18130, -1, 18131, 18131, 18131, -1, + 18132, 18132, 18132, -1, 18133, 18133, 18133, -1, + 18134, 18134, 18134, -1, 18135, 18135, 18135, -1, + 18136, 18136, 18136, -1, 18137, 18137, 18137, -1, + 18138, 18138, 18138, -1, 18139, 18139, 18139, -1, + 18140, 18140, 18140, -1, 18141, 18141, 18141, -1, + 18142, 18142, 18142, -1, 18143, 18143, 18143, -1, + 18144, 18144, 18144, -1, 18145, 18145, 18145, -1, + 18146, 18146, 18146, -1, 18147, 18147, 18147, -1, + 18148, 18148, 18148, -1, 18149, 18149, 18149, -1, + 18150, 18150, 18150, -1, 18151, 18151, 18151, -1, + 18152, 18152, 18152, -1, 18153, 18153, 18153, -1, + 18154, 18154, 18154, -1, 18155, 18155, 18155, -1, + 18156, 18156, 18156, -1, 18157, 18157, 18157, -1, + 18158, 18158, 18158, -1, 18159, 18159, 18159, -1, + 18160, 18160, 18160, -1, 18161, 18161, 18161, -1, + 18162, 18162, 18162, -1, 18163, 18163, 18163, -1, + 18164, 18164, 18164, -1, 18165, 18165, 18165, -1, + 18166, 18166, 18166, -1, 18167, 18167, 18167, -1, + 18168, 18168, 18168, -1, 18169, 18169, 18169, -1, + 18170, 18170, 18170, -1, 18171, 18171, 18171, -1, + 18172, 18172, 18172, -1, 18173, 18173, 18173, -1, + 18174, 18174, 18174, -1, 18175, 18175, 18175, -1, + 18176, 18176, 18176, -1, 18177, 18177, 18177, -1, + 18178, 18178, 18178, -1, 18179, 18179, 18179, -1, + 18180, 18180, 18180, -1, 18181, 18181, 18181, -1, + 18182, 18182, 18182, -1, 18183, 18183, 18183, -1, + 18184, 18184, 18184, -1, 18185, 18185, 18185, -1, + 18186, 18186, 18186, -1, 18187, 18187, 18187, -1, + 18188, 18188, 18188, -1, 18189, 18189, 18189, -1, + 18190, 18190, 18190, -1, 18191, 18191, 18191, -1, + 18192, 18192, 18192, -1, 18193, 18193, 18193, -1, + 18194, 18194, 18194, -1, 18195, 18195, 18195, -1, + 18196, 18196, 18196, -1, 18197, 18197, 18197, -1, + 18198, 18198, 18198, -1, 18199, 18199, 18199, -1, + 18200, 18200, 18200, -1, 18201, 18201, 18201, -1, + 18202, 18202, 18202, -1, 18203, 18203, 18203, -1, + 18204, 18204, 18204, -1, 18205, 18205, 18205, -1, + 18206, 18206, 18206, -1, 18207, 18207, 18207, -1, + 18208, 18208, 18208, -1, 18209, 18209, 18209, -1, + 18210, 18210, 18210, -1, 18211, 18211, 18211, -1, + 18212, 18212, 18212, -1, 18213, 18213, 18213, -1, + 18214, 18214, 18214, -1, 18215, 18215, 18215, -1, + 18216, 18216, 18216, -1, 18217, 18217, 18217, -1, + 18218, 18218, 18218, -1, 18219, 18219, 18219, -1, + 18220, 18220, 18220, -1, 18221, 18221, 18221, -1, + 18222, 18222, 18222, -1, 18223, 18223, 18223, -1, + 18224, 18224, 18224, -1, 18225, 18225, 18225, -1, + 18226, 18226, 18226, -1, 18227, 18227, 18227, -1, + 18228, 18228, 18228, -1, 18229, 18229, 18229, -1, + 18230, 18230, 18230, -1, 18231, 18231, 18231, -1, + 18232, 18232, 18232, -1, 18233, 18233, 18233, -1, + 18234, 18234, 18234, -1, 18235, 18235, 18235, -1, + 18236, 18236, 18236, -1, 18237, 18237, 18237, -1, + 18238, 18238, 18238, -1, 18239, 18239, 18239, -1, + 18240, 18240, 18240, -1, 18241, 18241, 18241, -1, + 18242, 18242, 18242, -1, 18243, 18243, 18243, -1, + 18244, 18244, 18244, -1, 18245, 18245, 18245, -1, + 18246, 18246, 18246, -1, 18247, 18247, 18247, -1, + 18248, 18248, 18248, -1, 18249, 18249, 18249, -1, + 18250, 18250, 18250, -1, 18251, 18251, 18251, -1, + 18252, 18252, 18252, -1, 18253, 18253, 18253, -1, + 18254, 18254, 18254, -1, 18255, 18255, 18255, -1, + 18256, 18256, 18256, -1, 18257, 18257, 18257, -1, + 18258, 18258, 18258, -1, 18259, 18259, 18259, -1, + 18260, 18260, 18260, -1, 18261, 18261, 18261, -1, + 18262, 18262, 18262, -1, 18263, 18263, 18263, -1, + 18264, 18264, 18264, -1, 18265, 18265, 18265, -1, + 18266, 18266, 18266, -1, 18267, 18267, 18267, -1, + 18268, 18268, 18268, -1, 18269, 18269, 18269, -1, + 18270, 18270, 18270, -1, 18271, 18271, 18271, -1, + 18272, 18272, 18272, -1, 18273, 18273, 18273, -1, + 18274, 18274, 18274, -1, 18275, 18275, 18275, -1, + 18276, 18276, 18276, -1, 18277, 18277, 18277, -1, + 18278, 18278, 18278, -1, 18279, 18279, 18279, -1, + 18280, 18280, 18280, -1, 18281, 18281, 18281, -1, + 18282, 18282, 18282, -1, 18283, 18283, 18283, -1, + 18284, 18284, 18284, -1, 18285, 18285, 18285, -1, + 18286, 18286, 18286, -1, 18287, 18287, 18287, -1, + 18288, 18288, 18288, -1, 18289, 18289, 18289, -1, + 18290, 18290, 18290, -1, 18291, 18291, 18291, -1, + 18292, 18292, 18292, -1, 18293, 18293, 18293, -1, + 18294, 18294, 18294, -1, 18295, 18295, 18295, -1, + 18296, 18296, 18296, -1, 18297, 18297, 18297, -1, + 18298, 18298, 18298, -1, 18299, 18299, 18299, -1, + 18300, 18300, 18300, -1, 18301, 18301, 18301, -1, + 18302, 18302, 18302, -1, 18303, 18303, 18303, -1, + 18304, 18304, 18304, -1, 18305, 18305, 18305, -1, + 18306, 18306, 18306, -1, 18307, 18307, 18307, -1, + 18308, 18308, 18308, -1, 18309, 18309, 18309, -1, + 18310, 18310, 18310, -1, 18311, 18311, 18311, -1, + 18312, 18312, 18312, -1, 18313, 18313, 18313, -1, + 18314, 18314, 18314, -1, 18315, 18315, 18315, -1, + 18316, 18316, 18316, -1, 18317, 18317, 18317, -1, + 18318, 18318, 18318, -1, 18319, 18319, 18319, -1, + 18320, 18320, 18320, -1, 18321, 18321, 18321, -1, + 18322, 18322, 18322, -1, 18323, 18323, 18323, -1, + 18324, 18324, 18324, -1, 18325, 18325, 18325, -1, + 18326, 18326, 18326, -1, 18327, 18327, 18327, -1, + 18328, 18328, 18328, -1, 18329, 18329, 18329, -1, + 18330, 18330, 18330, -1, 18331, 18331, 18331, -1, + 18332, 18332, 18332, -1, 18333, 18333, 18333, -1, + 18334, 18334, 18334, -1, 18335, 18335, 18335, -1, + 18336, 18336, 18336, -1, 18337, 18337, 18337, -1, + 18338, 18338, 18338, -1, 18339, 18339, 18339, -1, + 18340, 18340, 18340, -1, 18341, 18341, 18341, -1, + 18342, 18342, 18342, -1, 18343, 18343, 18343, -1, + 18344, 18344, 18344, -1, 18345, 18345, 18345, -1, + 18346, 18346, 18346, -1, 18347, 18347, 18347, -1, + 18348, 18348, 18348, -1, 18349, 18349, 18349, -1, + 18350, 18350, 18350, -1, 18351, 18351, 18351, -1, + 18352, 18352, 18352, -1, 18353, 18353, 18353, -1, + 18354, 18354, 18354, -1, 18355, 18355, 18355, -1, + 18356, 18356, 18356, -1, 18357, 18357, 18357, -1, + 18358, 18358, 18358, -1, 18359, 18359, 18359, -1, + 18360, 18360, 18360, -1, 18361, 18361, 18361, -1, + 18362, 18362, 18362, -1, 18363, 18363, 18363, -1, + 18364, 18364, 18364, -1, 18365, 18365, 18365, -1, + 18366, 18366, 18366, -1, 18367, 18367, 18367, -1, + 18368, 18368, 18368, -1, 18369, 18369, 18369, -1, + 18370, 18370, 18370, -1, 18371, 18371, 18371, -1, + 18372, 18372, 18372, -1, 18373, 18373, 18373, -1, + 18374, 18374, 18374, -1, 18375, 18375, 18375, -1, + 18376, 18376, 18376, -1, 18377, 18377, 18377, -1, + 18378, 18378, 18378, -1, 18379, 18379, 18379, -1, + 18380, 18380, 18380, -1, 18381, 18381, 18381, -1, + 18382, 18382, 18382, -1, 18383, 18383, 18383, -1, + 18384, 18384, 18384, -1, 18385, 18385, 18385, -1, + 18386, 18386, 18386, -1, 18387, 18387, 18387, -1, + 18388, 18388, 18388, -1, 18389, 18389, 18389, -1, + 18390, 18390, 18390, -1, 18391, 18391, 18391, -1, + 18392, 18392, 18392, -1, 18393, 18393, 18393, -1, + 18394, 18394, 18394, -1, 18395, 18395, 18395, -1, + 18396, 18396, 18396, -1, 18397, 18397, 18397, -1, + 18398, 18398, 18398, -1, 18399, 18399, 18399, -1, + 18400, 18400, 18400, -1, 18401, 18401, 18401, -1, + 18402, 18402, 18402, -1, 18403, 18403, 18403, -1, + 18404, 18404, 18404, -1, 18405, 18405, 18405, -1, + 18406, 18406, 18406, -1, 18407, 18407, 18407, -1, + 18408, 18408, 18408, -1, 18409, 18409, 18409, -1, + 18410, 18410, 18410, -1, 18411, 18411, 18411, -1, + 18412, 18412, 18412, -1, 18413, 18413, 18413, -1, + 18414, 18414, 18414, -1, 18415, 18415, 18415, -1, + 18416, 18416, 18416, -1, 18417, 18417, 18417, -1, + 18418, 18418, 18418, -1, 18419, 18419, 18419, -1, + 18420, 18420, 18420, -1, 18421, 18421, 18421, -1, + 18422, 18422, 18422, -1, 18423, 18423, 18423, -1, + 18424, 18424, 18424, -1, 18425, 18425, 18425, -1, + 18426, 18426, 18426, -1, 18427, 18427, 18427, -1, + 18428, 18428, 18428, -1, 18429, 18429, 18429, -1, + 18430, 18430, 18430, -1, 18431, 18431, 18431, -1, + 18432, 18432, 18432, -1, 18433, 18433, 18433, -1, + 18434, 18434, 18434, -1, 18435, 18435, 18435, -1, + 18436, 18436, 18436, -1, 18437, 18437, 18437, -1, + 18438, 18438, 18438, -1, 18439, 18439, 18439, -1, + 18440, 18440, 18440, -1, 18441, 18441, 18441, -1, + 18442, 18442, 18442, -1, 18443, 18443, 18443, -1, + 18444, 18444, 18444, -1, 18445, 18445, 18445, -1, + 18446, 18446, 18446, -1, 18447, 18447, 18447, -1, + 18448, 18448, 18448, -1, 18449, 18449, 18449, -1, + 18450, 18450, 18450, -1, 18451, 18451, 18451, -1, + 18452, 18452, 18452, -1, 18453, 18453, 18453, -1, + 18454, 18454, 18454, -1, 18455, 18455, 18455, -1, + 18456, 18456, 18456, -1, 18457, 18457, 18457, -1, + 18458, 18458, 18458, -1, 18459, 18459, 18459, -1, + 18460, 18460, 18460, -1, 18461, 18461, 18461, -1, + 18462, 18462, 18462, -1, 18463, 18463, 18463, -1, + 18464, 18464, 18464, -1, 18465, 18465, 18465, -1, + 18466, 18466, 18466, -1, 18467, 18467, 18467, -1, + 18468, 18468, 18468, -1, 18469, 18469, 18469, -1, + 18470, 18470, 18470, -1, 18471, 18471, 18471, -1, + 18472, 18472, 18472, -1, 18473, 18473, 18473, -1, + 18474, 18474, 18474, -1, 18475, 18475, 18475, -1, + 18476, 18476, 18476, -1, 18477, 18477, 18477, -1, + 18478, 18478, 18478, -1, 18479, 18479, 18479, -1, + 18480, 18480, 18480, -1, 18481, 18481, 18481, -1, + 18482, 18482, 18482, -1, 18483, 18483, 18483, -1, + 18484, 18484, 18484, -1, 18485, 18485, 18485, -1, + 18486, 18486, 18486, -1, 18487, 18487, 18487, -1, + 18488, 18488, 18488, -1, 18489, 18489, 18489, -1, + 18490, 18490, 18490, -1, 18491, 18491, 18491, -1, + 18492, 18492, 18492, -1, 18493, 18493, 18493, -1, + 18494, 18494, 18494, -1, 18495, 18495, 18495, -1, + 18496, 18496, 18496, -1, 18497, 18497, 18497, -1, + 18498, 18498, 18498, -1, 18499, 18499, 18499, -1, + 18500, 18500, 18500, -1, 18501, 18501, 18501, -1, + 18502, 18502, 18502, -1, 18503, 18503, 18503, -1, + 18504, 18504, 18504, -1, 18505, 18505, 18505, -1, + 18506, 18506, 18506, -1, 18507, 18507, 18507, -1, + 18508, 18508, 18508, -1, 18509, 18509, 18509, -1, + 18510, 18510, 18510, -1, 18511, 18511, 18511, -1, + 18512, 18512, 18512, -1, 18513, 18513, 18513, -1, + 18514, 18514, 18514, -1, 18515, 18515, 18515, -1, + 18516, 18516, 18516, -1, 18517, 18517, 18517, -1, + 18518, 18518, 18518, -1, 18519, 18519, 18519, -1, + 18520, 18520, 18520, -1, 18521, 18521, 18521, -1, + 18522, 18522, 18522, -1, 18523, 18523, 18523, -1, + 18524, 18524, 18524, -1, 18525, 18525, 18525, -1, + 18526, 18526, 18526, -1, 18527, 18527, 18527, -1, + 18528, 18528, 18528, -1, 18529, 18529, 18529, -1, + 18530, 18530, 18530, -1, 18531, 18531, 18531, -1, + 18532, 18532, 18532, -1, 18533, 18533, 18533, -1, + 18534, 18534, 18534, -1, 18535, 18535, 18535, -1, + 18536, 18536, 18536, -1, 18537, 18537, 18537, -1, + 18538, 18538, 18538, -1, 18539, 18539, 18539, -1, + 18540, 18540, 18540, -1, 18541, 18541, 18541, -1, + 18542, 18542, 18542, -1, 18543, 18543, 18543, -1, + 18544, 18544, 18544, -1, 18545, 18545, 18545, -1, + 18546, 18546, 18546, -1, 18547, 18547, 18547, -1, + 18548, 18548, 18548, -1, 18549, 18549, 18549, -1, + 18550, 18550, 18550, -1, 18551, 18551, 18551, -1, + 18552, 18552, 18552, -1, 18553, 18553, 18553, -1, + 18554, 18554, 18554, -1, 18555, 18555, 18555, -1, + 18556, 18556, 18556, -1, 18557, 18557, 18557, -1, + 18558, 18558, 18558, -1, 18559, 18559, 18559, -1, + 18560, 18560, 18560, -1, 18561, 18561, 18561, -1, + 18562, 18562, 18562, -1, 18563, 18563, 18563, -1, + 18564, 18564, 18564, -1, 18565, 18565, 18565, -1, + 18566, 18566, 18566, -1, 18567, 18567, 18567, -1, + 18568, 18568, 18568, -1, 18569, 18569, 18569, -1, + 18570, 18570, 18570, -1, 18571, 18571, 18571, -1, + 18572, 18572, 18572, -1, 18573, 18573, 18573, -1, + 18574, 18574, 18574, -1, 18575, 18575, 18575, -1, + 18576, 18576, 18576, -1, 18577, 18577, 18577, -1, + 18578, 18578, 18578, -1, 18579, 18579, 18579, -1, + 18580, 18580, 18580, -1, 18581, 18581, 18581, -1, + 18582, 18582, 18582, -1, 18583, 18583, 18583, -1, + 18584, 18584, 18584, -1, 18585, 18585, 18585, -1, + 18586, 18586, 18586, -1, 18587, 18587, 18587, -1, + 18588, 18588, 18588, -1, 18589, 18589, 18589, -1, + 18590, 18590, 18590, -1, 18591, 18591, 18591, -1, + 18592, 18592, 18592, -1, 18593, 18593, 18593, -1, + 18594, 18594, 18594, -1, 18595, 18595, 18595, -1, + 18596, 18596, 18596, -1, 18597, 18597, 18597, -1, + 18598, 18598, 18598, -1, 18599, 18599, 18599, -1, + 18600, 18600, 18600, -1, 18601, 18601, 18601, -1, + 18602, 18602, 18602, -1, 18603, 18603, 18603, -1, + 18604, 18604, 18604, -1, 18605, 18605, 18605, -1, + 18606, 18606, 18606, -1, 18607, 18607, 18607, -1, + 18608, 18608, 18608, -1, 18609, 18609, 18609, -1, + 18610, 18610, 18610, -1, 18611, 18611, 18611, -1, + 18612, 18612, 18612, -1, 18613, 18613, 18613, -1, + 18614, 18614, 18614, -1, 18615, 18615, 18615, -1, + 18616, 18616, 18616, -1, 18617, 18617, 18617, -1, + 18618, 18618, 18618, -1, 18619, 18619, 18619, -1, + 18620, 18620, 18620, -1, 18621, 18621, 18621, -1, + 18622, 18622, 18622, -1, 18623, 18623, 18623, -1, + 18624, 18624, 18624, -1, 18625, 18625, 18625, -1, + 18626, 18626, 18626, -1, 18627, 18627, 18627, -1, + 18628, 18628, 18628, -1, 18629, 18629, 18629, -1, + 18630, 18630, 18630, -1, 18631, 18631, 18631, -1, + 18632, 18632, 18632, -1, 18633, 18633, 18633, -1, + 18634, 18634, 18634, -1, 18635, 18635, 18635, -1, + 18636, 18636, 18636, -1, 18637, 18637, 18637, -1, + 18638, 18638, 18638, -1, 18639, 18639, 18639, -1, + 18640, 18640, 18640, -1, 18641, 18641, 18641, -1, + 18642, 18642, 18642, -1, 18643, 18643, 18643, -1, + 18644, 18644, 18644, -1, 18645, 18645, 18645, -1, + 18646, 18646, 18646, -1, 18647, 18647, 18647, -1, + 18648, 18648, 18648, -1, 18649, 18649, 18649, -1, + 18650, 18650, 18650, -1, 18651, 18651, 18651, -1, + 18652, 18652, 18652, -1, 18653, 18653, 18653, -1, + 18654, 18654, 18654, -1, 18655, 18655, 18655, -1, + 18656, 18656, 18656, -1, 18657, 18657, 18657, -1, + 18658, 18658, 18658, -1, 18659, 18659, 18659, -1, + 18660, 18660, 18660, -1, 18661, 18661, 18661, -1, + 18662, 18662, 18662, -1, 18663, 18663, 18663, -1, + 18664, 18664, 18664, -1, 18665, 18665, 18665, -1, + 18666, 18666, 18666, -1, 18667, 18667, 18667, -1, + 18668, 18668, 18668, -1, 18669, 18669, 18669, -1, + 18670, 18670, 18670, -1, 18671, 18671, 18671, -1, + 18672, 18672, 18672, -1, 18673, 18673, 18673, -1, + 18674, 18674, 18674, -1, 18675, 18675, 18675, -1, + 18676, 18676, 18676, -1, 18677, 18677, 18677, -1, + 18678, 18678, 18678, -1, 18679, 18679, 18679, -1, + 18680, 18680, 18680, -1, 18681, 18681, 18681, -1, + 18682, 18682, 18682, -1, 18683, 18683, 18683, -1, + 18684, 18684, 18684, -1, 18685, 18685, 18685, -1, + 18686, 18686, 18686, -1, 18687, 18687, 18687, -1, + 18688, 18688, 18688, -1, 18689, 18689, 18689, -1, + 18690, 18690, 18690, -1, 18691, 18691, 18691, -1, + 18692, 18692, 18692, -1, 18693, 18693, 18693, -1, + 18694, 18694, 18694, -1, 18695, 18695, 18695, -1, + 18696, 18696, 18696, -1, 18697, 18697, 18697, -1, + 18698, 18698, 18698, -1, 18699, 18699, 18699, -1, + 18700, 18700, 18700, -1, 18701, 18701, 18701, -1, + 18702, 18702, 18702, -1, 18703, 18703, 18703, -1, + 18704, 18704, 18704, -1, 18705, 18705, 18705, -1, + 18706, 18706, 18706, -1, 18707, 18707, 18707, -1, + 18708, 18708, 18708, -1, 18709, 18709, 18709, -1, + 18710, 18710, 18710, -1, 18711, 18711, 18711, -1, + 18712, 18712, 18712, -1, 18713, 18713, 18713, -1, + 18714, 18714, 18714, -1, 18715, 18715, 18715, -1, + 18716, 18716, 18716, -1, 18717, 18717, 18717, -1, + 18718, 18718, 18718, -1, 18719, 18719, 18719, -1, + 18720, 18720, 18720, -1, 18721, 18721, 18721, -1, + 18722, 18722, 18722, -1, 18723, 18723, 18723, -1, + 18724, 18724, 18724, -1, 18725, 18725, 18725, -1, + 18726, 18726, 18726, -1, 18727, 18727, 18727, -1, + 18728, 18728, 18728, -1, 18729, 18729, 18729, -1, + 18730, 18730, 18730, -1, 18731, 18731, 18731, -1, + 18732, 18732, 18732, -1, 18733, 18733, 18733, -1, + 18734, 18734, 18734, -1, 18735, 18735, 18735, -1, + 18736, 18736, 18736, -1, 18737, 18737, 18737, -1, + 18738, 18738, 18738, -1, 18739, 18739, 18739, -1, + 18740, 18740, 18740, -1, 18741, 18741, 18741, -1, + 18742, 18742, 18742, -1, 18743, 18743, 18743, -1, + 18744, 18744, 18744, -1, 18745, 18745, 18745, -1, + 18746, 18746, 18746, -1, 18747, 18747, 18747, -1, + 18748, 18748, 18748, -1, 18749, 18749, 18749, -1, + 18750, 18750, 18750, -1, 18751, 18751, 18751, -1, + 18752, 18752, 18752, -1, 18753, 18753, 18753, -1, + 18754, 18754, 18754, -1, 18755, 18755, 18755, -1, + 18756, 18756, 18756, -1, 18757, 18757, 18757, -1, + 18758, 18758, 18758, -1, 18759, 18759, 18759, -1, + 18760, 18760, 18760, -1, 18761, 18761, 18761, -1, + 18762, 18762, 18762, -1, 18763, 18763, 18763, -1, + 18764, 18764, 18764, -1, 18765, 18765, 18765, -1, + 18766, 18766, 18766, -1, 18767, 18767, 18767, -1, + 18768, 18768, 18768, -1, 18769, 18769, 18769, -1, + 18770, 18770, 18770, -1, 18771, 18771, 18771, -1, + 18772, 18772, 18772, -1, 18773, 18773, 18773, -1, + 18774, 18774, 18774, -1, 18775, 18775, 18775, -1, + 18776, 18776, 18776, -1, 18777, 18777, 18777, -1, + 18778, 18778, 18778, -1, 18779, 18779, 18779, -1, + 18780, 18780, 18780, -1, 18781, 18781, 18781, -1, + 18782, 18782, 18782, -1, 18783, 18783, 18783, -1, + 18784, 18784, 18784, -1, 18785, 18785, 18785, -1, + 18786, 18786, 18786, -1, 18787, 18787, 18787, -1, + 18788, 18788, 18788, -1, 18789, 18789, 18789, -1, + 18790, 18790, 18790, -1, 18791, 18791, 18791, -1, + 18792, 18792, 18792, -1, 18793, 18793, 18793, -1, + 18794, 18794, 18794, -1, 18795, 18795, 18795, -1, + 18796, 18796, 18796, -1, 18797, 18797, 18797, -1, + 18798, 18798, 18798, -1, 18799, 18799, 18799, -1, + 18800, 18800, 18800, -1, 18801, 18801, 18801, -1, + 18802, 18802, 18802, -1, 18803, 18803, 18803, -1, + 18804, 18804, 18804, -1, 18805, 18805, 18805, -1, + 18806, 18806, 18806, -1, 18807, 18807, 18807, -1, + 18808, 18808, 18808, -1, 18809, 18809, 18809, -1, + 18810, 18810, 18810, -1, 18811, 18811, 18811, -1, + 18812, 18812, 18812, -1, 18813, 18813, 18813, -1, + 18814, 18814, 18814, -1, 18815, 18815, 18815, -1, + 18816, 18816, 18816, -1, 18817, 18817, 18817, -1, + 18818, 18818, 18818, -1, 18819, 18819, 18819, -1, + 18820, 18820, 18820, -1, 18821, 18821, 18821, -1, + 18822, 18822, 18822, -1, 18823, 18823, 18823, -1, + 18824, 18824, 18824, -1, 18825, 18825, 18825, -1, + 18826, 18826, 18826, -1, 18827, 18827, 18827, -1, + 18828, 18828, 18828, -1, 18829, 18829, 18829, -1, + 18830, 18830, 18830, -1, 18831, 18831, 18831, -1, + 18832, 18832, 18832, -1, 18833, 18833, 18833, -1, + 18834, 18834, 18834, -1, 18835, 18835, 18835, -1, + 18836, 18836, 18836, -1, 18837, 18837, 18837, -1, + 18838, 18838, 18838, -1, 18839, 18839, 18839, -1, + 18840, 18840, 18840, -1, 18841, 18841, 18841, -1, + 18842, 18842, 18842, -1, 18843, 18843, 18843, -1, + 18844, 18844, 18844, -1, 18845, 18845, 18845, -1, + 18846, 18846, 18846, -1, 18847, 18847, 18847, -1, + 18848, 18848, 18848, -1, 18849, 18849, 18849, -1, + 18850, 18850, 18850, -1, 18851, 18851, 18851, -1, + 18852, 18852, 18852, -1, 18853, 18853, 18853, -1, + 18854, 18854, 18854, -1, 18855, 18855, 18855, -1, + 18856, 18856, 18856, -1, 18857, 18857, 18857, -1, + 18858, 18858, 18858, -1, 18859, 18859, 18859, -1, + 18860, 18860, 18860, -1, 18861, 18861, 18861, -1, + 18862, 18862, 18862, -1, 18863, 18863, 18863, -1, + 18864, 18864, 18864, -1, 18865, 18865, 18865, -1, + 18866, 18866, 18866, -1, 18867, 18867, 18867, -1, + 18868, 18868, 18868, -1, 18869, 18869, 18869, -1, + 18870, 18870, 18870, -1, 18871, 18871, 18871, -1, + 18872, 18872, 18872, -1, 18873, 18873, 18873, -1, + 18874, 18874, 18874, -1, 18875, 18875, 18875, -1, + 18876, 18876, 18876, -1, 18877, 18877, 18877, -1, + 18878, 18878, 18878, -1, 18879, 18879, 18879, -1, + 18880, 18880, 18880, -1, 18881, 18881, 18881, -1, + 18882, 18882, 18882, -1, 18883, 18883, 18883, -1, + 18884, 18884, 18884, -1, 18885, 18885, 18885, -1, + 18886, 18886, 18886, -1, 18887, 18887, 18887, -1, + 18888, 18888, 18888, -1, 18889, 18889, 18889, -1, + 18890, 18890, 18890, -1, 18891, 18891, 18891, -1, + 18892, 18892, 18892, -1, 18893, 18893, 18893, -1, + 18894, 18894, 18894, -1, 18895, 18895, 18895, -1, + 18896, 18896, 18896, -1, 18897, 18897, 18897, -1, + 18898, 18898, 18898, -1, 18899, 18899, 18899, -1, + 18900, 18900, 18900, -1, 18901, 18901, 18901, -1, + 18902, 18902, 18902, -1, 18903, 18903, 18903, -1, + 18904, 18904, 18904, -1, 18905, 18905, 18905, -1, + 18906, 18906, 18906, -1, 18907, 18907, 18907, -1, + 18908, 18908, 18908, -1, 18909, 18909, 18909, -1, + 18910, 18910, 18910, -1, 18911, 18911, 18911, -1, + 18912, 18912, 18912, -1, 18913, 18913, 18913, -1, + 18914, 18914, 18914, -1, 18915, 18915, 18915, -1, + 18916, 18916, 18916, -1, 18917, 18917, 18917, -1, + 18918, 18918, 18918, -1, 18919, 18919, 18919, -1, + 18920, 18920, 18920, -1, 18921, 18921, 18921, -1, + 18922, 18922, 18922, -1, 18923, 18923, 18923, -1, + 18924, 18924, 18924, -1, 18925, 18925, 18925, -1, + 18926, 18926, 18926, -1, 18927, 18927, 18927, -1, + 18928, 18928, 18928, -1, 18929, 18929, 18929, -1, + 18930, 18930, 18930, -1, 18931, 18931, 18931, -1, + 18932, 18932, 18932, -1, 18933, 18933, 18933, -1, + 18934, 18934, 18934, -1, 18935, 18935, 18935, -1, + 18936, 18936, 18936, -1, 18937, 18937, 18937, -1, + 18938, 18938, 18938, -1, 18939, 18939, 18939, -1, + 18940, 18940, 18940, -1, 18941, 18941, 18941, -1, + 18942, 18942, 18942, -1, 18943, 18943, 18943, -1, + 18944, 18944, 18944, -1, 18945, 18945, 18945, -1, + 18946, 18946, 18946, -1, 18947, 18947, 18947, -1, + 18948, 18948, 18948, -1, 18949, 18949, 18949, -1, + 18950, 18950, 18950, -1, 18951, 18951, 18951, -1, + 18952, 18952, 18952, -1, 18953, 18953, 18953, -1, + 18954, 18954, 18954, -1, 18955, 18955, 18955, -1, + 18956, 18956, 18956, -1, 18957, 18957, 18957, -1, + 18958, 18958, 18958, -1, 18959, 18959, 18959, -1, + 18960, 18960, 18960, -1, 18961, 18961, 18961, -1, + 18962, 18962, 18962, -1, 18963, 18963, 18963, -1, + 18964, 18964, 18964, -1, 18965, 18965, 18965, -1, + 18966, 18966, 18966, -1, 18967, 18967, 18967, -1, + 18968, 18968, 18968, -1, 18969, 18969, 18969, -1, + 18970, 18970, 18970, -1, 18971, 18971, 18971, -1, + 18972, 18972, 18972, -1, 18973, 18973, 18973, -1, + 18974, 18974, 18974, -1, 18975, 18975, 18975, -1, + 18976, 18976, 18976, -1, 18977, 18977, 18977, -1, + 18978, 18978, 18978, -1, 18979, 18979, 18979, -1, + 18980, 18980, 18980, -1, 18981, 18981, 18981, -1, + 18982, 18982, 18982, -1, 18983, 18983, 18983, -1, + 18984, 18984, 18984, -1, 18985, 18985, 18985, -1, + 18986, 18986, 18986, -1, 18987, 18987, 18987, -1, + 18988, 18988, 18988, -1, 18989, 18989, 18989, -1, + 18990, 18990, 18990, -1, 18991, 18991, 18991, -1, + 18992, 18992, 18992, -1, 18993, 18993, 18993, -1, + 18994, 18994, 18994, -1, 18995, 18995, 18995, -1, + 18996, 18996, 18996, -1, 18997, 18997, 18997, -1, + 18998, 18998, 18998, -1, 18999, 18999, 18999, -1, + 19000, 19000, 19000, -1, 19001, 19001, 19001, -1, + 19002, 19002, 19002, -1, 19003, 19003, 19003, -1, + 19004, 19004, 19004, -1, 19005, 19005, 19005, -1, + 19006, 19006, 19006, -1, 19007, 19007, 19007, -1, + 19008, 19008, 19008, -1, 19009, 19009, 19009, -1, + 19010, 19010, 19010, -1, 19011, 19011, 19011, -1, + 19012, 19012, 19012, -1, 19013, 19013, 19013, -1, + 19014, 19014, 19014, -1, 19015, 19015, 19015, -1, + 19016, 19016, 19016, -1, 19017, 19017, 19017, -1, + 19018, 19018, 19018, -1, 19019, 19019, 19019, -1, + 19020, 19020, 19020, -1, 19021, 19021, 19021, -1, + 19022, 19022, 19022, -1, 19023, 19023, 19023, -1, + 19024, 19024, 19024, -1, 19025, 19025, 19025, -1, + 19026, 19026, 19026, -1, 19027, 19027, 19027, -1, + 19028, 19028, 19028, -1, 19029, 19029, 19029, -1, + 19030, 19030, 19030, -1, 19031, 19031, 19031, -1, + 19032, 19032, 19032, -1, 19033, 19033, 19033, -1, + 19034, 19034, 19034, -1, 19035, 19035, 19035, -1, + 19036, 19036, 19036, -1, 19036, 19036, 19036, -1, + 19037, 19037, 19037, -1, 19037, 19037, 19037, -1, + 19038, 19038, 19038, -1, 19038, 19038, 19038, -1, + 19039, 19039, 19039, -1, 19039, 19039, 19039, -1, + 19040, 19040, 19040, -1, 19040, 19040, 19040, -1, + 19041, 19041, 19041, -1, 19041, 19041, 19041, -1, + 19042, 19042, 19042, -1, 19042, 19042, 19042, -1, + 19043, 19043, 19043, -1, 19043, 19043, 19043, -1, + 19044, 19044, 19044, -1, 19044, 19044, 19044, -1, + 19045, 19045, 19045, -1, 19045, 19045, 19045, -1, + 19046, 19046, 19046, -1, 19046, 19046, 19046, -1, + 19047, 19047, 19047, -1, 19047, 19047, 19047, -1, + 19048, 19048, 19048, -1, 19048, 19048, 19048, -1, + 19049, 19049, 19049, -1, 19049, 19049, 19049, -1, + 19050, 19050, 19050, -1, 19050, 19050, 19050, -1, + 19051, 19051, 19051, -1, 19051, 19051, 19051, -1, + 19052, 19052, 19052, -1, 19052, 19052, 19052, -1, + 19053, 19053, 19053, -1, 19053, 19053, 19053, -1, + 19054, 19054, 19054, -1, 19054, 19054, 19054, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19056, 19056, 19056, -1, 19056, 19056, 19056, -1, + 19057, 19057, 19057, -1, 19057, 19057, 19057, -1, + 19058, 19058, 19058, -1, 19058, 19058, 19058, -1, + 19059, 19059, 19059, -1, 19059, 19059, 19059, -1, + 19060, 19060, 19060, -1, 19060, 19060, 19060, -1, + 19061, 19061, 19061, -1, 19061, 19061, 19061, -1, + 19062, 19062, 19062, -1, 19062, 19062, 19062, -1, + 19063, 19063, 19063, -1, 19063, 19063, 19063, -1, + 19064, 19064, 19064, -1, 19064, 19064, 19064, -1, + 19065, 19065, 19065, -1, 19065, 19065, 19065, -1, + 19066, 19066, 19066, -1, 19066, 19066, 19066, -1, + 19067, 19067, 19067, -1, 19067, 19067, 19067, -1, + 19068, 19068, 19068, -1, 19068, 19068, 19068, -1, + 19069, 19069, 19069, -1, 19069, 19069, 19069, -1, + 19070, 19070, 19070, -1, 19070, 19070, 19070, -1, + 19071, 19071, 19071, -1, 19071, 19071, 19071, -1, + 19072, 19072, 19072, -1, 19072, 19072, 19072, -1, + 19073, 19073, 19073, -1, 19073, 19073, 19073, -1, + 19074, 19074, 19074, -1, 19074, 19074, 19074, -1, + 19075, 19075, 19075, -1, 19075, 19075, 19075, -1, + 19076, 19076, 19076, -1, 19076, 19076, 19076, -1, + 19077, 19077, 19077, -1, 19077, 19077, 19077, -1, + 19078, 19078, 19078, -1, 19078, 19078, 19078, -1, + 19079, 19079, 19079, -1, 19079, 19079, 19079, -1, + 19080, 19080, 19080, -1, 19080, 19080, 19080, -1, + 19081, 19081, 19081, -1, 19081, 19081, 19081, -1, + 19082, 19082, 19082, -1, 19082, 19082, 19082, -1, + 19083, 19083, 19083, -1, 19083, 19083, 19083, -1, + 19084, 19084, 19084, -1, 19084, 19084, 19084, -1, + 19085, 19085, 19085, -1, 19085, 19085, 19085, -1, + 19086, 19086, 19086, -1, 19086, 19086, 19086, -1, + 19087, 19087, 19087, -1, 19087, 19087, 19087, -1, + 19088, 19088, 19088, -1, 19088, 19088, 19088, -1, + 19089, 19089, 19089, -1, 19089, 19089, 19089, -1, + 19090, 19090, 19090, -1, 19090, 19090, 19090, -1, + 19091, 19091, 19091, -1, 19091, 19091, 19091, -1, + 19092, 19092, 19092, -1, 19092, 19092, 19092, -1, + 19093, 19093, 19093, -1, 19093, 19093, 19093, -1, + 19094, 19094, 19094, -1, 19094, 19094, 19094, -1, + 19095, 19095, 19095, -1, 19095, 19095, 19095, -1, + 19096, 19096, 19096, -1, 19096, 19096, 19096, -1, + 19097, 19097, 19097, -1, 19097, 19097, 19097, -1, + 19098, 19098, 19098, -1, 19098, 19098, 19098, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19055, 19055, 19055, -1, + 19055, 19055, 19055, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1, + 19099, 19099, 19099, -1, 19099, 19099, 19099, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link6.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link6.wrl new file mode 100644 index 0000000..e186477 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link6.wrl @@ -0,0 +1,15354 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.30000001 0.30000001 0.30000001 + shininess 0.40599999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.0069564502 -0.051767901 0.052800801, + -0.0073703802 -0.054842401 0.048565999, + -0.00348601 -0.052117102 0.052800499, + -0.061533201 -0.0103465 -0.041340798, + -0.058982201 -0.0109679 -0.046008699, + -0.060702499 -0.0144333 -0.041343998, + -0.062770903 -0.01493 -0.0365448, + -0.061631601 -0.0190892 -0.0365481, + -0.063391604 -0.019639101 -0.031633001, + -0.061936598 -0.0238293 -0.031636398, + -0.063386001 -0.0243914 -0.026622299, + -0.061613798 -0.0285706 -0.0266257, + -0.062755004 -0.0291044 -0.0215296, + -0.060669798 -0.0332308 -0.021532901, + -0.0615106 -0.033695702 -0.016372001, + -0.059121698 -0.037728898 -0.016375201, + -0.0596749 -0.038086198 -0.0111672, + -0.056997199 -0.041986901 -0.0111703, + -0.057280101 -0.0421996 -0.0059327199, + -0.054333299 -0.045931201 -0.0059357001, + -0.054368 -0.0459648 -0.00068639999, + -0.0511765 -0.049493499 -0.00068921002, + -0.050989099 -0.049316499 0.0045539699, + -0.047581501 -0.052611999 0.0045513501, + -0.047201999 -0.052196499 0.0097706104, + -0.043610699 -0.055232801 0.0097681899, + -0.043072 -0.054554701 0.0149458, + -0.0393328 -0.057309899 0.0149436, + -0.038670901 -0.056349698 0.020061901, + -0.034821901 -0.0588069 0.020059999, + -0.034074798 -0.057549499 0.025101701, + -0.030156201 -0.059696998 0.0251, + -0.029363601 -0.058132499 0.0300478, + -0.025416801 -0.059964001 0.0300464, + -0.0246193 -0.0580872 0.0348837, + -0.020686399 -0.059602 0.034882501, + -0.019925 -0.057413001 0.039592601, + -0.0160478 -0.058615599 0.039591599, + -0.0153631 -0.056119699 0.044158701, + -0.0115828 -0.057020601 0.044158, + -0.0110144 -0.054227699 0.048566502, + -0.038649999 0.057018202 -0.0228623, + -0.037711799 0.057019901 -0.0249871, + -0.038441699 0.056021102 -0.0265583, + -0.036927599 0.057021201 -0.026556101, + -0.036563601 0.0570217 -0.027284401, + 0.037805501 -0.026143 0.059966002, + 0.041125 -0.0262964 0.0568652, + 0.039782699 -0.0230163 0.059968501, + 0.037094701 -0.0214667 0.062873699, + 0.0032907401 -0.0027495599 0.0788588, + 0.0065673999 -0.00542452 0.078440398, + 0.0034962599 -0.0024761199 0.078859001, + 0.0061146398 -0.0059356298 0.078440003, + 0.00913925 -0.0088402303 0.077745803, + 0.00840325 -0.0095472597 0.077745199, + 0.0111484 -0.012645 0.076778203, + 0.0100996 -0.0135013 0.076777503, + 0.0125433 -0.016752301 0.075541899, + 0.0111595 -0.017707501 0.075541101, + 0.0132858 -0.021068901 0.074042097, + 0.0115522 -0.022069899 0.074041396, + 0.0133517 -0.025497099 0.072285503, + 0.0112613 -0.026489001 0.072284698, + 0.012731 -0.0299366 0.070279598, + 0.0102853 -0.0308642 0.070278801, + 0.0114286 -0.034286998 0.068032898, + 0.00863693 -0.035095599 0.068032302, + 0.0094640302 -0.038449299 0.0655552, + 0.0063436599 -0.039086401 0.065554701, + 0.0068709301 -0.0423287 0.062857099, + 0.00344664 -0.042744402 0.062856801, + 0.0036964 -0.0458358 0.0599503, + 0.00782206 -0.048181299 0.0568478, + 0.0097190896 -0.0478529 0.056848001, + 0.0073688198 -0.045389902 0.059950698, + 0.0103958 -0.051187702 0.0528013, + 0.0069564502 -0.051767901 0.052800801, + 0.0073703802 -0.054842401 0.048565999, + -0.054390799 -0.034692701 -0.036560498, + -0.052598599 -0.033544701 -0.041359201, + -0.051950201 -0.038247999 -0.0365634, + -0.053433701 -0.039345 -0.031648699, + -0.050684799 -0.042826101 -0.031651501, + -0.051870801 -0.043832801 -0.0266378, + -0.0488258 -0.047199499 -0.026640501, + -0.0497302 -0.048078202 -0.0215447, + -0.046406701 -0.051292501 -0.0215472, + -0.047049899 -0.052007601 -0.0163866, + -0.0434702 -0.055034 -0.016388999, + -0.043876901 -0.055553101 -0.0111811, + -0.040067799 -0.058359802 -0.0111834, + -0.0402667 -0.058653701 -0.0059458301, + -0.036258802 -0.061212201 -0.00594786, + -0.036281999 -0.0612556 -0.00069857598, + -0.0321096 -0.063542202 -0.00070039701, + -0.031992 -0.0633137 0.0045428299, + -0.027691901 -0.0653091 0.0045412402, + -0.027471 -0.064792298 0.00976058, + -0.0230825 -0.066482499 0.0097592296, + -0.0227974 -0.065665603 0.0149369, + -0.0183613 -0.067041598 0.0149358, + -0.0180523 -0.065917701 0.020054299, + -0.0136103 -0.066976301 0.0200535, + -0.0133183 -0.065543801 0.025095301, + -0.0089120502 -0.066287003 0.025094699, + -0.0086778197 -0.064549297 0.0300427, + -0.0043486198 -0.064984798 0.030042401, + -0.0042121802 -0.062950499 0.0348798, + 0 -0.063091397 0.034879699, + 0 -0.060773801 0.039589901, + 0.0040571401 -0.0606382 0.039590001, + 0.00388403 -0.058056001 0.0441572, + 0.00775071 -0.057666901 0.044157501, + 0.0110144 -0.054227699 0.048566502, + 0.0137888 -0.050379101 0.0528019, + 0.019037399 -0.044940598 0.056850299, + 0.0180058 -0.042308901 0.059953101, + 0.0164141 -0.0460492 0.056849401, + 0.020375 -0.048092101 0.052803699, + 0.0191145 -0.044907998 0.0568504, + 0.021551199 -0.043878201 0.056851201, + 0.023538901 -0.046624001 0.052804898, + 0.0215874 -0.050947901 0.048569102, + 0.0181388 -0.052276101 0.0485681, + 0.019074799 -0.054968301 0.044159599, + 0.0153631 -0.056119699 0.044158701, + 0.0160478 -0.058615599 0.039591599, + 0.012099 -0.0595566 0.039590899, + 0.0125614 -0.061827701 0.034880701, + 0.0084055504 -0.0625287 0.034880102, + 0.0086778197 -0.064549297 0.0300427, + 0.0043486198 -0.064984798 0.030042401, + 0.004466 -0.066734202 0.025094399, + 0 -0.066883601 0.0250942, + 0 -0.068345599 0.020052399, + -0.00456391 -0.068193004 0.0200525, + -0.0046420302 -0.069355801 0.014934, + -0.0092633199 -0.068890899 0.0149343, + -0.0093791699 -0.0697482 0.0097566303, + -0.0140164 -0.068966098 0.0097572599, + -0.0141291 -0.069516301 0.0045378902, + -0.018740499 -0.0684174 0.0045387601, + -0.0188093 -0.0686647 -0.00070447603, + -0.0233537 -0.067254998 -0.00070335303, + -0.0233387 -0.067207798 -0.00595264, + -0.0277759 -0.065498799 -0.0059512798, + -0.0276387 -0.065171003 -0.0111888, + -0.031930499 -0.0631795 -0.0111872, + -0.031634498 -0.062589698 -0.016395001, + -0.0357453 -0.060336899 -0.0163932, + -0.035256699 -0.059507798 -0.0215538, + -0.039153799 -0.057020001 -0.021551801, + -0.038441699 -0.055978701 -0.026647501, + -0.042096298 -0.053286102 -0.026645301, + -0.041133799 -0.052063201 -0.031658899, + -0.044521 -0.049199399 -0.031656601, + -0.0432849 -0.047828801 -0.036571, + -0.0463848 -0.044830799 -0.036568601, + -0.044856399 -0.0433488 -0.041367002, + -0.047653802 -0.0402559 -0.041364599, + -0.045810599 -0.0386931 -0.046030801, + -0.043079801 -0.0416288 -0.0460332, + -0.041776299 -0.043030102 -0.046034299, + -0.041858599 -0.046248 -0.0413693, + -0.039991699 -0.050613001 -0.036573201, + -0.037562799 -0.054694299 -0.031661, + -0.034615502 -0.058421299 -0.026649401, + -0.0312021 -0.061729699 -0.021555601, + -0.0273825 -0.064562798 -0.016396601, + -0.0232234 -0.066871598 -0.0111902, + -0.018797301 -0.068616502 -0.0059537599, + -0.014181 -0.069767699 -0.00070535397, + -0.0094545903 -0.0703049 0.0045372602, + -0.00470008 -0.070219003 0.0097562596, + 0 -0.069510899 0.0149339, + 0.00456391 -0.068193004 0.0200525, + 0.0089120502 -0.066287003 0.025094699, + 0.0129683 -0.063825503 0.0300433, + 0.0166611 -0.060850699 0.034881499, + 0.019925 -0.057413001 0.039592601, + 0.022701399 -0.0535716 0.044160798, + 0.0249395 -0.049392302 0.048570398, + 0.026597699 -0.044947699 0.052806199, + 0.022671301 -0.043245599 0.0568517, + 0.030247601 -0.038345698 0.0568556, + 0.029299799 -0.0390343 0.056855001, + 0.032345701 -0.041001901 0.052809399, + 0.0295376 -0.043070901 0.0528077, + 0.031295199 -0.045627899 0.048573401, + -0.033914801 -0.049370501 -0.046039298, + -0.032115102 -0.050644901 -0.0460403, + -0.035316501 -0.051414199 -0.041373499, + -0.031801298 -0.053658299 -0.041375201, + -0.0328849 -0.0554915 -0.036577102, + -0.0291031 -0.057564002 -0.036578801, + -0.0299342 -0.0592127 -0.031664599, + -0.0259107 -0.0610798 -0.031665999, + -0.026517 -0.062513597 -0.026652699, + -0.022281 -0.064145103 -0.026653999, + -0.022693699 -0.065337501 -0.0215584, + -0.0182778 -0.066707499 -0.021559499, + -0.018531101 -0.067636304 -0.0163991, + -0.0139712 -0.068723001 -0.016399899, + -0.0141019 -0.0693703 -0.0111921, + -0.0094364202 -0.0701572 -0.0111928, + -0.0094832703 -0.070509702 -0.00595527, + -0.0047522499 -0.070985697 -0.00595565, + -0.0047552902 -0.071035303 -0.000706363, + 0 -0.071194202 -0.00070649001, + 0 -0.070937701 0.0045367498, + 0.0047378801 -0.070779398 0.0045368802, + 0.00470008 -0.070219003 0.0097562596, + 0.0093791699 -0.0697482 0.0097566303, + 0.0092633199 -0.068890899 0.0149343, + 0.0138432 -0.068118297 0.014935, + 0.0136103 -0.066976301 0.0200535, + 0.0180523 -0.065917701 0.020054299, + 0.017665099 -0.064507902 0.0250961, + 0.0219329 -0.063183904 0.025097201, + 0.021356501 -0.0615278 0.0300451, + 0.025416801 -0.059964001 0.0300464, + 0.0246193 -0.0580872 0.0348837, + 0.028442301 -0.056313202 0.034885101, + 0.027395399 -0.0542452 0.039595101, + 0.0309553 -0.052294299 0.039596699, + 0.0296345 -0.050067998 0.044163499, + 0.032910202 -0.047977 0.044165201, + 0.034270301 -0.043435801 0.0485751, + 0.037516501 -0.036325201 0.052813102, + 0.035027899 -0.034086801 0.056859002, + 0.035009298 -0.03875 0.052811202, + 0.037092399 -0.041049901 0.048576999, + 0.036038801 -0.045671798 0.044167001, + 0.034377001 -0.050110001 0.039598402, + 0.032138199 -0.054287799 0.034886699, + 0.029363601 -0.058132499 0.0300478, + 0.0261028 -0.061578002 0.025098501, + 0.0224138 -0.064564802 0.0200554, + 0.0183613 -0.067041598 0.0149358, + 0.0140164 -0.068966098 0.0097572599, + 0.0094545903 -0.0703049 0.0045372602, + 0.0047552902 -0.071035303 -0.000706363, + 0 -0.071144603 -0.0059557701, + -0.0047287699 -0.070630699 -0.0111931, + -0.0093489503 -0.0695026 -0.016400499, + -0.0137802 -0.067779303 -0.021560401, + -0.0179454 -0.06549 -0.0266551, + -0.0217715 -0.062673897 -0.0316673, + -0.0251913 -0.059379201 -0.036580201, + -0.028144101 -0.055662502 -0.041376799, + -0.027052401 -0.0534999 -0.046042599, + -0.026750499 -0.053670101 -0.0460428, + -0.024361299 -0.057417899 -0.0413782, + -0.021167001 -0.060929202 -0.036581401, + -0.0175351 -0.063988097 -0.031668399, + -0.0135296 -0.066542402 -0.026655899, + -0.0092211496 -0.068548203 -0.021561, + -0.00468494 -0.069971897 -0.0164009, + 0 -0.070788801 -0.0111933, + 0.0047522499 -0.070985697 -0.00595565, + 0.0094893305 -0.070559099 -0.00070598401, + 0.0141291 -0.069516301 0.0045378902, + 0.018591 -0.067875803 0.0097581204, + 0.0227974 -0.065665603 0.0149369, + 0.0266751 -0.062923603 0.0200567, + 0.030156201 -0.059696998 0.0251, + 0.033179201 -0.056041501 0.030049499, + 0.035690598 -0.052019998 0.034888498, + 0.037645102 -0.047702 0.039600302, + 0.039006501 -0.043162599 0.044169001, + 0.039748799 -0.0384808 0.048579101, + 0.039856199 -0.033738401 0.052815098, + 0.035215002 -0.033870898 0.056859098, + 0.037790801 -0.030898301 0.056861501, + 0.038679998 -0.029872101 0.056862298, + 0.039282501 -0.028991001 0.056862999, + 0.042017799 -0.0310011 0.0528173, + 0.0422277 -0.035739999 0.048581298, + 0.0418 -0.040461101 0.044171199, + 0.040745001 -0.045081198 0.039602399, + 0.0390836 -0.049520001 0.034890499, + 0.036846701 -0.053700201 0.0300513, + 0.034074798 -0.057549499 0.025101701, + 0.0308173 -0.061001401 0.0200582, + 0.027131701 -0.0639963 0.0149382, + 0.0230825 -0.066482499 0.0097592296, + 0.018740499 -0.0684174 0.0045387601, + 0.014181 -0.069767699 -0.00070535397, + 0.0094832703 -0.070509702 -0.00595527, + 0.0047287699 -0.070630699 -0.0111931, + 0 -0.0701285 -0.016401, + -0.0046208999 -0.069011003 -0.021561399, + -0.0090534696 -0.067297399 -0.026656499, + -0.0132203 -0.065016396 -0.031669199, + -0.017048201 -0.062206902 -0.036582399, + -0.0204696 -0.0589168 -0.0413794, + -0.021104001 -0.0561294 -0.0460447, + -0.019663701 -0.0565877 -0.046045098, + -0.015842799 -0.057803601 -0.046046, + -0.023392901 -0.055132501 -0.046043899, + -0.030544801 -0.051530398 -0.046041001, + -0.037141401 -0.047085699 -0.046037499, + -0.0386739 -0.048940498 -0.041371498, + -0.0365199 -0.053171098 -0.036575299, + -0.033824001 -0.057080999 -0.0316629, + -0.030634699 -0.060602799 -0.0266512, + -0.0270082 -0.063676 -0.0215571, + -0.023008199 -0.0662475 -0.016398, + -0.018704399 -0.068273298 -0.0111913, + -0.0141719 -0.0697188 -0.00595464, + -0.0094893305 -0.070559099 -0.00070598401, + -0.0047378801 -0.070779398 0.0045368802, + 0 -0.070376098 0.0097561302, + 0.0046420302 -0.069355801 0.014934, + 0.0091074398 -0.067735799 0.020052901, + 0.0133183 -0.065543801 0.025095301, + 0.0172008 -0.062816903 0.030044099, + 0.020686399 -0.059602 0.034882501, + 0.023713199 -0.055954002 0.039593801, + 0.0262265 -0.051935699 0.044162098, + 0.028180299 -0.047616299 0.048571799, + 0.026096299 -0.041311499 0.056853201, + 0.0264073 -0.0411359 0.056853399, + 0.0245518 -0.038873401 0.059955899, + -0.037183098 -0.047049198 -0.046037499, + -0.040200301 -0.0444091 -0.046035402, + -0.0295376 -0.043070901 0.0528077, + -0.031295199 -0.045627899 0.048573401, + -0.026597699 -0.044947699 0.052806199, + -0.019037399 -0.044940598 0.056850299, + -0.0191145 -0.044907998 0.0568504, + -0.020375 -0.048092101 0.052803699, + -0.021551199 -0.043878201 0.056851201, + -0.0180058 -0.042308901 0.059953101, + -0.0164141 -0.0460492 0.056849401, + -0.017120101 -0.049345799 0.052802701, + -0.0215874 -0.050947901 0.048569102, + -0.0249395 -0.049392302 0.048570398, + -0.0262265 -0.051935699 0.044162098, + -0.0296345 -0.050067998 0.044163499, + -0.0309553 -0.052294299 0.039596699, + -0.034377001 -0.050110001 0.039598402, + -0.035690598 -0.052019998 0.034888498, + -0.0390836 -0.049520001 0.034890499, + -0.040349599 -0.051119201 0.0300534, + -0.043672301 -0.048310202 0.030055599, + -0.044851098 -0.049609501 0.025108, + -0.048063099 -0.046503 0.0251105, + -0.049116898 -0.047518201 0.020068999, + -0.05218 -0.044131499 0.0200717, + -0.053073101 -0.044882402 0.0149535, + -0.055951599 -0.041237399 0.0149564, + -0.056651399 -0.0417489 0.0097789299, + -0.059312899 -0.0378717 0.00978202, + -0.059789799 -0.0381721 0.0045628501, + -0.062205698 -0.034093201 0.0045660902, + -0.0624342 -0.034214299 -0.00067704299, + -0.064580098 -0.0299679 -0.000673662, + -0.064538799 -0.0299445 -0.0059229699, + -0.066395096 -0.025567001 -0.0059194802, + -0.0660671 -0.0254364 -0.0111572, + -0.0676191 -0.0209668 -0.0111536, + -0.066992298 -0.0207683 -0.0163617, + -0.0682308 -0.0162473 -0.0163581, + -0.067298099 -0.0160209 -0.021519201, + -0.068218999 -0.01149 -0.0215156, + -0.066978499 -0.0112767 -0.0266119, + -0.067583501 -0.0067777601 -0.026608299, + -0.066038199 -0.0066183698 -0.0316227, + -0.066334501 -0.0021925899 -0.031619199, + -0.064492702 -0.0021271601 -0.0365346, + -0.062367599 0.00211812 -0.041330799, + -0.059986901 0.00129237 -0.045999002, + -0.062367599 -0.0020522999 -0.0413341, + -0.0642047 -0.0064300201 -0.036538001, + -0.065447003 -0.0110144 -0.031626198, + -0.066074297 -0.0157251 -0.0266154, + -0.066076599 -0.0204801 -0.021522701, + -0.065454699 -0.0251964 -0.016365301, + -0.064219996 -0.0297924 -0.0111606, + -0.062394299 -0.0341883 -0.0059263501, + -0.060009498 -0.038308099 -0.00068030303, + -0.057106901 -0.042080302 0.0045597302, + -0.053736899 -0.045439601 0.0097759897, + -0.049957599 -0.0483271 0.0149507, + -0.0458344 -0.0506928 0.020066399, + -0.041438699 -0.0524945 0.0251057, + -0.036846701 -0.053700201 0.0300513, + -0.032138199 -0.054287799 0.034886699, + -0.027395399 -0.0542452 0.039595101, + -0.022701399 -0.0535716 0.044160798, + -0.0181388 -0.052276101 0.0485681, + -0.0137888 -0.050379101 0.0528019, + -0.0154543 -0.0463311 0.0568492, + -0.0116801 -0.047439199 0.056848299, + -0.0110631 -0.047620401 0.056848198, + -0.0109935 -0.04465 0.059951302, + -0.0103958 -0.051187702 0.0528013, + -0.0146092 -0.053371001 0.048567198, + -0.019074799 -0.054968301 0.044159599, + -0.023713199 -0.055954002 0.039593801, + -0.028442301 -0.056313202 0.034885101, + -0.033179201 -0.056041501 0.030049499, + -0.037841301 -0.0551451 0.025103601, + -0.0423472 -0.053640999 0.020064101, + -0.046618901 -0.051556099 0.0149482, + -0.050582401 -0.048927199 0.0097732097, + -0.054168999 -0.0458006 0.00455677, + -0.057316799 -0.0422308 -0.00068342697, + -0.059971198 -0.0382795 -0.0059296, + -0.062086102 -0.034015302 -0.011164, + -0.063624702 -0.029511999 -0.0163687, + -0.064560004 -0.0248478 -0.021526201, + -0.064874999 -0.020103199 -0.0266189, + -0.064563498 -0.015361 -0.0316296, + -0.063629903 -0.0107039 -0.036541399, + -0.0620891 -0.0062133102 -0.041337501, + -0.0597996 -0.0048635202 -0.0460039, + -0.059652399 -0.0059628799 -0.046004798, + -0.059120201 -0.0099372501 -0.046007901, + -0.0598877 -0.0019658101 -0.046001598, + -0.059932798 0.00203907 -0.045998398, + -0.0620891 0.00627913 -0.041327499, + -0.064492702 0.00218534 -0.036531199, + -0.061533201 0.0104123 -0.041324198, + -0.059542101 0.00743519 -0.045994099, + -0.0642047 0.0064881998 -0.036527701, + -0.066334501 0.00224295 -0.0316156, + -0.067886703 -0.00224847 -0.026604701, + -0.068835303 -0.0069078002 -0.021511899, + -0.0691645 -0.0116536 -0.016354499, + -0.068869203 -0.0164035 -0.01115, + -0.067954801 -0.0210751 -0.0059159002, + -0.066437602 -0.0255874 -0.00067017402, + -0.064343698 -0.029862201 0.0045694602, + -0.0617094 -0.033825502 0.0097852396, + -0.058580201 -0.037408099 0.0149594, + -0.055010099 -0.040547699 0.0200745, + -0.051060501 -0.043189101 0.0251131, + -0.046799898 -0.045285299 0.030058, + -0.042302102 -0.046799 0.0348926, + -0.037645102 -0.047702 0.039600302, + -0.032910202 -0.047977 0.044165201, + -0.028180299 -0.047616299 0.048571799, + -0.023538901 -0.046624001 0.052804898, + -0.022015801 -0.0436159 0.056851398, + -0.022671301 -0.043245599 0.0568517, + -0.036038801 -0.045671798 0.044167001, + -0.040745001 -0.045081198 0.039602399, + -0.045331601 -0.043869101 0.034894999, + -0.0497186 -0.0420583 0.0300606, + -0.053829901 -0.039682101 0.0251159, + -0.0575944 -0.036782999 0.0200775, + -0.060947198 -0.033411901 0.0149626, + -0.063830398 -0.029628299 0.0097885802, + -0.0661944 -0.0254979 0.0045729401, + -0.067998298 -0.0210928 -0.00066659501, + -0.069211103 -0.0164891 -0.0059122499, + -0.069811597 -0.0117669 -0.0111463, + -0.069789298 -0.0070078499 -0.0163508, + -0.0691441 -0.0022946401 -0.0215082, + -0.067886703 0.00229083 -0.0266011, + -0.066038199 0.0066687199 -0.031612098, + -0.063629903 0.0107621 -0.0365243, + -0.060702499 0.0144991 -0.041320998, + -0.05847 0.0134999 -0.045989301, + -0.058344599 0.0139398 -0.045988899, + -0.0596008 0.018521201 -0.041317798, + -0.062770903 0.0149882 -0.036520999, + -0.065447003 0.0110648 -0.0316086, + -0.067583501 0.0068201302 -0.0265975, + -0.0691441 0.0023288899 -0.0215046, + -0.070102401 -0.00233073 -0.016347099, + -0.0704422 -0.00707768 -0.0111425, + -0.070158198 -0.0118295 -0.00590854, + -0.0692553 -0.0165039 -0.00066294102, + -0.067749403 -0.021019701 0.0045765, + -0.065666303 -0.0252987 0.0097920299, + -0.063042 -0.029266501 0.0149659, + -0.0599216 -0.032853901 0.0200806, + -0.056358799 -0.035998099 0.0251188, + -0.052415099 -0.038643699 0.030063299, + -0.048158601 -0.040743399 0.034897499, + -0.043662999 -0.042259201 0.039604701, + -0.039006501 -0.043162599 0.044169001, + -0.034270301 -0.043435801 0.0485751, + -0.0323411 -0.036552701 0.056857001, + -0.035009298 -0.03875 0.052811202, + -0.030919099 -0.037857801 0.056855999, + -0.032345701 -0.041001901 0.052809399, + -0.030247601 -0.038345698 0.0568556, + -0.0275963 -0.0367718 0.059957501, + -0.0276068 -0.040264402 0.056854099, + -0.029299799 -0.0390343 0.056855001, + -0.037092399 -0.041049901 0.048576999, + -0.0418 -0.040461101 0.044171199, + -0.046386 -0.039248399 0.0396071, + -0.050770599 -0.0374359 0.034900099, + -0.054877602 -0.035056598 0.0300662, + -0.058635999 -0.032153402 0.025121899, + -0.061981101 -0.0287783 0.020083901, + -0.064855203 -0.0249904 0.0149693, + -0.067208901 -0.0208562 0.0097955596, + -0.069001801 -0.016447701 0.0045801401, + -0.070202999 -0.0118413 -0.00065922801, + -0.0707919 -0.0071169999 -0.00590479, + -0.070758201 -0.0023568501 -0.0111388, + -0.070102401 0.00235676 -0.016343299, + -0.068835303 0.0069420501 -0.0215009, + -0.066978499 0.0113191 -0.026593899, + -0.064563498 0.0154114 -0.031605098, + -0.061631601 0.0191474 -0.036517698, + -0.058232799 0.0224609 -0.041314598, + -0.056781799 0.019422799 -0.045984499, + -0.055921901 0.021573501 -0.0459828, + -0.054495402 0.0251415 -0.045979999, + -0.056604698 0.026300199 -0.041311599, + -0.060217001 0.0232212 -0.036514401, + -0.063391604 0.0196895 -0.031601701, + -0.066074297 0.0157675 -0.026590399, + -0.068218999 0.0115242 -0.021497199, + -0.069789298 0.0070338799 -0.0163396, + -0.070758201 0.0023745899 -0.011135, + -0.071109504 -0.0023727401 -0.0059010098, + -0.0708372 -0.00712582 -0.00065547298, + -0.069945998 -0.0118022 0.0045838398, + -0.0684513 -0.016320501 0.0097991796, + -0.066378698 -0.020602699 0.0149728, + -0.063763797 -0.024574099 0.020087199, + -0.060651399 -0.028165299 0.025125099, + -0.057094999 -0.031312902 0.0300692, + -0.053155798 -0.033961099 0.0349029, + -0.0489018 -0.036062699 0.0396096, + -0.044406801 -0.037578799 0.044173501, + -0.039748799 -0.0384808 0.048579101, + -0.042261399 -0.024446899 0.056866601, + -0.0457693 -0.025124401 0.052822001, + -0.041827898 -0.0252684 0.056866001, + -0.0439918 -0.0281255 0.052819598, + -0.0484928 -0.026613399 0.048588499, + -0.044856399 0.0434146 -0.041297901, + -0.044317201 0.040483899 -0.045967799, + -0.047653802 0.0403217 -0.041300401, + -0.049277499 0.041690599 -0.036499701, + -0.051950201 0.038306199 -0.036502399, + -0.053433701 0.039395399 -0.031585999, + -0.0559441 0.035738599 -0.031588901, + -0.057253201 0.036570299 -0.0265738, + -0.059566502 0.0326645 -0.026576901, + -0.060669798 0.033264998 -0.021479901, + -0.062755004 0.0291386 -0.0214832, + -0.063624702 0.029538 -0.0163217, + -0.065454699 0.0252224 -0.016325099, + -0.0660671 0.025454201 -0.0111166, + -0.0676191 0.020984599 -0.0111202, + -0.067954801 0.0210845 -0.0058823298, + -0.069211103 0.0164985 -0.0058859801, + -0.0692553 0.016504901 -0.000636657, + -0.070202999 0.0118423 -0.00064036902, + -0.069945998 0.0117948 0.0046026302, + -0.070577897 0.0070965602 0.00459889, + -0.070014901 0.0070357602 0.0098177698, + -0.070329003 0.00234351 0.0098140398, + -0.069460303 0.00231033 0.014991, + -0.068291403 -0.0022992101 0.020105001, + -0.069460303 -0.0023342001 0.0149873, + -0.067986399 -0.0068554902 0.0201013, + -0.066527799 -0.0067127701 0.0251422, + -0.065932199 -0.0111413 0.0251386, + -0.064199403 -0.0108531 0.0300855, + -0.063332699 -0.0151169 0.030082099, + -0.0613456 -0.0146472 0.0349182, + -0.0602322 -0.018712001 0.034915, + -0.058015201 -0.018028099 0.039624002, + -0.0566836 -0.0218629 0.039620899, + -0.054265 -0.020935001 0.0441867, + -0.052747902 -0.0245129 0.044183899, + -0.050159499 -0.023315201 0.0485911, + -0.047342401 -0.022011301 0.052824501, + -0.044096999 -0.020967901 0.056869399, + -0.051602099 -0.0199128 0.048593901, + -0.055539802 -0.0172638 0.044189699, + -0.059087601 -0.0141129 0.039627101, + -0.062185101 -0.0105172 0.034921501, + -0.064779297 -0.0065408102 0.0300889, + -0.066826299 -0.00225427 0.0251457, + -0.068291403 0.00226719 0.020108599, + -0.069150001 0.0069446 0.0149947, + -0.069388099 0.0116965 0.0098214904, + -0.069001801 0.0164403 0.0046063298, + -0.067998298 0.021093801 -0.00063300302, + -0.066395096 0.0255764 -0.00587876, + -0.064219996 0.0298102 -0.0111132, + -0.0615106 0.0337217 -0.016318399, + -0.058313601 0.037243102 -0.021476701, + -0.054684099 0.0403127 -0.026570801, + -0.050684799 0.042876501 -0.031583302, + -0.0463848 0.044888999 -0.036497202, + -0.041858599 0.0463138 -0.041295599, + -0.040233102 0.0445216 -0.045964599, + -0.043084402 0.041702598 -0.0459668, + -0.0457622 0.0387275 -0.045969199, + -0.04823 0.035727799 -0.045971598, + -0.050238401 0.037048802 -0.041303001, + -0.054390799 0.034750901 -0.0365052, + -0.058204498 0.031922199 -0.031592, + -0.061613798 0.028612999 -0.026580101, + -0.064560004 0.024882 -0.021486601, + -0.066992298 0.0207943 -0.016328599, + -0.068869203 0.016421299 -0.0111238, + -0.070158198 0.0118389 -0.00588969, + -0.0708372 0.0071268501 -0.000644124, + -0.070894502 0.0023665801 0.0045951302, + -0.070329003 -0.00235913 0.0098102903, + -0.069150001 -0.0069684698 0.0149837, + -0.067377701 -0.0113812 0.020097701, + -0.065042198 -0.0155204 0.0251351, + -0.062183201 -0.019313401 0.0300787, + -0.0588497 -0.022693301 0.0349118, + -0.055098802 -0.025600201 0.0396179, + -0.0509951 -0.0279814 0.044181101, + -0.046609499 -0.0297931 0.048586, + -0.040132798 -0.0277474 0.056864001, + -0.039282501 -0.028991001 0.056862999, + -0.037805501 -0.026143 0.059966002, + -0.042017799 -0.0310011 0.0528173, + -0.044518001 -0.032839801 0.048583601, + -0.039856199 -0.033738401 0.052815098, + -0.049014699 -0.031325001 0.044178501, + -0.053268 -0.029223301 0.039615002, + -0.057204399 -0.0265735 0.034908801, + -0.060755901 -0.0234237 0.0300755, + -0.063861601 -0.0198301 0.025131701, + -0.066468097 -0.015856201 0.020094199, + -0.068530999 -0.0115716 0.01498, + -0.070014901 -0.0070513901 0.0098065604, + -0.070894502 -0.0023739 0.00459135, + -0.071154997 0.0023795499 -0.000647904, + -0.0707919 0.00712639 -0.0058934502, + -0.069811597 0.0117847 -0.0111275, + -0.0682308 0.016273299 -0.0163322, + -0.066076599 0.0205143 -0.021490101, + -0.063386001 0.024433799 -0.0265835, + -0.060205001 0.027963299 -0.0315951, + -0.056588501 0.031040501 -0.036508199, + -0.052598599 0.0336105 -0.041305698, + -0.048299 0.035623901 -0.045971598, + -0.050515398 0.0322829 -0.045974299, + -0.051634699 0.030595699 -0.0459757, + -0.054723799 0.0300224 -0.0413086, + -0.0585334 0.027191499 -0.036511298, + -0.061936598 0.023879699 -0.0315984, + -0.064874999 0.020145601 -0.0265869, + -0.067298099 0.0160551 -0.021493601, + -0.0691645 0.0116796 -0.016335901, + -0.0704422 0.0070954198 -0.0111313, + -0.071109504 0.0023821399 -0.0058972202, + -0.071154997 -0.0023785101 -0.00065169297, + -0.070577897 -0.0071038799 0.00458758, + -0.069388099 -0.0117121 0.00980285, + -0.067605801 -0.0161232 0.0149764, + -0.065261699 -0.020260399 0.020090699, + -0.0623958 -0.024051299 0.0251284, + -0.059057299 -0.027429501 0.0300723, + -0.0553036 -0.0303351 0.034905799, + -0.051199298 -0.032715902 0.039612301, + -0.046815298 -0.034529001 0.044175901, + -0.0422277 -0.035739999 0.048581298, + -0.037516501 -0.036325201 0.052813102, + -0.035215002 -0.033870898 0.056859098, + -0.0351055 -0.0339972 0.056859002, + -0.035027899 -0.034086801 0.056859002, + -0.054418098 0.0252888 -0.045979898, + -0.052555799 0.028839501 -0.045977101, + -0.048244301 -0.035508901 -0.046028301, + -0.050238401 -0.036982998 -0.041361999, + -0.0496815 -0.033604901 -0.0460268, + -0.045971099 -0.038520701 -0.0460307, + -0.049277499 -0.041632399 -0.036566101, + -0.047709402 -0.046115801 -0.031654101, + -0.0455628 -0.0503553 -0.026643001, + -0.042876001 -0.054277498 -0.021549599, + -0.039696399 -0.057814602 -0.016391199, + -0.036079701 -0.060905699 -0.0111854, + -0.032088999 -0.063497402 -0.0059496802, + -0.0277937 -0.065544903 -0.00070199103, + -0.0232682 -0.067012899 0.00453988, + -0.018591 -0.067875803 0.0097581204, + -0.0138432 -0.068118297 0.014935, + -0.0091074398 -0.067735799 0.020052901, + -0.004466 -0.066734202 0.025094399, + 0 -0.065130197 0.030042199, + 0.0042121802 -0.062950499 0.0348798, + 0.0080961604 -0.060231801 0.0395904, + 0.0115828 -0.057020601 0.044158, + 0.0146092 -0.053371001 0.048567198, + 0.017120101 -0.049345799 0.052802701, + 0.016016001 -0.046165999 0.056849401, + 0.0154543 -0.0463311 0.0568492, + -0.050521001 -0.032216601 -0.046025701, + -0.052595802 -0.028785501 -0.046022899, + -0.054723799 -0.0299566 -0.0413564, + -0.056588501 -0.030982301 -0.0365576, + -0.056604698 -0.0262344 -0.041353401, + -0.0559441 -0.035688199 -0.031645801, + -0.054684099 -0.040270299 -0.026635, + -0.052831501 -0.044649199 -0.021542, + -0.050419401 -0.048748799 -0.016384, + -0.047490101 -0.0524984 -0.0111787, + -0.0440947 -0.055833202 -0.0059435801, + -0.040292501 -0.058695398 -0.00069653703, + -0.0361492 -0.061035499 0.00454464, + -0.031736799 -0.062812902 0.0097621595, + -0.027131701 -0.0639963 0.0149382, + -0.0224138 -0.064564802 0.0200554, + -0.017665099 -0.064507902 0.0250961, + -0.0129683 -0.063825503 0.0300433, + -0.0084055504 -0.0625287 0.034880102, + -0.0040571401 -0.0606382 0.039590001, + 0 -0.058185801 0.044157099, + 0.00369344 -0.0552123 0.048565701, + 0.00348601 -0.052117102 0.052800499, + 0.0055678501 -0.0485714 0.056847401, + 0.0039265598 -0.048665199 0.056847401, + 0.00650266 -0.0484096 0.056847598, + 0.0102507 -0.041638698 0.062857702, + 0.012523 -0.037563201 0.0655559, + 0.0141461 -0.0332563 0.068033703, + 0.0150941 -0.028815299 0.0702805, + 0.0153554 -0.024340199 0.072286397, + 0.0149334 -0.0199317 0.074043103, + 0.0138458 -0.0156889 0.075542703, + 0.0121248 -0.0117071 0.076778904, + 0.0098159797 -0.0080764396 0.077746399, + 0.00697758 -0.0048787398 0.0784408, + 0.00367912 -0.0021869401 0.078859299, + 0.00383811 -0.00188396 0.078859501, + 0.0076598101 -0.0036971001 0.078441799, + 0.00397221 -0.00156927 0.078859799, + 0.0109935 -0.04465 0.059951302, + 0.0128843 -0.047085602 0.056848601, + 0.0145468 -0.043620799 0.059952099, + 0.0135639 -0.040679 0.062858403, + 0.0167892 -0.039455701 0.062859401, + 0.0155008 -0.036433902 0.065556802, + 0.018378099 -0.035068698 0.065557897, + 0.0167719 -0.032010399 0.068034701, + 0.019288899 -0.030557301 0.068035901, + 0.0173593 -0.027507501 0.070281498, + 0.019511901 -0.0260217 0.070282698, + 0.017259501 -0.0230259 0.0722875, + 0.0190518 -0.021562601 0.072288699, + 0.016484 -0.018665601 0.074044101, + 0.017927799 -0.0172788 0.074045204, + 0.0150585 -0.0145241 0.075543597, + 0.016173501 -0.0132654 0.0755447, + 0.0130226 -0.0106937 0.076779701, + 0.0104291 -0.00726052 0.077747002, + 0.0138359 -0.0096114296 0.076780602, + 0.0109745 -0.0063980902 0.077747703, + 0.0073425001 -0.0043016002 0.078441299, + 0.0110631 -0.047620401 0.056848198, + 0.0116801 -0.047439199 0.056848299, + 0.019905601 -0.037977099 0.062860601, + 0.021136099 -0.033476301 0.065559201, + 0.021680901 -0.028906301 0.068037197, + 0.021538001 -0.0243674 0.070284002, + 0.0207204 -0.0199598 0.072289899, + 0.019255299 -0.0157804 0.074046403, + 0.0171836 -0.0119212 0.075545698, + 0.0145595 -0.0084671499 0.076781496, + 0.0114487 -0.0054944102 0.077748403, + 0.0079274299 -0.00306893 0.078442298, + 0.0040805498 -0.00124468 0.07886, + 0.0081436504 -0.00242135 0.078442797, + 0.0041624201 -0.00091252598 0.078860298, + 0.0118488 -0.0045555602 0.0777492, + 0.0151887 -0.00726829 0.076782398, + 0.0180823 -0.0105 0.075546898, + 0.020457899 -0.0141801 0.074047603, + 0.0222547 -0.018228 0.0722913, + 0.0234244 -0.0225555 0.070285499, + 0.0239322 -0.027068 0.068038702, + 0.0237571 -0.031667199 0.065560602, + 0.0228929 -0.036252402 0.062861897, + 0.021348 -0.0407231 0.059954401, + 0.022015801 -0.0436159 0.056851398, + 0.024857899 -0.0420109 0.056852698, + 0.0257317 -0.034292798 0.062863499, + 0.026224 -0.029653 0.065562204, + 0.0260283 -0.025054701 0.068040296, + 0.025158901 -0.020597599 0.070286997, + 0.0236446 -0.0163783 0.072292797, + 0.021527801 -0.0124881 0.074049003, + 0.018863801 -0.0090110898 0.075548001, + 0.015719401 -0.0060226899 0.076783396, + 0.0121719 -0.00358754 0.077749997, + 0.00830705 -0.00175838 0.078443304, + 0.0042173001 -0.00057487999 0.078860603, + 0.0042173001 0.00044928899 0.0788614, + 0.0084165698 0.00095950498 0.078445502, + 0.0041624201 0.00078693498 0.078861602, + 0.035583101 -0.0291005 0.059963599, + 0.033129901 -0.031869601 0.059961401, + 0.037242699 -0.031530902 0.056860998, + 0.033178799 -0.0271398 0.062869199, + 0.0352511 -0.0243821 0.062871397, + 0.032545902 -0.022516999 0.065567903, + 0.034247998 -0.0198253 0.065569997, + 0.031254999 -0.0180992 0.068045802, + 0.0326056 -0.0155258 0.068047903, + 0.029343801 -0.0139798 0.070292301, + 0.030369001 -0.0115735 0.070294201, + 0.0268634 -0.0102455 0.0722977, + 0.027596001 -0.0080508599 0.072299398, + 0.023876701 -0.00697499 0.074053399, + 0.024355801 -0.0050312602 0.074054897, + 0.0204577 -0.0042366702 0.0755518, + 0.0207274 -0.0025768799 0.075553201, + 0.016689301 -0.0020876301 0.0767866, + 0.016798301 -0.00073814701 0.076787598, + 0.012662 -0.00057216699 0.077752396, + 0.0084715104 0.000278967 0.078444898, + 0.012662 0.00044834099 0.077753201, + 0.00424483 0.000108225 0.078861102, + 0.0084715104 -0.00040389501 0.078444399, + 0.0125799 -0.00158938 0.077751599, + 0.0164722 -0.0034239299 0.076785497, + 0.0200553 -0.00586924 0.075550497, + 0.0232428 -0.0088737896 0.074051902, + 0.0259565 -0.0123741 0.072296001, + 0.028128199 -0.016295901 0.070290402, + 0.0297016 -0.0205558 0.068043903, + 0.030632701 -0.025063099 0.065565899, + 0.0308914 -0.0297217 0.062867098, + 0.0304619 -0.034432199 0.0599594, + 0.0327111 -0.0362131 0.056857299, + 0.0275963 -0.0367718 0.059957501, + 0.030919099 -0.037857801 0.056855999, + 0.028403699 -0.032111298 0.062865198, + 0.0285208 -0.0274469 0.065563999, + 0.027955599 -0.022879301 0.068042003, + 0.026730301 -0.0185066 0.070288703, + 0.024881201 -0.0144228 0.072294302, + 0.022458101 -0.0107155 0.074050397, + 0.019522799 -0.00746421 0.075549297, + 0.0161481 -0.0047385101 0.076784402, + 0.0124161 -0.0025967001 0.077750698, + 0.0084165698 -0.00108443 0.0784439, + 0.00424483 -0.000233817 0.078860797, + 0.0276068 -0.040264402 0.056854099, + 0.0323411 -0.036552701 0.056857001, + 0.0351055 -0.0339972 0.056859002, + 0.035728101 -0.0170053 0.065572299, + 0.033744901 -0.0128519 0.068049997, + 0.0311973 -0.0090923598 0.070296198, + 0.0281497 -0.0058044 0.072301202, + 0.0246769 -0.0030553101 0.074056499, + 0.020862799 -0.00090086099 0.075554498, + 0.016798301 0.00061585702 0.076788701, + 0.0125799 0.0014655601 0.077753998, + 0.00830705 0.0016334601 0.078446001, + 0.0040805498 0.00111908 0.0788619, + 0.0081436504 0.0022964301 0.0784465, + 0.00397221 0.00144367 0.078862198, + 0.0124161 0.0024728801 0.077754803, + 0.016689301 0.00196534 0.076789796, + 0.020862799 0.000780534 0.075555801, + 0.024838001 -0.00105995 0.074058101, + 0.028520901 -0.00352058 0.072302997, + 0.0318233 -0.0065528098 0.070298202, + 0.034665201 -0.0100951 0.068052202, + 0.036976401 -0.0140755 0.065574601, + 0.038697701 -0.0184124 0.062876202, + 0.042261399 -0.024446899 0.056866601, + 0.042769101 -0.0234848 0.056867398, + 0.041501898 -0.019740701 0.059971102, + 0.040049799 -0.0152389 0.062878698, + 0.0379849 -0.0110546 0.065577, + 0.035360798 -0.0072731799 0.0680544, + 0.032242902 -0.0039710202 0.070300303, + 0.0287071 -0.00121444 0.072304897, + 0.024838001 0.00094200799 0.074059702, + 0.0207274 0.00245656 0.075557202, + 0.0164722 0.00330164 0.076790802, + 0.0121719 0.00346372 0.0777556, + 0.0079274299 0.0029440001 0.078447104, + 0.00383811 0.00175837 0.078862399, + 0.019665999 0.0566766 -0.045954902, + 0.0198282 0.057036102 -0.0453141, + 0.023406001 0.0552308 -0.045956001, + 0.018735001 0.057036601 -0.0459546, + 0.0197927 0.057036102 -0.045334902, + 0.0217772 0.0570351 -0.044057, + 0.023659701 0.057034001 -0.042692099, + 0.030822501 0.057028499 -0.035815999, + 0.0328849 0.0555497 -0.036488701, + 0.0305063 0.0570288 -0.036189001, + 0.032369301 0.057027001 -0.033872601, + 0.0596008 0.018521201 -0.041317798, + 0.056781799 0.019422799 -0.045984499, + 0.058232799 0.0224609 -0.041314598, + 0.060217001 0.0232212 -0.036514401, + 0.0585334 0.027191499 -0.036511298, + 0.060205001 0.027963299 -0.0315951, + 0.058204498 0.031922199 -0.031592, + 0.059566502 0.0326645 -0.026576901, + 0.057253201 0.036570299 -0.0265738, + 0.058313601 0.037243102 -0.021476701, + 0.055696901 0.041054901 -0.0214737, + 0.0564688 0.041619599 -0.0163121, + 0.053563699 0.045298301 -0.016309099, + 0.0540649 0.045717798 -0.0111005, + 0.050891101 0.049226999 -0.0110977, + 0.051143799 0.049467102 -0.0058597298, + 0.0477258 0.0527726 -0.0058570998, + 0.0477564 0.052802298 -0.00060775399, + 0.044122901 0.055874199 -0.00060530799, + 0.043961398 0.0556654 0.0046375701, + 0.042580601 0.056999199 0.00097616302, + 0.042349 0.056997199 0.00360044, + 0.037665099 0.056984 0.020150499, + 0.038670901 0.056317698 0.0201516, + 0.038279202 0.056984998 0.018834701, + 0.037188001 0.056983199 0.0211726, + 0.023751199 0.05697 0.037723199, + 0.022786399 0.0569694 0.038446002, + 0.023713199 0.055890899 0.039682802, + 0.047653802 -0.0402559 -0.041364599, + 0.045971099 -0.038520701 -0.0460307, + 0.050238401 -0.036982998 -0.041361999, + 0.051950201 -0.038247999 -0.0365634, + 0.054390799 -0.034692701 -0.036560498, + 0.0559441 -0.035688199 -0.031645801, + 0.058204498 -0.031871799 -0.031642798, + 0.059566502 -0.032622099 -0.0266289, + 0.061613798 -0.0285706 -0.0266257, + 0.062755004 -0.0291044 -0.0215296, + 0.064560004 -0.0248478 -0.021526201, + 0.065454699 -0.0251964 -0.016365301, + 0.066992298 -0.0207683 -0.0163617, + 0.0676191 -0.0209668 -0.0111536, + 0.068869203 -0.0164035 -0.01115, + 0.069211103 -0.0164891 -0.0059122499, + 0.070158198 -0.0118295 -0.00590854, + 0.070202999 -0.0118413 -0.00065922801, + 0.0708372 -0.00712582 -0.00065547298, + 0.070577897 -0.0071038799 0.00458758, + 0.070894502 -0.0023739 0.00459135, + 0.070329003 -0.00235913 0.0098102903, + 0.069460303 0.00231033 0.014991, + 0.070329003 0.00234351 0.0098140398, + 0.069150001 0.0069446 0.0149947, + 0.067986399 0.0068234699 0.0201122, + 0.067377701 0.0113492 0.0201158, + 0.065932199 0.0111013 0.025156301, + 0.065042198 0.0154804 0.0251598, + 0.063332699 0.0150689 0.030106099, + 0.062183201 0.0192654 0.0301094, + 0.0602322 0.018656399 0.034944799, + 0.0588497 0.022637701 0.034947898, + 0.0566836 0.0217997 0.0396557, + 0.055098802 0.025536999 0.039658599, + 0.052747902 0.0244425 0.044222899, + 0.0509951 0.027911 0.0442256, + 0.0484928 0.026536001 0.0486308, + 0.046609499 0.0297157 0.0486334, + 0.0439918 0.028041299 0.052864298, + 0.042017799 0.030916899 0.0528666, + 0.048439 0.0058380002 0.056890801, + 0.051929399 0.0051820399 0.0528461, + 0.048347302 0.0069059902 0.056891602, + 0.051464502 0.0086389501 0.052848902, + 0.0550193 0.0054963198 0.0486141, + 0.047779299 0.00970909 0.056893799, + 0.047463499 0.0112676 0.0568951, + 0.0450087 0.0091408296 0.059994102, + 0.050769702 0.0120569 0.052851599, + 0.054526798 0.0091588004 0.048617002, + 0.057858501 0.0057854801 0.044208001, + 0.058118101 0.00190792 0.044204898, + 0.0607084 0.0019981 0.039639901, + 0.063028298 -0.0021351101 0.034928199, + 0.0607084 -0.0020612199 0.039636701, + 0.0627468 -0.0063401898 0.034924898, + 0.064779297 -0.0065408102 0.0300889, + 0.064199403 -0.0108531 0.0300855, + 0.065932199 -0.0111413 0.0251386, + 0.065042198 -0.0155204 0.0251351, + 0.066468097 -0.015856201 0.020094199, + 0.065261699 -0.020260399 0.020090699, + 0.066378698 -0.020602699 0.0149728, + 0.064855203 -0.0249904 0.0149693, + 0.065666303 -0.0252987 0.0097920299, + 0.063830398 -0.029628299 0.0097885802, + 0.064343698 -0.029862201 0.0045694602, + 0.062205698 -0.034093201 0.0045660902, + 0.0624342 -0.034214299 -0.00067704299, + 0.060009498 -0.038308099 -0.00068030303, + 0.059971198 -0.0382795 -0.0059296, + 0.057280101 -0.0421996 -0.0059327199, + 0.056997199 -0.041986901 -0.0111703, + 0.0540649 -0.045700099 -0.0111733, + 0.053563699 -0.045272298 -0.016381299, + 0.050419401 -0.048748799 -0.016384, + 0.0497302 -0.048078202 -0.0215447, + 0.046406701 -0.051292501 -0.0215472, + 0.0455628 -0.0503553 -0.026643001, + 0.042096298 -0.053286102 -0.026645301, + 0.041133799 -0.052063201 -0.031658899, + 0.037562799 -0.054694299 -0.031661, + 0.0365199 -0.053171098 -0.036575299, + 0.0328849 -0.0554915 -0.036577102, + 0.031801298 -0.053658299 -0.041375201, + 0.028144101 -0.055662502 -0.041376799, + 0.027052401 -0.0534999 -0.046042599, + 0.030544801 -0.051530398 -0.046041001, + 0.032115102 -0.050644901 -0.0460403, + 0.035316501 -0.051414199 -0.041373499, + 0.039991699 -0.050613001 -0.036573201, + 0.044521 -0.049199399 -0.031656601, + 0.0488258 -0.047199499 -0.026640501, + 0.052831501 -0.044649199 -0.021542, + 0.0564688 -0.0415936 -0.0163783, + 0.0596749 -0.038086198 -0.0111672, + 0.062394299 -0.0341883 -0.0059263501, + 0.064580098 -0.0299679 -0.000673662, + 0.0661944 -0.0254979 0.0045729401, + 0.067208901 -0.0208562 0.0097955596, + 0.067605801 -0.0161232 0.0149764, + 0.067377701 -0.0113812 0.020097701, + 0.066527799 -0.0067127701 0.0251422, + 0.065069899 -0.0021995001 0.0300924, + 0.063028298 0.0020794901 0.0349316, + 0.060437299 0.0060485099 0.039643101, + 0.0573406 0.0096369199 0.044211101, + 0.0537907 0.0127803 0.0486199, + 0.049848199 0.0154209 0.0528543, + 0.045571301 0.0175067 0.056900099, + 0.045648798 0.017268199 0.056899901, + 0.048704099 0.018716 0.0528569, + 0.052814402 0.016344501 0.048622701, + 0.056566499 0.0134453 0.0442141, + 0.059896201 0.0100717 0.039646301, + 0.0627468 0.0062845601 0.034934901, + 0.065069899 0.0021515801 0.030095801, + 0.066826299 -0.00225427 0.0251457, + 0.067986399 -0.0068554902 0.0201013, + 0.068530999 -0.0115716 0.01498, + 0.0684513 -0.016320501 0.0097991796, + 0.067749403 -0.021019701 0.0045765, + 0.066437602 -0.0255874 -0.00067017402, + 0.064538799 -0.0299445 -0.0059229699, + 0.062086102 -0.034015302 -0.011164, + 0.059121698 -0.037728898 -0.016375201, + 0.055696901 -0.041020699 -0.0215391, + 0.051870801 -0.043832801 -0.0266378, + 0.047709402 -0.046115801 -0.031654101, + 0.0432849 -0.047828801 -0.036571, + 0.0386739 -0.048940498 -0.041371498, + 0.037141401 -0.047085699 -0.046037499, + 0.033914801 -0.049370501 -0.046039298, + 0.023392901 -0.055132501 -0.046043899, + 0.024361299 -0.057417899 -0.0413782, + 0.021104001 -0.0561294 -0.0460447, + 0.026750499 -0.053670101 -0.0460428, + 0.0291031 -0.057564002 -0.036578801, + 0.033824001 -0.057080999 -0.0316629, + 0.038441699 -0.055978701 -0.026647501, + 0.042876001 -0.054277498 -0.021549599, + 0.047049899 -0.052007601 -0.0163866, + 0.050891101 -0.0492092 -0.0111761, + 0.054333299 -0.045931201 -0.0059357001, + 0.057316799 -0.0422308 -0.00068342697, + 0.059789799 -0.0381721 0.0045628501, + 0.0617094 -0.033825502 0.0097852396, + 0.063042 -0.029266501 0.0149659, + 0.063763797 -0.024574099 0.020087199, + 0.063861601 -0.0198301 0.025131701, + 0.063332699 -0.0151169 0.030082099, + 0.062185101 -0.0105172 0.034921501, + 0.060437299 -0.00611164 0.039633401, + 0.058118101 -0.0019783201 0.044201799, + 0.055266201 0.00180907 0.048611201, + 0.052162301 0.00170194 0.052843399, + 0.048775598 0.00191893 0.056887601, + 0.055266201 -0.00188649 0.048608199, + 0.057858501 -0.0058558802 0.044198699, + 0.059896201 -0.0101349 0.039630201, + 0.0613456 -0.0146472 0.0349182, + 0.062183201 -0.019313401 0.0300787, + 0.0623958 -0.024051299 0.0251284, + 0.061981101 -0.0287783 0.020083901, + 0.060947198 -0.033411901 0.0149626, + 0.059312899 -0.0378717 0.00978202, + 0.057106901 -0.042080302 0.0045597302, + 0.054368 -0.0459648 -0.00068639999, + 0.051143799 -0.049457699 -0.0059385002, + 0.047490101 -0.0524984 -0.0111787, + 0.0434702 -0.055034 -0.016388999, + 0.039153799 -0.057020001 -0.021551801, + 0.034615502 -0.058421299 -0.026649401, + 0.0299342 -0.0592127 -0.031664599, + 0.0251913 -0.059379201 -0.036580201, + 0.0204696 -0.0589168 -0.0413794, + 0.019663701 -0.0565877 -0.046045098, + 0.015842799 -0.057803601 -0.046046, + 0.016486401 -0.0601524 -0.041380402, + 0.021167001 -0.060929202 -0.036581401, + 0.0259107 -0.0610798 -0.031665999, + 0.030634699 -0.060602799 -0.0266512, + 0.035256699 -0.059507798 -0.0215538, + 0.039696399 -0.057814602 -0.016391199, + 0.043876901 -0.055553101 -0.0111811, + 0.0477258 -0.052763201 -0.00594114, + 0.0511765 -0.049493499 -0.00068921002, + 0.054168999 -0.0458006 0.00455677, + 0.056651399 -0.0417489 0.0097789299, + 0.058580201 -0.037408099 0.0149594, + 0.0599216 -0.032853901 0.0200806, + 0.060651399 -0.028165299 0.025125099, + 0.060755901 -0.0234237 0.0300755, + 0.0602322 -0.018712001 0.034915, + 0.059087601 -0.0141129 0.039627101, + 0.0573406 -0.0097073196 0.0441957, + 0.0550193 -0.00557373 0.0486053, + 0.052162301 -0.0017861 0.052840602, + 0.0488245 0.00134948 0.056887198, + 0.0487286 -0.0020099001 0.056884501, + 0.045899801 -0.0018975 0.059985299, + 0.0486653 -0.0042251102 0.056882799, + 0.0487381 -0.00167518 0.056884799, + 0.048563998 -0.0049293302 0.056882199, + 0.0484211 -0.0059232302 0.056881402, + 0.051929399 -0.0052661998 0.0528378, + 0.054526798 -0.00923621 0.048602398, + 0.056566499 -0.0135157 0.044192601, + 0.058015201 -0.018028099 0.039624002, + 0.0588497 -0.022693301 0.0349118, + 0.059057299 -0.027429501 0.0300723, + 0.058635999 -0.032153402 0.025121899, + 0.0575944 -0.036782999 0.0200775, + 0.055951599 -0.041237399 0.0149564, + 0.053736899 -0.045439601 0.0097759897, + 0.050989099 -0.049316499 0.0045539699, + 0.0477564 -0.0528013 -0.00069184398, + 0.0440947 -0.055833202 -0.0059435801, + 0.040067799 -0.058359802 -0.0111834, + 0.0357453 -0.060336899 -0.0163932, + 0.0312021 -0.061729699 -0.021555601, + 0.026517 -0.062513597 -0.026652699, + 0.0217715 -0.062673897 -0.0316673, + 0.017048201 -0.062206902 -0.036582399, + 0.0124297 -0.061119098 -0.041381199, + 0.0128532 -0.063206598 -0.0365832, + 0.0175351 -0.063988097 -0.031668399, + 0.022281 -0.064145103 -0.026653999, + 0.0270082 -0.063676 -0.0215571, + 0.031634498 -0.062589698 -0.016395001, + 0.036079701 -0.060905699 -0.0111854, + 0.0402667 -0.058653701 -0.0059458301, + 0.044122901 -0.0558732 -0.00069428998, + 0.047581501 -0.052611999 0.0045513501, + 0.050582401 -0.048927199 0.0097732097, + 0.053073101 -0.044882402 0.0149535, + 0.055010099 -0.040547699 0.0200745, + 0.056358799 -0.035998099 0.0251188, + 0.057094999 -0.031312902 0.0300692, + 0.057204399 -0.0265735 0.034908801, + 0.0566836 -0.0218629 0.039620899, + 0.055539802 -0.0172638 0.044189699, + 0.0537907 -0.0128577 0.0485995, + 0.051464502 -0.0087230997 0.052835099, + 0.00367912 0.00206135 0.078862697, + 0.0073425001 0.0041766702 0.078447998, + 0.0034962599 0.0023505299 0.078862898, + 0.0450087 -0.00923636 0.059979498, + 0.0441234 -0.0128283 0.0599766, + 0.047449399 -0.0113515 0.056877099, + 0.041967601 -0.0086178305 0.062884003, + 0.042520899 -0.0052130399 0.0628867, + 0.039257899 -0.0048189401 0.065582, + 0.039514199 -0.00164463 0.065584503, + 0.036060899 -0.00150744 0.068058997, + 0.032453399 0.00125188 0.070304401, + 0.036060899 0.00139905 0.0680613, + 0.032242902 0.0038590599 0.070306502, + 0.028520901 0.0034054299 0.072308503, + 0.0281497 0.0056892498 0.072310403, + 0.024355801 0.0049133198 0.074062802, + 0.023876701 0.0068570501 0.074064396, + 0.0200553 0.0057489099 0.075559802, + 0.019522799 0.0073438799 0.075561099, + 0.015719401 0.0059004002 0.076792903, + 0.0151887 0.0071459999 0.076793902, + 0.0114487 0.0053705801 0.077757098, + 0.0109745 0.0062742601 0.077757798, + 0.00697758 0.0047538099 0.078448497, + 0.0032907401 0.0026239699 0.078863099, + 0.0065673999 0.0052995901 0.078448899, + 0.0030638699 0.0028800699 0.0788633, + 0.0104291 0.00713669 0.077758498, + 0.0145595 0.0083448598 0.0767949, + 0.018863801 0.0088907601 0.075562298, + 0.0232428 0.0087558497 0.074065901, + 0.027596001 0.0079357103 0.072312102, + 0.0318233 0.00644085 0.070308499, + 0.035827 0.0042960201 0.068063602, + 0.042798501 -0.00177481 0.062889397, + 0.045602102 -0.00558487 0.0599824, + 0.048099499 -0.0081602801 0.056879599, + 0.047871601 -0.0097453604 0.056878399, + 0.039514199 0.0015401799 0.065586999, + 0.042798501 0.00167465 0.062892199, + 0.039257899 0.0047144899 0.065589599, + 0.035360798 0.0071647898 0.068065897, + 0.0311973 0.0089803999 0.0703106, + 0.0268634 0.0101303 0.072313897, + 0.022458101 0.0105975 0.074067399, + 0.0180823 0.0103796 0.075563498, + 0.0138359 0.0094891395 0.076795802, + 0.0098159797 0.00795261 0.077759102, + 0.0061146398 0.0058106999 0.078449301, + 0.0028171299 0.0031171299 0.078863502, + 0.00255212 0.0033334401 0.078863703, + 0.0050933301 0.0067154798 0.078450099, + 0.00227056 0.0035277801 0.0788638, + 0.045602102 0.0054893401 0.0599912, + 0.045899801 0.0018019601 0.059988301, + 0.048525002 0.00483739 0.05689, + 0.042520899 0.0051128799 0.062894903, + 0.041967601 0.0085176704 0.0628976, + 0.038747001 0.0078580501 0.065592103, + 0.0379849 0.0109502 0.065594502, + 0.034665201 0.0099866996 0.068068199, + 0.033744901 0.0127435 0.068070397, + 0.030369001 0.0114615 0.0703125, + 0.029343801 0.0138678 0.070314497, + 0.0259565 0.0122589 0.072315603, + 0.024881201 0.0143076 0.072317198, + 0.021527801 0.0123701 0.0740688, + 0.020457899 0.0140621 0.074070103, + 0.0171836 0.0118008 0.075564601, + 0.016173501 0.013145 0.075565703, + 0.0130226 0.0105715 0.076796599, + 0.0121248 0.0115849 0.076797403, + 0.00913925 0.0087163998 0.077759802, + 0.00840325 0.0094234301 0.077760302, + 0.00562221 0.00628372 0.078449696, + 0.048804201 0.0015856799 0.056887399, + 0.0481118 0.0080683501 0.056892499, + 0.041142099 0.0118669 0.062900297, + 0.036976401 0.0139711 0.065596901, + 0.0326056 0.0154174 0.068072498, + 0.028128199 0.0161839 0.0703163, + 0.0236446 0.016263099 0.0723188, + 0.019255299 0.0156624 0.0740714, + 0.0150585 0.0144037 0.075566702, + 0.0111484 0.0125228 0.076798201, + 0.0076127499 0.0100688 0.077760801, + 0.0045314101 0.0071034199 0.078450397, + 0.00197427 0.0036989199 0.078864001, + 0.00166518 0.0038455301 0.078864098, + 0.00332325 0.0077374601 0.078450903, + 0.00134529 0.00396686 0.078864202, + 0.00268483 0.0079796398 0.078451097, + 0.00101668 0.0040620798 0.078864299, + 0.0049671 0.0115963 0.077762097, + 0.0058890898 0.0111588 0.077761702, + 0.0078128902 0.014825 0.076800004, + 0.00898539 0.014148 0.076799497, + 0.0111595 0.017587099 0.075569198, + 0.0125433 0.016631899 0.075568497, + 0.0149334 0.0198137 0.0740747, + 0.016484 0.0185476 0.074073702, + 0.0190518 0.0214474 0.072322898, + 0.0207204 0.019844601 0.072321601, + 0.0234244 0.022443499 0.070321299, + 0.025158901 0.0204856 0.070319697, + 0.027955599 0.0227709 0.068078399, + 0.0297016 0.020447399 0.068076499, + 0.032545902 0.0224126 0.065603703, + 0.034247998 0.019720901 0.065601498, + 0.037094701 0.021366499 0.0629078, + 0.038697701 0.018312201 0.062905401, + 0.041501898 0.0196451 0.060002498, + 0.044856399 -0.0433488 -0.041367002, + 0.041858599 -0.046248 -0.0413693, + 0.041776299 -0.043030102 -0.046034299, + 0.0463848 -0.044830799 -0.036568601, + 0.049277499 -0.041632399 -0.036566101, + 0.050684799 -0.042826101 -0.031651501, + 0.053433701 -0.039345 -0.031648699, + 0.054684099 -0.040270299 -0.026635, + 0.057253201 -0.036527898 -0.026632, + 0.058313601 -0.0372089 -0.021536, + 0.060669798 -0.0332308 -0.021532901, + 0.0615106 -0.033695702 -0.016372001, + 0.063624702 -0.029511999 -0.0163687, + 0.064219996 -0.0297924 -0.0111606, + 0.0660671 -0.0254364 -0.0111572, + 0.066395096 -0.025567001 -0.0059194802, + 0.067954801 -0.0210751 -0.0059159002, + 0.067998298 -0.0210928 -0.00066659501, + 0.0692553 -0.0165039 -0.00066294102, + 0.069001801 -0.016447701 0.0045801401, + 0.069945998 -0.0118022 0.0045838398, + 0.069388099 -0.0117121 0.00980285, + 0.070014901 -0.0070513901 0.0098065604, + 0.069150001 -0.0069684698 0.0149837, + 0.069460303 -0.0023342001 0.0149873, + 0.068291403 -0.0022992101 0.020105001, + 0.066826299 0.0022142199 0.025149301, + 0.068291403 0.00226719 0.020108599, + 0.066527799 0.00667272 0.025152801, + 0.064779297 0.0064928802 0.030099301, + 0.064199403 0.0108051 0.0301027, + 0.062185101 0.0104616 0.034938201, + 0.0613456 0.0145916 0.034941498, + 0.059087601 0.0140497 0.039649501, + 0.058015201 0.0179649 0.039652601, + 0.055539802 0.017193399 0.044217099, + 0.054265 0.0208646 0.044220001, + 0.051602099 0.019835399 0.048625499, + 0.050159499 0.0232378 0.0486282, + 0.047342401 0.0219271 0.0528595, + 0.0457693 0.0250402 0.052862, + 0.043199599 0.0227488 0.0569042, + 0.0440608 0.020863 0.056902699, + 0.045516402 0.017675901 0.0569002, + 0.044234701 0.0204823 0.056902401, + 0.042951901 0.0162418 0.059999701, + 0.0441234 0.0127327 0.059997, + 0.046579801 0.0144028 0.056897599, + 0.040049799 0.0151387 0.062902898, + 0.035728101 0.016900901 0.0655993, + 0.031254999 0.0179908 0.068074502, + 0.026730301 0.018394601 0.070318103, + 0.0222547 0.018112799 0.072320201, + 0.017927799 0.017160799 0.074072599, + 0.0138458 0.0155685 0.075567603, + 0.0100996 0.0133791 0.076798901, + 0.00677288 0.0106485 0.0777613, + 0.0039400999 0.00744473 0.078450702, + 0.047239799 0.0123718 0.056896001, + 0.046864301 0.0135273 0.056896899, + 0.037183098 -0.047049198 -0.046037499, + 0.040200301 -0.0444091 -0.046035402, + 0.043079801 -0.0416288 -0.0460332, + 0.045810599 -0.0386931 -0.046030801, + 0.0543552 -0.0251863 -0.046020102, + 0.055498298 -0.022765599 -0.046018101, + 0.056604698 -0.0262344 -0.041353401, + 0.0528684 -0.0283347 -0.046022601, + 0.054723799 -0.0299566 -0.0413564, + 0.0585334 -0.027133301 -0.0365545, + 0.060217001 -0.023163 -0.036551401, + 0.061936598 -0.0238293 -0.031636398, + 0.063391604 -0.019639101 -0.031633001, + 0.064874999 -0.020103199 -0.0266189, + 0.066074297 -0.0157251 -0.0266154, + 0.067298099 -0.0160209 -0.021519201, + 0.068218999 -0.01149 -0.0215156, + 0.0691645 -0.0116536 -0.016354499, + 0.069789298 -0.0070078499 -0.0163508, + 0.0704422 -0.00707768 -0.0111425, + 0.070758201 -0.0023568501 -0.0111388, + 0.071109504 -0.0023727401 -0.0059010098, + 0.0708372 0.0071268501 -0.000644124, + 0.070577897 0.0070965602 0.00459889, + 0.071154997 0.0023795499 -0.000647904, + 0.069945998 0.0117948 0.0046026302, + 0.069388099 0.0116965 0.0098214904, + 0.0684513 0.016304901 0.0098251598, + 0.067605801 0.016099401 0.015002, + 0.066378698 0.0205789 0.0150056, + 0.065261699 0.020228401 0.020122901, + 0.063763797 0.024542101 0.0201263, + 0.0623958 0.024011301 0.025166599, + 0.060651399 0.028125299 0.0251699, + 0.059057299 0.0273815 0.030115901, + 0.057094999 0.031264901 0.030119, + 0.0553036 0.0302795 0.034954, + 0.053155798 0.033905499 0.034956899, + 0.051199298 0.032652698 0.039664298, + 0.0489018 0.035999499 0.039666999, + 0.046815298 0.0344586 0.044230901, + 0.044406801 0.037508398 0.0442333, + 0.0422277 0.035662599 0.048638102, + 0.039748799 0.038403399 0.0486403, + 0.037516501 0.036240999 0.052870899, + 0.035053499 0.033855598 0.0569131, + 0.035170201 0.033735499 0.056913, + 0.0369142 0.031941 0.056911599, + 0.033129901 0.031773999 0.060012098, + 0.033027399 0.035940401 0.056914698, + 0.035009298 0.038665801 0.052872799, + 0.0293185 0.0389731 0.056917202, + 0.032345701 0.040917698 0.052874599, + 0.02871 0.039470699 0.0569175, + 0.0295376 0.042986698 0.052876201, + 0.034270301 0.0433584 0.0486442, + 0.026063301 0.041171599 0.0569189, + 0.0248664 0.041940801 0.0569195, + 0.0245518 0.038777798 0.060017701, + 0.026597699 0.0448635 0.052877702, + 0.031295199 0.045550499 0.048645999, + 0.036038801 0.045601401 0.0442397, + 0.039006501 0.043092199 0.044237699, + 0.040745001 0.045018099 0.0396742, + 0.043662999 0.042196099 0.039671902, + 0.045331601 0.043813501 0.0349648, + 0.048158601 0.040687799 0.0349623, + 0.0497186 0.0420104 0.0301276, + 0.052415099 0.038595799 0.0301248, + 0.053829901 0.039642099 0.025179099, + 0.056358799 0.0359581 0.0251761, + 0.0575944 0.036750998 0.020136099, + 0.0599216 0.032821901 0.020132899, + 0.060947198 0.033388101 0.0150158, + 0.063042 0.0292427 0.0150125, + 0.063830398 0.0296127 0.0098357499, + 0.065666303 0.0252831 0.0098323002, + 0.0661944 0.025490601 0.0046135401, + 0.067749403 0.021012301 0.0046099699, + 0.067998298 0.021093801 -0.00063300302, + 0.0692553 0.016504901 -0.000636657, + 0.069211103 0.0164985 -0.0058859801, + 0.070158198 0.0118389 -0.00588969, + 0.069811597 0.0117847 -0.0111275, + 0.0704422 0.0070954198 -0.0111313, + 0.069789298 0.0070338799 -0.0163396, + 0.070102401 0.00235676 -0.016343299, + 0.0691441 0.0023288899 -0.0215046, + 0.067886703 -0.00224847 -0.026604701, + 0.0691441 -0.0022946401 -0.0215082, + 0.067583501 -0.0067777601 -0.026608299, + 0.066038199 -0.0066183698 -0.0316227, + 0.065447003 -0.0110144 -0.031626198, + 0.063629903 -0.0107039 -0.036541399, + 0.062770903 -0.01493 -0.0365448, + 0.060702499 -0.0144333 -0.041343998, + 0.0596008 -0.018455399 -0.041347198, + 0.057543401 -0.0169563 -0.046013501, + 0.058288701 -0.0138541 -0.046011001, + 0.058982201 -0.0109679 -0.046008699, + 0.061533201 -0.0103465 -0.041340798, + 0.0642047 -0.0064300201 -0.036538001, + 0.066334501 -0.0021925899 -0.031619199, + 0.067886703 0.00229083 -0.0266011, + 0.068835303 0.0069420501 -0.0215009, + 0.0691645 0.0116796 -0.016335901, + 0.068869203 0.016421299 -0.0111238, + 0.067954801 0.0210845 -0.0058823298, + 0.066437602 0.025588401 -0.000629424, + 0.064343698 0.029854899 0.0046170098, + 0.0617094 0.0338099 0.0098390998, + 0.058580201 0.037384301 0.015019, + 0.055010099 0.040515698 0.0201391, + 0.051060501 0.043149099 0.025181901, + 0.046799898 0.0452374 0.0301301, + 0.042302102 0.0467434 0.034967098, + 0.037645102 0.047638901 0.039676201, + 0.032910202 0.0479066 0.0442416, + 0.028180299 0.047538899 0.048647601, + 0.023538901 0.046539798 0.052879099, + 0.041247699 0.056992199 0.0098563498, + 0.0408848 0.056991 0.0113678, + 0.043610699 0.055217199 0.0098561402, + 0.043072 0.054530799 0.0150326, + 0.047201999 0.052180901 0.0098537197, + 0.047581501 0.052604701 0.0046351301, + 0.050989099 0.049309202 0.0046325098, + 0.0511765 0.049494501 -0.000610388, + 0.054368 0.045965798 -0.00061319699, + 0.054333299 0.0459406 -0.0058625401, + 0.057280101 0.042208999 -0.0058655101, + 0.056997199 0.042004701 -0.0111035, + 0.0596749 0.038104001 -0.0111066, + 0.059121698 0.037754901 -0.016315101, + 0.0615106 0.0337217 -0.016318399, + 0.060669798 0.033264998 -0.021479901, + 0.062755004 0.0291386 -0.0214832, + 0.061613798 0.028612999 -0.026580101, + 0.063386001 0.024433799 -0.0265835, + 0.061936598 0.023879699 -0.0315984, + 0.063391604 0.0196895 -0.031601701, + 0.061631601 0.0191474 -0.036517698, + 0.062770903 0.0149882 -0.036520999, + 0.060702499 0.0144991 -0.041320998, + 0.061533201 0.0104123 -0.041324198, + 0.05847 0.0134999 -0.045989301, + 0.050515398 0.0322829 -0.045974299, + 0.052598599 0.0336105 -0.041305698, + 0.051634699 0.030595699 -0.0459757, + 0.048299 0.035623901 -0.045971598, + 0.042876001 0.0543117 -0.0214632, + 0.042096298 0.053328499 -0.0265604, + 0.039129902 0.0570172 -0.021621799, + 0.038441699 0.056021102 -0.0265583, + 0.038578101 0.057018399 -0.023034601, + 0.041133799 0.0521136 -0.0315759, + 0.044521 0.049249802 -0.031578202, + 0.0432849 0.047887001 -0.036494799, + 0.0463848 0.044888999 -0.036497202, + 0.044856399 0.0434146 -0.041297901, + 0.047653802 0.0403217 -0.041300401, + 0.044317201 0.040483899 -0.045967799, + 0.0457622 0.0387275 -0.045969199, + 0.04823 0.035727799 -0.045971598, + 0.050238401 0.037048802 -0.041303001, + 0.049277499 0.041690599 -0.036499701, + 0.047709402 0.0461662 -0.031580601, + 0.0455628 0.050397702 -0.026562801, + 0.040254202 0.0570147 -0.018443299, + 0.039507899 0.057016499 -0.0206539, + 0.0434702 0.055059999 -0.016301399, + 0.046406701 0.0513267 -0.021465501, + 0.0488258 0.0472419 -0.0265653, + 0.050684799 0.042876501 -0.031583302, + 0.051950201 0.038306199 -0.036502399, + 0.043084402 0.041702598 -0.0459668, + 0.040233102 0.0445216 -0.045964599, + 0.028144101 0.055728301 -0.0412881, + 0.0288043 0.057030302 -0.038065098, + 0.031801298 0.053724099 -0.041289698, + 0.029966 0.0520177 -0.045958601, + 0.027024901 0.053517699 -0.045957401, + 0.024479499 0.054815799 -0.045956399, + 0.0590882 0.0100029 -0.045992099, + 0.059542101 0.00743519 -0.045994099, + 0.059643202 0.0060383398 -0.045995198, + 0.0620891 0.00627913 -0.041327499, + 0.059932798 0.00203907 -0.045998398, + 0.063629903 0.0107621 -0.0365243, + 0.064563498 0.0154114 -0.031605098, + 0.064874999 0.020145601 -0.0265869, + 0.064560004 0.024882 -0.021486601, + 0.063624702 0.029538 -0.0163217, + 0.062086102 0.034033101 -0.0111098, + 0.059971198 0.038288899 -0.00586863, + 0.057316799 0.042231798 -0.00061617099, + 0.054168999 0.045793299 0.0046297102, + 0.050582401 0.048911601 0.0098511204, + 0.046618901 0.051532201 0.0150302, + 0.0423472 0.053608999 0.020149499, + 0.062367599 0.00211812 -0.041330799, + 0.062367599 -0.0020522999 -0.0413341, + 0.059986901 0.00129237 -0.045999002, + 0.064492702 0.00218534 -0.036531199, + 0.0642047 0.0064881998 -0.036527701, + 0.066038199 0.0066687199 -0.031612098, + 0.065447003 0.0110648 -0.0316086, + 0.066978499 0.0113191 -0.026593899, + 0.066074297 0.0157675 -0.026590399, + 0.067298099 0.0160551 -0.021493601, + 0.066076599 0.0205143 -0.021490101, + 0.066992298 0.0207943 -0.016328599, + 0.065454699 0.0252224 -0.016325099, + 0.0660671 0.025454201 -0.0111166, + 0.064219996 0.0298102 -0.0111132, + 0.064538799 0.029953901 -0.0058752699, + 0.062394299 0.034197699 -0.0058718901, + 0.0624342 0.034215301 -0.00062255398, + 0.060009498 0.038309101 -0.00061929401, + 0.059789799 0.038164798 0.0046236301, + 0.057106901 0.042073 0.0046267398, + 0.056651399 0.041733298 0.0098454002, + 0.053736899 0.045423999 0.0098483404, + 0.053073101 0.0448585 0.0150249, + 0.049957599 0.048303202 0.0150277, + 0.049116898 0.047486201 0.0201446, + 0.0458344 0.0506608 0.0201471, + 0.044851098 0.049569499 0.025187001, + 0.041438699 0.052454501 0.025189299, + 0.040349599 0.051071301 0.030134801, + 0.0291795 0.056973901 0.032774001, + 0.028806301 0.056973599 0.033153199, + 0.032138199 0.054232199 0.0349731, + 0.028442301 0.056257602 0.034974702, + 0.0269632 0.056972198 0.034974601, + 0.027395399 0.054182101 0.039681502, + 0.027455101 0.0569725 0.0345258, + 0.0154442 0.046220101 0.056922901, + 0.017120101 0.0492616 0.0528812, + 0.0137611 0.0468207 0.056923401, + 0.0128948 0.047022101 0.056923602, + 0.0109935 0.044554401 0.060022298, + 0.0197962 0.056967799 0.040416099, + 0.018862501 0.0569674 0.040983699, + 0.019074799 0.054897901 0.044247098, + 0.022701399 0.0535012 0.044245999, + 0.0181388 0.052198701 0.0486513, + 0.0146092 0.053293601 0.048652101, + 0.0137888 0.050294898 0.052882101, + 0.0103958 0.051103499 0.052882701, + 0.0116722 0.0473064 0.056923799, + 0.0097154099 0.047761299 0.056924101, + 0.0215874 0.050870501 0.048650201, + 0.0262265 0.051865298 0.044244699, + 0.0309553 0.0522312 0.0396799, + 0.035690598 0.051964398 0.034971301, + 0.036846701 0.053652301 0.030136799, + 0.034664299 0.0569796 0.025655599, + 0.0337644 0.056978501 0.0269992, + 0.037841301 0.055105101 0.0251914, + 0.0598877 -0.0019658101 -0.046001598, + 0.0597996 -0.0048635202 -0.0460039, + 0.059652399 -0.0059628799 -0.046004798, + 0.0620891 -0.0062133102 -0.041337501, + 0.059120201 -0.0099372501 -0.046007901, + 0.064492702 -0.0021271601 -0.0365346, + 0.066334501 0.00224295 -0.0316156, + 0.067583501 0.0068201302 -0.0265975, + 0.068218999 0.0115242 -0.021497199, + 0.0682308 0.016273299 -0.0163322, + 0.0676191 0.020984599 -0.0111202, + 0.066395096 0.0255764 -0.00587876, + 0.064580098 0.029968901 -0.00062593498, + 0.062205698 0.0340859 0.0046203798, + 0.059312899 0.037856098 0.0098423203, + 0.055951599 0.041213501 0.015022, + 0.05218 0.044099499 0.0201419, + 0.048063099 0.046463002 0.025184499, + 0.043672301 0.048262302 0.0301325, + 0.0390836 0.049464401 0.0349693, + 0.034377001 0.050046898 0.039678201, + 0.0296345 0.049997602 0.044243202, + 0.0249395 0.049314901 0.048648998, + 0.020375 0.048007902 0.052880201, + 0.019013699 0.044946499 0.056921899, + 0.0190669 0.044920299 0.056921899, + 0.019141899 0.0448834 0.056921899, + 0.057271801 -0.0177278 -0.0460141, + 0.058232799 -0.0223951 -0.041350301, + 0.061631601 -0.0190892 -0.0365481, + 0.064563498 -0.015361 -0.0316296, + 0.066978499 -0.0112767 -0.0266119, + 0.068835303 -0.0069078002 -0.021511899, + 0.070102401 -0.00233073 -0.016347099, + 0.070758201 0.0023745899 -0.011135, + 0.0707919 0.00712639 -0.0058934502, + 0.070202999 0.0118423 -0.00064036902, + 0.069001801 0.0164403 0.0046063298, + 0.067208901 0.0208406 0.0098287696, + 0.064855203 0.024966599 0.0150091, + 0.061981101 0.028746299 0.020129699, + 0.058635999 0.032113399 0.0251731, + 0.054877602 0.035008602 0.030122001, + 0.050770599 0.0373803 0.0349597, + 0.046386 0.0391853 0.039669499, + 0.0418 0.0403907 0.044235598, + 0.037092399 0.040972501 0.0486423, + 0.032363601 0.036483102 0.056915201, + 0.071109504 0.0023821399 -0.0058972202, + 0.0559403 -0.021509999 -0.046017099, + 0.052595802 -0.028785501 -0.046022899, + 0.052598599 -0.033544701 -0.041359201, + 0.056588501 -0.030982301 -0.0365576, + 0.060205001 -0.0279129 -0.031639598, + 0.063386001 -0.0243914 -0.026622299, + 0.066076599 -0.0204801 -0.021522701, + 0.0682308 -0.0162473 -0.0163581, + 0.069811597 -0.0117669 -0.0111463, + 0.0707919 -0.0071169999 -0.00590479, + 0.071154997 -0.0023785101 -0.00065169297, + 0.070894502 0.0023665801 0.0045951302, + 0.070014901 0.0070357602 0.0098177698, + 0.068530999 0.0115478 0.0149984, + 0.066468097 0.015824201 0.020119401, + 0.063861601 0.0197901 0.0251633, + 0.060755901 0.023375699 0.030112701, + 0.057204399 0.0265179 0.034951001, + 0.053268 0.029160099 0.039661501, + 0.049014699 0.031254601 0.0442283, + 0.044518001 0.032762401 0.048635799, + 0.039856199 0.033654202 0.052868798, + 0.037276201 0.031471498 0.0569112, + 0.037787002 0.030809101 0.056910701, + 0.0496815 -0.033604901 -0.0460268, + 0.050521001 -0.032216601 -0.046025701, + 0.048244301 -0.035508901 -0.046028301, + 0.042239901 0.0243403 0.056905501, + 0.041115999 0.0262041 0.056906998, + 0.039782699 0.0229207 0.060005099, + 0.0428016 0.0234088 0.0569048, + 0.0352511 0.0242819 0.062910199, + 0.030632701 0.0249587 0.0656057, + 0.0260283 0.0249463 0.068080097, + 0.021538001 0.024255401 0.0703227, + 0.017259501 0.022910699 0.072324097, + 0.0132858 0.0209509 0.074075602, + 0.0097032702 0.0184278 0.075569898, + 0.0065897098 0.0154054 0.076800503, + 0.0040128902 0.0119582 0.077762298, + 0.0020290101 0.0081695896 0.078451201, + 0.00068147201 0.0041304398 0.078864299, + 0.00034184399 0.0041717002 0.078864299, + 0.00068222702 0.0083884597 0.078451402, + 0 0.0041854898 0.078864299, + 0.037805501 0.026047399 0.060007598, + 0.039269399 0.0288867 0.056909099, + 0.035583101 0.0290049 0.0600099, + 0.033178799 0.027039601 0.0629123, + 0.0308914 0.029621501 0.062914401, + 0.0285208 0.0273425 0.0656076, + 0.026224 0.0295486 0.065609299, + 0.0239322 0.0269596 0.068081699, + 0.021680901 0.0287979 0.068083197, + 0.019511901 0.025909699 0.070324101, + 0.0173593 0.0273955 0.070325203, + 0.0153554 0.024225 0.072325103, + 0.0133517 0.0253819 0.072325997, + 0.0115522 0.021951901 0.074076399, + 0.0097435704 0.022810001 0.0740771, + 0.0081841396 0.0191487 0.075570501, + 0.0066119302 0.019745 0.075570904, + 0.00532379 0.0158855 0.076800898, + 0.0040233498 0.0162622 0.076801203, + 0.0030326699 0.0122421 0.077762596, + 0.0020327701 0.0124463 0.077762701, + 0.00136003 0.0083061801 0.078451298, + 0.0403197 0.0275246 0.056908, + 0.040188901 0.0276943 0.056908201, + 0.028403699 0.032011099 0.062916301, + 0.0237571 0.031562801 0.065610997, + 0.019288899 0.030448901 0.068084501, + 0.0150941 0.0287033 0.070326298, + 0.0112613 0.0263738 0.072326802, + 0.0078717899 0.0235199 0.074077703, + 0.0049968399 0.020212701 0.075571299, + 0.0026968201 0.016533 0.076801397, + 0.00101969 0.0125692 0.077762797, + 0 0.0084159197 0.078451402, + -0.00034184399 0.0041717002 0.078864299, + -0.00068147201 0.0041304398 0.078864299, + -0.00136003 0.0083061801 0.078451298, + -0.00101668 0.0040620798 0.078864299, + 0.0275963 0.036676198 0.060015999, + 0.0304619 0.0343366 0.060014199, + 0.0302254 0.0382316 0.056916598, + 0.0257317 0.034192599 0.062918, + 0.0228929 0.036152199 0.062919602, + 0.021136099 0.033371899 0.065612398, + 0.018378099 0.034964301 0.065613702, + 0.0167719 0.031902 0.068085603, + 0.0141461 0.033147901 0.068086602, + 0.012731 0.0298246 0.0703272, + 0.0102853 0.030752201 0.0703279, + 0.0090979896 0.0271942 0.072327502, + 0.00687563 0.0278379 0.072328001, + 0.0059489501 0.0240769 0.074078098, + 0.0039875298 0.024477299 0.074078403, + 0.0033493401 0.0205491 0.075571597, + 0.00168012 0.0207518 0.075571701, + 0.0013528001 0.0166962 0.076801501, + 0 0.016750701 0.076801598, + 0 0.0126103 0.077762902, + -0.00101969 0.0125692 0.077762797, + -0.00068222702 0.0083884597 0.078451402, + 0.0327521 0.036165498 0.056914899, + 0.0276125 0.040176 0.0569181, + 0.019905601 0.0378769 0.062921003, + 0.0155008 0.0363295 0.0656147, + 0.0114286 0.0341786 0.068087399, + 0.0077729002 0.031479899 0.070328496, + 0.0046086698 0.028300701 0.072328404, + 0.0020002499 0.024718599 0.074078597, + 0 0.0208194 0.075571798, + -0.0013528001 0.0166962 0.076801501, + -0.0020327701 0.0124463 0.077762701, + -0.0020290101 0.0081695896 0.078451201, + -0.00134529 0.00396686 0.078864202, + -0.00166518 0.0038455301 0.078864098, + -0.00332325 0.0077374601 0.078450903, + -0.00197427 0.0036989199 0.078864001, + -0.0039400999 0.00744473 0.078450702, + -0.00227056 0.0035277801 0.0788638, + -0.0049671 0.0115963 0.077762097, + -0.0040128902 0.0119582 0.077762298, + -0.00532379 0.0158855 0.076800898, + -0.0040233498 0.0162622 0.076801203, + -0.0049968399 0.020212701 0.075571299, + -0.0033493401 0.0205491 0.075571597, + -0.0039875298 0.024477299 0.074078403, + -0.0020002499 0.024718599 0.074078597, + -0.0023118299 0.0285796 0.072328597, + 0 0.028672701 0.072328702, + 0 0.032423701 0.070329197, + 0.00261353 0.032318398 0.070329197, + 0.0029040501 0.035918899 0.0680888, + 0.0057892599 0.035568599 0.068088502, + 0.0063436599 0.038982 0.065616898, + 0.0094640302 0.038344901 0.065616399, + 0.0102507 0.041538499 0.062923901, + 0.0135639 0.040578801 0.062923104, + 0.0145468 0.0435252 0.060021501, + 0.0180058 0.042213298 0.060020398, + 0.015996 0.046023201 0.056922801, + 0.021348 0.040627498 0.060019199, + 0.0219955 0.043480501 0.0569207, + 0.0167892 0.039355502 0.062922202, + 0.012523 0.0374588 0.065615602, + 0.00863693 0.0349872 0.068088099, + 0.00521011 0.032003101 0.070328899, + 0.0023118299 0.0285796 0.072328597, + 0 0.0247992 0.074078701, + -0.00168012 0.0207518 0.075571701, + -0.0026968201 0.016533 0.076801397, + -0.0030326699 0.0122421 0.077762596, + -0.00268483 0.0079796398 0.078451097, + 0.024018399 0.0424858 0.056919899, + 0.0226715 0.0431481 0.056920499, + 0.0068709301 0.042228501 0.0629244, + 0.00318215 0.039365798 0.065617204, + 0 0.036035899 0.068088897, + -0.00261353 0.032318398 0.070329197, + -0.0046086698 0.028300701 0.072328404, + -0.0059489501 0.0240769 0.074078098, + -0.0066119302 0.019745 0.075570904, + -0.0065897098 0.0154054 0.076800503, + -0.0058890898 0.0111588 0.077761702, + -0.0045314101 0.0071034199 0.078450397, + -0.00255212 0.0033334401 0.078863703, + -0.0028171299 0.0031171299 0.078863502, + -0.00562221 0.00628372 0.078449696, + -0.0030638699 0.0028800699 0.0788633, + -0.00680352 0.056963801 0.045456301, + -0.0073703802 0.054765001 0.048653301, + -0.0046473802 0.0569635 0.0457973, + -0.0032907401 0.0026239699 0.078863099, + -0.0065673999 0.0052995901 0.078448899, + -0.0034962599 0.0023505299 0.078862898, + -0.0073688198 0.0452944 0.060022902, + -0.0036964 0.045740299 0.0600232, + -0.0065023 0.0482933 0.0569246, + -0.0068709301 0.042228501 0.0629244, + -0.0102507 0.041538499 0.062923901, + -0.0094640302 0.038344901 0.065616399, + -0.012523 0.0374588 0.065615602, + -0.0114286 0.0341786 0.068087399, + -0.0141461 0.033147901 0.068086602, + -0.012731 0.0298246 0.0703272, + -0.0150941 0.0287033 0.070326298, + -0.0133517 0.0253819 0.072325997, + -0.0153554 0.024225 0.072325103, + -0.0132858 0.0209509 0.074075602, + -0.0149334 0.0198137 0.0740747, + -0.0125433 0.016631899 0.075568497, + -0.0138458 0.0155685 0.075567603, + -0.0111484 0.0125228 0.076798201, + -0.0121248 0.0115849 0.076797403, + -0.00913925 0.0087163998 0.077759802, + -0.0098159797 0.00795261 0.077759102, + -0.00697758 0.0047538099 0.078448497, + -0.00367912 0.00206135 0.078862697, + -0.00383811 0.00175837 0.078862399, + -0.0076598101 0.0035721699 0.078447603, + -0.00397221 0.00144367 0.078862198, + -0.021348 0.040627498 0.060019199, + -0.0180058 0.042213298 0.060020398, + -0.0219955 0.043480501 0.0569207, + -0.019905601 0.0378769 0.062921003, + -0.0154442 0.046220101 0.056922901, + -0.015996 0.046023201 0.056922801, + -0.0145468 0.0435252 0.060021501, + -0.0167892 0.039355502 0.062922202, + -0.018378099 0.034964301 0.065613702, + -0.021136099 0.033371899 0.065612398, + -0.019288899 0.030448901 0.068084501, + -0.021680901 0.0287979 0.068083197, + -0.019511901 0.025909699 0.070324101, + -0.021538001 0.024255401 0.0703227, + -0.0190518 0.0214474 0.072322898, + -0.0207204 0.019844601 0.072321601, + -0.017927799 0.017160799 0.074072599, + -0.019255299 0.0156624 0.0740714, + -0.016173501 0.013145 0.075565703, + -0.0171836 0.0118008 0.075564601, + -0.0138359 0.0094891395 0.076795802, + -0.0145595 0.0083448598 0.0767949, + -0.0109745 0.0062742601 0.077757798, + -0.0114487 0.0053705801 0.077757098, + -0.0079274299 0.0029440001 0.078447104, + -0.0040805498 0.00111908 0.0788619, + -0.0081436504 0.0022964301 0.0784465, + -0.0041624201 0.00078693498 0.078861602, + -0.0118488 0.0044317399 0.077756301, + -0.0151887 0.0071459999 0.076793902, + -0.0180823 0.0103796 0.075563498, + -0.020457899 0.0140621 0.074070103, + -0.0222547 0.018112799 0.072320201, + -0.0234244 0.022443499 0.070321299, + -0.0239322 0.0269596 0.068081699, + -0.0237571 0.031562801 0.065610997, + -0.0228929 0.036152199 0.062919602, + -0.0245518 0.038777798 0.060017701, + -0.0276125 0.040176 0.0569181, + -0.0275963 0.036676198 0.060015999, + -0.026063301 0.041171599 0.0569189, + -0.0295376 0.042986698 0.052876201, + -0.0262265 0.051865298 0.044244699, + -0.0249395 0.049314901 0.048648998, + -0.022701399 0.0535012 0.044245999, + -0.028180299 0.047538899 0.048647601, + -0.026597699 0.0448635 0.052877702, + -0.024018399 0.0424858 0.056919899, + -0.0248664 0.041940801 0.0569195, + -0.0257317 0.034192599 0.062918, + -0.026224 0.0295486 0.065609299, + -0.0260283 0.0249463 0.068080097, + -0.025158901 0.0204856 0.070319697, + -0.0236446 0.016263099 0.0723188, + -0.021527801 0.0123701 0.0740688, + -0.018863801 0.0088907601 0.075562298, + -0.015719401 0.0059004002 0.076792903, + -0.0121719 0.00346372 0.0777556, + -0.00830705 0.0016334601 0.078446001, + -0.0042173001 0.00044928899 0.0788614, + -0.0084165698 0.00095950498 0.078445502, + -0.00424483 0.000108225 0.078861102, + -0.0124161 0.0024728801 0.077754803, + -0.0161481 0.00461622 0.076791897, + -0.019522799 0.0073438799 0.075561099, + -0.022458101 0.0105975 0.074067399, + -0.024881201 0.0143076 0.072317198, + -0.026730301 0.018394601 0.070318103, + -0.027955599 0.0227709 0.068078399, + -0.0285208 0.0273425 0.0656076, + -0.028403699 0.032011099 0.062916301, + -0.0293185 0.0389731 0.056917202, + -0.0302254 0.0382316 0.056916598, + -0.0304619 0.0343366 0.060014199, + -0.0308914 0.029621501 0.062914401, + -0.030632701 0.0249587 0.0656057, + -0.0297016 0.020447399 0.068076499, + -0.028128199 0.0161839 0.0703163, + -0.0259565 0.0122589 0.072315603, + -0.0232428 0.0087558497 0.074065901, + -0.0200553 0.0057489099 0.075559802, + -0.0164722 0.00330164 0.076790802, + -0.0125799 0.0014655601 0.077753998, + -0.0084715104 0.000278967 0.078444898, + -0.051464502 0.0086389501 0.052848902, + -0.051929399 0.0051820399 0.0528461, + -0.048347302 0.0069059902 0.056891602, + -0.054526798 0.0091588004 0.048617002, + -0.0537907 0.0127803 0.0486199, + -0.056566499 0.0134453 0.0442141, + -0.055539802 0.017193399 0.044217099, + -0.058015201 0.0179649 0.039652601, + -0.0566836 0.0217997 0.0396557, + -0.0588497 0.022637701 0.034947898, + -0.057204399 0.0265179 0.034951001, + -0.059057299 0.0273815 0.030115901, + -0.057094999 0.031264901 0.030119, + -0.058635999 0.032113399 0.0251731, + -0.056358799 0.0359581 0.0251761, + -0.0575944 0.036750998 0.020136099, + -0.055010099 0.040515698 0.0201391, + -0.055951599 0.041213501 0.015022, + -0.053073101 0.0448585 0.0150249, + -0.053736899 0.045423999 0.0098483404, + -0.050582401 0.048911601 0.0098511204, + -0.050989099 0.049309202 0.0046325098, + -0.047581501 0.052604701 0.0046351301, + -0.0477564 0.052802298 -0.00060775399, + -0.044122901 0.055874199 -0.00060530799, + -0.0440947 0.055842601 -0.0058546602, + -0.042668398 0.0570032 -0.0039538299, + -0.042677399 0.057001099 -0.00130937, + -0.0421267 0.057008199 -0.0102176, + -0.043876901 0.0555709 -0.0110927, + -0.042442899 0.057006098 -0.0076003699, + -0.041977499 0.057008799 -0.0110906, + -0.041683901 0.0570102 -0.0128086, + -0.042568501 0.057004701 -0.0058534802, + -0.0425286 0.057005301 -0.00661192, + -0.0477258 0.0527726 -0.0058570998, + -0.0511765 0.049494501 -0.000610388, + -0.054168999 0.045793299 0.0046297102, + -0.056651399 0.041733298 0.0098454002, + -0.058580201 0.037384301 0.015019, + -0.0599216 0.032821901 0.020132899, + -0.060651399 0.028125299 0.0251699, + -0.060755901 0.023375699 0.030112701, + -0.0602322 0.018656399 0.034944799, + -0.059087601 0.0140497 0.039649501, + -0.0573406 0.0096369199 0.044211101, + -0.0550193 0.0054963198 0.0486141, + -0.052162301 0.00170194 0.052843399, + -0.048775598 0.00191893 0.056887601, + -0.052162301 -0.0017861 0.052840602, + -0.0488245 0.00134948 0.056887198, + -0.055266201 0.00180907 0.048611201, + -0.057858501 0.0057854801 0.044208001, + -0.059896201 0.0100717 0.039646301, + -0.0613456 0.0145916 0.034941498, + -0.062183201 0.0192654 0.0301094, + -0.0623958 0.024011301 0.025166599, + -0.061981101 0.028746299 0.020129699, + -0.060947198 0.033388101 0.0150158, + -0.059312899 0.037856098 0.0098423203, + -0.057106901 0.042073 0.0046267398, + -0.054368 0.045965798 -0.00061319699, + -0.051143799 0.049467102 -0.0058597298, + -0.047490101 0.0525162 -0.0110951, + -0.0434702 0.055059999 -0.016301399, + -0.041115001 0.057012301 -0.0153712, + -0.0408605 0.057013001 -0.016298501, + -0.040420201 0.057014301 -0.017902801, + -0.039599001 0.057016298 -0.0204008, + -0.042876001 0.0543117 -0.0214632, + -0.047049899 0.052033599 -0.0163038, + -0.050891101 0.049226999 -0.0110977, + -0.054333299 0.0459406 -0.0058625401, + -0.057316799 0.042231798 -0.00061617099, + -0.059789799 0.038164798 0.0046236301, + -0.0617094 0.0338099 0.0098390998, + -0.063042 0.0292427 0.0150125, + -0.063763797 0.024542101 0.0201263, + -0.063861601 0.0197901 0.0251633, + -0.063332699 0.0150689 0.030106099, + -0.062185101 0.0104616 0.034938201, + -0.060437299 0.0060485099 0.039643101, + -0.058118101 0.00190792 0.044204898, + -0.055266201 -0.00188649 0.048608199, + -0.051929399 -0.0052661998 0.0528378, + -0.0486653 -0.0042251102 0.056882799, + -0.0487286 -0.0020099001 0.056884501, + -0.045899801 -0.0018975 0.059985299, + -0.0487381 -0.00167518 0.056884799, + -0.0450087 0.0091408296 0.059994102, + -0.0481118 0.0080683501 0.056892499, + -0.045602102 0.0054893401 0.0599912, + -0.042520899 0.0051128799 0.062894903, + -0.0441234 0.0127327 0.059997, + -0.042951901 0.0162418 0.059999701, + -0.046579801 0.0144028 0.056897599, + -0.041142099 0.0118669 0.062900297, + -0.0428016 0.0234088 0.0569048, + -0.042239901 0.0243403 0.056905501, + -0.0457693 0.0250402 0.052862, + -0.0484928 0.026536001 0.0486308, + -0.047342401 0.0219271 0.0528595, + -0.046609499 0.0297157 0.0486334, + -0.049014699 0.031254601 0.0442283, + -0.046815298 0.0344586 0.044230901, + -0.0489018 0.035999499 0.039666999, + -0.046386 0.0391853 0.039669499, + -0.048158601 0.040687799 0.0349623, + -0.045331601 0.043813501 0.0349648, + -0.046799898 0.0452374 0.0301301, + -0.043672301 0.048262302 0.0301325, + -0.044851098 0.049569499 0.025187001, + -0.041438699 0.052454501 0.025189299, + -0.0423472 0.053608999 0.020149499, + -0.038670901 0.056317698 0.0201516, + -0.039129701 0.056986701 0.016730299, + -0.037841301 0.055105101 0.0251914, + -0.040349599 0.051071301 0.030134801, + -0.042302102 0.0467434 0.034967098, + -0.043662999 0.042196099 0.039671902, + -0.044406801 0.037508398 0.0442333, + -0.044518001 0.032762401 0.048635799, + -0.0439918 0.028041299 0.052864298, + -0.0042173001 -0.00057487999 0.078860603, + -0.0084165698 -0.00108443 0.0784439, + -0.0041624201 -0.00091252598 0.078860298, + -0.037805501 0.026047399 0.060007598, + -0.035583101 0.0290049 0.0600099, + -0.039269399 0.0288867 0.056909099, + -0.0352511 0.0242819 0.062910199, + -0.037094701 0.021366499 0.0629078, + -0.034247998 0.019720901 0.065601498, + -0.035728101 0.016900901 0.0655993, + -0.0326056 0.0154174 0.068072498, + -0.033744901 0.0127435 0.068070397, + -0.030369001 0.0114615 0.0703125, + -0.0311973 0.0089803999 0.0703106, + -0.027596001 0.0079357103 0.072312102, + -0.0281497 0.0056892498 0.072310403, + -0.024355801 0.0049133198 0.074062802, + -0.0246769 0.00293737 0.074061297, + -0.0207274 0.00245656 0.075557202, + -0.020862799 0.000780534 0.075555801, + -0.016798301 0.00061585702 0.076788701, + -0.012662 -0.00057216699 0.077752396, + -0.016798301 -0.00073814701 0.076787598, + -0.0125799 -0.00158938 0.077751599, + -0.00830705 -0.00175838 0.078443304, + -0.0040805498 -0.00124468 0.07886, + -0.00397221 -0.00156927 0.078859799, + -0.0079274299 -0.00306893 0.078442298, + -0.00383811 -0.00188396 0.078859501, + -0.039782699 0.0229207 0.060005099, + -0.043199599 0.0227488 0.0569042, + -0.041501898 0.0196451 0.060002498, + -0.038697701 0.018312201 0.062905401, + -0.040049799 0.0151387 0.062902898, + -0.036976401 0.0139711 0.065596901, + -0.0379849 0.0109502 0.065594502, + -0.034665201 0.0099866996 0.068068199, + -0.035360798 0.0071647898 0.068065897, + -0.0318233 0.00644085 0.070308499, + -0.032242902 0.0038590599 0.070306502, + -0.028520901 0.0034054299 0.072308503, + -0.0287071 0.00109928 0.0723067, + -0.024838001 0.00094200799 0.074059702, + -0.020862799 -0.00090086099 0.075554498, + -0.024838001 -0.00105995 0.074058101, + -0.0207274 -0.0025768799 0.075553201, + -0.016689301 -0.0020876301 0.0767866, + -0.0164722 -0.0034239299 0.076785497, + -0.0124161 -0.0025967001 0.077750698, + -0.0121719 -0.00358754 0.077749997, + -0.0081436504 -0.00242135 0.078442797, + -0.041115999 0.0262041 0.056906998, + -0.0403197 0.0275246 0.056908, + -0.045571301 0.0175067 0.056900099, + -0.045516402 0.017675901 0.0569002, + -0.044234701 0.0204823 0.056902401, + -0.0440608 0.020863 0.056902699, + -0.038747001 0.0078580501 0.065592103, + -0.035827 0.0042960201 0.068063602, + -0.032453399 0.00125188 0.070304401, + -0.0287071 -0.00121444 0.072304897, + -0.0246769 -0.0030553101 0.074056499, + -0.0204577 -0.0042366702 0.0755518, + -0.0161481 -0.0047385101 0.076784402, + -0.0118488 -0.0045555602 0.0777492, + -0.0076598101 -0.0036971001 0.078441799, + -0.00367912 -0.0021869401 0.078859299, + -0.0073425001 -0.0043016002 0.078441299, + -0.0034962599 -0.0024761199 0.078859001, + -0.0114487 -0.0054944102 0.077748403, + -0.015719401 -0.0060226899 0.076783396, + -0.0200553 -0.00586924 0.075550497, + -0.024355801 -0.0050312602 0.074054897, + -0.028520901 -0.00352058 0.072302997, + -0.036060899 0.00139905 0.0680613, + -0.039257899 0.0047144899 0.065589599, + -0.041967601 0.0085176704 0.0628976, + -0.047463499 0.0112676 0.0568951, + -0.047239799 0.0123718 0.056896001, + -0.050769702 0.0120569 0.052851599, + -0.039514199 0.0015401799 0.065586999, + -0.032453399 -0.00136384 0.0703023, + -0.036060899 -0.00150744 0.068058997, + -0.032242902 -0.0039710202 0.070300303, + -0.0281497 -0.0058044 0.072301202, + -0.023876701 -0.00697499 0.074053399, + -0.019522799 -0.00746421 0.075549297, + -0.0151887 -0.00726829 0.076782398, + -0.0109745 -0.0063980902 0.077747703, + -0.00697758 -0.0048787398 0.0784408, + -0.0032907401 -0.0027495599 0.0788588, + -0.0065673999 -0.00542452 0.078440398, + -0.0030638699 -0.0030056599 0.078858599, + -0.0104291 -0.00726052 0.077747002, + -0.0145595 -0.0084671499 0.076781496, + -0.018863801 -0.0090110898 0.075548001, + -0.0232428 -0.0088737896 0.074051902, + -0.027596001 -0.0080508599 0.072299398, + -0.0318233 -0.0065528098 0.070298202, + -0.035827 -0.0044044098 0.068056703, + -0.039514199 -0.00164463 0.065584503, + -0.042798501 0.00167465 0.062892199, + -0.048439 0.0058380002 0.056890801, + -0.048525002 0.00483739 0.05689, + -0.045899801 0.0018019601 0.059988301, + -0.042798501 -0.00177481 0.062889397, + -0.039257899 -0.0048189401 0.065582, + -0.035360798 -0.0072731799 0.0680544, + -0.0311973 -0.0090923598 0.070296198, + -0.0268634 -0.0102455 0.0722977, + -0.022458101 -0.0107155 0.074050397, + -0.0180823 -0.0105 0.075546898, + -0.0138359 -0.0096114296 0.076780602, + -0.0098159797 -0.0080764396 0.077746399, + -0.0061146398 -0.0059356298 0.078440003, + -0.0028171299 -0.0032427199 0.078858398, + -0.00562221 -0.00640865 0.078439601, + -0.00255212 -0.0034590301 0.078858301, + -0.00913925 -0.0088402303 0.077745803, + -0.0130226 -0.0106937 0.076779701, + -0.021527801 -0.0124881 0.074049003, + -0.0171836 -0.0119212 0.075545698, + -0.0259565 -0.0123741 0.072296001, + -0.030369001 -0.0115735 0.070294201, + -0.034665201 -0.0100951 0.068052202, + -0.038747001 -0.0079624997 0.065579496, + -0.042520899 -0.0052130399 0.0628867, + -0.048804201 0.0015856799 0.056887399, + -0.047779299 0.00970909 0.056893799, + -0.052814402 0.016344501 0.048622701, + -0.054265 0.0208646 0.044220001, + -0.055098802 0.025536999 0.039658599, + -0.0553036 0.0302795 0.034954, + -0.054877602 0.035008602 0.030122001, + -0.053829901 0.039642099 0.025179099, + -0.05218 0.044099499 0.0201419, + -0.049957599 0.048303202 0.0150277, + -0.047201999 0.052180901 0.0098537197, + -0.043961398 0.0556654 0.0046375701, + -0.042557601 0.056999002 0.0013198199, + -0.042645302 0.057000499 -0.000604617, + -0.042310499 0.056996901 0.0039320202, + -0.042208798 0.056996301 0.0046379999, + -0.048704099 0.018716 0.0528569, + -0.049848199 0.0154209 0.0528543, + -0.045648798 0.017268199 0.056899901, + -0.051602099 0.019835399 0.048625499, + -0.050159499 0.0232378 0.0486282, + -0.052747902 0.0244425 0.044222899, + -0.0509951 0.027911 0.0442256, + -0.053268 0.029160099 0.039661501, + -0.051199298 0.032652698 0.039664298, + -0.053155798 0.033905499 0.034956899, + -0.050770599 0.0373803 0.0349597, + -0.052415099 0.038595799 0.0301248, + -0.0497186 0.0420104 0.0301276, + -0.051060501 0.043149099 0.025181901, + -0.048063099 0.046463002 0.025184499, + -0.049116898 0.047486201 0.0201446, + -0.0458344 0.0506608 0.0201471, + -0.046618901 0.051532201 0.0150302, + -0.043072 0.054530799 0.0150326, + -0.043610699 0.055217199 0.0098561402, + -0.040947501 0.056991201 0.0111301, + -0.0397476 0.056988001 0.0150332, + -0.0394006 0.0569872 0.0160487, + -0.040231001 0.0569892 0.0136188, + -0.041253999 0.056992199 0.0098568201, + -0.041436601 0.056992799 0.00909831, + -0.0419368 0.0569948 0.0065254602, + -0.046864301 0.0135273 0.056896899, + -0.038458601 0.0569853 0.018418999, + -0.037669498 0.056984 0.020151, + -0.0374065 0.056983501 0.020728201, + -0.034975499 0.056979999 0.0251571, + -0.036245398 0.056981701 0.022974901, + -0.0337625 0.056978501 0.0270177, + -0.033179201 0.055993602 0.030138699, + -0.033596501 0.0569783 0.0272724, + -0.033411801 0.056978099 0.027538599, + -0.031967498 0.056976501 0.029499101, + -0.039748799 0.038403399 0.0486403, + -0.037516501 0.036240999 0.052870899, + -0.037092399 0.040972501 0.0486423, + -0.039006501 0.043092199 0.044237699, + -0.036038801 0.045601401 0.0442397, + -0.037645102 0.047638901 0.039676201, + -0.034377001 0.050046898 0.039678201, + -0.035690598 0.051964398 0.034971301, + -0.032138199 0.054232199 0.0349731, + -0.0314449 0.056976002 0.030138399, + -0.0304427 0.056975 0.0313644, + -0.028839599 0.056973599 0.0331343, + -0.028803701 0.056973599 0.03317, + -0.0254042 0.056970999 0.036383498, + -0.027395399 0.054182101 0.039681502, + -0.0241735 0.056970298 0.0373757, + -0.0269734 0.056972198 0.034975, + -0.035009298 0.038665801 0.052872799, + -0.032363601 0.036483102 0.056915201, + -0.032345701 0.040917698 0.052874599, + -0.034270301 0.0433584 0.0486442, + -0.031295199 0.045550499 0.048645999, + -0.032910202 0.0479066 0.0442416, + -0.0296345 0.049997602 0.044243202, + -0.0309553 0.0522312 0.0396799, + -0.028442301 0.056257602 0.034974702, + -0.0271597 0.056972299 0.034807801, + -0.033027399 0.035940401 0.056914698, + -0.035053499 0.033855598 0.0569131, + -0.033129901 0.031773999 0.060012098, + -0.035170201 0.033735499 0.056913, + -0.0369142 0.031941 0.056911599, + -0.039856199 0.033654202 0.052868798, + -0.042017799 0.030916899 0.0528666, + -0.037787002 0.030809101 0.056910701, + -0.0422277 0.035662599 0.048638102, + -0.0418 0.0403907 0.044235598, + -0.040745001 0.045018099 0.0396742, + -0.0390836 0.049464401 0.0349693, + -0.036846701 0.053652301 0.030136799, + -0.034952201 0.056979999 0.025192801, + -0.040188901 0.0276943 0.056908201, + -0.037276201 0.031471498 0.0569112, + -0.033178799 0.027039601 0.0629123, + -0.032545902 0.0224126 0.065603703, + -0.031254999 0.0179908 0.068074502, + -0.029343801 0.0138678 0.070314497, + -0.0268634 0.0101303 0.072313897, + -0.023876701 0.0068570501 0.074064396, + -0.0204577 0.0041163401 0.075558499, + -0.016689301 0.00196534 0.076789796, + -0.012662 0.00044834099 0.077753201, + -0.0084715104 -0.00040389501 0.078444399, + -0.00424483 -0.000233817 0.078860797, + -0.0327521 0.036165498 0.056914899, + -0.02871 0.039470699 0.0569175, + -0.023713199 0.055890899 0.039682802, + -0.023573499 0.0569699 0.037859499, + -0.0216677 0.056968801 0.0392332, + -0.021075999 0.056968499 0.039628301, + -0.020986401 0.056968398 0.0396837, + -0.0197956 0.056967799 0.040419299, + -0.00893855 0.0569642 0.044988699, + -0.0110144 0.054150298 0.048652802, + -0.0076671098 0.056963999 0.045267198, + -0.0110525 0.056964699 0.044395, + -0.0114773 0.0569648 0.044248901, + -0.0137888 0.050294898 0.052882101, + -0.017120101 0.0492616 0.0528812, + -0.0137611 0.0468207 0.056923401, + -0.0146092 0.053293601 0.048652101, + -0.0115828 0.0569502 0.044248801, + -0.0115874 0.0569648 0.044211, + -0.0131314 0.056965198 0.0436799, + -0.0151744 0.056965899 0.0428451, + -0.0153631 0.056049298 0.044248, + -0.0181388 0.052198701 0.0486513, + -0.020375 0.048007902 0.052880201, + -0.019013699 0.044946499 0.056921899, + -0.023538901 0.046539798 0.052879099, + -0.019141899 0.0448834 0.056921899, + -0.0215874 0.050870501 0.048650201, + -0.019074799 0.054897901 0.044247098, + -0.0156158 0.0569661 0.042635199, + -0.017180501 0.0569667 0.0418914, + -0.019148299 0.056967501 0.040819202, + -0.0226715 0.0431481 0.056920499, + -0.0190669 0.044920299 0.056921899, + -0.0109935 0.044554401 0.060022298, + -0.0135639 0.040578801 0.062923104, + -0.0155008 0.0363295 0.0656147, + -0.0167719 0.031902 0.068085603, + -0.0173593 0.0273955 0.070325203, + -0.017259501 0.022910699 0.072324097, + -0.016484 0.0185476 0.074073702, + -0.0150585 0.0144037 0.075566702, + -0.0130226 0.0105715 0.076796599, + -0.0104291 0.00713669 0.077758498, + -0.0073425001 0.0041766702 0.078447998, + -0.0097154099 0.047761299 0.056924101, + -0.0083290599 0.0480837 0.056924399, + -0.0103958 0.051103499 0.052882701, + -0.0116722 0.0473064 0.056923799, + -0.0128948 0.047022101 0.056923602, + 0.0115872 0.0569648 0.044212501, + 0.0115828 0.0569502 0.044248801, + 0.0125875 0.056965102 0.0438798, + 0.0147303 0.056965701 0.043037999, + 0.0153631 0.056049298 0.044248, + 0.0114778 0.0569648 0.044248901, + 0.0110144 0.054150298 0.048652802, + 0.0108516 0.056964599 0.0444571, + -0.00348601 0.052032899 0.052883402, + -0.0069564502 0.051683702 0.0528832, + -0.0039244201 0.048589099 0.056924801, + -0.00369344 0.0551349 0.048653599, + 0 0.055258401 0.048653699, + -0.0024819099 0.056963399 0.046009399, + 0.00369344 0.0551349 0.048653599, + 0.00220835 0.056963399 0.046027001, + 0 0.0521494 0.052883498, + -0.0027884699 0.048719499 0.056924898, + 0.00348601 0.052032899 0.052883402, + 0.0027884699 0.048719499 0.056924898, + 0.0073703802 0.054765001 0.048653301, + 0.00439747 0.0569635 0.045828398, + 0.0039244201 0.048589099 0.056924801, + 0.0069564502 0.051683702 0.0528832, + 0.00871915 0.056964099 0.045042802, + 0.0076671699 0.056963999 0.0452663, + 0.0065677101 0.056963801 0.045499999, + 0.00381625 0.0569635 0.0458811, + 0 0.056963298 0.046093799, + -0.000308338 0.056963298 0.046092499, + -0.0038163599 0.0569635 0.045878701, + -0.0078322301 0.048140701 0.056924399, + -0.0032596199 0.048665401 0.056924898, + 0 0.045889199 0.060023401, + -0.00344664 0.042644199 0.062924802, + -0.0063436599 0.038982 0.065616898, + -0.00863693 0.0349872 0.068088099, + -0.0102853 0.030752201 0.0703279, + -0.0112613 0.0263738 0.072326802, + -0.0115522 0.021951901 0.074076399, + -0.0111595 0.017587099 0.075569198, + -0.0100996 0.0133791 0.076798901, + -0.00840325 0.0094234301 0.077760302, + -0.0061146398 0.0058106999 0.078449301, + -0.0076127499 0.0100688 0.077760801, + -0.00898539 0.014148 0.076799497, + -0.0097032702 0.0184278 0.075569898, + -0.0097435704 0.022810001 0.0740771, + -0.0090979896 0.0271942 0.072327502, + -0.0077729002 0.031479899 0.070328496, + -0.0057892599 0.035568599 0.068088502, + -0.00318215 0.039365798 0.065617204, + 0 0.042783201 0.062924899, + 0.0036964 0.045740299 0.0600232, + 0.0032596199 0.048665401 0.056924898, + 0.0065023 0.0482933 0.0569246, + 0.0078322301 0.048140701 0.056924399, + 0.0083290599 0.0480837 0.056924399, + 0.0073688198 0.0452944 0.060022902, + 0.00344664 0.042644199 0.062924802, + 0 0.039494101 0.065617301, + -0.0029040501 0.035918899 0.0680888, + -0.00521011 0.032003101 0.070328899, + -0.00687563 0.0278379 0.072328001, + -0.0078717899 0.0235199 0.074077703, + -0.0081841396 0.0191487 0.075570501, + -0.0078128902 0.014825 0.076800004, + -0.00677288 0.0106485 0.0777613, + -0.0050933301 0.0067154798 0.078450099, + 0.0156169 0.0569661 0.042628501, + 0.016821999 0.056966498 0.042071901, + 0.020850999 0.056968302 0.039774802, + 0.0209838 0.056968398 0.0396837, + 0.024173001 0.056970298 0.037378799, + 0.025645601 0.0569712 0.036176499, + 0.0308176 0.056975398 0.030923299, + 0.031442601 0.056976002 0.0301382, + 0.033179201 0.055993602 0.030138699, + 0.032368101 0.0569769 0.028975699, + 0.033231501 0.056977902 0.027794801, + 0.0349412 0.056979999 0.025191801, + 0.035982899 0.056981299 0.0234471, + 0.039129101 0.056986701 0.016747201, + 0.039255802 0.056986898 0.016435999, + 0.039746098 0.056988001 0.015033, + 0.040137399 0.056988899 0.0139132, + 0.0415016 0.056993 0.0087988004, + 0.041989401 0.056995101 0.00620881, + 0.042206001 0.056996301 0.0046378998, + 0.058344599 0.0139398 -0.045988899, + 0.0572455 0.0177959 -0.045985799, + 0.055921901 0.021573501 -0.0459828, + 0.054495402 0.0251415 -0.045979999, + 0.056604698 0.026300199 -0.041311599, + 0.056588501 0.031040501 -0.036508199, + 0.0559441 0.035738599 -0.031588901, + 0.054684099 0.0403127 -0.026570801, + 0.052831501 0.044683401 -0.0214708, + 0.050419401 0.048774801 -0.0163064, + 0.047490101 0.0525162 -0.0110951, + 0.0440947 0.055842601 -0.0058546602, + 0.042686898 0.057002399 -0.00296877, + 0.042683698 0.0570013 -0.0016617, + 0.0426424 0.057000499 -0.00060462899, + 0.042596299 0.0570045 -0.0056181299, + 0.0425766 0.057004701 -0.0058535701, + 0.042377401 0.057006601 -0.0082414597, + 0.041986302 0.057008799 -0.0110911, + 0.043876901 0.0555709 -0.0110927, + 0.0415635 0.057010699 -0.013404, + 0.0420327 0.057008602 -0.0108373, + 0.047049899 0.052033599 -0.0163038, + 0.0497302 0.0481124 -0.021468099, + 0.051870801 0.043875199 -0.026567999, + 0.053433701 0.039395399 -0.031585999, + 0.054390799 0.034750901 -0.0365052, + 0.054723799 0.0300224 -0.0413086, + 0.054418098 0.0252888 -0.045979898, + 0.052555799 0.028839501 -0.045977101, + 0.040970601 0.0570127 -0.015939999, + 0.040867899 0.057013001 -0.016299101, + 0.039193299 0.057017099 -0.0214596, + 0.037542 0.057020199 -0.0253457, + 0.036926098 0.057021201 -0.0265559, + 0.0364017 0.057022002 -0.027586499, + 0.033814698 0.057025399 -0.031851601, + 0.033994399 0.057025202 -0.031571299, + 0.0365199 0.053229298 -0.0364905, + 0.033761699 0.057025399 -0.031925701, + 0.035316501 0.051479999 -0.041291501, + 0.0386739 0.049006298 -0.041293502, + 0.0351368 0.048672002 -0.045961302, + 0.041858599 0.0463138 -0.041295599, + 0.039937399 0.044813801 -0.045964301, + 0.039991699 0.050671201 -0.036492601, + 0.037562799 0.054744702 -0.031573799, + 0.035158899 0.0570237 -0.0297556, + 0.037136801 0.047064699 -0.045962501, + 0.033925999 0.049455401 -0.045960601, + 0.030559501 0.0516336 -0.045958899, + 0.0302375 0.057029098 -0.036486901, + 0.028899999 0.057030302 -0.037969399, + 0.0272223 0.057031602 -0.039647002, + 0.025474999 0.057032801 -0.0412216, + 0.0253943 0.057032902 -0.041287001, + 0.0241732 0.057033699 -0.042276099, + 0.0152352 -0.057996899 -0.046046201, + 0.0119352 -0.0586842 -0.0460467, + 0.00920578 -0.059252899 -0.0460472, + 0.0083174398 -0.061812799 -0.041381702, + 0.0439918 -0.0281255 0.052819598, + 0.0457693 -0.025124401 0.052822001, + 0.041827898 -0.0252684 0.056866001, + 0.046609499 -0.0297931 0.048586, + 0.044518001 -0.032839801 0.048583601, + 0.046815298 -0.034529001 0.044175901, + 0.044406801 -0.037578799 0.044173501, + 0.046386 -0.039248399 0.0396071, + 0.043662999 -0.042259201 0.039604701, + 0.045331601 -0.043869101 0.034894999, + 0.042302102 -0.046799 0.0348926, + 0.043672301 -0.048310202 0.030055599, + 0.040349599 -0.051119201 0.0300534, + 0.041438699 -0.0524945 0.0251057, + 0.037841301 -0.0551451 0.025103601, + 0.038670901 -0.056349698 0.020061901, + 0.034821901 -0.0588069 0.020059999, + 0.035417899 -0.059808999 0.0149416, + 0.031344801 -0.062041201 0.0149398, + 0.031736799 -0.062812902 0.0097621595, + 0.027471 -0.064792298 0.00976058, + 0.027691901 -0.0653091 0.0045412402, + 0.0232682 -0.067012899 0.00453988, + 0.0233537 -0.067254998 -0.00070335303, + 0.0188093 -0.0686647 -0.00070447603, + 0.018797301 -0.068616502 -0.0059537599, + 0.0141719 -0.0697188 -0.00595464, + 0.0141019 -0.0693703 -0.0111921, + 0.0094364202 -0.0701572 -0.0111928, + 0.0093489503 -0.0695026 -0.016400499, + 0.00468494 -0.069971897 -0.0164009, + 0.0046208999 -0.069011003 -0.021561399, + 0 -0.069165602 -0.0215615, + 0 -0.067903496 -0.026657, + -0.0045368699 -0.067751698 -0.0266569, + -0.0044331299 -0.0661982 -0.031670101, + -0.0088464599 -0.065754101 -0.031669799, + -0.0086008403 -0.063923903 -0.0365838, + -0.0128532 -0.063206598 -0.0365832, + -0.0124297 -0.061119098 -0.041381199, + -0.016486401 -0.0601524 -0.041380402, + -0.0152352 -0.057996899 -0.046046201, + -0.0119352 -0.0586842 -0.0460467, + -0.00920578 -0.059252899 -0.0460472, + -0.0083174398 -0.061812799 -0.041381702, + -0.0043100398 -0.0643555 -0.036584198, + 0 -0.066346399 -0.031670202, + 0.0045368699 -0.067751698 -0.0266569, + 0.0092211496 -0.068548203 -0.021561, + 0.0139712 -0.068723001 -0.016399899, + 0.018704399 -0.068273298 -0.0111913, + 0.0233387 -0.067207798 -0.00595264, + 0.0277937 -0.065544903 -0.00070199103, + 0.031992 -0.0633137 0.0045428299, + 0.035860799 -0.060552701 0.0097639598, + 0.0393328 -0.057309899 0.0149436, + 0.0423472 -0.053640999 0.020064101, + 0.044851098 -0.049609501 0.025108, + 0.046799898 -0.045285299 0.030058, + 0.048158601 -0.040743399 0.034897499, + 0.0489018 -0.036062699 0.0396096, + 0.049014699 -0.031325001 0.044178501, + 0.0484928 -0.026613399 0.048588499, + 0.047342401 -0.022011301 0.052824501, + 0.044096999 -0.020967901 0.056869399, + 0.045506801 -0.0175715 0.0568721, + 0.042951901 -0.0163374 0.059973799, + 0.044430502 -0.020336101 0.056869902, + 0.049848199 -0.0155051 0.052829701, + 0.050769702 -0.0121411 0.052832302, + 0.046853598 -0.0136183 0.0568753, + 0.052814402 -0.016421899 0.048596598, + 0.051602099 -0.0199128 0.048593901, + 0.054265 -0.020935001 0.0441867, + 0.052747902 -0.0245129 0.044183899, + 0.055098802 -0.025600201 0.0396179, + 0.053268 -0.029223301 0.039615002, + 0.0553036 -0.0303351 0.034905799, + 0.053155798 -0.033961099 0.0349029, + 0.054877602 -0.035056598 0.0300662, + 0.052415099 -0.038643699 0.030063299, + 0.053829901 -0.039682101 0.0251159, + 0.051060501 -0.043189101 0.0251131, + 0.05218 -0.044131499 0.0200717, + 0.049116898 -0.047518201 0.020068999, + 0.049957599 -0.0483271 0.0149507, + 0.046618901 -0.051556099 0.0149482, + 0.047201999 -0.052196499 0.0097706104, + 0.043610699 -0.055232801 0.0097681899, + 0.043961398 -0.055672701 0.0045489101, + 0.040144999 -0.0584847 0.0045466698, + 0.040292501 -0.058695398 -0.00069653703, + 0.036281999 -0.0612556 -0.00069857598, + 0.036258802 -0.061212201 -0.00594786, + 0.032088999 -0.063497402 -0.0059496802, + 0.031930499 -0.0631795 -0.0111872, + 0.0276387 -0.065171003 -0.0111888, + 0.0273825 -0.064562798 -0.016396601, + 0.023008199 -0.0662475 -0.016398, + 0.022693699 -0.065337501 -0.0215584, + 0.0182778 -0.066707499 -0.021559499, + 0.0179454 -0.06549 -0.0266551, + 0.0135296 -0.066542402 -0.026655899, + 0.0132203 -0.065016396 -0.031669199, + 0.0088464599 -0.065754101 -0.031669799, + 0.0086008403 -0.063923903 -0.0365838, + 0.0043100398 -0.0643555 -0.036584198, + 0.0041680299 -0.0622303 -0.0413821, + 0 -0.0623696 -0.041382201, + 0.0030794099 -0.059884202 -0.046047699, + -0.0041680299 -0.0622303 -0.0413821, + -0.0030794099 -0.059884202 -0.046047699, + 0 -0.064499602 -0.036584299, + 0.0044331299 -0.0661982 -0.031670101, + 0.0090534696 -0.067297399 -0.026656499, + 0.0137802 -0.067779303 -0.021560401, + 0.018531101 -0.067636304 -0.0163991, + 0.0232234 -0.066871598 -0.0111902, + 0.0277759 -0.065498799 -0.0059512798, + 0.0321096 -0.063542202 -0.00070039701, + 0.0361492 -0.061035499 0.00454464, + 0.039824702 -0.058022302 0.0097659696, + 0.043072 -0.054554701 0.0149458, + 0.0458344 -0.0506928 0.020066399, + 0.048063099 -0.046503 0.0251105, + 0.0497186 -0.0420583 0.0300606, + 0.050770599 -0.0374359 0.034900099, + 0.051199298 -0.032715902 0.039612301, + 0.0509951 -0.0279814 0.044181101, + 0.050159499 -0.023315201 0.0485911, + 0.048704099 -0.018800201 0.052827001, + 0.0464538 -0.0151391 0.0568741, + 0.0455979 -0.017337499 0.056872301, + -0.0040034 -0.059788998 -0.046047602, + 0.0040034 -0.059788998 -0.046047602, + 0.047853399 -0.0098144598 0.056878299, + 0.046619602 -0.0145083 0.056874599, + 0.041142099 -0.0119671 0.062881298, + 0.038747001 -0.0079624997 0.065579496, + 0.035827 -0.0044044098 0.068056703, + 0.032453399 -0.00136384 0.0703023, + 0.0246769 0.00293737 0.074061297, + 0.0287071 0.00109928 0.0723067, + 0.0204577 0.0041163401 0.075558499, + 0.0161481 0.00461622 0.076791897, + 0.0118488 0.0044317399 0.077756301, + 0.0076598101 0.0035721699 0.078447603, + 0.0442922 -0.020598199 0.056869701, + 0.040132798 -0.0277474 0.056864001, + -0.0079920599 -0.059378002 -0.0460473, + 0.0079920599 -0.059378002 -0.0460473, + -0.019665999 0.0566766 -0.045954902, + -0.0197961 0.057036102 -0.0453148, + -0.018735001 0.057036601 -0.0459546, + -0.023406001 0.0552308 -0.045956001, + -0.022928899 0.057034399 -0.043240398, + -0.0209495 0.057035498 -0.044609498, + -0.0207205 0.057035699 -0.0447574, + -0.032471299 0.0570269 -0.033736899, + -0.0308927 0.057028499 -0.035732199, + -0.0328849 0.0555497 -0.036488701, + -0.033942599 0.057025202 -0.031661801, + -0.0365199 0.053229298 -0.0364905, + -0.0339997 0.057025202 -0.031571802, + -0.033762701 0.057025399 -0.031915501, + -0.031801298 0.053724099 -0.041289698, + -0.0302449 0.057029098 -0.0364873, + -0.030079801 0.057029199 -0.0366797, + -0.028806301 0.057030302 -0.0380507, + -0.028144101 0.055728301 -0.0412881, + -0.029966 0.0520177 -0.045958601, + -0.028409099 0.0570307 -0.0384783, + -0.026659399 0.057032 -0.040172499, + -0.0253777 0.057032902 -0.041286498, + -0.024479499 0.054815799 -0.045956399, + -0.024832301 0.0570333 -0.041760501, + -0.0241739 0.057033699 -0.0422724, + -0.027024901 0.053517699 -0.045957401, + -0.039937399 0.044813801 -0.045964301, + -0.0386739 0.049006298 -0.041293502, + -0.0432849 0.047887001 -0.036494799, + -0.047709402 0.0461662 -0.031580601, + -0.051870801 0.043875199 -0.026567999, + -0.055696901 0.041054901 -0.0214737, + -0.059121698 0.037754901 -0.016315101, + -0.062086102 0.034033101 -0.0111098, + -0.064538799 0.029953901 -0.0058752699, + -0.066437602 0.025588401 -0.000629424, + -0.067749403 0.021012301 0.0046099699, + -0.0684513 0.016304901 0.0098251598, + -0.068530999 0.0115478 0.0149984, + -0.067986399 0.0068234699 0.0201122, + -0.066826299 0.0022142199 0.025149301, + -0.065069899 -0.0021995001 0.0300924, + -0.0627468 -0.0063401898 0.034924898, + -0.059896201 -0.0101349 0.039630201, + -0.056566499 -0.0135157 0.044192601, + -0.052814402 -0.016421899 0.048596598, + -0.048704099 -0.018800201 0.052827001, + -0.044430502 -0.020336101 0.056869902, + -0.0455979 -0.017337499 0.056872301, + -0.042951901 -0.0163374 0.059973799, + -0.0464538 -0.0151391 0.0568741, + -0.045506801 -0.0175715 0.0568721, + -0.050769702 -0.0121411 0.052832302, + -0.0537907 -0.0128577 0.0485995, + -0.049848199 -0.0155051 0.052829701, + -0.046853598 -0.0136183 0.0568753, + -0.046619602 -0.0145083 0.056874599, + -0.0573406 -0.0097073196 0.0441957, + -0.060437299 -0.00611164 0.039633401, + -0.063028298 -0.0021351101 0.034928199, + -0.065069899 0.0021515801 0.030095801, + -0.066527799 0.00667272 0.025152801, + -0.067377701 0.0113492 0.0201158, + -0.067605801 0.016099401 0.015002, + -0.067208901 0.0208406 0.0098287696, + -0.0661944 0.025490601 0.0046135401, + -0.064580098 0.029968901 -0.00062593498, + -0.062394299 0.034197699 -0.0058718901, + -0.0596749 0.038104001 -0.0111066, + -0.0564688 0.041619599 -0.0163121, + -0.052831501 0.044683401 -0.0214708, + -0.0488258 0.0472419 -0.0265653, + -0.044521 0.049249802 -0.031578202, + -0.039991699 0.050671201 -0.036492601, + -0.035316501 0.051479999 -0.041291501, + -0.0351368 0.048672002 -0.045961302, + -0.037136801 0.047064699 -0.045962501, + -0.033925999 0.049455401 -0.045960601, + -0.030559501 0.0516336 -0.045958899, + -0.041133799 0.0521136 -0.0315759, + -0.0455628 0.050397702 -0.026562801, + -0.0497302 0.0481124 -0.021468099, + -0.053563699 0.045298301 -0.016309099, + -0.056997199 0.042004701 -0.0111035, + -0.059971198 0.038288899 -0.00586863, + -0.0624342 0.034215301 -0.00062255398, + -0.064343698 0.029854899 0.0046170098, + -0.065666303 0.0252831 0.0098323002, + -0.066378698 0.0205789 0.0150056, + -0.066468097 0.015824201 0.020119401, + -0.065932199 0.0111013 0.025156301, + -0.064779297 0.0064928802 0.030099301, + -0.063028298 0.0020794901 0.0349316, + -0.0607084 -0.0020612199 0.039636701, + -0.057858501 -0.0058558802 0.044198699, + -0.054526798 -0.00923621 0.048602398, + -0.051464502 -0.0087230997 0.052835099, + -0.0550193 -0.00557373 0.0486053, + -0.058118101 -0.0019783201 0.044201799, + -0.0607084 0.0019981 0.039639901, + -0.0627468 0.0062845601 0.034934901, + -0.064199403 0.0108051 0.0301027, + -0.065042198 0.0154804 0.0251598, + -0.065261699 0.020228401 0.020122901, + -0.064855203 0.024966599 0.0150091, + -0.063830398 0.0296127 0.0098357499, + -0.062205698 0.0340859 0.0046203798, + -0.060009498 0.038309101 -0.00061929401, + -0.057280101 0.042208999 -0.0058655101, + -0.0540649 0.045717798 -0.0111005, + -0.050419401 0.048774801 -0.0163064, + -0.046406701 0.0513267 -0.021465501, + -0.042096298 0.053328499 -0.0265604, + -0.037562799 0.054744702 -0.031573799, + -0.035306901 0.057023499 -0.029510099, + -0.039129999 0.0570172 -0.0216171, + -0.0391909 0.057017099 -0.021459401, + -0.0484211 -0.0059232302 0.056881402, + -0.048099499 -0.0081602801 0.056879599, + -0.045602102 -0.00558487 0.0599824, + -0.048563998 -0.0049293302 0.056882199, + -0.041967601 -0.0086178305 0.062884003, + -0.0379849 -0.0110546 0.065577, + -0.033744901 -0.0128519 0.068049997, + -0.029343801 -0.0139798 0.070292301, + -0.024881201 -0.0144228 0.072294302, + -0.020457899 -0.0141801 0.074047603, + -0.016173501 -0.0132654 0.0755447, + -0.0121248 -0.0117071 0.076778904, + -0.00840325 -0.0095472597 0.077745199, + -0.0050933301 -0.0068404102 0.078439303, + -0.00227056 -0.0036533701 0.0788581, + -0.00197427 -0.0038245099 0.078858003, + -0.0039400999 -0.00756966 0.078438699, + -0.00166518 -0.0039711199 0.078857899, + -0.0450087 -0.00923636 0.059979498, + -0.047449399 -0.0113515 0.056877099, + -0.0441234 -0.0128283 0.0599766, + -0.041142099 -0.0119671 0.062881298, + -0.040049799 -0.0152389 0.062878698, + -0.036976401 -0.0140755 0.065574601, + -0.035728101 -0.0170053 0.065572299, + -0.0326056 -0.0155258 0.068047903, + -0.031254999 -0.0180992 0.068045802, + -0.028128199 -0.016295901 0.070290402, + -0.026730301 -0.0185066 0.070288703, + -0.0236446 -0.0163783 0.072292797, + -0.0222547 -0.018228 0.0722913, + -0.019255299 -0.0157804 0.074046403, + -0.017927799 -0.0172788 0.074045204, + -0.0150585 -0.0145241 0.075543597, + -0.0138458 -0.0156889 0.075542703, + -0.0111484 -0.012645 0.076778203, + -0.0100996 -0.0135013 0.076777503, + -0.0076127499 -0.0101926 0.0777447, + -0.00677288 -0.0107723 0.077744201, + -0.0045314101 -0.0072283498 0.078438997, + -0.047871601 -0.0097453604 0.056878399, + -0.047853399 -0.0098144598 0.056878299, + -0.038697701 -0.0184124 0.062876202, + -0.034247998 -0.0198253 0.065569997, + -0.0297016 -0.0205558 0.068043903, + -0.025158901 -0.020597599 0.070286997, + -0.0207204 -0.0199598 0.072289899, + -0.016484 -0.018665601 0.074044101, + -0.0125433 -0.016752301 0.075541899, + -0.00898539 -0.0142703 0.076776899, + -0.0058890898 -0.0112826 0.077743798, + -0.00332325 -0.00786239 0.078438498, + -0.00134529 -0.0040924498 0.078857802, + -0.00101668 -0.0041876701 0.078857698, + -0.0020290101 -0.00829452 0.078438103, + -0.00068147201 -0.0042560301 0.078857601, + -0.039782699 -0.0230163 0.059968501, + -0.041501898 -0.019740701 0.059971102, + -0.042769101 -0.0234848 0.056867398, + -0.037094701 -0.0214667 0.062873699, + -0.0352511 -0.0243821 0.062871397, + -0.032545902 -0.022516999 0.065567903, + -0.030632701 -0.025063099 0.065565899, + -0.027955599 -0.022879301 0.068042003, + -0.0260283 -0.025054701 0.068040296, + -0.0234244 -0.0225555 0.070285499, + -0.021538001 -0.0243674 0.070284002, + -0.0190518 -0.021562601 0.072288699, + -0.017259501 -0.0230259 0.0722875, + -0.0149334 -0.0199317 0.074043103, + -0.0132858 -0.021068901 0.074042097, + -0.0111595 -0.017707501 0.075541101, + -0.0097032702 -0.0185482 0.075540401, + -0.0078128902 -0.0149473 0.076776303, + -0.0065897098 -0.0155277 0.076775901, + -0.0049671 -0.0117201 0.0777435, + -0.0040128902 -0.012082 0.077743202, + -0.00268483 -0.0081045702 0.078438297, + -0.0442922 -0.020598199 0.056869701, + -0.041125 -0.0262964 0.0568652, + -0.033178799 -0.0271398 0.062869199, + -0.0285208 -0.0274469 0.065563999, + -0.0239322 -0.027068 0.068038702, + -0.019511901 -0.0260217 0.070282698, + -0.0153554 -0.024340199 0.072286397, + -0.0115522 -0.022069899 0.074041396, + -0.0081841396 -0.019269099 0.075539902, + -0.00532379 -0.0160078 0.076775499, + -0.0030326699 -0.0123659 0.077743001, + -0.00136003 -0.0084311096 0.078437999, + -0.00034184399 -0.00429729 0.078857601, + 0 -0.0043110801 0.078857601, + 0 -0.0085408501 0.078437902, + 0.00034184399 -0.00429729 0.078857601, + 0.00068222702 -0.0085133901 0.078437902, + 0.00068147201 -0.0042560301 0.078857601, + 0 -0.0127341 0.077742703, + -0.00101969 -0.012693 0.077742703, + -0.0013528001 -0.016818499 0.076774798, + -0.0026968201 -0.0166553 0.076774999, + -0.0033493401 -0.020669499 0.075538799, + -0.0049968399 -0.0203331 0.075539, + -0.0059489501 -0.0241949 0.074039698, + -0.0078717899 -0.0236379 0.0740401, + -0.0090979896 -0.027309399 0.072284102, + -0.0112613 -0.026489001 0.072284698, + -0.012731 -0.0299366 0.070279598, + -0.0150941 -0.028815299 0.0702805, + -0.0167719 -0.032010399 0.068034701, + -0.019288899 -0.030557301 0.068035901, + -0.021136099 -0.033476301 0.065559201, + -0.0237571 -0.031667199 0.065560602, + -0.0257317 -0.034292798 0.062863499, + -0.028403699 -0.032111298 0.062865198, + -0.0304619 -0.034432199 0.0599594, + -0.033129901 -0.031869601 0.059961401, + -0.0327111 -0.0362131 0.056857299, + -0.035583101 -0.0291005 0.059963599, + -0.037242699 -0.031530902 0.056860998, + -0.0308914 -0.0297217 0.062867098, + -0.026224 -0.029653 0.065562204, + -0.021680901 -0.028906301 0.068037197, + -0.0173593 -0.027507501 0.070281498, + -0.0133517 -0.025497099 0.072285503, + -0.0097435704 -0.022927999 0.074040703, + -0.0066119302 -0.019865399 0.075539403, + -0.0040233498 -0.016384499 0.076775201, + -0.0020327701 -0.0125701 0.0777428, + -0.00068222702 -0.0085133901 0.078437902, + -0.038679998 -0.029872101 0.056862298, + -0.037790801 -0.030898301 0.056861501, + -0.0228929 -0.036252402 0.062861897, + -0.018378099 -0.035068698 0.065557897, + -0.0141461 -0.0332563 0.068033703, + -0.0102853 -0.0308642 0.070278801, + -0.00687563 -0.027953099 0.072283603, + -0.0039875298 -0.0245953 0.074039303, + -0.00168012 -0.0208722 0.075538598, + 0 -0.016873 0.076774798, + 0.00101969 -0.012693 0.077742703, + 0.00136003 -0.0084311096 0.078437999, + 0.00101668 -0.0041876701 0.078857698, + 0.00134529 -0.0040924498 0.078857802, + 0.00268483 -0.0081045702 0.078438297, + 0.00166518 -0.0039711199 0.078857899, + -0.0245518 -0.038873401 0.059955899, + -0.024857899 -0.0420109 0.056852698, + -0.021348 -0.0407231 0.059954401, + -0.019905601 -0.037977099 0.062860601, + -0.0167892 -0.039455701 0.062859401, + -0.0155008 -0.036433902 0.065556802, + -0.012523 -0.037563201 0.0655559, + -0.0114286 -0.034286998 0.068032898, + -0.00863693 -0.035095599 0.068032302, + -0.0077729002 -0.0315919 0.070278302, + -0.00521011 -0.032115102 0.070277803, + -0.0046086698 -0.0284159 0.072283201, + -0.0023118299 -0.028694799 0.072283, + -0.0020002499 -0.0248366 0.074039102, + 0 -0.0249172 0.074039102, + 0 -0.020939801 0.075538501, + 0.00168012 -0.0208722 0.075538598, + 0.0013528001 -0.016818499 0.076774798, + 0.0026968201 -0.0166553 0.076774999, + 0.0020327701 -0.0125701 0.0777428, + 0.0030326699 -0.0123659 0.077743001, + 0.0020290101 -0.00829452 0.078438103, + -0.0264073 -0.0411359 0.056853399, + -0.026096299 -0.041311499 0.056853201, + -0.0135639 -0.040679 0.062858403, + -0.0094640302 -0.038449299 0.0655552, + -0.0057892599 -0.035677001 0.068031803, + -0.00261353 -0.032430399 0.070277601, + 0 -0.0287879 0.072282903, + 0.0020002499 -0.0248366 0.074039102, + 0.0033493401 -0.020669499 0.075538799, + 0.0040233498 -0.016384499 0.076775201, + 0.0040128902 -0.012082 0.077743202, + 0.00332325 -0.00786239 0.078438498, + 0.00197427 -0.0038245099 0.078858003, + 0.0039400999 -0.00756966 0.078438699, + 0.00227056 -0.0036533701 0.0788581, + 0.0049671 -0.0117201 0.0777435, + 0.00532379 -0.0160078 0.076775499, + 0.0049968399 -0.0203331 0.075539, + 0.0039875298 -0.0245953 0.074039303, + 0.0023118299 -0.028694799 0.072283, + 0 -0.032535698 0.070277497, + -0.0029040501 -0.036027301 0.068031497, + -0.0063436599 -0.039086401 0.065554701, + -0.0102507 -0.041638698 0.062857702, + -0.0145468 -0.043620799 0.059952099, + -0.016016001 -0.046165999 0.056849401, + -0.0128843 -0.047085602 0.056848601, + -0.0068709301 -0.0423287 0.062857099, + -0.00318215 -0.039470199 0.065554403, + 0 -0.036144301 0.0680314, + 0.00261353 -0.032430399 0.070277601, + 0.0046086698 -0.0284159 0.072283201, + 0.0059489501 -0.0241949 0.074039698, + 0.0066119302 -0.019865399 0.075539403, + 0.0065897098 -0.0155277 0.076775901, + 0.0058890898 -0.0112826 0.077743798, + 0.0045314101 -0.0072283498 0.078438997, + 0.00255212 -0.0034590301 0.078858301, + 0.0050933301 -0.0068404102 0.078439303, + 0.0028171299 -0.0032427199 0.078858398, + 0.00677288 -0.0107723 0.077744201, + 0.0078128902 -0.0149473 0.076776303, + 0.0081841396 -0.019269099 0.075539902, + 0.0078717899 -0.0236379 0.0740401, + 0.00687563 -0.027953099 0.072283603, + 0.00521011 -0.032115102 0.070277803, + 0.0029040501 -0.036027301 0.068031497, + 0 -0.039598498 0.065554298, + -0.00344664 -0.042744402 0.062856801, + -0.0073688198 -0.045389902 0.059950698, + -0.0097190896 -0.0478529 0.056848001, + -0.00782206 -0.048181299 0.0568478, + -0.00650266 -0.0484096 0.056847598, + -0.058288701 -0.0138541 -0.046011001, + -0.057543401 -0.0169563 -0.046013501, + -0.059643202 0.0060383398 -0.045995198, + -0.0590882 0.0100029 -0.045992099, + -0.0572455 0.0177959 -0.045985799, + -0.0528684 -0.0283347 -0.046022601, + -0.0543552 -0.0251863 -0.046020102, + -0.055498298 -0.022765599 -0.046018101, + -0.058232799 -0.0223951 -0.041350301, + -0.0585334 -0.027133301 -0.0365545, + -0.058204498 -0.031871799 -0.031642798, + -0.057253201 -0.036527898 -0.026632, + -0.055696901 -0.041020699 -0.0215391, + -0.053563699 -0.045272298 -0.016381299, + -0.050891101 -0.0492092 -0.0111761, + -0.0477258 -0.052763201 -0.00594114, + -0.044122901 -0.0558732 -0.00069428998, + -0.040144999 -0.0584847 0.0045466698, + -0.035860799 -0.060552701 0.0097639598, + -0.031344801 -0.062041201 0.0149398, + -0.0266751 -0.062923603 0.0200567, + -0.0219329 -0.063183904 0.025097201, + -0.0172008 -0.062816903 0.030044099, + -0.0125614 -0.061827701 0.034880701, + -0.0080961604 -0.060231801 0.0395904, + -0.00388403 -0.058056001 0.0441572, + 0 -0.055335801 0.0485656, + 0 -0.052233599 0.052800398, + -0.00369344 -0.0552123 0.048565701, + -0.00775071 -0.057666901 0.044157501, + -0.012099 -0.0595566 0.039590899, + -0.0166611 -0.060850699 0.034881499, + -0.021356501 -0.0615278 0.0300451, + -0.0261028 -0.061578002 0.025098501, + -0.0308173 -0.061001401 0.0200582, + -0.035417899 -0.059808999 0.0149416, + -0.039824702 -0.058022302 0.0097659696, + -0.043961398 -0.055672701 0.0045489101, + -0.0477564 -0.0528013 -0.00069184398, + -0.051143799 -0.049457699 -0.0059385002, + -0.0540649 -0.045700099 -0.0111733, + -0.0564688 -0.0415936 -0.0163783, + -0.058313601 -0.0372089 -0.021536, + -0.059566502 -0.032622099 -0.0266289, + -0.060205001 -0.0279129 -0.031639598, + -0.060217001 -0.023163 -0.036551401, + -0.0596008 -0.018455399 -0.041347198, + -0.057271801 -0.0177278 -0.0460141, + -0.0559403 -0.021509999 -0.046017099, + 0 -0.048889801 0.0568472, + 0.0032580299 -0.048703499 0.0568473, + 0 -0.0459847 0.059950199, + -0.0036964 -0.0458358 0.0599503, + -0.0032580299 -0.048703499 0.0568473, + 0 -0.0428834 0.062856697, + 0.00318215 -0.039470199 0.065554403, + 0.0057892599 -0.035677001 0.068031803, + 0.0077729002 -0.0315919 0.070278302, + 0.0090979896 -0.027309399 0.072284102, + 0.0097435704 -0.022927999 0.074040703, + 0.0097032702 -0.0185482 0.075540401, + 0.00898539 -0.0142703 0.076776899, + 0.0076127499 -0.0101926 0.0777447, + 0.00562221 -0.00640865 0.078439601, + 0.0030638699 -0.0030056599 0.078858599, + 0 -6.29063e-005 0.079000004, + -0.0055678501 -0.0485714 0.056847401, + -0.0039265598 -0.048665199 0.056847401, + -0.0487464 0.0111627 -0.0459911, + -0.047194201 0.0165505 -0.045986801, + -0.0487464 0.0111707 -0.055991098, + -0.047194201 0.0165585 -0.055986799, + -0.049685601 0.0056428602 -0.055995502, + -0.049685601 0.0056349002 -0.0459955, + -0.050000001 4.4591801e-005 -0.056000002, + -0.050000001 3.6629001e-005 -0.046, + -0.011126 0.0487829 -0.045961201, + -0.00559822 0.049722299 -0.0459604, + -0.011126 0.048790898 -0.055961199, + -0.00559822 0.049730301 -0.055960398, + -0.016514 0.047238801 -0.055962399, + -0.016514 0.047230799 -0.045962401, + -0.016514 -0.047149599 -0.056037601, + -0.011126 -0.0487017 -0.056038801, + -0.016514 -0.047157601 -0.046037599, + -0.011126 -0.048709702 -0.046038799, + -0.0216942 -0.0450119 -0.046035901, + -0.0216942 -0.045003898 -0.056035899, + -0.0266016 -0.042299598 -0.046033699, + -0.0266016 -0.0422916 -0.056033701, + -0.0311745 -0.039055001 -0.046031099, + -0.0353553 -0.035318699 -0.0460281, + -0.0311745 -0.039046999 -0.0560311, + -0.0353553 -0.035310701 -0.056028102, + -0.039091598 -0.0311378 -0.046024799, + -0.039091598 -0.0311298 -0.056024801, + -0.049685601 -0.00556164 -0.0460044, + -0.049685601 -0.00555368 -0.056004401, + -0.0487464 -0.0110815 -0.056008801, + -0.0487464 -0.0110895 -0.046008799, + -0.047194201 -0.0164693 -0.0560131, + -0.045048401 -0.021649599 -0.056017298, + -0.042336199 -0.026557 -0.056021199, + -0.045048401 0.021738799 -0.055982701, + -0.042336199 0.026646201 -0.055978801, + -0.039091598 0.031219 -0.055975199, + -0.0353553 0.035399899 -0.055971801, + -0.0311745 0.039136201 -0.055968899, + -0.0266016 0.042380799 -0.055966299, + -0.0216942 0.045093101 -0.055964101, + -0.00559822 -0.049641099 -0.056039501, + 0 -0.049955402 -0.056039799, + 0.00559822 -0.049641099 -0.056039501, + 0.011126 -0.0487017 -0.056038801, + 0.016514 -0.047149599 -0.056037601, + 0 0.0500446 -0.055960201, + 0.00559822 0.049730301 -0.055960398, + 0.011126 0.048790898 -0.055961199, + 0.016514 0.047238801 -0.055962399, + 0.0216942 -0.045003898 -0.056035899, + 0.0266016 -0.0422916 -0.056033701, + 0.0311745 -0.039046999 -0.0560311, + 0.0353553 -0.035310701 -0.056028102, + 0.039091598 -0.0311298 -0.056024801, + 0.042336199 -0.026557 -0.056021199, + 0.045048401 -0.021649599 -0.056017298, + 0.047194201 -0.0164693 -0.0560131, + 0.0487464 -0.0110815 -0.056008801, + 0.049685601 -0.00555368 -0.056004401, + 0.050000001 4.4591801e-005 -0.056000002, + 0.049685601 0.0056428602 -0.055995502, + 0.0487464 0.0111707 -0.055991098, + 0.047194201 0.0165585 -0.055986799, + 0.0216942 0.045093101 -0.055964101, + 0.0266016 0.042380799 -0.055966299, + 0.0311745 0.039136201 -0.055968899, + 0.0353553 0.035399899 -0.055971801, + 0.039091598 0.031219 -0.055975199, + 0.042336199 0.026646201 -0.055978801, + 0.045048401 0.021738799 -0.055982701, + -0.047194201 -0.0164773 -0.046013098, + -0.042336199 0.026638201 -0.045978799, + -0.039091598 0.031211 -0.045975201, + -0.045048401 0.021730799 -0.0459827, + -0.0353553 0.035391901 -0.0459718, + -0.042336199 -0.026565 -0.046021201, + 0 0.050036602 -0.045960199, + 0.00559822 0.049722299 -0.0459604, + 0.011126 0.0487829 -0.045961201, + 0.016514 0.047230799 -0.045962401, + 0.0353553 -0.035318699 -0.0460281, + 0.0311745 -0.039055001 -0.046031099, + 0.039091598 -0.0311378 -0.046024799, + 0.0266016 -0.042299598 -0.046033699, + 0.0216942 -0.0450119 -0.046035901, + 0.016514 -0.047157601 -0.046037599, + 0.042336199 -0.026565 -0.046021201, + 0.045048401 -0.021657599 -0.0460173, + 0.050000001 3.6629001e-005 -0.046, + 0.049685601 -0.00556164 -0.0460044, + 0.049685601 0.0056349002 -0.0459955, + 0.0487464 0.0111627 -0.0459911, + 0.047194201 0.0165505 -0.045986801, + 0.045048401 0.021730799 -0.0459827, + 0.042336199 0.026638201 -0.045978799, + 0.039091598 0.031211 -0.045975201, + 0.0353553 0.035391901 -0.0459718, + 0.0311745 0.039128199 -0.045968901, + 0.0266016 0.0423728 -0.045966301, + 0.0216942 0.045085099 -0.045964099, + 0.0487464 -0.0110895 -0.046008799, + 0.047194201 -0.0164773 -0.046013098, + -0.016219201 0.056980301 0.024783, + -0.019645801 0.056982301 0.0222179, + -0.0226725 0.0569847 0.0191912, + -0.025237599 0.056987502 0.0157646, + -0.027288999 0.056990501 0.0120078, + -0.0287848 0.0569936 0.0079973703, + -0.0296946 0.056997001 0.00381483, + -0.029999999 0.057000399 -0.00045461199, + -0.0296946 0.0570038 -0.0047240499, + -0.0287848 0.0570071 -0.0089065898, + -0.027288999 0.0570103 -0.012917, + -0.025237599 0.057013299 -0.0166738, + -0.0226725 0.057016 -0.0201004, + -0.019645801 0.057018399 -0.023127099, + -0.016219201 0.0570205 -0.0256922, + -0.0124625 0.057022098 -0.0277436, + -0.0084519796 0.057023302 -0.029239399, + -0.0042694402 0.057023998 -0.030149201, + 0 0.0570243 -0.0304546, + 0.0042694402 0.057023998 -0.030149201, + 0.0084519796 0.057023302 -0.029239399, + 0.0124625 0.057022098 -0.0277436, + 0.016219201 0.0570205 -0.0256922, + 0.019645801 0.057018399 -0.023127099, + 0.0226725 0.057016 -0.0201004, + 0.025237599 0.057013299 -0.0166738, + 0.027288999 0.0570103 -0.012917, + 0.0287848 0.0570071 -0.0089065898, + 0.0296946 0.0570038 -0.0047240499, + 0.029999999 0.057000399 -0.00045461199, + 0.0296946 0.056997001 0.00381483, + 0.0287848 0.0569936 0.0079973703, + 0.027288999 0.056990501 0.0120078, + 0.025237599 0.056987502 0.0157646, + 0.0226725 0.0569847 0.0191912, + 0.019645801 0.056982301 0.0222179, + 0.016219201 0.056980301 0.024783, + 0.0124625 0.056978598 0.0268344, + 0.0084519796 0.056977499 0.028330199, + 0.0042694402 0.056976698 0.029239999, + 0 0.056976501 0.0295454, + -0.0042694402 0.056976698 0.029239999, + -0.0084519796 0.056977499 0.028330199, + -0.0124625 0.056978598 0.0268344, + 0 0.048719499 0.056924898, + 0.011126 -0.048709702 -0.046038799, + 0 -0.059884202 -0.046047699, + -0.00559822 -0.049649101 -0.046039499, + 0 -0.0499634 -0.046039801, + 0.00559822 -0.049649101 -0.046039499, + -0.0216942 0.045085099 -0.045964099, + -0.0266016 0.0423728 -0.045966301, + -0.0311745 0.039128199 -0.045968901, + -0.045048401 -0.021657599 -0.0460173 ] + + } + normal + Normal { + vector [ -0.080732398 -0.80280697 0.59074801, + -0.87336683 -0.17716296 -0.45369989, + -0.89605415 -0.18181401 -0.40500706, + -0.88189071 -0.24124691 -0.40505385, + -0.90315789 -0.24711697 -0.35105398, + -0.88461524 -0.30689305 -0.35110208, + -0.90242022 -0.3131201 -0.29596207, + -0.87947088 -0.37270597 -0.29600897, + -0.89384079 -0.37884492 -0.23984393, + -0.86653072 -0.43769485 -0.2398909, + -0.87751889 -0.44329295 -0.18289898, + -0.84594172 -0.50091285 -0.18294494, + -0.85365486 -0.50552696 -0.12536299, + -0.81797689 -0.56141496 -0.12540698, + -0.82259184 -0.5646289 -0.067357488, + -0.78304201 -0.61830598 -0.067400903, + -0.7847715 -0.61971766 -0.0091517642, + -0.74162585 -0.6707508 -0.0091930386, + -0.74074018 -0.6699962 0.049083009, + -0.69432783 -0.71798581 0.049043488, + -0.69113767 -0.71473461 0.10715895, + -0.64187592 -0.75928891 0.10712399, + -0.63672996 -0.75324887 0.16489698, + -0.58501893 -0.79408586 0.16486499, + -0.57830495 -0.78501791 0.22205897, + -0.52458578 -0.8218956 0.22202989, + -0.5167101 -0.80960417 0.27848107, + -0.46148878 -0.84231257 0.27845588, + -0.45289105 -0.82666713 0.33393303, + -0.39667225 -0.85507655 0.33390921, + -0.38778809 -0.83597416 0.38828808, + -0.331121 -0.86000401 0.38826799, + -0.322413 -0.83743799 0.441302, + -0.26574388 -0.85711557 0.44128579, + -0.25766206 -0.83109915 0.49283311, + -0.20162697 -0.84644789 0.49282095, + -0.19461392 -0.81705868 0.54271585, + -0.13963999 -0.82823288 0.54270697, + -0.13413294 -0.79562461 0.59075367, + -0.55724609 0.79325014 -0.24542002, + -0.53119618 0.80478728 -0.26485509, + -0.53119713 0.80478817 -0.26485005, + 0.61838388 -0.39158392 0.68136883, + 0.57769179 -0.36589089 0.72965479, + 0.078354336 -0.059684228 0.99513745, + 0.073371261 -0.065787368 0.99513251, + 0.12194496 -0.10880896 0.98655462, + 0.11285903 -0.11826903 0.98654723, + 0.15733507 -0.16455707 0.97373849, + 0.14363198 -0.17669699 0.9737289, + 0.18359594 -0.22563092 0.95675665, + 0.16491207 -0.23967113 0.95674551, + 0.20012005 -0.29065907 0.93566525, + 0.17615207 -0.30581611 0.93565333, + 0.20637804 -0.35814309 0.91057223, + 0.17693 -0.37359899 0.91056001, + 0.16717096 -0.44146189 0.88156974, + 0.187263 -0.49441099 0.84881699, + 0.14691103 -0.50788313 0.8488062, + 0.16204293 -0.56009674 0.81242466, + 0.116516 -0.57131797 0.81241602, + 0.12689905 -0.62213624 0.7725563, + 0.082371034 -0.67910028 0.72940934, + 0.12598699 -0.72830498 0.673572, + 0.13049302 -0.75430912 0.64342004, + 0.12738994 -0.75566363 0.6424517, + 0.13413794 -0.79562366 0.59075367, + -0.75384873 -0.5171718 -0.40527186, + -0.77202886 -0.52969491 -0.35127598, + -0.73491919 -0.58006114 -0.35131609, + -0.7497142 -0.5917871 -0.29617006, + -0.70848584 -0.64055282 -0.29620895, + -0.72006005 -0.65106505 -0.24005803, + -0.67496002 -0.69769901 -0.24009401, + -0.68351883 -0.70659381 -0.18310395, + -0.63477474 -0.75068069 -0.18313794, + -0.64056295 -0.7575739 -0.12554199, + -0.58854985 -0.79864883 -0.12557498, + -0.59186912 -0.80319917 -0.067543715, + -0.53686905 -0.84095514 -0.06757351, + -0.53805494 -0.8428579 -0.0093434388, + -0.48057407 -0.87690413 -0.0093707405, + -0.48000005 -0.87590313 0.048925407, + -0.42040494 -0.9060179 0.048900794, + -0.41847414 -0.9019013 0.10702103, + -0.35731608 -0.92783421 0.10700002, + -0.35445404 -0.92044812 0.16473502, + -0.29217416 -0.94207346 0.16471808, + -0.28881904 -0.93130523 0.22193307, + -0.22600199 -0.94851202 0.221919, + -0.15970999 -0.94711089 0.27834097, + -0.15673307 -0.92950535 0.33384812, + -0.094322346 -0.93789846 0.33384115, + -0.092209868 -0.91694367 0.38821584, + -0.030799396 -0.9210549 0.38821295, + -0.029989008 -0.89686823 0.44128013, + 0.029963303 -0.89686912 0.44128007, + 0.029052407 -0.86965519 0.49280411, + 0.087082677 -0.86577082 0.49280587, + 0.084054798 -0.83572 0.54268497, + 0.139641 -0.82824397 0.54268998, + 0.13413192 -0.79562253 0.59075665, + 0.18693706 -0.78488928 0.59076524, + 0.28760803 -0.68111104 0.67332709, + 0.29699194 -0.7032938 0.64588982, + 0.29713005 -0.70323515 0.64589018, + 0.28774303 -0.68105608 0.67332506, + 0.28762296 -0.68110693 0.67332494, + 0.29700598 -0.70328593 0.64589196, + 0.32491916 -0.7007404 0.63513035, + 0.33941492 -0.73194581 0.5908069, + 0.28982097 -0.75297487 0.59078991, + 0.30172089 -0.7838347 0.54274082, + 0.24872603 -0.80223614 0.54272705, + 0.25768897 -0.83109087 0.49283293, + 0.20161593 -0.84645069 0.49282083, + 0.20793693 -0.8729347 0.44130185, + 0.14919907 -0.88487339 0.4412922, + 0.15323192 -0.90873957 0.38821682, + 0.092210226 -0.91694623 0.38821009, + 0.094322659 -0.93790162 0.33383188, + 0.0315069 -0.94210702 0.33382899, + 0.032105003 -0.9599421 0.27835304, + -0.032088488 -0.95994264 0.27835292, + -0.032577712 -0.97452736 0.22189008, + -0.097582482 -0.97017586 0.22189297, + -0.098715343 -0.98139143 0.1646999, + -0.16401601 -0.97261012 0.16470702, + -0.16534093 -0.9804225 0.10692995, + -0.23046106 -0.96718723 0.10694202, + -0.23152398 -0.9716019 0.048849393, + -0.29591313 -0.95396435 0.048862819, + -0.29626688 -0.95505863 -0.0094304765, + -0.35940212 -0.93313533 -0.0094138738, + -0.35861009 -0.93103224 -0.067659318, + -0.41997278 -0.90501261 -0.067638367, + -0.41761822 -0.89989144 -0.12566006, + -0.47681883 -0.8699767 -0.12563595, + -0.47250873 -0.86206645 -0.18323989, + -0.52903694 -0.82858491 -0.18321298, + -0.52241391 -0.81816381 -0.24019094, + -0.57589269 -0.78145367 -0.24016188, + -0.56663501 -0.76884401 -0.29631701, + -0.61676812 -0.72925419 -0.29628605, + -0.60459632 -0.71481436 -0.35143119, + -0.65099823 -0.67284524 -0.35139811, + -0.63567132 -0.65695429 -0.40538019, + -0.67814827 -0.61303431 -0.40534419, + -0.65882432 -0.5955143 -0.45968822, + -0.64717919 -0.6016351 -0.46818212, + -0.64717716 -0.60163713 -0.46818212, + -0.61998111 -0.64070517 -0.45290211, + -0.63566327 -0.65695828 -0.40538618, + -0.59034425 -0.69794625 -0.40541914, + -0.60457629 -0.71482337 -0.35144717, + -0.55546206 -0.75360811 -0.35147804, + -0.56664997 -0.76883799 -0.29630399, + -0.51402819 -0.80496031 -0.29633412, + -0.52242488 -0.81815982 -0.24018094, + -0.46657878 -0.8512376 -0.24020588, + -0.47249213 -0.86207217 -0.18325604, + -0.4138529 -0.89170277 -0.18328096, + -0.41762978 -0.89988756 -0.12564895, + -0.35660613 -0.92576438 -0.12566805, + -0.35861704 -0.93103009 -0.067653105, + -0.29560095 -0.95291173 -0.067670286, + -0.29625386 -0.95506251 -0.0094428854, + -0.2318159 -0.97271365 -0.0094575966, + -0.23153891 -0.97159767 0.04886378, + -0.16614605 -0.98489034 0.048853718, + -0.16538306 -0.98041135 0.10696804, + -0.099528402 -0.98926902 0.106962, + -0.09873078 -0.98138773 0.16471295, + -0.032932609 -0.98579234 0.16470906, + -0.03255479 -0.97453266 0.22186993, + 0.032577798 -0.97453189 0.22186998, + 0.032088388 -0.95993865 0.27836692, + 0.096101798 -0.95565403 0.27836999, + 0.094311655 -0.93789953 0.33384085, + 0.15675999 -0.92950088 0.33384797, + 0.15325104 -0.90874225 0.38820308, + 0.21356708 -0.89648229 0.38821214, + 0.207946 -0.872935 0.44129699, + 0.26574111 -0.85710442 0.44130921, + 0.25765896 -0.8310889 0.49285194, + 0.31257886 -0.81201965 0.49286777, + 0.30170912 -0.78383428 0.54274815, + 0.353383 -0.76192302 0.54276502, + 0.33945197 -0.73194396 0.59078795, + 0.36864403 -0.67318708 0.64103109, + 0.38754675 -0.70763958 0.59080762, + 0.45073789 -0.62091386 0.6413278, + 0.45439973 -0.61723465 0.64229465, + 0.47832981 -0.64967173 0.59086978, + -0.51056582 -0.72064477 -0.46903482, + -0.47987211 -0.75132018 -0.45303512, + -0.49202606 -0.77039611 -0.40546307, + -0.43943921 -0.80154437 -0.40548718, + -0.45003113 -0.82091415 -0.35152808, + -0.39417216 -0.8491413 -0.35155013, + -0.40211117 -0.86629242 -0.29638514, + -0.34334198 -0.89121288 -0.29640496, + -0.34895182 -0.90582359 -0.24024189, + -0.28766602 -0.92710513 -0.24025904, + -0.29131296 -0.93890488 -0.18328798, + -0.22792903 -0.95626813 -0.18330202, + -0.23000702 -0.96503311 -0.12573001, + -0.16594192 -0.98380953 -0.067691669, + -0.099884041 -0.99269336 -0.067698725, + -0.100105 -0.994932 -0.0094542196, + -0.033396617 -0.99939746 -0.0094577642, + -0.033356711 -0.99825037 0.048821118, + 0.033350684 -0.99825054 0.048821077, + 0.033197489 -0.99371064 0.10694396, + 0.099528566 -0.98927063 0.10694696, + 0.098730989 -0.98138988 0.16469999, + 0.16405006 -0.97260433 0.16470706, + 0.16216795 -0.96148878 0.22190294, + 0.22600189 -0.94851351 0.22191289, + 0.28452596 -0.9173649 0.27836397, + 0.279223 -0.90031701 0.33386201, + 0.33869511 -0.87966532 0.33387813, + 0.331108 -0.86000901 0.38826799, + 0.38777816 -0.83597928 0.38828716, + 0.37757882 -0.8140406 0.44132978, + 0.43109792 -0.78699684 0.44135088, + 0.41798392 -0.76310885 0.49290389, + 0.467971 -0.73350197 0.492928, + 0.4516978 -0.70804965 0.54280275, + 0.47833988 -0.64966881 0.5908649, + 0.53593105 -0.55465007 0.63650703, + 0.56060094 -0.58012193 0.59091896, + 0.54199696 -0.64151996 0.54285496, + 0.51591998 -0.70059597 0.49294201, + 0.46799001 -0.73349798 0.49291599, + 0.48266807 -0.7564491 0.44138005, + 0.43109193 -0.78699785 0.44135493, + 0.38778883 -0.83597755 0.38827983, + 0.39667106 -0.85507512 0.33391404, + 0.33867186 -0.87966758 0.33389586, + 0.34510297 -0.89632189 0.27840796, + 0.28449208 -0.91736734 0.27839109, + 0.28882807 -0.93130237 0.22193308, + 0.2259959 -0.94851351 0.2219189, + 0.22861892 -0.95947462 0.16474794, + 0.16401504 -0.97260523 0.16473705, + 0.16534106 -0.98041838 0.10696804, + 0.099512376 -0.98927075 0.10696097, + 0.099971883 -0.99379188 0.048819393, + 0.033356689 -0.99825066 0.048815683, + 0.033396591 -0.99939764 -0.0094398661, + -0.033416301 -0.99939698 -0.0094398698, + -0.033342611 -0.99714637 -0.067730822, + -0.09985216 -0.99269462 -0.067727275, + -0.099292159 -0.98708063 -0.12574896, + -0.16351895 -0.96935779 -0.18332195, + -0.227918 -0.95626903 -0.183311, + -0.22506492 -0.94424963 -0.24028791, + -0.2876479 -0.92710662 -0.24027491, + -0.28302309 -0.91215229 -0.29643911, + -0.34331796 -0.89121586 -0.29642397, + -0.33654088 -0.87357372 -0.35158089, + -0.39415893 -0.84914291 -0.35156098, + -0.38488317 -0.8291114 -0.40551117, + -0.43943605 -0.80154514 -0.40548906, + -0.4267239 -0.77830583 -0.46059388, + -0.43610385 -0.7731927 -0.46041983, + -0.37465391 -0.80699581 -0.45649987, + -0.38489693 -0.82910991 -0.40550095, + -0.3286511 -0.85296017 -0.40552109, + -0.336573 -0.87357098 -0.35155699, + -0.2774511 -0.89410132 -0.35157311, + -0.28303707 -0.91215122 -0.29642907, + -0.2214649 -0.92901856 -0.29644185, + -0.22508407 -0.94424921 -0.24027206, + -0.16148399 -0.95717686 -0.24028197, + -0.16353095 -0.96935767 -0.18331194, + -0.0984338 -0.978113 -0.183319, + -0.09933152 -0.98708123 -0.12571403, + -0.033152398 -0.99151188 -0.12571798, + -0.033339206 -0.99714625 -0.067733817, + 0.033342604 -0.99714613 -0.067733809, + 0.033416294 -0.99939674 -0.0094577679, + 0.10008103 -0.99493438 -0.0094542336, + 0.099961542 -0.99379241 0.048828769, + 0.16614601 -0.98489112 0.048835907, + 0.16538307 -0.98041546 0.10693005, + 0.23049507 -0.96717924 0.10694102, + 0.22864705 -0.95947224 0.16472304, + 0.29217306 -0.94207025 0.16473804, + 0.28881884 -0.93130356 0.22193989, + 0.35038096 -0.9099279 0.22195597, + 0.34512308 -0.89631921 0.27839205, + 0.40421087 -0.87126368 0.27841192, + 0.39667794 -0.85507387 0.33390898, + 0.45288199 -0.82667202 0.333933, + 0.49571916 -0.77683032 0.38832614, + 0.48268005 -0.75644612 0.44137207, + 0.53210497 -0.72251797 0.44139794, + 0.51592201 -0.70059597 0.49294001, + 0.56155413 -0.66455817 0.49297011, + 0.54203105 -0.64150804 0.54283506, + 0.58362401 -0.60388798 0.54286498, + 0.56060195 -0.58012193 0.59091794, + 0.57076401 -0.516752 0.63811898, + 0.59805363 -0.54139769 0.59094864, + 0.57686299 -0.50036502 0.64565003, + 0.63227206 -0.43286306 0.64254308, + 0.60649323 -0.47944218 0.63427222, + 0.63286495 -0.50023293 0.59097296, + 0.5980677 -0.54139078 0.59094071, + 0.62261528 -0.56355327 0.54291624, + 0.58359396 -0.60389996 0.54288393, + 0.60461503 -0.62559807 0.49301907, + 0.56152487 -0.66456884 0.49298888, + 0.57914591 -0.68536884 0.44142887, + 0.53210098 -0.72251898 0.441401, + 0.54647726 -0.74198836 0.38835019, + 0.49572411 -0.77682918 0.38832209, + 0.50707895 -0.7945739 0.33395097, + 0.45289195 -0.82666987 0.33392498, + 0.46149218 -0.84231728 0.27843609, + 0.40420908 -0.87126416 0.27841306, + 0.35037896 -0.9099279 0.22195897, + 0.35444903 -0.92045009 0.16473502, + 0.29219496 -0.94206691 0.16471799, + 0.29455498 -0.94962686 0.10698698, + 0.23046003 -0.96718413 0.10697301, + 0.23152407 -0.97160125 0.048863713, + 0.16612692 -0.9848935 0.048853576, + 0.16632493 -0.98602551 -0.0094683357, + 0.10010498 -0.99493176 -0.009475668, + 0.099883743 -0.99269146 -0.06772723, + 0.033339314 -0.99714649 -0.067730829, + 0.033152409 -0.99151123 -0.12572403, + -0.033146109 -0.99151134 -0.12572405, + -0.032846406 -0.98250121 -0.18333705, + -0.098415703 -0.97811198 -0.18333399, + -0.097184002 -0.96582401 -0.24029, + -0.16148296 -0.95717674 -0.24028294, + -0.158886 -0.941737 -0.29645699, + -0.22146007 -0.92901838 -0.29644611, + -0.21708997 -0.91063589 -0.35158798, + -0.27744687 -0.89410156 -0.35157582, + -0.27091599 -0.87300599 -0.405543, + -0.32864422 -0.85296053 -0.40552625, + -0.32047781 -0.83172154 -0.45335773, + -0.26823306 -0.84261018 -0.46696812, + -0.26825413 -0.84260345 -0.46696821, + -0.35266599 -0.80935502 -0.46965, + -0.35267609 -0.80935121 -0.46964911, + -0.43426514 -0.76968431 -0.46797419, + -0.43424609 -0.76969516 -0.46797413, + -0.51056397 -0.72064596 -0.46903494, + -0.52755213 -0.71564919 -0.45775011, + -0.54238099 -0.73581702 -0.405458, + -0.49199307 -0.77040511 -0.40548605, + -0.50385803 -0.78903413 -0.35150003, + -0.45003301 -0.82091397 -0.35152599, + -0.45909619 -0.83749533 -0.29636511, + -0.40210891 -0.86629283 -0.29638693, + -0.40867686 -0.88049167 -0.24024491, + -0.34892592 -0.90582776 -0.24026394, + -0.35335013 -0.91736037 -0.18328606, + -0.29129505 -0.93890727 -0.18330404, + -0.29395297 -0.9475199 -0.12568898, + -0.23003709 -0.96502936 -0.12570305, + -0.23133509 -0.97051835 -0.067663923, + -0.16596092 -0.9838075 -0.067674272, + -0.16632704 -0.98602521 -0.0094683422, + -0.10008101 -0.99493414 -0.009475681, + -0.099961482 -0.99379289 0.048819393, + -0.033350695 -0.9982509 0.048815694, + -0.033197507 -0.99371225 0.10693002, + 0.033212889 -0.99371165 0.10692997, + 0.03294659 -0.98579162 0.16470994, + 0.098715238 -0.98138934 0.16471305, + 0.097581983 -0.97017086 0.22191498, + 0.16214602 -0.96148813 0.22192203, + 0.15971404 -0.94711024 0.27834105, + 0.21846002 -0.91695511 0.33386904, + 0.27919596 -0.90031791 0.33388197, + 0.27294597 -0.88020986 0.38824093, + 0.33112308 -0.86000818 0.38825709, + 0.32241488 -0.8374427 0.44129184, + 0.37760794 -0.81403786 0.44130993, + 0.41799384 -0.7631067 0.49289882, + 0.40345916 -0.73662525 0.5427742, + 0.45170707 -0.70804805 0.54279709, + 0.43389073 -0.68017656 0.59084564, + 0.35998198 -0.63809097 0.68062693, + 0.37562394 -0.66576493 0.64471996, + 0.41599199 -0.65213197 0.63377798, + 0.43391395 -0.68017292 0.59083295, + 0.38753876 -0.70764059 0.59081167, + 0.40344405 -0.73662704 0.54278308, + 0.35338601 -0.76192302 0.54276299, + 0.31259313 -0.81201929 0.49285918, + 0.3224 -0.83744299 0.441302, + 0.2657761 -0.85710531 0.44128615, + 0.27295607 -0.88021022 0.3882331, + 0.21355705 -0.89648122 0.3882201, + 0.21844597 -0.91695487 0.33387896, + 0.15673193 -0.92949766 0.33386987, + 0.15971 -0.94711 0.27834401, + 0.096142255 -0.95565951 0.27833688, + 0.097607218 -0.97017312 0.22189403, + 0.032554705 -0.97452813 0.22189003, + 0.032932505 -0.98579013 0.16472201, + -0.03294649 -0.98578966 0.16472194, + -0.033212807 -0.99371022 0.10694402, + -0.099512525 -0.98927224 0.10694702, + -0.099971846 -0.99379146 0.048828822, + -0.16612706 -0.98489434 0.048835918, + -0.16632493 -0.98602551 -0.0094700549, + -0.23181403 -0.97271413 -0.0094596306, + -0.23130298 -0.97052389 -0.06769269, + -0.29559106 -0.95291424 -0.067679115, + -0.29393384 -0.94752353 -0.12570594, + -0.35658583 -0.92576957 -0.12568694, + -0.35336292 -0.91735774 -0.18327396, + -0.41388407 -0.89169413 -0.18325302, + -0.40870291 -0.88048577 -0.24022195, + -0.46658611 -0.85123515 -0.24020006, + -0.45908299 -0.83749902 -0.29637501, + -0.51400888 -0.80496681 -0.29634994, + -0.50386518 -0.78903228 -0.35149413, + -0.5554769 -0.7536028 -0.35146591, + -0.54239893 -0.73581094 -0.40544495, + -0.5903489 -0.69794482 -0.40541491, + -0.57397205 -0.67853105 -0.45842305, + -0.58559376 -0.66871077 -0.45815486, + -0.58187693 -0.66461593 -0.46872693, + -0.58187103 -0.66462106 -0.46872705, + -0.43390891 -0.68016481 0.59084588, + -0.29713005 -0.70323515 0.64589018, + -0.29700598 -0.70328593 0.64589196, + -0.28762296 -0.68110693 0.67332494, + -0.28774303 -0.68105608 0.67332506, + -0.28760803 -0.68111104 0.67332709, + -0.29699194 -0.7032938 0.64588982, + -0.27736905 -0.72062218 0.6354292, + -0.28984082 -0.75296652 0.59079063, + -0.3394469 -0.73193181 0.59080589, + -0.35338283 -0.76192462 0.54276276, + -0.40345699 -0.73662001 0.54278302, + -0.41799191 -0.76310384 0.49290487, + -0.46798605 -0.73349303 0.49292707, + -0.48267007 -0.7564531 0.44137105, + -0.53210205 -0.72252005 0.44139805, + -0.54647797 -0.74198902 0.38834801, + -0.59477276 -0.70385176 0.38837886, + -0.60839695 -0.71992493 0.33400798, + -0.65513593 -0.67765194 0.33404297, + -0.66757208 -0.69046605 0.27857503, + -0.71217376 -0.64434779 0.2786119, + -0.72303325 -0.65412426 0.22213608, + -0.76509118 -0.6043781 0.22217706, + -0.77397019 -0.61134511 0.16500704, + -0.81307769 -0.55826783 0.16505094, + -0.81964803 -0.56273103 0.107289, + -0.85539681 -0.50673085 0.10733198, + -0.85934567 -0.50902283 0.049200781, + -0.89141202 -0.45051 0.0492476, + -0.89247721 -0.45100212 -0.009030072, + -0.92060924 -0.39038208 -0.008981402, + -0.91857976 -0.3894749 -0.067234188, + -0.94255197 -0.327234 -0.0671838, + -0.93726712 -0.32535303 -0.12520301, + -0.95690787 -0.26203796 -0.12515399, + -0.94825888 -0.25962397 -0.18275799, + -0.96349674 -0.19568396 -0.18270695, + -0.95143849 -0.19318709 -0.23967412, + -0.96222979 -0.12920597 -0.23962393, + -0.94675714 -0.12708202 -0.29580602, + -0.95314527 -0.063576914 -0.29575706, + -0.93433213 -0.062273506 -0.35092103, + -0.89081401 0.000361805 -0.454368, + -0.91233885 -0.060742892 -0.40490493, + -0.93433762 -0.062258378 -0.35090888, + -0.92807335 -0.12453304 -0.35095811, + -0.94675434 -0.12708904 -0.29581213, + -0.95143265 -0.19320093 -0.23968591, + -0.93639165 -0.25631392 -0.23973691, + -0.94826424 -0.25961205 -0.18274705, + -0.92879665 -0.32236889 -0.18279794, + -0.93726599 -0.32535499 -0.12520599, + -0.91343576 -0.38722891 -0.12525497, + -0.91858679 -0.38946092 -0.067219384, + -0.89051777 -0.44994789 -0.067267083, + -0.89248401 -0.45098901 -0.0090162102, + -0.86037499 -0.50958103 -0.0090621198, + -0.85934782 -0.5090189 0.049204789, + -0.82341927 -0.56530017 0.04915842, + -0.81963742 -0.56275028 0.10727005, + -0.78023499 -0.61622697 0.107227, + -0.77397788 -0.61133194 0.16501999, + -0.73142904 -0.66165906 0.16498101, + -0.7230382 -0.65411615 0.22214405, + -0.67774081 -0.70095384 0.22210594, + -0.66756523 -0.69047725 0.2785641, + -0.61996794 -0.73352593 0.27853096, + -0.60841286 -0.7199018 0.3340289, + -0.55899477 -0.75892663 0.33399886, + -0.54648 -0.74198598 0.38835099, + -0.49571976 -0.77683163 0.38832283, + -0.48267701 -0.75644398 0.44137901, + -0.431097 -0.78699499 0.44135499, + -0.41798621 -0.76311135 0.49289823, + -0.3533859 -0.7619217 0.54276484, + -0.30171889 -0.7838307 0.5427478, + -0.28982383 -0.7529825 0.59077865, + -0.22742806 -0.73372418 0.6402542, + -0.2388991 -0.77066529 0.59076422, + -0.20672196 -0.70445281 0.6789788, + -0.21520604 -0.7333172 0.64492816, + -0.17920801 -0.75249112 0.63375205, + -0.18693794 -0.78489071 0.59076273, + -0.23891385 -0.77065253 0.59077466, + -0.24872303 -0.80223709 0.54272705, + -0.30171111 -0.78383827 0.54274118, + -0.31258088 -0.8120237 0.49285981, + -0.37760395 -0.81402886 0.44132993, + -0.43109295 -0.78699887 0.44135195, + -0.49572277 -0.77682763 0.38832682, + -0.50707579 -0.79456967 0.33396584, + -0.55899179 -0.75893062 0.33399487, + -0.56960899 -0.773296 0.278494, + -0.61996406 -0.73353106 0.27852604, + -0.62941271 -0.74466163 0.22207789, + -0.67774528 -0.70094734 0.2221131, + -0.68561506 -0.70903808 0.16491501, + -0.73141104 -0.66168606 0.16495301, + -0.73732084 -0.66698581 0.10718198, + -0.78023314 -0.61623007 0.10722301, + -0.78383088 -0.61902696 0.049139194, + -0.82343298 -0.56527799 0.049182501, + -0.8244189 -0.56590694 -0.0090964492, + -0.86038059 -0.50957179 -0.0090520652, + -0.85848498 -0.508403 -0.067305401, + -0.89052188 -0.44994095 -0.067259796, + -0.91343302 -0.387234 -0.12526, + -0.90518087 -0.38368893 -0.18283999, + -0.92879987 -0.32236296 -0.18279198, + -0.93639034 -0.25631708 -0.23973909, + -0.92133522 -0.25214705 -0.29591107, + -0.92807162 -0.12453695 -0.35096088, + -0.90622145 -0.12155592 -0.40495276, + -0.91233987 -0.060741194 -0.40490294, + -0.88932014 -0.059161909 -0.45344207, + -0.87776387 -0.11715698 -0.46454793, + -0.87776226 -0.11716903 -0.46454811, + -0.8825779 -0.026459597 -0.46942094, + -0.88257676 -0.026497794 -0.46942088, + -0.88432932 0.064439826 -0.46239519, + -0.8846311 0.059577309 -0.46247005, + -0.91233885 0.061385993 -0.40480796, + -0.88363189 0.11920699 -0.45275193, + -0.90622067 0.12220596 -0.40475884, + -0.91233975 0.061387584 -0.4048059, + -0.93433326 0.062816918 -0.35082108, + -0.95314753 -0.06356997 -0.29575086, + -0.96871877 -0.064656988 -0.23958994, + -0.96222287 -0.12922598 -0.23964097, + -0.97442126 -0.13091303 -0.18266104, + -0.963494 -0.195692 -0.182713, + -0.97228235 -0.19752407 -0.12510504, + -0.95690662 -0.26204091 -0.12515695, + -0.9623031 -0.26356602 -0.06712541, + -0.94255537 -0.32722613 -0.067175619, + -0.94463736 -0.32799512 -0.0089207832, + -0.92061478 -0.39036891 -0.0089684781, + -0.91951537 -0.38994816 0.049315117, + -0.89142102 -0.45049 0.049268, + -0.88732523 -0.44846711 0.10738403, + -0.85539985 -0.50672489 0.10733598, + -0.84854281 -0.50271088 0.16509695, + -0.81307858 -0.55826575 0.16505292, + -0.80374986 -0.55190694 0.22222698, + -0.76509637 -0.60436827 0.2221861, + -0.75361198 -0.59534299 0.27863199, + -0.7121622 -0.64436918 0.27859205, + -0.69889098 -0.63240802 0.33408299, + -0.65513879 -0.67764777 0.33404589, + -0.64046568 -0.66251969 0.38842183, + -0.59478086 -0.70383883 0.38838992, + -0.57913715 -0.68537617 0.44142911, + -0.53210503 -0.722516 0.441401, + -0.51592183 -0.70059478 0.49294183, + -0.46797505 -0.73350805 0.49291506, + -0.45170021 -0.70805234 0.54279727, + -0.40344682 -0.73663163 0.54277474, + -0.38753974 -0.70764351 0.59080756, + -0.33942103 -0.73195904 0.59078705, + -0.32491916 -0.7007404 0.63513035, + -0.37764007 -0.66939908 0.63976008, + -0.37781087 -0.66930574 0.63975674, + -0.36864403 -0.67318708 0.64103109, + -0.38754523 -0.70763743 0.59081137, + -0.4338958 -0.68018371 0.59083372, + -0.45170522 -0.70804536 0.54280221, + -0.49797577 -0.6762827 0.54282779, + -0.51592016 -0.70059723 0.49294019, + -0.56153196 -0.66457695 0.49296993, + -0.57914305 -0.68536603 0.44143707, + -0.62360293 -0.64515394 0.44146994, + -0.64045632 -0.66253728 0.38840717, + -0.68325275 -0.61828679 0.38844186, + -0.69889802 -0.63239402 0.334095, + -0.73956984 -0.58428788 0.3341319, + -0.7536152 -0.59533513 0.27864006, + -0.80374712 -0.55191308 0.22222203, + -0.83879715 -0.49700812 0.22226606, + -0.84853488 -0.50272995 0.16507898, + -0.88020879 -0.44493389 0.16512495, + -0.88731974 -0.44848087 0.10737098, + -0.915286 -0.388217 0.10742, + -0.91951013 -0.38996205 0.049302608, + -0.94350511 -0.32766202 0.049353007, + -0.94463336 -0.32800612 -0.0089318827, + -0.96442974 -0.26418993 -0.0088809682, + -0.96230441 -0.26356184 -0.067121066, + -0.97776675 -0.19867995 -0.067070387, + -0.9722839 -0.19751897 -0.12510099, + -0.983311 -0.132145 -0.125049, + -0.97442365 -0.13090496 -0.18265393, + -0.98100126 -0.065521717 -0.18260205, + -0.96871978 -0.064654186 -0.23958693, + -0.95314723 0.064048015 -0.29564905, + -0.93433678 0.062832482 -0.35080892, + -0.92807299 0.12509499 -0.350759, + -0.9062193 0.12219904 -0.40476415, + -0.89605522 0.18245804 -0.40471509, + -0.87244558 0.17769991 -0.4552598, + -0.85361481 0.24370293 -0.46038088, + -0.85601473 0.23483892 -0.46053183, + -0.88189322 0.24188305 -0.40466908, + -0.89605486 0.18245499 -0.40471694, + -0.91766226 0.18680404 -0.35071409, + -0.92807198 0.125091 -0.35076299, + -0.94675601 0.12755901 -0.29560399, + -0.9531461 0.064040907 -0.29565403, + -0.96871966 0.065038577 -0.23948291, + -0.98100024 -0.065526217 -0.18260604, + -0.98994935 -0.066171221 -0.12498704, + -0.98331374 -0.13213398 -0.12503897, + -0.98885709 -0.13292602 -0.067024909, + -0.9777649 -0.19868697 -0.067076489, + -0.97992498 -0.19917201 -0.0088128196, + -0.96443462 -0.26417291 -0.0088654077, + -0.96328264 -0.26390392 0.049409781, + -0.94350791 -0.32765296 0.049360093, + -0.93917203 -0.326195 0.107484, + -0.91529113 -0.38820106 0.10743502, + -0.90795732 -0.38513714 0.16517507, + -0.8802104 -0.44492921 0.16512908, + -0.87010813 -0.43987006 0.22232004, + -0.83880085 -0.49699789 0.22227494, + -0.82620871 -0.48958483 0.2787219, + -0.77692682 -0.53359085 0.3341639, + -0.73956507 -0.58429909 0.33412302, + -0.72300333 -0.57126331 0.38849017, + -0.68325883 -0.61827385 0.3884519, + -0.6652838 -0.6020599 0.44149888, + -0.62359792 -0.64516294 0.44146395, + -0.60462624 -0.62558722 0.49301919, + -0.56154704 -0.66455007 0.49298906, + -0.54202294 -0.64149797 0.54285496, + -0.49797583 -0.67628175 0.5428288, + -0.47833675 -0.64966673 0.59086972, + -0.51596618 -0.56269717 0.64587224, + -0.49873394 -0.59041995 0.63456196, + -0.45076093 -0.62089592 0.64132893, + -0.4338989 -0.5977149 0.67414284, + -0.44948611 -0.6191451 0.64391118, + -0.43390208 -0.59772015 0.67413616, + -0.43387899 -0.597736 0.674137, + -0.45073789 -0.62091386 0.6413278, + -0.45439973 -0.61723465 0.64229465, + -0.47833219 -0.64967525 0.59086424, + -0.54200602 -0.64152998 0.54283398, + -0.58360213 -0.60390812 0.54286611, + -0.60461909 -0.62560207 0.49300906, + -0.64505708 -0.58379006 0.49304205, + -0.66528881 -0.60204786 0.44150788, + -0.70397216 -0.55629313 0.44154412, + -0.72299796 -0.57127696 0.38847995, + -0.75952703 -0.52170002 0.38852, + -0.77692336 -0.53360021 0.33415714, + -0.81081486 -0.48050895 0.33420098, + -0.82620913 -0.48958305 0.27872404, + -0.85704798 -0.43330899 0.27876899, + -0.87010986 -0.43986395 0.22232497, + -0.89753658 -0.38076082 0.22237189, + -0.90795797 -0.38513499 0.165177, + -0.93164444 -0.32363415 0.16522607, + -0.93917066 -0.32620087 0.10747796, + -0.95885497 -0.26274401 0.10753, + -0.96328121 -0.26391006 0.049404509, + -0.97875524 -0.19897805 0.04945641, + -0.97992551 -0.19916891 -0.0088100256, + -0.99104249 -0.13326006 -0.0087570138, + -0.98885834 -0.13292004 -0.067019522, + -0.9955309 -0.066585295 -0.066966891, + -0.98995036 -0.066165626 -0.12498204, + -0.98100036 0.065812521 -0.18250206, + -0.96871924 0.065035716 -0.23948605, + -0.96222526 0.12958802 -0.23943606, + -0.94675523 0.12755103 -0.29561007, + -0.93613487 0.19051597 -0.29555896, + -0.91766238 0.18680505 -0.35071313, + -0.9031567 0.24767491 -0.35066387, + -0.88189411 0.24189302 -0.40466106, + -0.86378831 0.30025911 -0.40461615, + -0.84241527 0.29287612 -0.45228314, + -0.82022387 0.32831696 -0.46844494, + -0.82022911 0.32830402 -0.46844506, + -0.81905121 0.3476921 -0.45636111, + -0.84181982 0.35730591 -0.4045639, + -0.86378801 0.30026701 -0.40461099, + -0.88461429 0.30745512 -0.35061213, + -0.90315676 0.24767993 -0.35065991, + -0.92133576 0.25261593 -0.29550895, + -0.93613499 0.19051699 -0.29555801, + -0.95143551 0.19358291 -0.23936588, + -0.96222687 0.12960899 -0.23941797, + -0.97442251 0.13120294 -0.18244591, + -0.98100078 0.065816887 -0.18249795, + -0.98995012 0.066370204 -0.12487502, + -0.99553025 -0.066590816 -0.066972017, + -0.99103963 -0.13327995 -0.0087754969, + -0.989856 -0.133167 0.049514301, + -0.97875625 -0.19897205 0.049461313, + -0.97425836 -0.19810407 0.10759003, + -0.95885724 -0.26273206 0.10754002, + -0.95117265 -0.2606729 0.16528794, + -0.93164736 -0.32361913 0.16523907, + -0.92095578 -0.31995192 0.22242095, + -0.89753711 -0.38075906 0.22237302, + -0.88406879 -0.37509292 0.27879694, + -0.85704303 -0.43333101 0.27875, + -0.84107029 -0.42530414 0.33424112, + -0.81081414 -0.48051307 0.33419704, + -0.79265082 -0.46979889 0.38857892, + -0.75953388 -0.52167594 0.38853893, + -0.73954898 -0.507999 0.44159299, + -0.70397806 -0.55627704 0.44155505, + -0.68257374 -0.53941584 0.49307582, + -0.64505607 -0.58379203 0.49304107, + -0.62262392 -0.56354392 0.54291594, + -0.58361524 -0.60387921 0.54288417, + -0.56060195 -0.58012193 0.59091794, + -0.67529976 -0.35686389 0.64545977, + -0.66506022 -0.39440915 0.63414222, + -0.69382393 -0.41141093 0.59105796, + -0.66138184 0.59855288 -0.45200488, + -0.67815316 0.6136831 -0.40435308, + -0.71760297 0.56702197 -0.40439093, + -0.73490304 0.58064008 -0.35039204, + -0.77201736 0.53027022 -0.35043219, + -0.78755718 0.54089409 -0.29527506, + -0.82193398 0.48704401 -0.29531801, + -0.83536339 0.49495423 -0.23914112, + -0.86653203 0.43807799 -0.239186, + -0.87752074 0.44358388 -0.18218295, + -0.90518022 0.3839801 -0.18223104, + -0.91343313 0.38743407 -0.12463901, + -0.93726701 0.325551 -0.124688, + -0.94255275 0.32733992 -0.066654287, + -0.96230435 0.26366809 -0.066705622, + -0.96442986 0.26420397 -0.0084446687, + -0.97992551 0.19918291 -0.0084956065, + -0.97875524 0.19889805 0.049778011, + -0.98985535 0.13309304 0.049726319, + -0.98530823 0.13243502 0.10783702, + -0.99196011 0.066316508 0.10778402, + -0.98400998 0.065738298 0.165538, + -0.97271621 -0.065291613 0.22262105, + -0.9581145 -0.064358972 0.27905989, + -0.95169061 -0.12821695 0.27900791, + -0.93395662 -0.12587595 0.33448488, + -0.92348075 -0.18798195 0.33443391, + -0.90279973 -0.18382195 0.38879585, + -0.88853312 -0.24369003 0.38874707, + -0.86515629 -0.2373291 0.44179115, + -0.84739071 -0.29460087 0.44174585, + -0.82161611 -0.28569204 0.49328205, + -0.80073112 -0.33991903 0.49323905, + -0.77288979 -0.32815391 0.54309887, + -0.74926519 -0.37906408 0.5430581, + -0.71971315 -0.36416808 0.5910961, + -0.68577677 -0.34704387 0.63974273, + -0.71971405 -0.36415502 0.59110308, + -0.74240899 -0.31524801 0.59114099, + -0.77289063 -0.32813385 0.54310977, + -0.79304314 -0.27581102 0.54314905, + -0.82161599 -0.285694 0.49328101, + -0.83884311 -0.23015803 0.49332505, + -0.86515582 -0.23732394 0.44179487, + -0.87904674 -0.17903495 0.44184089, + -0.90279931 -0.18382105 0.38879713, + -0.91304314 -0.12309302 0.38884506, + -0.93395436 -0.12586105 0.33449712, + -0.94025624 -0.063217312 0.3345471, + -0.95811623 -0.064368814 0.27905205, + -0.97271514 0.064952411 0.22272503, + -0.98400664 0.065753974 0.16555195, + -0.97741026 0.13131604 0.16560605, + -0.98531085 0.13242398 0.10782599, + -0.97426099 0.197933 0.10788, + -0.97875643 0.19889288 0.049773172, + -0.96328288 0.26382497 0.049824692, + -0.96443439 0.2641871 -0.008460233, + -0.94463724 0.3280091 -0.0084095215, + -0.94255501 0.32733199 -0.066662602, + -0.91858637 0.38956615 -0.06661392, + -0.91343498 0.38742799 -0.124644, + -0.88552576 0.44757089 -0.12459697, + -0.87752378 0.44357389 -0.18219295, + -0.84594756 0.50119376 -0.18214691, + -0.83535868 0.49496782 -0.23912892, + -0.80043411 0.54967606 -0.23908503, + -0.7875613 0.54088318 -0.29528412, + -0.74970996 0.59225494 -0.29524398, + -0.73491293 0.58061492 -0.35041296, + -0.69450879 0.62840676 -0.35037488, + -0.67816108 0.61366504 -0.40436706, + -0.63566518 0.65760517 -0.40433308, + -0.61711293 0.63846594 -0.45992693, + -0.62164408 0.62913907 -0.46662906, + -0.62161022 0.62917322 -0.46662816, + -0.68220025 0.5616222 -0.46817017, + -0.682208 0.56161302 -0.46816999, + -0.69810897 0.55165797 -0.45641801, + -0.71760595 0.56701392 -0.40439695, + -0.7538529 0.51781893 -0.40443695, + -0.7720241 0.53025007 -0.35044804, + -0.80570632 0.47748718 -0.35049012, + -0.82193112 0.48705307 -0.29531103, + -0.85260731 0.43107414 -0.29535711, + -0.86653513 0.43806705 -0.23919503, + -0.89384276 0.37922192 -0.23923995, + -0.90517944 0.38398317 -0.18222809, + -0.92879814 0.32265902 -0.18227802, + -0.93726635 0.32555413 -0.12468504, + -0.95690709 0.26224002 -0.12473602, + -0.96230352 0.26367188 -0.066701271, + -0.9777655 0.19879308 -0.066753931, + -0.97992486 0.19918597 -0.0084928293, + -0.99103975 0.13329397 -0.008544758, + -0.98985624 0.13308802 0.04972221, + -0.99653852 0.066662773 0.049668778, + -0.99196112 0.066310205 0.10777801, + -0.98400891 -0.066017695 0.16543299, + -0.97271824 -0.065307215 0.22260806, + -0.96619624 -0.13012803 0.22255705, + -0.95169109 -0.12822202 0.27900404, + -0.94102186 -0.19147298 0.27895498, + -0.92347813 -0.18795203 0.33445802, + -0.90887702 -0.24922401 0.33441001, + -0.888533 -0.24369501 0.388744, + -0.8702867 -0.30251589 0.38869685, + -0.84739071 -0.29460689 0.44174185, + -0.82584417 -0.3505511 0.44169611, + -0.80072999 -0.33994201 0.49322501, + -0.7762593 -0.39267415 0.49318218, + -0.74926496 -0.37907195 0.54305291, + -0.72231281 -0.42824993 0.5430159, + -0.69382399 -0.41141501 0.59105498, + -0.60989904 -0.41755006 0.67355406, + -0.63229084 -0.43283591 0.64254284, + -0.63125795 -0.43384793 0.64287597, + -0.66482085 -0.45684788 0.59101886, + -0.63286084 -0.5002299 0.59097987, + -0.66481882 -0.45685589 0.59101486, + -0.69211602 -0.47555599 0.54297501, + -0.72231191 -0.42825395 0.54301393, + -0.74832797 -0.44362301 0.493157, + -0.77626181 -0.39264792 0.49319887, + -0.80061072 -0.40491086 0.44166684, + -0.82584542 -0.35053077 0.44170967, + -0.84816515 -0.35995308 0.3886511, + -0.87028682 -0.30251694 0.38869593, + -0.89021724 -0.30939406 0.33434808, + -0.90887702 -0.249244 0.33439499, + -0.92614347 -0.25392985 0.27888682, + -0.94102263 -0.19149692 0.27893591, + -0.95535636 -0.19436507 0.22252308, + -0.96619523 -0.13010503 0.22257505, + -0.97741187 -0.13156798 0.16539599, + -0.98400766 -0.066001579 0.16544694, + -0.99196076 -0.066487983 0.10767198, + -0.99653751 0.066672273 0.049677476, + -0.99104226 0.13327403 -0.0085632615, + -0.98885798 0.133026 -0.066813096, + -0.97776645 0.19878609 -0.066760033, + -0.97228336 0.19771807 -0.12479104, + -0.95690751 0.26223689 -0.12473894, + -0.94826126 0.25991407 -0.18233304, + -0.92879897 0.322653 -0.182284, + -0.89384174 0.37922692 -0.23923594, + -0.8794741 0.37317804 -0.29540402, + -0.85260773 0.43107286 -0.29535788, + -0.83578169 0.42261484 -0.35052189, + -0.80570215 0.47750312 -0.35047808, + -0.78673053 0.46630874 -0.40448877, + -0.75385767 0.51780283 -0.40444884, + -0.73272419 0.50333911 -0.45800111, + -0.74045491 0.49209893 -0.45778295, + -0.73641008 0.48890206 -0.46762705, + -0.73640496 0.48890993 -0.46762693, + -0.76733053 0.45484373 -0.45201874, + -0.78673279 0.46629789 -0.40449691, + -0.81610519 0.41270009 -0.40453809, + -0.83578444 0.42260122 -0.35053217, + -0.8621192 0.36585009 -0.35057709, + -0.87947589 0.37316498 -0.29541498, + -0.90242201 0.31358501 -0.29546401, + -0.93639088 0.25669596 -0.23933098, + -0.94826245 0.25990212 -0.18234409, + -0.96349525 0.19598204 -0.18239504, + -0.97228301 0.197722 -0.124787, + -0.98331225 0.13233402 -0.12483903, + -0.98885751 0.13303193 -0.066807672, + -0.99553055 0.06669727 -0.066860773, + -0.9965381 -0.066741906 0.049571309, + -0.99196053 -0.066481672 0.10767795, + -0.98530966 -0.13259596 0.10762496, + -0.97741222 -0.13158002 0.16538504, + -0.96644723 -0.19658105 0.16533504, + -0.95535612 -0.19437203 0.22251803, + -0.94025666 -0.25773191 0.22246693, + -0.92614436 -0.25391108 0.2789011, + -0.90712661 -0.31521887 0.27885187, + -0.89021772 -0.30939087 0.33434987, + -0.86758572 -0.36815289 0.33430287, + -0.84816509 -0.35996103 0.38864407, + -0.82224983 -0.41580692 0.3885999, + -0.80061042 -0.40491369 0.44166467, + -0.77179533 -0.4574942 0.44162321, + -0.74832606 -0.44363406 0.49315006, + -0.71705592 -0.49261895 0.49310994, + -0.69211876 -0.47554082 0.54298484, + -0.65883279 -0.52071685 0.54294884, + -0.6328575 -0.50024164 0.59097356, + -0.59805876 -0.5414018 0.59093976, + -0.57076401 -0.516752 0.63811898, + -0.58195013 -0.50505012 0.63738418, + -0.58222413 -0.50474811 0.63737315, + -0.53593105 -0.55465007 0.63650703, + -0.56060094 -0.58012193 0.59091896, + -0.59806401 -0.54138702 0.59094799, + -0.62261897 -0.56355703 0.54290801, + -0.65882975 -0.5207268 0.54294282, + -0.68256795 -0.53943396 0.49306393, + -0.7170518 -0.49263287 0.49310189, + -0.73954093 -0.50802892 0.44157195, + -0.77179188 -0.45750993 0.44161293, + -0.79264611 -0.46982107 0.38856205, + -0.82225198 -0.41579601 0.388607, + -0.8410781 -0.42526606 0.33427003, + -0.86758786 -0.36813697 0.33431497, + -0.8840704 -0.37508217 0.27880612, + -0.90712702 -0.31521499 0.278855, + -0.92095298 -0.31997201 0.222404, + -0.94025546 -0.25774711 0.2224551, + -0.95117015 -0.26069203 0.16527301, + -0.96644676 -0.19659196 0.16532496, + -0.97425526 -0.19813305 0.10756402, + -0.98530936 -0.13260704 0.10761504, + -0.98985553 -0.13317195 0.049510177, + -0.99653786 -0.066751391 0.049562693, + -0.99553055 0.066691771 -0.066865772, + -0.98994976 0.066364482 -0.12488097, + -0.98331213 0.13234401 -0.12482902, + -0.97442234 0.13119504 -0.18245307, + -0.96349579 0.19597396 -0.18240096, + -0.95143539 0.19356908 -0.23937809, + -0.93639058 0.25669888 -0.23932888, + -0.92133564 0.25261891 -0.29550689, + -0.90242189 0.31359097 -0.29545796, + -0.88461423 0.30745205 -0.35061508, + -0.86211818 0.36585909 -0.35057008, + -0.8418209 0.35729396 -0.40457195, + -0.8161031 0.41271406 -0.40452805, + -0.79308617 0.40112609 -0.45838013, + -0.78692991 0.41333795 -0.45814094, + -0.78266412 0.41087005 -0.46757105, + -0.78266519 0.41086808 -0.46757111, + -0.70499104 -0.53177404 -0.46925905, + -0.70501179 -0.53174579 -0.46925983, + -0.65025598 -0.60501301 -0.45948499, + -0.69832093 -0.55109894 -0.45676893, + -0.71760803 -0.56637108 -0.40529305, + -0.67816603 -0.61302406 -0.40533006, + -0.6945132 -0.6278522 -0.3513591, + -0.65099984 -0.67284483 -0.35139591, + -0.66410398 -0.68643802 -0.296258, + -0.6167599 -0.72925884 -0.29629195, + -0.62684029 -0.74122536 -0.24011712, + -0.57590705 -0.78144711 -0.24014904, + -0.5832082 -0.79140031 -0.18317705, + -0.52904308 -0.82858211 -0.18320802, + -0.53386688 -0.83618581 -0.12561597, + -0.47681093 -0.86997986 -0.12564398, + -0.47950095 -0.87493289 -0.067611694, + -0.41997615 -0.9050113 -0.067635819, + -0.35940596 -0.9331339 -0.0094101392, + -0.3589769 -0.93206578 0.048877589, + -0.29591012 -0.95396537 0.048860017, + -0.29455012 -0.94962835 0.10698704, + -0.23049492 -0.96717566 0.10697296, + -0.22864696 -0.95946789 0.16474798, + -0.16405004 -0.97259927 0.16473705, + -0.16216695 -0.96148479 0.22192094, + -0.097606741 -0.97016835 0.22191508, + -0.096141338 -0.95565033 0.2783691, + -0.032104902 -0.95993811 0.27836704, + -0.031506788 -0.94210267 0.33384088, + 0.031491395 -0.94210291 0.33384198, + 0.030786207 -0.92105526 0.3882131, + 0.092201553 -0.91694456 0.38821581, + 0.089775302 -0.892865 0.44128501, + 0.14920095 -0.88487369 0.44129086, + 0.14466603 -0.8580302 0.49280411, + 0.20162903 -0.84645212 0.49281305, + 0.19461396 -0.81705791 0.54271692, + 0.24872309 -0.80223632 0.54272819, + 0.23891588 -0.77065963 0.5907647, + 0.28984499 -0.75297499 0.59077799, + 0.27736905 -0.72062218 0.6354292, + 0.21641007 -0.73810524 0.63903624, + 0.21676797 -0.73799193 0.63904595, + 0.22742806 -0.73372418 0.6402542, + 0.23889706 -0.7706582 0.59077412, + 0.18694001 -0.78489012 0.59076303, + 0.19461603 -0.81705815 0.54271609, + 0.13961294 -0.82823759 0.54270679, + 0.14464292 -0.85802561 0.49281877, + 0.087073319 -0.86576819 0.49281213, + 0.089804597 -0.89287198 0.44126499, + 0.029989304 -0.89687711 0.44126207, + 0.030799603 -0.92105913 0.38820305, + -0.030786285 -0.92105961 0.38820282, + -0.031491514 -0.9421075 0.33382913, + -0.094311878 -0.93790275 0.33383191, + -0.096102752 -0.9556635 0.27833688, + -0.15971293 -0.94710952 0.27834389, + -0.16214702 -0.96149212 0.22190402, + -0.22599597 -0.94851488 0.22191297, + -0.22861992 -0.95947862 0.16472293, + -0.29219395 -0.94206375 0.16473795, + -0.29455394 -0.94962674 0.10699098, + -0.35732409 -0.92783022 0.10700803, + -0.35897404 -0.9320671 0.048874609, + -0.42040101 -0.90601999 0.048896201, + -0.48057801 -0.87690198 -0.0093664303, + -0.47951993 -0.87492388 -0.067592792, + -0.53687614 -0.8409512 -0.067566216, + -0.5338648 -0.83618671 -0.12561895, + -0.5885371 -0.79865617 -0.12558803, + -0.58322006 -0.79139411 -0.18316601, + -0.63477796 -0.7506789 -0.18313399, + -0.62682933 -0.74123138 -0.24012712, + -0.67496121 -0.69769824 -0.24009308, + -0.66411096 -0.68643391 -0.29625198, + -0.70848036 -0.64055628 -0.29621515, + -0.6944952 -0.62786317 -0.3513751, + -0.73489726 -0.58007616 -0.35133711, + -0.71760094 -0.56637591 -0.40529895, + -0.75386202 -0.51716101 -0.40526101, + -0.73518497 -0.50430292 -0.45296994, + -0.75679868 -0.45726186 -0.46708381, + -0.75679684 -0.45726487 -0.46708387, + -0.76344889 -0.45181593 -0.46152794, + -0.78673583 -0.46565589 -0.4052299, + -0.81609911 -0.41206706 -0.40519506, + -0.78672814 -0.46566206 -0.40523806, + -0.8056978 -0.47694287 -0.3512499, + -0.77201188 -0.52970892 -0.35129198, + -0.78755391 -0.54042196 -0.29614696, + -0.74969822 -0.59179926 -0.29618612, + -0.76195031 -0.60152024 -0.2400111, + -0.72006601 -0.651061 -0.240051, + -0.72919583 -0.65936381 -0.18306495, + -0.6835202 -0.70659316 -0.18310204, + -0.68975323 -0.71308327 -0.12551005, + -0.64055997 -0.75757599 -0.125545, + -0.64417201 -0.76189399 -0.0675283, + -0.59185207 -0.80321014 -0.06756191, + -0.59315878 -0.80503172 -0.0093070064, + -0.53806108 -0.84285414 -0.0093365405, + -0.53741908 -0.84189409 0.048941009, + -0.47998893 -0.87590986 0.048913892, + -0.47778389 -0.8719328 0.10703198, + -0.41846094 -0.90190887 0.10700799, + -0.41510808 -0.89473021 0.16475205, + -0.35444891 -0.92045075 0.16473095, + -0.35037911 -0.90992832 0.22195707, + -0.28882793 -0.93130076 0.22193994, + -0.28449398 -0.91737491 0.27836397, + -0.21845895 -0.91695178 0.3338789, + -0.15675901 -0.92949313 0.33387002, + -0.15324992 -0.90873659 0.38821682, + -0.092201903 -0.91694701 0.38821, + -0.089776278 -0.89287478 0.44126487, + -0.029963596 -0.89687788 0.44126195, + -0.029052388 -0.86965472 0.49280483, + 0.029049493 -0.86965483 0.49280488, + 0.028039187 -0.83946061 0.54269677, + 0.084029078 -0.83571285 0.54269987, + 0.080715075 -0.80280882 0.59074789, + 0.08073312 -0.80281419 0.59073812, + 0.077355698 -0.769283 0.63420802, + 0.043543611 -0.76243317 0.6456002, + 0.042073075 -0.73672658 0.67488056, + 0.12223297 -0.70676184 0.6968118, + 0.13070692 -0.75567853 0.64176762, + 0.13066898 -0.7556839 0.64176893, + 0.125929 -0.728315 0.673572, + 0.088092655 -0.72607267 0.6819517, + 0.082385622 -0.67910719 0.72940117, + 0.12688597 -0.62213188 0.77256185, + 0.17649396 -0.60990387 0.7725718, + 0.16205806 -0.5601002 0.8124193, + 0.20655596 -0.54524386 0.8124308, + 0.18726499 -0.494412 0.84881598, + 0.22637294 -0.47774988 0.84882879, + 0.23570812 -0.40893921 0.88159543, + 0.20636705 -0.35814407 0.91057426, + 0.23444191 -0.34038988 0.91058868, + 0.20010599 -0.290663 0.93566698, + 0.222784 -0.27362099 0.93568099, + 0.18359101 -0.22563303 0.95675713, + 0.20110191 -0.21011889 0.95676953, + 0.15732799 -0.164561 0.97373903, + 0.16998394 -0.15138394 0.97374964, + 0.12193201 -0.10881902 0.9865551, + 0.13022804 -0.098658137 0.98656338, + 0.078357033 -0.059681524 0.99513733, + 0.08284536 -0.053178873 0.99514252, + 0.09017238 -0.03921669 0.99515378, + 0.20424289 -0.70568758 0.67844659, + 0.19015802 -0.65710008 0.72942406, + 0.24239203 -0.63966107 0.72943807, + 0.22495911 -0.59373331 0.77257633, + 0.2719239 -0.57372284 0.77259272, + 0.24967188 -0.52685678 0.81245667, + 0.29120401 -0.505059 0.81247503, + 0.26401091 -0.45798385 0.84885168, + 0.29996002 -0.43525305 0.84886914, + 0.26777491 -0.38864985 0.88161671, + 0.29811901 -0.365848 0.88163501, + 0.26101112 -0.32042015 0.91060644, + 0.28589705 -0.29837307 0.91062427, + 0.24403308 -0.25480908 0.93569237, + 0.26369593 -0.23433691 0.93570864, + 0.21730207 -0.19325508 0.95678234, + 0.19194803 -0.12216301 0.97377211, + 0.137684 -0.087856799 0.98657203, + 0.14424102 -0.076499708 0.98658115, + 0.086788207 -0.046348605 0.99514812, + 0.086795196 -0.046338495 0.99514788, + 0.082847565 -0.053176075 0.99514252, + 0.13769294 -0.087847352 0.98657155, + 0.130236 -0.098650903 0.98656303, + 0.16999398 -0.15137799 0.97374886, + 0.21728703 -0.19326302 0.95678413, + 0.20109192 -0.2101239 0.95677054, + 0.24402997 -0.25480998 0.93569291, + 0.22280397 -0.27361497 0.93567789, + 0.26103404 -0.32041404 0.91060209, + 0.23445208 -0.34038913 0.9105863, + 0.26777989 -0.38864881 0.88161558, + 0.23569287 -0.4089388 0.88159961, + 0.26402387 -0.45798379 0.84884757, + 0.226363 -0.47774899 0.84883201, + 0.24967794 -0.5268569 0.81245482, + 0.20653208 -0.54524016 0.81243932, + 0.22493286 -0.59372866 0.77258754, + 0.1764859 -0.60990262 0.77257454, + 0.19016796 -0.65710294 0.72941893, + 0.14642799 -0.71777892 0.68069994, + 0.12366898 -0.71544492 0.68763691, + 0.13040097 -0.75432682 0.64341784, + 0.17920801 -0.75249112 0.63375205, + 0.21520604 -0.7333172 0.64492816, + 0.20672196 -0.70445281 0.6789788, + 0.20670003 -0.70445907 0.67897904, + 0.21518405 -0.73332715 0.64492416, + 0.21514195 -0.73333883 0.64492482, + 0.20710707 -0.70599622 0.67725623, + 0.20733304 -0.70592517 0.67726117, + 0.207001 -0.70606399 0.67721802, + 0.25753891 -0.67958277 0.68690675, + 0.24238506 -0.63966018 0.72944117, + 0.29298803 -0.61810106 0.72945803, + 0.27191508 -0.57372218 0.7725963, + 0.31718111 -0.5499652 0.77261531, + 0.29123497 -0.50505894 0.81246388, + 0.33085904 -0.48000205 0.81248415, + 0.29995289 -0.43525285 0.84887171, + 0.3339631 -0.4096961 0.84889215, + 0.29813689 -0.36584389 0.88163072, + 0.3265571 -0.34066609 0.88165021, + 0.28590703 -0.29837003 0.91062212, + 0.30892 -0.27441099 0.91064101, + 0.26367503 -0.23434703 0.9357121, + 0.28162014 -0.2123691 0.93572944, + 0.24535803 -0.15591702 0.95681214, + 0.19195293 -0.12215895 0.97377163, + 0.20110604 -0.10630402 0.97378427, + 0.14425507 -0.076482534 0.98658049, + 0.14987594 -0.064637281 0.98658967, + 0.090176068 -0.039210286 0.99515367, + 0.092976652 -0.031825785 0.99515951, + 0.095169462 -0.024250191 0.99516565, + 0.092972368 -0.031834889 0.99515963, + 0.15452006 -0.052378319 0.98660034, + 0.14986603 -0.064652212 0.98659027, + 0.20892711 -0.089811645 0.97379845, + 0.20109504 -0.10631602 0.97378522, + 0.25704807 -0.13566902 0.95682824, + 0.24535994 -0.15591598 0.95681179, + 0.29773405 -0.18901804 0.93574923, + 0.2816129 -0.21237293 0.93573064, + 0.32993796 -0.24866797 0.91066188, + 0.30891693 -0.27441195 0.91064179, + 0.35283399 -0.31329799 0.88167602, + 0.32654196 -0.34067097 0.8816539, + 0.36579317 -0.38151017 0.84890842, + 0.33398309 -0.40969208 0.84888619, + 0.3683919 -0.45180187 0.81250381, + 0.33086598 -0.48000094 0.81248188, + 0.3603361 -0.52266514 0.77264416, + 0.31716281 -0.54996568 0.77262253, + 0.34174997 -0.59251696 0.72947294, + 0.29300013 -0.61810225 0.72945225, + 0.31107685 -0.65616667 0.68751466, + 0.36199012 -0.64170724 0.67614722, + 0.37764007 -0.66939908 0.63976008, + 0.37781087 -0.66930574 0.63975674, + 0.36216483 -0.64163768 0.67611969, + 0.3620441 -0.6417042 0.67612118, + 0.37564594 -0.66576695 0.64470494, + 0.37569308 -0.66574019 0.64470518, + 0.36004221 -0.63805538 0.68062842, + 0.36679798 -0.63585895 0.67907494, + 0.34175196 -0.59251696 0.72947192, + 0.38829294 -0.56308591 0.72949493, + 0.3603659 -0.52266288 0.77263182, + 0.40119481 -0.49198177 0.77265567, + 0.36836696 -0.45180595 0.81251287, + 0.40346906 -0.42070907 0.81253713, + 0.36579111 -0.38151014 0.84890932, + 0.39525685 -0.35083288 0.8489337, + 0.35285109 -0.31329209 0.88167125, + 0.3768619 -0.28388295 0.88169473, + 0.32995388 -0.24865891 0.91065872, + 0.348836 -0.221304 0.91068, + 0.29773915 -0.18901409 0.9357484, + 0.31191295 -0.16446595 0.93576777, + 0.25703809 -0.13568005 0.95682937, + 0.26706392 -0.11454796 0.95684665, + 0.20893905 -0.089796223 0.97379726, + 0.21542998 -0.072680496 0.97381085, + 0.15452895 -0.052363381 0.98659962, + 0.15817595 -0.039770685 0.98660964, + 0.095170066 -0.024248591 0.99516565, + 0.096748479 -0.016517697 0.99517179, + 0.096748978 0.014932796 0.99519676, + 0.55059719 -0.48832417 0.67703927, + 0.51160789 -0.45382389 0.72958982, + 0.54641682 -0.41119084 0.72962373, + 0.50711405 -0.38169107 0.77275312, + 0.53613681 -0.33964187 0.77278769, + 0.49228382 -0.31194389 0.81261772, + 0.51573807 -0.27132204 0.81264913, + 0.46757099 -0.246071 0.849015, + 0.48580205 -0.20765103 0.8490451, + 0.43367705 -0.18546902 0.88177413, + 0.44714189 -0.14996597 0.88180178, + 0.39148295 -0.13140899 0.91075391, + 0.40072486 -0.09949816 0.91077971, + 0.34203714 -0.085052237 0.9358294, + 0.34771296 -0.057245094 0.93585187, + 0.28653997 -0.047321893 0.95689887, + 0.28935608 -0.024133509 0.95691735, + 0.22637306 -0.019059803 0.97385424, + 0.16237892 0.012323295 0.98665154, + 0.097700655 0.0070949667 0.9951905, + 0.097700663 0.0070938077 0.99519062, + 0.16237895 -0.013891296 0.98663074, + 0.22637689 -0.019046491 0.97385353, + 0.22417402 -0.037195403 0.9738391, + 0.28654402 -0.047315009 0.95689809, + 0.28186402 -0.07023681 0.95688009, + 0.34203684 -0.085051566 0.93582958, + 0.33414498 -0.11229698 0.93580788, + 0.39147601 -0.13141599 0.91075599, + 0.37969005 -0.16249402 0.91073114, + 0.43367407 -0.18547101 0.88177514, + 0.41739792 -0.21977194 0.88174778, + 0.46756417 -0.24607609 0.84901732, + 0.44630912 -0.28289405 0.84898716, + 0.49229023 -0.31194016 0.81261539, + 0.46564519 -0.35054418 0.8125844, + 0.50713003 -0.38168401 0.77274603, + 0.47481123 -0.42126819 0.77271438, + 0.5116002 -0.45382714 0.72959322, + 0.51047903 -0.53201306 0.67555404, + 0.47346911 -0.4935241 0.72956216, + 0.45859018 -0.56224018 0.68817222, + 0.43227291 -0.53003991 0.72951883, + 0.47349823 -0.49351823 0.72954738, + 0.43943888 -0.45809388 0.77268583, + 0.47481012 -0.42126808 0.77271515, + 0.435965 -0.386886 0.81256002, + 0.46563405 -0.35054803 0.81258911, + 0.42214715 -0.31789911 0.84895933, + 0.44631001 -0.282893 0.84898698, + 0.39841905 -0.25263602 0.88172412, + 0.41739094 -0.21977697 0.88174987, + 0.36543387 -0.19252993 0.91070873, + 0.37968299 -0.16249999 0.91073298, + 0.3240799 -0.13882896 0.93578774, + 0.3341409 -0.11230197 0.93580878, + 0.27535489 -0.092692353 0.95686352, + 0.2818549 -0.070251375 0.95688164, + 0.2205029 -0.055138875 0.97382653, + 0.22416003 -0.037226003 0.97384113, + 0.16079506 -0.026932409 0.98662037, + 0.16237798 -0.013894398 0.98663086, + 0.097700603 -0.00867985 0.99517798, + 0.097700797 -0.0086787101 0.99517798, + 0.09674938 -0.016514596 0.99517179, + 0.16080095 -0.026916495 0.98661977, + 0.15817693 -0.039769381 0.98660952, + 0.22051211 -0.055122327 0.97382545, + 0.21542293 -0.072690479 0.97381163, + 0.27535993 -0.092685774 0.95686275, + 0.26707211 -0.11454006 0.95684546, + 0.324094 -0.138815 0.935785, + 0.31192896 -0.16445199 0.93576491, + 0.36544684 -0.1925199 0.91070557, + 0.34882396 -0.22131097 0.91068286, + 0.39840719 -0.25264311 0.8817274, + 0.37683499 -0.283896 0.88170201, + 0.42212701 -0.31790799 0.848966, + 0.39523882 -0.35083881 0.8489396, + 0.43596008 -0.3868871 0.81256217, + 0.40347409 -0.42070809 0.81253517, + 0.43941826 -0.45809928 0.77269447, + 0.401169 -0.49198499 0.77266699, + 0.43226722 -0.53004122 0.72952133, + 0.38829407 -0.56308508 0.72949505, + 0.41608477 -0.60330665 0.6803636, + 0.42770109 -0.58921909 0.68548715, + 0.44947401 -0.61915302 0.64391202, + 0.44948611 -0.6191451 0.64391118, + 0.43390208 -0.59772015 0.67413616, + 0.43387899 -0.597736 0.674137, + 0.4338989 -0.5977149 0.67414284, + 0.45076093 -0.62089592 0.64132893, + 0.49873394 -0.59041995 0.63456196, + 0.51596618 -0.56269717 0.64587224, + 0.49904895 -0.54428697 0.67431593, + 0.49906099 -0.54427701 0.67431498, + 0.51597708 -0.56268609 0.64587307, + 0.51596099 -0.56270099 0.64587301, + 0.49235299 -0.537009 0.68498898, + 0.55315793 -0.47961095 0.68116796, + 0.58222413 -0.50474811 0.63737315, + 0.58195013 -0.50505012 0.63738418, + 0.55288994 -0.47988993 0.68118894, + 0.55301595 -0.47975194 0.68118393, + 0.57685488 -0.50037986 0.6456458, + 0.57688689 -0.50034291 0.6456458, + 0.55666888 -0.48284987 0.67599982, + 0.55664903 -0.48287401 0.67599899, + 0.59388292 -0.40665394 0.69421595, + 0.58451307 -0.43977305 0.68186808, + 0.54642326 -0.41118822 0.72962034, + 0.57768917 -0.36589211 0.72965622, + 0.53613025 -0.33964616 0.77279037, + 0.56166905 -0.29541102 0.77282614, + 0.51572508 -0.27132902 0.81265509, + 0.53583091 -0.22895497 0.8126899, + 0.48578817 -0.20766208 0.84905028, + 0.50087219 -0.16788806 0.84908229, + 0.44713414 -0.14997406 0.88180429, + 0.45769516 -0.11351304 0.88183331, + 0.40072784 -0.099495165 0.9107787, + 0.40737686 -0.066925779 0.91080469, + 0.34770989 -0.05724958 0.93585265, + 0.35112792 -0.029111693 0.93587476, + 0.28935394 -0.024137994 0.95691776, + 0.2263729 0.017495193 0.97388351, + 0.16237794 0.012319895 0.98665166, + 0.16079701 0.025344504 0.98666209, + 0.096749082 0.014929698 0.99519688, + 0.095169798 0.0226654 0.99520302, + 0.092975207 0.030240403 0.9952091, + 0.095169999 0.022663699 0.99520302, + 0.15817694 0.038199484 0.98667163, + 0.16079694 0.025361691 0.98666161, + 0.22416997 0.035676695 0.97389686, + 0.22637592 0.017509094 0.97388262, + 0.28935403 0.022609401 0.95695513, + 0.35113612 -0.029094711 0.93587238, + 0.41137585 -0.033938389 0.91083372, + 0.40736908 -0.066937111 0.91080725, + 0.46528107 -0.076326609 0.8818661, + 0.45768672 -0.11352193 0.88183647, + 0.5008772 -0.16788305 0.84908032, + 0.55247617 -0.18507905 0.81272131, + 0.53583699 -0.22895101 0.81268698, + 0.58357686 -0.24925993 0.77285683, + 0.5616802 -0.29540512 0.77282029, + 0.60521489 -0.31821892 0.72969282, + 0.64998996 -0.34354097 0.67785895, + 0.65052724 -0.34196913 0.67813826, + 0.60520709 -0.31822404 0.72969705, + 0.62880605 -0.26849002 0.72973704, + 0.58358324 -0.24925609 0.77285331, + 0.60169804 -0.20148803 0.77289212, + 0.55247009 -0.18508501 0.81272411, + 0.5655148 -0.14004695 0.81276071, + 0.521209 -0.085385002 0.84914702, + 0.46528393 -0.076321892 0.88186491, + 0.41137505 -0.033939805 0.91083413, + 0.3511351 0.027622009 0.93591738, + 0.28935492 0.022614092 0.95695466, + 0.28654101 0.045790505 0.95697314, + 0.22416601 0.035643298 0.97389901, + 0.22050706 0.05357001 0.97391325, + 0.15817694 0.038198084 0.98667163, + 0.15452397 0.050808288 0.98668176, + 0.092973098 0.030250199 0.99520898, + 0.09017349 0.037632197 0.99521488, + 0.30705988 0.79472172 -0.52357584, + 0.30713218 0.79469347 -0.52357632, + 0.30711311 0.79470032 -0.52357715, + 0.31926501 0.808514 -0.49434301, + 0.34439987 0.81016868 -0.47435781, + 0.45254105 0.8053121 -0.38298705, + 0.46054381 0.8087067 -0.36591387, + 0.84241527 0.29287612 -0.45228314, + 0.86379027 0.30026013 -0.40461114, + 0.841824 0.35729599 -0.40456399, + 0.86211586 0.36585796 -0.35057697, + 0.83577889 0.42261294 -0.35053098, + 0.85260791 0.43107295 -0.29535696, + 0.82193518 0.48704612 -0.29531106, + 0.83536583 0.49495587 -0.23912895, + 0.80043817 0.5496701 -0.23908506, + 0.81058282 0.55658889 -0.18211095, + 0.77160573 0.60948777 -0.18206894, + 0.77864319 0.61499912 -0.12446203, + 0.73583895 0.66562796 -0.12442099, + 0.73999 0.66933399 -0.066384003, + 0.69361967 0.71727961 -0.066344872, + 0.69515193 0.71881694 -0.0081223091, + 0.64559883 0.76363385 -0.008087188, + 0.6448282 0.76267517 0.050232813, + 0.62171686 0.78162682 0.05027559, + 0.61463106 0.7869041 0.054870006, + 0.53451598 0.80730301 0.25010899, + 0.53451109 0.80729514 0.25014502, + 0.34279412 0.82007933 0.45821616, + 0.69832093 -0.55109894 -0.45676893, + 0.71760619 -0.56636912 -0.4052991, + 0.75385314 -0.51717407 -0.40526107, + 0.77202415 -0.5296911 -0.3512921, + 0.80570602 -0.47692901 -0.35124999, + 0.82193089 -0.48658195 -0.29608697, + 0.85260701 -0.43060401 -0.29604301, + 0.86653513 -0.43768507 -0.23989303, + 0.89384288 -0.37883994 -0.23984396, + 0.90517914 -0.38369307 -0.18284002, + 0.92879778 -0.32236892 -0.18279195, + 0.93726641 -0.32535514 -0.12520306, + 0.95690697 -0.262041 -0.125154, + 0.96230334 -0.26356608 -0.067121126, + 0.97776538 -0.19868708 -0.067070425, + 0.97992498 -0.19917201 -0.0088100396, + 0.99103975 -0.13327996 -0.0087570278, + 0.98985624 -0.13316703 0.049510211, + 0.99653852 -0.066741869 0.049562477, + 0.99196112 -0.066481806 0.10767201, + 0.98400891 0.065754093 0.16553798, + 0.97271812 0.064952604 0.22271203, + 0.96619636 0.12977405 0.22276308, + 0.95169097 0.12777799 0.279208, + 0.94102198 0.191029 0.279259, + 0.92347836 0.18742006 0.33475611, + 0.90887725 0.24869105 0.33480608, + 0.888533 0.243075 0.38913199, + 0.87028688 0.30189598 0.38917795, + 0.84739089 0.29390296 0.44220993, + 0.82584411 0.34984702 0.44225407, + 0.80073035 0.33915615 0.49376523, + 0.77625954 0.39188775 0.49380669, + 0.74926519 0.3782061 0.54365611, + 0.72231281 0.42738491 0.54369688, + 0.69382381 0.4104729 0.59170985, + 0.66482085 0.45590588 0.59174585, + 0.76065379 0.064795487 0.64591581, + 0.76601827 0.10251304 0.63459224, + 0.79920298 0.107009 0.59145898, + 0.72416008 0.14619902 0.67395705, + 0.750507 0.151563 0.64324802, + 0.75031513 0.15201102 0.64336604, + 0.7902317 0.16016693 0.59150678, + 0.79919988 0.10699899 0.59146494, + 0.83201098 0.111449 0.54344898, + 0.83762503 0.055645201 0.54340398, + 0.86780101 0.057705201 0.49355, + 0.89502221 -0.060267616 0.44193113, + 0.91920364 -0.061844178 0.38889584, + 0.91304231 -0.12309205 0.38884714, + 0.93395865 -0.12586096 0.33448488, + 0.92348623 -0.18795304 0.33443508, + 0.9410271 -0.19147404 0.27893704, + 0.92614836 -0.25391209 0.27888709, + 0.94025922 -0.25773305 0.22245505, + 0.92095965 -0.31995288 0.22240393, + 0.93164945 -0.32361981 0.16522589, + 0.90795714 -0.38513705 0.16517702, + 0.91529244 -0.38820177 0.10741993, + 0.88732678 -0.44846687 0.10737098, + 0.89142221 -0.45049012 0.049247611, + 0.859348 -0.50901902 0.049200799, + 0.86037511 -0.50958109 -0.009052081, + 0.82440114 -0.56593305 -0.0090964613, + 0.82258409 -0.56464005 -0.067357607, + 0.78303885 -0.61830992 -0.067400895, + 0.77864712 -0.61479509 -0.12544201, + 0.73583984 -0.6654278 -0.12548096, + 0.72919208 -0.65936804 -0.18306501, + 0.68351918 -0.70659417 -0.18310204, + 0.6749602 -0.69769919 -0.24009305, + 0.62683898 -0.74122298 -0.240128, + 0.61676222 -0.72925925 -0.29628611, + 0.56664801 -0.76883399 -0.29631799, + 0.5554648 -0.75361168 -0.35146588, + 0.5038591 -0.78903615 -0.3514941, + 0.49199876 -0.77041364 -0.40546283, + 0.43943611 -0.80154616 -0.40548709, + 0.4267239 -0.77830583 -0.46059388, + 0.43426514 -0.76968431 -0.46797419, + 0.43424609 -0.76969516 -0.46797413, + 0.47987211 -0.75132018 -0.45303512, + 0.49202013 -0.77038717 -0.40548709, + 0.54239601 -0.73580599 -0.405458, + 0.5554741 -0.75359917 -0.3514781, + 0.60459208 -0.71481007 -0.35144702, + 0.61676574 -0.72925377 -0.29629189, + 0.66410905 -0.68643308 -0.29625803, + 0.67496103 -0.69769806 -0.24009404, + 0.720065 -0.65105999 -0.24005701, + 0.72919518 -0.65936315 -0.18307005, + 0.7716071 -0.60919803 -0.18303101, + 0.77864331 -0.61480123 -0.12543604, + 0.81797898 -0.56141502 -0.125394, + 0.8225913 -0.56462818 -0.067369923, + 0.85848391 -0.50840193 -0.067325495, + 0.86038017 -0.50957215 -0.0090621216, + 0.89247727 -0.45100215 -0.0090162233, + 0.89141089 -0.45050994 0.049267892, + 0.91950989 -0.38996094 0.049315091, + 0.91528475 -0.3882159 0.10743498, + 0.93916988 -0.32620096 0.10748398, + 0.93164259 -0.32363284 0.16523893, + 0.95116776 -0.26069093 0.16528796, + 0.9402529 -0.25774598 0.22246698, + 0.95535755 -0.19436491 0.22251789, + 0.94101745 -0.19149509 0.27895513, + 0.95169175 -0.12821697 0.27900395, + 0.93395287 -0.12587498 0.33449596, + 0.94025737 -0.063206419 0.33454612, + 0.91920513 -0.061840508 0.38889307, + 0.89502275 0.059552886 0.44202688, + 0.8677963 0.057689622 0.49356017, + 0.86197972 0.11551695 0.49360582, + 0.83201069 0.11144696 0.54344982, + 0.82267714 0.16678302 0.54349405, + 0.79022914 0.16015002 0.59151506, + 0.77773589 0.21257298 0.59155697, + 0.73220807 0.23741902 0.63836008, + 0.72660202 0.25177601 0.63926399, + 0.76177102 0.26402599 0.59160399, + 0.77773416 0.21256505 0.59156209, + 0.8096742 0.22135106 0.54353613, + 0.8226772 0.16678604 0.54349309, + 0.85231668 0.17284994 0.49363881, + 0.86198473 0.11553995 0.49359182, + 0.88902473 0.11921697 0.44206589, + 0.89502591 0.059564091 0.44201893, + 0.91920489 0.061224893 0.38899094, + 0.9402535 -0.063217133 0.33455515, + 0.95811391 -0.064368695 0.27905998, + 0.95169002 -0.12822101 0.279008, + 0.96619201 -0.130127 0.22257601, + 0.95535499 -0.194372 0.222523, + 0.96644878 -0.19658196 0.16532496, + 0.95117509 -0.26067403 0.16527301, + 0.95885813 -0.26273304 0.10752901, + 0.93917274 -0.32619491 0.10747798, + 0.94350827 -0.32765308 0.049353011, + 0.91951567 -0.38994884 0.049302582, + 0.92061466 -0.39036885 -0.0089813769, + 0.89248389 -0.45098895 -0.009030059, + 0.89051789 -0.44994894 -0.067259796, + 0.85847354 -0.50842232 -0.067305334, + 0.85365719 -0.50552315 -0.12536304, + 0.81798589 -0.56140196 -0.12540698, + 0.81059414 -0.55628204 -0.18299602, + 0.77161217 -0.60918909 -0.18303904, + 0.76195282 -0.6015169 -0.24001095, + 0.72006106 -0.65106606 -0.24005203, + 0.70848507 -0.64055103 -0.29621503, + 0.66410482 -0.68643981 -0.29625195, + 0.65100008 -0.67284405 -0.35139704, + 0.60458004 -0.71482807 -0.35143104, + 0.59034503 -0.69794798 -0.405415, + 0.5423851 -0.73582119 -0.4054451, + 0.52755213 -0.71564919 -0.45775011, + 0.51056397 -0.72064596 -0.46903494, + 0.51056582 -0.72064477 -0.46903482, + 0.35266599 -0.80935502 -0.46965, + 0.35267609 -0.80935121 -0.46964911, + 0.43610385 -0.7731927 -0.46041983, + 0.37465391 -0.80699581 -0.45649987, + 0.384895 -0.82910597 -0.40551099, + 0.43943921 -0.80154335 -0.40548918, + 0.45003107 -0.8209151 -0.35152602, + 0.50386411 -0.78903019 -0.35150009, + 0.51401186 -0.8049708 -0.29633394, + 0.56663728 -0.76884735 -0.29630414, + 0.57589513 -0.78145617 -0.24014805, + 0.62683117 -0.74123317 -0.24011706, + 0.63477796 -0.75067788 -0.18313798, + 0.68351996 -0.70659292 -0.18310398, + 0.68975234 -0.71308237 -0.12552007, + 0.73583996 -0.66542792 -0.12547998, + 0.73998994 -0.66922796 -0.067445993, + 0.78304172 -0.61830574 -0.067405678, + 0.78477103 -0.61971802 -0.0091673201, + 0.82441872 -0.56590682 -0.0091248667, + 0.82343429 -0.56527817 0.049158517, + 0.85934532 -0.50902319 0.049204819, + 0.85539609 -0.50673103 0.10733701, + 0.88731813 -0.44848105 0.10738402, + 0.88020843 -0.44493321 0.16512908, + 0.90795827 -0.38513514 0.16517507, + 0.89753622 -0.38076109 0.22237305, + 0.92094964 -0.31996989 0.22242093, + 0.90712768 -0.31521589 0.2788519, + 0.92613941 -0.25392911 0.27890113, + 0.90887201 -0.24924199 0.33441001, + 0.92347288 -0.18797997 0.33445698, + 0.90279925 -0.18382205 0.38879707, + 0.91304344 -0.12309006 0.38884518, + 0.88902688 -0.11990298 0.44187593, + 0.89502686 -0.060256992 0.44192293, + 0.86780185 -0.058475886 0.49345788, + 0.83762819 0.055655815 0.54339814, + 0.80459613 0.053405806 0.59141606, + 0.7670328 0.050822888 0.63959181, + 0.80458581 0.053374387 0.59143287, + 0.83762884 -0.056510784 0.54330885, + 0.86779499 -0.058490802 0.49346799, + 0.86197698 -0.116325 0.49342099, + 0.8890177 -0.11992095 0.44188985, + 0.87904572 -0.17903493 0.44184285, + 0.90279979 -0.18382095 0.38879591, + 0.88853174 -0.24369495 0.38874692, + 0.90888226 -0.24922507 0.33439508, + 0.89021826 -0.30939105 0.33434808, + 0.90712601 -0.315218 0.278855, + 0.88406628 -0.37509215 0.27880609, + 0.89753729 -0.38075915 0.22237207, + 0.87010771 -0.43986884 0.22232392, + 0.88021088 -0.44492993 0.16512498, + 0.84854573 -0.50271183 0.16507894, + 0.85539973 -0.50672585 0.10733196, + 0.81963581 -0.56274891 0.10728898, + 0.8234179 -0.56529993 0.049182493, + 0.78382301 -0.61903697 0.049139101, + 0.78476089 -0.61973095 -0.0091517894, + 0.74162674 -0.67074978 -0.0091930367, + 0.73999208 -0.66922504 -0.067449905, + 0.69363517 -0.7171582 -0.067487314, + 0.6897462 -0.71309018 -0.12551004, + 0.64056325 -0.75757331 -0.12554504, + 0.63477474 -0.7506817 -0.18313394, + 0.5832091 -0.79140216 -0.18316604, + 0.57590592 -0.78144389 -0.24016197, + 0.52242416 -0.81815732 -0.24019109, + 0.51402491 -0.80495685 -0.29634896, + 0.45909399 -0.837493 -0.29637501, + 0.45003188 -0.82091379 -0.3515279, + 0.39415994 -0.8491469 -0.35154998, + 0.38488519 -0.82911539 -0.40550119, + 0.32864514 -0.85296243 -0.40552118, + 0.32047781 -0.83172154 -0.45335773, + 0.26823306 -0.84261018 -0.46696812, + 0.26825413 -0.84260345 -0.46696821, + 0.26278207 -0.84676319 -0.46253413, + 0.27090997 -0.87300789 -0.40554294, + 0.32865009 -0.8529582 -0.4055261, + 0.33656985 -0.87356257 -0.35158083, + 0.39417124 -0.84913749 -0.35156021, + 0.40211093 -0.86629188 -0.29638696, + 0.45908478 -0.83750159 -0.29636484, + 0.46658507 -0.85123414 -0.24020603, + 0.52241498 -0.81816602 -0.240181, + 0.52903813 -0.82858521 -0.18320805, + 0.58321804 -0.7913931 -0.18317701, + 0.58853775 -0.79865772 -0.12557496, + 0.64056021 -0.75757629 -0.12554204, + 0.6441732 -0.76189518 -0.067503817, + 0.6936208 -0.71717381 -0.067468286, + 0.69515175 -0.71880376 -0.0092299264, + 0.74162585 -0.6707508 -0.0091918884, + 0.74074 -0.66999602 0.049086999, + 0.78383231 -0.61902624 0.049127117, + 0.78023189 -0.61623096 0.10722698, + 0.8196491 -0.56273305 0.10727002, + 0.81307799 -0.558267 0.165052, + 0.84853202 -0.502729 0.165097, + 0.8387956 -0.49700677 0.2222749, + 0.87011081 -0.43986487 0.22231995, + 0.85705286 -0.43331093 0.27875096, + 0.8840729 -0.37508294 0.27879697, + 0.8675921 -0.36813802 0.33430302, + 0.89021689 -0.30939296 0.33434996, + 0.8702867 -0.30251589 0.38869685, + 0.88853413 -0.24369103 0.38874406, + 0.86515456 -0.23732889 0.44179478, + 0.87904686 -0.17903398 0.44184095, + 0.8523156 -0.17364091 0.49336275, + 0.86198783 -0.11630397 0.49340689, + 0.8320111 -0.11231302 0.54327106, + 0.83762413 -0.056521006 0.54331505, + 0.80458391 -0.054346792 0.59134692, + 0.77124053 -0.0005068687 0.63654363, + 0.73820192 -0.021631498 0.67423296, + 0.73820698 -0.0214855 0.67423201, + 0.73820919 -0.021624705 0.67422515, + 0.76269037 -0.022301812 0.64637929, + 0.76269484 -0.022158295 0.64637882, + 0.7626971 -0.022309301 0.64637107, + 0.7595278 -0.10971197 0.64115584, + 0.75952089 -0.10976499 0.64115494, + 0.77057064 -0.052074675 0.63522369, + 0.80459863 -0.054316975 0.59132969, + 0.79920411 -0.10794102 0.59128803, + 0.83201009 -0.11231501 0.54327208, + 0.8226769 -0.16765198 0.54322696, + 0.85231882 -0.17363696 0.49335888, + 0.83884883 -0.23015894 0.49331489, + 0.86515784 -0.23732394 0.44179088, + 0.84738886 -0.29460597 0.44174594, + 0.870287 -0.30251601 0.38869601, + 0.84816188 -0.35996097 0.38865095, + 0.8675819 -0.36815098 0.33431497, + 0.84106112 -0.42529905 0.33427104, + 0.8570379 -0.43332893 0.27876896, + 0.82620841 -0.48958424 0.27872413, + 0.8388027 -0.49699882 0.22226593, + 0.80375117 -0.55190712 0.22222206, + 0.81307888 -0.55826592 0.16505098, + 0.77397901 -0.61133403 0.165007, + 0.78023487 -0.61622792 0.10722298, + 0.73734176 -0.66696274 0.10718197, + 0.74074399 -0.66999203 0.049082901, + 0.69435126 -0.71796322 0.049043518, + 0.69518101 -0.71877497 -0.0092670303, + 0.64561522 -0.76360631 -0.0093033137, + 0.64419204 -0.76187712 -0.067528211, + 0.59186822 -0.80319828 -0.067561924, + 0.58854926 -0.79864728 -0.12558804, + 0.53386718 -0.83618528 -0.12561904, + 0.52904189 -0.82858181 -0.18321295, + 0.47249317 -0.86207527 -0.18323906, + 0.46657982 -0.85123873 -0.24019991, + 0.40867901 -0.88049698 -0.24022201, + 0.40210915 -0.86629331 -0.29638511, + 0.343321 -0.89122099 -0.29640499, + 0.33654404 -0.87358212 -0.35155702, + 0.27744809 -0.89410228 -0.35157311, + 0.27091613 -0.87300354 -0.40554824, + 0.21196011 -0.88915342 -0.40556017, + 0.21196696 -0.88914877 -0.4055669, + 0.21707797 -0.91063887 -0.35158798, + 0.27745107 -0.89410025 -0.35157609, + 0.28303608 -0.9121483 -0.29643911, + 0.34334013 -0.89120728 -0.29642412, + 0.34895018 -0.9058184 -0.24026412, + 0.40870079 -0.88048059 -0.24024488, + 0.41388208 -0.89168924 -0.18328105, + 0.47250777 -0.86206359 -0.18325591, + 0.47681877 -0.86997557 -0.12564394, + 0.53386503 -0.83618712 -0.12561601, + 0.53687584 -0.84095073 -0.06757348, + 0.59185302 -0.80321097 -0.067543797, + 0.59315926 -0.8050313 -0.0093178134, + 0.64559907 -0.76362014 -0.0092841005, + 0.64482695 -0.7627539 0.049037594, + 0.69432682 -0.7179848 0.049073089, + 0.69113719 -0.71473318 0.10717303, + 0.73731863 -0.66698372 0.10720995, + 0.73140776 -0.66168278 0.16498093, + 0.77396911 -0.61134309 0.16502002, + 0.76508969 -0.60437673 0.22218592, + 0.8037461 -0.55191207 0.22222804, + 0.82620984 -0.48958287 0.27872193, + 0.81081599 -0.48051 0.33419701, + 0.8410871 -0.42527106 0.33424103, + 0.82225382 -0.4157989 0.3885999, + 0.84816772 -0.35995388 0.38864484, + 0.8258509 -0.35053396 0.44169694, + 0.84739286 -0.29460198 0.44174093, + 0.82161683 -0.28569195 0.49328089, + 0.83883899 -0.23017301 0.493325, + 0.809672 -0.222224 0.54318303, + 0.82267761 -0.16764893 0.54322678, + 0.79023498 -0.161093 0.59125102, + 0.79919863 -0.10795095 0.59129369, + 0.75953811 -0.10265701 0.64231104, + 0.082845889 0.051594291 0.99522591, + 0.71180725 -0.17598206 0.67997122, + 0.66364509 -0.16415001 0.72981507, + 0.67465508 -0.11021701 0.72985804, + 0.62612879 -0.10236598 0.7729708, + 0.63228506 -0.051667206 0.77301115, + 0.58055794 -0.047522392 0.81283087, + 0.52633888 0.04181939 0.84924585, + 0.46528393 0.074922495 0.88198489, + 0.40737501 0.065487303 0.91091001, + 0.40072706 0.098048016 0.91093612, + 0.33414289 0.11081296 0.93598562, + 0.27535707 0.091169223 0.95700926, + 0.26706791 0.11302496 0.95702666, + 0.20893502 0.08824341 0.97394013, + 0.20110208 0.10475104 0.97395337, + 0.14425193 0.07490956 0.98670155, + 0.13768996 0.086274475 0.98671079, + 0.08284729 0.051591091 0.99522591, + 0.078354806 0.058099706 0.99523109, + 0.0733703 0.064203702 0.99523598, + 0.078356825 0.058096416 0.99523121, + 0.13022996 0.097088374 0.98671877, + 0.13768604 0.086286627 0.98671037, + 0.19194999 0.120613 0.97396499, + 0.20109791 0.10476695 0.97395253, + 0.25704411 0.13414305 0.95704448, + 0.26706895 0.11301397 0.95702773, + 0.32408687 0.13732195 0.93600762, + 0.33414313 0.11080604 0.93598634, + 0.39148 0.129968 0.91096199, + 0.40072593 0.098044284 0.91093689, + 0.45768911 0.11210803 0.88201624, + 0.46528178 0.074916862 0.88198656, + 0.52121389 0.084033176 0.84927881, + 0.52634007 0.041820604 0.84924513, + 0.63228625 -0.05166582 0.77301031, + 0.68128794 -0.055587694 0.72990197, + 0.67465395 -0.11021799 0.72985893, + 0.72338104 -0.11809801 0.68027407, + 0.72215337 -0.10437405 0.68381327, + 0.75659591 -0.10929398 0.64468396, + 0.75659734 -0.10928205 0.64468431, + 0.73006266 -0.10549295 0.67518872, + 0.73006094 -0.10550299 0.67518896, + 0.73006284 -0.10555498 0.67517883, + 0.72283804 -0.058906309 0.68850207, + 0.68128955 -0.055584766 0.7299006, + 0.63228583 0.05043599 0.77309179, + 0.57490718 0.092779733 0.81294131, + 0.52121121 0.084024727 0.84928131, + 0.45769212 0.11211903 0.88201326, + 0.44713712 0.14856003 0.88204223, + 0.39147893 0.12995799 0.91096389, + 0.37968683 0.16105193 0.91098857, + 0.32408696 0.13734098 0.93600488, + 0.31192011 0.16298006 0.93602538, + 0.25704104 0.13415802 0.95704311, + 0.19195108 0.12060805 0.97396535, + 0.13023502 0.097078614 0.98671913, + 0.12194204 0.10723504 0.98672736, + 0.073371209 0.064202406 0.9952361, + 0.067908876 0.069889277 0.99524063, + 0.055679828 0.079876535 0.9952485, + 0.73258781 0.058605187 0.67814481, + 0.68128783 0.054422189 0.72998983, + 0.67465442 0.10905407 0.7300334, + 0.62612295 0.10113298 0.77313787, + 0.61590576 0.15118293 0.77317768, + 0.56552005 0.13873401 0.81298214, + 0.55247194 0.18378398 0.8130179, + 0.5008738 0.16652994 0.84934872, + 0.48579395 0.20629597 0.8493799, + 0.43367508 0.18406504 0.88206923, + 0.41739509 0.21837504 0.88209623, + 0.36543998 0.19108297 0.91101086, + 0.34883013 0.21985008 0.91103429, + 0.29773703 0.18752304 0.9360491, + 0.28161782 0.21087688 0.93606746, + 0.21729195 0.19174296 0.95708877, + 0.16999206 0.14982507 0.97398937, + 0.15733302 0.16300401 0.9740001, + 0.11285795 0.11669695 0.98673451, + 0.061986484 0.075137287 0.99524474, + 0.061980978 0.075142972 0.99524462, + 0.067902774 0.069896668 0.99524051, + 0.11285494 0.11669993 0.98673439, + 0.12193298 0.10724898 0.98672688, + 0.16998693 0.14983495 0.97398865, + 0.29773599 0.18753 0.93604797, + 0.31192213 0.16295905 0.93602836, + 0.36543983 0.19106591 0.91101456, + 0.3796871 0.16104205 0.91099024, + 0.43367606 0.18406801 0.8820681, + 0.44713795 0.14857098 0.8820399, + 0.50087482 0.16653694 0.8493467, + 0.56552613 0.13875604 0.81297415, + 0.57491088 0.09278848 0.8129378, + 0.62612706 0.10114402 0.7731331, + 0.63228476 0.050434481 0.77309269, + 0.68128878 0.054425281 0.72998875, + 0.72745067 -0.00054637674 0.68615973, + 0.73059797 0.062254701 0.67996401, + 0.76676279 0.065396085 0.63859081, + 0.76676935 0.065294027 0.63859332, + 0.73059893 0.062156994 0.67997193, + 0.73059595 0.062192593 0.67997193, + 0.76066184 0.064801283 0.64590579, + 0.7606563 0.064864121 0.64590621, + 0.73281807 0.062446207 0.67755306, + 0.7328248 0.062380783 0.67755181, + 0.70762861 0.14281791 0.69200057, + 0.75031465 0.15150593 0.64348572, + 0.75030863 0.15153992 0.64348471, + 0.72415596 0.14621499 0.67395794, + 0.72199482 0.11678697 0.68197083, + 0.67465526 0.10905604 0.73003227, + 0.66364402 0.16299 0.73007601, + 0.61590677 0.15118894 0.77317572, + 0.60169375 0.20025493 0.77321571, + 0.55247277 0.18379191 0.81301558, + 0.53583509 0.22766303 0.81305009, + 0.48579583 0.20631292 0.84937471, + 0.46756813 0.24472606 0.84940517, + 0.41739509 0.21836704 0.88209826, + 0.39841291 0.25124294 0.88212478, + 0.34882912 0.21986407 0.91103131, + 0.32994404 0.24722303 0.91105312, + 0.28161493 0.21088396 0.93606675, + 0.26368907 0.23284006 0.93608421, + 0.21729808 0.19172807 0.95709038, + 0.20110001 0.208592 0.95710403, + 0.15732905 0.16301206 0.97399938, + 0.14362499 0.17515299 0.97400886, + 0.092554189 0.13327599 0.98674786, + 0.055687781 0.079869471 0.99524862, + 0.049024809 0.084082805 0.99525213, + 0.034760907 0.090855524 0.99525726, + 0.027279809 0.093352228 0.99525934, + 0.03476521 0.090853229 0.99525738, + 0.057780225 0.15153007 0.98676246, + 0.069838807 0.14639302 0.98675811, + 0.097361736 0.20440607 0.97403234, + 0.145155 0.250633 0.957138, + 0.16490896 0.23814194 0.95712775, + 0.20011701 0.28916401 0.93612897, + 0.22280003 0.27211902 0.93611515, + 0.26102704 0.31895503 0.91111612, + 0.28590393 0.29691693 0.91109776, + 0.32655188 0.33925587 0.88219571, + 0.35284504 0.31188303 0.88217312, + 0.39524886 0.34947389 0.84949768, + 0.4221389 0.3165409 0.84947079, + 0.46563882 0.34925789 0.8131417, + 0.49228683 0.31065187 0.81311071, + 0.53613412 0.3384091 0.77333015, + 0.56167388 0.29416993 0.77329582, + 0.60521102 0.317054 0.73020297, + 0.61998111 -0.64070517 -0.45290211, + 0.63566506 -0.65696108 -0.40537906, + 0.6781612 -0.61302012 -0.4053441, + 0.69450897 -0.62784797 -0.35137498, + 0.73491305 -0.58005607 -0.35133702, + 0.7497102 -0.59178412 -0.29618606, + 0.7875613 -0.54041219 -0.29614511, + 0.80043411 -0.54929405 -0.23996103, + 0.83535898 -0.49458599 -0.239917, + 0.84594768 -0.50090283 -0.18294494, + 0.8775239 -0.44328293 -0.18289898, + 0.88552588 -0.44737193 -0.12530899, + 0.9134351 -0.38722906 -0.12526001, + 0.91858613 -0.38946006 -0.067234308, + 0.94255477 -0.32722592 -0.067183785, + 0.94463724 -0.32799509 -0.0089318817, + 0.96443439 -0.26417309 -0.0088809524, + 0.96328288 -0.26390398 0.049404491, + 0.97875643 -0.19897188 0.049456369, + 0.97426099 -0.19810501 0.107564, + 0.98531073 -0.13259597 0.10761498, + 0.97741026 -0.13158002 0.16539605, + 0.98400664 -0.066017479 0.16544694, + 0.97271526 -0.065307014 0.22262105, + 0.95811623 0.063924313 0.27915406, + 0.94025636 0.062684424 0.33464712, + 0.93395436 0.12532805 0.33469713, + 0.91304302 0.122473 0.38904101, + 0.90279973 0.18320094 0.38908884, + 0.87904656 0.17833091 0.4421258, + 0.86515599 0.23661999 0.44217199, + 0.83884311 0.22937202 0.49369106, + 0.82161617 0.28490806 0.4937351, + 0.79304284 0.27494594 0.54358786, + 0.77289051 0.32726878 0.54363167, + 0.74240917 0.31430608 0.59164214, + 0.71971416 0.36321309 0.59168214, + 0.68937725 0.34784713 0.63542223, + 0.67159307 0.30616304 0.67470509, + 0.69407821 0.31645408 0.64661616, + 0.66141284 0.30152494 0.68674284, + 0.69407415 0.3164731 0.64661115, + 0.69405174 0.31652087 0.64661175, + 0.67156303 0.306227 0.67470598, + 0.67827779 0.2884469 0.67582375, + 0.62880594 0.26732698 0.73016393, + 0.69745123 0.23230208 0.67793626, + 0.64832729 0.2158611 0.73012036, + 0.62880683 0.26732793 0.7301628, + 0.58357996 0.24802397 0.77325189, + 0.56167489 0.29418394 0.7732898, + 0.51573092 0.27003896 0.81308091, + 0.49228689 0.31064394 0.81311381, + 0.42213616 0.31656212 0.8494643, + 0.376845 0.2825 0.882146, + 0.35284102 0.31189904 0.88216913, + 0.30891794 0.27296293 0.91107678, + 0.28590003 0.29692602 0.9110961, + 0.24403302 0.25331804 0.93609715, + 0.22278906 0.27213806 0.93611223, + 0.18359196 0.22410995 0.95711476, + 0.16489695 0.23815794 0.95712578, + 0.12900297 0.18613896 0.97401774, + 0.081459038 0.14029306 0.98675346, + 0.069843128 0.14638907 0.98675847, + 0.042023689 0.087761074 0.99525476, + 0.04200808 0.087770954 0.99525452, + 0.049001083 0.084100671 0.99525166, + 0.081441067 0.14030896 0.98675263, + 0.092541821 0.13328902 0.98674726, + 0.12900795 0.18613094 0.97401863, + 0.14363095 0.17514394 0.97400963, + 0.18359406 0.22410607 0.95711535, + 0.20109497 0.20860197 0.95710289, + 0.24403097 0.25332096 0.93609691, + 0.26368099 0.232862 0.93608099, + 0.30891913 0.2729601 0.91107732, + 0.32994798 0.24720398 0.91105688, + 0.37684983 0.28246984 0.88215357, + 0.39841408 0.25122905 0.88212824, + 0.46756783 0.24471791 0.84940767, + 0.51573092 0.27002397 0.81308585, + 0.5358339 0.22765595 0.81305283, + 0.58358002 0.24803001 0.77324998, + 0.60169607 0.20026202 0.77321213, + 0.6483283 0.21586511 0.73011833, + 0.66364425 0.16298807 0.73007625, + 0.71005905 0.17446601 0.68218607, + 0.70639515 0.14255802 0.69331318, + 0.75051272 0.15153494 0.64324778, + 0.74540591 0.20368297 0.63473094, + 0.72600204 0.23541203 0.64614403, + 0.70002884 0.22694694 0.67709285, + 0.7000308 0.22694094 0.67709285, + 0.72600502 0.235406 0.64614302, + 0.72601396 0.23537597 0.64614391, + 0.69669592 0.22582197 0.68089592, + 0.69668901 0.225843 0.68089598, + 0.69680393 0.22555196 0.68087494, + 0.73231661 0.23710889 0.63835073, + 0.70988601 0.30052799 0.63698101, + 0.7424078 0.3143549 0.59161788, + 0.76177412 0.26407304 0.59157908, + 0.79304361 0.27496988 0.54357475, + 0.80967498 0.221358 0.54353201, + 0.8388449 0.22938897 0.49367994, + 0.85231739 0.17285489 0.49363565, + 0.87904632 0.17832907 0.44212714, + 0.88902086 0.11919799 0.44207895, + 0.9130426 0.12246994 0.38904282, + 0.91920388 0.061220992 0.38899395, + 0.94025433 0.06267342 0.33465511, + 0.95811689 -0.064359196 0.27905196, + 0.97271925 -0.065291815 0.22260806, + 0.96619934 -0.13010505 0.22255707, + 0.97741377 -0.13156797 0.16538495, + 0.96644503 -0.196592 0.165335, + 0.97425234 -0.19813308 0.10759003, + 0.9588539 -0.26274398 0.10753998, + 0.96328098 -0.26391 0.049409799, + 0.94350511 -0.32766104 0.049360108, + 0.94463354 -0.32800585 -0.008920785, + 0.92060935 -0.39038214 -0.008968493, + 0.91858089 -0.38947493 -0.067219391, + 0.89052087 -0.44994193 -0.067267194, + 0.88552612 -0.44737107 -0.12531002, + 0.85365498 -0.50552797 -0.125358, + 0.84594315 -0.5009141 -0.18293504, + 0.8105849 -0.55630094 -0.18297899, + 0.80043709 -0.54928803 -0.23996504, + 0.76195073 -0.60152078 -0.24000791, + 0.74970222 -0.59180224 -0.29617012, + 0.70848209 -0.64055705 -0.29620904, + 0.69449919 -0.62786716 -0.35136008, + 0.65099782 -0.67284679 -0.35139591, + 0.63566899 -0.65695298 -0.405386, + 0.59034806 -0.69794303 -0.40541905, + 0.57397205 -0.67853105 -0.45842305, + 0.58559376 -0.66871077 -0.45815486, + 0.58187693 -0.66461593 -0.46872693, + 0.58187103 -0.66462106 -0.46872705, + 0.64717716 -0.60163713 -0.46818212, + 0.64717919 -0.6016351 -0.46818212, + 0.79852533 -0.37670317 -0.46952325, + 0.7985183 -0.37671816 -0.46952319, + 0.79471785 -0.40122291 -0.45545989, + 0.8161031 -0.41206905 -0.40518507, + 0.8418209 -0.35664997 -0.40513995, + 0.86211801 -0.36530101 -0.351152, + 0.88461411 -0.30689403 -0.35110402, + 0.90242189 -0.31311998 -0.29595697, + 0.92133564 -0.25214791 -0.29590887, + 0.93639088 -0.25631696 -0.23973697, + 0.95143551 -0.19318691 -0.23968588, + 0.96349555 -0.19568391 -0.18271291, + 0.97442234 -0.13090505 -0.18266106, + 0.98331225 -0.13214503 -0.12503903, + 0.98994964 -0.066165477 -0.12498695, + 0.99553055 -0.066585273 -0.066971868, + 0.99653786 0.066672392 0.049668893, + 0.98985553 0.13309294 0.049722176, + 0.98530924 0.13243502 0.10782702, + 0.97425526 0.19796105 0.10788002, + 0.966447 0.196328 0.165637, + 0.95117038 0.2604281 0.16568705, + 0.94025534 0.25739309 0.22286507, + 0.92095262 0.31961787 0.22291392, + 0.90712678 0.31477091 0.27935693, + 0.88407075 0.37463692 0.27940294, + 0.86758786 0.36760396 0.33490098, + 0.8410781 0.42473307 0.33494702, + 0.8222518 0.4151769 0.3892689, + 0.79264617 0.46920112 0.38931009, + 0.77179188 0.45680594 0.44234094, + 0.73954117 0.50732511 0.44238013, + 0.7170518 0.49184689 0.49388587, + 0.68256807 0.53864807 0.49392205, + 0.65883023 0.51986116 0.54377121, + 0.62261885 0.56269187 0.54380488, + 0.59806389 0.54044491 0.59180987, + 0.5471881 0.53117013 0.64687216, + 0.54713517 0.53122318 0.64687324, + 0.52980894 0.51436192 0.67433995, + 0.52985907 0.51431006 0.67434007, + 0.52981108 0.51435703 0.67434204, + 0.54713994 0.53121996 0.64687192, + 0.53637302 0.554093 0.63661999, + 0.56060106 0.57918006 0.59184206, + 0.483412 0.59063601 0.64611298, + 0.458527 0.62181997 0.63489598, + 0.47833219 0.64873326 0.59189826, + 0.39939591 0.62093687 0.67447782, + 0.41422305 0.64403206 0.64315003, + 0.4120349 0.64491683 0.64366883, + 0.43390909 0.67922318 0.59192812, + 0.47833681 0.64872473 0.59190375, + 0.49797612 0.67541617 0.54390514, + 0.54202318 0.64063221 0.54387617, + 0.56154698 0.663764 0.49404699, + 0.60462612 0.6248011 0.49401513, + 0.62359822 0.64445925 0.44249016, + 0.66528398 0.60135603 0.44245699, + 0.68325907 0.61765409 0.38943607, + 0.72300333 0.57064331 0.38940018, + 0.73956519 0.5837661 0.33505309, + 0.77692699 0.53305799 0.335013, + 0.82620901 0.48914 0.27950099, + 0.83880115 0.49664307 0.22306603, + 0.87010789 0.43951595 0.22301997, + 0.88021028 0.44466615 0.16583706, + 0.90795743 0.38487318 0.16578907, + 0.91529125 0.3880291 0.10805302, + 0.93917203 0.32602301 0.108004, + 0.94350791 0.32757398 0.049881794, + 0.96328264 0.26382491 0.049829982, + 0.9644345 0.26418689 -0.0084446762, + 0.97992486 0.19918597 -0.0084956093, + 0.97776502 0.19879299 -0.066760004, + 0.98885721 0.13303202 -0.066813111, + 0.98331362 0.13233295 -0.12482896, + 0.98994935 0.066370219 -0.12488104, + 0.98100013 0.065817006 -0.18250202, + 0.96871978 -0.064657085 -0.23958594, + 0.95314598 -0.063569903 -0.29575601, + 0.94675612 -0.12708901 -0.29580602, + 0.92807221 -0.12453303 -0.35096109, + 0.89605474 -0.18181096 -0.40500692, + 0.88189286 -0.24123897 -0.40505394, + 0.85926628 -0.23500109 -0.45435214, + 0.85854143 -0.2058901 -0.46959123, + 0.85853529 -0.20591608 -0.46959117, + 0.87336683 -0.17716296 -0.45369989, + 0.8960551 -0.18181401 -0.40500507, + 0.90621924 -0.12155503 -0.4049581, + 0.92807275 -0.12453697 -0.3509579, + 0.93433666 -0.062273778 -0.35090888, + 0.95314711 -0.063577004 -0.29575104, + 0.9687199 0.065035693 -0.23948297, + 0.98100114 0.065812506 -0.18249801, + 0.97442365 0.13119495 -0.18244594, + 0.98331088 0.13234398 -0.12483899, + 0.97228378 0.19771795 -0.12478697, + 0.97776687 0.19878598 -0.066753894, + 0.96230465 0.26366791 -0.066701181, + 0.96442974 0.26420394 -0.0084602181, + 0.94463336 0.32802013 -0.0084095029, + 0.94350511 0.32758301 0.049874809, + 0.91951013 0.38988307 0.049923606, + 0.91528624 0.3880451 0.10803802, + 0.88731998 0.448309 0.108085, + 0.88020915 0.44467005 0.16583301, + 0.84853482 0.50246686 0.16587895, + 0.83879679 0.49665388 0.22305794, + 0.80374688 0.55155891 0.22309998, + 0.75361484 0.59489089 0.27958795, + 0.73956996 0.58375496 0.33506197, + 0.69889802 0.63186097 0.33510199, + 0.68325305 0.61766708 0.38942605, + 0.64045602 0.66191798 0.38946199, + 0.62360299 0.64445001 0.44249699, + 0.57914311 0.68466216 0.44252813, + 0.5615319 0.66379082 0.49402788, + 0.51591992 0.69981092 0.49405593, + 0.49797606 0.67541707 0.54390407, + 0.45170507 0.70718008 0.54392904, + 0.43389601 0.67924201 0.59191602, + 0.38754481 0.70669562 0.59193772, + 0.59440178 0.79128867 0.14334795, + 0.60092187 0.78183883 0.16619596, + 0.63672966 0.75298554 0.1660969, + 0.64187568 0.75911766 0.10833295, + 0.69113797 0.71456295 0.10829698, + 0.69432783 0.71790683 0.050186887, + 0.74074018 0.66991717 0.05014991, + 0.74162579 0.67076474 -0.0081248069, + 0.78477186 0.61973095 -0.0081648193, + 0.78304231 0.61841226 -0.066416122, + 0.82259214 0.56473505 -0.06645821, + 0.81797689 0.56161392 -0.12451299, + 0.85365498 0.50572598 -0.124557, + 0.8459416 0.50120378 -0.18214691, + 0.87751913 0.44358307 -0.18219301, + 0.8665309 0.43807593 -0.23919398, + 0.89384073 0.37922686 -0.23923992, + 0.87947088 0.37317696 -0.29541498, + 0.90242022 0.31359109 -0.29546306, + 0.88461512 0.30745202 -0.35061303, + 0.90315813 0.24767503 -0.35066003, + 0.88189077 0.24189194 -0.4046689, + 0.89605427 0.18245804 -0.40471709, + 0.87244558 0.17769991 -0.4552598, + 0.73640496 0.48890993 -0.46762693, + 0.73641008 0.48890206 -0.46762705, + 0.57516795 0.78237486 -0.23889597, + 0.60985309 0.75606209 -0.23759103, + 0.57601106 0.78199512 -0.23810703, + 0.56663483 0.76931471 -0.29509288, + 0.61676812 0.72972518 -0.29512405, + 0.60459602 0.71537298 -0.35029301, + 0.65099818 0.67340416 -0.35032609, + 0.63567102 0.65759897 -0.40433401, + 0.67814797 0.61367899 -0.40436801, + 0.66138184 0.59855288 -0.45200488, + 0.68220025 0.5616222 -0.46817017, + 0.682208 0.56161302 -0.46816999, + 0.69810897 0.55165797 -0.45641801, + 0.71760821 0.56701517 -0.40439114, + 0.67816597 0.61366898 -0.40435299, + 0.69451296 0.62841094 -0.35035896, + 0.6510002 0.6734032 -0.35032409, + 0.66410404 0.68690908 -0.29516402, + 0.61676031 0.72972935 -0.29513016, + 0.62683994 0.74160695 -0.23893698, + 0.58472526 0.78700429 -0.19677608, + 0.59638792 0.78179389 -0.18198799, + 0.63477784 0.75096983 -0.18193795, + 0.62682903 0.74161297 -0.238947, + 0.67496103 0.69808006 -0.23898102, + 0.66411096 0.68690497 -0.29515797, + 0.70848018 0.64102715 -0.29519507, + 0.69449496 0.62842196 -0.35037497, + 0.73489708 0.58063507 -0.35041302, + 0.71760106 0.56702006 -0.40439707, + 0.7538619 0.51780593 -0.40443695, + 0.73272419 0.50333911 -0.45800111, + 0.74045491 0.49209893 -0.45778295, + 0.62161022 0.62917322 -0.46662816, + 0.62164408 0.62913907 -0.46662906, + 0.43766886 0.79897273 -0.41241786, + 0.42807186 0.78149468 -0.45389485, + 0.4011789 0.78697884 -0.46874288, + 0.40115783 0.78698963 -0.46874279, + 0.86963409 0.15410802 -0.46902806, + 0.86963588 0.15409799 -0.46902794, + 0.88256115 0.064280108 -0.46578306, + 0.88256341 0.064248927 -0.46578321, + 0.88363189 0.11920699 -0.45275193, + 0.90621847 0.12220593 -0.40476376, + 0.89605576 0.18245496 -0.40471491, + 0.90315527 0.24768005 -0.35066408, + 0.92133635 0.25261608 -0.29550713, + 0.90242398 0.31358501 -0.29545799, + 0.89384389 0.37922195 -0.23923597, + 0.9051789 0.38398293 -0.18223098, + 0.87752575 0.44357389 -0.18218295, + 0.85365802 0.50572199 -0.124552, + 0.85847259 0.50852776 -0.06651587, + 0.82258368 0.56474584 -0.066470474, + 0.82440072 0.56594682 -0.0082236072, + 0.78476071 0.61974478 -0.0081803668, + 0.78382385 0.61895788 0.050112888, + 0.7407428 0.66991383 0.050153989, + 0.73733974 0.66678876 0.10827196, + 0.69114894 0.71454996 0.10831199, + 0.68561178 0.70877874 0.16603994, + 0.63671279 0.75300473 0.16607393, + 0.62940478 0.74431676 0.22325392, + 0.89081401 0.000361805 -0.454368, + 0.91233873 0.061387584 -0.40480793, + 0.93433774 0.062817082 -0.35080892, + 0.92807311 0.12509102 -0.35076004, + 0.94675422 0.12755904 -0.29561007, + 0.95143253 0.19358291 -0.23937789, + 0.93639135 0.25669608 -0.23932908, + 0.94826448 0.25990212 -0.18233308, + 0.92879689 0.32265896 -0.18228398, + 0.93726599 0.32555401 -0.124688, + 0.91343576 0.3874279 -0.12463797, + 0.91858703 0.38956699 -0.066599101, + 0.89051771 0.45005485 -0.066550374, + 0.89248389 0.45100293 -0.0082979687, + 0.86037487 0.50959492 -0.008250569, + 0.85934782 0.50893986 0.05001539, + 0.82341915 0.56522113 0.050058611, + 0.81963712 0.56257904 0.10816602, + 0.78023463 0.61605573 0.10820895, + 0.77397752 0.61106867 0.1659939, + 0.73142874 0.66139579 0.16603494, + 0.72303778 0.65376174 0.22318593, + 0.67774105 0.70059907 0.22322203, + 0.66756481 0.69003284 0.27966395, + 0.6199677 0.73308164 0.27969888, + 0.60841286 0.71936882 0.33517492, + 0.42767072 0.7996245 0.42154276, + 0.39002484 0.80736768 0.44276184, + 0.39253587 0.8125627 0.43087986, + 0.40921009 0.8183822 0.40348208, + 0.43989414 0.80238527 0.40332514, + 0.43109316 0.78629529 0.44260415, + 0.256473 0.71821398 0.64683098, + 0.16720892 0.71869266 0.67492372, + 0.301467 0.813968 0.496562, + 0.31211415 0.81002337 0.49643424, + 0.30171096 0.78297287 0.54398894, + 0.24872294 0.80137181 0.5440039, + 0.23891397 0.7697109 0.59200096, + 0.186938 0.78394902 0.59201199, + 0.177559 0.744551 0.64351898, + 0.17318499 0.74445993 0.64481497, + 0.1672 0.718687 0.674932, + 0.167243 0.71867698 0.674932, + 0.17363605 0.74619716 0.64268219, + 0.17360009 0.74620634 0.6426813, + 0.22888403 0.73740208 0.63549209, + 0.23889886 0.76972353 0.59199065, + 0.28982395 0.7520408 0.59197688, + 0.30171898 0.78296489 0.54399592, + 0.35338622 0.76105648 0.54397732, + 0.41798615 0.76232529 0.49411318, + 0.431097 0.786291 0.442608, + 0.48267707 0.75574011 0.44258305, + 0.49572012 0.77621216 0.38955909, + 0.54647988 0.7413668 0.38953191, + 0.55899483 0.7583937 0.33520687, + 0.5074932 0.79151028 0.34053212, + 0.51461118 0.7891413 0.3353081, + 0.55899185 0.7583977 0.33520287, + 0.56960911 0.77285117 0.27972606, + 0.61996377 0.73308676 0.2796939, + 0.62941283 0.7443068 0.22326393, + 0.67774498 0.70059299 0.22322901, + 0.68561482 0.70877481 0.16604395, + 0.73141122 0.66142225 0.16600706, + 0.73732102 0.66681403 0.108244, + 0.78023285 0.61605889 0.10820498, + 0.78383088 0.61894792 0.050124992, + 0.82343346 0.56519836 0.050082728, + 0.82441884 0.56592089 -0.0081951879, + 0.86038089 0.50958496 -0.0082405293, + 0.85848516 0.5085091 -0.066495612, + 0.89052171 0.45004785 -0.06654308, + 0.9134329 0.38743293 -0.12464398, + 0.90518087 0.38397995 -0.18222798, + 0.92880023 0.32265308 -0.18227805, + 0.9363901 0.25669903 -0.23933104, + 0.92133522 0.25261807 -0.29550907, + 0.92807138 0.12509504 -0.35076311, + 0.90622157 0.12219994 -0.40475881, + 0.91233975 0.061385885 -0.4048059, + 0.8846311 0.059577309 -0.46247005, + 0.88432932 0.064439826 -0.46239519, + 0.88257676 -0.026497794 -0.46942088, + 0.8825779 -0.026459597 -0.46942094, + 0.87776226 -0.11716903 -0.46454811, + 0.87776387 -0.11715698 -0.46454793, + 0.88932014 -0.059161909 -0.45344207, + 0.91233897 -0.060741201 -0.40490499, + 0.93433225 0.062832318 -0.35082108, + 0.95314538 0.064047925 -0.29565513, + 0.94675702 0.127552 -0.29560399, + 0.96222967 0.12958795 -0.23941791, + 0.95143837 0.19356908 -0.23936608, + 0.96349686 0.19597398 -0.18239498, + 0.94825912 0.25991404 -0.18234402, + 0.95690787 0.26223698 -0.12473599, + 0.93726712 0.32555202 -0.12468501, + 0.94255221 0.3273401 -0.066662617, + 0.91858 0.38958099 -0.066613801, + 0.92060912 0.39039606 -0.0083596809, + 0.89247721 0.45101613 -0.0083118118, + 0.89141202 0.45043099 0.049965002, + 0.85934567 0.5089438 0.050011382, + 0.85539711 0.50655907 0.10813802, + 0.81964773 0.56255984 0.10818496, + 0.81307799 0.55800402 0.165939, + 0.77397031 0.61108124 0.16598105, + 0.76509088 0.60402393 0.22313897, + 0.72303283 0.65376985 0.22317794, + 0.71217394 0.64390296 0.27963796, + 0.66757172 0.69002163 0.27967489, + 0.65513599 0.67711902 0.33512199, + 0.60839701 0.719392 0.335154, + 0.59477311 0.70323217 0.3894991, + 0.54647785 0.74136984 0.3895289, + 0.53210175 0.72181666 0.4425478, + 0.48267013 0.75574917 0.44257513, + 0.46798593 0.73270696 0.49409494, + 0.41799209 0.76231819 0.49411911, + 0.40345699 0.73575503 0.54395503, + 0.35338318 0.76105934 0.54397523, + 0.33944696 0.73098993 0.59197092, + 0.28984094 0.75202483 0.59198886, + 0.27703005 0.71872717 0.63771915, + 0.34043908 0.69077915 0.63790721, + 0.34017497 0.69090194 0.63791496, + 0.32412803 0.69801909 0.63852209, + 0.33942109 0.73101717 0.59195215, + 0.38753983 0.70670164 0.59193373, + 0.40344715 0.73576623 0.54394716, + 0.45170012 0.70718718 0.54392409, + 0.46797499 0.73272198 0.49408299, + 0.51592189 0.69980884 0.49405688, + 0.53210473 0.72181261 0.44255072, + 0.57913685 0.68467277 0.44251984, + 0.59478122 0.70321923 0.38951015, + 0.64046603 0.66190004 0.38947606, + 0.65513879 0.67711478 0.33512488, + 0.69889122 0.63187522 0.33508912, + 0.71216184 0.64392483 0.27961794, + 0.75361168 0.59489876 0.27957991, + 0.76509613 0.60401404 0.22314803, + 0.80375016 0.55155212 0.22310506, + 0.813079 0.558002 0.165941, + 0.84854299 0.50244701 0.165897, + 0.85539931 0.50655419 0.10814304, + 0.88732541 0.44829521 0.10809805, + 0.89142102 0.45041099 0.049985401, + 0.91951537 0.38986915 0.049936119, + 0.92061478 0.39038292 -0.0083467783, + 0.94463724 0.3280091 -0.008398422, + 0.94255549 0.32733214 -0.066654429, + 0.96230322 0.26367205 -0.066705614, + 0.95690674 0.26223993 -0.12473897, + 0.97228235 0.19772308 -0.12479104, + 0.96349412 0.19598202 -0.18240102, + 0.97442126 0.13120303 -0.18245305, + 0.96222275 0.12960798 -0.23943494, + 0.96871901 0.065038502 -0.23948599, + 0.95314765 0.064040877 -0.29564887, + 0.93433315 -0.062258106 -0.35092103, + 0.91233975 -0.060742885 -0.40490291, + 0.90622067 -0.12156195 -0.40495285, + 0.87787712 -0.11770201 -0.46419606, + 0.87795013 -0.11718801 -0.46418807, + 0.83612984 -0.29398194 -0.46309987, + 0.8373552 -0.29039007 -0.46315211, + 0.86378801 -0.299615 -0.405094, + 0.88189387 -0.24124897 -0.40504593, + 0.9031567 -0.24711591 -0.35105789, + 0.93613487 -0.19004497 -0.29586196, + 0.94675535 -0.12708105 -0.29581213, + 0.96222526 -0.12920603 -0.23964205, + 0.96871901 -0.064654298 -0.23959, + 0.98100054 -0.065521672 -0.18260591, + 0.98995036 0.066364624 -0.12487604, + 0.9955309 0.06669189 -0.066860795, + 0.98885834 0.13302605 -0.066807725, + 0.99104238 0.13327405 -0.0085447729, + 0.97992551 0.19918291 -0.0084928265, + 0.97875524 0.19889905 0.049773213, + 0.96328121 0.26383105 0.049824711, + 0.95885521 0.26257205 0.10794802, + 0.93917066 0.32602888 0.10799796, + 0.93164462 0.32336989 0.16574094, + 0.90795797 0.38487101 0.165791, + 0.89753675 0.3804059 0.22297794, + 0.8701098 0.43950987 0.22302493, + 0.85704768 0.43286484 0.27945891, + 0.82620871 0.48913881 0.27950391, + 0.81081527 0.47997618 0.33496511, + 0.77692282 0.53306788 0.33500692, + 0.75952703 0.52108097 0.38935, + 0.72299796 0.57065696 0.38938993, + 0.70397234 0.55558926 0.44242921, + 0.66528893 0.60134393 0.44246593, + 0.6450572 0.58300412 0.49397111, + 0.60461897 0.62481594 0.49400494, + 0.58360201 0.60304302 0.543827, + 0.54200625 0.64066428 0.54385525, + 0.49583387 0.58597487 0.64092284, + 0.56060207 0.57918006 0.59184104, + 0.58361506 0.60301405 0.54384506, + 0.6226244 0.5626784 0.54381239, + 0.64505619 0.58300614 0.49397013, + 0.68257391 0.53862995 0.49393395, + 0.70397782 0.55557287 0.44244087, + 0.73954916 0.50729513 0.44240111, + 0.75953418 0.52105612 0.3893691, + 0.792651 0.469179 0.38932699, + 0.81081414 0.47998005 0.33496204, + 0.84107 0.42477199 0.33491799, + 0.85704273 0.43288684 0.2794399, + 0.88406861 0.37464881 0.27939388, + 0.89753687 0.38040495 0.22297896, + 0.92095578 0.31959692 0.22293094, + 0.93164736 0.32335511 0.16575506, + 0.95117277 0.26040894 0.16570295, + 0.95885736 0.2625601 0.10795803, + 0.97425836 0.19793208 0.10790604, + 0.97875625 0.19889304 0.049778111, + 0.989856 0.13308799 0.0497263, + 0.99103951 0.13329394 -0.0085632261, + 0.99553025 0.066697411 -0.066865817, + 0.98995012 -0.066171207 -0.12498102, + 0.9810009 -0.065526195 -0.18260199, + 0.97442251 -0.13091294 -0.1826539, + 0.96222699 -0.129227 -0.23962399, + 0.95143563 -0.19320093 -0.23967391, + 0.93613499 -0.190046 -0.29586101, + 0.92133576 -0.25214493 -0.29591095, + 0.90315688 -0.24712098 -0.35105398, + 0.88461387 -0.30689698 -0.35110196, + 0.86378771 -0.29962289 -0.40508884, + 0.84182012 -0.35666102 -0.40513206, + 0.82078129 -0.34770113 -0.45323515, + 0.8348189 -0.29350498 -0.46575993, + 0.83481342 -0.29352015 -0.4657602, + 0.7593388 -0.4588109 -0.46140787, + 0.76344889 -0.45181593 -0.46152794, + 0.78673285 -0.46565294 -0.40523893, + 0.81610519 -0.41205508 -0.40519509, + 0.8357842 -0.42204309 -0.3512041, + 0.86211902 -0.36529201 -0.35115901, + 0.87947589 -0.37269396 -0.29600897, + 0.90242201 -0.31311399 -0.29596299, + 0.93639112 -0.25631404 -0.23973903, + 0.94826221 -0.25961205 -0.18275805, + 0.96349514 -0.19569203 -0.18270701, + 0.97228312 -0.19752303 -0.12510101, + 0.98331237 -0.13213505 -0.12504904, + 0.98885751 -0.13292594 -0.06701947, + 0.99553055 -0.066590771 -0.066966869, + 0.99772936 -0.066784419 -0.0087218527, + 0.9965381 0.066662908 0.049677506, + 0.99196053 0.066310167 0.10778395, + 0.98530978 0.13242397 0.10783598, + 0.9774121 0.13131602 0.16559501, + 0.96644747 0.19631709 0.16564707, + 0.95535576 0.19401796 0.22282794, + 0.94025654 0.25737789 0.22287689, + 0.92614424 0.25346705 0.27930507, + 0.90712625 0.31477508 0.27935407, + 0.89021778 0.30885795 0.33484191, + 0.86758584 0.3676199 0.33488891, + 0.8481648 0.35934192 0.3892169, + 0.82224989 0.41518694 0.38926193, + 0.80061066 0.40420982 0.44230878, + 0.77179533 0.45679021 0.44235122, + 0.74832606 0.44284806 0.49385607, + 0.71705592 0.49183294 0.49389395, + 0.69211924 0.47467518 0.54374117, + 0.65883327 0.51985121 0.54377717, + 0.63285792 0.49929994 0.59176892, + 0.598059 0.54045999 0.59180099, + 0.57259697 0.51739395 0.63595295, + 0.6080901 0.46834713 0.64099717, + 0.60805911 0.46838611 0.64099818, + 0.6017971 0.47471711 0.64224917, + 0.63286084 0.49928787 0.59177589, + 0.66481924 0.45591414 0.59174126, + 0.6921162 0.47469011 0.54373211, + 0.72231221 0.42738816 0.54369515, + 0.74832797 0.442837 0.49386299, + 0.77626216 0.39186209 0.49382311, + 0.8006109 0.40420693 0.44231093, + 0.82584572 0.34982687 0.44226685, + 0.84816587 0.35933298 0.38922295, + 0.870287 0.30189699 0.38917699, + 0.8902173 0.30886111 0.33484012, + 0.90887702 0.248712 0.334791, + 0.92614335 0.2534861 0.27929109, + 0.94102252 0.19105291 0.27924088, + 0.95535612 0.19401103 0.22283302, + 0.96619511 0.12975101 0.22278203, + 0.97741187 0.13130398 0.16560599, + 0.98400766 0.065738074 0.16555195, + 0.99196064 0.066316478 0.10777796, + 0.99653751 -0.066751368 0.049571179, + 0.99772936 -0.066784821 -0.0087215025, + 0.99104226 -0.13326003 -0.0087755015, + 0.98885787 -0.13291998 -0.067024894, + 0.97776634 -0.19868007 -0.067076519, + 0.97228336 -0.19751908 -0.12510504, + 0.95690745 -0.26203811 -0.12515706, + 0.94826102 -0.259624 -0.18274701, + 0.92879874 -0.3223629 -0.18279795, + 0.89384186 -0.37884495 -0.23983997, + 0.8794741 -0.37270704 -0.29599804, + 0.85260785 -0.43060192 -0.29604393, + 0.83578199 -0.42205599 -0.35119399, + 0.80570185 -0.47694495 -0.35123798, + 0.78673071 -0.46566382 -0.40523085, + 0.75385779 -0.51715785 -0.4052729, + 0.73518497 -0.50430292 -0.45296994, + 0.75679868 -0.45726186 -0.46708381, + 0.75679684 -0.45726487 -0.46708387, + 0.70499104 -0.53177404 -0.46925905, + 0.70501179 -0.53174579 -0.46925983, + 0.65025598 -0.60501301 -0.45948499, + 0.65882432 -0.5955143 -0.45968822, + 0.67815316 -0.61303812 -0.40533009, + 0.71760327 -0.56637716 -0.40529314, + 0.7349028 -0.58008188 -0.35131592, + 0.77201712 -0.52971208 -0.35127604, + 0.78755718 -0.5404231 -0.29613605, + 0.8219341 -0.48657307 -0.29609302, + 0.83536315 -0.49457312 -0.23992907, + 0.86653215 -0.43769607 -0.23988403, + 0.87752086 -0.44329295 -0.18288898, + 0.90517974 -0.38368991 -0.18284295, + 0.91343325 -0.38723508 -0.12525503, + 0.93726712 -0.32535204 -0.12520601, + 0.94255263 -0.32723388 -0.067175575, + 0.96230412 -0.26356202 -0.06712541, + 0.96442986 -0.26418996 -0.0088654188, + 0.97992551 -0.19916891 -0.0088128056, + 0.97875524 -0.19897704 0.049461212, + 0.98985523 -0.13317303 0.049514312, + 0.98530823 -0.13260703 0.10762502, + 0.99196011 -0.06648811 0.10767802, + 0.98400998 -0.0660019 0.165433, + 0.97271621 0.064937018 0.22272506, + 0.95811462 0.063914478 0.2791619, + 0.9516905 0.12777306 0.27921212, + 0.93395662 0.12534395 0.33468488, + 0.92348075 0.18744895 0.33473292, + 0.9027999 0.18320198 0.38908795, + 0.888533 0.24307001 0.389135, + 0.86515611 0.23662503 0.44216907, + 0.84739089 0.29389697 0.44221395, + 0.82161617 0.28490606 0.49373612, + 0.800731 0.33913299 0.49377999, + 0.77288985 0.32728797 0.54362094, + 0.74926537 0.37819818 0.54366124, + 0.71971279 0.36322591 0.59167588, + 0.69382417 0.41046908 0.59171212, + 0.65924197 0.38994601 0.64291698, + 0.65469825 0.39427915 0.64491421, + 0.63190305 0.38050905 0.67521209, + 0.63190377 0.38050684 0.67521274, + 0.65690184 0.39560691 0.6418528, + 0.65689617 0.39561608 0.64185315, + 0.63189977 0.38051686 0.67521077, + 0.6420778 0.3364459 0.68886882, + 0.6052109 0.3170639 0.7301988, + 0.57769096 0.36473098 0.73023593, + 0.53613275 0.33841684 0.77332765, + 0.5071218 0.38044786 0.77336073, + 0.46564099 0.34924501 0.813146, + 0.43596199 0.38559499 0.81317502, + 0.39524484 0.34949288 0.84949172, + 0.36579192 0.3801569 0.8495158, + 0.32654712 0.33927211 0.8821913, + 0.29812485 0.36445081 0.88221157, + 0.26101708 0.31897712 0.9111113, + 0.23444504 0.33894402 0.91112709, + 0.20010893 0.28917691 0.93612665, + 0.17612895 0.30433995 0.93613875, + 0.14514202 0.25064802 0.95713609, + 0.12444796 0.26150891 0.95714462, + 0.097359434 0.20440708 0.97403234, + 0.080537096 0.21157497 0.97403789, + 0.057770606 0.15153602 0.98676211, + 0.045322016 0.15569206 0.98676538, + 0.027269106 0.093356721 0.99525923, + 0.019586392 0.095250361 0.99526066, + 0.0039508613 0.097145535 0.99526238, + 0.58627409 0.44001207 0.68020004, + 0.54641986 0.4100239 0.73027784, + 0.51160395 0.45266694 0.73031092, + 0.47481099 0.42003599 0.77338499, + 0.43942595 0.45687595 0.7734139, + 0.40347201 0.41941199 0.81320602, + 0.36838287 0.45049787 0.81323171, + 0.33397704 0.40833306 0.84954309, + 0.29995793 0.4338969 0.84956384, + 0.26777589 0.38724682 0.88223356, + 0.23570488 0.4075278 0.88224959, + 0.20636904 0.3566981 0.91114122, + 0.17691304 0.37215808 0.91115326, + 0.15100303 0.3175261 0.93614924, + 0.12492602 0.32863602 0.93615812, + 0.10294498 0.27066395 0.95715374, + 0.080768973 0.27806792 0.95715964, + 0.063189104 0.21736403 0.97404313, + 0.045441985 0.22173892 0.97404665, + 0.032596398 0.15882801 0.98676801, + 0.019631494 0.16093495 0.98676974, + 0.011811798 0.09651088 0.99526179, + 0.011820698 0.096508682 0.99526191, + 0.019608198 0.095243081 0.99526089, + 0.032589994 0.15883096 0.98676777, + 0.045320813 0.15569302 0.98676527, + 0.063181169 0.2173689 0.97404253, + 0.080534391 0.21157597 0.97403789, + 0.10293999 0.27066898 0.9571529, + 0.12445597 0.26150095 0.95714575, + 0.15102394 0.31750289 0.93615365, + 0.17614698 0.30431697 0.93614286, + 0.20637488 0.3566888 0.91114348, + 0.23445003 0.33893502 0.91112912, + 0.26777792 0.38724285 0.88223469, + 0.29813203 0.36443403 0.8822161, + 0.33396903 0.40835205 0.84953713, + 0.36579192 0.3801589 0.84951484, + 0.40347093 0.41941693 0.81320387, + 0.43596295 0.38558993 0.81317687, + 0.47481117 0.42003715 0.77338427, + 0.50712097 0.38046494 0.77335286, + 0.54641992 0.41003093 0.73027396, + 0.57769072 0.36472782 0.73023766, + 0.61923075 0.39103484 0.68091476, + 0.62396705 0.37572607 0.68519706, + 0.65469331 0.39428717 0.64491427, + 0.63736796 0.43702593 0.63464195, + 0.60522026 0.46597019 0.64543027, + 0.57924396 0.44591895 0.68237293, + 0.5791449 0.44605389 0.68236881, + 0.60508895 0.46608993 0.64546692, + 0.60509288 0.46608487 0.6454668, + 0.58345509 0.44937605 0.67649204, + 0.58345103 0.44938105 0.67649204, + 0.58348596 0.44934794 0.67648393, + 0.54301977 0.48052275 0.68864167, + 0.51160485 0.45265985 0.73031479, + 0.47348681 0.49234381 0.73034775, + 0.43943211 0.45685613 0.77342218, + 0.40118605 0.49073905 0.77345014, + 0.36837512 0.45052114 0.81322229, + 0.33086088 0.47871083 0.8132447, + 0.29995483 0.43390372 0.84956151, + 0.26402095 0.45662588 0.84957981, + 0.23569691 0.40754086 0.88224572, + 0.20208292 0.42518279 0.88225961, + 0.17692605 0.37214208 0.91115725, + 0.14635497 0.38516691 0.91116774, + 0.12492304 0.32863912 0.93615735, + 0.097987153 0.33763084 0.93616456, + 0.080748029 0.2780821 0.95715737, + 0.058064975 0.28367284 0.95716155, + 0.045426078 0.22174689 0.97404552, + 0.027351286 0.22468489 0.97404754, + 0.019619407 0.16093905 0.98676938, + 0.0065520001 0.161994 0.98676997, + 0.0039421311 0.097146921 0.99526227, + -0.0039509111 0.097146824 0.99526227, + -0.019585701 0.095246799 0.99526101, + 0.46445495 0.56833595 0.67917293, + 0.4322708 0.52887577 0.73036462, + 0.38829282 0.56192374 0.73039067, + 0.36035708 0.52142012 0.77347517, + 0.31717601 0.54872602 0.773498, + 0.29122809 0.50375217 0.8132773, + 0.24967712 0.52556026 0.81329441, + 0.22636494 0.47640088 0.84958881, + 0.18726395 0.49306089 0.84960181, + 0.16716808 0.4400492 0.88227642, + 0.13114603 0.45207512 0.88228625, + 0.11482397 0.39570391 0.91117173, + 0.082550079 0.4036589 0.91117775, + 0.070458919 0.34440812 0.93617237, + 0.042465691 0.3489579 0.93617576, + 0.034994703 0.28741702 0.95716614, + 0.011685294 0.28929886 0.95716751, + 0.0091418037 0.22614707 0.97405034, + -0.0091465721 0.22614706 0.97405022, + -0.006561121 0.16199301 0.98677009, + -0.019631805 0.16093804 0.98676926, + -0.011811698 0.096510082 0.99526191, + -0.011820797 0.096510075 0.99526179, + -0.0039421013 0.097146235 0.99526238, + -0.0065519223 0.16199206 0.98677033, + 0.0065610623 0.16199206 0.98677033, + 0.009146505 0.22614589 0.97405052, + 0.02737581 0.22467408 0.97404933, + 0.034992792 0.28741795 0.95716578, + 0.058077093 0.28366598 0.95716286, + 0.070474289 0.34439796 0.93617487, + 0.098013625 0.3376101 0.93616927, + 0.11483405 0.39569515 0.9111743, + 0.14634597 0.3851749 0.91116577, + 0.1671541 0.44006428 0.88227153, + 0.20208396 0.42518193 0.88225979, + 0.22637093 0.47639284 0.84959167, + 0.26401389 0.4566378 0.84957558, + 0.29121184 0.50377876 0.81326658, + 0.33086413 0.47870418 0.81324732, + 0.36034492 0.52144688 0.77346283, + 0.40117693 0.49076393 0.77343887, + 0.43226907 0.52888209 0.73036104, + 0.47348005 0.49237207 0.73033303, + 0.50332296 0.52347791 0.68748593, + 0.46502218 0.56818116 0.67891425, + 0.486763 0.59480202 0.63974398, + 0.48670805 0.59484905 0.63974208, + 0.46497199 0.56823099 0.67890698, + 0.46505299 0.56816101 0.67891002, + 0.48341617 0.59064323 0.64610326, + 0.48337111 0.59068012 0.6461032, + 0.46480006 0.56794006 0.67926806, + 0.46484518 0.56790519 0.67926621, + 0.39162585 0.60885078 0.68987674, + 0.41368195 0.64320797 0.64432192, + 0.41368806 0.64320403 0.64432204, + 0.39939395 0.62093794 0.67447793, + 0.4157472 0.60173333 0.6819613, + 0.38829294 0.56192195 0.73039192, + 0.34175003 0.59135509 0.73041505, + 0.31716815 0.54874122 0.77349037, + 0.27192211 0.57248729 0.77350938, + 0.2496729 0.52556485 0.81329268, + 0.20655204 0.54393715 0.81330717, + 0.18726493 0.49305883 0.8496027, + 0.14690892 0.50653177 0.84961361, + 0.13114394 0.45207679 0.88228559, + 0.094289161 0.46116081 0.88229269, + 0.082554281 0.40365592 0.91117877, + 0.049747989 0.40898791 0.91118276, + 0.042461712 0.3489601 0.93617523, + 0.014162398 0.35124397 0.9361769, + 0.011670901 0.28930402 0.95716614, + -0.011685599 0.28930396 0.9571659, + -0.0091417553 0.22614589 0.97405052, + -0.027350413 0.2246771 0.97404945, + -0.019619092 0.16093694 0.98676962, + -0.032589704 0.15882902 0.98676813, + -0.019608594 0.095244877 0.99526078, + -0.027280306 0.093354024 0.99525923, + -0.042006798 0.087768294 0.99525487, + -0.049027178 0.084086962 0.99525154, + -0.042024285 0.087762468 0.99525464, + -0.069843605 0.14639102 0.98675811, + -0.057770021 0.15153506 0.98676234, + -0.080537394 0.21157497 0.97403789, + -0.063189633 0.2173671 0.97404248, + -0.08077158 0.27807695 0.95715678, + -0.058077876 0.28366986 0.95716155, + -0.070475914 0.34440508 0.93617225, + -0.042461496 0.34895796 0.93617588, + -0.04974778 0.40898585 0.91118371, + -0.016607497 0.41166091 0.91118574, + -0.018968096 0.47029987 0.88230276, + 0.018976292 0.47029981 0.8823027, + 0.021257708 0.52695018 0.8496303, + 0.063644908 0.52352804 0.84962809, + 0.070199996 0.57754797 0.81333286, + 0.11651603 0.57002014 0.81332719, + 0.12689702 0.62089807 0.77355212, + 0.17648698 0.60867494 0.77354187, + 0.19016692 0.65593475 0.73046976, + 0.26120505 0.68816221 0.6769082, + 0.24238594 0.63850081 0.73045582, + 0.31546101 0.66432101 0.67761499, + 0.29299697 0.61693394 0.73044193, + 0.24238998 0.63849592 0.73045892, + 0.22495407 0.59248924 0.77353227, + 0.17649305 0.6086691 0.77354521, + 0.16205601 0.55879909 0.81331509, + 0.116512 0.57002401 0.81332499, + 0.10563098 0.51670086 0.84962481, + 0.06365291 0.52352208 0.84963113, + 0.018968293 0.47030383 0.88230067, + 0.016607698 0.41166493 0.91118389, + -0.016617397 0.4116649 0.91118377, + -0.014183498 0.35124296 0.9361769, + -0.042465899 0.34896001 0.93617499, + -0.034994692 0.28741795 0.95716578, + -0.058064006 0.28366804 0.9571631, + -0.045425322 0.22174311 0.97404647, + -0.063180499 0.21736699 0.97404301, + -0.045320813 0.15569302 0.98676527, + -0.057781093 0.15153298 0.98676187, + -0.034765307 0.090853624 0.99525726, + -0.03476071 0.090854831 0.99525738, + -0.027268909 0.093355827 0.99525934, + -0.045322012 0.15569302 0.98676527, + -0.032596596 0.15882899 0.98676789, + -0.045443121 0.22174411 0.97404546, + -0.027376497 0.22467998 0.9740479, + -0.034992702 0.28741702 0.95716614, + -0.011670704 0.28930008 0.95716739, + -0.014162004 0.35123509 0.93618023, + 0.014183098 0.35123497 0.93617988, + 0.016617199 0.41165999 0.91118598, + 0.049750276 0.40898579 0.9111836, + 0.09429054 0.46115917 0.88229328, + 0.10562495 0.51670575 0.84962261, + 0.14691091 0.50652969 0.8496145, + 0.16204605 0.5588091 0.81331021, + 0.206536 0.543957 0.81329799, + 0.22493804 0.59251004 0.77352113, + 0.27191702 0.57249403 0.7735061, + 0.29299119 0.61694437 0.73043543, + 0.3417511 0.59135312 0.73041618, + 0.36550289 0.63253075 0.68287075, + 0.38825095 0.60354692 0.69641393, + 0.41423705 0.64402306 0.64315003, + 0.37136617 0.67713732 0.63527328, + 0.33678713 0.68439931 0.64666229, + 0.32520387 0.66082072 0.6764307, + 0.32519984 0.66082269 0.6764307, + 0.33678201 0.68440199 0.646662, + 0.33673415 0.68442529 0.64666229, + 0.32247296 0.65538996 0.68298995, + 0.3226749 0.6552968 0.68298382, + 0.322927 0.65518498 0.68297201, + 0.24501309 0.68615824 0.68494922, + 0.25644308 0.71822524 0.64683026, + 0.25646606 0.71821719 0.6468302, + 0.24793503 0.69428909 0.67564106, + 0.24794306 0.69428617 0.67564118, + 0.20174292 0.69596964 0.68914866, + 0.19015892 0.65594274 0.73046476, + 0.12688705 0.62090731 0.77354634, + 0.070192412 0.57755411 0.81332916, + 0.023447003 0.58132708 0.81333214, + 0.021257395 0.5269509 0.84962982, + -0.021257695 0.5269509 0.84962982, + -0.018976491 0.47030377 0.88230056, + -0.049750406 0.40898705 0.91118312, + -0.082549669 0.40365684 0.91117871, + -0.070457578 0.34440187 0.93617463, + -0.097983457 0.33761784 0.93616956, + -0.080745861 0.27807489 0.95715952, + -0.10293899 0.27066597 0.95715386, + -0.080534093 0.21157597 0.97403789, + -0.097362123 0.20440604 0.97403222, + -0.06983842 0.14639206 0.98675835, + -0.081438266 0.14030394 0.98675352, + -0.048999894 0.084098592 0.99525189, + -0.055678882 0.079875067 0.99524862, + -0.067909926 0.069890529 0.99524045, + -0.087501206 0.8279531 0.55392903, + -0.078354321 0.058099315 0.99523121, + -0.088455573 0.72797674 0.67987174, + -0.082385629 0.67794424 0.73048222, + -0.12688605 0.62090129 0.77355134, + -0.17649399 0.60867292 0.77354187, + -0.16205798 0.55880594 0.81330991, + -0.20655593 0.54394984 0.81329769, + -0.18726501 0.49306005 0.8496021, + -0.22637306 0.47639811 0.84958816, + -0.23570788 0.40753478 0.8822456, + -0.20636705 0.3566941 0.91114324, + -0.23444209 0.33894011 0.9111293, + -0.20010591 0.28917286 0.93612856, + -0.22278386 0.27213085 0.93611544, + -0.18359104 0.22410905 0.95711523, + -0.201102 0.20859499 0.95710301, + -0.15732798 0.16300999 0.97399986, + -0.16998392 0.14983292 0.97398955, + -0.12193203 0.10724702 0.98672724, + -0.13022803 0.097086824 0.98671925, + -0.078357011 0.058096606 0.99523109, + -0.08284539 0.051593993 0.99522591, + -0.090172403 0.037631799 0.995215, + -0.31546101 0.66432101 0.67761499, + -0.29299989 0.61693978 0.73043579, + -0.24793503 0.69428909 0.67564106, + -0.26120505 0.68816221 0.6769082, + -0.24238494 0.63849783 0.7304588, + -0.29298782 0.61693865 0.73044157, + -0.27191502 0.57249105 0.77350914, + -0.31718108 0.54873413 0.77349019, + -0.29123515 0.50376421 0.81326741, + -0.33085904 0.47870806 0.81324714, + -0.29995286 0.4339008 0.8495636, + -0.3339628 0.40834376 0.84954351, + -0.29813713 0.36443913 0.88221228, + -0.32655686 0.33926186 0.8821916, + -0.28590697 0.29691997 0.91109586, + -0.30891988 0.2729609 0.91107672, + -0.263675 0.232857 0.93608397, + -0.28162009 0.21087907 0.93606633, + -0.24535803 0.15439302 0.95705914, + -0.191953 0.120608 0.97396499, + -0.20110607 0.10475304 0.97395235, + -0.144255 0.0749112 0.98670101, + -0.14987606 0.063066021 0.98669136, + -0.090176091 0.037625395 0.99521488, + -0.092976697 0.030240901 0.99520898, + -0.0951695 0.022665299 0.99520302, + -0.092972405 0.030250004 0.9952091, + -0.15452008 0.050807025 0.98668247, + -0.14986598 0.063080892 0.98669189, + -0.20892705 0.088260725 0.97394025, + -0.20109507 0.10476504 0.97395337, + -0.25704804 0.13414502 0.95704311, + -0.24535994 0.15439197 0.95705879, + -0.29773399 0.187528 0.93604898, + -0.2816129 0.21088293 0.93606764, + -0.32993788 0.24721791 0.9110567, + -0.30891684 0.27296188 0.91107756, + -0.35283387 0.31189388 0.88217372, + -0.32654202 0.33926702 0.88219512, + -0.3657929 0.38015792 0.84951484, + -0.33398286 0.4083398 0.84953761, + -0.36839196 0.45050794 0.81322187, + -0.33086598 0.47870693 0.81324488, + -0.36033618 0.52143425 0.77347535, + -0.31716317 0.54873431 0.77349746, + -0.34174997 0.59135395 0.73041594, + -0.4157472 0.60173333 0.6819613, + -0.39939395 0.62093794 0.67447793, + -0.41368806 0.64320403 0.64432204, + -0.3533859 0.76105767 0.54397583, + -0.40344405 0.73576206 0.54395509, + -0.38753891 0.70669883 0.5919379, + -0.4339141 0.67923117 0.59191513, + -0.4120349 0.64491683 0.64366883, + -0.38825095 0.60354692 0.69641393, + -0.41423705 0.64402306 0.64315003, + -0.41422305 0.64403206 0.64315003, + -0.39939591 0.62093687 0.67447782, + -0.36550289 0.63253075 0.68287075, + -0.34175199 0.59135401 0.73041499, + -0.36036599 0.52143198 0.77346301, + -0.40119514 0.49075019 0.77343827, + -0.36836702 0.45051205 0.81323111, + -0.40346894 0.41941494 0.8132059, + -0.3657909 0.38015792 0.8495158, + -0.395257 0.34948099 0.849491, + -0.35285097 0.31188798 0.88216889, + -0.37686181 0.28247884 0.88214558, + -0.32995409 0.24720906 0.91105324, + -0.34883603 0.21985403 0.91103113, + -0.29773906 0.18752405 0.93604821, + -0.31191313 0.16297606 0.93602836, + -0.25703806 0.13415603 0.95704424, + -0.26706398 0.11302398 0.95702785, + -0.20893903 0.088245206 0.97393912, + -0.21543008 0.071129523 0.97392535, + -0.15452898 0.050792091 0.98668176, + -0.15817596 0.038199391 0.98667175, + -0.095170103 0.022663699 0.99520302, + -0.096748486 0.014932798 0.99519688, + -0.097700752 0.0070938165 0.9951905, + -0.09674938 0.014929696 0.99519676, + -0.16080105 0.02534521 0.98666137, + -0.15817694 0.038198084 0.98667163, + -0.220512 0.053571299 0.973912, + -0.21542303 0.071139507 0.97392613, + -0.27536002 0.09116181 0.95700914, + -0.2670719 0.11301596 0.95702666, + -0.32409391 0.13732497 0.93600476, + -0.31192884 0.16296193 0.93602556, + -0.36544698 0.19106998 0.91101086, + -0.34882399 0.219861 0.91103399, + -0.39840686 0.25123891 0.88212872, + -0.37683493 0.28249198 0.88215286, + -0.42212707 0.31655604 0.84947109, + -0.39523894 0.34948698 0.8494969, + -0.43596005 0.38559306 0.81317711, + -0.403474 0.41941401 0.81320399, + -0.43941811 0.45686811 0.77342319, + -0.40116882 0.49075377 0.77344966, + -0.43226686 0.52887881 0.73036474, + -0.46480006 0.56794006 0.67926806, + -0.46445495 0.56833595 0.67917293, + -0.43227291 0.52887785 0.73036182, + -0.47349811 0.49235612 0.7303322, + -0.43943912 0.45686311 0.77341419, + -0.47481 0.420037 0.77338499, + -0.43596494 0.38559195 0.8131749, + -0.46563405 0.34925404 0.81314611, + -0.4221468 0.31654686 0.8494646, + -0.44631016 0.28154108 0.84943628, + -0.39841905 0.25123203 0.88212514, + -0.41739085 0.21837293 0.88209867, + -0.36543399 0.19108 0.91101402, + -0.37968281 0.16104993 0.9109906, + -0.32407987 0.13733895 0.93600762, + -0.33414111 0.11081204 0.93598634, + -0.27535498 0.091168396 0.95700985, + -0.28185508 0.068727419 0.95699233, + -0.22050303 0.053587906 0.97391313, + -0.22416006 0.035675108 0.97389925, + -0.160795 0.0253611 0.98666197, + -0.16237794 0.012323095 0.98665166, + -0.097700566 0.0070949579 0.99519062, + -0.76601827 0.10251304 0.63459224, + -0.79919869 0.10700896 0.59146476, + -0.79023486 0.16015099 0.59150696, + -0.82267791 0.16678299 0.54349291, + -0.80967218 0.22135806 0.54353613, + -0.83883899 0.229387 0.493691, + -0.82161689 0.28490597 0.49373493, + -0.8473928 0.29389793 0.44220987, + -0.82585084 0.34982991 0.44225487, + -0.84816813 0.35933402 0.38921705, + -0.82225388 0.41517895 0.38926193, + -0.8410871 0.42473805 0.33491802, + -0.81081599 0.47997701 0.33496201, + -0.82621014 0.48913807 0.27950102, + -0.80374587 0.55155796 0.22310597, + -0.76508987 0.60402197 0.22314797, + -0.7739687 0.61107975 0.16599394, + -0.73140794 0.66141891 0.16603498, + -0.73731881 0.66681182 0.10827198, + -0.69113684 0.71456182 0.10831098, + -0.69432676 0.71790576 0.050216481, + -0.64482695 0.76267487 0.050252192, + -0.64559901 0.76363403 -0.0080679804, + -0.62465125 0.78086227 -0.0080592325, + -0.61526209 0.7883212 -0.0014659504, + -0.61084098 0.78836501 -0.073170602, + -0.6003899 0.7931788 -0.10197797, + -0.60039127 0.79317838 -0.10197305, + -0.60549611 0.79523617 -0.031208808, + -0.60549587 0.79523581 -0.031222092, + -0.61148608 0.78951913 -0.052386206, + -0.62050486 0.7813918 -0.066336684, + -0.64419228 0.76198334 -0.066314831, + -0.64561516 0.7636202 -0.0080872122, + -0.69518095 0.71878892 -0.0081223194, + -0.6943512 0.71788418 0.05018691, + -0.74074399 0.66991299 0.050149798, + -0.73734194 0.66679096 0.10824399, + -0.78023499 0.61605603 0.108205, + -0.77397913 0.61107004 0.16598101, + -0.8130793 0.55800217 0.16593906, + -0.80375099 0.55155301 0.22310001, + -0.83880287 0.49664393 0.22305697, + -0.826208 0.48914 0.279504, + -0.8570376 0.43288478 0.27945888, + -0.84106129 0.42476615 0.33494711, + -0.8675819 0.36761796 0.33490098, + -0.84816229 0.35934111 0.38922316, + -0.87028688 0.30189598 0.38917795, + -0.8473891 0.29390204 0.44221407, + -0.86515802 0.23661999 0.442168, + -0.83884883 0.22937293 0.49368089, + -0.8523187 0.17285094 0.49363482, + -0.82267672 0.16678594 0.54349381, + -0.83201027 0.11144904 0.54345018, + -0.79920417 0.10699902 0.5914591, + -0.7670328 0.050822888 0.63959181, + -0.80459887 0.053375192 0.59141493, + -0.77124053 -0.0005068687 0.63654363, + -0.80458385 0.053404991 0.59143287, + -0.83762383 0.055655584 0.54340488, + -0.83201116 0.11144703 0.5434491, + -0.86198771 0.11551796 0.49359182, + -0.8523156 0.17285492 0.49363875, + -0.87904674 0.17832996 0.44212589, + -0.86515468 0.23662491 0.44217184, + -0.88853413 0.24307103 0.38913205, + -0.87028641 0.30189714 0.38917819, + -0.89021701 0.30886 0.334842, + -0.8675921 0.36760503 0.33488902, + -0.88407278 0.37463892 0.27939394, + -0.85705256 0.43286678 0.27944088, + -0.87011099 0.43950999 0.22302, + -0.83879584 0.49665189 0.22306594, + -0.8485322 0.50246513 0.16589704, + -0.81307769 0.55800384 0.16594094, + -0.8196494 0.56256127 0.10816605, + -0.78023213 0.61605906 0.10820901, + -0.78383231 0.61894727 0.050112918, + -0.74074 0.66991699 0.050154001, + -0.74162579 0.67076474 -0.0081236577, + -0.69515216 0.71881717 -0.0080851819, + -0.69362104 0.71728003 -0.066326104, + -0.64417297 0.76200187 -0.066290289, + -0.64056015 0.75777519 -0.12433603, + -0.61064005 0.7820791 -0.12438302, + -0.60091788 0.7882058 -0.13277598, + -0.59117001 0.79018801 -0.16162001, + -0.59116971 0.79018867 -0.16161792, + -0.58681911 0.78655517 -0.19228704, + -0.59645432 0.78174335 -0.18198809, + -0.63477516 0.75097215 -0.18193804, + -0.64056319 0.75777221 -0.12433903, + -0.6897462 0.7132892 -0.12437403, + -0.69363493 0.71726495 -0.066345096, + -0.73999238 0.66933131 -0.066384129, + -0.74162716 0.67076319 -0.0081248116, + -0.78476083 0.6197449 -0.0081648184, + -0.78382301 0.618958 0.050124899, + -0.82341844 0.5652203 0.050082721, + -0.81963599 0.56257701 0.108185, + -0.85540003 0.50655401 0.108138, + -0.84854591 0.50244796 0.16587898, + -0.88021111 0.44466606 0.16583301, + -0.87010747 0.43951473 0.22302386, + -0.89753711 0.38040507 0.22297803, + -0.8840661 0.37464803 0.27940303, + -0.90712571 0.31477389 0.2793569, + -0.89021814 0.30885902 0.33484003, + -0.90888214 0.24869303 0.33479103, + -0.88853174 0.24307494 0.38913491, + -0.90280002 0.183201 0.389088, + -0.8790459 0.17833099 0.44212693, + -0.88901776 0.11921697 0.44207987, + -0.8619768 0.11553897 0.49360588, + -0.86779529 0.057704821 0.49356017, + -0.8376289 0.055645492 0.54339796, + -0.80458587 -0.054316193 0.59134692, + -0.77057064 -0.052074675 0.63522369, + -0.7626971 -0.022309301 0.64637107, + -0.73820192 -0.021631498 0.67423296, + -0.73820698 -0.0214855 0.67423201, + -0.76269484 -0.022158295 0.64637882, + -0.76269037 -0.022301812 0.64637929, + -0.73820919 -0.021624705 0.67422515, + -0.72199482 0.11678697 0.68197083, + -0.67465425 0.10905604 0.73003322, + -0.69745123 0.23230208 0.67793626, + -0.64832932 0.21586211 0.73011833, + -0.65690184 0.39560691 0.6418528, + -0.71971905 0.36321503 0.59167504, + -0.69382226 0.41047215 0.59171224, + -0.72231418 0.42738509 0.54369509, + -0.69212395 0.47467893 0.54373193, + -0.71705961 0.49183571 0.4938857, + -0.6825788 0.53863388 0.49392289, + -0.70398283 0.55557686 0.44242787, + -0.66528082 0.60135287 0.44246587, + -0.68326205 0.61765707 0.38942605, + -0.64046979 0.66190475 0.38946185, + -0.65514022 0.67711526 0.33512112, + -0.60841811 0.71937418 0.33515409, + -0.61996913 0.73308218 0.27969405, + -0.57727987 0.7833128 0.23058394, + -0.5696041 0.77285516 0.27972504, + -0.56961012 0.77285218 0.27972105, + -0.55899084 0.75839669 0.33520687, + -0.60839224 0.71938622 0.33517513, + -0.5947699 0.70322883 0.38950992, + -0.64045185 0.66191381 0.38947591, + -0.62360507 0.64445204 0.44249105, + -0.66529256 0.60134667 0.44245672, + -0.64505798 0.58300501 0.49396899, + -0.68256253 0.53864366 0.49393463, + -0.65882707 0.51985908 0.54377705, + -0.69211119 0.47468713 0.54374111, + -0.66481674 0.45591184 0.59174573, + -0.69382524 0.41047016 0.59171021, + -0.65924197 0.38994601 0.64291698, + -0.096748978 -0.016517697 0.99517179, + -0.58627409 0.44001207 0.68020004, + -0.54642314 0.4100261 0.7302742, + -0.57768899 0.36473 0.73023802, + -0.53613019 0.33841512 0.77333027, + -0.56166923 0.29418015 0.77329534, + -0.51572502 0.270035 0.81308597, + -0.53583109 0.22766106 0.81305319, + -0.48578793 0.20630997 0.8493799, + -0.50087184 0.16653594 0.84934872, + -0.44713405 0.14857002 0.88204211, + -0.45769495 0.11210898 0.8820129, + -0.40072799 0.098044597 0.910936, + -0.407377 0.065475203 0.91091001, + -0.34770989 0.05575908 0.93594265, + -0.35112801 0.0276212 0.93592, + -0.289354 0.022614 0.95695502, + -0.22637311 -0.01904621 0.97385448, + -0.16237798 -0.013891198 0.98663086, + -0.16079707 -0.026915813 0.98662049, + -0.096749075 -0.016514596 0.99517179, + -0.09516976 -0.024250291 0.99516565, + -0.090173468 -0.039217085 0.99515367, + -0.6420778 0.3364459 0.68886882, + -0.60520697 0.31706196 0.73020291, + -0.62880576 0.2673279 0.73016375, + -0.58358312 0.24802506 0.77324915, + -0.60169804 0.20025603 0.77321213, + -0.55246991 0.18379095 0.81301785, + -0.56551468 0.13875294 0.81298256, + -0.52120894 0.084032595 0.84928191, + -0.46528417 0.074917428 0.88198531, + -0.41137499 0.032489199 0.910887, + -0.35113502 -0.029112404 0.93587214, + -0.28935516 -0.024138112 0.95691746, + -0.28654099 -0.047314499 0.95689899, + -0.22416598 -0.037194297 0.97384089, + -0.22050692 -0.055120982 0.97382665, + -0.15817693 -0.039769381 0.98660952, + -0.15452394 -0.052379582 0.98659962, + -0.092973053 -0.031835087 0.99515951, + -0.092975169 -0.031825289 0.99515963, + -0.095169961 -0.024248591 0.99516565, + -0.15817693 -0.039770782 0.98660952, + -0.160797 -0.026932901 0.98662001, + -0.22416994 -0.037227694 0.97383875, + -0.22637589 -0.01906009 0.97385353, + -0.28935397 -0.024133395 0.95691788, + -0.35113618 0.027604314 0.93591744, + -0.41137585 0.032487787 0.9108867, + -0.4073689 0.065486483 0.91091275, + -0.46528083 0.07492207 0.88198668, + -0.45768699 0.112118 0.882016, + -0.50087684 0.16653094 0.8493467, + -0.55247599 0.18378501 0.81301498, + -0.53583676 0.2276569 0.81305057, + -0.58357674 0.2480289 0.77325273, + -0.56168014 0.29417306 0.77329016, + -0.60521472 0.31705686 0.73019862, + -0.57769203 0.36472902 0.73023605, + -0.61923075 0.39103484 0.68091476, + -0.62396705 0.37572607 0.68519706, + -0.65469331 0.39428717 0.64491427, + -0.65469825 0.39427915 0.64491421, + -0.63190305 0.38050905 0.67521209, + -0.63190377 0.38050684 0.67521274, + -0.63189977 0.38051686 0.67521077, + -0.65689617 0.39561608 0.64185315, + -0.68937725 0.34784713 0.63542223, + -0.69680393 0.22555196 0.68087494, + -0.66141284 0.30152494 0.68674284, + -0.69407415 0.3164731 0.64661115, + -0.69405174 0.31652087 0.64661175, + -0.69407821 0.31645408 0.64661616, + -0.67159307 0.30616304 0.67470509, + -0.67156303 0.306227 0.67470598, + -0.67827779 0.2884469 0.67582375, + -0.62880701 0.26732701 0.73016298, + -0.64832568 0.2158649 0.73012066, + -0.60169178 0.20026092 0.77321571, + -0.61590791 0.15118396 0.77317584, + -0.56552988 0.13873696 0.81297481, + -0.57491195 0.092780493 0.81293786, + -0.52121496 0.084025294 0.84927887, + -0.52634007 0.041819505 0.84924513, + -0.41137505 -0.033938304 0.91083413, + -0.35112989 -0.029094189 0.93587464, + -0.34771088 -0.057244781 0.93585265, + -0.28654301 -0.047322299 0.95689797, + -0.28186095 -0.070252784 0.95687973, + -0.22050692 -0.055139981 0.97382563, + -0.21542689 -0.072679266 0.97381151, + -0.15452603 -0.05236261 0.98660022, + -0.14987206 -0.064635724 0.98659039, + -0.090175577 -0.039209988 0.99515378, + -0.086793408 -0.046337605 0.99514812, + -0.082845859 -0.053179175 0.99514252, + -0.086789094 -0.046349097 0.99514788, + -0.14424603 -0.076502115 0.98658025, + -0.14986798 -0.064653292 0.98658991, + -0.20893203 -0.089814007 0.97379714, + -0.21542597 -0.072691292 0.97381085, + -0.27535692 -0.092684768 0.95686364, + -0.28185892 -0.07023558 0.95688164, + -0.34771198 -0.057249893 0.93585187, + -0.4073711 -0.066924818 0.91080725, + -0.41137505 -0.033939905 0.91083413, + -0.52633888 0.041820489 0.84924585, + -0.57490611 0.09278772 0.81294119, + -0.62612104 0.10114302 0.77313811, + -0.61590403 0.15118802 0.7731781, + -0.66364408 0.16298902 0.73007607, + -0.75051272 0.15153494 0.64324778, + -0.70639515 0.14255802 0.69331318, + -0.71005905 0.17446601 0.68218607, + -0.66364479 0.16298795 0.73007578, + -0.67465532 0.10905505 0.73003238, + -0.62612891 0.10113399 0.77313286, + -0.6322847 0.050435979 0.77309263, + -0.52633905 -0.043171804 0.84917814, + -0.46528378 -0.076326966 0.88186461, + -0.40737486 -0.066937879 0.91080469, + -0.40072691 -0.099498577 0.91077876, + -0.33414298 -0.11230299 0.93580788, + -0.27535698 -0.092693195 0.95686287, + -0.26706812 -0.11454906 0.95684546, + -0.20893507 -0.08979433 0.97379833, + -0.20110208 -0.10630204 0.97378534, + -0.144252 -0.076480903 0.98658103, + -0.13769001 -0.08784581 0.98657215, + -0.08284726 -0.053175975 0.99514252, + -0.078354828 -0.059684623 0.99513733, + -0.073370263 -0.065788567 0.99513251, + -0.078356832 -0.059681322 0.99513733, + -0.13022998 -0.098659582 0.98656291, + -0.13768595 -0.087857768 0.98657167, + -0.19194992 -0.12216396 0.97377163, + -0.20109807 -0.10631803 0.97378439, + -0.25704387 -0.13566694 0.95682955, + -0.26706913 -0.11453805 0.95684648, + -0.32408696 -0.13881199 0.93578786, + -0.33414292 -0.11229597 0.93580878, + -0.39147994 -0.13141799 0.91075391, + -0.40072584 -0.09949486 0.91077971, + -0.45768884 -0.11351196 0.88183671, + -0.46528205 -0.076321408 0.8818661, + -0.52121395 -0.085385695 0.84914386, + -0.52633977 -0.043172978 0.8491776, + -0.580558 -0.047521699 0.81283098, + -0.63228583 0.050434589 0.77309179, + -0.68128771 0.054425173 0.72998965, + -0.73281807 0.062446207 0.67755306, + -0.73258781 0.058605187 0.67814481, + -0.68128991 0.054422293 0.72998792, + -0.63228619 -0.05166721 0.77301019, + -0.58055913 -0.04752231 0.81283015, + -0.57490689 -0.094074279 0.81279284, + -0.52121127 -0.085377134 0.84914643, + -0.45769188 -0.11352297 0.88183373, + -0.44713685 -0.14996395 0.8818047, + -0.39147893 -0.13140799 0.91075587, + -0.37968701 -0.16250201 0.91073102, + -0.32408699 -0.138831 0.935785, + -0.31191987 -0.16446994 0.93576467, + -0.25704107 -0.13568203 0.95682824, + -0.19195105 -0.12215803 0.97377223, + -0.13023503 -0.098649919 0.98656327, + -0.12194203 -0.10880702 0.98655522, + -0.073371165 -0.065787271 0.99513251, + -0.067908905 -0.071474209 0.9951281, + -0.061980985 -0.076727882 0.99512374, + -0.067902803 -0.0714816 0.99512798, + -0.11285503 -0.11827203 0.98654723, + -0.12193297 -0.10882097 0.98655474, + -0.16998695 -0.15138596 0.97374874, + -0.29773605 -0.18902004 0.93574822, + -0.31192195 -0.16444896 0.93576777, + -0.36544004 -0.19251603 0.91070914, + -0.37968692 -0.16249196 0.91073275, + -0.43367594 -0.18547198 0.88177389, + -0.44713807 -0.14997502 0.88180214, + -0.50087517 -0.16788906 0.84908032, + -0.56552613 -0.14005002 0.81275219, + -0.57491094 -0.094082989 0.8127889, + -0.626127 -0.102376 0.77297097, + -0.63228506 -0.051665708 0.77301115, + -0.68128896 -0.055587791 0.72990096, + -0.72745067 -0.00054637674 0.68615973, + -0.73059797 0.062254701 0.67996401, + -0.76676279 0.065396085 0.63859081, + -0.76676935 0.065294027 0.63859332, + -0.73059893 0.062156994 0.67997193, + -0.73059595 0.062192593 0.67997193, + -0.76066184 0.064801283 0.64590579, + -0.7606563 0.064864121 0.64590621, + -0.76065379 0.064795487 0.64591581, + -0.7328248 0.062380783 0.67755181, + -0.70762861 0.14281791 0.69200057, + -0.75031465 0.15150593 0.64348572, + -0.75030863 0.15153992 0.64348471, + -0.72415596 0.14621499 0.67395794, + -0.72416008 0.14619902 0.67395705, + -0.750507 0.151563 0.64324802, + -0.75031513 0.15201102 0.64336604, + -0.7902261 0.16016501 0.59151506, + -0.7777378 0.21256596 0.59155691, + -0.80967599 0.221352 0.54353303, + -0.79305071 0.27494892 0.54357481, + -0.82161599 0.28490701 0.493736, + -0.80072314 0.33915302 0.49377906, + -0.82583791 0.34984398 0.44226795, + -0.80060989 0.40420893 0.44231093, + -0.82224768 0.41518486 0.38926885, + -0.79265702 0.46918201 0.38931099, + -0.81081301 0.47997999 0.33496499, + -0.7769289 0.53305894 0.33500698, + -0.75361013 0.59489703 0.27958804, + -0.76509798 0.60401499 0.223139, + -0.72303903 0.65376306 0.22317803, + -0.73143208 0.66139907 0.16600701, + -0.68561125 0.70877826 0.16604406, + -0.69115019 0.71455115 0.10829702, + -0.64188206 0.75911212 0.10833401, + -0.64484382 0.76266181 0.05023279, + -0.62283796 0.78073388 0.050274592, + -0.60598403 0.7949751 0.028250003, + -0.60598499 0.79497498 0.0282315, + -0.61144608 0.78912312 0.058467206, + -0.60247201 0.793338 0.087420702, + -0.72660202 0.25177601 0.63926399, + -0.76178902 0.26403201 0.59157801, + -0.74242526 0.31431311 0.59161824, + -0.7728979 0.32727098 0.54361993, + -0.74926203 0.37820506 0.54366106, + -0.77625114 0.39188406 0.49382305, + -0.74832284 0.44284588 0.49386287, + -0.7718001 0.45679307 0.44234005, + -0.73955709 0.50730103 0.44238105, + -0.75954127 0.52106017 0.38935015, + -0.72300708 0.57064605 0.38938907, + -0.73956335 0.5837633 0.33506215, + -0.69888705 0.63187307 0.33510202, + -0.71215779 0.64392078 0.2796379, + -0.66756308 0.69003004 0.27967504, + -0.67773992 0.70059794 0.22322898, + -0.62940419 0.74431419 0.22326405, + -0.63671005 0.75300211 0.16609702, + -0.60050511 0.78215915 0.16619505, + -0.58245105 0.78796512 0.19965403, + -0.58244711 0.78795916 0.19968905, + -0.59435707 0.78564912 0.17174202, + -0.59538192 0.79044187 0.14395098, + -0.59538096 0.79044187 0.14395499, + -0.60316879 0.78885269 0.11789296, + -0.60246992 0.79333586 0.087454095, + -0.61430323 0.78158629 0.10841804, + -0.64187497 0.75911689 0.10834198, + -0.63673228 0.75298834 0.16607407, + -0.68561476 0.70877576 0.16603994, + -0.67774618 0.70059419 0.22322206, + -0.72303206 0.65376806 0.22318603, + -0.71217799 0.64390701 0.279618, + -0.75361699 0.59489202 0.27958, + -0.73957264 0.58375669 0.33505285, + -0.77692109 0.53306603 0.33501402, + -0.75951999 0.52107698 0.38936901, + -0.79264027 0.46919718 0.38932714, + -0.77178764 0.4568038 0.4423508, + -0.80061197 0.40420699 0.44230899, + -0.77627027 0.39186615 0.49380717, + -0.80073899 0.339136 0.493765, + -0.77288413 0.32728502 0.54363108, + -0.79303485 0.27496698 0.54358894, + -0.76175714 0.26406804 0.59160304, + -0.77773219 0.21257204 0.59156209, + -0.74540591 0.20368297 0.63473094, + -0.72600204 0.23541203 0.64614403, + -0.70002884 0.22694694 0.67709285, + -0.7000308 0.22694094 0.67709285, + -0.72600502 0.235406 0.64614302, + -0.72601396 0.23537597 0.64614391, + -0.69669592 0.22582197 0.68089592, + -0.69668901 0.225843 0.68089598, + -0.73220807 0.23741902 0.63836008, + -0.73231661 0.23710889 0.63835073, + -0.70988601 0.30052799 0.63698101, + -0.74239081 0.31434792 0.59164286, + -0.71970892 0.36322397 0.59168196, + -0.74926841 0.37819925 0.54365629, + -0.72231096 0.42738795 0.54369694, + -0.74833125 0.44283915 0.49385619, + -0.71704817 0.49184412 0.49389413, + -0.73953217 0.50731909 0.44240212, + -0.70396775 0.5555858 0.44244084, + -0.72299498 0.57065398 0.38940001, + -0.68325007 0.61766404 0.38943607, + -0.69890124 0.63186425 0.33508912, + -0.65513575 0.67711776 0.33512488, + -0.667575 0.69002301 0.27966401, + -0.61996275 0.73308575 0.27969891, + -0.62941396 0.74430895 0.22325397, + -0.58397394 0.7804479 0.22332796, + -0.57758862 0.78320253 0.23018487, + -0.57862192 0.78232586 0.23057097, + -0.53692013 0.80719417 0.24526405, + -0.53691691 0.80718988 0.24528497, + -0.54413396 0.79093987 0.27987897, + -0.51923811 0.79918915 0.30280107, + -0.5418328 0.79224467 0.2806519, + -0.52651322 0.77756238 0.34377417, + -0.49739975 0.79564565 0.34574783, + -0.47249177 0.80940664 0.34872982, + -0.56060207 0.57918006 0.59184104, + -0.5836243 0.60302228 0.54382622, + -0.54203123 0.64064229 0.54385626, + -0.56155407 0.66377205 0.49402806, + -0.51592201 0.69981003 0.494055, + -0.53210509 0.72181404 0.44254807, + -0.48267975 0.75574267 0.44257578, + -0.49571893 0.7762109 0.38956293, + -0.45385206 0.80134213 0.38970405, + -0.45700714 0.8069073 0.37422612, + -0.46907017 0.79527229 0.38407716, + -0.4247008 0.79791367 0.4277418, + -0.44257605 0.80182314 0.40150505, + -0.36992791 0.80747783 0.45949188, + -0.39592808 0.80505019 0.44174111, + -0.49583387 0.58597487 0.64092284, + -0.47833988 0.64872783 0.5918979, + -0.45169821 0.70718437 0.54392922, + -0.46797088 0.73271585 0.49409589, + -0.41798386 0.76232272 0.49411881, + -0.43109792 0.78629285 0.44260389, + -0.39230993 0.80625087 0.44277793, + -0.39317685 0.8080337 0.43874085, + -0.40392777 0.81970555 0.40610975, + -0.43934107 0.80137509 0.40592805, + -0.4310919 0.7862938 0.44260788, + -0.48266777 0.75574565 0.4425838, + -0.46798989 0.73271179 0.49408388, + -0.51592004 0.69981009 0.49405706, + -0.54199719 0.64065427 0.54387617, + -0.56060106 0.57918006 0.59184206, + -0.53637302 0.554093 0.63661999, + -0.52981108 0.51435703 0.67434204, + -0.54713994 0.53121996 0.64687192, + -0.5471881 0.53117013 0.64687216, + -0.52985907 0.51431006 0.67434007, + -0.52980894 0.51436192 0.67433995, + -0.54713517 0.53122318 0.64687324, + -0.57259697 0.51739395 0.63595295, + -0.59805393 0.54045594 0.59180993, + -0.6017971 0.47471711 0.64224917, + -0.63286495 0.49929094 0.59176892, + -0.598068 0.54044902 0.591802, + -0.62261504 0.56268805 0.54381305, + -0.5835939 0.60303485 0.54384488, + -0.60461491 0.62481195 0.49401495, + -0.56152481 0.66378278 0.49404681, + -0.57914597 0.68466496 0.44251993, + -0.53210104 0.72181505 0.44255105, + -0.54647714 0.74136919 0.38953108, + -0.49572387 0.77620983 0.38955891, + -0.50534517 0.79131627 0.34415811, + -0.51316279 0.79014069 0.33517388, + -0.51296115 0.79018933 0.33536813, + -0.5129751 0.79021215 0.33529308, + -0.55899584 0.75839472 0.33520287, + -0.54648095 0.74136692 0.38952994, + -0.59478402 0.70322299 0.38949901, + -0.57913393 0.68466991 0.44252795, + -0.62359589 0.6444568 0.44249687, + -0.60463011 0.62480509 0.49400511, + -0.64505577 0.58300585 0.49397081, + -0.62262785 0.56268185 0.54380488, + -0.65883642 0.51985329 0.54377133, + -0.63285381 0.49929687 0.59177589, + -0.66482383 0.45590788 0.59174091, + -0.63736796 0.43702593 0.63464195, + -0.60522026 0.46597019 0.64543027, + -0.57924396 0.44591895 0.68237293, + -0.5791449 0.44605389 0.68236881, + -0.60508895 0.46608993 0.64546692, + -0.60509288 0.46608487 0.6454668, + -0.58345509 0.44937605 0.67649204, + -0.58345103 0.44938105 0.67649204, + -0.60805911 0.46838611 0.64099818, + -0.6080901 0.46834713 0.64099717, + -0.58348596 0.44934794 0.67648393, + -0.54301977 0.48052275 0.68864167, + -0.51160794 0.45266095 0.73031193, + -0.5464167 0.41002876 0.7302776, + -0.50711417 0.38045916 0.77336031, + -0.5361371 0.33841109 0.77332717, + -0.49228412 0.31065005 0.81311315, + -0.51573807 0.27002802 0.81308013, + -0.46757087 0.24471894 0.84940583, + -0.48580182 0.20629893 0.84937471, + -0.43367708 0.18406504 0.88206822, + -0.44714215 0.14856206 0.88203931, + -0.39148301 0.129959 0.91096199, + -0.40072501 0.098047599 0.91093701, + -0.34771296 0.055754691 0.93594187, + -0.28654 0.045797899 0.95697302, + -0.28935584 0.022609489 0.95695454, + -0.22637308 0.017508805 0.97388333, + -0.16237894 -0.013894496 0.98663062, + -0.0977007 -0.0086798603 0.99517798, + -0.0977007 -0.0086786998 0.99517798, + -0.16237892 0.012319994 0.98665154, + -0.22637692 0.017495494 0.97388262, + -0.22417402 0.035644505 0.9738971, + -0.28654405 0.045791011 0.95697224, + -0.28186393 0.068712786 0.95699078, + -0.33414486 0.11080695 0.93598557, + -0.39147601 0.12996601 0.91096401, + -0.3796899 0.16104396 0.91098875, + -0.4336741 0.18406704 0.88206923, + -0.41739786 0.21836792 0.88209671, + -0.46756405 0.24472404 0.84940809, + -0.44630879 0.28154185 0.84943658, + -0.49229005 0.31064603 0.81311113, + -0.46564481 0.34924987 0.8131417, + -0.50712997 0.38045293 0.77335286, + -0.47481117 0.42003715 0.77338427, + -0.51159996 0.45266494 0.73031497, + -0.47346905 0.49236205 0.73034704, + -0.50332296 0.52347791 0.68748593, + -0.46502218 0.56818116 0.67891425, + -0.486763 0.59480202 0.63974398, + -0.48670805 0.59484905 0.63974208, + -0.46497199 0.56823099 0.67890698, + -0.46505299 0.56816101 0.67891002, + -0.48341617 0.59064323 0.64610326, + -0.48337111 0.59068012 0.6461032, + -0.483412 0.59063601 0.64611298, + -0.46484518 0.56790519 0.67926621, + -0.39162585 0.60885078 0.68987674, + -0.41368195 0.64320797 0.64432192, + -0.458527 0.62181997 0.63489598, + -0.47832987 0.6487298 0.59190387, + -0.43389094 0.67923492 0.59192795, + -0.45170695 0.70718294 0.54392391, + -0.40345895 0.73575991 0.54394692, + -0.41799405 0.76232111 0.49411306, + -0.37538794 0.80854189 0.45314893, + -0.36495999 0.81323689 0.45326594, + -0.33209398 0.82270187 0.46138394, + -0.32248014 0.81372243 0.48359323, + -0.3159129 0.79906482 0.51156086, + -0.31961098 0.80843788 0.49424395, + -0.30815104 0.80966514 0.49948505, + -0.12250105 0.81945229 0.5599032, + -0.15312093 0.8237617 0.54586685, + -0.18649799 0.8188259 0.54290193, + -0.22888403 0.73740208 0.63549209, + -0.23889685 0.7697165 0.59200066, + -0.18693995 0.78394783 0.59201288, + -0.19461603 0.8161931 0.54401606, + -0.11561901 0.83141112 0.54349607, + -0.12764104 0.91959924 0.37154409, + -0.12754905 0.91961443 0.37153819, + -0.21007907 0.83117932 0.51478916, + -0.19383703 0.81292713 0.54916006, + -0.19461399 0.81619298 0.54401702, + -0.248723 0.80137098 0.54400498, + -0.23891599 0.76971799 0.59199101, + -0.27703005 0.71872717 0.63771915, + -0.28984508 0.75203329 0.59197623, + -0.32412803 0.69801909 0.63852209, + -0.33941498 0.73100394 0.59197193, + -0.28982091 0.7520327 0.59198874, + -0.30172101 0.782969 0.543989, + -0.24872594 0.8013708 0.5440039, + -0.25536701 0.82280999 0.50771201, + -0.24119188 0.82698357 0.50786275, + -0.24678206 0.8178702 0.51979512, + -0.2729069 0.82097667 0.50151682, + -0.3065109 0.81194568 0.49678484, + -0.31205705 0.8098762 0.49671012, + -0.30170894 0.78296882 0.54399586, + -0.35338289 0.76105767 0.5439778, + -0.33945203 0.73100203 0.59195304, + -0.38754684 0.70669776 0.59193379, + -0.37136617 0.67713732 0.63527328, + -0.33678713 0.68439931 0.64666229, + -0.32520387 0.66082072 0.6764307, + -0.32519984 0.66082269 0.6764307, + -0.33678201 0.68440199 0.646662, + -0.33673415 0.68442529 0.64666229, + -0.32247296 0.65538996 0.68298995, + -0.3226749 0.6552968 0.68298382, + -0.34017497 0.69090194 0.63791496, + -0.34043908 0.69077915 0.63790721, + -0.322927 0.65518498 0.68297201, + -0.24501309 0.68615824 0.68494922, + -0.25644308 0.71822524 0.64683026, + -0.25646606 0.71821719 0.6468302, + -0.256473 0.71821398 0.64683098, + -0.24794306 0.69428617 0.67564118, + -0.20174292 0.69596964 0.68914866, + -0.19015788 0.65593761 0.73046958, + -0.24239188 0.63849872 0.73045564, + -0.22495903 0.59250206 0.77352113, + -0.27192405 0.57249212 0.77350515, + -0.24967197 0.52556193 0.81329489, + -0.29120401 0.50376499 0.81327802, + -0.26401091 0.45663184 0.84957969, + -0.29996014 0.43390021 0.84956139, + -0.26777491 0.38724485 0.88223469, + -0.29811913 0.36444411 0.88221627, + -0.26101089 0.31896985 0.91111559, + -0.28589708 0.29692212 0.9110983, + -0.24403296 0.25331897 0.93609691, + -0.2636959 0.2328469 0.93608057, + -0.21730196 0.19173098 0.95708889, + -0.19194809 0.12061206 0.97396547, + -0.13768396 0.086285472 0.98671067, + -0.14424096 0.074928373 0.98670167, + -0.086788155 0.044763677 0.99522054, + -0.086795248 0.044753622 0.99522048, + -0.082847595 0.051591191 0.99522591, + -0.13769303 0.086276226 0.98671025, + -0.13023598 0.097079687 0.98671889, + -0.16999394 0.14982694 0.97398865, + -0.21728693 0.19173892 0.95709062, + -0.201092 0.2086 0.95710403, + -0.24402985 0.25331986 0.93609744, + -0.22280386 0.27212486 0.93611246, + -0.26103401 0.318964 0.911111, + -0.23445202 0.33893904 0.91112709, + -0.26778013 0.38724416 0.88223344, + -0.23569287 0.40753478 0.88224959, + -0.2640239 0.45663184 0.8495757, + -0.22636293 0.47639683 0.84959167, + -0.24967788 0.52556276 0.81329256, + -0.2065319 0.54394579 0.81330657, + -0.22493307 0.59249723 0.77353227, + -0.17648605 0.60867113 0.77354521, + -0.19016796 0.65593994 0.73046494, + -0.146469 0.716892 0.68162501, + -0.16458507 0.70717835 0.68761235, + -0.17324401 0.74444705 0.64481407, + -0.17318499 0.74445993 0.64481497, + -0.1672 0.718687 0.674932, + -0.167243 0.71867698 0.674932, + -0.16720892 0.71869266 0.67492372, + -0.17360009 0.74620634 0.6426813, + -0.17363605 0.74619716 0.64268219, + -0.177559 0.744551 0.64351898, + -0.18693696 0.78394783 0.5920139, + -0.13413197 0.79468083 0.5920229, + -0.139221 0.82488501 0.54788899, + -0.11986803 0.82779217 0.54808015, + 0.12749898 0.91445887 0.38406894, + 0.2043581 0.8288244 0.52085322, + 0.19261891 0.80781263 0.55707878, + 0.11615802 0.83132613 0.54351103, + 0.12754698 0.91445088 0.38407195, + 0.18034896 0.8200838 0.54308087, + -0.076824009 0.76298314 0.64183706, + -0.08073312 0.80187219 0.5920161, + -0.027704092 0.82807881 0.55992687, + -0.026949091 0.80547273 0.59201974, + 0.027690703 0.8276791 0.56051809, + 0.02694891 0.80546731 0.59202725, + -0.026934097 0.8054679 0.59202695, + -0.025779394 0.77087981 0.63645881, + 0.025779394 0.77087981 0.63645881, + 0.026934296 0.80547386 0.59201896, + 0.083239846 0.82699251 0.55601662, + 0.080715761 0.80187362 0.5920167, + 0.076824009 0.76298314 0.64183706, + 0.080732398 0.80186498 0.592026, + 0.13413298 0.79468286 0.59201992, + 0.138722 0.82192099 0.55245101, + 0.14998402 0.82376713 0.54672909, + 0.11628596 0.82836068 0.54799283, + 0.11634 0.82835299 0.547993, + 0.083956033 0.8272773 0.55548519, + 0.049938791 0.83272582 0.55142885, + 0.049976524 0.83272344 0.55142921, + 0.016744902 0.83218712 0.55424207, + -0.00233575 0.83230102 0.55431902, + -0.021222701 0.83106512 0.55577004, + -0.053911924 0.83269042 0.55110824, + -0.053918406 0.83269012 0.55110806, + -0.083182693 0.82642388 0.55686992, + -0.080715075 0.80186683 0.59202588, + -0.13413799 0.79468191 0.59201992, + -0.12859495 0.76178569 0.63493776, + -0.087062709 0.75836211 0.64599305, + -0.08353778 0.7276088 0.68088681, + -0.083549619 0.72760719 0.68088716, + -0.08707533 0.75836229 0.64599127, + -0.087077409 0.75836211 0.64599109, + -0.08387927 0.73046577 0.67777878, + -0.083899908 0.73046309 0.67777908, + -0.087616906 0.76287812 0.64057803, + -0.087656125 0.7628752 0.64057618, + -0.083937868 0.73046374 0.67777377, + -0.029218104 0.72478908 0.68835104, + -0.027510596 0.68236595 0.73049295, + -0.082370974 0.67793781 0.73048985, + -0.12689902 0.62090504 0.7735461, + -0.11651602 0.57002306 0.81332511, + -0.16204296 0.55880189 0.81331581, + -0.14691097 0.50653088 0.84961385, + -0.18726301 0.49305907 0.84960312, + -0.16717093 0.44005778 0.88227159, + -0.17692994 0.37214887 0.91115367, + -0.20637804 0.35669309 0.91114122, + -0.17615201 0.304326 0.93613899, + -0.20011996 0.28916895 0.93612677, + -0.16491199 0.23814698 0.9571259, + -0.18359596 0.22410694 0.95711476, + -0.14363199 0.175147 0.97400898, + -0.15733506 0.16300605 0.97399938, + -0.11285904 0.11669704 0.98673433, + -0.12194497 0.10723697 0.98672676, + -0.073371299 0.064202502 0.99523598, + -0.073370107 0.064203508 0.9952361, + -0.067902274 0.069896176 0.99524063, + -0.11285494 0.11669993 0.98673439, + -0.10302405 0.12540907 0.98674148, + -0.14362296 0.17514996 0.97400975, + -0.12900206 0.1861361 0.97401845, + -0.164893 0.238152 0.95712799, + -0.14513896 0.25064293 0.95713776, + -0.17612401 0.30432999 0.93614298, + -0.15099791 0.31751582 0.93615347, + -0.17690894 0.37214887 0.91115773, + -0.14634494 0.38517085 0.91116768, + -0.1671499 0.44005573 0.88227648, + -0.131144 0.45207599 0.88228601, + -0.14690897 0.50652987 0.8496148, + -0.10563198 0.5167039 0.84962285, + -0.11651103 0.57002109 0.81332719, + -0.070191808 0.57755005 0.81333214, + -0.025561687 0.63321269 0.77355564, + -0.027543416 0.68238443 0.73047441, + 0.027511399 0.68238503 0.73047501, + 0.029218104 0.72478908 0.68835104, + 0.083937868 0.73046374 0.67777377, + 0.087656125 0.7628752 0.64057618, + 0.087616906 0.76287812 0.64057803, + 0.083899908 0.73046309 0.67777908, + 0.08387927 0.73046577 0.67777878, + 0.087077409 0.75836211 0.64599109, + 0.08707533 0.75836229 0.64599127, + 0.087062709 0.75836211 0.64599305, + 0.08353778 0.7276088 0.68088681, + 0.083549619 0.72760719 0.68088716, + 0.088455573 0.72797674 0.67987174, + 0.082384594 0.67793596 0.73048997, + 0.027542591 0.68236375 0.73049378, + 0.025561614 0.63320827 0.77355933, + -0.025554894 0.6332078 0.77355981, + -0.023464305 0.58132613 0.8133322, + -0.070200615 0.57755309 0.81332916, + -0.063644305 0.52352303 0.84963113, + -0.105624 0.516702 0.84962499, + -0.09429054 0.46116072 0.88229245, + -0.13114601 0.45207706 0.88228512, + -0.114823 0.39569899 0.911174, + -0.14635697 0.38517091 0.91116577, + -0.12492301 0.32863703 0.93615812, + -0.15102902 0.31751403 0.93614912, + -0.12445796 0.26150391 0.95714462, + -0.14515899 0.25063896 0.95713586, + -0.12900998 0.18613395 0.97401774, + -0.092540175 0.13328597 0.98674774, + -0.10302195 0.12540995 0.98674154, + -0.061986879 0.075137772 0.99524462, + -0.061980285 0.075141989 0.99524474, + -0.055688225 0.079870239 0.9952485, + -0.092556611 0.13327901 0.98674715, + -0.081460893 0.14029598 0.98675287, + -0.097359136 0.20440708 0.97403234, + -0.12444595 0.2615059 0.95714563, + -0.10294601 0.27066603 0.95715314, + -0.12492694 0.32863685 0.93615758, + -0.098016664 0.33762187 0.93616462, + -0.11483496 0.39570084 0.91117167, + -0.082554676 0.40365791 0.91117775, + -0.094289258 0.46115926 0.88229352, + -0.063653499 0.52352703 0.84962797, + -0.021257408 0.52695018 0.8496303, + -0.023446606 0.58131713 0.81333917, + 0.023463896 0.58131695 0.81333888, + 0.025555113 0.63321328 0.77355534, + 0.082372107 0.67794603 0.73048204, + 0.146469 0.716892 0.68162501, + 0.16458507 0.70717835 0.68761235, + 0.17324401 0.74444705 0.64481407, + 0.12859495 0.76178569 0.63493776, + 0.13413797 0.79467982 0.5920229, + 0.18694 0.78394699 0.59201401, + 0.24872509 0.80137032 0.54400516, + 0.25561601 0.823614 0.50628102, + 0.23361497 0.8300159 0.50645596, + 0.24220394 0.81587982 0.52504987, + 0.26813105 0.82137918 0.50343013, + 0.30464685 0.80960763 0.50172275, + 0.33392191 0.80679184 0.48742488, + 0.32380196 0.81984186 0.47224095, + 0.31934789 0.80854368 0.49424082, + 0.37529817 0.80834836 0.45356822, + 0.3698658 0.81080955 0.45363772, + 0.37247482 0.80780166 0.4568578, + 0.40053019 0.80387539 0.43972722, + 0.44762385 0.80134273 0.39684084, + 0.47744811 0.79189515 0.3807171, + 0.45823595 0.81022191 0.36545897, + 0.45336294 0.8016209 0.38969994, + 0.49572319 0.77620828 0.38956314, + 0.50564176 0.79178464 0.34264186, + 0.5105139 0.78868079 0.34257591, + 0.47691217 0.80655032 0.34933013, + 0.51638895 0.79868788 0.30893397, + 0.51638591 0.79868287 0.30895197, + 0.53570205 0.79504913 0.28446501, + 0.54681081 0.78909272 0.2798759, + 0.56960511 0.77285618 0.27972007, + 0.57714194 0.78312391 0.23156898, + 0.56741601 0.79017699 0.231645, + 0.57477504 0.78395313 0.23463003, + 0.58427274 0.78022373 0.22332993, + 0.58174986 0.78738785 0.20392996, + 0.58175188 0.78739083 0.20391296, + 0.5922901 0.7865932 0.17453805, + 0.59440273 0.79129064 0.14333393, + 0.60556632 0.78748834 0.11468005, + 0.60205513 0.79406416 0.083616219, + 0.602054 0.79406202 0.0836455, + 0.61369991 0.78205991 0.10841899, + 0.641882 0.75911099 0.108342, + 0.6448437 0.76266062 0.050252277, + 0.69435018 0.71788317 0.05021641, + 0.69518119 0.71878916 -0.008085222, + 0.74162716 0.67076319 -0.0081236623, + 0.73999304 0.66933107 -0.066380106, + 0.78303885 0.61841595 -0.06642089, + 0.7786482 0.61499411 -0.12445603, + 0.81798714 0.56160206 -0.12450001, + 0.810597 0.55657399 -0.18209299, + 0.84594941 0.50119424 -0.18213709, + 0.83535701 0.49496499 -0.239141, + 0.86653709 0.43806806 -0.23918603, + 0.85260713 0.43107405 -0.29535803, + 0.87947875 0.37316692 -0.29540393, + 0.8621217 0.3658509 -0.35056987, + 0.88461322 0.30745506 -0.35061508, + 0.86378598 0.300266 -0.404616, + 0.88189614 0.24188402 -0.40466207, + 0.85601473 0.23483892 -0.46053183, + 0.85361481 0.24370293 -0.46038088, + 0.85039687 0.24275997 -0.46678993, + 0.85039884 0.24275294 -0.46678987, + 0.82022387 0.32831696 -0.46844494, + 0.82022911 0.32830402 -0.46844506, + 0.81905121 0.3476921 -0.45636111, + 0.84181619 0.3573041 -0.40457308, + 0.81610912 0.41270205 -0.40452805, + 0.83578813 0.42260307 -0.35052103, + 0.80571038 0.47748923 -0.35047817, + 0.82192916 0.48705211 -0.29531807, + 0.78756332 0.54088515 -0.29527512, + 0.80043298 0.54967499 -0.23909099, + 0.76195312 0.60189909 -0.23905003, + 0.77161312 0.60948104 -0.18206102, + 0.72919118 0.65965819 -0.18202004, + 0.73583996 0.66562694 -0.12441999, + 0.68974483 0.71328884 -0.12438297, + 0.69363576 0.71726578 -0.066326074, + 0.64419293 0.76198488 -0.06629049, + 0.64561474 0.76362067 -0.0080679776, + 0.62593699 0.77983201 -0.0080599198, + 0.61561114 0.78804719 0.0021349106, + 0.60529375 0.79563171 0.02428339, + 0.60529405 0.79563111 0.024296304, + 0.61066276 0.7916317 -0.020253092, + 0.60706329 0.79307836 -0.050010223, + 0.60705906 0.7930721 -0.050160609, + 0.60170102 0.79119903 -0.109362, + 0.60169989 0.79119885 -0.10936898, + 0.60598975 0.79145569 -0.07983847, + 0.62136829 0.78070533 -0.066337027, + 0.64417177 0.76200068 -0.066314779, + 0.64055991 0.75777489 -0.12433898, + 0.68975323 0.71328223 -0.12437405, + 0.68352008 0.70688409 -0.18197602, + 0.72919607 0.65965408 -0.18201502, + 0.72006625 0.65144223 -0.23901409, + 0.7619499 0.60190195 -0.23905297, + 0.74969804 0.59227008 -0.29524404, + 0.78755486 0.54089195 -0.29528496, + 0.77201229 0.53026718 -0.35044813, + 0.80569816 0.47750112 -0.35049009, + 0.78672791 0.46630695 -0.40449595, + 0.81609911 0.41271207 -0.40453807, + 0.79308617 0.40112609 -0.45838013, + 0.78692991 0.41333795 -0.45814094, + 0.78266412 0.41087005 -0.46757105, + 0.78266519 0.41086808 -0.46757111, + 0.76733053 0.45484373 -0.45201874, + 0.78673613 0.46630007 -0.40448806, + 0.75384903 0.51781601 -0.404448, + 0.77202916 0.53025311 -0.3504321, + 0.73491901 0.58061999 -0.35039201, + 0.7497142 0.5922581 -0.29522705, + 0.70848626 0.64102322 -0.29518911, + 0.72005993 0.65144694 -0.23901998, + 0.67495984 0.69808084 -0.23898195, + 0.68351877 0.70688474 -0.18197794, + 0.63477463 0.7509715 -0.1819419, + 0.64056295 0.75777286 -0.12433598, + 0.61090392 0.78187287 -0.12438299, + 0.59709692 0.7900399 -0.13896799, + 0.59156877 0.78843868 -0.16855495, + 0.59155589 0.7884208 -0.16868396, + 0.57677418 0.78542429 -0.22458908, + 0.57674581 0.78538573 -0.22479692, + 0.55192816 0.79653227 -0.24680309, + 0.53015095 0.80406189 -0.26911798, + 0.53014386 0.80405182 -0.26916194, + 0.52390397 0.78302789 -0.33524898, + 0.49860007 0.79035515 -0.35600102, + 0.49313706 0.79553413 -0.35205302, + 0.50351292 0.78905386 -0.35194996, + 0.49199307 0.7710501 -0.40425807, + 0.5288862 0.71818322 -0.45220816, + 0.54238087 0.73646182 -0.40428591, + 0.57473665 0.68016261 -0.45503473, + 0.59034914 0.69858921 -0.4043031, + 0.54239917 0.73645526 -0.40427315, + 0.55547708 0.75416112 -0.35026604, + 0.50421917 0.78936231 -0.35024312, + 0.50896174 0.79675567 -0.32578886, + 0.52633083 0.79524571 -0.30093187, + 0.53664112 0.7904852 -0.29521105, + 0.56664979 0.76930869 -0.29507989, + 0.55546206 0.75416714 -0.35027704, + 0.60457629 0.71538234 -0.35030818, + 0.59034413 0.69859117 -0.4043071, + 0.63566297 0.65760303 -0.40434, + 0.61711293 0.63846594 -0.45992693, + 0.62399906 0.63184303 -0.45978206, + 0.553258 0.68874401 -0.468548, + 0.55322808 0.68876809 -0.46854806, + 0.48063487 0.74322581 -0.46540889, + 0.48064095 0.74322194 -0.46540895, + 0.48180005 0.74483508 -0.46161607, + 0.47714475 0.74777663 -0.46169579, + 0.49202606 0.7710411 -0.40423506, + 0.44596195 0.79853886 -0.40429395, + 0.44641688 0.79935282 -0.4021779, + 0.44777089 0.7980088 -0.40333992, + 0.42514193 0.79940587 -0.42450494, + 0.41321191 0.8118028 -0.4125919, + 0.38783506 0.81542712 -0.42972407, + 0.37889683 0.79903662 -0.4668808, + 0.38123491 0.80395383 -0.45641887, + 0.37039882 0.80888164 -0.45663479, + 0.38096416 0.79644531 -0.46961817, + 0.31818908 0.82345515 -0.46976313, + 0.26903602 -0.84485114 -0.46243507, + 0.20645288 -0.86600548 -0.45542473, + 0.18004596 -0.86409384 -0.47002688, + 0.180117 -0.864079 -0.470027, + 0.14828098 -0.87864989 -0.45385793, + 0.15209794 -0.90131772 -0.40557685, + 0.66506022 -0.39440915 0.63414222, + 0.69382495 -0.41141194 0.59105593, + 0.66481674 -0.45685384 0.59101874, + 0.69211102 -0.47555301 0.54298401, + 0.6588273 -0.52072424 0.54294825, + 0.68256307 -0.53942907 0.49307606, + 0.64505792 -0.58379096 0.49303994, + 0.66529292 -0.60204995 0.44149894, + 0.62360501 -0.64515603 0.44146401, + 0.64045221 -0.66253316 0.38842109, + 0.59477025 -0.70384824 0.38838914, + 0.60839212 -0.7199192 0.33402908, + 0.55899066 -0.75892955 0.3339988, + 0.56961006 -0.77329713 0.27848902, + 0.51671314 -0.80960917 0.27846107, + 0.52458882 -0.82190073 0.22200392, + 0.46853113 -0.85510516 0.22197706, + 0.47396907 -0.86498213 0.16480102, + 0.41510695 -0.89472586 0.16477798, + 0.41845995 -0.90190786 0.10702098, + 0.35732403 -0.92783111 0.10700002, + 0.35897398 -0.93206686 0.048877593, + 0.29591316 -0.95396447 0.048860021, + 0.29626685 -0.95505852 -0.0094428752, + 0.23181403 -0.97271413 -0.0094576012, + 0.23130392 -0.97052562 -0.067663878, + 0.16594194 -0.98381066 -0.067674279, + 0.099331081 -0.98707676 -0.12574898, + 0.098433517 -0.97811013 -0.18333401, + 0.032855399 -0.98250097 -0.183337, + 0.032444283 -0.97015852 -0.24029088, + -0.032465898 -0.97015786 -0.24029097, + -0.031943996 -0.95451587 -0.29644397, + -0.095644385 -0.95024991 -0.29644096, + -0.093756534 -0.93144435 -0.35159811, + -0.15575902 -0.92310512 -0.35159102, + -0.15209097 -0.90131879 -0.40557691, + -0.21195893 -0.88915068 -0.40556684, + -0.20645288 -0.86600548 -0.45542473, + -0.18004596 -0.86409384 -0.47002688, + -0.180117 -0.864079 -0.470027, + -0.14828098 -0.87864989 -0.45385793, + -0.15209799 -0.90131986 -0.40557194, + -0.09151309 -0.90946788 -0.40557793, + -0.093718626 -0.93143725 -0.35162708, + -0.031287305 -0.93561614 -0.35163003, + -0.031917501 -0.95450997 -0.29646599, + 0.031943813 -0.95450938 -0.29646513, + 0.032465789 -0.97015363 -0.24030791, + 0.097183719 -0.96582025 -0.24030507, + 0.098415978 -0.97811478 -0.18331896, + 0.16351992 -0.96935952 -0.18331191, + 0.23003697 -0.9650259 -0.12572998, + 0.2313339 -0.9705165 -0.067692667, + 0.29560104 -0.95291114 -0.067679107, + 0.29625389 -0.95506263 -0.0094304765, + 0.35940591 -0.93313378 -0.0094138579, + 0.35897696 -0.9320659 0.048874594, + 0.42040586 -0.90601772 0.048896082, + 0.41847393 -0.90190285 0.10700799, + 0.47781488 -0.87191582 0.10703198, + 0.47398725 -0.86497539 0.16478407, + 0.53065193 -0.8314119 0.16481099, + 0.5245589 -0.82191283 0.22202994, + 0.57828307 -0.78503412 0.22205903, + 0.56960386 -0.77329981 0.27849394, + 0.61996895 -0.73352695 0.27852598, + 0.60841805 -0.71990705 0.33400804, + 0.65513998 -0.67764801 0.334043, + 0.64047009 -0.66252404 0.38840705, + 0.68326175 -0.61827677 0.38844186, + 0.66528076 -0.60205674 0.44150785, + 0.70398277 -0.55628079 0.44154286, + 0.68257856 -0.53941971 0.4930647, + 0.71705961 -0.49262169 0.49310172, + 0.69212419 -0.47554412 0.54297513, + 0.72231418 -0.42825109 0.5430131, + 0.69382203 -0.411414 0.59105802, + 0.68577677 -0.34704387 0.63974273, + 0.71971893 -0.36415696 0.59109592, + 0.68835115 -0.26852205 0.67384619, + 0.73935503 -0.203042 0.64197201, + 0.77773201 -0.213514 0.591223, + 0.7617569 -0.26500997 0.59118193, + 0.79303485 -0.27583298 0.54314995, + 0.77288389 -0.32815096 0.54310894, + 0.80073911 -0.33992204 0.49322405, + 0.77626985 -0.39265195 0.49318293, + 0.80061179 -0.40491092 0.44166487, + 0.77178752 -0.45750773 0.44162273, + 0.79264009 -0.46981707 0.38857907, + 0.75951964 -0.52169675 0.38853881, + 0.77692187 -0.53359795 0.33416396, + 0.73957258 -0.58428967 0.33412278, + 0.75361729 -0.59533626 0.27863207, + 0.71217835 -0.6443513 0.27859211, + 0.72303194 -0.65412295 0.22214396, + 0.67774642 -0.70094842 0.22210613, + 0.68561506 -0.70903903 0.16491102, + 0.63673216 -0.75325221 0.16487405, + 0.64187479 -0.75928873 0.10713197, + 0.58973378 -0.80046469 0.10709997, + 0.59245723 -0.80411232 0.048969019, + 0.53741914 -0.84189415 0.048938412, + 0.53806108 -0.84285414 -0.0093434406, + 0.48057795 -0.87690187 -0.0093707386, + 0.47951901 -0.87492299 -0.067611597, + 0.4199729 -0.90501279 -0.067635782, + 0.41761884 -0.89989269 -0.12564896, + 0.35658604 -0.92577213 -0.12566802, + 0.35336313 -0.91735536 -0.18328606, + 0.29131201 -0.93890202 -0.183304, + 0.28766507 -0.92710125 -0.24027506, + 0.22508302 -0.9442451 -0.24028903, + 0.22146507 -0.92901725 -0.29644606, + 0.15887401 -0.94173902 -0.29645699, + 0.15573907 -0.9231084 -0.35159117, + 0.093719706 -0.9314481 -0.35159802, + 0.091513976 -0.90947676 -0.4055579, + 0.029764289 -0.89021373 -0.45456985, + 0.030543104 -0.91355711 -0.40556207, + -0.029764289 -0.89021373 -0.45456985, + -0.030543003 -0.91355312 -0.40557107, + 0.030555004 -0.91355312 -0.40557006, + 0.031291198 -0.9356159 -0.35162997, + 0.093755253 -0.93143356 -0.35162681, + 0.095643274 -0.95023978 -0.29647395, + 0.158885 -0.94173402 -0.29646701, + 0.2250659 -0.9442535 -0.24027188, + 0.22791889 -0.95627052 -0.18330191, + 0.29129598 -0.93890989 -0.18328899, + 0.29395202 -0.94751811 -0.12570502, + 0.35660508 -0.92576224 -0.12568703, + 0.35861689 -0.93102962 -0.067659281, + 0.41997609 -0.90501124 -0.067638412, + 0.48057407 -0.87690413 -0.0093664313, + 0.47999987 -0.87590379 0.048913889, + 0.53741598 -0.841896 0.048941001, + 0.53494585 -0.83807272 0.10708396, + 0.58972001 -0.80047297 0.107114, + 0.58499414 -0.79410416 0.16486505, + 0.63670993 -0.75326586 0.16489698, + 0.62940401 -0.74466902 0.222078, + 0.67773974 -0.70095277 0.22211292, + 0.66756296 -0.69047493 0.27857497, + 0.71215802 -0.64436501 0.27861199, + 0.69888681 -0.63240582 0.33409593, + 0.73956323 -0.58429623 0.33413211, + 0.7230072 -0.5712651 0.3884801, + 0.75954086 -0.52167994 0.38851994, + 0.73955685 -0.5080049 0.44157287, + 0.7718001 -0.45749706 0.44161206, + 0.74832284 -0.44363189 0.49315688, + 0.7762512 -0.39267009 0.49319813, + 0.74926215 -0.3790701 0.5430581, + 0.77289772 -0.32813689 0.54309779, + 0.74242502 -0.31525499 0.59111702, + 0.76178885 -0.26497394 0.5911569, + 0.72946578 -0.25378591 0.63519478, + 0.71098703 -0.27732202 0.64621204, + 0.68834805 -0.26853004 0.67384607, + 0.6883508 -0.26852095 0.67384684, + 0.71099079 -0.2773129 0.64621174, + 0.71099007 -0.27731404 0.64621204, + 0.71018493 -0.30166897 0.63610792, + 0.74239063 -0.31528986 0.5911417, + 0.71970874 -0.36416587 0.59110278, + 0.74926782 -0.37906492 0.54305387, + 0.72231096 -0.42825294 0.54301596, + 0.74833125 -0.44362515 0.49315017, + 0.71704817 -0.49263012 0.49311012, + 0.73953193 -0.50802296 0.44159395, + 0.70396793 -0.55628991 0.44155493, + 0.72299492 -0.57127392 0.38848993, + 0.68324977 -0.61828375 0.38845184, + 0.698901 -0.632397 0.33408299, + 0.65513575 -0.67765075 0.33404589, + 0.66757482 -0.69046783 0.27856395, + 0.61996305 -0.73353004 0.27853101, + 0.62941432 -0.74466336 0.2220681, + 0.57830763 -0.7850225 0.22203587, + 0.58502209 -0.7940892 0.16483805, + 0.5306561 -0.83141017 0.16480705, + 0.53493989 -0.83807582 0.10708997, + 0.47778195 -0.87192988 0.10706399, + 0.47998911 -0.87590921 0.048925411, + 0.42040092 -0.90601975 0.04890069, + 0.35940212 -0.93313533 -0.0094101541, + 0.35860991 -0.93103278 -0.067653082, + 0.29559186 -0.95291454 -0.067670271, + 0.29393396 -0.94752586 -0.12568799, + 0.2300081 -0.96503633 -0.12570305, + 0.22792906 -0.95626622 -0.18331204, + 0.16353096 -0.96935576 -0.18332195, + 0.097166277 -0.96582574 -0.24028994, + 0.095604487 -0.9502539 -0.29644096, + 0.031917691 -0.95451677 -0.29644394, + 0.031287309 -0.93561727 -0.35162708, + -0.031291205 -0.93561715 -0.35162702, + -0.030555103 -0.91355711 -0.40556106, + -0.091540597 -0.90947402 -0.40555799, + -0.088706307 -0.8812561 -0.46424007, + -0.090814181 -0.88105679 -0.46421087, + 0.090814181 -0.88105679 -0.46421087, + 0.088706307 -0.8812561 -0.46424007, + 0.091539726 -0.90946525 -0.40557808, + 0.15209198 -0.90132087 -0.40557194, + 0.15575801 -0.9230991 -0.35160702, + 0.21708892 -0.91063273 -0.35159689, + 0.22145994 -0.92901975 -0.29644194, + 0.2830241 -0.91215527 -0.29642913, + 0.2876491 -0.92711037 -0.2402591, + 0.34892783 -0.90583259 -0.24024288, + 0.35334992 -0.91736275 -0.18327396, + 0.41385484 -0.89170772 -0.18325295, + 0.41762999 -0.89988601 -0.12566, + 0.47681218 -0.86998028 -0.12563604, + 0.47950113 -0.8749342 -0.067592815, + 0.53687006 -0.84095514 -0.067566209, + 0.538055 -0.84285802 -0.0093365302, + 0.59315008 -0.80503809 -0.0093070213, + 0.59244108 -0.8041231 0.048985906, + 0.64484382 -0.76274085 0.049018189, + 0.64188194 -0.7592839 0.10712399, + 0.69114995 -0.71472293 0.10715899, + 0.68561095 -0.70904195 0.16491598, + 0.73143196 -0.66166294 0.16495298, + 0.72303939 -0.65411741 0.22213614, + 0.76509827 -0.60436922 0.22217707, + 0.75360984 -0.59534186 0.27863994, + 0.77692902 -0.53359199 0.33415699, + 0.81081313 -0.48051205 0.33420104, + 0.7926569 -0.46980193 0.38856295, + 0.82224756 -0.4158048 0.38860682, + 0.80060971 -0.40491286 0.44166684, + 0.82583803 -0.350548 0.44171, + 0.8007232 -0.33993909 0.49323812, + 0.82161582 -0.28569293 0.49328187, + 0.79305083 -0.27581495 0.54313588, + 0.80967629 -0.22221808 0.54317915, + 0.77773768 -0.21350792 0.59121776, + 0.79022563 -0.16110693 0.59125972, + 0.75761127 -0.15451106 0.63415426, + 0.73896635 -0.1951481 0.64486128, + 0.70640284 -0.18660195 0.68276983, + 0.70648783 -0.18623996 0.6827808, + 0.73913401 -0.194791 0.644777, + 0.73913503 -0.194787 0.644777, + 0.71297807 -0.18793602 0.67553109, + 0.71296221 -0.18799208 0.67553222, + 0.74236739 -0.19569509 0.64077628, + 0.74238384 -0.19563696 0.64077485, + 0.71298605 -0.18793803 0.67552209, + 0.68798292 -0.23022898 0.68823993, + 0.64832902 -0.217024 0.729774, + 0.66364396 -0.16415098 0.72981596, + 0.61590409 -0.15242003 0.77293617, + 0.62612098 -0.102375 0.77297598, + 0.57490629 -0.094082348 0.81279242, + 0.58055913 -0.04752171 0.81283015, + 0.52633905 -0.043172903 0.84917814, + 0.41137499 0.0324893 0.910887, + 0.40737092 0.065474182 0.91091275, + 0.34771198 0.055759493 0.93594187, + 0.2818591 0.068711624 0.95699233, + 0.27535704 0.091160804 0.95701009, + 0.2154261 0.071140438 0.97392547, + 0.208932 0.088262998 0.973939, + 0.14986792 0.063081972 0.98669153, + 0.14424597 0.074930787 0.98670077, + 0.086789057 0.044764176 0.99522054, + 0.086793371 0.044752683 0.99522066, + 0.090175591 0.037625097 0.99521488, + 0.14987202 0.063064404 0.98669213, + 0.15452605 0.050791319 0.98668236, + 0.21542703 0.071128309 0.97392613, + 0.22050706 0.053589012 0.97391224, + 0.28186116 0.068728827 0.95699048, + 0.28654304 0.045798305 0.95697212, + 0.34771088 0.055754282 0.93594265, + 0.35112992 0.027603693 0.93591976, + 0.41137499 0.032487702 0.910887, + 0.52633977 -0.043171879 0.8491776, + 0.52121502 -0.085377797 0.84914398, + 0.57491207 -0.094075017 0.81278914, + 0.56552994 -0.14003098 0.8127529, + 0.61590797 -0.15241599 0.7729339, + 0.6016919 -0.20149195 0.77289581, + 0.64832592 -0.21702696 0.72977597, + 0.62880731 -0.26848912 0.72973633, + 0.66881907 -0.28550202 0.68641806, + 0.64915079 -0.34307587 0.67889774, + 0.68038017 -0.3595241 0.63861215, + 0.68029296 -0.35969797 0.63860697, + 0.64907795 -0.34324896 0.67887992, + 0.64918101 -0.34304401 0.67888498, + 0.6753282 -0.3568131 0.64545816, + 0.67529768 -0.35686982 0.6454587, + 0.67529976 -0.35686389 0.64545977, + 0.649993 -0.34353501 0.67785901, + 0.59701389 -0.40876091 0.69028181, + 0.63179499 -0.43250501 0.64325303, + 0.63178098 -0.43252701 0.64325202, + 0.60988206 -0.41757506 0.67355406, + 0.60989904 -0.41755006 0.67355406, + 0.63229084 -0.43283591 0.64254284, + 0.63125795 -0.43384793 0.64287597, + 0.66482383 -0.45684987 0.59101391, + 0.63285381 -0.5002389 0.59097987, + 0.65883595 -0.52071893 0.54294294, + 0.62262797 -0.56354702 0.54290801, + 0.64505577 -0.58379173 0.49304181, + 0.60463023 -0.62559122 0.49300918, + 0.62359589 -0.64516079 0.44146988, + 0.57913393 -0.68537396 0.44143695, + 0.59478408 -0.70384204 0.38837907, + 0.54648089 -0.74198681 0.38834792, + 0.55899578 -0.75892764 0.33399487, + 0.50706118 -0.79457933 0.33396512, + 0.51668888 -0.80961782 0.27848095, + 0.46146813 -0.8423242 0.27845505, + 0.46850184 -0.8551147 0.22200193, + 0.41513491 -0.89471775 0.16475196, + 0.35445398 -0.9204489 0.16473098, + 0.35731608 -0.92783326 0.10700803, + 0.29455 -0.949628 0.106991, + 0.29591006 -0.95396525 0.048862811, + 0.23153909 -0.97159839 0.04884962, + 0.2318159 -0.97271365 -0.0094596259, + 0.16632704 -0.98602521 -0.0094700614, + 0.16596104 -0.98380625 -0.067691714, + 0.099852353 -0.99269652 -0.067698568, + 0.099292718 -0.9870851 -0.12571402, + 0.033146102 -0.99151212 -0.12571801, + 0.032846484 -0.98250252 -0.18332991, + -0.032855514 -0.98250246 -0.18332909, + -0.032444105 -0.97015411 -0.24030903, + -0.097165912 -0.9658221 -0.24030504, + -0.095603481 -0.95024377 -0.29647395, + -0.15887301 -0.94173598 -0.29646701, + -0.15573807 -0.92310244 -0.35160717, + -0.21707807 -0.91063529 -0.35159713, + -0.21196793 -0.88915169 -0.40555984, + -0.27090898 -0.87300587 -0.40554795, + -0.26278207 -0.84676319 -0.46253413, + -0.26903602 -0.84485114 -0.46243507, + -0.090768926 -0.88027525 -0.46570012, + -0.090743691 -0.88027787 -0.46569994, + 0.090743691 -0.88027787 -0.46569994, + 0.090768926 -0.88027525 -0.46570012, + -0.30951405 0.80084521 -0.51268715, + -0.30944186 0.80087262 -0.51268774, + -0.33277014 0.81143034 -0.48046324, + -0.32081887 0.80682468 -0.49609381, + -0.30947712 0.80091327 -0.51260316, + -0.46173987 0.8085888 -0.36466491, + -0.52669692 0.78188586 -0.33353397, + -0.50027817 0.7901383 -0.35412312, + -0.49655193 0.79368287 -0.35143098, + -0.5036332 0.78924131 -0.35135713, + -0.49199918 0.77105832 -0.40423515, + -0.44695807 0.79797614 -0.40430507, + -0.45079488 0.80480683 -0.38609591, + -0.46234411 0.7933082 -0.39610609, + -0.44054884 0.79935968 -0.40858385, + -0.42807186 0.78149468 -0.45389485, + -0.43795216 0.79948831 -0.41111615, + -0.44318387 0.79663885 -0.4110409, + -0.40328509 0.81512719 -0.41584709, + -0.38285014 0.81238532 -0.43983614, + -0.379529 0.805363 -0.45535499, + -0.39587706 0.79772812 -0.45487505, + -0.3578729 0.81280482 -0.45964688, + -0.36557388 0.80366868 -0.46954483, + -0.3182511 0.82361418 -0.46944213, + -0.40115783 0.78698963 -0.46874279, + -0.4011789 0.78697884 -0.46874288, + -0.62399906 0.63184303 -0.45978206, + -0.57473665 0.68016261 -0.45503473, + -0.59034795 0.69858795 -0.40430695, + -0.63566905 0.65759706 -0.40434006, + -0.65099818 0.67340517 -0.35032409, + -0.69449919 0.62842619 -0.35035908, + -0.70848197 0.64102793 -0.29518896, + -0.74970222 0.59227324 -0.29522711, + -0.76195091 0.60190195 -0.23904997, + -0.80043679 0.54966986 -0.23908994, + -0.81058532 0.55659115 -0.18209305, + -0.84594345 0.50120431 -0.1821371, + -0.8536551 0.50572705 -0.12455201, + -0.88552612 0.44757006 -0.12459801, + -0.89052111 0.45004806 -0.066550605, + -0.91858065 0.38958186 -0.066599078, + -0.92060924 0.39039609 -0.0083467718, + -0.94463348 0.32802016 -0.0083984137, + -0.94350511 0.32758203 0.049881909, + -0.96328098 0.26383099 0.049830001, + -0.95885402 0.26257199 0.107958, + -0.97425246 0.19796109 0.10790605, + -0.96644527 0.19632804 0.16564704, + -0.97741377 0.13130397 0.16559495, + -0.96619922 0.12975103 0.22276406, + -0.97271913 0.064937204 0.22271203, + -0.95811689 0.063914694 0.27915397, + -0.94025421 -0.063206218 0.33455509, + -0.91920388 -0.061840393 0.38889593, + -0.91304272 -0.12308995 0.38884684, + -0.88902068 -0.11990196 0.44188884, + -0.87904602 -0.179033 0.441843, + -0.85231715 -0.17364104 0.49336013, + -0.8388449 -0.23017497 0.49331394, + -0.8096748 -0.22222394 0.54317886, + -0.79304361 -0.27583587 0.54313576, + -0.76177388 -0.26501498 0.59115791, + -0.74240798 -0.31529701 0.59111601, + -0.71018493 -0.30166897 0.63610792, + -0.68834805 -0.26853004 0.67384607, + -0.6883508 -0.26852095 0.67384684, + -0.68835115 -0.26852205 0.67384619, + -0.71099007 -0.27731404 0.64621204, + -0.71099079 -0.2773129 0.64621174, + -0.71098703 -0.27732202 0.64621204, + -0.77773571 -0.21351492 0.59121776, + -0.73935503 -0.203042 0.64197201, + -0.74236739 -0.19569509 0.64077628, + -0.74238384 -0.19563696 0.64077485, + -0.72946578 -0.25378591 0.63519478, + -0.76177132 -0.2649681 0.59118223, + -0.77773398 -0.213507 0.591223, + -0.80967391 -0.22221696 0.54318297, + -0.8226769 -0.16765198 0.54322696, + -0.85231668 -0.17363594 0.49336281, + -0.86198485 -0.11632597 0.49340689, + -0.88902456 -0.11992094 0.44187579, + -0.89502615 -0.060267907 0.44192305, + -0.91920489 -0.061844293 0.38889295, + -0.9402535 0.062684327 0.33465514, + -0.95811391 0.063924193 0.27916196, + -0.9516899 0.12777698 0.27921197, + -0.96619213 0.12977302 0.22278203, + -0.95535463 0.19401793 0.22283292, + -0.96644902 0.196318 0.165637, + -0.95117533 0.2604101 0.16568705, + -0.95885825 0.26256105 0.10794702, + -0.93917274 0.32602292 0.10799798, + -0.94350827 0.3275741 0.049874812, + -0.91951567 0.38986984 0.04992348, + -0.92061466 0.39038286 -0.0083596874, + -0.89248377 0.45100287 -0.0083118184, + -0.89051813 0.45005506 -0.066543207, + -0.8584733 0.50852919 -0.06649562, + -0.85365731 0.50572217 -0.12455705, + -0.81798589 0.56160092 -0.12451299, + -0.8105939 0.55657291 -0.18210998, + -0.77161199 0.60948002 -0.182069, + -0.76195312 0.60189807 -0.23905303, + -0.720061 0.65144801 -0.239014, + -0.70848495 0.64102197 -0.29519498, + -0.66410482 0.68691081 -0.29515794, + -0.65099996 0.67340297 -0.35032496, + -0.60457999 0.71538699 -0.350292, + -0.59034491 0.69859284 -0.40430292, + -0.54238492 0.73646593 -0.40427294, + -0.5288862 0.71818322 -0.45220816, + -0.55322808 0.68876809 -0.46854806, + -0.553258 0.68874401 -0.468548, + -0.48063487 0.74322581 -0.46540889, + -0.48064095 0.74322194 -0.46540895, + -0.48180005 0.74483508 -0.46161607, + -0.47714475 0.74777663 -0.46169579, + -0.49202019 0.77103227 -0.40425915, + -0.54239583 0.73645079 -0.40428585, + -0.55547392 0.7541579 -0.35027796, + -0.60459203 0.71536899 -0.350308, + -0.61676627 0.72972435 -0.29513016, + -0.66410917 0.68690419 -0.29516405, + -0.67496079 0.69807982 -0.23898195, + -0.72006518 0.65144116 -0.23902006, + -0.729195 0.65965402 -0.18201999, + -0.7716068 0.6094889 -0.18206096, + -0.77864331 0.61500025 -0.12445605, + -0.81797898 0.56161398 -0.1245, + -0.82259184 0.56473386 -0.066470586, + -0.85848385 0.50850886 -0.066515788, + -0.86038083 0.5095849 -0.0082505886, + -0.89247727 0.45101616 -0.0082979631, + -0.89141089 0.45043093 0.049985293, + -0.91950989 0.38988194 0.049936093, + -0.91528457 0.38804483 0.10805295, + -0.93917 0.326029 0.108004, + -0.93164259 0.32336885 0.16575493, + -0.95116788 0.26042697 0.16570298, + -0.94025278 0.25739193 0.22287694, + -0.95535725 0.19401105 0.22282806, + -0.94101751 0.19105092 0.27925888, + -0.95169163 0.12777296 0.27920792, + -0.93395275 0.12534297 0.33469591, + -0.94025749 0.062673628 0.33464614, + -0.91920513 0.061221108 0.38899106, + -0.89502299 -0.060256802 0.44193101, + -0.867796 -0.058475599 0.49346799, + -0.8619799 -0.11630298 0.49342093, + -0.83201057 -0.11231295 0.54327178, + -0.8226769 -0.16764899 0.54322791, + -0.79022914 -0.16109201 0.59125906, + -0.79023182 -0.16110896 0.5912509, + -0.7992003 -0.10794104 0.59129322, + -0.83201087 -0.11231498 0.54327095, + -0.83762491 -0.056510493 0.54331493, + -0.86780071 -0.058491077 0.49345782, + -0.89502198 0.059563801 0.442027, + -0.91920364 0.061224777 0.38899386, + -0.91304225 0.12247203 0.38904309, + -0.93395877 0.12532797 0.33468491, + -0.92348641 0.18742108 0.33473316, + -0.9410271 0.19103003 0.27924103, + -0.92614824 0.25346807 0.27929106, + -0.9402591 0.25737903 0.22286503, + -0.92095977 0.3195979 0.22291294, + -0.93164957 0.32335585 0.16574092, + -0.90795714 0.38487306 0.16579102, + -0.91529268 0.38802984 0.10803796, + -0.88732702 0.448295 0.108085, + -0.89142221 0.45041111 0.049965013, + -0.859348 0.50893998 0.0500114, + -0.86037499 0.50959498 -0.0082405303, + -0.8244009 0.56594694 -0.008195159, + -0.82258439 0.56474632 -0.066458233, + -0.78303915 0.61841613 -0.066416115, + -0.77864718 0.61499411 -0.12446203, + -0.72919184 0.65965885 -0.18201496, + -0.68351907 0.70688504 -0.18197602, + -0.67496002 0.69808102 -0.23898099, + -0.62683904 0.74160403 -0.23894803, + -0.61676222 0.72973025 -0.29512411, + -0.56664801 0.76930499 -0.295093, + -0.55546498 0.75417 -0.35026601, + -0.50478524 0.78899735 -0.35025018, + -0.51008809 0.79725909 -0.32278204, + -0.52940613 0.79420018 -0.29828706, + -0.53566617 0.79114729 -0.29520813, + -0.56663704 0.7693181 -0.29508004, + -0.57604104 0.78203511 -0.23790303, + -0.61694795 0.75039989 -0.23722397, + -0.57690513 0.78612715 -0.22177605, + -0.57685596 0.78606188 -0.22213498, + -0.57498211 0.78251219 -0.23889406, + -0.62683076 0.74161476 -0.23893692, + -0.63477784 0.75096881 -0.18194196, + -0.68351978 0.70688379 -0.18197794, + -0.6897518 0.71328181 -0.12438397, + -0.73998964 0.66933471 -0.066380069, + -0.78304201 0.61841202 -0.066420898, + -0.7847718 0.61973089 -0.008180378, + -0.8244186 0.56592071 -0.0082236165, + -0.82343429 0.5651992 0.050058719, + -0.85934532 0.50894415 0.05001542, + -0.85539639 0.50655925 0.10814305, + -0.88731831 0.44830915 0.10809804, + -0.88020825 0.44467011 0.16583705, + -0.90795827 0.38487116 0.16578905, + -0.89753598 0.38040701 0.22297899, + -0.92094922 0.31961608 0.22293106, + -0.90712726 0.3147721 0.27935407, + -0.92613935 0.25348508 0.2793051, + -0.90887201 0.24871001 0.334806, + -0.92347288 0.18744698 0.33475596, + -0.90279931 0.18320206 0.38908914, + -0.91304332 0.12247004 0.38904116, + -0.88902712 0.11919902 0.44206607, + -0.89502668 0.059553079 0.44201884, + -0.86780202 0.057689901 0.49355, + -0.83762848 -0.056521233 0.54330832, + -0.80459619 -0.054347612 0.59133011, + -0.79920286 -0.10795099 0.59128791, + -0.75953811 -0.10265701 0.64231104, + -0.75659734 -0.10928205 0.64468431, + -0.73006266 -0.10549295 0.67518872, + -0.73006094 -0.10550299 0.67518896, + -0.7595278 -0.10971197 0.64115584, + -0.75952089 -0.10976499 0.64115494, + -0.73006284 -0.10555498 0.67517883, + -0.72283804 -0.058906309 0.68850207, + -0.681288 -0.055584699 0.72990203, + -0.67465407 -0.11021601 0.72985905, + -0.62612283 -0.10236498 0.7729758, + -0.61590588 -0.15241498 0.77293581, + -0.56552011 -0.14002803 0.81276017, + -0.55247217 -0.18507805 0.81272429, + -0.50087416 -0.16788206 0.84908229, + -0.48579371 -0.20764787 0.84905052, + -0.43367505 -0.18546902 0.88177514, + -0.4173952 -0.2197791 0.88174742, + -0.36543989 -0.19253293 0.91070569, + -0.3488301 -0.22130007 0.91068321, + -0.29773712 -0.18901308 0.93574935, + -0.28161785 -0.21236689 0.93573058, + -0.21729203 -0.19326703 0.9567821, + -0.16999193 -0.15137592 0.97374952, + -0.15733302 -0.16455501 0.97373915, + -0.11285803 -0.11826904 0.98654735, + -0.061986484 -0.076722182 0.99512374, + -0.055679802 -0.0814614 0.99511999, + -0.04200808 -0.089355752 0.99511355, + -0.71180725 -0.17598206 0.67997122, + -0.66364402 -0.16415 0.72981602, + -0.64832801 -0.21702699 0.729774, + -0.60169613 -0.20149304 0.77289218, + -0.5835799 -0.24926195 0.77285379, + -0.53583413 -0.22895005 0.81268919, + -0.51573098 -0.27131799 0.81265497, + -0.46756795 -0.24606997 0.8490169, + -0.39841408 -0.25263306 0.88172722, + -0.37684992 -0.28387395 0.88170278, + -0.32994804 -0.24865402 0.91066211, + -0.30891889 -0.27440992 0.91064173, + -0.26368102 -0.23435202 0.93570912, + -0.24403109 -0.25481108 0.93569237, + -0.20109491 -0.21012589 0.95676953, + -0.18359405 -0.22563006 0.95675725, + -0.14363107 -0.17669509 0.97372949, + -0.12900798 -0.18768197 0.97372091, + -0.092541769 -0.13486096 0.98653364, + -0.08144109 -0.14188099 0.98652786, + -0.049001079 -0.085685566 0.99511653, + -0.049024794 -0.085667692 0.99511689, + -0.055687808 -0.081454411 0.99512011, + -0.092554219 -0.13484803 0.98653424, + -0.14362499 -0.17670299 0.9737289, + -0.15732893 -0.16456194 0.97373867, + -0.20109993 -0.21011592 0.95677066, + -0.21729796 -0.19325195 0.95678377, + -0.2636891 -0.23433009 0.93571234, + -0.28161496 -0.21237397 0.93572986, + -0.32994413 -0.2486731 0.9106583, + -0.34882909 -0.22131406 0.91068023, + -0.39841285 -0.25264692 0.8817237, + -0.41739479 -0.21977089 0.88174957, + -0.46756783 -0.24607791 0.8490147, + -0.48579606 -0.20766503 0.8490451, + -0.53583485 -0.22895692 0.81268668, + -0.55247295 -0.18508598 0.81272191, + -0.60169387 -0.20148596 0.77289581, + -0.61590677 -0.15242094 0.77293372, + -0.66364378 -0.16415194 0.72981578, + -0.67465502 -0.110218 0.72985798, + -0.72338104 -0.11809801 0.68027407, + -0.72215337 -0.10437405 0.68381327, + -0.75659591 -0.10929398 0.64468396, + -0.75761127 -0.15451106 0.63415426, + -0.73896635 -0.1951481 0.64486128, + -0.70640284 -0.18660195 0.68276983, + -0.70648783 -0.18623996 0.6827808, + -0.73913401 -0.194791 0.644777, + -0.73913503 -0.194787 0.644777, + -0.71297807 -0.18793602 0.67553109, + -0.71296221 -0.18799208 0.67553222, + -0.71298605 -0.18793803 0.67552209, + -0.68798292 -0.23022898 0.68823993, + -0.64832705 -0.21702303 0.72977608, + -0.62880707 -0.26849002 0.72973603, + -0.5835799 -0.24925594 0.77285582, + -0.56167495 -0.29541597 0.77281988, + -0.51573098 -0.27133301 0.81265002, + -0.49228707 -0.31193802 0.81261814, + -0.4221361 -0.3179141 0.84895921, + -0.37684509 -0.28390405 0.88169521, + -0.35284102 -0.31330404 0.88167113, + -0.30891803 -0.27441302 0.91064113, + -0.28590006 -0.29837605 0.91062224, + -0.2440329 -0.25480792 0.93569267, + -0.22278894 -0.27362794 0.93567777, + -0.18359195 -0.22563392 0.95675665, + -0.16489704 -0.23968206 0.95674527, + -0.12900303 -0.18768905 0.97372025, + -0.081458971 -0.14186496 0.98652864, + -0.069843099 -0.14796101 0.98652399, + -0.042023685 -0.089345969 0.99511367, + -0.034760911 -0.092440426 0.99511135, + -0.019586392 -0.096835263 0.99510765, + -0.65052724 -0.34196913 0.67813826, + -0.60521102 -0.31822601 0.729693, + -0.57769114 -0.3658931 0.72965419, + -0.53613281 -0.33964789 0.77278769, + -0.50712192 -0.38167894 0.77275389, + -0.46564081 -0.35053989 0.81258869, + -0.43596205 -0.38688907 0.81256014, + -0.39524505 -0.35084504 0.84893411, + -0.36579213 -0.38150916 0.84890932, + -0.32654703 -0.34067604 0.88165009, + -0.29812503 -0.36585504 0.88163012, + -0.26101708 -0.32042712 0.91060227, + -0.2344451 -0.34039411 0.9105863, + -0.20010903 -0.29066703 0.93566513, + -0.17612901 -0.30583003 0.93565309, + -0.14514196 -0.2521719 0.95673567, + -0.12444799 -0.26303297 0.95672691, + -0.097359456 -0.20595789 0.97370553, + -0.080537096 -0.21312498 0.97369987, + -0.057770625 -0.15310808 0.98651946, + -0.045322005 -0.15726401 0.98651612, + -0.027269106 -0.094941624 0.99510926, + -0.027279813 -0.094937146 0.9951095, + -0.03476521 -0.092438132 0.99511135, + -0.057780184 -0.15310197 0.98651975, + -0.069838777 -0.14796494 0.98652363, + -0.097361676 -0.20595595 0.97370577, + -0.14515495 -0.25215691 0.95673764, + -0.16490905 -0.23966606 0.95674723, + -0.20011708 -0.29065409 0.93566734, + -0.22279993 -0.27360892 0.93568063, + -0.26102698 -0.32040596 0.91060686, + -0.28590399 -0.29836699 0.91062403, + -0.32655212 -0.34066013 0.88165432, + -0.35284483 -0.31328684 0.8816756, + -0.39524907 -0.35082603 0.84894013, + -0.4221389 -0.31789291 0.84896582, + -0.4656392 -0.35055217 0.8125844, + -0.49228707 -0.31194603 0.8126151, + -0.53613418 -0.33964011 0.77279031, + -0.561674 -0.29540199 0.77282602, + -0.60521072 -0.31821585 0.72969764, + -0.62880623 -0.26848909 0.72973722, + -0.66881907 -0.28550202 0.68641806, + -0.64915079 -0.34307587 0.67889774, + -0.68038017 -0.3595241 0.63861215, + -0.68029296 -0.35969797 0.63860697, + -0.64907795 -0.34324896 0.67887992, + -0.64918101 -0.34304401 0.67888498, + -0.6753282 -0.3568131 0.64545816, + -0.67529768 -0.35686982 0.6454587, + -0.64998996 -0.34354097 0.67785895, + -0.649993 -0.34353501 0.67785901, + -0.59701389 -0.40876091 0.69028181, + -0.63179499 -0.43250501 0.64325303, + -0.63178098 -0.43252701 0.64325202, + -0.60988206 -0.41757506 0.67355406, + -0.61838388 -0.39158392 0.68136883, + -0.57769096 -0.36588997 0.72965592, + -0.54642004 -0.41119307 0.72962004, + -0.50712103 -0.38169599 0.77274603, + -0.435963 -0.386884 0.81256199, + -0.40347105 -0.42071107 0.81253511, + -0.36579213 -0.38151115 0.84890831, + -0.33396897 -0.40970394 0.84888589, + -0.29813194 -0.3658379 0.88163477, + -0.26777801 -0.38864699 0.88161701, + -0.23445009 -0.34038511 0.91058832, + -0.20637508 -0.35813913 0.91057432, + -0.17614701 -0.30580702 0.93565714, + -0.151024 -0.318993 0.93564701, + -0.12445602 -0.26302502 0.9567281, + -0.10293996 -0.27219293 0.95672065, + -0.080534376 -0.21312696 0.97369975, + -0.063181207 -0.21892004 0.9736951, + -0.045320801 -0.15726499 0.986516, + -0.032590017 -0.16040307 0.9865135, + -0.0196082 -0.096827999 0.99510801, + -0.0118207 -0.098093599 0.995107, + 0.0039509111 -0.098731719 0.99510622, + 0.011820798 -0.098094985 0.99510688, + 0.0039421013 -0.098731138 0.99510634, + 0.00655192 -0.163564 0.98651099, + -0.006561059 -0.16356398 0.98651087, + -0.0091465106 -0.22769703 0.97368914, + -0.02737581 -0.22622508 0.97369033, + -0.034992795 -0.28894198 0.95670688, + -0.058077093 -0.28518996 0.95670986, + -0.070474319 -0.34588811 0.93562537, + -0.098013565 -0.33909988 0.93563062, + -0.11483397 -0.3971459 0.91054279, + -0.14634608 -0.38662517 0.91055143, + -0.16715392 -0.44146881 0.88156956, + -0.20208396 -0.42658591 0.88158178, + -0.22637103 -0.47774506 0.84883213, + -0.2640141 -0.45799014 0.84884727, + -0.29121208 -0.50507319 0.81246328, + -0.33086398 -0.47999895 0.81248391, + -0.3603451 -0.52267814 0.77263117, + -0.40117714 -0.49199519 0.77265632, + -0.4322691 -0.53004414 0.72951818, + -0.51047903 -0.53201306 0.67555404, + -0.47347993 -0.49353495 0.72954792, + -0.55059719 -0.48832417 0.67703927, + -0.51160502 -0.45382199 0.72959298, + -0.47348693 -0.49350595 0.72956294, + -0.43943173 -0.45808774 0.77269351, + -0.40118623 -0.4919703 0.77266747, + -0.36837491 -0.45181587 0.81250381, + -0.33086115 -0.48000523 0.81248134, + -0.29995486 -0.4352558 0.84886956, + -0.26402092 -0.45797786 0.84885168, + -0.23569691 -0.40894485 0.88159573, + -0.2020831 -0.42658719 0.88158143, + -0.17692596 -0.3735919 0.91056377, + -0.14635508 -0.38661718 0.9105534, + -0.124923 -0.330129 0.935633, + -0.097987175 -0.33912092 0.93562573, + -0.080748022 -0.27960607 0.95671326, + -0.058064975 -0.28519684 0.95670855, + -0.045426112 -0.22329806 0.97369123, + -0.027351283 -0.22623587 0.97368842, + -0.019619392 -0.16251095 0.98651165, + -0.0065519977 -0.16356593 0.98651063, + -0.0039421315 -0.098731838 0.99510634, + -0.0039508617 -0.098730445 0.99510646, + -0.011811798 -0.098095782 0.99510688, + -0.019631501 -0.16250701 0.98651212, + -0.032596391 -0.16039996 0.98651373, + -0.045442011 -0.22329006 0.97369224, + -0.063189082 -0.21891494 0.97369576, + -0.080768973 -0.27959192 0.95671564, + -0.10294495 -0.27218789 0.95672154, + -0.12492596 -0.33012587 0.93563366, + -0.15100308 -0.31901616 0.93564242, + -0.17691293 -0.37360787 0.91055971, + -0.20636904 -0.3581481 0.91057223, + -0.23570491 -0.40893185 0.88159972, + -0.26777595 -0.38865092 0.88161576, + -0.29995796 -0.43524894 0.84887189, + -0.33397701 -0.40968499 0.84889197, + -0.36838311 -0.45179215 0.81251329, + -0.40347192 -0.4207069 0.81253684, + -0.43942615 -0.45810714 0.77268529, + -0.51160413 -0.45382911 0.72958916, + -0.54642004 -0.41118607 0.72962403, + -0.58451307 -0.43977305 0.68186808, + -0.59388292 -0.40665394 0.69421595, + -0.63227206 -0.43286306 0.64254308, + -0.60649323 -0.47944218 0.63427222, + -0.57686299 -0.50036502 0.64565003, + -0.55664903 -0.48287401 0.67599899, + -0.55666888 -0.48284987 0.67599982, + -0.57688689 -0.50034291 0.6456458, + -0.57685488 -0.50037986 0.6456458, + -0.55301595 -0.47975194 0.68118393, + -0.55288994 -0.47988993 0.68118894, + -0.55315793 -0.47961095 0.68116796, + -0.49235299 -0.537009 0.68498898, + -0.51596099 -0.56270099 0.64587301, + -0.51597708 -0.56268609 0.64587307, + -0.49906099 -0.54427701 0.67431498, + -0.49904895 -0.54428697 0.67431593, + -0.45859018 -0.56224018 0.68817222, + -0.43227115 -0.53003818 0.72952121, + -0.38829294 -0.56308591 0.72949493, + -0.36035699 -0.52265102 0.77264398, + -0.3171761 -0.5499571 0.77262318, + -0.29122797 -0.50504696 0.81247389, + -0.24967706 -0.52685511 0.81245619, + -0.22636506 -0.47775313 0.84882915, + -0.18726395 -0.49441287 0.8488158, + -0.16716807 -0.44145414 0.88157427, + -0.13114598 -0.45347995 0.88156486, + -0.11482406 -0.39715424 0.91054052, + -0.082550101 -0.40510899 0.91053402, + -0.070458889 -0.34589797 0.93562287, + -0.042465702 -0.35044801 0.935619, + -0.034994703 -0.28894103 0.95670712, + -0.011685294 -0.29082286 0.95670551, + -0.0091417991 -0.22769797 0.9736889, + 0.0091465693 -0.22769797 0.9736889, + 0.0065611186 -0.16356495 0.98651075, + 0.01963179 -0.16250992 0.98651153, + 0.0118117 -0.098095 0.995107, + 0.019585703 -0.096831717 0.99510813, + 0.03476071 -0.092439733 0.99511135, + -0.36679798 -0.63585895 0.67907494, + -0.34175104 -0.59251606 0.72947305, + -0.29299098 -0.61810696 0.72945195, + -0.2719171 -0.57372528 0.77259338, + -0.22493811 -0.5937413 0.77257633, + -0.20653602 -0.54525107 0.8124311, + -0.162046 -0.56010401 0.812419, + -0.14691098 -0.50788194 0.84880686, + -0.10562498 -0.51805788 0.84879881, + -0.094290465 -0.46256381 0.8815577, + -0.049750309 -0.41043609 0.91053122, + -0.016617201 -0.41311106 0.91052914, + -0.014183094 -0.35272482 0.93561959, + 0.014161998 -0.35272497 0.93561989, + 0.011670694 -0.29082382 0.95670539, + 0.034992706 -0.28894106 0.95670724, + 0.027376497 -0.22623096 0.9736889, + 0.045443103 -0.22329503 0.97369111, + 0.032596584 -0.16040093 0.9865135, + 0.045321997 -0.15726498 0.98651588, + 0.027268909 -0.094940834 0.99510938, + 0.027280306 -0.094938919 0.99510926, + 0.019608594 -0.096829779 0.99510777, + 0.032589693 -0.16040096 0.98651373, + 0.0196191 -0.16250899 0.98651201, + 0.027350387 -0.2262269 0.97369051, + 0.0091417506 -0.22769703 0.97368914, + 0.0116856 -0.29082799 0.95670402, + -0.011670901 -0.29082802 0.95670414, + -0.014162406 -0.35273418 0.93561643, + -0.042461719 -0.35045019 0.9356184, + -0.049748022 -0.41043821 0.91053039, + -0.082554303 -0.40510601 0.91053498, + -0.094289221 -0.46256512 0.88155723, + -0.13114408 -0.45348126 0.88156456, + -0.146909 -0.50788403 0.84880602, + -0.18726493 -0.49441081 0.84881669, + -0.20655195 -0.54523188 0.8124398, + -0.24967299 -0.52685899 0.812455, + -0.27192184 -0.57371867 0.77259654, + -0.31716803 -0.54997307 0.77261513, + -0.34175 -0.59251797 0.72947198, + -0.38829285 -0.56308484 0.72949576, + -0.41608477 -0.60330665 0.6803636, + -0.42770109 -0.58921909 0.68548715, + -0.44947401 -0.61915302 0.64391202, + -0.41599199 -0.65213197 0.63377798, + -0.37562394 -0.66576493 0.64471996, + -0.35998198 -0.63809097 0.68062693, + -0.36004221 -0.63805538 0.68062842, + -0.37569308 -0.66574019 0.64470518, + -0.37564594 -0.66576695 0.64470494, + -0.3620441 -0.6417042 0.67612118, + -0.36216483 -0.64163768 0.67611969, + -0.36199012 -0.64170724 0.67614722, + -0.31107685 -0.65616667 0.68751466, + -0.29299718 -0.61809635 0.72945839, + -0.2423901 -0.63965821 0.72944123, + -0.22495386 -0.59372061 0.77258754, + -0.176493 -0.6099 0.77257502, + -0.16205607 -0.56009322 0.81242436, + -0.11651199 -0.57131892 0.8124159, + -0.105631 -0.518053 0.84880102, + -0.063652903 -0.52487499 0.84879601, + -0.018968305 -0.47170913 0.88155025, + -0.0166077 -0.41311601 0.91052699, + 0.016617397 -0.41311592 0.91052675, + 0.014183493 -0.35273281 0.93561661, + 0.04246591 -0.3504501 0.93561822, + 0.034994692 -0.28894195 0.95670676, + 0.058064006 -0.28519204 0.9567101, + 0.045425303 -0.22329403 0.97369212, + 0.063180476 -0.21891792 0.97369564, + 0.045320801 -0.15726499 0.986516, + 0.057781115 -0.15310504 0.98651922, + 0.034765311 -0.092438526 0.99511135, + 0.042006791 -0.089353174 0.99511379, + 0.049027223 -0.085671835 0.99511647, + 0.042024281 -0.089347355 0.99511355, + 0.069843575 -0.14796294 0.98652363, + 0.057769977 -0.15310694 0.98651963, + 0.080537371 -0.21312593 0.97369963, + 0.063189618 -0.21891706 0.97369522, + 0.08077158 -0.27960095 0.95671278, + 0.058077879 -0.28519392 0.95670867, + 0.070475921 -0.34589612 0.93562233, + 0.042461511 -0.3504481 0.93561924, + 0.049747817 -0.41043615 0.91053128, + 0.016607497 -0.41311193 0.91052878, + 0.018968098 -0.47170395 0.88155288, + -0.018976295 -0.47170389 0.88155276, + -0.063644893 -0.52488095 0.84879291, + -0.070199989 -0.57884288 0.81241184, + -0.11651602 -0.57131505 0.8124181, + -0.12689705 -0.62212926 0.77256233, + -0.17648709 -0.60990632 0.77257138, + -0.19016707 -0.65709722 0.72942424, + -0.24238606 -0.63966316 0.72943819, + -0.25753891 -0.67958277 0.68690675, + -0.207001 -0.70606399 0.67721802, + -0.21641007 -0.73810524 0.63903624, + -0.21676797 -0.73799193 0.63904595, + -0.20733304 -0.70592517 0.67726117, + -0.20710707 -0.70599622 0.67725623, + -0.21514195 -0.73333883 0.64492482, + -0.21518405 -0.73332715 0.64492416, + -0.20670003 -0.70445907 0.67897904, + -0.20424289 -0.70568758 0.67844659, + -0.19015904 -0.65710521 0.72941917, + -0.12688696 -0.6221379 0.77255684, + -0.070192389 -0.57884794 0.81240886, + -0.023446999 -0.58262199 0.81240499, + 0.018976493 -0.47170782 0.88155073, + 0.049750391 -0.41043693 0.91053087, + 0.082549699 -0.40510699 0.91053498, + 0.070457608 -0.34589204 0.93562514, + 0.097983487 -0.33910796 0.93563086, + 0.080745861 -0.27959889 0.95671552, + 0.10293895 -0.27218989 0.95672154, + 0.080534101 -0.213126 0.97369999, + 0.097362064 -0.20595592 0.97370565, + 0.06983839 -0.14796399 0.98652387, + 0.081438281 -0.14187597 0.98652875, + 0.048999891 -0.08568348 0.99511677, + 0.055678915 -0.081460021 0.99512023, + 0.061980292 -0.076726891 0.99512386, + 0.055688206 -0.081455104 0.99512011, + 0.092556559 -0.13485093 0.98653352, + 0.081460908 -0.14186801 0.9865281, + 0.097359076 -0.20595695 0.97370577, + 0.124446 -0.26302999 0.95672798, + 0.10294598 -0.27218994 0.95672077, + 0.12492697 -0.33012792 0.93563277, + 0.098016687 -0.33911198 0.93562585, + 0.11483505 -0.39715117 0.9105404, + 0.082554698 -0.405108 0.91053402, + 0.094289079 -0.46256387 0.88155776, + 0.063653484 -0.52487987 0.84879285, + 0.023446597 -0.58261096 0.81241286, + -0.023463909 -0.5826112 0.81241232, + -0.025555106 -0.63444418 0.77254617, + -0.082372099 -0.67910898 0.72940099, + -0.14642799 -0.71777892 0.68069994, + -0.12366898 -0.71544492 0.68763691, + -0.13040097 -0.75432682 0.64341784, + -0.13049302 -0.75430912 0.64342004, + -0.12598699 -0.72830498 0.673572, + -0.125929 -0.728315 0.673572, + -0.13066898 -0.7556839 0.64176893, + -0.12738994 -0.75566363 0.6424517, + -0.13413793 -0.79562151 0.59075665, + -0.18693995 -0.7848888 0.59076488, + -0.19461496 -0.81705785 0.54271686, + -0.24872494 -0.80223584 0.54272789, + -0.25768611 -0.83108044 0.49285224, + -0.31259096 -0.81201488 0.49286795, + -0.322402 -0.837448 0.441291, + -0.37758282 -0.8140496 0.44130978, + -0.38778007 -0.83598214 0.38827905, + -0.45288289 -0.82667482 0.33392492, + -0.50706416 -0.79458332 0.33395112, + -0.51669186 -0.80962282 0.27846095, + -0.56960487 -0.77330083 0.27848893, + -0.57828569 -0.78503865 0.2220359, + -0.62940508 -0.74467105 0.22206803, + -0.63671321 -0.75326818 0.16487405, + -0.68561202 -0.70904201 0.164911, + -0.69114876 -0.71472174 0.10717396, + -0.73734003 -0.66696006 0.10721002, + -0.74074292 -0.66999292 0.049086992, + -0.78382391 -0.61903691 0.049127091, + -0.78476083 -0.61973089 -0.0091673378, + -0.82440084 -0.56593287 -0.0091248984, + -0.82258385 -0.56463891 -0.067369789, + -0.85847282 -0.50842088 -0.067325585, + -0.8536579 -0.50552297 -0.12535799, + -0.87752599 -0.44328299 -0.182889, + -0.9051789 -0.38369194 -0.18284298, + -0.89384401 -0.37884 -0.23984, + -0.90242398 -0.31311399 -0.295957, + -0.92133611 -0.25214604 -0.29590902, + -0.90315503 -0.247122 -0.35105801, + -0.8960557 -0.18181095 -0.40500486, + -0.90621829 -0.12156204 -0.40495816, + -0.87787712 -0.11770201 -0.46419606, + -0.87795013 -0.11718801 -0.46418807, + -0.85853529 -0.20591608 -0.46959117, + -0.85854143 -0.2058901 -0.46959123, + -0.88256115 0.064280108 -0.46578306, + -0.88256341 0.064248927 -0.46578321, + -0.86963588 0.15409799 -0.46902794, + -0.86963409 0.15410802 -0.46902806, + -0.85039687 0.24275997 -0.46678993, + -0.85039884 0.24275294 -0.46678987, + -0.7593388 -0.4588109 -0.46140787, + -0.79471785 -0.40122291 -0.45545989, + -0.7985183 -0.37671816 -0.46952319, + -0.79852533 -0.37670317 -0.46952325, + -0.82078129 -0.34770113 -0.45323515, + -0.84181613 -0.35666004 -0.40514106, + -0.81610912 -0.41205707 -0.40518507, + -0.83578801 -0.42204499 -0.35119301, + -0.80571002 -0.47693101 -0.35123801, + -0.82192898 -0.486581 -0.296094, + -0.78756332 -0.54041415 -0.29613611, + -0.8004328 -0.54929388 -0.23996595, + -0.76195347 -0.60151738 -0.24000815, + -0.7716133 -0.60919023 -0.18303105, + -0.72919095 -0.65936792 -0.18306999, + -0.73583996 -0.66542792 -0.12547998, + -0.68974483 -0.71308982 -0.12551898, + -0.69363606 -0.71715903 -0.067468308, + -0.64419317 -0.76187819 -0.067503914, + -0.6456148 -0.76360685 -0.0092840884, + -0.59315008 -0.80503809 -0.0093178106, + -0.59244221 -0.80412328 0.048969019, + -0.53741604 -0.84189612 0.048938408, + -0.53494596 -0.83807188 0.10708998, + -0.47781417 -0.8719123 0.10706404, + -0.47398517 -0.86497331 0.16480106, + -0.41513294 -0.89471388 0.16477798, + -0.35038102 -0.90992713 0.22195902, + -0.34512109 -0.89631522 0.27840707, + -0.28452283 -0.91735744 0.27839181, + -0.27922106 -0.90031022 0.33388209, + -0.21844704 -0.91695821 0.3338691, + -0.213558 -0.89648402 0.38821301, + -0.15323307 -0.90874529 0.38820314, + -0.14919892 -0.88487357 0.44129178, + -0.089803606 -0.89286214 0.44128507, + -0.087073602 -0.865771 0.492807, + -0.029049607 -0.86965519 0.49280411, + -0.028039396 -0.83946687 0.54268694, + 0.028055483 -0.83946651 0.5426867, + 0.026949095 -0.80641484 0.59073585, + 0.026934087 -0.80640966 0.59074372, + -0.026948897 -0.80640888 0.59074396, + -0.028055295 -0.8394599 0.54269695, + -0.0840538 -0.835711 0.54269898, + -0.087082379 -0.86576682 0.49281287, + -0.14466493 -0.85802257 0.49281776, + -0.14920095 -0.88487267 0.44129285, + -0.20794496 -0.87293279 0.44130188, + -0.21356697 -0.89647889 0.38821995, + -0.27294704 -0.88021314 0.38823307, + -0.27919888 -0.90032458 0.33386186, + -0.3386749 -0.87967277 0.3338789, + -0.34510502 -0.89632612 0.27839202, + -0.40421006 -0.8712641 0.27841204, + -0.46852818 -0.85510027 0.22200207, + -0.47396994 -0.86498487 0.16478398, + -0.53065616 -0.83140928 0.16481106, + -0.53494096 -0.83807588 0.10708398, + -0.58973378 -0.80046272 0.10711396, + -0.59245604 -0.80411214 0.048985906, + -0.6448282 -0.7627542 0.049018111, + -0.64559895 -0.7636199 -0.0093033193, + -0.69515204 -0.71880305 -0.009267061, + -0.69361997 -0.71717292 -0.067487195, + -0.73999017 -0.66922718 -0.067449912, + -0.73583895 -0.66542894 -0.12548098, + -0.77864319 -0.6148001 -0.12544203, + -0.77160591 -0.60919696 -0.18303898, + -0.81058288 -0.55629796 -0.18299699, + -0.80043787 -0.54928893 -0.23995997, + -0.83536601 -0.49457401 -0.239917, + -0.82193512 -0.48657507 -0.29608703, + -0.85260803 -0.43060201 -0.29604301, + -0.83577883 -0.4220539 -0.35120392, + -0.86211598 -0.36529899 -0.35115901, + -0.84182388 -0.35665098 -0.40513295, + -0.86379087 -0.29961497 -0.40508795, + -0.8373552 -0.29039007 -0.46315211, + -0.83481342 -0.29352015 -0.4657602, + -0.8348189 -0.29350498 -0.46575993, + -0.83612984 -0.29398194 -0.46309987, + -0.85926628 -0.23500109 -0.45435214, + -0.88189626 -0.24124005 -0.40504608, + -0.86378568 -0.29962188 -0.40509385, + -0.8846131 -0.30689704 -0.35110402, + -0.86212188 -0.36529198 -0.35115197, + -0.87947875 -0.37269592 -0.29599795, + -0.85260713 -0.43060306 -0.29604402, + -0.86653715 -0.43768612 -0.23988406, + -0.83535683 -0.49458387 -0.23992895, + -0.84594911 -0.50090408 -0.18293501, + -0.81059718 -0.55628312 -0.18297905, + -0.81798714 -0.56140304 -0.12539402, + -0.77864814 -0.61479509 -0.12543601, + -0.78303915 -0.61830914 -0.067405716, + -0.73999274 -0.66922474 -0.067445979, + -0.74162674 -0.67074978 -0.0091918865, + -0.69518125 -0.71877521 -0.0092299338, + -0.69435018 -0.71796221 0.049073011, + -0.64484376 -0.76273972 0.049037583, + -0.64188182 -0.75928283 0.10713198, + -0.58972108 -0.80047411 0.10710002, + -0.58499688 -0.79410779 0.16483796, + -0.53065306 -0.83141214 0.16480702, + -0.52456278 -0.82191759 0.22200289, + -0.46850413 -0.85512018 0.22197606, + -0.46147019 -0.84232932 0.27843609, + -0.4042111 -0.87126321 0.27841306, + -0.39667714 -0.85507232 0.33391413, + -0.3386929 -0.87965977 0.33389491, + -0.33110914 -0.86001343 0.38825718, + -0.27295503 -0.88020712 0.38824105, + -0.26577303 -0.85709411 0.44131005, + -0.20793788 -0.87293744 0.44129574, + -0.201617 -0.84645498 0.49281299, + -0.14464499 -0.8580339 0.49280393, + -0.13961405 -0.82824832 0.54269016, + -0.084030107 -0.8357231 0.54268408, + -0.08071582 -0.8028152 0.59073913, + -0.0269343 -0.80641598 0.59073502, + -0.025737191 -0.77063173 0.63676077, + 0.025737191 -0.77063173 0.63676077, + 0.043568812 -0.76244116 0.64558917, + 0.04364989 -0.76243579 0.64558983, + 0.042175315 -0.73671925 0.67488223, + 0.029632889 -0.73617077 0.67614675, + 0.027510613 -0.6835283 0.72940534, + -0.029632889 -0.73617077 0.67614675, + -0.027511396 -0.68354696 0.72938794, + 0.027543392 -0.68354684 0.72938681, + 0.025561703 -0.63444406 0.77254611, + 0.070191786 -0.57884389 0.81241184, + 0.11651102 -0.57131606 0.8124181, + 0.10563201 -0.51805604 0.84879911, + 0.14690903 -0.50788212 0.84880716, + 0.13114397 -0.45348087 0.88156474, + 0.16714996 -0.44145989 0.88157475, + 0.14634506 -0.38662115 0.91055328, + 0.17690901 -0.37359902 0.91056412, + 0.15099797 -0.31900591 0.93564677, + 0.17612405 -0.30582005 0.93565726, + 0.1451389 -0.25216684 0.9567374, + 0.16489308 -0.23967612 0.95674747, + 0.12900198 -0.18768695 0.97372079, + 0.14362292 -0.1767009 0.97372955, + 0.10302404 -0.12698105 0.98654038, + 0.11285503 -0.11827203 0.98654723, + 0.067902297 -0.071481101 0.99512798, + 0.073370062 -0.065788373 0.99513251, + 0.02449809 -0.022497993 0.99944663, + 0.02616231 -0.020459708 0.99944836, + 0.0276617 -0.0182875 0.99945003, + 0.028980397 -0.016003499 0.99945188, + 0.030108593 -0.013625797 0.99945378, + 0.031044593 -0.011157798 0.99945575, + 0.031777192 -0.0086284382 0.99945778, + 0.032304194 -0.0060465084 0.99945974, + 0.032622095 -0.0034290696 0.99946189, + 0.032728199 -0.000795856 0.99946398, + 0.032622103 0.0018373502 0.99946612, + 0.032304205 0.0044547906 0.99946815, + 0.031777207 0.0070367218 0.99947023, + 0.031044608 0.0095660416 0.99947226, + 0.030108608 0.012034003 0.99947423, + 0.028980404 0.014411702 0.99947613, + 0.027661696 0.016695699 0.99947786, + 0.026162291 0.018867893 0.99947965, + 0.024498105 0.020906206 0.99948126, + 0.022674695 0.022804594 0.99948275, + 0.020695006 0.024558406 0.99948424, + 0.018591309 0.026139213 0.99948549, + 0.016369492 0.027544187 0.99948651, + 0.014025893 0.028774187 0.99948752, + 0.011606503 0.029805012 0.99948835, + 0.0091086999 0.0306389 0.99948901, + 0.0065397569 0.031272084 0.99948955, + 0.0039469791 0.031693492 0.99948978, + 0.00131919 0.031905599 0.99949002, + -0.00131919 0.031905599 0.99949002, + -0.0039469791 0.031693492 0.99948978, + -0.0065397569 0.031272084 0.99948955, + -0.0091086999 0.0306389 0.99948901, + -0.011606503 0.029805012 0.99948835, + -0.014025893 0.028774187 0.99948752, + -0.016369492 0.027544187 0.99948651, + -0.018591309 0.026139213 0.99948549, + -0.020695006 0.024558406 0.99948424, + -0.022674695 0.022804594 0.99948275, + -0.024498105 0.020906206 0.99948126, + -0.026162291 0.018867893 0.99947965, + -0.027661696 0.016695699 0.99947786, + -0.028980404 0.014411702 0.99947613, + -0.030108608 0.012034003 0.99947423, + -0.031044608 0.0095660416 0.99947226, + -0.031777207 0.0070367218 0.99947023, + -0.032304205 0.0044547906 0.99946815, + -0.032622103 0.0018373502 0.99946612, + -0.032728199 -0.000795856 0.99946398, + -0.032622095 -0.0034290696 0.99946189, + -0.032304194 -0.0060465084 0.99945974, + -0.031777192 -0.0086284382 0.99945778, + -0.031044593 -0.011157798 0.99945575, + -0.030108593 -0.013625797 0.99945378, + -0.028980397 -0.016003499 0.99945188, + -0.0276617 -0.0182875 0.99945003, + -0.02616231 -0.020459708 0.99944836, + -0.02449809 -0.022497993 0.99944663, + -0.022674706 -0.024396406 0.99944526, + -0.020694995 -0.026150195 0.99944377, + -0.01859129 -0.027730986 0.99944252, + -0.016369505 -0.029136011 0.99944139, + -0.014025906 -0.030366015 0.99944049, + -0.011606496 -0.031396788 0.99943966, + -0.0091086999 -0.032230701 0.999439, + -0.0065397564 -0.032863881 0.99943841, + -0.0039469805 -0.033285305 0.99943811, + -0.00131919 -0.033497401 0.99943799, + 0.00131919 -0.033497401 0.99943799, + 0.0039469805 -0.033285305 0.99943811, + 0.0065397564 -0.032863881 0.99943841, + 0.0091086999 -0.032230701 0.999439, + 0.011606496 -0.031396788 0.99943966, + 0.014025906 -0.030366015 0.99944049, + 0.016369505 -0.029136011 0.99944139, + 0.01859129 -0.027730986 0.99944252, + 0.020694995 -0.026150195 0.99944377, + 0.022674706 -0.024396406 0.99944526, + 0.067909889 -0.071475394 0.99512786, + 0.061986886 -0.076722682 0.99512374, + 0.10302205 -0.12698206 0.9865405, + 0.092540219 -0.13485803 0.98653424, + 0.12901002 -0.18768503 0.97372013, + 0.14515908 -0.25216311 0.95673549, + 0.12445799 -0.26302797 0.95672691, + 0.15102907 -0.31900412 0.93564236, + 0.12492295 -0.33012688 0.93563366, + 0.146357 -0.38662201 0.91055101, + 0.11482298 -0.39714894 0.91054291, + 0.13114604 -0.45348114 0.88156432, + 0.094290614 -0.46256506 0.88155711, + 0.10562402 -0.51805413 0.8488012, + 0.063644297 -0.524876 0.84879601, + 0.070200607 -0.57884806 0.81240809, + 0.023464296 -0.58261997 0.81240588, + 0.025554908 -0.63443923 0.77255028, + -0.025561605 -0.63443905 0.77255011, + -0.027542608 -0.68352616 0.72940618, + -0.082384594 -0.67909896 0.72940892, + -0.088092655 -0.72607267 0.6819517, + -0.12223297 -0.70676184 0.6968118, + -0.13070692 -0.75567853 0.64176762, + -0.077355698 -0.769283 0.63420802, + -0.043543611 -0.76243317 0.6456002, + -0.042073075 -0.73672658 0.67488056, + -0.042175315 -0.73671925 0.67488223, + -0.04364989 -0.76243579 0.64558983, + -0.043568812 -0.76244116 0.64558917, + -0.04167651 -0.72937816 0.68284017, + 0.04167651 -0.72937816 0.68284017, + 0.52062505 -0.61627805 0.59089005, + 0.44273987 -0.80820984 0.38830191, + 0.36611879 -0.78932154 0.49287769, + -0.93642378 0.00027939194 -0.35087091, + -0.9708879 0.00019073697 -0.23953398, + -0.7916792 -0.54367411 0.27868006, + -0.52062505 -0.61627805 0.59089005, + -0.98319566 0.00014536495 -0.18255495, + -0.99216586 9.9477984e-005 -0.12492798, + -0.98621213 -0.00013177401 0.16548601, + -0.99418074 -8.577948e-005 0.10772498, + -0.91716921 0.31866109 -0.23928206, + -0.99775845 5.3286625e-005 -0.06691923, + 0.18156205 -0.13720903 0.97376025, + 0.23207791 -0.17515694 0.95679665, + 0.098018624 -0.00079244818 0.99518424, + 0.22710994 -0.00077547482 0.97386879, + 0.29029498 -0.00076199189 0.9569369, + 0.51270211 -0.12705703 0.84911317, + 0.89702588 -0.00035193897 0.44197795, + 0.86974287 -0.00039296894 0.49350494, + 0.83950371 -0.00043266284 0.5433538, + 0.58244789 -0.0006472728 0.81286782, + 0.63434279 -0.00061556778 0.77305168, + 0.18156207 0.13565904 0.97397739, + 0.23207809 0.17363305 0.95707434, + 0.51270175 0.12570494 0.84931457, + 0.11356195 0.19590291 0.97402555, + 0.96026111 -0.00022224503 0.27910304, + 0.9708879 0.00019073697 -0.23953398, + 0.79167885 0.54322988 0.27954593, + 0.91716921 0.31866109 -0.23928206, + 0.93642378 0.00027939194 -0.35087091, + 0.98319566 0.00014536495 -0.18255495, + 0.520625 0.615336 0.59187102, + 0.99775845 5.3286625e-005 -0.06691923, + 0.99216586 9.9477984e-005 -0.12492798, + 0.99418074 -8.577948e-005 0.10772498, + 0.91716921 -0.31827909 -0.23979005, + 0.98621213 -0.00013177401 0.16548601, + -0.29029498 -0.00076199189 0.9569369, + -0.51270175 0.12570494 0.84931457, + -0.41271293 -0.00072530296 0.9108609, + -0.52805191 -0.00067621295 0.84921187, + -0.58244789 -0.0006472728 0.81286782, + -0.63434279 -0.00061556778 0.77305168, + -0.18156205 -0.13720903 0.97376025, + -0.51270211 -0.12705703 0.84911317, + -0.79167885 0.54322988 0.27954593, + -0.520625 0.615336 0.59187102, + -0.22710994 -0.00077547482 0.97386879, + -0.098018624 -0.00079244818 0.99518424, + -0.36611891 0.78853583 0.49413389, + -0.23207809 0.17363305 0.95707434, + -0.18156207 0.13565904 0.97397739, + -0.11356195 0.19590291 0.97402555, + 0.7916792 -0.54367411 0.27868006, + 0.52805191 -0.00067621295 0.84921187, + 0.41271293 -0.00072530296 0.9108609, + -0.96026111 -0.00022224503 0.27910304, + -0.89702588 -0.00035193897 0.44197795, + -0.86974287 -0.00039296894 0.49350494, + -0.83950371 -0.00043266284 0.5433538, + -0.23207791 -0.17515694 0.95679665, + -0.11356195 -0.19745292 0.9737125, + -0.44273987 -0.80820984 0.38830191, + -0.91716921 -0.31827909 -0.23979005, + -0.4103682 -0.88449043 0.22197911, + 0.11356195 -0.19745292 0.9737125, + -0.96091723 0.27683607 0.00022044005, + -0.98587137 0.16750406 0.00013338105, + -0.99842674 0.056071784 4.464899e-005, + -0.16754 0.985865 0.00078502699, + -0.27681008 0.96092439 0.00076516828, + -0.27681008 -0.96092439 -0.00076516828, + -0.38268194 -0.92387986 -0.00073566986, + -0.48372883 -0.87521768 -0.00069692079, + -0.6663568 -0.74563283 -0.00059373386, + -0.57866567 -0.81556457 -0.00064941973, + -0.74564081 -0.6663478 -0.0005306009, + -0.99842674 -0.056071784 -4.464899e-005, + -0.98587137 -0.16750406 -0.00013338105, + 0 0.00079628272 -0.99999964, + -0.96091723 -0.27683607 -0.00022044005, + -0.91438031 0.0003223801 -0.40485615, + -0.95528078 0.00023546095 -0.29569995, + -0.81555885 0.5786739 0.00046078887, + -0.87522489 0.48371595 0.00038517494, + -0.74564081 0.6663478 0.0005306009, + -0.97489321 -0.00017731104 0.22267306, + -0.92387635 0.38269114 0.00030473011, + -0.81555885 -0.5786739 -0.00046078887, + 0.35227892 -0.00074523682 0.93589479, + -0.056054726 0.99842745 0.00079503143, + 0.056054726 0.99842745 0.00079503143, + 0.16754 0.985865 0.00078502699, + 0.27681008 0.96092439 0.00076516828, + 0.92126226 -0.00030970809 0.38894209, + 0.94235849 -0.00026644013 0.33460516, + 0.6663568 -0.74563283 -0.00059373386, + 0.74564081 -0.6663478 -0.0005306009, + 0.57866567 -0.81556457 -0.00064941973, + 0.48372883 -0.87521768 -0.00069692079, + 0.38268194 -0.92387986 -0.00073566986, + 0.8063857 -0.00047091281 0.59138978, + 0.68350685 -0.00058124191 0.72994381, + 0.97489321 -0.00017731104 0.22267306, + 0.81555885 -0.5786739 -0.00046078887, + 0.87522489 -0.48371595 -0.00038517494, + 0.95528078 0.00023546095 -0.29569995, + 0.99842674 -0.056071784 -4.464899e-005, + 0.99842674 0.056071784 4.464899e-005, + 0.98587137 0.16750406 0.00013338105, + 0.96091723 0.27683607 0.00022044005, + 0.92387635 0.38269114 0.00030473011, + 0.87522489 0.48371595 0.00038517494, + 0.81555885 0.5786739 0.00046078887, + 0.74564081 0.6663478 0.0005306009, + 0.6663568 0.74563283 0.00059373386, + 0.57866567 0.81556457 0.00064941973, + 0.48372883 0.87521768 0.00069692079, + 0.38268194 0.92387986 0.00073566986, + 0.91438031 0.0003223801 -0.40485615, + 0.98587137 -0.16750406 -0.00013338105, + 0.96091723 -0.27683607 -0.00022044005, + 0.92387635 -0.38269114 -0.00030473011, + -0.8063857 -0.00047091281 0.59138978, + -0.35227892 -0.00074523682 0.93589479, + -0.47138983 -0.00070226076 0.88192469, + -0.68350685 -0.00058124191 0.72994381, + 0 0.99999964 0.00079628272, + 0 0.73833698 0.67443198, + 0 0.7624281 0.64707303, + 0.27681008 -0.96092439 -0.00076516828, + 0 -0.88258559 -0.47015175, + 0.47138983 -0.00070226076 0.88192469, + -0.16754 -0.985865 -0.00078502699, + -0.056054726 -0.99842745 -0.00079503143, + 0.056054726 -0.99842745 -0.00079503143, + 0.16754 -0.985865 -0.00078502699, + -0.38268194 0.92387986 0.00073566986, + -0.48372883 0.87521768 0.00069692079, + -0.57866567 0.81556457 0.00064941973, + -0.6663568 0.74563283 0.00059373386, + -0.94235849 -0.00026644013 0.33460516, + -0.92126226 -0.00030970809 0.38894209, + -0.92387635 -0.38269114 -0.00030473011, + -0.87522489 -0.48371595 -0.00038517494, + 0.20208396 -0.42658591 0.88158178, + 0.07644666 -0.63033569 0.77254963, + -0.22261006 -0.93432623 0.27835107, + -0.16500995 -0.97824365 -0.12574196, + 0.22261006 -0.93432623 0.27835107, + 0.49797612 -0.67628217 0.54282814, + 0.41036779 -0.88449061 0.2219789, + -0.93613523 -0.19004504 -0.29586107, + -0.36611879 -0.78932154 0.49287769, + -0.88552576 -0.44737187 -0.12530997, + -0.91766214 -0.18624601 -0.35101104, + -0.99772936 -0.066784821 -0.0087218527, + -0.99876797 -3.95143e-005 0.0496234, + -0.99772936 0.066798225 -0.0086154826, + -0.99996245 6.9020134e-006 -0.0086677941, + -0.42090386 -0.90705669 -0.0093894759, + 0.13672297 -0.67027581 0.7294088, + 0.16290702 -0.0007856451 0.98664111, + 0.46986118 -0.038637914 0.88189429, + 0.46986088 0.037234392 0.88195479, + 0.34203696 0.083560996 0.93596387, + 0.58055896 0.046227798 0.81290489, + 0.24535903 0.15439202 0.95705914, + 0.44630894 0.28154096 0.84943688, + 0.99996239 6.9020061e-006 -0.0086677745, + 0.99772936 0.066798225 -0.0086151427, + 0.91766191 -0.18624699 -0.35101098, + 0.91766202 0.18680499 -0.350714, + 0.88552624 0.44757012 -0.12459703, + 0.93613523 0.19051604 -0.29555807, + 0.36611891 0.78853583 0.49413389, + 0.99876809 -3.9514205e-005 0.049623307, + 0.056822326 0.4672482 0.88229841, + 0.13672297 0.66911381 0.73047483, + 0.076446891 0.62910396 0.77355289, + -0.056822818 0.46724817 0.88229829, + -0.13672297 0.66911381 0.73047483, + -0.20208301 0.42518201 0.88226002, + -0.388293 0.56192303 0.73039103, + -0.46986094 0.037233397 0.88195491, + -0.34203714 -0.085052334 0.9358294, + -0.46986118 -0.038637914 0.88189429, + -0.5805583 0.046227824 0.81290543, + -0.245359 -0.15591601 0.95681202, + -0.49797577 0.67541671 0.54390478, + -0.34203696 0.083561093 0.93596387, + -0.16290702 -0.0007856451 0.98664111, + 0.19461496 0.81619281 0.5440169, + -0.07644669 0.62910396 0.77355289, + 0.16148394 -0.95717663 -0.24028291, + 0.42090386 -0.90705669 -0.009389746, + -0.73583996 0.66562694 -0.12441999, + -0.44630912 -0.28289405 0.84898716, + -0.47481081 -0.42126784 0.77271467, + -0.056822792 -0.46865293 0.88155288, + -0.021257395 -0.52830291 0.84878981, + -0.13672297 -0.67027581 0.7294088, + -0.076446861 -0.63033569 0.77254963, + 0.021257395 -0.52830291 0.84878981, + 0.056822792 -0.46865293 0.88155288, + 0.10302295 0.12540895 0.98674154, + 0.16500996 -0.97824377 -0.12574098, + -0.10302305 -0.12698106 0.9865405 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 5, 6, 3, -1, 6, 5, 7, -1, + 7, 8, 6, -1, 8, 7, 9, -1, + 9, 10, 8, -1, 10, 9, 11, -1, + 11, 12, 10, -1, 12, 11, 13, -1, + 13, 14, 12, -1, 14, 13, 15, -1, + 15, 16, 14, -1, 16, 15, 17, -1, + 17, 18, 16, -1, 18, 17, 19, -1, + 19, 20, 18, -1, 20, 19, 21, -1, + 21, 22, 20, -1, 22, 21, 23, -1, + 23, 24, 22, -1, 24, 23, 25, -1, + 25, 26, 24, -1, 26, 25, 27, -1, + 27, 28, 26, -1, 28, 27, 29, -1, + 29, 30, 28, -1, 30, 29, 31, -1, + 31, 32, 30, -1, 32, 31, 33, -1, + 33, 34, 32, -1, 34, 33, 35, -1, + 35, 36, 34, -1, 36, 35, 37, -1, + 37, 38, 36, -1, 38, 37, 39, -1, + 39, 40, 38, -1, 40, 39, 1, -1, + 1, 0, 40, -1, 41, 42, 43, -1, + 44, 43, 42, -1, 44, 45, 43, -1, + 46, 47, 48, -1, 48, 49, 46, -1, + 50, 51, 52, -1, 51, 50, 53, -1, + 53, 54, 51, -1, 54, 53, 55, -1, + 55, 56, 54, -1, 56, 55, 57, -1, + 57, 58, 56, -1, 58, 57, 59, -1, + 59, 60, 58, -1, 60, 59, 61, -1, + 61, 62, 60, -1, 62, 61, 63, -1, + 64, 63, 65, -1, 65, 66, 64, -1, + 66, 65, 67, -1, 67, 68, 66, -1, + 68, 67, 69, -1, 69, 70, 68, -1, + 71, 72, 70, -1, 73, 74, 75, -1, + 74, 73, 76, -1, 77, 76, 73, -1, + 77, 78, 76, -1, 79, 80, 81, -1, + 81, 82, 79, -1, 82, 81, 83, -1, + 83, 84, 82, -1, 84, 83, 85, -1, + 85, 86, 84, -1, 86, 85, 87, -1, + 87, 88, 86, -1, 88, 87, 89, -1, + 89, 90, 88, -1, 90, 89, 91, -1, + 91, 92, 90, -1, 92, 91, 93, -1, + 93, 94, 92, -1, 94, 93, 95, -1, + 95, 96, 94, -1, 96, 95, 97, -1, + 97, 98, 96, -1, 98, 97, 99, -1, + 99, 100, 98, -1, 100, 99, 101, -1, + 101, 102, 100, -1, 102, 101, 103, -1, + 104, 103, 105, -1, 105, 106, 104, -1, + 106, 105, 107, -1, 107, 108, 106, -1, + 108, 107, 109, -1, 109, 110, 108, -1, + 110, 109, 111, -1, 111, 112, 110, -1, + 112, 111, 113, -1, 113, 78, 112, -1, + 78, 113, 114, -1, 114, 76, 78, -1, + 76, 114, 115, -1, 116, 117, 118, -1, + 116, 118, 119, -1, 116, 119, 120, -1, + 120, 117, 116, -1, 120, 121, 117, -1, + 120, 119, 121, -1, 122, 121, 119, -1, + 119, 123, 122, -1, 123, 119, 124, -1, + 124, 125, 123, -1, 125, 124, 126, -1, + 126, 127, 125, -1, 127, 126, 128, -1, + 128, 129, 127, -1, 129, 128, 130, -1, + 130, 131, 129, -1, 131, 130, 132, -1, + 132, 133, 131, -1, 133, 132, 134, -1, + 134, 135, 133, -1, 135, 134, 136, -1, + 136, 137, 135, -1, 137, 136, 138, -1, + 138, 139, 137, -1, 139, 138, 140, -1, + 140, 141, 139, -1, 141, 140, 142, -1, + 142, 143, 141, -1, 143, 142, 144, -1, + 144, 145, 143, -1, 145, 144, 146, -1, + 146, 147, 145, -1, 147, 146, 148, -1, + 148, 149, 147, -1, 149, 148, 150, -1, + 150, 151, 149, -1, 151, 150, 152, -1, + 152, 153, 151, -1, 153, 152, 154, -1, + 154, 155, 153, -1, 155, 154, 156, -1, + 156, 157, 155, -1, 157, 156, 158, -1, + 158, 159, 157, -1, 159, 158, 160, -1, + 160, 161, 159, -1, 162, 159, 161, -1, + 162, 163, 159, -1, 159, 163, 164, -1, + 164, 157, 159, -1, 157, 164, 165, -1, + 165, 155, 157, -1, 155, 165, 166, -1, + 166, 153, 155, -1, 153, 166, 167, -1, + 167, 151, 153, -1, 151, 167, 168, -1, + 168, 149, 151, -1, 149, 168, 169, -1, + 169, 147, 149, -1, 147, 169, 170, -1, + 170, 145, 147, -1, 145, 170, 171, -1, + 171, 143, 145, -1, 143, 171, 172, -1, + 172, 141, 143, -1, 141, 172, 173, -1, + 173, 139, 141, -1, 139, 173, 174, -1, + 174, 137, 139, -1, 137, 174, 175, -1, + 175, 135, 137, -1, 135, 175, 176, -1, + 176, 133, 135, -1, 133, 176, 177, -1, + 177, 131, 133, -1, 131, 177, 178, -1, + 178, 129, 131, -1, 129, 178, 179, -1, + 179, 127, 129, -1, 127, 179, 180, -1, + 180, 125, 127, -1, 125, 180, 181, -1, + 181, 123, 125, -1, 123, 181, 182, -1, + 182, 122, 123, -1, 122, 183, 184, -1, + 122, 182, 183, -1, 185, 186, 187, -1, + 187, 186, 188, -1, 188, 189, 187, -1, + 190, 191, 192, -1, 193, 192, 191, -1, + 193, 194, 192, -1, 194, 193, 195, -1, + 195, 196, 194, -1, 196, 195, 197, -1, + 197, 198, 196, -1, 198, 197, 199, -1, + 199, 200, 198, -1, 200, 199, 201, -1, + 201, 202, 200, -1, 202, 201, 203, -1, + 203, 204, 202, -1, 205, 206, 204, -1, + 206, 205, 207, -1, 207, 208, 206, -1, + 208, 207, 209, -1, 209, 210, 208, -1, + 210, 209, 211, -1, 211, 212, 210, -1, + 212, 211, 213, -1, 213, 214, 212, -1, + 214, 213, 215, -1, 215, 216, 214, -1, + 216, 215, 217, -1, 218, 217, 219, -1, + 219, 220, 218, -1, 220, 219, 221, -1, + 221, 222, 220, -1, 222, 221, 223, -1, + 223, 224, 222, -1, 224, 223, 225, -1, + 225, 226, 224, -1, 226, 225, 227, -1, + 227, 189, 226, -1, 228, 187, 189, -1, + 229, 230, 231, -1, 231, 232, 229, -1, + 228, 233, 232, -1, 227, 234, 233, -1, + 234, 227, 225, -1, 225, 235, 234, -1, + 235, 225, 223, -1, 236, 223, 221, -1, + 221, 237, 236, -1, 237, 221, 219, -1, + 219, 238, 237, -1, 238, 219, 217, -1, + 217, 239, 238, -1, 239, 217, 215, -1, + 215, 240, 239, -1, 240, 215, 213, -1, + 213, 241, 240, -1, 241, 213, 211, -1, + 211, 242, 241, -1, 242, 211, 209, -1, + 209, 243, 242, -1, 243, 209, 207, -1, + 207, 244, 243, -1, 244, 207, 205, -1, + 205, 245, 244, -1, 203, 246, 245, -1, + 246, 203, 201, -1, 201, 247, 246, -1, + 247, 201, 199, -1, 199, 248, 247, -1, + 248, 199, 197, -1, 197, 249, 248, -1, + 249, 197, 195, -1, 195, 250, 249, -1, + 250, 195, 193, -1, 250, 193, 251, -1, + 251, 252, 250, -1, 250, 252, 253, -1, + 253, 249, 250, -1, 249, 253, 254, -1, + 254, 248, 249, -1, 248, 254, 255, -1, + 255, 247, 248, -1, 247, 255, 256, -1, + 256, 246, 247, -1, 246, 256, 257, -1, + 257, 245, 246, -1, 245, 257, 258, -1, + 258, 244, 245, -1, 244, 258, 259, -1, + 259, 243, 244, -1, 243, 259, 260, -1, + 260, 242, 243, -1, 242, 260, 261, -1, + 261, 241, 242, -1, 241, 261, 262, -1, + 262, 240, 241, -1, 240, 262, 263, -1, + 263, 239, 240, -1, 239, 263, 264, -1, + 264, 238, 239, -1, 238, 264, 265, -1, + 265, 237, 238, -1, 237, 265, 266, -1, + 266, 236, 237, -1, 236, 266, 267, -1, + 235, 267, 268, -1, 268, 234, 235, -1, + 234, 268, 269, -1, 269, 233, 234, -1, + 233, 269, 270, -1, 270, 232, 233, -1, + 232, 270, 271, -1, 271, 229, 232, -1, + 229, 272, 273, -1, 229, 271, 272, -1, + 274, 272, 275, -1, 276, 275, 277, -1, + 277, 275, 272, -1, 272, 278, 277, -1, + 278, 272, 271, -1, 271, 279, 278, -1, + 279, 271, 270, -1, 270, 280, 279, -1, + 280, 270, 269, -1, 269, 281, 280, -1, + 281, 269, 268, -1, 268, 282, 281, -1, + 282, 268, 267, -1, 267, 283, 282, -1, + 283, 267, 266, -1, 266, 284, 283, -1, + 284, 266, 265, -1, 285, 265, 264, -1, + 264, 286, 285, -1, 286, 264, 263, -1, + 263, 287, 286, -1, 287, 263, 262, -1, + 262, 288, 287, -1, 288, 262, 261, -1, + 261, 289, 288, -1, 289, 261, 260, -1, + 260, 290, 289, -1, 290, 260, 259, -1, + 259, 291, 290, -1, 291, 259, 258, -1, + 258, 292, 291, -1, 292, 258, 257, -1, + 257, 293, 292, -1, 293, 257, 256, -1, + 256, 294, 293, -1, 294, 256, 255, -1, + 255, 295, 294, -1, 295, 255, 254, -1, + 254, 296, 295, -1, 296, 254, 253, -1, + 296, 253, 297, -1, 298, 296, 297, -1, + 298, 299, 296, -1, 300, 297, 253, -1, + 300, 253, 252, -1, 301, 251, 193, -1, + 301, 193, 191, -1, 190, 192, 302, -1, + 303, 302, 192, -1, 192, 304, 303, -1, + 304, 192, 194, -1, 194, 305, 304, -1, + 305, 194, 196, -1, 196, 306, 305, -1, + 306, 196, 198, -1, 198, 307, 306, -1, + 307, 198, 200, -1, 200, 308, 307, -1, + 308, 200, 202, -1, 202, 309, 308, -1, + 309, 202, 204, -1, 204, 310, 309, -1, + 310, 204, 206, -1, 206, 311, 310, -1, + 311, 206, 208, -1, 208, 312, 311, -1, + 312, 208, 210, -1, 210, 313, 312, -1, + 313, 210, 212, -1, 212, 314, 313, -1, + 314, 212, 214, -1, 214, 315, 314, -1, + 315, 214, 216, -1, 216, 316, 315, -1, + 218, 317, 316, -1, 317, 218, 220, -1, + 220, 318, 317, -1, 318, 220, 222, -1, + 222, 319, 318, -1, 319, 222, 224, -1, + 320, 224, 226, -1, 226, 321, 320, -1, + 321, 226, 189, -1, 189, 188, 321, -1, + 322, 323, 324, -1, 322, 183, 323, -1, + 188, 323, 183, -1, 183, 321, 188, -1, + 321, 183, 182, -1, 182, 320, 321, -1, + 320, 182, 181, -1, 319, 181, 180, -1, + 180, 318, 319, -1, 318, 180, 179, -1, + 179, 317, 318, -1, 317, 179, 178, -1, + 178, 316, 317, -1, 316, 178, 177, -1, + 177, 315, 316, -1, 315, 177, 176, -1, + 176, 314, 315, -1, 314, 176, 175, -1, + 175, 313, 314, -1, 313, 175, 174, -1, + 174, 312, 313, -1, 312, 174, 173, -1, + 173, 311, 312, -1, 311, 173, 172, -1, + 172, 310, 311, -1, 310, 172, 171, -1, + 171, 309, 310, -1, 309, 171, 170, -1, + 170, 308, 309, -1, 308, 170, 169, -1, + 169, 307, 308, -1, 307, 169, 168, -1, + 168, 306, 307, -1, 306, 168, 167, -1, + 167, 305, 306, -1, 305, 167, 166, -1, + 166, 304, 305, -1, 304, 166, 165, -1, + 165, 303, 304, -1, 303, 165, 164, -1, + 303, 164, 325, -1, 325, 302, 303, -1, + 326, 325, 164, -1, 326, 164, 163, -1, + 327, 328, 329, -1, 330, 331, 332, -1, + 331, 333, 332, -1, 331, 334, 333, -1, + 331, 330, 334, -1, 330, 335, 334, -1, + 330, 332, 335, -1, 336, 335, 332, -1, + 332, 337, 336, -1, 337, 332, 338, -1, + 338, 339, 337, -1, 339, 338, 340, -1, + 340, 341, 339, -1, 341, 340, 342, -1, + 342, 343, 341, -1, 343, 342, 344, -1, + 344, 345, 343, -1, 345, 344, 346, -1, + 346, 347, 345, -1, 347, 346, 348, -1, + 348, 349, 347, -1, 349, 348, 350, -1, + 350, 351, 349, -1, 351, 350, 352, -1, + 352, 353, 351, -1, 353, 352, 354, -1, + 354, 355, 353, -1, 355, 354, 356, -1, + 356, 357, 355, -1, 357, 356, 358, -1, + 358, 359, 357, -1, 359, 358, 360, -1, + 360, 361, 359, -1, 361, 360, 362, -1, + 362, 363, 361, -1, 363, 362, 364, -1, + 364, 365, 363, -1, 365, 364, 366, -1, + 366, 367, 365, -1, 367, 366, 368, -1, + 368, 369, 367, -1, 369, 368, 370, -1, + 370, 371, 369, -1, 372, 373, 374, -1, + 371, 374, 375, -1, 375, 369, 371, -1, + 369, 375, 376, -1, 376, 367, 369, -1, + 377, 365, 367, -1, 365, 377, 378, -1, + 378, 363, 365, -1, 363, 378, 379, -1, + 379, 361, 363, -1, 361, 379, 380, -1, + 380, 359, 361, -1, 359, 380, 381, -1, + 381, 357, 359, -1, 357, 381, 382, -1, + 382, 355, 357, -1, 355, 382, 383, -1, + 383, 353, 355, -1, 353, 383, 384, -1, + 384, 351, 353, -1, 351, 384, 385, -1, + 385, 349, 351, -1, 349, 385, 386, -1, + 386, 347, 349, -1, 347, 386, 387, -1, + 387, 345, 347, -1, 345, 387, 388, -1, + 388, 343, 345, -1, 343, 388, 389, -1, + 389, 341, 343, -1, 341, 389, 390, -1, + 390, 339, 341, -1, 391, 337, 339, -1, + 337, 391, 392, -1, 392, 336, 337, -1, + 336, 393, 394, -1, 336, 392, 393, -1, + 395, 396, 397, -1, 395, 393, 396, -1, + 398, 396, 393, -1, 393, 399, 398, -1, + 399, 393, 392, -1, 392, 400, 399, -1, + 400, 392, 391, -1, 391, 401, 400, -1, + 390, 402, 401, -1, 402, 390, 389, -1, + 403, 389, 388, -1, 388, 404, 403, -1, + 404, 388, 387, -1, 387, 405, 404, -1, + 405, 387, 386, -1, 386, 406, 405, -1, + 406, 386, 385, -1, 385, 407, 406, -1, + 407, 385, 384, -1, 384, 408, 407, -1, + 408, 384, 383, -1, 383, 409, 408, -1, + 409, 383, 382, -1, 382, 410, 409, -1, + 410, 382, 381, -1, 381, 411, 410, -1, + 411, 381, 380, -1, 412, 380, 379, -1, + 379, 413, 412, -1, 413, 379, 378, -1, + 414, 378, 377, -1, 377, 415, 414, -1, + 416, 376, 375, -1, 375, 417, 416, -1, + 417, 375, 374, -1, 417, 374, 418, -1, + 419, 417, 418, -1, 419, 420, 417, -1, + 421, 418, 374, -1, 421, 374, 373, -1, + 422, 373, 372, -1, 372, 423, 422, -1, + 372, 424, 423, -1, 423, 425, 426, -1, + 423, 427, 425, -1, 427, 423, 424, -1, + 424, 428, 427, -1, 429, 370, 368, -1, + 368, 430, 429, -1, 430, 368, 366, -1, + 366, 431, 430, -1, 431, 366, 364, -1, + 364, 432, 431, -1, 432, 364, 362, -1, + 362, 433, 432, -1, 433, 362, 360, -1, + 360, 434, 433, -1, 434, 360, 358, -1, + 358, 435, 434, -1, 435, 358, 356, -1, + 356, 436, 435, -1, 436, 356, 354, -1, + 354, 437, 436, -1, 437, 354, 352, -1, + 352, 438, 437, -1, 438, 352, 350, -1, + 350, 439, 438, -1, 439, 350, 348, -1, + 348, 440, 439, -1, 440, 348, 346, -1, + 346, 441, 440, -1, 441, 346, 344, -1, + 344, 442, 441, -1, 442, 344, 342, -1, + 342, 443, 442, -1, 443, 342, 340, -1, + 340, 444, 443, -1, 444, 340, 338, -1, + 338, 445, 444, -1, 445, 338, 332, -1, + 445, 332, 333, -1, 446, 445, 333, -1, + 446, 447, 445, -1, 445, 447, 329, -1, + 329, 444, 445, -1, 444, 329, 328, -1, + 328, 443, 444, -1, 443, 328, 448, -1, + 448, 442, 443, -1, 442, 448, 449, -1, + 449, 441, 442, -1, 441, 449, 450, -1, + 450, 440, 441, -1, 440, 450, 451, -1, + 451, 439, 440, -1, 439, 451, 452, -1, + 452, 438, 439, -1, 453, 437, 438, -1, + 437, 453, 454, -1, 454, 436, 437, -1, + 436, 454, 455, -1, 455, 435, 436, -1, + 435, 455, 456, -1, 456, 434, 435, -1, + 434, 456, 457, -1, 457, 433, 434, -1, + 433, 457, 458, -1, 458, 432, 433, -1, + 432, 458, 459, -1, 459, 431, 432, -1, + 431, 459, 460, -1, 460, 430, 431, -1, + 430, 460, 461, -1, 461, 429, 430, -1, + 428, 462, 463, -1, 463, 427, 428, -1, + 427, 463, 464, -1, 464, 425, 427, -1, + 425, 464, 465, -1, 465, 466, 425, -1, + 467, 466, 465, -1, 465, 468, 467, -1, + 465, 469, 468, -1, 469, 465, 464, -1, + 464, 470, 469, -1, 470, 464, 463, -1, + 463, 471, 470, -1, 471, 463, 462, -1, + 462, 472, 471, -1, 473, 461, 460, -1, + 460, 474, 473, -1, 474, 460, 459, -1, + 459, 475, 474, -1, 475, 459, 458, -1, + 458, 476, 475, -1, 476, 458, 457, -1, + 457, 477, 476, -1, 477, 457, 456, -1, + 456, 478, 477, -1, 478, 456, 455, -1, + 455, 479, 478, -1, 479, 455, 454, -1, + 454, 480, 479, -1, 480, 454, 453, -1, + 453, 481, 480, -1, 452, 482, 481, -1, + 482, 452, 451, -1, 451, 483, 482, -1, + 483, 451, 450, -1, 450, 484, 483, -1, + 484, 450, 449, -1, 449, 485, 484, -1, + 485, 449, 448, -1, 448, 486, 485, -1, + 486, 448, 328, -1, 328, 327, 486, -1, + 487, 488, 489, -1, 490, 489, 488, -1, + 491, 489, 490, -1, 491, 492, 489, -1, + 493, 494, 327, -1, 494, 493, 492, -1, + 494, 492, 491, -1, 491, 490, 494, -1, + 490, 327, 494, -1, 490, 486, 327, -1, + 495, 485, 486, -1, 485, 495, 496, -1, + 496, 484, 485, -1, 484, 496, 497, -1, + 497, 483, 484, -1, 483, 497, 498, -1, + 498, 482, 483, -1, 482, 498, 499, -1, + 499, 481, 482, -1, 481, 499, 500, -1, + 500, 480, 481, -1, 480, 500, 501, -1, + 501, 479, 480, -1, 479, 501, 502, -1, + 502, 478, 479, -1, 478, 502, 503, -1, + 503, 477, 478, -1, 477, 503, 504, -1, + 504, 476, 477, -1, 476, 504, 505, -1, + 505, 475, 476, -1, 475, 505, 506, -1, + 506, 474, 475, -1, 474, 506, 507, -1, + 507, 473, 474, -1, 472, 508, 509, -1, + 509, 471, 472, -1, 471, 509, 510, -1, + 510, 470, 471, -1, 470, 510, 511, -1, + 511, 469, 470, -1, 469, 511, 512, -1, + 512, 468, 469, -1, 468, 512, 513, -1, + 468, 513, 514, -1, 515, 514, 513, -1, + 515, 513, 516, -1, 517, 516, 513, -1, + 513, 518, 517, -1, 518, 513, 512, -1, + 512, 519, 518, -1, 519, 512, 511, -1, + 511, 520, 519, -1, 520, 511, 510, -1, + 510, 521, 520, -1, 521, 510, 509, -1, + 509, 522, 521, -1, 522, 509, 508, -1, + 508, 523, 522, -1, 524, 507, 506, -1, + 525, 506, 505, -1, 505, 526, 525, -1, + 526, 505, 504, -1, 504, 527, 526, -1, + 527, 504, 503, -1, 503, 528, 527, -1, + 528, 503, 502, -1, 502, 529, 528, -1, + 529, 502, 501, -1, 501, 530, 529, -1, + 530, 501, 500, -1, 500, 531, 530, -1, + 531, 500, 499, -1, 499, 532, 531, -1, + 532, 499, 498, -1, 498, 533, 532, -1, + 533, 498, 497, -1, 497, 534, 533, -1, + 534, 497, 496, -1, 496, 535, 534, -1, + 535, 496, 495, -1, 495, 488, 535, -1, + 536, 537, 538, -1, 539, 538, 537, -1, + 537, 540, 539, -1, 541, 542, 543, -1, + 543, 544, 541, -1, 544, 543, 545, -1, + 545, 546, 544, -1, 546, 545, 547, -1, + 547, 548, 546, -1, 548, 547, 549, -1, + 549, 550, 548, -1, 550, 549, 551, -1, + 551, 552, 550, -1, 552, 551, 553, -1, + 553, 554, 552, -1, 554, 553, 555, -1, + 555, 556, 554, -1, 556, 555, 557, -1, + 557, 558, 556, -1, 558, 557, 559, -1, + 559, 560, 558, -1, 560, 559, 561, -1, + 561, 562, 560, -1, 562, 561, 563, -1, + 563, 564, 562, -1, 565, 566, 567, -1, + 567, 568, 565, -1, 568, 567, 569, -1, + 569, 570, 568, -1, 570, 569, 571, -1, + 571, 572, 570, -1, 572, 571, 573, -1, + 573, 574, 572, -1, 574, 573, 575, -1, + 575, 576, 574, -1, 576, 575, 577, -1, + 577, 578, 576, -1, 578, 577, 540, -1, + 540, 537, 578, -1, 579, 537, 580, -1, + 579, 578, 537, -1, 578, 579, 581, -1, + 581, 576, 578, -1, 576, 581, 582, -1, + 582, 574, 576, -1, 574, 582, 583, -1, + 583, 572, 574, -1, 572, 583, 584, -1, + 584, 570, 572, -1, 570, 584, 585, -1, + 585, 568, 570, -1, 568, 585, 586, -1, + 586, 565, 568, -1, 564, 587, 588, -1, + 588, 562, 564, -1, 562, 588, 589, -1, + 589, 560, 562, -1, 560, 589, 590, -1, + 590, 558, 560, -1, 558, 590, 591, -1, + 591, 556, 558, -1, 556, 591, 592, -1, + 592, 554, 556, -1, 554, 592, 593, -1, + 593, 552, 554, -1, 552, 593, 594, -1, + 594, 550, 552, -1, 550, 594, 595, -1, + 595, 548, 550, -1, 548, 595, 596, -1, + 596, 546, 548, -1, 546, 596, 597, -1, + 597, 544, 546, -1, 544, 597, 598, -1, + 598, 541, 544, -1, 541, 598, 599, -1, + 599, 600, 541, -1, 601, 541, 600, -1, + 601, 542, 541, -1, 602, 543, 542, -1, + 602, 603, 543, -1, 604, 543, 603, -1, + 604, 545, 543, -1, 545, 604, 605, -1, + 605, 547, 545, -1, 547, 605, 606, -1, + 606, 549, 547, -1, 549, 606, 607, -1, + 607, 551, 549, -1, 551, 607, 608, -1, + 608, 553, 551, -1, 553, 608, 609, -1, + 609, 555, 553, -1, 555, 609, 610, -1, + 610, 557, 555, -1, 557, 610, 611, -1, + 611, 559, 557, -1, 559, 611, 612, -1, + 612, 561, 559, -1, 561, 612, 613, -1, + 613, 563, 561, -1, 566, 614, 615, -1, + 615, 567, 566, -1, 567, 615, 616, -1, + 616, 569, 567, -1, 569, 616, 617, -1, + 617, 571, 569, -1, 571, 617, 618, -1, + 618, 573, 571, -1, 573, 618, 619, -1, + 619, 575, 573, -1, 575, 619, 620, -1, + 620, 577, 575, -1, 577, 620, 621, -1, + 621, 540, 577, -1, 540, 621, 622, -1, + 622, 539, 540, -1, 623, 624, 625, -1, + 624, 623, 626, -1, 626, 623, 539, -1, + 539, 622, 626, -1, 626, 627, 628, -1, + 627, 626, 622, -1, 622, 629, 627, -1, + 629, 622, 621, -1, 621, 630, 629, -1, + 630, 621, 620, -1, 620, 631, 630, -1, + 631, 620, 619, -1, 619, 632, 631, -1, + 632, 619, 618, -1, 618, 633, 632, -1, + 633, 618, 617, -1, 617, 634, 633, -1, + 634, 617, 616, -1, 616, 635, 634, -1, + 635, 616, 615, -1, 615, 636, 635, -1, + 636, 615, 614, -1, 614, 637, 636, -1, + 638, 613, 612, -1, 639, 612, 611, -1, + 611, 640, 639, -1, 640, 611, 610, -1, + 610, 641, 640, -1, 641, 610, 609, -1, + 609, 642, 641, -1, 642, 609, 608, -1, + 643, 608, 607, -1, 607, 644, 643, -1, + 644, 607, 606, -1, 606, 645, 644, -1, + 645, 606, 605, -1, 605, 646, 645, -1, + 646, 605, 604, -1, 604, 647, 646, -1, + 647, 604, 603, -1, 648, 646, 647, -1, + 648, 649, 646, -1, 650, 646, 649, -1, + 650, 645, 646, -1, 645, 650, 651, -1, + 651, 644, 645, -1, 644, 651, 652, -1, + 652, 643, 644, -1, 643, 652, 653, -1, + 642, 653, 654, -1, 654, 641, 642, -1, + 641, 654, 655, -1, 655, 640, 641, -1, + 640, 655, 656, -1, 656, 639, 640, -1, + 639, 656, 657, -1, 637, 658, 659, -1, + 659, 636, 637, -1, 636, 659, 660, -1, + 660, 635, 636, -1, 635, 660, 661, -1, + 661, 634, 635, -1, 634, 661, 662, -1, + 662, 633, 634, -1, 633, 662, 663, -1, + 663, 632, 633, -1, 632, 663, 664, -1, + 664, 631, 632, -1, 631, 664, 665, -1, + 665, 630, 631, -1, 630, 665, 666, -1, + 666, 629, 630, -1, 629, 666, 667, -1, + 667, 627, 629, -1, 627, 667, 668, -1, + 668, 628, 627, -1, 628, 668, 669, -1, + 669, 670, 628, -1, 671, 670, 669, -1, + 671, 669, 672, -1, 669, 488, 672, -1, + 669, 535, 488, -1, 535, 669, 668, -1, + 668, 534, 535, -1, 534, 668, 667, -1, + 667, 533, 534, -1, 533, 667, 666, -1, + 666, 532, 533, -1, 532, 666, 665, -1, + 665, 531, 532, -1, 531, 665, 664, -1, + 664, 530, 531, -1, 530, 664, 663, -1, + 663, 529, 530, -1, 529, 663, 662, -1, + 662, 528, 529, -1, 528, 662, 661, -1, + 661, 527, 528, -1, 527, 661, 660, -1, + 660, 526, 527, -1, 526, 660, 659, -1, + 659, 525, 526, -1, 525, 659, 658, -1, + 523, 657, 656, -1, 656, 522, 523, -1, + 522, 656, 655, -1, 655, 521, 522, -1, + 521, 655, 654, -1, 654, 520, 521, -1, + 520, 654, 653, -1, 653, 519, 520, -1, + 519, 653, 652, -1, 652, 518, 519, -1, + 518, 652, 651, -1, 651, 517, 518, -1, + 517, 651, 650, -1, 517, 650, 673, -1, + 673, 516, 517, -1, 674, 673, 650, -1, + 674, 650, 649, -1, 675, 676, 677, -1, + 675, 678, 676, -1, 161, 160, 678, -1, + 160, 676, 678, -1, 160, 679, 676, -1, + 679, 160, 158, -1, 158, 680, 679, -1, + 680, 158, 156, -1, 156, 681, 680, -1, + 681, 156, 154, -1, 154, 682, 681, -1, + 682, 154, 152, -1, 152, 683, 682, -1, + 683, 152, 150, -1, 150, 684, 683, -1, + 684, 150, 148, -1, 148, 685, 684, -1, + 685, 148, 146, -1, 686, 146, 144, -1, + 144, 687, 686, -1, 687, 144, 142, -1, + 142, 688, 687, -1, 688, 142, 140, -1, + 140, 689, 688, -1, 689, 140, 138, -1, + 138, 690, 689, -1, 690, 138, 136, -1, + 136, 691, 690, -1, 691, 136, 134, -1, + 134, 692, 691, -1, 692, 134, 132, -1, + 132, 693, 692, -1, 693, 132, 130, -1, + 130, 694, 693, -1, 694, 130, 128, -1, + 128, 695, 694, -1, 695, 128, 126, -1, + 126, 696, 695, -1, 696, 126, 124, -1, + 124, 697, 696, -1, 697, 124, 119, -1, + 697, 119, 118, -1, 698, 697, 118, -1, + 698, 699, 697, -1, 697, 699, 115, -1, + 115, 696, 697, -1, 696, 115, 114, -1, + 114, 695, 696, -1, 695, 114, 113, -1, + 113, 694, 695, -1, 694, 113, 111, -1, + 111, 693, 694, -1, 693, 111, 109, -1, + 109, 692, 693, -1, 692, 109, 107, -1, + 107, 691, 692, -1, 691, 107, 105, -1, + 105, 690, 691, -1, 690, 105, 103, -1, + 103, 689, 690, -1, 689, 103, 101, -1, + 101, 688, 689, -1, 688, 101, 99, -1, + 99, 687, 688, -1, 687, 99, 97, -1, + 97, 686, 687, -1, 686, 97, 95, -1, + 685, 95, 93, -1, 93, 684, 685, -1, + 684, 93, 91, -1, 91, 683, 684, -1, + 683, 91, 89, -1, 89, 682, 683, -1, + 682, 89, 87, -1, 87, 681, 682, -1, + 681, 87, 85, -1, 85, 680, 681, -1, + 680, 85, 83, -1, 83, 679, 680, -1, + 679, 83, 81, -1, 81, 676, 679, -1, + 676, 81, 80, -1, 80, 677, 676, -1, + 700, 677, 80, -1, 700, 80, 701, -1, + 702, 701, 80, -1, 80, 79, 702, -1, + 702, 703, 704, -1, 703, 702, 79, -1, + 79, 705, 703, -1, 705, 79, 82, -1, + 82, 706, 705, -1, 706, 82, 84, -1, + 84, 707, 706, -1, 707, 84, 86, -1, + 86, 708, 707, -1, 708, 86, 88, -1, + 88, 709, 708, -1, 709, 88, 90, -1, + 90, 710, 709, -1, 710, 90, 92, -1, + 92, 711, 710, -1, 711, 92, 94, -1, + 94, 712, 711, -1, 712, 94, 96, -1, + 96, 713, 712, -1, 713, 96, 98, -1, + 98, 714, 713, -1, 714, 98, 100, -1, + 100, 715, 714, -1, 715, 100, 102, -1, + 102, 716, 715, -1, 104, 717, 716, -1, + 717, 104, 106, -1, 106, 718, 717, -1, + 718, 106, 108, -1, 108, 719, 718, -1, + 719, 108, 110, -1, 110, 720, 719, -1, + 720, 110, 112, -1, 112, 721, 720, -1, + 721, 112, 78, -1, 78, 77, 721, -1, + 722, 721, 77, -1, 77, 723, 722, -1, + 724, 722, 723, -1, 724, 723, 72, -1, + 723, 725, 72, -1, 725, 723, 77, -1, + 725, 77, 73, -1, 73, 75, 725, -1, + 75, 72, 725, -1, 75, 70, 72, -1, + 726, 68, 70, -1, 68, 726, 727, -1, + 727, 66, 68, -1, 66, 727, 728, -1, + 728, 64, 66, -1, 64, 728, 729, -1, + 62, 729, 730, -1, 730, 60, 62, -1, + 60, 730, 731, -1, 731, 58, 60, -1, + 58, 731, 732, -1, 732, 56, 58, -1, + 56, 732, 733, -1, 733, 54, 56, -1, + 54, 733, 734, -1, 734, 51, 54, -1, + 51, 734, 735, -1, 735, 52, 51, -1, + 52, 735, 736, -1, 737, 738, 739, -1, + 740, 741, 742, -1, 742, 743, 740, -1, + 743, 742, 744, -1, 744, 745, 743, -1, + 745, 744, 746, -1, 746, 747, 745, -1, + 747, 746, 748, -1, 748, 749, 747, -1, + 749, 748, 750, -1, 750, 751, 749, -1, + 751, 750, 752, -1, 752, 753, 751, -1, + 753, 752, 754, -1, 754, 755, 753, -1, + 755, 754, 756, -1, 756, 757, 755, -1, + 758, 759, 760, -1, 760, 761, 758, -1, + 761, 760, 738, -1, 738, 737, 761, -1, + 736, 761, 737, -1, 761, 736, 735, -1, + 735, 758, 761, -1, 758, 735, 734, -1, + 757, 734, 733, -1, 733, 755, 757, -1, + 755, 733, 732, -1, 732, 753, 755, -1, + 753, 732, 731, -1, 731, 751, 753, -1, + 751, 731, 730, -1, 730, 749, 751, -1, + 749, 730, 729, -1, 729, 747, 749, -1, + 747, 729, 728, -1, 728, 745, 747, -1, + 745, 728, 727, -1, 727, 743, 745, -1, + 743, 727, 726, -1, 726, 740, 743, -1, + 740, 75, 74, -1, 74, 762, 740, -1, + 74, 76, 762, -1, 76, 115, 762, -1, + 763, 762, 115, -1, 763, 740, 762, -1, + 763, 741, 740, -1, 741, 763, 115, -1, + 741, 115, 699, -1, 699, 742, 741, -1, + 699, 698, 742, -1, 698, 118, 742, -1, + 742, 118, 117, -1, 117, 744, 742, -1, + 744, 117, 764, -1, 764, 746, 744, -1, + 746, 764, 765, -1, 765, 748, 746, -1, + 748, 765, 766, -1, 766, 750, 748, -1, + 750, 766, 767, -1, 767, 752, 750, -1, + 752, 767, 768, -1, 768, 754, 752, -1, + 754, 768, 769, -1, 769, 756, 754, -1, + 756, 769, 770, -1, 759, 770, 771, -1, + 771, 760, 759, -1, 760, 771, 772, -1, + 772, 738, 760, -1, 738, 772, 773, -1, + 773, 739, 738, -1, 739, 773, 774, -1, + 774, 775, 776, -1, 775, 774, 773, -1, + 773, 777, 775, -1, 777, 773, 772, -1, + 772, 778, 777, -1, 778, 772, 771, -1, + 771, 779, 778, -1, 779, 771, 770, -1, + 770, 780, 779, -1, 780, 770, 769, -1, + 769, 781, 780, -1, 781, 769, 768, -1, + 768, 782, 781, -1, 782, 768, 767, -1, + 767, 783, 782, -1, 783, 767, 766, -1, + 766, 784, 783, -1, 784, 766, 765, -1, + 765, 785, 784, -1, 785, 765, 764, -1, + 764, 786, 785, -1, 786, 764, 117, -1, + 786, 117, 121, -1, 787, 786, 121, -1, + 787, 121, 122, -1, 787, 122, 184, -1, + 184, 786, 787, -1, 184, 788, 786, -1, + 788, 184, 183, -1, 788, 183, 322, -1, + 322, 324, 788, -1, 324, 786, 788, -1, + 324, 785, 786, -1, 785, 324, 789, -1, + 789, 784, 785, -1, 784, 789, 790, -1, + 790, 783, 784, -1, 783, 790, 791, -1, + 791, 782, 783, -1, 782, 791, 792, -1, + 792, 781, 782, -1, 781, 792, 793, -1, + 793, 780, 781, -1, 780, 793, 794, -1, + 794, 779, 780, -1, 779, 794, 795, -1, + 795, 778, 779, -1, 778, 795, 796, -1, + 796, 777, 778, -1, 777, 796, 797, -1, + 797, 775, 777, -1, 775, 797, 798, -1, + 798, 776, 775, -1, 776, 798, 799, -1, + 800, 801, 802, -1, 803, 804, 805, -1, + 803, 806, 804, -1, 806, 803, 807, -1, + 807, 808, 806, -1, 808, 807, 809, -1, + 809, 810, 808, -1, 810, 809, 811, -1, + 811, 812, 810, -1, 812, 811, 813, -1, + 813, 814, 812, -1, 814, 813, 815, -1, + 815, 816, 814, -1, 816, 815, 817, -1, + 817, 818, 816, -1, 818, 817, 819, -1, + 819, 820, 818, -1, 820, 819, 821, -1, + 821, 822, 820, -1, 823, 824, 801, -1, + 801, 800, 823, -1, 825, 823, 800, -1, + 822, 826, 827, -1, 827, 820, 822, -1, + 820, 827, 828, -1, 828, 818, 820, -1, + 818, 828, 829, -1, 829, 816, 818, -1, + 816, 829, 830, -1, 830, 814, 816, -1, + 814, 830, 831, -1, 831, 812, 814, -1, + 812, 831, 832, -1, 832, 810, 812, -1, + 810, 832, 833, -1, 833, 808, 810, -1, + 808, 833, 834, -1, 834, 806, 808, -1, + 806, 834, 835, -1, 835, 804, 806, -1, + 836, 837, 804, -1, 804, 835, 836, -1, + 836, 838, 839, -1, 836, 840, 838, -1, + 840, 836, 835, -1, 835, 841, 840, -1, + 841, 835, 834, -1, 834, 842, 841, -1, + 842, 834, 833, -1, 833, 843, 842, -1, + 843, 833, 832, -1, 832, 844, 843, -1, + 844, 832, 831, -1, 831, 845, 844, -1, + 845, 831, 830, -1, 830, 846, 845, -1, + 846, 830, 829, -1, 829, 847, 846, -1, + 847, 829, 828, -1, 828, 848, 847, -1, + 848, 828, 827, -1, 827, 849, 848, -1, + 849, 827, 826, -1, 826, 850, 849, -1, + 799, 849, 850, -1, 849, 799, 798, -1, + 798, 848, 849, -1, 848, 798, 797, -1, + 797, 847, 848, -1, 847, 797, 796, -1, + 796, 846, 847, -1, 846, 796, 795, -1, + 795, 845, 846, -1, 845, 795, 794, -1, + 794, 844, 845, -1, 844, 794, 793, -1, + 793, 843, 844, -1, 843, 793, 792, -1, + 792, 842, 843, -1, 842, 792, 791, -1, + 791, 841, 842, -1, 841, 791, 790, -1, + 790, 840, 841, -1, 840, 790, 789, -1, + 789, 838, 840, -1, 838, 789, 324, -1, + 324, 851, 838, -1, 851, 324, 323, -1, + 851, 323, 188, -1, 851, 188, 186, -1, + 186, 838, 851, -1, 186, 185, 838, -1, + 185, 839, 838, -1, 185, 187, 839, -1, + 187, 231, 839, -1, 852, 839, 231, -1, + 852, 836, 839, -1, 852, 837, 836, -1, + 837, 852, 231, -1, 837, 231, 230, -1, + 230, 804, 837, -1, 853, 804, 230, -1, + 853, 230, 229, -1, 853, 229, 273, -1, + 273, 804, 853, -1, 273, 805, 804, -1, + 805, 273, 272, -1, 805, 272, 274, -1, + 274, 803, 805, -1, 274, 275, 803, -1, + 275, 276, 803, -1, 46, 803, 276, -1, + 46, 807, 803, -1, 807, 46, 49, -1, + 49, 809, 807, -1, 809, 49, 854, -1, + 854, 811, 809, -1, 811, 854, 855, -1, + 855, 813, 811, -1, 813, 855, 856, -1, + 856, 815, 813, -1, 815, 856, 857, -1, + 857, 817, 815, -1, 817, 857, 858, -1, + 858, 819, 817, -1, 819, 858, 859, -1, + 859, 821, 819, -1, 824, 860, 861, -1, + 861, 801, 824, -1, 801, 861, 862, -1, + 862, 802, 801, -1, 802, 862, 863, -1, + 863, 864, 865, -1, 864, 863, 862, -1, + 862, 866, 864, -1, 866, 862, 861, -1, + 861, 867, 866, -1, 867, 861, 860, -1, + 860, 868, 867, -1, 869, 859, 858, -1, + 858, 870, 869, -1, 870, 858, 857, -1, + 857, 871, 870, -1, 871, 857, 856, -1, + 872, 856, 855, -1, 855, 873, 872, -1, + 873, 855, 854, -1, 854, 874, 873, -1, + 874, 854, 49, -1, 49, 48, 874, -1, + 875, 876, 48, -1, 48, 876, 877, -1, + 877, 874, 48, -1, 874, 877, 878, -1, + 878, 873, 874, -1, 873, 878, 879, -1, + 879, 872, 873, -1, 872, 879, 880, -1, + 871, 880, 881, -1, 881, 870, 871, -1, + 882, 869, 870, -1, 868, 883, 884, -1, + 884, 867, 868, -1, 867, 884, 885, -1, + 885, 866, 867, -1, 866, 885, 886, -1, + 886, 864, 866, -1, 864, 886, 887, -1, + 887, 865, 864, -1, 865, 887, 888, -1, + 889, 890, 891, -1, 889, 892, 893, -1, + 893, 890, 889, -1, 894, 891, 890, -1, + 894, 895, 891, -1, 896, 897, 898, -1, + 899, 897, 896, -1, 900, 901, 902, -1, + 902, 903, 900, -1, 903, 902, 904, -1, + 904, 905, 903, -1, 905, 904, 906, -1, + 906, 907, 905, -1, 907, 906, 908, -1, + 908, 909, 907, -1, 909, 908, 910, -1, + 910, 911, 909, -1, 911, 910, 912, -1, + 912, 913, 911, -1, 913, 912, 914, -1, + 914, 915, 913, -1, 915, 914, 916, -1, + 916, 917, 915, -1, 917, 916, 918, -1, + 918, 919, 917, -1, 918, 920, 919, -1, + 921, 919, 920, -1, 922, 923, 924, -1, + 922, 925, 923, -1, 926, 927, 928, -1, + 929, 930, 931, -1, 931, 932, 929, -1, + 932, 931, 933, -1, 933, 934, 932, -1, + 934, 933, 935, -1, 935, 936, 934, -1, + 936, 935, 937, -1, 937, 938, 936, -1, + 938, 937, 939, -1, 939, 940, 938, -1, + 940, 939, 941, -1, 941, 942, 940, -1, + 942, 941, 943, -1, 943, 944, 942, -1, + 944, 943, 945, -1, 945, 946, 944, -1, + 946, 945, 947, -1, 947, 948, 946, -1, + 948, 947, 949, -1, 949, 950, 948, -1, + 951, 952, 953, -1, 953, 954, 951, -1, + 954, 953, 955, -1, 955, 956, 954, -1, + 956, 955, 957, -1, 957, 958, 956, -1, + 958, 957, 959, -1, 959, 960, 958, -1, + 960, 959, 961, -1, 961, 962, 960, -1, + 962, 961, 963, -1, 963, 964, 962, -1, + 964, 963, 965, -1, 965, 966, 964, -1, + 966, 965, 967, -1, 967, 968, 966, -1, + 968, 967, 969, -1, 970, 971, 972, -1, + 973, 972, 971, -1, 971, 974, 973, -1, + 975, 976, 977, -1, 976, 975, 978, -1, + 978, 975, 973, -1, 973, 979, 978, -1, + 979, 973, 974, -1, 974, 980, 979, -1, + 980, 974, 981, -1, 981, 982, 980, -1, + 983, 984, 985, -1, 985, 986, 983, -1, + 986, 985, 987, -1, 987, 988, 986, -1, + 988, 987, 989, -1, 989, 990, 988, -1, + 990, 989, 991, -1, 991, 992, 990, -1, + 992, 991, 993, -1, 993, 994, 992, -1, + 994, 993, 995, -1, 995, 996, 994, -1, + 996, 995, 997, -1, 997, 998, 996, -1, + 998, 997, 999, -1, 999, 1000, 998, -1, + 1000, 999, 1001, -1, 1001, 1002, 1000, -1, + 1002, 1001, 1003, -1, 1003, 1004, 1002, -1, + 1004, 1003, 1005, -1, 1005, 1006, 1004, -1, + 1006, 1005, 1007, -1, 1007, 1008, 1006, -1, + 1008, 1007, 1009, -1, 1009, 1010, 1008, -1, + 1010, 1009, 1011, -1, 1011, 1012, 1010, -1, + 1012, 1011, 1013, -1, 1013, 1014, 1012, -1, + 1014, 1013, 1015, -1, 1015, 1016, 1014, -1, + 1017, 1014, 1016, -1, 1017, 1018, 1014, -1, + 1014, 1018, 1019, -1, 1019, 1012, 1014, -1, + 1012, 1019, 1020, -1, 1020, 1010, 1012, -1, + 1010, 1020, 1021, -1, 1021, 1008, 1010, -1, + 1008, 1021, 1022, -1, 1022, 1006, 1008, -1, + 1006, 1022, 1023, -1, 1023, 1004, 1006, -1, + 1004, 1023, 1024, -1, 1024, 1002, 1004, -1, + 1002, 1024, 1025, -1, 1025, 1000, 1002, -1, + 1000, 1025, 1026, -1, 1026, 998, 1000, -1, + 998, 1026, 1027, -1, 1027, 996, 998, -1, + 996, 1027, 1028, -1, 1028, 994, 996, -1, + 994, 1028, 1029, -1, 1029, 992, 994, -1, + 992, 1029, 1030, -1, 1030, 990, 992, -1, + 990, 1030, 1031, -1, 1031, 988, 990, -1, + 988, 1031, 1032, -1, 1032, 986, 988, -1, + 986, 1032, 1033, -1, 1033, 983, 986, -1, + 982, 1034, 1035, -1, 1035, 980, 982, -1, + 980, 1035, 1036, -1, 1036, 979, 980, -1, + 979, 1036, 1037, -1, 1037, 978, 979, -1, + 978, 1037, 1038, -1, 1039, 1040, 1041, -1, + 1041, 1040, 1038, -1, 1038, 1042, 1041, -1, + 1042, 1038, 1037, -1, 1037, 1043, 1042, -1, + 1043, 1037, 1036, -1, 1036, 1044, 1043, -1, + 1044, 1036, 1035, -1, 1035, 1045, 1044, -1, + 1045, 1035, 1034, -1, 1034, 1046, 1045, -1, + 1047, 1033, 1032, -1, 1032, 1048, 1047, -1, + 1048, 1032, 1031, -1, 1031, 1049, 1048, -1, + 1049, 1031, 1030, -1, 1030, 1050, 1049, -1, + 1050, 1030, 1029, -1, 1029, 1051, 1050, -1, + 1051, 1029, 1028, -1, 1028, 1052, 1051, -1, + 1052, 1028, 1027, -1, 1027, 1053, 1052, -1, + 1053, 1027, 1026, -1, 1026, 1054, 1053, -1, + 1054, 1026, 1025, -1, 1025, 1055, 1054, -1, + 1055, 1025, 1024, -1, 1024, 1056, 1055, -1, + 1056, 1024, 1023, -1, 1023, 1057, 1056, -1, + 1057, 1023, 1022, -1, 1022, 1058, 1057, -1, + 1058, 1022, 1021, -1, 1021, 1059, 1058, -1, + 1059, 1021, 1020, -1, 1020, 1060, 1059, -1, + 1060, 1020, 1019, -1, 1060, 1019, 1061, -1, + 1062, 1061, 1019, -1, 1062, 1019, 1018, -1, + 1063, 1064, 1065, -1, 1063, 1066, 1064, -1, + 1016, 1015, 1066, -1, 1015, 1064, 1066, -1, + 1015, 1067, 1064, -1, 1067, 1015, 1013, -1, + 1013, 1068, 1067, -1, 1068, 1013, 1011, -1, + 1011, 1069, 1068, -1, 1069, 1011, 1009, -1, + 1009, 1070, 1069, -1, 1070, 1009, 1007, -1, + 1007, 1071, 1070, -1, 1071, 1007, 1005, -1, + 1005, 1072, 1071, -1, 1072, 1005, 1003, -1, + 1003, 1073, 1072, -1, 1073, 1003, 1001, -1, + 1001, 1074, 1073, -1, 1074, 1001, 999, -1, + 999, 1075, 1074, -1, 1075, 999, 997, -1, + 997, 1076, 1075, -1, 1076, 997, 995, -1, + 995, 1077, 1076, -1, 1077, 995, 993, -1, + 993, 1078, 1077, -1, 1078, 993, 991, -1, + 991, 1079, 1078, -1, 1079, 991, 989, -1, + 989, 1080, 1079, -1, 1080, 989, 987, -1, + 987, 1081, 1080, -1, 1081, 987, 985, -1, + 985, 1082, 1081, -1, 1082, 985, 984, -1, + 984, 1083, 1082, -1, 1084, 981, 974, -1, + 974, 971, 1084, -1, 1085, 971, 1086, -1, + 1085, 1084, 971, -1, 1083, 1087, 1088, -1, + 1088, 1082, 1083, -1, 1082, 1088, 1089, -1, + 1089, 1081, 1082, -1, 1081, 1089, 1090, -1, + 1090, 1080, 1081, -1, 1080, 1090, 1091, -1, + 1091, 1079, 1080, -1, 1079, 1091, 1092, -1, + 1092, 1078, 1079, -1, 1078, 1092, 1093, -1, + 1093, 1077, 1078, -1, 1077, 1093, 1094, -1, + 1094, 1076, 1077, -1, 1076, 1094, 1095, -1, + 1095, 1075, 1076, -1, 1075, 1095, 1096, -1, + 1096, 1074, 1075, -1, 1074, 1096, 1097, -1, + 1097, 1073, 1074, -1, 1073, 1097, 1098, -1, + 1098, 1072, 1073, -1, 1072, 1098, 1099, -1, + 1099, 1071, 1072, -1, 1071, 1099, 1100, -1, + 1100, 1070, 1071, -1, 1070, 1100, 1101, -1, + 1101, 1069, 1070, -1, 1069, 1101, 1102, -1, + 1102, 1068, 1069, -1, 1068, 1102, 1103, -1, + 1103, 1067, 1068, -1, 1067, 1103, 1104, -1, + 1104, 1064, 1067, -1, 1064, 1104, 1105, -1, + 1105, 1065, 1064, -1, 1106, 1065, 1105, -1, + 1106, 1105, 1107, -1, 1108, 1107, 1105, -1, + 1105, 1109, 1108, -1, 1109, 1105, 1104, -1, + 1104, 1110, 1109, -1, 1110, 1104, 1103, -1, + 1103, 1111, 1110, -1, 1111, 1103, 1102, -1, + 1102, 1112, 1111, -1, 1112, 1102, 1101, -1, + 1101, 1113, 1112, -1, 1113, 1101, 1100, -1, + 1100, 1114, 1113, -1, 1114, 1100, 1099, -1, + 1099, 1115, 1114, -1, 1115, 1099, 1098, -1, + 1098, 1116, 1115, -1, 1116, 1098, 1097, -1, + 1097, 1117, 1116, -1, 1117, 1097, 1096, -1, + 1096, 1118, 1117, -1, 1118, 1096, 1095, -1, + 1095, 1119, 1118, -1, 1119, 1095, 1094, -1, + 1094, 1120, 1119, -1, 1120, 1094, 1093, -1, + 1093, 1121, 1120, -1, 1121, 1093, 1092, -1, + 1092, 1122, 1121, -1, 1122, 1092, 1091, -1, + 1091, 1123, 1122, -1, 1123, 1091, 1090, -1, + 1090, 1124, 1123, -1, 1124, 1090, 1089, -1, + 1089, 1125, 1124, -1, 1125, 1089, 1088, -1, + 1088, 1126, 1125, -1, 1126, 1088, 1087, -1, + 1087, 1127, 1126, -1, 1085, 1128, 1127, -1, + 1129, 1130, 1131, -1, 1129, 1132, 1130, -1, + 1132, 1128, 1130, -1, 1132, 1127, 1128, -1, + 1132, 1129, 1127, -1, 1129, 1131, 1127, -1, + 1133, 1134, 1135, -1, 1133, 1135, 1131, -1, + 1135, 1127, 1131, -1, 1135, 1126, 1127, -1, + 1126, 1135, 1136, -1, 1136, 1125, 1126, -1, + 1125, 1136, 1137, -1, 1137, 1124, 1125, -1, + 1124, 1137, 1138, -1, 1138, 1123, 1124, -1, + 1123, 1138, 1139, -1, 1139, 1122, 1123, -1, + 1122, 1139, 1140, -1, 1140, 1121, 1122, -1, + 1121, 1140, 1141, -1, 1141, 1120, 1121, -1, + 1120, 1141, 1142, -1, 1142, 1119, 1120, -1, + 1119, 1142, 1143, -1, 1143, 1118, 1119, -1, + 1118, 1143, 1144, -1, 1144, 1117, 1118, -1, + 1117, 1144, 1145, -1, 1145, 1116, 1117, -1, + 1116, 1145, 1146, -1, 1146, 1115, 1116, -1, + 1115, 1146, 1147, -1, 1147, 1114, 1115, -1, + 1114, 1147, 1148, -1, 1148, 1113, 1114, -1, + 1113, 1148, 1149, -1, 1149, 1112, 1113, -1, + 1112, 1149, 1150, -1, 1150, 1111, 1112, -1, + 1111, 1150, 1151, -1, 1151, 1110, 1111, -1, + 1110, 1151, 1152, -1, 1152, 1109, 1110, -1, + 1109, 1152, 1153, -1, 1153, 1108, 1109, -1, + 1108, 1153, 1154, -1, 1155, 1154, 1153, -1, + 1153, 1156, 1155, -1, 1156, 1153, 1152, -1, + 1152, 1157, 1156, -1, 1157, 1152, 1151, -1, + 1151, 1158, 1157, -1, 1158, 1151, 1150, -1, + 1150, 1159, 1158, -1, 1159, 1150, 1149, -1, + 1149, 1160, 1159, -1, 1160, 1149, 1148, -1, + 1148, 1161, 1160, -1, 1161, 1148, 1147, -1, + 1147, 1162, 1161, -1, 1162, 1147, 1146, -1, + 1146, 1163, 1162, -1, 1163, 1146, 1145, -1, + 1145, 1164, 1163, -1, 1164, 1145, 1144, -1, + 1144, 1165, 1164, -1, 1165, 1144, 1143, -1, + 1143, 1166, 1165, -1, 1166, 1143, 1142, -1, + 1167, 1142, 1141, -1, 1141, 1168, 1167, -1, + 1168, 1141, 1140, -1, 1140, 1169, 1168, -1, + 1169, 1140, 1139, -1, 1139, 1170, 1169, -1, + 1170, 1139, 1138, -1, 1138, 1171, 1170, -1, + 1171, 1138, 1137, -1, 1137, 1172, 1171, -1, + 1172, 1137, 1136, -1, 1136, 1173, 1172, -1, + 1173, 1136, 1135, -1, 1135, 1134, 1173, -1, + 1174, 1175, 1176, -1, 1177, 1178, 1179, -1, + 1177, 1180, 1178, -1, 1180, 1177, 1181, -1, + 1181, 1182, 1180, -1, 1182, 1181, 1183, -1, + 1183, 1184, 1182, -1, 1185, 1186, 1187, -1, + 1188, 1187, 1189, -1, 1189, 1190, 1188, -1, + 1190, 1189, 1191, -1, 1192, 1191, 1193, -1, + 1193, 1194, 1192, -1, 1194, 1193, 1195, -1, + 1195, 1196, 1194, -1, 1196, 1195, 1197, -1, + 1197, 1175, 1196, -1, 1175, 1197, 1198, -1, + 1198, 1176, 1175, -1, 1176, 1198, 1199, -1, + 1199, 1200, 1201, -1, 1200, 1199, 1198, -1, + 1198, 1202, 1200, -1, 1202, 1198, 1197, -1, + 1197, 1203, 1202, -1, 1203, 1197, 1195, -1, + 1195, 1204, 1203, -1, 1204, 1195, 1193, -1, + 1193, 1205, 1204, -1, 1205, 1193, 1191, -1, + 1191, 1206, 1205, -1, 1206, 1191, 1189, -1, + 1189, 1207, 1206, -1, 1207, 1189, 1187, -1, + 1187, 1208, 1207, -1, 1208, 1187, 1186, -1, + 1209, 1183, 1181, -1, 1181, 1210, 1209, -1, + 1210, 1181, 1177, -1, 1177, 1211, 1210, -1, + 1211, 1177, 1212, -1, 1211, 1212, 1173, -1, + 1211, 1173, 1134, -1, 1134, 1210, 1211, -1, + 1134, 1133, 1210, -1, 1133, 1131, 1210, -1, + 1210, 1131, 1130, -1, 1130, 1209, 1210, -1, + 1213, 1214, 1215, -1, 1208, 1215, 1216, -1, + 1216, 1207, 1208, -1, 1217, 1206, 1207, -1, + 1206, 1217, 1218, -1, 1218, 1205, 1206, -1, + 1205, 1218, 1219, -1, 1219, 1204, 1205, -1, + 1204, 1219, 1220, -1, 1220, 1203, 1204, -1, + 1221, 1202, 1203, -1, 1222, 1200, 1202, -1, + 1200, 1222, 1223, -1, 1223, 1201, 1200, -1, + 1201, 1223, 1224, -1, 1225, 1226, 1227, -1, + 1228, 1229, 1230, -1, 1228, 1231, 1229, -1, + 1231, 1228, 1232, -1, 1232, 1233, 1231, -1, + 1233, 1232, 1234, -1, 1234, 1235, 1233, -1, + 1235, 1234, 1236, -1, 1236, 1237, 1235, -1, + 1237, 1236, 1238, -1, 1238, 1239, 1237, -1, + 1239, 1238, 1240, -1, 1240, 1241, 1239, -1, + 1241, 1240, 1242, -1, 1242, 1243, 1241, -1, + 1243, 1242, 1244, -1, 1245, 1244, 1246, -1, + 1246, 1247, 1245, -1, 1247, 1246, 1248, -1, + 1248, 1249, 1247, -1, 1226, 1225, 1249, -1, + 1224, 1249, 1225, -1, 1249, 1224, 1223, -1, + 1223, 1247, 1249, -1, 1247, 1223, 1222, -1, + 1222, 1245, 1247, -1, 1220, 1241, 1243, -1, + 1241, 1220, 1219, -1, 1219, 1239, 1241, -1, + 1239, 1219, 1218, -1, 1218, 1237, 1239, -1, + 1237, 1218, 1217, -1, 1217, 1235, 1237, -1, + 1216, 1233, 1235, -1, 1233, 1216, 1215, -1, + 1215, 1231, 1233, -1, 1231, 1215, 1214, -1, + 1214, 1229, 1231, -1, 1229, 1130, 1128, -1, + 1250, 1229, 1128, -1, 1250, 1128, 1085, -1, + 1250, 1085, 1086, -1, 1086, 1229, 1250, -1, + 1086, 1230, 1229, -1, 1230, 1086, 971, -1, + 1230, 971, 970, -1, 970, 1228, 1230, -1, + 970, 972, 1228, -1, 972, 1251, 1228, -1, + 1251, 972, 973, -1, 1251, 973, 975, -1, + 975, 977, 1251, -1, 977, 1228, 1251, -1, + 977, 1232, 1228, -1, 1232, 977, 1252, -1, + 1252, 1234, 1232, -1, 1234, 1252, 1253, -1, + 1253, 1236, 1234, -1, 1236, 1253, 1254, -1, + 1254, 1238, 1236, -1, 1238, 1254, 1255, -1, + 1255, 1240, 1238, -1, 1240, 1255, 1256, -1, + 1256, 1242, 1240, -1, 1242, 1256, 1257, -1, + 1257, 1244, 1242, -1, 1244, 1257, 1258, -1, + 1258, 1246, 1244, -1, 1246, 1258, 1259, -1, + 1259, 1248, 1246, -1, 1248, 1259, 1260, -1, + 1226, 1260, 1261, -1, 1261, 1227, 1226, -1, + 1227, 1261, 1262, -1, 1263, 1264, 1265, -1, + 1265, 1266, 1267, -1, 1266, 1265, 1264, -1, + 1264, 1268, 1266, -1, 1268, 1264, 1269, -1, + 1269, 1270, 1268, -1, 1271, 1272, 1270, -1, + 1272, 1271, 1273, -1, 1273, 1274, 1272, -1, + 1274, 1273, 1275, -1, 1275, 1276, 1274, -1, + 1276, 1275, 1277, -1, 1277, 1278, 1276, -1, + 1278, 1277, 1279, -1, 1279, 1280, 1278, -1, + 1280, 1279, 1281, -1, 1281, 1282, 1280, -1, + 1282, 1281, 1283, -1, 1283, 1284, 1282, -1, + 1284, 1283, 1285, -1, 1285, 1286, 1284, -1, + 1287, 1288, 1289, -1, 1287, 1290, 1288, -1, + 1290, 1287, 1291, -1, 1291, 1292, 1290, -1, + 1292, 1291, 1293, -1, 1293, 1294, 1292, -1, + 1294, 1293, 1295, -1, 1295, 1296, 1294, -1, + 1296, 1295, 1297, -1, 1297, 1298, 1296, -1, + 1298, 1297, 1299, -1, 1299, 1300, 1298, -1, + 1300, 1299, 1301, -1, 1301, 1302, 1300, -1, + 1302, 1301, 1303, -1, 1303, 1304, 1302, -1, + 1304, 1303, 1305, -1, 1305, 1306, 1304, -1, + 1306, 1305, 1307, -1, 1307, 1308, 1306, -1, + 1308, 1307, 1309, -1, 1309, 1310, 1308, -1, + 1310, 1309, 1311, -1, 1311, 1312, 1310, -1, + 1313, 1314, 1315, -1, 1315, 1316, 1313, -1, + 1316, 1315, 1317, -1, 1317, 1318, 1316, -1, + 1318, 1317, 1319, -1, 1319, 1320, 1318, -1, + 1320, 1319, 1321, -1, 1321, 1322, 1320, -1, + 1322, 1321, 1323, -1, 1323, 1324, 1322, -1, + 1324, 1323, 1325, -1, 1325, 1326, 1324, -1, + 1326, 1325, 1327, -1, 1327, 1328, 1326, -1, + 1329, 1328, 1286, -1, 1329, 1326, 1328, -1, + 1330, 1331, 1332, -1, 1331, 1330, 1326, -1, + 1331, 1326, 1329, -1, 1329, 1286, 1331, -1, + 1286, 1332, 1331, -1, 1286, 1285, 1332, -1, + 1333, 1334, 1332, -1, 1332, 1335, 1333, -1, + 1335, 1332, 1285, -1, 1285, 1336, 1335, -1, + 1336, 1285, 1283, -1, 1283, 1337, 1336, -1, + 1337, 1283, 1281, -1, 1338, 1281, 1279, -1, + 1279, 1339, 1338, -1, 1339, 1279, 1277, -1, + 1277, 1340, 1339, -1, 1340, 1277, 1275, -1, + 1275, 1341, 1340, -1, 1341, 1275, 1273, -1, + 1273, 1342, 1341, -1, 1342, 1273, 1271, -1, + 1271, 1343, 1342, -1, 1269, 1344, 1343, -1, + 1344, 1269, 1264, -1, 1264, 1263, 1344, -1, + 1262, 1344, 1263, -1, 1344, 1262, 1261, -1, + 1261, 1343, 1344, -1, 1343, 1261, 1260, -1, + 1260, 1342, 1343, -1, 1342, 1260, 1259, -1, + 1259, 1341, 1342, -1, 1341, 1259, 1258, -1, + 1258, 1340, 1341, -1, 1340, 1258, 1257, -1, + 1257, 1339, 1340, -1, 1339, 1257, 1256, -1, + 1256, 1338, 1339, -1, 1338, 1256, 1255, -1, + 1337, 1255, 1254, -1, 1254, 1336, 1337, -1, + 1336, 1254, 1253, -1, 1253, 1335, 1336, -1, + 1335, 1253, 1252, -1, 1252, 1333, 1335, -1, + 1333, 1252, 977, -1, 977, 976, 1333, -1, + 1345, 1333, 976, -1, 976, 978, 1345, -1, + 978, 1038, 1345, -1, 1346, 1345, 1038, -1, + 1346, 1333, 1345, -1, 1346, 1334, 1333, -1, + 1334, 1346, 1038, -1, 1334, 1038, 1040, -1, + 1040, 1332, 1334, -1, 1040, 1039, 1332, -1, + 1039, 1330, 1332, -1, 1039, 1041, 1330, -1, + 1041, 1326, 1330, -1, 1041, 1324, 1326, -1, + 1324, 1041, 1042, -1, 1042, 1322, 1324, -1, + 1322, 1042, 1043, -1, 1043, 1320, 1322, -1, + 1320, 1043, 1044, -1, 1044, 1318, 1320, -1, + 1318, 1044, 1045, -1, 1045, 1316, 1318, -1, + 1316, 1045, 1046, -1, 1046, 1313, 1316, -1, + 1312, 1047, 1048, -1, 1048, 1310, 1312, -1, + 1310, 1048, 1049, -1, 1049, 1308, 1310, -1, + 1308, 1049, 1050, -1, 1050, 1306, 1308, -1, + 1306, 1050, 1051, -1, 1051, 1304, 1306, -1, + 1304, 1051, 1052, -1, 1052, 1302, 1304, -1, + 1302, 1052, 1053, -1, 1053, 1300, 1302, -1, + 1300, 1053, 1054, -1, 1054, 1298, 1300, -1, + 1298, 1054, 1055, -1, 1055, 1296, 1298, -1, + 1296, 1055, 1056, -1, 1056, 1294, 1296, -1, + 1294, 1056, 1057, -1, 1057, 1292, 1294, -1, + 1292, 1057, 1058, -1, 1058, 1290, 1292, -1, + 1290, 1058, 1059, -1, 1059, 1288, 1290, -1, + 1288, 1059, 1060, -1, 1060, 1347, 1288, -1, + 1347, 1060, 1061, -1, 1348, 1288, 1347, -1, + 1348, 1289, 1288, -1, 1349, 1287, 1289, -1, + 1349, 1350, 1287, -1, 1351, 1352, 1353, -1, + 1351, 1353, 1354, -1, 1355, 1354, 1353, -1, + 1353, 1356, 1355, -1, 1356, 1353, 1357, -1, + 1357, 1358, 1356, -1, 1358, 1357, 1359, -1, + 1359, 1360, 1358, -1, 1360, 1359, 1361, -1, + 1361, 1362, 1360, -1, 1362, 1361, 1363, -1, + 1363, 1364, 1362, -1, 1364, 1363, 1365, -1, + 1365, 1366, 1364, -1, 1366, 1365, 1367, -1, + 1367, 1368, 1366, -1, 1369, 1370, 1371, -1, + 1370, 1369, 1372, -1, 1372, 1373, 1370, -1, + 1373, 1372, 1374, -1, 1374, 1375, 1373, -1, + 1375, 1374, 1376, -1, 1376, 1377, 1375, -1, + 1377, 1376, 1378, -1, 1378, 1379, 1377, -1, + 1379, 1378, 1380, -1, 1380, 1381, 1379, -1, + 1381, 1380, 1382, -1, 1382, 1383, 1381, -1, + 1383, 1382, 1384, -1, 1384, 1385, 1383, -1, + 1385, 1384, 1386, -1, 1386, 1387, 1385, -1, + 1387, 1386, 1388, -1, 1388, 1389, 1387, -1, + 1389, 1388, 1390, -1, 1390, 1391, 1389, -1, + 1392, 1393, 1391, -1, 1393, 1394, 1391, -1, + 1393, 1395, 1394, -1, 1393, 1392, 1395, -1, + 1392, 1396, 1395, -1, 1392, 1391, 1396, -1, + 1397, 1396, 1391, -1, 1391, 1390, 1397, -1, + 1398, 1399, 1400, -1, 1401, 1400, 1399, -1, + 1399, 1402, 1401, -1, 1403, 1404, 1405, -1, + 1404, 1403, 1406, -1, 1406, 1403, 1401, -1, + 1401, 1407, 1406, -1, 1407, 1401, 1402, -1, + 1402, 1408, 1407, -1, 1408, 1402, 1409, -1, + 1409, 1410, 1408, -1, 1410, 1409, 1411, -1, + 1411, 1412, 1410, -1, 1412, 1411, 1413, -1, + 1413, 1414, 1412, -1, 1414, 1413, 1415, -1, + 1415, 1416, 1414, -1, 1416, 1415, 1417, -1, + 1418, 1417, 1419, -1, 1419, 1420, 1418, -1, + 1420, 1419, 1421, -1, 1421, 1422, 1420, -1, + 1422, 1421, 1423, -1, 1423, 1424, 1422, -1, + 1424, 1423, 1425, -1, 1425, 1426, 1424, -1, + 1426, 1425, 1427, -1, 1427, 1428, 1426, -1, + 1428, 1427, 1429, -1, 1429, 1430, 1428, -1, + 1430, 1429, 1431, -1, 1431, 1432, 1430, -1, + 1432, 1431, 1433, -1, 1433, 1434, 1432, -1, + 1435, 1436, 1437, -1, 1437, 1438, 1435, -1, + 1438, 1437, 1439, -1, 1439, 1440, 1438, -1, + 1441, 1442, 1440, -1, 1442, 1441, 1443, -1, + 1443, 1444, 1442, -1, 1445, 1442, 1444, -1, + 1445, 1446, 1442, -1, 1447, 1442, 1446, -1, + 1447, 1440, 1442, -1, 1440, 1447, 1448, -1, + 1448, 1438, 1440, -1, 1438, 1448, 1449, -1, + 1449, 1435, 1438, -1, 1434, 1450, 1451, -1, + 1451, 1432, 1434, -1, 1432, 1451, 1452, -1, + 1452, 1430, 1432, -1, 1430, 1452, 1453, -1, + 1453, 1428, 1430, -1, 1428, 1453, 1454, -1, + 1454, 1426, 1428, -1, 1426, 1454, 1455, -1, + 1455, 1424, 1426, -1, 1424, 1455, 1456, -1, + 1456, 1422, 1424, -1, 1422, 1456, 1457, -1, + 1457, 1420, 1422, -1, 1420, 1457, 1458, -1, + 1458, 1418, 1420, -1, 1418, 1458, 1459, -1, + 1416, 1459, 1460, -1, 1460, 1414, 1416, -1, + 1414, 1460, 1461, -1, 1461, 1412, 1414, -1, + 1412, 1461, 1462, -1, 1462, 1410, 1412, -1, + 1410, 1462, 1463, -1, 1463, 1408, 1410, -1, + 1408, 1463, 1464, -1, 1464, 1407, 1408, -1, + 1407, 1464, 1465, -1, 1465, 1406, 1407, -1, + 1406, 1465, 1466, -1, 1467, 1468, 1469, -1, + 1469, 1468, 1470, -1, 1469, 1470, 1471, -1, + 1471, 1472, 1469, -1, 1472, 1471, 1473, -1, + 1473, 1474, 1472, -1, 1474, 1473, 1475, -1, + 1475, 1476, 1474, -1, 1476, 1475, 1477, -1, + 1477, 1478, 1476, -1, 1478, 1477, 1479, -1, + 1479, 1480, 1478, -1, 1480, 1479, 1481, -1, + 1481, 1482, 1480, -1, 1482, 1481, 1483, -1, + 1483, 1484, 1482, -1, 1484, 1483, 1485, -1, + 1485, 1486, 1484, -1, 1486, 1485, 1487, -1, + 1487, 1488, 1486, -1, 1488, 1487, 1489, -1, + 1489, 1490, 1488, -1, 1490, 1489, 1491, -1, + 1490, 1491, 1492, -1, 1493, 1494, 1495, -1, + 1493, 1496, 1494, -1, 1497, 1498, 1499, -1, + 1499, 1500, 1501, -1, 1500, 1499, 1498, -1, + 1498, 1502, 1500, -1, 1502, 1498, 1503, -1, + 1503, 1504, 1502, -1, 1504, 1503, 1505, -1, + 1505, 1506, 1504, -1, 1506, 1505, 1507, -1, + 1506, 1507, 1508, -1, 1509, 1508, 1507, -1, + 1509, 1507, 1510, -1, 1511, 1510, 1507, -1, + 1507, 1512, 1511, -1, 1512, 1507, 1505, -1, + 1505, 1513, 1512, -1, 1513, 1505, 1503, -1, + 1503, 1514, 1513, -1, 1514, 1503, 1498, -1, + 1498, 1497, 1514, -1, 1515, 1497, 1516, -1, + 1497, 1515, 1517, -1, 1497, 1517, 1518, -1, + 1518, 1514, 1497, -1, 1514, 1518, 1519, -1, + 1519, 1513, 1514, -1, 1513, 1519, 1520, -1, + 1520, 1512, 1513, -1, 1512, 1520, 1521, -1, + 1521, 1511, 1512, -1, 1511, 1521, 1494, -1, + 1511, 1494, 1496, -1, 1496, 1510, 1511, -1, + 1522, 1506, 1508, -1, 1522, 1523, 1506, -1, + 1524, 1525, 1526, -1, 1526, 1527, 1524, -1, + 1528, 1524, 1527, -1, 1528, 1529, 1524, -1, + 1530, 1492, 1491, -1, 1530, 1491, 1531, -1, + 1532, 1533, 1534, -1, 1532, 1531, 1533, -1, + 1533, 1531, 1491, -1, 1491, 1535, 1533, -1, + 1535, 1491, 1489, -1, 1536, 1489, 1487, -1, + 1487, 1537, 1536, -1, 1537, 1487, 1485, -1, + 1538, 1485, 1483, -1, 1483, 1539, 1538, -1, + 1539, 1483, 1481, -1, 1540, 1481, 1479, -1, + 1479, 1541, 1540, -1, 1541, 1479, 1477, -1, + 1477, 1542, 1541, -1, 1542, 1477, 1475, -1, + 1475, 1543, 1542, -1, 1543, 1475, 1473, -1, + 1473, 1544, 1543, -1, 1544, 1473, 1471, -1, + 1471, 1545, 1544, -1, 1545, 1471, 1470, -1, + 1470, 1546, 1545, -1, 1547, 1548, 1549, -1, + 1550, 1547, 1551, -1, 1551, 1552, 1550, -1, + 1552, 1551, 1553, -1, 1553, 1554, 1552, -1, + 1555, 1556, 1554, -1, 1556, 1555, 1557, -1, + 1557, 1558, 1556, -1, 1558, 1557, 1559, -1, + 1559, 1560, 1558, -1, 1560, 1559, 1561, -1, + 1561, 1562, 1560, -1, 1562, 1561, 1563, -1, + 1563, 1564, 1562, -1, 1564, 1563, 1565, -1, + 1565, 1566, 1564, -1, 1566, 1565, 1567, -1, + 1567, 1568, 1566, -1, 1568, 1567, 1569, -1, + 1569, 1570, 1568, -1, 1570, 1569, 1571, -1, + 1571, 1572, 1570, -1, 1572, 1571, 1573, -1, + 1573, 1574, 1572, -1, 1574, 1573, 1575, -1, + 1575, 1576, 1574, -1, 1577, 1578, 1579, -1, + 1580, 1581, 1582, -1, 1581, 1580, 1583, -1, + 1578, 1583, 1580, -1, 1580, 1579, 1578, -1, + 1580, 1582, 1579, -1, 1584, 1585, 1586, -1, + 1587, 1588, 1586, -1, 1589, 1590, 1591, -1, + 1591, 1592, 1589, -1, 1591, 1593, 1592, -1, + 1593, 1591, 1594, -1, 1594, 1595, 1593, -1, + 1595, 1594, 1596, -1, 1595, 1596, 1597, -1, + 1598, 1597, 1596, -1, 1597, 1598, 1588, -1, + 1597, 1588, 1587, -1, 1587, 1595, 1597, -1, + 1587, 1586, 1595, -1, 1595, 1586, 1585, -1, + 1585, 1593, 1595, -1, 1593, 1585, 1599, -1, + 1599, 1592, 1593, -1, 1592, 1599, 1600, -1, + 1582, 1600, 1601, -1, 1601, 1579, 1582, -1, + 1579, 1601, 1602, -1, 1602, 1603, 1579, -1, + 1603, 1602, 1576, -1, 1576, 1575, 1603, -1, + 1604, 1605, 1603, -1, 1603, 1606, 1604, -1, + 1606, 1603, 1575, -1, 1575, 1546, 1606, -1, + 1546, 1575, 1573, -1, 1573, 1545, 1546, -1, + 1545, 1573, 1571, -1, 1571, 1544, 1545, -1, + 1544, 1571, 1569, -1, 1569, 1543, 1544, -1, + 1543, 1569, 1567, -1, 1567, 1542, 1543, -1, + 1542, 1567, 1565, -1, 1565, 1541, 1542, -1, + 1541, 1565, 1563, -1, 1563, 1540, 1541, -1, + 1540, 1563, 1561, -1, 1539, 1561, 1559, -1, + 1559, 1538, 1539, -1, 1538, 1559, 1557, -1, + 1537, 1557, 1555, -1, 1555, 1536, 1537, -1, + 1535, 1553, 1551, -1, 1551, 1533, 1535, -1, + 1533, 1551, 1547, -1, 1547, 1534, 1533, -1, + 1534, 1547, 1549, -1, 1607, 1549, 1548, -1, + 1607, 1548, 1608, -1, 1609, 1610, 1611, -1, + 1609, 1608, 1610, -1, 1610, 1608, 1548, -1, + 1548, 1612, 1610, -1, 1613, 1550, 1552, -1, + 1552, 1614, 1613, -1, 1614, 1552, 1554, -1, + 1554, 1615, 1614, -1, 1615, 1554, 1556, -1, + 1556, 1616, 1615, -1, 1616, 1556, 1558, -1, + 1558, 1617, 1616, -1, 1617, 1558, 1560, -1, + 1560, 1618, 1617, -1, 1618, 1560, 1562, -1, + 1562, 1619, 1618, -1, 1619, 1562, 1564, -1, + 1564, 1620, 1619, -1, 1620, 1564, 1566, -1, + 1566, 1621, 1620, -1, 1621, 1566, 1568, -1, + 1568, 1622, 1621, -1, 1622, 1568, 1570, -1, + 1570, 1623, 1622, -1, 1623, 1570, 1572, -1, + 1572, 1624, 1623, -1, 1624, 1572, 1574, -1, + 1574, 1625, 1624, -1, 1625, 1574, 1576, -1, + 1576, 1626, 1625, -1, 1626, 1576, 1602, -1, + 1602, 1627, 1626, -1, 1627, 1602, 1601, -1, + 1601, 1628, 1627, -1, 1628, 1601, 1600, -1, + 1600, 1629, 1628, -1, 1629, 1600, 1599, -1, + 1599, 1630, 1629, -1, 1630, 1599, 1585, -1, + 1630, 1585, 1631, -1, 1632, 1630, 1631, -1, + 1632, 1633, 1630, -1, 1630, 1633, 1466, -1, + 1466, 1629, 1630, -1, 1629, 1466, 1465, -1, + 1465, 1628, 1629, -1, 1628, 1465, 1464, -1, + 1464, 1627, 1628, -1, 1627, 1464, 1463, -1, + 1463, 1626, 1627, -1, 1626, 1463, 1462, -1, + 1462, 1625, 1626, -1, 1625, 1462, 1461, -1, + 1461, 1624, 1625, -1, 1624, 1461, 1460, -1, + 1460, 1623, 1624, -1, 1623, 1460, 1459, -1, + 1459, 1622, 1623, -1, 1622, 1459, 1458, -1, + 1458, 1621, 1622, -1, 1621, 1458, 1457, -1, + 1457, 1620, 1621, -1, 1620, 1457, 1456, -1, + 1456, 1619, 1620, -1, 1619, 1456, 1455, -1, + 1455, 1618, 1619, -1, 1618, 1455, 1454, -1, + 1454, 1617, 1618, -1, 1617, 1454, 1453, -1, + 1453, 1616, 1617, -1, 1616, 1453, 1452, -1, + 1452, 1615, 1616, -1, 1615, 1452, 1451, -1, + 1451, 1614, 1615, -1, 1614, 1451, 1450, -1, + 1450, 1613, 1614, -1, 1612, 1449, 1448, -1, + 1448, 1610, 1612, -1, 1610, 1448, 1447, -1, + 1447, 1611, 1610, -1, 1611, 1447, 1446, -1, + 1634, 1444, 1443, -1, 1443, 1635, 1634, -1, + 1443, 1636, 1635, -1, 1636, 1443, 1441, -1, + 1441, 1637, 1636, -1, 1439, 1638, 1637, -1, + 1638, 1439, 1437, -1, 1437, 1639, 1638, -1, + 1639, 1437, 1436, -1, 1436, 1640, 1639, -1, + 1641, 1433, 1431, -1, 1431, 1642, 1641, -1, + 1642, 1431, 1429, -1, 1429, 1643, 1642, -1, + 1643, 1429, 1427, -1, 1427, 1644, 1643, -1, + 1644, 1427, 1425, -1, 1425, 1645, 1644, -1, + 1645, 1425, 1423, -1, 1423, 1646, 1645, -1, + 1646, 1423, 1421, -1, 1421, 1647, 1646, -1, + 1647, 1421, 1419, -1, 1419, 1648, 1647, -1, + 1648, 1419, 1417, -1, 1417, 1649, 1648, -1, + 1649, 1417, 1415, -1, 1415, 1650, 1649, -1, + 1650, 1415, 1413, -1, 1413, 1651, 1650, -1, + 1651, 1413, 1411, -1, 1411, 1652, 1651, -1, + 1652, 1411, 1409, -1, 1409, 1653, 1652, -1, + 1653, 1409, 1402, -1, 1397, 1399, 1654, -1, + 1653, 1397, 1390, -1, 1390, 1652, 1653, -1, + 1652, 1390, 1388, -1, 1388, 1651, 1652, -1, + 1651, 1388, 1386, -1, 1386, 1650, 1651, -1, + 1650, 1386, 1384, -1, 1384, 1649, 1650, -1, + 1649, 1384, 1382, -1, 1382, 1648, 1649, -1, + 1648, 1382, 1380, -1, 1380, 1647, 1648, -1, + 1647, 1380, 1378, -1, 1378, 1646, 1647, -1, + 1646, 1378, 1376, -1, 1376, 1645, 1646, -1, + 1645, 1376, 1374, -1, 1374, 1644, 1645, -1, + 1644, 1374, 1372, -1, 1372, 1643, 1644, -1, + 1643, 1372, 1369, -1, 1369, 1642, 1643, -1, + 1655, 1641, 1642, -1, 1640, 1367, 1365, -1, + 1365, 1639, 1640, -1, 1639, 1365, 1363, -1, + 1363, 1638, 1639, -1, 1638, 1363, 1361, -1, + 1361, 1637, 1638, -1, 1637, 1361, 1359, -1, + 1359, 1636, 1637, -1, 1636, 1359, 1357, -1, + 1357, 1635, 1636, -1, 1635, 1357, 1353, -1, + 1635, 1353, 1352, -1, 1656, 1635, 1352, -1, + 1656, 1634, 1635, -1, 1657, 1354, 1355, -1, + 1355, 1658, 1657, -1, 1355, 1659, 1658, -1, + 1659, 1355, 1356, -1, 1356, 1660, 1659, -1, + 1660, 1356, 1358, -1, 1358, 1661, 1660, -1, + 1661, 1358, 1360, -1, 1662, 1360, 1362, -1, + 1362, 1663, 1662, -1, 1663, 1362, 1364, -1, + 1364, 1664, 1663, -1, 1664, 1364, 1366, -1, + 1366, 1665, 1664, -1, 1665, 1366, 1368, -1, + 1368, 1666, 1665, -1, 1667, 1371, 1370, -1, + 1370, 1668, 1667, -1, 1668, 1370, 1373, -1, + 1373, 1669, 1668, -1, 1669, 1373, 1375, -1, + 1375, 1670, 1669, -1, 1670, 1375, 1377, -1, + 1377, 1671, 1670, -1, 1671, 1377, 1379, -1, + 1379, 1672, 1671, -1, 1672, 1379, 1381, -1, + 1381, 1673, 1672, -1, 1673, 1381, 1383, -1, + 1383, 1674, 1673, -1, 1674, 1383, 1385, -1, + 1385, 1675, 1674, -1, 1675, 1385, 1387, -1, + 1387, 1676, 1675, -1, 1676, 1387, 1389, -1, + 1389, 1677, 1676, -1, 1677, 1389, 1391, -1, + 1677, 1391, 1394, -1, 1678, 1677, 1394, -1, + 1678, 1679, 1677, -1, 1677, 1679, 969, -1, + 969, 1676, 1677, -1, 1676, 969, 967, -1, + 967, 1675, 1676, -1, 1675, 967, 965, -1, + 965, 1674, 1675, -1, 1674, 965, 963, -1, + 963, 1673, 1674, -1, 1673, 963, 961, -1, + 961, 1672, 1673, -1, 1672, 961, 959, -1, + 959, 1671, 1672, -1, 1671, 959, 957, -1, + 957, 1670, 1671, -1, 1670, 957, 955, -1, + 955, 1669, 1670, -1, 1669, 955, 953, -1, + 953, 1668, 1669, -1, 1668, 953, 952, -1, + 952, 1667, 1668, -1, 1666, 949, 947, -1, + 947, 1665, 1666, -1, 1665, 947, 945, -1, + 945, 1664, 1665, -1, 1664, 945, 943, -1, + 943, 1663, 1664, -1, 1663, 943, 941, -1, + 941, 1662, 1663, -1, 1662, 941, 939, -1, + 1661, 939, 937, -1, 937, 1660, 1661, -1, + 1660, 937, 935, -1, 935, 1659, 1660, -1, + 1659, 935, 933, -1, 933, 1658, 1659, -1, + 1658, 933, 931, -1, 1658, 931, 1680, -1, + 1681, 1658, 1680, -1, 1681, 1657, 1658, -1, + 1682, 1680, 931, -1, 1682, 931, 930, -1, + 1350, 930, 929, -1, 929, 1287, 1350, -1, + 929, 1291, 1287, -1, 1291, 929, 932, -1, + 932, 1293, 1291, -1, 1293, 932, 934, -1, + 934, 1295, 1293, -1, 1295, 934, 936, -1, + 936, 1297, 1295, -1, 1297, 936, 938, -1, + 938, 1299, 1297, -1, 1299, 938, 940, -1, + 940, 1301, 1299, -1, 1301, 940, 942, -1, + 942, 1303, 1301, -1, 1303, 942, 944, -1, + 944, 1305, 1303, -1, 1305, 944, 946, -1, + 946, 1307, 1305, -1, 1307, 946, 948, -1, + 948, 1309, 1307, -1, 1309, 948, 950, -1, + 950, 1311, 1309, -1, 1314, 951, 954, -1, + 954, 1315, 1314, -1, 1315, 954, 956, -1, + 956, 1317, 1315, -1, 1317, 956, 958, -1, + 958, 1319, 1317, -1, 1319, 958, 960, -1, + 960, 1321, 1319, -1, 1321, 960, 962, -1, + 962, 1323, 1321, -1, 1323, 962, 964, -1, + 964, 1325, 1323, -1, 1325, 964, 966, -1, + 966, 1327, 1325, -1, 1327, 966, 968, -1, + 1327, 968, 1683, -1, 1684, 1683, 968, -1, + 1683, 1684, 1685, -1, 1683, 1685, 1686, -1, + 1686, 1327, 1683, -1, 1686, 1328, 1327, -1, + 1686, 1685, 1328, -1, 1685, 1286, 1328, -1, + 1685, 1284, 1286, -1, 1284, 1685, 1687, -1, + 1687, 1282, 1284, -1, 1282, 1687, 1688, -1, + 1688, 1280, 1282, -1, 1280, 1688, 1689, -1, + 1689, 1278, 1280, -1, 1278, 1689, 1690, -1, + 1690, 1276, 1278, -1, 1276, 1690, 1691, -1, + 1691, 1274, 1276, -1, 1274, 1691, 1692, -1, + 1692, 1272, 1274, -1, 1272, 1692, 1693, -1, + 1693, 1270, 1272, -1, 1270, 1693, 1694, -1, + 1694, 1268, 1270, -1, 1268, 1694, 1695, -1, + 1695, 1266, 1268, -1, 1266, 1695, 1696, -1, + 1696, 1267, 1266, -1, 1267, 1696, 1697, -1, + 1698, 1699, 1700, -1, 1701, 1702, 1703, -1, + 1703, 1704, 1701, -1, 1704, 1703, 1705, -1, + 1705, 1706, 1704, -1, 1706, 1705, 1707, -1, + 1707, 1708, 1706, -1, 1708, 1707, 1709, -1, + 1709, 1710, 1708, -1, 1710, 1709, 1711, -1, + 1711, 1712, 1710, -1, 1712, 1711, 1713, -1, + 1713, 1714, 1712, -1, 1714, 1713, 1715, -1, + 1715, 1716, 1714, -1, 1716, 1715, 1717, -1, + 1717, 1718, 1716, -1, 1718, 1717, 1719, -1, + 1719, 1720, 1718, -1, 1720, 1719, 1721, -1, + 1721, 1722, 1720, -1, 1722, 1721, 1699, -1, + 1699, 1698, 1722, -1, 1697, 1722, 1698, -1, + 1722, 1697, 1696, -1, 1696, 1720, 1722, -1, + 1720, 1696, 1695, -1, 1695, 1718, 1720, -1, + 1718, 1695, 1694, -1, 1694, 1716, 1718, -1, + 1716, 1694, 1693, -1, 1693, 1714, 1716, -1, + 1714, 1693, 1692, -1, 1692, 1712, 1714, -1, + 1712, 1692, 1691, -1, 1691, 1710, 1712, -1, + 1710, 1691, 1690, -1, 1690, 1708, 1710, -1, + 1708, 1690, 1689, -1, 1689, 1706, 1708, -1, + 1706, 1689, 1688, -1, 1688, 1704, 1706, -1, + 1704, 1688, 1687, -1, 1687, 1701, 1704, -1, + 1701, 1687, 1685, -1, 1701, 1685, 1684, -1, + 1684, 1723, 1701, -1, 1684, 968, 1723, -1, + 968, 969, 1723, -1, 1724, 1723, 969, -1, + 1724, 1701, 1723, -1, 1724, 1702, 1701, -1, + 1702, 1724, 969, -1, 1702, 969, 1679, -1, + 1679, 1703, 1702, -1, 1679, 1678, 1703, -1, + 1678, 1394, 1703, -1, 1703, 1394, 1395, -1, + 1395, 1705, 1703, -1, 1705, 1395, 1725, -1, + 1725, 1707, 1705, -1, 1707, 1725, 1726, -1, + 1726, 1709, 1707, -1, 1709, 1726, 1727, -1, + 1727, 1711, 1709, -1, 1711, 1727, 1728, -1, + 1728, 1713, 1711, -1, 1713, 1728, 1729, -1, + 1729, 1715, 1713, -1, 1715, 1729, 1730, -1, + 1730, 1717, 1715, -1, 1717, 1730, 1731, -1, + 1731, 1719, 1717, -1, 1719, 1731, 1732, -1, + 1732, 1721, 1719, -1, 1721, 1732, 1733, -1, + 1733, 1699, 1721, -1, 1699, 1733, 1734, -1, + 1734, 1700, 1699, -1, 1700, 1734, 1735, -1, + 1736, 1737, 1738, -1, 1739, 1740, 1741, -1, + 1739, 1742, 1740, -1, 1742, 1739, 1743, -1, + 1743, 1744, 1742, -1, 1744, 1743, 1745, -1, + 1745, 1746, 1744, -1, 1746, 1745, 1747, -1, + 1747, 1748, 1746, -1, 1748, 1747, 1749, -1, + 1749, 1750, 1748, -1, 1750, 1749, 1751, -1, + 1751, 1752, 1750, -1, 1752, 1751, 1753, -1, + 1753, 1754, 1752, -1, 1754, 1753, 1755, -1, + 1755, 1756, 1754, -1, 1756, 1755, 1757, -1, + 1757, 1758, 1756, -1, 1758, 1757, 1759, -1, + 1759, 1760, 1758, -1, 1760, 1759, 1737, -1, + 1737, 1736, 1760, -1, 1735, 1760, 1736, -1, + 1760, 1735, 1734, -1, 1734, 1758, 1760, -1, + 1758, 1734, 1733, -1, 1733, 1756, 1758, -1, + 1756, 1733, 1732, -1, 1732, 1754, 1756, -1, + 1754, 1732, 1731, -1, 1731, 1752, 1754, -1, + 1752, 1731, 1730, -1, 1730, 1750, 1752, -1, + 1750, 1730, 1729, -1, 1729, 1748, 1750, -1, + 1748, 1729, 1728, -1, 1728, 1746, 1748, -1, + 1746, 1728, 1727, -1, 1727, 1744, 1746, -1, + 1744, 1727, 1726, -1, 1726, 1742, 1744, -1, + 1742, 1726, 1725, -1, 1725, 1740, 1742, -1, + 1740, 1725, 1395, -1, 1740, 1395, 1396, -1, + 1761, 1740, 1396, -1, 1761, 1396, 1397, -1, + 1761, 1397, 1654, -1, 1654, 1740, 1761, -1, + 1654, 1741, 1740, -1, 1741, 1654, 1399, -1, + 1741, 1399, 1398, -1, 1398, 1739, 1741, -1, + 1398, 1400, 1739, -1, 1400, 1762, 1739, -1, + 1762, 1400, 1401, -1, 1762, 1401, 1403, -1, + 1403, 1405, 1762, -1, 1405, 1739, 1762, -1, + 1405, 1743, 1739, -1, 1743, 1405, 1763, -1, + 1763, 1745, 1743, -1, 1745, 1763, 1764, -1, + 1764, 1747, 1745, -1, 1747, 1764, 1765, -1, + 1765, 1749, 1747, -1, 1749, 1765, 1766, -1, + 1766, 1751, 1749, -1, 1751, 1766, 1767, -1, + 1767, 1753, 1751, -1, 1753, 1767, 1768, -1, + 1768, 1755, 1753, -1, 1755, 1768, 1769, -1, + 1769, 1757, 1755, -1, 1757, 1769, 1770, -1, + 1770, 1759, 1757, -1, 1759, 1770, 1771, -1, + 1771, 1737, 1759, -1, 1737, 1771, 1772, -1, + 1772, 1738, 1737, -1, 1738, 1772, 1773, -1, + 1774, 1775, 1776, -1, 1776, 1777, 1778, -1, + 1777, 1776, 1775, -1, 1775, 1779, 1777, -1, + 1779, 1775, 1780, -1, 1780, 1781, 1779, -1, + 1781, 1780, 1782, -1, 1782, 1783, 1781, -1, + 1783, 1782, 1784, -1, 1784, 1785, 1783, -1, + 1785, 1784, 1786, -1, 1786, 1787, 1785, -1, + 1787, 1786, 1788, -1, 1788, 1789, 1787, -1, + 1789, 1788, 1790, -1, 1790, 1791, 1789, -1, + 1791, 1790, 1792, -1, 1792, 1793, 1791, -1, + 1793, 1792, 1794, -1, 1794, 1795, 1793, -1, + 1795, 1794, 1796, -1, 1796, 1797, 1795, -1, + 1797, 1798, 1799, -1, 1797, 1796, 1798, -1, + 1800, 1801, 1798, -1, 1798, 1802, 1800, -1, + 1802, 1798, 1796, -1, 1796, 1803, 1802, -1, + 1803, 1796, 1794, -1, 1794, 1804, 1803, -1, + 1804, 1794, 1792, -1, 1792, 1805, 1804, -1, + 1805, 1792, 1790, -1, 1806, 1790, 1788, -1, + 1788, 1807, 1806, -1, 1807, 1788, 1786, -1, + 1786, 1808, 1807, -1, 1808, 1786, 1784, -1, + 1784, 1809, 1808, -1, 1809, 1784, 1782, -1, + 1782, 1810, 1809, -1, 1810, 1782, 1780, -1, + 1780, 1811, 1810, -1, 1811, 1780, 1775, -1, + 1775, 1774, 1811, -1, 1773, 1811, 1774, -1, + 1811, 1773, 1772, -1, 1772, 1810, 1811, -1, + 1810, 1772, 1771, -1, 1771, 1809, 1810, -1, + 1809, 1771, 1770, -1, 1770, 1808, 1809, -1, + 1808, 1770, 1769, -1, 1769, 1807, 1808, -1, + 1807, 1769, 1768, -1, 1768, 1806, 1807, -1, + 1806, 1768, 1767, -1, 1805, 1767, 1766, -1, + 1766, 1804, 1805, -1, 1804, 1766, 1765, -1, + 1765, 1803, 1804, -1, 1803, 1765, 1764, -1, + 1764, 1802, 1803, -1, 1802, 1764, 1763, -1, + 1763, 1800, 1802, -1, 1800, 1763, 1405, -1, + 1405, 1404, 1800, -1, 1812, 1800, 1404, -1, + 1404, 1406, 1812, -1, 1406, 1466, 1812, -1, + 1813, 1812, 1466, -1, 1813, 1800, 1812, -1, + 1813, 1801, 1800, -1, 1801, 1813, 1466, -1, + 1801, 1466, 1633, -1, 1633, 1798, 1801, -1, + 1633, 1632, 1798, -1, 1632, 1631, 1798, -1, + 1631, 1799, 1798, -1, 1799, 1631, 1585, -1, + 1799, 1585, 1584, -1, 1584, 1797, 1799, -1, + 1584, 1586, 1797, -1, 1797, 1586, 1588, -1, + 1588, 1795, 1797, -1, 1814, 1793, 1795, -1, + 1815, 1791, 1793, -1, 1791, 1815, 1816, -1, + 1816, 1789, 1791, -1, 1789, 1816, 1817, -1, + 1817, 1787, 1789, -1, 1818, 1785, 1787, -1, + 1785, 1818, 1819, -1, 1819, 1783, 1785, -1, + 1783, 1819, 1820, -1, 1820, 1781, 1783, -1, + 1781, 1820, 1821, -1, 1821, 1779, 1781, -1, + 1779, 1821, 1822, -1, 1822, 1777, 1779, -1, + 1777, 1822, 1823, -1, 1823, 1778, 1777, -1, + 1778, 1823, 1824, -1, 1825, 1826, 1827, -1, + 1828, 1829, 1830, -1, 1831, 1832, 1833, -1, + 1834, 1835, 1836, -1, 1834, 1837, 1835, -1, + 1838, 1839, 1837, -1, 1839, 1838, 1840, -1, + 1840, 1841, 1839, -1, 1841, 1840, 1842, -1, + 1842, 1843, 1841, -1, 1843, 1842, 1844, -1, + 1845, 1844, 1846, -1, 1846, 1847, 1845, -1, + 1847, 1846, 1848, -1, 1848, 1849, 1847, -1, + 1849, 1848, 1850, -1, 1850, 1851, 1849, -1, + 1851, 1850, 1852, -1, 1852, 1853, 1851, -1, + 1853, 1852, 1854, -1, 1854, 1832, 1853, -1, + 1832, 1854, 1855, -1, 1855, 1833, 1832, -1, + 1833, 1855, 1856, -1, 1857, 1858, 1859, -1, + 1860, 1861, 1862, -1, 1860, 1863, 1861, -1, + 1864, 1865, 1866, -1, 1866, 1865, 1861, -1, + 1861, 1867, 1866, -1, 1867, 1861, 1863, -1, + 1863, 1868, 1867, -1, 1868, 1863, 1869, -1, + 1869, 1870, 1868, -1, 1870, 1869, 1871, -1, + 1871, 1872, 1870, -1, 1872, 1871, 1873, -1, + 1873, 1874, 1872, -1, 1874, 1873, 1875, -1, + 1875, 1876, 1874, -1, 1876, 1875, 1877, -1, + 1877, 1878, 1876, -1, 1878, 1877, 1879, -1, + 1880, 1879, 1881, -1, 1881, 1882, 1880, -1, + 1882, 1881, 1883, -1, 1883, 1858, 1882, -1, + 1858, 1883, 1884, -1, 1884, 1859, 1858, -1, + 1859, 1884, 1885, -1, 1885, 1886, 1887, -1, + 1886, 1885, 1884, -1, 1884, 1888, 1886, -1, + 1888, 1884, 1883, -1, 1883, 1889, 1888, -1, + 1889, 1883, 1881, -1, 1881, 1890, 1889, -1, + 1890, 1881, 1879, -1, 1879, 1891, 1890, -1, + 1891, 1879, 1877, -1, 1877, 1892, 1891, -1, + 1892, 1877, 1875, -1, 1875, 1893, 1892, -1, + 1893, 1875, 1873, -1, 1873, 1894, 1893, -1, + 1894, 1873, 1871, -1, 1871, 1895, 1894, -1, + 1895, 1871, 1869, -1, 1869, 1896, 1895, -1, + 1896, 1869, 1863, -1, 1863, 1860, 1896, -1, + 1897, 1898, 1899, -1, 1900, 1898, 1897, -1, + 1898, 1900, 1901, -1, 1902, 1903, 1904, -1, + 1903, 1902, 1905, -1, 1905, 1906, 1903, -1, + 1906, 1905, 1901, -1, 1906, 1901, 1900, -1, + 1907, 1908, 1860, -1, 1908, 1907, 1906, -1, + 1908, 1906, 1900, -1, 1900, 1897, 1908, -1, + 1897, 1860, 1908, -1, 1897, 1896, 1860, -1, + 1909, 1895, 1896, -1, 1895, 1909, 1910, -1, + 1910, 1894, 1895, -1, 1894, 1910, 1911, -1, + 1911, 1893, 1894, -1, 1893, 1911, 1912, -1, + 1912, 1892, 1893, -1, 1892, 1912, 1913, -1, + 1913, 1891, 1892, -1, 1891, 1913, 1914, -1, + 1914, 1890, 1891, -1, 1890, 1914, 1915, -1, + 1915, 1889, 1890, -1, 1889, 1915, 1916, -1, + 1916, 1888, 1889, -1, 1888, 1916, 1917, -1, + 1917, 1886, 1888, -1, 1886, 1917, 1918, -1, + 1918, 1887, 1886, -1, 1887, 1918, 1919, -1, + 1919, 1920, 1921, -1, 1920, 1919, 1918, -1, + 1918, 1922, 1920, -1, 1922, 1918, 1917, -1, + 1917, 1923, 1922, -1, 1923, 1917, 1916, -1, + 1916, 1924, 1923, -1, 1924, 1916, 1915, -1, + 1915, 1925, 1924, -1, 1925, 1915, 1914, -1, + 1914, 1926, 1925, -1, 1926, 1914, 1913, -1, + 1913, 1927, 1926, -1, 1927, 1913, 1912, -1, + 1912, 1928, 1927, -1, 1928, 1912, 1911, -1, + 1911, 1929, 1928, -1, 1929, 1911, 1910, -1, + 1910, 1930, 1929, -1, 1930, 1910, 1909, -1, + 1909, 1899, 1930, -1, 1931, 1932, 1899, -1, + 1899, 1932, 1933, -1, 1933, 1930, 1899, -1, + 1930, 1933, 1934, -1, 1934, 1929, 1930, -1, + 1929, 1934, 1935, -1, 1935, 1928, 1929, -1, + 1928, 1935, 1936, -1, 1936, 1927, 1928, -1, + 1927, 1936, 1937, -1, 1937, 1926, 1927, -1, + 1926, 1937, 1938, -1, 1938, 1925, 1926, -1, + 1925, 1938, 1939, -1, 1939, 1924, 1925, -1, + 1924, 1939, 1940, -1, 1940, 1923, 1924, -1, + 1923, 1940, 1941, -1, 1941, 1922, 1923, -1, + 1922, 1941, 1942, -1, 1942, 1920, 1922, -1, + 1920, 1942, 1943, -1, 1943, 1921, 1920, -1, + 1944, 1945, 1946, -1, 1944, 1947, 1945, -1, + 1947, 1944, 1948, -1, 1948, 1949, 1947, -1, + 1949, 1948, 1950, -1, 1950, 1951, 1949, -1, + 1951, 1950, 1952, -1, 1952, 1953, 1951, -1, + 1953, 1952, 1954, -1, 1954, 1955, 1953, -1, + 1955, 1954, 1956, -1, 1956, 1957, 1955, -1, + 1957, 1956, 1958, -1, 1958, 1959, 1957, -1, + 1960, 1961, 1959, -1, 1961, 1960, 1962, -1, + 1962, 1963, 1961, -1, 1963, 1962, 1964, -1, + 1964, 1965, 1963, -1, 1965, 1964, 1966, -1, + 1966, 1967, 1965, -1, 1967, 1966, 1968, -1, + 1968, 1969, 1967, -1, 1969, 1968, 1970, -1, + 1971, 1970, 1968, -1, 1972, 1973, 1974, -1, + 1975, 1973, 1972, -1, 1975, 1976, 1973, -1, + 1977, 1969, 1970, -1, 1977, 1978, 1969, -1, + 1978, 1974, 1969, -1, 1969, 1974, 1973, -1, + 1969, 1973, 1979, -1, 1979, 1967, 1969, -1, + 1967, 1979, 1980, -1, 1980, 1965, 1967, -1, + 1965, 1980, 1981, -1, 1981, 1963, 1965, -1, + 1963, 1981, 1982, -1, 1982, 1961, 1963, -1, + 1961, 1982, 1983, -1, 1983, 1959, 1961, -1, + 1959, 1983, 1984, -1, 1984, 1957, 1959, -1, + 1957, 1984, 1985, -1, 1985, 1955, 1957, -1, + 1955, 1985, 1986, -1, 1986, 1953, 1955, -1, + 1953, 1986, 1987, -1, 1987, 1951, 1953, -1, + 1951, 1987, 1988, -1, 1988, 1949, 1951, -1, + 1949, 1988, 1989, -1, 1989, 1947, 1949, -1, + 1947, 1989, 1990, -1, 1990, 1945, 1947, -1, + 1991, 1992, 1945, -1, 1945, 1990, 1991, -1, + 1991, 1993, 1994, -1, 1995, 1991, 1990, -1, + 1990, 1996, 1995, -1, 1996, 1990, 1989, -1, + 1989, 1997, 1996, -1, 1997, 1989, 1988, -1, + 1988, 1998, 1997, -1, 1998, 1988, 1987, -1, + 1987, 1999, 1998, -1, 1999, 1987, 1986, -1, + 1986, 2000, 1999, -1, 2000, 1986, 1985, -1, + 1985, 2001, 2000, -1, 2001, 1985, 1984, -1, + 1984, 2002, 2001, -1, 2002, 1984, 1983, -1, + 1983, 2003, 2002, -1, 2003, 1983, 1982, -1, + 1982, 2004, 2003, -1, 2004, 1982, 1981, -1, + 1981, 2005, 2004, -1, 2005, 1981, 1980, -1, + 1980, 2006, 2005, -1, 2006, 1980, 1979, -1, + 1979, 2007, 2006, -1, 2007, 1979, 1973, -1, + 1973, 2008, 2007, -1, 1973, 1976, 2008, -1, + 2009, 2008, 1976, -1, 2010, 2008, 2009, -1, + 2010, 2011, 2008, -1, 2012, 2013, 2011, -1, + 2013, 2008, 2011, -1, 2008, 2013, 2014, -1, + 2014, 2007, 2008, -1, 2007, 2014, 2015, -1, + 2015, 2006, 2007, -1, 2006, 2015, 2016, -1, + 2016, 2005, 2006, -1, 2005, 2016, 2017, -1, + 2017, 2004, 2005, -1, 2004, 2017, 2018, -1, + 2018, 2003, 2004, -1, 2003, 2018, 2019, -1, + 2019, 2002, 2003, -1, 2002, 2019, 2020, -1, + 2020, 2001, 2002, -1, 2001, 2020, 2021, -1, + 2021, 2000, 2001, -1, 2000, 2021, 2022, -1, + 2022, 1999, 2000, -1, 1999, 2022, 2023, -1, + 2023, 1998, 1999, -1, 1998, 2023, 2024, -1, + 2024, 1997, 1998, -1, 1997, 2024, 2025, -1, + 2025, 1996, 1997, -1, 1996, 2025, 2026, -1, + 2026, 1995, 1996, -1, 1993, 2027, 2028, -1, + 2028, 2029, 1993, -1, 2030, 1993, 2029, -1, + 2030, 2029, 2031, -1, 2030, 2031, 2032, -1, + 2032, 1993, 2030, -1, 2032, 1994, 1993, -1, + 2032, 2031, 1994, -1, 2033, 2034, 2035, -1, + 2035, 2036, 2033, -1, 2037, 2038, 2039, -1, + 2037, 2040, 2038, -1, 2041, 2042, 2043, -1, + 2043, 2044, 2045, -1, 2044, 2043, 2046, -1, + 2046, 2047, 2044, -1, 2047, 2046, 2048, -1, + 2048, 2049, 2047, -1, 2049, 2048, 2050, -1, + 2050, 2051, 2049, -1, 2051, 2050, 2052, -1, + 2052, 2053, 2051, -1, 2053, 2052, 2054, -1, + 2054, 2055, 2053, -1, 2055, 2054, 2056, -1, + 2056, 2057, 2055, -1, 2058, 2059, 2057, -1, + 2057, 2056, 2058, -1, 2060, 2058, 2056, -1, + 2056, 2061, 2060, -1, 2061, 2056, 2054, -1, + 2054, 2062, 2061, -1, 2062, 2054, 2052, -1, + 2052, 2063, 2062, -1, 2063, 2052, 2050, -1, + 2050, 2064, 2063, -1, 2064, 2050, 2048, -1, + 2048, 2065, 2064, -1, 2065, 2048, 2046, -1, + 2046, 2066, 2065, -1, 2066, 2046, 2043, -1, + 2043, 2042, 2066, -1, 2067, 2068, 2069, -1, + 2070, 2071, 2072, -1, 2070, 2073, 2071, -1, + 2073, 2070, 2074, -1, 2074, 2075, 2073, -1, + 2075, 2074, 2076, -1, 2076, 2077, 2075, -1, + 2077, 2076, 2078, -1, 2078, 2079, 2077, -1, + 2079, 2078, 2080, -1, 2080, 2081, 2079, -1, + 2081, 2080, 2082, -1, 2082, 2083, 2081, -1, + 2083, 2082, 2084, -1, 2084, 2085, 2083, -1, + 2085, 2084, 2086, -1, 2086, 2087, 2085, -1, + 2088, 2089, 2090, -1, 2090, 2068, 2088, -1, + 2068, 2090, 2091, -1, 2091, 2069, 2068, -1, + 2069, 2091, 2092, -1, 2093, 2094, 2095, -1, + 2096, 2097, 2098, -1, 2098, 2099, 2096, -1, + 2099, 2098, 2100, -1, 2100, 2101, 2099, -1, + 2101, 2100, 2102, -1, 2102, 2103, 2101, -1, + 2103, 2102, 2104, -1, 2105, 2104, 2106, -1, + 2106, 2107, 2105, -1, 2108, 2109, 2107, -1, + 2110, 2111, 2112, -1, 2112, 2113, 2110, -1, + 2113, 2112, 2114, -1, 2114, 2115, 2113, -1, + 2115, 2114, 2116, -1, 2116, 2117, 2115, -1, + 2117, 2116, 2094, -1, 2094, 2093, 2117, -1, + 2092, 2117, 2093, -1, 2117, 2092, 2091, -1, + 2091, 2115, 2117, -1, 2115, 2091, 2090, -1, + 2090, 2113, 2115, -1, 2113, 2090, 2089, -1, + 2089, 2110, 2113, -1, 2109, 2086, 2084, -1, + 2084, 2107, 2109, -1, 2107, 2084, 2082, -1, + 2082, 2105, 2107, -1, 2105, 2082, 2080, -1, + 2103, 2080, 2078, -1, 2078, 2101, 2103, -1, + 2101, 2078, 2076, -1, 2076, 2099, 2101, -1, + 2099, 2076, 2074, -1, 2074, 2096, 2099, -1, + 2096, 2074, 2070, -1, 2070, 2118, 2096, -1, + 2118, 2070, 2119, -1, 2118, 2119, 2066, -1, + 2118, 2066, 2042, -1, 2042, 2096, 2118, -1, + 2042, 2041, 2096, -1, 2041, 2097, 2096, -1, + 2041, 2043, 2097, -1, 2043, 2045, 2097, -1, + 2120, 2038, 2121, -1, 2121, 2038, 2122, -1, + 2122, 2045, 2121, -1, 2122, 2123, 2045, -1, + 2123, 2097, 2045, -1, 2123, 2098, 2097, -1, + 2123, 2122, 2098, -1, 2098, 2122, 2038, -1, + 2038, 2100, 2098, -1, 2100, 2038, 2040, -1, + 2040, 2102, 2100, -1, 2102, 2040, 2124, -1, + 2124, 2104, 2102, -1, 2104, 2124, 2125, -1, + 2125, 2106, 2104, -1, 2106, 2125, 2126, -1, + 2111, 2127, 2128, -1, 2128, 2112, 2111, -1, + 2112, 2128, 2129, -1, 2129, 2114, 2112, -1, + 2114, 2129, 2130, -1, 2130, 2116, 2114, -1, + 2116, 2130, 2131, -1, 2131, 2094, 2116, -1, + 2094, 2131, 2132, -1, 2132, 2095, 2094, -1, + 2095, 2132, 2133, -1, 2133, 2134, 2135, -1, + 2134, 2133, 2132, -1, 2132, 2136, 2134, -1, + 2136, 2132, 2131, -1, 2131, 2137, 2136, -1, + 2137, 2131, 2130, -1, 2130, 2138, 2137, -1, + 2138, 2130, 2129, -1, 2139, 2129, 2128, -1, + 2128, 2140, 2139, -1, 2140, 2128, 2127, -1, + 2141, 2126, 2125, -1, 2142, 2125, 2124, -1, + 2124, 2143, 2142, -1, 2143, 2124, 2040, -1, + 2040, 2037, 2143, -1, 2144, 2145, 2146, -1, + 2145, 2144, 2037, -1, 2033, 2037, 2144, -1, + 2033, 2143, 2037, -1, 2143, 2033, 2036, -1, + 2036, 2142, 2143, -1, 2142, 2036, 2147, -1, + 2148, 2149, 2150, -1, 2140, 2150, 2151, -1, + 2151, 2139, 2140, -1, 2139, 2151, 2152, -1, + 2138, 2152, 2153, -1, 2153, 2137, 2138, -1, + 2137, 2153, 2154, -1, 2154, 2136, 2137, -1, + 2136, 2154, 2155, -1, 2155, 2134, 2136, -1, + 2134, 2155, 2156, -1, 2156, 2135, 2134, -1, + 2135, 2156, 2157, -1, 2157, 2158, 2159, -1, + 2158, 2157, 2156, -1, 2156, 2160, 2158, -1, + 2160, 2156, 2155, -1, 2155, 2161, 2160, -1, + 2161, 2155, 2154, -1, 2154, 2162, 2161, -1, + 2162, 2154, 2153, -1, 2153, 2163, 2162, -1, + 2163, 2153, 2152, -1, 2152, 2164, 2163, -1, + 2164, 2152, 2151, -1, 2151, 2165, 2164, -1, + 2165, 2151, 2150, -1, 2150, 2166, 2165, -1, + 2166, 2150, 2149, -1, 2149, 2167, 2166, -1, + 2168, 2147, 2036, -1, 2036, 2035, 2168, -1, + 2169, 2170, 2035, -1, 2035, 2170, 2171, -1, + 2171, 2168, 2035, -1, 2167, 2172, 2173, -1, + 2173, 2166, 2167, -1, 2166, 2173, 2174, -1, + 2174, 2165, 2166, -1, 2175, 2164, 2165, -1, + 2164, 2175, 2176, -1, 2176, 2163, 2164, -1, + 2163, 2176, 2177, -1, 2177, 2162, 2163, -1, + 2162, 2177, 2178, -1, 2178, 2161, 2162, -1, + 2179, 2160, 2161, -1, 2180, 2158, 2160, -1, + 2158, 2180, 2181, -1, 2181, 2159, 2158, -1, + 2159, 2181, 2182, -1, 2182, 2183, 2184, -1, + 2183, 2182, 2181, -1, 2181, 2185, 2183, -1, + 2185, 2181, 2180, -1, 2180, 2186, 2185, -1, + 2178, 2187, 2188, -1, 2187, 2178, 2177, -1, + 2177, 2189, 2187, -1, 2189, 2177, 2176, -1, + 2176, 2190, 2189, -1, 2190, 2176, 2175, -1, + 2175, 2191, 2190, -1, 2174, 2192, 2191, -1, + 2192, 2174, 2173, -1, 2173, 2193, 2192, -1, + 2193, 2173, 2172, -1, 2172, 2031, 2193, -1, + 2171, 1994, 2031, -1, 2194, 1994, 2171, -1, + 2194, 1991, 1994, -1, 2194, 1992, 1991, -1, + 1992, 2194, 2171, -1, 1992, 2171, 2170, -1, + 2170, 1945, 1992, -1, 2170, 2169, 1945, -1, + 2169, 1946, 1945, -1, 2169, 2035, 1946, -1, + 1946, 2035, 2034, -1, 2034, 1944, 1946, -1, + 2034, 2195, 1944, -1, 2195, 2034, 2033, -1, + 2195, 2033, 2144, -1, 2144, 2146, 2195, -1, + 2146, 1944, 2195, -1, 2146, 1948, 1944, -1, + 1948, 2146, 2196, -1, 2196, 1950, 1948, -1, + 1950, 2196, 2197, -1, 2197, 1952, 1950, -1, + 1952, 2197, 2198, -1, 2198, 1954, 1952, -1, + 1954, 2198, 2199, -1, 2199, 1956, 1954, -1, + 1956, 2199, 2200, -1, 2200, 1958, 1956, -1, + 1958, 2200, 2201, -1, 1960, 2201, 2202, -1, + 2202, 1962, 1960, -1, 1962, 2202, 2203, -1, + 2203, 1964, 1962, -1, 1964, 2203, 2204, -1, + 2204, 1966, 1964, -1, 1966, 2204, 2205, -1, + 2205, 1968, 1966, -1, 1968, 2205, 2206, -1, + 2207, 1968, 2206, -1, 2207, 1971, 1968, -1, + 2208, 2206, 2205, -1, 2209, 2208, 2205, -1, + 2210, 2211, 2212, -1, 2210, 2213, 2211, -1, + 2213, 2210, 2214, -1, 2214, 2215, 2213, -1, + 2215, 2214, 2216, -1, 2216, 2217, 2215, -1, + 2217, 2216, 2218, -1, 2218, 2219, 2217, -1, + 2219, 2218, 2220, -1, 2220, 2221, 2219, -1, + 2221, 2220, 2222, -1, 2222, 2223, 2221, -1, + 2223, 2222, 2224, -1, 2224, 2225, 2223, -1, + 2225, 2224, 2226, -1, 2226, 2227, 2225, -1, + 2227, 2226, 2228, -1, 2228, 2229, 2227, -1, + 2229, 2228, 2230, -1, 2231, 2228, 2232, -1, + 2231, 2233, 2228, -1, 2233, 2230, 2228, -1, + 2234, 2229, 2230, -1, 2234, 2235, 2229, -1, + 2235, 2236, 2229, -1, 2209, 2205, 2236, -1, + 2205, 2229, 2236, -1, 2229, 2205, 2204, -1, + 2204, 2227, 2229, -1, 2227, 2204, 2203, -1, + 2203, 2225, 2227, -1, 2225, 2203, 2202, -1, + 2202, 2223, 2225, -1, 2223, 2202, 2201, -1, + 2201, 2221, 2223, -1, 2221, 2201, 2200, -1, + 2200, 2219, 2221, -1, 2219, 2200, 2199, -1, + 2199, 2217, 2219, -1, 2217, 2199, 2198, -1, + 2198, 2215, 2217, -1, 2215, 2198, 2197, -1, + 2197, 2213, 2215, -1, 2213, 2197, 2196, -1, + 2196, 2211, 2213, -1, 2211, 2196, 2146, -1, + 2146, 2145, 2211, -1, 2237, 2211, 2145, -1, + 2237, 2145, 2037, -1, 2237, 2037, 2039, -1, + 2039, 2211, 2237, -1, 2039, 2212, 2211, -1, + 2212, 2039, 2038, -1, 2212, 2038, 2120, -1, + 2120, 2210, 2212, -1, 2120, 2121, 2210, -1, + 2210, 2121, 2045, -1, 2045, 2214, 2210, -1, + 2214, 2045, 2044, -1, 2044, 2216, 2214, -1, + 2216, 2044, 2047, -1, 2047, 2218, 2216, -1, + 2218, 2047, 2049, -1, 2049, 2220, 2218, -1, + 2220, 2049, 2051, -1, 2051, 2222, 2220, -1, + 2222, 2051, 2053, -1, 2053, 2224, 2222, -1, + 2224, 2053, 2055, -1, 2055, 2226, 2224, -1, + 2226, 2055, 2057, -1, 2057, 2228, 2226, -1, + 2057, 2232, 2228, -1, 2232, 2057, 2059, -1, + 2059, 2058, 2238, -1, 2239, 2238, 2058, -1, + 2239, 2058, 2240, -1, 2058, 2060, 2240, -1, + 2241, 2242, 2060, -1, 2242, 2240, 2060, -1, + 2243, 2244, 2245, -1, 2245, 2244, 2246, -1, + 2247, 2246, 2244, -1, 2248, 2249, 2250, -1, + 2250, 2251, 2248, -1, 2251, 2250, 2252, -1, + 2252, 2253, 2251, -1, 2253, 2252, 2254, -1, + 2254, 2255, 2253, -1, 2255, 2254, 2256, -1, + 2256, 2244, 2255, -1, 2244, 2256, 2257, -1, + 2257, 2247, 2244, -1, 2258, 2257, 2256, -1, + 2259, 2256, 2260, -1, 2259, 2258, 2256, -1, + 2261, 2262, 2263, -1, 2261, 2264, 2262, -1, + 2265, 2266, 2267, -1, 2268, 2267, 2269, -1, + 2270, 2269, 2271, -1, 2271, 2272, 2270, -1, + 2272, 2271, 2262, -1, 2262, 2273, 2272, -1, + 2273, 2262, 2264, -1, 2264, 2274, 2273, -1, + 2260, 2273, 2274, -1, 2273, 2260, 2256, -1, + 2256, 2272, 2273, -1, 2272, 2256, 2254, -1, + 2254, 2270, 2272, -1, 2270, 2254, 2252, -1, + 2268, 2252, 2250, -1, 2265, 2250, 2249, -1, + 2265, 2249, 2275, -1, 2276, 2277, 2275, -1, + 2276, 2275, 2249, -1, 2276, 2249, 2278, -1, + 2278, 2277, 2276, -1, 2278, 2279, 2277, -1, + 2278, 2249, 2279, -1, 2280, 2279, 2249, -1, + 2249, 2248, 2280, -1, 2280, 2281, 2282, -1, + 2280, 2283, 2281, -1, 2283, 2280, 2248, -1, + 2248, 2284, 2283, -1, 2284, 2248, 2251, -1, + 2251, 2285, 2284, -1, 2285, 2251, 2253, -1, + 2253, 2286, 2285, -1, 2286, 2253, 2255, -1, + 2255, 2287, 2286, -1, 2287, 2255, 2244, -1, + 2244, 2243, 2287, -1, 2243, 2288, 2287, -1, + 2288, 2241, 2060, -1, 2060, 2287, 2288, -1, + 2287, 2060, 2061, -1, 2061, 2286, 2287, -1, + 2286, 2061, 2062, -1, 2062, 2285, 2286, -1, + 2285, 2062, 2063, -1, 2063, 2284, 2285, -1, + 2284, 2063, 2064, -1, 2064, 2283, 2284, -1, + 2283, 2064, 2065, -1, 2065, 2281, 2283, -1, + 2281, 2065, 2066, -1, 2066, 2119, 2281, -1, + 2289, 2281, 2119, -1, 2289, 2119, 2070, -1, + 2289, 2070, 2072, -1, 2072, 2281, 2289, -1, + 2072, 2282, 2281, -1, 2282, 2072, 2071, -1, + 2282, 2071, 2290, -1, 2290, 2280, 2282, -1, + 2290, 2279, 2280, -1, 2290, 2071, 2279, -1, + 2071, 2277, 2279, -1, 2071, 2291, 2277, -1, + 2291, 2071, 2073, -1, 2073, 2292, 2291, -1, + 2292, 2073, 2075, -1, 2075, 2293, 2292, -1, + 2293, 2075, 2077, -1, 2077, 2294, 2293, -1, + 2294, 2077, 2079, -1, 2079, 2295, 2294, -1, + 2295, 2079, 2081, -1, 2081, 2296, 2295, -1, + 2296, 2081, 2083, -1, 2297, 2083, 2085, -1, + 2085, 2298, 2297, -1, 2298, 2085, 2087, -1, + 2087, 2299, 2298, -1, 2300, 2088, 2068, -1, + 2068, 2067, 2300, -1, 2301, 2300, 2067, -1, + 2299, 1943, 1942, -1, 1942, 2298, 2299, -1, + 2298, 1942, 1941, -1, 1941, 2297, 2298, -1, + 2297, 1941, 1940, -1, 2296, 1940, 1939, -1, + 1939, 2295, 2296, -1, 2295, 1939, 1938, -1, + 1938, 2294, 2295, -1, 2294, 1938, 1937, -1, + 1937, 2293, 2294, -1, 2293, 1937, 1936, -1, + 1936, 2292, 2293, -1, 2292, 1936, 1935, -1, + 1935, 2291, 2292, -1, 2291, 1935, 1934, -1, + 1934, 2277, 2291, -1, 2277, 1934, 1933, -1, + 1933, 2275, 2277, -1, 2302, 2275, 1933, -1, + 2302, 2265, 2275, -1, 2302, 2266, 2265, -1, + 2266, 2302, 1933, -1, 2266, 1933, 1932, -1, + 1932, 2267, 2266, -1, 1932, 1931, 2267, -1, + 1931, 2303, 2267, -1, 1931, 1899, 2303, -1, + 2303, 1899, 1898, -1, 1898, 1901, 2303, -1, + 1901, 2267, 2303, -1, 1901, 2269, 2267, -1, + 2269, 1901, 1905, -1, 1905, 2271, 2269, -1, + 2271, 1905, 1902, -1, 1902, 2262, 2271, -1, + 2304, 2263, 2262, -1, 2263, 2304, 2305, -1, + 2305, 2304, 2306, -1, 2306, 2304, 2307, -1, + 2308, 2307, 2304, -1, 2304, 1904, 2308, -1, + 2308, 1904, 2309, -1, 2310, 2311, 2312, -1, + 2310, 2313, 2311, -1, 2313, 2314, 2311, -1, + 2315, 2316, 2317, -1, 2315, 2318, 2316, -1, + 2318, 2315, 2311, -1, 2311, 2319, 2318, -1, + 2319, 2311, 2314, -1, 2319, 2314, 2320, -1, + 2320, 2321, 2319, -1, 2321, 2322, 2323, -1, + 2323, 2319, 2321, -1, 2323, 2318, 2319, -1, + 2318, 2323, 2324, -1, 2324, 2316, 2318, -1, + 2325, 2326, 2316, -1, 2316, 2324, 2325, -1, + 2325, 2327, 2328, -1, 2325, 2329, 2327, -1, + 2329, 2325, 2324, -1, 2324, 2330, 2329, -1, + 2330, 2324, 2323, -1, 2323, 2331, 2330, -1, + 2331, 2323, 2322, -1, 2332, 2330, 2331, -1, + 2332, 2333, 2330, -1, 2309, 2330, 2333, -1, + 2330, 2309, 1904, -1, 1904, 2329, 2330, -1, + 2329, 1904, 1903, -1, 1903, 2327, 2329, -1, + 2327, 1903, 1906, -1, 1906, 1907, 2327, -1, + 2334, 2327, 1907, -1, 2334, 1907, 1860, -1, + 2334, 1860, 1862, -1, 1862, 2327, 2334, -1, + 1862, 2328, 2327, -1, 2328, 1862, 1861, -1, + 2328, 1861, 2335, -1, 2335, 2325, 2328, -1, + 2335, 2326, 2325, -1, 2335, 1861, 2326, -1, + 2326, 1861, 1865, -1, 1865, 2316, 2326, -1, + 1865, 1864, 2316, -1, 1864, 2317, 2316, -1, + 1864, 1866, 2317, -1, 1866, 2336, 2317, -1, + 1866, 2337, 2336, -1, 2337, 1866, 1867, -1, + 1867, 2338, 2337, -1, 2338, 1867, 1868, -1, + 1868, 2339, 2338, -1, 2339, 1868, 1870, -1, + 1870, 2340, 2339, -1, 2340, 1870, 1872, -1, + 1872, 2341, 2340, -1, 2341, 1872, 1874, -1, + 1874, 2342, 2341, -1, 2342, 1874, 1876, -1, + 1876, 2343, 2342, -1, 2343, 1876, 1878, -1, + 1878, 2344, 2343, -1, 2345, 1880, 1882, -1, + 1882, 2346, 2345, -1, 2346, 1882, 1858, -1, + 1858, 1857, 2346, -1, 1856, 2346, 1857, -1, + 2346, 1856, 1855, -1, 1855, 2345, 2346, -1, + 2345, 1855, 1854, -1, 2344, 1854, 1852, -1, + 1852, 2343, 2344, -1, 2343, 1852, 1850, -1, + 1850, 2342, 2343, -1, 2342, 1850, 1848, -1, + 1848, 2341, 2342, -1, 2341, 1848, 1846, -1, + 1846, 2340, 2341, -1, 2340, 1846, 1844, -1, + 1844, 2339, 2340, -1, 2339, 1844, 1842, -1, + 1842, 2338, 2339, -1, 2338, 1842, 1840, -1, + 1840, 2337, 2338, -1, 2337, 1840, 1838, -1, + 1838, 2336, 2337, -1, 1834, 2347, 2336, -1, + 2347, 1834, 2348, -1, 2347, 2348, 2349, -1, + 2347, 2349, 2350, -1, 2350, 2336, 2347, -1, + 2350, 2351, 2336, -1, 2351, 2317, 2336, -1, + 2351, 2315, 2317, -1, 2351, 2350, 2315, -1, + 2315, 2350, 2349, -1, 2349, 2311, 2315, -1, + 2311, 2349, 1829, -1, 1829, 2312, 2311, -1, + 2312, 1829, 1828, -1, 2352, 2353, 2354, -1, + 2355, 2354, 2356, -1, 2356, 2354, 2353, -1, + 2353, 2357, 2358, -1, 2353, 2352, 2357, -1, + 2359, 2358, 2357, -1, 2360, 2361, 2362, -1, + 2360, 2363, 2361, -1, 2363, 2364, 2365, -1, + 2363, 2360, 2364, -1, 2366, 2367, 2364, -1, + 2364, 2368, 2366, -1, 2368, 2364, 2360, -1, + 2360, 2369, 2368, -1, 2370, 2368, 2371, -1, + 2370, 2366, 2368, -1, 2366, 2372, 2373, -1, + 2366, 2370, 2372, -1, 2370, 2374, 2375, -1, + 2375, 2372, 2370, -1, 2372, 2375, 2358, -1, + 2358, 2376, 2372, -1, 2376, 2358, 2359, -1, + 2377, 2372, 2376, -1, 2377, 2378, 2372, -1, + 2378, 2373, 2372, -1, 2379, 2366, 2373, -1, + 2379, 2367, 2366, -1, 2380, 2364, 2367, -1, + 2380, 2381, 2364, -1, 2381, 2365, 2364, -1, + 2382, 2363, 2365, -1, 2382, 1830, 2363, -1, + 2363, 1830, 1829, -1, 1829, 2361, 2363, -1, + 2361, 1829, 2349, -1, 2349, 2348, 2361, -1, + 2383, 2361, 2348, -1, 2383, 2348, 1834, -1, + 2383, 1834, 1836, -1, 1836, 2361, 2383, -1, + 1836, 2362, 2361, -1, 2362, 1836, 1835, -1, + 2362, 1835, 2384, -1, 2384, 2360, 2362, -1, + 2384, 2369, 2360, -1, 2384, 1835, 2369, -1, + 1835, 2385, 2369, -1, 1835, 2386, 2385, -1, + 2386, 1835, 1837, -1, 2387, 1837, 1839, -1, + 1839, 2388, 2387, -1, 2388, 1839, 1841, -1, + 1841, 2389, 2388, -1, 2389, 1841, 1843, -1, + 1843, 2390, 2389, -1, 1845, 2391, 2390, -1, + 2391, 1845, 1847, -1, 1847, 2392, 2391, -1, + 2392, 1847, 1849, -1, 1849, 2393, 2392, -1, + 2393, 1849, 1851, -1, 1851, 2394, 2393, -1, + 2394, 1851, 1853, -1, 1853, 2395, 2394, -1, + 2395, 1853, 1832, -1, 1832, 1831, 2395, -1, + 1827, 2395, 1831, -1, 2395, 1827, 1826, -1, + 1826, 2394, 2395, -1, 2394, 1826, 2396, -1, + 2396, 2393, 2394, -1, 2393, 2396, 2397, -1, + 2397, 2392, 2393, -1, 2392, 2397, 2398, -1, + 2398, 2391, 2392, -1, 2391, 2398, 2399, -1, + 2399, 2390, 2391, -1, 2390, 2399, 2400, -1, + 2400, 2389, 2390, -1, 2389, 2400, 2401, -1, + 2401, 2388, 2389, -1, 2388, 2401, 2402, -1, + 2402, 2387, 2388, -1, 2387, 2402, 2403, -1, + 2386, 2403, 2404, -1, 2404, 2385, 2386, -1, + 2385, 2404, 2405, -1, 2405, 2371, 2385, -1, + 2406, 2371, 2405, -1, 2406, 2370, 2371, -1, + 2406, 2374, 2370, -1, 2374, 2406, 2405, -1, + 2374, 2405, 2407, -1, 2407, 2375, 2374, -1, + 2407, 2408, 2375, -1, 2408, 2409, 2375, -1, + 2408, 2410, 2409, -1, 2408, 2407, 2410, -1, + 2410, 2407, 2405, -1, 2405, 2411, 2410, -1, + 2411, 2405, 2404, -1, 2404, 2412, 2411, -1, + 2412, 2404, 2403, -1, 2403, 2413, 2412, -1, + 2413, 2403, 2402, -1, 2402, 2414, 2413, -1, + 2414, 2402, 2401, -1, 2401, 2415, 2414, -1, + 2415, 2401, 2400, -1, 2400, 2416, 2415, -1, + 2416, 2400, 2399, -1, 2399, 2417, 2416, -1, + 2417, 2399, 2398, -1, 2398, 2418, 2417, -1, + 2418, 2398, 2397, -1, 2419, 2397, 2396, -1, + 2396, 2420, 2419, -1, 2420, 2396, 1826, -1, + 1826, 1825, 2420, -1, 1824, 2420, 1825, -1, + 2420, 1824, 1823, -1, 1823, 2419, 2420, -1, + 2419, 1823, 1822, -1, 2418, 1822, 1821, -1, + 1821, 2417, 2418, -1, 2417, 1821, 1820, -1, + 1820, 2416, 2417, -1, 2416, 1820, 1819, -1, + 1819, 2415, 2416, -1, 2415, 1819, 1818, -1, + 1818, 2414, 2415, -1, 1817, 2413, 2414, -1, + 2413, 1817, 1816, -1, 1816, 2412, 2413, -1, + 2412, 1816, 1815, -1, 1815, 2411, 2412, -1, + 1814, 2410, 2411, -1, 2410, 1588, 1598, -1, + 1598, 2409, 2410, -1, 1598, 1596, 2409, -1, + 1596, 2375, 2409, -1, 1596, 2358, 2375, -1, + 2358, 1596, 1594, -1, 2356, 1594, 1591, -1, + 2356, 1591, 2421, -1, 2421, 2355, 2356, -1, + 2422, 2421, 1591, -1, 2422, 1591, 1590, -1, + 2423, 1589, 1592, -1, 2423, 1592, 2424, -1, + 2424, 928, 927, -1, 928, 2424, 1592, -1, + 928, 1582, 2425, -1, 2425, 926, 928, -1, + 2426, 2425, 1582, -1, 2426, 1582, 1581, -1, + 1577, 1579, 2427, -1, 2427, 1579, 2428, -1, + 2428, 2429, 2430, -1, 2429, 2428, 1579, -1, + 2429, 1579, 1603, -1, 2429, 1603, 1605, -1, + 1605, 2431, 2429, -1, 2431, 2430, 2429, -1, + 2432, 1604, 1606, -1, 2432, 1606, 2433, -1, + 2433, 1606, 925, -1, 1606, 923, 925, -1, + 923, 1606, 1546, -1, 923, 1546, 2434, -1, + 2434, 924, 923, -1, 2435, 2434, 1546, -1, + 1546, 1470, 2435, -1, 2436, 2435, 1470, -1, + 2436, 1470, 2437, -1, 2437, 1470, 1468, -1, + 1467, 1469, 2438, -1, 2438, 1469, 2439, -1, + 2440, 919, 921, -1, 2440, 2439, 919, -1, + 919, 2439, 1469, -1, 919, 1469, 1472, -1, + 1472, 917, 919, -1, 917, 1472, 1474, -1, + 1474, 915, 917, -1, 915, 1474, 1476, -1, + 1476, 913, 915, -1, 913, 1476, 1478, -1, + 1478, 911, 913, -1, 911, 1478, 1480, -1, + 1480, 909, 911, -1, 909, 1480, 1482, -1, + 1482, 907, 909, -1, 907, 1482, 1484, -1, + 1484, 905, 907, -1, 905, 1484, 1486, -1, + 1486, 903, 905, -1, 903, 1486, 1488, -1, + 1488, 900, 903, -1, 900, 1488, 1490, -1, + 1490, 2441, 900, -1, 2441, 1490, 1492, -1, + 2442, 900, 2441, -1, 2442, 901, 900, -1, + 2443, 902, 901, -1, 2443, 2444, 902, -1, + 2445, 902, 2444, -1, 2445, 904, 902, -1, + 904, 2445, 2446, -1, 2446, 906, 904, -1, + 906, 2446, 2447, -1, 2447, 908, 906, -1, + 908, 2447, 2448, -1, 2448, 910, 908, -1, + 910, 2448, 2449, -1, 2449, 912, 910, -1, + 912, 2449, 2450, -1, 2450, 914, 912, -1, + 914, 2450, 2451, -1, 2451, 916, 914, -1, + 916, 2451, 2452, -1, 2452, 918, 916, -1, + 918, 2452, 2453, -1, 2453, 2454, 918, -1, + 2455, 918, 2454, -1, 2455, 920, 918, -1, + 2456, 2453, 2452, -1, 2457, 2452, 2458, -1, + 2457, 2456, 2452, -1, 2459, 2460, 2461, -1, + 2459, 2462, 2460, -1, 2458, 2460, 2462, -1, + 2460, 2458, 2452, -1, 2460, 2452, 2451, -1, + 2451, 2463, 2460, -1, 2463, 2451, 2450, -1, + 2450, 2464, 2463, -1, 2464, 2450, 2449, -1, + 2449, 2465, 2464, -1, 2465, 2449, 2448, -1, + 2448, 2466, 2465, -1, 2466, 2448, 2447, -1, + 2447, 2467, 2466, -1, 2467, 2447, 2446, -1, + 2446, 2468, 2467, -1, 2468, 2446, 2445, -1, + 2445, 2469, 2468, -1, 2469, 2445, 2444, -1, + 2470, 2468, 2469, -1, 2470, 1495, 2468, -1, + 2468, 1495, 1494, -1, 1494, 2467, 2468, -1, + 2467, 1494, 1521, -1, 1521, 2466, 2467, -1, + 2466, 1521, 1520, -1, 1520, 2465, 2466, -1, + 2465, 1520, 1519, -1, 1519, 2464, 2465, -1, + 2464, 1519, 1518, -1, 1518, 2463, 2464, -1, + 2463, 1518, 1517, -1, 1517, 2460, 2463, -1, + 1517, 2461, 2460, -1, 2471, 2461, 1517, -1, + 2472, 2471, 1517, -1, 2472, 1517, 1515, -1, + 2473, 1516, 1497, -1, 2473, 1497, 1499, -1, + 2474, 1501, 1500, -1, 2475, 1500, 2476, -1, + 2475, 2474, 1500, -1, 2477, 2478, 2479, -1, + 2477, 2479, 2480, -1, 2480, 897, 899, -1, + 897, 2480, 2479, -1, 2479, 2481, 897, -1, + 2481, 2482, 2483, -1, 2481, 2479, 2482, -1, + 2484, 2485, 2482, -1, 2482, 2486, 2484, -1, + 2486, 2482, 2479, -1, 2479, 2487, 2486, -1, + 2487, 2479, 2478, -1, 2478, 2488, 2487, -1, + 2488, 2476, 2487, -1, 2487, 2476, 1500, -1, + 2487, 1500, 1502, -1, 1502, 2486, 2487, -1, + 2486, 1502, 1504, -1, 1504, 2484, 2486, -1, + 2484, 1504, 1506, -1, 2484, 1506, 1523, -1, + 1523, 2485, 2484, -1, 2489, 2482, 2485, -1, + 2489, 2483, 2482, -1, 2490, 2481, 2483, -1, + 2490, 2491, 2481, -1, 2491, 1527, 1526, -1, + 1526, 2481, 2491, -1, 1526, 897, 2481, -1, + 897, 1526, 2492, -1, 2492, 898, 897, -1, + 2493, 2492, 1526, -1, 2493, 1526, 1525, -1, + 1525, 1524, 2494, -1, 2495, 2494, 1524, -1, + 2496, 2495, 1524, -1, 2496, 1524, 1529, -1, + 2496, 1529, 2497, -1, 2497, 891, 895, -1, + 891, 2497, 1529, -1, 1107, 1108, 2498, -1, + 1108, 1154, 2498, -1, 2499, 2498, 1154, -1, + 2499, 1154, 2500, -1, 2501, 2500, 1154, -1, + 1154, 1155, 2501, -1, 2502, 2503, 2504, -1, + 2502, 2505, 2503, -1, 2505, 2502, 2506, -1, + 2506, 2507, 2505, -1, 2507, 2506, 2508, -1, + 2508, 2509, 2507, -1, 2509, 2508, 2510, -1, + 2510, 2511, 2509, -1, 2511, 2510, 2512, -1, + 2512, 2513, 2511, -1, 2513, 2512, 2514, -1, + 2514, 2515, 2513, -1, 2515, 2514, 2516, -1, + 2516, 2517, 2515, -1, 2517, 2516, 2518, -1, + 2518, 2519, 2517, -1, 2519, 2518, 2520, -1, + 2520, 2521, 2519, -1, 2521, 2520, 2522, -1, + 2522, 2523, 2521, -1, 2523, 2522, 2524, -1, + 2524, 2525, 2523, -1, 2525, 2524, 2526, -1, + 2526, 2527, 2525, -1, 2527, 2526, 2528, -1, + 2528, 2529, 2527, -1, 2529, 2528, 2530, -1, + 2531, 2530, 2532, -1, 2532, 2533, 2531, -1, + 2533, 2532, 2534, -1, 2534, 2535, 2533, -1, + 2535, 2534, 2536, -1, 2536, 2537, 2535, -1, + 2537, 2536, 2538, -1, 2538, 2539, 2537, -1, + 2539, 2538, 2540, -1, 2540, 2541, 2539, -1, + 2541, 2540, 2542, -1, 2542, 2543, 2541, -1, + 2544, 2541, 2543, -1, 2544, 2545, 2541, -1, + 2546, 2541, 2545, -1, 2546, 2539, 2541, -1, + 2539, 2546, 2547, -1, 2547, 2537, 2539, -1, + 2537, 2547, 2548, -1, 2548, 2535, 2537, -1, + 2535, 2548, 2549, -1, 2549, 2533, 2535, -1, + 2533, 2549, 2550, -1, 2550, 2531, 2533, -1, + 2531, 2550, 2551, -1, 2529, 2551, 2552, -1, + 2552, 2527, 2529, -1, 2527, 2552, 2553, -1, + 2553, 2525, 2527, -1, 2525, 2553, 2554, -1, + 2554, 2523, 2525, -1, 2523, 2554, 2555, -1, + 2555, 2521, 2523, -1, 2521, 2555, 2556, -1, + 2556, 2519, 2521, -1, 2519, 2556, 2557, -1, + 2557, 2517, 2519, -1, 2517, 2557, 2558, -1, + 2558, 2515, 2517, -1, 2515, 2558, 2559, -1, + 2559, 2513, 2515, -1, 2513, 2559, 2560, -1, + 2560, 2511, 2513, -1, 2511, 2560, 2561, -1, + 2561, 2509, 2511, -1, 2509, 2561, 2562, -1, + 2562, 2507, 2509, -1, 2507, 2562, 2563, -1, + 2563, 2505, 2507, -1, 2505, 2563, 2564, -1, + 2564, 2503, 2505, -1, 2565, 2566, 2503, -1, + 2503, 2564, 2565, -1, 2567, 2568, 2569, -1, + 2570, 2571, 2572, -1, 2570, 2573, 2571, -1, + 2573, 2570, 2574, -1, 2574, 2575, 2573, -1, + 2575, 2574, 2576, -1, 2576, 2577, 2575, -1, + 2577, 2576, 2578, -1, 2578, 2579, 2577, -1, + 2579, 2578, 2580, -1, 2580, 2581, 2579, -1, + 2581, 2580, 2582, -1, 2582, 2583, 2581, -1, + 2583, 2582, 2584, -1, 2584, 2585, 2583, -1, + 2585, 2584, 2586, -1, 2586, 2587, 2585, -1, + 2587, 2586, 2588, -1, 2588, 2589, 2587, -1, + 2589, 2588, 2590, -1, 2590, 2591, 2589, -1, + 2591, 2590, 2592, -1, 2592, 2593, 2591, -1, + 2593, 2592, 2594, -1, 2594, 2595, 2593, -1, + 2595, 2594, 2596, -1, 2596, 2597, 2595, -1, + 2597, 2596, 2598, -1, 2598, 2599, 2597, -1, + 2599, 2598, 2600, -1, 2600, 2601, 2599, -1, + 2601, 2600, 2602, -1, 2602, 2603, 2601, -1, + 2603, 2602, 2604, -1, 2604, 2605, 2603, -1, + 2605, 2604, 2606, -1, 2606, 2607, 2605, -1, + 2607, 2606, 2608, -1, 2608, 2609, 2607, -1, + 2609, 2610, 2611, -1, 2609, 2608, 2610, -1, + 2612, 2613, 2610, -1, 2610, 2614, 2612, -1, + 2614, 2610, 2608, -1, 2608, 2615, 2614, -1, + 2615, 2608, 2606, -1, 2606, 2616, 2615, -1, + 2616, 2606, 2604, -1, 2617, 2604, 2602, -1, + 2602, 2618, 2617, -1, 2618, 2602, 2600, -1, + 2600, 2619, 2618, -1, 2619, 2600, 2598, -1, + 2598, 2620, 2619, -1, 2620, 2598, 2596, -1, + 2621, 2596, 2594, -1, 2594, 2622, 2621, -1, + 2622, 2594, 2592, -1, 2592, 2623, 2622, -1, + 2623, 2592, 2590, -1, 2590, 2624, 2623, -1, + 2624, 2590, 2588, -1, 2588, 2625, 2624, -1, + 2625, 2588, 2586, -1, 2586, 2626, 2625, -1, + 2626, 2586, 2584, -1, 2584, 2627, 2626, -1, + 2627, 2584, 2582, -1, 2582, 2628, 2627, -1, + 2628, 2582, 2580, -1, 2580, 2629, 2628, -1, + 2629, 2580, 2578, -1, 2578, 2630, 2629, -1, + 2630, 2578, 2576, -1, 2576, 2631, 2630, -1, + 2631, 2576, 2574, -1, 2574, 2632, 2631, -1, + 2632, 2574, 2570, -1, 2570, 2633, 2632, -1, + 2634, 2632, 2633, -1, 2634, 2633, 2568, -1, + 2634, 2568, 2567, -1, 2567, 2632, 2634, -1, + 2567, 2569, 2632, -1, 2565, 2632, 2569, -1, + 2565, 2631, 2632, -1, 2631, 2565, 2564, -1, + 2564, 2630, 2631, -1, 2630, 2564, 2563, -1, + 2563, 2629, 2630, -1, 2629, 2563, 2562, -1, + 2562, 2628, 2629, -1, 2628, 2562, 2561, -1, + 2561, 2627, 2628, -1, 2627, 2561, 2560, -1, + 2560, 2626, 2627, -1, 2626, 2560, 2559, -1, + 2559, 2625, 2626, -1, 2625, 2559, 2558, -1, + 2558, 2624, 2625, -1, 2624, 2558, 2557, -1, + 2557, 2623, 2624, -1, 2623, 2557, 2556, -1, + 2556, 2622, 2623, -1, 2622, 2556, 2555, -1, + 2555, 2621, 2622, -1, 2621, 2555, 2554, -1, + 2620, 2554, 2553, -1, 2553, 2619, 2620, -1, + 2619, 2553, 2552, -1, 2552, 2618, 2619, -1, + 2618, 2552, 2551, -1, 2551, 2617, 2618, -1, + 2617, 2551, 2550, -1, 2616, 2550, 2549, -1, + 2549, 2615, 2616, -1, 2615, 2549, 2548, -1, + 2548, 2614, 2615, -1, 2614, 2548, 2547, -1, + 2547, 2612, 2614, -1, 2612, 2547, 2546, -1, + 2612, 2546, 2635, -1, 2635, 2613, 2612, -1, + 2636, 2609, 2611, -1, 2609, 2636, 2501, -1, + 2501, 2607, 2609, -1, 2607, 2501, 1155, -1, + 1155, 2605, 2607, -1, 2605, 1155, 1156, -1, + 1156, 2603, 2605, -1, 2603, 1156, 1157, -1, + 1157, 2601, 2603, -1, 2601, 1157, 1158, -1, + 1158, 2599, 2601, -1, 2599, 1158, 1159, -1, + 1159, 2597, 2599, -1, 2597, 1159, 1160, -1, + 1160, 2595, 2597, -1, 2595, 1160, 1161, -1, + 1161, 2593, 2595, -1, 2593, 1161, 1162, -1, + 1162, 2591, 2593, -1, 2591, 1162, 1163, -1, + 1163, 2589, 2591, -1, 2589, 1163, 1164, -1, + 1164, 2587, 2589, -1, 2587, 1164, 1165, -1, + 1165, 2585, 2587, -1, 2585, 1165, 1166, -1, + 1166, 2583, 2585, -1, 1167, 2581, 2583, -1, + 2581, 1167, 1168, -1, 1168, 2579, 2581, -1, + 2579, 1168, 1169, -1, 1169, 2577, 2579, -1, + 2577, 1169, 1170, -1, 1170, 2575, 2577, -1, + 2575, 1170, 1171, -1, 1171, 2573, 2575, -1, + 2573, 1171, 1172, -1, 1172, 2571, 2573, -1, + 2571, 1172, 1173, -1, 1173, 1212, 2571, -1, + 2637, 2571, 1212, -1, 2637, 1212, 1177, -1, + 2637, 1177, 1179, -1, 1179, 2571, 2637, -1, + 1179, 2572, 2571, -1, 2572, 1179, 1178, -1, + 2572, 1178, 2638, -1, 2638, 2570, 2572, -1, + 2638, 2633, 2570, -1, 2638, 1178, 2633, -1, + 1178, 2568, 2633, -1, 1178, 2639, 2568, -1, + 2639, 1178, 1180, -1, 1180, 2640, 2639, -1, + 2640, 1180, 1182, -1, 1182, 2641, 2640, -1, + 2641, 1182, 1184, -1, 1184, 2642, 2641, -1, + 1188, 2643, 2644, -1, 2643, 1188, 1190, -1, + 1190, 2645, 2643, -1, 1192, 2646, 2645, -1, + 2646, 1192, 1194, -1, 1194, 2647, 2646, -1, + 2647, 1194, 1196, -1, 1196, 2648, 2647, -1, + 2648, 1196, 1175, -1, 1175, 1174, 2648, -1, + 888, 2648, 1174, -1, 2648, 888, 887, -1, + 887, 2647, 2648, -1, 2647, 887, 886, -1, + 886, 2646, 2647, -1, 2646, 886, 885, -1, + 885, 2645, 2646, -1, 2645, 885, 884, -1, + 884, 2643, 2645, -1, 2643, 884, 883, -1, + 883, 2644, 2643, -1, 881, 2641, 2642, -1, + 2641, 881, 880, -1, 880, 2640, 2641, -1, + 2640, 880, 879, -1, 879, 2639, 2640, -1, + 2639, 879, 878, -1, 878, 2568, 2639, -1, + 2568, 878, 877, -1, 877, 2569, 2568, -1, + 2649, 2569, 877, -1, 2649, 2565, 2569, -1, + 2649, 2566, 2565, -1, 2566, 2649, 877, -1, + 2566, 877, 876, -1, 876, 2503, 2566, -1, + 876, 875, 2503, -1, 875, 2504, 2503, -1, + 875, 48, 2504, -1, 2504, 48, 47, -1, + 47, 2502, 2504, -1, 47, 2650, 2502, -1, + 2650, 47, 46, -1, 2650, 46, 276, -1, + 276, 277, 2650, -1, 277, 2502, 2650, -1, + 277, 2506, 2502, -1, 2506, 277, 278, -1, + 278, 2508, 2506, -1, 2508, 278, 279, -1, + 279, 2510, 2508, -1, 2510, 279, 280, -1, + 280, 2512, 2510, -1, 2512, 280, 281, -1, + 281, 2514, 2512, -1, 2514, 281, 282, -1, + 282, 2516, 2514, -1, 2516, 282, 283, -1, + 283, 2518, 2516, -1, 2518, 283, 284, -1, + 284, 2520, 2518, -1, 285, 2522, 2520, -1, + 2522, 285, 286, -1, 286, 2524, 2522, -1, + 2524, 286, 287, -1, 287, 2526, 2524, -1, + 2526, 287, 288, -1, 288, 2528, 2526, -1, + 2528, 288, 289, -1, 289, 2530, 2528, -1, + 2530, 289, 290, -1, 290, 2532, 2530, -1, + 2532, 290, 291, -1, 291, 2534, 2532, -1, + 2534, 291, 292, -1, 292, 2536, 2534, -1, + 2536, 292, 293, -1, 293, 2538, 2536, -1, + 2538, 293, 294, -1, 294, 2540, 2538, -1, + 2540, 294, 295, -1, 295, 2542, 2540, -1, + 2542, 295, 296, -1, 2542, 296, 299, -1, + 299, 2543, 2542, -1, 2651, 2546, 2545, -1, + 2651, 2635, 2546, -1, 2652, 2501, 2636, -1, + 2652, 2500, 2501, -1, 2653, 2654, 2655, -1, + 2653, 2656, 2654, -1, 2657, 2658, 2656, -1, + 2658, 2659, 2656, -1, 2659, 2654, 2656, -1, + 2660, 2661, 2662, -1, 2663, 2664, 2665, -1, + 2663, 2666, 2664, -1, 2666, 2660, 2662, -1, + 2662, 2664, 2666, -1, 2662, 2667, 2664, -1, + 2662, 2668, 2667, -1, 2668, 2662, 2661, -1, + 2669, 2667, 2668, -1, 2669, 2670, 2667, -1, + 2667, 2671, 2672, -1, 2671, 2667, 2670, -1, + 2670, 2673, 2671, -1, 2674, 2671, 2673, -1, + 2675, 2671, 2674, -1, 2675, 2676, 2671, -1, + 2675, 2677, 2676, -1, 2677, 2678, 2676, -1, + 2678, 2657, 2656, -1, 2656, 2676, 2678, -1, + 2679, 2671, 2676, -1, 2679, 2672, 2671, -1, + 600, 599, 2680, -1, 599, 2681, 2680, -1, + 599, 2682, 2681, -1, 2682, 599, 598, -1, + 598, 2683, 2682, -1, 2683, 598, 597, -1, + 597, 2684, 2683, -1, 2684, 597, 596, -1, + 596, 2685, 2684, -1, 2685, 596, 595, -1, + 595, 2686, 2685, -1, 2686, 595, 594, -1, + 594, 2687, 2686, -1, 2687, 594, 593, -1, + 593, 2688, 2687, -1, 2688, 593, 592, -1, + 592, 2689, 2688, -1, 2689, 592, 591, -1, + 591, 2690, 2689, -1, 2690, 591, 590, -1, + 590, 2691, 2690, -1, 2691, 590, 589, -1, + 589, 2692, 2691, -1, 2692, 589, 588, -1, + 588, 2693, 2692, -1, 2693, 588, 587, -1, + 587, 2694, 2693, -1, 2695, 586, 585, -1, + 585, 2696, 2695, -1, 2696, 585, 584, -1, + 584, 2697, 2696, -1, 2697, 584, 583, -1, + 583, 2698, 2697, -1, 2698, 583, 582, -1, + 582, 2699, 2698, -1, 2699, 582, 581, -1, + 581, 2700, 2699, -1, 2700, 581, 579, -1, + 579, 2701, 2700, -1, 2702, 2703, 2704, -1, + 2702, 2705, 2703, -1, 2705, 2701, 2703, -1, + 2705, 2700, 2701, -1, 2705, 2702, 2700, -1, + 2702, 2704, 2700, -1, 2706, 2707, 2708, -1, + 2708, 2709, 2706, -1, 2710, 2709, 2708, -1, + 2710, 2708, 2704, -1, 2708, 2700, 2704, -1, + 2708, 2699, 2700, -1, 2699, 2708, 2707, -1, + 2707, 2698, 2699, -1, 2698, 2707, 2711, -1, + 2711, 2697, 2698, -1, 2697, 2711, 2712, -1, + 2712, 2696, 2697, -1, 2696, 2712, 2713, -1, + 2713, 2695, 2696, -1, 2694, 2714, 2715, -1, + 2715, 2693, 2694, -1, 2693, 2715, 2716, -1, + 2716, 2692, 2693, -1, 2692, 2716, 2717, -1, + 2717, 2691, 2692, -1, 2691, 2717, 2718, -1, + 2718, 2690, 2691, -1, 2690, 2718, 2719, -1, + 2719, 2689, 2690, -1, 2689, 2719, 2720, -1, + 2720, 2688, 2689, -1, 2688, 2720, 2721, -1, + 2721, 2687, 2688, -1, 2687, 2721, 2722, -1, + 2722, 2686, 2687, -1, 2686, 2722, 2723, -1, + 2723, 2685, 2686, -1, 2685, 2723, 2724, -1, + 2724, 2684, 2685, -1, 2684, 2724, 2725, -1, + 2725, 2683, 2684, -1, 2683, 2725, 2726, -1, + 2726, 2682, 2683, -1, 2682, 2726, 2727, -1, + 2727, 2681, 2682, -1, 2681, 2727, 2728, -1, + 2728, 2729, 2681, -1, 2730, 2681, 2729, -1, + 2730, 2680, 2681, -1, 2731, 2729, 2728, -1, + 2731, 2728, 2732, -1, 2732, 2667, 2672, -1, + 2667, 2732, 2728, -1, 2728, 2664, 2667, -1, + 2664, 2728, 2727, -1, 2727, 2733, 2664, -1, + 2733, 2727, 2726, -1, 2726, 2734, 2733, -1, + 2734, 2726, 2725, -1, 2725, 2735, 2734, -1, + 2735, 2725, 2724, -1, 2724, 2736, 2735, -1, + 2736, 2724, 2723, -1, 2723, 2737, 2736, -1, + 2737, 2723, 2722, -1, 2722, 2738, 2737, -1, + 2738, 2722, 2721, -1, 2721, 2739, 2738, -1, + 2739, 2721, 2720, -1, 2720, 2740, 2739, -1, + 2740, 2720, 2719, -1, 2719, 2741, 2740, -1, + 2741, 2719, 2718, -1, 2718, 2742, 2741, -1, + 2742, 2718, 2717, -1, 2717, 2743, 2742, -1, + 2743, 2717, 2716, -1, 2716, 2744, 2743, -1, + 2744, 2716, 2715, -1, 2715, 2745, 2744, -1, + 2745, 2715, 2714, -1, 2714, 2746, 2745, -1, + 2747, 2713, 2712, -1, 2712, 2748, 2747, -1, + 2748, 2712, 2711, -1, 2711, 2749, 2748, -1, + 2749, 2711, 2707, -1, 2707, 2706, 2749, -1, + 2750, 2749, 2706, -1, 2749, 2750, 2751, -1, + 2751, 2748, 2749, -1, 2748, 2751, 2752, -1, + 2752, 2747, 2748, -1, 2746, 2753, 2754, -1, + 2754, 2745, 2746, -1, 2745, 2754, 2755, -1, + 2755, 2744, 2745, -1, 2744, 2755, 2756, -1, + 2756, 2743, 2744, -1, 2743, 2756, 2757, -1, + 2757, 2742, 2743, -1, 2742, 2757, 2758, -1, + 2758, 2741, 2742, -1, 2741, 2758, 2759, -1, + 2759, 2740, 2741, -1, 2740, 2759, 2760, -1, + 2760, 2739, 2740, -1, 2739, 2760, 2761, -1, + 2761, 2738, 2739, -1, 2738, 2761, 2762, -1, + 2762, 2737, 2738, -1, 2737, 2762, 2763, -1, + 2763, 2736, 2737, -1, 2764, 2735, 2736, -1, + 2735, 2764, 2765, -1, 2765, 2734, 2735, -1, + 2734, 2765, 2766, -1, 2766, 2733, 2734, -1, + 2733, 2766, 2767, -1, 2767, 2664, 2733, -1, + 2767, 2665, 2664, -1, 2665, 2767, 2768, -1, + 2768, 2767, 45, -1, 2767, 43, 45, -1, + 43, 2767, 2766, -1, 43, 2766, 2769, -1, + 2769, 41, 43, -1, 2770, 2013, 2012, -1, + 2770, 2769, 2013, -1, 2013, 2769, 2766, -1, + 2013, 2766, 2765, -1, 2765, 2014, 2013, -1, + 2014, 2765, 2764, -1, 2764, 2015, 2014, -1, + 2763, 2016, 2015, -1, 2016, 2763, 2762, -1, + 2762, 2017, 2016, -1, 2017, 2762, 2761, -1, + 2761, 2018, 2017, -1, 2018, 2761, 2760, -1, + 2760, 2019, 2018, -1, 2019, 2760, 2759, -1, + 2759, 2020, 2019, -1, 2020, 2759, 2758, -1, + 2758, 2021, 2020, -1, 2021, 2758, 2757, -1, + 2757, 2022, 2021, -1, 2022, 2757, 2756, -1, + 2756, 2023, 2022, -1, 2023, 2756, 2755, -1, + 2755, 2024, 2023, -1, 2024, 2755, 2754, -1, + 2754, 2025, 2024, -1, 2025, 2754, 2753, -1, + 2753, 2026, 2025, -1, 2027, 2752, 2751, -1, + 2751, 2028, 2027, -1, 2028, 2751, 2750, -1, + 2028, 2750, 2771, -1, 2772, 2771, 2750, -1, + 2771, 2772, 2773, -1, 2771, 2773, 2774, -1, + 2774, 2028, 2771, -1, 2774, 2029, 2028, -1, + 2774, 2773, 2029, -1, 2773, 2031, 2029, -1, + 2773, 2193, 2031, -1, 2193, 2773, 2775, -1, + 2775, 2192, 2193, -1, 2192, 2775, 2776, -1, + 2776, 2191, 2192, -1, 2191, 2776, 2777, -1, + 2777, 2190, 2191, -1, 2190, 2777, 2778, -1, + 2778, 2189, 2190, -1, 2189, 2778, 2779, -1, + 2779, 2187, 2189, -1, 2187, 2779, 2780, -1, + 2780, 2188, 2187, -1, 2188, 2780, 2781, -1, + 2186, 2781, 2782, -1, 2782, 2185, 2186, -1, + 2185, 2782, 2783, -1, 2783, 2183, 2185, -1, + 2784, 2184, 2183, -1, 2184, 2784, 2785, -1, + 2786, 2787, 2788, -1, 2789, 2790, 2791, -1, + 2791, 2792, 2789, -1, 2792, 2791, 2793, -1, + 2793, 2794, 2792, -1, 2794, 2793, 2795, -1, + 2795, 2796, 2794, -1, 2796, 2795, 2797, -1, + 2797, 2798, 2796, -1, 2799, 2800, 2798, -1, + 2800, 2799, 2801, -1, 2801, 2802, 2800, -1, + 2802, 2801, 2803, -1, 2803, 2804, 2802, -1, + 2804, 2803, 2805, -1, 2805, 2806, 2804, -1, + 2806, 2805, 2807, -1, 2807, 2808, 2806, -1, + 2808, 2807, 2809, -1, 2809, 2810, 2808, -1, + 2810, 2809, 2787, -1, 2787, 2786, 2810, -1, + 2785, 2810, 2786, -1, 2810, 2785, 2784, -1, + 2784, 2808, 2810, -1, 2783, 2806, 2808, -1, + 2806, 2783, 2782, -1, 2782, 2804, 2806, -1, + 2804, 2782, 2781, -1, 2781, 2802, 2804, -1, + 2802, 2781, 2780, -1, 2780, 2800, 2802, -1, + 2800, 2780, 2779, -1, 2779, 2798, 2800, -1, + 2798, 2779, 2778, -1, 2778, 2796, 2798, -1, + 2796, 2778, 2777, -1, 2777, 2794, 2796, -1, + 2794, 2777, 2776, -1, 2776, 2792, 2794, -1, + 2792, 2776, 2775, -1, 2775, 2789, 2792, -1, + 2789, 2775, 2773, -1, 2789, 2773, 2772, -1, + 2772, 2811, 2789, -1, 2772, 2750, 2811, -1, + 2750, 2706, 2811, -1, 2812, 2811, 2706, -1, + 2812, 2789, 2811, -1, 2812, 2790, 2789, -1, + 2790, 2812, 2706, -1, 2790, 2706, 2709, -1, + 2709, 2791, 2790, -1, 2709, 2710, 2791, -1, + 2710, 2704, 2791, -1, 2791, 2704, 2703, -1, + 2703, 2793, 2791, -1, 2793, 2703, 2813, -1, + 2813, 2795, 2793, -1, 2795, 2813, 2814, -1, + 2814, 2797, 2795, -1, 2797, 2814, 2815, -1, + 2799, 2815, 2816, -1, 2816, 2801, 2799, -1, + 2801, 2816, 2817, -1, 2817, 2803, 2801, -1, + 2803, 2817, 2818, -1, 2818, 2805, 2803, -1, + 2805, 2818, 2819, -1, 2819, 2807, 2805, -1, + 2807, 2819, 2820, -1, 2820, 2809, 2807, -1, + 2821, 2787, 2809, -1, 2787, 2821, 2822, -1, + 2822, 2788, 2787, -1, 2788, 2822, 2823, -1, + 2824, 2825, 2826, -1, 2827, 2828, 2829, -1, + 2827, 2830, 2828, -1, 2830, 2827, 2831, -1, + 2831, 2832, 2830, -1, 2832, 2831, 2833, -1, + 2833, 2834, 2832, -1, 2834, 2833, 2835, -1, + 2835, 2836, 2834, -1, 2836, 2835, 2837, -1, + 2837, 2838, 2836, -1, 2838, 2837, 2839, -1, + 2839, 2840, 2838, -1, 2840, 2839, 2841, -1, + 2841, 2842, 2840, -1, 2842, 2841, 2843, -1, + 2843, 2844, 2842, -1, 2844, 2843, 2845, -1, + 2845, 2846, 2844, -1, 2846, 2845, 2847, -1, + 2847, 2848, 2846, -1, 2848, 2847, 2825, -1, + 2825, 2824, 2848, -1, 2823, 2848, 2824, -1, + 2848, 2823, 2822, -1, 2822, 2846, 2848, -1, + 2846, 2822, 2821, -1, 2821, 2844, 2846, -1, + 2820, 2842, 2844, -1, 2842, 2820, 2819, -1, + 2819, 2840, 2842, -1, 2840, 2819, 2818, -1, + 2818, 2838, 2840, -1, 2838, 2818, 2817, -1, + 2817, 2836, 2838, -1, 2836, 2817, 2816, -1, + 2816, 2834, 2836, -1, 2834, 2816, 2815, -1, + 2815, 2832, 2834, -1, 2832, 2815, 2814, -1, + 2814, 2830, 2832, -1, 2830, 2814, 2813, -1, + 2813, 2828, 2830, -1, 2828, 2813, 2703, -1, + 2828, 2703, 2701, -1, 2849, 2828, 2701, -1, + 2849, 2701, 579, -1, 2849, 579, 580, -1, + 580, 2828, 2849, -1, 580, 2829, 2828, -1, + 2829, 580, 537, -1, 2829, 537, 536, -1, + 536, 2827, 2829, -1, 536, 538, 2827, -1, + 538, 2850, 2827, -1, 2850, 538, 539, -1, + 2850, 539, 623, -1, 623, 625, 2850, -1, + 625, 2827, 2850, -1, 625, 2831, 2827, -1, + 2831, 625, 2851, -1, 2851, 2833, 2831, -1, + 2852, 2835, 2833, -1, 2835, 2852, 2853, -1, + 2853, 2837, 2835, -1, 2837, 2853, 2854, -1, + 2854, 2839, 2837, -1, 2839, 2854, 2855, -1, + 2855, 2841, 2839, -1, 2841, 2855, 2856, -1, + 2856, 2843, 2841, -1, 2843, 2856, 2857, -1, + 2857, 2845, 2843, -1, 2845, 2857, 2858, -1, + 2858, 2847, 2845, -1, 2847, 2858, 2859, -1, + 2859, 2825, 2847, -1, 2825, 2859, 2860, -1, + 2860, 2826, 2825, -1, 2826, 2860, 2861, -1, + 2862, 2863, 2864, -1, 2864, 2865, 2866, -1, + 2865, 2864, 2863, -1, 2863, 2867, 2865, -1, + 2867, 2863, 2868, -1, 2868, 2869, 2867, -1, + 2869, 2868, 2870, -1, 2870, 2871, 2869, -1, + 2871, 2870, 2872, -1, 2872, 2873, 2871, -1, + 2873, 2872, 2874, -1, 2874, 2875, 2873, -1, + 2875, 2874, 2876, -1, 2876, 2877, 2875, -1, + 2877, 2876, 2878, -1, 2878, 2879, 2877, -1, + 2879, 2878, 2880, -1, 2880, 2881, 2879, -1, + 2881, 2880, 2882, -1, 2882, 2883, 2881, -1, + 2883, 2882, 2884, -1, 2884, 2885, 2883, -1, + 2885, 2886, 2887, -1, 2885, 2884, 2886, -1, + 2888, 2889, 2886, -1, 2886, 2890, 2888, -1, + 2890, 2886, 2884, -1, 2884, 2891, 2890, -1, + 2891, 2884, 2882, -1, 2882, 2892, 2891, -1, + 2892, 2882, 2880, -1, 2880, 2893, 2892, -1, + 2893, 2880, 2878, -1, 2878, 2894, 2893, -1, + 2894, 2878, 2876, -1, 2876, 2895, 2894, -1, + 2895, 2876, 2874, -1, 2874, 2896, 2895, -1, + 2896, 2874, 2872, -1, 2872, 2897, 2896, -1, + 2897, 2872, 2870, -1, 2870, 2898, 2897, -1, + 2898, 2870, 2868, -1, 2868, 2899, 2898, -1, + 2899, 2868, 2863, -1, 2863, 2862, 2899, -1, + 2861, 2899, 2862, -1, 2899, 2861, 2860, -1, + 2860, 2898, 2899, -1, 2898, 2860, 2859, -1, + 2859, 2897, 2898, -1, 2897, 2859, 2858, -1, + 2858, 2896, 2897, -1, 2896, 2858, 2857, -1, + 2857, 2895, 2896, -1, 2895, 2857, 2856, -1, + 2856, 2894, 2895, -1, 2894, 2856, 2855, -1, + 2855, 2893, 2894, -1, 2893, 2855, 2854, -1, + 2854, 2892, 2893, -1, 2892, 2854, 2853, -1, + 2853, 2891, 2892, -1, 2891, 2853, 2852, -1, + 2852, 2890, 2891, -1, 2851, 2888, 2890, -1, + 2888, 2851, 625, -1, 625, 624, 2888, -1, + 2900, 2888, 624, -1, 624, 626, 2900, -1, + 626, 628, 2900, -1, 2901, 2900, 628, -1, + 2901, 2888, 2900, -1, 2901, 2889, 2888, -1, + 2889, 2901, 628, -1, 2889, 628, 670, -1, + 670, 2886, 2889, -1, 670, 671, 2886, -1, + 671, 672, 2886, -1, 672, 2887, 2886, -1, + 2887, 672, 488, -1, 2887, 488, 487, -1, + 487, 2885, 2887, -1, 487, 489, 2885, -1, + 2885, 489, 492, -1, 492, 2883, 2885, -1, + 2883, 492, 2902, -1, 2902, 2881, 2883, -1, + 2881, 2902, 2903, -1, 2903, 2879, 2881, -1, + 2879, 2903, 2904, -1, 2904, 2877, 2879, -1, + 2877, 2904, 2905, -1, 2905, 2875, 2877, -1, + 2875, 2905, 2906, -1, 2906, 2873, 2875, -1, + 2873, 2906, 2907, -1, 2907, 2871, 2873, -1, + 2871, 2907, 2908, -1, 2908, 2869, 2871, -1, + 2869, 2908, 2909, -1, 2909, 2867, 2869, -1, + 2867, 2909, 2910, -1, 2910, 2865, 2867, -1, + 2865, 2910, 2911, -1, 2911, 2866, 2865, -1, + 2866, 2911, 2912, -1, 2913, 2914, 2915, -1, + 2916, 2917, 2918, -1, 2918, 2919, 2916, -1, + 2919, 2918, 2920, -1, 2920, 2921, 2919, -1, + 2921, 2920, 2922, -1, 2922, 2923, 2921, -1, + 2923, 2922, 2924, -1, 2924, 2925, 2923, -1, + 2925, 2924, 2926, -1, 2926, 2927, 2925, -1, + 2928, 2929, 2927, -1, 2929, 2928, 2930, -1, + 2930, 2931, 2929, -1, 2931, 2930, 2932, -1, + 2932, 2933, 2931, -1, 2933, 2932, 2934, -1, + 2934, 2935, 2933, -1, 2935, 2934, 2936, -1, + 2936, 2937, 2935, -1, 2937, 2936, 2914, -1, + 2914, 2913, 2937, -1, 2912, 2937, 2913, -1, + 2937, 2912, 2911, -1, 2911, 2935, 2937, -1, + 2935, 2911, 2910, -1, 2910, 2933, 2935, -1, + 2933, 2910, 2909, -1, 2909, 2931, 2933, -1, + 2931, 2909, 2908, -1, 2908, 2929, 2931, -1, + 2929, 2908, 2907, -1, 2907, 2927, 2929, -1, + 2927, 2907, 2906, -1, 2906, 2925, 2927, -1, + 2925, 2906, 2905, -1, 2905, 2923, 2925, -1, + 2923, 2905, 2904, -1, 2904, 2921, 2923, -1, + 2921, 2904, 2903, -1, 2903, 2919, 2921, -1, + 2919, 2903, 2902, -1, 2902, 2916, 2919, -1, + 2916, 2902, 492, -1, 2916, 492, 493, -1, + 493, 2938, 2916, -1, 493, 327, 2938, -1, + 327, 329, 2938, -1, 2939, 2938, 329, -1, + 2939, 2916, 2938, -1, 2939, 2917, 2916, -1, + 2917, 2939, 329, -1, 2917, 329, 447, -1, + 447, 2918, 2917, -1, 447, 446, 2918, -1, + 446, 333, 2918, -1, 2918, 333, 334, -1, + 334, 2920, 2918, -1, 2920, 334, 2940, -1, + 2940, 2922, 2920, -1, 2922, 2940, 2941, -1, + 2941, 2924, 2922, -1, 2924, 2941, 2942, -1, + 2942, 2926, 2924, -1, 2926, 2942, 2943, -1, + 2928, 2943, 2944, -1, 2944, 2930, 2928, -1, + 2930, 2944, 2945, -1, 2945, 2932, 2930, -1, + 2932, 2945, 2946, -1, 2946, 2934, 2932, -1, + 2934, 2946, 2947, -1, 2947, 2936, 2934, -1, + 2936, 2947, 2948, -1, 2948, 2914, 2936, -1, + 2914, 2948, 2949, -1, 2949, 2915, 2914, -1, + 2915, 2949, 2950, -1, 2950, 2951, 2952, -1, + 2951, 2950, 2949, -1, 2949, 2953, 2951, -1, + 2953, 2949, 2948, -1, 2948, 2954, 2953, -1, + 2954, 2948, 2947, -1, 2947, 2955, 2954, -1, + 2955, 2947, 2946, -1, 2946, 2956, 2955, -1, + 2956, 2946, 2945, -1, 2945, 2957, 2956, -1, + 2957, 2945, 2944, -1, 2944, 2958, 2957, -1, + 2958, 2944, 2943, -1, 2959, 2943, 2942, -1, + 2942, 2960, 2959, -1, 2960, 2942, 2941, -1, + 2941, 2961, 2960, -1, 2961, 2941, 2940, -1, + 2940, 2962, 2961, -1, 2962, 2940, 334, -1, + 2962, 334, 335, -1, 2963, 2962, 335, -1, + 2963, 335, 336, -1, 2963, 336, 394, -1, + 394, 2962, 2963, -1, 394, 2964, 2962, -1, + 2964, 394, 393, -1, 2964, 393, 395, -1, + 395, 397, 2964, -1, 397, 2962, 2964, -1, + 397, 2961, 2962, -1, 2965, 2960, 2961, -1, + 2966, 2959, 2960, -1, 2959, 2966, 2967, -1, + 2968, 2957, 2958, -1, 2969, 2956, 2957, -1, + 2956, 2969, 2970, -1, 2970, 2955, 2956, -1, + 2955, 2970, 2971, -1, 2971, 2954, 2955, -1, + 2954, 2971, 2972, -1, 2972, 2953, 2954, -1, + 2953, 2972, 2973, -1, 2973, 2951, 2953, -1, + 2951, 2973, 2974, -1, 2974, 2952, 2951, -1, + 2952, 2974, 2975, -1, 2975, 2976, 2977, -1, + 2976, 2975, 2974, -1, 2974, 2978, 2976, -1, + 2978, 2974, 2973, -1, 2979, 2973, 2972, -1, + 2972, 2980, 2979, -1, 2980, 2972, 2971, -1, + 2971, 2981, 2980, -1, 2981, 2971, 2970, -1, + 2970, 2982, 2981, -1, 2982, 2970, 2969, -1, + 2969, 2983, 2982, -1, 2968, 2984, 2983, -1, + 2967, 2985, 2984, -1, 2985, 2967, 2966, -1, + 2966, 2986, 2985, -1, 2965, 2987, 2986, -1, + 397, 2988, 2987, -1, 2988, 397, 396, -1, + 2988, 396, 398, -1, 2988, 398, 2989, -1, + 2989, 2987, 2988, -1, 2989, 2990, 2987, -1, + 2990, 2989, 0, -1, 0, 2989, 398, -1, + 398, 40, 0, -1, 40, 398, 399, -1, + 399, 38, 40, -1, 38, 399, 400, -1, + 400, 36, 38, -1, 36, 400, 401, -1, + 401, 34, 36, -1, 34, 401, 402, -1, + 402, 32, 34, -1, 403, 30, 32, -1, + 30, 403, 404, -1, 404, 28, 30, -1, + 28, 404, 405, -1, 405, 26, 28, -1, + 26, 405, 406, -1, 406, 24, 26, -1, + 24, 406, 407, -1, 407, 22, 24, -1, + 22, 407, 408, -1, 408, 20, 22, -1, + 20, 408, 409, -1, 409, 18, 20, -1, + 18, 409, 410, -1, 410, 16, 18, -1, + 16, 410, 411, -1, 411, 14, 16, -1, + 412, 12, 14, -1, 12, 412, 413, -1, + 413, 10, 12, -1, 414, 8, 10, -1, + 8, 414, 415, -1, 415, 6, 8, -1, + 416, 3, 6, -1, 3, 416, 417, -1, + 3, 417, 420, -1, 420, 4, 3, -1, + 2991, 5, 4, -1, 2991, 2992, 5, -1, + 2993, 422, 423, -1, 2993, 423, 426, -1, + 2994, 426, 425, -1, 2994, 425, 466, -1, + 2995, 467, 468, -1, 2995, 468, 514, -1, + 701, 702, 2996, -1, 702, 704, 2996, -1, + 2997, 2996, 704, -1, 2997, 704, 2998, -1, + 2999, 2998, 704, -1, 704, 3000, 2999, -1, + 3000, 704, 703, -1, 703, 3001, 3000, -1, + 3001, 703, 705, -1, 705, 3002, 3001, -1, + 3002, 705, 706, -1, 706, 3003, 3002, -1, + 3003, 706, 707, -1, 707, 3004, 3003, -1, + 3004, 707, 708, -1, 708, 3005, 3004, -1, + 3005, 708, 709, -1, 709, 3006, 3005, -1, + 3006, 709, 710, -1, 710, 3007, 3006, -1, + 3007, 710, 711, -1, 711, 3008, 3007, -1, + 3008, 711, 712, -1, 712, 3009, 3008, -1, + 3009, 712, 713, -1, 713, 3010, 3009, -1, + 3010, 713, 714, -1, 3011, 714, 715, -1, + 715, 3012, 3011, -1, 3012, 715, 716, -1, + 716, 3013, 3012, -1, 3013, 716, 717, -1, + 717, 3014, 3013, -1, 3014, 717, 718, -1, + 718, 3015, 3014, -1, 3015, 718, 719, -1, + 719, 3016, 3015, -1, 3016, 719, 720, -1, + 720, 3017, 3016, -1, 3017, 720, 721, -1, + 721, 722, 3017, -1, 3018, 3017, 722, -1, + 3017, 3018, 3019, -1, 3019, 3016, 3017, -1, + 3016, 3019, 3020, -1, 3020, 3015, 3016, -1, + 3015, 3020, 3021, -1, 3021, 3014, 3015, -1, + 3014, 3021, 3022, -1, 3022, 3013, 3014, -1, + 3013, 3022, 3023, -1, 3023, 3012, 3013, -1, + 3012, 3023, 3024, -1, 3024, 3011, 3012, -1, + 3011, 3024, 3025, -1, 3010, 3025, 3026, -1, + 3026, 3009, 3010, -1, 3009, 3026, 3027, -1, + 3027, 3008, 3009, -1, 3008, 3027, 3028, -1, + 3028, 3007, 3008, -1, 3007, 3028, 3029, -1, + 3029, 3006, 3007, -1, 3006, 3029, 3030, -1, + 3030, 3005, 3006, -1, 3005, 3030, 3031, -1, + 3031, 3004, 3005, -1, 3004, 3031, 3032, -1, + 3032, 3003, 3004, -1, 3003, 3032, 3033, -1, + 3033, 3002, 3003, -1, 3002, 3033, 3034, -1, + 3034, 3001, 3002, -1, 3001, 3034, 3035, -1, + 3035, 3000, 3001, -1, 3000, 3035, 3036, -1, + 3036, 2999, 3000, -1, 2999, 3036, 3037, -1, + 3037, 3038, 2999, -1, 3039, 2999, 3038, -1, + 3039, 2998, 2999, -1, 3038, 3037, 2992, -1, + 3037, 5, 2992, -1, 3037, 7, 5, -1, + 7, 3037, 3036, -1, 3036, 9, 7, -1, + 9, 3036, 3035, -1, 3035, 11, 9, -1, + 11, 3035, 3034, -1, 3034, 13, 11, -1, + 13, 3034, 3033, -1, 3033, 15, 13, -1, + 15, 3033, 3032, -1, 3032, 17, 15, -1, + 17, 3032, 3031, -1, 3031, 19, 17, -1, + 19, 3031, 3030, -1, 3030, 21, 19, -1, + 21, 3030, 3029, -1, 3029, 23, 21, -1, + 23, 3029, 3028, -1, 3028, 25, 23, -1, + 25, 3028, 3027, -1, 3027, 27, 25, -1, + 27, 3027, 3026, -1, 3026, 29, 27, -1, + 29, 3026, 3025, -1, 3025, 31, 29, -1, + 31, 3025, 3024, -1, 3024, 33, 31, -1, + 33, 3024, 3023, -1, 3023, 35, 33, -1, + 35, 3023, 3022, -1, 3022, 37, 35, -1, + 37, 3022, 3021, -1, 3021, 39, 37, -1, + 39, 3021, 3020, -1, 3020, 1, 39, -1, + 1, 3020, 3019, -1, 3019, 2, 1, -1, + 2, 3019, 3018, -1, 3018, 3040, 2, -1, + 3018, 722, 3040, -1, 3041, 3040, 722, -1, + 3041, 722, 724, -1, 724, 72, 3041, -1, + 72, 3042, 3041, -1, 72, 71, 3042, -1, + 3043, 3044, 3042, -1, 3042, 3045, 3043, -1, + 3045, 3042, 71, -1, 71, 3046, 3045, -1, + 69, 3047, 3046, -1, 3047, 69, 67, -1, + 67, 3048, 3047, -1, 3048, 67, 65, -1, + 65, 3049, 3048, -1, 3049, 65, 63, -1, + 63, 3050, 3049, -1, 3050, 63, 61, -1, + 61, 3051, 3050, -1, 3051, 61, 59, -1, + 59, 3052, 3051, -1, 3052, 59, 57, -1, + 57, 3053, 3052, -1, 3053, 57, 55, -1, + 55, 3054, 3053, -1, 3054, 55, 53, -1, + 53, 3055, 3054, -1, 3055, 53, 50, -1, + 3055, 50, 3056, -1, 50, 52, 3056, -1, + 52, 736, 3056, -1, 736, 737, 3056, -1, + 737, 739, 3056, -1, 739, 774, 3056, -1, + 774, 776, 3056, -1, 776, 799, 3056, -1, + 799, 850, 3056, -1, 850, 825, 3056, -1, + 825, 800, 3056, -1, 800, 802, 3056, -1, + 802, 863, 3056, -1, 863, 865, 3056, -1, + 865, 888, 3056, -1, 888, 1174, 3056, -1, + 1174, 1176, 3056, -1, 1176, 1199, 3056, -1, + 1199, 1201, 3056, -1, 1201, 1224, 3056, -1, + 1224, 1225, 3056, -1, 1225, 1227, 3056, -1, + 1227, 1262, 3056, -1, 1262, 1263, 3056, -1, + 1263, 1265, 3056, -1, 1265, 1267, 3056, -1, + 1267, 1697, 3056, -1, 1697, 1698, 3056, -1, + 1698, 1700, 3056, -1, 1700, 1735, 3056, -1, + 1735, 1736, 3056, -1, 1736, 1738, 3056, -1, + 1738, 1773, 3056, -1, 1773, 1774, 3056, -1, + 1774, 1776, 3056, -1, 1776, 1778, 3056, -1, + 1778, 1824, 3056, -1, 1824, 1825, 3056, -1, + 1825, 1827, 3056, -1, 1827, 1831, 3056, -1, + 1831, 1833, 3056, -1, 1833, 1856, 3056, -1, + 1856, 1857, 3056, -1, 1857, 1859, 3056, -1, + 1859, 1885, 3056, -1, 1885, 1887, 3056, -1, + 1887, 1919, 3056, -1, 1919, 1921, 3056, -1, + 1921, 2301, 3056, -1, 2301, 2067, 3056, -1, + 2067, 2069, 3056, -1, 2069, 2092, 3056, -1, + 2092, 2093, 3056, -1, 2093, 2095, 3056, -1, + 2095, 2133, 3056, -1, 2133, 2135, 3056, -1, + 2135, 2157, 3056, -1, 2157, 2159, 3056, -1, + 2159, 2182, 3056, -1, 2182, 2184, 3056, -1, + 2184, 2785, 3056, -1, 2785, 2786, 3056, -1, + 2786, 2788, 3056, -1, 2788, 2823, 3056, -1, + 2823, 2824, 3056, -1, 2824, 2826, 3056, -1, + 2826, 2861, 3056, -1, 2861, 2862, 3056, -1, + 2862, 2864, 3056, -1, 2864, 2866, 3056, -1, + 2866, 2912, 3056, -1, 2912, 2913, 3056, -1, + 2913, 2915, 3056, -1, 2915, 2950, 3056, -1, + 2950, 2952, 3056, -1, 2952, 2975, 3056, -1, + 2975, 2977, 3056, -1, 2977, 3055, 3056, -1, + 2977, 3054, 3055, -1, 3054, 2977, 2976, -1, + 2976, 3053, 3054, -1, 3053, 2976, 2978, -1, + 2978, 3052, 3053, -1, 2979, 3051, 3052, -1, + 3051, 2979, 2980, -1, 2980, 3050, 3051, -1, + 3050, 2980, 2981, -1, 2981, 3049, 3050, -1, + 3049, 2981, 2982, -1, 2982, 3048, 3049, -1, + 3048, 2982, 2983, -1, 2983, 3047, 3048, -1, + 3047, 2983, 2984, -1, 2984, 3046, 3047, -1, + 3046, 2984, 2985, -1, 2985, 3045, 3046, -1, + 3045, 2985, 2986, -1, 2986, 3043, 3045, -1, + 3043, 2986, 2987, -1, 2987, 2990, 3043, -1, + 3057, 3043, 2990, -1, 2990, 0, 3057, -1, + 0, 2, 3057, -1, 3058, 3057, 2, -1, + 3058, 3043, 3057, -1, 3058, 3044, 3043, -1, + 3044, 3058, 2, -1, 3044, 2, 3040, -1, + 3040, 3042, 3044, -1, 3040, 3041, 3042, -1, + 187, 228, 231, -1, 231, 228, 232, -1, + 223, 236, 235, -1, 235, 236, 267, -1, + 224, 320, 319, -1, 319, 320, 181, -1, + 371, 370, 424, -1, 424, 370, 428, -1, + 429, 461, 462, -1, 462, 461, 472, -1, + 438, 452, 453, -1, 453, 452, 481, -1, + 488, 495, 490, -1, 490, 495, 486, -1, + 461, 473, 472, -1, 472, 473, 508, -1, + 473, 507, 508, -1, 508, 507, 523, -1, + 564, 563, 566, -1, 566, 563, 614, -1, + 563, 613, 614, -1, 614, 613, 637, -1, + 608, 643, 642, -1, 642, 643, 653, -1, + 507, 524, 523, -1, 523, 524, 657, -1, + 759, 758, 757, -1, 757, 758, 734, -1, + 757, 756, 759, -1, 759, 756, 770, -1, + 850, 826, 825, -1, 825, 826, 823, -1, + 822, 821, 824, -1, 824, 821, 860, -1, + 821, 859, 860, -1, 860, 859, 868, -1, + 856, 872, 871, -1, 871, 872, 880, -1, + 984, 983, 982, -1, 982, 983, 1034, -1, + 982, 981, 984, -1, 984, 981, 1083, -1, + 981, 1084, 1083, -1, 1083, 1084, 1087, -1, + 1184, 1183, 1186, -1, 1186, 1183, 1213, -1, + 1183, 1209, 1213, -1, 1213, 1209, 1214, -1, + 1202, 1221, 1222, -1, 1222, 1221, 1245, -1, + 1244, 1245, 1243, -1, 1243, 1245, 1221, -1, + 1207, 1216, 1217, -1, 1217, 1216, 1235, -1, + 1270, 1269, 1271, -1, 1271, 1269, 1343, -1, + 1314, 1313, 1312, -1, 1312, 1313, 1047, -1, + 1436, 1435, 1434, -1, 1434, 1435, 1450, -1, + 1417, 1418, 1416, -1, 1416, 1418, 1459, -1, + 1485, 1538, 1537, -1, 1537, 1538, 1557, -1, + 1550, 1613, 1612, -1, 1612, 1613, 1449, -1, + 1434, 1433, 1436, -1, 1436, 1433, 1640, -1, + 1402, 1399, 1653, -1, 1653, 1399, 1397, -1, + 1368, 1367, 1655, -1, 1655, 1367, 1641, -1, + 1433, 1641, 1640, -1, 1640, 1641, 1367, -1, + 950, 949, 952, -1, 952, 949, 1667, -1, + 1360, 1662, 1661, -1, 1661, 1662, 939, -1, + 952, 951, 950, -1, 950, 951, 1311, -1, + 2087, 2086, 2089, -1, 2089, 2086, 2110, -1, + 2104, 2105, 2103, -1, 2103, 2105, 2080, -1, + 2109, 2108, 2111, -1, 2111, 2108, 2127, -1, + 2126, 2141, 2148, -1, 2148, 2141, 2149, -1, + 2141, 2147, 2149, -1, 2149, 2147, 2167, -1, + 2147, 2168, 2167, -1, 2167, 2168, 2172, -1, + 2160, 2179, 2180, -1, 2180, 2179, 2186, -1, + 2165, 2174, 2175, -1, 2175, 2174, 2191, -1, + 1959, 1958, 1960, -1, 1960, 1958, 2201, -1, + 2267, 2268, 2265, -1, 2265, 2268, 2250, -1, + 2089, 2088, 2087, -1, 2087, 2088, 2299, -1, + 1921, 1943, 2301, -1, 2301, 1943, 2300, -1, + 1904, 2304, 1902, -1, 1902, 2304, 2262, -1, + 1879, 1880, 1878, -1, 1878, 1880, 2344, -1, + 1880, 2345, 2344, -1, 2344, 2345, 1854, -1, + 2397, 2419, 2418, -1, 2418, 2419, 1822, -1, + 1142, 1167, 1166, -1, 1166, 1167, 2583, -1, + 1186, 1185, 1184, -1, 1184, 1185, 2642, -1, + 869, 882, 883, -1, 883, 882, 2644, -1, + 565, 586, 587, -1, 587, 586, 2694, -1, + 2713, 2747, 2746, -1, 2746, 2747, 2753, -1, + 2747, 2752, 2753, -1, 2753, 2752, 2026, -1, + 1995, 2026, 2027, -1, 2027, 2026, 2752, -1, + 2179, 2188, 2186, -1, 2186, 2188, 2781, -1, + 2809, 2820, 2821, -1, 2821, 2820, 2844, -1, + 389, 403, 402, -1, 402, 403, 32, -1, + 378, 414, 413, -1, 413, 414, 10, -1, + 714, 3011, 3010, -1, 3010, 3011, 3025, -1, + 2973, 2979, 2978, -1, 2978, 2979, 3052, -1, + 3059, 3060, 3061, -1, 3061, 3060, 3062, -1, + 3061, 3063, 3059, -1, 3059, 3063, 3064, -1, + 3063, 3065, 3064, -1, 3064, 3065, 3066, -1, + 3067, 3068, 3069, -1, 3069, 3068, 3070, -1, + 3069, 3071, 3067, -1, 3067, 3071, 3072, -1, + 3073, 3074, 3075, -1, 3075, 3074, 3076, -1, + 3075, 3077, 3073, -1, 3073, 3077, 3078, -1, + 3077, 3079, 3078, -1, 3078, 3079, 3080, -1, + 3081, 3082, 3083, -1, 3083, 3082, 3084, -1, + 3083, 3080, 3081, -1, 3081, 3080, 3079, -1, + 3082, 3085, 3084, -1, 3084, 3085, 3086, -1, + 3087, 3066, 3088, -1, 3088, 3066, 3065, -1, + 3088, 3089, 3087, -1, 3087, 3089, 3090, -1, + 3091, 3089, 3092, -1, 3092, 3089, 3093, -1, + 3089, 3088, 3093, -1, 3093, 3088, 3065, -1, + 3093, 3065, 3063, -1, 3063, 3061, 3093, -1, + 3093, 3061, 3062, -1, 3093, 3062, 3086, -1, + 3086, 3062, 3084, -1, 3084, 3062, 3083, -1, + 3083, 3062, 3094, -1, 3083, 3094, 3095, -1, + 3095, 3096, 3083, -1, 3083, 3096, 3097, -1, + 3083, 3097, 3098, -1, 3098, 3099, 3083, -1, + 3083, 3099, 3100, -1, 3083, 3100, 3071, -1, + 3083, 3071, 3080, -1, 3080, 3071, 3078, -1, + 3078, 3071, 3073, -1, 3073, 3071, 3074, -1, + 3074, 3071, 3101, -1, 3101, 3071, 3102, -1, + 3102, 3071, 3103, -1, 3103, 3071, 3104, -1, + 3104, 3071, 3105, -1, 3105, 3071, 3069, -1, + 3105, 3069, 3070, -1, 3070, 3106, 3105, -1, + 3105, 3106, 3107, -1, 3105, 3107, 3108, -1, + 3108, 3109, 3105, -1, 3105, 3109, 3110, -1, + 3110, 3109, 3111, -1, 3111, 3109, 3112, -1, + 3112, 3109, 3113, -1, 3113, 3109, 3114, -1, + 3114, 3109, 3115, -1, 3115, 3109, 3116, -1, + 3116, 3109, 3117, -1, 3117, 3109, 3118, -1, + 3118, 3109, 3119, -1, 3119, 3109, 3120, -1, + 3120, 3109, 3121, -1, 3121, 3109, 3122, -1, + 3122, 3109, 3123, -1, 3123, 3109, 3124, -1, + 3123, 3124, 3125, -1, 3125, 3126, 3123, -1, + 3123, 3126, 3127, -1, 3123, 3127, 3128, -1, + 3128, 3129, 3123, -1, 3123, 3129, 3130, -1, + 3089, 3091, 3090, -1, 3090, 3091, 3131, -1, + 424, 372, 371, -1, 371, 372, 374, -1, + 370, 429, 428, -1, 428, 429, 462, -1, + 3132, 3133, 3095, -1, 3095, 3133, 3096, -1, + 3095, 3094, 3132, -1, 3132, 3094, 3134, -1, + 3133, 3135, 3096, -1, 3096, 3135, 3097, -1, + 566, 565, 564, -1, 564, 565, 587, -1, + 3094, 3062, 3134, -1, 3134, 3062, 3060, -1, + 3085, 3136, 3086, -1, 3086, 3136, 3093, -1, + 859, 869, 868, -1, 868, 869, 883, -1, + 3106, 3070, 3137, -1, 3137, 3070, 3068, -1, + 3137, 3138, 3106, -1, 3106, 3138, 3107, -1, + 3138, 3139, 3107, -1, 3107, 3139, 3108, -1, + 3139, 3140, 3108, -1, 3108, 3140, 3109, -1, + 983, 1033, 1034, -1, 1034, 1033, 1046, -1, + 1033, 1047, 1046, -1, 1046, 1047, 1313, -1, + 3141, 3142, 3113, -1, 3113, 3142, 3112, -1, + 3113, 3114, 3141, -1, 3141, 3114, 3143, -1, + 3142, 3144, 3112, -1, 3112, 3144, 3111, -1, + 3144, 3145, 3111, -1, 3111, 3145, 3110, -1, + 3145, 3146, 3110, -1, 3110, 3146, 3105, -1, + 1084, 1085, 1087, -1, 1087, 1085, 1127, -1, + 1209, 1130, 1214, -1, 1214, 1130, 1229, -1, + 1312, 1311, 1314, -1, 1314, 1311, 951, -1, + 3114, 3115, 3143, -1, 3143, 3115, 3147, -1, + 3115, 3116, 3147, -1, 3147, 3116, 3148, -1, + 1435, 1449, 1450, -1, 1450, 1449, 1613, -1, + 3149, 3150, 3120, -1, 3120, 3150, 3119, -1, + 3120, 3121, 3149, -1, 3149, 3121, 3151, -1, + 3121, 3122, 3151, -1, 3151, 3122, 3152, -1, + 3153, 3152, 3123, -1, 3123, 3152, 3122, -1, + 3123, 3130, 3153, -1, 3153, 3130, 3154, -1, + 3130, 3129, 3154, -1, 3154, 3129, 3155, -1, + 3129, 3128, 3155, -1, 3155, 3128, 3156, -1, + 3128, 3127, 3156, -1, 3156, 3127, 3157, -1, + 3127, 3126, 3157, -1, 3157, 3126, 3158, -1, + 3126, 3125, 3158, -1, 3158, 3125, 3159, -1, + 3125, 3124, 3159, -1, 3159, 3124, 3160, -1, + 3124, 3109, 3160, -1, 3160, 3109, 3140, -1, + 1547, 1550, 1548, -1, 1548, 1550, 1612, -1, + 3150, 3161, 3119, -1, 3119, 3161, 3118, -1, + 3161, 3162, 3118, -1, 3118, 3162, 3117, -1, + 3162, 3148, 3117, -1, 3117, 3148, 3116, -1, + 1991, 1995, 1993, -1, 1993, 1995, 2027, -1, + 2111, 2110, 2109, -1, 2109, 2110, 2086, -1, + 2108, 2126, 2127, -1, 2127, 2126, 2148, -1, + 2168, 2171, 2172, -1, 2172, 2171, 2031, -1, + 2274, 2264, 2260, -1, 2260, 2264, 3163, -1, + 2260, 3163, 3164, -1, 2260, 3164, 2259, -1, + 2259, 3164, 2258, -1, 2258, 3164, 2257, -1, + 2257, 3164, 2247, -1, 3164, 3165, 2247, -1, + 2247, 3165, 2246, -1, 2246, 3165, 2245, -1, + 2245, 3165, 2243, -1, 2243, 3165, 2288, -1, + 2288, 3165, 2241, -1, 3165, 3166, 2241, -1, + 2241, 3166, 2242, -1, 2242, 3166, 2240, -1, + 2240, 3166, 2239, -1, 2239, 3166, 2238, -1, + 2238, 3166, 3167, -1, 2238, 3167, 2059, -1, + 2059, 3167, 2232, -1, 2232, 3167, 2231, -1, + 2231, 3167, 2233, -1, 3167, 3168, 2233, -1, + 2233, 3168, 2230, -1, 2230, 3168, 2234, -1, + 2234, 3168, 2235, -1, 3168, 3169, 2235, -1, + 2235, 3169, 2236, -1, 2236, 3169, 2209, -1, + 2209, 3169, 2208, -1, 3169, 3170, 2208, -1, + 2208, 3170, 2206, -1, 2206, 3170, 2207, -1, + 2207, 3170, 1971, -1, 3170, 3171, 1971, -1, + 1971, 3171, 1970, -1, 1970, 3171, 1977, -1, + 1977, 3171, 1978, -1, 1978, 3171, 1974, -1, + 1974, 3171, 3172, -1, 1974, 3172, 1972, -1, + 1972, 3172, 1975, -1, 1975, 3172, 1976, -1, + 1976, 3172, 3173, -1, 1976, 3173, 2009, -1, + 2009, 3173, 2010, -1, 2010, 3173, 2011, -1, + 2011, 3173, 2012, -1, 3173, 3174, 2012, -1, + 2012, 3174, 2770, -1, 2770, 3174, 2769, -1, + 2769, 3174, 41, -1, 41, 3174, 42, -1, + 42, 3174, 3175, -1, 42, 3175, 44, -1, + 44, 3175, 45, -1, 45, 3175, 2768, -1, + 2768, 3175, 2665, -1, 3175, 3176, 2665, -1, + 2665, 3176, 2663, -1, 2663, 3176, 2666, -1, + 2666, 3176, 2660, -1, 2660, 3176, 2661, -1, + 2661, 3176, 3177, -1, 2661, 3177, 2668, -1, + 2668, 3177, 2669, -1, 2669, 3177, 2670, -1, + 2670, 3177, 2673, -1, 2673, 3177, 2674, -1, + 2674, 3177, 2675, -1, 3177, 3178, 2675, -1, + 2675, 3178, 2677, -1, 2677, 3178, 2678, -1, + 2678, 3178, 2657, -1, 2657, 3178, 2658, -1, + 2658, 3178, 2659, -1, 2659, 3178, 2654, -1, + 2654, 3178, 3179, -1, 2654, 3179, 2655, -1, + 2655, 3179, 3180, -1, 2655, 3180, 3181, -1, + 2655, 3181, 892, -1, 892, 3181, 3182, -1, + 892, 3182, 3183, -1, 892, 3183, 893, -1, + 893, 3183, 890, -1, 3183, 3184, 890, -1, + 890, 3184, 894, -1, 894, 3184, 895, -1, + 895, 3184, 2497, -1, 2497, 3184, 2496, -1, + 2496, 3184, 2495, -1, 3184, 3185, 2495, -1, + 2495, 3185, 2494, -1, 2494, 3185, 1525, -1, + 1525, 3185, 2493, -1, 2493, 3185, 2492, -1, + 2492, 3185, 898, -1, 898, 3185, 896, -1, + 896, 3185, 3186, -1, 896, 3186, 899, -1, + 899, 3186, 2480, -1, 2480, 3186, 2477, -1, + 2477, 3186, 2478, -1, 3186, 3187, 2478, -1, + 2478, 3187, 2488, -1, 2488, 3187, 2476, -1, + 2476, 3187, 2475, -1, 2475, 3187, 2474, -1, + 2474, 3187, 3188, -1, 2474, 3188, 1501, -1, + 1501, 3188, 1499, -1, 1499, 3188, 2473, -1, + 2473, 3188, 1516, -1, 3188, 3189, 1516, -1, + 1516, 3189, 1515, -1, 1515, 3189, 2472, -1, + 2472, 3189, 2471, -1, 2471, 3189, 2461, -1, + 2461, 3189, 3190, -1, 2461, 3190, 2459, -1, + 2459, 3190, 2462, -1, 2462, 3190, 2458, -1, + 2458, 3190, 3191, -1, 2458, 3191, 2457, -1, + 2457, 3191, 2456, -1, 2456, 3191, 2453, -1, + 2453, 3191, 3192, -1, 2453, 3192, 2454, -1, + 2454, 3192, 2455, -1, 2455, 3192, 920, -1, + 920, 3192, 921, -1, 3192, 3193, 921, -1, + 921, 3193, 2440, -1, 2440, 3193, 2439, -1, + 2439, 3193, 2438, -1, 3193, 3194, 2438, -1, + 2438, 3194, 1467, -1, 1467, 3194, 1468, -1, + 1468, 3194, 2437, -1, 3194, 3195, 2437, -1, + 2437, 3195, 2436, -1, 2436, 3195, 2435, -1, + 2435, 3195, 2434, -1, 2434, 3195, 924, -1, + 924, 3195, 3196, -1, 924, 3196, 922, -1, + 922, 3196, 925, -1, 925, 3196, 2433, -1, + 2433, 3196, 2432, -1, 3196, 3197, 2432, -1, + 2432, 3197, 1604, -1, 1604, 3197, 1605, -1, + 1605, 3197, 2431, -1, 2431, 3197, 2430, -1, + 2430, 3197, 3198, -1, 2430, 3198, 2428, -1, + 2428, 3198, 2427, -1, 2427, 3198, 1577, -1, + 1577, 3198, 1578, -1, 3198, 3199, 1578, -1, + 1578, 3199, 1583, -1, 1583, 3199, 1581, -1, + 1581, 3199, 2426, -1, 2426, 3199, 2425, -1, + 2425, 3199, 926, -1, 3199, 3200, 926, -1, + 926, 3200, 927, -1, 927, 3200, 2424, -1, + 2424, 3200, 2423, -1, 2423, 3200, 1589, -1, + 1589, 3200, 1590, -1, 1590, 3200, 2422, -1, + 2422, 3200, 3201, -1, 2422, 3201, 2421, -1, + 2421, 3201, 2355, -1, 2355, 3201, 2354, -1, + 2354, 3201, 2352, -1, 2352, 3201, 2357, -1, + 2357, 3201, 3202, -1, 2357, 3202, 2359, -1, + 2359, 3202, 2376, -1, 2376, 3202, 2377, -1, + 2377, 3202, 2378, -1, 2378, 3202, 2373, -1, + 2373, 3202, 2379, -1, 3202, 3203, 2379, -1, + 2379, 3203, 2367, -1, 2367, 3203, 2380, -1, + 2380, 3203, 2381, -1, 2381, 3203, 2365, -1, + 2365, 3203, 2382, -1, 3203, 3204, 2382, -1, + 2382, 3204, 1830, -1, 1830, 3204, 1828, -1, + 1828, 3204, 2312, -1, 2312, 3204, 2310, -1, + 2310, 3204, 2313, -1, 2313, 3204, 2314, -1, + 2314, 3204, 2320, -1, 3204, 3205, 2320, -1, + 2320, 3205, 2321, -1, 2321, 3205, 2322, -1, + 2322, 3205, 2331, -1, 2331, 3205, 2332, -1, + 2332, 3205, 3206, -1, 2332, 3206, 2333, -1, + 2333, 3206, 2309, -1, 2309, 3206, 2308, -1, + 2308, 3206, 2307, -1, 2307, 3206, 2306, -1, + 2306, 3206, 2305, -1, 2305, 3206, 2263, -1, + 2263, 3206, 3163, -1, 2263, 3163, 2261, -1, + 2261, 3163, 2264, -1, 2371, 3207, 2385, -1, + 2385, 3207, 2369, -1, 2369, 3207, 2368, -1, + 2368, 3207, 2371, -1, 3146, 3208, 3105, -1, + 3105, 3208, 3104, -1, 2613, 3209, 2610, -1, + 2610, 3209, 2611, -1, 1185, 2644, 2642, -1, + 2642, 2644, 882, -1, 3074, 3101, 3076, -1, + 3076, 3101, 3210, -1, 3101, 3102, 3210, -1, + 3210, 3102, 3211, -1, 3102, 3103, 3211, -1, + 3211, 3103, 3212, -1, 3103, 3104, 3212, -1, + 3212, 3104, 3208, -1, 3071, 3100, 3072, -1, + 3072, 3100, 3213, -1, 3100, 3099, 3213, -1, + 3213, 3099, 3214, -1, 3099, 3098, 3214, -1, + 3214, 3098, 3215, -1, 3098, 3097, 3215, -1, + 3215, 3097, 3135, -1, 586, 2695, 2694, -1, + 2694, 2695, 2714, -1, 2695, 2713, 2714, -1, + 2714, 2713, 2746, -1, 3091, 3092, 3131, -1, + 3131, 3092, 3216, -1, 3092, 3093, 3216, -1, + 3216, 3093, 3136, -1, 63, 64, 62, -1, + 62, 64, 729, -1, 70, 69, 71, -1, + 71, 69, 3046, -1, 103, 104, 102, -1, + 102, 104, 716, -1, 204, 203, 205, -1, + 205, 203, 245, -1, 217, 218, 216, -1, + 216, 218, 316, -1, 189, 227, 228, -1, + 228, 227, 233, -1, 265, 285, 284, -1, + 284, 285, 2520, -1, 367, 376, 377, -1, + 377, 376, 415, -1, 339, 390, 391, -1, + 391, 390, 401, -1, 380, 412, 411, -1, + 411, 412, 14, -1, 376, 416, 415, -1, + 415, 416, 6, -1, 506, 525, 524, -1, + 524, 525, 658, -1, 613, 638, 637, -1, + 637, 638, 658, -1, 612, 639, 638, -1, + 638, 639, 657, -1, 638, 657, 658, -1, + 658, 657, 524, -1, 146, 686, 685, -1, + 685, 686, 95, -1, 70, 75, 726, -1, + 726, 75, 740, -1, 824, 823, 822, -1, + 822, 823, 826, -1, 870, 881, 882, -1, + 882, 881, 2642, -1, 1187, 1188, 1185, -1, + 1185, 1188, 2644, -1, 1191, 1192, 1190, -1, + 1190, 1192, 2645, -1, 1186, 1213, 1208, -1, + 1208, 1213, 1215, -1, 1203, 1220, 1221, -1, + 1221, 1220, 1243, -1, 1281, 1338, 1337, -1, + 1337, 1338, 1255, -1, 1655, 1371, 1368, -1, + 1368, 1371, 1666, -1, 1371, 1655, 1369, -1, + 1369, 1655, 1642, -1, 1440, 1439, 1441, -1, + 1441, 1439, 1637, -1, 1489, 1536, 1535, -1, + 1535, 1536, 1553, -1, 1481, 1540, 1539, -1, + 1539, 1540, 1561, -1, 1554, 1553, 1555, -1, + 1555, 1553, 1536, -1, 1600, 1582, 1592, -1, + 1592, 1582, 928, -1, 1371, 1667, 1666, -1, + 1666, 1667, 949, -1, 1790, 1806, 1805, -1, + 1805, 1806, 1767, -1, 1795, 1588, 1814, -1, + 1814, 1588, 2410, -1, 1793, 1814, 1815, -1, + 1815, 1814, 2411, -1, 1787, 1817, 1818, -1, + 1818, 1817, 2414, -1, 1837, 1834, 1838, -1, + 1838, 1834, 2336, -1, 1844, 1845, 1843, -1, + 1843, 1845, 2390, -1, 1899, 1909, 1897, -1, + 1897, 1909, 1896, -1, 2107, 2106, 2108, -1, + 2108, 2106, 2126, -1, 2129, 2139, 2138, -1, + 2138, 2139, 2152, -1, 2127, 2148, 2140, -1, + 2140, 2148, 2150, -1, 2125, 2142, 2141, -1, + 2141, 2142, 2147, -1, 2161, 2178, 2179, -1, + 2179, 2178, 2188, -1, 2269, 2270, 2268, -1, + 2268, 2270, 2252, -1, 2083, 2297, 2296, -1, + 2296, 2297, 1940, -1, 2088, 2300, 2299, -1, + 2299, 2300, 1943, -1, 2353, 2358, 2356, -1, + 2356, 2358, 1594, -1, 1837, 2387, 2386, -1, + 2386, 2387, 2403, -1, 2604, 2617, 2616, -1, + 2616, 2617, 2550, -1, 2596, 2621, 2620, -1, + 2620, 2621, 2554, -1, 2736, 2763, 2764, -1, + 2764, 2763, 2015, -1, 2798, 2797, 2799, -1, + 2799, 2797, 2815, -1, 2833, 2851, 2852, -1, + 2852, 2851, 2890, -1, 2927, 2926, 2928, -1, + 2928, 2926, 2943, -1, 2943, 2959, 2958, -1, + 2958, 2959, 2967, -1, 2961, 397, 2965, -1, + 2965, 397, 2987, -1, 2960, 2965, 2966, -1, + 2966, 2965, 2986, -1, 2958, 2967, 2968, -1, + 2968, 2967, 2984, -1, 2957, 2968, 2969, -1, + 2969, 2968, 2983, -1, 1249, 1248, 1226, -1, + 1226, 1248, 1260, -1, 2530, 2531, 2529, -1, + 2529, 2531, 2551, -1, 2183, 2783, 2784, -1, + 2784, 2783, 2808, -1, 3060, 3059, 2995, -1, + 2995, 3059, 467, -1, 467, 3059, 466, -1, + 466, 3059, 2994, -1, 3059, 3064, 2994, -1, + 2994, 3064, 426, -1, 426, 3064, 2993, -1, + 2993, 3064, 422, -1, 3064, 3066, 422, -1, + 422, 3066, 373, -1, 373, 3066, 421, -1, + 421, 3066, 3087, -1, 421, 3087, 418, -1, + 418, 3087, 419, -1, 419, 3087, 420, -1, + 420, 3087, 3090, -1, 420, 3090, 4, -1, + 4, 3090, 2991, -1, 2991, 3090, 2992, -1, + 2992, 3090, 3131, -1, 2992, 3131, 3038, -1, + 3038, 3131, 3039, -1, 3039, 3131, 2998, -1, + 2998, 3131, 3216, -1, 2998, 3216, 2997, -1, + 2997, 3216, 2996, -1, 2996, 3216, 701, -1, + 701, 3216, 3136, -1, 701, 3136, 700, -1, + 700, 3136, 677, -1, 677, 3136, 675, -1, + 675, 3136, 3085, -1, 675, 3085, 678, -1, + 678, 3085, 161, -1, 3085, 3082, 161, -1, + 161, 3082, 162, -1, 162, 3082, 163, -1, + 163, 3082, 326, -1, 3082, 3081, 326, -1, + 326, 3081, 325, -1, 325, 3081, 302, -1, + 302, 3081, 190, -1, 3081, 3079, 190, -1, + 190, 3079, 191, -1, 191, 3079, 301, -1, + 301, 3079, 3077, -1, 301, 3077, 251, -1, + 251, 3077, 252, -1, 252, 3077, 300, -1, + 300, 3077, 3075, -1, 300, 3075, 297, -1, + 297, 3075, 298, -1, 298, 3075, 299, -1, + 299, 3075, 3076, -1, 299, 3076, 2543, -1, + 2543, 3076, 2544, -1, 2544, 3076, 2545, -1, + 2545, 3076, 3210, -1, 2545, 3210, 2651, -1, + 2651, 3210, 2635, -1, 3210, 3211, 2635, -1, + 2635, 3211, 2613, -1, 2613, 3211, 3209, -1, + 3209, 3211, 2611, -1, 2611, 3211, 2636, -1, + 2636, 3211, 3212, -1, 2636, 3212, 2652, -1, + 2652, 3212, 2500, -1, 3212, 3208, 2500, -1, + 2500, 3208, 2499, -1, 2499, 3208, 2498, -1, + 2498, 3208, 1107, -1, 3208, 3146, 1107, -1, + 1107, 3146, 1106, -1, 1106, 3146, 1065, -1, + 1065, 3146, 1063, -1, 3146, 3145, 1063, -1, + 1063, 3145, 1066, -1, 1066, 3145, 1016, -1, + 1016, 3145, 1017, -1, 3145, 3144, 1017, -1, + 1017, 3144, 1018, -1, 1018, 3144, 1062, -1, + 1062, 3144, 3142, -1, 1062, 3142, 1061, -1, + 1061, 3142, 1347, -1, 1347, 3142, 1348, -1, + 1348, 3142, 3141, -1, 1348, 3141, 1289, -1, + 1289, 3141, 1349, -1, 1349, 3141, 1350, -1, + 1350, 3141, 3143, -1, 1350, 3143, 930, -1, + 930, 3143, 1682, -1, 3143, 3147, 1682, -1, + 1682, 3147, 1680, -1, 1680, 3147, 1681, -1, + 1681, 3147, 1657, -1, 3147, 3148, 1657, -1, + 1657, 3148, 1354, -1, 1354, 3148, 1351, -1, + 1351, 3148, 1352, -1, 3148, 3162, 1352, -1, + 1352, 3162, 1656, -1, 1656, 3162, 1634, -1, + 1634, 3162, 1444, -1, 3162, 3161, 1444, -1, + 1444, 3161, 1445, -1, 1445, 3161, 1446, -1, + 1446, 3161, 1611, -1, 3161, 3150, 1611, -1, + 1611, 3150, 1609, -1, 1609, 3150, 1608, -1, + 1608, 3150, 1607, -1, 3150, 3149, 1607, -1, + 1607, 3149, 1549, -1, 1549, 3149, 1534, -1, + 1534, 3149, 3151, -1, 1534, 3151, 1532, -1, + 1532, 3151, 1531, -1, 1531, 3151, 1530, -1, + 1530, 3151, 3152, -1, 1530, 3152, 1492, -1, + 1492, 3152, 2441, -1, 2441, 3152, 2442, -1, + 2442, 3152, 3153, -1, 2442, 3153, 901, -1, + 901, 3153, 2443, -1, 3153, 3154, 2443, -1, + 2443, 3154, 2444, -1, 2444, 3154, 2469, -1, + 2469, 3154, 2470, -1, 3154, 3155, 2470, -1, + 2470, 3155, 1495, -1, 1495, 3155, 1493, -1, + 1493, 3155, 1496, -1, 3155, 3156, 1496, -1, + 1496, 3156, 1510, -1, 1510, 3156, 1509, -1, + 1509, 3156, 1508, -1, 3156, 3157, 1508, -1, + 1508, 3157, 1522, -1, 1522, 3157, 1523, -1, + 1523, 3157, 3158, -1, 1523, 3158, 2485, -1, + 2485, 3158, 2489, -1, 2489, 3158, 2483, -1, + 2483, 3158, 2490, -1, 3158, 3159, 2490, -1, + 2490, 3159, 2491, -1, 2491, 3159, 1527, -1, + 1527, 3159, 3160, -1, 1527, 3160, 1528, -1, + 1528, 3160, 1529, -1, 1529, 3160, 891, -1, + 891, 3160, 3140, -1, 891, 3140, 889, -1, + 889, 3140, 892, -1, 3140, 3139, 892, -1, + 892, 3139, 3138, -1, 892, 3138, 3137, -1, + 892, 3137, 2655, -1, 2655, 3137, 3068, -1, + 2655, 3068, 3067, -1, 3067, 3072, 2655, -1, + 2655, 3072, 2653, -1, 2653, 3072, 2656, -1, + 2656, 3072, 3213, -1, 2656, 3213, 2676, -1, + 2676, 3213, 2679, -1, 2679, 3213, 2672, -1, + 2672, 3213, 3214, -1, 2672, 3214, 2732, -1, + 2732, 3214, 2731, -1, 3214, 3215, 2731, -1, + 2731, 3215, 2729, -1, 2729, 3215, 2730, -1, + 2730, 3215, 2680, -1, 2680, 3215, 600, -1, + 600, 3215, 3135, -1, 600, 3135, 601, -1, + 601, 3135, 542, -1, 3135, 3133, 542, -1, + 542, 3133, 602, -1, 602, 3133, 603, -1, + 603, 3133, 647, -1, 3133, 3132, 647, -1, + 647, 3132, 648, -1, 648, 3132, 649, -1, + 649, 3132, 674, -1, 3132, 3134, 674, -1, + 674, 3134, 673, -1, 673, 3134, 516, -1, + 516, 3134, 515, -1, 3134, 3060, 515, -1, + 515, 3060, 514, -1, 3060, 2995, 514, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2176, 2176, 2176, -1, 2177, 2177, 2177, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2228, 2228, 2228, -1, 2229, 2229, 2229, -1, + 2230, 2230, 2230, -1, 2231, 2231, 2231, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2256, 2256, 2256, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2265, 2265, 2265, -1, + 2266, 2266, 2266, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2269, 2269, 2269, -1, + 2270, 2270, 2270, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2273, 2273, 2273, -1, + 2274, 2274, 2274, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2277, 2277, 2277, -1, + 2278, 2278, 2278, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2283, 2283, 2283, -1, + 2284, 2284, 2284, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2305, 2305, 2305, -1, + 2306, 2306, 2306, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2311, 2311, 2311, -1, + 2312, 2312, 2312, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2323, 2323, 2323, -1, + 2324, 2324, 2324, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2331, 2331, 2331, -1, + 2332, 2332, 2332, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2345, 2345, 2345, -1, + 2346, 2346, 2346, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2351, 2351, 2351, -1, + 2352, 2352, 2352, -1, 2353, 2353, 2353, -1, + 2354, 2354, 2354, -1, 2355, 2355, 2355, -1, + 2356, 2356, 2356, -1, 2357, 2357, 2357, -1, + 2358, 2358, 2358, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2405, 2405, 2405, -1, + 2406, 2406, 2406, -1, 2407, 2407, 2407, -1, + 2408, 2408, 2408, -1, 2409, 2409, 2409, -1, + 2410, 2410, 2410, -1, 2411, 2411, 2411, -1, + 2412, 2412, 2412, -1, 2413, 2413, 2413, -1, + 2414, 2414, 2414, -1, 2415, 2415, 2415, -1, + 2416, 2416, 2416, -1, 2417, 2417, 2417, -1, + 2418, 2418, 2418, -1, 2419, 2419, 2419, -1, + 2420, 2420, 2420, -1, 2421, 2421, 2421, -1, + 2422, 2422, 2422, -1, 2423, 2423, 2423, -1, + 2424, 2424, 2424, -1, 2425, 2425, 2425, -1, + 2426, 2426, 2426, -1, 2427, 2427, 2427, -1, + 2428, 2428, 2428, -1, 2429, 2429, 2429, -1, + 2430, 2430, 2430, -1, 2431, 2431, 2431, -1, + 2432, 2432, 2432, -1, 2433, 2433, 2433, -1, + 2434, 2434, 2434, -1, 2435, 2435, 2435, -1, + 2436, 2436, 2436, -1, 2437, 2437, 2437, -1, + 2438, 2438, 2438, -1, 2439, 2439, 2439, -1, + 2440, 2440, 2440, -1, 2441, 2441, 2441, -1, + 2442, 2442, 2442, -1, 2443, 2443, 2443, -1, + 2444, 2444, 2444, -1, 2445, 2445, 2445, -1, + 2446, 2446, 2446, -1, 2447, 2447, 2447, -1, + 2448, 2448, 2448, -1, 2449, 2449, 2449, -1, + 2450, 2450, 2450, -1, 2451, 2451, 2451, -1, + 2452, 2452, 2452, -1, 2453, 2453, 2453, -1, + 2454, 2454, 2454, -1, 2455, 2455, 2455, -1, + 2456, 2456, 2456, -1, 2457, 2457, 2457, -1, + 2458, 2458, 2458, -1, 2459, 2459, 2459, -1, + 2460, 2460, 2460, -1, 2461, 2461, 2461, -1, + 2462, 2462, 2462, -1, 2463, 2463, 2463, -1, + 2464, 2464, 2464, -1, 2465, 2465, 2465, -1, + 2466, 2466, 2466, -1, 2467, 2467, 2467, -1, + 2468, 2468, 2468, -1, 2469, 2469, 2469, -1, + 2470, 2470, 2470, -1, 2471, 2471, 2471, -1, + 2472, 2472, 2472, -1, 2473, 2473, 2473, -1, + 2474, 2474, 2474, -1, 2475, 2475, 2475, -1, + 2476, 2476, 2476, -1, 2477, 2477, 2477, -1, + 2478, 2478, 2478, -1, 2479, 2479, 2479, -1, + 2480, 2480, 2480, -1, 2481, 2481, 2481, -1, + 2482, 2482, 2482, -1, 2483, 2483, 2483, -1, + 2484, 2484, 2484, -1, 2485, 2485, 2485, -1, + 2486, 2486, 2486, -1, 2487, 2487, 2487, -1, + 2488, 2488, 2488, -1, 2489, 2489, 2489, -1, + 2490, 2490, 2490, -1, 2491, 2491, 2491, -1, + 2492, 2492, 2492, -1, 2493, 2493, 2493, -1, + 2494, 2494, 2494, -1, 2495, 2495, 2495, -1, + 2496, 2496, 2496, -1, 2497, 2497, 2497, -1, + 2498, 2498, 2498, -1, 2499, 2499, 2499, -1, + 2500, 2500, 2500, -1, 2501, 2501, 2501, -1, + 2502, 2502, 2502, -1, 2503, 2503, 2503, -1, + 2504, 2504, 2504, -1, 2505, 2505, 2505, -1, + 2506, 2506, 2506, -1, 2507, 2507, 2507, -1, + 2508, 2508, 2508, -1, 2509, 2509, 2509, -1, + 2510, 2510, 2510, -1, 2511, 2511, 2511, -1, + 2512, 2512, 2512, -1, 2513, 2513, 2513, -1, + 2514, 2514, 2514, -1, 2515, 2515, 2515, -1, + 2516, 2516, 2516, -1, 2517, 2517, 2517, -1, + 2518, 2518, 2518, -1, 2519, 2519, 2519, -1, + 2520, 2520, 2520, -1, 2521, 2521, 2521, -1, + 2522, 2522, 2522, -1, 2523, 2523, 2523, -1, + 2524, 2524, 2524, -1, 2525, 2525, 2525, -1, + 2526, 2526, 2526, -1, 2527, 2527, 2527, -1, + 2528, 2528, 2528, -1, 2529, 2529, 2529, -1, + 2530, 2530, 2530, -1, 2531, 2531, 2531, -1, + 2532, 2532, 2532, -1, 2533, 2533, 2533, -1, + 2534, 2534, 2534, -1, 2535, 2535, 2535, -1, + 2536, 2536, 2536, -1, 2537, 2537, 2537, -1, + 2538, 2538, 2538, -1, 2539, 2539, 2539, -1, + 2540, 2540, 2540, -1, 2541, 2541, 2541, -1, + 2542, 2542, 2542, -1, 2543, 2543, 2543, -1, + 2544, 2544, 2544, -1, 2545, 2545, 2545, -1, + 2546, 2546, 2546, -1, 2547, 2547, 2547, -1, + 2548, 2548, 2548, -1, 2549, 2549, 2549, -1, + 2550, 2550, 2550, -1, 2551, 2551, 2551, -1, + 2552, 2552, 2552, -1, 2553, 2553, 2553, -1, + 2554, 2554, 2554, -1, 2555, 2555, 2555, -1, + 2556, 2556, 2556, -1, 2557, 2557, 2557, -1, + 2558, 2558, 2558, -1, 2559, 2559, 2559, -1, + 2560, 2560, 2560, -1, 2561, 2561, 2561, -1, + 2562, 2562, 2562, -1, 2563, 2563, 2563, -1, + 2564, 2564, 2564, -1, 2565, 2565, 2565, -1, + 2566, 2566, 2566, -1, 2567, 2567, 2567, -1, + 2568, 2568, 2568, -1, 2569, 2569, 2569, -1, + 2570, 2570, 2570, -1, 2571, 2571, 2571, -1, + 2572, 2572, 2572, -1, 2573, 2573, 2573, -1, + 2574, 2574, 2574, -1, 2575, 2575, 2575, -1, + 2576, 2576, 2576, -1, 2577, 2577, 2577, -1, + 2578, 2578, 2578, -1, 2579, 2579, 2579, -1, + 2580, 2580, 2580, -1, 2581, 2581, 2581, -1, + 2582, 2582, 2582, -1, 2583, 2583, 2583, -1, + 2584, 2584, 2584, -1, 2585, 2585, 2585, -1, + 2586, 2586, 2586, -1, 2587, 2587, 2587, -1, + 2588, 2588, 2588, -1, 2589, 2589, 2589, -1, + 2590, 2590, 2590, -1, 2591, 2591, 2591, -1, + 2592, 2592, 2592, -1, 2593, 2593, 2593, -1, + 2594, 2594, 2594, -1, 2595, 2595, 2595, -1, + 2596, 2596, 2596, -1, 2597, 2597, 2597, -1, + 2598, 2598, 2598, -1, 2599, 2599, 2599, -1, + 2600, 2600, 2600, -1, 2601, 2601, 2601, -1, + 2602, 2602, 2602, -1, 2603, 2603, 2603, -1, + 2604, 2604, 2604, -1, 2605, 2605, 2605, -1, + 2606, 2606, 2606, -1, 2607, 2607, 2607, -1, + 2608, 2608, 2608, -1, 2609, 2609, 2609, -1, + 2610, 2610, 2610, -1, 2611, 2611, 2611, -1, + 2612, 2612, 2612, -1, 2613, 2613, 2613, -1, + 2614, 2614, 2614, -1, 2615, 2615, 2615, -1, + 2616, 2616, 2616, -1, 2617, 2617, 2617, -1, + 2618, 2618, 2618, -1, 2619, 2619, 2619, -1, + 2620, 2620, 2620, -1, 2621, 2621, 2621, -1, + 2622, 2622, 2622, -1, 2623, 2623, 2623, -1, + 2624, 2624, 2624, -1, 2625, 2625, 2625, -1, + 2626, 2626, 2626, -1, 2627, 2627, 2627, -1, + 2628, 2628, 2628, -1, 2629, 2629, 2629, -1, + 2630, 2630, 2630, -1, 2631, 2631, 2631, -1, + 2632, 2632, 2632, -1, 2633, 2633, 2633, -1, + 2634, 2634, 2634, -1, 2635, 2635, 2635, -1, + 2636, 2636, 2636, -1, 2637, 2637, 2637, -1, + 2638, 2638, 2638, -1, 2639, 2639, 2639, -1, + 2640, 2640, 2640, -1, 2641, 2641, 2641, -1, + 2642, 2642, 2642, -1, 2643, 2643, 2643, -1, + 2644, 2644, 2644, -1, 2645, 2645, 2645, -1, + 2646, 2646, 2646, -1, 2647, 2647, 2647, -1, + 2648, 2648, 2648, -1, 2649, 2649, 2649, -1, + 2650, 2650, 2650, -1, 2651, 2651, 2651, -1, + 2652, 2652, 2652, -1, 2653, 2653, 2653, -1, + 2654, 2654, 2654, -1, 2655, 2655, 2655, -1, + 2656, 2656, 2656, -1, 2657, 2657, 2657, -1, + 2658, 2658, 2658, -1, 2659, 2659, 2659, -1, + 2660, 2660, 2660, -1, 2661, 2661, 2661, -1, + 2662, 2662, 2662, -1, 2663, 2663, 2663, -1, + 2664, 2664, 2664, -1, 2665, 2665, 2665, -1, + 2666, 2666, 2666, -1, 2667, 2667, 2667, -1, + 2668, 2668, 2668, -1, 2669, 2669, 2669, -1, + 2670, 2670, 2670, -1, 2671, 2671, 2671, -1, + 2672, 2672, 2672, -1, 2673, 2673, 2673, -1, + 2674, 2674, 2674, -1, 2675, 2675, 2675, -1, + 2676, 2676, 2676, -1, 2677, 2677, 2677, -1, + 2678, 2678, 2678, -1, 2679, 2679, 2679, -1, + 2680, 2680, 2680, -1, 2681, 2681, 2681, -1, + 2682, 2682, 2682, -1, 2683, 2683, 2683, -1, + 2684, 2684, 2684, -1, 2685, 2685, 2685, -1, + 2686, 2686, 2686, -1, 2687, 2687, 2687, -1, + 2688, 2688, 2688, -1, 2689, 2689, 2689, -1, + 2690, 2690, 2690, -1, 2691, 2691, 2691, -1, + 2692, 2692, 2692, -1, 2693, 2693, 2693, -1, + 2694, 2694, 2694, -1, 2695, 2695, 2695, -1, + 2696, 2696, 2696, -1, 2697, 2697, 2697, -1, + 2698, 2698, 2698, -1, 2699, 2699, 2699, -1, + 2700, 2700, 2700, -1, 2701, 2701, 2701, -1, + 2702, 2702, 2702, -1, 2703, 2703, 2703, -1, + 2704, 2704, 2704, -1, 2705, 2705, 2705, -1, + 2706, 2706, 2706, -1, 2707, 2707, 2707, -1, + 2708, 2708, 2708, -1, 2709, 2709, 2709, -1, + 2710, 2710, 2710, -1, 2711, 2711, 2711, -1, + 2712, 2712, 2712, -1, 2713, 2713, 2713, -1, + 2714, 2714, 2714, -1, 2715, 2715, 2715, -1, + 2716, 2716, 2716, -1, 2717, 2717, 2717, -1, + 2718, 2718, 2718, -1, 2719, 2719, 2719, -1, + 2720, 2720, 2720, -1, 2721, 2721, 2721, -1, + 2722, 2722, 2722, -1, 2723, 2723, 2723, -1, + 2724, 2724, 2724, -1, 2725, 2725, 2725, -1, + 2726, 2726, 2726, -1, 2727, 2727, 2727, -1, + 2728, 2728, 2728, -1, 2729, 2729, 2729, -1, + 2730, 2730, 2730, -1, 2731, 2731, 2731, -1, + 2732, 2732, 2732, -1, 2733, 2733, 2733, -1, + 2734, 2734, 2734, -1, 2735, 2735, 2735, -1, + 2736, 2736, 2736, -1, 2737, 2737, 2737, -1, + 2738, 2738, 2738, -1, 2739, 2739, 2739, -1, + 2740, 2740, 2740, -1, 2741, 2741, 2741, -1, + 2742, 2742, 2742, -1, 2743, 2743, 2743, -1, + 2744, 2744, 2744, -1, 2745, 2745, 2745, -1, + 2746, 2746, 2746, -1, 2747, 2747, 2747, -1, + 2748, 2748, 2748, -1, 2749, 2749, 2749, -1, + 2750, 2750, 2750, -1, 2751, 2751, 2751, -1, + 2752, 2752, 2752, -1, 2753, 2753, 2753, -1, + 2754, 2754, 2754, -1, 2755, 2755, 2755, -1, + 2756, 2756, 2756, -1, 2757, 2757, 2757, -1, + 2758, 2758, 2758, -1, 2759, 2759, 2759, -1, + 2760, 2760, 2760, -1, 2761, 2761, 2761, -1, + 2762, 2762, 2762, -1, 2763, 2763, 2763, -1, + 2764, 2764, 2764, -1, 2765, 2765, 2765, -1, + 2766, 2766, 2766, -1, 2767, 2767, 2767, -1, + 2768, 2768, 2768, -1, 2769, 2769, 2769, -1, + 2770, 2770, 2770, -1, 2771, 2771, 2771, -1, + 2772, 2772, 2772, -1, 2773, 2773, 2773, -1, + 2774, 2774, 2774, -1, 2775, 2775, 2775, -1, + 2776, 2776, 2776, -1, 2777, 2777, 2777, -1, + 2778, 2778, 2778, -1, 2779, 2779, 2779, -1, + 2780, 2780, 2780, -1, 2781, 2781, 2781, -1, + 2782, 2782, 2782, -1, 2783, 2783, 2783, -1, + 2784, 2784, 2784, -1, 2785, 2785, 2785, -1, + 2786, 2786, 2786, -1, 2787, 2787, 2787, -1, + 2788, 2788, 2788, -1, 2789, 2789, 2789, -1, + 2790, 2790, 2790, -1, 2791, 2791, 2791, -1, + 2792, 2792, 2792, -1, 2793, 2793, 2793, -1, + 2794, 2794, 2794, -1, 2795, 2795, 2795, -1, + 2796, 2796, 2796, -1, 2797, 2797, 2797, -1, + 2798, 2798, 2798, -1, 2799, 2799, 2799, -1, + 2800, 2800, 2800, -1, 2801, 2801, 2801, -1, + 2802, 2802, 2802, -1, 2803, 2803, 2803, -1, + 2804, 2804, 2804, -1, 2805, 2805, 2805, -1, + 2806, 2806, 2806, -1, 2807, 2807, 2807, -1, + 2808, 2808, 2808, -1, 2809, 2809, 2809, -1, + 2810, 2810, 2810, -1, 2811, 2811, 2811, -1, + 2812, 2812, 2812, -1, 2813, 2813, 2813, -1, + 2814, 2814, 2814, -1, 2815, 2815, 2815, -1, + 2816, 2816, 2816, -1, 2817, 2817, 2817, -1, + 2818, 2818, 2818, -1, 2819, 2819, 2819, -1, + 2820, 2820, 2820, -1, 2821, 2821, 2821, -1, + 2822, 2822, 2822, -1, 2823, 2823, 2823, -1, + 2824, 2824, 2824, -1, 2825, 2825, 2825, -1, + 2826, 2826, 2826, -1, 2827, 2827, 2827, -1, + 2828, 2828, 2828, -1, 2829, 2829, 2829, -1, + 2830, 2830, 2830, -1, 2831, 2831, 2831, -1, + 2832, 2832, 2832, -1, 2833, 2833, 2833, -1, + 2834, 2834, 2834, -1, 2835, 2835, 2835, -1, + 2836, 2836, 2836, -1, 2837, 2837, 2837, -1, + 2838, 2838, 2838, -1, 2839, 2839, 2839, -1, + 2840, 2840, 2840, -1, 2841, 2841, 2841, -1, + 2842, 2842, 2842, -1, 2843, 2843, 2843, -1, + 2844, 2844, 2844, -1, 2845, 2845, 2845, -1, + 2846, 2846, 2846, -1, 2847, 2847, 2847, -1, + 2848, 2848, 2848, -1, 2849, 2849, 2849, -1, + 2850, 2850, 2850, -1, 2851, 2851, 2851, -1, + 2852, 2852, 2852, -1, 2853, 2853, 2853, -1, + 2854, 2854, 2854, -1, 2855, 2855, 2855, -1, + 2856, 2856, 2856, -1, 2857, 2857, 2857, -1, + 2858, 2858, 2858, -1, 2859, 2859, 2859, -1, + 2860, 2860, 2860, -1, 2861, 2861, 2861, -1, + 2862, 2862, 2862, -1, 2863, 2863, 2863, -1, + 2864, 2864, 2864, -1, 2865, 2865, 2865, -1, + 2866, 2866, 2866, -1, 2867, 2867, 2867, -1, + 2868, 2868, 2868, -1, 2869, 2869, 2869, -1, + 2870, 2870, 2870, -1, 2871, 2871, 2871, -1, + 2872, 2872, 2872, -1, 2873, 2873, 2873, -1, + 2874, 2874, 2874, -1, 2875, 2875, 2875, -1, + 2876, 2876, 2876, -1, 2877, 2877, 2877, -1, + 2878, 2878, 2878, -1, 2879, 2879, 2879, -1, + 2880, 2880, 2880, -1, 2881, 2881, 2881, -1, + 2882, 2882, 2882, -1, 2883, 2883, 2883, -1, + 2884, 2884, 2884, -1, 2885, 2885, 2885, -1, + 2886, 2886, 2886, -1, 2887, 2887, 2887, -1, + 2888, 2888, 2888, -1, 2889, 2889, 2889, -1, + 2890, 2890, 2890, -1, 2891, 2891, 2891, -1, + 2892, 2892, 2892, -1, 2893, 2893, 2893, -1, + 2894, 2894, 2894, -1, 2895, 2895, 2895, -1, + 2896, 2896, 2896, -1, 2897, 2897, 2897, -1, + 2898, 2898, 2898, -1, 2899, 2899, 2899, -1, + 2900, 2900, 2900, -1, 2901, 2901, 2901, -1, + 2902, 2902, 2902, -1, 2903, 2903, 2903, -1, + 2904, 2904, 2904, -1, 2905, 2905, 2905, -1, + 2906, 2906, 2906, -1, 2907, 2907, 2907, -1, + 2908, 2908, 2908, -1, 2909, 2909, 2909, -1, + 2910, 2910, 2910, -1, 2911, 2911, 2911, -1, + 2912, 2912, 2912, -1, 2913, 2913, 2913, -1, + 2914, 2914, 2914, -1, 2915, 2915, 2915, -1, + 2916, 2916, 2916, -1, 2917, 2917, 2917, -1, + 2918, 2918, 2918, -1, 2919, 2919, 2919, -1, + 2920, 2920, 2920, -1, 2921, 2921, 2921, -1, + 2922, 2922, 2922, -1, 2923, 2923, 2923, -1, + 2924, 2924, 2924, -1, 2925, 2925, 2925, -1, + 2926, 2926, 2926, -1, 2927, 2927, 2927, -1, + 2928, 2928, 2928, -1, 2929, 2929, 2929, -1, + 2930, 2930, 2930, -1, 2931, 2931, 2931, -1, + 2932, 2932, 2932, -1, 2933, 2933, 2933, -1, + 2934, 2934, 2934, -1, 2935, 2935, 2935, -1, + 2936, 2936, 2936, -1, 2937, 2937, 2937, -1, + 2938, 2938, 2938, -1, 2939, 2939, 2939, -1, + 2940, 2940, 2940, -1, 2941, 2941, 2941, -1, + 2942, 2942, 2942, -1, 2943, 2943, 2943, -1, + 2944, 2944, 2944, -1, 2945, 2945, 2945, -1, + 2946, 2946, 2946, -1, 2947, 2947, 2947, -1, + 2948, 2948, 2948, -1, 2949, 2949, 2949, -1, + 2950, 2950, 2950, -1, 2951, 2951, 2951, -1, + 2952, 2952, 2952, -1, 2953, 2953, 2953, -1, + 2954, 2954, 2954, -1, 2955, 2955, 2955, -1, + 2956, 2956, 2956, -1, 2957, 2957, 2957, -1, + 2958, 2958, 2958, -1, 2959, 2959, 2959, -1, + 2960, 2960, 2960, -1, 2961, 2961, 2961, -1, + 2962, 2962, 2962, -1, 2963, 2963, 2963, -1, + 2964, 2964, 2964, -1, 2965, 2965, 2965, -1, + 2966, 2966, 2966, -1, 2967, 2967, 2967, -1, + 2968, 2968, 2968, -1, 2969, 2969, 2969, -1, + 2970, 2970, 2970, -1, 2971, 2971, 2971, -1, + 2972, 2972, 2972, -1, 2973, 2973, 2973, -1, + 2974, 2974, 2974, -1, 2975, 2975, 2975, -1, + 2976, 2976, 2976, -1, 2977, 2977, 2977, -1, + 2978, 2978, 2978, -1, 2979, 2979, 2979, -1, + 2980, 2980, 2980, -1, 2981, 2981, 2981, -1, + 2982, 2982, 2982, -1, 2983, 2983, 2983, -1, + 2984, 2984, 2984, -1, 2985, 2985, 2985, -1, + 2986, 2986, 2986, -1, 2987, 2987, 2987, -1, + 2988, 2988, 2988, -1, 2989, 2989, 2989, -1, + 2990, 2990, 2990, -1, 2991, 2991, 2991, -1, + 2992, 2992, 2992, -1, 2993, 2993, 2993, -1, + 2994, 2994, 2994, -1, 2995, 2995, 2995, -1, + 2996, 2996, 2996, -1, 2997, 2997, 2997, -1, + 2998, 2998, 2998, -1, 2999, 2999, 2999, -1, + 3000, 3000, 3000, -1, 3001, 3001, 3001, -1, + 3002, 3002, 3002, -1, 3003, 3003, 3003, -1, + 3004, 3004, 3004, -1, 3005, 3005, 3005, -1, + 3006, 3006, 3006, -1, 3007, 3007, 3007, -1, + 3008, 3008, 3008, -1, 3009, 3009, 3009, -1, + 3010, 3010, 3010, -1, 3011, 3011, 3011, -1, + 3012, 3012, 3012, -1, 3013, 3013, 3013, -1, + 3014, 3014, 3014, -1, 3015, 3015, 3015, -1, + 3016, 3016, 3016, -1, 3017, 3017, 3017, -1, + 3018, 3018, 3018, -1, 3019, 3019, 3019, -1, + 3020, 3020, 3020, -1, 3021, 3021, 3021, -1, + 3022, 3022, 3022, -1, 3023, 3023, 3023, -1, + 3024, 3024, 3024, -1, 3025, 3025, 3025, -1, + 3026, 3026, 3026, -1, 3027, 3027, 3027, -1, + 3028, 3028, 3028, -1, 3029, 3029, 3029, -1, + 3030, 3030, 3030, -1, 3031, 3031, 3031, -1, + 3032, 3032, 3032, -1, 3033, 3033, 3033, -1, + 3034, 3034, 3034, -1, 3035, 3035, 3035, -1, + 3036, 3036, 3036, -1, 3037, 3037, 3037, -1, + 3038, 3038, 3038, -1, 3039, 3039, 3039, -1, + 3040, 3040, 3040, -1, 3041, 3041, 3041, -1, + 3042, 3042, 3042, -1, 3043, 3043, 3043, -1, + 3044, 3044, 3044, -1, 3045, 3045, 3045, -1, + 3046, 3046, 3046, -1, 3047, 3047, 3047, -1, + 3048, 3048, 3048, -1, 3049, 3049, 3049, -1, + 3050, 3050, 3050, -1, 3051, 3051, 3051, -1, + 3052, 3052, 3052, -1, 3053, 3053, 3053, -1, + 3054, 3054, 3054, -1, 3055, 3055, 3055, -1, + 3056, 3056, 3056, -1, 3057, 3057, 3057, -1, + 3058, 3058, 3058, -1, 3059, 3059, 3059, -1, + 3060, 3060, 3060, -1, 3061, 3061, 3061, -1, + 3062, 3062, 3062, -1, 3063, 3063, 3063, -1, + 3064, 3064, 3064, -1, 3065, 3065, 3065, -1, + 3066, 3066, 3066, -1, 3067, 3067, 3067, -1, + 3068, 3068, 3068, -1, 3069, 3069, 3069, -1, + 3070, 3070, 3070, -1, 3071, 3071, 3071, -1, + 3072, 3072, 3072, -1, 3073, 3073, 3073, -1, + 3074, 3074, 3074, -1, 3075, 3075, 3075, -1, + 3076, 3076, 3076, -1, 3077, 3077, 3077, -1, + 3078, 3078, 3078, -1, 3079, 3079, 3079, -1, + 3080, 3080, 3080, -1, 3081, 3081, 3081, -1, + 3082, 3082, 3082, -1, 3083, 3083, 3083, -1, + 3084, 3084, 3084, -1, 3085, 3085, 3085, -1, + 3086, 3086, 3086, -1, 3087, 3087, 3087, -1, + 3088, 3088, 3088, -1, 3089, 3089, 3089, -1, + 3090, 3090, 3090, -1, 3091, 3091, 3091, -1, + 3092, 3092, 3092, -1, 3093, 3093, 3093, -1, + 3094, 3094, 3094, -1, 3095, 3095, 3095, -1, + 3096, 3096, 3096, -1, 3097, 3097, 3097, -1, + 3098, 3098, 3098, -1, 3099, 3099, 3099, -1, + 3100, 3100, 3100, -1, 3101, 3101, 3101, -1, + 3102, 3102, 3102, -1, 3103, 3103, 3103, -1, + 3104, 3104, 3104, -1, 3105, 3105, 3105, -1, + 3106, 3106, 3106, -1, 3107, 3107, 3107, -1, + 3108, 3108, 3108, -1, 3109, 3109, 3109, -1, + 3110, 3110, 3110, -1, 3111, 3111, 3111, -1, + 3112, 3112, 3112, -1, 3113, 3113, 3113, -1, + 3114, 3114, 3114, -1, 3115, 3115, 3115, -1, + 3116, 3116, 3116, -1, 3117, 3117, 3117, -1, + 3118, 3118, 3118, -1, 3119, 3119, 3119, -1, + 3120, 3120, 3120, -1, 3121, 3121, 3121, -1, + 3122, 3122, 3122, -1, 3123, 3123, 3123, -1, + 3124, 3124, 3124, -1, 3125, 3125, 3125, -1, + 3126, 3126, 3126, -1, 3127, 3127, 3127, -1, + 3128, 3128, 3128, -1, 3129, 3129, 3129, -1, + 3130, 3130, 3130, -1, 3131, 3131, 3131, -1, + 3132, 3132, 3132, -1, 3133, 3133, 3133, -1, + 3134, 3134, 3134, -1, 3135, 3135, 3135, -1, + 3136, 3136, 3136, -1, 3137, 3137, 3137, -1, + 3138, 3138, 3138, -1, 3139, 3139, 3139, -1, + 3140, 3140, 3140, -1, 3141, 3141, 3141, -1, + 3142, 3142, 3142, -1, 3143, 3143, 3143, -1, + 3144, 3144, 3144, -1, 3145, 3145, 3145, -1, + 3146, 3146, 3146, -1, 3147, 3147, 3147, -1, + 3148, 3148, 3148, -1, 3149, 3149, 3149, -1, + 3150, 3150, 3150, -1, 3151, 3151, 3151, -1, + 3152, 3152, 3152, -1, 3153, 3153, 3153, -1, + 3154, 3154, 3154, -1, 3155, 3155, 3155, -1, + 3156, 3156, 3156, -1, 3157, 3157, 3157, -1, + 3158, 3158, 3158, -1, 3159, 3159, 3159, -1, + 3160, 3160, 3160, -1, 3161, 3161, 3161, -1, + 3162, 3162, 3162, -1, 3163, 3163, 3163, -1, + 3164, 3164, 3164, -1, 3165, 3165, 3165, -1, + 3166, 3166, 3166, -1, 3167, 3167, 3167, -1, + 3168, 3168, 3168, -1, 3169, 3169, 3169, -1, + 3170, 3170, 3170, -1, 3171, 3171, 3171, -1, + 3172, 3172, 3172, -1, 3173, 3173, 3173, -1, + 3174, 3174, 3174, -1, 3175, 3175, 3175, -1, + 3176, 3176, 3176, -1, 3177, 3177, 3177, -1, + 3178, 3178, 3178, -1, 3179, 3179, 3179, -1, + 3180, 3180, 3180, -1, 3181, 3181, 3181, -1, + 3182, 3182, 3182, -1, 3183, 3183, 3183, -1, + 3184, 3184, 3184, -1, 3185, 3185, 3185, -1, + 3186, 3186, 3186, -1, 3187, 3187, 3187, -1, + 3188, 3188, 3188, -1, 3189, 3189, 3189, -1, + 3190, 3190, 3190, -1, 3191, 3191, 3191, -1, + 3192, 3192, 3192, -1, 3193, 3193, 3193, -1, + 3194, 3194, 3194, -1, 3195, 3195, 3195, -1, + 3196, 3196, 3196, -1, 3197, 3197, 3197, -1, + 3198, 3198, 3198, -1, 3199, 3199, 3199, -1, + 3200, 3200, 3200, -1, 3201, 3201, 3201, -1, + 3202, 3202, 3202, -1, 3203, 3203, 3203, -1, + 3204, 3204, 3204, -1, 3205, 3205, 3205, -1, + 3206, 3206, 3206, -1, 3207, 3207, 3207, -1, + 3208, 3208, 3208, -1, 3209, 3209, 3209, -1, + 3210, 3210, 3210, -1, 3211, 3211, 3211, -1, + 3212, 3212, 3212, -1, 3213, 3213, 3213, -1, + 3214, 3214, 3214, -1, 3215, 3215, 3215, -1, + 3216, 3216, 3216, -1, 3217, 3217, 3217, -1, + 3218, 3218, 3218, -1, 3219, 3219, 3219, -1, + 3220, 3220, 3220, -1, 3221, 3221, 3221, -1, + 3222, 3222, 3222, -1, 3223, 3223, 3223, -1, + 3224, 3224, 3224, -1, 3225, 3225, 3225, -1, + 3226, 3226, 3226, -1, 3227, 3227, 3227, -1, + 3228, 3228, 3228, -1, 3229, 3229, 3229, -1, + 3230, 3230, 3230, -1, 3231, 3231, 3231, -1, + 3232, 3232, 3232, -1, 3233, 3233, 3233, -1, + 3234, 3234, 3234, -1, 3235, 3235, 3235, -1, + 3236, 3236, 3236, -1, 3237, 3237, 3237, -1, + 3238, 3238, 3238, -1, 3239, 3239, 3239, -1, + 3240, 3240, 3240, -1, 3241, 3241, 3241, -1, + 3242, 3242, 3242, -1, 3243, 3243, 3243, -1, + 3244, 3244, 3244, -1, 3245, 3245, 3245, -1, + 3246, 3246, 3246, -1, 3247, 3247, 3247, -1, + 3248, 3248, 3248, -1, 3249, 3249, 3249, -1, + 3250, 3250, 3250, -1, 3251, 3251, 3251, -1, + 3252, 3252, 3252, -1, 3253, 3253, 3253, -1, + 3254, 3254, 3254, -1, 3255, 3255, 3255, -1, + 3256, 3256, 3256, -1, 3257, 3257, 3257, -1, + 3258, 3258, 3258, -1, 3259, 3259, 3259, -1, + 3260, 3260, 3260, -1, 3261, 3261, 3261, -1, + 3262, 3262, 3262, -1, 3263, 3263, 3263, -1, + 3264, 3264, 3264, -1, 3265, 3265, 3265, -1, + 3266, 3266, 3266, -1, 3267, 3267, 3267, -1, + 3268, 3268, 3268, -1, 3269, 3269, 3269, -1, + 3270, 3270, 3270, -1, 3271, 3271, 3271, -1, + 3272, 3272, 3272, -1, 3273, 3273, 3273, -1, + 3274, 3274, 3274, -1, 3275, 3275, 3275, -1, + 3276, 3276, 3276, -1, 3277, 3277, 3277, -1, + 3278, 3278, 3278, -1, 3279, 3279, 3279, -1, + 3280, 3280, 3280, -1, 3281, 3281, 3281, -1, + 3282, 3282, 3282, -1, 3283, 3283, 3283, -1, + 3284, 3284, 3284, -1, 3285, 3285, 3285, -1, + 3286, 3286, 3286, -1, 3287, 3287, 3287, -1, + 3288, 3288, 3288, -1, 3289, 3289, 3289, -1, + 3290, 3290, 3290, -1, 3291, 3291, 3291, -1, + 3292, 3292, 3292, -1, 3293, 3293, 3293, -1, + 3294, 3294, 3294, -1, 3295, 3295, 3295, -1, + 3296, 3296, 3296, -1, 3297, 3297, 3297, -1, + 3298, 3298, 3298, -1, 3299, 3299, 3299, -1, + 3300, 3300, 3300, -1, 3301, 3301, 3301, -1, + 3302, 3302, 3302, -1, 3303, 3303, 3303, -1, + 3304, 3304, 3304, -1, 3305, 3305, 3305, -1, + 3306, 3306, 3306, -1, 3307, 3307, 3307, -1, + 3308, 3308, 3308, -1, 3309, 3309, 3309, -1, + 3310, 3310, 3310, -1, 3311, 3311, 3311, -1, + 3312, 3312, 3312, -1, 3313, 3313, 3313, -1, + 3314, 3314, 3314, -1, 3315, 3315, 3315, -1, + 3316, 3316, 3316, -1, 3317, 3317, 3317, -1, + 3318, 3318, 3318, -1, 3319, 3319, 3319, -1, + 3320, 3320, 3320, -1, 3321, 3321, 3321, -1, + 3322, 3322, 3322, -1, 3323, 3323, 3323, -1, + 3324, 3324, 3324, -1, 3325, 3325, 3325, -1, + 3326, 3326, 3326, -1, 3327, 3327, 3327, -1, + 3328, 3328, 3328, -1, 3329, 3329, 3329, -1, + 3330, 3330, 3330, -1, 3331, 3331, 3331, -1, + 3332, 3332, 3332, -1, 3333, 3333, 3333, -1, + 3334, 3334, 3334, -1, 3335, 3335, 3335, -1, + 3336, 3336, 3336, -1, 3337, 3337, 3337, -1, + 3338, 3338, 3338, -1, 3339, 3339, 3339, -1, + 3340, 3340, 3340, -1, 3341, 3341, 3341, -1, + 3342, 3342, 3342, -1, 3343, 3343, 3343, -1, + 3344, 3344, 3344, -1, 3345, 3345, 3345, -1, + 3346, 3346, 3346, -1, 3347, 3347, 3347, -1, + 3348, 3348, 3348, -1, 3349, 3349, 3349, -1, + 3350, 3350, 3350, -1, 3351, 3351, 3351, -1, + 3352, 3352, 3352, -1, 3353, 3353, 3353, -1, + 3354, 3354, 3354, -1, 3355, 3355, 3355, -1, + 3356, 3356, 3356, -1, 3357, 3357, 3357, -1, + 3358, 3358, 3358, -1, 3359, 3359, 3359, -1, + 3360, 3360, 3360, -1, 3361, 3361, 3361, -1, + 3362, 3362, 3362, -1, 3363, 3363, 3363, -1, + 3364, 3364, 3364, -1, 3365, 3365, 3365, -1, + 3366, 3366, 3366, -1, 3367, 3367, 3367, -1, + 3368, 3368, 3368, -1, 3369, 3369, 3369, -1, + 3370, 3370, 3370, -1, 3371, 3371, 3371, -1, + 3372, 3372, 3372, -1, 3373, 3373, 3373, -1, + 3374, 3374, 3374, -1, 3375, 3375, 3375, -1, + 3376, 3376, 3376, -1, 3377, 3377, 3377, -1, + 3378, 3378, 3378, -1, 3379, 3379, 3379, -1, + 3380, 3380, 3380, -1, 3381, 3381, 3381, -1, + 3382, 3382, 3382, -1, 3383, 3383, 3383, -1, + 3384, 3384, 3384, -1, 3385, 3385, 3385, -1, + 3386, 3386, 3386, -1, 3387, 3387, 3387, -1, + 3388, 3388, 3388, -1, 3389, 3389, 3389, -1, + 3390, 3390, 3390, -1, 3391, 3391, 3391, -1, + 3392, 3392, 3392, -1, 3393, 3393, 3393, -1, + 3394, 3394, 3394, -1, 3395, 3395, 3395, -1, + 3396, 3396, 3396, -1, 3397, 3397, 3397, -1, + 3398, 3398, 3398, -1, 3399, 3399, 3399, -1, + 3400, 3400, 3400, -1, 3401, 3401, 3401, -1, + 3402, 3402, 3402, -1, 3403, 3403, 3403, -1, + 3404, 3404, 3404, -1, 3405, 3405, 3405, -1, + 3406, 3406, 3406, -1, 3407, 3407, 3407, -1, + 3408, 3408, 3408, -1, 3409, 3409, 3409, -1, + 3410, 3410, 3410, -1, 3411, 3411, 3411, -1, + 3412, 3412, 3412, -1, 3413, 3413, 3413, -1, + 3414, 3414, 3414, -1, 3415, 3415, 3415, -1, + 3416, 3416, 3416, -1, 3417, 3417, 3417, -1, + 3418, 3418, 3418, -1, 3419, 3419, 3419, -1, + 3420, 3420, 3420, -1, 3421, 3421, 3421, -1, + 3422, 3422, 3422, -1, 3423, 3423, 3423, -1, + 3424, 3424, 3424, -1, 3425, 3425, 3425, -1, + 3426, 3426, 3426, -1, 3427, 3427, 3427, -1, + 3428, 3428, 3428, -1, 3429, 3429, 3429, -1, + 3430, 3430, 3430, -1, 3431, 3431, 3431, -1, + 3432, 3432, 3432, -1, 3433, 3433, 3433, -1, + 3434, 3434, 3434, -1, 3435, 3435, 3435, -1, + 3436, 3436, 3436, -1, 3437, 3437, 3437, -1, + 3438, 3438, 3438, -1, 3439, 3439, 3439, -1, + 3440, 3440, 3440, -1, 3441, 3441, 3441, -1, + 3442, 3442, 3442, -1, 3443, 3443, 3443, -1, + 3444, 3444, 3444, -1, 3445, 3445, 3445, -1, + 3446, 3446, 3446, -1, 3447, 3447, 3447, -1, + 3448, 3448, 3448, -1, 3449, 3449, 3449, -1, + 3450, 3450, 3450, -1, 3451, 3451, 3451, -1, + 3452, 3452, 3452, -1, 3453, 3453, 3453, -1, + 3454, 3454, 3454, -1, 3455, 3455, 3455, -1, + 3456, 3456, 3456, -1, 3457, 3457, 3457, -1, + 3458, 3458, 3458, -1, 3459, 3459, 3459, -1, + 3460, 3460, 3460, -1, 3461, 3461, 3461, -1, + 3462, 3462, 3462, -1, 3463, 3463, 3463, -1, + 3464, 3464, 3464, -1, 3465, 3465, 3465, -1, + 3466, 3466, 3466, -1, 3467, 3467, 3467, -1, + 3468, 3468, 3468, -1, 3469, 3469, 3469, -1, + 3470, 3470, 3470, -1, 3471, 3471, 3471, -1, + 3472, 3472, 3472, -1, 3473, 3473, 3473, -1, + 3474, 3474, 3474, -1, 3475, 3475, 3475, -1, + 3476, 3476, 3476, -1, 3477, 3477, 3477, -1, + 3478, 3478, 3478, -1, 3479, 3479, 3479, -1, + 3480, 3480, 3480, -1, 3481, 3481, 3481, -1, + 3482, 3482, 3482, -1, 3483, 3483, 3483, -1, + 3484, 3484, 3484, -1, 3485, 3485, 3485, -1, + 3486, 3486, 3486, -1, 3487, 3487, 3487, -1, + 3488, 3488, 3488, -1, 3489, 3489, 3489, -1, + 3490, 3490, 3490, -1, 3491, 3491, 3491, -1, + 3492, 3492, 3492, -1, 3493, 3493, 3493, -1, + 3494, 3494, 3494, -1, 3495, 3495, 3495, -1, + 3496, 3496, 3496, -1, 3497, 3497, 3497, -1, + 3498, 3498, 3498, -1, 3499, 3499, 3499, -1, + 3500, 3500, 3500, -1, 3501, 3501, 3501, -1, + 3502, 3502, 3502, -1, 3503, 3503, 3503, -1, + 3504, 3504, 3504, -1, 3505, 3505, 3505, -1, + 3506, 3506, 3506, -1, 3507, 3507, 3507, -1, + 3508, 3508, 3508, -1, 3509, 3509, 3509, -1, + 3510, 3510, 3510, -1, 3511, 3511, 3511, -1, + 3512, 3512, 3512, -1, 3513, 3513, 3513, -1, + 3514, 3514, 3514, -1, 3515, 3515, 3515, -1, + 3516, 3516, 3516, -1, 3517, 3517, 3517, -1, + 3518, 3518, 3518, -1, 3519, 3519, 3519, -1, + 3520, 3520, 3520, -1, 3521, 3521, 3521, -1, + 3522, 3522, 3522, -1, 3523, 3523, 3523, -1, + 3524, 3524, 3524, -1, 3525, 3525, 3525, -1, + 3526, 3526, 3526, -1, 3527, 3527, 3527, -1, + 3528, 3528, 3528, -1, 3529, 3529, 3529, -1, + 3530, 3530, 3530, -1, 3531, 3531, 3531, -1, + 3532, 3532, 3532, -1, 3533, 3533, 3533, -1, + 3534, 3534, 3534, -1, 3535, 3535, 3535, -1, + 3536, 3536, 3536, -1, 3537, 3537, 3537, -1, + 3538, 3538, 3538, -1, 3539, 3539, 3539, -1, + 3540, 3540, 3540, -1, 3541, 3541, 3541, -1, + 3542, 3542, 3542, -1, 3543, 3543, 3543, -1, + 3544, 3544, 3544, -1, 3545, 3545, 3545, -1, + 3546, 3546, 3546, -1, 3547, 3547, 3547, -1, + 3548, 3548, 3548, -1, 3549, 3549, 3549, -1, + 3550, 3550, 3550, -1, 3551, 3551, 3551, -1, + 3552, 3552, 3552, -1, 3553, 3553, 3553, -1, + 3554, 3554, 3554, -1, 3555, 3555, 3555, -1, + 3556, 3556, 3556, -1, 3557, 3557, 3557, -1, + 3558, 3558, 3558, -1, 3559, 3559, 3559, -1, + 3560, 3560, 3560, -1, 3561, 3561, 3561, -1, + 3562, 3562, 3562, -1, 3563, 3563, 3563, -1, + 3564, 3564, 3564, -1, 3565, 3565, 3565, -1, + 3566, 3566, 3566, -1, 3567, 3567, 3567, -1, + 3568, 3568, 3568, -1, 3569, 3569, 3569, -1, + 3570, 3570, 3570, -1, 3571, 3571, 3571, -1, + 3572, 3572, 3572, -1, 3573, 3573, 3573, -1, + 3574, 3574, 3574, -1, 3575, 3575, 3575, -1, + 3576, 3576, 3576, -1, 3577, 3577, 3577, -1, + 3578, 3578, 3578, -1, 3579, 3579, 3579, -1, + 3580, 3580, 3580, -1, 3581, 3581, 3581, -1, + 3582, 3582, 3582, -1, 3583, 3583, 3583, -1, + 3584, 3584, 3584, -1, 3585, 3585, 3585, -1, + 3586, 3586, 3586, -1, 3587, 3587, 3587, -1, + 3588, 3588, 3588, -1, 3589, 3589, 3589, -1, + 3590, 3590, 3590, -1, 3591, 3591, 3591, -1, + 3592, 3592, 3592, -1, 3593, 3593, 3593, -1, + 3594, 3594, 3594, -1, 3595, 3595, 3595, -1, + 3596, 3596, 3596, -1, 3597, 3597, 3597, -1, + 3598, 3598, 3598, -1, 3599, 3599, 3599, -1, + 3600, 3600, 3600, -1, 3601, 3601, 3601, -1, + 3602, 3602, 3602, -1, 3603, 3603, 3603, -1, + 3604, 3604, 3604, -1, 3605, 3605, 3605, -1, + 3606, 3606, 3606, -1, 3607, 3607, 3607, -1, + 3608, 3608, 3608, -1, 3609, 3609, 3609, -1, + 3610, 3610, 3610, -1, 3611, 3611, 3611, -1, + 3612, 3612, 3612, -1, 3613, 3613, 3613, -1, + 3614, 3614, 3614, -1, 3615, 3615, 3615, -1, + 3616, 3616, 3616, -1, 3617, 3617, 3617, -1, + 3618, 3618, 3618, -1, 3619, 3619, 3619, -1, + 3620, 3620, 3620, -1, 3621, 3621, 3621, -1, + 3622, 3622, 3622, -1, 3623, 3623, 3623, -1, + 3624, 3624, 3624, -1, 3625, 3625, 3625, -1, + 3626, 3626, 3626, -1, 3627, 3627, 3627, -1, + 3628, 3628, 3628, -1, 3629, 3629, 3629, -1, + 3630, 3630, 3630, -1, 3631, 3631, 3631, -1, + 3632, 3632, 3632, -1, 3633, 3633, 3633, -1, + 3634, 3634, 3634, -1, 3635, 3635, 3635, -1, + 3636, 3636, 3636, -1, 3637, 3637, 3637, -1, + 3638, 3638, 3638, -1, 3639, 3639, 3639, -1, + 3640, 3640, 3640, -1, 3641, 3641, 3641, -1, + 3642, 3642, 3642, -1, 3643, 3643, 3643, -1, + 3644, 3644, 3644, -1, 3645, 3645, 3645, -1, + 3646, 3646, 3646, -1, 3647, 3647, 3647, -1, + 3648, 3648, 3648, -1, 3649, 3649, 3649, -1, + 3650, 3650, 3650, -1, 3651, 3651, 3651, -1, + 3652, 3652, 3652, -1, 3653, 3653, 3653, -1, + 3654, 3654, 3654, -1, 3655, 3655, 3655, -1, + 3656, 3656, 3656, -1, 3657, 3657, 3657, -1, + 3658, 3658, 3658, -1, 3659, 3659, 3659, -1, + 3660, 3660, 3660, -1, 3661, 3661, 3661, -1, + 3662, 3662, 3662, -1, 3663, 3663, 3663, -1, + 3664, 3664, 3664, -1, 3665, 3665, 3665, -1, + 3666, 3666, 3666, -1, 3667, 3667, 3667, -1, + 3668, 3668, 3668, -1, 3669, 3669, 3669, -1, + 3670, 3670, 3670, -1, 3671, 3671, 3671, -1, + 3672, 3672, 3672, -1, 3673, 3673, 3673, -1, + 3674, 3674, 3674, -1, 3675, 3675, 3675, -1, + 3676, 3676, 3676, -1, 3677, 3677, 3677, -1, + 3678, 3678, 3678, -1, 3679, 3679, 3679, -1, + 3680, 3680, 3680, -1, 3681, 3681, 3681, -1, + 3682, 3682, 3682, -1, 3683, 3683, 3683, -1, + 3684, 3684, 3684, -1, 3685, 3685, 3685, -1, + 3686, 3686, 3686, -1, 3687, 3687, 3687, -1, + 3688, 3688, 3688, -1, 3689, 3689, 3689, -1, + 3690, 3690, 3690, -1, 3691, 3691, 3691, -1, + 3692, 3692, 3692, -1, 3693, 3693, 3693, -1, + 3694, 3694, 3694, -1, 3695, 3695, 3695, -1, + 3696, 3696, 3696, -1, 3697, 3697, 3697, -1, + 3698, 3698, 3698, -1, 3699, 3699, 3699, -1, + 3700, 3700, 3700, -1, 3701, 3701, 3701, -1, + 3702, 3702, 3702, -1, 3703, 3703, 3703, -1, + 3704, 3704, 3704, -1, 3705, 3705, 3705, -1, + 3706, 3706, 3706, -1, 3707, 3707, 3707, -1, + 3708, 3708, 3708, -1, 3709, 3709, 3709, -1, + 3710, 3710, 3710, -1, 3711, 3711, 3711, -1, + 3712, 3712, 3712, -1, 3713, 3713, 3713, -1, + 3714, 3714, 3714, -1, 3715, 3715, 3715, -1, + 3716, 3716, 3716, -1, 3717, 3717, 3717, -1, + 3718, 3718, 3718, -1, 3719, 3719, 3719, -1, + 3720, 3720, 3720, -1, 3721, 3721, 3721, -1, + 3722, 3722, 3722, -1, 3723, 3723, 3723, -1, + 3724, 3724, 3724, -1, 3725, 3725, 3725, -1, + 3726, 3726, 3726, -1, 3727, 3727, 3727, -1, + 3728, 3728, 3728, -1, 3729, 3729, 3729, -1, + 3730, 3730, 3730, -1, 3731, 3731, 3731, -1, + 3732, 3732, 3732, -1, 3733, 3733, 3733, -1, + 3734, 3734, 3734, -1, 3735, 3735, 3735, -1, + 3736, 3736, 3736, -1, 3737, 3737, 3737, -1, + 3738, 3738, 3738, -1, 3739, 3739, 3739, -1, + 3740, 3740, 3740, -1, 3741, 3741, 3741, -1, + 3742, 3742, 3742, -1, 3743, 3743, 3743, -1, + 3744, 3744, 3744, -1, 3745, 3745, 3745, -1, + 3746, 3746, 3746, -1, 3747, 3747, 3747, -1, + 3748, 3748, 3748, -1, 3749, 3749, 3749, -1, + 3750, 3750, 3750, -1, 3751, 3751, 3751, -1, + 3752, 3752, 3752, -1, 3753, 3753, 3753, -1, + 3754, 3754, 3754, -1, 3755, 3755, 3755, -1, + 3756, 3756, 3756, -1, 3757, 3757, 3757, -1, + 3758, 3758, 3758, -1, 3759, 3759, 3759, -1, + 3760, 3760, 3760, -1, 3761, 3761, 3761, -1, + 3762, 3762, 3762, -1, 3763, 3763, 3763, -1, + 3764, 3764, 3764, -1, 3765, 3765, 3765, -1, + 3766, 3766, 3766, -1, 3767, 3767, 3767, -1, + 3768, 3768, 3768, -1, 3769, 3769, 3769, -1, + 3770, 3770, 3770, -1, 3771, 3771, 3771, -1, + 3772, 3772, 3772, -1, 3773, 3773, 3773, -1, + 3774, 3774, 3774, -1, 3775, 3775, 3775, -1, + 3776, 3776, 3776, -1, 3777, 3777, 3777, -1, + 3778, 3778, 3778, -1, 3779, 3779, 3779, -1, + 3780, 3780, 3780, -1, 3781, 3781, 3781, -1, + 3782, 3782, 3782, -1, 3783, 3783, 3783, -1, + 3784, 3784, 3784, -1, 3785, 3785, 3785, -1, + 3786, 3786, 3786, -1, 3787, 3787, 3787, -1, + 3788, 3788, 3788, -1, 3789, 3789, 3789, -1, + 3790, 3790, 3790, -1, 3791, 3791, 3791, -1, + 3792, 3792, 3792, -1, 3793, 3793, 3793, -1, + 3794, 3794, 3794, -1, 3795, 3795, 3795, -1, + 3796, 3796, 3796, -1, 3797, 3797, 3797, -1, + 3798, 3798, 3798, -1, 3799, 3799, 3799, -1, + 3800, 3800, 3800, -1, 3801, 3801, 3801, -1, + 3802, 3802, 3802, -1, 3803, 3803, 3803, -1, + 3804, 3804, 3804, -1, 3805, 3805, 3805, -1, + 3806, 3806, 3806, -1, 3807, 3807, 3807, -1, + 3808, 3808, 3808, -1, 3809, 3809, 3809, -1, + 3810, 3810, 3810, -1, 3811, 3811, 3811, -1, + 3812, 3812, 3812, -1, 3813, 3813, 3813, -1, + 3814, 3814, 3814, -1, 3815, 3815, 3815, -1, + 3816, 3816, 3816, -1, 3817, 3817, 3817, -1, + 3818, 3818, 3818, -1, 3819, 3819, 3819, -1, + 3820, 3820, 3820, -1, 3821, 3821, 3821, -1, + 3822, 3822, 3822, -1, 3823, 3823, 3823, -1, + 3824, 3824, 3824, -1, 3825, 3825, 3825, -1, + 3826, 3826, 3826, -1, 3827, 3827, 3827, -1, + 3828, 3828, 3828, -1, 3829, 3829, 3829, -1, + 3830, 3830, 3830, -1, 3831, 3831, 3831, -1, + 3832, 3832, 3832, -1, 3833, 3833, 3833, -1, + 3834, 3834, 3834, -1, 3835, 3835, 3835, -1, + 3836, 3836, 3836, -1, 3837, 3837, 3837, -1, + 3838, 3838, 3838, -1, 3839, 3839, 3839, -1, + 3840, 3840, 3840, -1, 3841, 3841, 3841, -1, + 3842, 3842, 3842, -1, 3843, 3843, 3843, -1, + 3844, 3844, 3844, -1, 3845, 3845, 3845, -1, + 3846, 3846, 3846, -1, 3847, 3847, 3847, -1, + 3848, 3848, 3848, -1, 3849, 3849, 3849, -1, + 3850, 3850, 3850, -1, 3851, 3851, 3851, -1, + 3852, 3852, 3852, -1, 3853, 3853, 3853, -1, + 3854, 3854, 3854, -1, 3855, 3855, 3855, -1, + 3856, 3856, 3856, -1, 3857, 3857, 3857, -1, + 3858, 3858, 3858, -1, 3859, 3859, 3859, -1, + 3860, 3860, 3860, -1, 3861, 3861, 3861, -1, + 3862, 3862, 3862, -1, 3863, 3863, 3863, -1, + 3864, 3864, 3864, -1, 3865, 3865, 3865, -1, + 3866, 3866, 3866, -1, 3867, 3867, 3867, -1, + 3868, 3868, 3868, -1, 3869, 3869, 3869, -1, + 3870, 3870, 3870, -1, 3871, 3871, 3871, -1, + 3872, 3872, 3872, -1, 3873, 3873, 3873, -1, + 3874, 3874, 3874, -1, 3875, 3875, 3875, -1, + 3876, 3876, 3876, -1, 3877, 3877, 3877, -1, + 3878, 3878, 3878, -1, 3879, 3879, 3879, -1, + 3880, 3880, 3880, -1, 3881, 3881, 3881, -1, + 3882, 3882, 3882, -1, 3883, 3883, 3883, -1, + 3884, 3884, 3884, -1, 3885, 3885, 3885, -1, + 3886, 3886, 3886, -1, 3887, 3887, 3887, -1, + 3888, 3888, 3888, -1, 3889, 3889, 3889, -1, + 3890, 3890, 3890, -1, 3891, 3891, 3891, -1, + 3892, 3892, 3892, -1, 3893, 3893, 3893, -1, + 3894, 3894, 3894, -1, 3895, 3895, 3895, -1, + 3896, 3896, 3896, -1, 3897, 3897, 3897, -1, + 3898, 3898, 3898, -1, 3899, 3899, 3899, -1, + 3900, 3900, 3900, -1, 3901, 3901, 3901, -1, + 3902, 3902, 3902, -1, 3903, 3903, 3903, -1, + 3904, 3904, 3904, -1, 3905, 3905, 3905, -1, + 3906, 3906, 3906, -1, 3907, 3907, 3907, -1, + 3908, 3908, 3908, -1, 3909, 3909, 3909, -1, + 3910, 3910, 3910, -1, 3911, 3911, 3911, -1, + 3912, 3912, 3912, -1, 3913, 3913, 3913, -1, + 3914, 3914, 3914, -1, 3915, 3915, 3915, -1, + 3916, 3916, 3916, -1, 3917, 3917, 3917, -1, + 3918, 3918, 3918, -1, 3919, 3919, 3919, -1, + 3920, 3920, 3920, -1, 3921, 3921, 3921, -1, + 3922, 3922, 3922, -1, 3923, 3923, 3923, -1, + 3924, 3924, 3924, -1, 3925, 3925, 3925, -1, + 3926, 3926, 3926, -1, 3927, 3927, 3927, -1, + 3928, 3928, 3928, -1, 3929, 3929, 3929, -1, + 3930, 3930, 3930, -1, 3931, 3931, 3931, -1, + 3932, 3932, 3932, -1, 3933, 3933, 3933, -1, + 3934, 3934, 3934, -1, 3935, 3935, 3935, -1, + 3936, 3936, 3936, -1, 3937, 3937, 3937, -1, + 3938, 3938, 3938, -1, 3939, 3939, 3939, -1, + 3940, 3940, 3940, -1, 3941, 3941, 3941, -1, + 3942, 3942, 3942, -1, 3943, 3943, 3943, -1, + 3944, 3944, 3944, -1, 3945, 3945, 3945, -1, + 3946, 3946, 3946, -1, 3947, 3947, 3947, -1, + 3948, 3948, 3948, -1, 3949, 3949, 3949, -1, + 3950, 3950, 3950, -1, 3951, 3951, 3951, -1, + 3952, 3952, 3952, -1, 3953, 3953, 3953, -1, + 3954, 3954, 3954, -1, 3955, 3955, 3955, -1, + 3956, 3956, 3956, -1, 3957, 3957, 3957, -1, + 3958, 3958, 3958, -1, 3959, 3959, 3959, -1, + 3960, 3960, 3960, -1, 3961, 3961, 3961, -1, + 3962, 3962, 3962, -1, 3963, 3963, 3963, -1, + 3964, 3964, 3964, -1, 3965, 3965, 3965, -1, + 3966, 3966, 3966, -1, 3967, 3967, 3967, -1, + 3968, 3968, 3968, -1, 3969, 3969, 3969, -1, + 3970, 3970, 3970, -1, 3971, 3971, 3971, -1, + 3972, 3972, 3972, -1, 3973, 3973, 3973, -1, + 3974, 3974, 3974, -1, 3975, 3975, 3975, -1, + 3976, 3976, 3976, -1, 3977, 3977, 3977, -1, + 3978, 3978, 3978, -1, 3979, 3979, 3979, -1, + 3980, 3980, 3980, -1, 3981, 3981, 3981, -1, + 3982, 3982, 3982, -1, 3983, 3983, 3983, -1, + 3984, 3984, 3984, -1, 3985, 3985, 3985, -1, + 3986, 3986, 3986, -1, 3987, 3987, 3987, -1, + 3988, 3988, 3988, -1, 3989, 3989, 3989, -1, + 3990, 3990, 3990, -1, 3991, 3991, 3991, -1, + 3992, 3992, 3992, -1, 3993, 3993, 3993, -1, + 3994, 3994, 3994, -1, 3995, 3995, 3995, -1, + 3996, 3996, 3996, -1, 3997, 3997, 3997, -1, + 3998, 3998, 3998, -1, 3999, 3999, 3999, -1, + 4000, 4000, 4000, -1, 4001, 4001, 4001, -1, + 4002, 4002, 4002, -1, 4003, 4003, 4003, -1, + 4004, 4004, 4004, -1, 4005, 4005, 4005, -1, + 4006, 4006, 4006, -1, 4007, 4007, 4007, -1, + 4008, 4008, 4008, -1, 4009, 4009, 4009, -1, + 4010, 4010, 4010, -1, 4011, 4011, 4011, -1, + 4012, 4012, 4012, -1, 4013, 4013, 4013, -1, + 4014, 4014, 4014, -1, 4015, 4015, 4015, -1, + 4016, 4016, 4016, -1, 4017, 4017, 4017, -1, + 4018, 4018, 4018, -1, 4019, 4019, 4019, -1, + 4020, 4020, 4020, -1, 4021, 4021, 4021, -1, + 4022, 4022, 4022, -1, 4023, 4023, 4023, -1, + 4024, 4024, 4024, -1, 4025, 4025, 4025, -1, + 4026, 4026, 4026, -1, 4027, 4027, 4027, -1, + 4028, 4028, 4028, -1, 4029, 4029, 4029, -1, + 4030, 4030, 4030, -1, 4031, 4031, 4031, -1, + 4032, 4032, 4032, -1, 4033, 4033, 4033, -1, + 4034, 4034, 4034, -1, 4035, 4035, 4035, -1, + 4036, 4036, 4036, -1, 4037, 4037, 4037, -1, + 4038, 4038, 4038, -1, 4039, 4039, 4039, -1, + 4040, 4040, 4040, -1, 4041, 4041, 4041, -1, + 4042, 4042, 4042, -1, 4043, 4043, 4043, -1, + 4044, 4044, 4044, -1, 4045, 4045, 4045, -1, + 4046, 4046, 4046, -1, 4047, 4047, 4047, -1, + 4048, 4048, 4048, -1, 4049, 4049, 4049, -1, + 4050, 4050, 4050, -1, 4051, 4051, 4051, -1, + 4052, 4052, 4052, -1, 4053, 4053, 4053, -1, + 4054, 4054, 4054, -1, 4055, 4055, 4055, -1, + 4056, 4056, 4056, -1, 4057, 4057, 4057, -1, + 4058, 4058, 4058, -1, 4059, 4059, 4059, -1, + 4060, 4060, 4060, -1, 4061, 4061, 4061, -1, + 4062, 4062, 4062, -1, 4063, 4063, 4063, -1, + 4064, 4064, 4064, -1, 4065, 4065, 4065, -1, + 4066, 4066, 4066, -1, 4067, 4067, 4067, -1, + 4068, 4068, 4068, -1, 4069, 4069, 4069, -1, + 4070, 4070, 4070, -1, 4071, 4071, 4071, -1, + 4072, 4072, 4072, -1, 4073, 4073, 4073, -1, + 4074, 4074, 4074, -1, 4075, 4075, 4075, -1, + 4076, 4076, 4076, -1, 4077, 4077, 4077, -1, + 4078, 4078, 4078, -1, 4079, 4079, 4079, -1, + 4080, 4080, 4080, -1, 4081, 4081, 4081, -1, + 4082, 4082, 4082, -1, 4083, 4083, 4083, -1, + 4084, 4084, 4084, -1, 4085, 4085, 4085, -1, + 4086, 4086, 4086, -1, 4087, 4087, 4087, -1, + 4088, 4088, 4088, -1, 4089, 4089, 4089, -1, + 4090, 4090, 4090, -1, 4091, 4091, 4091, -1, + 4092, 4092, 4092, -1, 4093, 4093, 4093, -1, + 4094, 4094, 4094, -1, 4095, 4095, 4095, -1, + 4096, 4096, 4096, -1, 4097, 4097, 4097, -1, + 4098, 4098, 4098, -1, 4099, 4099, 4099, -1, + 4100, 4100, 4100, -1, 4101, 4101, 4101, -1, + 4102, 4102, 4102, -1, 4103, 4103, 4103, -1, + 4104, 4104, 4104, -1, 4105, 4105, 4105, -1, + 4106, 4106, 4106, -1, 4107, 4107, 4107, -1, + 4108, 4108, 4108, -1, 4109, 4109, 4109, -1, + 4110, 4110, 4110, -1, 4111, 4111, 4111, -1, + 4112, 4112, 4112, -1, 4113, 4113, 4113, -1, + 4114, 4114, 4114, -1, 4115, 4115, 4115, -1, + 4116, 4116, 4116, -1, 4117, 4117, 4117, -1, + 4118, 4118, 4118, -1, 4119, 4119, 4119, -1, + 4120, 4120, 4120, -1, 4121, 4121, 4121, -1, + 4122, 4122, 4122, -1, 4123, 4123, 4123, -1, + 4124, 4124, 4124, -1, 4125, 4125, 4125, -1, + 4126, 4126, 4126, -1, 4127, 4127, 4127, -1, + 4128, 4128, 4128, -1, 4129, 4129, 4129, -1, + 4130, 4130, 4130, -1, 4131, 4131, 4131, -1, + 4132, 4132, 4132, -1, 4133, 4133, 4133, -1, + 4134, 4134, 4134, -1, 4135, 4135, 4135, -1, + 4136, 4136, 4136, -1, 4137, 4137, 4137, -1, + 4138, 4138, 4138, -1, 4139, 4139, 4139, -1, + 4140, 4140, 4140, -1, 4141, 4141, 4141, -1, + 4142, 4142, 4142, -1, 4143, 4143, 4143, -1, + 4144, 4144, 4144, -1, 4145, 4145, 4145, -1, + 4146, 4146, 4146, -1, 4147, 4147, 4147, -1, + 4148, 4148, 4148, -1, 4149, 4149, 4149, -1, + 4150, 4150, 4150, -1, 4151, 4151, 4151, -1, + 4152, 4152, 4152, -1, 4153, 4153, 4153, -1, + 4154, 4154, 4154, -1, 4155, 4155, 4155, -1, + 4156, 4156, 4156, -1, 4157, 4157, 4157, -1, + 4158, 4158, 4158, -1, 4159, 4159, 4159, -1, + 4160, 4160, 4160, -1, 4161, 4161, 4161, -1, + 4162, 4162, 4162, -1, 4163, 4163, 4163, -1, + 4164, 4164, 4164, -1, 4165, 4165, 4165, -1, + 4166, 4166, 4166, -1, 4167, 4167, 4167, -1, + 4168, 4168, 4168, -1, 4169, 4169, 4169, -1, + 4170, 4170, 4170, -1, 4171, 4171, 4171, -1, + 4172, 4172, 4172, -1, 4173, 4173, 4173, -1, + 4174, 4174, 4174, -1, 4175, 4175, 4175, -1, + 4176, 4176, 4176, -1, 4177, 4177, 4177, -1, + 4178, 4178, 4178, -1, 4179, 4179, 4179, -1, + 4180, 4180, 4180, -1, 4181, 4181, 4181, -1, + 4182, 4182, 4182, -1, 4183, 4183, 4183, -1, + 4184, 4184, 4184, -1, 4185, 4185, 4185, -1, + 4186, 4186, 4186, -1, 4187, 4187, 4187, -1, + 4188, 4188, 4188, -1, 4189, 4189, 4189, -1, + 4190, 4190, 4190, -1, 4191, 4191, 4191, -1, + 4192, 4192, 4192, -1, 4193, 4193, 4193, -1, + 4194, 4194, 4194, -1, 4195, 4195, 4195, -1, + 4196, 4196, 4196, -1, 4197, 4197, 4197, -1, + 4198, 4198, 4198, -1, 4199, 4199, 4199, -1, + 4200, 4200, 4200, -1, 4201, 4201, 4201, -1, + 4202, 4202, 4202, -1, 4203, 4203, 4203, -1, + 4204, 4204, 4204, -1, 4205, 4205, 4205, -1, + 4206, 4206, 4206, -1, 4207, 4207, 4207, -1, + 4208, 4208, 4208, -1, 4209, 4209, 4209, -1, + 4210, 4210, 4210, -1, 4211, 4211, 4211, -1, + 4212, 4212, 4212, -1, 4213, 4213, 4213, -1, + 4214, 4214, 4214, -1, 4215, 4215, 4215, -1, + 4216, 4216, 4216, -1, 4217, 4217, 4217, -1, + 4218, 4218, 4218, -1, 4219, 4219, 4219, -1, + 4220, 4220, 4220, -1, 4221, 4221, 4221, -1, + 4222, 4222, 4222, -1, 4223, 4223, 4223, -1, + 4224, 4224, 4224, -1, 4225, 4225, 4225, -1, + 4226, 4226, 4226, -1, 4227, 4227, 4227, -1, + 4228, 4228, 4228, -1, 4229, 4229, 4229, -1, + 4230, 4230, 4230, -1, 4231, 4231, 4231, -1, + 4232, 4232, 4232, -1, 4233, 4233, 4233, -1, + 4234, 4234, 4234, -1, 4235, 4235, 4235, -1, + 4236, 4236, 4236, -1, 4237, 4237, 4237, -1, + 4238, 4238, 4238, -1, 4239, 4239, 4239, -1, + 4240, 4240, 4240, -1, 4241, 4241, 4241, -1, + 4242, 4242, 4242, -1, 4243, 4243, 4243, -1, + 4244, 4244, 4244, -1, 4245, 4245, 4245, -1, + 4246, 4246, 4246, -1, 4247, 4247, 4247, -1, + 4248, 4248, 4248, -1, 4249, 4249, 4249, -1, + 4250, 4250, 4250, -1, 4251, 4251, 4251, -1, + 4252, 4252, 4252, -1, 4253, 4253, 4253, -1, + 4254, 4254, 4254, -1, 4255, 4255, 4255, -1, + 4256, 4256, 4256, -1, 4257, 4257, 4257, -1, + 4258, 4258, 4258, -1, 4259, 4259, 4259, -1, + 4260, 4260, 4260, -1, 4261, 4261, 4261, -1, + 4262, 4262, 4262, -1, 4263, 4263, 4263, -1, + 4264, 4264, 4264, -1, 4265, 4265, 4265, -1, + 4266, 4266, 4266, -1, 4267, 4267, 4267, -1, + 4268, 4268, 4268, -1, 4269, 4269, 4269, -1, + 4270, 4270, 4270, -1, 4271, 4271, 4271, -1, + 4272, 4272, 4272, -1, 4273, 4273, 4273, -1, + 4274, 4274, 4274, -1, 4275, 4275, 4275, -1, + 4276, 4276, 4276, -1, 4277, 4277, 4277, -1, + 4278, 4278, 4278, -1, 4279, 4279, 4279, -1, + 4280, 4280, 4280, -1, 4281, 4281, 4281, -1, + 4282, 4282, 4282, -1, 4283, 4283, 4283, -1, + 4284, 4284, 4284, -1, 4285, 4285, 4285, -1, + 4286, 4286, 4286, -1, 4287, 4287, 4287, -1, + 4288, 4288, 4288, -1, 4289, 4289, 4289, -1, + 4290, 4290, 4290, -1, 4291, 4291, 4291, -1, + 4292, 4292, 4292, -1, 4293, 4293, 4293, -1, + 4294, 4294, 4294, -1, 4295, 4295, 4295, -1, + 4296, 4296, 4296, -1, 4297, 4297, 4297, -1, + 4298, 4298, 4298, -1, 4299, 4299, 4299, -1, + 4300, 4300, 4300, -1, 4301, 4301, 4301, -1, + 4302, 4302, 4302, -1, 4303, 4303, 4303, -1, + 4304, 4304, 4304, -1, 4305, 4305, 4305, -1, + 4306, 4306, 4306, -1, 4307, 4307, 4307, -1, + 4308, 4308, 4308, -1, 4309, 4309, 4309, -1, + 4310, 4310, 4310, -1, 4311, 4311, 4311, -1, + 4312, 4312, 4312, -1, 4313, 4313, 4313, -1, + 4314, 4314, 4314, -1, 4315, 4315, 4315, -1, + 4316, 4316, 4316, -1, 4317, 4317, 4317, -1, + 4318, 4318, 4318, -1, 4319, 4319, 4319, -1, + 4320, 4320, 4320, -1, 4321, 4321, 4321, -1, + 4322, 4322, 4322, -1, 4323, 4323, 4323, -1, + 4324, 4324, 4324, -1, 4325, 4325, 4325, -1, + 4326, 4326, 4326, -1, 4327, 4327, 4327, -1, + 4328, 4328, 4328, -1, 4329, 4329, 4329, -1, + 4330, 4330, 4330, -1, 4331, 4331, 4331, -1, + 4332, 4332, 4332, -1, 4333, 4333, 4333, -1, + 4334, 4334, 4334, -1, 4335, 4335, 4335, -1, + 4336, 4336, 4336, -1, 4337, 4337, 4337, -1, + 4338, 4338, 4338, -1, 4339, 4339, 4339, -1, + 4340, 4340, 4340, -1, 4341, 4341, 4341, -1, + 4342, 4342, 4342, -1, 4343, 4343, 4343, -1, + 4344, 4344, 4344, -1, 4345, 4345, 4345, -1, + 4346, 4346, 4346, -1, 4347, 4347, 4347, -1, + 4348, 4348, 4348, -1, 4349, 4349, 4349, -1, + 4350, 4350, 4350, -1, 4351, 4351, 4351, -1, + 4352, 4352, 4352, -1, 4353, 4353, 4353, -1, + 4354, 4354, 4354, -1, 4355, 4355, 4355, -1, + 4356, 4356, 4356, -1, 4357, 4357, 4357, -1, + 4358, 4358, 4358, -1, 4359, 4359, 4359, -1, + 4360, 4360, 4360, -1, 4361, 4361, 4361, -1, + 4362, 4362, 4362, -1, 4363, 4363, 4363, -1, + 4364, 4364, 4364, -1, 4365, 4365, 4365, -1, + 4366, 4366, 4366, -1, 4367, 4367, 4367, -1, + 4368, 4368, 4368, -1, 4369, 4369, 4369, -1, + 4370, 4370, 4370, -1, 4371, 4371, 4371, -1, + 4372, 4372, 4372, -1, 4373, 4373, 4373, -1, + 4374, 4374, 4374, -1, 4375, 4375, 4375, -1, + 4376, 4376, 4376, -1, 4377, 4377, 4377, -1, + 4378, 4378, 4378, -1, 4379, 4379, 4379, -1, + 4380, 4380, 4380, -1, 4381, 4381, 4381, -1, + 4382, 4382, 4382, -1, 4383, 4383, 4383, -1, + 4384, 4384, 4384, -1, 4385, 4385, 4385, -1, + 4386, 4386, 4386, -1, 4387, 4387, 4387, -1, + 4388, 4388, 4388, -1, 4389, 4389, 4389, -1, + 4390, 4390, 4390, -1, 4391, 4391, 4391, -1, + 4392, 4392, 4392, -1, 4393, 4393, 4393, -1, + 4394, 4394, 4394, -1, 4395, 4395, 4395, -1, + 4396, 4396, 4396, -1, 4397, 4397, 4397, -1, + 4398, 4398, 4398, -1, 4399, 4399, 4399, -1, + 4400, 4400, 4400, -1, 4401, 4401, 4401, -1, + 4402, 4402, 4402, -1, 4403, 4403, 4403, -1, + 4404, 4404, 4404, -1, 4405, 4405, 4405, -1, + 4406, 4406, 4406, -1, 4407, 4407, 4407, -1, + 4408, 4408, 4408, -1, 4409, 4409, 4409, -1, + 4410, 4410, 4410, -1, 4411, 4411, 4411, -1, + 4412, 4412, 4412, -1, 4413, 4413, 4413, -1, + 4414, 4414, 4414, -1, 4415, 4415, 4415, -1, + 4416, 4416, 4416, -1, 4417, 4417, 4417, -1, + 4418, 4418, 4418, -1, 4419, 4419, 4419, -1, + 4420, 4420, 4420, -1, 4421, 4421, 4421, -1, + 4422, 4422, 4422, -1, 4423, 4423, 4423, -1, + 4424, 4424, 4424, -1, 4425, 4425, 4425, -1, + 4426, 4426, 4426, -1, 4427, 4427, 4427, -1, + 4428, 4428, 4428, -1, 4429, 4429, 4429, -1, + 4430, 4430, 4430, -1, 4431, 4431, 4431, -1, + 4432, 4432, 4432, -1, 4433, 4433, 4433, -1, + 4434, 4434, 4434, -1, 4435, 4435, 4435, -1, + 4436, 4436, 4436, -1, 4437, 4437, 4437, -1, + 4438, 4438, 4438, -1, 4439, 4439, 4439, -1, + 4440, 4440, 4440, -1, 4441, 4441, 4441, -1, + 4442, 4442, 4442, -1, 4443, 4443, 4443, -1, + 4444, 4444, 4444, -1, 4445, 4445, 4445, -1, + 4446, 4446, 4446, -1, 4447, 4447, 4447, -1, + 4448, 4448, 4448, -1, 4449, 4449, 4449, -1, + 4450, 4450, 4450, -1, 4451, 4451, 4451, -1, + 4452, 4452, 4452, -1, 4453, 4453, 4453, -1, + 4454, 4454, 4454, -1, 4455, 4455, 4455, -1, + 4456, 4456, 4456, -1, 4457, 4457, 4457, -1, + 4458, 4458, 4458, -1, 4459, 4459, 4459, -1, + 4460, 4460, 4460, -1, 4461, 4461, 4461, -1, + 4462, 4462, 4462, -1, 4463, 4463, 4463, -1, + 4464, 4464, 4464, -1, 4465, 4465, 4465, -1, + 4466, 4466, 4466, -1, 4467, 4467, 4467, -1, + 4468, 4468, 4468, -1, 4469, 4469, 4469, -1, + 4470, 4470, 4470, -1, 4471, 4471, 4471, -1, + 4472, 4472, 4472, -1, 4473, 4473, 4473, -1, + 4474, 4474, 4474, -1, 4475, 4475, 4475, -1, + 4476, 4476, 4476, -1, 4477, 4477, 4477, -1, + 4478, 4478, 4478, -1, 4479, 4479, 4479, -1, + 4480, 4480, 4480, -1, 4481, 4481, 4481, -1, + 4482, 4482, 4482, -1, 4483, 4483, 4483, -1, + 4484, 4484, 4484, -1, 4485, 4485, 4485, -1, + 4486, 4486, 4486, -1, 4487, 4487, 4487, -1, + 4488, 4488, 4488, -1, 4489, 4489, 4489, -1, + 4490, 4490, 4490, -1, 4491, 4491, 4491, -1, + 4492, 4492, 4492, -1, 4493, 4493, 4493, -1, + 4494, 4494, 4494, -1, 4495, 4495, 4495, -1, + 4496, 4496, 4496, -1, 4497, 4497, 4497, -1, + 4498, 4498, 4498, -1, 4499, 4499, 4499, -1, + 4500, 4500, 4500, -1, 4501, 4501, 4501, -1, + 4502, 4502, 4502, -1, 4503, 4503, 4503, -1, + 4504, 4504, 4504, -1, 4505, 4505, 4505, -1, + 4506, 4506, 4506, -1, 4507, 4507, 4507, -1, + 4508, 4508, 4508, -1, 4509, 4509, 4509, -1, + 4510, 4510, 4510, -1, 4511, 4511, 4511, -1, + 4512, 4512, 4512, -1, 4513, 4513, 4513, -1, + 4514, 4514, 4514, -1, 4515, 4515, 4515, -1, + 4516, 4516, 4516, -1, 4517, 4517, 4517, -1, + 4518, 4518, 4518, -1, 4519, 4519, 4519, -1, + 4520, 4520, 4520, -1, 4521, 4521, 4521, -1, + 4522, 4522, 4522, -1, 4523, 4523, 4523, -1, + 4524, 4524, 4524, -1, 4525, 4525, 4525, -1, + 4526, 4526, 4526, -1, 4527, 4527, 4527, -1, + 4528, 4528, 4528, -1, 4529, 4529, 4529, -1, + 4530, 4530, 4530, -1, 4531, 4531, 4531, -1, + 4532, 4532, 4532, -1, 4533, 4533, 4533, -1, + 4534, 4534, 4534, -1, 4535, 4535, 4535, -1, + 4536, 4536, 4536, -1, 4537, 4537, 4537, -1, + 4538, 4538, 4538, -1, 4539, 4539, 4539, -1, + 4540, 4540, 4540, -1, 4541, 4541, 4541, -1, + 4542, 4542, 4542, -1, 4543, 4543, 4543, -1, + 4544, 4544, 4544, -1, 4545, 4545, 4545, -1, + 4546, 4546, 4546, -1, 4547, 4547, 4547, -1, + 4548, 4548, 4548, -1, 4549, 4549, 4549, -1, + 4550, 4550, 4550, -1, 4551, 4551, 4551, -1, + 4552, 4552, 4552, -1, 4553, 4553, 4553, -1, + 4554, 4554, 4554, -1, 4555, 4555, 4555, -1, + 4556, 4556, 4556, -1, 4557, 4557, 4557, -1, + 4558, 4558, 4558, -1, 4559, 4559, 4559, -1, + 4560, 4560, 4560, -1, 4561, 4561, 4561, -1, + 4562, 4562, 4562, -1, 4563, 4563, 4563, -1, + 4564, 4564, 4564, -1, 4565, 4565, 4565, -1, + 4566, 4566, 4566, -1, 4567, 4567, 4567, -1, + 4568, 4568, 4568, -1, 4569, 4569, 4569, -1, + 4570, 4570, 4570, -1, 4571, 4571, 4571, -1, + 4572, 4572, 4572, -1, 4573, 4573, 4573, -1, + 4574, 4574, 4574, -1, 4575, 4575, 4575, -1, + 4576, 4576, 4576, -1, 4577, 4577, 4577, -1, + 4578, 4578, 4578, -1, 4579, 4579, 4579, -1, + 4580, 4580, 4580, -1, 4581, 4581, 4581, -1, + 4582, 4582, 4582, -1, 4583, 4583, 4583, -1, + 4584, 4584, 4584, -1, 4585, 4585, 4585, -1, + 4586, 4586, 4586, -1, 4587, 4587, 4587, -1, + 4588, 4588, 4588, -1, 4589, 4589, 4589, -1, + 4590, 4590, 4590, -1, 4591, 4591, 4591, -1, + 4592, 4592, 4592, -1, 4593, 4593, 4593, -1, + 4594, 4594, 4594, -1, 4595, 4595, 4595, -1, + 4596, 4596, 4596, -1, 4597, 4597, 4597, -1, + 4598, 4598, 4598, -1, 4599, 4599, 4599, -1, + 4600, 4600, 4600, -1, 4601, 4601, 4601, -1, + 4602, 4602, 4602, -1, 4603, 4603, 4603, -1, + 4604, 4604, 4604, -1, 4605, 4605, 4605, -1, + 4606, 4606, 4606, -1, 4607, 4607, 4607, -1, + 4608, 4608, 4608, -1, 4609, 4609, 4609, -1, + 4610, 4610, 4610, -1, 4611, 4611, 4611, -1, + 4612, 4612, 4612, -1, 4613, 4613, 4613, -1, + 4614, 4614, 4614, -1, 4615, 4615, 4615, -1, + 4616, 4616, 4616, -1, 4617, 4617, 4617, -1, + 4618, 4618, 4618, -1, 4619, 4619, 4619, -1, + 4620, 4620, 4620, -1, 4621, 4621, 4621, -1, + 4622, 4622, 4622, -1, 4623, 4623, 4623, -1, + 4624, 4624, 4624, -1, 4625, 4625, 4625, -1, + 4626, 4626, 4626, -1, 4627, 4627, 4627, -1, + 4628, 4628, 4628, -1, 4629, 4629, 4629, -1, + 4630, 4630, 4630, -1, 4631, 4631, 4631, -1, + 4632, 4632, 4632, -1, 4633, 4633, 4633, -1, + 4634, 4634, 4634, -1, 4635, 4635, 4635, -1, + 4636, 4636, 4636, -1, 4637, 4637, 4637, -1, + 4638, 4638, 4638, -1, 4639, 4639, 4639, -1, + 4640, 4640, 4640, -1, 4641, 4641, 4641, -1, + 4642, 4642, 4642, -1, 4643, 4643, 4643, -1, + 4644, 4644, 4644, -1, 4645, 4645, 4645, -1, + 4646, 4646, 4646, -1, 4647, 4647, 4647, -1, + 4648, 4648, 4648, -1, 4649, 4649, 4649, -1, + 4650, 4650, 4650, -1, 4651, 4651, 4651, -1, + 4652, 4652, 4652, -1, 4653, 4653, 4653, -1, + 4654, 4654, 4654, -1, 4655, 4655, 4655, -1, + 4656, 4656, 4656, -1, 4657, 4657, 4657, -1, + 4658, 4658, 4658, -1, 4659, 4659, 4659, -1, + 4660, 4660, 4660, -1, 4661, 4661, 4661, -1, + 4662, 4662, 4662, -1, 4663, 4663, 4663, -1, + 4664, 4664, 4664, -1, 4665, 4665, 4665, -1, + 4666, 4666, 4666, -1, 4667, 4667, 4667, -1, + 4668, 4668, 4668, -1, 4669, 4669, 4669, -1, + 4670, 4670, 4670, -1, 4671, 4671, 4671, -1, + 4672, 4672, 4672, -1, 4673, 4673, 4673, -1, + 4674, 4674, 4674, -1, 4675, 4675, 4675, -1, + 4676, 4676, 4676, -1, 4677, 4677, 4677, -1, + 4678, 4678, 4678, -1, 4679, 4679, 4679, -1, + 4680, 4680, 4680, -1, 4681, 4681, 4681, -1, + 4682, 4682, 4682, -1, 4683, 4683, 4683, -1, + 4684, 4684, 4684, -1, 4685, 4685, 4685, -1, + 4686, 4686, 4686, -1, 4687, 4687, 4687, -1, + 4688, 4688, 4688, -1, 4689, 4689, 4689, -1, + 4690, 4690, 4690, -1, 4691, 4691, 4691, -1, + 4692, 4692, 4692, -1, 4693, 4693, 4693, -1, + 4694, 4694, 4694, -1, 4695, 4695, 4695, -1, + 4696, 4696, 4696, -1, 4697, 4697, 4697, -1, + 4698, 4698, 4698, -1, 4699, 4699, 4699, -1, + 4700, 4700, 4700, -1, 4701, 4701, 4701, -1, + 4702, 4702, 4702, -1, 4703, 4703, 4703, -1, + 4704, 4704, 4704, -1, 4705, 4705, 4705, -1, + 4706, 4706, 4706, -1, 4707, 4707, 4707, -1, + 4708, 4708, 4708, -1, 4709, 4709, 4709, -1, + 4710, 4710, 4710, -1, 4711, 4711, 4711, -1, + 4712, 4712, 4712, -1, 4713, 4713, 4713, -1, + 4714, 4714, 4714, -1, 4715, 4715, 4715, -1, + 4716, 4716, 4716, -1, 4717, 4717, 4717, -1, + 4718, 4718, 4718, -1, 4719, 4719, 4719, -1, + 4720, 4720, 4720, -1, 4721, 4721, 4721, -1, + 4722, 4722, 4722, -1, 4723, 4723, 4723, -1, + 4724, 4724, 4724, -1, 4725, 4725, 4725, -1, + 4726, 4726, 4726, -1, 4727, 4727, 4727, -1, + 4728, 4728, 4728, -1, 4729, 4729, 4729, -1, + 4730, 4730, 4730, -1, 4731, 4731, 4731, -1, + 4732, 4732, 4732, -1, 4733, 4733, 4733, -1, + 4734, 4734, 4734, -1, 4735, 4735, 4735, -1, + 4736, 4736, 4736, -1, 4737, 4737, 4737, -1, + 4738, 4738, 4738, -1, 4739, 4739, 4739, -1, + 4740, 4740, 4740, -1, 4741, 4741, 4741, -1, + 4742, 4742, 4742, -1, 4743, 4743, 4743, -1, + 4744, 4744, 4744, -1, 4745, 4745, 4745, -1, + 4746, 4746, 4746, -1, 4747, 4747, 4747, -1, + 4748, 4748, 4748, -1, 4749, 4749, 4749, -1, + 4750, 4750, 4750, -1, 4751, 4751, 4751, -1, + 4752, 4752, 4752, -1, 4753, 4753, 4753, -1, + 4754, 4754, 4754, -1, 4755, 4755, 4755, -1, + 4756, 4756, 4756, -1, 4757, 4757, 4757, -1, + 4758, 4758, 4758, -1, 4759, 4759, 4759, -1, + 4760, 4760, 4760, -1, 4761, 4761, 4761, -1, + 4762, 4762, 4762, -1, 4763, 4763, 4763, -1, + 4764, 4764, 4764, -1, 4765, 4765, 4765, -1, + 4766, 4766, 4766, -1, 4767, 4767, 4767, -1, + 4768, 4768, 4768, -1, 4769, 4769, 4769, -1, + 4770, 4770, 4770, -1, 4771, 4771, 4771, -1, + 4772, 4772, 4772, -1, 4773, 4773, 4773, -1, + 4774, 4774, 4774, -1, 4775, 4775, 4775, -1, + 4776, 4776, 4776, -1, 4777, 4777, 4777, -1, + 4778, 4778, 4778, -1, 4779, 4779, 4779, -1, + 4780, 4780, 4780, -1, 4781, 4781, 4781, -1, + 4782, 4782, 4782, -1, 4783, 4783, 4783, -1, + 4784, 4784, 4784, -1, 4785, 4785, 4785, -1, + 4786, 4786, 4786, -1, 4787, 4787, 4787, -1, + 4788, 4788, 4788, -1, 4789, 4789, 4789, -1, + 4790, 4790, 4790, -1, 4791, 4791, 4791, -1, + 4792, 4792, 4792, -1, 4793, 4793, 4793, -1, + 4794, 4794, 4794, -1, 4795, 4795, 4795, -1, + 4796, 4796, 4796, -1, 4797, 4797, 4797, -1, + 4798, 4798, 4798, -1, 4799, 4799, 4799, -1, + 4800, 4800, 4800, -1, 4801, 4801, 4801, -1, + 4802, 4802, 4802, -1, 4803, 4803, 4803, -1, + 4804, 4804, 4804, -1, 4805, 4805, 4805, -1, + 4806, 4806, 4806, -1, 4807, 4807, 4807, -1, + 4808, 4808, 4808, -1, 4809, 4809, 4809, -1, + 4810, 4810, 4810, -1, 4811, 4811, 4811, -1, + 4812, 4812, 4812, -1, 4813, 4813, 4813, -1, + 4814, 4814, 4814, -1, 4815, 4815, 4815, -1, + 4816, 4816, 4816, -1, 4817, 4817, 4817, -1, + 4818, 4818, 4818, -1, 4819, 4819, 4819, -1, + 4820, 4820, 4820, -1, 4821, 4821, 4821, -1, + 4822, 4822, 4822, -1, 4823, 4823, 4823, -1, + 4824, 4824, 4824, -1, 4825, 4825, 4825, -1, + 4826, 4826, 4826, -1, 4827, 4827, 4827, -1, + 4828, 4828, 4828, -1, 4829, 4829, 4829, -1, + 4830, 4830, 4830, -1, 4831, 4831, 4831, -1, + 4832, 4832, 4832, -1, 4833, 4833, 4833, -1, + 4834, 4834, 4834, -1, 4835, 4835, 4835, -1, + 4836, 4836, 4836, -1, 4837, 4837, 4837, -1, + 4838, 4838, 4838, -1, 4839, 4839, 4839, -1, + 4840, 4840, 4840, -1, 4841, 4841, 4841, -1, + 4842, 4842, 4842, -1, 4843, 4843, 4843, -1, + 4844, 4844, 4844, -1, 4845, 4845, 4845, -1, + 4846, 4846, 4846, -1, 4847, 4847, 4847, -1, + 4848, 4848, 4848, -1, 4849, 4849, 4849, -1, + 4850, 4850, 4850, -1, 4851, 4851, 4851, -1, + 4852, 4852, 4852, -1, 4853, 4853, 4853, -1, + 4854, 4854, 4854, -1, 4855, 4855, 4855, -1, + 4856, 4856, 4856, -1, 4857, 4857, 4857, -1, + 4858, 4858, 4858, -1, 4859, 4859, 4859, -1, + 4860, 4860, 4860, -1, 4861, 4861, 4861, -1, + 4862, 4862, 4862, -1, 4863, 4863, 4863, -1, + 4864, 4864, 4864, -1, 4865, 4865, 4865, -1, + 4866, 4866, 4866, -1, 4867, 4867, 4867, -1, + 4868, 4868, 4868, -1, 4869, 4869, 4869, -1, + 4870, 4870, 4870, -1, 4871, 4871, 4871, -1, + 4872, 4872, 4872, -1, 4873, 4873, 4873, -1, + 4874, 4874, 4874, -1, 4875, 4875, 4875, -1, + 4876, 4876, 4876, -1, 4877, 4877, 4877, -1, + 4878, 4878, 4878, -1, 4879, 4879, 4879, -1, + 4880, 4880, 4880, -1, 4881, 4881, 4881, -1, + 4882, 4882, 4882, -1, 4883, 4883, 4883, -1, + 4884, 4884, 4884, -1, 4885, 4885, 4885, -1, + 4886, 4886, 4886, -1, 4887, 4887, 4887, -1, + 4888, 4888, 4888, -1, 4889, 4889, 4889, -1, + 4890, 4890, 4890, -1, 4891, 4891, 4891, -1, + 4892, 4892, 4892, -1, 4893, 4893, 4893, -1, + 4894, 4894, 4894, -1, 4895, 4895, 4895, -1, + 4896, 4896, 4896, -1, 4897, 4897, 4897, -1, + 4898, 4898, 4898, -1, 4899, 4899, 4899, -1, + 4900, 4900, 4900, -1, 4901, 4901, 4901, -1, + 4902, 4902, 4902, -1, 4903, 4903, 4903, -1, + 4904, 4904, 4904, -1, 4905, 4905, 4905, -1, + 4906, 4906, 4906, -1, 4907, 4907, 4907, -1, + 4908, 4908, 4908, -1, 4909, 4909, 4909, -1, + 4910, 4910, 4910, -1, 4911, 4911, 4911, -1, + 4912, 4912, 4912, -1, 4913, 4913, 4913, -1, + 4914, 4914, 4914, -1, 4915, 4915, 4915, -1, + 4916, 4916, 4916, -1, 4917, 4917, 4917, -1, + 4918, 4918, 4918, -1, 4919, 4919, 4919, -1, + 4920, 4920, 4920, -1, 4921, 4921, 4921, -1, + 4922, 4922, 4922, -1, 4923, 4923, 4923, -1, + 4924, 4924, 4924, -1, 4925, 4925, 4925, -1, + 4926, 4926, 4926, -1, 4927, 4927, 4927, -1, + 4928, 4928, 4928, -1, 4929, 4929, 4929, -1, + 4930, 4930, 4930, -1, 4931, 4931, 4931, -1, + 4932, 4932, 4932, -1, 4933, 4933, 4933, -1, + 4934, 4934, 4934, -1, 4935, 4935, 4935, -1, + 4936, 4936, 4936, -1, 4937, 4937, 4937, -1, + 4938, 4938, 4938, -1, 4939, 4939, 4939, -1, + 4940, 4940, 4940, -1, 4941, 4941, 4941, -1, + 4942, 4942, 4942, -1, 4943, 4943, 4943, -1, + 4944, 4944, 4944, -1, 4945, 4945, 4945, -1, + 4946, 4946, 4946, -1, 4947, 4947, 4947, -1, + 4948, 4948, 4948, -1, 4949, 4949, 4949, -1, + 4950, 4950, 4950, -1, 4951, 4951, 4951, -1, + 4952, 4952, 4952, -1, 4953, 4953, 4953, -1, + 4954, 4954, 4954, -1, 4955, 4955, 4955, -1, + 4956, 4956, 4956, -1, 4957, 4957, 4957, -1, + 4958, 4958, 4958, -1, 4959, 4959, 4959, -1, + 4960, 4960, 4960, -1, 4961, 4961, 4961, -1, + 4962, 4962, 4962, -1, 4963, 4963, 4963, -1, + 4964, 4964, 4964, -1, 4965, 4965, 4965, -1, + 4966, 4966, 4966, -1, 4967, 4967, 4967, -1, + 4968, 4968, 4968, -1, 4969, 4969, 4969, -1, + 4970, 4970, 4970, -1, 4971, 4971, 4971, -1, + 4972, 4972, 4972, -1, 4973, 4973, 4973, -1, + 4974, 4974, 4974, -1, 4975, 4975, 4975, -1, + 4976, 4976, 4976, -1, 4977, 4977, 4977, -1, + 4978, 4978, 4978, -1, 4979, 4979, 4979, -1, + 4980, 4980, 4980, -1, 4981, 4981, 4981, -1, + 4982, 4982, 4982, -1, 4983, 4983, 4983, -1, + 4984, 4984, 4984, -1, 4985, 4985, 4985, -1, + 4986, 4986, 4986, -1, 4987, 4987, 4987, -1, + 4988, 4988, 4988, -1, 4989, 4989, 4989, -1, + 4990, 4990, 4990, -1, 4991, 4991, 4991, -1, + 4992, 4992, 4992, -1, 4993, 4993, 4993, -1, + 4994, 4994, 4994, -1, 4995, 4995, 4995, -1, + 4996, 4996, 4996, -1, 4997, 4997, 4997, -1, + 4998, 4998, 4998, -1, 4999, 4999, 4999, -1, + 5000, 5000, 5000, -1, 5001, 5001, 5001, -1, + 5002, 5002, 5002, -1, 5003, 5003, 5003, -1, + 5004, 5004, 5004, -1, 5005, 5005, 5005, -1, + 5006, 5006, 5006, -1, 5007, 5007, 5007, -1, + 5008, 5008, 5008, -1, 5009, 5009, 5009, -1, + 5010, 5010, 5010, -1, 5011, 5011, 5011, -1, + 5012, 5012, 5012, -1, 5013, 5013, 5013, -1, + 5014, 5014, 5014, -1, 5015, 5015, 5015, -1, + 5016, 5016, 5016, -1, 5017, 5017, 5017, -1, + 5018, 5018, 5018, -1, 5019, 5019, 5019, -1, + 5020, 5020, 5020, -1, 5021, 5021, 5021, -1, + 5022, 5022, 5022, -1, 5023, 5023, 5023, -1, + 5024, 5024, 5024, -1, 5025, 5025, 5025, -1, + 5026, 5026, 5026, -1, 5027, 5027, 5027, -1, + 5028, 5028, 5028, -1, 5029, 5029, 5029, -1, + 5030, 5030, 5030, -1, 5031, 5031, 5031, -1, + 5032, 5032, 5032, -1, 5033, 5033, 5033, -1, + 5034, 5034, 5034, -1, 5035, 5035, 5035, -1, + 5036, 5036, 5036, -1, 5037, 5037, 5037, -1, + 5038, 5038, 5038, -1, 5039, 5039, 5039, -1, + 5040, 5040, 5040, -1, 5041, 5041, 5041, -1, + 5042, 5042, 5042, -1, 5043, 5043, 5043, -1, + 5044, 5044, 5044, -1, 5045, 5045, 5045, -1, + 5046, 5046, 5046, -1, 5047, 5047, 5047, -1, + 5048, 5048, 5048, -1, 5049, 5049, 5049, -1, + 5050, 5050, 5050, -1, 5051, 5051, 5051, -1, + 5052, 5052, 5052, -1, 5053, 5053, 5053, -1, + 5054, 5054, 5054, -1, 5055, 5055, 5055, -1, + 5056, 5056, 5056, -1, 5057, 5057, 5057, -1, + 5058, 5058, 5058, -1, 5059, 5059, 5059, -1, + 5060, 5060, 5060, -1, 5061, 5061, 5061, -1, + 5062, 5062, 5062, -1, 5063, 5063, 5063, -1, + 5064, 5064, 5064, -1, 5065, 5065, 5065, -1, + 5066, 5066, 5066, -1, 5067, 5067, 5067, -1, + 5068, 5068, 5068, -1, 5069, 5069, 5069, -1, + 5070, 5070, 5070, -1, 5071, 5071, 5071, -1, + 5072, 5072, 5072, -1, 5073, 5073, 5073, -1, + 5074, 5074, 5074, -1, 5075, 5075, 5075, -1, + 5076, 5076, 5076, -1, 5077, 5077, 5077, -1, + 5078, 5078, 5078, -1, 5079, 5079, 5079, -1, + 5080, 5080, 5080, -1, 5081, 5081, 5081, -1, + 5082, 5082, 5082, -1, 5083, 5083, 5083, -1, + 5084, 5084, 5084, -1, 5085, 5085, 5085, -1, + 5086, 5086, 5086, -1, 5087, 5087, 5087, -1, + 5088, 5088, 5088, -1, 5089, 5089, 5089, -1, + 5090, 5090, 5090, -1, 5091, 5091, 5091, -1, + 5092, 5092, 5092, -1, 5093, 5093, 5093, -1, + 5094, 5094, 5094, -1, 5095, 5095, 5095, -1, + 5096, 5096, 5096, -1, 5097, 5097, 5097, -1, + 5098, 5098, 5098, -1, 5099, 5099, 5099, -1, + 5100, 5100, 5100, -1, 5101, 5101, 5101, -1, + 5102, 5102, 5102, -1, 5103, 5103, 5103, -1, + 5104, 5104, 5104, -1, 5105, 5105, 5105, -1, + 5106, 5106, 5106, -1, 5107, 5107, 5107, -1, + 5108, 5108, 5108, -1, 5109, 5109, 5109, -1, + 5110, 5110, 5110, -1, 5111, 5111, 5111, -1, + 5112, 5112, 5112, -1, 5113, 5113, 5113, -1, + 5114, 5114, 5114, -1, 5115, 5115, 5115, -1, + 5116, 5116, 5116, -1, 5117, 5117, 5117, -1, + 5118, 5118, 5118, -1, 5119, 5119, 5119, -1, + 5120, 5120, 5120, -1, 5121, 5121, 5121, -1, + 5122, 5122, 5122, -1, 5123, 5123, 5123, -1, + 5124, 5124, 5124, -1, 5125, 5125, 5125, -1, + 5126, 5126, 5126, -1, 5127, 5127, 5127, -1, + 5128, 5128, 5128, -1, 5129, 5129, 5129, -1, + 5130, 5130, 5130, -1, 5131, 5131, 5131, -1, + 5132, 5132, 5132, -1, 5133, 5133, 5133, -1, + 5134, 5134, 5134, -1, 5135, 5135, 5135, -1, + 5136, 5136, 5136, -1, 5137, 5137, 5137, -1, + 5138, 5138, 5138, -1, 5139, 5139, 5139, -1, + 5140, 5140, 5140, -1, 5141, 5141, 5141, -1, + 5142, 5142, 5142, -1, 5143, 5143, 5143, -1, + 5144, 5144, 5144, -1, 5145, 5145, 5145, -1, + 5146, 5146, 5146, -1, 5147, 5147, 5147, -1, + 5148, 5148, 5148, -1, 5149, 5149, 5149, -1, + 5150, 5150, 5150, -1, 5151, 5151, 5151, -1, + 5152, 5152, 5152, -1, 5153, 5153, 5153, -1, + 5154, 5154, 5154, -1, 5155, 5155, 5155, -1, + 5156, 5156, 5156, -1, 5157, 5157, 5157, -1, + 5158, 5158, 5158, -1, 5159, 5159, 5159, -1, + 5160, 5160, 5160, -1, 5161, 5161, 5161, -1, + 5162, 5162, 5162, -1, 5163, 5163, 5163, -1, + 5164, 5164, 5164, -1, 5165, 5165, 5165, -1, + 5166, 5166, 5166, -1, 5167, 5167, 5167, -1, + 5168, 5168, 5168, -1, 5169, 5169, 5169, -1, + 5170, 5170, 5170, -1, 5171, 5171, 5171, -1, + 5172, 5172, 5172, -1, 5173, 5173, 5173, -1, + 5174, 5174, 5174, -1, 5175, 5175, 5175, -1, + 5176, 5176, 5176, -1, 5177, 5177, 5177, -1, + 5178, 5178, 5178, -1, 5179, 5179, 5179, -1, + 5180, 5180, 5180, -1, 5181, 5181, 5181, -1, + 5182, 5182, 5182, -1, 5183, 5183, 5183, -1, + 5184, 5184, 5184, -1, 5185, 5185, 5185, -1, + 5186, 5186, 5186, -1, 5187, 5187, 5187, -1, + 5188, 5188, 5188, -1, 5189, 5189, 5189, -1, + 5190, 5190, 5190, -1, 5191, 5191, 5191, -1, + 5192, 5192, 5192, -1, 5193, 5193, 5193, -1, + 5194, 5194, 5194, -1, 5195, 5195, 5195, -1, + 5196, 5196, 5196, -1, 5197, 5197, 5197, -1, + 5198, 5198, 5198, -1, 5199, 5199, 5199, -1, + 5200, 5200, 5200, -1, 5201, 5201, 5201, -1, + 5202, 5202, 5202, -1, 5203, 5203, 5203, -1, + 5204, 5204, 5204, -1, 5205, 5205, 5205, -1, + 5206, 5206, 5206, -1, 5207, 5207, 5207, -1, + 5208, 5208, 5208, -1, 5209, 5209, 5209, -1, + 5210, 5210, 5210, -1, 5211, 5211, 5211, -1, + 5212, 5212, 5212, -1, 5213, 5213, 5213, -1, + 5214, 5214, 5214, -1, 5215, 5215, 5215, -1, + 5216, 5216, 5216, -1, 5217, 5217, 5217, -1, + 5218, 5218, 5218, -1, 5219, 5219, 5219, -1, + 5220, 5220, 5220, -1, 5221, 5221, 5221, -1, + 5222, 5222, 5222, -1, 5223, 5223, 5223, -1, + 5224, 5224, 5224, -1, 5225, 5225, 5225, -1, + 5226, 5226, 5226, -1, 5227, 5227, 5227, -1, + 5228, 5228, 5228, -1, 5229, 5229, 5229, -1, + 5230, 5230, 5230, -1, 5231, 5231, 5231, -1, + 5232, 5232, 5232, -1, 5233, 5233, 5233, -1, + 5234, 5234, 5234, -1, 5235, 5235, 5235, -1, + 5236, 5236, 5236, -1, 5237, 5237, 5237, -1, + 5238, 5238, 5238, -1, 5239, 5239, 5239, -1, + 5240, 5240, 5240, -1, 5241, 5241, 5241, -1, + 5242, 5242, 5242, -1, 5243, 5243, 5243, -1, + 5244, 5244, 5244, -1, 5245, 5245, 5245, -1, + 5246, 5246, 5246, -1, 5247, 5247, 5247, -1, + 5248, 5248, 5248, -1, 5249, 5249, 5249, -1, + 5250, 5250, 5250, -1, 5251, 5251, 5251, -1, + 5252, 5252, 5252, -1, 5253, 5253, 5253, -1, + 5254, 5254, 5254, -1, 5255, 5255, 5255, -1, + 5256, 5256, 5256, -1, 5257, 5257, 5257, -1, + 5258, 5258, 5258, -1, 5259, 5259, 5259, -1, + 5260, 5260, 5260, -1, 5261, 5261, 5261, -1, + 5262, 5262, 5262, -1, 5263, 5263, 5263, -1, + 5264, 5264, 5264, -1, 5265, 5265, 5265, -1, + 5266, 5266, 5266, -1, 5267, 5267, 5267, -1, + 5268, 5268, 5268, -1, 5269, 5269, 5269, -1, + 5270, 5270, 5270, -1, 5271, 5271, 5271, -1, + 5272, 5272, 5272, -1, 5273, 5273, 5273, -1, + 5274, 5274, 5274, -1, 5275, 5275, 5275, -1, + 5276, 5276, 5276, -1, 5277, 5277, 5277, -1, + 5278, 5278, 5278, -1, 5279, 5279, 5279, -1, + 5280, 5280, 5280, -1, 5281, 5281, 5281, -1, + 5282, 5282, 5282, -1, 5283, 5283, 5283, -1, + 5284, 5284, 5284, -1, 5285, 5285, 5285, -1, + 5286, 5286, 5286, -1, 5287, 5287, 5287, -1, + 5288, 5288, 5288, -1, 5289, 5289, 5289, -1, + 5290, 5290, 5290, -1, 5291, 5291, 5291, -1, + 5292, 5292, 5292, -1, 5293, 5293, 5293, -1, + 5294, 5294, 5294, -1, 5295, 5295, 5295, -1, + 5296, 5296, 5296, -1, 5297, 5297, 5297, -1, + 5298, 5298, 5298, -1, 5299, 5299, 5299, -1, + 5300, 5300, 5300, -1, 5301, 5301, 5301, -1, + 5302, 5302, 5302, -1, 5303, 5303, 5303, -1, + 5304, 5304, 5304, -1, 5305, 5305, 5305, -1, + 5306, 5306, 5306, -1, 5307, 5307, 5307, -1, + 5308, 5308, 5308, -1, 5309, 5309, 5309, -1, + 5310, 5310, 5310, -1, 5311, 5311, 5311, -1, + 5312, 5312, 5312, -1, 5313, 5313, 5313, -1, + 5314, 5314, 5314, -1, 5315, 5315, 5315, -1, + 5316, 5316, 5316, -1, 5317, 5317, 5317, -1, + 5318, 5318, 5318, -1, 5319, 5319, 5319, -1, + 5320, 5320, 5320, -1, 5321, 5321, 5321, -1, + 5322, 5322, 5322, -1, 5323, 5323, 5323, -1, + 5324, 5324, 5324, -1, 5325, 5325, 5325, -1, + 5326, 5326, 5326, -1, 5327, 5327, 5327, -1, + 5328, 5328, 5328, -1, 5329, 5329, 5329, -1, + 5330, 5330, 5330, -1, 5331, 5331, 5331, -1, + 5332, 5332, 5332, -1, 5333, 5333, 5333, -1, + 5334, 5334, 5334, -1, 5335, 5335, 5335, -1, + 5336, 5336, 5336, -1, 5337, 5337, 5337, -1, + 5338, 5338, 5338, -1, 5339, 5339, 5339, -1, + 5340, 5340, 5340, -1, 5341, 5341, 5341, -1, + 5342, 5342, 5342, -1, 5343, 5343, 5343, -1, + 5344, 5344, 5344, -1, 5345, 5345, 5345, -1, + 5346, 5346, 5346, -1, 5347, 5347, 5347, -1, + 5348, 5348, 5348, -1, 5349, 5349, 5349, -1, + 5350, 5350, 5350, -1, 5351, 5351, 5351, -1, + 5352, 5352, 5352, -1, 5353, 5353, 5353, -1, + 5354, 5354, 5354, -1, 5355, 5355, 5355, -1, + 5356, 5356, 5356, -1, 5357, 5357, 5357, -1, + 5358, 5358, 5358, -1, 5359, 5359, 5359, -1, + 5360, 5360, 5360, -1, 5361, 5361, 5361, -1, + 5362, 5362, 5362, -1, 5363, 5363, 5363, -1, + 5364, 5364, 5364, -1, 5365, 5365, 5365, -1, + 5366, 5366, 5366, -1, 5367, 5367, 5367, -1, + 5368, 5368, 5368, -1, 5369, 5369, 5369, -1, + 5370, 5370, 5370, -1, 5371, 5371, 5371, -1, + 5372, 5372, 5372, -1, 5373, 5373, 5373, -1, + 5374, 5374, 5374, -1, 5375, 5375, 5375, -1, + 5376, 5376, 5376, -1, 5377, 5377, 5377, -1, + 5378, 5378, 5378, -1, 5379, 5379, 5379, -1, + 5380, 5380, 5380, -1, 5381, 5381, 5381, -1, + 5382, 5382, 5382, -1, 5383, 5383, 5383, -1, + 5384, 5384, 5384, -1, 5385, 5385, 5385, -1, + 5386, 5386, 5386, -1, 5387, 5387, 5387, -1, + 5388, 5388, 5388, -1, 5389, 5389, 5389, -1, + 5390, 5390, 5390, -1, 5391, 5391, 5391, -1, + 5392, 5392, 5392, -1, 5393, 5393, 5393, -1, + 5394, 5394, 5394, -1, 5395, 5395, 5395, -1, + 5396, 5396, 5396, -1, 5397, 5397, 5397, -1, + 5398, 5398, 5398, -1, 5399, 5399, 5399, -1, + 5400, 5400, 5400, -1, 5401, 5401, 5401, -1, + 5402, 5402, 5402, -1, 5403, 5403, 5403, -1, + 5404, 5404, 5404, -1, 5405, 5405, 5405, -1, + 5406, 5406, 5406, -1, 5407, 5407, 5407, -1, + 5408, 5408, 5408, -1, 5409, 5409, 5409, -1, + 5410, 5410, 5410, -1, 5411, 5411, 5411, -1, + 5412, 5412, 5412, -1, 5413, 5413, 5413, -1, + 5414, 5414, 5414, -1, 5415, 5415, 5415, -1, + 5416, 5416, 5416, -1, 5417, 5417, 5417, -1, + 5418, 5418, 5418, -1, 5419, 5419, 5419, -1, + 5420, 5420, 5420, -1, 5421, 5421, 5421, -1, + 5422, 5422, 5422, -1, 5423, 5423, 5423, -1, + 5424, 5424, 5424, -1, 5425, 5425, 5425, -1, + 5426, 5426, 5426, -1, 5427, 5427, 5427, -1, + 5428, 5428, 5428, -1, 5429, 5429, 5429, -1, + 5430, 5430, 5430, -1, 5431, 5431, 5431, -1, + 5432, 5432, 5432, -1, 5433, 5433, 5433, -1, + 5434, 5434, 5434, -1, 5435, 5435, 5435, -1, + 5436, 5436, 5436, -1, 5437, 5437, 5437, -1, + 5438, 5438, 5438, -1, 5439, 5439, 5439, -1, + 5440, 5440, 5440, -1, 5441, 5441, 5441, -1, + 5442, 5442, 5442, -1, 5443, 5443, 5443, -1, + 5444, 5444, 5444, -1, 5445, 5445, 5445, -1, + 5446, 5446, 5446, -1, 5447, 5447, 5447, -1, + 5448, 5448, 5448, -1, 5449, 5449, 5449, -1, + 5450, 5450, 5450, -1, 5451, 5451, 5451, -1, + 5452, 5452, 5452, -1, 5453, 5453, 5453, -1, + 5454, 5454, 5454, -1, 5455, 5455, 5455, -1, + 5456, 5456, 5456, -1, 5457, 5457, 5457, -1, + 5458, 5458, 5458, -1, 5459, 5459, 5459, -1, + 5460, 5460, 5460, -1, 5461, 5461, 5461, -1, + 5462, 5462, 5462, -1, 5463, 5463, 5463, -1, + 5464, 5464, 5464, -1, 5465, 5465, 5465, -1, + 5466, 5466, 5466, -1, 5467, 5467, 5467, -1, + 5468, 5468, 5468, -1, 5469, 5469, 5469, -1, + 5470, 5470, 5470, -1, 5471, 5471, 5471, -1, + 5472, 5472, 5472, -1, 5473, 5473, 5473, -1, + 5474, 5474, 5474, -1, 5475, 5475, 5475, -1, + 5476, 5476, 5476, -1, 5477, 5477, 5477, -1, + 5478, 5478, 5478, -1, 5479, 5479, 5479, -1, + 5480, 5480, 5480, -1, 5481, 5481, 5481, -1, + 5482, 5482, 5482, -1, 5483, 5483, 5483, -1, + 5484, 5484, 5484, -1, 5485, 5485, 5485, -1, + 5486, 5486, 5486, -1, 5487, 5487, 5487, -1, + 5488, 5488, 5488, -1, 5489, 5489, 5489, -1, + 5490, 5490, 5490, -1, 5491, 5491, 5491, -1, + 5492, 5492, 5492, -1, 5493, 5493, 5493, -1, + 5494, 5494, 5494, -1, 5495, 5495, 5495, -1, + 5496, 5496, 5496, -1, 5497, 5497, 5497, -1, + 5498, 5498, 5498, -1, 5499, 5499, 5499, -1, + 5500, 5500, 5500, -1, 5501, 5501, 5501, -1, + 5502, 5502, 5502, -1, 5502, 5502, 5502, -1, + 5503, 5503, 5503, -1, 5503, 5503, 5503, -1, + 5504, 5504, 5504, -1, 5504, 5504, 5504, -1, + 5505, 5505, 5505, -1, 5505, 5505, 5505, -1, + 5506, 5506, 5506, -1, 5506, 5506, 5506, -1, + 5507, 5507, 5507, -1, 5507, 5507, 5507, -1, + 5508, 5508, 5508, -1, 5508, 5508, 5508, -1, + 5509, 5509, 5509, -1, 5509, 5509, 5509, -1, + 5510, 5510, 5510, -1, 5510, 5510, 5510, -1, + 5511, 5511, 5511, -1, 5511, 5511, 5511, -1, + 5512, 5512, 5512, -1, 5512, 5512, 5512, -1, + 5513, 5513, 5513, -1, 5513, 5513, 5513, -1, + 5514, 5514, 5514, -1, 5514, 5514, 5514, -1, + 5515, 5515, 5515, -1, 5515, 5515, 5515, -1, + 5516, 5516, 5516, -1, 5516, 5516, 5516, -1, + 5517, 5517, 5517, -1, 5517, 5517, 5517, -1, + 5518, 5518, 5518, -1, 5518, 5518, 5518, -1, + 5519, 5519, 5519, -1, 5519, 5519, 5519, -1, + 5520, 5520, 5520, -1, 5520, 5520, 5520, -1, + 5521, 5521, 5521, -1, 5521, 5521, 5521, -1, + 5522, 5522, 5522, -1, 5522, 5522, 5522, -1, + 5523, 5523, 5523, -1, 5523, 5523, 5523, -1, + 5524, 5524, 5524, -1, 5524, 5524, 5524, -1, + 5525, 5525, 5525, -1, 5525, 5525, 5525, -1, + 5526, 5526, 5526, -1, 5526, 5526, 5526, -1, + 5527, 5527, 5527, -1, 5527, 5527, 5527, -1, + 5528, 5528, 5528, -1, 5528, 5528, 5528, -1, + 5529, 5529, 5529, -1, 5529, 5529, 5529, -1, + 5530, 5530, 5530, -1, 5530, 5530, 5530, -1, + 5531, 5531, 5531, -1, 5531, 5531, 5531, -1, + 5532, 5532, 5532, -1, 5532, 5532, 5532, -1, + 5533, 5533, 5533, -1, 5533, 5533, 5533, -1, + 5534, 5534, 5534, -1, 5534, 5534, 5534, -1, + 5535, 5535, 5535, -1, 5535, 5535, 5535, -1, + 5536, 5536, 5536, -1, 5536, 5536, 5536, -1, + 5537, 5537, 5537, -1, 5537, 5537, 5537, -1, + 5538, 5538, 5538, -1, 5538, 5538, 5538, -1, + 5539, 5539, 5539, -1, 5539, 5539, 5539, -1, + 5540, 5540, 5540, -1, 5540, 5540, 5540, -1, + 5541, 5541, 5541, -1, 5541, 5541, 5541, -1, + 5542, 5542, 5542, -1, 5542, 5542, 5542, -1, + 5543, 5543, 5543, -1, 5543, 5543, 5543, -1, + 5544, 5544, 5544, -1, 5544, 5544, 5544, -1, + 5545, 5545, 5545, -1, 5545, 5545, 5545, -1, + 5546, 5546, 5546, -1, 5546, 5546, 5546, -1, + 5547, 5547, 5547, -1, 5547, 5547, 5547, -1, + 5548, 5548, 5548, -1, 5548, 5548, 5548, -1, + 5549, 5549, 5549, -1, 5549, 5549, 5549, -1, + 5550, 5550, 5550, -1, 5550, 5550, 5550, -1, + 5551, 5551, 5551, -1, 5551, 5551, 5551, -1, + 5552, 5552, 5552, -1, 5552, 5552, 5552, -1, + 5553, 5553, 5553, -1, 5553, 5553, 5553, -1, + 5554, 5554, 5554, -1, 5554, 5554, 5554, -1, + 5555, 5555, 5555, -1, 5555, 5555, 5555, -1, + 5556, 5556, 5556, -1, 5556, 5556, 5556, -1, + 5557, 5557, 5557, -1, 5557, 5557, 5557, -1, + 5558, 5558, 5558, -1, 5558, 5558, 5558, -1, + 5559, 5559, 5559, -1, 5559, 5559, 5559, -1, + 5560, 5560, 5560, -1, 5560, 5560, 5560, -1, + 5561, 5561, 5561, -1, 5561, 5561, 5561, -1, + 5562, 5562, 5562, -1, 5562, 5562, 5562, -1, + 5563, 5563, 5563, -1, 5563, 5563, 5563, -1, + 5564, 5564, 5564, -1, 5564, 5564, 5564, -1, + 5565, 5565, 5565, -1, 5565, 5565, 5565, -1, + 5566, 5566, 5566, -1, 5566, 5566, 5566, -1, + 5567, 5567, 5567, -1, 5567, 5567, 5567, -1, + 5568, 5568, 5568, -1, 5568, 5568, 5568, -1, + 5569, 5569, 5569, -1, 5569, 5569, 5569, -1, + 5570, 5570, 5570, -1, 5570, 5570, 5570, -1, + 5571, 5571, 5571, -1, 5571, 5571, 5571, -1, + 5572, 5572, 5572, -1, 5572, 5572, 5572, -1, + 5573, 5573, 5573, -1, 5573, 5573, 5573, -1, + 5574, 5574, 5574, -1, 5574, 5574, 5574, -1, + 5575, 5575, 5575, -1, 5575, 5575, 5575, -1, + 5576, 5576, 5576, -1, 5576, 5576, 5576, -1, + 5577, 5577, 5577, -1, 5577, 5577, 5577, -1, + 5578, 5578, 5578, -1, 5578, 5578, 5578, -1, + 5579, 5579, 5579, -1, 5579, 5579, 5579, -1, + 5580, 5580, 5580, -1, 5580, 5580, 5580, -1, + 5581, 5581, 5581, -1, 5581, 5581, 5581, -1, + 5582, 5582, 5582, -1, 5582, 5582, 5582, -1, + 5583, 5583, 5583, -1, 5583, 5583, 5583, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5585, 5585, 5585, -1, 5585, 5585, 5585, -1, + 5586, 5586, 5586, -1, 5586, 5586, 5586, -1, + 5587, 5587, 5587, -1, 5587, 5587, 5587, -1, + 5588, 5588, 5588, -1, 5588, 5588, 5588, -1, + 5589, 5589, 5589, -1, 5589, 5589, 5589, -1, + 5590, 5590, 5590, -1, 5590, 5590, 5590, -1, + 5591, 5591, 5591, -1, 5591, 5591, 5591, -1, + 5592, 5592, 5592, -1, 5592, 5592, 5592, -1, + 5593, 5593, 5593, -1, 5593, 5593, 5593, -1, + 5594, 5594, 5594, -1, 5594, 5594, 5594, -1, + 5595, 5595, 5595, -1, 5595, 5595, 5595, -1, + 5596, 5596, 5596, -1, 5596, 5596, 5596, -1, + 5597, 5597, 5597, -1, 5597, 5597, 5597, -1, + 5598, 5598, 5598, -1, 5598, 5598, 5598, -1, + 5599, 5599, 5599, -1, 5599, 5599, 5599, -1, + 5600, 5600, 5600, -1, 5600, 5600, 5600, -1, + 5601, 5601, 5601, -1, 5601, 5601, 5601, -1, + 5602, 5602, 5602, -1, 5602, 5602, 5602, -1, + 5603, 5603, 5603, -1, 5603, 5603, 5603, -1, + 5604, 5604, 5604, -1, 5604, 5604, 5604, -1, + 5605, 5605, 5605, -1, 5605, 5605, 5605, -1, + 5606, 5606, 5606, -1, 5606, 5606, 5606, -1, + 5607, 5607, 5607, -1, 5607, 5607, 5607, -1, + 5608, 5608, 5608, -1, 5608, 5608, 5608, -1, + 5609, 5609, 5609, -1, 5609, 5609, 5609, -1, + 5610, 5610, 5610, -1, 5610, 5610, 5610, -1, + 5611, 5611, 5611, -1, 5611, 5611, 5611, -1, + 5612, 5612, 5612, -1, 5612, 5612, 5612, -1, + 5613, 5613, 5613, -1, 5613, 5613, 5613, -1, + 5614, 5614, 5614, -1, 5614, 5614, 5614, -1, + 5615, 5615, 5615, -1, 5615, 5615, 5615, -1, + 5616, 5616, 5616, -1, 5616, 5616, 5616, -1, + 5617, 5617, 5617, -1, 5617, 5617, 5617, -1, + 5618, 5618, 5618, -1, 5618, 5618, 5618, -1, + 5619, 5619, 5619, -1, 5619, 5619, 5619, -1, + 5620, 5620, 5620, -1, 5620, 5620, 5620, -1, + 5621, 5621, 5621, -1, 5621, 5621, 5621, -1, + 5622, 5622, 5622, -1, 5622, 5622, 5622, -1, + 5623, 5623, 5623, -1, 5623, 5623, 5623, -1, + 5624, 5624, 5624, -1, 5624, 5624, 5624, -1, + 5625, 5625, 5625, -1, 5625, 5625, 5625, -1, + 5626, 5626, 5626, -1, 5626, 5626, 5626, -1, + 5627, 5627, 5627, -1, 5627, 5627, 5627, -1, + 5628, 5628, 5628, -1, 5628, 5628, 5628, -1, + 5629, 5629, 5629, -1, 5629, 5629, 5629, -1, + 5630, 5630, 5630, -1, 5630, 5630, 5630, -1, + 5631, 5631, 5631, -1, 5631, 5631, 5631, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5632, 5632, 5632, -1, + 5632, 5632, 5632, -1, 5633, 5633, 5633, -1, + 5633, 5633, 5633, -1, 5634, 5634, 5634, -1, + 5634, 5634, 5634, -1, 5635, 5635, 5635, -1, + 5635, 5635, 5635, -1, 5636, 5636, 5636, -1, + 5636, 5636, 5636, -1, 5637, 5637, 5637, -1, + 5637, 5637, 5637, -1, 5638, 5638, 5638, -1, + 5638, 5638, 5638, -1, 5639, 5639, 5639, -1, + 5639, 5639, 5639, -1, 5640, 5640, 5640, -1, + 5640, 5640, 5640, -1, 5641, 5641, 5641, -1, + 5641, 5641, 5641, -1, 5642, 5642, 5642, -1, + 5642, 5642, 5642, -1, 5643, 5643, 5643, -1, + 5643, 5643, 5643, -1, 5644, 5644, 5644, -1, + 5644, 5644, 5644, -1, 5645, 5645, 5645, -1, + 5645, 5645, 5645, -1, 5646, 5646, 5646, -1, + 5646, 5646, 5646, -1, 5647, 5647, 5647, -1, + 5647, 5647, 5647, -1, 5648, 5648, 5648, -1, + 5648, 5648, 5648, -1, 5649, 5649, 5649, -1, + 5649, 5649, 5649, -1, 5650, 5650, 5650, -1, + 5650, 5650, 5650, -1, 5651, 5651, 5651, -1, + 5651, 5651, 5651, -1, 5652, 5652, 5652, -1, + 5652, 5652, 5652, -1, 5653, 5653, 5653, -1, + 5653, 5653, 5653, -1, 5654, 5654, 5654, -1, + 5654, 5654, 5654, -1, 5655, 5655, 5655, -1, + 5655, 5655, 5655, -1, 5656, 5656, 5656, -1, + 5656, 5656, 5656, -1, 5657, 5657, 5657, -1, + 5657, 5657, 5657, -1, 5658, 5658, 5658, -1, + 5658, 5658, 5658, -1, 5659, 5659, 5659, -1, + 5659, 5659, 5659, -1, 5660, 5660, 5660, -1, + 5660, 5660, 5660, -1, 5661, 5661, 5661, -1, + 5661, 5661, 5661, -1, 5662, 5662, 5662, -1, + 5662, 5662, 5662, -1, 5663, 5663, 5663, -1, + 5663, 5663, 5663, -1, 5664, 5664, 5664, -1, + 5664, 5664, 5664, -1, 5665, 5665, 5665, -1, + 5665, 5665, 5665, -1, 5666, 5666, 5666, -1, + 5666, 5666, 5666, -1, 5667, 5667, 5667, -1, + 5667, 5667, 5667, -1, 5668, 5668, 5668, -1, + 5668, 5668, 5668, -1, 5669, 5669, 5669, -1, + 5669, 5669, 5669, -1, 5670, 5670, 5670, -1, + 5670, 5670, 5670, -1, 5671, 5671, 5671, -1, + 5671, 5671, 5671, -1, 5672, 5672, 5672, -1, + 5672, 5672, 5672, -1, 5673, 5673, 5673, -1, + 5673, 5673, 5673, -1, 5674, 5674, 5674, -1, + 5674, 5674, 5674, -1, 5675, 5675, 5675, -1, + 5675, 5675, 5675, -1, 5676, 5676, 5676, -1, + 5676, 5676, 5676, -1, 5677, 5677, 5677, -1, + 5677, 5677, 5677, -1, 5678, 5678, 5678, -1, + 5678, 5678, 5678, -1, 5679, 5679, 5679, -1, + 5679, 5679, 5679, -1, 5680, 5680, 5680, -1, + 5680, 5680, 5680, -1, 5681, 5681, 5681, -1, + 5681, 5681, 5681, -1, 5682, 5682, 5682, -1, + 5682, 5682, 5682, -1, 5683, 5683, 5683, -1, + 5683, 5683, 5683, -1, 5684, 5684, 5684, -1, + 5684, 5684, 5684, -1, 5685, 5685, 5685, -1, + 5685, 5685, 5685, -1, 5686, 5686, 5686, -1, + 5686, 5686, 5686, -1, 5687, 5687, 5687, -1, + 5687, 5687, 5687, -1, 5688, 5688, 5688, -1, + 5688, 5688, 5688, -1, 5689, 5689, 5689, -1, + 5689, 5689, 5689, -1, 5690, 5690, 5690, -1, + 5690, 5690, 5690, -1, 5691, 5691, 5691, -1, + 5691, 5691, 5691, -1, 5692, 5692, 5692, -1, + 5692, 5692, 5692, -1, 5693, 5693, 5693, -1, + 5693, 5693, 5693, -1, 5694, 5694, 5694, -1, + 5694, 5694, 5694, -1, 5695, 5695, 5695, -1, + 5695, 5695, 5695, -1, 5696, 5696, 5696, -1, + 5696, 5696, 5696, -1, 5697, 5697, 5697, -1, + 5697, 5697, 5697, -1, 5698, 5698, 5698, -1, + 5698, 5698, 5698, -1, 5699, 5699, 5699, -1, + 5699, 5699, 5699, -1, 5700, 5700, 5700, -1, + 5700, 5700, 5700, -1, 5701, 5701, 5701, -1, + 5701, 5701, 5701, -1, 5702, 5702, 5702, -1, + 5702, 5702, 5702, -1, 5703, 5703, 5703, -1, + 5703, 5703, 5703, -1, 5704, 5704, 5704, -1, + 5704, 5704, 5704, -1, 5705, 5705, 5705, -1, + 5705, 5705, 5705, -1, 5706, 5706, 5706, -1, + 5706, 5706, 5706, -1, 5707, 5707, 5707, -1, + 5707, 5707, 5707, -1, 5708, 5708, 5708, -1, + 5708, 5708, 5708, -1, 5709, 5709, 5709, -1, + 5709, 5709, 5709, -1, 5710, 5710, 5710, -1, + 5710, 5710, 5710, -1, 5711, 5711, 5711, -1, + 5711, 5711, 5711, -1, 5712, 5712, 5712, -1, + 5712, 5712, 5712, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1, + 5584, 5584, 5584, -1, 5584, 5584, 5584, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link7.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link7.wrl new file mode 100644 index 0000000..cabada2 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-link7.wrl @@ -0,0 +1,2968 @@ +#VRML V2.0 utf8 + + +Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.027812799 0.0152884 0.078000002, + 0.027812799 0.0152884 0.072999999, + 0.0256724 0.0187138 0.078000002, + 0.00762054 0.0310643 0.072999999, + 0.0088388296 0.030668501 0.078000002, + 0.0118001 0.029706299 0.072999999, + 0.00762054 0.0310643 0.078000002, + 0.0118001 0.029706299 0.078000002, + 0.0074952501 0.039791498 0.061999999, + 0.0067140502 0.032809801 0.072999999, + 0.0123607 0.0385423 0.061999999, + -0.038743299 0.0104476 0.061999999, + -0.031776302 0.0094032902 0.072999999, + -0.0371911 0.015225 0.061999999, + -0.038743299 -0.0094475998 0.061999999, + -0.0371911 -0.014225 0.061999999, + -0.031776302 -0.0084032901 0.072999999, + -0.032360699 -0.023011399 0.061999999, + -0.0291587 -0.0268819 0.061999999, + -0.0255985 -0.020325899 0.072999999, + -0.0025116201 -0.0394211 0.061999999, + -0.0022519999 -0.032423101 0.072999999, + -0.0074952501 -0.0387915 0.061999999, + -0.025497001 -0.030320499 0.061999999, + -0.022524299 -0.023617599 0.072999999, + -0.0214331 -0.033273101 0.061999999, + -0.0190305 -0.026459999 0.072999999, + -0.0170312 -0.035693102 0.061999999, + -0.0151821 -0.028800201 0.072999999, + -0.0123607 -0.037542298 0.061999999, + -0.011051 -0.0305946 0.072999999, + -0.0067140502 -0.031809799 0.072999999, + -0.035052299 -0.018770101 0.061999999, + -0.030268 -0.0126472 0.072999999, + -0.0281958 -0.0166463 0.072999999, + -0.039684601 0.00551333 0.061999999, + -0.0326926 0.0049935002 0.072999999, + -0.039999999 0.00050000002 0.061999999, + -0.033 0.00050000002 0.072999999, + -0.039684601 -0.0045133298 0.061999999, + -0.0326926 -0.0039935 0.072999999, + 0.0296003 0.0112736 0.072999999, + 0.0301551 0.0093388297 0.078000002, + 0.0308116 0.0070492201 0.072999999, + 0.039684601 0.00551333 0.061999999, + 0.038743299 0.0104476 0.061999999, + 0.0326926 0.0049935002 0.072999999, + 0.031922799 0.0086983498 0.072999999, + 0.031776302 0.0094032902 0.072999999, + 0.0371911 0.015225 0.061999999, + 0.0123607 -0.037542298 0.061999999, + 0.0170312 -0.035693102 0.061999999, + 0.011051 -0.0305946 0.072999999, + 0.0214331 -0.033273101 0.061999999, + 0.0151821 -0.028800201 0.072999999, + 0.025497001 -0.030320499 0.061999999, + 0.0190305 -0.026459999 0.072999999, + 0.0291587 -0.0268819 0.061999999, + 0.022524299 -0.023617599 0.072999999, + 0.032360699 -0.023011399 0.061999999, + 0.0255985 -0.020325899 0.072999999, + 0.035052299 -0.018770101 0.061999999, + 0.0281958 -0.0166463 0.072999999, + 0.0371911 -0.014225 0.061999999, + 0.030268 -0.0126472 0.072999999, + 0.038743299 -0.0094475998 0.061999999, + 0.031776302 -0.0084032901 0.072999999, + 0.039684601 -0.0045133298 0.061999999, + 0.0326926 -0.0039935 0.072999999, + 0.039999999 0.00050000002 0.061999999, + 0.033 0.00050000002 0.072999999, + -0.035052299 0.019770101 0.061999999, + -0.0281958 0.0176463 0.072999999, + -0.032360699 0.0240114 0.061999999, + -0.030268 0.0136472 0.072999999, + 0.0025116201 0.040421098 0.061999999, + 0.0022519999 0.0334231 0.072999999, + 0.019393301 0.025322299 0.078000002, + 0.0213388 0.023570601 0.078000002, + 0.019393301 0.025322299 0.072999999, + 0.022659199 0.022381701 0.072999999, + 0.023999801 0.023037599 0.072999999, + 0.0255985 0.021325899 0.072999999, + 0.0291587 0.0278819 0.061999999, + 0.022524299 0.024617599 0.072999999, + 0.025497001 0.031320501 0.061999999, + 0.0214331 0.034273099 0.061999999, + 0.0190305 0.02746 0.072999999, + 0.020987101 0.025868099 0.072999999, + 0.0176454 0.0283022 0.072999999, + 0.0151821 0.029800201 0.072999999, + 0.0170312 0.0366931 0.061999999, + 0.011051 0.031594601 0.072999999, + 0.032360699 0.0240114 0.061999999, + 0.0266372 0.0198543 0.072999999, + 0.0281958 0.0176463 0.072999999, + 0.0231148 0.021838799 0.078000002, + 0.025483999 0.0190152 0.072999999, + 0.022659199 0.022381701 0.078000002, + 0.018146999 0.0211407 0.07, + 0.019039599 0.020850699 0.07, + 0.018213799 0.021119 0.078000002, + 0.019039599 0.020850699 0.078000002, + 0.018146999 0.0211407 0.078000002, + 0.014026 0.0303024 0.072999999, + 0.0101843 0.031837501 0.072999999, + 0.00617916 0.032883301 0.072999999, + -0.0214331 0.034273099 0.061999999, + -0.025497001 0.031320501 0.061999999, + -0.0190305 0.02746 0.072999999, + -0.0291587 0.0278819 0.061999999, + -0.022524299 0.024617599 0.072999999, + -0.0302797 0.0091825798 0.072999999, + -0.0302229 0.0093388297 0.078000002, + -0.0287767 0.0133122 0.072999999, + -0.0302797 0.0091825798 0.078000002, + -0.0302797 -0.0081825797 0.072999999, + -0.0287767 -0.0123122 0.072999999, + -0.0302229 -0.0083388304 0.078000002, + -0.017614599 -0.025614699 0.072999999, + -0.018213799 -0.025146499 0.078000002, + -0.021077599 -0.022909099 0.072999999, + -0.0097340401 -0.029458299 0.072999999, + -0.0054699201 -0.0305214 0.072999999, + -0.0088388296 -0.0296815 0.078000002, + 0.00762054 -0.0300643 0.072999999, + 0.0118001 -0.028706299 0.072999999, + 0.0088388296 -0.029668501 0.078000002, + 0.019039599 -0.019850699 0.078000002, + 0.019039599 -0.019850699 0.07, + 0.018213799 -0.020119 0.078000002, + 0.019039599 0.0155047 0.078000002, + 0.019039599 0.0155047 0.07, + 0.018213799 0.0152363 0.078000002, + 0.018146999 0.0152146 0.07, + -0.018146999 -0.0142146 0.07, + -0.018213799 -0.0142363 0.078000002, + -0.019039599 -0.0145047 0.07, + -0.019039599 -0.0145047 0.078000002, + -0.018146999 -0.0142146 0.078000002, + -0.0111369 -0.0106369 0.078000002, + -0.0111369 -0.0106369 0.071999997, + -0.0130229 -0.0083388304 0.078000002, + -0.0088388296 -0.0125229 0.078000002, + -0.0087502301 -0.0125956 0.071999997, + -0.0087502301 -0.0125956 0.078000002, + -0.018146999 -0.0201407 0.07, + -0.019039599 -0.019850699 0.07, + -0.018213799 -0.020119 0.078000002, + -0.019039599 -0.019850699 0.078000002, + -0.0203507 -0.0185396 0.078000002, + -0.0203507 -0.0185396 0.07, + -0.020618999 -0.0177138 0.078000002, + -0.020640699 -0.017647 0.07, + -0.020640699 -0.017647 0.078000002, + -0.0150047 -0.0185396 0.078000002, + -0.0147363 -0.0177138 0.078000002, + -0.0150047 -0.0185396 0.07, + -0.0147146 -0.017647 0.078000002, + -0.0147146 -0.017647 0.07, + -0.0130956 -0.00825023 0.078000002, + -0.0130956 -0.00825023 0.071999997, + 0.0111369 -0.0106369 0.078000002, + 0.0111369 -0.0106369 0.071999997, + 0.0088388296 -0.0125229 0.078000002, + 0.0130229 -0.0083388304 0.078000002, + 0.0130956 -0.00825023 0.071999997, + 0.0130956 -0.00825023 0.078000002, + 0.0087502301 -0.0125956 0.078000002, + 0.0087502301 -0.0125956 0.071999997, + -0.0147146 0.018647 0.07, + -0.0147363 0.0187138 0.078000002, + -0.0150047 0.0195396 0.07, + -0.0150047 0.0195396 0.078000002, + -0.017614599 0.0266147 0.078000002, + -0.017614599 0.0266147 0.072999999, + -0.018213799 0.026146499 0.078000002, + -0.021077599 0.023909099 0.072999999, + -0.0241304 0.020747799 0.072999999, + -0.023076801 0.021838799 0.078000002, + -0.020640699 0.018647 0.07, + -0.0203507 0.0195396 0.07, + -0.020618999 0.0187138 0.078000002, + -0.020640699 0.018647 0.078000002, + -0.0241304 0.020747799 0.078000002, + -0.025608201 0.0187138 0.078000002, + -0.0203507 0.0195396 0.078000002, + -0.019039599 0.020850699 0.078000002, + -0.019039599 0.020850699 0.07, + -0.018213799 0.021119 0.078000002, + -0.018146999 0.0211407 0.078000002, + -0.018146999 0.0211407 0.07, + -0.021077599 0.023909099 0.078000002, + -0.0111369 0.0116369 0.078000002, + -0.0111369 0.0116369 0.071999997, + -0.0088388296 0.0135229 0.078000002, + -0.0130229 0.0093388297 0.078000002, + -0.018146999 0.0152146 0.07, + -0.019039599 0.0155047 0.07, + -0.018213799 0.0152363 0.078000002, + -0.019039599 0.0155047 0.078000002, + -0.018146999 0.0152146 0.078000002, + -0.0130956 0.0092502302 0.078000002, + -0.0130956 0.0092502302 0.071999997, + -0.0087502301 0.0135956 0.071999997, + -0.0087502301 0.0135956 0.078000002, + 0.0087502301 0.0135956 0.078000002, + 0.0087502301 0.0135956 0.071999997, + 0.0088388296 0.0135229 0.078000002, + 0.0111369 0.0116369 0.071999997, + 0.0111369 0.0116369 0.078000002, + 0.0130229 0.0093388297 0.078000002, + 0.0130956 0.0092502302 0.071999997, + 0.0130956 0.0092502302 0.078000002, + 0.018146999 0.0152146 0.078000002, + 0.0296003 -0.0102736 0.072999999, + 0.0308116 -0.00604922 0.072999999, + 0.0301551 -0.0083388304 0.078000002, + 0.022659199 -0.0213817 0.072999999, + 0.0213388 -0.022570601 0.078000002, + 0.019393301 -0.024322299 0.072999999, + 0.022659199 -0.0213817 0.078000002, + 0.020640699 -0.017647 0.07, + 0.0203507 -0.0185396 0.07, + 0.020618999 -0.0177138 0.078000002, + 0.0203507 -0.0185396 0.078000002, + 0.020640699 -0.017647 0.078000002, + 0.025483999 -0.0180152 0.078000002, + 0.025483999 -0.0180152 0.072999999, + 0.0256724 -0.0177138 0.078000002, + 0.027812799 -0.0142884 0.072999999, + 0.027812799 -0.0142884 0.078000002, + 0.0296003 -0.0102736 0.078000002, + 0.0308116 -0.00604922 0.078000002, + 0.018146999 -0.0142146 0.078000002, + 0.018146999 -0.0142146 0.07, + 0.018213799 -0.0142363 0.078000002, + 0.019039599 -0.0145047 0.07, + 0.019039599 -0.0145047 0.078000002, + 0.019393301 -0.024322299 0.078000002, + 0.0147146 -0.017647 0.07, + 0.0147363 -0.0177138 0.078000002, + 0.0150047 -0.0185396 0.07, + 0.018146999 -0.0201407 0.078000002, + 0.018146999 -0.0201407 0.07, + 0.0147146 -0.017647 0.078000002, + 0.0150047 -0.0185396 0.078000002, + 0.0118001 -0.028706299 0.078000002, + 0.00762054 -0.0300643 0.078000002, + 0.00617916 -0.031883299 0.072999999, + 0.0022519999 -0.032423101 0.072999999, + 0.0074952501 -0.0387915 0.061999999, + 0.0025116201 -0.0394211 0.061999999, + -0.0054699201 -0.0305214 0.078000002, + -0.0097340401 -0.029458299 0.078000002, + -0.017614599 -0.025614699 0.078000002, + -0.018146999 -0.0201407 0.078000002, + -0.021077599 -0.022909099 0.078000002, + -0.0241304 -0.019747799 0.078000002, + -0.025608201 -0.0177138 0.078000002, + -0.0241304 -0.019747799 0.072999999, + -0.0287767 -0.0123122 0.078000002, + -0.0302797 -0.0081825797 0.078000002, + -0.0287767 0.0133122 0.078000002, + -0.023999801 0.023037599 0.072999999, + -0.0255985 0.021325899 0.072999999, + -0.020987101 0.025868099 0.072999999, + -0.0176454 0.0283022 0.072999999, + -0.0151821 0.029800201 0.072999999, + -0.014026 0.0303024 0.072999999, + -0.011051 0.031594601 0.072999999, + -0.0170312 0.0366931 0.061999999, + -0.0123607 0.0385423 0.061999999, + -0.0101843 0.031837501 0.072999999, + -0.0067140502 0.032809801 0.072999999, + -0.0097340401 0.030458299 0.078000002, + -0.0088388296 0.0306815 0.078000002, + -0.0097340401 0.030458299 0.072999999, + -0.0054699201 0.031521399 0.072999999, + -0.00617916 0.032883301 0.072999999, + -0.0022519999 0.0334231 0.072999999, + -0.0074952501 0.039791498 0.061999999, + -0.0025116201 0.040421098 0.061999999, + -0.0054699201 0.031521399 0.078000002, + -0.0147146 0.018647 0.078000002, + 0.0147146 0.018647 0.078000002, + 0.0147146 0.018647 0.07, + 0.0147363 0.0187138 0.078000002, + 0.0150047 0.0195396 0.07, + 0.0150047 0.0195396 0.078000002, + 0.020640699 0.018647 0.078000002, + 0.020618999 0.0187138 0.078000002, + 0.020640699 0.018647 0.07, + 0.0203507 0.0195396 0.07, + 0.0203507 0.0195396 0.078000002, + 0.025483999 0.0190152 0.078000002, + 0.028858701 0.0163671 0.072999999, + 0.030268 0.0136472 0.072999999, + 0.035052299 0.019770101 0.061999999, + 0.0306297 0.0126293 0.072999999, + 0.0296003 0.0112736 0.078000002, + 0.0308116 0.0070492201 0.078000002, + 0.032717202 0.0046344502 0.072999999, + 0.032717202 -0.00363445 0.072999999, + 0.031922799 -0.0076983501 0.072999999, + 0.0306297 -0.0116293 0.072999999, + 0.028858701 -0.0153671 0.072999999, + 0.0266372 -0.0188543 0.072999999, + 0.023999801 -0.022037599 0.072999999, + 0.020987101 -0.024868101 0.072999999, + 0.0176454 -0.0273022 0.072999999, + 0.014026 -0.0293024 0.072999999, + 0.0101843 -0.0308375 0.072999999, + 0.0067140502 -0.031809799 0.072999999, + -0.00617916 -0.031883299 0.072999999, + -0.0101843 -0.0308375 0.072999999, + -0.014026 -0.0293024 0.072999999, + -0.0176454 -0.0273022 0.072999999, + -0.020987101 -0.024868101 0.072999999, + -0.023999801 -0.022037599 0.072999999, + -0.0266372 -0.0188543 0.072999999, + -0.028858701 -0.0153671 0.072999999, + -0.0306297 -0.0116293 0.072999999, + -0.031922799 -0.0076983501 0.072999999, + -0.032717202 -0.00363445 0.072999999, + -0.032717202 0.0046344502 0.072999999, + -0.031922799 0.0086983498 0.072999999, + -0.0306297 0.0126293 0.072999999, + -0.028858701 0.0163671 0.072999999, + -0.0266372 0.0198543 0.072999999, + 0.0020720901 0.0334231 0.072999999, + -0.0020720901 0.0334231 0.072999999, + 0.0020720901 -0.032423101 0.072999999, + -0.0020720901 -0.032423101 0.072999999, + 0.00285317 0.026427099 0.078000002, + 0.0024270499 0.027263399 0.078000002, + 0.00285317 0.026427099 0.07, + 0.0024270499 0.027263399 0.07, + 0.003 0.0255 0.07, + 0.003 0.0255 0.078000002, + 0.00176336 0.027927101 0.078000002, + 0.00176336 0.027927101 0.07, + 0.00329265 0.031827401 0.072999999, + -0.00109933 0.031980801 0.072999999, + 0.00329265 0.031827401 0.078000002, + -0.00109933 0.031980801 0.078000002, + 0.00285317 0.0245729 0.07, + 0.00285317 0.0245729 0.078000002, + 0.00176336 0.0230729 0.07, + 0.00092705101 0.0226468 0.07, + 0.00176336 0.0230729 0.078000002, + 0.00092705101 0.0226468 0.078000002, + 0.0024270499 0.0237366 0.078000002, + 0.0024270499 0.0237366 0.07, + 0.00092705101 0.028353199 0.07, + 0 0.0285 0.07, + -0.00092705101 0.028353199 0.07, + 0 0.022500001 0.07, + -0.00176336 0.027927101 0.07, + -0.0024270499 0.027263399 0.07, + -0.00092705101 0.0226468 0.07, + -0.00176336 0.0230729 0.07, + -0.0024270499 0.0237366 0.07, + -0.00285317 0.0245729 0.07, + -0.003 0.0255 0.07, + -0.00285317 0.026427099 0.07, + 0.01575 0.027779801 0.078000002, + 0.01575 0.027779801 0.072999999, + 0.0042694402 -0.029194601 0.057, + 0 -0.0295 0.057, + 0.0042694402 -0.029194601 0.046999998, + 0 -0.0295 0.046999998, + 0.0084519796 -0.028284799 0.046999998, + 0.0084519796 -0.028284799 0.057, + -0.0042694402 -0.029194601 0.057, + -0.0042694402 -0.029194601 0.046999998, + -0.0025116201 -0.0394211 0.057, + 0.0025116201 -0.0394211 0.057, + -0.0074952501 -0.0387915 0.057, + -0.0084519796 -0.028284799 0.046999998, + -0.0084519796 -0.028284799 0.057, + -0.0124625 -0.026789 0.057, + -0.0124625 -0.026789 0.046999998, + -0.016219201 -0.0247376 0.057, + -0.016219201 -0.0247376 0.046999998, + -0.025497001 -0.030320499 0.057, + -0.0291587 -0.0268819 0.057, + -0.0214331 -0.033273101 0.057, + -0.0170312 -0.035693102 0.057, + -0.0123607 -0.037542298 0.057, + -0.019645801 -0.022172499 0.057, + -0.019645801 -0.022172499 0.046999998, + -0.032360699 -0.023011399 0.057, + -0.035052299 -0.018770101 0.057, + -0.0371911 -0.014225 0.057, + -0.0226725 -0.0191458 0.057, + -0.0226725 -0.0191458 0.046999998, + -0.025237599 -0.0157192 0.057, + -0.025237599 -0.0157192 0.046999998, + -0.027288999 -0.0119625 0.057, + -0.027288999 -0.0119625 0.046999998, + -0.0287848 -0.0079519805 0.057, + -0.0287848 -0.0079519805 0.046999998, + -0.038743299 -0.0094475998 0.057, + -0.039684601 0.00551333 0.057, + -0.038743299 0.0104476 0.057, + -0.039999999 0.00050000002 0.057, + -0.039684601 -0.0045133298 0.057, + -0.0296946 -0.0037694499 0.057, + -0.0296946 -0.0037694499 0.046999998, + 0.025237599 0.0167192 0.046999998, + 0.0226725 0.0201458 0.046999998, + 0.025237599 0.0167192 0.057, + 0.0226725 0.0201458 0.057, + 0.027288999 0.0129625 0.057, + 0.027288999 0.0129625 0.046999998, + 0.0371911 0.015225 0.057, + 0.038743299 0.0104476 0.057, + 0.035052299 0.019770101 0.057, + 0.0287848 0.0089519797 0.057, + 0.0287848 0.0089519797 0.046999998, + 0.0296946 0.0047694398 0.057, + 0.0296946 0.0047694398 0.046999998, + 0.039684601 0.00551333 0.057, + 0.0296946 -0.0037694499 0.057, + 0.0287848 -0.0079519805 0.057, + 0.0296946 -0.0037694499 0.046999998, + 0.0287848 -0.0079519805 0.046999998, + 0.029999999 0.00050000002 0.046999998, + 0.029999999 0.00050000002 0.057, + 0.0226725 -0.0191458 0.057, + 0.019645801 -0.022172499 0.057, + 0.0226725 -0.0191458 0.046999998, + 0.019645801 -0.022172499 0.046999998, + 0.025237599 -0.0157192 0.046999998, + 0.025237599 -0.0157192 0.057, + 0.027288999 -0.0119625 0.057, + 0.027288999 -0.0119625 0.046999998, + 0.016219201 -0.0247376 0.046999998, + 0.0124625 -0.026789 0.046999998, + 0.019645801 0.0231725 0.046999998, + 0.016219201 0.0257376 0.046999998, + 0.0124625 0.027789 0.046999998, + 0.0084519796 0.029284799 0.046999998, + 0.0042694402 0.030194599 0.046999998, + 0 0.0305 0.046999998, + -0.0042694402 0.030194599 0.046999998, + -0.029999999 0.00050000002 0.046999998, + -0.0296946 0.0047694398 0.046999998, + -0.0084519796 0.029284799 0.046999998, + -0.0124625 0.027789 0.046999998, + -0.0287848 0.0089519797 0.046999998, + -0.027288999 0.0129625 0.046999998, + -0.025237599 0.0167192 0.046999998, + -0.0226725 0.0201458 0.046999998, + -0.019645801 0.0231725 0.046999998, + -0.016219201 0.0257376 0.046999998, + 0.016219201 -0.0247376 0.057, + 0.0170312 -0.035693102 0.057, + 0.0123607 -0.037542298 0.057, + 0.0214331 -0.033273101 0.057, + 0.025497001 -0.030320499 0.057, + 0.0291587 -0.0268819 0.057, + 0.032360699 -0.023011399 0.057, + 0.035052299 -0.018770101 0.057, + 0.0371911 -0.014225 0.057, + 0.038743299 -0.0094475998 0.057, + 0.039684601 -0.0045133298 0.057, + 0.039999999 0.00050000002 0.057, + -0.029999999 0.00050000002 0.057, + -0.0296946 0.0047694398 0.057, + -0.0371911 0.015225 0.057, + -0.027288999 0.0129625 0.057, + -0.025237599 0.0167192 0.057, + -0.0287848 0.0089519797 0.057, + -0.035052299 0.019770101 0.057, + -0.032360699 0.0240114 0.057, + -0.0042694402 0.030194599 0.057, + -0.0084519796 0.029284799 0.057, + 0 0.0305 0.057, + 0.0025116201 0.040421098 0.057, + 0.0074952501 0.039791498 0.057, + -0.0025116201 0.040421098 0.057, + 0.0042694402 0.030194599 0.057, + 0.0084519796 0.029284799 0.057, + 0.0123607 0.0385423 0.057, + 0.0124625 0.027789 0.057, + 0.016219201 0.0257376 0.057, + 0.025497001 0.031320501 0.057, + 0.0291587 0.0278819 0.057, + 0.0214331 0.034273099 0.057, + 0.0170312 0.0366931 0.057, + 0.019645801 0.0231725 0.057, + 0.032360699 0.0240114 0.057, + 0.019799 0.020299001 0.07, + 0.020640699 0.0177084 0.07, + 0.0203507 0.0168157 0.07, + 0.019799 0.016056299 0.07, + 0.017208399 0.0211407 0.07, + 0.0163157 0.020850699 0.07, + 0.0155563 0.020299001 0.07, + 0.017208399 0.0152146 0.07, + 0.0163157 0.0155047 0.07, + 0.0147146 0.0177084 0.07, + 0.0155563 0.016056299 0.07, + 0.0150047 0.0168157 0.07, + 0.019799 0.020299001 0.078000002, + 0.017208399 0.0211407 0.078000002, + -0.0074952501 0.039791498 0.057, + -0.0124625 0.027789 0.057, + -0.025497001 0.031320501 0.057, + -0.0214331 0.034273099 0.057, + -0.0291587 0.0278819 0.057, + -0.019645801 0.0231725 0.057, + -0.016219201 0.0257376 0.057, + -0.0226725 0.0201458 0.057, + -0.0311934 0.0048839501 0.072999999, + -0.0311934 0.0048839501 0.078000002, + -0.0024270499 -0.0227366 0.07, + -0.00176336 -0.0220729 0.07, + -0.0024270499 -0.0227366 0.078000002, + -0.00176336 -0.0220729 0.078000002, + -0.00285317 -0.023572899 0.078000002, + -0.00285317 -0.023572899 0.07, + -0.003 -0.024499999 0.078000002, + -0.003 -0.024499999 0.07, + 0.019799 -0.019299001 0.078000002, + 0.019799 -0.019299001 0.07, + 0.019799 0.016056299 0.078000002, + 0.0203507 0.0168157 0.078000002, + 0.0060272599 0.0150511 0.078000002, + 0.0060272599 0.0150511 0.071999997, + -0.0060272599 0.0150511 0.071999997, + -0.00307267 0.0159474 0.071999997, + -0.0145511 0.0065272599 0.071999997, + -0.0154474 0.00357267 0.071999997, + -0.01575 0.00050000002 0.071999997, + -0.0154474 -0.0025726701 0.071999997, + 0 0.016249999 0.071999997, + 0.00307267 0.0159474 0.071999997, + 0.0145511 0.0065272599 0.071999997, + 0.0154474 0.00357267 0.071999997, + -0.0145511 -0.0055272598 0.071999997, + -0.0060272599 -0.0140511 0.071999997, + -0.00307267 -0.0149474 0.071999997, + 0 -0.01525 0.071999997, + 0.00307267 -0.0149474 0.071999997, + 0.0060272599 -0.0140511 0.071999997, + 0.01575 0.00050000002 0.071999997, + 0.0154474 -0.0025726701 0.071999997, + 0.0145511 -0.0055272598 0.071999997, + -0.0145511 0.0065272599 0.078000002, + -0.0154474 0.00357267 0.078000002, + -0.023236601 0.00292705 0.078000002, + -0.0240729 0.0033531699 0.078000002, + -0.023236601 0.00292705 0.07, + -0.0240729 0.0033531699 0.07, + -0.022572899 0.00226336 0.07, + -0.022572899 0.00226336 0.078000002, + -0.022146801 0.00142705 0.07, + -0.022146801 0.00142705 0.078000002, + -0.025 0.0035000001 0.078000002, + -0.025 0.0035000001 0.07, + -0.022 0.00050000002 0.07, + -0.022 0.00050000002 0.078000002, + -0.0240729 -0.00235317 0.078000002, + -0.023236601 -0.0019270499 0.078000002, + -0.0240729 -0.00235317 0.07, + -0.023236601 -0.0019270499 0.07, + -0.025 -0.0024999999 0.07, + -0.025 -0.0024999999 0.078000002, + -0.022146801 -0.00042705101 0.07, + -0.022572899 -0.00126336 0.07, + -0.022146801 -0.00042705101 0.078000002, + -0.022572899 -0.00126336 0.078000002, + -0.0259271 -0.00235317 0.07, + -0.0267634 -0.0019270499 0.07, + -0.0274271 -0.00126336 0.07, + -0.0278532 -0.00042705101 0.07, + -0.028000001 0.00050000002 0.07, + -0.0278532 0.00142705 0.07, + -0.0274271 0.00226336 0.07, + -0.0267634 0.00292705 0.07, + -0.0259271 0.0033531699 0.07, + -0.0259271 -0.00235317 0.078000002, + -0.0267634 -0.0019270499 0.078000002, + -0.0274271 -0.00126336 0.078000002, + -0.0278532 -0.00042705101 0.078000002, + -0.028000001 0.00050000002 0.078000002, + -0.0278532 0.00142705 0.078000002, + -0.0274271 0.00226336 0.078000002, + -0.0267634 0.00292705 0.078000002, + -0.0259271 0.0033531699 0.078000002, + -0.0154474 -0.0025726701 0.078000002, + -0.01575 0.00050000002 0.078000002, + -0.0145511 -0.0055272598 0.078000002, + 0.00285317 -0.025427099 0.078000002, + 0.003 -0.024499999 0.078000002, + 0.00285317 -0.025427099 0.07, + 0.003 -0.024499999 0.07, + 0.0024270499 -0.026263401 0.07, + 0.0024270499 -0.026263401 0.078000002, + 0.00285317 -0.023572899 0.078000002, + 0.00285317 -0.023572899 0.07, + 0.00092705101 -0.0216468 0.07, + 0.00176336 -0.0220729 0.07, + 0.00092705101 -0.0216468 0.078000002, + 0.00176336 -0.0220729 0.078000002, + 0 -0.021500001 0.078000002, + 0 -0.021500001 0.07, + 0.0024270499 -0.0227366 0.07, + 0.0024270499 -0.0227366 0.078000002, + 0.00176336 -0.0269271 0.07, + -0.00092705101 -0.0216468 0.07, + -0.00285317 -0.025427099 0.07, + 0.00092705101 -0.027353199 0.07, + 0 -0.0275 0.07, + -0.0024270499 -0.026263401 0.07, + -0.00176336 -0.0269271 0.07, + -0.00092705101 -0.027353199 0.07, + -0.00092705101 -0.0216468 0.078000002, + -0.019799 -0.0150563 0.078000002, + -0.0203507 -0.015815699 0.078000002, + -0.019799 -0.0150563 0.07, + -0.0203507 -0.015815699 0.07, + -0.017208399 -0.0142146 0.07, + -0.017208399 -0.0142146 0.078000002, + -0.0147146 -0.0167084 0.078000002, + -0.0147146 -0.0167084 0.07, + -0.0150047 -0.015815699 0.078000002, + -0.0150047 -0.015815699 0.07, + -0.0155563 -0.0150563 0.078000002, + -0.0155563 -0.0150563 0.07, + -0.0060272599 -0.0140511 0.078000002, + -0.017208399 -0.0201407 0.078000002, + -0.0163157 -0.019850699 0.078000002, + -0.017208399 -0.0201407 0.07, + -0.0163157 -0.019850699 0.07, + -0.019799 -0.019299001 0.07, + -0.020640699 -0.0167084 0.07, + -0.0155563 -0.019299001 0.07, + -0.0163157 -0.0145047 0.07, + -0.019799 -0.019299001 0.078000002, + -0.020640699 -0.0167084 0.078000002, + -0.0155563 -0.019299001 0.078000002, + -0.0163157 -0.0145047 0.078000002, + -0.00307267 -0.0149474 0.078000002, + 0 -0.01525 0.078000002, + 0.00307267 -0.0149474 0.078000002, + 0.01575 0.00050000002 0.078000002, + 0.0154474 -0.0025726701 0.078000002, + 0.0154474 0.00357267 0.078000002, + 0.0145511 -0.0055272598 0.078000002, + 0.017208399 -0.0142146 0.078000002, + 0.017208399 -0.0142146 0.07, + 0.0163157 -0.0145047 0.078000002, + 0.0163157 -0.0145047 0.07, + 0.0155563 -0.0150563 0.078000002, + 0.0155563 -0.0150563 0.07, + 0.0150047 -0.015815699 0.078000002, + 0.0150047 -0.015815699 0.07, + 0.0147146 -0.0167084 0.078000002, + 0.0147146 -0.0167084 0.07, + 0.0060272599 -0.0140511 0.078000002, + 0.0145511 0.0065272599 0.078000002, + -0.0155563 0.020299001 0.078000002, + -0.0155563 0.020299001 0.07, + -0.0163157 0.020850699 0.078000002, + -0.0163157 0.020850699 0.07, + -0.0147146 0.0177084 0.07, + -0.0150047 0.0168157 0.07, + -0.0155563 0.016056299 0.07, + -0.0163157 0.0155047 0.07, + -0.017208399 0.0152146 0.07, + -0.019799 0.016056299 0.07, + -0.0203507 0.0168157 0.07, + -0.017208399 0.0211407 0.07, + -0.019799 0.020299001 0.07, + -0.020640699 0.0177084 0.07, + -0.017208399 0.0211407 0.078000002, + -0.0138087 0.028812001 0.078000002, + -0.0138087 0.028812001 0.072999999, + -0.003 0.0255 0.078000002, + -0.00285317 0.026427099 0.078000002, + -0.00285317 0.0245729 0.078000002, + -0.0024270499 0.0237366 0.078000002, + -0.019799 0.016056299 0.078000002, + -0.0203507 0.0168157 0.078000002, + -0.020640699 0.0177084 0.078000002, + -0.019799 0.020299001 0.078000002, + -0.0150047 0.0168157 0.078000002, + -0.0155563 0.016056299 0.078000002, + -0.0147146 0.0177084 0.078000002, + -0.0163157 0.0155047 0.078000002, + -0.017208399 0.0152146 0.078000002, + -0.0060272599 0.0150511 0.078000002, + -0.00307267 0.0159474 0.078000002, + 0 0.016249999 0.078000002, + 0.00307267 0.0159474 0.078000002, + 0.0147146 0.0177084 0.078000002, + 0.017208399 0.0152146 0.078000002, + 0.0163157 0.0155047 0.078000002, + 0.0155563 0.016056299 0.078000002, + 0.0150047 0.0168157 0.078000002, + 0.0274271 -0.00126336 0.078000002, + 0.0278532 -0.00042705101 0.078000002, + 0.0274271 -0.00126336 0.07, + 0.0278532 -0.00042705101 0.07, + 0.0267634 -0.0019270499 0.07, + 0.0267634 -0.0019270499 0.078000002, + 0.0278532 0.00142705 0.078000002, + 0.0274271 0.00226336 0.078000002, + 0.0278532 0.00142705 0.07, + 0.0274271 0.00226336 0.07, + 0.028000001 0.00050000002 0.07, + 0.028000001 0.00050000002 0.078000002, + 0.0267634 0.00292705 0.078000002, + 0.0267634 0.00292705 0.07, + 0.0203507 -0.015815699 0.07, + 0.020640699 -0.0167084 0.07, + 0.0203507 -0.015815699 0.078000002, + 0.020640699 -0.0167084 0.078000002, + 0.019799 -0.0150563 0.078000002, + 0.019799 -0.0150563 0.07, + 0.017208399 -0.0201407 0.07, + 0.0163157 -0.019850699 0.07, + 0.0155563 -0.019299001 0.07, + 0.023236601 -0.0019270499 0.07, + 0.022572899 -0.00126336 0.07, + 0.023236601 -0.0019270499 0.078000002, + 0.022572899 -0.00126336 0.078000002, + 0.0240729 -0.00235317 0.078000002, + 0.0240729 -0.00235317 0.07, + 0.022146801 -0.00042705101 0.07, + 0.022146801 -0.00042705101 0.078000002, + 0.025 -0.0024999999 0.078000002, + 0.025 -0.0024999999 0.07, + 0.0259271 -0.00235317 0.078000002, + 0.0259271 -0.00235317 0.07, + 0.022 0.00050000002 0.07, + 0.022146801 0.00142705 0.07, + 0.0259271 0.0033531699 0.07, + 0.025 0.0035000001 0.07, + 0.0240729 0.0033531699 0.07, + 0.022572899 0.00226336 0.07, + 0.023236601 0.00292705 0.07, + 0.031423301 -0.00169733 0.072999999, + 0.031423301 -0.00169733 0.078000002, + 0.031423301 0.00269733 0.072999999, + 0.031423301 0.00269733 0.078000002, + 0.022 0.00050000002 0.078000002, + 0.022146801 0.00142705 0.078000002, + 0.025 0.0035000001 0.078000002, + 0.0259271 0.0033531699 0.078000002, + 0.0240729 0.0033531699 0.078000002, + 0.022572899 0.00226336 0.078000002, + 0.023236601 0.00292705 0.078000002, + 0.017208399 -0.0201407 0.078000002, + 0.0163157 -0.019850699 0.078000002, + 0.0155563 -0.019299001 0.078000002, + 0.01575 -0.026779801 0.078000002, + 0.01575 -0.026779801 0.072999999, + 0.00329265 -0.030827399 0.078000002, + 0.00329265 -0.030827399 0.072999999, + -0.00176336 -0.0269271 0.078000002, + -0.0024270499 -0.026263401 0.078000002, + -0.00092705101 -0.027353199 0.078000002, + -0.00285317 -0.025427099 0.078000002, + 0.00092705101 -0.027353199 0.078000002, + 0 -0.0275 0.078000002, + 0.00176336 -0.0269271 0.078000002, + -0.00109933 -0.030980799 0.078000002, + -0.00109933 -0.030980799 0.072999999, + 0.0124625 -0.026789 0.057, + 0.0074952501 -0.0387915 0.057, + -0.0138087 -0.027812 0.078000002, + -0.0138087 -0.027812 0.072999999, + -0.0267135 -0.0161925 0.078000002, + -0.0267135 -0.0161925 0.072999999, + -0.0311934 -0.0038839499 0.078000002, + -0.0311934 -0.0038839499 0.072999999, + -0.031500001 0.00050000002 0.078000002, + -0.031500001 0.00050000002 0.072999999, + -0.0267135 0.0171925 0.078000002, + -0.0267135 0.0171925 0.072999999, + -0.0170312 0.0366931 0.057, + -0.0123607 0.0385423 0.057, + 0.00092705101 0.028353199 0.078000002, + 0 0.0285 0.078000002, + -0.00092705101 0.028353199 0.078000002, + -0.00176336 0.027927101 0.078000002, + -0.0024270499 0.027263399 0.078000002, + 0 0.022500001 0.078000002, + -0.00092705101 0.0226468 0.078000002, + -0.00176336 0.0230729 0.078000002, + 0.0155563 0.020299001 0.078000002, + 0.0163157 0.020850699 0.078000002, + 0.020640699 0.0177084 0.078000002, + 0.018213799 0.0261179 0.078000002, + 0.018213799 -0.0251179 0.078000002, + -0.018213799 0.0093388297 0.078000002, + -0.018213799 -0.0083388304 0.078000002, + -0.0088388296 -0.0177138 0.078000002, + 0.0088388296 -0.0177138 0.078000002, + 0.018213799 -0.0083388304 0.078000002, + 0.0213388 -0.0177138 0.078000002, + 0.0213388 -0.0083388304 0.078000002, + 0.0213388 0.0093388297 0.078000002, + 0.018213799 0.0093388297 0.078000002, + 0.0088388296 0.0187138 0.078000002, + -0.0088388296 0.0187138 0.078000002, + -0.0088388296 0.021838799 0.078000002, + -0.018213799 0.021838799 0.078000002, + 0.0088388296 0.021838799 0.078000002, + 0.018213799 0.021838799 0.078000002, + 0.0213388 0.021838799 0.078000002, + 0.0213388 0.0187138 0.078000002 ] + + } + normal + Normal { + vector [ 0.84805131 0.5299142 0, + 0.30901298 0.95105785 -7.6900187e-006, + 0.30898407 0.95106721 0, + 0.30902407 0.95105422 0, + 0.21017903 0.81861609 0.53450209, + -0.80406612 0.26124504 0.53406805, + -0.80406612 -0.26124504 0.53406805, + -0.65213102 -0.53949702 0.53260499, + -0.10584998 -0.83785784 0.53552788, + -0.57940298 -0.61699498 0.53254998, + -0.49744081 -0.68466675 0.53271383, + -0.40759394 -0.74139994 0.53309792, + -0.31131694 -0.78628981 0.53369486, + -0.21017903 -0.81861609 0.53450209, + -0.76537567 -0.36016488 0.53336781, + -0.71446383 -0.45341089 0.53287888, + -0.8298918 0.15831695 0.53499091, + -0.84247571 0.053001881 0.53612083, + -0.84247571 -0.053001881 0.53612083, + -0.8298918 -0.15831695 0.53499091, + 0.961263 0.27563301 -4.53545e-006, + 0.8298918 0.15831695 0.53499091, + 0.8248713 0.17139307 0.53871316, + 0.8248648 0.17142196 0.53871387, + 0.80406612 0.26124504 0.53406805, + 0.31131694 -0.78628981 0.53369486, + 0.40759394 -0.74139994 0.53309792, + 0.49744081 -0.68466675 0.53271383, + 0.57940298 -0.61699498 0.53254998, + 0.65213102 -0.53949702 0.53260499, + 0.71446383 -0.45341089 0.53287888, + 0.76537567 -0.36016488 0.53336781, + 0.80406612 -0.26124504 0.53406805, + 0.8298918 -0.15831695 0.53499091, + 0.84247571 -0.053001881 0.53612083, + 0.84247571 0.053001881 0.53612083, + -0.71446383 0.45341089 0.53287888, + -0.76537567 0.36016488 0.53336781, + 0.10584998 0.83785784 0.53552788, + 0.66912282 0.74315184 0, + 0.66912705 0.74314809 -2.8283603e-006, + 0.61461222 0.57403719 0.54104817, + 0.61464995 0.57399696 0.54104793, + 0.57940298 0.61699498 0.53254998, + 0.49744081 0.68466675 0.53271383, + 0.53078294 0.65238392 0.54098493, + 0.53073889 0.65241981 0.54098487, + 0.43705779 0.71879363 0.54066277, + 0.43710184 0.71876675 0.54066283, + 0.40759394 0.74139994 0.53309792, + 0.31131694 0.78628981 0.53369486, + 0.65213102 0.53949702 0.53260499, + 0.687181 0.48503301 0.540856, + 0.68716198 0.48506001 0.540856, + 0.76604772 0.64278376 -8.6679274e-006, + 0.76600885 0.64282995 0, + 0.66913283 0.74314284 0, + -0.30899313 -0.95106435 3.8449014e-007, + -0.30899704 -0.9510631 0, + -0.30895188 -0.95107764 0, + 0.33532012 0.77192932 0.54007918, + 0.33529484 0.77194065 0.54007876, + 0.22726394 0.81090981 0.5392369, + 0.2272069 0.81092662 0.53923577, + 0.11474297 0.83501381 0.53813189, + 0.11477399 0.83500886 0.53813297, + -0.49744081 0.68466675 0.53271383, + -0.57940298 0.61699498 0.53254998, + -0.93969703 0.34200799 -1.30066e-005, + -0.93983054 0.34164086 0, + -0.93969703 -0.34200799 -1.30066e-005, + -0.61566275 -0.7880097 8.2071974e-006, + -0.24190806 -0.97029924 -2.3747004e-006, + 0.30901298 -0.95105785 -7.6900187e-006, + -0.30899704 0.9510631 0, + -0.30910105 0.95102924 0, + -0.30909085 0.95103252 1.1704694e-006, + 0.30909085 -0.95103252 1.1704694e-006, + 0.30910105 -0.95102924 0, + 0.30896395 -0.95107377 0, + 0.7730068 0.6343978 0, + 0.6343978 0.7730068 0, + 0.63439506 0.77300912 1.5673402e-006, + 0.63433182 0.7730608 0, + 0.30899313 0.95106435 3.8449014e-007, + 0.30899704 0.9510631 0, + 0.9510631 0.30899704 0, + 0.95106435 0.30899313 3.8449014e-007, + 0.95107764 0.30895188 0, + -0.95102924 0.30910105 0, + -0.95107377 0.30896395 0, + -0.95103252 0.30909085 1.1704694e-006, + 0.7730608 0.63433182 0, + 0.77300912 0.63439506 1.5673402e-006, + -0.6343978 0.7730068 0, + -0.7730068 0.6343978 0, + -0.77300912 0.63439506 1.5673402e-006, + -0.7730608 0.63433182 0, + -0.63433182 0.7730608 0, + -0.63439506 0.77300912 1.5673402e-006, + -0.95103252 -0.30909085 1.1704694e-006, + -0.95102924 -0.30910105 0, + -0.61570489 0.7879768 0, + -0.61566275 0.7880097 8.2071974e-006, + -0.71934307 0.69465506 6.4899009e-006, + 0.95106435 -0.30899313 3.8449014e-007, + 0.95107764 -0.30895188 0, + -0.8090142 0.58778912 0, + -0.71932876 0.69466978 0, + 0.9510631 -0.30899704 0, + 0.30899704 -0.9510631 0, + 0.30895188 -0.95107764 0, + 0.30899313 -0.95106435 3.8449014e-007, + -0.71935093 0.69464695 0, + -0.61565387 0.7880168 0, + 0.6343978 -0.7730068 0, + 0.7730068 -0.6343978 0, + 0.30909085 0.95103252 1.1704694e-006, + 0.30910105 0.95102924 0, + 0.30896395 0.95107377 0, + 0.7730608 -0.63433182 0, + 0.77300912 -0.63439506 1.5673402e-006, + 0.63439506 -0.77300912 1.5673402e-006, + 0.63433182 -0.7730608 0, + -0.63433182 -0.7730608 0, + -0.63439506 -0.77300912 1.5673402e-006, + -0.6343978 -0.7730068 0, + -0.7730068 -0.6343978 0, + -0.77300912 -0.63439506 1.5673402e-006, + -0.7730608 -0.63433182 0, + -0.30896395 0.95107377 0, + 0.961263 -0.27563301 -4.53545e-006, + 0.66912705 -0.74314809 -2.8283603e-006, + 0.66913283 -0.74314284 0, + -0.95106435 0.30899313 3.8449014e-007, + -0.9510631 0.30899704 0, + -0.95107764 0.30895188 0, + 0.84796584 -0.53005087 0, + 0.8480444 -0.52992523 -1.0536805e-005, + 0.84805131 -0.5299142 0, + 0.96125978 -0.27564394 0, + 0.9612655 -0.27562389 0, + -0.30896395 -0.95107377 0, + -0.30909085 -0.95103252 1.1704694e-006, + -0.30910105 -0.95102924 0, + 0.66912282 -0.74315184 0, + 0.95103252 0.30909085 1.1704694e-006, + -0.30895188 0.95107764 0, + -0.30899313 0.95106435 3.8449014e-007, + 0.95107377 0.30896395 0, + 0.95102924 0.30910105 0, + 0.30902407 -0.95105422 0, + 0.30898407 -0.95106721 0, + 0.11477399 -0.83500886 0.53813297, + 0.10584998 -0.83785784 0.53552788, + -0.24190497 -0.9702999 0, + -0.24192096 -0.97029591 0, + -0.61570489 -0.7879768 0, + 0.30895188 0.95107764 0, + -0.61565387 -0.7880168 0, + -0.8090142 -0.58778912 0, + -0.93969166 -0.34202287 0, + -0.93983054 -0.34164086 0, + -0.93969166 0.34202287 0, + -0.61461222 0.57403719 0.54104817, + -0.61464995 0.57399696 0.54104793, + -0.53073889 0.65241981 0.54098487, + -0.53078294 0.65238392 0.54098493, + -0.43705779 0.71879363 0.54066277, + -0.43710184 0.71876675 0.54066283, + -0.33529484 0.77194065 0.54007876, + -0.33532012 0.77192932 0.54007918, + -0.40759394 0.74139994 0.53309792, + -0.31131694 0.78628981 0.53369486, + -0.22726394 0.81090981 0.5392369, + -0.2272069 0.81092662 0.53923577, + -0.24192096 0.97029591 0, + -0.24190806 0.97029924 -2.3747004e-006, + -0.11477399 0.83500886 0.53813297, + -0.11474297 0.83501381 0.53813189, + -0.21017903 0.81861609 0.53450209, + -0.10584998 0.83785784 0.53552788, + -0.24190497 0.9702999 0, + -0.95107377 -0.30896395 0, + 0.95107377 -0.30896395 0, + 0.95103252 -0.30909085 1.1704694e-006, + 0.95102924 -0.30910105 0, + -0.95107764 -0.30895188 0, + -0.95106435 -0.30899313 3.8449014e-007, + -0.9510631 -0.30899704 0, + 0.76605588 0.64277393 0, + 0.84796584 0.53005087 0, + 0.8480444 0.52992523 -1.0536805e-005, + 0.74707907 0.38709405 0.54039907, + 0.74705708 0.38713506 0.54040009, + 0.71446383 0.45341089 0.53287888, + 0.76537567 0.36016488 0.53336781, + 0.79326838 0.28188014 0.53969324, + 0.79324698 0.281939 0.53969401, + 0.96125978 0.27564394 0, + 0.9612655 0.27562389 0, + 0.8413009 0.057643194 0.53748494, + 0.84130889 0.057545993 0.53748292, + 0.84130889 -0.057545993 0.53748292, + 0.8413009 -0.057643294 0.53748494, + 0.8248713 -0.17139307 0.53871316, + 0.8248648 -0.17142196 0.53871387, + 0.79324698 -0.281939 0.53969401, + 0.79326838 -0.28188014 0.53969324, + 0.74707907 -0.38709405 0.54039907, + 0.74705708 -0.38713506 0.54040009, + 0.68716198 -0.48506001 0.540856, + 0.687181 -0.48503301 0.540856, + 0.61461222 -0.57403719 0.54104817, + 0.61464995 -0.57399696 0.54104793, + 0.53073889 -0.65241981 0.54098487, + 0.53078294 -0.65238392 0.54098493, + 0.43705779 -0.71879363 0.54066277, + 0.43710184 -0.71876675 0.54066283, + 0.33532012 -0.77192932 0.54007918, + 0.33529484 -0.77194065 0.54007876, + 0.22726394 -0.81090981 0.5392369, + 0.2272069 -0.81092662 0.53923577, + 0.11474297 -0.83501381 0.53813189, + 0.21017903 -0.81861609 0.53450209, + -0.11477399 -0.83500886 0.53813297, + -0.11474297 -0.83501381 0.53813189, + -0.2272069 -0.81092662 0.53923577, + -0.22726394 -0.81090981 0.5392369, + -0.33529484 -0.77194065 0.54007876, + -0.33532012 -0.77192932 0.54007918, + -0.43710184 -0.71876675 0.54066283, + -0.43705779 -0.71879363 0.54066277, + -0.53078294 -0.65238392 0.54098493, + -0.53073889 -0.65241981 0.54098487, + -0.61464995 -0.57399696 0.54104793, + -0.61461222 -0.57403719 0.54104817, + -0.687181 -0.48503301 0.540856, + -0.68716198 -0.48506001 0.540856, + -0.74705708 -0.38713506 0.54040009, + -0.74707907 -0.38709405 0.54039907, + -0.79326838 -0.28188014 0.53969324, + -0.79324698 -0.281939 0.53969401, + -0.8248648 -0.17142196 0.53871387, + -0.8248713 -0.17139307 0.53871316, + -0.8413009 -0.057643294 0.53748494, + -0.84130889 -0.057545993 0.53748292, + -0.84130889 0.057545993 0.53748292, + -0.8413009 0.057643194 0.53748494, + -0.8248713 0.17139307 0.53871316, + -0.8248648 0.17142196 0.53871387, + -0.79324698 0.281939 0.53969401, + -0.79326838 0.28188014 0.53969324, + -0.74707907 0.38709405 0.54039907, + -0.74705708 0.38713506 0.54040009, + -0.68716198 0.48506001 0.540856, + -0.687181 0.48503301 0.540856, + -0.65213102 0.53949702 0.53260499, + 0 0.84373111 0.53676605, + 0 -0.84373111 0.53676605, + 0.91354579 0.4067359 0, + -0.89100474 -0.45399389 0, + -0.98768973 -0.15642595 0, + -0.70711237 -0.70710135 0, + 0.034906086 0.99939054 0, + 0.17364293 0.98480862 0, + -0.98768973 0.15642595 0, + -0.45397401 0.89101499 0, + -0.70711237 0.70710135 0, + -0.89100474 0.45399389 0, + 0 0 1, + 0.43837184 0.8987937 0, + 0.071349524 -0.99745136 0, + 0.21255289 -0.97714955 0, + -0.071349524 -0.99745136 0, + 0 -1 0, + -0.12533703 -0.99211425 0, + -0.21255289 -0.97714955 0, + -0.34945503 -0.93695313 0, + -0.47926387 -0.87767076 0, + -0.684551 -0.72896498 0, + -0.58778626 -0.80901629 0, + -0.48175889 -0.87630373 0, + -0.36812803 -0.92977512 0, + -0.24868298 -0.9685849 0, + -0.59927464 -0.80054355 0, + -0.77050912 -0.63742906 0, + -0.9048239 -0.42578593 0, + -0.84432912 -0.53582507 0, + -0.70710677 -0.70710677 0, + -0.80054355 -0.59927464 0, + -0.87767076 -0.47926387 0, + -0.93695313 -0.34945503 0, + -0.95106077 -0.30900395 0, + -0.98228598 0.187388 0, + -0.99802691 0.062787995 0, + -0.99802691 -0.062787995 0, + -0.98228598 -0.187388 0, + -0.97714955 -0.21255289 0, + 0.80054355 0.59927464 0, + 0.87767076 0.47926387 0, + 0.95106077 0.30900395 0, + 0.9048239 0.42578593 0, + 0.93695313 0.34945503 0, + 0.97714955 0.21255289 0, + 0.98228598 0.187388 0, + 0.97714955 -0.21255289 0, + 0.99745136 -0.07134942 0, + 0.70710677 -0.70710677 0, + 0.80054355 -0.59927464 0, + 0.93695313 -0.34945503 0, + 0.87767076 -0.47926387 0, + 0 0 -1, + 0.99745136 0.071349524 0, + 0.59927464 -0.80054355 0, + 0.36812803 -0.92977512 0, + 0.48175889 -0.87630373 0, + 0.58778626 -0.80901629 0, + 0.684551 -0.72896498 0, + 0.77050912 -0.63742906 0, + 0.84432912 -0.53582507 0, + 0.9048239 -0.42578593 0, + 0.95106077 -0.30900395 0, + 0.98228598 -0.187388 0, + 0.99802691 -0.062787995 0, + 0.99802691 0.062787995 0, + -0.99745136 -0.07134942 0, + -0.99745136 0.071349524 0, + -0.95106077 0.30900395 0, + -0.87767076 0.47926387 0, + -0.93695313 0.34945503 0, + -0.97714955 0.21255289 0, + -0.84432912 0.53582507 0, + -0.9048239 0.42578593 0, + -0.21255289 0.97714955 0, + -0.071349524 0.99745136 0, + 0.12533703 0.99211425 0, + 0 1 0, + 0.071349524 0.99745136 0, + 0.21255289 0.97714955 0, + 0.24868298 0.9685849 0, + 0.34945503 0.93695313 0, + 0.47926387 0.87767076 0, + 0.684551 0.72896498 0, + 0.58778626 0.80901629 0, + 0.48175889 0.87630373 0, + 0.36812803 0.92977512 0, + 0.59927464 0.80054355 0, + 0.77050912 0.63742906 0, + -0.58776021 -0.8090353 0, + -0.12533703 0.99211425 0, + -0.34945503 0.93695313 0, + -0.58778626 0.80901629 0, + -0.684551 0.72896498 0, + -0.59927464 0.80054355 0, + -0.70710677 0.70710677 0, + -0.80054355 0.59927464 0, + -0.77050912 0.63742906 0, + -0.97814775 0.20791095 0, + 0.70711237 -0.70710135 0, + 0.89100474 -0.45399389 0, + 0.98768973 -0.15642595 0, + -0.58776021 0.8090353 0, + -0.58768964 0.8090865 0, + -0.80903566 0.58775967 0, + -0.47140688 -0.88191575 0, + 0.88191575 -0.47140688 0, + 0.95693725 -0.29029506 0, + -0.45399389 -0.89100474 0, + -0.70710135 -0.70711237 0, + -0.89101499 -0.45397401 0, + -0.15642595 -0.98768973 0, + -0.98769343 -0.15640192 0, + -0.45399389 0.89100474 0, + -0.15642595 0.98768973 0, + -0.89101499 0.45397401 0, + -0.98769343 0.15640192 0, + -0.70710135 0.70711237 0, + 0.15642595 0.98768973 0, + 0.45399389 0.89100474 0, + 0.70710135 0.70711237 0, + 0.89101499 0.45397401 0, + 0.98769343 0.15640192 0, + 0.98769343 -0.15640192 0, + 0.89101499 -0.45397401 0, + 0.70710135 -0.70711237 0, + 0.45399389 -0.89100474 0, + 0.99518573 0.098006979 0, + 0.95693725 0.29029506 0, + -0.45397401 -0.89101499 0, + -0.15640192 -0.98769343 0, + 0.15640192 -0.98769343 0, + 0.80903471 -0.58776075 0, + 0.58769006 -0.80908614 0, + -1 0 0, + -0.95104289 -0.30905896 0, + -0.80908567 -0.58769071 0, + 0.47140688 0.88191575 0, + -0.30896211 0.95107436 0, + 0.58776021 0.8090353 0, + 0.80903471 0.58776075 0, + 1 0 0, + -0.80908614 0.58769006 0, + -0.58769071 -0.80908567 0, + -0.30905986 -0.95104253 0, + 0.88191575 0.47140688 0, + 0.29029506 0.95693725 0, + 0.098006979 0.99518573 0, + -0.098006979 0.99518573 0, + -0.99518573 0.098006979 0, + -0.99518573 -0.098006979 0, + -0.95693725 0.29029506 0, + -0.88191575 0.47140688 0, + 0.30905986 -0.95104253 0, + 0.80908567 -0.58769071 0, + 0.95104289 -0.30905896 0, + -0.29029506 0.95693725 0, + -0.47140688 0.88191575 0, + -0.95693725 -0.29029506 0, + -0.88191575 -0.47140688 0, + 0.99518573 -0.098006979 0, + -0.30896211 -0.95107436 0, + -0.49999395 0.8660289 0, + -0.37461188 0.92718166 0, + 0.98768973 0.15642595 0, + 0.89100474 0.45399389 0, + 0.58768964 0.8090865 0, + 0.80903566 0.58775967 0, + 0.95107436 0.30896211 0, + 0.58776021 -0.8090353 0, + -0.95104253 0.30905986 0, + -0.30905986 0.95104253 0, + 0.47140688 -0.88191575 0, + 0.29029506 -0.95693725 0, + 0.098006979 -0.99518573 0, + -0.098006979 -0.99518573 0, + -0.29029506 -0.95693725 0, + 0.30905986 0.95104253 0, + 0.80908567 0.58769071 0, + 0.95104253 0.30905986 0, + 0.76604772 -0.64278376 0, + -0.95107436 -0.30896211 0, + -0.80903471 -0.58776075 0, + -0.80903471 0.58776075 0, + 0.91354579 -0.4067359 0, + 0.99026555 -0.13919094 0, + 0.15642595 -0.98768973 0, + 0.30896211 0.95107436 0, + 0.43837184 -0.8987937 0, + 0.17364293 -0.98480862 0, + 0.70711237 0.70710135 0, + 0.45397401 0.89101499 0, + -0.15640192 0.98769343 0, + 0.15640192 0.98769343 0, + 0.034906086 -0.99939054 0, + 0.47926387 -0.87767076 0, + 0.34945503 -0.93695313 0, + 0.24868298 -0.9685849 0, + 0.12533703 -0.99211425 0, + -0.10453601 -0.99452114 0, + 0.45397401 -0.89101499 0, + -0.37461188 -0.92718166 0, + -0.49999395 -0.8660289 0, + -0.71934307 -0.69465506 0, + 0.95107436 -0.30896211 0, + -0.88294691 -0.46947294 0, + -0.97814775 -0.20791095 0, + -0.99756336 -0.069766626 0, + -0.99756336 0.069766626 0, + -0.88294691 0.46947294 0, + -0.48175889 0.87630373 0, + -0.36812803 0.92977512 0, + -0.24868298 0.9685849 0, + -0.47926387 0.87767076 0, + -0.10453601 0.99452114 0, + 0.30896211 -0.95107436 0, + -0.95107436 0.30896211 0, + 0.84432912 0.53582507 0, + 0.70710677 0.70710677 0, + 0.99026555 0.13919094 0, + 0.55920291 0.82903081 2.9648794e-007, + -0.80901498 -0.58778799 0, + 0.55920291 -0.82903081 0, + -0.80901498 0.58778799 -4.46713e-008 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 4, 3, -1, 7, 5, 4, -1, + 8, 9, 10, -1, 11, 12, 13, -1, + 14, 15, 16, -1, 17, 18, 19, -1, + 20, 21, 22, -1, 23, 24, 18, -1, + 25, 26, 23, -1, 27, 28, 25, -1, + 29, 30, 27, -1, 22, 31, 29, -1, + 15, 32, 33, -1, 32, 17, 34, -1, + 35, 36, 11, -1, 37, 38, 35, -1, + 37, 39, 38, -1, 39, 14, 40, -1, + 41, 42, 43, -1, 44, 45, 46, -1, + 47, 46, 45, -1, 47, 45, 48, -1, + 45, 49, 48, -1, 50, 51, 52, -1, + 51, 53, 54, -1, 53, 55, 56, -1, + 55, 57, 58, -1, 59, 60, 57, -1, + 61, 62, 59, -1, 63, 64, 61, -1, + 65, 66, 63, -1, 67, 68, 65, -1, + 69, 70, 67, -1, 69, 44, 70, -1, + 71, 72, 73, -1, 13, 74, 71, -1, + 75, 76, 8, -1, 77, 78, 79, -1, + 80, 79, 78, -1, 81, 82, 83, -1, + 81, 83, 84, -1, 85, 84, 83, -1, + 86, 87, 85, -1, 88, 85, 87, -1, + 88, 84, 85, -1, 89, 87, 86, -1, + 89, 86, 90, -1, 91, 90, 86, -1, + 10, 92, 91, -1, 93, 83, 82, -1, + 94, 93, 82, -1, 94, 95, 93, -1, + 80, 96, 97, -1, 98, 96, 80, -1, + 98, 80, 78, -1, 99, 100, 101, -1, + 102, 101, 100, -1, 103, 99, 101, -1, + 104, 90, 91, -1, 104, 91, 92, -1, + 105, 92, 10, -1, 105, 10, 9, -1, + 106, 9, 8, -1, 106, 8, 76, -1, + 107, 108, 109, -1, 108, 110, 111, -1, + 112, 113, 114, -1, 115, 113, 112, -1, + 116, 117, 118, -1, 119, 120, 121, -1, + 122, 123, 124, -1, 125, 126, 127, -1, + 128, 129, 130, -1, 131, 132, 133, -1, + 134, 133, 132, -1, 135, 136, 137, -1, + 138, 137, 136, -1, 139, 136, 135, -1, + 140, 141, 142, -1, 140, 143, 141, -1, + 144, 141, 143, -1, 145, 144, 143, -1, + 146, 147, 148, -1, 149, 148, 147, -1, + 150, 151, 152, -1, 153, 152, 151, -1, + 154, 152, 153, -1, 155, 156, 157, -1, + 158, 159, 156, -1, 159, 157, 156, -1, + 160, 142, 161, -1, 161, 142, 141, -1, + 162, 163, 164, -1, 162, 165, 163, -1, + 166, 163, 165, -1, 167, 166, 165, -1, + 168, 164, 169, -1, 169, 164, 163, -1, + 170, 171, 172, -1, 173, 172, 171, -1, + 174, 175, 176, -1, 175, 177, 176, -1, + 178, 179, 177, -1, 180, 181, 182, -1, + 183, 180, 182, -1, 184, 178, 185, -1, + 184, 179, 178, -1, 186, 182, 181, -1, + 187, 188, 189, -1, 190, 189, 191, -1, + 191, 189, 188, -1, 192, 177, 179, -1, + 192, 176, 177, -1, 193, 194, 195, -1, + 193, 196, 194, -1, 197, 198, 199, -1, + 200, 199, 198, -1, 201, 197, 199, -1, + 202, 203, 196, -1, 203, 194, 196, -1, + 204, 195, 194, -1, 205, 195, 204, -1, + 206, 207, 208, -1, 207, 209, 208, -1, + 210, 208, 209, -1, 210, 209, 211, -1, + 212, 211, 209, -1, 213, 211, 212, -1, + 214, 133, 134, -1, 215, 216, 217, -1, + 218, 219, 220, -1, 221, 219, 218, -1, + 222, 223, 224, -1, 225, 224, 223, -1, + 226, 222, 224, -1, 227, 228, 229, -1, + 228, 230, 229, -1, 231, 229, 230, -1, + 232, 215, 217, -1, 233, 217, 216, -1, + 234, 235, 236, -1, 235, 237, 236, -1, + 238, 236, 237, -1, 239, 220, 219, -1, + 240, 241, 242, -1, 243, 130, 244, -1, + 244, 130, 129, -1, 245, 241, 240, -1, + 246, 242, 241, -1, 247, 127, 126, -1, + 248, 125, 127, -1, 249, 250, 251, -1, + 252, 251, 250, -1, 253, 124, 123, -1, + 254, 122, 124, -1, 255, 120, 119, -1, + 256, 146, 148, -1, 257, 121, 120, -1, + 258, 259, 260, -1, 261, 118, 117, -1, + 262, 116, 118, -1, 263, 114, 113, -1, + 264, 110, 265, -1, 264, 111, 110, -1, + 266, 108, 111, -1, 266, 109, 108, -1, + 267, 107, 109, -1, 267, 268, 107, -1, + 269, 270, 271, -1, 269, 271, 268, -1, + 271, 107, 268, -1, 272, 271, 270, -1, + 273, 272, 270, -1, 273, 274, 272, -1, + 275, 276, 277, -1, 277, 276, 278, -1, + 279, 280, 281, -1, 279, 281, 274, -1, + 281, 272, 274, -1, 282, 281, 280, -1, + 283, 278, 276, -1, 284, 171, 170, -1, + 285, 286, 287, -1, 286, 288, 287, -1, + 289, 287, 288, -1, 290, 291, 292, -1, + 292, 291, 293, -1, 294, 293, 291, -1, + 295, 97, 96, -1, 295, 2, 97, -1, + 97, 2, 1, -1, 296, 297, 298, -1, + 296, 298, 95, -1, 298, 93, 95, -1, + 49, 298, 297, -1, 299, 49, 297, -1, + 299, 48, 49, -1, 300, 42, 41, -1, + 301, 43, 42, -1, 302, 44, 46, -1, + 302, 70, 44, -1, 303, 67, 70, -1, + 303, 68, 67, -1, 304, 65, 68, -1, + 304, 66, 65, -1, 305, 63, 66, -1, + 305, 64, 63, -1, 306, 61, 64, -1, + 306, 62, 61, -1, 307, 59, 62, -1, + 307, 60, 59, -1, 308, 57, 60, -1, + 308, 58, 57, -1, 309, 55, 58, -1, + 309, 56, 55, -1, 310, 53, 56, -1, + 310, 54, 53, -1, 311, 51, 54, -1, + 311, 52, 51, -1, 312, 50, 52, -1, + 312, 313, 50, -1, 249, 251, 313, -1, + 251, 50, 313, -1, 314, 22, 21, -1, + 314, 31, 22, -1, 315, 29, 31, -1, + 315, 30, 29, -1, 316, 27, 30, -1, + 316, 28, 27, -1, 317, 25, 28, -1, + 317, 26, 25, -1, 318, 23, 26, -1, + 318, 24, 23, -1, 319, 18, 24, -1, + 319, 19, 18, -1, 320, 17, 19, -1, + 320, 34, 17, -1, 321, 32, 34, -1, + 321, 33, 32, -1, 322, 15, 33, -1, + 322, 16, 15, -1, 323, 14, 16, -1, + 323, 40, 14, -1, 324, 39, 40, -1, + 324, 38, 39, -1, 325, 35, 38, -1, + 325, 36, 35, -1, 326, 11, 36, -1, + 326, 12, 11, -1, 327, 13, 12, -1, + 327, 74, 13, -1, 328, 71, 74, -1, + 328, 72, 71, -1, 329, 73, 72, -1, + 329, 265, 73, -1, 73, 265, 110, -1, + 76, 75, 330, -1, 330, 75, 282, -1, + 330, 282, 331, -1, 331, 282, 280, -1, + 250, 332, 252, -1, 252, 332, 333, -1, + 252, 333, 20, -1, 20, 333, 21, -1, + 0, 300, 1, -1, 1, 300, 41, -1, + 334, 335, 336, -1, 336, 335, 337, -1, + 336, 338, 334, -1, 334, 338, 339, -1, + 335, 340, 337, -1, 337, 340, 341, -1, + 342, 343, 344, -1, 344, 343, 345, -1, + 344, 6, 342, -1, 342, 6, 3, -1, + 338, 346, 339, -1, 339, 346, 347, -1, + 348, 349, 350, -1, 350, 349, 351, -1, + 350, 352, 348, -1, 348, 352, 353, -1, + 352, 347, 353, -1, 353, 347, 346, -1, + 353, 346, 348, -1, 348, 346, 349, -1, + 346, 338, 349, -1, 349, 338, 336, -1, + 349, 336, 337, -1, 337, 341, 349, -1, + 349, 341, 354, -1, 349, 354, 355, -1, + 355, 356, 349, -1, 349, 356, 357, -1, + 356, 358, 357, -1, 357, 358, 359, -1, + 357, 359, 360, -1, 360, 359, 361, -1, + 361, 359, 362, -1, 362, 359, 363, -1, + 363, 359, 364, -1, 364, 359, 365, -1, + 7, 366, 5, -1, 5, 366, 367, -1, + 368, 369, 370, -1, 370, 369, 371, -1, + 370, 372, 368, -1, 368, 372, 373, -1, + 369, 374, 371, -1, 371, 374, 375, -1, + 376, 377, 20, -1, 20, 377, 252, -1, + 20, 22, 376, -1, 376, 22, 378, -1, + 379, 375, 380, -1, 380, 375, 374, -1, + 380, 381, 379, -1, 379, 381, 382, -1, + 381, 383, 382, -1, 382, 383, 384, -1, + 23, 18, 385, -1, 385, 18, 386, -1, + 385, 387, 23, -1, 23, 387, 25, -1, + 387, 388, 25, -1, 25, 388, 27, -1, + 388, 389, 27, -1, 27, 389, 29, -1, + 389, 378, 29, -1, 29, 378, 22, -1, + 383, 390, 384, -1, 384, 390, 391, -1, + 18, 17, 386, -1, 386, 17, 392, -1, + 32, 15, 393, -1, 393, 15, 394, -1, + 393, 392, 32, -1, 32, 392, 17, -1, + 390, 395, 391, -1, 391, 395, 396, -1, + 395, 397, 396, -1, 396, 397, 398, -1, + 397, 399, 398, -1, 398, 399, 400, -1, + 399, 401, 400, -1, 400, 401, 402, -1, + 15, 14, 394, -1, 394, 14, 403, -1, + 35, 11, 404, -1, 404, 11, 405, -1, + 404, 406, 35, -1, 35, 406, 37, -1, + 406, 407, 37, -1, 37, 407, 39, -1, + 407, 403, 39, -1, 39, 403, 14, -1, + 401, 408, 402, -1, 402, 408, 409, -1, + 410, 411, 412, -1, 412, 411, 413, -1, + 412, 414, 410, -1, 410, 414, 415, -1, + 49, 45, 416, -1, 416, 45, 417, -1, + 416, 418, 49, -1, 49, 418, 298, -1, + 414, 419, 415, -1, 415, 419, 420, -1, + 419, 421, 420, -1, 420, 421, 422, -1, + 45, 44, 417, -1, 417, 44, 423, -1, + 424, 425, 426, -1, 426, 425, 427, -1, + 426, 428, 424, -1, 424, 428, 429, -1, + 430, 431, 432, -1, 432, 431, 433, -1, + 432, 434, 430, -1, 430, 434, 435, -1, + 425, 436, 427, -1, 427, 436, 437, -1, + 436, 435, 437, -1, 437, 435, 434, -1, + 437, 434, 427, -1, 427, 434, 426, -1, + 434, 432, 426, -1, 426, 432, 428, -1, + 428, 432, 422, -1, 422, 432, 433, -1, + 422, 433, 438, -1, 438, 439, 422, -1, + 422, 439, 372, -1, 422, 372, 370, -1, + 370, 371, 422, -1, 422, 371, 375, -1, + 422, 375, 379, -1, 379, 382, 422, -1, + 422, 382, 384, -1, 422, 384, 391, -1, + 391, 396, 422, -1, 422, 396, 398, -1, + 422, 398, 400, -1, 400, 402, 422, -1, + 422, 402, 409, -1, 422, 409, 420, -1, + 420, 409, 415, -1, 415, 409, 410, -1, + 410, 409, 411, -1, 411, 409, 440, -1, + 440, 409, 441, -1, 441, 409, 442, -1, + 442, 409, 443, -1, 443, 409, 444, -1, + 444, 409, 445, -1, 445, 409, 446, -1, + 446, 409, 447, -1, 446, 447, 448, -1, + 446, 448, 449, -1, 449, 448, 450, -1, + 448, 451, 450, -1, 450, 451, 452, -1, + 450, 452, 453, -1, 453, 454, 450, -1, + 450, 454, 455, -1, 450, 455, 456, -1, + 428, 422, 429, -1, 429, 422, 421, -1, + 431, 457, 433, -1, 433, 457, 438, -1, + 51, 50, 458, -1, 458, 50, 459, -1, + 458, 460, 51, -1, 51, 460, 53, -1, + 460, 461, 53, -1, 53, 461, 55, -1, + 461, 462, 55, -1, 55, 462, 57, -1, + 462, 463, 57, -1, 57, 463, 59, -1, + 463, 464, 59, -1, 59, 464, 61, -1, + 464, 465, 61, -1, 61, 465, 63, -1, + 465, 466, 63, -1, 63, 466, 65, -1, + 466, 467, 65, -1, 65, 467, 67, -1, + 467, 468, 67, -1, 67, 468, 69, -1, + 468, 423, 69, -1, 69, 423, 44, -1, + 408, 469, 409, -1, 409, 469, 447, -1, + 469, 470, 447, -1, 447, 470, 448, -1, + 11, 13, 405, -1, 405, 13, 471, -1, + 472, 473, 452, -1, 452, 473, 453, -1, + 452, 451, 472, -1, 472, 451, 474, -1, + 451, 448, 474, -1, 474, 448, 470, -1, + 71, 73, 475, -1, 475, 73, 476, -1, + 475, 471, 71, -1, 71, 471, 13, -1, + 446, 449, 477, -1, 477, 449, 478, -1, + 477, 479, 446, -1, 446, 479, 445, -1, + 75, 8, 480, -1, 480, 8, 481, -1, + 480, 482, 75, -1, 75, 482, 282, -1, + 479, 483, 445, -1, 445, 483, 444, -1, + 483, 484, 444, -1, 444, 484, 443, -1, + 8, 10, 481, -1, 481, 10, 485, -1, + 442, 443, 486, -1, 486, 443, 484, -1, + 486, 487, 442, -1, 442, 487, 441, -1, + 85, 83, 488, -1, 488, 83, 489, -1, + 488, 490, 85, -1, 85, 490, 86, -1, + 490, 491, 86, -1, 86, 491, 91, -1, + 491, 485, 91, -1, 91, 485, 10, -1, + 487, 492, 441, -1, 441, 492, 440, -1, + 83, 93, 489, -1, 489, 93, 493, -1, + 100, 99, 494, -1, 494, 99, 293, -1, + 293, 99, 292, -1, 292, 99, 495, -1, + 495, 99, 496, -1, 496, 99, 497, -1, + 497, 99, 132, -1, 132, 99, 134, -1, + 99, 498, 134, -1, 134, 498, 499, -1, + 134, 499, 500, -1, 500, 288, 134, -1, + 134, 288, 286, -1, 134, 286, 501, -1, + 501, 286, 502, -1, 286, 503, 502, -1, + 502, 503, 504, -1, 503, 505, 504, -1, + 100, 494, 102, -1, 102, 494, 506, -1, + 103, 507, 99, -1, 99, 507, 498, -1, + 482, 508, 282, -1, 282, 508, 281, -1, + 449, 450, 478, -1, 478, 450, 509, -1, + 108, 107, 510, -1, 510, 107, 511, -1, + 510, 512, 108, -1, 108, 512, 110, -1, + 513, 514, 455, -1, 455, 514, 456, -1, + 455, 454, 513, -1, 513, 454, 515, -1, + 454, 453, 515, -1, 515, 453, 473, -1, + 512, 476, 110, -1, 110, 476, 73, -1, + 112, 516, 115, -1, 115, 516, 517, -1, + 518, 519, 520, -1, 520, 519, 521, -1, + 520, 522, 518, -1, 518, 522, 523, -1, + 522, 524, 523, -1, 523, 524, 525, -1, + 128, 526, 129, -1, 129, 526, 527, -1, + 131, 528, 132, -1, 132, 528, 497, -1, + 528, 529, 497, -1, 497, 529, 496, -1, + 206, 530, 207, -1, 207, 530, 531, -1, + 532, 204, 533, -1, 533, 204, 194, -1, + 533, 194, 203, -1, 203, 534, 533, -1, + 533, 534, 535, -1, 533, 535, 536, -1, + 536, 537, 533, -1, 533, 537, 538, -1, + 538, 537, 539, -1, 539, 537, 531, -1, + 531, 537, 207, -1, 207, 537, 209, -1, + 209, 537, 212, -1, 212, 537, 540, -1, + 540, 537, 541, -1, 541, 537, 542, -1, + 541, 542, 161, -1, 161, 141, 541, -1, + 541, 141, 144, -1, 541, 144, 543, -1, + 543, 544, 541, -1, 541, 544, 545, -1, + 541, 545, 546, -1, 546, 547, 541, -1, + 541, 547, 169, -1, 541, 169, 163, -1, + 541, 163, 548, -1, 548, 163, 549, -1, + 549, 163, 550, -1, 550, 163, 166, -1, + 202, 551, 203, -1, 203, 551, 534, -1, + 551, 552, 534, -1, 534, 552, 535, -1, + 553, 554, 555, -1, 555, 554, 556, -1, + 555, 557, 553, -1, 553, 557, 558, -1, + 557, 559, 558, -1, 558, 559, 560, -1, + 554, 561, 556, -1, 556, 561, 562, -1, + 559, 563, 560, -1, 560, 563, 564, -1, + 565, 566, 567, -1, 567, 566, 568, -1, + 567, 569, 565, -1, 565, 569, 570, -1, + 571, 572, 573, -1, 573, 572, 574, -1, + 573, 564, 571, -1, 571, 564, 563, -1, + 572, 568, 574, -1, 574, 568, 566, -1, + 568, 572, 567, -1, 567, 572, 571, -1, + 567, 571, 569, -1, 569, 571, 575, -1, + 575, 571, 576, -1, 576, 571, 577, -1, + 577, 571, 578, -1, 578, 571, 579, -1, + 579, 571, 580, -1, 580, 571, 581, -1, + 581, 571, 582, -1, 582, 571, 583, -1, + 571, 563, 583, -1, 583, 563, 559, -1, + 583, 559, 557, -1, 557, 555, 583, -1, + 583, 555, 556, -1, 583, 556, 562, -1, + 569, 575, 570, -1, 570, 575, 584, -1, + 575, 576, 584, -1, 584, 576, 585, -1, + 576, 577, 585, -1, 585, 577, 586, -1, + 577, 578, 586, -1, 586, 578, 587, -1, + 578, 579, 587, -1, 587, 579, 588, -1, + 579, 580, 588, -1, 588, 580, 589, -1, + 580, 581, 589, -1, 589, 581, 590, -1, + 581, 582, 590, -1, 590, 582, 591, -1, + 582, 583, 591, -1, 591, 583, 592, -1, + 537, 536, 593, -1, 593, 536, 594, -1, + 593, 595, 537, -1, 537, 595, 542, -1, + 596, 597, 598, -1, 598, 597, 599, -1, + 598, 600, 596, -1, 596, 600, 601, -1, + 597, 602, 599, -1, 599, 602, 603, -1, + 604, 605, 606, -1, 606, 605, 607, -1, + 606, 608, 604, -1, 604, 608, 609, -1, + 605, 610, 607, -1, 607, 610, 611, -1, + 610, 605, 603, -1, 603, 605, 604, -1, + 603, 604, 609, -1, 603, 609, 599, -1, + 599, 609, 598, -1, 598, 609, 600, -1, + 600, 609, 612, -1, 609, 613, 612, -1, + 612, 613, 519, -1, 612, 519, 518, -1, + 518, 523, 612, -1, 612, 523, 525, -1, + 612, 525, 614, -1, 612, 614, 615, -1, + 615, 614, 616, -1, 614, 617, 616, -1, + 616, 617, 618, -1, 616, 618, 619, -1, + 610, 603, 611, -1, 611, 603, 602, -1, + 608, 620, 609, -1, 609, 620, 613, -1, + 621, 622, 623, -1, 623, 622, 624, -1, + 623, 137, 621, -1, 621, 137, 138, -1, + 135, 625, 139, -1, 139, 625, 626, -1, + 158, 627, 159, -1, 159, 627, 628, -1, + 627, 629, 628, -1, 628, 629, 630, -1, + 629, 631, 630, -1, 630, 631, 632, -1, + 145, 633, 144, -1, 144, 633, 543, -1, + 634, 635, 636, -1, 636, 635, 637, -1, + 636, 146, 634, -1, 634, 146, 256, -1, + 147, 146, 638, -1, 638, 146, 151, -1, + 151, 146, 153, -1, 153, 146, 639, -1, + 146, 636, 639, -1, 639, 636, 637, -1, + 639, 637, 640, -1, 640, 157, 639, -1, + 639, 157, 159, -1, 639, 159, 628, -1, + 628, 630, 639, -1, 639, 630, 632, -1, + 639, 632, 641, -1, 641, 625, 639, -1, + 639, 625, 135, -1, 639, 135, 137, -1, + 137, 623, 639, -1, 639, 623, 624, -1, + 147, 638, 149, -1, 149, 638, 642, -1, + 150, 642, 151, -1, 151, 642, 638, -1, + 153, 639, 154, -1, 154, 639, 643, -1, + 635, 644, 637, -1, 637, 644, 640, -1, + 644, 155, 640, -1, 640, 155, 157, -1, + 631, 645, 632, -1, 632, 645, 641, -1, + 645, 626, 641, -1, 641, 626, 625, -1, + 161, 542, 160, -1, 160, 542, 595, -1, + 633, 646, 543, -1, 543, 646, 544, -1, + 646, 647, 544, -1, 544, 647, 545, -1, + 647, 648, 545, -1, 545, 648, 546, -1, + 548, 549, 649, -1, 649, 549, 650, -1, + 649, 651, 548, -1, 548, 651, 541, -1, + 549, 550, 650, -1, 650, 550, 652, -1, + 550, 166, 652, -1, 652, 166, 167, -1, + 234, 653, 235, -1, 235, 653, 654, -1, + 653, 655, 654, -1, 654, 655, 656, -1, + 655, 657, 656, -1, 656, 657, 658, -1, + 657, 659, 658, -1, 658, 659, 660, -1, + 659, 661, 660, -1, 660, 661, 662, -1, + 661, 245, 662, -1, 662, 245, 240, -1, + 547, 546, 663, -1, 663, 546, 648, -1, + 663, 168, 547, -1, 547, 168, 169, -1, + 651, 664, 541, -1, 541, 664, 540, -1, + 664, 213, 540, -1, 540, 213, 212, -1, + 536, 535, 594, -1, 594, 535, 552, -1, + 173, 665, 172, -1, 172, 665, 666, -1, + 665, 667, 666, -1, 666, 667, 668, -1, + 666, 668, 172, -1, 172, 668, 170, -1, + 170, 668, 669, -1, 669, 668, 670, -1, + 670, 668, 671, -1, 671, 668, 672, -1, + 672, 668, 673, -1, 673, 668, 197, -1, + 197, 668, 198, -1, 198, 668, 674, -1, + 674, 668, 675, -1, 675, 668, 676, -1, + 675, 676, 191, -1, 191, 188, 675, -1, + 675, 188, 677, -1, 675, 677, 181, -1, + 181, 180, 675, -1, 675, 180, 678, -1, + 667, 679, 668, -1, 668, 679, 676, -1, + 174, 680, 175, -1, 175, 680, 681, -1, + 680, 275, 681, -1, 681, 275, 277, -1, + 364, 365, 682, -1, 682, 365, 683, -1, + 682, 684, 364, -1, 364, 684, 363, -1, + 684, 685, 363, -1, 363, 685, 362, -1, + 686, 200, 674, -1, 674, 200, 198, -1, + 674, 675, 686, -1, 686, 675, 687, -1, + 675, 678, 687, -1, 687, 678, 688, -1, + 678, 180, 688, -1, 688, 180, 183, -1, + 181, 677, 186, -1, 186, 677, 689, -1, + 187, 689, 188, -1, 188, 689, 677, -1, + 191, 676, 190, -1, 190, 676, 679, -1, + 670, 671, 690, -1, 690, 671, 691, -1, + 690, 692, 670, -1, 670, 692, 669, -1, + 671, 672, 691, -1, 691, 672, 693, -1, + 672, 673, 693, -1, 693, 673, 694, -1, + 673, 197, 694, -1, 694, 197, 201, -1, + 204, 532, 205, -1, 205, 532, 695, -1, + 532, 533, 695, -1, 695, 533, 696, -1, + 533, 538, 696, -1, 696, 538, 697, -1, + 538, 539, 697, -1, 697, 539, 698, -1, + 539, 531, 698, -1, 698, 531, 530, -1, + 285, 699, 286, -1, 286, 699, 503, -1, + 700, 214, 501, -1, 501, 214, 134, -1, + 501, 502, 700, -1, 700, 502, 701, -1, + 502, 504, 701, -1, 701, 504, 702, -1, + 504, 505, 702, -1, 702, 505, 703, -1, + 505, 503, 703, -1, 703, 503, 699, -1, + 704, 705, 706, -1, 706, 705, 707, -1, + 706, 708, 704, -1, 704, 708, 709, -1, + 710, 711, 712, -1, 712, 711, 713, -1, + 712, 714, 710, -1, 710, 714, 715, -1, + 711, 716, 713, -1, 713, 716, 717, -1, + 714, 707, 715, -1, 715, 707, 705, -1, + 227, 221, 228, -1, 228, 221, 218, -1, + 718, 719, 720, -1, 720, 719, 721, -1, + 720, 722, 718, -1, 718, 722, 723, -1, + 719, 222, 721, -1, 721, 222, 226, -1, + 719, 718, 222, -1, 222, 718, 223, -1, + 223, 718, 527, -1, 527, 718, 129, -1, + 718, 723, 129, -1, 129, 723, 237, -1, + 129, 237, 235, -1, 235, 654, 129, -1, + 129, 654, 656, -1, 129, 656, 658, -1, + 658, 660, 129, -1, 129, 660, 662, -1, + 129, 662, 240, -1, 129, 240, 244, -1, + 244, 240, 724, -1, 724, 240, 725, -1, + 725, 240, 242, -1, 725, 242, 726, -1, + 223, 527, 225, -1, 225, 527, 526, -1, + 230, 215, 231, -1, 231, 215, 232, -1, + 727, 728, 729, -1, 729, 728, 730, -1, + 729, 731, 727, -1, 727, 731, 732, -1, + 728, 733, 730, -1, 730, 733, 734, -1, + 731, 735, 732, -1, 732, 735, 736, -1, + 735, 737, 736, -1, 736, 737, 738, -1, + 736, 738, 732, -1, 732, 738, 727, -1, + 727, 738, 728, -1, 728, 738, 733, -1, + 733, 738, 739, -1, 739, 738, 740, -1, + 738, 708, 740, -1, 740, 708, 706, -1, + 740, 706, 707, -1, 707, 714, 740, -1, + 740, 714, 712, -1, 740, 712, 713, -1, + 713, 717, 740, -1, 740, 717, 741, -1, + 740, 741, 742, -1, 742, 743, 740, -1, + 740, 743, 744, -1, 743, 745, 744, -1, + 737, 709, 738, -1, 738, 709, 708, -1, + 216, 746, 233, -1, 233, 746, 747, -1, + 746, 748, 747, -1, 747, 748, 749, -1, + 733, 739, 734, -1, 734, 739, 750, -1, + 739, 740, 750, -1, 750, 740, 751, -1, + 742, 741, 752, -1, 752, 741, 753, -1, + 752, 754, 742, -1, 742, 754, 743, -1, + 755, 751, 744, -1, 744, 751, 740, -1, + 744, 745, 755, -1, 755, 745, 756, -1, + 745, 743, 756, -1, 756, 743, 754, -1, + 237, 723, 238, -1, 238, 723, 722, -1, + 757, 243, 724, -1, 724, 243, 244, -1, + 724, 725, 757, -1, 757, 725, 758, -1, + 246, 759, 242, -1, 242, 759, 726, -1, + 759, 758, 726, -1, 726, 758, 725, -1, + 760, 247, 761, -1, 761, 247, 126, -1, + 248, 762, 125, -1, 125, 762, 763, -1, + 618, 617, 764, -1, 764, 617, 765, -1, + 764, 766, 618, -1, 618, 766, 619, -1, + 617, 614, 765, -1, 765, 614, 767, -1, + 615, 616, 768, -1, 768, 616, 769, -1, + 768, 770, 615, -1, 615, 770, 612, -1, + 616, 619, 769, -1, 769, 619, 766, -1, + 762, 771, 763, -1, 763, 771, 772, -1, + 439, 438, 773, -1, 773, 438, 457, -1, + 773, 373, 439, -1, 439, 373, 372, -1, + 774, 459, 251, -1, 251, 459, 50, -1, + 251, 252, 774, -1, 774, 252, 377, -1, + 771, 253, 772, -1, 772, 253, 123, -1, + 614, 525, 767, -1, 767, 525, 524, -1, + 770, 601, 612, -1, 612, 601, 600, -1, + 620, 521, 613, -1, 613, 521, 519, -1, + 254, 775, 122, -1, 122, 775, 776, -1, + 775, 255, 776, -1, 776, 255, 119, -1, + 257, 258, 121, -1, 121, 258, 260, -1, + 639, 624, 643, -1, 643, 624, 622, -1, + 777, 261, 778, -1, 778, 261, 117, -1, + 262, 779, 116, -1, 116, 779, 780, -1, + 779, 781, 780, -1, 780, 781, 782, -1, + 781, 517, 782, -1, 782, 517, 516, -1, + 583, 562, 592, -1, 592, 562, 561, -1, + 263, 783, 114, -1, 114, 783, 784, -1, + 107, 271, 511, -1, 511, 271, 785, -1, + 271, 272, 785, -1, 785, 272, 786, -1, + 272, 281, 786, -1, 786, 281, 508, -1, + 514, 509, 456, -1, 456, 509, 450, -1, + 343, 278, 345, -1, 345, 278, 283, -1, + 354, 341, 787, -1, 787, 341, 340, -1, + 787, 788, 354, -1, 354, 788, 355, -1, + 788, 789, 355, -1, 355, 789, 356, -1, + 358, 356, 790, -1, 790, 356, 789, -1, + 790, 791, 358, -1, 358, 791, 359, -1, + 349, 357, 351, -1, 351, 357, 792, -1, + 357, 360, 792, -1, 792, 360, 793, -1, + 791, 683, 359, -1, 359, 683, 365, -1, + 685, 794, 362, -1, 362, 794, 361, -1, + 794, 793, 361, -1, 361, 793, 360, -1, + 170, 669, 284, -1, 284, 669, 692, -1, + 288, 500, 289, -1, 289, 500, 795, -1, + 500, 499, 795, -1, 795, 499, 796, -1, + 499, 498, 796, -1, 796, 498, 507, -1, + 529, 797, 496, -1, 496, 797, 495, -1, + 797, 290, 495, -1, 495, 290, 292, -1, + 494, 293, 506, -1, 506, 293, 294, -1, + 93, 298, 493, -1, 493, 298, 418, -1, + 492, 413, 440, -1, 440, 413, 411, -1, + 741, 717, 753, -1, 753, 717, 716, -1, + 301, 749, 43, -1, 43, 749, 748, -1, + 366, 798, 367, -1, 367, 798, 79, -1, + 798, 77, 79, -1, 260, 259, 778, -1, + 778, 259, 777, -1, 239, 799, 220, -1, + 220, 799, 761, -1, 799, 760, 761, -1, + 783, 185, 784, -1, 784, 185, 178, -1, + 570, 584, 118, -1, 118, 584, 262, -1, + 584, 585, 262, -1, 262, 585, 779, -1, + 585, 586, 779, -1, 779, 586, 587, -1, + 779, 587, 781, -1, 781, 587, 588, -1, + 781, 588, 589, -1, 781, 589, 517, -1, + 517, 589, 590, -1, 517, 590, 591, -1, + 517, 591, 115, -1, 115, 591, 592, -1, + 115, 592, 113, -1, 113, 592, 561, -1, + 113, 561, 800, -1, 800, 561, 554, -1, + 800, 554, 553, -1, 553, 558, 800, -1, + 800, 558, 560, -1, 800, 560, 564, -1, + 800, 564, 801, -1, 801, 564, 573, -1, + 801, 573, 574, -1, 574, 566, 801, -1, + 801, 566, 565, -1, 801, 565, 570, -1, + 570, 118, 801, -1, 801, 118, 138, -1, + 801, 138, 136, -1, 136, 139, 801, -1, + 801, 139, 626, -1, 801, 626, 142, -1, + 142, 626, 645, -1, 142, 645, 631, -1, + 142, 631, 140, -1, 140, 631, 143, -1, + 631, 629, 143, -1, 143, 629, 627, -1, + 143, 627, 802, -1, 802, 627, 158, -1, + 802, 158, 156, -1, 156, 155, 802, -1, + 802, 155, 124, -1, 802, 124, 524, -1, + 524, 124, 767, -1, 767, 124, 765, -1, + 765, 124, 253, -1, 765, 253, 764, -1, + 764, 253, 766, -1, 253, 771, 766, -1, + 766, 771, 769, -1, 771, 762, 769, -1, + 769, 762, 768, -1, 768, 762, 770, -1, + 770, 762, 248, -1, 770, 248, 601, -1, + 601, 248, 596, -1, 248, 127, 596, -1, + 596, 127, 597, -1, 524, 522, 802, -1, + 802, 522, 520, -1, 802, 520, 521, -1, + 521, 620, 802, -1, 802, 620, 608, -1, + 802, 608, 803, -1, 803, 608, 606, -1, + 803, 606, 607, -1, 607, 611, 803, -1, + 803, 611, 602, -1, 803, 602, 597, -1, + 597, 127, 803, -1, 803, 127, 246, -1, + 803, 246, 241, -1, 241, 245, 803, -1, + 803, 245, 661, -1, 803, 661, 164, -1, + 164, 661, 659, -1, 164, 659, 657, -1, + 164, 657, 162, -1, 162, 657, 165, -1, + 657, 655, 165, -1, 165, 655, 653, -1, + 165, 653, 804, -1, 804, 653, 234, -1, + 804, 234, 236, -1, 165, 804, 167, -1, + 167, 804, 652, -1, 652, 804, 650, -1, + 650, 804, 649, -1, 164, 168, 803, -1, + 803, 168, 663, -1, 803, 663, 648, -1, + 648, 647, 803, -1, 803, 647, 802, -1, + 647, 646, 802, -1, 802, 646, 633, -1, + 802, 633, 145, -1, 145, 143, 802, -1, + 246, 127, 759, -1, 759, 127, 247, -1, + 759, 247, 758, -1, 758, 247, 760, -1, + 758, 760, 757, -1, 757, 760, 799, -1, + 757, 799, 243, -1, 243, 799, 130, -1, + 799, 239, 130, -1, 130, 239, 128, -1, + 239, 219, 128, -1, 128, 219, 526, -1, + 526, 219, 225, -1, 225, 219, 805, -1, + 225, 805, 224, -1, 224, 805, 226, -1, + 226, 805, 721, -1, 721, 805, 806, -1, + 721, 806, 720, -1, 720, 806, 722, -1, + 722, 806, 238, -1, 238, 806, 236, -1, + 236, 806, 804, -1, 804, 806, 807, -1, + 804, 807, 808, -1, 808, 807, 133, -1, + 808, 133, 214, -1, 214, 700, 808, -1, + 808, 700, 211, -1, 808, 211, 213, -1, + 213, 664, 808, -1, 808, 664, 651, -1, + 808, 651, 649, -1, 649, 804, 808, -1, + 700, 701, 211, -1, 211, 701, 702, -1, + 211, 702, 210, -1, 210, 702, 208, -1, + 702, 703, 208, -1, 208, 703, 699, -1, + 208, 699, 809, -1, 809, 699, 285, -1, + 809, 285, 287, -1, 208, 809, 206, -1, + 206, 809, 530, -1, 530, 809, 698, -1, + 698, 809, 697, -1, 133, 807, 131, -1, + 131, 807, 528, -1, 528, 807, 529, -1, + 529, 807, 797, -1, 219, 221, 805, -1, + 805, 221, 227, -1, 805, 227, 229, -1, + 805, 229, 806, -1, 806, 229, 231, -1, + 806, 231, 232, -1, 232, 217, 806, -1, + 806, 217, 735, -1, 806, 735, 731, -1, + 731, 729, 806, -1, 806, 729, 730, -1, + 806, 730, 734, -1, 734, 750, 806, -1, + 806, 750, 807, -1, 750, 751, 807, -1, + 807, 751, 755, -1, 807, 755, 756, -1, + 756, 754, 807, -1, 807, 754, 752, -1, + 807, 752, 42, -1, 42, 752, 753, -1, + 42, 753, 716, -1, 42, 716, 301, -1, + 301, 716, 711, -1, 301, 711, 710, -1, + 710, 715, 301, -1, 301, 715, 749, -1, + 749, 715, 747, -1, 747, 715, 705, -1, + 747, 705, 704, -1, 747, 704, 233, -1, + 233, 704, 709, -1, 233, 709, 217, -1, + 217, 709, 737, -1, 217, 737, 735, -1, + 42, 300, 807, -1, 807, 300, 0, -1, + 807, 0, 2, -1, 155, 644, 124, -1, + 124, 644, 254, -1, 644, 635, 254, -1, + 254, 635, 775, -1, 775, 635, 255, -1, + 255, 635, 634, -1, 255, 634, 120, -1, + 120, 634, 256, -1, 120, 256, 148, -1, + 120, 148, 257, -1, 257, 148, 149, -1, + 257, 149, 642, -1, 257, 642, 258, -1, + 258, 642, 150, -1, 258, 150, 152, -1, + 258, 152, 259, -1, 259, 152, 154, -1, + 259, 154, 643, -1, 259, 643, 777, -1, + 777, 643, 622, -1, 777, 622, 261, -1, + 261, 622, 621, -1, 261, 621, 118, -1, + 118, 621, 138, -1, 142, 160, 801, -1, + 801, 160, 595, -1, 801, 595, 593, -1, + 593, 594, 801, -1, 801, 594, 800, -1, + 594, 552, 800, -1, 800, 552, 551, -1, + 800, 551, 202, -1, 202, 196, 800, -1, + 800, 196, 694, -1, 800, 694, 201, -1, + 201, 199, 800, -1, 800, 199, 200, -1, + 800, 200, 113, -1, 113, 200, 686, -1, + 113, 686, 263, -1, 263, 686, 687, -1, + 263, 687, 783, -1, 783, 687, 688, -1, + 783, 688, 185, -1, 185, 688, 183, -1, + 185, 183, 182, -1, 185, 182, 184, -1, + 184, 182, 186, -1, 184, 186, 179, -1, + 179, 186, 689, -1, 179, 689, 187, -1, + 694, 196, 693, -1, 693, 196, 691, -1, + 196, 193, 691, -1, 691, 193, 195, -1, + 691, 195, 690, -1, 690, 195, 692, -1, + 692, 195, 810, -1, 810, 195, 205, -1, + 810, 205, 695, -1, 695, 696, 810, -1, + 810, 696, 697, -1, 810, 697, 809, -1, + 692, 810, 284, -1, 284, 810, 171, -1, + 810, 811, 171, -1, 171, 811, 173, -1, + 173, 811, 665, -1, 665, 811, 667, -1, + 667, 811, 679, -1, 679, 811, 812, -1, + 679, 812, 190, -1, 190, 812, 189, -1, + 189, 812, 187, -1, 187, 812, 179, -1, + 179, 812, 192, -1, 192, 812, 176, -1, + 812, 811, 176, -1, 176, 811, 174, -1, + 174, 811, 680, -1, 680, 811, 275, -1, + 275, 811, 276, -1, 276, 811, 682, -1, + 276, 682, 683, -1, 683, 791, 276, -1, + 276, 791, 283, -1, 791, 790, 283, -1, + 283, 790, 789, -1, 283, 789, 345, -1, + 345, 789, 788, -1, 345, 788, 344, -1, + 344, 788, 787, -1, 344, 787, 340, -1, + 344, 340, 6, -1, 6, 340, 335, -1, + 6, 335, 334, -1, 6, 334, 4, -1, + 4, 334, 339, -1, 4, 339, 813, -1, + 813, 339, 347, -1, 813, 347, 352, -1, + 352, 350, 813, -1, 813, 350, 351, -1, + 813, 351, 792, -1, 4, 813, 7, -1, + 7, 813, 366, -1, 366, 813, 798, -1, + 798, 813, 814, -1, 798, 814, 77, -1, + 77, 814, 78, -1, 682, 811, 684, -1, + 684, 811, 685, -1, 685, 811, 794, -1, + 794, 811, 793, -1, 793, 811, 792, -1, + 792, 811, 813, -1, 811, 810, 813, -1, + 813, 810, 809, -1, 813, 809, 287, -1, + 287, 289, 813, -1, 813, 289, 795, -1, + 813, 795, 796, -1, 796, 507, 813, -1, + 813, 507, 814, -1, 507, 103, 814, -1, + 814, 103, 101, -1, 814, 101, 102, -1, + 814, 102, 815, -1, 815, 102, 506, -1, + 815, 506, 294, -1, 814, 815, 78, -1, + 78, 815, 98, -1, 98, 815, 96, -1, + 96, 815, 816, -1, 96, 816, 295, -1, + 295, 816, 2, -1, 2, 816, 807, -1, + 807, 816, 797, -1, 797, 816, 290, -1, + 290, 816, 291, -1, 291, 816, 294, -1, + 294, 816, 815, -1, 3, 5, 105, -1, + 105, 5, 92, -1, 92, 5, 104, -1, + 104, 5, 367, -1, 104, 367, 90, -1, + 90, 367, 89, -1, 367, 79, 89, -1, + 89, 79, 87, -1, 87, 79, 88, -1, + 88, 79, 84, -1, 79, 80, 84, -1, + 84, 80, 81, -1, 81, 80, 82, -1, + 82, 80, 97, -1, 82, 97, 94, -1, + 94, 97, 95, -1, 97, 1, 95, -1, + 95, 1, 296, -1, 296, 1, 297, -1, + 297, 1, 41, -1, 297, 41, 299, -1, + 299, 41, 48, -1, 41, 43, 48, -1, + 48, 43, 47, -1, 47, 43, 46, -1, + 46, 43, 748, -1, 46, 748, 302, -1, + 302, 748, 70, -1, 748, 746, 70, -1, + 70, 746, 303, -1, 303, 746, 68, -1, + 68, 746, 216, -1, 68, 216, 304, -1, + 304, 216, 66, -1, 216, 215, 66, -1, + 66, 215, 305, -1, 305, 215, 64, -1, + 64, 215, 230, -1, 64, 230, 306, -1, + 306, 230, 62, -1, 230, 228, 62, -1, + 62, 228, 307, -1, 307, 228, 60, -1, + 60, 228, 218, -1, 60, 218, 308, -1, + 308, 218, 58, -1, 218, 220, 58, -1, + 58, 220, 309, -1, 309, 220, 56, -1, + 56, 220, 310, -1, 220, 761, 310, -1, + 310, 761, 54, -1, 54, 761, 311, -1, + 311, 761, 126, -1, 311, 126, 52, -1, + 52, 126, 312, -1, 126, 125, 312, -1, + 312, 125, 313, -1, 313, 125, 249, -1, + 249, 125, 763, -1, 249, 763, 250, -1, + 250, 763, 332, -1, 763, 772, 332, -1, + 332, 772, 333, -1, 333, 772, 21, -1, + 21, 772, 123, -1, 21, 123, 314, -1, + 314, 123, 31, -1, 123, 122, 31, -1, + 31, 122, 315, -1, 315, 122, 30, -1, + 30, 122, 776, -1, 30, 776, 316, -1, + 316, 776, 28, -1, 28, 776, 317, -1, + 317, 776, 119, -1, 317, 119, 26, -1, + 26, 119, 318, -1, 119, 121, 318, -1, + 318, 121, 24, -1, 24, 121, 319, -1, + 319, 121, 260, -1, 319, 260, 19, -1, + 19, 260, 320, -1, 260, 778, 320, -1, + 320, 778, 34, -1, 34, 778, 321, -1, + 321, 778, 117, -1, 321, 117, 33, -1, + 33, 117, 322, -1, 117, 116, 322, -1, + 322, 116, 16, -1, 16, 116, 323, -1, + 323, 116, 780, -1, 323, 780, 40, -1, + 40, 780, 324, -1, 780, 782, 324, -1, + 324, 782, 38, -1, 38, 782, 325, -1, + 325, 782, 516, -1, 325, 516, 36, -1, + 36, 516, 326, -1, 516, 112, 326, -1, + 326, 112, 12, -1, 12, 112, 327, -1, + 327, 112, 114, -1, 327, 114, 74, -1, + 74, 114, 328, -1, 114, 784, 328, -1, + 328, 784, 72, -1, 72, 784, 329, -1, + 329, 784, 178, -1, 329, 178, 265, -1, + 265, 178, 264, -1, 178, 177, 264, -1, + 264, 177, 111, -1, 111, 177, 266, -1, + 266, 177, 175, -1, 266, 175, 109, -1, + 109, 175, 267, -1, 175, 681, 267, -1, + 267, 681, 268, -1, 268, 681, 269, -1, + 269, 681, 270, -1, 681, 277, 270, -1, + 270, 277, 273, -1, 273, 277, 274, -1, + 274, 277, 278, -1, 274, 278, 279, -1, + 279, 278, 280, -1, 278, 343, 280, -1, + 280, 343, 331, -1, 331, 343, 330, -1, + 330, 343, 342, -1, 330, 342, 76, -1, + 76, 342, 106, -1, 342, 3, 106, -1, + 106, 3, 9, -1, 3, 105, 9, -1, + 368, 373, 774, -1, 774, 373, 459, -1, + 373, 773, 459, -1, 459, 773, 458, -1, + 773, 457, 458, -1, 458, 457, 460, -1, + 460, 457, 461, -1, 461, 457, 431, -1, + 461, 431, 462, -1, 462, 431, 430, -1, + 462, 430, 463, -1, 463, 430, 435, -1, + 463, 435, 464, -1, 464, 435, 436, -1, + 464, 436, 465, -1, 465, 436, 425, -1, + 465, 425, 466, -1, 466, 425, 424, -1, + 466, 424, 467, -1, 467, 424, 429, -1, + 467, 429, 468, -1, 468, 429, 423, -1, + 429, 421, 423, -1, 423, 421, 417, -1, + 421, 419, 417, -1, 417, 419, 416, -1, + 419, 414, 416, -1, 416, 414, 418, -1, + 414, 412, 418, -1, 418, 412, 493, -1, + 412, 413, 493, -1, 493, 413, 489, -1, + 413, 492, 489, -1, 489, 492, 488, -1, + 492, 487, 488, -1, 488, 487, 490, -1, + 490, 487, 491, -1, 491, 487, 486, -1, + 491, 486, 485, -1, 485, 486, 484, -1, + 485, 484, 481, -1, 481, 484, 483, -1, + 481, 483, 480, -1, 480, 483, 479, -1, + 480, 479, 482, -1, 482, 479, 477, -1, + 482, 477, 508, -1, 508, 477, 478, -1, + 508, 478, 786, -1, 786, 478, 509, -1, + 786, 509, 785, -1, 785, 509, 514, -1, + 785, 514, 511, -1, 511, 514, 510, -1, + 514, 513, 510, -1, 510, 513, 512, -1, + 513, 515, 512, -1, 512, 515, 476, -1, + 515, 473, 476, -1, 476, 473, 475, -1, + 473, 472, 475, -1, 475, 472, 471, -1, + 472, 474, 471, -1, 471, 474, 405, -1, + 474, 470, 405, -1, 405, 470, 404, -1, + 470, 469, 404, -1, 404, 469, 406, -1, + 406, 469, 407, -1, 407, 469, 408, -1, + 407, 408, 403, -1, 403, 408, 401, -1, + 403, 401, 394, -1, 394, 401, 399, -1, + 394, 399, 393, -1, 393, 399, 397, -1, + 393, 397, 392, -1, 392, 397, 395, -1, + 392, 395, 386, -1, 386, 395, 390, -1, + 386, 390, 385, -1, 385, 390, 383, -1, + 385, 383, 387, -1, 387, 383, 388, -1, + 383, 381, 388, -1, 388, 381, 389, -1, + 381, 380, 389, -1, 389, 380, 378, -1, + 380, 374, 378, -1, 378, 374, 376, -1, + 374, 369, 376, -1, 376, 369, 377, -1, + 369, 368, 377, -1, 377, 368, 774, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 258, 258, 258, -1, + 258, 258, 258, -1, 258, 258, 258, -1, + 259, 259, 259, -1, 259, 259, 259, -1, + 259, 259, 259, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 260, 260, 260, -1, + 261, 261, 261, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 262, 262, 262, -1, + 263, 263, 263, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 264, 264, 264, -1, + 265, 265, 265, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 266, 266, 266, -1, + 267, 267, 267, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 268, 268, 268, -1, + 269, 269, 269, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 271, 271, 271, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 272, 272, 272, -1, + 273, 273, 273, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 274, 274, 274, -1, + 275, 275, 275, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 276, 276, 276, -1, + 277, 277, 277, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 278, 278, 278, -1, + 279, 279, 279, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 280, 280, 280, -1, + 281, 281, 281, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 282, 282, 282, -1, + 283, 283, 283, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 284, 284, 284, -1, + 285, 285, 285, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 286, 286, 286, -1, + 287, 287, 287, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 288, 288, 288, -1, + 289, 289, 289, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 290, 290, 290, -1, + 291, 291, 291, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 292, 292, 292, -1, + 293, 293, 293, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 294, 294, 294, -1, + 295, 295, 295, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 296, 296, 296, -1, + 297, 297, 297, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 298, 298, 298, -1, + 299, 299, 299, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 300, 300, 300, -1, + 301, 301, 301, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 302, 302, 302, -1, + 303, 303, 303, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 304, 304, 304, -1, + 305, 305, 305, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 306, 306, 306, -1, + 307, 307, 307, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 308, 308, 308, -1, + 309, 309, 309, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 310, 310, 310, -1, + 311, 311, 311, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 313, 313, 313, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 314, 314, 314, -1, + 315, 315, 315, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 316, 316, 316, -1, + 317, 317, 317, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 318, 318, 318, -1, + 319, 319, 319, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 320, 320, 320, -1, + 321, 321, 321, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 322, 322, 322, -1, + 323, 323, 323, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 324, 324, 324, -1, + 325, 325, 325, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 326, 326, 326, -1, + 327, 327, 327, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 328, 328, 328, -1, + 329, 329, 329, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 330, 330, 330, -1, + 331, 331, 331, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 332, 332, 332, -1, + 333, 333, 333, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 334, 334, 334, -1, + 335, 335, 335, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 336, 336, 336, -1, + 337, 337, 337, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 338, 338, 338, -1, + 339, 339, 339, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 340, 340, 340, -1, + 341, 341, 341, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 342, 342, 342, -1, + 343, 343, 343, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 344, 344, 344, -1, + 345, 345, 345, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 346, 346, 346, -1, + 347, 347, 347, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 348, 348, 348, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 349, 349, 349, -1, 349, 349, 349, -1, + 275, 275, 275, -1, 275, 275, 275, -1, + 350, 350, 350, -1, 350, 350, 350, -1, + 351, 351, 351, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 352, 352, 352, -1, + 353, 353, 353, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 354, 354, 354, -1, + 355, 355, 355, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 356, 356, 356, -1, + 357, 357, 357, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 358, 358, 358, -1, + 359, 359, 359, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 360, 360, 360, -1, + 361, 361, 361, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 362, 362, 362, -1, + 363, 363, 363, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 364, 364, 364, -1, + 365, 365, 365, -1, 365, 365, 365, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 366, 366, 366, -1, 366, 366, 366, -1, + 367, 367, 367, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 368, 368, 368, -1, + 369, 369, 369, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 370, 370, 370, -1, + 371, 371, 371, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 372, 372, 372, -1, + 373, 373, 373, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 374, 374, 374, -1, + 375, 375, 375, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 376, 376, 376, -1, + 377, 377, 377, -1, 377, 377, 377, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 378, 378, 378, -1, 378, 378, 378, -1, + 379, 379, 379, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 380, 380, 380, -1, + 381, 381, 381, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 382, 382, 382, -1, + 383, 383, 383, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 384, 384, 384, -1, + 385, 385, 385, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 386, 386, 386, -1, + 387, 387, 387, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 388, 388, 388, -1, + 266, 266, 266, -1, 266, 266, 266, -1, + 269, 269, 269, -1, 269, 269, 269, -1, + 262, 262, 262, -1, 262, 262, 262, -1, + 389, 389, 389, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 390, 390, 390, -1, + 263, 263, 263, -1, 263, 263, 263, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 261, 261, 261, -1, 261, 261, 261, -1, + 391, 391, 391, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 392, 392, 392, -1, + 393, 393, 393, -1, 393, 393, 393, -1, + 275, 275, 275, -1, 275, 275, 275, -1, + 394, 394, 394, -1, 394, 394, 394, -1, + 395, 395, 395, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 396, 396, 396, -1, + 397, 397, 397, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 398, 398, 398, -1, + 337, 337, 337, -1, 337, 337, 337, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 399, 399, 399, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 400, 400, 400, -1, + 401, 401, 401, -1, 401, 401, 401, -1, + 362, 362, 362, -1, 362, 362, 362, -1, + 402, 402, 402, -1, 402, 402, 402, -1, + 403, 403, 403, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 404, 404, 404, -1, + 405, 405, 405, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 406, 406, 406, -1, + 407, 407, 407, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 408, 408, 408, -1, + 409, 409, 409, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 410, 410, 410, -1, + 411, 411, 411, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 412, 412, 412, -1, + 275, 275, 275, -1, 275, 275, 275, -1, + 413, 413, 413, -1, 413, 413, 413, -1, + 393, 393, 393, -1, 393, 393, 393, -1, + 414, 414, 414, -1, 414, 414, 414, -1, + 415, 415, 415, -1, 415, 415, 415, -1, + 401, 401, 401, -1, 401, 401, 401, -1, + 416, 416, 416, -1, 416, 416, 416, -1, + 417, 417, 417, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 418, 418, 418, -1, + 419, 419, 419, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 420, 420, 420, -1, + 396, 396, 396, -1, 396, 396, 396, -1, + 349, 349, 349, -1, 349, 349, 349, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 421, 421, 421, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 422, 422, 422, -1, + 423, 423, 423, -1, 423, 423, 423, -1, + 361, 361, 361, -1, 361, 361, 361, -1, + 424, 424, 424, -1, 424, 424, 424, -1, + 425, 425, 425, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 426, 426, 426, -1, + 427, 427, 427, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 428, 428, 428, -1, + 401, 401, 401, -1, 401, 401, 401, -1, + 392, 392, 392, -1, 392, 392, 392, -1, + 429, 429, 429, -1, 429, 429, 429, -1, + 275, 275, 275, -1, 275, 275, 275, -1, + 402, 402, 402, -1, 402, 402, 402, -1, + 430, 430, 430, -1, 430, 430, 430, -1, + 363, 363, 363, -1, 363, 363, 363, -1, + 431, 431, 431, -1, 431, 431, 431, -1, + 337, 337, 337, -1, 337, 337, 337, -1, + 432, 432, 432, -1, 432, 432, 432, -1, + 433, 433, 433, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 434, 434, 434, -1, + 435, 435, 435, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 436, 436, 436, -1, + 401, 401, 401, -1, 401, 401, 401, -1, + 337, 337, 337, -1, 337, 337, 337, -1, + 437, 437, 437, -1, 437, 437, 437, -1, + 426, 426, 426, -1, 426, 426, 426, -1, + 438, 438, 438, -1, 438, 438, 438, -1, + 439, 439, 439, -1, 439, 439, 439, -1, + 375, 375, 375, -1, 375, 375, 375, -1, + 377, 377, 377, -1, 377, 377, 377, -1, + 370, 370, 370, -1, 370, 370, 370, -1, + 372, 372, 372, -1, 372, 372, 372, -1, + 369, 369, 369, -1, 369, 369, 369, -1, + 376, 376, 376, -1, 376, 376, 376, -1, + 440, 440, 440, -1, 440, 440, 440, -1, + 441, 441, 441, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 442, 442, 442, -1, + 394, 394, 394, -1, 394, 394, 394, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 443, 443, 443, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 444, 444, 444, -1, + 380, 380, 380, -1, 380, 380, 380, -1, + 379, 379, 379, -1, 379, 379, 379, -1, + 381, 381, 381, -1, 381, 381, 381, -1, + 378, 378, 378, -1, 378, 378, 378, -1, + 374, 374, 374, -1, 374, 374, 374, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 373, 373, 373, -1, 373, 373, 373, -1, + 445, 445, 445, -1, 445, 445, 445, -1, + 401, 401, 401, -1, 401, 401, 401, -1, + 382, 382, 382, -1, 382, 382, 382, -1, + 383, 383, 383, -1, 383, 383, 383, -1, + 371, 371, 371, -1, 371, 371, 371, -1, + 446, 446, 446, -1, 446, 446, 446, -1, + 384, 384, 384, -1, 384, 384, 384, -1, + 385, 385, 385, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 386, 386, 386, -1, + 403, 403, 403, -1, 403, 403, 403, -1, + 337, 337, 337, -1, 337, 337, 337, -1, + 447, 447, 447, -1, 447, 447, 447, -1, + 438, 438, 438, -1, 438, 438, 438, -1, + 399, 399, 399, -1, 399, 399, 399, -1, + 448, 448, 448, -1, 448, 448, 448, -1, + 449, 449, 449, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 450, 450, 450, -1, + 451, 451, 451, -1, 451, 451, 451, -1, + 425, 425, 425, -1, 425, 425, 425, -1, + 452, 452, 452, -1, 452, 452, 452, -1, + 267, 267, 267, -1, 267, 267, 267, -1, + 453, 453, 453, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 454, 454, 454, -1, + 455, 455, 455, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 456, 456, 456, -1, + 457, 457, 457, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 458, 458, 458, -1, + 459, 459, 459, -1, 459, 459, 459, -1, + 424, 424, 424, -1, 424, 424, 424, -1, + 268, 268, 268, -1, 268, 268, 268, -1, + 460, 460, 460, -1, 460, 460, 460, -1, + 461, 461, 461, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 462, 462, 462, -1, + 463, 463, 463, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 464, 464, 464, -1, + 465, 465, 465, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 466, 466, 466, -1, + 467, 467, 467, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 468, 468, 468, -1, + 446, 446, 446, -1, 446, 446, 446, -1, + 469, 469, 469, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 470, 470, 470, -1, + 471, 471, 471, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 472, 472, 472, -1, + 473, 473, 473, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 474, 474, 474, -1, + 389, 389, 389, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 390, 390, 390, -1, + 391, 391, 391, -1, 391, 391, 391, -1, + 460, 460, 460, -1, 460, 460, 460, -1, + 359, 359, 359, -1, 359, 359, 359, -1, + 452, 452, 452, -1, 452, 452, 452, -1, + 453, 453, 453, -1, 453, 453, 453, -1, + 360, 360, 360, -1, 360, 360, 360, -1, + 450, 450, 450, -1, 450, 450, 450, -1, + 451, 451, 451, -1, 451, 451, 451, -1, + 394, 394, 394, -1, 394, 394, 394, -1, + 414, 414, 414, -1, 414, 414, 414, -1, + 429, 429, 429, -1, 429, 429, 429, -1, + 475, 475, 475, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 476, 476, 476, -1, + 394, 394, 394, -1, 394, 394, 394, -1, + 442, 442, 442, -1, 442, 442, 442, -1, + 477, 477, 477, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 478, 478, 478, -1, + 368, 368, 368, -1, 368, 368, 368, -1, + 479, 479, 479, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 480, 480, 480, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 481, 481, 481, -1, 482, 482, 482, -1, + 482, 482, 482, -1, 482, 482, 482, -1, + 483, 483, 483, -1, 483, 483, 483, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 270, 270, 270, -1, 270, 270, 270, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1, + 312, 312, 312, -1, 312, 312, 312, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-lwr4-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-lwr4-right.wrl new file mode 100644 index 0000000..dfc0b15 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-lwr4-right.wrl @@ -0,0 +1,161 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF link0 Transform { + children [ +# Inline { +# url "link0-right.wrl" +# } +# Transform { +# translation 0.05 0 0.03 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# } +# } +# geometry Box { +# size 0.1 0.1 0.06 +# } +# } +# ] +# } + ] + } + DEF link1 Transform { + rotation 1 0 0 1.570796 + translation 0 0 0.31 + children [ + Inline { + url "link1-right.wrl" + } + ] + } + DEF link2 Transform { + translation 0 0 0.31 + children [ + Inline { + url "link2-right.wrl" + } + ] + } + DEF link3 Transform { + rotation 1 0 0 -1.570796 + translation 0 0 0.71 + children [ + Inline { + url "link3-right.wrl" + } + ] + } + DEF link4 Transform { + translation 0 0 0.71 + children [ + Inline { + url "link4-right.wrl" + } + ] + } + DEF link5 Transform { + rotation 1 0 0 1.570796 + translation 0 0 1.1 + children [ + Inline { + url "link5-right.wrl" + } + ] + } + DEF link6 Transform { + translation 0 0 1.1 + children [ + Inline { + url "link6-right.wrl" + } + ] + } + DEF link7 Transform { + translation 0 0 1.1 + children [ + Inline { + url "link7-right.wrl" + } + Transform { + rotation 1 0 0 1.570796 + translation 0 0 0.1 + children [ + Shape { + appearance Appearance { + material Material { + } + } + geometry Cylinder { + radius 0.045 + height 0.055 + } + } + ] + } + Transform { + rotation 0 0 1 1.570796 + translation 0 0 0.165 #0.12 + children [ + Shape { + appearance Appearance { + material Material { + } + } + geometry Box { + size 0.22 0.07 0.08 + } + } + Transform { + translation 0.08 0 0.08 + children [ + Shape { + appearance Appearance { + material Material { + #transparency 0.5 + } + } + geometry Box { + size 0.02 0.05 0.10 + } + } + ] + } + Transform { + translation -0.08 0 0.08 + children [ + Shape { + appearance Appearance { + material Material { + #transparency 0.5 + #diffuseColor 0.3 0.3 0.3 + } + } + geometry Box { + size 0.02 0.05 0.10 + } + } + ] + } + Transform { + translation 0.11 0 -0.02 + children [ + Shape { + appearance Appearance { + material Material { + } + } + geometry Box { + size 0.06 0.03 0.04 + } + } + ] + } + ] + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-swiwel.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-swiwel.wrl new file mode 100644 index 0000000..89f48fa --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/kuka-swiwel.wrl @@ -0,0 +1,9206 @@ +#VRML V2.0 utf8 + + +Group { + children [ + Group { + children + Group { + children + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.17649999 0.17649999 0.17649999 + specularColor 0.74510002 0.74510002 0.74510002 + shininess 0.021299999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.0048316303 -0.059805103 0.119, + -0.010955201 -0.058991406 0.119, + -0.0079039205 -0.059477102 0.10200001, + -0.058072705 -0.015085101 0.119, + -0.059316006 -0.0090340506 0.119, + -0.058772303 -0.0120756 0.10200001, + -0.033327099 0.049893003 0.119, + -0.028020401 0.053055201 0.119, + -0.0307144 0.051542401 0.10200001, + 0.038590305 0.045943301 0.10200001, + 0.036174003 0.047869001 0.119, + 0.040904205 0.043895803 0.119, + 0.057096504 -0.018439 0.119, + 0.054897901 -0.024211902 0.119, + 0.056071501 -0.021353802 0.10200001, + 0.042828102 -0.042020902 0.10200001, + 0.044934504 -0.0397604 0.119, + 0.040608104 -0.044169903 0.119, + 0.0358513 -0.0481112 0.119, + 0.038280502 -0.046201803 0.10200001, + 0.0307144 -0.051542401 0.119, + 0.033327099 -0.049893003 0.10200001, + 0.028020401 -0.053055201 0.10200001, + 0.025252001 -0.054427303 0.119, + 0.022416702 -0.055655103 0.10200001, + 0.025218502 -0.054355204 0.10200001, + 0.030673701 -0.051474102 0.10200001, + 0.0405543 -0.044111304 0.10200001, + 0.048784502 -0.034929503 0.119, + 0.0469217 -0.037394501 0.10200001, + 0.048719902 -0.034883205 0.10200001, + 0.050518002 -0.0323718 0.10200001, + 0.052117504 -0.029728301 0.119, + 0.052048404 -0.029688902 0.10200001, + 0.053578705 -0.027005902 0.10200001, + 0.049018301 0.034600701 0.119, + 0.052316204 0.0293772 0.119, + 0.050734505 0.032031402 0.10200001, + 0.053759106 0.026645001 0.10200001, + 0.055059504 0.023842201 0.119, + 0.056213904 0.020976201 0.10200001, + 0.057219204 0.018054601 0.119, + 0.058072705 0.015085101 0.10200001, + 0.058772303 0.0120756 0.119, + 0.059316006 0.0090340506 0.10200001, + 0.059702404 0.0059685605 0.119, + 0.059930503 0.0028872401 0.10200001, + 0.059999701 -0.00020173201 0.119, + 0.059909701 -0.0032901701 0.10200001, + 0.059660904 -0.0063698906 0.119, + 0.059253901 -0.0094327098 0.10200001, + 0.058689702 -0.012470501 0.119, + 0.057970002 -0.0154753 0.10200001, + 0.054825101 -0.024179801 0.10200001, + 0.057020701 -0.018414499 0.10200001, + 0.058611903 -0.012454001 0.10200001, + 0.059920102 -0.00020146501 0.10200001, + 0.0596232 0.0059606503 0.10200001, + 0.058694303 0.0120596 0.10200001, + 0.057143301 0.018030701 0.10200001, + 0.048953302 0.034554798 0.10200001, + 0.047172103 0.037078202 0.10200001, + 0.045200802 0.039457403 0.119, + 0.045140903 0.039405104 0.10200001, + 0.0431097 0.041731901 0.10200001, + -0.016575301 0.057665005 0.119, + -0.010558301 0.059063703 0.119, + -0.0135848 0.0584419 0.10200001, + -0.0044293702 0.059836302 0.119, + -0.0075038001 0.059528902 0.10200001, + 0.0017465302 0.059974603 0.119, + -0.0013432 0.059985004 0.10200001, + 0.0079039205 0.059477102 0.119, + 0.0048316303 0.059805103 0.10200001, + 0.013977501 0.058349203 0.119, + 0.010955201 0.058991406 0.10200001, + 0.019903 0.056602802 0.119, + 0.016962701 0.0575523 0.10200001, + 0.0256174 0.054256305 0.119, + 0.0227904 0.055503104 0.10200001, + 0.028376501 0.052865602 0.10200001, + 0.031060303 0.051334705 0.119, + 0.033661801 0.049667705 0.10200001, + 0.040849999 0.043837603 0.10200001, + 0.036126003 0.047805503 0.10200001, + 0.031019202 0.051266704 0.10200001, + 0.025583502 0.0541844 0.10200001, + 0.019876601 0.0565277 0.10200001, + 0.013959 0.058271803 0.10200001, + 0.0078934403 0.059398305 0.10200001, + 0.0017442201 0.059895102 0.10200001, + -0.0044235 0.059756905 0.10200001, + -0.0165534 0.057588603 0.10200001, + -0.019521901 0.0567353 0.10200001, + -0.022416702 0.055655103 0.119, + -0.022387 0.055581301 0.10200001, + -0.025252001 0.054427303 0.10200001, + -0.059660904 0.0063698906 0.10200001, + -0.059909701 0.0032901701 0.119, + -0.059253901 0.0094327098 0.119, + -0.057970002 0.0154753 0.119, + -0.058689702 0.012470501 0.10200001, + -0.056071501 0.021353802 0.119, + -0.057096504 0.018439 0.10200001, + -0.053578705 0.027005902 0.119, + -0.054897901 0.024211902 0.10200001, + -0.050518002 0.0323718 0.119, + -0.052117504 0.029728301 0.10200001, + -0.048784502 0.034929503 0.10200001, + -0.0469217 0.037394501 0.119, + -0.044934504 0.0397604 0.10200001, + -0.042828102 0.042020902 0.119, + -0.038280502 0.046201803 0.119, + -0.040608104 0.044169903 0.10200001, + -0.0358513 0.0481112 0.10200001, + -0.027983202 0.052984904 0.10200001, + -0.033282902 0.049826805 0.10200001, + -0.0382297 0.046140503 0.10200001, + -0.042771302 0.041965201 0.10200001, + -0.046859503 0.037345003 0.10200001, + -0.053507704 0.026970102 0.10200001, + -0.055997204 0.021325501 0.10200001, + -0.057893105 0.015454701 0.10200001, + -0.059999701 0.00020173201 0.10200001, + -0.059930503 -0.0028872401 0.119, + -0.059851006 -0.0028834101 0.10200001, + -0.059702404 -0.0059685605 0.10200001, + -0.0227904 -0.055503104 0.119, + -0.028376501 -0.052865602 0.119, + -0.0256174 -0.054256305 0.10200001, + -0.031060303 -0.051334705 0.10200001, + -0.033661801 -0.049667705 0.119, + -0.038590305 -0.045943301 0.119, + -0.036174003 -0.047869001 0.10200001, + -0.0431097 -0.041731901 0.119, + -0.040904205 -0.043895803 0.10200001, + -0.047172103 -0.037078202 0.119, + -0.045200802 -0.039457403 0.10200001, + -0.050734505 -0.032031402 0.119, + -0.049018301 -0.034600701 0.10200001, + -0.052316204 -0.0293772 0.10200001, + -0.053759106 -0.026645001 0.119, + -0.055059504 -0.023842201 0.10200001, + -0.056213904 -0.020976201 0.119, + -0.057219204 -0.018054601 0.10200001, + -0.059237305 -0.0090220701 0.10200001, + -0.057995703 -0.0150651 0.10200001, + -0.056139305 -0.020948401 0.10200001, + -0.053687803 -0.0266097 0.10200001, + -0.0506672 -0.0319889 0.10200001, + -0.047109604 -0.037029002 0.10200001, + -0.033617202 -0.049601901 0.10200001, + -0.028338902 -0.052795503 0.10200001, + -0.022760201 -0.055429503 0.10200001, + -0.019903 -0.056602802 0.10200001, + -0.016962701 -0.0575523 0.119, + -0.016940201 -0.057476003 0.10200001, + -0.013977501 -0.058349203 0.10200001, + 0.016575301 -0.057665005 0.10200001, + 0.019521901 -0.0567353 0.119, + 0.0135848 -0.0584419 0.119, + 0.010558301 -0.059063703 0.10200001, + 0.0075038001 -0.059528902 0.119, + 0.0013432 -0.059985004 0.119, + 0.0044293702 -0.059836302 0.10200001, + -0.0017465302 -0.059974603 0.10200001, + -0.0109407 -0.058913205 0.10200001, + -0.0048252302 -0.059725802 0.10200001, + 0.0013414201 -0.059905402 0.10200001, + 0.0135668 -0.058364403 0.10200001, + 0.019496001 -0.056660101 0.10200001, + 0.044874903 -0.039707702 0.10200001, + 0.059581801 -0.0063614403 0.10200001, + -0.050451003 0.0323289 0.10200001, + 0.036642503 -0.034019504 0.119, + 0.040221103 -0.029702902 0.119, + 0.036642503 -0.034019504 0.10200001, + 0.040221103 -0.029702902 0.10200001, + 0.0326031 -0.037908301 0.10200001, + 0.0326031 -0.037908301 0.119, + 0.028153701 -0.041320302 0.10200001, + 0.028153701 -0.041320302 0.119, + 0.0233503 -0.044212703 0.10200001, + 0.0233503 -0.044212703 0.119, + 0.018253202 -0.0465491 0.10200001, + 0.018253202 -0.0465491 0.119, + 0.012926601 -0.048300102 0.10200001, + 0.012926601 -0.048300102 0.119, + 0.035803799 -0.048047405 0.10200001, + 0.043293901 -0.025012802 0.119, + 0.043293901 -0.025012802 0.10200001, + 0.045822203 -0.020008201 0.119, + 0.045822203 -0.020008201 0.10200001, + 0.041320302 0.028153701 0.10200001, + 0.044212703 0.0233503 0.10200001, + 0.041320302 0.028153701 0.119, + 0.044212703 0.0233503 0.119, + 0.037908301 0.0326031 0.119, + 0.037908301 0.0326031 0.10200001, + 0.0465491 0.018253202 0.10200001, + 0.0465491 0.018253202 0.119, + 0.048300102 0.012926601 0.10200001, + 0.048300102 0.012926601 0.119, + 0.049443699 0.0074374503 0.10200001, + 0.049443699 0.0074374503 0.119, + 0.047774304 -0.0147519 0.10200001, + 0.047774304 -0.0147519 0.119, + 0.049125601 -0.0093101505 0.119, + 0.049125601 -0.0093101505 0.10200001, + 0.049859103 -0.0037513003 0.119, + 0.049859103 -0.0037513003 0.10200001, + 0.049965601 0.0018547401 0.119, + 0.049965601 0.0018547401 0.10200001, + 0.034019504 0.036642503 0.119, + 0.034019504 0.036642503 0.10200001, + -0.012926601 0.048300102 0.10200001, + -0.0074374503 0.049443699 0.10200001, + -0.012926601 0.048300102 0.119, + -0.0074374503 0.049443699 0.119, + -0.018253202 0.0465491 0.119, + -0.018253202 0.0465491 0.10200001, + -0.0018547401 0.049965601 0.10200001, + -0.0018547401 0.049965601 0.119, + 0.0037513003 0.049859103 0.10200001, + 0.0037513003 0.049859103 0.119, + 0.0093101505 0.049125601 0.10200001, + 0.0093101505 0.049125601 0.119, + 0.029702902 0.040221103 0.10200001, + 0.029702902 0.040221103 0.119, + 0.025012802 0.043293901 0.119, + 0.025012802 0.043293901 0.10200001, + 0.020008201 0.045822203 0.119, + 0.020008201 0.045822203 0.10200001, + 0.0147519 0.047774304 0.119, + 0.0147519 0.047774304 0.10200001, + -0.0233503 0.044212703 0.119, + -0.0233503 0.044212703 0.10200001, + -0.049859103 0.0037513003 0.119, + -0.049965601 -0.0018547401 0.119, + -0.049859103 0.0037513003 0.10200001, + -0.049965601 -0.0018547401 0.10200001, + -0.049125601 0.0093101505 0.10200001, + -0.049125601 0.0093101505 0.119, + -0.047774304 0.0147519 0.10200001, + -0.047774304 0.0147519 0.119, + -0.045822203 0.020008201 0.10200001, + -0.045822203 0.020008201 0.119, + -0.028153701 0.041320302 0.10200001, + -0.028153701 0.041320302 0.119, + -0.0326031 0.037908301 0.119, + -0.0326031 0.037908301 0.10200001, + -0.036642503 0.034019504 0.119, + -0.036642503 0.034019504 0.10200001, + -0.040221103 0.029702902 0.119, + -0.040221103 0.029702902 0.10200001, + -0.043293901 0.025012802 0.119, + -0.043293901 0.025012802 0.10200001, + -0.049443699 -0.0074374503 0.119, + -0.049443699 -0.0074374503 0.10200001, + -0.020008201 -0.045822203 0.119, + -0.0147519 -0.047774304 0.119, + -0.020008201 -0.045822203 0.10200001, + -0.0147519 -0.047774304 0.10200001, + -0.025012802 -0.043293901 0.10200001, + -0.025012802 -0.043293901 0.119, + -0.029702902 -0.040221103 0.10200001, + -0.029702902 -0.040221103 0.119, + -0.034019504 -0.036642503 0.10200001, + -0.034019504 -0.036642503 0.119, + -0.048300102 -0.012926601 0.10200001, + -0.048300102 -0.012926601 0.119, + -0.0465491 -0.018253202 0.119, + -0.0465491 -0.018253202 0.10200001, + -0.044212703 -0.0233503 0.119, + -0.044212703 -0.0233503 0.10200001, + -0.041320302 -0.028153701 0.119, + -0.041320302 -0.028153701 0.10200001, + -0.037908301 -0.0326031 0.119, + -0.037908301 -0.0326031 0.10200001, + -0.043052502 -0.041676603 0.10200001, + -0.038539104 -0.045882404 0.10200001, + -0.0093101505 -0.049125601 0.119, + -0.0093101505 -0.049125601 0.10200001, + -0.0037513003 -0.049859103 0.10200001, + -0.0037513003 -0.049859103 0.119, + 0.0018547401 -0.049965601 0.119, + 0.0018547401 -0.049965601 0.10200001, + 0.0074374503 -0.049443699 0.119, + 0.0074374503 -0.049443699 0.10200001, + 0.054986503 0.023810601 0.10200001, + 0.052246802 0.029338202 0.10200001, + -0.010544301 0.058985405 0.10200001, + -0.059175305 0.0094202012 0.10200001, + -0.059830301 0.0032858101 0.10200001, + 0.0074938508 -0.059450004 0.10200001 ] + + } + normal + Normal { + vector [ -0.13172001 -0.99127597 0.0046791499, + -0.97952622 -0.20126204 0.0046811011, + -0.51189011 0.85903823 0.0046753609, + 0.64316899 0.76571 0.0046800501, + 0.93450969 -0.35590687 0.0046778182, + 0.71379304 -0.70034105 0.0046815607, + 0.63800603 -0.77001709 0.0046809004, + 0.55543375 -0.83154756 0.0046839975, + 0.46700314 -0.88424331 0.0046810312, + 0.42085779 -0.90711457 -0.0046764677, + 0.42087278 -0.90710759 -0.0046764677, + 0.51189774 -0.85903358 -0.0046769176, + 0.51188278 -0.85904258 -0.0046769176, + 0.67680424 -0.73614824 -0.0046794312, + 0.67678702 -0.73616397 -0.0046794298, + 0.78202122 -0.62323421 0.0046778014, + 0.81304795 -0.58217794 -0.0046752198, + 0.81307423 -0.58214116 -0.0046752221, + 0.84195095 -0.53953391 0.0046798494, + 0.86860794 -0.49547794 -0.0046789497, + 0.86863011 -0.49543905 -0.0046789506, + 0.89297539 -0.4500812 0.0046773325, + 0.84556383 0.53385389 0.0046780389, + 0.89597887 0.44407195 0.0046773897, + 0.93688428 0.34960812 0.0046802717, + 0.96786863 0.2514129 0.0046768179, + 0.98858947 0.15056191 0.0046797772, + 0.99883038 0.048125915 0.0046789316, + 0.99848402 -0.054843698 0.0046775201, + 0.98755318 -0.15721603 0.0046816007, + 0.96615976 -0.25790194 0.0046822391, + 0.91495663 -0.40352485 -0.0046801181, + 0.91495132 -0.40353715 -0.0046801213, + 0.9515999 -0.30730397 -0.0046859989, + 0.95158702 -0.30734399 -0.0046859998, + 0.97815651 -0.2078169 -0.0046782475, + 0.97815001 -0.207848 -0.0046782494, + 0.99998337 -0.0033679211 -0.0046821819, + 0.99998337 -0.003366681 -0.0046821819, + 0.99502754 0.099489652 -0.0046819979, + 0.99503088 0.099456996 -0.0046819993, + 0.97952336 0.20127606 -0.004683672, + 0.97952914 0.20124802 -0.0046836706, + 0.95364547 0.30089611 -0.0046808124, + 0.95364296 0.30090401 -0.00468081, + 0.81696218 0.57667214 -0.0046807011, + 0.81696308 0.57667106 -0.0046807006, + 0.78619009 0.61796707 0.0046793707, + 0.75334394 0.65761 -0.00467763, + 0.75332958 0.65762663 -0.0046776272, + 0.71848285 0.69552886 0.0046798093, + -0.22641894 0.97401875 0.0046828091, + -0.12506604 0.99213737 0.0046779616, + -0.022387909 0.99973845 0.0046805218, + 0.080534101 0.99674094 0.0046768198, + 0.18258193 0.98317951 0.0046811877, + 0.2827009 0.95919675 0.0046784086, + 0.37984678 0.9250375 0.0046769977, + 0.47294083 0.8810817 0.0046805087, + 0.56101769 0.82779062 0.0046800277, + 0.68173099 0.73158801 -0.0046782894, + 0.68172997 0.73158902 -0.0046782894, + 0.60288519 0.79781431 -0.004682322, + 0.6029011 0.79780215 -0.0046823216, + 0.51768601 0.85555798 -0.0046739001, + 0.51764798 0.85558099 -0.0046739001, + 0.42696986 0.90425372 -0.0046760384, + 0.42693186 0.90427172 -0.0046760384, + 0.33172187 0.94336563 -0.0046825879, + 0.33171204 0.94336903 -0.0046825903, + 0.23294586 0.97247845 -0.0046811472, + 0.23296897 0.97247291 -0.004681149, + 0.13173695 0.99127364 -0.0046760682, + 0.13170402 0.99127811 -0.0046760705, + 0.029137984 0.99956441 -0.0046785171, + 0.029105809 0.99956536 -0.0046785218, + -0.073848158 0.99725842 -0.0046832273, + -0.073816195 0.99726087 -0.0046832296, + -0.27625197 0.96107388 -0.0046750996, + -0.27626199 0.96107101 -0.0046751001, + -0.32535392 0.94558066 0.004681088, + -0.3736071 0.92757523 -0.004679671, + -0.37361795 0.92757088 -0.0046796696, + -0.42086509 0.90711123 0.0046779909, + -0.99433815 0.10615902 0.004679461, + -0.97815311 0.20783302 0.0046753404, + -0.9515934 0.30732381 0.0046821972, + -0.91495401 0.40353099 0.0046789399, + -0.86861879 0.49545887 0.0046829586, + -0.81306094 0.58215994 0.0046792594, + -0.74890673 0.66265875 0.0046798685, + -0.6767959 0.73615587 0.0046772789, + -0.5975197 0.8018406 0.0046786778, + -0.46698895 0.88425088 -0.004678349, + -0.4670158 0.88423657 -0.0046783476, + -0.55542594 0.83155286 -0.0046821893, + -0.55544204 0.83154213 -0.0046821903, + -0.63801599 0.77000892 -0.00468321, + -0.6379962 0.77002525 -0.0046832119, + -0.71378517 0.70034915 -0.0046795211, + -0.71380103 0.700333 -0.0046795197, + -0.78201497 0.62324202 -0.0046759099, + -0.7820279 0.62322593 -0.0046759094, + -0.89297497 0.450082 -0.00467723, + -0.89297557 0.45008078 -0.0046772277, + -0.93450785 0.35591191 -0.0046767588, + -0.93451202 0.35590097 -0.0046767602, + -0.96616089 0.25789797 -0.0046829893, + -0.96615863 0.2579059 -0.0046829884, + -0.99998337 0.0033673011 0.0046822913, + -0.99882954 -0.048141275 -0.0046817376, + -0.99883109 -0.048110407 -0.0046817404, + -0.99502921 -0.09947332 0.0046790107, + -0.42695084 -0.90426266 0.0046798484, + -0.5176667 -0.85556948 0.0046778973, + -0.60289317 -0.79780823 0.0046805013, + -0.68172997 -0.73158902 0.0046783001, + -0.75333703 -0.65761793 0.0046796193, + -0.81696254 -0.57667166 0.0046806373, + -0.87192899 -0.48960999 0.0046826797, + -0.91764486 -0.39737397 0.0046790997, + -0.95364422 -0.30090007 0.0046816007, + -0.98858702 -0.15057801 -0.00468275, + -0.98859191 -0.15054598 -0.0046827495, + -0.96786463 -0.25142792 -0.004679638, + -0.9678725 -0.25139788 -0.0046796375, + -0.93687916 -0.34962207 -0.0046829907, + -0.93689001 -0.34959301 -0.00468298, + -0.89597231 -0.44408515 -0.0046800012, + -0.89598531 -0.44405916 -0.0046800012, + -0.84555173 -0.53387284 -0.0046821879, + -0.84557575 -0.53383487 -0.0046821884, + -0.78619182 -0.61796486 -0.0046789488, + -0.78618872 -0.61796874 -0.0046789483, + -0.56103557 -0.8277784 -0.0046760966, + -0.56099975 -0.82780272 -0.0046760985, + -0.47294721 -0.88107842 -0.0046791318, + -0.4729338 -0.88108557 -0.0046791276, + -0.37983307 -0.92504317 -0.0046796808, + -0.37986088 -0.92503178 -0.0046796785, + -0.3317171 -0.9433673 0.0046834718, + -0.28269693 -0.95919788 -0.0046791197, + -0.28270513 -0.95919544 -0.0046791225, + -0.23295695 -0.97247577 0.0046789991, + 0.27625683 -0.96107244 0.004676017, + 0.17596292 -0.98438567 0.0046790186, + 0.073832177 -0.99725968 0.0046803188, + -0.029121896 -0.99956489 0.0046814396, + -0.18259694 -0.98317665 -0.0046784384, + -0.18256703 -0.98318219 -0.0046784407, + -0.080517724 -0.99674225 -0.004679821, + -0.080550566 -0.99673951 -0.0046798177, + 0.022404602 -0.9997381 -0.0046835504, + 0.022371294 -0.99973875 -0.0046835491, + 0.22640404 -0.97402221 -0.0046800808, + 0.22643289 -0.97401553 -0.0046800775, + 0.32533985 -0.94558555 -0.0046784375, + 0.32536799 -0.94557595 -0.0046784398, + 0.37361294 -0.92757291 0.0046807397, + 0.74890673 -0.66265875 -0.0046798582, + 0.99433815 -0.10615902 -0.004679461, + -0.84195095 0.53953391 -0.0046798792, + -0.76984763 0.6382277 0, + -0.69354922 0.72040921 0, + -0.60852087 0.79353786 0, + -0.5158537 0.85667658 0, + -0.41668785 0.90904963 0, + -0.31228694 0.94998783 0, + 0.5975197 -0.8018406 -0.0046786778, + -0.83646321 0.5480231 0, + -0.8925643 0.45092013 0, + -0.85667658 -0.5158537 0, + -0.79353786 -0.60852087 0, + -0.90904963 -0.41668785 0, + -0.94998783 -0.31228694 0, + -0.97897947 -0.20395909 0, + -0.9374392 0.34814909 0, + -0.97052491 0.24100097 0, + -0.99140638 0.13081792 0, + -0.99981952 0.018993691 0, + -0.99565864 -0.093079261 0, + -0.72040921 -0.69354922 0, + 0.20395909 -0.97897947 0, + 0.31228694 -0.94998783 0, + 0.093079261 -0.99565864 0, + -0.018993691 -0.99981952 0, + -0.13081792 -0.99140638 0, + -0.6382277 -0.76984763 0, + -0.5480231 -0.83646321 0, + -0.45092013 -0.8925643 0, + -0.34814909 -0.9374392 0, + -0.24100097 -0.97052491 0, + 0.41668785 -0.90904963 0, + 0.99981952 -0.018993691 0, + 0.99140638 -0.13081792 0, + 0.97052491 -0.24100097 0, + 0.9374392 -0.34814909 0, + 0.5158537 -0.85667658 0, + 0.60852087 -0.79353786 0, + 0.69354922 -0.72040921 0, + 0.76984763 -0.6382277 0, + 0.83646321 -0.5480231 0, + 0.8925643 -0.45092013 0, + 0.99565864 0.093079261 0, + 0.34814909 0.9374392 0, + 0.45092013 0.8925643 0, + 0.5480231 0.83646321 0, + 0.6382277 0.76984763 0, + 0.97897947 0.20395909 0, + 0.94998783 0.31228694 0, + 0.90904963 0.41668785 0, + 0.85667658 0.5158537 0, + 0.79353786 0.60852087 0, + 0.72040921 0.69354922 0, + -0.71848285 -0.69552886 -0.0046798093, + -0.64316899 -0.76571 -0.0046800501, + 0.24100097 0.97052491 0, + 0.13081792 0.99140638 0, + 0.018993691 0.99981952 0, + -0.093079261 0.99565864 0, + -0.20395909 0.97897947 0, + 0.91764486 0.39737397 -0.0046791993, + 0.87192899 0.48960999 -0.00468277, + -0.17596292 0.98438567 -0.0046788985, + -0.9875533 0.15721506 -0.0046815514, + -0.99848402 0.054843798 -0.0046775201, + 0.12506703 -0.99213725 -0.0046778512, + 0 0 -1, + 0 0 1 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 9, 10, 11, -1, + 12, 13, 14, -1, 15, 16, 17, -1, + 17, 18, 19, -1, 18, 20, 21, -1, + 22, 20, 23, -1, 24, 25, 23, -1, + 23, 25, 22, -1, 22, 26, 20, -1, + 20, 26, 21, -1, 19, 27, 17, -1, + 17, 27, 15, -1, 28, 16, 29, -1, + 29, 30, 28, -1, 28, 30, 31, -1, + 32, 28, 31, -1, 31, 33, 32, -1, + 32, 33, 34, -1, 34, 13, 32, -1, + 35, 36, 37, -1, 38, 36, 39, -1, + 40, 39, 41, -1, 42, 41, 43, -1, + 44, 43, 45, -1, 46, 45, 47, -1, + 48, 47, 49, -1, 50, 49, 51, -1, + 51, 12, 52, -1, 34, 53, 13, -1, + 13, 53, 14, -1, 14, 54, 12, -1, + 12, 54, 52, -1, 52, 55, 51, -1, + 51, 55, 50, -1, 48, 56, 47, -1, + 47, 56, 46, -1, 46, 57, 45, -1, + 45, 57, 44, -1, 44, 58, 43, -1, + 43, 58, 42, -1, 42, 59, 41, -1, + 41, 59, 40, -1, 37, 60, 35, -1, + 35, 60, 61, -1, 61, 62, 35, -1, + 61, 63, 62, -1, 62, 63, 64, -1, + 64, 11, 62, -1, 65, 66, 67, -1, + 66, 68, 69, -1, 68, 70, 71, -1, + 70, 72, 73, -1, 72, 74, 75, -1, + 74, 76, 77, -1, 76, 78, 79, -1, + 80, 78, 81, -1, 82, 81, 10, -1, + 64, 83, 11, -1, 11, 83, 9, -1, + 9, 84, 10, -1, 10, 84, 82, -1, + 82, 85, 81, -1, 81, 85, 80, -1, + 80, 86, 78, -1, 78, 86, 79, -1, + 79, 87, 76, -1, 76, 87, 77, -1, + 77, 88, 74, -1, 74, 88, 75, -1, + 75, 89, 72, -1, 72, 89, 73, -1, + 73, 90, 70, -1, 70, 90, 71, -1, + 71, 91, 68, -1, 68, 91, 69, -1, + 67, 92, 65, -1, 65, 92, 93, -1, + 93, 94, 65, -1, 93, 95, 94, -1, + 94, 95, 96, -1, 7, 94, 96, -1, + 97, 98, 99, -1, 99, 100, 101, -1, + 100, 102, 103, -1, 102, 104, 105, -1, + 104, 106, 107, -1, 108, 106, 109, -1, + 110, 109, 111, -1, 111, 112, 113, -1, + 112, 6, 114, -1, 96, 115, 7, -1, + 7, 115, 8, -1, 8, 116, 6, -1, + 6, 116, 114, -1, 114, 117, 112, -1, + 112, 117, 113, -1, 113, 118, 111, -1, + 111, 118, 110, -1, 110, 119, 109, -1, + 109, 119, 108, -1, 107, 120, 104, -1, + 104, 120, 105, -1, 105, 121, 102, -1, + 102, 121, 103, -1, 103, 122, 100, -1, + 100, 122, 101, -1, 123, 124, 98, -1, + 123, 125, 124, -1, 124, 125, 126, -1, + 4, 124, 126, -1, 127, 128, 129, -1, + 130, 128, 131, -1, 131, 132, 133, -1, + 132, 134, 135, -1, 134, 136, 137, -1, + 136, 138, 139, -1, 140, 138, 141, -1, + 142, 141, 143, -1, 143, 3, 144, -1, + 126, 145, 4, -1, 4, 145, 5, -1, + 5, 146, 3, -1, 3, 146, 144, -1, + 144, 147, 143, -1, 143, 147, 142, -1, + 142, 148, 141, -1, 141, 148, 140, -1, + 140, 149, 138, -1, 138, 149, 139, -1, + 139, 150, 136, -1, 136, 150, 137, -1, + 133, 151, 131, -1, 131, 151, 130, -1, + 130, 152, 128, -1, 128, 152, 129, -1, + 129, 153, 127, -1, 127, 153, 154, -1, + 155, 127, 154, -1, 154, 156, 155, -1, + 155, 156, 157, -1, 1, 155, 157, -1, + 158, 159, 160, -1, 161, 160, 162, -1, + 162, 163, 164, -1, 165, 163, 0, -1, + 157, 166, 1, -1, 1, 166, 2, -1, + 2, 167, 0, -1, 0, 167, 165, -1, + 165, 168, 163, -1, 163, 168, 164, -1, + 161, 169, 160, -1, 160, 169, 158, -1, + 158, 170, 159, -1, 159, 170, 24, -1, + 23, 159, 24, -1, 15, 171, 16, -1, + 16, 171, 29, -1, 50, 172, 49, -1, + 49, 172, 48, -1, 108, 173, 106, -1, + 106, 173, 107, -1, 174, 175, 176, -1, + 176, 175, 177, -1, 176, 178, 174, -1, + 174, 178, 179, -1, 178, 180, 179, -1, + 179, 180, 181, -1, 180, 182, 181, -1, + 181, 182, 183, -1, 182, 184, 183, -1, + 183, 184, 185, -1, 184, 186, 185, -1, + 185, 186, 187, -1, 21, 188, 18, -1, + 18, 188, 19, -1, 175, 189, 177, -1, + 177, 189, 190, -1, 189, 191, 190, -1, + 190, 191, 192, -1, 193, 194, 195, -1, + 195, 194, 196, -1, 195, 197, 193, -1, + 193, 197, 198, -1, 194, 199, 196, -1, + 196, 199, 200, -1, 199, 201, 200, -1, + 200, 201, 202, -1, 201, 203, 202, -1, + 202, 203, 204, -1, 205, 192, 206, -1, + 206, 192, 191, -1, 206, 207, 205, -1, + 205, 207, 208, -1, 207, 209, 208, -1, + 208, 209, 210, -1, 209, 211, 210, -1, + 210, 211, 212, -1, 211, 204, 212, -1, + 212, 204, 203, -1, 197, 213, 198, -1, + 198, 213, 214, -1, 215, 216, 217, -1, + 217, 216, 218, -1, 217, 219, 215, -1, + 215, 219, 220, -1, 216, 221, 218, -1, + 218, 221, 222, -1, 221, 223, 222, -1, + 222, 223, 224, -1, 223, 225, 224, -1, + 224, 225, 226, -1, 227, 214, 228, -1, + 228, 214, 213, -1, 228, 229, 227, -1, + 227, 229, 230, -1, 229, 231, 230, -1, + 230, 231, 232, -1, 231, 233, 232, -1, + 232, 233, 234, -1, 233, 226, 234, -1, + 234, 226, 225, -1, 219, 235, 220, -1, + 220, 235, 236, -1, 237, 238, 239, -1, + 239, 238, 240, -1, 239, 241, 237, -1, + 237, 241, 242, -1, 241, 243, 242, -1, + 242, 243, 244, -1, 243, 245, 244, -1, + 244, 245, 246, -1, 247, 236, 248, -1, + 248, 236, 235, -1, 248, 249, 247, -1, + 247, 249, 250, -1, 249, 251, 250, -1, + 250, 251, 252, -1, 251, 253, 252, -1, + 252, 253, 254, -1, 253, 255, 254, -1, + 254, 255, 256, -1, 255, 246, 256, -1, + 256, 246, 245, -1, 238, 257, 240, -1, + 240, 257, 258, -1, 259, 260, 261, -1, + 261, 260, 262, -1, 261, 263, 259, -1, + 259, 263, 264, -1, 263, 265, 264, -1, + 264, 265, 266, -1, 265, 267, 266, -1, + 266, 267, 268, -1, 269, 258, 270, -1, + 270, 258, 257, -1, 270, 271, 269, -1, + 269, 271, 272, -1, 271, 273, 272, -1, + 272, 273, 274, -1, 273, 275, 274, -1, + 274, 275, 276, -1, 275, 277, 276, -1, + 276, 277, 278, -1, 277, 268, 278, -1, + 278, 268, 267, -1, 137, 279, 134, -1, + 134, 279, 135, -1, 135, 280, 132, -1, + 132, 280, 133, -1, 260, 281, 262, -1, + 262, 281, 282, -1, 283, 282, 284, -1, + 284, 282, 281, -1, 284, 285, 283, -1, + 283, 285, 286, -1, 285, 287, 286, -1, + 286, 287, 288, -1, 287, 187, 288, -1, + 288, 187, 186, -1, 40, 289, 39, -1, + 39, 289, 38, -1, 38, 290, 36, -1, + 36, 290, 37, -1, 69, 291, 66, -1, + 66, 291, 67, -1, 101, 292, 99, -1, + 99, 292, 97, -1, 97, 293, 98, -1, + 98, 293, 123, -1, 164, 294, 162, -1, + 162, 294, 161, -1, 182, 180, 26, -1, + 26, 180, 21, -1, 21, 180, 188, -1, + 188, 180, 178, -1, 188, 178, 19, -1, + 19, 178, 27, -1, 178, 176, 27, -1, + 27, 176, 15, -1, 15, 176, 171, -1, + 171, 176, 29, -1, 176, 177, 29, -1, + 29, 177, 30, -1, 30, 177, 31, -1, + 31, 177, 190, -1, 31, 190, 33, -1, + 33, 190, 34, -1, 190, 192, 34, -1, + 34, 192, 53, -1, 53, 192, 14, -1, + 14, 192, 205, -1, 14, 205, 54, -1, + 54, 205, 52, -1, 205, 208, 52, -1, + 52, 208, 55, -1, 55, 208, 50, -1, + 50, 208, 172, -1, 208, 210, 172, -1, + 172, 210, 48, -1, 48, 210, 56, -1, + 56, 210, 212, -1, 56, 212, 46, -1, + 46, 212, 57, -1, 212, 203, 57, -1, + 57, 203, 44, -1, 44, 203, 58, -1, + 58, 203, 201, -1, 58, 201, 42, -1, + 42, 201, 59, -1, 201, 199, 59, -1, + 59, 199, 40, -1, 40, 199, 289, -1, + 289, 199, 194, -1, 289, 194, 38, -1, + 38, 194, 290, -1, 194, 193, 290, -1, + 290, 193, 37, -1, 37, 193, 60, -1, + 60, 193, 61, -1, 193, 198, 61, -1, + 61, 198, 63, -1, 63, 198, 64, -1, + 64, 198, 214, -1, 64, 214, 83, -1, + 83, 214, 9, -1, 214, 227, 9, -1, + 9, 227, 84, -1, 84, 227, 82, -1, + 82, 227, 230, -1, 82, 230, 85, -1, + 85, 230, 80, -1, 80, 230, 86, -1, + 86, 230, 232, -1, 86, 232, 79, -1, + 79, 232, 87, -1, 232, 234, 87, -1, + 87, 234, 77, -1, 77, 234, 88, -1, + 88, 234, 225, -1, 88, 225, 75, -1, + 75, 225, 89, -1, 225, 223, 89, -1, + 89, 223, 73, -1, 73, 223, 90, -1, + 90, 223, 221, -1, 90, 221, 71, -1, + 71, 221, 91, -1, 221, 216, 91, -1, + 91, 216, 69, -1, 69, 216, 291, -1, + 291, 216, 215, -1, 291, 215, 67, -1, + 67, 215, 92, -1, 92, 215, 93, -1, + 93, 215, 220, -1, 93, 220, 95, -1, + 95, 220, 96, -1, 220, 236, 96, -1, + 96, 236, 115, -1, 115, 236, 8, -1, + 8, 236, 247, -1, 8, 247, 116, -1, + 116, 247, 114, -1, 247, 250, 114, -1, + 114, 250, 117, -1, 117, 250, 113, -1, + 113, 250, 118, -1, 250, 252, 118, -1, + 118, 252, 110, -1, 110, 252, 119, -1, + 119, 252, 254, -1, 119, 254, 108, -1, + 108, 254, 173, -1, 254, 256, 173, -1, + 173, 256, 107, -1, 107, 256, 120, -1, + 120, 256, 245, -1, 120, 245, 105, -1, + 105, 245, 121, -1, 245, 243, 121, -1, + 121, 243, 103, -1, 103, 243, 122, -1, + 122, 243, 241, -1, 122, 241, 101, -1, + 101, 241, 292, -1, 241, 239, 292, -1, + 292, 239, 97, -1, 97, 239, 293, -1, + 293, 239, 123, -1, 239, 240, 123, -1, + 123, 240, 125, -1, 125, 240, 126, -1, + 126, 240, 258, -1, 126, 258, 145, -1, + 145, 258, 5, -1, 258, 269, 5, -1, + 5, 269, 146, -1, 146, 269, 144, -1, + 144, 269, 272, -1, 144, 272, 147, -1, + 147, 272, 142, -1, 142, 272, 148, -1, + 148, 272, 274, -1, 148, 274, 140, -1, + 140, 274, 149, -1, 274, 276, 149, -1, + 149, 276, 139, -1, 139, 276, 150, -1, + 150, 276, 278, -1, 150, 278, 137, -1, + 137, 278, 279, -1, 278, 267, 279, -1, + 279, 267, 135, -1, 135, 267, 280, -1, + 280, 267, 265, -1, 280, 265, 133, -1, + 133, 265, 151, -1, 265, 263, 151, -1, + 151, 263, 130, -1, 130, 263, 152, -1, + 152, 263, 261, -1, 152, 261, 129, -1, + 129, 261, 153, -1, 153, 261, 154, -1, + 154, 261, 262, -1, 154, 262, 156, -1, + 156, 262, 157, -1, 262, 282, 157, -1, + 157, 282, 166, -1, 166, 282, 2, -1, + 2, 282, 283, -1, 2, 283, 167, -1, + 167, 283, 165, -1, 283, 286, 165, -1, + 165, 286, 168, -1, 168, 286, 164, -1, + 164, 286, 288, -1, 164, 288, 294, -1, + 294, 288, 161, -1, 161, 288, 169, -1, + 169, 288, 186, -1, 169, 186, 158, -1, + 158, 186, 170, -1, 186, 184, 170, -1, + 170, 184, 24, -1, 24, 184, 25, -1, + 25, 184, 182, -1, 25, 182, 22, -1, + 22, 182, 26, -1, 16, 174, 17, -1, + 17, 174, 179, -1, 17, 179, 18, -1, + 18, 179, 181, -1, 18, 181, 20, -1, + 20, 181, 183, -1, 20, 183, 23, -1, + 23, 183, 185, -1, 23, 185, 159, -1, + 159, 185, 187, -1, 159, 187, 160, -1, + 160, 187, 287, -1, 160, 287, 162, -1, + 162, 287, 285, -1, 162, 285, 163, -1, + 163, 285, 284, -1, 163, 284, 0, -1, + 0, 284, 281, -1, 0, 281, 1, -1, + 1, 281, 155, -1, 281, 260, 155, -1, + 155, 260, 127, -1, 260, 259, 127, -1, + 127, 259, 128, -1, 259, 264, 128, -1, + 128, 264, 131, -1, 264, 266, 131, -1, + 131, 266, 132, -1, 266, 268, 132, -1, + 132, 268, 134, -1, 268, 277, 134, -1, + 134, 277, 136, -1, 277, 275, 136, -1, + 136, 275, 138, -1, 275, 273, 138, -1, + 138, 273, 141, -1, 273, 271, 141, -1, + 141, 271, 143, -1, 271, 270, 143, -1, + 143, 270, 3, -1, 270, 257, 3, -1, + 3, 257, 4, -1, 4, 257, 124, -1, + 124, 257, 238, -1, 124, 238, 98, -1, + 98, 238, 237, -1, 98, 237, 99, -1, + 99, 237, 242, -1, 99, 242, 100, -1, + 100, 242, 244, -1, 100, 244, 102, -1, + 102, 244, 246, -1, 102, 246, 104, -1, + 104, 246, 255, -1, 104, 255, 106, -1, + 106, 255, 253, -1, 106, 253, 109, -1, + 109, 253, 251, -1, 109, 251, 111, -1, + 111, 251, 249, -1, 111, 249, 112, -1, + 112, 249, 248, -1, 112, 248, 6, -1, + 6, 248, 235, -1, 6, 235, 7, -1, + 7, 235, 94, -1, 235, 219, 94, -1, + 94, 219, 65, -1, 219, 217, 65, -1, + 65, 217, 66, -1, 217, 218, 66, -1, + 66, 218, 68, -1, 218, 222, 68, -1, + 68, 222, 70, -1, 222, 224, 70, -1, + 70, 224, 72, -1, 224, 226, 72, -1, + 72, 226, 74, -1, 226, 233, 74, -1, + 74, 233, 76, -1, 233, 231, 76, -1, + 76, 231, 78, -1, 231, 229, 78, -1, + 78, 229, 81, -1, 229, 228, 81, -1, + 81, 228, 10, -1, 228, 213, 10, -1, + 10, 213, 11, -1, 11, 213, 62, -1, + 62, 213, 197, -1, 62, 197, 35, -1, + 35, 197, 195, -1, 35, 195, 36, -1, + 36, 195, 196, -1, 36, 196, 39, -1, + 39, 196, 200, -1, 39, 200, 41, -1, + 41, 200, 202, -1, 41, 202, 43, -1, + 43, 202, 204, -1, 43, 204, 45, -1, + 45, 204, 211, -1, 45, 211, 47, -1, + 47, 211, 209, -1, 47, 209, 49, -1, + 49, 209, 207, -1, 49, 207, 51, -1, + 51, 207, 206, -1, 51, 206, 12, -1, + 12, 206, 191, -1, 12, 191, 13, -1, + 13, 191, 32, -1, 191, 189, 32, -1, + 32, 189, 28, -1, 189, 175, 28, -1, + 28, 175, 16, -1, 174, 16, 175, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 159, 159, 159, -1, 160, 160, 160, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 161, 161, 161, -1, 162, 162, 162, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 163, 163, 163, -1, 164, 164, 164, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 165, 165, 165, -1, 166, 166, 166, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 167, 167, 167, -1, 168, 168, 168, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 169, 169, 169, -1, 170, 170, 170, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 171, 171, 171, -1, 172, 172, 172, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 173, 173, 173, -1, 174, 174, 174, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 175, 175, 175, -1, 176, 176, 176, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 177, 177, 177, -1, 178, 178, 178, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 179, 179, 179, -1, 180, 180, 180, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 181, 181, 181, -1, 182, 182, 182, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 183, 183, 183, -1, 184, 184, 184, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 185, 185, 185, -1, 186, 186, 186, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 187, 187, 187, -1, 188, 188, 188, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 189, 189, 189, -1, 190, 190, 190, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 191, 191, 191, -1, 192, 192, 192, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 193, 193, 193, -1, 194, 194, 194, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 195, 195, 195, -1, 196, 196, 196, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 197, 197, 197, -1, 198, 198, 198, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 199, 199, 199, -1, 200, 200, 200, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 201, 201, 201, -1, 202, 202, 202, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 203, 203, 203, -1, 204, 204, 204, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 205, 205, 205, -1, 206, 206, 206, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 207, 207, 207, -1, 208, 208, 208, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 209, 209, 209, -1, 210, 210, 210, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 211, 211, 211, -1, 212, 212, 212, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 213, 213, 213, -1, 214, 214, 214, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 215, 215, 215, -1, 216, 216, 216, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 217, 217, 217, -1, 218, 218, 218, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 219, 219, 219, -1, 220, 220, 220, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 221, 221, 221, -1, 222, 222, 222, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 223, 223, 223, -1, 224, 224, 224, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 225, 225, 225, -1, 226, 226, 226, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 227, 227, 227, -1, + 227, 227, 227, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1, + 228, 228, 228, -1, 228, 228, 228, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } + + } + + }, + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.61570001 0.59609997 0.59609997 + ambientIntensity 0.31769803 + specularColor 0.50590003 0.50590003 0.50590003 + shininess 0.039099999 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.0275915 0.041793205 0, + -0.027598102 0.041801304 0.020000001, + -0.027007401 0.041071802 0.020000001, + 0.0220915 0.043992702 0, + 0.022401901 0.044801302 0.020000001, + 0.0220656 0.043925002 0.020000001, + 0.0220915 0.042707402 0, + 0.0220164 0.042987704 0.020000001, + 0.022259401 0.042081103 0.020000001, + 0.0220656 0.043925002 0, + 0.0220164 0.042987704 0, + 0.060897402 -0.035608102 0.0087875305, + 0.063117601 -0.031505503 0.0087875305, + 0.061146304 -0.030521501 0.0176419, + 0.064676702 -0.033742201 0, + 0.062963605 -0.0368177 0, + 0.062065803 -0.038429502 0, + 0.058410805 -0.039554901 0.0087875305, + 0.0589955 -0.034495998 0.0176419, + 0.0594032 -0.029651402 0.026555801, + 0.061233006 -0.025660602 0.026555801, + 0.059672702 -0.025006702 0.035522003, + 0.061195001 -0.021008302 0.035522003, + 0.059838802 -0.020542702 0.044533003, + 0.061065704 -0.016543001 0.044533003, + 0.059931803 -0.0162358 0.053581405, + 0.060873803 -0.0122394 0.053581405, + 0.059977002 -0.012059101 0.062659808, + 0.060642902 -0.0080688111 0.062659808, + 0.059994705 -0.0079825707 0.071760699, + 0.060391106 -0.0040000305 0.071760699, + 0.059999403 -0.0039740903 0.080876604, + 0.060130905 0 0.080876604, + 0.060000002 0 0.090000004, + 0.059999403 0.0039740903 0.080876604, + 0.060523402 0 0.071760699, + 0.061043601 -0.0040432503 0.062659808, + 0.0615496 -0.0081894509 0.053581405, + 0.062025506 -0.012471001 0.044533003, + 0.062449604 -0.016917901 0.035522003, + 0.062794998 -0.021557601 0.026555801, + 0.063029803 -0.026413603 0.0176419, + 0.0650618 -0.027265102 0.0087875305, + 0.065346904 -0.032538898 0, + 0.064637706 -0.022190202 0.0176419, + 0.064082503 -0.017360302 0.026555801, + 0.063431203 -0.012753601 0.035522003, + 0.0627141 -0.0083443904 0.044533003, + 0.061956301 -0.0041037002 0.053581405, + 0.061177302 0 0.062659808, + 0.060391106 0.0040000305 0.071760699, + 0.059605602 0.0079307901 0.080876604, + 0.059682 0.0061692605 0.090000004, + 0.059795801 0.0039616702 0.090000004, + 0.059682 0.0061692605 0.10200001, + 0.060000002 0 0.10200001, + -0.0104591 0.0697641 0.0087875305, + -0.015047001 0.068920307 0.0087875305, + -0.014577 0.066767901 0.0176419, + -0.0189579 0.065658502 0.0176419, + -0.018417401 0.063786708 0.026555801, + -0.0225929 0.062430002 0.026555801, + -0.022017201 0.060839202 0.035522003, + -0.025989901 0.0592511 0.035522003, + -0.025414001 0.057938002 0.044533003, + -0.029187601 0.056131702 0.044533003, + -0.028645601 0.055089504 0.053581405, + -0.032223903 0.053075805 0.053581405, + -0.031749204 0.0522939 0.062659808, + -0.035135899 0.050081301 0.062659808, + -0.0347603 0.049546003 0.071760699, + -0.037958901 0.047140304 0.071760699, + -0.037712701 0.046834599 0.080876604, + -0.038435601 0.046072803 0.090000004, + -0.040725499 0.044239704 0.080876604, + -0.0435603 0.041451402 0.080876604, + -0.042969104 0.041876599 0.090000004, + -0.040991403 0.044528503 0.071760699, + -0.038369 0.047649603 0.062659808, + -0.035661202 0.050830103 0.053581405, + -0.032833502 0.054080006 0.044533003, + -0.029849101 0.057403903 0.035522003, + -0.026669502 0.060800303 0.026555801, + -0.023255801 0.064262003 0.0176419, + -0.019569002 0.067775205 0.0087875305, + -0.0199774 0.070213303 0, + -0.0155552 0.071253404 0, + -0.020246401 0.070123106 0, + -0.024823202 0.068589106 0, + -0.013413701 0.071757004 0, + -0.0067355903 0.072688602 0, + -0.010813001 0.072119802 0, + -0.028198602 0.052960705 0.10200001, + -0.022603702 0.055579402 0.10200001, + -0.024075601 0.054890502 0.090000004, + -0.022603702 0.055579402 0.090000004, + -0.016769102 0.057609003 0.090000004, + -0.016680501 0.057771001 0.080876604, + -0.020462099 0.056542199 0.080876604, + -0.016789401 0.058148105 0.071760699, + -0.012909601 0.059130602 0.071760699, + -0.0090703703 0.060501203 0.062659808, + -0.013049101 0.059769403 0.062659808, + -0.0092059905 0.061405804 0.053581405, + -0.0051275203 0.061880004 0.053581405, + -0.0052245306 0.063050702 0.044533003, + -0.00104605 0.063258104 0.044533003, + -0.0010697601 0.064691804 0.035522003, + 0.0032081003 0.064621009 0.035522003, + 0.0032919801 0.066310704 0.026555801, + 0.0076673008 0.065948099 0.026555801, + 0.0078922901 0.067883305 0.0176419, + 0.0123615 0.067213304 0.0176419, + 0.012760001 0.069380097 0.0087875305, + 0.013203001 0.071786404 0, + 0.0084222499 0.072453305 0, + 0.013413701 0.071757004 0, + 0.0173175 0.068385102 0.0087875305, + 0.038583804 0.059056904 0.0087875305, + 0.038429502 0.062065803 0, + 0.037500001 0.062583603 0, + -0.00099420105 0.060122702 0.080876604, + -0.0049655703 0.0599255 0.080876604, + -0.0046305303 0.059821103 0.090000004, + -0.00100069 0.060515203 0.071760699, + 0.00300098 0.060449004 0.071760699, + 0.0030334003 0.061102103 0.062659808, + 0.0070650405 0.060768005 0.062659808, + 0.0071706804 0.061676603 0.053581405, + 0.011231201 0.061067801 0.053581405, + 0.011443701 0.062223203 0.044533003, + 0.015531101 0.061330803 0.044533003, + 0.015883101 0.062720798 0.035522003, + 0.019993601 0.061533906 0.035522003, + 0.020516401 0.063142903 0.026555801, + 0.024644701 0.061648902 0.026555801, + 0.0253678 0.063457906 0.0176419, + 0.029506302 0.061642602 0.0176419, + 0.030457601 0.063629799 0.0087875305, + 0.034596302 0.061477803 0.0087875305, + 0.032538898 0.065346904 0, + 0.035763402 0.063550904 0, + 0.033515804 0.059557803 0.0176419, + 0.0286652 0.059885301 0.026555801, + 0.024016703 0.060078003 0.035522003, + 0.019550502 0.060170304 0.044533003, + 0.0152427 0.060192004 0.053581405, + 0.011065801 0.060168203 0.062659808, + 0.0069895303 0.060118504 0.071760699, + 0.00298152 0.060056902 0.080876604, + 0.0015448701 0.059980102 0.090000004, + 0.0077039003 0.059503403 0.10200001, + 0.0137813 0.058395904 0.10200001, + 0.010838601 0.058932099 0.090000004, + 0.065346904 0.032538898 0, + 0.063117601 0.031505503 0.0087875305, + 0.0650618 0.027265102 0.0087875305, + 0.061146304 0.030521501 0.0176419, + 0.036012903 0.0479904 0.090000004, + 0.036143504 0.048055902 0.080876604, + 0.032888502 0.050339602 0.080876604, + 0.036379501 0.048369601 0.071760699, + 0.039496701 0.045859504 0.071760699, + 0.0399235 0.046355002 0.062659808, + 0.042899802 0.043615103 0.062659808, + 0.0435412 0.044267204 0.053581405, + 0.046371702 0.041292705 0.053581405, + 0.047249004 0.042074002 0.044533003, + 0.0499264 0.0388593 0.044533003, + 0.051057901 0.039739899 0.035522003, + 0.053572703 0.036278602 0.035522003, + 0.054973401 0.037227202 0.026555801, + 0.057313602 0.0335126 0.026555801, + 0.0589955 0.034495998 0.0176419, + 0.060897402 0.035608102 0.0087875305, + 0.064676702 0.033742201 0, + 0.056586605 0.038319603 0.0176419, + 0.0523929 0.040779002 0.026555801, + 0.048319805 0.043027502 0.035522003, + 0.044365004 0.045104701 0.044533003, + 0.040520404 0.047048103 0.053581405, + 0.036772501 0.048892204 0.062659808, + 0.033103202 0.050668202 0.071760699, + 0.029489601 0.0524031 0.080876604, + 0.030887602 0.051438902 0.090000004, + 0.039108898 0.045407504 0.090000004, + 0.036062699 0.047948703 0.090000004, + 0.036012903 0.0479904 0.10200001, + 0.039240602 0.045562103 0.080876604, + 0.040756404 0.044033103 0.090000004, + 0.040756404 0.044033103 0.10200001, + 0.032775603 0.0501686 0.090000004, + 0.030887602 0.051438902 0.10200001, + 0.025434902 0.054342102 0.10200001, + 0.029395701 0.052233204 0.090000004, + 0.025893701 0.054097805 0.090000004, + 0.042441301 0.043148901 0.071760699, + 0.045688502 0.040684402 0.062659808, + 0.048999302 0.0381377 0.053581405, + 0.052385505 0.035474602 0.044533003, + 0.055853203 0.032658603 0.035522003, + 0.0594032 0.029651402 0.026555801, + 0.063029803 0.026413603 0.0176419, + 0.068070509 0.026370602 0, + 0.066721499 0.022905501 0.0087875305, + 0.0680895 0.018445801 0.0087875305, + 0.070213303 0.0199774 0, + 0.064637706 0.022190202 0.0176419, + 0.061233006 0.025660602 0.026555801, + 0.057889502 0.028895902 0.035522003, + 0.054615505 0.031934902 0.044533003, + 0.051412802 0.0348159 0.053581405, + 0.048277501 0.037575904 0.062659808, + 0.045200203 0.040249601 0.071760699, + 0.042166002 0.042869002 0.080876604, + 0.045067903 0.039609101 0.10200001, + 0.0447958 0.039888304 0.090000004, + 0.042026799 0.042729501 0.090000004, + 0.048901703 0.034765303 0.10200001, + 0.047287602 0.036804602 0.090000004, + 0.049634304 0.033613499 0.090000004, + 0.0522171 0.029552901 0.10200001, + 0.054979004 0.024027202 0.10200001, + 0.053612601 0.026761001 0.090000004, + 0.056699503 0.019463301 0.090000004, + 0.055300001 0.023175802 0.090000004, + 0.0568728 0.019524502 0.080876604, + 0.057158101 0.018246902 0.090000004, + 0.058038902 0.015723001 0.080876604, + 0.058417805 0.0158257 0.071760699, + 0.0185815 0.057187904 0.080876604, + 0.022320401 0.055834804 0.080876604, + 0.022466103 0.056199301 0.071760699, + 0.0197125 0.056669403 0.090000004, + 0.018526802 0.057014503 0.090000004, + 0.0197125 0.056669403 0.10200001, + 0.014717301 0.058123406 0.090000004, + 0.014761301 0.058290903 0.080876604, + 0.018702801 0.0575612 0.071760699, + 0.022708902 0.056806501 0.062659808, + 0.026413603 0.055181403 0.062659808, + 0.026808502 0.056006502 0.053581405, + 0.030451402 0.054112203 0.053581405, + 0.031027501 0.055136003 0.044533003, + 0.034603599 0.052964803 0.044533003, + 0.035387903 0.054165203 0.035522003, + 0.038890302 0.051708002 0.035522003, + 0.039907202 0.053060003 0.026555801, + 0.043326702 0.050306503 0.026555801, + 0.044598103 0.051782701 0.0176419, + 0.047922902 0.048722003 0.0176419, + 0.049467903 0.0502926 0.0087875305, + 0.052683603 0.046913303 0.0087875305, + 0.053947702 0.0491798 0, + 0.054491505 0.048524801 0, + 0.055045106 0.047858201 0, + 0.055668902 0.0433289 0.0087875305, + 0.051038202 0.045448203 0.0176419, + 0.046556804 0.047333002 0.026555801, + 0.042222701 0.049024604 0.035522003, + 0.038028501 0.050562002 0.044533003, + 0.033961102 0.051981401 0.053581405, + 0.030002801 0.053315103 0.062659808, + 0.026131302 0.0545916 0.071760699, + 0.025434902 0.054342102 0.090000004, + 0.025961801 0.054237504 0.080876604, + 0.029682102 0.052745204 0.071760699, + 0.033460803 0.0512156 0.062659808, + 0.037322301 0.049623203 0.053581405, + 0.041287001 0.047938205 0.044533003, + 0.0453704 0.046126902 0.035522003, + 0.0495832 0.044152502 0.026555801, + 0.053930305 0.041975703 0.0176419, + 0.058410805 0.039554901 0.0087875305, + 0.0582553 0.0439923 0, + 0.062065803 0.038429502 0, + 0.0603812 0.040888805 0, + 0.057575405 0.044811103 0, + 0.069927499 0.0093041705 0.0087875305, + 0.072286598 0.0096175708 0, + 0.071871698 0.012591501 0, + 0.048901703 0.034765303 0.090000004, + 0.0497889 0.033716302 0.080876604, + 0.047451701 0.036933202 0.080876604, + 0.050113901 0.033936404 0.071760699, + 0.044907004 0.039988499 0.080876604, + 0.045067903 0.039609101 0.090000004, + 0.047761504 0.037174303 0.071760699, + 0.050655402 0.034303103 0.062659808, + 0.052811701 0.030880202 0.062659808, + 0.053601302 0.031341903 0.053581405, + 0.055555601 0.027730802 0.053581405, + 0.056606606 0.028255502 0.044533003, + 0.058350302 0.024452602 0.044533003, + 0.059672702 0.025006702 0.035522003, + 0.061195001 0.021008302 0.035522003, + 0.062794998 0.021557601 0.026555801, + 0.064082503 0.017360302 0.026555801, + 0.065963 0.0178697 0.0176419, + 0.066999704 0.0134711 0.0176419, + 0.069159701 0.013905401 0.0087875305, + 0.071757004 0.013413701 0, + 0.072688602 0.0067355903 0, + 0.070389509 0.0046622804 0.0087875305, + 0.067743599 0.0090135904 0.0176419, + 0.065089703 0.0130871 0.026555801, + 0.062449604 0.016917901 0.035522003, + 0.059838802 0.020542702 0.044533003, + 0.057266802 0.023998503 0.053581405, + 0.054737203 0.027322302 0.062659808, + 0.052247204 0.030550102 0.071760699, + 0.069927499 -0.0093041705 0.0087875305, + 0.070389509 -0.0046622804 0.0087875305, + 0.0681912 -0.0045166705 0.0176419, + 0.054979004 0.024027202 0.090000004, + 0.055458102 0.023240501 0.080876604, + 0.053800903 0.026855001 0.080876604, + 0.0558201 0.023392301 0.071760699, + 0.0572441 0.019651901 0.071760699, + 0.057862602 0.019864202 0.062659808, + 0.059048902 0.015996601 0.062659808, + 0.059931803 0.0162358 0.053581405, + 0.060873803 0.0122394 0.053581405, + 0.062025506 0.012471001 0.044533003, + 0.0627141 0.0083443904 0.044533003, + 0.064135402 0.0085335001 0.035522003, + 0.064559199 0.0042761005 0.035522003, + 0.066247202 0.00438791 0.026555801, + 0.06639231 0 0.026555801, + 0.0683406 0 0.0176419, + 0.070543706 0 0.0087875305, + 0.0727771 -0.0048216903 0, + 0.0681912 0.0045166705 0.0176419, + 0.065812305 0.0087566301 0.026555801, + 0.063431203 0.012753601 0.035522003, + 0.061065704 0.016543001 0.044533003, + 0.0587277 0.0201612 0.053581405, + 0.056423202 0.023645002 0.062659808, + 0.054152101 0.027030302 0.071760699, + 0.051908404 0.030352 0.080876604, + 0.0522171 0.029552901 0.090000004, + 0.051763702 0.030265803 0.090000004, + 0.0727771 0.0048216903 0, + 0.073000006 0 0, + 0.072688602 -0.0067355903 0, + 0.072286598 -0.0096175708 0, + 0.071871698 -0.012591501 0, + 0.071757004 -0.013413701 0, + 0.069159701 -0.013905401 0.0087875305, + 0.067743599 -0.0090135904 0.0176419, + 0.066247202 -0.00438791 0.026555801, + 0.064700603 0 0.035522003, + 0.063128501 0.0041813403 0.044533003, + 0.0615496 0.0081894509 0.053581405, + 0.059977002 0.012059101 0.062659808, + 0.071529604 0.0143806 0, + 0.0704244 0.0190796 0, + 0.068972602 0.023678901 0, + 0.0653124 0.032600902 0, + 0.062963605 0.0368177 0, + 0.0222423 0.0556405 0.090000004, + -0.058021706 0.015280301 0.10200001, + -0.058021706 0.015280301 0.090000004, + -0.058340803 0.013753101 0.090000004, + -0.059285305 0.00923343 0.10200001, + -0.059152305 0.0098695504 0.090000004, + -0.058527004 0.013795501 0.080876604, + -0.057487305 0.017633401 0.080876604, + -0.051431704 0.051695805 0, + -0.0511037 0.048629604 0.0087875305, + -0.047778003 0.051900703 0.0087875305, + -0.049507603 0.047110803 0.0176419, + -0.052513003 0.043735802 0.0176419, + -0.051016003 0.042489 0.026555801, + -0.053712506 0.039024401 0.026555801, + -0.052343901 0.038030103 0.035522003, + -0.054742903 0.034487501 0.035522003, + -0.053529702 0.033723202 0.044533003, + -0.055641502 0.030111702 0.044533003, + -0.0546083 0.029552501 0.053581405, + -0.056442104 0.0258788 0.053581405, + -0.055610601 0.025497602 0.062659808, + -0.057174202 0.021766502 0.062659808, + -0.056563102 0.021533901 0.071760699, + -0.057862602 0.017748501 0.071760699, + -0.056143004 0.021165101 0.090000004, + -0.056196205 0.021394201 0.080876604, + -0.055016205 0.025225101 0.071760699, + -0.053803906 0.029117202 0.062659808, + -0.052535802 0.033097003 0.053581405, + -0.051183902 0.037187304 0.044533003, + -0.049716003 0.041406401 0.035522003, + -0.048096299 0.045767803 0.026555801, + -0.046285804 0.050279804 0.0176419, + -0.0491798 0.053947702 0, + -0.044243403 0.054944903 0.0087875305, + -0.052883502 0.028619101 0.080876604, + -0.052708603 0.028523002 0.090000004, + -0.050754502 0.031975601 0.090000004, + -0.040515304 0.057748903 0.0087875305, + -0.0366101 0.060300302 0.0087875305, + -0.038429502 0.062065803 0, + -0.039250001 0.055945303 0.0176419, + -0.037500001 0.062583603 0, + -0.032544702 0.062588006 0.0087875305, + -0.035466705 0.058417004 0.0176419, + -0.038131002 0.054350402 0.026555801, + -0.041639704 0.0517115 0.026555801, + -0.040578704 0.050393801 0.035522003, + -0.0438205 0.0476018 0.035522003, + -0.042849403 0.046546903 0.044533003, + -0.045832004 0.043613203 0.044533003, + -0.044981003 0.042803399 0.053581405, + -0.047711603 0.0397369 0.053581405, + -0.047008704 0.039151601 0.062659808, + -0.049493503 0.035959102 0.062659808, + -0.048964504 0.035574801 0.071760699, + -0.0512086 0.032260899 0.071760699, + -0.050876502 0.032051701 0.080876604, + -0.050626501 0.032201804 0.090000004, + -0.048646901 0.035344005 0.080876604, + -0.046506304 0.038733102 0.071760699, + -0.044318404 0.042172801 0.062659808, + -0.0420538 0.045682602 0.053581405, + -0.039679404 0.049277101 0.044533003, + -0.037159402 0.052965503 0.035522003, + -0.034455601 0.056751706 0.026555801, + -0.031528302 0.060633305 0.0176419, + -0.032538898 0.065346904 0, + -0.028337101 0.064602099 0.0087875305, + -0.0275915 0.067531407 0, + -0.024005601 0.066333704 0.0087875305, + -0.027452102 0.062584504 0.0176419, + -0.030629501 0.058904804 0.026555801, + -0.033577599 0.0553056 0.035522003, + -0.0363359 0.051791806 0.044533003, + -0.038942702 0.048362102 0.053581405, + -0.041434303 0.045009606 0.062659808, + -0.043844704 0.041722003 0.071760699, + -0.046204604 0.038481902 0.080876604, + -0.047047202 0.037236601 0.090000004, + -0.050626501 0.032201804 0.10200001, + -0.047047202 0.037236601 0.10200001, + -0.048478805 0.035222903 0.090000004, + -0.0107568 0.059027903 0.10200001, + -0.0107568 0.059027903 0.090000004, + -0.012781701 0.05855 0.090000004, + -0.042969104 0.041876599 0.10200001, + -0.038435601 0.046072803 0.10200001, + -0.040583003 0.044085205 0.090000004, + -0.016769102 0.057609003 0.10200001, + -0.016642701 0.057638805 0.090000004, + -0.012825901 0.058747105 0.080876604, + 0.021799201 0.067091107 0.0087875305, + 0.026185602 0.065503702 0.0087875305, + 0.026370602 0.068070509 0, + 0.021118402 0.064995803 0.0176419, + 0.016776601 0.0662494 0.0176419, + 0.016298402 0.064360805 0.026555801, + 0.012009101 0.065297209 0.026555801, + 0.011703101 0.063633405 0.035522003, + 0.0074719302 0.064267702 0.035522003, + 0.0073063406 0.062843502 0.044533003, + 0.0031370001 0.063189 0.044533003, + 0.0030787601 0.062015705 0.053581405, + -0.0010266301 0.062083501 0.053581405, + -0.0010115 0.061169002 0.062659808, + -0.0050519803 0.060968403 0.062659808, + -0.0049979906 0.060316704 0.071760699, + -0.0089152306 0.059466302 0.080876604, + -0.0089734299 0.059854504 0.071760699, + -0.0046305303 0.059821103 0.10200001, + -0.0049527204 0.059779305 0.090000004, + -0.0088871503 0.059269905 0.090000004, + 0.0015448701 0.059980102 0.10200001, + -0.0009900541 0.059914801 0.090000004, + -0.046060201 0.038359601 0.090000004, + -0.043441005 0.041339699 0.090000004, + -0.053669203 0.026825601 0.10200001, + -0.056143004 0.021165101 0.10200001, + -0.054476302 0.024978902 0.090000004, + -0.056065001 0.021343701 0.090000004, + -0.054659404 0.025061501 0.080876604, + -0.053669203 0.026825601 0.090000004, + -0.053228803 0.028806001 0.071760699, + -0.051761802 0.032609504 0.062659808, + -0.050233506 0.036496799 0.053581405, + -0.048614301 0.040488701 0.044533003, + -0.046870802 0.044601604 0.035522003, + -0.044966303 0.048846405 0.026555801, + -0.042861599 0.053228904 0.0176419, + -0.0439923 0.0582553 0, + -0.057290103 0.017572001 0.090000004, + -0.059626304 0.0059346003 0.090000004, + -0.0599204 0.0030887302 0.10200001, + 0.0029706601 0.059869703 0.090000004, + 0.0069263703 0.059563503 0.090000004, + 0.031500403 0.065805398 0, + 0.010876501 0.059139002 0.080876604, + 0.0069441902 0.059728604 0.080876604, + 0.0077039003 0.059503403 0.090000004, + 0.0109475 0.059525102 0.071760699, + 0.014857601 0.0586714 0.071760699, + 0.015018101 0.059305303 0.062659808, + 0.018904801 0.058183104 0.062659808, + 0.019187501 0.059053004 0.053581405, + 0.023048403 0.057655804 0.053581405, + 0.023484502 0.058746602 0.044533003, + 0.027315702 0.057066105 0.044533003, + 0.027934801 0.058359403 0.035522003, + 0.0317307 0.056385603 0.035522003, + 0.032560401 0.057859905 0.026555801, + 0.036313202 0.055581406 0.026555801, + 0.037378803 0.057212505 0.0176419, + 0.041078202 0.054617003 0.0176419, + 0.046035804 0.053452004 0.0087875305, + 0.042402502 0.056377705 0.0087875305, + 0.0439923 0.0582553 0, + 0.043875303 0.058335401 0, + 0.039893102 0.061063305 0, + 0.0137813 0.058395904 0.090000004, + 0.0491798 0.053947702 0, + 0.047596503 0.055262405 0, + 0.051137004 0.051990505 0, + 0.027084501 0.067755304 0, + 0.022534501 0.069356203 0, + 0.0220915 0.069504701 0, + 0.0199774 0.070213303 0, + -0.020393001 0.056348402 0.090000004, + -0.033494599 0.049780603 0.10200001, + -0.033494599 0.049780603 0.090000004, + -0.034430403 0.049078401 0.090000004, + 0.0034978201 0.070457004 0.0087875305, + 0.0036160401 0.072832808 0, + 0 0.073000006 0, + -0.0011663701 0.07053411 0.0087875305, + -0.00112994 0.068331301 0.0176419, + -0.00564352 0.068107203 0.0176419, + -0.0054826401 0.066165604 0.026555801, + -0.0098435702 0.065658607 0.026555801, + -0.0095927501 0.063985504 0.035522003, + -0.013800601 0.063211605 0.035522003, + -0.0134948 0.061810803 0.044533003, + -0.017550401 0.0607838 0.044533003, + -0.017224502 0.059655104 0.053581405, + -0.0211295 0.058386303 0.053581405, + -0.0208182 0.057526201 0.062659808, + -0.024574701 0.056024604 0.062659808, + -0.024312001 0.055425804 0.071760699, + -0.027922003 0.053697802 0.071760699, + -0.031206101 0.051399402 0.080876604, + -0.027740901 0.053349502 0.080876604, + -0.028198602 0.052960705 0.090000004, + -0.031097602 0.051220004 0.090000004, + -0.037603803 0.046697002 0.090000004, + -0.034534901 0.049224604 0.080876604, + -0.0314098 0.051735003 0.071760699, + -0.028223602 0.054277904 0.062659808, + -0.024942102 0.056862205 0.053581405, + -0.021529302 0.059491005 0.044533003, + -0.0179481 0.062161405 0.035522003, + -0.014161501 0.064864404 0.026555801, + -0.0101324 0.067585297 0.0176419, + -0.0058254604 0.070302807 0.0087875305, + -0.00120486 0.072944298 0, + -0.00602694 0.072721399 0, + -0.026370602 0.068070509 0, + -0.029292401 0.066780403 0, + -0.0336546 0.064725503 0, + -0.027229402 0.045308702 0.020000001, + -0.027740601 0.044521503 0.020000001, + -0.0275915 0.0447511 0, + -0.027740601 0.044521503 0, + -0.027229402 0.045308702 0, + -0.0378718 0.062376503 0, + -0.041884605 0.059699103 0, + -0.045739401 0.056804504 0, + -0.052843802 0.050283603 0, + -0.053947702 0.0491798 0, + -0.055045106 0.047858201 0, + 0.059682 -0.0061692605 0.10200001, + 0.059795801 -0.0039616702 0.090000004, + 0.058731303 -0.0122731 0.10200001, + 0.057158101 -0.018246902 0.10200001, + 0.057837006 -0.015668901 0.090000004, + -0.059285305 0.00923343 0.090000004, + -0.059310801 0.0098972199 0.080876604, + -0.059835203 0.0059557003 0.080876604, + -0.059698004 0.0099618305 0.071760699, + -0.058909103 0.013885501 0.071760699, + -0.059545506 0.014035501 0.062659808, + -0.058487706 0.017940301 0.062659808, + -0.059362203 0.0182085 0.053581405, + -0.058029003 0.022092 0.053581405, + -0.057509903 0.026368402 0.044533003, + -0.059126902 0.022509901 0.044533003, + -0.058813304 0.026966 0.035522003, + -0.056902502 0.030794101 0.035522003, + -0.058390304 0.031599302 0.026555801, + -0.0561742 0.0353892 0.026555801, + -0.057822704 0.036427703 0.0176419, + -0.055288702 0.040169604 0.0176419, + -0.057071101 0.041464601 0.0087875305, + -0.054205902 0.045145802 0.0087875305, + -0.0582553 0.0439923 0, + -0.056033403 0.046668001 0, + 0.022320401 -0.055834804 0.080876604, + 0.025961801 -0.054237504 0.080876604, + 0.025434902 -0.054342102 0.090000004, + 0.022466103 -0.056199301 0.071760699, + 0.018702801 -0.0575612 0.071760699, + 0.018904801 -0.058183104 0.062659808, + 0.015018101 -0.059305303 0.062659808, + 0.0152427 -0.060192004 0.053581405, + 0.011231201 -0.061067801 0.053581405, + 0.011443701 -0.062223203 0.044533003, + 0.0073063406 -0.062843502 0.044533003, + 0.0074719302 -0.064267702 0.035522003, + 0.0032081003 -0.064621009 0.035522003, + 0.0032919801 -0.066310704 0.026555801, + -0.0010977301 -0.066383302 0.026555801, + -0.00112994 -0.068331301 0.0176419, + -0.00564352 -0.068107203 0.0176419, + -0.0058254604 -0.070302807 0.0087875305, + -0.0104591 -0.0697641 0.0087875305, + -0.0067355903 -0.072688602 0, + -0.013413701 -0.071757004 0, + -0.010813001 -0.072119802 0, + -0.00602694 -0.072721399 0, + -0.00120486 -0.072944298 0, + 0.037500001 -0.062583603 0, + 0.038429502 -0.062065803 0, + 0.038583804 -0.059056904 0.0087875305, + 0.034596302 -0.061477803 0.0087875305, + 0.037378803 -0.057212505 0.0176419, + 0.041078202 -0.054617003 0.0176419, + 0.039907202 -0.053060003 0.026555801, + 0.043326702 -0.050306503 0.026555801, + 0.042222701 -0.049024604 0.035522003, + 0.0453704 -0.046126902 0.035522003, + 0.044365004 -0.045104701 0.044533003, + 0.047249004 -0.042074002 0.044533003, + 0.046371702 -0.041292705 0.053581405, + 0.048999302 -0.0381377 0.053581405, + 0.048277501 -0.037575904 0.062659808, + 0.050655402 -0.034303103 0.062659808, + 0.050113901 -0.033936404 0.071760699, + 0.052247204 -0.030550102 0.071760699, + 0.051908404 -0.030352 0.080876604, + 0.053800903 -0.026855001 0.080876604, + 0.0522171 -0.029552901 0.090000004, + -0.068070509 0.026370602 0, + -0.068205707 0.025967101 0, + -0.065927699 0.025099002 0.0087875305, + -0.069739707 0.021390202 0, + -0.057487305 -0.017633401 0.080876604, + -0.056196205 -0.021394201 0.080876604, + -0.056143004 -0.021165101 0.090000004, + -0.057862602 -0.017748501 0.071760699, + -0.068662107 0.016184401 0.0087875305, + -0.069581598 0.0116111 0.0087875305, + -0.067408502 0.0112485 0.0176419, + -0.068004601 0.0067688301 0.0176419, + -0.066356003 0.0021951499 0.026555801, + -0.066065907 0.0065758703 0.026555801, + -0.064665206 0.00213922 0.035522003, + -0.0629557 -0.0062662903 0.044533003, + -0.063232206 -0.0020918101 0.044533003, + -0.064665206 -0.00213922 0.035522003, + -0.061786704 -0.0061499402 0.053581405, + -0.061245203 -0.010220001 0.053581405, + -0.060343001 -0.010069501 0.062659808, + -0.059545506 -0.014035501 0.062659808, + -0.058909103 -0.013885501 0.071760699, + -0.058021706 -0.015280301 0.090000004, + -0.058527004 -0.013795501 0.080876604, + -0.070196904 -0.0069870404 0.0087875305, + -0.072620004 -0.0072273901 0, + -0.071953103 -0.0120083 0, + -0.031206101 -0.051399402 0.080876604, + -0.027740901 -0.053349502 0.080876604, + -0.028198602 -0.052960705 0.090000004, + -0.0314098 -0.051735003 0.071760699, + -0.059686702 -0.037602101 0.0087875305, + -0.0617451 -0.038897704 0, + -0.059017103 -0.0428802 0, + -0.062065803 -0.038429502 0, + -0.062041406 -0.033575103 0.0087875305, + -0.057822704 -0.036427703 0.0176419, + -0.055288702 -0.040169604 0.0176419, + -0.053712506 -0.039024401 0.026555801, + -0.051016003 -0.042489 0.026555801, + -0.049716003 -0.041406401 0.035522003, + -0.046870802 -0.044601604 0.035522003, + -0.045832004 -0.043613203 0.044533003, + -0.042849403 -0.046546903 0.044533003, + -0.0420538 -0.045682602 0.053581405, + -0.038942702 -0.048362102 0.053581405, + -0.038369 -0.047649603 0.062659808, + -0.035135899 -0.050081301 0.062659808, + -0.0347603 -0.049546003 0.071760699, + -0.033494599 -0.049780603 0.090000004, + -0.034534901 -0.049224604 0.080876604, + -0.037958901 -0.047140304 0.071760699, + -0.041434303 -0.045009606 0.062659808, + -0.044981003 -0.042803399 0.053581405, + -0.048614301 -0.040488701 0.044533003, + -0.052343901 -0.038030103 0.035522003, + -0.0561742 -0.0353892 0.026555801, + -0.060103804 -0.032526501 0.0176419, + -0.065346904 -0.032538898 0, + -0.064676702 -0.033742201 0, + -0.064124703 -0.029401401 0.0087875305, + -0.068070509 -0.026370602 0, + -0.067545101 -0.0275605 0, + -0.065927699 -0.025099002 0.0087875305, + -0.062122006 -0.028483102 0.0176419, + -0.058390304 -0.031599302 0.026555801, + -0.054742903 -0.034487501 0.035522003, + -0.051183902 -0.037187304 0.044533003, + -0.047711603 -0.0397369 0.053581405, + -0.044318404 -0.042172801 0.062659808, + -0.040991403 -0.044528503 0.071760699, + -0.037712701 -0.046834599 0.080876604, + -0.037603803 -0.046697002 0.090000004, + -0.038435601 -0.046072803 0.090000004, + -0.040725499 -0.044239704 0.080876604, + -0.047008704 -0.039151601 0.062659808, + -0.043844704 -0.041722003 0.071760699, + -0.050233506 -0.036496799 0.053581405, + -0.053529702 -0.033723202 0.044533003, + -0.056902502 -0.030794101 0.035522003, + -0.060351104 -0.027671102 0.026555801, + -0.063868701 -0.024315203 0.0176419, + -0.067442402 -0.020687001 0.0087875305, + -0.069739707 -0.021390202 0, + -0.068662107 -0.016184401 0.0087875305, + -0.065336101 -0.0200409 0.0176419, + -0.062047902 -0.023622001 0.026555801, + -0.058813304 -0.026966 0.035522003, + -0.055641502 -0.030111702 0.044533003, + -0.052535802 -0.033097003 0.053581405, + -0.049493503 -0.035959102 0.062659808, + -0.046506304 -0.038733102 0.071760699, + -0.0435603 -0.041451402 0.080876604, + -0.042969104 -0.041876599 0.090000004, + -0.0366101 -0.060300302 0.0087875305, + -0.0378718 -0.062376503 0, + -0.037500001 -0.062583603 0, + -0.040515304 -0.057748903 0.0087875305, + -0.035466705 -0.058417004 0.0176419, + -0.031528302 -0.060633305 0.0176419, + -0.030629501 -0.058904804 0.026555801, + -0.026669502 -0.060800303 0.026555801, + -0.025989901 -0.0592511 0.035522003, + -0.022017201 -0.060839202 0.035522003, + -0.021529302 -0.059491005 0.044533003, + -0.017550401 -0.0607838 0.044533003, + -0.017224502 -0.059655104 0.053581405, + -0.0132442 -0.060663104 0.053581405, + -0.013049101 -0.059769403 0.062659808, + -0.0090703703 -0.060501203 0.062659808, + -0.0089734299 -0.059854504 0.071760699, + -0.0049979906 -0.060316704 0.071760699, + -0.0046305303 -0.059821103 0.090000004, + -0.0049655703 -0.0599255 0.080876604, + -0.00099420105 -0.060122702 0.080876604, + -0.028337101 -0.064602099 0.0087875305, + -0.0275915 -0.067531407 0, + -0.0275605 -0.067545101 0, + -0.029292401 -0.066780403 0, + -0.032538898 -0.065346904 0, + -0.032544702 -0.062588006 0.0087875305, + -0.023255801 -0.064262003 0.0176419, + -0.027452102 -0.062584504 0.0176419, + -0.0225929 -0.062430002 0.026555801, + -0.018417401 -0.063786708 0.026555801, + -0.0179481 -0.062161405 0.035522003, + -0.013800601 -0.063211605 0.035522003, + -0.0134948 -0.061810803 0.044533003, + -0.0093801608 -0.062567502 0.044533003, + -0.0092059905 -0.061405804 0.053581405, + -0.0051275203 -0.061880004 0.053581405, + -0.0050519803 -0.060968403 0.062659808, + -0.0010115 -0.061169002 0.062659808, + -0.00100069 -0.060515203 0.071760699, + 0.00300098 -0.060449004 0.071760699, + 0.00298152 -0.060056902 0.080876604, + 0.0069441902 -0.059728604 0.080876604, + 0.0069263703 -0.059563503 0.090000004, + 0.0015448701 -0.059980102 0.10200001, + 0.0015448701 -0.059980102 0.090000004, + 0.0029706601 -0.059869703 0.090000004, + -0.052708603 -0.028523002 0.090000004, + -0.050754502 -0.031975601 0.090000004, + -0.050626501 -0.032201804 0.10200001, + -0.052883502 -0.028619101 0.080876604, + -0.053669203 -0.026825601 0.090000004, + -0.053669203 -0.026825601 0.10200001, + -0.048478805 -0.035222903 0.090000004, + -0.047047202 -0.037236601 0.10200001, + -0.042969104 -0.041876599 0.10200001, + -0.046060201 -0.038359601 0.090000004, + 0.025434902 -0.054342102 0.10200001, + 0.0197125 -0.056669403 0.10200001, + 0.0222423 -0.0556405 0.090000004, + 0.0185815 -0.057187904 0.080876604, + 0.018526802 -0.057014503 0.090000004, + 0.014717301 -0.058123406 0.090000004, + 0.010838601 -0.058932099 0.090000004, + 0.0137813 -0.058395904 0.10200001, + 0.0077039003 -0.059503403 0.10200001, + -0.0336546 -0.064725503 0, + -0.054205902 -0.045145802 0.0087875305, + -0.056033403 -0.046668001 0, + -0.055045106 -0.047858201 0, + -0.020462099 -0.056542199 0.080876604, + -0.020393001 -0.056348402 0.090000004, + -0.022603702 -0.055579402 0.090000004, + -0.016769102 -0.057609003 0.090000004, + -0.016769102 -0.057609003 0.10200001, + -0.016642701 -0.057638805 0.090000004, + -0.0107568 -0.059027903 0.10200001, + -0.0107568 -0.059027903 0.090000004, + -0.0088871503 -0.059269905 0.090000004, + -0.012781701 -0.05855 0.090000004, + -0.012825901 -0.058747105 0.080876604, + -0.047778003 -0.051900703 0.0087875305, + -0.0511037 -0.048629604 0.0087875305, + -0.051431704 -0.051695805 0, + -0.046285804 -0.050279804 0.0176419, + -0.042861599 -0.053228904 0.0176419, + -0.041639704 -0.0517115 0.026555801, + -0.038131002 -0.054350402 0.026555801, + -0.037159402 -0.052965503 0.035522003, + -0.033577599 -0.0553056 0.035522003, + -0.032833502 -0.054080006 0.044533003, + -0.029187601 -0.056131702 0.044533003, + -0.028645601 -0.055089504 0.053581405, + -0.024942102 -0.056862205 0.053581405, + -0.024574701 -0.056024604 0.062659808, + -0.0208182 -0.057526201 0.062659808, + -0.0205957 -0.056911401 0.071760699, + -0.016789401 -0.058148105 0.071760699, + -0.016680501 -0.057771001 0.080876604, + -0.024312001 -0.055425804 0.071760699, + -0.028223602 -0.054277904 0.062659808, + -0.032223903 -0.053075805 0.053581405, + -0.0363359 -0.051791806 0.044533003, + -0.040578704 -0.050393801 0.035522003, + -0.044966303 -0.048846405 0.026555801, + -0.049507603 -0.047110803 0.0176419, + -0.053947702 -0.0491798 0, + -0.052843802 -0.050283603 0, + -0.073000006 0 0, + -0.072888605 -0.0024103201 0, + -0.070505209 -0.0023324103 0.0087875305, + -0.072688602 -0.0067355903 0, + -0.0582553 -0.0439923 0, + -0.057071101 -0.041464601 0.0087875305, + -0.052513003 -0.043735802 0.0176419, + -0.048096299 -0.045767803 0.026555801, + -0.0438205 -0.0476018 0.035522003, + -0.039679404 -0.049277101 0.044533003, + -0.035661202 -0.050830103 0.053581405, + -0.031749204 -0.0522939 0.062659808, + -0.027922003 -0.053697802 0.071760699, + -0.024154302 -0.055066302 0.080876604, + -0.028198602 -0.052960705 0.10200001, + -0.033494599 -0.049780603 0.10200001, + -0.031097602 -0.051220004 0.090000004, + -0.024075601 -0.054890502 0.090000004, + -0.022603702 -0.055579402 0.10200001, + -0.027668901 -0.053208701 0.090000004, + -0.034430403 -0.049078401 0.090000004, + -0.038435601 -0.046072803 0.10200001, + -0.0046305303 -0.059821103 0.10200001, + -0.0049527204 -0.059779305 0.090000004, + -0.0089152306 -0.059466302 0.080876604, + -0.012909601 -0.059130602 0.071760699, + -0.016970802 -0.0587763 0.062659808, + -0.0211295 -0.058386303 0.053581405, + -0.025414001 -0.057938002 0.044533003, + -0.029849101 -0.057403903 0.035522003, + -0.034455601 -0.056751706 0.026555801, + -0.039250001 -0.055945303 0.0176419, + -0.044243403 -0.054944903 0.0087875305, + -0.0491798 -0.053947702 0, + -0.0275915 -0.041793205 0, + -0.027007401 -0.041071802 0.020000001, + -0.027598102 -0.041801304 0.020000001, + -0.027598102 -0.041801304 0, + -0.0275915 -0.0447511 0, + -0.027740601 -0.044521503 0, + -0.027740601 -0.044521503 0.020000001, + -0.027229402 -0.045308702 0.020000001, + -0.027229402 -0.045308702 0, + -0.038429502 -0.062065803 0, + -0.0439923 -0.0582553 0, + -0.041884605 -0.059699103 0, + -0.045739401 -0.056804504 0, + -0.0009900541 -0.059914801 0.090000004, + -0.040583003 -0.044085205 0.090000004, + -0.064138204 -0.034708902 0, + -0.066292904 -0.030396501 0, + -0.068205707 -0.025967101 0, + -0.070213303 -0.0199774 0, + -0.071757004 -0.013413701 0, + -0.070977002 -0.016730102 0, + -0.068004601 -0.0067688301 0.0176419, + -0.067408502 -0.0112485 0.0176419, + -0.065486804 -0.010927801 0.026555801, + -0.064621404 -0.015232001 0.026555801, + -0.062974803 -0.014843901 0.035522003, + -0.061856102 -0.0189735 0.035522003, + -0.0604853 -0.018553 0.044533003, + -0.059126902 -0.022509901 0.044533003, + -0.056442104 -0.0258788 0.053581405, + -0.058029003 -0.022092 0.053581405, + -0.055610601 -0.025497602 0.062659808, + -0.053803906 -0.029117202 0.062659808, + -0.053228803 -0.028806001 0.071760699, + -0.0512086 -0.032260899 0.071760699, + -0.050876502 -0.032051701 0.080876604, + -0.050626501 -0.032201804 0.090000004, + -0.048646901 -0.035344005 0.080876604, + -0.046204604 -0.038481902 0.080876604, + -0.047047202 -0.037236601 0.090000004, + -0.048964504 -0.035574801 0.071760699, + -0.051761802 -0.032609504 0.062659808, + -0.0546083 -0.029552501 0.053581405, + -0.057509903 -0.026368402 0.044533003, + -0.060466904 -0.0230201 0.035522003, + -0.0634735 -0.019469602 0.026555801, + -0.066517703 -0.015679 0.0176419, + -0.069581598 -0.0116111 0.0087875305, + -0.071871698 -0.012591501 0, + -0.043441005 -0.041339699 0.090000004, + -0.055016205 -0.025225101 0.071760699, + -0.057174202 -0.021766502 0.062659808, + -0.059362203 -0.0182085 0.053581405, + -0.061579205 -0.014514901 0.044533003, + -0.063818201 -0.0106494 0.035522003, + -0.066065907 -0.0065758703 0.026555801, + -0.068303205 -0.0022595699 0.0176419, + -0.070505209 0.0023324103 0.0087875305, + -0.072688602 0.0067355903 0, + -0.072888605 0.0024103201 0, + -0.071953103 0.0120083 0, + -0.072620004 0.0072273901 0, + -0.070196904 0.0069870404 0.0087875305, + -0.068303205 0.0022595699 0.0176419, + -0.066356003 -0.0021951499 0.026555801, + -0.064382501 -0.00640831 0.035522003, + -0.062403902 -0.0104134 0.044533003, + -0.060435802 -0.014245401 0.053581405, + -0.058487706 -0.017940301 0.062659808, + -0.056563102 -0.021533901 0.071760699, + -0.054659404 -0.025061501 0.080876604, + -0.056143004 -0.021165101 0.10200001, + -0.056065001 -0.021343701 0.090000004, + -0.054476302 -0.024978902 0.090000004, + 0.0123615 -0.067213304 0.0176419, + 0.0078922901 -0.067883305 0.0176419, + 0.00814672 -0.070071802 0.0087875305, + 0.016298402 -0.064360805 0.026555801, + 0.012009101 -0.065297209 0.026555801, + 0.015883101 -0.062720798 0.035522003, + 0.019993601 -0.061533906 0.035522003, + 0.019550502 -0.060170304 0.044533003, + 0.023484502 -0.058746602 0.044533003, + 0.023048403 -0.057655804 0.053581405, + 0.026808502 -0.056006502 0.053581405, + 0.026413603 -0.055181403 0.062659808, + 0.030002801 -0.053315103 0.062659808, + 0.029682102 -0.052745204 0.071760699, + 0.033103202 -0.050668202 0.071760699, + 0.032888502 -0.050339602 0.080876604, + 0.036143504 -0.048055902 0.080876604, + 0.036012903 -0.0479904 0.090000004, + 0.045067903 -0.039609101 0.090000004, + 0.044907004 -0.039988499 0.080876604, + 0.047451701 -0.036933202 0.080876604, + 0.045200203 -0.040249601 0.071760699, + 0.042441301 -0.043148901 0.071760699, + 0.042899802 -0.043615103 0.062659808, + 0.0399235 -0.046355002 0.062659808, + 0.040520404 -0.047048103 0.053581405, + 0.037322301 -0.049623203 0.053581405, + 0.038028501 -0.050562002 0.044533003, + 0.034603599 -0.052964803 0.044533003, + 0.035387903 -0.054165203 0.035522003, + 0.0317307 -0.056385603 0.035522003, + 0.032560401 -0.057859905 0.026555801, + 0.0286652 -0.059885301 0.026555801, + 0.029506302 -0.061642602 0.0176419, + 0.0253678 -0.063457906 0.0176419, + 0.026185602 -0.065503702 0.0087875305, + 0.021799201 -0.067091107 0.0087875305, + 0.026370602 -0.068070509 0, + 0.027084501 -0.067755304 0, + 0.0275605 -0.067545101 0, + 0.030457601 -0.063629799 0.0087875305, + 0.033515804 -0.059557803 0.0176419, + 0.036313202 -0.055581406 0.026555801, + 0.038890302 -0.051708002 0.035522003, + 0.041287001 -0.047938205 0.044533003, + 0.0435412 -0.044267204 0.053581405, + 0.045688502 -0.040684402 0.062659808, + 0.047761504 -0.037174303 0.071760699, + 0.0497889 -0.033716302 0.080876604, + 0.048901703 -0.034765303 0.090000004, + 0.053612601 -0.026761001 0.090000004, + 0.054979004 -0.024027202 0.10200001, + 0.0522171 -0.029552901 0.10200001, + 0.042026799 -0.042729501 0.090000004, + 0.0447958 -0.039888304 0.090000004, + 0.045067903 -0.039609101 0.10200001, + 0.042166002 -0.042869002 0.080876604, + 0.040756404 -0.044033103 0.090000004, + 0.040756404 -0.044033103 0.10200001, + 0.047287602 -0.036804602 0.090000004, + 0.048901703 -0.034765303 0.10200001, + 0.049634304 -0.033613499 0.090000004, + 0.051763702 -0.030265803 0.090000004, + 0.039496701 -0.045859504 0.071760699, + 0.036772501 -0.048892204 0.062659808, + 0.033961102 -0.051981401 0.053581405, + 0.031027501 -0.055136003 0.044533003, + 0.027934801 -0.058359403 0.035522003, + 0.024644701 -0.061648902 0.026555801, + 0.021118402 -0.064995803 0.0176419, + 0.0199774 -0.070213303 0, + 0.0220915 -0.069504701 0, + 0.0173175 -0.068385102 0.0087875305, + 0.012760001 -0.069380097 0.0087875305, + 0.013413701 -0.071757004 0, + 0.016776601 -0.0662494 0.0176419, + 0.020516401 -0.063142903 0.026555801, + 0.024016703 -0.060078003 0.035522003, + 0.027315702 -0.057066105 0.044533003, + 0.030451402 -0.054112203 0.053581405, + 0.033460803 -0.0512156 0.062659808, + 0.036379501 -0.048369601 0.071760699, + 0.039240602 -0.045562103 0.080876604, + 0.036012903 -0.0479904 0.10200001, + 0.036062699 -0.047948703 0.090000004, + 0.039108898 -0.045407504 0.090000004, + 0.030887602 -0.051438902 0.10200001, + 0.032775603 -0.0501686 0.090000004, + 0.030887602 -0.051438902 0.090000004, + 0.0084222499 -0.072453305 0, + 0.0067355903 -0.072688602 0, + 0.0034978201 -0.070457004 0.0087875305, + -0.0011663701 -0.07053411 0.0087875305, + 0 -0.073000006 0, + 0.0033885802 -0.068256505 0.0176419, + 0.0076673008 -0.065948099 0.026555801, + 0.011703101 -0.063633405 0.035522003, + 0.015531101 -0.061330803 0.044533003, + 0.019187501 -0.059053004 0.053581405, + 0.022708902 -0.056806501 0.062659808, + 0.026131302 -0.0545916 0.071760699, + 0.029489601 -0.0524031 0.080876604, + 0.025893701 -0.054097805 0.090000004, + 0.029395701 -0.052233204 0.090000004, + -0.058021706 -0.015280301 0.10200001, + -0.057290103 -0.017572001 0.090000004, + -0.071871698 0.012591501 0, + -0.071757004 0.013413701 0, + -0.070977002 0.016730102 0, + -0.070213303 0.0199774 0, + -0.067442402 0.020687001 0.0087875305, + -0.066517703 0.015679 0.0176419, + -0.065486804 0.010927801 0.026555801, + -0.064382501 0.00640831 0.035522003, + -0.063232206 0.0020918101 0.044533003, + -0.062058106 -0.00205297 0.053581405, + -0.060876504 -0.0060593402 0.062659808, + -0.059698004 -0.0099618305 0.071760699, + -0.065336101 0.0200409 0.0176419, + -0.063868701 0.024315203 0.0176419, + -0.0634735 0.019469602 0.026555801, + -0.064621404 0.015232001 0.026555801, + -0.062974803 0.014843901 0.035522003, + -0.063818201 0.0106494 0.035522003, + -0.062403902 0.0104134 0.044533003, + -0.0629557 0.0062662903 0.044533003, + -0.061786704 0.0061499402 0.053581405, + -0.062058106 0.00205297 0.053581405, + -0.060225803 -0.0059945802 0.071760699, + -0.060490303 -0.0020011102 0.071760699, + -0.061143905 -0.0020227302 0.062659808, + -0.059835203 -0.0059557003 0.080876604, + -0.059310801 -0.0098972199 0.080876604, + -0.059285305 -0.00923343 0.090000004, + -0.059152305 -0.0098695504 0.090000004, + -0.067545101 0.0275605 0, + -0.064124703 0.029401401 0.0087875305, + -0.060225803 0.0059945802 0.071760699, + -0.060490303 0.0020011102 0.071760699, + -0.060098004 0.0019881302 0.080876604, + -0.060876504 0.0060593402 0.062659808, + -0.060343001 0.010069501 0.062659808, + -0.061245203 0.010220001 0.053581405, + -0.060435802 0.014245401 0.053581405, + -0.061579205 0.014514901 0.044533003, + -0.0604853 0.018553 0.044533003, + -0.061856102 0.0189735 0.035522003, + -0.060466904 0.0230201 0.035522003, + -0.062047902 0.023622001 0.026555801, + -0.060351104 0.027671102 0.026555801, + -0.062122006 0.028483102 0.0176419, + -0.060103804 0.032526501 0.0176419, + -0.062041406 0.033575103 0.0087875305, + -0.059686702 0.037602101 0.0087875305, + -0.062065803 0.038429502 0, + -0.064138204 0.034708902 0, + -0.064676702 0.033742201 0, + -0.065346904 0.032538898 0, + -0.061143905 0.0020227302 0.062659808, + -0.060098004 -0.0019881302 0.080876604, + -0.0599204 -0.0030887302 0.090000004, + -0.059626304 -0.0059346003 0.090000004, + -0.059285305 -0.00923343 0.10200001, + -0.058340803 -0.013753101 0.090000004, + 0.056699503 -0.019463301 0.090000004, + 0.0568728 -0.019524502 0.080876604, + 0.055300001 -0.023175802 0.090000004, + 0.054979004 -0.024027202 0.090000004, + 0.032538898 -0.065346904 0, + 0.031500403 -0.065805398 0, + 0.035763402 -0.063550904 0, + 0.022534501 -0.069356203 0, + 0.017905002 -0.070700705 0, + 0.013203001 -0.071786404 0, + 0.0036160401 -0.072832808 0, + 0.0197125 -0.056669403 0.090000004, + 0.014857601 -0.0586714 0.071760699, + 0.011065801 -0.060168203 0.062659808, + 0.0071706804 -0.061676603 0.053581405, + 0.0031370001 -0.063189 0.044533003, + -0.0010697601 -0.064691804 0.035522003, + -0.0054826401 -0.066165604 0.026555801, + -0.0101324 -0.067585297 0.0176419, + -0.015047001 -0.068920307 0.0087875305, + -0.0199774 -0.070213303 0, + -0.0155552 -0.071253404 0, + 0.010876501 -0.059139002 0.080876604, + 0.014761301 -0.058290903 0.080876604, + 0.0137813 -0.058395904 0.090000004, + 0.0109475 -0.059525102 0.071760699, + 0.0069895303 -0.060118504 0.071760699, + 0.0070650405 -0.060768005 0.062659808, + 0.0030334003 -0.061102103 0.062659808, + 0.0030787601 -0.062015705 0.053581405, + -0.0010266301 -0.062083501 0.053581405, + -0.00104605 -0.063258104 0.044533003, + -0.0052245306 -0.063050702 0.044533003, + -0.0053429301 -0.064479604 0.035522003, + -0.0095927501 -0.063985504 0.035522003, + -0.0098435702 -0.065658607 0.026555801, + -0.014161501 -0.064864404 0.026555801, + -0.014577 -0.066767901 0.0176419, + -0.0189579 -0.065658502 0.0176419, + -0.019569002 -0.067775205 0.0087875305, + -0.024005601 -0.066333704 0.0087875305, + -0.024823202 -0.068589106 0, + -0.026370602 -0.068070509 0, + -0.020246401 -0.070123106 0, + 0.0077039003 -0.059503403 0.090000004, + 0.0220915 -0.043992702 0, + 0.0220656 -0.043925002 0, + 0.0220656 -0.043925002 0.020000001, + 0.022401901 -0.044801302 0.020000001, + 0.022401901 -0.044801302 0, + 0.022259401 -0.042081103 0.020000001, + 0.0220164 -0.042987704 0.020000001, + 0.0220915 -0.042707402 0, + 0.0220164 -0.042987704 0, + -0.027007401 -0.041071802 0, + -0.066292904 0.030396501 0, + -0.0617451 0.038897704 0, + -0.059017103 0.0428802 0, + -0.0599204 0.0030887302 0.090000004, + -0.0599204 -0.0030887302 0.10200001, + 0.059411902 -0.0079035703 0.090000004, + 0.058801305 -0.011823701 0.090000004, + 0.059605602 -0.0079307901 0.080876604, + 0.058038902 -0.015723001 0.080876604, + 0.058951102 -0.011852801 0.080876604, + 0.058731303 -0.0122731 0.090000004, + 0.058417805 -0.0158257 0.071760699, + 0.0572441 -0.019651901 0.071760699, + 0.057862602 -0.019864202 0.062659808, + 0.056423202 -0.023645002 0.062659808, + 0.057266802 -0.023998503 0.053581405, + 0.055555601 -0.027730802 0.053581405, + 0.056606606 -0.028255502 0.044533003, + 0.054615505 -0.031934902 0.044533003, + 0.055853203 -0.032658603 0.035522003, + 0.053572703 -0.036278602 0.035522003, + 0.054973401 -0.037227202 0.026555801, + 0.0523929 -0.040779002 0.026555801, + 0.053930305 -0.041975703 0.0176419, + 0.051038202 -0.045448203 0.0176419, + 0.049467903 -0.0502926 0.0087875305, + 0.052683603 -0.046913303 0.0087875305, + 0.053947702 -0.0491798 0, + 0.054491505 -0.048524801 0, + 0.055045106 -0.047858201 0, + 0.055668902 -0.0433289 0.0087875305, + 0.056586605 -0.038319603 0.0176419, + 0.057313602 -0.0335126 0.026555801, + 0.057889502 -0.028895902 0.035522003, + 0.058350302 -0.024452602 0.044533003, + 0.0587277 -0.0201612 0.053581405, + 0.059048902 -0.015996601 0.062659808, + 0.059336003 -0.0119302 0.071760699, + 0.057158101 -0.018246902 0.090000004, + 0.0558201 -0.023392301 0.071760699, + 0.054737203 -0.027322302 0.062659808, + 0.053601302 -0.031341903 0.053581405, + 0.052385505 -0.035474602 0.044533003, + 0.051057901 -0.039739899 0.035522003, + 0.0495832 -0.044152502 0.026555801, + 0.047922902 -0.048722003 0.0176419, + 0.046035804 -0.053452004 0.0087875305, + 0.0491798 -0.053947702 0, + 0.042402502 -0.056377705 0.0087875305, + 0.0439923 -0.0582553 0, + 0.044598103 -0.051782701 0.0176419, + 0.046556804 -0.047333002 0.026555801, + 0.048319805 -0.043027502 0.035522003, + 0.0499264 -0.0388593 0.044533003, + 0.051412802 -0.0348159 0.053581405, + 0.052811701 -0.030880202 0.062659808, + 0.054152101 -0.027030302 0.071760699, + 0.055458102 -0.023240501 0.080876604, + 0.039893102 -0.061063305 0, + 0.043875303 -0.058335401 0, + 0.047596503 -0.055262405 0, + 0.051137004 -0.051990505 0, + 0.022259401 -0.042081103 0, + 0.057837006 0.015668901 0.090000004, + 0.057158101 0.018246902 0.10200001, + 0.058731303 0.0122731 0.10200001, + 0.059411902 0.0079035703 0.090000004, + 0.058801305 0.011823701 0.090000004, + 0.059682 -0.0061692605 0.090000004, + 0.0582553 -0.0439923 0, + 0.0603812 -0.040888805 0, + 0.057575405 -0.044811103 0, + -0.027007401 0.041071802 0, + -0.027598102 0.041801304 0, + 0.0067355903 0.072688602 0, + 0.00814672 0.070071802 0.0087875305, + 0.0033885802 0.068256505 0.0176419, + -0.0010977301 0.066383302 0.026555801, + -0.0053429301 0.064479604 0.035522003, + -0.0093801608 0.062567502 0.044533003, + -0.0132442 0.060663104 0.053581405, + -0.016970802 0.0587763 0.062659808, + -0.0205957 0.056911401 0.071760699, + -0.024154302 0.055066302 0.080876604, + -0.027668901 0.053208701 0.090000004, + 0.017905002 0.070700705 0, + 0.022401901 0.044801302 0, + 0.022259401 0.042081103 0, + 0.0653124 -0.032600902 0, + 0.071529604 -0.0143806 0, + 0.0680895 -0.018445801 0.0087875305, + 0.066999704 -0.0134711 0.0176419, + 0.065812305 -0.0087566301 0.026555801, + 0.064559199 -0.0042761005 0.035522003, + 0.063266806 0 0.044533003, + 0.061956301 0.0041037002 0.053581405, + 0.060642902 0.0080688111 0.062659808, + 0.059336003 0.0119302 0.071760699, + 0.058731303 0.0122731 0.090000004, + 0.058951102 0.011852801 0.080876604, + 0.059994705 0.0079825707 0.071760699, + 0.061043601 0.0040432503 0.062659808, + 0.062092002 0 0.053581405, + 0.063128501 -0.0041813403 0.044533003, + 0.064135402 -0.0085335001 0.035522003, + 0.065089703 -0.0130871 0.026555801, + 0.065963 -0.0178697 0.0176419, + 0.066721499 -0.022905501 0.0087875305, + 0.070213303 -0.0199774 0, + 0.068070509 -0.026370602 0, + 0.068972602 -0.023678901 0, + 0.0704244 -0.0190796 0, + -0.0599204 0.0019838002 0.090000004, + -0.0599204 -0.0019838002 0.090000004, + 0.057212602 -0.0239105 0, + 0.057567701 -0.023213601 0, + 0.057212602 -0.0239105 0.020000001, + 0.057567701 -0.023213601 0.020000001, + 0.0570902 -0.024683101 0.020000001, + 0.0570902 -0.024683101 0, + 0.057212602 -0.025455602 0.020000001, + 0.057567701 -0.026152501 0.020000001, + 0.058120802 -0.026705602 0.020000001, + 0.058817703 -0.027060701 0.020000001, + 0.059590202 -0.027183101 0.020000001, + 0.060362805 -0.027060701 0.020000001, + 0.061059702 -0.026705602 0.020000001, + 0.061612803 -0.026152501 0.020000001, + 0.061967902 -0.025455602 0.020000001, + 0.058120802 -0.022660501 0.020000001, + 0.058817703 -0.022305401 0.020000001, + 0.059590202 -0.022183102 0.020000001, + 0.060362805 -0.022305401 0.020000001, + 0.061059702 -0.022660501 0.020000001, + 0.062090203 -0.024683101 0.020000001, + 0.061967902 -0.0239105 0.020000001, + 0.061612803 -0.023213601 0.020000001, + 0.057212602 -0.025455602 0, + -0.023500001 0.040703204 0, + -0.024376301 0.040366799 0, + -0.023500001 0.040703204 0.020000001, + -0.024376301 0.040366799 0.020000001, + -0.0227706 0.0412939 0.020000001, + -0.0227706 0.0412939 0, + -0.026220201 0.040560603 0.020000001, + -0.025313601 0.040317703 0.020000001, + -0.026220201 0.040560603 0, + -0.025313601 0.040317703 0, + -0.022259401 0.042081103 0.020000001, + -0.0220164 0.042987704 0.020000001, + -0.0220656 0.043925002 0.020000001, + -0.022401901 0.044801302 0.020000001, + -0.0229926 0.045530703 0.020000001, + -0.023779802 0.046041902 0.020000001, + -0.027934402 0.042677503 0.020000001, + -0.0246864 0.046284802 0.020000001, + -0.0256237 0.046235699 0.020000001, + -0.026500002 0.045899302 0.020000001, + -0.027983602 0.043614902 0.020000001, + -0.0235481 0.057362705 0, + -0.024292002 0.057121001 0, + -0.0235481 0.057362705 0.020000001, + -0.024292002 0.057121001 0.020000001, + -0.022915302 0.057822499 0.020000001, + -0.022915302 0.057822499 0, + -0.0222139 0.059199102 0, + -0.022455601 0.058455303 0, + -0.0222139 0.059199102 0.020000001, + -0.022455601 0.058455303 0.020000001, + -0.0222139 0.059981301 0.020000001, + -0.0222139 0.059981301 0, + -0.025074201 0.057121001 0, + -0.025074201 0.057121001 0.020000001, + -0.027152302 0.059199102 0, + -0.027152302 0.059981301 0, + -0.027152302 0.059199102 0.020000001, + -0.027152302 0.059981301 0.020000001, + -0.026910601 0.058455303 0.020000001, + -0.026910601 0.058455303 0, + -0.026450802 0.057822499 0.020000001, + -0.026910601 0.060725205 0.020000001, + -0.026450802 0.061358005 0.020000001, + -0.025818102 0.061817702 0.020000001, + -0.025818102 0.057362705 0.020000001, + -0.025074201 0.062059503 0.020000001, + -0.024292002 0.062059503 0.020000001, + -0.0235481 0.061817702 0.020000001, + -0.022915302 0.061358005 0.020000001, + -0.022455601 0.060725205 0.020000001, + -0.026450802 0.057822499 0, + -0.025818102 0.057362705 0, + -0.024292002 0.062059503 0, + -0.025074201 0.062059503 0, + -0.0235481 0.061817702 0, + -0.022915302 0.061358005 0, + -0.025818102 0.061817702 0, + -0.022455601 0.060725205 0, + 0.023779802 0.046041902 0, + 0.0246864 0.046284802 0, + 0.023779802 0.046041902 0.020000001, + 0.0246864 0.046284802 0.020000001, + 0.0229926 0.045530703 0.020000001, + 0.0229926 0.045530703 0, + 0.027983602 0.043614902 0.020000001, + 0.027740601 0.044521503 0.020000001, + 0.027983602 0.043614902 0, + 0.027740601 0.044521503 0, + 0.027934402 0.042677503 0, + 0.027934402 0.042677503 0.020000001, + 0.027598102 0.041801304 0, + 0.027598102 0.041801304 0.020000001, + 0.027007401 0.041071802 0, + 0.027007401 0.041071802 0.020000001, + 0.027060701 0.060362805 0.020000001, + 0.026705602 0.061059702 0.020000001, + 0.027060701 0.060362805 0, + 0.026705602 0.061059702 0, + 0.027183101 0.059590202 0, + 0.027183101 0.059590202 0.020000001, + 0.048236601 -0.0024270501 0, + 0.0475729 -0.0017633601 0, + 0.048236601 -0.0024270501 0.020000001, + 0.0475729 -0.0017633601 0.020000001, + 0.049072903 -0.00285317 0.020000001, + 0.049072903 -0.00285317 0, + 0.050000001 -0.003 0.020000001, + 0.050000001 -0.003 0, + 0.050927103 -0.00285317 0.020000001, + 0.050927103 -0.00285317 0, + 0.051763404 -0.0024270501 0.020000001, + 0.051763404 -0.0024270501 0, + 0.052427102 -0.0017633601 0, + 0.052427102 -0.0017633601 0.020000001, + 0.052853201 -0.00092705106 0.020000001, + 0.052853201 -0.00092705106 0, + 0.049072903 0.00285317 0, + 0.050000001 0.003 0, + 0.049072903 0.00285317 0.020000001, + 0.050000001 0.003 0.020000001, + 0.048236601 0.0024270501 0.020000001, + 0.048236601 0.0024270501 0, + 0.050927103 0.00285317 0, + 0.050927103 0.00285317 0.020000001, + 0.051763404 0.0024270501 0, + 0.052427102 0.0017633601 0, + 0.051763404 0.0024270501 0.020000001, + 0.052427102 0.0017633601 0.020000001, + 0.052853201 0.00092705106 0, + 0.053000003 0 0, + 0.052853201 0.00092705106 0.020000001, + 0.053000003 0 0.020000001, + 0.0475729 0.0017633601 0.020000001, + 0.047146805 0.00092705106 0.020000001, + 0.047000002 0 0.020000001, + 0.047146805 -0.00092705106 0.020000001, + 0.047000002 0 0, + 0.047146805 0.00092705106 0, + 0.047146805 -0.00092705106 0, + 0.0475729 0.0017633601 0, + 0.060725205 0.022455601 0.020000001, + 0.061358005 0.022915302 0.020000001, + 0.060725205 0.022455601 0, + 0.061358005 0.022915302 0, + 0.059981301 0.0222139 0, + 0.059981301 0.0222139 0.020000001, + 0.061817702 0.0235481 0.020000001, + 0.061817702 0.0235481 0, + 0.062059503 0.024292002 0.020000001, + 0.062059503 0.024292002 0, + 0.057822499 0.026450802 0, + 0.058455303 0.026910601 0, + 0.057822499 0.026450802 0.020000001, + 0.058455303 0.026910601 0.020000001, + 0.057362705 0.025818102 0.020000001, + 0.057362705 0.025818102 0, + 0.061817702 0.025818102 0.020000001, + 0.061358005 0.026450802 0.020000001, + 0.061817702 0.025818102 0, + 0.061358005 0.026450802 0, + 0.062059503 0.025074201 0, + 0.062059503 0.025074201 0.020000001, + 0.060725205 0.026910601 0.020000001, + 0.060725205 0.026910601 0, + 0.059981301 0.027152302 0.020000001, + 0.059981301 0.027152302 0, + 0.059199102 0.027152302 0.020000001, + 0.059199102 0.027152302 0, + 0.057121001 0.025074201 0.020000001, + 0.057121001 0.024292002 0.020000001, + 0.057362705 0.0235481 0.020000001, + 0.057822499 0.022915302 0.020000001, + 0.059199102 0.0222139 0.020000001, + 0.058455303 0.022455601 0.020000001, + 0.057121001 0.025074201 0, + 0.057121001 0.024292002 0, + 0.057362705 0.0235481 0, + 0.059199102 0.0222139 0, + 0.058455303 0.022455601 0, + 0.057822499 0.022915302 0, + 0.026152501 0.061612803 0.020000001, + 0.026152501 0.061612803 0, + 0.027060701 0.058817703 0, + 0.027060701 0.058817703 0.020000001, + 0.026705602 0.058120802 0, + 0.026705602 0.058120802 0.020000001, + 0.026152501 0.057567701 0, + 0.026152501 0.057567701 0.020000001, + 0.0256237 0.046235699 0.020000001, + 0.0256237 0.046235699 0, + 0.026500002 0.045899302 0, + 0.026500002 0.045899302 0.020000001, + 0.027229402 0.045308702 0, + 0.027229402 0.045308702 0.020000001, + 0.0227706 0.0412939 0.020000001, + 0.026220201 0.040560603 0.020000001, + 0.025313601 0.040317703 0.020000001, + 0.024376301 0.040366799 0.020000001, + 0.023500001 0.040703204 0.020000001, + 0.025455602 0.057212602 0, + 0.025455602 0.057212602 0.020000001, + 0.024683101 0.0570902 0, + 0.024683101 0.0570902 0.020000001, + 0.0239105 0.057212602 0, + 0.0239105 0.057212602 0.020000001, + 0.025455602 0.061967902 0.020000001, + 0.023213601 0.057567701 0.020000001, + 0.022660501 0.058120802 0.020000001, + 0.022305401 0.058817703 0.020000001, + 0.022183102 0.059590202 0.020000001, + 0.022305401 0.060362805 0.020000001, + 0.022660501 0.061059702 0.020000001, + 0.023213601 0.061612803 0.020000001, + 0.0239105 0.061967902 0.020000001, + 0.024683101 0.062090203 0.020000001, + 0.023213601 0.057567701 0, + 0.025455602 0.061967902 0, + 0.024683101 0.062090203 0, + 0.0239105 0.061967902 0, + 0.023213601 0.061612803 0, + 0.022660501 0.061059702 0, + 0.022183102 0.059590202 0, + 0.022305401 0.058817703 0, + 0.022305401 0.060362805 0, + 0.022660501 0.058120802 0, + -0.026450802 0.061358005 0, + -0.026910601 0.060725205 0, + -0.0246864 0.046284802 0, + -0.023779802 0.046041902 0, + -0.0256237 0.046235699 0, + -0.027983602 0.043614902 0, + -0.027934402 0.042677503 0, + -0.026500002 0.045899302 0, + 0.026220201 -0.040560603 0.020000001, + 0.025313601 -0.040317703 0.020000001, + 0.026220201 -0.040560603 0, + 0.025313601 -0.040317703 0, + 0.027007401 -0.041071802 0, + 0.027007401 -0.041071802 0.020000001, + -0.059590202 0.022183102 0.020000001, + -0.058817703 0.022305401 0.020000001, + -0.059590202 0.022183102 0, + -0.058817703 0.022305401 0, + -0.060362805 0.022305401 0, + -0.060362805 0.022305401 0.020000001, + -0.051763404 0.0024270501 0, + -0.050927103 0.00285317 0, + -0.051763404 0.0024270501 0.020000001, + -0.050927103 0.00285317 0.020000001, + -0.052427102 0.0017633601 0.020000001, + -0.052427102 0.0017633601 0, + -0.052853201 0.00092705106 0.020000001, + -0.052853201 0.00092705106 0, + -0.0475729 0.0017633601 0.020000001, + -0.048236601 0.0024270501 0.020000001, + -0.0475729 0.0017633601 0, + -0.048236601 0.0024270501 0, + -0.047146805 0.00092705106 0, + -0.047146805 0.00092705106 0.020000001, + -0.049072903 0.00285317 0.020000001, + -0.049072903 0.00285317 0, + -0.050000001 0.003 0.020000001, + -0.050000001 0.003 0, + -0.057567701 0.026152501 0.020000001, + -0.058120802 0.026705602 0.020000001, + -0.057567701 0.026152501 0, + -0.058120802 0.026705602 0, + -0.057212602 0.025455602 0, + -0.057212602 0.025455602 0.020000001, + -0.058817703 0.027060701 0.020000001, + -0.058817703 0.027060701 0, + -0.057212602 0.0239105 0.020000001, + -0.0570902 0.024683101 0.020000001, + -0.057212602 0.0239105 0, + -0.0570902 0.024683101 0, + -0.057567701 0.023213601 0, + -0.057567701 0.023213601 0.020000001, + -0.058120802 0.022660501 0, + -0.058120802 0.022660501 0.020000001, + -0.061059702 0.022660501 0.020000001, + -0.061612803 0.023213601 0.020000001, + -0.061967902 0.0239105 0.020000001, + -0.062090203 0.024683101 0.020000001, + -0.061967902 0.025455602 0.020000001, + -0.061612803 0.026152501 0.020000001, + -0.061059702 0.026705602 0.020000001, + -0.060362805 0.027060701 0.020000001, + -0.059590202 0.027183101 0.020000001, + -0.053000003 0 0.020000001, + -0.047000002 0 0.020000001, + -0.052853201 -0.00092705106 0.020000001, + -0.052427102 -0.0017633601 0.020000001, + -0.047146805 -0.00092705106 0.020000001, + -0.0475729 -0.0017633601 0.020000001, + -0.051763404 -0.0024270501 0.020000001, + -0.048236601 -0.0024270501 0.020000001, + -0.049072903 -0.00285317 0.020000001, + -0.050000001 -0.003 0.020000001, + -0.050927103 -0.00285317 0.020000001, + -0.053000003 0 0, + -0.047000002 0 0, + -0.0220164 -0.042987704 0.020000001, + -0.022259401 -0.042081103 0.020000001, + -0.0220164 -0.042987704 0, + -0.022259401 -0.042081103 0, + -0.0220656 -0.043925002 0, + -0.0220656 -0.043925002 0.020000001, + -0.022401901 -0.044801302 0, + -0.022401901 -0.044801302 0.020000001, + 0.024292002 -0.057121001 0.020000001, + 0.0235481 -0.057362705 0.020000001, + 0.024292002 -0.057121001 0, + 0.0235481 -0.057362705 0, + 0.025074201 -0.057121001 0, + 0.025074201 -0.057121001 0.020000001, + 0.0235481 -0.061817702 0, + 0.022915302 -0.061358005 0, + 0.0235481 -0.061817702 0.020000001, + 0.022915302 -0.061358005 0.020000001, + 0.024292002 -0.062059503 0.020000001, + 0.024292002 -0.062059503 0, + 0.025074201 -0.062059503 0.020000001, + 0.025074201 -0.062059503 0, + -0.060725205 -0.026910601 0, + -0.061358005 -0.026450802 0, + -0.060725205 -0.026910601 0.020000001, + -0.061358005 -0.026450802 0.020000001, + -0.059981301 -0.027152302 0.020000001, + -0.059981301 -0.027152302 0, + -0.059199102 -0.027152302 0.020000001, + -0.058455303 -0.026910601 0.020000001, + -0.057822499 -0.026450802 0.020000001, + -0.061817702 -0.025818102 0.020000001, + -0.057362705 -0.025818102 0.020000001, + -0.057121001 -0.025074201 0.020000001, + -0.057121001 -0.024292002 0.020000001, + -0.057362705 -0.0235481 0.020000001, + -0.062059503 -0.025074201 0.020000001, + -0.062059503 -0.024292002 0.020000001, + -0.061817702 -0.0235481 0.020000001, + -0.061358005 -0.022915302 0.020000001, + -0.060725205 -0.022455601 0.020000001, + -0.059981301 -0.0222139 0.020000001, + -0.059199102 -0.0222139 0.020000001, + -0.057822499 -0.022915302 0.020000001, + -0.058455303 -0.022455601 0.020000001, + -0.059199102 -0.027152302 0, + -0.027060701 -0.060362805 0.020000001, + -0.026705602 -0.061059702 0.020000001, + -0.027060701 -0.060362805 0, + -0.026705602 -0.061059702 0, + -0.027183101 -0.059590202 0, + -0.027183101 -0.059590202 0.020000001, + -0.026152501 -0.061612803 0.020000001, + -0.026152501 -0.061612803 0, + -0.025455602 -0.057212602 0, + -0.024683101 -0.0570902 0, + -0.025455602 -0.057212602 0.020000001, + -0.024683101 -0.0570902 0.020000001, + -0.026152501 -0.057567701 0.020000001, + -0.026152501 -0.057567701 0, + -0.026705602 -0.058120802 0, + -0.026705602 -0.058120802 0.020000001, + -0.027060701 -0.058817703 0.020000001, + -0.027060701 -0.058817703 0, + -0.026500002 -0.045899302 0.020000001, + -0.0256237 -0.046235699 0.020000001, + -0.026500002 -0.045899302 0, + -0.0256237 -0.046235699 0, + -0.0246864 -0.046284802 0.020000001, + -0.0246864 -0.046284802 0, + -0.027983602 -0.043614902 0.020000001, + -0.027934402 -0.042677503 0.020000001, + -0.026220201 -0.040560603 0.020000001, + -0.025313601 -0.040317703 0.020000001, + -0.024376301 -0.040366799 0.020000001, + -0.023500001 -0.040703204 0.020000001, + -0.0227706 -0.0412939 0.020000001, + -0.023779802 -0.046041902 0.020000001, + -0.0229926 -0.045530703 0.020000001, + -0.062059503 -0.024292002 0, + -0.061817702 -0.0235481 0, + -0.062059503 -0.025074201 0, + -0.061358005 -0.022915302 0, + -0.060725205 -0.022455601 0, + -0.059981301 -0.0222139 0, + -0.059199102 -0.0222139 0, + -0.058455303 -0.022455601 0, + -0.057822499 -0.022915302 0, + -0.057362705 -0.0235481 0, + -0.057121001 -0.024292002 0, + -0.027934402 -0.042677503 0, + -0.027983602 -0.043614902 0, + -0.058455303 -0.026910601 0, + -0.057822499 -0.026450802 0, + -0.061817702 -0.025818102 0, + -0.057362705 -0.025818102 0, + -0.057121001 -0.025074201 0, + 0.026450802 -0.061358005 0.020000001, + 0.026910601 -0.060725205 0.020000001, + 0.026450802 -0.061358005 0, + 0.026910601 -0.060725205 0, + 0.025818102 -0.061817702 0, + 0.025818102 -0.061817702 0.020000001, + 0.027152302 -0.059981301 0.020000001, + 0.027152302 -0.059981301 0, + 0.027152302 -0.059199102 0.020000001, + 0.027152302 -0.059199102 0, + 0.026910601 -0.058455303 0.020000001, + 0.026910601 -0.058455303 0, + 0.026450802 -0.057822499 0.020000001, + 0.025818102 -0.057362705 0.020000001, + 0.022455601 -0.060725205 0.020000001, + 0.0222139 -0.059981301 0.020000001, + 0.022915302 -0.057822499 0.020000001, + 0.0222139 -0.059199102 0.020000001, + 0.022455601 -0.058455303 0.020000001, + 0.026450802 -0.057822499 0, + 0.025818102 -0.057362705 0, + 0.022455601 -0.060725205 0, + -0.022305401 -0.060362805 0.020000001, + -0.022183102 -0.059590202 0.020000001, + -0.022305401 -0.060362805 0, + -0.022183102 -0.059590202 0, + -0.022660501 -0.061059702 0, + -0.022660501 -0.061059702 0.020000001, + -0.022305401 -0.058817703 0.020000001, + -0.022305401 -0.058817703 0, + -0.022660501 -0.058120802 0, + -0.022660501 -0.058120802 0.020000001, + -0.023213601 -0.057567701 0.020000001, + -0.023213601 -0.057567701 0, + -0.023213601 -0.061612803 0.020000001, + -0.023213601 -0.061612803 0, + -0.0239105 -0.061967902 0, + -0.0239105 -0.061967902 0.020000001, + -0.024683101 -0.062090203 0, + -0.024683101 -0.062090203 0.020000001, + -0.025455602 -0.061967902 0, + -0.025455602 -0.061967902 0.020000001, + -0.0239105 -0.057212602 0.020000001, + -0.0239105 -0.057212602 0, + -0.0229926 -0.045530703 0, + -0.023779802 -0.046041902 0, + 0.0229926 -0.045530703 0.020000001, + 0.0229926 -0.045530703 0, + -0.0227706 -0.0412939 0, + -0.023500001 -0.040703204 0, + -0.024376301 -0.040366799 0, + -0.025313601 -0.040317703 0, + -0.026220201 -0.040560603 0, + -0.050000001 -0.003 0, + -0.050927103 -0.00285317 0, + -0.049072903 -0.00285317 0, + -0.051763404 -0.0024270501 0, + -0.052427102 -0.0017633601 0, + -0.048236601 -0.0024270501 0, + -0.0475729 -0.0017633601 0, + -0.047146805 -0.00092705106 0, + -0.052853201 -0.00092705106 0, + -0.061059702 0.022660501 0, + -0.061612803 0.023213601 0, + -0.061967902 0.0239105 0, + -0.062090203 0.024683101 0, + -0.061967902 0.025455602 0, + -0.061612803 0.026152501 0, + -0.061059702 0.026705602 0, + -0.060362805 0.027060701 0, + -0.059590202 0.027183101 0, + 0.027598102 -0.041801304 0, + 0.027934402 -0.042677503 0, + 0.027598102 -0.041801304 0.020000001, + 0.027934402 -0.042677503 0.020000001, + 0.0246864 -0.046284802 0.020000001, + 0.0256237 -0.046235699 0.020000001, + 0.0246864 -0.046284802 0, + 0.0256237 -0.046235699 0, + 0.023779802 -0.046041902 0, + 0.023779802 -0.046041902 0.020000001, + 0.027983602 -0.043614902 0, + 0.027983602 -0.043614902 0.020000001, + 0.027740601 -0.044521503 0, + 0.027740601 -0.044521503 0.020000001, + 0.027229402 -0.045308702 0, + 0.027229402 -0.045308702 0.020000001, + 0.026500002 -0.045899302 0.020000001, + 0.0227706 -0.0412939 0.020000001, + 0.023500001 -0.040703204 0.020000001, + 0.024376301 -0.040366799 0.020000001, + 0.026500002 -0.045899302 0, + 0.022455601 -0.058455303 0, + 0.022915302 -0.057822499 0, + 0.0222139 -0.059199102 0, + 0.0222139 -0.059981301 0, + 0.024376301 -0.040366799 0, + 0.023500001 -0.040703204 0, + 0.0227706 -0.0412939 0, + -0.022259401 0.042081103 0, + -0.0220164 0.042987704 0, + -0.0220656 0.043925002 0, + -0.022401901 0.044801302 0, + -0.0229926 0.045530703 0, + 0.026220201 0.040560603 0, + 0.0227706 0.0412939 0, + 0.023500001 0.040703204 0, + 0.024376301 0.040366799 0, + 0.025313601 0.040317703 0, + 0.057567701 -0.026152501 0, + 0.058120802 -0.026705602 0, + 0.058817703 -0.027060701 0, + 0.059590202 -0.027183101 0, + 0.060362805 -0.027060701 0, + 0.061059702 -0.026705602 0, + 0.061612803 -0.026152501 0, + 0.061967902 -0.025455602 0, + 0.058120802 -0.022660501 0, + 0.058817703 -0.022305401 0, + 0.059590202 -0.022183102 0, + 0.060362805 -0.022305401 0, + 0.061059702 -0.022660501 0, + 0.062090203 -0.024683101 0, + 0.061967902 -0.0239105 0, + 0.061612803 -0.023213601 0, + 0.051431704 0.051695805 0, + 0.067267902 0.028188301 0, + -0.049430601 0.053696901 0, + -0.049430601 -0.053696901 0, + 0.051431704 -0.051695805 0, + 0.067267902 -0.028188301 0, + 0 -0.067545101 0, + -0.0275915 -0.051695805 0, + -0.037500001 -0.051695805 0, + -0.037500001 -0.033742201 0, + -0.0275915 -0.033742201 0, + 0 -0.033742201 0, + 0 -0.051695805 0, + -0.055045106 -0.033742201 0, + -0.055045106 -0.012591501 0, + -0.067545101 -0.012591501 0, + -0.067545101 0.012591501 0, + -0.055045106 0.012591501 0, + -0.037500001 -0.012591501 0, + -0.037500001 0.012591501 0, + -0.055045106 0.033742201 0, + -0.037500001 0.033742201 0, + -0.037500001 0.051695805 0, + -0.0275915 0.051695805 0, + 0 0.051695805 0, + -0.0275915 0.012591501 0, + -0.0275915 0.033742201 0, + 0 0.012591501 0, + 0 0.033742201 0, + 0.0220915 0.012591501 0, + 0.0220915 0.033742201 0, + 0.037500001 0.012591501 0, + 0.037500001 0.033742201 0, + 0.055045106 0.012591501 0, + 0.055045106 0.033742201 0, + 0.055045106 -0.012591501 0, + 0.037500001 -0.012591501 0, + 0.0220915 -0.012591501 0, + 0 -0.012591501 0, + -0.0275915 -0.012591501 0, + 0.0220915 -0.033742201 0, + 0.037500001 -0.033742201 0, + 0.0220915 -0.051695805 0, + 0.055045106 -0.033742201 0, + 0.0220915 0.051695805 0, + 0.037500001 0.051695805 0, + 0.037500001 -0.051695805 0, + 0.0220915 -0.067545101 0 ] + + } + normal + Normal { + vector [ 0.77716494 0.62929696 1.6952798e-006, + 0.93360919 -0.35829306 -3.793881e-006, + 0.96590525 0.25889605 -1.4522103e-006, + 0.93398356 -0.35731584 0, + 0.96593124 0.25879905 0, + 0.85347754 -0.46187574 0.24134387, + 0.84752071 -0.45865181 0.26710889, + 0.84290415 -0.46950909 0.26281905, + 0.84290308 -0.46951106 0.26281902, + 0.81397039 -0.51282519 0.27287811, + 0.82107162 -0.51729876 0.24133688, + 0.85348588 -0.46186393 0.24133697, + 0.85922164 -0.46496886 0.21340592, + 0.8932609 -0.40956494 0.18531497, + 0.91837019 -0.34964907 0.18531504, + 0.92295802 -0.35139501 0.157067, + 0.94416612 -0.28962103 0.15706702, + 0.94808364 -0.29082292 0.12868296, + 0.96523398 -0.22751699 0.128683, + 0.96842825 -0.22827004 0.10019802, + 0.98139596 -0.163775 0.100198, + 0.98382646 -0.16418007 0.071627326, + 0.99252701 -0.098790802 0.071627289, + 0.99416262 -0.09895356 0.042999685, + 0.99852854 -0.03304068 0.042999681, + 0.99935025 -0.033067908 0.014338603, + 0.99935025 0.033067908 0.014338603, + 0.99852884 0.033040691 0.042993091, + 0.99852931 -0.033025511 0.042993113, + 0.99688619 -0.032971106 0.071629211, + 0.99252647 -0.098794945 0.071629226, + 0.99007535 -0.098550938 0.10019303, + 0.98139864 -0.16376194 0.10019296, + 0.97816139 -0.16322207 0.12868106, + 0.96523517 -0.22751305 0.12868103, + 0.96124858 -0.2265729 0.15705393, + 0.94417602 -0.28959599 0.15705401, + 0.93948317 -0.28815708 0.18530203, + 0.91838199 -0.34962499 0.18530199, + 0.91303831 -0.34759009 0.21340607, + 0.8821348 -0.4044649 0.24134295, + 0.87542999 -0.40138 0.26928899, + 0.88213998 -0.40445599 0.241339, + 0.90693718 -0.34528309 0.24133906, + 0.91303188 -0.34760293 0.21341299, + 0.93947428 -0.2881791 0.18531306, + 0.95646685 -0.22545597 0.18531297, + 0.96124578 -0.22658195 0.15705796, + 0.97816104 -0.16322401 0.12868102, + 0.98680925 -0.098228119 0.12868103, + 0.99007499 -0.098553203 0.100194, + 0.99688667 -0.032964788 0.071626373, + 0.99688643 0.032971215 0.071626432, + 0.99852908 0.033025503 0.042999707, + 0.99416316 0.098947123 0.042999711, + 0.99502563 0.099032961 0.010788595, + 0.99867415 0.051477712 6.2981314e-007, + -0.17553699 0.95443499 0.241331, + -0.23823012 0.94074744 0.2413311, + -0.23983096 0.9470669 0.21341397, + -0.30189797 0.92914587 0.21341397, + -0.303664 0.93458402 0.185313, + -0.36476386 0.91247267 0.18531293, + -0.36658585 0.91703165 0.15705994, + -0.42639586 0.89079666 0.15705994, + -0.42816496 0.89449298 0.128675, + -0.48635209 0.86423618 0.12867603, + -0.48796082 0.86709571 0.10019596, + -0.54418904 0.8329581 0.10019601, + -0.54553592 0.83502096 0.071628883, + -0.59953493 0.7971369 0.071629182, + -0.60052294 0.79845089 0.042994898, + -0.65255833 0.75765038 0.011557406, + -0.65199786 0.75700086 0.042995095, + -0.70118296 0.71287692 0.012212998, + -0.65198851 0.75700849 0.043000571, + -0.65091622 0.75576323 0.07162492, + -0.59954309 0.79713112 0.071624905, + -0.5980618 0.79516268 0.10019197, + -0.54419601 0.83295393 0.100192, + -0.54240084 0.83020663 0.12867896, + -0.48634282 0.86424071 0.12867996, + -0.48433313 0.8606692 0.15706703, + -0.42638081 0.89080262 0.15706694, + -0.42426205 0.88637614 0.18530801, + -0.36477688 0.91246873 0.18530694, + -0.36265409 0.90715921 0.21341105, + -0.30190301 0.92914492 0.213411, + -0.2998879 0.92294371 0.24133392, + -0.238225 0.94074798 0.24133399, + -0.236367 0.93340898 0.26995999, + -0.22094311 0.9393844 0.26218513, + -0.30632299 0.91351402 0.26769099, + -0.30619511 0.91355628 0.2676931, + -0.22091006 0.93939215 0.26218507, + -0.17400898 0.9461239 0.27307597, + -0.133351 0.95591313 0.26162502, + -0.13334794 0.95591354 0.26162487, + -0.423915 0.90570199 1.78828e-006, + -0.42390284 0.90570766 0, + -0.30900708 0.95095831 0.013884705, + -0.3087509 0.9501707 0.042994481, + -0.245258 0.96850401 0.042994399, + -0.180429 0.980977 0.0716215, + -0.17998292 0.97855353 0.10019495, + -0.11490999 0.98830998 0.100195, + -0.11453099 0.98505086 0.12867598, + -0.04916152 0.99046737 0.12867604, + -0.048958283 0.98637366 0.15706694, + 0.016342895 0.98745263 0.15706694, + 0.016261593 0.9825446 0.18531491, + 0.081160799 0.97932202 0.185314, + 0.080688603 0.973625 0.21341, + 0.14387502 0.95971811 0.24133202, + 0.13310499 0.95418113 0.26799503, + 0.13312295 0.95417869 0.26799491, + 0.20539008 0.94077229 0.26974508, + 0.46732599 0.83889502 0.279037, + -0.049590189 0.99868178 0.013249196, + -0.049548581 0.99784565 0.042999286, + 0.016525589 0.99893838 0.042999275, + 0.0164984 0.99729502 0.0716267, + 0.082374014 0.99402422 0.071626715, + 0.082170486 0.99156886 0.10019598, + 0.14752893 0.98396951 0.10019595, + 0.14704198 0.98072386 0.12868299, + 0.21153192 0.96886271 0.12868296, + 0.21065789 0.9648596 0.15706393, + 0.27397099 0.94882596 0.15706401, + 0.27260903 0.94410908 0.18531701, + 0.33439982 0.92403156 0.18531691, + 0.33245504 0.91865814 0.21340302, + 0.3924399 0.89467877 0.21340294, + 0.38981903 0.88870615 0.24133503, + 0.44769579 0.86100256 0.24133588, + 0.4439421 0.85378218 0.27197707, + 0.46968895 0.84326988 0.26131997, + 0.46970379 0.8432616 0.26131988, + 0.49986812 0.82334018 0.26878005, + 0.50362492 0.82952988 0.24133396, + 0.44769284 0.86100471 0.24133392, + 0.45070076 0.86679059 0.21340789, + 0.39245009 0.89467317 0.21340804, + 0.39474598 0.89990801 0.185314, + 0.33439496 0.924034 0.185314, + 0.33606613 0.92865133 0.15705505, + 0.27395114 0.94883341 0.15705408, + 0.27508789 0.95276862 0.12867996, + 0.21152397 0.96886486 0.12867999, + 0.21222408 0.97207129 0.10019103, + 0.14751893 0.98397154 0.10019095, + 0.14788398 0.98640788 0.071623787, + 0.082367502 0.99402493 0.071623795, + 0.08250317 0.99566263 0.043002386, + 0.016532801 0.99893814 0.043002505, + 0.016547106 0.99980235 0.011022003, + 0.17928001 0.98379815 -4.6769906e-006, + 0.87542999 0.40138 0.26928899, + 0.88213891 0.40445593 0.24134298, + 0.57428205 0.8185361 0.014097502, + 0.57380813 0.81786019 0.04299951, + 0.62660104 0.77815306 0.042999905, + 0.6255697 0.77687258 0.071633868, + 0.67554486 0.73383087 0.071634091, + 0.67387688 0.73201895 0.10019099, + 0.72077888 0.68588597 0.10019099, + 0.71840119 0.68362319 0.12868203, + 0.76201129 0.63464928 0.12868206, + 0.75886393 0.63202792 0.15705498, + 0.79897475 0.58049387 0.15705496, + 0.79500389 0.57760793 0.18530498, + 0.83143806 0.52380604 0.18530503, + 0.826599 0.52075696 0.213416, + 0.85922009 0.46496704 0.21341603, + 0.85348392 0.46186393 0.24134398, + 0.84752071 0.45865181 0.26710889, + 0.85347927 0.46187609 0.24133706, + 0.82107937 0.51728624 0.24133712, + 0.8265962 0.52076215 0.21341404, + 0.79038227 0.57423919 0.21341307, + 0.79500842 0.57760036 0.1853091, + 0.75509292 0.62888396 0.18530999, + 0.75886554 0.63202566 0.15705591, + 0.71543163 0.68080163 0.15705593, + 0.71839887 0.68362594 0.12868099, + 0.67165828 0.72960037 0.12868007, + 0.67388088 0.73201483 0.10019398, + 0.62400788 0.77496791 0.10019398, + 0.62555301 0.776887 0.071624093, + 0.57285815 0.8165192 0.071624421, + 0.57380176 0.81786472 0.042995881, + 0.51847625 0.8540104 0.042995818, + 0.51892591 0.85475087 0.010817399, + 0.64058572 0.76788664 -1.0032894e-005, + 0.64042729 0.76769638 0.022253811, + 0.64043331 0.76769137 0.022253811, + 0.64059162 0.76788163 0, + 0.64060313 0.76787215 -2.5514908e-006, + 0.55824029 0.82967937 1.2550905e-006, + 0.46996978 0.88268256 -2.7007586e-006, + 0.46997294 0.88268089 -1.0623199e-006, + 0.46986699 0.88248092 0.0212698, + 0.46984604 0.88249207 0.021269802, + 0.46995276 0.88269156 0, + 0.55823493 0.82968295 0, + 0.55809397 0.82947385 0.022453198, + 0.55810291 0.82946789 0.022453198, + 0.55824393 0.82967687 0, + 0.64200801 0.766698 0, + 0.64193898 0.76661497 0.0146932, + 0.62709612 0.77880311 0.014705004, + 0.62658417 0.77816719 0.042990409, + 0.67664307 0.73505509 0.042990204, + 0.67552966 0.73384565 0.07162486, + 0.72257894 0.68756795 0.071624592, + 0.72079378 0.68586874 0.10020097, + 0.76454198 0.636738 0.100201, + 0.76202029 0.63463724 0.12868804, + 0.802293 0.58289403 0.12868799, + 0.79897898 0.58048701 0.157059, + 0.83560121 0.52640617 0.15705805, + 0.83144689 0.52378893 0.18531398, + 0.86423868 0.46770784 0.18531293, + 0.85921186 0.46498695 0.21340598, + 0.88213605 0.40446502 0.24133801, + 0.89906949 0.34227583 0.27298585, + 0.90694135 0.34527215 0.24133912, + 0.92010462 0.28223991 0.27156588, + 0.92777407 0.28459302 0.24133402, + 0.90693891 0.34528297 0.24133296, + 0.91303331 0.34760311 0.21340607, + 0.89326125 0.40956509 0.18531305, + 0.86423802 0.467709 0.185313, + 0.86855721 0.47004613 0.15705104, + 0.8355931 0.52642107 0.15705103, + 0.8390587 0.52860379 0.12867996, + 0.80228269 0.58290982 0.12867996, + 0.7645269 0.63675797 0.10018999, + 0.76641995 0.63833493 0.071618296, + 0.72256899 0.68757898 0.071618199, + 0.72375923 0.68871123 0.043004014, + 0.67666608 0.73503309 0.043004103, + 0.67725319 0.73567116 0.010770103, + 0.71614724 0.69794923 2.645551e-007, + 0.71597987 0.69778687 0.021593599, + 0.71600157 0.69776458 0.021593587, + 0.716169 0.697927 0, + 0.71615362 0.69794261 -3.1914185e-006, + 0.78411478 0.62061578 -1.4287594e-006, + 0.84377772 0.5366928 -9.843227e-007, + 0.89448857 0.44709077 2.148679e-006, + 0.93572176 0.35273892 3.6304491e-006, + 0.93553185 0.35266796 0.020135999, + 0.93551862 0.35270286 0.020135993, + 0.95597303 0.29324201 0.0111697, + 0.95514834 0.29298908 0.043001615, + 0.33998391 0.93944776 0.042997688, + 0.34027696 0.94025791 0.011253598, + 0.27940097 0.95996785 0.019920496, + 0.27945611 0.96015847 0, + 0.27943286 0.95995849 0.019920489, + 0.27734804 0.96058214 0.018973202, + 0.27714097 0.95986688 0.042994596, + 0.33997804 0.93945009 0.042994704, + 0.33941805 0.93790418 0.071631111, + 0.400677 0.91341501 0.071631499, + 0.39968783 0.91115856 0.10019796, + 0.45902899 0.88275301 0.100197, + 0.45751485 0.87984163 0.12868096, + 0.51466304 0.84768105 0.12868102, + 0.51253605 0.84417814 0.15706702, + 0.56719887 0.80846483 0.15706696, + 0.56438071 0.80444652 0.18531089, + 0.6163156 0.76538545 0.18531087, + 0.61272973 0.76093262 0.2134099, + 0.66167933 0.71877438 0.21341009, + 0.65726292 0.71397793 0.24133196, + 0.70301235 0.66897827 0.2413331, + 0.6972298 0.66347581 0.27142295, + 0.74177176 0.61584175 0.26554391, + 0.74167901 0.61595303 0.26554498, + 0.74083775 0.61701274 0.26543289, + 0.70301312 0.6689772 0.24133405, + 0.70773739 0.67347229 0.21340808, + 0.66167706 0.71877712 0.21340801, + 0.66554815 0.72298318 0.18531305, + 0.61632013 0.76538116 0.18531404, + 0.61939877 0.76920474 0.15706395, + 0.567195 0.80846798 0.15706499, + 0.56954926 0.81182325 0.12867305, + 0.5146482 0.84769124 0.12867305, + 0.51635104 0.85049611 0.10019001, + 0.45901507 0.88276106 0.10019001, + 0.46015093 0.88494688 0.07162419, + 0.40066284 0.91342163 0.071624279, + 0.40132293 0.91492689 0.042997595, + 0.40167099 0.91569602 0.0126991, + 0.40133107 0.91492313 0.043001704, + 0.46092209 0.8863982 0.043001711, + 0.46016383 0.88493973 0.07163047, + 0.51764494 0.85259187 0.071630396, + 0.51636678 0.85048556 0.10019796, + 0.57144815 0.81449819 0.10019802, + 0.56956309 0.81181216 0.12868103, + 0.62195522 0.77240723 0.12868105, + 0.6193859 0.76921684 0.15705597, + 0.66888094 0.72658896 0.15705699, + 0.6655547 0.72297579 0.18531792, + 0.71189111 0.6773982 0.18531802, + 0.70774907 0.67345709 0.21341701, + 0.75069797 0.62522501 0.213416, + 0.78511107 0.57040209 0.24133402, + 0.77855563 0.56563973 0.27185085, + 0.79633081 0.54547989 0.26135993, + 0.79632717 0.54548514 0.26136005, + 0.741871 0.616018 0.26485696, + 0.74185699 0.61603498 0.26485696, + 0.95597267 0.13337095 0.26139691, + 0.80896896 0.58774692 0.011089098, + 0.80827087 0.58723897 0.042995196, + 0.76832712 0.63992405 0.013061201, + 0.7676819 0.63938689 0.043000296, + 0.80827713 0.58723009 0.043000404, + 0.80694729 0.58626318 0.071635231, + 0.84393191 0.53164595 0.07163509, + 0.84184819 0.5303331 0.10019203, + 0.87504113 0.47356606 0.10019101, + 0.87215561 0.47200376 0.12867394, + 0.90144455 0.4133288 0.12867394, + 0.89772028 0.41162112 0.15705505, + 0.92295951 0.35139582 0.15705593, + 0.91837251 0.34964982 0.18530191, + 0.93947643 0.28817913 0.18530208, + 0.93400806 0.28650203 0.21341403, + 0.95090759 0.22411887 0.21341389, + 0.94455975 0.22262295 0.24134193, + 0.957205 0.15972701 0.24134199, + 0.94987988 0.15850498 0.26945198, + 0.95248222 0.13286602 0.27408805, + 0.95597601 0.133347 0.261397, + 0.95730114 0.095279805 0.27294004, + 0.96567088 0.096112885 0.24133396, + 0.9572041 0.15974401 0.24133402, + 0.9636361 0.16081701 0.21340904, + 0.9509061 0.22413103 0.21340801, + 0.95647013 0.22544202 0.18531302, + 0.93948132 0.28815609 0.18531306, + 0.94417423 0.2895951 0.15706603, + 0.9229663 0.35137311 0.15706705, + 0.92679566 0.35283089 0.12868595, + 0.90145469 0.41330281 0.12868595, + 0.90443885 0.41467097 0.10019199, + 0.8750416 0.47356477 0.10019195, + 0.87720811 0.47473705 0.071629606, + 0.84392601 0.53165603 0.071629703, + 0.84531707 0.53253204 0.042995106, + 0.96567166 -0.096112959 0.24133091, + 0.90894872 0.41674086 0.011796696, + 0.90817142 0.41638419 0.042997919, + 0.93369937 0.35546711 0.042997215, + 0.93216312 0.35488206 0.071628608, + 0.95358187 0.29249096 0.071628794, + 0.95122653 0.2917679 0.10019696, + 0.96842825 0.22827004 0.10019702, + 0.96523422 0.22751705 0.12868103, + 0.97816104 0.16322401 0.12868102, + 0.97784811 0.097338706 0.18530601, + 0.97642761 0.03228939 0.21341592, + 0.97642744 -0.032297514 0.2134161, + 0.96991241 -0.032082014 0.2413311, + 0.96437699 -0.031895299 0.262602, + 0.96991301 -0.0320784 0.24132898, + 0.96991289 0.032081995 0.24132897, + 0.97642833 0.032297511 0.21341208, + 0.97215718 0.096776523 0.21341205, + 0.97784799 0.097342998 0.185304, + 0.96927911 0.16174202 0.18530402, + 0.96124786 0.22657298 0.15705797, + 0.96523499 0.227513 0.128683, + 0.94808429 0.29082108 0.12868305, + 0.95122242 0.29178411 0.10019004, + 0.92985964 0.35400987 0.10018996, + 0.93216187 0.35488597 0.071626596, + 0.90667474 0.41570488 0.07162638, + 0.90816897 0.41639 0.042995401, + 0.87865895 0.47551 0.042995401, + 0.87940919 0.47591713 0.011929103, + 0.8436591 0.53656209 0.018450502, + 0.84594798 0.53294599 0.0184526, + 0.84530985 0.53254396 0.042989392, + 0.87865216 0.47552311 0.042989407, + 0.87720662 0.47473982 0.071627967, + 0.90667689 0.41569993 0.071628392, + 0.9044376 0.41467381 0.10019095, + 0.92986071 0.35400689 0.10019097, + 0.92679316 0.35283905 0.12868203, + 0.94808388 0.29082298 0.12868199, + 0.94416797 0.28962198 0.15705401, + 0.96124637 0.22658208 0.15705407, + 0.95646811 0.22545601 0.18530601, + 0.96927923 0.16173904 0.18530604, + 0.96363735 0.16079706 0.21341808, + 0.97215718 0.096763819 0.21341807, + 0.96567112 0.096118212 0.24133101, + 0.96991253 0.032078385 0.24133088, + 0.96437699 0.031895299 0.262602, + 0.96385062 0.044569585 0.26268888, + 0.96213061 0.044477977 0.26893589, + 0.96213061 -0.044477977 0.26893589, + 0.96385062 -0.044569585 0.26268888, + 0.95730114 -0.095279805 0.27294004, + 0.95597601 -0.133347 0.261397, + 0.95597267 -0.13337095 0.26139691, + 0.95248222 -0.13286602 0.27408805, + 0.94987988 -0.15850498 0.26945198, + 0.95720702 -0.15972701 0.24133399, + 0.96567029 -0.096118137 0.24133408, + 0.97215843 -0.096763946 0.21341209, + 0.97642857 -0.032289386 0.2134119, + 0.98214388 -0.032478396 0.18530698, + 0.98704964 0.032639984 0.15705894, + 0.98680913 0.098229811 0.12868102, + 0.97816139 0.16322207 0.12868106, + 0.98139822 0.16376203 0.10019802, + 0.96842891 0.22826697 0.10019799, + 0.95357591 0.29251298 0.07161849, + 0.95514655 0.29299489 0.042998776, + 0.93370032 0.35546413 0.04299831, + 0.93440098 0.35573101 0.018715, + 0.93554103 0.35272202 0.018713402, + 0.93570477 0.35278392 0, + 0.89449239 0.4470832 0, + 0.89425468 0.44696382 0.023061991, + 0.89424711 0.44697905 0.023062002, + 0.89448494 0.44709799 0, + 0.84380305 0.53665304 0, + 0.84377068 0.53670382 4.2679685e-006, + 0.84359598 0.53659302 0.020341299, + 0.84360754 0.53657472 0.020341288, + 0.84378201 0.536686 0, + 0.78411084 0.62062085 0, + 0.7839061 0.62045908 0.022845501, + 0.78391308 0.62045014 0.022845501, + 0.78411788 0.62061197 0, + 0.71615267 0.69794369 0, + 0.71605664 0.69784969 0.016391892, + 0.72433317 0.68925512 0.016398303, + 0.72376066 0.68870968 0.043004781, + 0.76768804 0.63937908 0.043004703, + 0.76642555 0.63832766 0.071622252, + 0.80693108 0.58628708 0.071622409, + 0.84184706 0.53033507 0.10019101, + 0.83906901 0.52858496 0.12869, + 0.87216997 0.47197297 0.12869, + 0.86856723 0.47002408 0.15706202, + 0.8977257 0.41160685 0.15706193, + 0.89326268 0.40956086 0.18531494, + 0.9183799 0.34962398 0.18531497, + 0.91303676 0.34758991 0.21341296, + 0.934008 0.28650299 0.213413, + 0.92777449 0.28459081 0.24133486, + 0.94455802 0.222638 0.241335, + 0.93851137 0.22121207 0.2650691, + 0.93861914 0.22075002 0.26507303, + 0.93855506 0.22074804 0.26530102, + 0.9385702 0.22068405 0.26530105, + 0.9151774 0.30675715 0.26143909, + 0.91519052 0.30671787 0.26143885, + 0.84171021 0.46837115 0.26861209, + 0.841515 0.46872401 0.268608, + 0.84290415 0.46950909 0.26281905, + 0.84290308 0.46951106 0.26281902, + 0.81397039 0.51282519 0.27287811, + 0.82107288 0.51729995 0.24132997, + 0.78510696 0.57040995 0.24132897, + 0.79038072 0.57424176 0.21341193, + 0.75069314 0.62523204 0.21341202, + 0.7550872 0.62889212 0.18530504, + 0.71187305 0.67742109 0.18530402, + 0.71542901 0.68080503 0.15705401, + 0.66887707 0.72659308 0.15705402, + 0.67165136 0.7296074 0.12867607, + 0.62194622 0.77241534 0.12867606, + 0.62400413 0.77497119 0.10019203, + 0.57143623 0.81450731 0.10019203, + 0.57285118 0.81652433 0.07162112, + 0.51762795 0.8526029 0.071621194, + 0.51848066 0.85400754 0.042997975, + 0.460915 0.88640201 0.042998102, + 0.46127495 0.88709396 0.017026298, + 0.46992704 0.88254112 0.017021202, + 0.46999505 0.88266909 0, + 0.3767271 0.92632425 0, + 0.37662813 0.92608035 0.022946907, + 0.37664515 0.92607331 0.022946907, + 0.37674418 0.92631739 0, + 0.37673506 0.92632115 -2.3173002e-006, + -0.97886097 0.20452701 0, + -0.97885633 0.20454906 -2.911831e-006, + -0.97885793 0.204541 -6.2673294e-006, + -0.97864372 0.20449592 0.020923493, + -0.97864664 0.20448193 0.020923493, + -0.96515191 0.26146296 0.010902699, + -0.67614102 0.68742698 0.26509899, + -0.68050188 0.69185996 0.24134398, + -0.72473907 0.64537305 0.24134403, + -0.72961134 0.64971131 0.2134071, + -0.77097273 0.60004884 0.21340692, + -0.77548516 0.60356116 0.18530203, + -0.81773108 0.55375707 0.15706402, + -0.85253489 0.49851292 0.15706399, + -0.85607117 0.50058115 0.12868802, + -0.88728464 0.44290584 0.12868695, + -0.8902216 0.44437179 0.10019495, + -0.91764611 0.38456002 0.10019601, + -0.91991889 0.38551193 0.071622886, + -0.94339031 0.3238591 0.071623221, + -0.94494468 0.32439288 0.042998783, + -0.94572759 0.32467285 0.013667594, + -0.94494098 0.32440296 0.0430035, + -0.92143267 0.38615087 0.043003585, + -0.91991699 0.38551599 0.071624897, + -0.89243579 0.4454529 0.071624689, + -0.89023203 0.44435301 0.100186, + -0.85891861 0.50221676 0.10018595, + -0.8560853 0.50056016 0.12867604, + -0.82112902 0.55604792 0.128677, + -0.81773579 0.55375087 0.15706097, + -0.77934396 0.60659289 0.15706098, + -0.77546972 0.60357773 0.18531194, + -0.73388499 0.65350801 0.185311, + -0.72961599 0.64970702 0.213404, + -0.68508714 0.6965012 0.21340504, + -0.68051326 0.6918512 0.24133709, + -0.62831908 0.72953606 0.27017102, + -0.6332978 0.73531681 0.24133594, + -0.87007058 0.49244177 0.02186669, + -0.52649522 0.80585945 0.27091214, + -0.53078187 0.81242079 0.24133594, + -0.47272196 0.84005898 0.266148, + -0.47591388 0.84573078 0.24134094, + -0.53077304 0.81242514 0.24134101, + -0.53433889 0.8178848 0.21341595, + -0.58722705 0.78078008 0.21341701, + -0.59066367 0.78535056 0.18531288, + -0.64128077 0.74459273 0.18531194, + -0.64448482 0.74831277 0.15705794, + -0.69253582 0.70407879 0.15705796, + -0.69540882 0.7069999 0.12867697, + -0.74061656 0.65949166 0.12867692, + -0.74306715 0.6616742 0.10019203, + -0.78517294 0.61111796 0.10019199, + -0.78711671 0.6126318 0.071621381, + -0.82588506 0.55927104 0.071621604, + -0.82724631 0.56019217 0.042992912, + -0.8624711 0.50427705 0.042993005, + -0.86316216 0.50468111 0.015751904, + -0.87020969 0.49242982 0.015743895, + -0.82792187 0.56068188 0.013462299, + -0.82723087 0.56021386 0.043004394, + -0.78841138 0.61364329 0.043004718, + -0.78711486 0.61263394 0.071622886, + -0.74490309 0.66331708 0.07162331, + -0.74306267 0.66167879 0.10019496, + -0.69770902 0.70933992 0.100195, + -0.69540775 0.70700067 0.12867795, + -0.64716315 0.75141317 0.12867802, + -0.64449 0.74830902 0.15705501, + -0.59362072 0.78927058 0.15705493, + -0.59066993 0.78534687 0.18530896, + -0.53748226 0.82266235 0.18530907, + -0.53435516 0.81787622 0.21340805, + -0.47912294 0.85140985 0.21340697, + -0.47592509 0.84572619 0.24133506, + -0.41545784 0.86792469 0.2722159, + -0.35764116 0.89461541 0.26787314, + -0.36023495 0.90110385 0.24133497, + -0.421817 0.881208 0.21340798, + -0.47912204 0.85141003 0.21340801, + -0.48192611 0.85639119 0.18531404, + -0.53747308 0.82266718 0.18531404, + -0.54015911 0.82677817 0.15705405, + -0.59362197 0.78926992 0.15705399, + -0.59608471 0.79254359 0.12867594, + -0.64716768 0.75140965 0.12867594, + -0.64930874 0.7538957 0.10019596, + -0.69770795 0.70934099 0.100195, + -0.69943535 0.71109742 0.071628734, + -0.74489474 0.66332579 0.071628481, + -0.74612206 0.66441905 0.043002702, + -0.78841352 0.61364067 0.043003075, + -0.78909618 0.6141721 0.010954003, + -0.81503201 0.57941598 2.6662399e-006, + -0.229702 0.973261 0, + -0.67927855 0.73388052 1.9364386e-006, + -0.22968997 0.97326386 -2.1163698e-006, + -0.22969091 0.97326362 -2.4361991e-006, + -0.22963408 0.97302532 0.022133708, + -0.22964494 0.97302276 0.022133695, + 0.32753488 0.90506268 0.27126092, + 0.33023587 0.91252565 0.24133192, + 0.26919797 0.93235791 0.24133196, + 0.27100706 0.93862319 0.21340504, + 0.20837404 0.95448315 0.21340606, + 0.20959389 0.96006858 0.18530691, + 0.14568706 0.97182131 0.18530707, + 0.14641501 0.97667605 0.15705602, + 0.081559122 0.98421621 0.15705605, + 0.081897385 0.98829889 0.12867899, + 0.016375002 0.99155104 0.12867902, + 0.016429203 0.99483311 0.10018601, + -0.04933688 0.99374467 0.10018596, + -0.04945901 0.99620426 0.071629822, + -0.18070693 0.98259664 0.042997386, + -0.1808629 0.98344952 0.010749495, + -0.12840104 0.99172235 -6.8545023e-006, + -0.12837002 0.9914881 0.021738904, + -0.12833495 0.99149263 0.021738892, + -0.128365 0.99172699 0, + -0.12840301 0.99172211 -5.9493009e-006, + -0.025738891 0.99966866 -2.6926391e-006, + -0.75112319 0.66016209 4.2811911e-007, + -0.75112456 0.6601606 1.3694691e-006, + -0.75096291 0.66001886 0.020733498, + -0.75096369 0.66001779 0.020733492, + -0.75112498 0.66016001 0, + -0.81502414 0.57942706 0, + -0.81481439 0.57927728 0.022702113, + -0.81482673 0.57925975 0.022702092, + -0.81503695 0.57940894 0, + -0.8703174 0.49249122 0, + -0.87027907 0.49255905 -1.6960302e-006, + -0.87028694 0.49254501 3.9941701e-006, + -0.91631597 0.40045601 2.9067e-006, + -0.91631466 0.40045884 3.9050988e-006, + -0.91609269 0.40036187 0.022010192, + -0.91608709 0.40037504 0.022010202, + -0.916309 0.40047199 0, + -0.87029886 0.49252391 0, + -0.87009096 0.49240601 0.0218668, + -0.89466673 0.44660485 0.010746497, + -0.89389074 0.44621691 0.043008387, + -0.86245286 0.50430691 0.043008491, + -0.86103415 0.50347811 0.071623512, + -0.8258822 0.55927509 0.071624018, + -0.82384169 0.55789381 0.10019697, + -0.78516597 0.61112601 0.100197, + -0.78257638 0.6091103 0.12868106, + -0.74061066 0.65949768 0.12868094, + -0.73755026 0.65677226 0.15706606, + -0.69252396 0.70408887 0.15706497, + -0.68908274 0.70058978 0.18530793, + -0.64128882 0.74458683 0.18530795, + -0.63755822 0.74025434 0.21340808, + -0.58724278 0.78077078 0.2134079, + -0.58332282 0.77555883 0.24133594, + -0.57823712 0.76880419 0.27309707, + -0.58331907 0.77556103 0.24133801, + -0.63329482 0.73531872 0.24133791, + -0.63755018 0.74026018 0.21341205, + -0.68507499 0.69651097 0.213412, + -0.68908435 0.70058841 0.18530712, + -0.7338922 0.65350109 0.18530704, + -0.73755795 0.65676492 0.15706098, + -0.77934486 0.60659194 0.15705997, + -0.78257769 0.60910875 0.12867996, + -0.8211239 0.55605495 0.12867999, + -0.82384086 0.55789495 0.10019699, + -0.85890418 0.50223911 0.10019802, + -0.86103112 0.50348306 0.071626306, + -0.8924337 0.44545683 0.071626477, + -0.89390427 0.44619116 0.042995315, + -0.92144006 0.38613403 0.042995304, + -0.92218345 0.38644579 0.015400791, + -0.91630238 0.40019119 0.015392408, + -0.91641086 0.40023893 0, + -0.95263118 0.30412805 0, + -0.95238715 0.30405006 0.022631906, + -0.95239013 0.30404103 0.022631902, + -0.9526341 0.30411902 0, + -0.95263243 0.30412415 1.1914105e-006, + -0.99470115 0.102809 3.5273504e-006, + 0.077167705 0.9970181 -3.5978205e-006, + 0.077176645 0.99701738 -7.1562058e-006, + 0.077160403 0.99680698 0.0205449, + 0.077181526 0.99680531 0.020544808, + 0.07719779 0.99701583 0, + -0.025751609 0.99966836 0, + -0.025744896 0.99940884 0.022785896, + -0.025723308 0.99940932 0.022785908, + -0.025730001 0.99966902 0, + -0.12865198 0.99168986 0, + -0.12863497 0.99156177 0.016070496, + -0.11546998 0.99318081 0.016077898, + -0.049551878 0.99784553 0.042997882, + -0.049470402 0.99620414 0.071624808, + 0.016494203 0.99729526 0.071624912, + 0.016453493 0.9948315 0.10019696, + 0.082171872 0.99156862 0.10019697, + 0.081900924 0.9882983 0.12868105, + 0.14703603 0.98072517 0.12868004, + 0.14642802 0.97667313 0.15706201, + 0.21065398 0.96486086 0.15706196, + 0.20960708 0.96006435 0.18531407, + 0.2726019 0.94411165 0.18531394, + 0.27101704 0.9386192 0.21341005, + 0.33246797 0.91865188 0.21340998, + 0.33024904 0.9125191 0.24133903, + 0.38982686 0.88870162 0.24133892, + 0.38738206 0.88312805 0.26461303, + 0.38948905 0.88219512 0.26463199, + 0.14826891 0.98887342 0.012062793, + 0.14814295 0.98803067 0.043001484, + 0.21311009 0.97608143 0.043001417, + 0.21275993 0.97447562 0.071627177, + 0.27668488 0.95828754 0.071626961, + 0.27600098 0.95592099 0.100192, + 0.33857581 0.93558955 0.10019195, + 0.33745888 0.9325037 0.12867896, + 0.39835179 0.90816152 0.12867995, + 0.39670616 0.90440929 0.15706106, + 0.45561486 0.8762117 0.15706094, + 0.45334983 0.87185669 0.18530995, + 0.50999093 0.83998185 0.18530999, + 0.5070228 0.83509272 0.21341993, + 0.56110877 0.79975569 0.21341893, + 0.60864514 0.7558502 0.24133304, + 0.60397279 0.75004768 0.26952791, + 0.5442149 0.79488796 0.26829696, + 0.54442024 0.79474634 0.26830012, + 0.54521096 0.7959829 0.26297596, + 0.554138 0.78981996 0.262898, + 0.5036239 0.82953078 0.24133293, + 0.50700766 0.83510447 0.21340986, + 0.45070603 0.86678714 0.21341103, + 0.45334384 0.87186062 0.18530592, + 0.39473107 0.89991623 0.18530604, + 0.39670211 0.90441132 0.15705906, + 0.33607396 0.92864788 0.15705898, + 0.33746794 0.93249977 0.12868397, + 0.27509597 0.95276588 0.12868398, + 0.27600703 0.95591909 0.10019401, + 0.21223091 0.97206956 0.10019395, + 0.21275592 0.97447664 0.071625367, + 0.14788704 0.98640722 0.071625315, + 0.14813094 0.98803264 0.042996284, + 0.082489111 0.99566412 0.042996209, + 0.082551777 0.99642074 0.018192796, + 0.077054203 0.99686092 0.01819, + 0.077066898 0.99702597 0, + 0.17929699 0.98379499 0, + 0.17924894 0.98353362 0.023049293, + 0.17921402 0.98354006 0.023049302, + 0.17926091 0.98380154 0, + 0.27952603 0.96013808 0, + 0.27947605 0.95996517 0.018972203, + 0.21327397 0.97692287 0.011665898, + 0.213091 0.97608596 0.0429928, + 0.27713609 0.95986837 0.042992514, + 0.27667999 0.95828909 0.071625009, + 0.33940393 0.9379099 0.071624592, + 0.33856583 0.93559361 0.10018796, + 0.39966777 0.91116846 0.10018794, + 0.39834899 0.90816301 0.12867799, + 0.45750985 0.87984473 0.12867795, + 0.45561978 0.8762086 0.15706393, + 0.51252967 0.84418255 0.15706392, + 0.50998294 0.83998787 0.18530498, + 0.564372 0.80445403 0.185305, + 0.56108797 0.79977387 0.21340598, + 0.61272418 0.76093817 0.21340606, + 0.60863596 0.75585985 0.24132597, + 0.65725595 0.71398592 0.24132696, + 0.6515401 0.7077772 0.27303305, + 0.61644197 0.74238193 0.26242796, + 0.61645669 0.74236965 0.26242787, + 0.68249995 0.68250197 0.26150501, + 0.38940808 0.88188118 0.26579505, + 0.38937399 0.88189596 0.26579601, + 0.30672112 0.91515535 0.26155812, + 0.30676496 0.91514087 0.26155797, + 0.30673906 0.91514921 0.26155907, + 0.26685596 0.92424387 0.27305898, + 0.2691991 0.93235731 0.24133307, + 0.20838191 0.95448053 0.2134099, + 0.14568897 0.97182083 0.18530796, + 0.081147127 0.97932428 0.18530805, + 0.081552513 0.98421717 0.15705302, + 0.016311692 0.98745561 0.15705192, + 0.016379299 0.99155086 0.12868099, + -0.049150012 0.99046725 0.12868103, + -0.049312696 0.99374491 0.10019699, + -0.11490602 0.98831022 0.10019702, + -0.18041191 0.9809795 0.071629263, + -0.18070906 0.98259634 0.042996313, + -0.2452549 0.96850467 0.042996086, + -0.24545404 0.96929115 0.015062002, + -0.22944602 0.97320503 0.015052401, + -0.22947206 0.97331524 0, + -0.32846412 0.94424731 0.022545308, + -0.32846111 0.94424838 0.022545308, + -0.32854387 0.94448864 0, + -0.60019135 0.79985648 0, + 0.04458401 0.96423018 0.26129007, + 0.015904892 0.96213752 0.27209985, + 0.016039992 0.97031051 0.24132988, + -0.048123021 0.96924949 0.2413291, + -0.048446275 0.97576052 0.2134109, + -0.11282202 0.97042614 0.21341103, + -0.11348205 0.97610444 0.18531607, + -0.17775102 0.96646911 0.18531601, + -0.17863901 0.97129911 0.15705502, + -0.24243499 0.95737094 0.15705501, + -0.24344099 0.96134096 0.128686, + -0.30644578 0.94314939 0.12868592, + -0.3074601 0.9462713 0.10019403, + -0.36930889 0.9238897 0.10019396, + -0.37022403 0.92617708 0.07162521, + -0.43064696 0.89967388 0.071625493, + -0.48998407 0.87067014 0.043000903, + -0.49039894 0.87140793 0.012533198, + -0.51477826 0.85732335 0, + -0.51464212 0.85709721 0.022973906, + -0.51467592 0.85707688 0.022973899, + -0.51481205 0.85730314 0, + -0.51479322 0.85731441 4.9524324e-006, + -0.60021192 0.79984099 2.55533e-006, + -0.6002177 0.79983658 -2.6417686e-007, + -0.60010099 0.79968196 0.0196885, + -0.60007519 0.79970127 0.019688508, + -0.54690981 0.83711469 0.011346196, + -0.54643905 0.83639413 0.043002304, + -0.48998094 0.87067187 0.043002594, + -0.48917514 0.86924028 0.071617432, + -0.43066287 0.89966685 0.071617685, + -0.42960015 0.89744431 0.10018703, + -0.36932501 0.92388397 0.100187, + -0.36810604 0.92083514 0.12868801, + -0.30644181 0.94315046 0.12868792, + -0.30517584 0.93925452 0.15706192, + -0.24241988 0.9573735 0.15706192, + -0.24121498 0.9526149 0.18531097, + -0.177763 0.96646792 0.185311, + -0.17672805 0.96084529 0.21340908, + -0.11282799 0.9704259 0.21340898, + -0.11207503 0.96394926 0.24133205, + -0.048118301 0.96924901 0.24133199, + -0.047819417 0.96322733 0.2643981, + -0.044538207 0.96337724 0.26442507, + -0.044511478 0.96293151 0.26604789, + -0.044567686 0.96292865 0.26604891, + -0.11115699 0.95611286 0.27109498, + -0.11206803 0.96394926 0.24133506, + -0.17552793 0.95443559 0.24133489, + -0.176708 0.96084702 0.21341801, + -0.23982206 0.94706821 0.21341807, + -0.24122602 0.95261306 0.18530601, + -0.30368009 0.93458021 0.18530604, + -0.30519682 0.93924946 0.15705191, + -0.36660302 0.9170261 0.15705201, + -0.3681241 0.92082918 0.12867904, + -0.42815581 0.89449656 0.12867995, + -0.42957294 0.89745587 0.10019998, + -0.48795283 0.8670997 0.10019996, + -0.48916084 0.86924767 0.07162407, + -0.54554516 0.8350153 0.071624622, + -0.54644406 0.83639109 0.043000005, + -0.60051471 0.79845661 0.04299948, + -0.6009593 0.79904836 0.019224508, + -0.60010397 0.79969102 0.019223901, + -0.60021532 0.79983848 0, + -0.67927283 0.73388582 0, + -0.679093 0.73369098 0.023031298, + -0.67910379 0.73368084 0.023031294, + -0.67928374 0.73387569 0, + -0.75110906 0.66017807 0, + -0.75098896 0.66007197 0.017901499, + -0.74669665 0.66492373 0.017904691, + -0.74612594 0.66441494 0.043000598, + -0.69943488 0.7110979 0.071629092, + -0.65090901 0.75576901 0.071629003, + -0.64930099 0.75390202 0.1002, + -0.59804696 0.79517287 0.10019998, + -0.59607393 0.79255086 0.12868199, + -0.54239571 0.83020943 0.12868193, + -0.54015517 0.82678032 0.15705606, + -0.48435611 0.86065823 0.15705605, + -0.481949 0.85638094 0.18530199, + -0.42427304 0.88637209 0.18530202, + -0.421803 0.88121301 0.21341498, + -0.36264497 0.90716189 0.21341497, + -0.36022389 0.90110666 0.24134091, + -0.29987508 0.92294627 0.24134007, + -0.29811203 0.91751909 0.26322603, + -0.30656004 0.91471213 0.26329204, + -0.38799992 0.87870383 0.27809292, + -0.38988096 0.8830229 0.26127297, + -0.38989812 0.88301522 0.26127309, + -0.46928695 0.84258789 0.26422596, + -0.46931595 0.84257185 0.26422596, + 0.83867782 -0.5446279 8.794818e-008, + 0.83867389 -0.54463392 0, + 0.83867902 -0.544626 0, + -0.46904895 0.84206796 0.26629797, + -0.46910489 0.84203684 0.26629794, + -0.54542512 0.79625618 0.26170102, + -0.54544002 0.79624599 0.26170096, + -0.61652398 0.74243999 0.26207098, + -0.61650914 0.74245214 0.26207104, + -0.68214911 0.6820991 0.26346406, + -0.68209362 0.68215466 0.26346388, + -0.73910135 0.61371922 0.27762911, + 0.99867415 -0.051477712 6.2981314e-007, + 0.96702886 -0.25466698 -1.1942898e-006, + -0.99118936 0.13187404 0.012364805, + -0.99034828 0.13176204 0.042999513, + -0.9778623 0.19661108 0.071619928, + -0.96273196 0.26080197 0.071619898, + -0.96035379 0.26015696 0.10019398, + -0.94105798 0.32306501 0.100194, + -0.91461879 0.3832939 0.12867898, + -0.91083944 0.38170975 0.15706392, + -0.88362586 0.44106293 0.15706299, + -0.87923449 0.43887073 0.18530789, + -0.84829897 0.496034 0.18530799, + -0.84336132 0.49314615 0.21342108, + -0.80892754 0.54780269 0.21342088, + -0.80353022 0.54414719 0.24133608, + -0.76581424 0.59605825 0.24133608, + -0.75931495 0.59100002 0.27232301, + -0.74261117 0.61666316 0.26125705, + 0.40167099 -0.91569602 0.0126991, + 0.4013311 -0.91492325 0.04299761, + 0.33997801 -0.93945003 0.042997699, + 0.3394179 -0.93790478 0.071624584, + 0.27668491 -0.95828766 0.071624979, + 0.27600095 -0.95592088 0.10019398, + 0.21222404 -0.97207111 0.10019401, + 0.21152388 -0.96886444 0.12868293, + 0.14703599 -0.98072487 0.12868299, + 0.146429 -0.97667402 0.157056, + 0.081552476 -0.98421675 0.15705597, + 0.081146911 -0.97932315 0.18531403, + 0.016250297 -0.98254502 0.185314, + 0.016155692 -0.97682852 0.21341291, + -0.048446305 -0.9757601 0.21341303, + -0.048122983 -0.96924865 0.24133192, + -0.11206801 -0.96395004 0.24133202, + -0.11115699 -0.95611286 0.27109498, + -0.13334794 -0.95591354 0.26162487, + -0.133351 -0.95591313 0.26162502, + -0.044567686 -0.96292865 0.26604891, + -0.044511478 -0.96293151 0.26604789, + 0.46732599 -0.83889502 0.279037, + 0.49986812 -0.82334018 0.26878005, + 0.50362504 -0.82953012 0.24133302, + 0.56111014 -0.7997582 0.21340606, + 0.61273092 -0.76093286 0.21340598, + 0.61631513 -0.76538515 0.18531404, + 0.66555494 -0.72297698 0.185313, + 0.66888124 -0.72658926 0.15705407, + 0.71543187 -0.68080187 0.15705399, + 0.71839869 -0.68362576 0.12868196, + 0.76202077 -0.63463789 0.12868197, + 0.76454276 -0.63673878 0.10018996, + 0.80692995 -0.58628702 0.071635097, + 0.8439256 -0.53165579 0.07163506, + 0.84531689 -0.53253293 0.042989392, + 0.87865877 -0.4755109 0.042989388, + 0.87940919 -0.47591713 0.011929103, + -0.91373551 0.30616486 0.26711488, + -0.91371012 0.30624002 0.26711604, + -0.94572759 -0.32467285 0.013667594, + -0.94494116 -0.32440305 0.042998806, + -0.9514032 0.19128603 0.24133304, + -0.961963 0.12800598 0.24133299, + -0.97482675 0.064554982 0.21341395, + -0.98053265 0.064932778 0.18530892, + -0.98543066 -0.065270975 0.15705395, + -0.98951763 -0.065541573 0.12868196, + -0.98302388 -0.13078599 0.12868199, + -0.98627752 -0.13121894 0.10019095, + -0.97544307 -0.19614503 0.10019001, + -0.97785825 -0.19663103 0.071620017, + -0.96273065 -0.26080692 0.071619876, + -0.96515191 -0.26146296 0.010902699, + -0.95449954 -0.13314493 0.26683888, + -0.49039894 -0.87140793 0.012533198, + -0.48998407 -0.87067014 0.043002605, + -0.79515404 -0.54467803 0.26656303, + -0.79516548 -0.54466128 0.26656315, + -0.83101416 -0.4859181 0.27073807, + -0.83773911 -0.48985004 0.24133003, + -0.80353129 -0.54414821 0.24133009, + -0.80892819 -0.5478031 0.21341704, + -0.7709707 -0.60004777 0.21341692, + -0.77548373 -0.60355973 0.18531194, + -0.73389113 -0.65350103 0.18531102, + -0.73755687 -0.65676492 0.15706599, + -0.69253492 -0.70407802 0.15706499, + -0.6954087 -0.70699978 0.12867795, + -0.64716756 -0.75140947 0.1286779, + -0.64930856 -0.75389546 0.10019992, + -0.59806168 -0.79516166 0.10019995, + -0.59954286 -0.79713082 0.071629174, + -0.54554492 -0.835015 0.071628891, + -0.546444 -0.83639097 0.0430023, + -0.54690981 -0.83711469 0.011346196, + -0.54643911 -0.83639419 0.043000013, + -0.60052276 -0.79845071 0.042999484, + -0.59953505 -0.79713708 0.071624905, + -0.65090919 -0.75576919 0.071624912, + -0.64930075 -0.75390273 0.10019596, + -0.69770902 -0.70933992 0.100195, + -0.69540793 -0.70700085 0.12867698, + -0.74061102 -0.65949798 0.128677, + -0.73755085 -0.65677291 0.15706098, + -0.77934402 -0.60659301 0.15705998, + -0.77547163 -0.60357869 0.18530092, + -0.8136695 -0.55100369 0.18530189, + -0.80893248 -0.54779536 0.21342112, + -0.84336901 -0.49313298 0.213421, + -0.83774209 -0.48984307 0.24133402, + -0.84316403 -0.46961901 0.261787, + -0.86071724 -0.42962715 0.27310508, + -0.86828524 -0.43340409 0.24133304, + -0.88056189 -0.38881594 0.27098498, + -0.88858694 -0.37237799 0.267858, + -0.89502704 -0.37507603 0.24133903, + -0.86828905 -0.43339303 0.24133903, + -0.87412393 -0.43630493 0.21341397, + -0.84336269 -0.49314681 0.21341392, + -0.84829998 -0.49603501 0.18530101, + -0.81366897 -0.55100489 0.18530098, + -0.81773168 -0.55375677 0.15706094, + -0.77934438 -0.6065923 0.15706107, + -0.78257763 -0.60910869 0.12868094, + -0.74061626 -0.65949124 0.12868105, + -0.74306697 -0.66167402 0.100195, + -0.69770795 -0.70934099 0.100195, + -0.65091598 -0.75576299 0.071629003, + -0.65198869 -0.75700867 0.04299508, + -0.60051489 -0.79845691 0.042994898, + -0.6009593 -0.79904836 0.019224508, + -0.60010397 -0.79969102 0.019223901, + -0.65255833 -0.75765038 0.011557406, + -0.6519981 -0.75700021 0.043000612, + -0.74490273 -0.66331673 0.071628481, + -0.74306285 -0.66167897 0.10019199, + -0.78516638 -0.6111263 0.10019205, + -0.78257602 -0.60911101 0.12868001, + -0.82112873 -0.55604774 0.12867996, + -0.81773591 -0.55374992 0.15706399, + -0.85254371 -0.49849781 0.15706395, + -0.84830672 -0.49602082 0.18530793, + -0.87923133 -0.43887717 0.18530808, + -0.8741166 -0.43632379 0.21340489, + -0.90103781 -0.37760991 0.21340494, + -0.89502341 -0.37508914 0.24133211, + -0.91236627 -0.31322813 0.26358309, + -0.91785729 -0.3151131 0.24133307, + -0.93668276 -0.25373694 0.24133594, + -0.91785824 -0.31510806 0.24133605, + -0.92402512 -0.31722504 0.21341501, + -0.90104461 -0.37758783 0.21341489, + -0.9063186 -0.37979782 0.18531092, + -0.8792339 -0.43887094 0.18531097, + -0.88362712 -0.44106302 0.15705602, + -0.85253578 -0.49851388 0.15705597, + -0.85607266 -0.50058174 0.12867594, + -0.8211242 -0.55605513 0.12867703, + -0.82384086 -0.55789495 0.10019699, + -0.78517205 -0.61111808 0.10019702, + -0.78711706 -0.61263108 0.071622908, + -0.7448951 -0.66332608 0.07162331, + -0.74612218 -0.66441911 0.043000612, + -0.70118296 -0.71287692 0.012212998, + -0.46904895 -0.84206796 0.26629797, + -0.53078091 -0.81241995 0.24134095, + -0.47592402 -0.84572512 0.24134101, + -0.47912282 -0.85140967 0.2134079, + -0.42180404 -0.88121414 0.21340801, + -0.42427185 -0.88637167 0.18530694, + -0.36476395 -0.91247386 0.18530698, + -0.36658686 -0.9170326 0.15705192, + -0.30517694 -0.93925589 0.15705198, + -0.3064419 -0.94315064 0.12868595, + -0.24345607 -0.96133721 0.12868603, + -0.24426191 -0.96451867 0.10019896, + -0.17998303 -0.97855318 0.10019902, + -0.18042906 -0.98097634 0.071629219, + -0.11518896 -0.99075764 0.071629375, + -0.049590189 -0.99868178 0.013249196, + -0.049548689 -0.99784577 0.042997889, + -0.39005819 -0.88295543 0.26123613, + -0.38988096 -0.8830229 0.26127297, + -0.38989812 -0.88301522 0.26127309, + -0.41545784 -0.86792469 0.2722159, + -0.3602241 -0.90110821 0.24133506, + -0.36264497 -0.9071629 0.21341097, + -0.30189785 -0.92914659 0.2134109, + -0.30366507 -0.93458503 0.18530601, + -0.24121501 -0.95261598 0.185306, + -0.24241991 -0.95737463 0.15705495, + -0.17862703 -0.97130126 0.15705504, + -0.179368 -0.97533101 0.128673, + -0.11453103 -0.98505116 0.12867303, + -0.11490998 -0.98830986 0.10019699, + -0.04933688 -0.99374366 0.10019697, + -0.049459081 -0.99620461 0.071624875, + 0.016498402 -0.99729514 0.071624905, + 0.016525604 -0.99893826 0.043002512, + 0.082489081 -0.99566376 0.04300249, + 0.082551777 -0.99642074 0.018192796, + 0.07719779 -0.99701583 0, + -0.87027907 -0.49255905 -1.6960302e-006, + -0.87007058 -0.49244177 0.02186669, + -0.87009096 -0.49240601 0.0218668, + -0.87029886 -0.49252391 0, + -0.87028694 -0.49254501 3.9941701e-006, + -0.81503201 -0.57941598 2.6662399e-006, + -0.75112319 -0.66016209 4.2811911e-007, + 0.37673506 -0.92632115 -2.3173002e-006, + 0.27943286 -0.95995849 0.019920489, + 0.17928001 -0.98379815 -4.6769906e-006, + 0.077167705 -0.9970181 -3.5984106e-006, + 0.077176645 -0.99701738 -7.1580353e-006, + 0.077160403 -0.99680698 0.0205449, + 0.077181526 -0.99680531 0.020544808, + 0.016547106 -0.99980235 0.011022003, + 0.016532803 -0.99893826 0.042999309, + -0.049551878 -0.99784553 0.042999279, + -0.04947038 -0.99620366 0.071629867, + -0.11518995 -0.99075752 0.07162977, + -0.11490595 -0.98831052 0.10019495, + -0.17997405 -0.97855526 0.10019502, + -0.17938001 -0.97532809 0.12867801, + -0.24344096 -0.96134186 0.12867899, + -0.24243493 -0.95736974 0.15706195, + -0.30519602 -0.93924814 0.15706201, + -0.30367905 -0.93457913 0.18531302, + -0.36477596 -0.9124679 0.18531297, + -0.36265409 -0.9071582 0.21341504, + -0.42181709 -0.88120615 0.21341504, + -0.47591415 -0.84573227 0.24133509, + -0.47272196 -0.84005898 0.266148, + -0.46931595 -0.84257185 0.26422596, + -0.46928695 -0.84258789 0.26422596, + -0.74262381 -0.6166479 0.26125693, + -0.32846111 -0.94424838 0.022545308, + -0.32846412 -0.94424731 0.022545308, + -0.22947206 -0.97331524 0, + -0.128365 -0.99172699 0, + -0.229702 -0.973261 0, + -0.22964494 -0.97302276 0.022133695, + -0.22963408 -0.97302532 0.022133708, + -0.67614102 -0.68742698 0.26509899, + -0.68050271 -0.69186163 0.24133688, + -0.63329506 -0.73531908 0.24133602, + -0.63755077 -0.74026078 0.2134079, + -0.587228 -0.78078198 0.21340798, + -0.59066415 -0.78535116 0.18530902, + -0.53747392 -0.8226679 0.18530896, + -0.54015899 -0.82677799 0.157056, + -0.48433381 -0.86067069 0.15705596, + -0.48634386 -0.86424071 0.12867595, + -0.42815605 -0.8944971 0.12867501, + -0.42957309 -0.89745724 0.10018703, + -0.36930999 -0.92388999 0.100187, + -0.37022385 -0.92617762 0.071618073, + -0.30821502 -0.9486171 0.071617909, + -0.30872205 -0.95018011 0.042994607, + -0.24525493 -0.96850479 0.042994387, + -0.24545404 -0.96929115 0.015062002, + -0.22944602 -0.97320503 0.015052401, + -0.30900708 -0.95095831 0.013884705, + -0.30875102 -0.9501701 0.043007605, + -0.37084898 -0.92769688 0.043007497, + -0.37023902 -0.92617112 0.07162521, + -0.43066305 -0.89966613 0.071625404, + -0.42959914 -0.89744329 0.10020003, + -0.48795989 -0.86709577 0.10019997, + -0.48635107 -0.86423612 0.12868002, + -0.54239595 -0.83020985 0.12867899, + -0.54015493 -0.82678092 0.15705399, + -0.59362084 -0.78927082 0.15705398, + -0.59066927 -0.78534633 0.18531309, + -0.64128888 -0.74458587 0.18531199, + -0.63755769 -0.74025369 0.2134119, + -0.68508613 -0.69650006 0.21341202, + -0.68051201 -0.69185001 0.241344, + -0.72474802 -0.64536297 0.241344, + -0.71979874 -0.64095575 0.26658091, + -0.73910135 -0.61371922 0.27762911, + -0.68209362 -0.68215466 0.26346388, + -0.68214911 -0.6820991 0.26346406, + -0.96407253 -0.044556178 0.26187587, + -0.96407133 -0.044579614 0.26187608, + -0.74261117 -0.61666316 0.26125705, + -0.75931495 -0.59100002 0.27232301, + -0.76581407 -0.59605807 0.24133703, + -0.72474074 -0.64537376 0.24133691, + -0.72961169 -0.64971179 0.21340393, + -0.6850757 -0.69651276 0.21340393, + -0.68908417 -0.70058823 0.18530805, + -0.64128137 -0.74459344 0.18530712, + -0.64448518 -0.74831319 0.15705504, + -0.59362185 -0.78926975 0.15705495, + -0.59608418 -0.79254317 0.12868203, + -0.54240108 -0.8302061 0.12868202, + -0.54419577 -0.83295357 0.10019595, + -0.48795307 -0.86710012 0.10019601, + -0.48916188 -0.86924773 0.071617387, + -0.43064713 -0.8996743 0.07161773, + -0.37083405 -0.92770308 0.043000706, + -0.37115604 -0.92850703 0.010861902, + -0.51479322 -0.85731441 4.9524324e-006, + -0.423915 -0.90570199 1.78828e-006, + -0.42390484 -0.9057067 5.8104279e-006, + -0.4238109 -0.90550476 0.021104194, + -0.42380804 -0.90550613 0.021104202, + -0.42390284 -0.90570766 0, + -0.32854387 -0.94448864 0, + -0.60021192 -0.79984099 2.55533e-006, + -0.12840301 -0.99172211 -5.9493009e-006, + -0.12840104 -0.99172235 -6.8545023e-006, + -0.12837002 -0.9914881 0.021738904, + -0.12833495 -0.99149263 0.021738892, + -0.1808629 -0.98344952 0.010749495, + -0.18070695 -0.98259676 0.042996287, + -0.24525797 -0.96850389 0.042996094, + -0.30822393 -0.94861388 0.071622394, + -0.30746311 -0.94627035 0.10019403, + -0.36932507 -0.9238832 0.10019402, + -0.36810699 -0.92083597 0.12867901, + -0.42816508 -0.89449221 0.12867904, + -0.42639494 -0.89079589 0.15706697, + -0.48435494 -0.86065686 0.15706697, + -0.48194799 -0.85637897 0.185314, + -0.53748178 -0.82266158 0.18531393, + -0.53435397 -0.81787503 0.213416, + -0.58724195 -0.78076893 0.21341699, + -0.58332306 -0.77555805 0.24133801, + -0.63329697 -0.73531693 0.24133797, + -0.62831908 -0.72953606 0.27017102, + 0.77716494 -0.62929696 1.6952798e-006, + 0.77511907 -0.63181514 0, + 0.83867389 0.54463392 0, + 0.83867782 0.5446279 8.794818e-008, + 0.83867902 0.544626 0, + -0.46910489 -0.84203684 0.26629794, + -0.52649522 -0.80585945 0.27091214, + -0.54544002 -0.79624599 0.26170096, + -0.54542512 -0.79625618 0.26170102, + -0.61650914 -0.74245214 0.26207104, + -0.61652398 -0.74243999 0.26207098, + -0.57823712 -0.76880419 0.27309707, + -0.58332002 -0.77556098 0.24133599, + -0.53077281 -0.81242669 0.24133591, + -0.53434014 -0.81788617 0.21340804, + -0.47912216 -0.85141027 0.21340707, + -0.48192716 -0.85639328 0.18530206, + -0.424263 -0.88637698 0.18530199, + -0.42638093 -0.89080387 0.15705997, + -0.3666029 -0.91702479 0.15705995, + -0.36812314 -0.92082828 0.12868804, + -0.30644602 -0.94314909 0.12868801, + -0.30746016 -0.94627142 0.10019305, + -0.2442489 -0.96452254 0.10019295, + -0.18041202 -0.9809801 0.071621411, + -0.18070906 -0.98259634 0.042997416, + -0.11546998 -0.99318081 0.016077898, + -0.12863497 -0.99156177 0.016070496, + -0.12865198 -0.99168986 0, + -0.025730001 -0.99966902 0, + -0.025723308 -0.99940932 0.022785908, + -0.025744896 -0.99940884 0.022785896, + -0.025751609 -0.99966836 0, + -0.025738891 -0.99966866 -2.6926391e-006, + -0.67927855 -0.73388052 1.9364386e-006, + -0.67928374 -0.73387569 0, + -0.67910379 -0.73368084 0.023031294, + -0.679093 -0.73369098 0.023031298, + -0.67927283 -0.73388582 0, + -0.60021532 -0.79983848 0, + -0.6002177 -0.79983658 -2.6417686e-007, + -0.60010099 -0.79968196 0.0196885, + -0.60007519 -0.79970127 0.019688508, + -0.60019135 -0.79985648 0, + -0.51481205 -0.85730314 0, + -0.51467592 -0.85707688 0.022973899, + -0.51464212 -0.85709721 0.022973906, + -0.51477826 -0.85732335 0, + -0.42401305 -0.9056561 0, + -0.42394915 -0.90552032 0.017320506, + -0.43169191 -0.90185475 0.017325094, + -0.48998097 -0.87067199 0.043000899, + -0.48917493 -0.86923987 0.071624085, + -0.54553676 -0.83502066 0.071624562, + -0.54418921 -0.8329584 0.10019205, + -0.59804696 -0.79517388 0.10019199, + -0.59607506 -0.79255104 0.12867601, + -0.64716387 -0.75141293 0.12867598, + -0.64448971 -0.74830866 0.15705791, + -0.69252467 -0.7040897 0.15705791, + -0.68908292 -0.7005899 0.18530698, + -0.73388505 -0.65350908 0.18530703, + -0.72961503 -0.64970708 0.21340702, + -0.77096003 -0.60006505 0.21340702, + -0.76581299 -0.59605998 0.24133599, + -0.80353665 -0.54413778 0.24133588, + -0.79863989 -0.54082197 0.26398095, + -0.79572487 -0.54508191 0.26402196, + -0.8431533 -0.46964219 0.26178008, + -0.84313893 -0.469668 0.26177999, + -0.88283932 -0.38982716 0.2619721, + -0.88284731 -0.38980913 0.2619721, + -0.91373551 -0.30616486 0.26711488, + -0.91371012 -0.30624002 0.26711604, + -0.91460133 -0.30659509 0.26363608, + -0.92868 -0.251569 0.27251899, + -0.93963176 -0.22099794 0.26125094, + -0.93963552 -0.22098188 0.26125085, + -0.95450121 -0.13313302 0.26683906, + -0.96059912 -0.063626207 0.27055702, + -0.96832091 -0.064137593 0.24133196, + -0.96196324 -0.12800601 0.24133205, + -0.96340066 -0.19370092 0.18530793, + -0.94849366 -0.25694492 0.18530793, + -0.95323116 -0.25822905 0.15706104, + -0.93407917 -0.3206681 0.15706104, + -0.91462332 -0.38328311 0.12867905, + -0.91764992 -0.38455099 0.100196, + -0.89023101 -0.44435301 0.100196, + -0.89243561 -0.44545278 0.071626462, + -0.86103398 -0.50347799 0.071626298, + -0.8624534 -0.50430721 0.042993117, + -0.82792187 -0.56068188 0.013462299, + -0.82723129 -0.56021416 0.042992912, + -0.78909618 -0.6141721 0.010954003, + -0.78841341 -0.61364061 0.043004669, + -0.82724589 -0.56019193 0.043004394, + -0.825885 -0.55927098 0.071624003, + -0.86103129 -0.50348318 0.071623519, + -0.85890502 -0.50224 0.100186, + -0.89022267 -0.44437185 0.10018596, + -0.88728601 -0.44290701 0.128674, + -0.91461957 -0.38329381 0.12867394, + -0.91083997 -0.38170999 0.157061, + -0.93407899 -0.320669 0.15705998, + -0.92943519 -0.31907508 0.18531404, + -0.94849575 -0.25693294 0.18531395, + -0.94297707 -0.25543803 0.21341403, + -0.95140237 -0.19129007 0.24133307, + -0.96196324 -0.12800403 0.24133304, + -0.95615244 -0.12723106 0.26378912, + -0.95530564 -0.13334595 0.26383692, + -0.95531905 -0.13326199 0.26383102, + -0.94330019 -0.18965705 0.27242404, + -0.95140266 -0.19128592 0.24133492, + -0.93668234 -0.2537401 0.24133408, + -0.94297624 -0.25544405 0.21341105, + -0.92402285 -0.31723496 0.21340998, + -0.92943102 -0.31909201 0.185306, + -0.90631545 -0.37980777 0.18530588, + -0.91084206 -0.38170403 0.15706302, + -0.8836329 -0.44104895 0.15706299, + -0.88729805 -0.44287905 0.12868701, + -0.85608417 -0.50055909 0.12868802, + -0.85891771 -0.5022158 0.10019797, + -0.82384169 -0.55789381 0.10019697, + -0.82588226 -0.55927521 0.071621619, + -0.78711498 -0.612634 0.071621403, + -0.78841144 -0.61364335 0.043003123, + -0.74612576 -0.66441476 0.043002684, + -0.74669665 -0.66492373 0.017904691, + -0.75098896 -0.66007197 0.017901499, + -0.75110906 -0.66017807 0, + -0.75112456 -0.6601606 1.3694691e-006, + -0.75096291 -0.66001886 0.020733498, + -0.75096369 -0.66001779 0.020733492, + -0.75112498 -0.66016001 0, + -0.81502414 -0.57942706 0, + -0.81481439 -0.57927728 0.022702113, + -0.81482673 -0.57925975 0.022702092, + -0.81503695 -0.57940894 0, + -0.8703174 -0.49249122 0, + -0.87020969 -0.49242982 0.015743895, + -0.86316216 -0.50468111 0.015751904, + -0.86247087 -0.50427592 0.043008596, + -0.89390421 -0.44619009 0.043008309, + -0.89243382 -0.44545689 0.071624689, + -0.91991866 -0.38551185 0.071624875, + -0.91764659 -0.38455981 0.10019195, + -0.94105828 -0.32306513 0.10019103, + -0.95718664 -0.25929791 0.12867896, + -0.95323187 -0.25822598 0.15706196, + -0.96339917 -0.19371304 0.18530305, + -0.97409505 -0.12962101 0.18530302, + -0.97482693 -0.064552203 0.213414, + -0.96832001 -0.064121298 0.24134, + -0.96198314 0 0.27310902, + -0.96407133 0.044579614 0.26187608, + -0.96407253 0.044556178 0.26187587, + -0.95449954 0.13314493 0.26683888, + -0.95450121 0.13313302 0.26683906, + -0.96059912 0.063626207 0.27055702, + -0.96831888 0.064137496 0.24133997, + -0.97482693 -0.064554997 0.213413, + -0.98053288 -0.06493289 0.18530796, + -0.97409564 -0.12960896 0.18530793, + -0.97896111 -0.13025601 0.15706201, + -0.97222751 -0.19548792 0.12867793, + -0.95718616 -0.25930005 0.12867802, + -0.96035361 -0.26015791 0.10019396, + -0.9410603 -0.3230581 0.10019403, + -0.94339073 -0.32385787 0.071623169, + -0.91991717 -0.38551608 0.071622916, + -0.92143267 -0.38615185 0.042995285, + -0.89389127 -0.44621715 0.042995315, + -0.89466673 -0.44660485 0.010746497, + -0.91631466 -0.40045884 3.9050988e-006, + -0.91609269 -0.40036187 0.022010192, + -0.91608709 -0.40037504 0.022010202, + -0.916309 -0.40047199 0, + -0.91631597 -0.40045601 2.9067e-006, + 0.14387506 -0.95971537 0.24134308, + 0.20837405 -0.95448232 0.21341008, + 0.20959288 -0.96006739 0.1853139, + 0.27260891 -0.94410962 0.18531394, + 0.27397206 -0.94882721 0.15705504, + 0.33607385 -0.92864853 0.15705493, + 0.33746815 -0.93250042 0.12867907, + 0.3983489 -0.90816277 0.12867998, + 0.39966694 -0.91116786 0.10019699, + 0.45901516 -0.88276029 0.10019704, + 0.46015117 -0.88494629 0.071630523, + 0.51762807 -0.85260206 0.071630508, + 0.51848072 -0.85400766 0.042995777, + 0.57380819 -0.81786031 0.042995911, + 0.57428205 -0.8185361 0.014097502, + 0.76832712 -0.63992405 0.013061201, + 0.76768172 -0.63938677 0.043004684, + 0.72375923 -0.68871123 0.043004815, + 0.72256917 -0.6875782 0.071624614, + 0.67554474 -0.73383176 0.071624875, + 0.67387617 -0.73201919 0.10019402, + 0.62400407 -0.77497107 0.10019401, + 0.6219458 -0.7724148 0.12868097, + 0.56954908 -0.81182212 0.12868102, + 0.56719524 -0.80846733 0.15706706, + 0.51252919 -0.84418225 0.15706705, + 0.50998211 -0.83998716 0.18531005, + 0.45334387 -0.87185985 0.18530996, + 0.45070595 -0.86678791 0.21340796, + 0.39243901 -0.89467794 0.21340798, + 0.389819 -0.88870502 0.241339, + 0.33023506 -0.91252416 0.24133906, + 0.32753488 -0.90506268 0.27126092, + 0.38937399 -0.88189596 0.26579601, + 0.38943917 -0.88186741 0.26579511, + 0.38726312 -0.88285828 0.26568508, + 0.38982686 -0.88870269 0.24133492, + 0.44769222 -0.86100441 0.24133611, + 0.45070088 -0.86678976 0.21341096, + 0.50702423 -0.83509433 0.21341009, + 0.50999212 -0.83998215 0.18530504, + 0.56438088 -0.80444777 0.18530495, + 0.56719905 -0.80846512 0.15706502, + 0.619385 -0.769216 0.15706401, + 0.62195569 -0.77240765 0.12867594, + 0.67165864 -0.72960067 0.12867594, + 0.67388111 -0.73201507 0.10019101, + 0.72079414 -0.68587005 0.10019101, + 0.72257924 -0.68756825 0.071618222, + 0.76642573 -0.63832784 0.071618281, + 0.76768821 -0.6393792 0.043000314, + 0.80827039 -0.58723933 0.043000523, + 0.80896896 -0.58774692 0.011089098, + 0.89448857 -0.44709077 2.148679e-006, + 0.71614724 -0.69794923 2.645551e-007, + 0.71597987 -0.69778687 0.021593599, + 0.71600157 -0.69776458 0.021593587, + 0.716169 -0.697927 0, + 0.71615362 -0.69794261 -3.1914185e-006, + 0.78411478 -0.62061578 -1.4287594e-006, + 0.84377772 -0.5366928 -9.843227e-007, + 0.84377068 -0.53670382 4.2679685e-006, + 0.84359598 -0.53659302 0.020341299, + 0.84360754 -0.53657472 0.020341288, + 0.84378201 -0.536686 0, + 0.78411084 -0.62062085 0, + 0.7839061 -0.62045908 0.022845501, + 0.78391308 -0.62045014 0.022845501, + 0.78411788 -0.62061197 0, + 0.71615267 -0.69794369 0, + 0.71605664 -0.69784969 0.016391892, + 0.72433317 -0.68925512 0.016398303, + 0.72376066 -0.68870968 0.04300398, + 0.67664266 -0.73505467 0.04300398, + 0.67552924 -0.73384523 0.071634233, + 0.62555307 -0.77688605 0.071633808, + 0.62400806 -0.77496809 0.10019201, + 0.57144809 -0.81449908 0.10019201, + 0.56956393 -0.81181288 0.12867299, + 0.5146631 -0.84768218 0.12867303, + 0.51253593 -0.84417886 0.15706399, + 0.45561385 -0.8762117 0.15706395, + 0.45335022 -0.8718574 0.18530607, + 0.39474705 -0.89990908 0.18530601, + 0.39245012 -0.8946743 0.21340308, + 0.33246902 -0.91865313 0.21340302, + 0.33024901 -0.912521 0.24133199, + 0.30673906 -0.91514921 0.26155907, + 0.26685596 -0.92424387 0.27305898, + 0.26919892 -0.93235767 0.24133192, + 0.20539008 -0.94077229 0.26974508, + 0.26919791 -0.93235767 0.2413329, + 0.27100703 -0.93862212 0.21341002, + 0.33245486 -0.91865653 0.2134099, + 0.33440003 -0.92403209 0.18531403, + 0.39473 -0.89991498 0.185314, + 0.39670202 -0.90441108 0.15706101, + 0.45561999 -0.87620902 0.157061, + 0.45751011 -0.87984419 0.12868103, + 0.51464808 -0.84769011 0.12868102, + 0.51635104 -0.8504951 0.10019802, + 0.57143593 -0.81450689 0.10019799, + 0.57285106 -0.81652415 0.071624406, + 0.62557018 -0.77687323 0.071624123, + 0.62660128 -0.77815336 0.04299042, + 0.67666596 -0.73503399 0.0429901, + 0.67725319 -0.73567116 0.010770103, + 0.64058572 -0.76788664 -1.0032894e-005, + 0.64042729 -0.76769638 0.022253811, + 0.64043331 -0.76769137 0.022253811, + 0.64059162 -0.76788163 0, + 0.64060313 -0.76787215 -2.5514908e-006, + 0.55824029 -0.82967937 1.2550905e-006, + 0.55823493 -0.82968295 0, + 0.55809397 -0.82947385 0.022453198, + 0.55810291 -0.82946789 0.022453198, + 0.55824393 -0.82967687 0, + 0.64200801 -0.766698 0, + 0.64193898 -0.76661497 0.0146932, + 0.62709612 -0.77880311 0.014705004, + 0.62658387 -0.77816683 0.04299989, + 0.57380104 -0.81786513 0.042999502, + 0.5728578 -0.81651968 0.071620971, + 0.51764601 -0.85259193 0.071621299, + 0.5163672 -0.85048622 0.10019004, + 0.45903009 -0.88275325 0.10019002, + 0.45751506 -0.87984204 0.12867801, + 0.39835188 -0.90816176 0.12867796, + 0.39670587 -0.90440971 0.15705894, + 0.33606502 -0.92865109 0.15705901, + 0.33439389 -0.92403364 0.18531694, + 0.27260202 -0.94411111 0.18531701, + 0.27101707 -0.93862033 0.21340507, + 0.20838304 -0.95448124 0.21340606, + 0.14389698 -0.95971489 0.24133196, + 0.14305808 -0.95411444 0.26305911, + 0.13329801 -0.95550704 0.26313102, + 0.079444401 -0.95879698 0.27275801, + 0.080134474 -0.96712571 0.24134292, + 0.015904892 -0.96213752 0.27209985, + 0.016039902 -0.97030807 0.24134003, + 0.080140784 -0.96712589 0.24133997, + 0.080679372 -0.97362566 0.21340993, + 0.14568898 -0.97182095 0.185307, + 0.20960693 -0.96006566 0.18530694, + 0.21065409 -0.9648605 0.15706408, + 0.27395096 -0.94883186 0.15706399, + 0.27508804 -0.95276809 0.12868401, + 0.337459 -0.93250299 0.128684, + 0.33857599 -0.93559003 0.100188, + 0.39968786 -0.91115963 0.10018796, + 0.40067804 -0.91341513 0.071624309, + 0.46016404 -0.88494015 0.071624205, + 0.46092215 -0.88639832 0.042998116, + 0.51847613 -0.85401028 0.042998016, + 0.51892591 -0.85475087 0.010817399, + 0.46997294 -0.88268089 -1.0623199e-006, + 0.46986699 -0.88248092 0.0212698, + 0.46984604 -0.88249207 0.021269802, + 0.46995276 -0.88269156 0, + 0.46996978 -0.88268256 -2.7007586e-006, + -0.95263243 -0.30412415 1.1914105e-006, + -0.9526341 -0.30411902 0, + -0.95239013 -0.30404103 0.022631902, + -0.95238715 -0.30405006 0.022631906, + -0.95263118 -0.30412805 0, + -0.91641086 -0.40023893 0, + -0.91630238 -0.40019119 0.015392408, + -0.92218345 -0.38644579 0.015400791, + -0.92143977 -0.38613391 0.043003589, + -0.94494432 -0.32439309 0.043003514, + -0.94339043 -0.32385916 0.071622834, + -0.96273184 -0.26080194 0.071622394, + -0.96035379 -0.26015696 0.10019498, + -0.97544438 -0.19613606 0.10019403, + -0.97222733 -0.19548908 0.12867804, + -0.98302299 -0.130798 0.128677, + -0.97896123 -0.13025703 0.15706104, + -0.98543066 -0.065255277 0.15706094, + -0.98053277 -0.064930983 0.18530895, + -0.97482705 0.06455221 0.21341303, + -0.96832192 0.064121403 0.24133199, + -0.96196353 0.12800394 0.24133189, + -0.95615244 0.12723106 0.26378912, + -0.95530564 0.13334595 0.26383692, + -0.95531905 0.13326199 0.26383102, + -0.94330019 0.18965705 0.27242404, + -0.93963176 0.22099794 0.26125094, + -0.93963552 0.22098188 0.26125085, + -0.92868 0.251569 0.27251899, + -0.93668318 0.25373706 0.24133405, + -0.95140189 0.19128998 0.24133497, + -0.97409409 0.12962101 0.18530801, + -0.980533 0.064930998 0.18530799, + -0.98543179 0.065255389 0.15705398, + -0.98951751 -0.065549769 0.12867895, + -0.98627812 -0.13121201 0.10019401, + -0.98872006 -0.13153702 0.071628511, + -0.97786164 -0.19661093 0.071628779, + -0.91785908 0.31510803 0.24133302, + -0.92402601 0.31722498 0.213411, + -0.94297791 0.25543797 0.21341097, + -0.94849688 0.25693297 0.18530796, + -0.96339822 0.19371304 0.18530804, + -0.98302239 0.13079706 0.12868206, + -0.98951709 0.065549806 0.12868302, + -0.99525052 -0.065918468 0.07163287, + -0.99689102 -0.066027097 0.042996395, + -0.9903484 -0.13176192 0.042996373, + -0.99118936 -0.13187404 0.012364805, + -0.97868246 -0.2046221 0.017622808, + -0.98022753 -0.19708692 0.01762679, + -0.99034923 -0.13175502 0.04299951, + -0.98871994 -0.131538 0.0716279, + -0.99525011 -0.065929711 0.071628004, + -0.98951811 0.065541707 0.12867902, + -0.98542964 0.065270878 0.15706094, + -0.97409666 0.12960896 0.18530294, + -0.96340162 0.19370092 0.18530294, + -0.94297558 0.25544387 0.21341389, + -0.93668211 0.25373903 0.24133602, + -0.91785663 0.31511289 0.24133591, + -0.91236627 0.31322813 0.26358309, + -0.91460133 0.30659509 0.26363608, + -0.88056189 0.38881594 0.27098498, + -0.88858694 0.37237799 0.267858, + -0.89502823 0.3750771 0.24133304, + -0.99689114 0.066027105 0.042994905, + -0.99525082 0.06591849 0.071627893, + -0.98627841 0.13121192 0.10019094, + -0.97544479 0.19613597 0.10018999, + -0.97222733 0.19548908 0.12867804, + -0.95718676 0.25929794 0.12867796, + -0.95323199 0.25822601 0.157061, + -0.93407887 0.32066897 0.15706098, + -0.92943656 0.31907585 0.18530591, + -0.90631914 0.37979904 0.18530601, + -0.90104657 0.37758881 0.21340489, + -0.8741256 0.43630579 0.21340489, + -0.86829025 0.4333941 0.24133304, + -0.83773798 0.48984998 0.24133399, + -0.83101416 0.4859181 0.27073807, + -0.8431533 0.46964219 0.26178008, + -0.84313893 0.469668 0.26177999, + -0.84316403 0.46961901 0.261787, + -0.86071724 0.42962715 0.27310508, + -0.86828369 0.43340382 0.24133892, + -0.89502162 0.37508884 0.24133892, + -0.9010359 0.37760895 0.21341497, + -0.92402202 0.31723398 0.21341498, + -0.92942977 0.3190909 0.18531395, + -0.94849241 0.25694513 0.18531409, + -0.95323104 0.25822902 0.15706201, + -0.97222751 0.19548792 0.12867793, + -0.98302454 0.13078594 0.12867694, + -0.98627722 0.13121903 0.10019402, + -0.99524963 0.065929681 0.071632877, + -0.9968909 -0.066030696 0.042994898, + -0.99774814 -0.066087402 0.011450202, + -0.99443936 -0.10276703 0.023007607, + -0.9944365 -0.10279495 0.023007588, + -0.99469978 -0.10282197 0, + -0.97883433 -0.20465405 0, + -0.97885793 -0.204541 -6.2673294e-006, + -0.97864372 -0.20449592 0.020923493, + -0.97864664 -0.20448193 0.020923493, + -0.97886097 -0.20452701 0, + -0.97885633 -0.20454906 -2.911831e-006, + 0.93571645 -0.35275316 -2.4657611e-006, + 0.93553185 -0.35266796 0.020135999, + 0.93572176 -0.35273892 3.6304491e-006, + 0.93570477 -0.35278392 0, + 0.89449239 -0.4470832 0, + 0.89425468 -0.44696382 0.023061991, + 0.89424711 -0.44697905 0.023062002, + 0.89448494 -0.44709799 0, + 0.84380305 -0.53665304 0, + 0.8436591 -0.53656209 0.018450502, + 0.84594798 -0.53294599 0.0184526, + 0.84531015 -0.53254312 0.04299511, + 0.80827761 -0.58722973 0.042995181, + 0.80694789 -0.58626395 0.071622394, + 0.76641965 -0.63833469 0.07162226, + 0.76452607 -0.63675708 0.10020101, + 0.72077823 -0.68588525 0.10020103, + 0.71840131 -0.68362325 0.12868105, + 0.67165107 -0.72960705 0.12868002, + 0.66887677 -0.72659272 0.15705694, + 0.61939979 -0.76920569 0.15705596, + 0.61631995 -0.76538199 0.185311, + 0.56437129 -0.80445337 0.1853101, + 0.5610863 -0.79977143 0.21341912, + 0.50700599 -0.83510292 0.21342, + 0.50362378 -0.8295306 0.24133389, + 0.447696 -0.86100298 0.24133399, + 0.4439421 -0.85378218 0.27197707, + 0.38948905 -0.88219512 0.26463199, + 0.38953292 -0.88217574 0.2646319, + 0.46968895 -0.84326988 0.26131997, + 0.46970379 -0.8432616 0.26131988, + 0.30672112 -0.91515535 0.26155812, + 0.30676496 -0.91514087 0.26155797, + 0.22092207 -0.93935728 0.2623001, + 0.22092608 -0.93935633 0.2623001, + 0.13312295 -0.95417869 0.26799491, + 0.13310499 -0.95418113 0.26799503, + 0.044572182 -0.96423066 0.26128992, + 0.04458401 -0.96423018 0.26129007, + -0.044538207 -0.96337724 0.26442507, + -0.047819417 -0.96322733 0.2643981, + -0.048118383 -0.96924967 0.24132891, + 0.016062308 -0.97031045 0.2413291, + 0.016170196 -0.97682977 0.21340595, + 0.080688685 -0.97362578 0.21340595, + 0.08116091 -0.97932315 0.18530801, + 0.14568701 -0.97182107 0.18530801, + 0.14641501 -0.97667509 0.15706201, + 0.210658 -0.96486002 0.15706199, + 0.21153201 -0.96886313 0.12868002, + 0.27509609 -0.9527663 0.12868005, + 0.27600709 -0.95591933 0.10019203, + 0.33856606 -0.93559325 0.10019203, + 0.33940411 -0.93790931 0.071631022, + 0.40066183 -0.91342157 0.071631461, + 0.40132284 -0.91492665 0.043001685, + 0.46091494 -0.88640189 0.043001693, + 0.46127495 -0.88709396 0.017026298, + 0.46992704 -0.88254112 0.017021202, + 0.46999505 -0.88266909 0, + 0.3767271 -0.92632425 0, + 0.37662813 -0.92608035 0.022946907, + 0.37664515 -0.92607331 0.022946907, + 0.37674418 -0.92631739 0, + 0.27945611 -0.96015847 0, + 0.27940097 -0.95996785 0.019920496, + 0.34027696 -0.94025791 0.011253598, + 0.33998394 -0.93944788 0.042994693, + 0.27713606 -0.95986825 0.042994611, + 0.27667996 -0.95828897 0.071626991, + 0.21275589 -0.97447652 0.07162717, + 0.21223097 -0.97206986 0.10019099, + 0.14752901 -0.98396993 0.100191, + 0.14704204 -0.98072422 0.12868004, + 0.081897371 -0.98829865 0.12867996, + 0.081559092 -0.98421687 0.15705198, + 0.016342901 -0.98745501 0.15705298, + 0.016261598 -0.98254585 0.18530896, + -0.048727017 -0.98147148 0.18530907, + -0.048443489 -0.97576076 0.21341096, + -0.11282695 -0.97042555 0.2134109, + -0.11207395 -0.96394855 0.24133489, + -0.17553699 -0.95443392 0.241335, + -0.17400898 -0.9461239 0.27307597, + -0.22094311 -0.9393844 0.26218513, + -0.22091006 -0.93939215 0.26218507, + 0.21327397 -0.97692287 0.011665898, + 0.21309093 -0.97608566 0.043001384, + 0.14813091 -0.98803246 0.043001473, + 0.14788705 -0.98640734 0.071623825, + 0.082373947 -0.9940244 0.071623757, + 0.082170479 -0.99156874 0.10019698, + 0.016429201 -0.99483198 0.100197, + 0.016374998 -0.99155086 0.12868099, + -0.049161483 -0.99046665 0.12868096, + -0.048958384 -0.98637563 0.15705495, + -0.11405201 -0.98098207 0.15705502, + -0.11348501 -0.97610408 0.18531601, + -0.17776202 -0.96646714 0.18531601, + -0.17672801 -0.96084309 0.21341902, + -0.23983003 -0.94706613 0.21341804, + -0.23822993 -0.94074667 0.24133392, + -0.29987499 -0.922948 0.24133399, + -0.29811203 -0.91751909 0.26322603, + -0.30656004 -0.91471213 0.26329204, + -0.30619511 -0.91355628 0.2676931, + -0.30632299 -0.91351402 0.26769099, + -0.236367 -0.93340898 0.26995999, + -0.23822495 -0.94074881 0.24133094, + -0.1755289 -0.95443642 0.24133085, + -0.17670803 -0.96084911 0.21340904, + -0.11282197 -0.97042662 0.21340893, + -0.11348196 -0.97610462 0.18531494, + -0.048739385 -0.98146975 0.18531495, + -0.048982874 -0.98637253 0.15706693, + 0.016311703 -0.98745322 0.15706703, + 0.016379302 -0.99155104 0.12867902, + 0.081900857 -0.98829854 0.12867895, + 0.08217188 -0.99156874 0.10019597, + 0.14751801 -0.98397112 0.10019601, + 0.14788394 -0.98640764 0.071625277, + 0.21275999 -0.9744758 0.071625382, + 0.21311091 -0.97608155 0.042992778, + 0.277141 -0.959867 0.042992499, + 0.27734804 -0.96058214 0.018973202, + 0.27947605 -0.95996517 0.018972203, + 0.27952603 -0.96013808 0, + 0.17926091 -0.98380154 0, + 0.17921402 -0.98354006 0.023049302, + 0.17924894 -0.98353362 0.023049293, + 0.17929699 -0.98379499 0, + 0.077066898 -0.99702597 0, + 0.077054203 -0.99686092 0.01819, + 0.14826891 -0.98887342 0.012062793, + 0.14814298 -0.98803085 0.042996295, + 0.082503192 -0.99566281 0.042996295, + 0.082367495 -0.99402481 0.071626686, + 0.0164942 -0.99729514 0.071626708, + 0.016453495 -0.99483263 0.10018596, + -0.0493128 -0.99374598 0.100186, + -0.049150102 -0.99046803 0.128676, + -0.114538 -0.98505002 0.128676, + -0.11406397 -0.98097974 0.15706097, + -0.17863901 -0.9712981 0.15706101, + -0.17775102 -0.96647012 0.18531102, + -0.24122602 -0.9526121 0.18531102, + -0.23982203 -0.94706905 0.21341403, + -0.30190307 -0.92914426 0.21341404, + -0.29988804 -0.9229421 0.24134003, + -0.36023387 -0.90110272 0.24134091, + -0.35762799 -0.89458394 0.26799601, + -0.38799703 -0.87870508 0.27809304, + 0.93398356 0.35731584 0, + 0.93360919 0.35829306 -3.793881e-006, + 0.93357778 0.35837492 0, + 0.96590525 -0.25889605 -1.4522103e-006, + 0.96593124 -0.25879905 0, + 0.77718824 -0.62926817 0, + -0.88284731 0.38980913 0.2619721, + -0.88283932 0.38982716 0.2619721, + -0.79516548 0.54466128 0.26656315, + -0.79515404 0.54467803 0.26656303, + -0.79572487 0.54508191 0.26402196, + -0.79863989 0.54082197 0.26398095, + -0.80353791 0.54413795 0.24133097, + -0.83774316 0.48984313 0.24133006, + -0.84337014 0.49313405 0.21341403, + -0.87411487 0.43632293 0.21341397, + -0.87923086 0.43887693 0.18531097, + -0.90631485 0.37980691 0.18531096, + -0.91084236 0.38170418 0.15706107, + -0.93407929 0.32066813 0.15706004, + -0.95718604 0.25930002 0.12867902, + -0.96035343 0.26015812 0.10019504, + -0.97544265 0.19614492 0.10019396, + -0.97785765 0.19663092 0.071628779, + -0.99034935 0.13175504 0.042996414, + -0.99689078 0.066030689 0.042996388, + -0.99774814 0.066087402 0.011450202, + -0.99470252 -0.10279495 0, + -0.99470115 -0.102809 3.5284402e-006, + 0.98808664 -0.15389894 2.1815692e-006, + 0.98808587 -0.15390398 9.4443891e-008, + 0.98785877 -0.15386896 0.021432295, + 0.97324866 -0.22939292 0.012879496, + 0.97242904 -0.22920004 0.043001205, + 0.95514643 -0.29299515 0.043001518, + 0.95357513 -0.29251304 0.071628906, + 0.93216163 -0.35488588 0.071628571, + 0.92985952 -0.35400984 0.10019095, + 0.90443897 -0.414671 0.100191, + 0.9014563 -0.41330311 0.12867405, + 0.8721717 -0.47197384 0.12867495, + 0.86856872 -0.47002482 0.15705095, + 0.8356027 -0.52640581 0.15705095, + 0.83144855 -0.52378976 0.18530391, + 0.7950089 -0.5776009 0.18530498, + 0.79038286 -0.5742389 0.21341197, + 0.75069851 -0.6252256 0.21341187, + 0.70301217 -0.6689781 0.24133405, + 0.6972298 -0.66347581 0.27142295, + 0.74177176 -0.61584175 0.26554391, + 0.74167901 -0.61595303 0.26554498, + 0.74083775 -0.61701274 0.26543289, + 0.78510553 -0.57040966 0.24133386, + 0.79038018 -0.57424212 0.21341306, + 0.82659906 -0.52075803 0.21341303, + 0.83143681 -0.5238049 0.18531395, + 0.86423802 -0.467709 0.185313, + 0.86855519 -0.47004613 0.15706202, + 0.89771914 -0.41162103 0.15706201, + 0.90144318 -0.41332808 0.12868603, + 0.92679262 -0.35283884 0.12868595, + 0.92986077 -0.35400692 0.10018998, + 0.95122731 -0.29176813 0.10019004, + 0.95358264 -0.29249087 0.071618468, + 0.97242701 -0.22920799 0.043004699, + 0.98544753 -0.16444993 0.04300458, + 0.98622227 -0.16457903 0.016718004, + 0.9879474 -0.15388507 0.016712207, + 0.98808527 -0.15390706 0, + 0.96702778 -0.25467095 0, + 0.96677411 -0.25460404 0.022904001, + 0.96677649 -0.25459486 0.022903984, + 0.96703017 -0.25466207 0, + 0.93570822 -0.3527751 0, + 0.93551862 -0.35270286 0.020135993, + 0.95597303 -0.29324201 0.0111697, + 0.95514846 -0.2929891 0.042998817, + 0.93369925 -0.35546708 0.042998306, + 0.93216324 -0.35488209 0.071626626, + 0.90667701 -0.41569996 0.071626402, + 0.90443748 -0.41467375 0.10019194, + 0.87504101 -0.473566 0.100192, + 0.87215376 -0.47200289 0.12868997, + 0.83905774 -0.5286029 0.12868997, + 0.83559233 -0.52642024 0.15705806, + 0.79897434 -0.58049321 0.15705907, + 0.795003 -0.57760799 0.18530898, + 0.75508666 -0.62889171 0.1853089, + 0.75069207 -0.62523204 0.21341603, + 0.7077359 -0.67347091 0.21341696, + 0.70301378 -0.66897678 0.2413329, + 0.6515401 -0.7077772 0.27303305, + 0.65725505 -0.71398509 0.24133202, + 0.60397279 -0.75004768 0.26952791, + 0.60864615 -0.75585127 0.24132708, + 0.65726376 -0.71397871 0.24132691, + 0.66167974 -0.71877468 0.2134079, + 0.70775062 -0.67345864 0.21340689, + 0.71189296 -0.67739993 0.18530498, + 0.75509399 -0.62888402 0.185305, + 0.75886565 -0.63202572 0.15705493, + 0.79897976 -0.58048689 0.15705496, + 0.80229372 -0.5828948 0.12867996, + 0.83907038 -0.52858526 0.12868007, + 0.84184694 -0.53033501 0.100192, + 0.87504172 -0.47356483 0.10019097, + 0.87720817 -0.47473711 0.071628116, + 0.90667498 -0.41570401 0.071628399, + 0.90816891 -0.41638994 0.042997897, + 0.93370044 -0.35546416 0.042997219, + 0.93440098 -0.35573101 0.018715, + 0.93554103 -0.35272202 0.018713402, + 0.90894872 -0.41674086 0.011796696, + 0.90817165 -0.41638383 0.042995386, + 0.87865198 -0.47552299 0.042995401, + 0.87720656 -0.47473976 0.071629561, + 0.84393221 -0.53164613 0.071629718, + 0.84184831 -0.53033316 0.10019103, + 0.80228204 -0.58290905 0.12868801, + 0.76201069 -0.63464874 0.12868795, + 0.75886381 -0.63202786 0.15705597, + 0.71542871 -0.68080479 0.15705596, + 0.71187115 -0.67741913 0.18531802, + 0.66554809 -0.72298205 0.18531801, + 0.66167676 -0.71877676 0.21340993, + 0.61272418 -0.76093715 0.21341005, + 0.60863405 -0.75585908 0.24133302, + 0.554138 -0.78981996 0.262898, + 0.54521096 -0.7959829 0.26297596, + 0.54442024 -0.79474634 0.26830012, + 0.5442149 -0.79488796 0.26829696, + 0.61645669 -0.74236965 0.26242787, + 0.61644197 -0.74238193 0.26242796, + 0.68249995 -0.68250197 0.26150501, + 0.96589363 -0.25893891 0, + -0.74262381 0.6166479 0.26125693, + -0.71979874 0.64095575 0.26658091, + -0.72474974 0.64536375 0.24133691, + -0.76581323 0.5960592 0.24133709, + -0.77095807 0.60006404 0.21341701, + -0.80893314 0.54779607 0.21341701, + -0.84830815 0.49602103 0.18530102, + -0.85254461 0.49849877 0.15705593, + -0.88363367 0.44104981 0.15705596, + -0.88729954 0.44287974 0.12867393, + -0.91462404 0.38328302 0.12867402, + -0.91765028 0.38455111 0.10019203, + -0.94106066 0.32305789 0.10019097, + -0.94339079 0.3238579 0.071622878, + -0.96273041 0.26080713 0.071622439, + -0.98022753 0.19708692 0.01762679, + -0.97868246 0.2046221 0.017622808, + -0.97883433 0.20465405 0, + -0.99469978 0.10282197 0, + -0.9944365 0.10279495 0.023007588, + -0.99443936 0.10276703 0.023007607, + -0.99470252 0.10279495 0, + 0.96702886 0.25466698 -1.1942898e-006, + 0.98808664 0.15389894 2.1815692e-006, + 0.98808587 0.15390398 9.4443891e-008, + 0.98785877 0.15386896 0.021432295, + 0.98786187 0.15384899 0.021432297, + 0.98808891 0.15388398 0, + 0.99867392 0.051481102 0, + 0.99842447 0.051468223 0.022351412, + 0.99842477 0.051462889 0.022351395, + 0.99867427 0.051475815 0, + 0.99867427 -0.051475815 0, + 0.99842477 -0.051462889 0.022351395, + 0.99842447 -0.051468223 0.022351412, + 0.99867392 -0.051481102 0, + 0.98808891 -0.15388398 0, + 0.98786187 -0.15384899 0.021432297, + 0.99502563 -0.099032961 0.010788595, + 0.99416327 -0.098947227 0.042996913, + 0.98545063 -0.16443294 0.042996984, + 0.98383003 -0.16416201 0.071619108, + 0.96842903 -0.228267 0.100197, + 0.95122164 -0.29178387 0.10019697, + 0.94808441 -0.29082111 0.12868206, + 0.9267962 -0.3528311 0.12868203, + 0.92296791 -0.351374 0.157056, + 0.8977263 -0.41160813 0.15705505, + 0.8932631 -0.40956104 0.18531302, + 0.86423868 -0.46770784 0.18531293, + 0.8592099 -0.46498594 0.21341597, + 0.82659578 -0.52076191 0.21341595, + 0.82108098 -0.51728702 0.24133, + 0.78511178 -0.5704028 0.24132991, + 0.77855563 -0.56563973 0.27185085, + 0.79632717 -0.54548514 0.26136005, + 0.79633081 -0.54547989 0.26135993, + 0.741871 -0.616018 0.26485696, + 0.74185699 -0.61603498 0.26485696, + 0.77718824 0.62926817 0, + 0.77511907 0.63181514 0, + 0.044572182 0.96423066 0.26128992, + 0.079444401 0.95879698 0.27275801, + 0.08013463 0.96712637 0.24134007, + 0.016062295 0.97030765 0.24133991, + 0.016170204 0.97682822 0.21341306, + -0.048443511 0.97576022 0.21341306, + -0.048727013 0.98147029 0.18531506, + -0.11348502 0.9761042 0.18531504, + -0.11405201 0.98098111 0.15706101, + -0.17862706 0.9713003 0.15706106, + -0.17936805 0.97533023 0.12867802, + -0.24345604 0.9613381 0.12867902, + -0.24426204 0.96451926 0.10019302, + -0.30746284 0.94627053 0.10019295, + -0.30822405 0.94861424 0.071617916, + -0.37023884 0.92617166 0.071617976, + -0.37084907 0.92769712 0.043000706, + -0.43169191 0.90185475 0.017325094, + -0.42394915 0.90552032 0.017320506, + -0.42401305 0.9056561 0, + -0.42390484 0.9057067 5.8104279e-006, + -0.4238109 0.90550476 0.021104194, + -0.42380804 0.90550613 0.021104202, + -0.37115604 0.92850703 0.010861902, + -0.37083396 0.9277029 0.043007597, + -0.30872187 0.95017952 0.043007582, + -0.30821404 0.9486171 0.071622409, + -0.244249 0.964522 0.10019899, + -0.17997396 0.97855479 0.10019897, + -0.17937995 0.97532874 0.12867297, + -0.11453804 0.98505038 0.12867305, + -0.11406396 0.98098063 0.15705495, + -0.048983011 0.98637426 0.15705605, + -0.048739497 0.98147088 0.18530896, + 0.016250297 0.98254597 0.18530898, + 0.016155798 0.97683001 0.213406, + 0.080679469 0.97362661 0.21340592, + 0.080140717 0.96712512 0.24134302, + 0.143897 0.95971203 0.24134299, + 0.14305808 0.95411444 0.26305911, + 0.13329801 0.95550704 0.26313102, + 0.22092608 0.93935633 0.2623001, + 0.22092207 0.93935728 0.2623001, + 0.93357778 -0.35837492 0, + 0.96589363 0.25893891 0, + 0.841515 -0.46872401 0.268608, + 0.84171021 -0.46837115 0.26861209, + 0.93861914 -0.22075002 0.26507303, + 0.93851137 -0.22121207 0.2650691, + 0.94455636 -0.22263707 0.24134208, + 0.95720214 -0.15974401 0.24134202, + 0.96363413 -0.16081701 0.21341804, + 0.97215587 -0.096776389 0.21341799, + 0.9778477 -0.097342968 0.18530592, + 0.98214406 -0.032477804 0.18530601, + 0.98705018 -0.032640006 0.15705605, + 0.98705 0.032646701 0.157056, + 0.99114394 0.0327821 0.128682, + 0.98680913 0.098228104 0.12868202, + 0.99007511 0.098553218 0.10019301, + 0.98139644 0.16377507 0.10019305, + 0.98382688 0.16418098 0.07161919, + 0.97242719 0.22920804 0.043001208, + 0.97324866 0.22939292 0.012879496, + 0.97242892 0.22920001 0.043004699, + 0.98545033 0.16443306 0.043004613, + 0.98382938 0.16416205 0.071627319, + 0.99252659 0.098794952 0.071627364, + 0.99007523 0.098550923 0.10019402, + 0.99114388 0.032774895 0.12868497, + 0.99114352 -0.032782082 0.12868492, + 0.98704946 -0.032646716 0.15705907, + 0.97784847 -0.097338744 0.18530408, + 0.96927959 -0.16173893 0.18530391, + 0.96363962 -0.16079696 0.2134079, + 0.9509089 -0.22411896 0.21340796, + 0.94456148 -0.22262309 0.24133511, + 0.92777383 -0.28459293 0.24133497, + 0.92010462 -0.28223991 0.27156588, + 0.91519052 -0.30671787 0.26143885, + 0.9151774 -0.30675715 0.26143909, + 0.9385702 -0.22068405 0.26530105, + 0.93855506 -0.22074804 0.26530102, + 0.89906949 -0.34227583 0.27298585, + 0.90694273 -0.34527287 0.2413329, + 0.92777467 -0.2845909 0.24133392, + 0.95090503 -0.22413 0.213414, + 0.95647138 -0.22544186 0.18530588, + 0.96927875 -0.16174196 0.18530595, + 0.9868089 -0.098229788 0.12868199, + 0.99114418 -0.032774907 0.12868203, + 0.99688643 0.032964814 0.071629226, + 0.99252689 0.09879069 0.071629182, + 0.99416274 0.098953575 0.042996887, + 0.98544788 0.16444999 0.042996891, + 0.98622227 0.16457903 0.016718004, + 0.9879474 0.15388507 0.016712207, + 0.98808527 0.15390706 0, + 0.96702778 0.25467095 0, + 0.96677411 0.25460404 0.022904001, + 0.96677649 0.25459486 0.022903984, + 0.96703017 0.25466207 0, + 0.93570822 0.3527751 0, + 0.93571645 0.35275316 -2.4657611e-006, + 0.7456882 0.6210531 0.24133405, + 0.80493814 0.58483905 0.10019001, + 0.55736482 0.79441977 0.2413329, + 0.20699207 0.94811028 0.24133208, + -0.96842551 -0.12886594 0.21341389, + -0.97044063 0 0.24133991, + 0.20699207 -0.94811028 0.24133208, + -0.98268026 0 0.18530902, + -0.97696209 0 0.21341303, + -0.96842551 0.12886594 0.21341389, + -0.98759001 0 0.15705401, + -0.99496788 0 0.10019398, + -0.99168628 0 0.12867905, + -0.99907535 0 0.042994812, + -0.99981064 0 0.019462794, + 0.7456882 -0.6210531 0.24133405, + 0.80493814 -0.58483905 0.10019001, + 0.55736482 -0.79441977 0.2413329, + 0.99442434 -0.032883409 0.10019403, + 0.99442434 0.032883409 0.10019403, + 0.89100116 -0.4540011 0, + 0.98768151 -0.15647693 0, + 0 0 -1, + 0.98767841 0.15649691 0, + 0.99862522 -0.052419212 0, + -0.35838911 0.93357235 0, + -0.62934721 0.77712429 0, + 0.25879785 0.96593153 0, + 0.5446279 0.83867782 0, + -0.052311692 0.99863088 0, + -0.30901113 0.95105839 0, + -0.58781981 0.80899185 0, + -0.95104676 0.30904695 0, + -1 0 0, + 0 1 0, + 1 0 0, + 0.95104778 0.30904391 0, + 0.80899018 0.58782214 0, + 0.58788007 0.80894804 0, + 0 -1 0, + -0.30912602 -0.95102108 0, + -0.58773702 -0.80905199 0, + 0.30912602 -0.95102108 0, + 0.30901113 0.95105839 0, + -0.80905199 -0.58773702 0, + 0.25879785 -0.96593153 0, + 0.5446279 -0.83867782 0, + -0.96590525 -0.25889605 0, + -0.99862552 0.052413676 0, + -0.93359536 0.35832912 0, + -0.77716494 0.62929696 0, + -0.89100116 -0.4540011 0, + -0.98768198 -0.15647498 0, + 0.70710123 0.70711225 0, + 0.45399392 0.8910048 0, + 0.15642595 0.98768961 0, + -0.15642595 0.98768961 0, + -0.45399392 0.8910048 0, + -0.70710123 0.70711225 0, + -0.89101636 0.45397121 0, + 0.15642595 -0.98768961 0, + 0.45399392 -0.8910048 0, + -0.15642595 -0.98768961 0, + -0.70710123 -0.70711225 0, + -0.45399392 -0.8910048 0, + -0.98769319 -0.15640403 0, + -0.89101636 -0.45397121 0, + -0.98769319 0.15640403 0, + 0.98769319 -0.15640403 0, + 0.98769319 0.15640403 0, + 0.89101636 -0.45397121 0, + 0.70710123 -0.70711225 0, + -0.58773702 0.80905199 0, + -0.30900902 0.95105904 0, + -0.80905199 0.58773702 0, + -0.95102108 0.30912602 0, + 0.58782214 -0.80899018 0, + 0.80894804 -0.58788007 0, + -0.80900836 -0.58779722 0, + -0.95102108 -0.30912602 0, + -0.58782214 -0.80899018 0, + -0.30900693 -0.95105988 0, + 0.30904391 -0.95104778 0, + 0.95105839 -0.30901113 0, + 0.95105839 0.30901113 0, + 0.30904695 0.95104676 0, + 0.80899185 0.58781981 0, + 0.58773702 0.80905199 0, + -0.70710677 -0.70710677 0, + -0.98767877 0.15649496 0, + -0.89100116 0.4540011 0, + -0.70710677 0.70710677 0, + -0.052315783 -0.99863064 0, + -0.35838497 -0.9335739 0, + -0.62928313 -0.7771762 0, + -0.83867782 -0.5446279 0, + -0.4540011 0.89100116 0, + -0.15649691 0.98767841 0, + 0.15647693 0.98768151 0, + 0.4540011 0.89100116 0, + -0.15636799 -0.98769885 0, + -0.4540011 -0.89100116 0, + 0.15634899 -0.98770189 0, + 0.4540011 -0.89100116 0, + 0.70710677 -0.70710677 0, + 0.98769832 0.15637104 0, + 0.98770154 -0.15635093 0, + 0.89100116 0.4540011 0, + 0.70710677 0.70710677 0, + 0 0 1, + 0.58779722 -0.80900836 0, + 0.80899018 -0.58782214 0, + 0.95105988 -0.30900693 0, + -0.25879785 -0.96593153 0, + 0.052315783 -0.99863064 0, + 0.96590525 -0.25889605 0, + 0.99862552 0.052413676 0, + 0.35838497 -0.9335739 0, + 0.62928313 -0.7771762 0, + -0.5446279 -0.83867782 0, + -0.15637104 0.98769832 0, + 0.15635093 0.98770154 0, + -0.98768151 0.15647693 0, + -0.98767841 -0.15649691 0, + -0.99862522 0.052419212 0, + -0.93360919 0.35829306 0, + 0.30901113 -0.95105839 0, + 0.30912602 0.95102108 0, + 0.58782214 0.80899018 0, + 0.30900693 0.95105988 0, + 0.98768198 0.15647498 0, + 0.15649691 -0.98767841 0, + 0.98767877 -0.15649496 0, + 0.35838497 0.9335739 0, + 0.62928313 0.7771762 0, + 0.052315783 0.99863064 0, + 0.95102108 -0.30912602 0, + 0.80905199 -0.58773702 0, + 0.58773702 -0.80905199 0, + 0.30900902 -0.95105904 0, + -0.30904695 -0.95104676 0, + -0.80899185 -0.58781981 0, + -0.95105839 -0.30901113 0, + 0.93359536 -0.35832912 0, + 0.99862552 -0.052413676 0, + 0.96590525 0.25889605 0, + -0.58782214 0.80899018 0, + -0.30904391 0.95104778 0, + 0.80900836 0.58779722 0, + 0.95102108 0.30912602 0, + -0.80894804 0.58788007 0, + -0.95105839 0.30901113 0, + -0.96821016 -0.19468103 0.15706202, + -0.96821016 0.19468103 0.15706202, + -0.9974311 0 0.071632907, + -0.80899018 0.58782214 0, + -0.58779722 0.80900836 0, + -0.95105988 0.30900693 0, + -0.95104778 -0.30904391 0, + -0.80899018 -0.58782214 0, + -0.58788007 -0.80894804 0, + -0.30901113 -0.95105839 0, + 0.80905199 0.58773702 0, + -0.30912602 0.95102108 0, + -0.98770154 0.15635093 0, + -0.98769832 -0.15637104 0, + -0.15634899 0.98770189 0, + 0.15636799 0.98769885 0, + -0.15647693 -0.98768151 0, + -0.5446279 0.83867782 0, + -0.77712375 0.6293478 0, + -0.25879785 0.96593153 0, + 0.99862522 0.052419212 0, + 0.77712375 0.6293478 0, + -0.62934721 -0.77712429 0, + -0.35838911 -0.93357235 0, + -0.052311692 -0.99863088 0, + 0.89101636 0.45397121 0, + 0.98770189 0.15634899 0, + 0.98769885 -0.15636799 0, + 0.15647498 -0.98768198 0, + -0.15649496 -0.98767877 0, + -0.93359536 -0.35832912 0, + -0.77716494 -0.62929696 0, + -0.052315783 0.99863064 0, + -0.99862552 -0.052413676 0, + -0.96590525 0.25889605 0, + -0.83867782 0.5446279 0, + -0.62928313 0.7771762 0, + -0.35838497 0.9335739 0, + 0.95104676 -0.30904695 0, + 0.58781981 -0.80899185 0, + 0.95105904 0.30900902 0, + 0.052311692 -0.99863088 0, + 0.35838911 -0.93357235 0, + 0.62934721 -0.77712429 0, + -0.99862522 -0.052419212 0, + -0.93360919 -0.35829306 0, + -0.77712375 -0.6293478 0, + 0.93359536 0.35832912 0, + -0.95105904 -0.30900902 0, + 0.77712375 -0.6293478 0, + 0.62934721 0.77712429 0, + 0.35838911 0.93357235 0, + 0.052311692 0.99863088 0, + 0.15649496 0.98767877 0, + -0.15647498 0.98768198 0, + 0.15637104 -0.98769832 0, + -0.15635093 -0.98770154 0, + -0.98769885 0.15636799 0, + -0.98770189 -0.15634899 0, + 0.88806486 -0.40718397 0.21340598, + 0.93400788 -0.28650293 0.21341397, + 0.97412008 -0.16255002 0.15705901, + -0.70058709 0.71227014 0.043000408, + -0.244854 0.96691102 0.071622297, + 0.14484103 0.9661662 0.21341005, + 0.88806522 0.40718308 0.21340606, + 0.68250102 0.68250102 0.26150501, + 0.27948806 0.96014917 -3.1930806e-006, + 0.9741202 0.16255003 0.15705803, + 0.9827323 0.097824037 0.15705906, + 0.98214388 0.032477796 0.18530698, + 0.970828 0.22883099 0.071619302, + 0.88270009 0.38975504 0.26254803, + -0.96431655 0.26123685 0.042999078, + -0.81366968 0.55100381 0.18530095, + -0.41900182 0.87532556 0.24133489, + -0.11518995 0.99075752 0.071629368, + -0.11537796 0.99239063 0.042997885, + -0.32854599 0.94448799 -3.9983101e-007, + -0.431357 0.90115601 0.043000799, + -0.68135566 0.68135673 0.26740885, + -0.97947311 0.19693501 0.042999603, + -0.93795437 0.32199913 0.12867905, + -0.96431655 -0.26123685 0.042999078, + -0.69943488 -0.7110979 0.07162869, + -0.70058709 -0.71227014 0.043000408, + -0.11537796 -0.99239063 0.042997386, + -0.41900182 -0.87532556 0.24133489, + 0.27948806 -0.96014917 -3.4041007e-006, + -0.32854599 -0.94448799 -3.9983101e-007, + -0.22968997 -0.97326386 -2.1163698e-006, + -0.431357 -0.90115601 0.043000899, + -0.244854 -0.96691102 0.071621701, + -0.68135566 -0.68135673 0.26740885, + -0.95779401 -0.19257499 0.213414, + -0.93795437 -0.32199913 0.12867905, + 0.14484103 -0.9661662 0.21341005, + -0.95779419 0.19257404 0.21341404, + -0.99279195 -0.065766901 0.100194, + -0.97947311 -0.19693501 0.042999502, + -0.97896135 0.13025604 0.15706106, + -0.99279195 0.065766901 0.100194, + -0.98871994 0.131538 0.071628504, + 0.68250102 -0.68250102 0.26150501, + 0.97082788 -0.22883198 0.071619295, + 0.9827323 -0.097824037 0.15705906, + 0.88269979 -0.3897559 0.26254791 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 5, -1, + 6, 7, 8, -1, 5, 9, 3, -1, + 6, 10, 7, -1, 11, 12, 13, -1, + 14, 12, 11, -1, 11, 15, 14, -1, + 16, 15, 11, -1, 16, 11, 17, -1, + 17, 11, 18, -1, 13, 18, 11, -1, + 18, 13, 19, -1, 19, 20, 21, -1, + 22, 21, 20, -1, 21, 22, 23, -1, + 24, 23, 22, -1, 23, 24, 25, -1, + 26, 25, 24, -1, 25, 26, 27, -1, + 28, 27, 26, -1, 27, 28, 29, -1, + 30, 29, 28, -1, 29, 30, 31, -1, + 32, 31, 30, -1, 31, 32, 33, -1, + 33, 32, 34, -1, 34, 32, 35, -1, + 30, 35, 32, -1, 35, 30, 36, -1, + 28, 36, 30, -1, 36, 28, 37, -1, + 26, 37, 28, -1, 37, 26, 38, -1, + 24, 38, 26, -1, 38, 24, 39, -1, + 22, 39, 24, -1, 39, 22, 40, -1, + 20, 40, 22, -1, 40, 20, 41, -1, + 41, 13, 12, -1, 42, 12, 43, -1, + 12, 42, 41, -1, 44, 41, 42, -1, + 41, 44, 40, -1, 40, 45, 39, -1, + 46, 39, 45, -1, 39, 46, 38, -1, + 38, 47, 37, -1, 48, 37, 47, -1, + 37, 48, 36, -1, 36, 49, 35, -1, + 50, 35, 49, -1, 35, 50, 34, -1, + 51, 34, 50, -1, 34, 51, 52, -1, + 53, 54, 55, -1, 56, 57, 58, -1, + 59, 58, 57, -1, 58, 59, 60, -1, + 61, 60, 59, -1, 60, 61, 62, -1, + 63, 62, 61, -1, 62, 63, 64, -1, + 65, 64, 63, -1, 64, 65, 66, -1, + 67, 66, 65, -1, 66, 67, 68, -1, + 69, 68, 67, -1, 68, 69, 70, -1, + 71, 70, 69, -1, 70, 71, 72, -1, + 73, 72, 74, -1, 74, 72, 71, -1, + 74, 75, 76, -1, 71, 77, 74, -1, + 77, 71, 78, -1, 69, 78, 71, -1, + 78, 69, 79, -1, 67, 79, 69, -1, + 79, 67, 80, -1, 65, 80, 67, -1, + 80, 65, 81, -1, 63, 81, 65, -1, + 81, 63, 82, -1, 61, 82, 63, -1, + 82, 61, 83, -1, 59, 83, 61, -1, + 83, 59, 84, -1, 57, 84, 59, -1, + 85, 84, 57, -1, 57, 86, 85, -1, + 85, 87, 84, -1, 84, 87, 88, -1, + 89, 86, 57, -1, 89, 57, 56, -1, + 90, 91, 56, -1, 56, 91, 89, -1, + 92, 93, 94, -1, 93, 95, 94, -1, + 96, 97, 98, -1, 98, 97, 99, -1, + 100, 99, 97, -1, 101, 102, 100, -1, + 102, 101, 103, -1, 104, 103, 101, -1, + 103, 104, 105, -1, 106, 105, 104, -1, + 105, 106, 107, -1, 108, 107, 106, -1, + 107, 108, 109, -1, 110, 109, 108, -1, + 109, 110, 111, -1, 111, 112, 113, -1, + 113, 114, 115, -1, 116, 114, 113, -1, + 116, 113, 117, -1, 118, 119, 120, -1, + 121, 122, 123, -1, 122, 121, 124, -1, + 125, 124, 121, -1, 124, 125, 126, -1, + 127, 126, 125, -1, 126, 127, 128, -1, + 129, 128, 127, -1, 128, 129, 130, -1, + 131, 130, 129, -1, 130, 131, 132, -1, + 133, 132, 131, -1, 132, 133, 134, -1, + 135, 134, 133, -1, 134, 135, 136, -1, + 137, 136, 135, -1, 136, 137, 138, -1, + 139, 138, 137, -1, 140, 138, 139, -1, + 139, 141, 140, -1, 120, 141, 139, -1, + 120, 139, 118, -1, 118, 139, 142, -1, + 137, 142, 139, -1, 142, 137, 143, -1, + 135, 143, 137, -1, 143, 135, 144, -1, + 133, 144, 135, -1, 144, 133, 145, -1, + 131, 145, 133, -1, 145, 131, 146, -1, + 129, 146, 131, -1, 146, 129, 147, -1, + 127, 147, 129, -1, 147, 127, 148, -1, + 125, 148, 127, -1, 148, 125, 149, -1, + 121, 149, 125, -1, 150, 149, 121, -1, + 151, 152, 153, -1, 154, 155, 156, -1, + 156, 155, 157, -1, 158, 159, 160, -1, + 160, 159, 161, -1, 162, 161, 159, -1, + 161, 162, 163, -1, 164, 163, 162, -1, + 163, 164, 165, -1, 166, 165, 164, -1, + 165, 166, 167, -1, 168, 167, 166, -1, + 167, 168, 169, -1, 170, 169, 168, -1, + 169, 170, 171, -1, 172, 171, 170, -1, + 171, 172, 173, -1, 157, 173, 172, -1, + 173, 157, 155, -1, 174, 155, 175, -1, + 155, 174, 173, -1, 176, 173, 174, -1, + 173, 176, 171, -1, 177, 171, 176, -1, + 171, 177, 169, -1, 178, 169, 177, -1, + 169, 178, 167, -1, 179, 167, 178, -1, + 167, 179, 165, -1, 180, 165, 179, -1, + 165, 180, 163, -1, 181, 163, 180, -1, + 163, 181, 161, -1, 182, 161, 181, -1, + 161, 182, 160, -1, 183, 160, 182, -1, + 160, 183, 184, -1, 185, 186, 187, -1, + 186, 185, 188, -1, 188, 185, 189, -1, + 190, 189, 185, -1, 187, 190, 185, -1, + 191, 192, 187, -1, 193, 192, 194, -1, + 194, 195, 193, -1, 195, 194, 183, -1, + 183, 194, 184, -1, 192, 184, 194, -1, + 191, 184, 192, -1, 184, 191, 160, -1, + 160, 191, 158, -1, 187, 158, 191, -1, + 186, 158, 187, -1, 158, 186, 159, -1, + 188, 159, 186, -1, 159, 188, 162, -1, + 196, 162, 188, -1, 162, 196, 164, -1, + 197, 164, 196, -1, 164, 197, 166, -1, + 198, 166, 197, -1, 166, 198, 168, -1, + 199, 168, 198, -1, 168, 199, 170, -1, + 200, 170, 199, -1, 170, 200, 172, -1, + 201, 172, 200, -1, 172, 201, 157, -1, + 157, 202, 156, -1, 203, 156, 204, -1, + 204, 156, 202, -1, 204, 205, 206, -1, + 205, 204, 207, -1, 202, 207, 204, -1, + 207, 202, 208, -1, 208, 201, 209, -1, + 200, 209, 201, -1, 209, 200, 210, -1, + 199, 210, 200, -1, 210, 199, 211, -1, + 198, 211, 199, -1, 197, 212, 198, -1, + 212, 197, 213, -1, 196, 213, 197, -1, + 213, 196, 214, -1, 188, 214, 196, -1, + 189, 214, 188, -1, 215, 216, 217, -1, + 214, 217, 216, -1, 189, 217, 214, -1, + 217, 189, 190, -1, 217, 190, 215, -1, + 215, 218, 219, -1, 220, 218, 221, -1, + 221, 222, 223, -1, 224, 225, 222, -1, + 225, 224, 226, -1, 226, 224, 227, -1, + 228, 226, 227, -1, 226, 228, 229, -1, + 230, 231, 232, -1, 231, 230, 233, -1, + 230, 234, 233, -1, 235, 233, 234, -1, + 236, 234, 230, -1, 230, 237, 236, -1, + 237, 230, 238, -1, 232, 238, 230, -1, + 238, 232, 239, -1, 240, 239, 232, -1, + 239, 240, 241, -1, 242, 241, 240, -1, + 241, 242, 243, -1, 244, 243, 242, -1, + 243, 244, 245, -1, 246, 245, 244, -1, + 245, 246, 247, -1, 248, 247, 246, -1, + 247, 248, 249, -1, 250, 249, 248, -1, + 249, 250, 251, -1, 252, 251, 250, -1, + 251, 252, 253, -1, 252, 254, 253, -1, + 255, 254, 252, -1, 255, 252, 256, -1, + 250, 257, 252, -1, 257, 250, 258, -1, + 248, 258, 250, -1, 258, 248, 259, -1, + 246, 259, 248, -1, 259, 246, 260, -1, + 244, 260, 246, -1, 260, 244, 261, -1, + 242, 261, 244, -1, 261, 242, 262, -1, + 240, 262, 242, -1, 262, 240, 263, -1, + 232, 263, 240, -1, 263, 232, 231, -1, + 264, 265, 231, -1, 231, 265, 263, -1, + 266, 263, 265, -1, 263, 266, 262, -1, + 267, 262, 266, -1, 262, 267, 261, -1, + 268, 261, 267, -1, 261, 268, 260, -1, + 269, 260, 268, -1, 260, 269, 259, -1, + 270, 259, 269, -1, 259, 270, 258, -1, + 271, 258, 270, -1, 258, 271, 257, -1, + 272, 257, 271, -1, 273, 256, 272, -1, + 274, 256, 273, -1, 275, 276, 273, -1, + 273, 276, 274, -1, 274, 277, 256, -1, + 256, 277, 255, -1, 278, 279, 280, -1, + 281, 282, 283, -1, 283, 282, 284, -1, + 283, 285, 286, -1, 285, 283, 287, -1, + 284, 287, 283, -1, 287, 284, 288, -1, + 289, 288, 284, -1, 288, 289, 290, -1, + 291, 290, 289, -1, 290, 291, 292, -1, + 293, 292, 291, -1, 292, 293, 294, -1, + 295, 294, 293, -1, 294, 295, 296, -1, + 297, 296, 295, -1, 296, 297, 298, -1, + 299, 298, 297, -1, 298, 299, 300, -1, + 278, 300, 299, -1, 280, 300, 278, -1, + 300, 280, 301, -1, 302, 279, 278, -1, + 278, 303, 302, -1, 303, 278, 304, -1, + 299, 304, 278, -1, 304, 299, 305, -1, + 297, 305, 299, -1, 305, 297, 306, -1, + 295, 306, 297, -1, 306, 295, 307, -1, + 293, 307, 295, -1, 307, 293, 308, -1, + 291, 308, 293, -1, 308, 291, 309, -1, + 289, 309, 291, -1, 309, 289, 310, -1, + 284, 310, 289, -1, 310, 284, 282, -1, + 311, 312, 313, -1, 314, 315, 316, -1, + 316, 315, 317, -1, 318, 317, 315, -1, + 317, 318, 319, -1, 320, 319, 318, -1, + 319, 320, 321, -1, 322, 321, 320, -1, + 321, 322, 323, -1, 324, 323, 322, -1, + 325, 326, 327, -1, 327, 328, 329, -1, + 313, 329, 328, -1, 329, 313, 312, -1, + 330, 312, 331, -1, 312, 330, 329, -1, + 332, 329, 330, -1, 329, 332, 327, -1, + 333, 327, 332, -1, 327, 333, 325, -1, + 334, 325, 333, -1, 335, 323, 334, -1, + 323, 335, 321, -1, 336, 321, 335, -1, + 321, 336, 319, -1, 337, 319, 336, -1, + 319, 337, 317, -1, 338, 317, 337, -1, + 317, 338, 316, -1, 339, 316, 338, -1, + 316, 339, 340, -1, 339, 341, 340, -1, + 341, 339, 282, -1, 282, 339, 310, -1, + 338, 310, 339, -1, 310, 338, 309, -1, + 337, 309, 338, -1, 309, 337, 308, -1, + 336, 308, 337, -1, 308, 336, 307, -1, + 335, 307, 336, -1, 307, 335, 306, -1, + 334, 306, 335, -1, 306, 334, 305, -1, + 333, 305, 334, -1, 305, 333, 304, -1, + 332, 304, 333, -1, 304, 332, 303, -1, + 330, 303, 332, -1, 342, 303, 330, -1, + 303, 342, 302, -1, 330, 343, 342, -1, + 331, 343, 330, -1, 344, 331, 312, -1, + 344, 312, 311, -1, 311, 345, 344, -1, + 346, 345, 311, -1, 347, 346, 348, -1, + 311, 348, 346, -1, 348, 311, 349, -1, + 313, 349, 311, -1, 349, 313, 350, -1, + 328, 350, 313, -1, 350, 328, 351, -1, + 351, 326, 352, -1, 352, 324, 353, -1, + 322, 353, 324, -1, 353, 322, 354, -1, + 320, 354, 322, -1, 318, 229, 320, -1, + 229, 318, 226, -1, 315, 226, 318, -1, + 226, 315, 225, -1, 314, 225, 315, -1, + 225, 314, 222, -1, 222, 314, 223, -1, + 316, 223, 314, -1, 340, 223, 316, -1, + 223, 340, 221, -1, 221, 340, 341, -1, + 221, 341, 220, -1, 282, 220, 341, -1, + 281, 220, 282, -1, 220, 281, 218, -1, + 218, 281, 219, -1, 283, 219, 281, -1, + 286, 219, 283, -1, 219, 286, 215, -1, + 215, 286, 216, -1, 285, 216, 286, -1, + 216, 285, 214, -1, 214, 285, 213, -1, + 287, 213, 285, -1, 213, 287, 212, -1, + 288, 212, 287, -1, 290, 211, 288, -1, + 211, 290, 210, -1, 292, 210, 290, -1, + 210, 292, 209, -1, 294, 209, 292, -1, + 209, 294, 208, -1, 296, 208, 294, -1, + 208, 296, 207, -1, 298, 207, 296, -1, + 207, 298, 205, -1, 300, 205, 298, -1, + 205, 300, 355, -1, 301, 355, 300, -1, + 355, 356, 205, -1, 205, 356, 206, -1, + 206, 357, 204, -1, 204, 357, 203, -1, + 154, 358, 155, -1, 155, 358, 175, -1, + 175, 359, 174, -1, 174, 359, 275, -1, + 273, 174, 275, -1, 174, 273, 176, -1, + 272, 176, 273, -1, 176, 272, 177, -1, + 271, 177, 272, -1, 177, 271, 178, -1, + 270, 178, 271, -1, 178, 270, 179, -1, + 269, 179, 270, -1, 179, 269, 180, -1, + 268, 180, 269, -1, 180, 268, 181, -1, + 267, 181, 268, -1, 181, 267, 182, -1, + 266, 182, 267, -1, 182, 266, 183, -1, + 265, 183, 266, -1, 183, 265, 195, -1, + 264, 195, 265, -1, 195, 264, 193, -1, + 193, 264, 360, -1, 231, 360, 264, -1, + 233, 360, 231, -1, 360, 233, 235, -1, + 360, 235, 193, -1, 361, 362, 363, -1, + 364, 361, 363, -1, 363, 365, 364, -1, + 365, 363, 366, -1, 366, 363, 362, -1, + 367, 366, 362, -1, 368, 369, 370, -1, + 370, 369, 371, -1, 372, 371, 369, -1, + 371, 372, 373, -1, 374, 373, 372, -1, + 373, 374, 375, -1, 375, 376, 377, -1, + 378, 377, 376, -1, 377, 378, 379, -1, + 380, 379, 378, -1, 379, 380, 381, -1, + 382, 381, 380, -1, 381, 382, 383, -1, + 384, 383, 382, -1, 383, 384, 367, -1, + 385, 386, 367, -1, 367, 386, 383, -1, + 387, 383, 386, -1, 383, 387, 381, -1, + 388, 381, 387, -1, 381, 388, 379, -1, + 389, 379, 388, -1, 379, 389, 377, -1, + 390, 377, 389, -1, 377, 390, 375, -1, + 391, 375, 390, -1, 375, 391, 373, -1, + 392, 373, 391, -1, 373, 392, 371, -1, + 393, 371, 392, -1, 371, 393, 370, -1, + 394, 370, 395, -1, 395, 370, 393, -1, + 396, 397, 398, -1, 399, 400, 401, -1, + 400, 399, 402, -1, 403, 400, 404, -1, + 404, 400, 405, -1, 402, 405, 400, -1, + 405, 402, 406, -1, 407, 406, 402, -1, + 406, 407, 408, -1, 409, 408, 407, -1, + 408, 409, 410, -1, 411, 410, 409, -1, + 410, 411, 412, -1, 413, 412, 411, -1, + 412, 413, 414, -1, 415, 414, 413, -1, + 414, 415, 416, -1, 417, 416, 415, -1, + 416, 417, 418, -1, 396, 418, 417, -1, + 398, 418, 396, -1, 418, 398, 419, -1, + 420, 418, 419, -1, 418, 420, 416, -1, + 421, 416, 420, -1, 416, 421, 414, -1, + 422, 414, 421, -1, 414, 422, 412, -1, + 423, 412, 422, -1, 412, 423, 410, -1, + 424, 410, 423, -1, 410, 424, 408, -1, + 425, 408, 424, -1, 408, 425, 406, -1, + 426, 406, 425, -1, 406, 426, 405, -1, + 427, 405, 426, -1, 405, 427, 404, -1, + 428, 404, 429, -1, 430, 429, 431, -1, + 431, 429, 432, -1, 432, 427, 433, -1, + 426, 433, 427, -1, 433, 426, 434, -1, + 425, 434, 426, -1, 434, 425, 435, -1, + 424, 435, 425, -1, 435, 424, 436, -1, + 423, 436, 424, -1, 436, 423, 437, -1, + 422, 437, 423, -1, 437, 422, 438, -1, + 421, 438, 422, -1, 438, 421, 439, -1, + 420, 439, 421, -1, 440, 439, 420, -1, + 441, 442, 443, -1, 444, 445, 446, -1, + 447, 448, 449, -1, 450, 444, 446, -1, + 446, 451, 450, -1, 451, 446, 452, -1, + 452, 446, 445, -1, 453, 454, 455, -1, + 454, 453, 456, -1, 457, 456, 453, -1, + 456, 457, 458, -1, 459, 458, 457, -1, + 458, 459, 460, -1, 461, 460, 459, -1, + 460, 461, 462, -1, 463, 462, 461, -1, + 462, 463, 464, -1, 465, 464, 463, -1, + 464, 465, 466, -1, 467, 466, 465, -1, + 466, 467, 468, -1, 452, 469, 470, -1, + 445, 469, 452, -1, 471, 472, 473, -1, + 469, 473, 472, -1, 445, 473, 469, -1, + 473, 445, 444, -1, 473, 444, 471, -1, + 471, 474, 475, -1, 476, 442, 447, -1, + 447, 477, 476, -1, 439, 476, 477, -1, + 440, 476, 439, -1, 476, 440, 442, -1, + 442, 440, 443, -1, 420, 443, 440, -1, + 419, 443, 420, -1, 443, 419, 441, -1, + 441, 419, 398, -1, 441, 398, 397, -1, + 397, 478, 441, -1, 479, 478, 480, -1, + 480, 481, 479, -1, 481, 480, 482, -1, + 482, 480, 483, -1, 478, 483, 480, -1, + 397, 483, 478, -1, 483, 397, 396, -1, + 483, 396, 482, -1, 482, 396, 484, -1, + 417, 484, 396, -1, 484, 417, 485, -1, + 415, 485, 417, -1, 485, 415, 486, -1, + 413, 486, 415, -1, 486, 413, 487, -1, + 411, 487, 413, -1, 487, 411, 488, -1, + 409, 488, 411, -1, 488, 409, 489, -1, + 407, 489, 409, -1, 489, 407, 490, -1, + 402, 490, 407, -1, 490, 402, 399, -1, + 491, 395, 399, -1, 399, 395, 490, -1, + 393, 490, 395, -1, 490, 393, 489, -1, + 392, 489, 393, -1, 489, 392, 488, -1, + 391, 488, 392, -1, 488, 391, 487, -1, + 390, 487, 391, -1, 487, 390, 486, -1, + 389, 486, 390, -1, 486, 389, 485, -1, + 388, 485, 389, -1, 485, 388, 484, -1, + 387, 484, 388, -1, 484, 387, 482, -1, + 386, 482, 387, -1, 482, 386, 481, -1, + 385, 481, 386, -1, 481, 385, 479, -1, + 479, 385, 492, -1, 367, 492, 385, -1, + 362, 492, 367, -1, 492, 362, 361, -1, + 492, 361, 479, -1, 493, 494, 364, -1, + 495, 474, 151, -1, 151, 496, 495, -1, + 149, 495, 496, -1, 150, 495, 149, -1, + 495, 150, 474, -1, 474, 150, 475, -1, + 121, 475, 150, -1, 123, 475, 121, -1, + 475, 123, 471, -1, 471, 123, 472, -1, + 122, 472, 123, -1, 472, 122, 469, -1, + 124, 468, 122, -1, 468, 124, 466, -1, + 126, 466, 124, -1, 466, 126, 464, -1, + 128, 464, 126, -1, 464, 128, 462, -1, + 130, 462, 128, -1, 462, 130, 460, -1, + 132, 460, 130, -1, 460, 132, 458, -1, + 134, 458, 132, -1, 458, 134, 456, -1, + 136, 456, 134, -1, 456, 136, 454, -1, + 138, 454, 136, -1, 454, 138, 497, -1, + 140, 497, 138, -1, 498, 499, 500, -1, + 499, 498, 501, -1, 502, 501, 498, -1, + 501, 502, 503, -1, 504, 503, 502, -1, + 503, 504, 505, -1, 506, 505, 504, -1, + 505, 506, 507, -1, 508, 507, 506, -1, + 507, 508, 509, -1, 510, 509, 508, -1, + 509, 510, 511, -1, 512, 511, 510, -1, + 511, 512, 513, -1, 514, 513, 512, -1, + 515, 516, 514, -1, 517, 516, 515, -1, + 517, 518, 516, -1, 516, 518, 519, -1, + 118, 519, 119, -1, 519, 118, 516, -1, + 142, 513, 118, -1, 513, 142, 511, -1, + 143, 511, 142, -1, 511, 143, 509, -1, + 144, 509, 143, -1, 509, 144, 507, -1, + 145, 507, 144, -1, 507, 145, 505, -1, + 146, 505, 145, -1, 505, 146, 503, -1, + 147, 503, 146, -1, 503, 147, 501, -1, + 148, 501, 147, -1, 501, 148, 499, -1, + 149, 499, 148, -1, 496, 499, 149, -1, + 499, 496, 500, -1, 151, 500, 496, -1, + 153, 500, 151, -1, 500, 153, 498, -1, + 498, 153, 520, -1, 152, 520, 153, -1, + 236, 520, 152, -1, 520, 236, 237, -1, + 520, 237, 498, -1, 498, 237, 502, -1, + 238, 502, 237, -1, 502, 238, 504, -1, + 239, 504, 238, -1, 504, 239, 506, -1, + 241, 506, 239, -1, 506, 241, 508, -1, + 243, 508, 241, -1, 508, 243, 510, -1, + 245, 510, 243, -1, 510, 245, 512, -1, + 247, 512, 245, -1, 512, 247, 514, -1, + 249, 514, 247, -1, 514, 249, 515, -1, + 251, 515, 249, -1, 521, 515, 251, -1, + 521, 522, 515, -1, 515, 522, 517, -1, + 251, 523, 521, -1, 497, 524, 454, -1, + 454, 524, 455, -1, 455, 525, 453, -1, + 453, 525, 526, -1, 453, 526, 527, -1, + 527, 117, 453, -1, 453, 117, 457, -1, + 457, 112, 459, -1, 459, 110, 461, -1, + 108, 461, 110, -1, 461, 108, 463, -1, + 106, 463, 108, -1, 463, 106, 465, -1, + 104, 465, 106, -1, 465, 104, 467, -1, + 101, 467, 104, -1, 100, 470, 101, -1, + 470, 100, 452, -1, 97, 452, 100, -1, + 452, 97, 451, -1, 96, 451, 97, -1, + 451, 96, 450, -1, 98, 528, 96, -1, + 95, 528, 98, -1, 528, 95, 93, -1, + 529, 530, 531, -1, 532, 533, 534, -1, + 534, 535, 532, -1, 532, 535, 536, -1, + 537, 536, 535, -1, 536, 537, 538, -1, + 539, 538, 537, -1, 538, 539, 540, -1, + 541, 540, 539, -1, 540, 541, 542, -1, + 543, 542, 541, -1, 542, 543, 544, -1, + 545, 544, 543, -1, 544, 545, 546, -1, + 547, 546, 545, -1, 546, 547, 548, -1, + 549, 548, 547, -1, 550, 551, 549, -1, + 552, 551, 550, -1, 92, 552, 553, -1, + 550, 553, 552, -1, 530, 553, 550, -1, + 553, 530, 529, -1, 553, 529, 92, -1, + 448, 529, 531, -1, 531, 554, 448, -1, + 554, 531, 555, -1, 555, 531, 530, -1, + 550, 555, 530, -1, 555, 550, 556, -1, + 549, 556, 550, -1, 556, 549, 557, -1, + 547, 557, 549, -1, 557, 547, 558, -1, + 545, 558, 547, -1, 558, 545, 559, -1, + 543, 559, 545, -1, 559, 543, 560, -1, + 541, 560, 543, -1, 560, 541, 561, -1, + 539, 561, 541, -1, 561, 539, 562, -1, + 537, 562, 539, -1, 562, 537, 563, -1, + 535, 563, 537, -1, 563, 535, 564, -1, + 534, 564, 535, -1, 564, 565, 563, -1, + 563, 565, 90, -1, 56, 563, 90, -1, + 563, 56, 562, -1, 58, 562, 56, -1, + 562, 58, 561, -1, 60, 561, 58, -1, + 561, 60, 560, -1, 62, 560, 60, -1, + 560, 62, 559, -1, 64, 559, 62, -1, + 559, 64, 558, -1, 66, 558, 64, -1, + 558, 66, 557, -1, 68, 557, 66, -1, + 557, 68, 556, -1, 70, 556, 68, -1, + 556, 70, 555, -1, 72, 555, 70, -1, + 555, 72, 554, -1, 73, 554, 72, -1, + 554, 73, 448, -1, 448, 73, 449, -1, + 74, 449, 73, -1, 76, 449, 74, -1, + 449, 76, 447, -1, 447, 76, 477, -1, + 75, 477, 76, -1, 477, 75, 439, -1, + 439, 75, 438, -1, 438, 77, 437, -1, + 78, 437, 77, -1, 437, 78, 436, -1, + 79, 436, 78, -1, 436, 79, 435, -1, + 80, 435, 79, -1, 435, 80, 434, -1, + 81, 434, 80, -1, 434, 81, 433, -1, + 82, 433, 81, -1, 433, 82, 432, -1, + 83, 432, 82, -1, 432, 83, 431, -1, + 84, 431, 83, -1, 88, 431, 84, -1, + 431, 88, 566, -1, 431, 566, 430, -1, + 430, 567, 429, -1, 429, 567, 428, -1, + 428, 568, 404, -1, 404, 568, 403, -1, + 569, 570, 571, -1, 570, 572, 571, -1, + 571, 573, 569, -1, 403, 574, 400, -1, + 400, 574, 401, -1, 401, 575, 399, -1, + 399, 575, 491, -1, 491, 576, 395, -1, + 395, 576, 394, -1, 368, 577, 369, -1, + 369, 577, 578, -1, 369, 578, 579, -1, + 55, 580, 581, -1, 582, 583, 584, -1, + 585, 586, 587, -1, 587, 586, 588, -1, + 588, 589, 590, -1, 591, 590, 589, -1, + 590, 591, 592, -1, 593, 592, 591, -1, + 594, 595, 593, -1, 595, 594, 596, -1, + 597, 596, 594, -1, 596, 597, 598, -1, + 599, 598, 597, -1, 598, 599, 600, -1, + 601, 600, 599, -1, 600, 601, 602, -1, + 603, 602, 601, -1, 604, 602, 603, -1, + 603, 605, 604, -1, 606, 607, 608, -1, + 607, 606, 609, -1, 610, 609, 606, -1, + 609, 610, 611, -1, 612, 611, 610, -1, + 611, 612, 613, -1, 614, 613, 612, -1, + 613, 614, 615, -1, 616, 615, 614, -1, + 615, 616, 617, -1, 618, 617, 616, -1, + 617, 618, 619, -1, 620, 619, 618, -1, + 619, 620, 621, -1, 622, 621, 620, -1, + 621, 622, 623, -1, 624, 623, 622, -1, + 625, 623, 624, -1, 626, 627, 624, -1, + 624, 627, 625, -1, 625, 628, 623, -1, + 623, 628, 629, -1, 630, 631, 632, -1, + 632, 633, 630, -1, 633, 632, 634, -1, + 634, 635, 636, -1, 637, 636, 635, -1, + 636, 637, 638, -1, 639, 638, 637, -1, + 638, 639, 640, -1, 641, 640, 639, -1, + 640, 641, 642, -1, 643, 642, 641, -1, + 642, 643, 644, -1, 644, 645, 646, -1, + 647, 646, 645, -1, 646, 647, 648, -1, + 649, 648, 647, -1, 650, 648, 649, -1, + 651, 652, 653, -1, 653, 652, 654, -1, + 655, 656, 657, -1, 656, 655, 658, -1, + 659, 660, 661, -1, 662, 661, 660, -1, + 663, 664, 662, -1, 664, 663, 665, -1, + 666, 667, 668, -1, 667, 666, 669, -1, + 670, 669, 666, -1, 669, 670, 671, -1, + 672, 671, 670, -1, 671, 672, 673, -1, + 658, 673, 672, -1, 674, 675, 655, -1, + 676, 677, 678, -1, 679, 680, 681, -1, + 680, 679, 682, -1, 683, 684, 685, -1, + 686, 684, 683, -1, 686, 683, 687, -1, + 687, 683, 688, -1, 689, 688, 683, -1, + 688, 689, 690, -1, 691, 690, 689, -1, + 690, 691, 692, -1, 693, 692, 691, -1, + 692, 693, 694, -1, 695, 694, 693, -1, + 694, 695, 696, -1, 697, 696, 695, -1, + 696, 697, 698, -1, 699, 698, 697, -1, + 698, 699, 700, -1, 682, 700, 699, -1, + 700, 682, 679, -1, 701, 702, 679, -1, + 679, 702, 700, -1, 703, 700, 702, -1, + 700, 703, 698, -1, 704, 698, 703, -1, + 698, 704, 696, -1, 705, 696, 704, -1, + 696, 705, 694, -1, 706, 694, 705, -1, + 694, 706, 692, -1, 707, 692, 706, -1, + 692, 707, 690, -1, 708, 690, 707, -1, + 690, 708, 688, -1, 709, 688, 708, -1, + 688, 709, 687, -1, 710, 711, 687, -1, + 687, 712, 710, -1, 712, 687, 709, -1, + 713, 714, 715, -1, 712, 715, 714, -1, + 715, 712, 716, -1, 709, 716, 712, -1, + 716, 709, 717, -1, 708, 717, 709, -1, + 717, 708, 718, -1, 707, 718, 708, -1, + 718, 707, 719, -1, 706, 719, 707, -1, + 719, 706, 720, -1, 705, 720, 706, -1, + 720, 705, 721, -1, 704, 721, 705, -1, + 703, 722, 704, -1, 722, 703, 723, -1, + 702, 723, 703, -1, 724, 723, 702, -1, + 723, 724, 725, -1, 726, 723, 725, -1, + 723, 726, 722, -1, 727, 721, 728, -1, + 721, 727, 720, -1, 729, 720, 727, -1, + 720, 729, 719, -1, 730, 719, 729, -1, + 719, 730, 718, -1, 731, 718, 730, -1, + 718, 731, 717, -1, 732, 717, 731, -1, + 717, 732, 716, -1, 733, 716, 732, -1, + 716, 733, 715, -1, 715, 734, 735, -1, + 734, 715, 733, -1, 736, 734, 737, -1, + 733, 737, 734, -1, 737, 733, 738, -1, + 732, 738, 733, -1, 738, 732, 739, -1, + 731, 739, 732, -1, 739, 731, 740, -1, + 730, 740, 731, -1, 740, 730, 741, -1, + 729, 741, 730, -1, 741, 729, 742, -1, + 727, 742, 729, -1, 742, 727, 743, -1, + 728, 743, 727, -1, 743, 728, 744, -1, + 745, 744, 726, -1, 746, 747, 748, -1, + 749, 746, 750, -1, 751, 750, 746, -1, + 750, 751, 752, -1, 753, 752, 751, -1, + 752, 753, 754, -1, 755, 754, 753, -1, + 754, 755, 756, -1, 757, 756, 755, -1, + 756, 757, 758, -1, 759, 758, 757, -1, + 758, 759, 760, -1, 761, 760, 759, -1, + 760, 761, 762, -1, 763, 762, 761, -1, + 764, 765, 766, -1, 766, 765, 763, -1, + 767, 768, 769, -1, 767, 770, 768, -1, + 771, 770, 767, -1, 767, 772, 771, -1, + 773, 774, 767, -1, 774, 773, 775, -1, + 776, 775, 773, -1, 775, 776, 777, -1, + 778, 777, 776, -1, 777, 778, 779, -1, + 780, 779, 778, -1, 779, 780, 781, -1, + 782, 781, 780, -1, 781, 782, 783, -1, + 784, 783, 782, -1, 783, 784, 785, -1, + 786, 785, 784, -1, 785, 786, 787, -1, + 788, 787, 786, -1, 787, 788, 789, -1, + 790, 791, 792, -1, 793, 794, 795, -1, + 794, 793, 796, -1, 796, 793, 797, -1, + 798, 797, 793, -1, 795, 798, 793, -1, + 799, 800, 795, -1, 801, 800, 802, -1, + 803, 804, 805, -1, 806, 807, 808, -1, + 809, 810, 811, -1, 811, 790, 792, -1, + 792, 789, 811, -1, 789, 792, 787, -1, + 787, 792, 791, -1, 766, 787, 791, -1, + 787, 766, 785, -1, 763, 785, 766, -1, + 785, 763, 783, -1, 761, 783, 763, -1, + 783, 761, 781, -1, 759, 781, 761, -1, + 781, 759, 779, -1, 757, 779, 759, -1, + 779, 757, 777, -1, 755, 777, 757, -1, + 777, 755, 775, -1, 753, 775, 755, -1, + 775, 753, 774, -1, 751, 774, 753, -1, + 746, 772, 751, -1, 772, 746, 748, -1, + 748, 812, 772, -1, 772, 812, 771, -1, + 813, 814, 815, -1, 816, 817, 818, -1, + 819, 817, 816, -1, 820, 819, 821, -1, + 822, 823, 824, -1, 825, 823, 822, -1, + 823, 825, 826, -1, 826, 825, 821, -1, + 827, 828, 829, -1, 828, 827, 830, -1, + 831, 830, 827, -1, 830, 831, 832, -1, + 833, 832, 831, -1, 832, 833, 834, -1, + 835, 834, 833, -1, 834, 835, 836, -1, + 837, 836, 835, -1, 836, 837, 838, -1, + 839, 838, 837, -1, 838, 839, 840, -1, + 841, 840, 839, -1, 840, 841, 842, -1, + 843, 842, 841, -1, 842, 843, 844, -1, + 826, 844, 843, -1, 821, 844, 826, -1, + 844, 821, 819, -1, 816, 844, 819, -1, + 844, 816, 842, -1, 845, 842, 816, -1, + 842, 845, 840, -1, 846, 840, 845, -1, + 840, 846, 838, -1, 847, 838, 846, -1, + 838, 847, 836, -1, 848, 836, 847, -1, + 836, 848, 834, -1, 849, 834, 848, -1, + 834, 849, 832, -1, 850, 832, 849, -1, + 832, 850, 830, -1, 851, 830, 850, -1, + 830, 851, 828, -1, 813, 828, 851, -1, + 828, 813, 815, -1, 815, 852, 828, -1, + 852, 853, 828, -1, 828, 853, 829, -1, + 854, 855, 856, -1, 856, 855, 857, -1, + 858, 814, 813, -1, 813, 859, 858, -1, + 859, 813, 860, -1, 851, 860, 813, -1, + 860, 851, 861, -1, 850, 861, 851, -1, + 861, 850, 862, -1, 849, 862, 850, -1, + 862, 849, 863, -1, 848, 863, 849, -1, + 863, 848, 864, -1, 847, 864, 848, -1, + 864, 847, 865, -1, 846, 865, 847, -1, + 865, 846, 866, -1, 845, 866, 846, -1, + 816, 867, 845, -1, 818, 867, 816, -1, + 868, 869, 870, -1, 871, 872, 868, -1, + 868, 873, 871, -1, 867, 871, 873, -1, + 818, 871, 867, -1, 871, 818, 872, -1, + 872, 818, 817, -1, 874, 869, 875, -1, + 876, 822, 824, -1, 824, 877, 876, -1, + 877, 824, 878, -1, 878, 824, 823, -1, + 826, 878, 823, -1, 878, 826, 879, -1, + 843, 879, 826, -1, 841, 880, 843, -1, + 880, 841, 881, -1, 839, 881, 841, -1, + 881, 839, 882, -1, 837, 882, 839, -1, + 882, 837, 883, -1, 835, 883, 837, -1, + 883, 835, 884, -1, 833, 884, 835, -1, + 884, 833, 885, -1, 831, 885, 833, -1, + 885, 831, 886, -1, 827, 886, 831, -1, + 886, 827, 887, -1, 888, 889, 890, -1, + 890, 891, 888, -1, 892, 893, 894, -1, + 892, 894, 895, -1, 895, 896, 892, -1, + 897, 747, 746, -1, 897, 746, 749, -1, + 898, 899, 749, -1, 749, 899, 897, -1, + 887, 900, 886, -1, 886, 900, 898, -1, + 749, 886, 898, -1, 886, 749, 885, -1, + 750, 885, 749, -1, 885, 750, 884, -1, + 752, 884, 750, -1, 884, 752, 883, -1, + 754, 883, 752, -1, 883, 754, 882, -1, + 756, 882, 754, -1, 882, 756, 881, -1, + 758, 881, 756, -1, 881, 758, 880, -1, + 760, 880, 758, -1, 762, 879, 760, -1, + 879, 762, 878, -1, 878, 765, 877, -1, + 764, 877, 765, -1, 877, 764, 876, -1, + 876, 764, 901, -1, 766, 901, 764, -1, + 791, 901, 766, -1, 901, 791, 790, -1, + 901, 790, 876, -1, 902, 875, 801, -1, + 801, 745, 902, -1, 726, 902, 745, -1, + 725, 902, 726, -1, 902, 725, 875, -1, + 875, 725, 724, -1, 875, 724, 874, -1, + 702, 874, 724, -1, 701, 874, 702, -1, + 874, 701, 869, -1, 869, 701, 870, -1, + 679, 870, 701, -1, 681, 870, 679, -1, + 870, 681, 868, -1, 868, 681, 873, -1, + 680, 873, 681, -1, 873, 680, 867, -1, + 682, 866, 680, -1, 866, 682, 865, -1, + 699, 865, 682, -1, 865, 699, 864, -1, + 697, 864, 699, -1, 864, 697, 863, -1, + 695, 863, 697, -1, 863, 695, 862, -1, + 693, 862, 695, -1, 862, 693, 861, -1, + 691, 861, 693, -1, 861, 691, 860, -1, + 689, 860, 691, -1, 860, 689, 859, -1, + 683, 859, 689, -1, 685, 859, 683, -1, + 859, 685, 858, -1, 687, 903, 686, -1, + 711, 903, 687, -1, 712, 904, 710, -1, + 714, 904, 712, -1, 715, 905, 713, -1, + 735, 905, 715, -1, 906, 735, 734, -1, + 906, 734, 736, -1, 907, 908, 736, -1, + 736, 908, 906, -1, 857, 677, 676, -1, + 857, 676, 856, -1, 856, 676, 909, -1, + 910, 909, 676, -1, 911, 912, 913, -1, + 914, 913, 912, -1, 913, 914, 915, -1, + 916, 915, 914, -1, 917, 918, 916, -1, + 918, 917, 919, -1, 920, 919, 917, -1, + 919, 920, 921, -1, 922, 921, 920, -1, + 921, 922, 923, -1, 924, 923, 925, -1, + 925, 923, 922, -1, 925, 926, 927, -1, + 926, 925, 928, -1, 922, 928, 925, -1, + 928, 922, 929, -1, 920, 929, 922, -1, + 929, 920, 930, -1, 917, 930, 920, -1, + 930, 917, 931, -1, 916, 931, 917, -1, + 931, 916, 932, -1, 914, 932, 916, -1, + 932, 914, 933, -1, 912, 933, 914, -1, + 933, 912, 934, -1, 934, 910, 935, -1, + 676, 935, 910, -1, 678, 935, 676, -1, + 935, 678, 936, -1, 935, 936, 907, -1, + 736, 935, 907, -1, 935, 736, 934, -1, + 737, 934, 736, -1, 934, 737, 933, -1, + 738, 933, 737, -1, 933, 738, 932, -1, + 739, 932, 738, -1, 932, 739, 931, -1, + 740, 931, 739, -1, 931, 740, 930, -1, + 741, 930, 740, -1, 930, 741, 929, -1, + 742, 929, 741, -1, 929, 742, 928, -1, + 743, 928, 742, -1, 928, 743, 926, -1, + 744, 926, 743, -1, 926, 744, 937, -1, + 745, 937, 744, -1, 937, 745, 801, -1, + 802, 937, 801, -1, 937, 802, 926, -1, + 926, 802, 927, -1, 800, 927, 802, -1, + 799, 927, 800, -1, 927, 799, 925, -1, + 925, 799, 924, -1, 795, 924, 799, -1, + 794, 924, 795, -1, 924, 794, 923, -1, + 796, 923, 794, -1, 923, 796, 921, -1, + 938, 921, 796, -1, 921, 938, 919, -1, + 939, 919, 938, -1, 919, 939, 918, -1, + 940, 918, 939, -1, 941, 915, 940, -1, + 915, 941, 913, -1, 913, 942, 911, -1, + 943, 911, 942, -1, 944, 909, 943, -1, + 909, 944, 856, -1, 856, 945, 854, -1, + 946, 947, 945, -1, 945, 947, 854, -1, + 948, 949, 950, -1, 950, 949, 946, -1, + 945, 950, 946, -1, 950, 945, 951, -1, + 943, 952, 944, -1, 952, 943, 953, -1, + 942, 953, 943, -1, 953, 942, 954, -1, + 954, 941, 955, -1, 940, 955, 941, -1, + 955, 940, 956, -1, 939, 956, 940, -1, + 956, 939, 957, -1, 938, 957, 939, -1, + 957, 938, 958, -1, 796, 958, 938, -1, + 958, 796, 797, -1, 959, 960, 961, -1, + 958, 961, 960, -1, 797, 961, 958, -1, + 961, 797, 798, -1, 961, 798, 959, -1, + 962, 963, 964, -1, 965, 966, 962, -1, + 966, 965, 967, -1, 968, 967, 965, -1, + 967, 968, 969, -1, 970, 969, 968, -1, + 969, 970, 971, -1, 972, 971, 970, -1, + 971, 972, 973, -1, 974, 973, 972, -1, + 973, 974, 975, -1, 976, 975, 974, -1, + 975, 976, 977, -1, 978, 977, 976, -1, + 977, 978, 979, -1, 980, 981, 982, -1, + 982, 981, 983, -1, 984, 983, 981, -1, + 983, 984, 985, -1, 986, 985, 984, -1, + 985, 986, 987, -1, 988, 987, 986, -1, + 987, 988, 989, -1, 990, 989, 988, -1, + 989, 990, 991, -1, 992, 991, 990, -1, + 991, 992, 993, -1, 994, 993, 992, -1, + 993, 994, 995, -1, 996, 995, 994, -1, + 995, 996, 997, -1, 998, 997, 996, -1, + 999, 997, 998, -1, 999, 1000, 997, -1, + 997, 1000, 1001, -1, 1002, 997, 1001, -1, + 997, 1002, 995, -1, 1003, 995, 1002, -1, + 995, 1003, 993, -1, 1004, 993, 1003, -1, + 993, 1004, 991, -1, 1005, 991, 1004, -1, + 991, 1005, 989, -1, 1006, 989, 1005, -1, + 989, 1006, 987, -1, 1007, 987, 1006, -1, + 987, 1007, 985, -1, 1008, 985, 1007, -1, + 985, 1008, 983, -1, 1009, 983, 1008, -1, + 983, 1009, 982, -1, 1010, 982, 1009, -1, + 982, 1010, 1011, -1, 1012, 1013, 1014, -1, + 1015, 1016, 1017, -1, 1016, 1015, 1018, -1, + 1018, 1015, 1019, -1, 1020, 1019, 1015, -1, + 1017, 1020, 1015, -1, 1021, 1022, 1017, -1, + 1014, 1022, 1023, -1, 1023, 1024, 1014, -1, + 1024, 1023, 1010, -1, 1010, 1023, 1011, -1, + 1022, 1011, 1023, -1, 1021, 1011, 1022, -1, + 1011, 1021, 982, -1, 982, 1021, 980, -1, + 1017, 980, 1021, -1, 1016, 980, 1017, -1, + 980, 1016, 981, -1, 1018, 981, 1016, -1, + 981, 1018, 984, -1, 1025, 984, 1018, -1, + 984, 1025, 986, -1, 1026, 986, 1025, -1, + 986, 1026, 988, -1, 1027, 988, 1026, -1, + 988, 1027, 990, -1, 1028, 990, 1027, -1, + 990, 1028, 992, -1, 1029, 992, 1028, -1, + 992, 1029, 994, -1, 1030, 994, 1029, -1, + 994, 1030, 996, -1, 1031, 996, 1030, -1, + 996, 1031, 998, -1, 1032, 1033, 998, -1, + 998, 1034, 1032, -1, 1034, 998, 1031, -1, + 1034, 1035, 1036, -1, 1031, 1037, 1034, -1, + 1037, 1031, 1038, -1, 1030, 1038, 1031, -1, + 1038, 1030, 1039, -1, 1029, 1039, 1030, -1, + 1039, 1029, 1040, -1, 1028, 1040, 1029, -1, + 1040, 1028, 1041, -1, 1027, 1041, 1028, -1, + 1041, 1027, 1042, -1, 1026, 1042, 1027, -1, + 1042, 1026, 1043, -1, 1025, 1043, 1026, -1, + 1043, 1025, 1044, -1, 1018, 1044, 1025, -1, + 1044, 1018, 1019, -1, 1045, 1046, 1047, -1, + 1044, 1047, 1046, -1, 1019, 1047, 1044, -1, + 1047, 1019, 1020, -1, 1047, 1020, 1045, -1, + 1045, 1048, 1049, -1, 1048, 1050, 1049, -1, + 977, 1049, 1050, -1, 979, 1049, 977, -1, + 1049, 979, 1045, -1, 1045, 979, 1046, -1, + 978, 1046, 979, -1, 1046, 978, 1044, -1, + 1044, 978, 1043, -1, 976, 1043, 978, -1, + 1043, 976, 1042, -1, 974, 1042, 976, -1, + 1042, 974, 1041, -1, 972, 1041, 974, -1, + 1041, 972, 1040, -1, 970, 1040, 972, -1, + 1040, 970, 1039, -1, 968, 1039, 970, -1, + 1039, 968, 1038, -1, 965, 1038, 968, -1, + 1038, 965, 1037, -1, 962, 1037, 965, -1, + 964, 1035, 962, -1, 1035, 964, 1051, -1, + 1052, 1051, 964, -1, 1052, 964, 1053, -1, + 1053, 964, 963, -1, 1053, 1054, 1055, -1, + 1054, 1053, 1056, -1, 963, 1056, 1053, -1, + 1056, 963, 1057, -1, 1057, 966, 1058, -1, + 967, 1058, 966, -1, 1058, 967, 1059, -1, + 969, 1059, 967, -1, 1059, 969, 1060, -1, + 971, 1060, 969, -1, 1060, 971, 1061, -1, + 973, 1061, 971, -1, 1061, 973, 1062, -1, + 975, 1062, 973, -1, 1062, 975, 1063, -1, + 977, 1063, 975, -1, 1050, 1063, 977, -1, + 803, 1064, 1065, -1, 1063, 1065, 1064, -1, + 1050, 1065, 1063, -1, 1065, 1050, 1048, -1, + 1065, 1048, 803, -1, 959, 1066, 1067, -1, + 1066, 674, 1067, -1, 655, 1067, 674, -1, + 657, 1067, 655, -1, 1067, 657, 959, -1, + 959, 657, 960, -1, 656, 960, 657, -1, + 960, 656, 958, -1, 958, 656, 957, -1, + 658, 957, 656, -1, 957, 658, 956, -1, + 672, 956, 658, -1, 956, 672, 955, -1, + 670, 955, 672, -1, 955, 670, 954, -1, + 666, 954, 670, -1, 954, 666, 953, -1, + 668, 953, 666, -1, 953, 668, 952, -1, + 662, 951, 663, -1, 951, 662, 950, -1, + 660, 950, 662, -1, 950, 660, 948, -1, + 1068, 948, 660, -1, 1069, 1068, 660, -1, + 1069, 660, 659, -1, 659, 1070, 1069, -1, + 1071, 1070, 659, -1, 659, 1072, 1071, -1, + 1072, 659, 1073, -1, 661, 1073, 659, -1, + 1074, 664, 1075, -1, 665, 1075, 664, -1, + 1075, 665, 1076, -1, 669, 1077, 667, -1, + 671, 1078, 669, -1, 1078, 671, 1079, -1, + 673, 1079, 671, -1, 1080, 1081, 653, -1, + 1081, 1080, 1082, -1, 1083, 1082, 1080, -1, + 1082, 1083, 1084, -1, 1085, 1084, 1083, -1, + 1086, 1087, 1088, -1, 1089, 1088, 1087, -1, + 1090, 1091, 1092, -1, 1091, 1090, 1093, -1, + 1094, 1093, 1090, -1, 1093, 1094, 1095, -1, + 1094, 1096, 1095, -1, 1096, 1094, 675, -1, + 1090, 1079, 1094, -1, 1079, 1090, 1078, -1, + 1092, 1078, 1090, -1, 1087, 1076, 1089, -1, + 1076, 1087, 1075, -1, 1075, 1085, 1074, -1, + 1083, 1074, 1085, -1, 1080, 1073, 1083, -1, + 1073, 1080, 1072, -1, 653, 1072, 1080, -1, + 654, 1072, 653, -1, 1072, 654, 1071, -1, + 653, 1097, 651, -1, 1097, 653, 1098, -1, + 1098, 653, 1081, -1, 1099, 1100, 1101, -1, + 1100, 1099, 1102, -1, 1102, 1103, 1104, -1, + 1105, 1104, 1103, -1, 1104, 1105, 1106, -1, + 1107, 1106, 1105, -1, 1106, 1107, 1108, -1, + 1109, 1108, 1107, -1, 1108, 1109, 1110, -1, + 1111, 1110, 1109, -1, 1110, 1111, 1112, -1, + 1113, 1112, 1111, -1, 1112, 1113, 1114, -1, + 1115, 1114, 1113, -1, 1114, 1115, 1116, -1, + 1116, 1117, 1114, -1, 1114, 1117, 1118, -1, + 1114, 1118, 1119, -1, 1119, 1098, 1114, -1, + 1114, 1098, 1112, -1, 1081, 1112, 1098, -1, + 1112, 1081, 1110, -1, 1082, 1110, 1081, -1, + 1110, 1082, 1108, -1, 1084, 1108, 1082, -1, + 1108, 1084, 1106, -1, 1106, 1086, 1104, -1, + 1088, 1104, 1086, -1, 1104, 1088, 1102, -1, + 1102, 1120, 1100, -1, 1093, 1121, 1091, -1, + 1122, 1121, 1093, -1, 1093, 1123, 1122, -1, + 1095, 1123, 1093, -1, 1123, 1095, 1124, -1, + 1124, 1095, 1096, -1, 1124, 1096, 1125, -1, + 675, 1125, 1096, -1, 674, 1125, 675, -1, + 1125, 674, 1066, -1, 1125, 1066, 1124, -1, + 1126, 583, 1013, -1, 1127, 1126, 1128, -1, + 1013, 1128, 1126, -1, 1013, 1129, 1128, -1, + 1012, 1129, 1013, -1, 1129, 1012, 649, -1, + 649, 1012, 650, -1, 1014, 650, 1012, -1, + 1024, 650, 1014, -1, 650, 1024, 648, -1, + 1010, 648, 1024, -1, 648, 1010, 646, -1, + 1009, 646, 1010, -1, 646, 1009, 644, -1, + 1008, 644, 1009, -1, 644, 1008, 642, -1, + 1007, 642, 1008, -1, 642, 1007, 640, -1, + 1006, 640, 1007, -1, 640, 1006, 638, -1, + 1005, 638, 1006, -1, 638, 1005, 636, -1, + 1004, 636, 1005, -1, 636, 1004, 634, -1, + 1003, 634, 1004, -1, 634, 1003, 633, -1, + 1002, 633, 1003, -1, 633, 1002, 1130, -1, + 1002, 1131, 1130, -1, 1001, 1131, 1002, -1, + 1130, 1132, 633, -1, 633, 1132, 630, -1, + 998, 1133, 999, -1, 1033, 1133, 998, -1, + 1034, 1134, 1032, -1, 1036, 1134, 1034, -1, + 1035, 1135, 1036, -1, 1051, 1135, 1035, -1, + 1053, 1136, 1052, -1, 1055, 1136, 1053, -1, + 1054, 629, 1055, -1, 629, 1054, 623, -1, + 623, 1054, 621, -1, 1056, 621, 1054, -1, + 621, 1056, 619, -1, 1057, 619, 1056, -1, + 619, 1057, 617, -1, 1058, 617, 1057, -1, + 617, 1058, 615, -1, 1059, 615, 1058, -1, + 615, 1059, 613, -1, 1060, 613, 1059, -1, + 613, 1060, 611, -1, 1061, 611, 1060, -1, + 611, 1061, 609, -1, 1062, 609, 1061, -1, + 609, 1062, 607, -1, 1063, 607, 1062, -1, + 1064, 607, 1063, -1, 607, 1064, 608, -1, + 803, 608, 1064, -1, 805, 608, 803, -1, + 608, 805, 606, -1, 606, 805, 1137, -1, + 804, 1137, 805, -1, 807, 1137, 804, -1, + 1137, 807, 806, -1, 1137, 806, 606, -1, + 606, 806, 610, -1, 1138, 610, 806, -1, + 610, 1138, 612, -1, 1139, 612, 1138, -1, + 612, 1139, 614, -1, 1140, 614, 1139, -1, + 614, 1140, 616, -1, 1141, 616, 1140, -1, + 616, 1141, 618, -1, 1142, 618, 1141, -1, + 618, 1142, 620, -1, 1143, 620, 1142, -1, + 620, 1143, 622, -1, 1144, 622, 1143, -1, + 622, 1144, 624, -1, 1145, 624, 1144, -1, + 624, 1145, 626, -1, 1146, 1147, 1145, -1, + 1145, 1147, 626, -1, 1148, 1149, 1150, -1, + 1149, 1148, 1151, -1, 1152, 1151, 1148, -1, + 1151, 1152, 1153, -1, 1154, 1153, 1152, -1, + 1153, 1154, 1155, -1, 1156, 1155, 1154, -1, + 1155, 1156, 1157, -1, 1158, 1157, 1156, -1, + 1157, 1158, 1159, -1, 1160, 1159, 1158, -1, + 1159, 1160, 1161, -1, 1162, 1161, 1160, -1, + 1161, 1162, 1163, -1, 1164, 1163, 1162, -1, + 1163, 1164, 1165, -1, 1166, 1165, 1164, -1, + 1165, 1166, 1167, -1, 1168, 1167, 1166, -1, + 1167, 1169, 1165, -1, 1165, 1169, 1146, -1, + 1145, 1165, 1146, -1, 1165, 1145, 1163, -1, + 1144, 1163, 1145, -1, 1163, 1144, 1161, -1, + 1143, 1161, 1144, -1, 1161, 1143, 1159, -1, + 1142, 1159, 1143, -1, 1159, 1142, 1157, -1, + 1141, 1157, 1142, -1, 1157, 1141, 1155, -1, + 1140, 1155, 1141, -1, 1155, 1140, 1153, -1, + 1139, 1153, 1140, -1, 1153, 1139, 1151, -1, + 1138, 1151, 1139, -1, 1151, 1138, 1149, -1, + 806, 1149, 1138, -1, 808, 1149, 806, -1, + 1149, 808, 1150, -1, 810, 1150, 808, -1, + 809, 1150, 810, -1, 1150, 809, 1148, -1, + 1148, 809, 1170, -1, 811, 1170, 809, -1, + 789, 1170, 811, -1, 1170, 789, 788, -1, + 1170, 788, 1148, -1, 1148, 788, 1152, -1, + 786, 1152, 788, -1, 1152, 786, 1154, -1, + 784, 1154, 786, -1, 1154, 784, 1156, -1, + 782, 1156, 784, -1, 1156, 782, 1158, -1, + 780, 1158, 782, -1, 1158, 780, 1160, -1, + 778, 1160, 780, -1, 1160, 778, 1162, -1, + 776, 1162, 778, -1, 1162, 776, 1164, -1, + 773, 1164, 776, -1, 1164, 773, 1166, -1, + 767, 1166, 773, -1, 769, 1166, 767, -1, + 1166, 769, 1168, -1, 1171, 1172, 1173, -1, + 1171, 1173, 1174, -1, 1174, 1175, 1171, -1, + 1176, 1177, 1178, -1, 1177, 1179, 1178, -1, + 888, 1180, 889, -1, 1098, 1181, 1097, -1, + 1119, 1181, 1098, -1, 1115, 1182, 1116, -1, + 1183, 1182, 1115, -1, 604, 1183, 602, -1, + 1115, 602, 1183, -1, 602, 1115, 600, -1, + 1113, 600, 1115, -1, 600, 1113, 598, -1, + 1111, 598, 1113, -1, 598, 1111, 596, -1, + 1109, 596, 1111, -1, 596, 1109, 595, -1, + 1107, 595, 1109, -1, 1105, 592, 1107, -1, + 592, 1105, 590, -1, 1103, 590, 1105, -1, + 590, 1103, 588, -1, 588, 1099, 587, -1, + 1101, 587, 1099, -1, 587, 1101, 1184, -1, + 1185, 1122, 1123, -1, 1124, 1185, 1123, -1, + 1186, 580, 582, -1, 582, 1187, 1186, -1, + 1188, 1186, 1187, -1, 1189, 1190, 1191, -1, + 1190, 1189, 1192, -1, 1193, 1192, 1189, -1, + 1192, 1193, 1194, -1, 1195, 1194, 1193, -1, + 1194, 1195, 1196, -1, 1197, 1196, 1195, -1, + 1196, 1197, 1198, -1, 1199, 1198, 1197, -1, + 1198, 1199, 1200, -1, 1201, 1200, 1199, -1, + 1200, 1201, 1202, -1, 1203, 1202, 1201, -1, + 1202, 1203, 1204, -1, 1205, 1204, 1203, -1, + 1206, 1207, 1205, -1, 1208, 1207, 1206, -1, + 1208, 1209, 1207, -1, 1207, 1209, 1210, -1, + 1211, 1207, 1210, -1, 1212, 1204, 1211, -1, + 1204, 1212, 1202, -1, 1213, 1202, 1212, -1, + 1202, 1213, 1200, -1, 1214, 1200, 1213, -1, + 1200, 1214, 1198, -1, 1215, 1198, 1214, -1, + 1198, 1215, 1196, -1, 1216, 1196, 1215, -1, + 1196, 1216, 1194, -1, 1217, 1194, 1216, -1, + 1194, 1217, 1192, -1, 1192, 1218, 1190, -1, + 1188, 1190, 1218, -1, 1187, 1190, 1188, -1, + 1190, 1187, 1191, -1, 582, 1191, 1187, -1, + 584, 1191, 582, -1, 1191, 584, 1189, -1, + 1189, 584, 1219, -1, 583, 1219, 584, -1, + 1126, 1219, 583, -1, 1219, 1126, 1127, -1, + 1219, 1127, 1189, -1, 1189, 1127, 1193, -1, + 1220, 1193, 1127, -1, 1193, 1220, 1195, -1, + 1221, 1195, 1220, -1, 1195, 1221, 1197, -1, + 1222, 1197, 1221, -1, 1197, 1222, 1199, -1, + 1223, 1199, 1222, -1, 1199, 1223, 1201, -1, + 1224, 1201, 1223, -1, 1201, 1224, 1203, -1, + 1225, 1203, 1224, -1, 1203, 1225, 1205, -1, + 1226, 1205, 1225, -1, 1205, 1226, 1206, -1, + 1206, 1227, 1228, -1, 1227, 1206, 1226, -1, + 1227, 1229, 1230, -1, 1229, 1227, 1231, -1, + 1226, 1231, 1227, -1, 1231, 1226, 1232, -1, + 1225, 1232, 1226, -1, 1232, 1225, 1233, -1, + 1224, 1233, 1225, -1, 1233, 1224, 1234, -1, + 1223, 1234, 1224, -1, 1234, 1223, 1235, -1, + 1222, 1235, 1223, -1, 1235, 1222, 1236, -1, + 1221, 1236, 1222, -1, 1236, 1221, 1237, -1, + 1220, 1237, 1221, -1, 1237, 1220, 1238, -1, + 1127, 1238, 1220, -1, 1128, 1238, 1127, -1, + 1238, 1128, 1129, -1, 649, 1238, 1129, -1, + 1238, 649, 1237, -1, 647, 1237, 649, -1, + 1237, 647, 1236, -1, 645, 1236, 647, -1, + 1236, 645, 1235, -1, 1235, 643, 1234, -1, + 641, 1234, 643, -1, 1234, 641, 1233, -1, + 639, 1233, 641, -1, 1233, 639, 1232, -1, + 637, 1232, 639, -1, 1232, 637, 1231, -1, + 635, 1231, 637, -1, 1231, 635, 1229, -1, + 1229, 632, 1239, -1, 631, 1239, 632, -1, + 1239, 1240, 1229, -1, 1229, 1240, 1230, -1, + 1230, 1241, 1227, -1, 1227, 1241, 1228, -1, + 1228, 1242, 1206, -1, 1178, 1243, 1176, -1, + 579, 605, 603, -1, 579, 603, 369, -1, + 369, 603, 372, -1, 601, 372, 603, -1, + 372, 601, 374, -1, 599, 374, 601, -1, + 597, 376, 599, -1, 376, 597, 378, -1, + 594, 378, 597, -1, 378, 594, 380, -1, + 593, 380, 594, -1, 380, 593, 382, -1, + 591, 382, 593, -1, 382, 591, 384, -1, + 589, 384, 591, -1, 366, 586, 365, -1, + 585, 365, 586, -1, 365, 585, 364, -1, + 364, 585, 493, -1, 587, 493, 585, -1, + 1184, 493, 587, -1, 493, 1184, 494, -1, + 1244, 1245, 1246, -1, 1246, 54, 1247, -1, + 1247, 1248, 1246, -1, 1248, 1247, 51, -1, + 51, 1247, 52, -1, 54, 52, 1247, -1, + 53, 52, 54, -1, 52, 53, 34, -1, + 34, 53, 33, -1, 55, 33, 53, -1, + 581, 33, 55, -1, 33, 581, 31, -1, + 31, 581, 1249, -1, 580, 1249, 581, -1, + 1186, 1249, 580, -1, 1249, 1186, 1188, -1, + 1249, 1188, 31, -1, 31, 1188, 29, -1, + 1218, 29, 1188, -1, 29, 1218, 27, -1, + 27, 1217, 25, -1, 1216, 25, 1217, -1, + 25, 1216, 23, -1, 1215, 23, 1216, -1, + 23, 1215, 21, -1, 1214, 21, 1215, -1, + 21, 1214, 19, -1, 1213, 19, 1214, -1, + 19, 1213, 18, -1, 1212, 18, 1213, -1, + 18, 1212, 17, -1, 1211, 17, 1212, -1, + 17, 1211, 1250, -1, 1250, 1251, 17, -1, + 17, 1251, 16, -1, 1211, 1252, 1250, -1, + 1210, 1252, 1211, -1, 2, 1253, 0, -1, + 0, 1254, 1, -1, 1255, 533, 532, -1, + 532, 1256, 1255, -1, 1256, 532, 1257, -1, + 536, 1257, 532, -1, 1257, 536, 1258, -1, + 538, 1258, 536, -1, 1258, 538, 1259, -1, + 540, 1259, 538, -1, 1259, 540, 1260, -1, + 542, 1260, 540, -1, 1260, 542, 1261, -1, + 544, 1261, 542, -1, 1261, 544, 1262, -1, + 546, 1262, 544, -1, 1262, 546, 1263, -1, + 548, 1263, 546, -1, 1263, 548, 1264, -1, + 1264, 551, 1265, -1, 552, 1265, 551, -1, + 1265, 552, 92, -1, 94, 1265, 92, -1, + 1265, 94, 1264, -1, 1264, 94, 95, -1, + 98, 1264, 95, -1, 1264, 98, 1263, -1, + 99, 1263, 98, -1, 1263, 99, 1262, -1, + 1262, 102, 1261, -1, 103, 1261, 102, -1, + 1261, 103, 1260, -1, 105, 1260, 103, -1, + 1260, 105, 1259, -1, 107, 1259, 105, -1, + 1259, 107, 1258, -1, 109, 1258, 107, -1, + 1258, 109, 1257, -1, 111, 1257, 109, -1, + 1257, 111, 1256, -1, 113, 1256, 111, -1, + 115, 1256, 113, -1, 1256, 115, 1255, -1, + 117, 1266, 116, -1, 527, 1266, 117, -1, + 3, 1267, 4, -1, 8, 1268, 6, -1, + 14, 1269, 12, -1, 12, 1269, 43, -1, + 348, 1270, 347, -1, 1270, 348, 1271, -1, + 1271, 348, 1272, -1, 349, 1272, 348, -1, + 1272, 349, 1273, -1, 350, 1273, 349, -1, + 1273, 350, 1274, -1, 351, 1274, 350, -1, + 1274, 351, 1275, -1, 352, 1275, 351, -1, + 1275, 352, 1276, -1, 353, 1276, 352, -1, + 1276, 353, 1277, -1, 354, 1277, 353, -1, + 1277, 354, 1278, -1, 1278, 229, 228, -1, + 1279, 1280, 228, -1, 228, 1280, 1278, -1, + 1281, 1278, 1280, -1, 1278, 1281, 1277, -1, + 1282, 1277, 1281, -1, 1277, 1282, 1276, -1, + 1276, 1283, 1275, -1, 1284, 1275, 1283, -1, + 1275, 1284, 1274, -1, 1274, 1285, 1273, -1, + 1286, 1273, 1285, -1, 1273, 1286, 1272, -1, + 1287, 1272, 1286, -1, 1272, 1287, 1271, -1, + 1288, 1271, 1287, -1, 1289, 1271, 1288, -1, + 1290, 1291, 1288, -1, 1288, 1291, 1289, -1, + 1289, 1292, 1271, -1, 1271, 1292, 1270, -1, + 1288, 42, 1290, -1, 42, 1288, 44, -1, + 1287, 44, 1288, -1, 1286, 45, 1287, -1, + 45, 1286, 46, -1, 1285, 46, 1286, -1, + 47, 1284, 48, -1, 1283, 48, 1284, -1, + 49, 1282, 50, -1, 1281, 50, 1282, -1, + 50, 1281, 51, -1, 1280, 51, 1281, -1, + 51, 1280, 1248, -1, 1279, 1248, 1280, -1, + 1248, 1279, 1246, -1, 1246, 1279, 1244, -1, + 228, 1244, 1279, -1, 227, 1244, 228, -1, + 1244, 227, 1245, -1, 1245, 227, 224, -1, + 222, 1245, 224, -1, 252, 257, 256, -1, + 256, 257, 272, -1, 198, 212, 211, -1, + 211, 212, 288, -1, 514, 516, 513, -1, + 513, 516, 118, -1, 113, 112, 117, -1, + 117, 112, 457, -1, 910, 911, 909, -1, + 909, 911, 943, -1, 856, 944, 945, -1, + 945, 944, 951, -1, 1034, 1037, 1035, -1, + 1035, 1037, 962, -1, 665, 663, 668, -1, + 668, 663, 952, -1, 944, 952, 951, -1, + 951, 952, 663, -1, 662, 664, 661, -1, + 661, 664, 1074, -1, 668, 667, 665, -1, + 665, 667, 1076, -1, 1120, 1089, 1092, -1, + 1092, 1089, 1077, -1, 667, 1077, 1076, -1, + 1076, 1077, 1089, -1, 1101, 1100, 1121, -1, + 1121, 1100, 1091, -1, 1184, 1101, 1293, -1, + 1293, 1101, 1121, -1, 1293, 1121, 1294, -1, + 1294, 1121, 1122, -1, 1205, 1207, 1204, -1, + 1204, 1207, 1211, -1, 644, 643, 645, -1, + 645, 643, 1235, -1, 634, 632, 635, -1, + 635, 632, 1229, -1, 36, 48, 49, -1, + 49, 48, 1283, -1, 1276, 1282, 1283, -1, + 1283, 1282, 49, -1, 1295, 1296, 1297, -1, + 1297, 1296, 1298, -1, 1297, 1299, 1295, -1, + 1295, 1299, 1300, -1, 1299, 1297, 1301, -1, + 1301, 1297, 1302, -1, 1302, 1297, 1303, -1, + 1303, 1297, 1304, -1, 1304, 1297, 1305, -1, + 1305, 1297, 1306, -1, 1306, 1297, 1307, -1, + 1307, 1297, 1308, -1, 1308, 1297, 1309, -1, + 1309, 1297, 1298, -1, 1309, 1298, 1310, -1, + 1310, 1311, 1309, -1, 1309, 1311, 1312, -1, + 1309, 1312, 1313, -1, 1313, 1314, 1309, -1, + 1309, 1314, 1315, -1, 1315, 1314, 1316, -1, + 1316, 1314, 1317, -1, 1299, 1301, 1300, -1, + 1300, 1301, 1318, -1, 5, 7, 9, -1, + 9, 7, 10, -1, 1319, 1320, 1321, -1, + 1321, 1320, 1322, -1, 1321, 1323, 1319, -1, + 1319, 1323, 1324, -1, 1325, 1326, 1327, -1, + 1327, 1326, 1328, -1, 1327, 1253, 1325, -1, + 1325, 1253, 2, -1, 1326, 1322, 1328, -1, + 1328, 1322, 1320, -1, 1322, 1326, 1321, -1, + 1321, 1326, 1325, -1, 1321, 1325, 1323, -1, + 1323, 1325, 1329, -1, 1329, 1325, 1330, -1, + 1330, 1325, 1331, -1, 1331, 1325, 1332, -1, + 1332, 1325, 1333, -1, 1333, 1325, 1334, -1, + 1334, 1325, 2, -1, 1334, 2, 1, -1, + 1, 1335, 1334, -1, 1334, 1335, 1336, -1, + 1336, 1335, 1337, -1, 1337, 1335, 1338, -1, + 1338, 1335, 569, -1, 569, 1335, 1339, -1, + 569, 1339, 570, -1, 1340, 1341, 1342, -1, + 1342, 1341, 1343, -1, 1342, 1344, 1340, -1, + 1340, 1344, 1345, -1, 1346, 1347, 1348, -1, + 1348, 1347, 1349, -1, 1348, 1350, 1346, -1, + 1346, 1350, 1351, -1, 1341, 1352, 1343, -1, + 1343, 1352, 1353, -1, 1354, 1355, 1356, -1, + 1356, 1355, 1357, -1, 1356, 1358, 1354, -1, + 1354, 1358, 1359, -1, 1358, 1356, 1360, -1, + 1360, 1356, 1357, -1, 1360, 1357, 1361, -1, + 1361, 1362, 1360, -1, 1360, 1362, 1363, -1, + 1360, 1363, 1364, -1, 1364, 1363, 1353, -1, + 1363, 1365, 1353, -1, 1353, 1365, 1366, -1, + 1353, 1366, 1343, -1, 1343, 1366, 1367, -1, + 1343, 1367, 1368, -1, 1368, 1369, 1343, -1, + 1343, 1369, 1350, -1, 1343, 1350, 1342, -1, + 1342, 1350, 1344, -1, 1350, 1348, 1344, -1, + 1344, 1348, 1349, -1, 1358, 1360, 1359, -1, + 1359, 1360, 1370, -1, 1360, 1364, 1370, -1, + 1370, 1364, 1371, -1, 1366, 1365, 1372, -1, + 1372, 1365, 1373, -1, 1372, 1374, 1366, -1, + 1366, 1374, 1367, -1, 1374, 1375, 1367, -1, + 1367, 1375, 1368, -1, 1365, 1363, 1373, -1, + 1373, 1363, 1376, -1, 1364, 1353, 1371, -1, + 1371, 1353, 1352, -1, 1375, 1377, 1368, -1, + 1368, 1377, 1369, -1, 1378, 1379, 1380, -1, + 1380, 1379, 1381, -1, 1380, 1382, 1378, -1, + 1378, 1382, 1383, -1, 1384, 1385, 1386, -1, + 1386, 1385, 1387, -1, 1386, 1388, 1384, -1, + 1384, 1388, 1389, -1, 1388, 1390, 1389, -1, + 1389, 1390, 1391, -1, 1390, 1392, 1391, -1, + 1391, 1392, 1393, -1, 1394, 1395, 1396, -1, + 1396, 1395, 1397, -1, 1396, 1398, 1394, -1, + 1394, 1398, 1399, -1, 1400, 1401, 1402, -1, + 1402, 1401, 1403, -1, 1402, 1404, 1400, -1, + 1400, 1404, 1405, -1, 1404, 1406, 1405, -1, + 1405, 1406, 1407, -1, 1406, 1408, 1407, -1, + 1407, 1408, 1409, -1, 1408, 1410, 1409, -1, + 1409, 1410, 1411, -1, 1412, 1411, 1413, -1, + 1413, 1411, 1410, -1, 1413, 1414, 1412, -1, + 1412, 1414, 1415, -1, 1416, 1417, 1418, -1, + 1418, 1417, 1419, -1, 1418, 1420, 1416, -1, + 1416, 1420, 1421, -1, 1417, 1422, 1419, -1, + 1419, 1422, 1423, -1, 1424, 1425, 1426, -1, + 1426, 1425, 1427, -1, 1426, 1423, 1424, -1, + 1424, 1423, 1422, -1, 1428, 1429, 1430, -1, + 1430, 1429, 1431, -1, 1430, 1427, 1428, -1, + 1428, 1427, 1425, -1, 1427, 1430, 1426, -1, + 1426, 1430, 1423, -1, 1430, 1431, 1423, -1, + 1423, 1431, 1419, -1, 1419, 1431, 1418, -1, + 1418, 1431, 1420, -1, 1420, 1431, 1432, -1, + 1432, 1431, 1433, -1, 1433, 1431, 1434, -1, + 1434, 1431, 1435, -1, 1431, 1414, 1435, -1, + 1435, 1414, 1413, -1, 1435, 1413, 1410, -1, + 1410, 1408, 1435, -1, 1435, 1408, 1406, -1, + 1435, 1406, 1404, -1, 1404, 1402, 1435, -1, + 1435, 1402, 1403, -1, 1429, 1415, 1431, -1, + 1431, 1415, 1414, -1, 1436, 1437, 1434, -1, + 1434, 1437, 1433, -1, 1434, 1435, 1436, -1, + 1436, 1435, 1438, -1, 1437, 1439, 1433, -1, + 1433, 1439, 1432, -1, 1439, 1421, 1432, -1, + 1432, 1421, 1420, -1, 1440, 1441, 1442, -1, + 1442, 1441, 1443, -1, 1442, 1444, 1440, -1, + 1440, 1444, 1445, -1, 1441, 1446, 1443, -1, + 1443, 1446, 1447, -1, 1446, 1448, 1447, -1, + 1447, 1448, 1449, -1, 1450, 1451, 1452, -1, + 1452, 1451, 1453, -1, 1452, 1454, 1450, -1, + 1450, 1454, 1455, -1, 1456, 1457, 1458, -1, + 1458, 1457, 1459, -1, 1458, 1460, 1456, -1, + 1456, 1460, 1461, -1, 1457, 1462, 1459, -1, + 1459, 1462, 1463, -1, 1462, 1464, 1463, -1, + 1463, 1464, 1465, -1, 1464, 1466, 1465, -1, + 1465, 1466, 1467, -1, 1466, 1453, 1467, -1, + 1467, 1453, 1451, -1, 1453, 1466, 1452, -1, + 1452, 1466, 1464, -1, 1452, 1464, 1462, -1, + 1462, 1457, 1452, -1, 1452, 1457, 1456, -1, + 1452, 1456, 1454, -1, 1454, 1456, 1468, -1, + 1456, 1461, 1468, -1, 1468, 1461, 1448, -1, + 1468, 1448, 1469, -1, 1469, 1448, 1446, -1, + 1469, 1446, 1441, -1, 1441, 1440, 1469, -1, + 1469, 1440, 1445, -1, 1469, 1445, 1470, -1, + 1470, 1445, 1471, -1, 1445, 1472, 1471, -1, + 1471, 1472, 1473, -1, 1454, 1468, 1455, -1, + 1455, 1468, 1474, -1, 1460, 1449, 1461, -1, + 1461, 1449, 1448, -1, 1468, 1469, 1474, -1, + 1474, 1469, 1475, -1, 1469, 1470, 1475, -1, + 1475, 1470, 1476, -1, 1444, 1477, 1445, -1, + 1445, 1477, 1472, -1, 1477, 1478, 1472, -1, + 1472, 1478, 1473, -1, 1470, 1471, 1476, -1, + 1476, 1471, 1479, -1, 1471, 1473, 1479, -1, + 1479, 1473, 1478, -1, 1395, 1480, 1397, -1, + 1397, 1480, 1481, -1, 1398, 1482, 1399, -1, + 1399, 1482, 1483, -1, 1482, 1484, 1483, -1, + 1483, 1484, 1485, -1, 1484, 1486, 1485, -1, + 1485, 1486, 1487, -1, 1488, 1381, 1489, -1, + 1489, 1381, 1379, -1, 1489, 1490, 1488, -1, + 1488, 1490, 1491, -1, 1490, 1492, 1491, -1, + 1491, 1492, 1493, -1, 1491, 1493, 1488, -1, + 1488, 1493, 1381, -1, 1381, 1493, 1380, -1, + 1380, 1493, 1382, -1, 1493, 1385, 1382, -1, + 1382, 1385, 1384, -1, 1382, 1384, 1389, -1, + 1389, 1391, 1382, -1, 1382, 1391, 1393, -1, + 1382, 1393, 4, -1, 4, 1393, 5, -1, + 5, 1393, 7, -1, 7, 1393, 8, -1, + 8, 1393, 1494, -1, 1494, 1393, 1495, -1, + 1494, 1495, 1496, -1, 1496, 1497, 1494, -1, + 1494, 1497, 1498, -1, 1492, 1387, 1493, -1, + 1493, 1387, 1385, -1, 1486, 1499, 1487, -1, + 1487, 1499, 1500, -1, 1499, 1501, 1500, -1, + 1500, 1501, 1502, -1, 1501, 1503, 1502, -1, + 1502, 1503, 1504, -1, 1502, 1504, 1500, -1, + 1500, 1504, 1487, -1, 1487, 1504, 1485, -1, + 1485, 1504, 1483, -1, 1483, 1504, 1399, -1, + 1399, 1504, 1394, -1, 1394, 1504, 1395, -1, + 1395, 1504, 1480, -1, 1480, 1504, 1505, -1, + 1505, 1504, 1506, -1, 1505, 1506, 1507, -1, + 1507, 1508, 1505, -1, 1505, 1508, 1509, -1, + 1505, 1509, 1510, -1, 1510, 1511, 1505, -1, + 1505, 1511, 1512, -1, 1505, 1512, 1513, -1, + 1513, 1514, 1505, -1, 1503, 1515, 1504, -1, + 1504, 1515, 1506, -1, 1505, 1514, 1516, -1, + 1516, 1514, 1517, -1, 1516, 1481, 1505, -1, + 1505, 1481, 1480, -1, 1514, 1513, 1517, -1, + 1517, 1513, 1518, -1, 1513, 1512, 1518, -1, + 1518, 1512, 1519, -1, 1512, 1511, 1519, -1, + 1519, 1511, 1520, -1, 1509, 1508, 1521, -1, + 1521, 1508, 1522, -1, 1521, 1523, 1509, -1, + 1509, 1523, 1510, -1, 1523, 1520, 1510, -1, + 1510, 1520, 1511, -1, 1508, 1507, 1522, -1, + 1522, 1507, 1524, -1, 1507, 1506, 1524, -1, + 1524, 1506, 1515, -1, 529, 448, 92, -1, + 92, 448, 93, -1, 93, 448, 450, -1, + 450, 448, 444, -1, 448, 447, 444, -1, + 444, 447, 471, -1, 471, 447, 474, -1, + 474, 447, 442, -1, 474, 442, 441, -1, + 441, 478, 474, -1, 474, 478, 479, -1, + 474, 479, 361, -1, 361, 364, 474, -1, + 474, 364, 494, -1, 474, 494, 151, -1, + 151, 494, 152, -1, 152, 494, 235, -1, + 235, 494, 193, -1, 193, 494, 192, -1, + 192, 494, 187, -1, 187, 494, 190, -1, + 190, 494, 215, -1, 215, 494, 218, -1, + 218, 494, 221, -1, 221, 494, 222, -1, + 222, 494, 1245, -1, 1245, 494, 1246, -1, + 1246, 494, 54, -1, 54, 494, 55, -1, + 55, 494, 1185, -1, 55, 1185, 580, -1, + 580, 1185, 582, -1, 582, 1185, 583, -1, + 583, 1185, 1124, -1, 583, 1124, 1066, -1, + 583, 1066, 1013, -1, 1013, 1066, 1014, -1, + 1014, 1066, 1022, -1, 1022, 1066, 1017, -1, + 1017, 1066, 1020, -1, 1020, 1066, 1045, -1, + 1045, 1066, 1048, -1, 1048, 1066, 803, -1, + 1066, 959, 803, -1, 803, 959, 798, -1, + 803, 798, 795, -1, 795, 800, 803, -1, + 803, 800, 801, -1, 803, 801, 804, -1, + 804, 801, 810, -1, 810, 801, 811, -1, + 811, 801, 790, -1, 790, 801, 876, -1, + 876, 801, 875, -1, 876, 875, 869, -1, + 876, 869, 822, -1, 822, 869, 820, -1, + 820, 869, 872, -1, 872, 869, 868, -1, + 1363, 1362, 1376, -1, 1376, 1362, 1525, -1, + 1362, 1361, 1525, -1, 1525, 1361, 1526, -1, + 1361, 1357, 1526, -1, 1526, 1357, 1355, -1, + 1527, 1528, 1336, -1, 1336, 1528, 1334, -1, + 1336, 1337, 1527, -1, 1527, 1337, 1529, -1, + 570, 1339, 572, -1, 572, 1339, 1530, -1, + 1339, 1335, 1530, -1, 1530, 1335, 1531, -1, + 1532, 1529, 1338, -1, 1338, 1529, 1337, -1, + 1338, 569, 1532, -1, 1532, 569, 573, -1, + 1533, 1534, 1535, -1, 1535, 1534, 1536, -1, + 1535, 1537, 1533, -1, 1533, 1537, 1538, -1, + 1539, 1540, 1541, -1, 1541, 1540, 1542, -1, + 1541, 1543, 1539, -1, 1539, 1543, 1544, -1, + 1545, 1546, 1547, -1, 1547, 1546, 1548, -1, + 1547, 1549, 1545, -1, 1545, 1549, 1550, -1, + 1549, 1551, 1550, -1, 1550, 1551, 1552, -1, + 1553, 1554, 1555, -1, 1555, 1554, 1556, -1, + 1555, 1557, 1553, -1, 1553, 1557, 1558, -1, + 1554, 1559, 1556, -1, 1556, 1559, 1560, -1, + 1559, 1561, 1560, -1, 1560, 1561, 1562, -1, + 1563, 1564, 1565, -1, 1565, 1564, 1566, -1, + 1565, 1567, 1563, -1, 1563, 1567, 1568, -1, + 1564, 1569, 1566, -1, 1566, 1569, 1570, -1, + 1571, 1572, 1573, -1, 1573, 1572, 1574, -1, + 1573, 1575, 1571, -1, 1571, 1575, 1576, -1, + 1577, 1542, 1578, -1, 1578, 1542, 1540, -1, + 1578, 1576, 1577, -1, 1577, 1576, 1575, -1, + 1576, 1578, 1571, -1, 1571, 1578, 1540, -1, + 1571, 1540, 1539, -1, 1539, 1544, 1571, -1, + 1571, 1544, 1579, -1, 1571, 1579, 1580, -1, + 1580, 1581, 1571, -1, 1571, 1581, 1582, -1, + 1571, 1582, 1583, -1, 1583, 1584, 1571, -1, + 1571, 1584, 1585, -1, 1571, 1585, 1586, -1, + 1586, 1587, 1571, -1, 1571, 1587, 1569, -1, + 1571, 1569, 1564, -1, 1564, 1563, 1571, -1, + 1571, 1563, 1568, -1, 1571, 1568, 1572, -1, + 1572, 1568, 1574, -1, 1574, 1568, 1567, -1, + 1561, 1548, 1562, -1, 1562, 1548, 1546, -1, + 1548, 1561, 1547, -1, 1547, 1561, 1559, -1, + 1547, 1559, 1554, -1, 1547, 1554, 1549, -1, + 1549, 1554, 1551, -1, 1551, 1554, 1588, -1, + 1588, 1554, 1553, -1, 1588, 1553, 1558, -1, + 1558, 1589, 1588, -1, 1588, 1589, 1590, -1, + 1590, 1589, 1591, -1, 1591, 1589, 1592, -1, + 1591, 1592, 1593, -1, 1591, 1593, 1594, -1, + 1594, 1593, 1595, -1, 1594, 1595, 1596, -1, + 1596, 1597, 1594, -1, 1594, 1597, 1598, -1, + 1551, 1588, 1552, -1, 1552, 1588, 1599, -1, + 1557, 1600, 1558, -1, 1558, 1600, 1589, -1, + 1601, 1602, 1603, -1, 1603, 1602, 1604, -1, + 1603, 1605, 1601, -1, 1601, 1605, 1606, -1, + 1605, 1607, 1606, -1, 1606, 1607, 1608, -1, + 1609, 1610, 1611, -1, 1611, 1610, 1612, -1, + 1611, 1613, 1609, -1, 1609, 1613, 1614, -1, + 1615, 1616, 1617, -1, 1617, 1616, 1618, -1, + 1617, 1619, 1615, -1, 1615, 1619, 1620, -1, + 1619, 1621, 1620, -1, 1620, 1621, 1622, -1, + 1623, 1624, 1625, -1, 1625, 1624, 1626, -1, + 1625, 1627, 1623, -1, 1623, 1627, 1628, -1, + 1627, 1625, 1629, -1, 1629, 1625, 1626, -1, + 1629, 1626, 1630, -1, 1630, 1626, 1631, -1, + 1626, 1632, 1631, -1, 1631, 1632, 1633, -1, + 1633, 1632, 1634, -1, 1634, 1632, 1635, -1, + 1635, 1632, 1636, -1, 1636, 1632, 1637, -1, + 1636, 1637, 1638, -1, 1638, 1639, 1636, -1, + 1636, 1639, 1640, -1, 1636, 1640, 1641, -1, + 1641, 1642, 1636, -1, 1636, 1642, 1643, -1, + 1636, 1643, 1644, -1, 1644, 1643, 1645, -1, + 1627, 1629, 1628, -1, 1628, 1629, 1646, -1, + 1647, 1648, 1649, -1, 1649, 1648, 1650, -1, + 1649, 1651, 1647, -1, 1647, 1651, 1652, -1, + 1648, 1653, 1650, -1, 1650, 1653, 1654, -1, + 1655, 1656, 1657, -1, 1657, 1656, 1658, -1, + 1657, 1659, 1655, -1, 1655, 1659, 1660, -1, + 1661, 1660, 1662, -1, 1662, 1660, 1659, -1, + 1662, 1663, 1661, -1, 1661, 1663, 1664, -1, + 1663, 1652, 1664, -1, 1664, 1652, 1651, -1, + 1665, 1666, 1667, -1, 1667, 1666, 1668, -1, + 1667, 896, 1665, -1, 1665, 896, 895, -1, + 1666, 1669, 1668, -1, 1668, 1669, 1670, -1, + 1666, 1665, 1669, -1, 1669, 1665, 895, -1, + 1669, 895, 894, -1, 894, 1671, 1669, -1, + 1669, 1671, 1672, -1, 1669, 1672, 890, -1, + 890, 889, 1669, -1, 1669, 889, 1673, -1, + 1669, 1673, 1674, -1, 1674, 1675, 1669, -1, + 1669, 1675, 1676, -1, 1669, 1676, 1677, -1, + 1677, 1602, 1669, -1, 1669, 1602, 1601, -1, + 1669, 1601, 1606, -1, 1669, 1606, 1678, -1, + 1678, 1606, 1608, -1, 1678, 1608, 1679, -1, + 1680, 1681, 1638, -1, 1638, 1681, 1639, -1, + 1638, 1637, 1680, -1, 1680, 1637, 1682, -1, + 1681, 1683, 1639, -1, 1639, 1683, 1640, -1, + 1683, 1684, 1640, -1, 1640, 1684, 1641, -1, + 1684, 1685, 1641, -1, 1641, 1685, 1642, -1, + 1643, 1642, 1686, -1, 1686, 1642, 1685, -1, + 1686, 1687, 1643, -1, 1643, 1687, 1645, -1, + 1688, 1689, 1644, -1, 1644, 1689, 1636, -1, + 1644, 1645, 1688, -1, 1688, 1645, 1687, -1, + 1689, 1690, 1636, -1, 1636, 1690, 1635, -1, + 890, 1672, 891, -1, 891, 1672, 1691, -1, + 1672, 1671, 1691, -1, 1691, 1671, 1692, -1, + 1671, 894, 1692, -1, 1692, 894, 893, -1, + 1630, 1631, 1693, -1, 1693, 1631, 1694, -1, + 1693, 1646, 1630, -1, 1630, 1646, 1629, -1, + 1624, 1695, 1626, -1, 1626, 1695, 1632, -1, + 1695, 1682, 1632, -1, 1632, 1682, 1637, -1, + 1631, 1633, 1694, -1, 1694, 1633, 1696, -1, + 1633, 1634, 1696, -1, 1696, 1634, 1697, -1, + 1634, 1635, 1697, -1, 1697, 1635, 1690, -1, + 913, 941, 942, -1, 942, 941, 954, -1, + 1085, 1086, 1084, -1, 1084, 1086, 1106, -1, + 1092, 1091, 1120, -1, 1120, 1091, 1100, -1, + 1698, 1699, 1700, -1, 1700, 1699, 1701, -1, + 1700, 1702, 1698, -1, 1698, 1702, 1703, -1, + 1699, 1704, 1701, -1, 1701, 1704, 1705, -1, + 1704, 1706, 1705, -1, 1705, 1706, 1707, -1, + 1706, 1708, 1707, -1, 1707, 1708, 1709, -1, + 1708, 1706, 1710, -1, 1710, 1706, 1704, -1, + 1710, 1704, 1699, -1, 1699, 1698, 1710, -1, + 1710, 1698, 1703, -1, 1710, 1703, 1621, -1, + 1621, 1619, 1710, -1, 1710, 1619, 1711, -1, + 1711, 1619, 1614, -1, 1614, 1619, 1609, -1, + 1619, 1617, 1609, -1, 1609, 1617, 1618, -1, + 1609, 1618, 1712, -1, 1712, 1713, 1609, -1, + 1609, 1713, 1610, -1, 1610, 1713, 1714, -1, + 1714, 1713, 1715, -1, 1714, 1715, 1716, -1, + 1708, 1710, 1709, -1, 1709, 1710, 1717, -1, + 1710, 1711, 1717, -1, 1717, 1711, 1718, -1, + 1711, 1614, 1718, -1, 1718, 1614, 1613, -1, + 1616, 1719, 1618, -1, 1618, 1719, 1712, -1, + 1621, 1703, 1622, -1, 1622, 1703, 1702, -1, + 1720, 1721, 1722, -1, 1722, 1721, 1723, -1, + 1722, 1724, 1720, -1, 1720, 1724, 1725, -1, + 1721, 1726, 1723, -1, 1723, 1726, 1727, -1, + 1728, 1727, 1729, -1, 1729, 1727, 1726, -1, + 1729, 1730, 1728, -1, 1728, 1730, 1731, -1, + 1732, 1725, 1733, -1, 1733, 1725, 1724, -1, + 1733, 1734, 1732, -1, 1732, 1734, 1735, -1, + 1734, 1736, 1735, -1, 1735, 1736, 1737, -1, + 1736, 1738, 1737, -1, 1737, 1738, 1739, -1, + 1737, 1739, 1735, -1, 1735, 1739, 1732, -1, + 1732, 1739, 1725, -1, 1725, 1739, 1720, -1, + 1720, 1739, 1721, -1, 1721, 1739, 1726, -1, + 1726, 1739, 1729, -1, 1729, 1739, 1730, -1, + 1730, 1739, 1740, -1, 1740, 1739, 1653, -1, + 1740, 1653, 1648, -1, 1648, 1647, 1740, -1, + 1740, 1647, 1652, -1, 1740, 1652, 1663, -1, + 1663, 1662, 1740, -1, 1740, 1662, 1659, -1, + 1740, 1659, 1657, -1, 1657, 1658, 1740, -1, + 1738, 1654, 1739, -1, 1739, 1654, 1653, -1, + 1730, 1740, 1731, -1, 1731, 1740, 1741, -1, + 1740, 1658, 1741, -1, 1741, 1658, 1656, -1, + 1742, 1743, 1679, -1, 1679, 1743, 1678, -1, + 1679, 1608, 1742, -1, 1742, 1608, 1607, -1, + 1743, 1670, 1678, -1, 1678, 1670, 1669, -1, + 1172, 1179, 1173, -1, 1173, 1179, 1177, -1, + 1174, 1744, 1175, -1, 1175, 1744, 1745, -1, + 1602, 1677, 1604, -1, 1604, 1677, 1746, -1, + 1677, 1676, 1746, -1, 1746, 1676, 1747, -1, + 1676, 1675, 1747, -1, 1747, 1675, 1748, -1, + 1675, 1674, 1748, -1, 1748, 1674, 1749, -1, + 1674, 1673, 1749, -1, 1749, 1673, 1750, -1, + 1673, 889, 1750, -1, 1750, 889, 1180, -1, + 1751, 1752, 1597, -1, 1597, 1752, 1598, -1, + 1597, 1596, 1751, -1, 1751, 1596, 1753, -1, + 1754, 1755, 1594, -1, 1594, 1755, 1591, -1, + 1594, 1598, 1754, -1, 1754, 1598, 1752, -1, + 1596, 1595, 1753, -1, 1753, 1595, 1756, -1, + 1595, 1593, 1756, -1, 1756, 1593, 1757, -1, + 1593, 1592, 1757, -1, 1757, 1592, 1758, -1, + 1755, 1759, 1591, -1, 1591, 1759, 1590, -1, + 1759, 1599, 1590, -1, 1590, 1599, 1588, -1, + 1592, 1589, 1758, -1, 1758, 1589, 1600, -1, + 1543, 1760, 1544, -1, 1544, 1760, 1579, -1, + 1760, 1761, 1579, -1, 1579, 1761, 1580, -1, + 1761, 1762, 1580, -1, 1580, 1762, 1581, -1, + 1762, 1763, 1581, -1, 1581, 1763, 1582, -1, + 1763, 1764, 1582, -1, 1582, 1764, 1583, -1, + 1764, 1765, 1583, -1, 1583, 1765, 1584, -1, + 1765, 1766, 1584, -1, 1584, 1766, 1585, -1, + 1766, 1767, 1585, -1, 1585, 1767, 1586, -1, + 1767, 1768, 1586, -1, 1586, 1768, 1587, -1, + 1768, 1570, 1587, -1, 1587, 1570, 1569, -1, + 1122, 1185, 1294, -1, 1294, 1185, 1293, -1, + 1185, 494, 1293, -1, 1293, 494, 1184, -1, + 1769, 1770, 1771, -1, 1771, 1770, 1772, -1, + 1771, 1538, 1769, -1, 1769, 1538, 1537, -1, + 1773, 1774, 1775, -1, 1775, 1774, 1776, -1, + 1775, 1777, 1773, -1, 1773, 1777, 1778, -1, + 1777, 1745, 1778, -1, 1778, 1745, 1744, -1, + 1770, 1779, 1772, -1, 1772, 1779, 1780, -1, + 1779, 1781, 1780, -1, 1780, 1781, 1782, -1, + 1781, 1783, 1782, -1, 1782, 1783, 1784, -1, + 1782, 1784, 1780, -1, 1780, 1784, 1772, -1, + 1784, 1785, 1772, -1, 1772, 1785, 1774, -1, + 1772, 1774, 1773, -1, 1773, 1778, 1772, -1, + 1772, 1778, 1771, -1, 1771, 1778, 1538, -1, + 1538, 1778, 1533, -1, 1778, 1744, 1533, -1, + 1533, 1744, 1174, -1, 1533, 1174, 1173, -1, + 1173, 1177, 1533, -1, 1533, 1177, 1176, -1, + 1533, 1176, 1786, -1, 1786, 1787, 1533, -1, + 1533, 1787, 1534, -1, 1787, 1788, 1534, -1, + 1783, 1789, 1784, -1, 1784, 1789, 1785, -1, + 1789, 1776, 1785, -1, 1785, 1776, 1774, -1, + 1790, 1791, 1716, -1, 1716, 1791, 1714, -1, + 1716, 1715, 1790, -1, 1790, 1715, 1792, -1, + 1791, 1612, 1714, -1, 1714, 1612, 1610, -1, + 1715, 1713, 1792, -1, 1792, 1713, 1793, -1, + 1713, 1712, 1793, -1, 1793, 1712, 1719, -1, + 1534, 1788, 1536, -1, 1536, 1788, 1794, -1, + 1788, 1787, 1794, -1, 1794, 1787, 1795, -1, + 1787, 1786, 1795, -1, 1795, 1786, 1796, -1, + 1786, 1176, 1796, -1, 1796, 1176, 1243, -1, + 1323, 1329, 1324, -1, 1324, 1329, 1797, -1, + 1329, 1330, 1797, -1, 1797, 1330, 1798, -1, + 1330, 1331, 1798, -1, 1798, 1331, 1799, -1, + 1800, 1799, 1332, -1, 1332, 1799, 1331, -1, + 1332, 1333, 1800, -1, 1800, 1333, 1801, -1, + 1333, 1334, 1801, -1, 1801, 1334, 1528, -1, + 1254, 1531, 1, -1, 1, 1531, 1335, -1, + 1344, 1349, 1345, -1, 1345, 1349, 1347, -1, + 1350, 1369, 1351, -1, 1351, 1369, 1377, -1, + 1267, 1383, 4, -1, 4, 1383, 1382, -1, + 1392, 1802, 1393, -1, 1393, 1802, 1495, -1, + 1803, 1268, 1494, -1, 1494, 1268, 8, -1, + 1494, 1498, 1803, -1, 1803, 1498, 1804, -1, + 1498, 1497, 1804, -1, 1804, 1497, 1805, -1, + 1497, 1496, 1805, -1, 1805, 1496, 1806, -1, + 1496, 1495, 1806, -1, 1806, 1495, 1802, -1, + 1435, 1403, 1438, -1, 1438, 1403, 1401, -1, + 1301, 1302, 1318, -1, 1318, 1302, 1807, -1, + 1302, 1303, 1807, -1, 1807, 1303, 1808, -1, + 1303, 1304, 1808, -1, 1808, 1304, 1809, -1, + 1304, 1305, 1809, -1, 1809, 1305, 1810, -1, + 1305, 1306, 1810, -1, 1810, 1306, 1811, -1, + 1812, 1811, 1307, -1, 1307, 1811, 1306, -1, + 1307, 1308, 1812, -1, 1812, 1308, 1813, -1, + 1308, 1309, 1813, -1, 1813, 1309, 1814, -1, + 1296, 1815, 1298, -1, 1298, 1815, 1310, -1, + 1815, 1816, 1310, -1, 1310, 1816, 1311, -1, + 1816, 1817, 1311, -1, 1311, 1817, 1312, -1, + 1817, 1818, 1312, -1, 1312, 1818, 1313, -1, + 1818, 1819, 1313, -1, 1313, 1819, 1314, -1, + 1820, 1814, 1315, -1, 1315, 1814, 1309, -1, + 1315, 1316, 1820, -1, 1820, 1316, 1821, -1, + 1822, 1821, 1317, -1, 1317, 1821, 1316, -1, + 1317, 1314, 1822, -1, 1822, 1314, 1819, -1, + 19, 13, 20, -1, 20, 13, 41, -1, + 40, 44, 45, -1, 45, 44, 1287, -1, + 38, 46, 47, -1, 47, 46, 1285, -1, + 74, 77, 75, -1, 75, 77, 438, -1, + 100, 102, 99, -1, 99, 102, 1262, -1, + 111, 110, 112, -1, 112, 110, 459, -1, + 157, 201, 202, -1, 202, 201, 208, -1, + 253, 1823, 251, -1, 251, 1823, 523, -1, + 235, 234, 152, -1, 152, 234, 236, -1, + 324, 325, 323, -1, 323, 325, 334, -1, + 325, 324, 326, -1, 326, 324, 352, -1, + 327, 326, 328, -1, 328, 326, 351, -1, + 320, 229, 354, -1, 354, 229, 1278, -1, + 203, 1824, 156, -1, 156, 1824, 154, -1, + 367, 384, 366, -1, 366, 384, 589, -1, + 375, 374, 376, -1, 376, 374, 599, -1, + 404, 427, 429, -1, 429, 427, 432, -1, + 468, 467, 470, -1, 470, 467, 101, -1, + 470, 469, 468, -1, 468, 469, 122, -1, + 96, 528, 450, -1, 450, 528, 93, -1, + 549, 551, 548, -1, 548, 551, 1264, -1, + 394, 1825, 370, -1, 370, 1825, 368, -1, + 588, 586, 589, -1, 589, 586, 366, -1, + 593, 595, 592, -1, 592, 595, 1107, -1, + 658, 655, 673, -1, 673, 655, 675, -1, + 704, 722, 721, -1, 721, 722, 728, -1, + 722, 726, 728, -1, 728, 726, 744, -1, + 763, 765, 762, -1, 762, 765, 878, -1, + 767, 774, 772, -1, 772, 774, 751, -1, + 808, 807, 810, -1, 810, 807, 804, -1, + 819, 820, 817, -1, 817, 820, 872, -1, + 821, 825, 820, -1, 820, 825, 822, -1, + 845, 867, 866, -1, 866, 867, 680, -1, + 843, 880, 879, -1, 879, 880, 760, -1, + 887, 827, 1826, -1, 1826, 827, 829, -1, + 911, 910, 912, -1, 912, 910, 934, -1, + 916, 918, 915, -1, 915, 918, 940, -1, + 962, 966, 963, -1, 963, 966, 1057, -1, + 661, 1074, 1073, -1, 1073, 1074, 1083, -1, + 669, 1078, 1077, -1, 1077, 1078, 1092, -1, + 673, 675, 1079, -1, 1079, 675, 1094, -1, + 1086, 1085, 1087, -1, 1087, 1085, 1075, -1, + 1089, 1120, 1088, -1, 1088, 1120, 1102, -1, + 1102, 1099, 1103, -1, 1103, 1099, 588, -1, + 1208, 1206, 1827, -1, 1827, 1206, 1242, -1, + 1192, 1217, 1218, -1, 1218, 1217, 27, -1, + 1274, 1284, 1285, -1, 1285, 1284, 47, -1, + 43, 1828, 42, -1, 42, 1828, 1290, -1, + 1723, 1829, 1722, -1, 1722, 1829, 1724, -1, + 1724, 1829, 1733, -1, 1733, 1829, 1734, -1, + 1734, 1829, 769, -1, 769, 1829, 1168, -1, + 1168, 1829, 1167, -1, 1167, 1829, 1169, -1, + 1169, 1829, 1146, -1, 1146, 1829, 1147, -1, + 1147, 1829, 626, -1, 626, 1829, 627, -1, + 627, 1829, 625, -1, 625, 1829, 628, -1, + 628, 1829, 629, -1, 629, 1829, 1055, -1, + 1055, 1829, 1136, -1, 1136, 1829, 1052, -1, + 1052, 1829, 1051, -1, 1051, 1829, 1135, -1, + 1135, 1829, 1036, -1, 1036, 1829, 1134, -1, + 1734, 769, 1736, -1, 1736, 769, 1738, -1, + 769, 768, 1738, -1, 1738, 768, 1654, -1, + 1654, 768, 1650, -1, 1650, 768, 1649, -1, + 1649, 768, 1651, -1, 1651, 768, 1830, -1, + 1651, 1830, 1664, -1, 1664, 1830, 1661, -1, + 1661, 1830, 1660, -1, 1660, 1830, 1655, -1, + 1655, 1830, 1656, -1, 1656, 1830, 1741, -1, + 768, 770, 1830, -1, 1830, 770, 771, -1, + 1830, 771, 812, -1, 812, 748, 1830, -1, + 1830, 748, 1831, -1, 1830, 1831, 892, -1, + 892, 1831, 893, -1, 893, 1831, 1692, -1, + 1692, 1831, 1832, -1, 1692, 1832, 1691, -1, + 1691, 1832, 891, -1, 891, 1832, 888, -1, + 888, 1832, 1833, -1, 888, 1833, 1180, -1, + 1180, 1833, 1750, -1, 1750, 1833, 1749, -1, + 1749, 1833, 1748, -1, 1748, 1833, 1747, -1, + 1747, 1833, 1834, -1, 1747, 1834, 1746, -1, + 1746, 1834, 1604, -1, 1604, 1834, 1603, -1, + 1603, 1834, 1835, -1, 1603, 1835, 1605, -1, + 1605, 1835, 1607, -1, 1607, 1835, 1742, -1, + 1742, 1835, 1743, -1, 892, 896, 1830, -1, + 1830, 896, 1667, -1, 1830, 1667, 1668, -1, + 1668, 1670, 1830, -1, 1830, 1670, 1743, -1, + 1830, 1743, 1835, -1, 1830, 1835, 1741, -1, + 1741, 1835, 1731, -1, 1731, 1835, 1728, -1, + 1728, 1835, 1727, -1, 1727, 1835, 1723, -1, + 1723, 1835, 1829, -1, 748, 747, 1831, -1, + 1831, 747, 897, -1, 1831, 897, 899, -1, + 899, 898, 1831, -1, 1831, 898, 900, -1, + 1831, 900, 887, -1, 887, 1826, 1831, -1, + 1831, 1826, 829, -1, 1831, 829, 1832, -1, + 1832, 829, 853, -1, 1832, 853, 852, -1, + 852, 815, 1832, -1, 1832, 815, 1836, -1, + 1832, 1836, 1837, -1, 1837, 1836, 1690, -1, + 1837, 1690, 1689, -1, 1689, 1688, 1837, -1, + 1837, 1688, 1687, -1, 1837, 1687, 1686, -1, + 1686, 1685, 1837, -1, 1837, 1685, 1838, -1, + 1837, 1838, 1839, -1, 1839, 1838, 855, -1, + 1839, 855, 854, -1, 854, 947, 1839, -1, + 1839, 947, 946, -1, 1839, 946, 949, -1, + 949, 948, 1839, -1, 1839, 948, 1068, -1, + 1839, 1068, 1069, -1, 1069, 1070, 1839, -1, + 1839, 1070, 1071, -1, 1839, 1071, 654, -1, + 654, 652, 1839, -1, 1839, 652, 651, -1, + 1839, 651, 1097, -1, 855, 1838, 857, -1, + 857, 1838, 677, -1, 677, 1838, 678, -1, + 678, 1838, 936, -1, 936, 1838, 907, -1, + 907, 1838, 908, -1, 908, 1838, 906, -1, + 906, 1838, 735, -1, 735, 1838, 905, -1, + 905, 1838, 713, -1, 713, 1838, 714, -1, + 714, 1838, 1680, -1, 714, 1680, 1682, -1, + 1682, 1695, 714, -1, 714, 1695, 904, -1, + 1695, 1624, 904, -1, 904, 1624, 710, -1, + 1624, 1623, 710, -1, 710, 1623, 711, -1, + 1623, 1628, 711, -1, 711, 1628, 1836, -1, + 711, 1836, 903, -1, 903, 1836, 686, -1, + 686, 1836, 684, -1, 684, 1836, 685, -1, + 685, 1836, 858, -1, 858, 1836, 814, -1, + 815, 814, 1836, -1, 1628, 1646, 1836, -1, + 1836, 1646, 1693, -1, 1836, 1693, 1694, -1, + 1694, 1696, 1836, -1, 1836, 1696, 1697, -1, + 1836, 1697, 1690, -1, 1680, 1838, 1681, -1, + 1681, 1838, 1683, -1, 1683, 1838, 1684, -1, + 1684, 1838, 1685, -1, 1839, 1097, 1762, -1, + 1762, 1097, 1763, -1, 1763, 1097, 1764, -1, + 1764, 1097, 1765, -1, 1097, 1181, 1765, -1, + 1765, 1181, 1766, -1, 1181, 1119, 1766, -1, + 1766, 1119, 1767, -1, 1119, 1118, 1767, -1, + 1767, 1118, 1768, -1, 1762, 1761, 1839, -1, + 1839, 1761, 1760, -1, 1839, 1760, 1543, -1, + 1543, 1541, 1839, -1, 1839, 1541, 1840, -1, + 1839, 1840, 1837, -1, 1837, 1840, 1599, -1, + 1837, 1599, 1759, -1, 1759, 1755, 1837, -1, + 1837, 1755, 1754, -1, 1837, 1754, 1752, -1, + 1752, 1751, 1837, -1, 1837, 1751, 1753, -1, + 1837, 1753, 1841, -1, 1841, 1753, 1756, -1, + 1841, 1756, 1757, -1, 1757, 1758, 1841, -1, + 1841, 1758, 1600, -1, 1841, 1600, 1842, -1, + 1842, 1600, 1557, -1, 1842, 1557, 1555, -1, + 1555, 1556, 1842, -1, 1842, 1556, 1560, -1, + 1842, 1560, 1840, -1, 1840, 1560, 1562, -1, + 1840, 1562, 1546, -1, 1546, 1545, 1840, -1, + 1840, 1545, 1550, -1, 1840, 1550, 1552, -1, + 1599, 1840, 1552, -1, 1837, 1841, 1832, -1, + 1832, 1841, 1833, -1, 1541, 1542, 1840, -1, + 1840, 1542, 1577, -1, 1840, 1577, 1575, -1, + 1575, 1573, 1840, -1, 1840, 1573, 1574, -1, + 1840, 1574, 1843, -1, 1843, 1574, 1567, -1, + 1843, 1567, 1565, -1, 1565, 1566, 1843, -1, + 1843, 1566, 1570, -1, 1843, 1570, 1768, -1, + 1768, 1118, 1843, -1, 1843, 1118, 1117, -1, + 1843, 1117, 1116, -1, 1116, 1182, 1843, -1, + 1843, 1182, 1183, -1, 1843, 1183, 604, -1, + 604, 605, 1843, -1, 1843, 605, 579, -1, + 1843, 579, 1844, -1, 1844, 579, 578, -1, + 1844, 578, 577, -1, 577, 368, 1844, -1, + 1844, 368, 1845, -1, 1844, 1845, 1530, -1, + 1530, 1845, 572, -1, 572, 1845, 571, -1, + 571, 1845, 1846, -1, 571, 1846, 573, -1, + 573, 1846, 1532, -1, 1532, 1846, 1529, -1, + 1529, 1846, 1527, -1, 1527, 1846, 1528, -1, + 1528, 1846, 1847, -1, 1528, 1847, 1801, -1, + 1801, 1847, 1800, -1, 1800, 1847, 1799, -1, + 1799, 1847, 1798, -1, 1530, 1531, 1844, -1, + 1844, 1531, 1254, -1, 1844, 1254, 0, -1, + 368, 1825, 1845, -1, 1845, 1825, 394, -1, + 1845, 394, 576, -1, 576, 491, 1845, -1, + 1845, 491, 575, -1, 1845, 575, 401, -1, + 401, 574, 1845, -1, 1845, 574, 403, -1, + 1845, 403, 1846, -1, 1846, 403, 568, -1, + 1846, 568, 428, -1, 428, 567, 1846, -1, + 1846, 567, 430, -1, 1846, 430, 1355, -1, + 1355, 430, 1526, -1, 1526, 430, 1525, -1, + 1525, 430, 1376, -1, 1376, 430, 1373, -1, + 1373, 430, 566, -1, 1373, 566, 88, -1, + 1373, 88, 1372, -1, 1372, 88, 87, -1, + 1372, 87, 1374, -1, 1374, 87, 85, -1, + 1374, 85, 1375, -1, 1375, 85, 86, -1, + 1375, 86, 89, -1, 1375, 89, 1377, -1, + 1377, 89, 91, -1, 1377, 91, 90, -1, + 90, 565, 1377, -1, 1377, 565, 564, -1, + 1377, 564, 534, -1, 1377, 534, 1351, -1, + 1351, 534, 1847, -1, 1351, 1847, 1346, -1, + 1346, 1847, 1347, -1, 1347, 1847, 1345, -1, + 1345, 1847, 1340, -1, 1847, 1846, 1340, -1, + 1340, 1846, 1341, -1, 1341, 1846, 1352, -1, + 1352, 1846, 1371, -1, 1371, 1846, 1370, -1, + 1370, 1846, 1359, -1, 1359, 1846, 1354, -1, + 1354, 1846, 1355, -1, 534, 533, 1847, -1, + 1847, 533, 1255, -1, 1847, 1255, 115, -1, + 115, 114, 1847, -1, 1847, 114, 116, -1, + 1847, 116, 1266, -1, 1840, 1843, 1842, -1, + 1842, 1843, 1844, -1, 1842, 1844, 1848, -1, + 1848, 1844, 1849, -1, 1848, 1849, 1850, -1, + 1850, 1849, 1851, -1, 1850, 1851, 1852, -1, + 1852, 1851, 1853, -1, 1852, 1853, 1854, -1, + 1854, 1853, 1855, -1, 1854, 1855, 1856, -1, + 1856, 1855, 1857, -1, 1856, 1857, 1475, -1, + 1475, 1857, 1474, -1, 1474, 1857, 1455, -1, + 1455, 1857, 1450, -1, 1450, 1857, 1451, -1, + 1451, 1857, 1467, -1, 1467, 1857, 1465, -1, + 1465, 1857, 175, -1, 1465, 175, 1463, -1, + 1463, 175, 358, -1, 1463, 358, 154, -1, + 1463, 154, 1459, -1, 1459, 154, 1824, -1, + 1459, 1824, 1458, -1, 1458, 1824, 1460, -1, + 1824, 203, 1460, -1, 1460, 203, 357, -1, + 1460, 357, 1449, -1, 1449, 357, 1447, -1, + 357, 206, 1447, -1, 1447, 206, 356, -1, + 1447, 356, 1443, -1, 1443, 356, 355, -1, + 1443, 355, 301, -1, 301, 280, 1443, -1, + 1443, 280, 1442, -1, 1442, 280, 1444, -1, + 1444, 280, 1856, -1, 1444, 1856, 1477, -1, + 1477, 1856, 1478, -1, 1478, 1856, 1479, -1, + 1479, 1856, 1476, -1, 1856, 1475, 1476, -1, + 280, 279, 1856, -1, 1856, 279, 302, -1, + 1856, 302, 342, -1, 342, 343, 1856, -1, + 1856, 343, 1858, -1, 1856, 1858, 1429, -1, + 1429, 1858, 1415, -1, 1415, 1858, 1412, -1, + 1412, 1858, 1411, -1, 1411, 1858, 1409, -1, + 1409, 1858, 1407, -1, 1407, 1858, 1405, -1, + 1405, 1858, 1859, -1, 1405, 1859, 1400, -1, + 1400, 1859, 1401, -1, 1401, 1859, 1438, -1, + 1438, 1859, 1436, -1, 1429, 1428, 1856, -1, + 1856, 1428, 1425, -1, 1856, 1425, 1424, -1, + 1424, 1422, 1856, -1, 1856, 1422, 1417, -1, + 1856, 1417, 1416, -1, 1856, 1416, 1854, -1, + 1854, 1416, 1421, -1, 1854, 1421, 1439, -1, + 1439, 1437, 1854, -1, 1854, 1437, 1436, -1, + 1854, 1436, 1859, -1, 1854, 1859, 1852, -1, + 1852, 1859, 1860, -1, 1852, 1860, 1850, -1, + 1850, 1860, 1861, -1, 1850, 1861, 1848, -1, + 1848, 1861, 1862, -1, 1848, 1862, 1842, -1, + 1842, 1862, 1841, -1, 1841, 1862, 1833, -1, + 1833, 1862, 1834, -1, 1862, 1861, 1834, -1, + 1834, 1861, 1863, -1, 1834, 1863, 1178, -1, + 1178, 1863, 1243, -1, 1243, 1863, 1796, -1, + 1796, 1863, 1795, -1, 1795, 1863, 1794, -1, + 1794, 1863, 1536, -1, 1536, 1863, 1535, -1, + 1535, 1863, 1864, -1, 1535, 1864, 1537, -1, + 1537, 1864, 1769, -1, 1769, 1864, 1770, -1, + 1770, 1864, 1779, -1, 1178, 1179, 1834, -1, + 1834, 1179, 1835, -1, 1179, 1172, 1835, -1, + 1835, 1172, 1171, -1, 1835, 1171, 1865, -1, + 1865, 1171, 1175, -1, 1865, 1175, 1745, -1, + 1745, 1777, 1865, -1, 1865, 1777, 1775, -1, + 1865, 1775, 1776, -1, 1861, 1860, 1863, -1, + 1863, 1860, 1864, -1, 1860, 1859, 1864, -1, + 1864, 1859, 1866, -1, 1864, 1866, 1210, -1, + 1210, 1866, 1252, -1, 1252, 1866, 1250, -1, + 1250, 1866, 1251, -1, 1251, 1866, 16, -1, + 16, 1866, 15, -1, 15, 1866, 14, -1, + 14, 1866, 1810, -1, 14, 1810, 1811, -1, + 14, 1811, 1269, -1, 1269, 1811, 1812, -1, + 1269, 1812, 43, -1, 43, 1812, 1813, -1, + 43, 1813, 1828, -1, 1828, 1813, 1814, -1, + 1828, 1814, 1290, -1, 1290, 1814, 1820, -1, + 1290, 1820, 1291, -1, 1291, 1820, 1821, -1, + 1291, 1821, 1289, -1, 1289, 1821, 1822, -1, + 1289, 1822, 1292, -1, 1292, 1822, 1270, -1, + 1822, 1819, 1270, -1, 1270, 1819, 347, -1, + 347, 1819, 346, -1, 346, 1819, 1818, -1, + 346, 1818, 1858, -1, 1858, 1818, 1817, -1, + 1858, 1817, 1816, -1, 1816, 1815, 1858, -1, + 1858, 1815, 1296, -1, 1858, 1296, 1295, -1, + 1295, 1300, 1858, -1, 1858, 1300, 1866, -1, + 1858, 1866, 1859, -1, 1300, 1318, 1866, -1, + 1866, 1318, 1807, -1, 1866, 1807, 1808, -1, + 1808, 1809, 1866, -1, 1866, 1809, 1810, -1, + 346, 1858, 345, -1, 345, 1858, 344, -1, + 344, 1858, 331, -1, 331, 1858, 343, -1, + 1210, 1209, 1864, -1, 1864, 1209, 1208, -1, + 1864, 1208, 1827, -1, 175, 1857, 359, -1, + 359, 1857, 275, -1, 275, 1857, 276, -1, + 276, 1857, 274, -1, 274, 1857, 277, -1, + 277, 1857, 255, -1, 1857, 1855, 255, -1, + 255, 1855, 254, -1, 254, 1855, 253, -1, + 253, 1855, 1823, -1, 1844, 0, 1849, -1, + 1849, 0, 1253, -1, 1849, 1253, 1327, -1, + 1327, 1328, 1849, -1, 1849, 1328, 1320, -1, + 1849, 1320, 1319, -1, 1849, 1319, 1851, -1, + 1851, 1319, 1324, -1, 1851, 1324, 1797, -1, + 1797, 1798, 1851, -1, 1851, 1798, 1847, -1, + 1851, 1847, 10, -1, 10, 1847, 9, -1, + 9, 1847, 3, -1, 3, 1847, 1867, -1, + 3, 1867, 1267, -1, 1267, 1867, 1383, -1, + 1383, 1867, 1378, -1, 1378, 1867, 1379, -1, + 1379, 1867, 1489, -1, 1489, 1867, 1868, -1, + 1489, 1868, 1490, -1, 1490, 1868, 1492, -1, + 1492, 1868, 1387, -1, 1387, 1868, 1386, -1, + 1847, 1266, 1867, -1, 1867, 1266, 527, -1, + 1867, 527, 526, -1, 10, 6, 1851, -1, + 1851, 6, 1853, -1, 6, 1268, 1853, -1, + 1853, 1268, 1803, -1, 1853, 1803, 1804, -1, + 1804, 1805, 1853, -1, 1853, 1805, 1806, -1, + 1853, 1806, 1802, -1, 1853, 1802, 1855, -1, + 1855, 1802, 1392, -1, 1855, 1392, 1390, -1, + 1390, 1388, 1855, -1, 1855, 1388, 1386, -1, + 1855, 1386, 1868, -1, 1855, 1868, 1823, -1, + 1823, 1868, 523, -1, 523, 1868, 521, -1, + 521, 1868, 522, -1, 522, 1868, 517, -1, + 517, 1868, 518, -1, 518, 1868, 519, -1, + 519, 1868, 119, -1, 119, 1868, 120, -1, + 120, 1868, 1482, -1, 120, 1482, 1398, -1, + 120, 1398, 141, -1, 141, 1398, 1396, -1, + 141, 1396, 140, -1, 140, 1396, 1397, -1, + 140, 1397, 497, -1, 497, 1397, 1481, -1, + 497, 1481, 524, -1, 524, 1481, 1516, -1, + 524, 1516, 1517, -1, 524, 1517, 455, -1, + 455, 1517, 525, -1, 1517, 1518, 525, -1, + 525, 1518, 526, -1, 1518, 1519, 526, -1, + 526, 1519, 1520, -1, 526, 1520, 1523, -1, + 1523, 1521, 526, -1, 526, 1521, 1867, -1, + 1521, 1522, 1867, -1, 1867, 1522, 1524, -1, + 1867, 1524, 1515, -1, 1515, 1503, 1867, -1, + 1867, 1503, 1501, -1, 1867, 1501, 1499, -1, + 1867, 1499, 1868, -1, 1868, 1499, 1486, -1, + 1868, 1486, 1484, -1, 1868, 1484, 1482, -1, + 1864, 1827, 1869, -1, 1869, 1827, 1242, -1, + 1869, 1242, 1228, -1, 1228, 1241, 1869, -1, + 1869, 1241, 1230, -1, 1869, 1230, 1240, -1, + 1240, 1239, 1869, -1, 1869, 1239, 631, -1, + 1869, 631, 630, -1, 1864, 1869, 1779, -1, + 1779, 1869, 1781, -1, 1781, 1869, 1783, -1, + 1783, 1869, 1789, -1, 1789, 1869, 1776, -1, + 1776, 1869, 1865, -1, 1865, 1869, 1613, -1, + 1613, 1869, 1718, -1, 1718, 1869, 1717, -1, + 1717, 1869, 1709, -1, 1709, 1869, 1707, -1, + 1707, 1869, 630, -1, 1707, 630, 1705, -1, + 1705, 630, 1132, -1, 1705, 1132, 1701, -1, + 1701, 1132, 1130, -1, 1701, 1130, 1131, -1, + 1701, 1131, 1700, -1, 1700, 1131, 1702, -1, + 1131, 1001, 1702, -1, 1702, 1001, 1622, -1, + 1613, 1611, 1865, -1, 1865, 1611, 1612, -1, + 1865, 1612, 1791, -1, 1791, 1790, 1865, -1, + 1865, 1790, 1792, -1, 1865, 1792, 1793, -1, + 1793, 1870, 1865, -1, 1865, 1870, 1835, -1, + 1835, 1870, 1829, -1, 1829, 1870, 1134, -1, + 1134, 1870, 1032, -1, 1032, 1870, 1033, -1, + 1033, 1870, 1133, -1, 1133, 1870, 999, -1, + 999, 1870, 1000, -1, 1000, 1870, 1001, -1, + 1001, 1870, 1622, -1, 1622, 1870, 1620, -1, + 1620, 1870, 1615, -1, 1615, 1870, 1616, -1, + 1616, 1870, 1719, -1, 1719, 1870, 1793, -1 ] + normalIndex [ 0, 0, 0, -1, 1, 1, 1, -1, + 2, 2, 2, -1, 3, 3, 3, -1, + 4, 4, 4, -1, 5, 5, 5, -1, + 6, 6, 6, -1, 7, 7, 7, -1, + 8, 8, 8, -1, 9, 9, 9, -1, + 10, 10, 10, -1, 11, 11, 11, -1, + 12, 12, 12, -1, 13, 13, 13, -1, + 14, 14, 14, -1, 15, 15, 15, -1, + 16, 16, 16, -1, 17, 17, 17, -1, + 18, 18, 18, -1, 19, 19, 19, -1, + 20, 20, 20, -1, 21, 21, 21, -1, + 22, 22, 22, -1, 23, 23, 23, -1, + 24, 24, 24, -1, 25, 25, 25, -1, + 26, 26, 26, -1, 27, 27, 27, -1, + 28, 28, 28, -1, 29, 29, 29, -1, + 30, 30, 30, -1, 31, 31, 31, -1, + 32, 32, 32, -1, 33, 33, 33, -1, + 34, 34, 34, -1, 35, 35, 35, -1, + 36, 36, 36, -1, 37, 37, 37, -1, + 38, 38, 38, -1, 39, 39, 39, -1, + 40, 40, 40, -1, 41, 41, 41, -1, + 42, 42, 42, -1, 43, 43, 43, -1, + 44, 44, 44, -1, 45, 45, 45, -1, + 46, 46, 46, -1, 47, 47, 47, -1, + 48, 48, 48, -1, 49, 49, 49, -1, + 50, 50, 50, -1, 51, 51, 51, -1, + 52, 52, 52, -1, 53, 53, 53, -1, + 54, 54, 54, -1, 55, 55, 55, -1, + 56, 56, 56, -1, 57, 57, 57, -1, + 58, 58, 58, -1, 59, 59, 59, -1, + 60, 60, 60, -1, 61, 61, 61, -1, + 62, 62, 62, -1, 63, 63, 63, -1, + 64, 64, 64, -1, 65, 65, 65, -1, + 66, 66, 66, -1, 67, 67, 67, -1, + 68, 68, 68, -1, 69, 69, 69, -1, + 70, 70, 70, -1, 71, 71, 71, -1, + 72, 72, 72, -1, 73, 73, 73, -1, + 74, 74, 74, -1, 75, 75, 75, -1, + 76, 76, 76, -1, 77, 77, 77, -1, + 78, 78, 78, -1, 79, 79, 79, -1, + 80, 80, 80, -1, 81, 81, 81, -1, + 82, 82, 82, -1, 83, 83, 83, -1, + 84, 84, 84, -1, 85, 85, 85, -1, + 86, 86, 86, -1, 87, 87, 87, -1, + 88, 88, 88, -1, 89, 89, 89, -1, + 90, 90, 90, -1, 91, 91, 91, -1, + 92, 92, 92, -1, 93, 93, 93, -1, + 94, 94, 94, -1, 95, 95, 95, -1, + 96, 96, 96, -1, 97, 97, 97, -1, + 98, 98, 98, -1, 99, 99, 99, -1, + 100, 100, 100, -1, 101, 101, 101, -1, + 102, 102, 102, -1, 103, 103, 103, -1, + 104, 104, 104, -1, 105, 105, 105, -1, + 106, 106, 106, -1, 107, 107, 107, -1, + 108, 108, 108, -1, 109, 109, 109, -1, + 110, 110, 110, -1, 111, 111, 111, -1, + 112, 112, 112, -1, 113, 113, 113, -1, + 114, 114, 114, -1, 115, 115, 115, -1, + 116, 116, 116, -1, 117, 117, 117, -1, + 118, 118, 118, -1, 119, 119, 119, -1, + 120, 120, 120, -1, 121, 121, 121, -1, + 122, 122, 122, -1, 123, 123, 123, -1, + 124, 124, 124, -1, 125, 125, 125, -1, + 126, 126, 126, -1, 127, 127, 127, -1, + 128, 128, 128, -1, 129, 129, 129, -1, + 130, 130, 130, -1, 131, 131, 131, -1, + 132, 132, 132, -1, 133, 133, 133, -1, + 134, 134, 134, -1, 135, 135, 135, -1, + 136, 136, 136, -1, 137, 137, 137, -1, + 138, 138, 138, -1, 139, 139, 139, -1, + 140, 140, 140, -1, 141, 141, 141, -1, + 142, 142, 142, -1, 143, 143, 143, -1, + 144, 144, 144, -1, 145, 145, 145, -1, + 146, 146, 146, -1, 147, 147, 147, -1, + 148, 148, 148, -1, 149, 149, 149, -1, + 150, 150, 150, -1, 151, 151, 151, -1, + 152, 152, 152, -1, 153, 153, 153, -1, + 154, 154, 154, -1, 155, 155, 155, -1, + 156, 156, 156, -1, 157, 157, 157, -1, + 158, 158, 158, -1, 159, 159, 159, -1, + 160, 160, 160, -1, 161, 161, 161, -1, + 162, 162, 162, -1, 163, 163, 163, -1, + 164, 164, 164, -1, 165, 165, 165, -1, + 166, 166, 166, -1, 167, 167, 167, -1, + 168, 168, 168, -1, 169, 169, 169, -1, + 170, 170, 170, -1, 171, 171, 171, -1, + 172, 172, 172, -1, 173, 173, 173, -1, + 174, 174, 174, -1, 175, 175, 175, -1, + 176, 176, 176, -1, 177, 177, 177, -1, + 178, 178, 178, -1, 179, 179, 179, -1, + 180, 180, 180, -1, 181, 181, 181, -1, + 182, 182, 182, -1, 183, 183, 183, -1, + 184, 184, 184, -1, 185, 185, 185, -1, + 186, 186, 186, -1, 187, 187, 187, -1, + 188, 188, 188, -1, 189, 189, 189, -1, + 190, 190, 190, -1, 191, 191, 191, -1, + 192, 192, 192, -1, 193, 193, 193, -1, + 194, 194, 194, -1, 195, 195, 195, -1, + 196, 196, 196, -1, 197, 197, 197, -1, + 198, 198, 198, -1, 199, 199, 199, -1, + 200, 200, 200, -1, 201, 201, 201, -1, + 202, 202, 202, -1, 203, 203, 203, -1, + 204, 204, 204, -1, 205, 205, 205, -1, + 206, 206, 206, -1, 207, 207, 207, -1, + 208, 208, 208, -1, 209, 209, 209, -1, + 210, 210, 210, -1, 211, 211, 211, -1, + 212, 212, 212, -1, 213, 213, 213, -1, + 214, 214, 214, -1, 215, 215, 215, -1, + 216, 216, 216, -1, 217, 217, 217, -1, + 218, 218, 218, -1, 219, 219, 219, -1, + 220, 220, 220, -1, 221, 221, 221, -1, + 222, 222, 222, -1, 223, 223, 223, -1, + 224, 224, 224, -1, 225, 225, 225, -1, + 226, 226, 226, -1, 227, 227, 227, -1, + 228, 228, 228, -1, 229, 229, 229, -1, + 230, 230, 230, -1, 231, 231, 231, -1, + 232, 232, 232, -1, 233, 233, 233, -1, + 234, 234, 234, -1, 235, 235, 235, -1, + 236, 236, 236, -1, 237, 237, 237, -1, + 238, 238, 238, -1, 239, 239, 239, -1, + 240, 240, 240, -1, 241, 241, 241, -1, + 242, 242, 242, -1, 243, 243, 243, -1, + 244, 244, 244, -1, 245, 245, 245, -1, + 246, 246, 246, -1, 247, 247, 247, -1, + 248, 248, 248, -1, 249, 249, 249, -1, + 250, 250, 250, -1, 251, 251, 251, -1, + 252, 252, 252, -1, 253, 253, 253, -1, + 254, 254, 254, -1, 255, 255, 255, -1, + 256, 256, 256, -1, 257, 257, 257, -1, + 258, 258, 258, -1, 259, 259, 259, -1, + 260, 260, 260, -1, 261, 261, 261, -1, + 262, 262, 262, -1, 263, 263, 263, -1, + 264, 264, 264, -1, 265, 265, 265, -1, + 266, 266, 266, -1, 267, 267, 267, -1, + 268, 268, 268, -1, 269, 269, 269, -1, + 270, 270, 270, -1, 271, 271, 271, -1, + 272, 272, 272, -1, 273, 273, 273, -1, + 274, 274, 274, -1, 275, 275, 275, -1, + 276, 276, 276, -1, 277, 277, 277, -1, + 278, 278, 278, -1, 279, 279, 279, -1, + 280, 280, 280, -1, 281, 281, 281, -1, + 282, 282, 282, -1, 283, 283, 283, -1, + 284, 284, 284, -1, 285, 285, 285, -1, + 286, 286, 286, -1, 287, 287, 287, -1, + 288, 288, 288, -1, 289, 289, 289, -1, + 290, 290, 290, -1, 291, 291, 291, -1, + 292, 292, 292, -1, 293, 293, 293, -1, + 294, 294, 294, -1, 295, 295, 295, -1, + 296, 296, 296, -1, 297, 297, 297, -1, + 298, 298, 298, -1, 299, 299, 299, -1, + 300, 300, 300, -1, 301, 301, 301, -1, + 302, 302, 302, -1, 303, 303, 303, -1, + 304, 304, 304, -1, 305, 305, 305, -1, + 306, 306, 306, -1, 307, 307, 307, -1, + 308, 308, 308, -1, 309, 309, 309, -1, + 310, 310, 310, -1, 311, 311, 311, -1, + 312, 312, 312, -1, 313, 313, 313, -1, + 314, 314, 314, -1, 315, 315, 315, -1, + 316, 316, 316, -1, 317, 317, 317, -1, + 318, 318, 318, -1, 319, 319, 319, -1, + 320, 320, 320, -1, 321, 321, 321, -1, + 322, 322, 322, -1, 323, 323, 323, -1, + 324, 324, 324, -1, 325, 325, 325, -1, + 326, 326, 326, -1, 327, 327, 327, -1, + 328, 328, 328, -1, 329, 329, 329, -1, + 330, 330, 330, -1, 331, 331, 331, -1, + 332, 332, 332, -1, 333, 333, 333, -1, + 334, 334, 334, -1, 335, 335, 335, -1, + 336, 336, 336, -1, 337, 337, 337, -1, + 338, 338, 338, -1, 339, 339, 339, -1, + 340, 340, 340, -1, 341, 341, 341, -1, + 342, 342, 342, -1, 343, 343, 343, -1, + 344, 344, 344, -1, 345, 345, 345, -1, + 346, 346, 346, -1, 347, 347, 347, -1, + 348, 348, 348, -1, 349, 349, 349, -1, + 350, 350, 350, -1, 351, 351, 351, -1, + 352, 352, 352, -1, 353, 353, 353, -1, + 354, 354, 354, -1, 355, 355, 355, -1, + 356, 356, 356, -1, 357, 357, 357, -1, + 358, 358, 358, -1, 359, 359, 359, -1, + 360, 360, 360, -1, 361, 361, 361, -1, + 362, 362, 362, -1, 363, 363, 363, -1, + 364, 364, 364, -1, 365, 365, 365, -1, + 366, 366, 366, -1, 367, 367, 367, -1, + 368, 368, 368, -1, 369, 369, 369, -1, + 370, 370, 370, -1, 371, 371, 371, -1, + 372, 372, 372, -1, 373, 373, 373, -1, + 374, 374, 374, -1, 375, 375, 375, -1, + 376, 376, 376, -1, 377, 377, 377, -1, + 378, 378, 378, -1, 379, 379, 379, -1, + 380, 380, 380, -1, 381, 381, 381, -1, + 382, 382, 382, -1, 383, 383, 383, -1, + 384, 384, 384, -1, 385, 385, 385, -1, + 386, 386, 386, -1, 387, 387, 387, -1, + 388, 388, 388, -1, 389, 389, 389, -1, + 390, 390, 390, -1, 391, 391, 391, -1, + 392, 392, 392, -1, 393, 393, 393, -1, + 394, 394, 394, -1, 395, 395, 395, -1, + 396, 396, 396, -1, 397, 397, 397, -1, + 398, 398, 398, -1, 399, 399, 399, -1, + 400, 400, 400, -1, 401, 401, 401, -1, + 402, 402, 402, -1, 403, 403, 403, -1, + 404, 404, 404, -1, 405, 405, 405, -1, + 406, 406, 406, -1, 407, 407, 407, -1, + 408, 408, 408, -1, 409, 409, 409, -1, + 410, 410, 410, -1, 411, 411, 411, -1, + 412, 412, 412, -1, 413, 413, 413, -1, + 414, 414, 414, -1, 415, 415, 415, -1, + 416, 416, 416, -1, 417, 417, 417, -1, + 418, 418, 418, -1, 419, 419, 419, -1, + 420, 420, 420, -1, 421, 421, 421, -1, + 422, 422, 422, -1, 423, 423, 423, -1, + 424, 424, 424, -1, 425, 425, 425, -1, + 426, 426, 426, -1, 427, 427, 427, -1, + 428, 428, 428, -1, 429, 429, 429, -1, + 430, 430, 430, -1, 431, 431, 431, -1, + 432, 432, 432, -1, 433, 433, 433, -1, + 434, 434, 434, -1, 435, 435, 435, -1, + 436, 436, 436, -1, 437, 437, 437, -1, + 438, 438, 438, -1, 439, 439, 439, -1, + 440, 440, 440, -1, 441, 441, 441, -1, + 442, 442, 442, -1, 443, 443, 443, -1, + 444, 444, 444, -1, 445, 445, 445, -1, + 446, 446, 446, -1, 447, 447, 447, -1, + 448, 448, 448, -1, 449, 449, 449, -1, + 450, 450, 450, -1, 451, 451, 451, -1, + 452, 452, 452, -1, 453, 453, 453, -1, + 454, 454, 454, -1, 455, 455, 455, -1, + 456, 456, 456, -1, 457, 457, 457, -1, + 458, 458, 458, -1, 459, 459, 459, -1, + 460, 460, 460, -1, 461, 461, 461, -1, + 462, 462, 462, -1, 463, 463, 463, -1, + 464, 464, 464, -1, 465, 465, 465, -1, + 466, 466, 466, -1, 467, 467, 467, -1, + 468, 468, 468, -1, 469, 469, 469, -1, + 470, 470, 470, -1, 471, 471, 471, -1, + 472, 472, 472, -1, 473, 473, 473, -1, + 474, 474, 474, -1, 475, 475, 475, -1, + 476, 476, 476, -1, 477, 477, 477, -1, + 478, 478, 478, -1, 479, 479, 479, -1, + 480, 480, 480, -1, 481, 481, 481, -1, + 482, 482, 482, -1, 483, 483, 483, -1, + 484, 484, 484, -1, 485, 485, 485, -1, + 486, 486, 486, -1, 487, 487, 487, -1, + 488, 488, 488, -1, 489, 489, 489, -1, + 490, 490, 490, -1, 491, 491, 491, -1, + 492, 492, 492, -1, 493, 493, 493, -1, + 494, 494, 494, -1, 495, 495, 495, -1, + 496, 496, 496, -1, 497, 497, 497, -1, + 498, 498, 498, -1, 499, 499, 499, -1, + 500, 500, 500, -1, 501, 501, 501, -1, + 502, 502, 502, -1, 503, 503, 503, -1, + 504, 504, 504, -1, 505, 505, 505, -1, + 506, 506, 506, -1, 507, 507, 507, -1, + 508, 508, 508, -1, 509, 509, 509, -1, + 510, 510, 510, -1, 511, 511, 511, -1, + 512, 512, 512, -1, 513, 513, 513, -1, + 514, 514, 514, -1, 515, 515, 515, -1, + 516, 516, 516, -1, 517, 517, 517, -1, + 518, 518, 518, -1, 519, 519, 519, -1, + 520, 520, 520, -1, 521, 521, 521, -1, + 522, 522, 522, -1, 523, 523, 523, -1, + 524, 524, 524, -1, 525, 525, 525, -1, + 526, 526, 526, -1, 527, 527, 527, -1, + 528, 528, 528, -1, 529, 529, 529, -1, + 530, 530, 530, -1, 531, 531, 531, -1, + 532, 532, 532, -1, 533, 533, 533, -1, + 534, 534, 534, -1, 535, 535, 535, -1, + 536, 536, 536, -1, 537, 537, 537, -1, + 538, 538, 538, -1, 539, 539, 539, -1, + 540, 540, 540, -1, 541, 541, 541, -1, + 542, 542, 542, -1, 543, 543, 543, -1, + 544, 544, 544, -1, 545, 545, 545, -1, + 546, 546, 546, -1, 547, 547, 547, -1, + 548, 548, 548, -1, 549, 549, 549, -1, + 550, 550, 550, -1, 551, 551, 551, -1, + 552, 552, 552, -1, 553, 553, 553, -1, + 554, 554, 554, -1, 555, 555, 555, -1, + 556, 556, 556, -1, 557, 557, 557, -1, + 558, 558, 558, -1, 559, 559, 559, -1, + 560, 560, 560, -1, 561, 561, 561, -1, + 562, 562, 562, -1, 563, 563, 563, -1, + 564, 564, 564, -1, 565, 565, 565, -1, + 566, 566, 566, -1, 567, 567, 567, -1, + 568, 568, 568, -1, 569, 569, 569, -1, + 570, 570, 570, -1, 571, 571, 571, -1, + 572, 572, 572, -1, 573, 573, 573, -1, + 574, 574, 574, -1, 575, 575, 575, -1, + 576, 576, 576, -1, 577, 577, 577, -1, + 578, 578, 578, -1, 579, 579, 579, -1, + 580, 580, 580, -1, 581, 581, 581, -1, + 582, 582, 582, -1, 583, 583, 583, -1, + 584, 584, 584, -1, 585, 585, 585, -1, + 586, 586, 586, -1, 587, 587, 587, -1, + 588, 588, 588, -1, 589, 589, 589, -1, + 590, 590, 590, -1, 591, 591, 591, -1, + 592, 592, 592, -1, 593, 593, 593, -1, + 594, 594, 594, -1, 595, 595, 595, -1, + 596, 596, 596, -1, 597, 597, 597, -1, + 598, 598, 598, -1, 599, 599, 599, -1, + 600, 600, 600, -1, 601, 601, 601, -1, + 602, 602, 602, -1, 603, 603, 603, -1, + 604, 604, 604, -1, 605, 605, 605, -1, + 606, 606, 606, -1, 607, 607, 607, -1, + 608, 608, 608, -1, 609, 609, 609, -1, + 610, 610, 610, -1, 611, 611, 611, -1, + 612, 612, 612, -1, 613, 613, 613, -1, + 614, 614, 614, -1, 615, 615, 615, -1, + 616, 616, 616, -1, 617, 617, 617, -1, + 618, 618, 618, -1, 619, 619, 619, -1, + 620, 620, 620, -1, 621, 621, 621, -1, + 622, 622, 622, -1, 623, 623, 623, -1, + 624, 624, 624, -1, 625, 625, 625, -1, + 626, 626, 626, -1, 627, 627, 627, -1, + 628, 628, 628, -1, 629, 629, 629, -1, + 630, 630, 630, -1, 631, 631, 631, -1, + 632, 632, 632, -1, 633, 633, 633, -1, + 634, 634, 634, -1, 635, 635, 635, -1, + 636, 636, 636, -1, 637, 637, 637, -1, + 638, 638, 638, -1, 639, 639, 639, -1, + 640, 640, 640, -1, 641, 641, 641, -1, + 642, 642, 642, -1, 643, 643, 643, -1, + 644, 644, 644, -1, 645, 645, 645, -1, + 646, 646, 646, -1, 647, 647, 647, -1, + 648, 648, 648, -1, 649, 649, 649, -1, + 650, 650, 650, -1, 651, 651, 651, -1, + 652, 652, 652, -1, 653, 653, 653, -1, + 654, 654, 654, -1, 655, 655, 655, -1, + 656, 656, 656, -1, 657, 657, 657, -1, + 658, 658, 658, -1, 659, 659, 659, -1, + 660, 660, 660, -1, 661, 661, 661, -1, + 662, 662, 662, -1, 663, 663, 663, -1, + 664, 664, 664, -1, 665, 665, 665, -1, + 666, 666, 666, -1, 667, 667, 667, -1, + 668, 668, 668, -1, 669, 669, 669, -1, + 670, 670, 670, -1, 671, 671, 671, -1, + 672, 672, 672, -1, 673, 673, 673, -1, + 674, 674, 674, -1, 675, 675, 675, -1, + 676, 676, 676, -1, 677, 677, 677, -1, + 678, 678, 678, -1, 679, 679, 679, -1, + 680, 680, 680, -1, 681, 681, 681, -1, + 682, 682, 682, -1, 683, 683, 683, -1, + 684, 684, 684, -1, 685, 685, 685, -1, + 686, 686, 686, -1, 687, 687, 687, -1, + 688, 688, 688, -1, 689, 689, 689, -1, + 690, 690, 690, -1, 691, 691, 691, -1, + 692, 692, 692, -1, 693, 693, 693, -1, + 694, 694, 694, -1, 695, 695, 695, -1, + 696, 696, 696, -1, 697, 697, 697, -1, + 698, 698, 698, -1, 699, 699, 699, -1, + 700, 700, 700, -1, 701, 701, 701, -1, + 702, 702, 702, -1, 703, 703, 703, -1, + 704, 704, 704, -1, 705, 705, 705, -1, + 706, 706, 706, -1, 707, 707, 707, -1, + 708, 708, 708, -1, 709, 709, 709, -1, + 710, 710, 710, -1, 711, 711, 711, -1, + 712, 712, 712, -1, 713, 713, 713, -1, + 714, 714, 714, -1, 715, 715, 715, -1, + 716, 716, 716, -1, 717, 717, 717, -1, + 718, 718, 718, -1, 719, 719, 719, -1, + 720, 720, 720, -1, 721, 721, 721, -1, + 722, 722, 722, -1, 723, 723, 723, -1, + 724, 724, 724, -1, 725, 725, 725, -1, + 726, 726, 726, -1, 727, 727, 727, -1, + 728, 728, 728, -1, 729, 729, 729, -1, + 730, 730, 730, -1, 731, 731, 731, -1, + 732, 732, 732, -1, 733, 733, 733, -1, + 734, 734, 734, -1, 735, 735, 735, -1, + 736, 736, 736, -1, 737, 737, 737, -1, + 738, 738, 738, -1, 739, 739, 739, -1, + 740, 740, 740, -1, 741, 741, 741, -1, + 742, 742, 742, -1, 743, 743, 743, -1, + 744, 744, 744, -1, 745, 745, 745, -1, + 746, 746, 746, -1, 747, 747, 747, -1, + 748, 748, 748, -1, 749, 749, 749, -1, + 750, 750, 750, -1, 751, 751, 751, -1, + 752, 752, 752, -1, 753, 753, 753, -1, + 754, 754, 754, -1, 755, 755, 755, -1, + 756, 756, 756, -1, 757, 757, 757, -1, + 758, 758, 758, -1, 759, 759, 759, -1, + 760, 760, 760, -1, 761, 761, 761, -1, + 762, 762, 762, -1, 763, 763, 763, -1, + 764, 764, 764, -1, 765, 765, 765, -1, + 766, 766, 766, -1, 767, 767, 767, -1, + 768, 768, 768, -1, 769, 769, 769, -1, + 770, 770, 770, -1, 771, 771, 771, -1, + 772, 772, 772, -1, 773, 773, 773, -1, + 774, 774, 774, -1, 775, 775, 775, -1, + 776, 776, 776, -1, 777, 777, 777, -1, + 778, 778, 778, -1, 779, 779, 779, -1, + 780, 780, 780, -1, 781, 781, 781, -1, + 782, 782, 782, -1, 783, 783, 783, -1, + 784, 784, 784, -1, 785, 785, 785, -1, + 786, 786, 786, -1, 787, 787, 787, -1, + 788, 788, 788, -1, 789, 789, 789, -1, + 790, 790, 790, -1, 791, 791, 791, -1, + 792, 792, 792, -1, 793, 793, 793, -1, + 794, 794, 794, -1, 795, 795, 795, -1, + 796, 796, 796, -1, 797, 797, 797, -1, + 798, 798, 798, -1, 799, 799, 799, -1, + 800, 800, 800, -1, 801, 801, 801, -1, + 802, 802, 802, -1, 803, 803, 803, -1, + 804, 804, 804, -1, 805, 805, 805, -1, + 806, 806, 806, -1, 807, 807, 807, -1, + 808, 808, 808, -1, 809, 809, 809, -1, + 810, 810, 810, -1, 811, 811, 811, -1, + 812, 812, 812, -1, 813, 813, 813, -1, + 814, 814, 814, -1, 815, 815, 815, -1, + 816, 816, 816, -1, 817, 817, 817, -1, + 818, 818, 818, -1, 819, 819, 819, -1, + 820, 820, 820, -1, 821, 821, 821, -1, + 822, 822, 822, -1, 823, 823, 823, -1, + 824, 824, 824, -1, 825, 825, 825, -1, + 826, 826, 826, -1, 827, 827, 827, -1, + 828, 828, 828, -1, 829, 829, 829, -1, + 830, 830, 830, -1, 831, 831, 831, -1, + 832, 832, 832, -1, 833, 833, 833, -1, + 834, 834, 834, -1, 835, 835, 835, -1, + 836, 836, 836, -1, 837, 837, 837, -1, + 838, 838, 838, -1, 839, 839, 839, -1, + 840, 840, 840, -1, 841, 841, 841, -1, + 842, 842, 842, -1, 843, 843, 843, -1, + 844, 844, 844, -1, 845, 845, 845, -1, + 846, 846, 846, -1, 847, 847, 847, -1, + 848, 848, 848, -1, 849, 849, 849, -1, + 850, 850, 850, -1, 851, 851, 851, -1, + 852, 852, 852, -1, 853, 853, 853, -1, + 854, 854, 854, -1, 855, 855, 855, -1, + 856, 856, 856, -1, 857, 857, 857, -1, + 858, 858, 858, -1, 859, 859, 859, -1, + 860, 860, 860, -1, 861, 861, 861, -1, + 862, 862, 862, -1, 863, 863, 863, -1, + 864, 864, 864, -1, 865, 865, 865, -1, + 866, 866, 866, -1, 867, 867, 867, -1, + 868, 868, 868, -1, 869, 869, 869, -1, + 870, 870, 870, -1, 871, 871, 871, -1, + 872, 872, 872, -1, 873, 873, 873, -1, + 874, 874, 874, -1, 875, 875, 875, -1, + 876, 876, 876, -1, 877, 877, 877, -1, + 878, 878, 878, -1, 879, 879, 879, -1, + 880, 880, 880, -1, 881, 881, 881, -1, + 882, 882, 882, -1, 883, 883, 883, -1, + 884, 884, 884, -1, 885, 885, 885, -1, + 886, 886, 886, -1, 887, 887, 887, -1, + 888, 888, 888, -1, 889, 889, 889, -1, + 890, 890, 890, -1, 891, 891, 891, -1, + 892, 892, 892, -1, 893, 893, 893, -1, + 894, 894, 894, -1, 895, 895, 895, -1, + 896, 896, 896, -1, 897, 897, 897, -1, + 898, 898, 898, -1, 899, 899, 899, -1, + 900, 900, 900, -1, 901, 901, 901, -1, + 902, 902, 902, -1, 903, 903, 903, -1, + 904, 904, 904, -1, 905, 905, 905, -1, + 906, 906, 906, -1, 907, 907, 907, -1, + 908, 908, 908, -1, 909, 909, 909, -1, + 910, 910, 910, -1, 911, 911, 911, -1, + 912, 912, 912, -1, 913, 913, 913, -1, + 914, 914, 914, -1, 915, 915, 915, -1, + 916, 916, 916, -1, 917, 917, 917, -1, + 918, 918, 918, -1, 919, 919, 919, -1, + 920, 920, 920, -1, 921, 921, 921, -1, + 922, 922, 922, -1, 923, 923, 923, -1, + 924, 924, 924, -1, 925, 925, 925, -1, + 926, 926, 926, -1, 927, 927, 927, -1, + 928, 928, 928, -1, 929, 929, 929, -1, + 930, 930, 930, -1, 931, 931, 931, -1, + 932, 932, 932, -1, 933, 933, 933, -1, + 934, 934, 934, -1, 935, 935, 935, -1, + 936, 936, 936, -1, 937, 937, 937, -1, + 938, 938, 938, -1, 939, 939, 939, -1, + 940, 940, 940, -1, 941, 941, 941, -1, + 942, 942, 942, -1, 943, 943, 943, -1, + 944, 944, 944, -1, 945, 945, 945, -1, + 946, 946, 946, -1, 947, 947, 947, -1, + 948, 948, 948, -1, 949, 949, 949, -1, + 950, 950, 950, -1, 951, 951, 951, -1, + 952, 952, 952, -1, 953, 953, 953, -1, + 954, 954, 954, -1, 955, 955, 955, -1, + 956, 956, 956, -1, 957, 957, 957, -1, + 958, 958, 958, -1, 959, 959, 959, -1, + 960, 960, 960, -1, 961, 961, 961, -1, + 962, 962, 962, -1, 963, 963, 963, -1, + 964, 964, 964, -1, 965, 965, 965, -1, + 966, 966, 966, -1, 967, 967, 967, -1, + 968, 968, 968, -1, 969, 969, 969, -1, + 970, 970, 970, -1, 971, 971, 971, -1, + 972, 972, 972, -1, 973, 973, 973, -1, + 974, 974, 974, -1, 975, 975, 975, -1, + 976, 976, 976, -1, 977, 977, 977, -1, + 978, 978, 978, -1, 979, 979, 979, -1, + 980, 980, 980, -1, 981, 981, 981, -1, + 982, 982, 982, -1, 983, 983, 983, -1, + 984, 984, 984, -1, 985, 985, 985, -1, + 986, 986, 986, -1, 987, 987, 987, -1, + 988, 988, 988, -1, 989, 989, 989, -1, + 990, 990, 990, -1, 991, 991, 991, -1, + 992, 992, 992, -1, 993, 993, 993, -1, + 994, 994, 994, -1, 995, 995, 995, -1, + 996, 996, 996, -1, 997, 997, 997, -1, + 998, 998, 998, -1, 999, 999, 999, -1, + 1000, 1000, 1000, -1, 1001, 1001, 1001, -1, + 1002, 1002, 1002, -1, 1003, 1003, 1003, -1, + 1004, 1004, 1004, -1, 1005, 1005, 1005, -1, + 1006, 1006, 1006, -1, 1007, 1007, 1007, -1, + 1008, 1008, 1008, -1, 1009, 1009, 1009, -1, + 1010, 1010, 1010, -1, 1011, 1011, 1011, -1, + 1012, 1012, 1012, -1, 1013, 1013, 1013, -1, + 1014, 1014, 1014, -1, 1015, 1015, 1015, -1, + 1016, 1016, 1016, -1, 1017, 1017, 1017, -1, + 1018, 1018, 1018, -1, 1019, 1019, 1019, -1, + 1020, 1020, 1020, -1, 1021, 1021, 1021, -1, + 1022, 1022, 1022, -1, 1023, 1023, 1023, -1, + 1024, 1024, 1024, -1, 1025, 1025, 1025, -1, + 1026, 1026, 1026, -1, 1027, 1027, 1027, -1, + 1028, 1028, 1028, -1, 1029, 1029, 1029, -1, + 1030, 1030, 1030, -1, 1031, 1031, 1031, -1, + 1032, 1032, 1032, -1, 1033, 1033, 1033, -1, + 1034, 1034, 1034, -1, 1035, 1035, 1035, -1, + 1036, 1036, 1036, -1, 1037, 1037, 1037, -1, + 1038, 1038, 1038, -1, 1039, 1039, 1039, -1, + 1040, 1040, 1040, -1, 1041, 1041, 1041, -1, + 1042, 1042, 1042, -1, 1043, 1043, 1043, -1, + 1044, 1044, 1044, -1, 1045, 1045, 1045, -1, + 1046, 1046, 1046, -1, 1047, 1047, 1047, -1, + 1048, 1048, 1048, -1, 1049, 1049, 1049, -1, + 1050, 1050, 1050, -1, 1051, 1051, 1051, -1, + 1052, 1052, 1052, -1, 1053, 1053, 1053, -1, + 1054, 1054, 1054, -1, 1055, 1055, 1055, -1, + 1056, 1056, 1056, -1, 1057, 1057, 1057, -1, + 1058, 1058, 1058, -1, 1059, 1059, 1059, -1, + 1060, 1060, 1060, -1, 1061, 1061, 1061, -1, + 1062, 1062, 1062, -1, 1063, 1063, 1063, -1, + 1064, 1064, 1064, -1, 1065, 1065, 1065, -1, + 1066, 1066, 1066, -1, 1067, 1067, 1067, -1, + 1068, 1068, 1068, -1, 1069, 1069, 1069, -1, + 1070, 1070, 1070, -1, 1071, 1071, 1071, -1, + 1072, 1072, 1072, -1, 1073, 1073, 1073, -1, + 1074, 1074, 1074, -1, 1075, 1075, 1075, -1, + 1076, 1076, 1076, -1, 1077, 1077, 1077, -1, + 1078, 1078, 1078, -1, 1079, 1079, 1079, -1, + 1080, 1080, 1080, -1, 1081, 1081, 1081, -1, + 1082, 1082, 1082, -1, 1083, 1083, 1083, -1, + 1084, 1084, 1084, -1, 1085, 1085, 1085, -1, + 1086, 1086, 1086, -1, 1087, 1087, 1087, -1, + 1088, 1088, 1088, -1, 1089, 1089, 1089, -1, + 1090, 1090, 1090, -1, 1091, 1091, 1091, -1, + 1092, 1092, 1092, -1, 1093, 1093, 1093, -1, + 1094, 1094, 1094, -1, 1095, 1095, 1095, -1, + 1096, 1096, 1096, -1, 1097, 1097, 1097, -1, + 1098, 1098, 1098, -1, 1099, 1099, 1099, -1, + 1100, 1100, 1100, -1, 1101, 1101, 1101, -1, + 1102, 1102, 1102, -1, 1103, 1103, 1103, -1, + 1104, 1104, 1104, -1, 1105, 1105, 1105, -1, + 1106, 1106, 1106, -1, 1107, 1107, 1107, -1, + 1108, 1108, 1108, -1, 1109, 1109, 1109, -1, + 1110, 1110, 1110, -1, 1111, 1111, 1111, -1, + 1112, 1112, 1112, -1, 1113, 1113, 1113, -1, + 1114, 1114, 1114, -1, 1115, 1115, 1115, -1, + 1116, 1116, 1116, -1, 1117, 1117, 1117, -1, + 1118, 1118, 1118, -1, 1119, 1119, 1119, -1, + 1120, 1120, 1120, -1, 1121, 1121, 1121, -1, + 1122, 1122, 1122, -1, 1123, 1123, 1123, -1, + 1124, 1124, 1124, -1, 1125, 1125, 1125, -1, + 1126, 1126, 1126, -1, 1127, 1127, 1127, -1, + 1128, 1128, 1128, -1, 1129, 1129, 1129, -1, + 1130, 1130, 1130, -1, 1131, 1131, 1131, -1, + 1132, 1132, 1132, -1, 1133, 1133, 1133, -1, + 1134, 1134, 1134, -1, 1135, 1135, 1135, -1, + 1136, 1136, 1136, -1, 1137, 1137, 1137, -1, + 1138, 1138, 1138, -1, 1139, 1139, 1139, -1, + 1140, 1140, 1140, -1, 1141, 1141, 1141, -1, + 1142, 1142, 1142, -1, 1143, 1143, 1143, -1, + 1144, 1144, 1144, -1, 1145, 1145, 1145, -1, + 1146, 1146, 1146, -1, 1147, 1147, 1147, -1, + 1148, 1148, 1148, -1, 1149, 1149, 1149, -1, + 1150, 1150, 1150, -1, 1151, 1151, 1151, -1, + 1152, 1152, 1152, -1, 1153, 1153, 1153, -1, + 1154, 1154, 1154, -1, 1155, 1155, 1155, -1, + 1156, 1156, 1156, -1, 1157, 1157, 1157, -1, + 1158, 1158, 1158, -1, 1159, 1159, 1159, -1, + 1160, 1160, 1160, -1, 1161, 1161, 1161, -1, + 1162, 1162, 1162, -1, 1163, 1163, 1163, -1, + 1164, 1164, 1164, -1, 1165, 1165, 1165, -1, + 1166, 1166, 1166, -1, 1167, 1167, 1167, -1, + 1168, 1168, 1168, -1, 1169, 1169, 1169, -1, + 1170, 1170, 1170, -1, 1171, 1171, 1171, -1, + 1172, 1172, 1172, -1, 1173, 1173, 1173, -1, + 1174, 1174, 1174, -1, 1175, 1175, 1175, -1, + 1176, 1176, 1176, -1, 1177, 1177, 1177, -1, + 1178, 1178, 1178, -1, 1179, 1179, 1179, -1, + 1180, 1180, 1180, -1, 1181, 1181, 1181, -1, + 1182, 1182, 1182, -1, 1183, 1183, 1183, -1, + 1184, 1184, 1184, -1, 1185, 1185, 1185, -1, + 1186, 1186, 1186, -1, 1187, 1187, 1187, -1, + 1188, 1188, 1188, -1, 1189, 1189, 1189, -1, + 1190, 1190, 1190, -1, 1191, 1191, 1191, -1, + 1192, 1192, 1192, -1, 1193, 1193, 1193, -1, + 1194, 1194, 1194, -1, 1195, 1195, 1195, -1, + 1196, 1196, 1196, -1, 1197, 1197, 1197, -1, + 1198, 1198, 1198, -1, 1199, 1199, 1199, -1, + 1200, 1200, 1200, -1, 1201, 1201, 1201, -1, + 1202, 1202, 1202, -1, 1203, 1203, 1203, -1, + 1204, 1204, 1204, -1, 1205, 1205, 1205, -1, + 1206, 1206, 1206, -1, 1207, 1207, 1207, -1, + 1208, 1208, 1208, -1, 1209, 1209, 1209, -1, + 1210, 1210, 1210, -1, 1211, 1211, 1211, -1, + 1212, 1212, 1212, -1, 1213, 1213, 1213, -1, + 1214, 1214, 1214, -1, 1215, 1215, 1215, -1, + 1216, 1216, 1216, -1, 1217, 1217, 1217, -1, + 1218, 1218, 1218, -1, 1219, 1219, 1219, -1, + 1220, 1220, 1220, -1, 1221, 1221, 1221, -1, + 1222, 1222, 1222, -1, 1223, 1223, 1223, -1, + 1224, 1224, 1224, -1, 1225, 1225, 1225, -1, + 1226, 1226, 1226, -1, 1227, 1227, 1227, -1, + 1228, 1228, 1228, -1, 1229, 1229, 1229, -1, + 1230, 1230, 1230, -1, 1231, 1231, 1231, -1, + 1232, 1232, 1232, -1, 1233, 1233, 1233, -1, + 1234, 1234, 1234, -1, 1235, 1235, 1235, -1, + 1236, 1236, 1236, -1, 1237, 1237, 1237, -1, + 1238, 1238, 1238, -1, 1239, 1239, 1239, -1, + 1240, 1240, 1240, -1, 1241, 1241, 1241, -1, + 1242, 1242, 1242, -1, 1243, 1243, 1243, -1, + 1244, 1244, 1244, -1, 1245, 1245, 1245, -1, + 1246, 1246, 1246, -1, 1247, 1247, 1247, -1, + 1248, 1248, 1248, -1, 1249, 1249, 1249, -1, + 1250, 1250, 1250, -1, 1251, 1251, 1251, -1, + 1252, 1252, 1252, -1, 1253, 1253, 1253, -1, + 1254, 1254, 1254, -1, 1255, 1255, 1255, -1, + 1256, 1256, 1256, -1, 1257, 1257, 1257, -1, + 1258, 1258, 1258, -1, 1259, 1259, 1259, -1, + 1260, 1260, 1260, -1, 1261, 1261, 1261, -1, + 1262, 1262, 1262, -1, 1263, 1263, 1263, -1, + 1264, 1264, 1264, -1, 1265, 1265, 1265, -1, + 1266, 1266, 1266, -1, 1267, 1267, 1267, -1, + 1268, 1268, 1268, -1, 1269, 1269, 1269, -1, + 1270, 1270, 1270, -1, 1271, 1271, 1271, -1, + 1272, 1272, 1272, -1, 1273, 1273, 1273, -1, + 1274, 1274, 1274, -1, 1275, 1275, 1275, -1, + 1276, 1276, 1276, -1, 1277, 1277, 1277, -1, + 1278, 1278, 1278, -1, 1279, 1279, 1279, -1, + 1280, 1280, 1280, -1, 1281, 1281, 1281, -1, + 1282, 1282, 1282, -1, 1283, 1283, 1283, -1, + 1284, 1284, 1284, -1, 1285, 1285, 1285, -1, + 1286, 1286, 1286, -1, 1287, 1287, 1287, -1, + 1288, 1288, 1288, -1, 1289, 1289, 1289, -1, + 1290, 1290, 1290, -1, 1291, 1291, 1291, -1, + 1292, 1292, 1292, -1, 1293, 1293, 1293, -1, + 1294, 1294, 1294, -1, 1295, 1295, 1295, -1, + 1296, 1296, 1296, -1, 1297, 1297, 1297, -1, + 1298, 1298, 1298, -1, 1299, 1299, 1299, -1, + 1300, 1300, 1300, -1, 1301, 1301, 1301, -1, + 1302, 1302, 1302, -1, 1303, 1303, 1303, -1, + 1304, 1304, 1304, -1, 1305, 1305, 1305, -1, + 1306, 1306, 1306, -1, 1307, 1307, 1307, -1, + 1308, 1308, 1308, -1, 1309, 1309, 1309, -1, + 1310, 1310, 1310, -1, 1311, 1311, 1311, -1, + 1312, 1312, 1312, -1, 1313, 1313, 1313, -1, + 1314, 1314, 1314, -1, 1315, 1315, 1315, -1, + 1316, 1316, 1316, -1, 1317, 1317, 1317, -1, + 1318, 1318, 1318, -1, 1319, 1319, 1319, -1, + 1320, 1320, 1320, -1, 1321, 1321, 1321, -1, + 1322, 1322, 1322, -1, 1323, 1323, 1323, -1, + 1324, 1324, 1324, -1, 1325, 1325, 1325, -1, + 1326, 1326, 1326, -1, 1327, 1327, 1327, -1, + 1328, 1328, 1328, -1, 1329, 1329, 1329, -1, + 1330, 1330, 1330, -1, 1331, 1331, 1331, -1, + 1332, 1332, 1332, -1, 1333, 1333, 1333, -1, + 1334, 1334, 1334, -1, 1335, 1335, 1335, -1, + 1336, 1336, 1336, -1, 1337, 1337, 1337, -1, + 1338, 1338, 1338, -1, 1339, 1339, 1339, -1, + 1340, 1340, 1340, -1, 1341, 1341, 1341, -1, + 1342, 1342, 1342, -1, 1343, 1343, 1343, -1, + 1344, 1344, 1344, -1, 1345, 1345, 1345, -1, + 1346, 1346, 1346, -1, 1347, 1347, 1347, -1, + 1348, 1348, 1348, -1, 1349, 1349, 1349, -1, + 1350, 1350, 1350, -1, 1351, 1351, 1351, -1, + 1352, 1352, 1352, -1, 1353, 1353, 1353, -1, + 1354, 1354, 1354, -1, 1355, 1355, 1355, -1, + 1356, 1356, 1356, -1, 1357, 1357, 1357, -1, + 1358, 1358, 1358, -1, 1359, 1359, 1359, -1, + 1360, 1360, 1360, -1, 1361, 1361, 1361, -1, + 1362, 1362, 1362, -1, 1363, 1363, 1363, -1, + 1364, 1364, 1364, -1, 1365, 1365, 1365, -1, + 1366, 1366, 1366, -1, 1367, 1367, 1367, -1, + 1368, 1368, 1368, -1, 1369, 1369, 1369, -1, + 1370, 1370, 1370, -1, 1371, 1371, 1371, -1, + 1372, 1372, 1372, -1, 1373, 1373, 1373, -1, + 1374, 1374, 1374, -1, 1375, 1375, 1375, -1, + 1376, 1376, 1376, -1, 1377, 1377, 1377, -1, + 1378, 1378, 1378, -1, 1379, 1379, 1379, -1, + 1380, 1380, 1380, -1, 1381, 1381, 1381, -1, + 1382, 1382, 1382, -1, 1383, 1383, 1383, -1, + 1384, 1384, 1384, -1, 1385, 1385, 1385, -1, + 1386, 1386, 1386, -1, 1387, 1387, 1387, -1, + 1388, 1388, 1388, -1, 1389, 1389, 1389, -1, + 1390, 1390, 1390, -1, 1391, 1391, 1391, -1, + 1392, 1392, 1392, -1, 1393, 1393, 1393, -1, + 1394, 1394, 1394, -1, 1395, 1395, 1395, -1, + 1396, 1396, 1396, -1, 1397, 1397, 1397, -1, + 1398, 1398, 1398, -1, 1399, 1399, 1399, -1, + 1400, 1400, 1400, -1, 1401, 1401, 1401, -1, + 1402, 1402, 1402, -1, 1403, 1403, 1403, -1, + 1404, 1404, 1404, -1, 1405, 1405, 1405, -1, + 1406, 1406, 1406, -1, 1407, 1407, 1407, -1, + 1408, 1408, 1408, -1, 1409, 1409, 1409, -1, + 1410, 1410, 1410, -1, 1411, 1411, 1411, -1, + 1412, 1412, 1412, -1, 1413, 1413, 1413, -1, + 1414, 1414, 1414, -1, 1415, 1415, 1415, -1, + 1416, 1416, 1416, -1, 1417, 1417, 1417, -1, + 1418, 1418, 1418, -1, 1419, 1419, 1419, -1, + 1420, 1420, 1420, -1, 1421, 1421, 1421, -1, + 1422, 1422, 1422, -1, 1423, 1423, 1423, -1, + 1424, 1424, 1424, -1, 1425, 1425, 1425, -1, + 1426, 1426, 1426, -1, 1427, 1427, 1427, -1, + 1428, 1428, 1428, -1, 1429, 1429, 1429, -1, + 1430, 1430, 1430, -1, 1431, 1431, 1431, -1, + 1432, 1432, 1432, -1, 1433, 1433, 1433, -1, + 1434, 1434, 1434, -1, 1435, 1435, 1435, -1, + 1436, 1436, 1436, -1, 1437, 1437, 1437, -1, + 1438, 1438, 1438, -1, 1439, 1439, 1439, -1, + 1440, 1440, 1440, -1, 1441, 1441, 1441, -1, + 1442, 1442, 1442, -1, 1443, 1443, 1443, -1, + 1444, 1444, 1444, -1, 1445, 1445, 1445, -1, + 1446, 1446, 1446, -1, 1447, 1447, 1447, -1, + 1448, 1448, 1448, -1, 1449, 1449, 1449, -1, + 1450, 1450, 1450, -1, 1451, 1451, 1451, -1, + 1452, 1452, 1452, -1, 1453, 1453, 1453, -1, + 1454, 1454, 1454, -1, 1455, 1455, 1455, -1, + 1456, 1456, 1456, -1, 1457, 1457, 1457, -1, + 1458, 1458, 1458, -1, 1459, 1459, 1459, -1, + 1460, 1460, 1460, -1, 1461, 1461, 1461, -1, + 1462, 1462, 1462, -1, 1463, 1463, 1463, -1, + 1464, 1464, 1464, -1, 1465, 1465, 1465, -1, + 1466, 1466, 1466, -1, 1467, 1467, 1467, -1, + 1468, 1468, 1468, -1, 1469, 1469, 1469, -1, + 1470, 1470, 1470, -1, 1471, 1471, 1471, -1, + 1472, 1472, 1472, -1, 1473, 1473, 1473, -1, + 1474, 1474, 1474, -1, 1475, 1475, 1475, -1, + 1476, 1476, 1476, -1, 1477, 1477, 1477, -1, + 1478, 1478, 1478, -1, 1479, 1479, 1479, -1, + 1480, 1480, 1480, -1, 1481, 1481, 1481, -1, + 1482, 1482, 1482, -1, 1483, 1483, 1483, -1, + 1484, 1484, 1484, -1, 1485, 1485, 1485, -1, + 1486, 1486, 1486, -1, 1487, 1487, 1487, -1, + 1488, 1488, 1488, -1, 1489, 1489, 1489, -1, + 1490, 1490, 1490, -1, 1491, 1491, 1491, -1, + 1492, 1492, 1492, -1, 1493, 1493, 1493, -1, + 1494, 1494, 1494, -1, 1495, 1495, 1495, -1, + 1496, 1496, 1496, -1, 1497, 1497, 1497, -1, + 1498, 1498, 1498, -1, 1499, 1499, 1499, -1, + 1500, 1500, 1500, -1, 1501, 1501, 1501, -1, + 1502, 1502, 1502, -1, 1503, 1503, 1503, -1, + 1504, 1504, 1504, -1, 1505, 1505, 1505, -1, + 1506, 1506, 1506, -1, 1507, 1507, 1507, -1, + 1508, 1508, 1508, -1, 1509, 1509, 1509, -1, + 1510, 1510, 1510, -1, 1511, 1511, 1511, -1, + 1512, 1512, 1512, -1, 1513, 1513, 1513, -1, + 1514, 1514, 1514, -1, 1515, 1515, 1515, -1, + 1516, 1516, 1516, -1, 1517, 1517, 1517, -1, + 1518, 1518, 1518, -1, 1519, 1519, 1519, -1, + 1520, 1520, 1520, -1, 1521, 1521, 1521, -1, + 1522, 1522, 1522, -1, 1523, 1523, 1523, -1, + 1524, 1524, 1524, -1, 1525, 1525, 1525, -1, + 1526, 1526, 1526, -1, 1527, 1527, 1527, -1, + 1528, 1528, 1528, -1, 1529, 1529, 1529, -1, + 1530, 1530, 1530, -1, 1531, 1531, 1531, -1, + 1532, 1532, 1532, -1, 1533, 1533, 1533, -1, + 1534, 1534, 1534, -1, 1535, 1535, 1535, -1, + 1536, 1536, 1536, -1, 1537, 1537, 1537, -1, + 1538, 1538, 1538, -1, 1539, 1539, 1539, -1, + 1540, 1540, 1540, -1, 1541, 1541, 1541, -1, + 1542, 1542, 1542, -1, 1543, 1543, 1543, -1, + 1544, 1544, 1544, -1, 1545, 1545, 1545, -1, + 1546, 1546, 1546, -1, 1547, 1547, 1547, -1, + 1548, 1548, 1548, -1, 1549, 1549, 1549, -1, + 1550, 1550, 1550, -1, 1551, 1551, 1551, -1, + 1552, 1552, 1552, -1, 1553, 1553, 1553, -1, + 1554, 1554, 1554, -1, 1555, 1555, 1555, -1, + 1556, 1556, 1556, -1, 1557, 1557, 1557, -1, + 1558, 1558, 1558, -1, 1559, 1559, 1559, -1, + 1560, 1560, 1560, -1, 1561, 1561, 1561, -1, + 1562, 1562, 1562, -1, 1563, 1563, 1563, -1, + 1564, 1564, 1564, -1, 1565, 1565, 1565, -1, + 1566, 1566, 1566, -1, 1567, 1567, 1567, -1, + 1568, 1568, 1568, -1, 1569, 1569, 1569, -1, + 1570, 1570, 1570, -1, 1571, 1571, 1571, -1, + 1572, 1572, 1572, -1, 1573, 1573, 1573, -1, + 1574, 1574, 1574, -1, 1575, 1575, 1575, -1, + 1576, 1576, 1576, -1, 1577, 1577, 1577, -1, + 1578, 1578, 1578, -1, 1579, 1579, 1579, -1, + 1580, 1580, 1580, -1, 1581, 1581, 1581, -1, + 1582, 1582, 1582, -1, 1583, 1583, 1583, -1, + 1584, 1584, 1584, -1, 1585, 1585, 1585, -1, + 1586, 1586, 1586, -1, 1587, 1587, 1587, -1, + 1588, 1588, 1588, -1, 1589, 1589, 1589, -1, + 1590, 1590, 1590, -1, 1591, 1591, 1591, -1, + 1592, 1592, 1592, -1, 1593, 1593, 1593, -1, + 1594, 1594, 1594, -1, 1595, 1595, 1595, -1, + 1596, 1596, 1596, -1, 1597, 1597, 1597, -1, + 1598, 1598, 1598, -1, 1599, 1599, 1599, -1, + 1600, 1600, 1600, -1, 1601, 1601, 1601, -1, + 1602, 1602, 1602, -1, 1603, 1603, 1603, -1, + 1604, 1604, 1604, -1, 1605, 1605, 1605, -1, + 1606, 1606, 1606, -1, 1607, 1607, 1607, -1, + 1608, 1608, 1608, -1, 1609, 1609, 1609, -1, + 1610, 1610, 1610, -1, 1611, 1611, 1611, -1, + 1612, 1612, 1612, -1, 1613, 1613, 1613, -1, + 1614, 1614, 1614, -1, 1615, 1615, 1615, -1, + 1616, 1616, 1616, -1, 1617, 1617, 1617, -1, + 1618, 1618, 1618, -1, 1619, 1619, 1619, -1, + 1620, 1620, 1620, -1, 1621, 1621, 1621, -1, + 1622, 1622, 1622, -1, 1623, 1623, 1623, -1, + 1624, 1624, 1624, -1, 1625, 1625, 1625, -1, + 1626, 1626, 1626, -1, 1627, 1627, 1627, -1, + 1628, 1628, 1628, -1, 1629, 1629, 1629, -1, + 1630, 1630, 1630, -1, 1631, 1631, 1631, -1, + 1632, 1632, 1632, -1, 1633, 1633, 1633, -1, + 1634, 1634, 1634, -1, 1635, 1635, 1635, -1, + 1636, 1636, 1636, -1, 1637, 1637, 1637, -1, + 1638, 1638, 1638, -1, 1639, 1639, 1639, -1, + 1640, 1640, 1640, -1, 1641, 1641, 1641, -1, + 1642, 1642, 1642, -1, 1643, 1643, 1643, -1, + 1644, 1644, 1644, -1, 1645, 1645, 1645, -1, + 1646, 1646, 1646, -1, 1647, 1647, 1647, -1, + 1648, 1648, 1648, -1, 1649, 1649, 1649, -1, + 1650, 1650, 1650, -1, 1651, 1651, 1651, -1, + 1652, 1652, 1652, -1, 1653, 1653, 1653, -1, + 1654, 1654, 1654, -1, 1655, 1655, 1655, -1, + 1656, 1656, 1656, -1, 1657, 1657, 1657, -1, + 1658, 1658, 1658, -1, 1659, 1659, 1659, -1, + 1660, 1660, 1660, -1, 1661, 1661, 1661, -1, + 1662, 1662, 1662, -1, 1663, 1663, 1663, -1, + 1664, 1664, 1664, -1, 1665, 1665, 1665, -1, + 1666, 1666, 1666, -1, 1667, 1667, 1667, -1, + 1668, 1668, 1668, -1, 1669, 1669, 1669, -1, + 1670, 1670, 1670, -1, 1671, 1671, 1671, -1, + 1672, 1672, 1672, -1, 1673, 1673, 1673, -1, + 1674, 1674, 1674, -1, 1675, 1675, 1675, -1, + 1676, 1676, 1676, -1, 1677, 1677, 1677, -1, + 1678, 1678, 1678, -1, 1679, 1679, 1679, -1, + 1680, 1680, 1680, -1, 1681, 1681, 1681, -1, + 1682, 1682, 1682, -1, 1683, 1683, 1683, -1, + 1684, 1684, 1684, -1, 1685, 1685, 1685, -1, + 1686, 1686, 1686, -1, 1687, 1687, 1687, -1, + 1688, 1688, 1688, -1, 1689, 1689, 1689, -1, + 1690, 1690, 1690, -1, 1691, 1691, 1691, -1, + 1692, 1692, 1692, -1, 1693, 1693, 1693, -1, + 1694, 1694, 1694, -1, 1695, 1695, 1695, -1, + 1696, 1696, 1696, -1, 1697, 1697, 1697, -1, + 1698, 1698, 1698, -1, 1699, 1699, 1699, -1, + 1700, 1700, 1700, -1, 1701, 1701, 1701, -1, + 1702, 1702, 1702, -1, 1703, 1703, 1703, -1, + 1704, 1704, 1704, -1, 1705, 1705, 1705, -1, + 1706, 1706, 1706, -1, 1707, 1707, 1707, -1, + 1708, 1708, 1708, -1, 1709, 1709, 1709, -1, + 1710, 1710, 1710, -1, 1711, 1711, 1711, -1, + 1712, 1712, 1712, -1, 1713, 1713, 1713, -1, + 1714, 1714, 1714, -1, 1715, 1715, 1715, -1, + 1716, 1716, 1716, -1, 1717, 1717, 1717, -1, + 1718, 1718, 1718, -1, 1719, 1719, 1719, -1, + 1720, 1720, 1720, -1, 1721, 1721, 1721, -1, + 1722, 1722, 1722, -1, 1723, 1723, 1723, -1, + 1724, 1724, 1724, -1, 1725, 1725, 1725, -1, + 1726, 1726, 1726, -1, 1727, 1727, 1727, -1, + 1728, 1728, 1728, -1, 1729, 1729, 1729, -1, + 1730, 1730, 1730, -1, 1731, 1731, 1731, -1, + 1732, 1732, 1732, -1, 1733, 1733, 1733, -1, + 1734, 1734, 1734, -1, 1735, 1735, 1735, -1, + 1736, 1736, 1736, -1, 1737, 1737, 1737, -1, + 1738, 1738, 1738, -1, 1739, 1739, 1739, -1, + 1740, 1740, 1740, -1, 1741, 1741, 1741, -1, + 1742, 1742, 1742, -1, 1743, 1743, 1743, -1, + 1744, 1744, 1744, -1, 1745, 1745, 1745, -1, + 1746, 1746, 1746, -1, 1747, 1747, 1747, -1, + 1748, 1748, 1748, -1, 1749, 1749, 1749, -1, + 1750, 1750, 1750, -1, 1751, 1751, 1751, -1, + 1752, 1752, 1752, -1, 1753, 1753, 1753, -1, + 1754, 1754, 1754, -1, 1755, 1755, 1755, -1, + 1756, 1756, 1756, -1, 1757, 1757, 1757, -1, + 1758, 1758, 1758, -1, 1759, 1759, 1759, -1, + 1760, 1760, 1760, -1, 1761, 1761, 1761, -1, + 1762, 1762, 1762, -1, 1763, 1763, 1763, -1, + 1764, 1764, 1764, -1, 1765, 1765, 1765, -1, + 1766, 1766, 1766, -1, 1767, 1767, 1767, -1, + 1768, 1768, 1768, -1, 1769, 1769, 1769, -1, + 1770, 1770, 1770, -1, 1771, 1771, 1771, -1, + 1772, 1772, 1772, -1, 1773, 1773, 1773, -1, + 1774, 1774, 1774, -1, 1775, 1775, 1775, -1, + 1776, 1776, 1776, -1, 1777, 1777, 1777, -1, + 1778, 1778, 1778, -1, 1779, 1779, 1779, -1, + 1780, 1780, 1780, -1, 1781, 1781, 1781, -1, + 1782, 1782, 1782, -1, 1783, 1783, 1783, -1, + 1784, 1784, 1784, -1, 1785, 1785, 1785, -1, + 1786, 1786, 1786, -1, 1787, 1787, 1787, -1, + 1788, 1788, 1788, -1, 1789, 1789, 1789, -1, + 1790, 1790, 1790, -1, 1791, 1791, 1791, -1, + 1792, 1792, 1792, -1, 1793, 1793, 1793, -1, + 1794, 1794, 1794, -1, 1795, 1795, 1795, -1, + 1796, 1796, 1796, -1, 1797, 1797, 1797, -1, + 1798, 1798, 1798, -1, 1799, 1799, 1799, -1, + 1800, 1800, 1800, -1, 1801, 1801, 1801, -1, + 1802, 1802, 1802, -1, 1803, 1803, 1803, -1, + 1804, 1804, 1804, -1, 1805, 1805, 1805, -1, + 1806, 1806, 1806, -1, 1807, 1807, 1807, -1, + 1808, 1808, 1808, -1, 1809, 1809, 1809, -1, + 1810, 1810, 1810, -1, 1811, 1811, 1811, -1, + 1812, 1812, 1812, -1, 1813, 1813, 1813, -1, + 1814, 1814, 1814, -1, 1815, 1815, 1815, -1, + 1816, 1816, 1816, -1, 1817, 1817, 1817, -1, + 1818, 1818, 1818, -1, 1819, 1819, 1819, -1, + 1820, 1820, 1820, -1, 1821, 1821, 1821, -1, + 1822, 1822, 1822, -1, 1823, 1823, 1823, -1, + 1824, 1824, 1824, -1, 1825, 1825, 1825, -1, + 1826, 1826, 1826, -1, 1827, 1827, 1827, -1, + 1828, 1828, 1828, -1, 1829, 1829, 1829, -1, + 1830, 1830, 1830, -1, 1831, 1831, 1831, -1, + 1832, 1832, 1832, -1, 1833, 1833, 1833, -1, + 1834, 1834, 1834, -1, 1835, 1835, 1835, -1, + 1836, 1836, 1836, -1, 1837, 1837, 1837, -1, + 1838, 1838, 1838, -1, 1839, 1839, 1839, -1, + 1840, 1840, 1840, -1, 1841, 1841, 1841, -1, + 1842, 1842, 1842, -1, 1843, 1843, 1843, -1, + 1844, 1844, 1844, -1, 1845, 1845, 1845, -1, + 1846, 1846, 1846, -1, 1847, 1847, 1847, -1, + 1848, 1848, 1848, -1, 1849, 1849, 1849, -1, + 1850, 1850, 1850, -1, 1851, 1851, 1851, -1, + 1852, 1852, 1852, -1, 1853, 1853, 1853, -1, + 1854, 1854, 1854, -1, 1855, 1855, 1855, -1, + 1856, 1856, 1856, -1, 1857, 1857, 1857, -1, + 1858, 1858, 1858, -1, 1859, 1859, 1859, -1, + 1860, 1860, 1860, -1, 1861, 1861, 1861, -1, + 1862, 1862, 1862, -1, 1863, 1863, 1863, -1, + 1864, 1864, 1864, -1, 1865, 1865, 1865, -1, + 1866, 1866, 1866, -1, 1867, 1867, 1867, -1, + 1868, 1868, 1868, -1, 1869, 1869, 1869, -1, + 1870, 1870, 1870, -1, 1871, 1871, 1871, -1, + 1872, 1872, 1872, -1, 1873, 1873, 1873, -1, + 1874, 1874, 1874, -1, 1875, 1875, 1875, -1, + 1876, 1876, 1876, -1, 1877, 1877, 1877, -1, + 1878, 1878, 1878, -1, 1879, 1879, 1879, -1, + 1880, 1880, 1880, -1, 1881, 1881, 1881, -1, + 1882, 1882, 1882, -1, 1883, 1883, 1883, -1, + 1884, 1884, 1884, -1, 1885, 1885, 1885, -1, + 1886, 1886, 1886, -1, 1887, 1887, 1887, -1, + 1888, 1888, 1888, -1, 1889, 1889, 1889, -1, + 1890, 1890, 1890, -1, 1891, 1891, 1891, -1, + 1892, 1892, 1892, -1, 1893, 1893, 1893, -1, + 1894, 1894, 1894, -1, 1895, 1895, 1895, -1, + 1896, 1896, 1896, -1, 1897, 1897, 1897, -1, + 1898, 1898, 1898, -1, 1899, 1899, 1899, -1, + 1900, 1900, 1900, -1, 1901, 1901, 1901, -1, + 1902, 1902, 1902, -1, 1903, 1903, 1903, -1, + 1904, 1904, 1904, -1, 1905, 1905, 1905, -1, + 1906, 1906, 1906, -1, 1907, 1907, 1907, -1, + 1908, 1908, 1908, -1, 1909, 1909, 1909, -1, + 1910, 1910, 1910, -1, 1911, 1911, 1911, -1, + 1912, 1912, 1912, -1, 1913, 1913, 1913, -1, + 1914, 1914, 1914, -1, 1915, 1915, 1915, -1, + 1916, 1916, 1916, -1, 1917, 1917, 1917, -1, + 1918, 1918, 1918, -1, 1919, 1919, 1919, -1, + 1920, 1920, 1920, -1, 1921, 1921, 1921, -1, + 1922, 1922, 1922, -1, 1923, 1923, 1923, -1, + 1924, 1924, 1924, -1, 1925, 1925, 1925, -1, + 1926, 1926, 1926, -1, 1927, 1927, 1927, -1, + 1928, 1928, 1928, -1, 1929, 1929, 1929, -1, + 1930, 1930, 1930, -1, 1931, 1931, 1931, -1, + 1932, 1932, 1932, -1, 1933, 1933, 1933, -1, + 1934, 1934, 1934, -1, 1935, 1935, 1935, -1, + 1936, 1936, 1936, -1, 1937, 1937, 1937, -1, + 1938, 1938, 1938, -1, 1939, 1939, 1939, -1, + 1940, 1940, 1940, -1, 1941, 1941, 1941, -1, + 1942, 1942, 1942, -1, 1943, 1943, 1943, -1, + 1944, 1944, 1944, -1, 1945, 1945, 1945, -1, + 1946, 1946, 1946, -1, 1947, 1947, 1947, -1, + 1948, 1948, 1948, -1, 1949, 1949, 1949, -1, + 1950, 1950, 1950, -1, 1951, 1951, 1951, -1, + 1952, 1952, 1952, -1, 1953, 1953, 1953, -1, + 1954, 1954, 1954, -1, 1955, 1955, 1955, -1, + 1956, 1956, 1956, -1, 1957, 1957, 1957, -1, + 1958, 1958, 1958, -1, 1959, 1959, 1959, -1, + 1960, 1960, 1960, -1, 1961, 1961, 1961, -1, + 1962, 1962, 1962, -1, 1963, 1963, 1963, -1, + 1964, 1964, 1964, -1, 1965, 1965, 1965, -1, + 1966, 1966, 1966, -1, 1967, 1967, 1967, -1, + 1968, 1968, 1968, -1, 1969, 1969, 1969, -1, + 1970, 1970, 1970, -1, 1971, 1971, 1971, -1, + 1972, 1972, 1972, -1, 1973, 1973, 1973, -1, + 1974, 1974, 1974, -1, 1975, 1975, 1975, -1, + 1976, 1976, 1976, -1, 1977, 1977, 1977, -1, + 1978, 1978, 1978, -1, 1979, 1979, 1979, -1, + 1980, 1980, 1980, -1, 1981, 1981, 1981, -1, + 1982, 1982, 1982, -1, 1983, 1983, 1983, -1, + 1984, 1984, 1984, -1, 1985, 1985, 1985, -1, + 1986, 1986, 1986, -1, 1987, 1987, 1987, -1, + 1988, 1988, 1988, -1, 1989, 1989, 1989, -1, + 1990, 1990, 1990, -1, 1991, 1991, 1991, -1, + 1992, 1992, 1992, -1, 1993, 1993, 1993, -1, + 1994, 1994, 1994, -1, 1995, 1995, 1995, -1, + 1996, 1996, 1996, -1, 1997, 1997, 1997, -1, + 1998, 1998, 1998, -1, 1999, 1999, 1999, -1, + 2000, 2000, 2000, -1, 2001, 2001, 2001, -1, + 2002, 2002, 2002, -1, 2003, 2003, 2003, -1, + 2004, 2004, 2004, -1, 2005, 2005, 2005, -1, + 2006, 2006, 2006, -1, 2007, 2007, 2007, -1, + 2008, 2008, 2008, -1, 2009, 2009, 2009, -1, + 2010, 2010, 2010, -1, 2011, 2011, 2011, -1, + 2012, 2012, 2012, -1, 2013, 2013, 2013, -1, + 2014, 2014, 2014, -1, 2015, 2015, 2015, -1, + 2016, 2016, 2016, -1, 2017, 2017, 2017, -1, + 2018, 2018, 2018, -1, 2019, 2019, 2019, -1, + 2020, 2020, 2020, -1, 2021, 2021, 2021, -1, + 2022, 2022, 2022, -1, 2023, 2023, 2023, -1, + 2024, 2024, 2024, -1, 2025, 2025, 2025, -1, + 2026, 2026, 2026, -1, 2027, 2027, 2027, -1, + 2028, 2028, 2028, -1, 2029, 2029, 2029, -1, + 2030, 2030, 2030, -1, 2031, 2031, 2031, -1, + 2032, 2032, 2032, -1, 2033, 2033, 2033, -1, + 2034, 2034, 2034, -1, 2035, 2035, 2035, -1, + 2036, 2036, 2036, -1, 2037, 2037, 2037, -1, + 2038, 2038, 2038, -1, 2039, 2039, 2039, -1, + 2040, 2040, 2040, -1, 2041, 2041, 2041, -1, + 2042, 2042, 2042, -1, 2043, 2043, 2043, -1, + 2044, 2044, 2044, -1, 2045, 2045, 2045, -1, + 2046, 2046, 2046, -1, 2047, 2047, 2047, -1, + 2048, 2048, 2048, -1, 2049, 2049, 2049, -1, + 2050, 2050, 2050, -1, 2051, 2051, 2051, -1, + 2052, 2052, 2052, -1, 2053, 2053, 2053, -1, + 2054, 2054, 2054, -1, 2055, 2055, 2055, -1, + 2056, 2056, 2056, -1, 2057, 2057, 2057, -1, + 2058, 2058, 2058, -1, 2059, 2059, 2059, -1, + 2060, 2060, 2060, -1, 2061, 2061, 2061, -1, + 2062, 2062, 2062, -1, 2063, 2063, 2063, -1, + 2064, 2064, 2064, -1, 2065, 2065, 2065, -1, + 2066, 2066, 2066, -1, 2067, 2067, 2067, -1, + 2068, 2068, 2068, -1, 2069, 2069, 2069, -1, + 2070, 2070, 2070, -1, 2071, 2071, 2071, -1, + 2072, 2072, 2072, -1, 2073, 2073, 2073, -1, + 2074, 2074, 2074, -1, 2075, 2075, 2075, -1, + 2076, 2076, 2076, -1, 2077, 2077, 2077, -1, + 2078, 2078, 2078, -1, 2079, 2079, 2079, -1, + 2080, 2080, 2080, -1, 2081, 2081, 2081, -1, + 2082, 2082, 2082, -1, 2083, 2083, 2083, -1, + 2084, 2084, 2084, -1, 2085, 2085, 2085, -1, + 2086, 2086, 2086, -1, 2087, 2087, 2087, -1, + 2088, 2088, 2088, -1, 2089, 2089, 2089, -1, + 2090, 2090, 2090, -1, 2091, 2091, 2091, -1, + 2092, 2092, 2092, -1, 2093, 2093, 2093, -1, + 2094, 2094, 2094, -1, 2095, 2095, 2095, -1, + 2096, 2096, 2096, -1, 2097, 2097, 2097, -1, + 2098, 2098, 2098, -1, 2099, 2099, 2099, -1, + 2100, 2100, 2100, -1, 2101, 2101, 2101, -1, + 2102, 2102, 2102, -1, 2103, 2103, 2103, -1, + 2104, 2104, 2104, -1, 2105, 2105, 2105, -1, + 2106, 2106, 2106, -1, 2107, 2107, 2107, -1, + 2108, 2108, 2108, -1, 2109, 2109, 2109, -1, + 2110, 2110, 2110, -1, 2111, 2111, 2111, -1, + 2112, 2112, 2112, -1, 2113, 2113, 2113, -1, + 2114, 2114, 2114, -1, 2115, 2115, 2115, -1, + 2116, 2116, 2116, -1, 2117, 2117, 2117, -1, + 2118, 2118, 2118, -1, 2119, 2119, 2119, -1, + 2120, 2120, 2120, -1, 2121, 2121, 2121, -1, + 2122, 2122, 2122, -1, 2123, 2123, 2123, -1, + 2124, 2124, 2124, -1, 2125, 2125, 2125, -1, + 2126, 2126, 2126, -1, 2127, 2127, 2127, -1, + 2128, 2128, 2128, -1, 2129, 2129, 2129, -1, + 2130, 2130, 2130, -1, 2131, 2131, 2131, -1, + 2132, 2132, 2132, -1, 2133, 2133, 2133, -1, + 2134, 2134, 2134, -1, 2135, 2135, 2135, -1, + 2136, 2136, 2136, -1, 2137, 2137, 2137, -1, + 2138, 2138, 2138, -1, 2139, 2139, 2139, -1, + 2140, 2140, 2140, -1, 2141, 2141, 2141, -1, + 2142, 2142, 2142, -1, 2143, 2143, 2143, -1, + 2144, 2144, 2144, -1, 2145, 2145, 2145, -1, + 2146, 2146, 2146, -1, 2147, 2147, 2147, -1, + 2147, 2147, 2147, -1, 2148, 2148, 2148, -1, + 2148, 2148, 2148, -1, 2149, 2149, 2149, -1, + 2149, 2149, 2149, -1, 2150, 2150, 2150, -1, + 2150, 2150, 2150, -1, 2151, 2151, 2151, -1, + 2151, 2151, 2151, -1, 2152, 2152, 2152, -1, + 2152, 2152, 2152, -1, 2153, 2153, 2153, -1, + 2153, 2153, 2153, -1, 2154, 2154, 2154, -1, + 2154, 2154, 2154, -1, 2155, 2155, 2155, -1, + 2155, 2155, 2155, -1, 2156, 2156, 2156, -1, + 2156, 2156, 2156, -1, 2157, 2157, 2157, -1, + 2157, 2157, 2157, -1, 2158, 2158, 2158, -1, + 2158, 2158, 2158, -1, 2159, 2159, 2159, -1, + 2159, 2159, 2159, -1, 2160, 2160, 2160, -1, + 2160, 2160, 2160, -1, 2161, 2161, 2161, -1, + 2161, 2161, 2161, -1, 2161, 2161, 2161, -1, + 2161, 2161, 2161, -1, 2162, 2162, 2162, -1, + 2162, 2162, 2162, -1, 2163, 2163, 2163, -1, + 2163, 2163, 2163, -1, 2164, 2164, 2164, -1, + 2164, 2164, 2164, -1, 2165, 2165, 2165, -1, + 2165, 2165, 2165, -1, 2166, 2166, 2166, -1, + 2166, 2166, 2166, -1, 2167, 2167, 2167, -1, + 2167, 2167, 2167, -1, 2168, 2168, 2168, -1, + 2168, 2168, 2168, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2170, 2170, 2170, -1, + 2170, 2170, 2170, -1, 2171, 2171, 2171, -1, + 2171, 2171, 2171, -1, 2172, 2172, 2172, -1, + 2172, 2172, 2172, -1, 2173, 2173, 2173, -1, + 2173, 2173, 2173, -1, 2174, 2174, 2174, -1, + 2174, 2174, 2174, -1, 2175, 2175, 2175, -1, + 2175, 2175, 2175, -1, 2176, 2176, 2176, -1, + 2176, 2176, 2176, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2177, 2177, 2177, -1, + 2177, 2177, 2177, -1, 2178, 2178, 2178, -1, + 2178, 2178, 2178, -1, 2179, 2179, 2179, -1, + 2179, 2179, 2179, -1, 2180, 2180, 2180, -1, + 2180, 2180, 2180, -1, 2181, 2181, 2181, -1, + 2181, 2181, 2181, -1, 2182, 2182, 2182, -1, + 2182, 2182, 2182, -1, 2183, 2183, 2183, -1, + 2183, 2183, 2183, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2184, 2184, 2184, -1, + 2184, 2184, 2184, -1, 2185, 2185, 2185, -1, + 2185, 2185, 2185, -1, 2186, 2186, 2186, -1, + 2186, 2186, 2186, -1, 2187, 2187, 2187, -1, + 2187, 2187, 2187, -1, 2188, 2188, 2188, -1, + 2188, 2188, 2188, -1, 2189, 2189, 2189, -1, + 2189, 2189, 2189, -1, 2190, 2190, 2190, -1, + 2190, 2190, 2190, -1, 2191, 2191, 2191, -1, + 2191, 2191, 2191, -1, 2192, 2192, 2192, -1, + 2192, 2192, 2192, -1, 2193, 2193, 2193, -1, + 2193, 2193, 2193, -1, 2194, 2194, 2194, -1, + 2194, 2194, 2194, -1, 2195, 2195, 2195, -1, + 2195, 2195, 2195, -1, 2196, 2196, 2196, -1, + 2196, 2196, 2196, -1, 2197, 2197, 2197, -1, + 2197, 2197, 2197, -1, 2198, 2198, 2198, -1, + 2198, 2198, 2198, -1, 2199, 2199, 2199, -1, + 2199, 2199, 2199, -1, 2200, 2200, 2200, -1, + 2200, 2200, 2200, -1, 2201, 2201, 2201, -1, + 2201, 2201, 2201, -1, 2202, 2202, 2202, -1, + 2202, 2202, 2202, -1, 2203, 2203, 2203, -1, + 2203, 2203, 2203, -1, 2204, 2204, 2204, -1, + 2204, 2204, 2204, -1, 2205, 2205, 2205, -1, + 2205, 2205, 2205, -1, 2206, 2206, 2206, -1, + 2206, 2206, 2206, -1, 2207, 2207, 2207, -1, + 2207, 2207, 2207, -1, 2208, 2208, 2208, -1, + 2208, 2208, 2208, -1, 2209, 2209, 2209, -1, + 2209, 2209, 2209, -1, 2210, 2210, 2210, -1, + 2210, 2210, 2210, -1, 2211, 2211, 2211, -1, + 2211, 2211, 2211, -1, 2212, 2212, 2212, -1, + 2212, 2212, 2212, -1, 2213, 2213, 2213, -1, + 2213, 2213, 2213, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2214, 2214, 2214, -1, + 2214, 2214, 2214, -1, 2215, 2215, 2215, -1, + 2215, 2215, 2215, -1, 2216, 2216, 2216, -1, + 2216, 2216, 2216, -1, 2217, 2217, 2217, -1, + 2217, 2217, 2217, -1, 2218, 2218, 2218, -1, + 2218, 2218, 2218, -1, 2219, 2219, 2219, -1, + 2219, 2219, 2219, -1, 2220, 2220, 2220, -1, + 2220, 2220, 2220, -1, 2221, 2221, 2221, -1, + 2221, 2221, 2221, -1, 2222, 2222, 2222, -1, + 2222, 2222, 2222, -1, 2223, 2223, 2223, -1, + 2223, 2223, 2223, -1, 2224, 2224, 2224, -1, + 2224, 2224, 2224, -1, 2225, 2225, 2225, -1, + 2225, 2225, 2225, -1, 2226, 2226, 2226, -1, + 2226, 2226, 2226, -1, 2227, 2227, 2227, -1, + 2227, 2227, 2227, -1, 2228, 2228, 2228, -1, + 2228, 2228, 2228, -1, 2186, 2186, 2186, -1, + 2186, 2186, 2186, -1, 2229, 2229, 2229, -1, + 2229, 2229, 2229, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2230, 2230, 2230, -1, + 2230, 2230, 2230, -1, 2180, 2180, 2180, -1, + 2180, 2180, 2180, -1, 2182, 2182, 2182, -1, + 2182, 2182, 2182, -1, 2231, 2231, 2231, -1, + 2231, 2231, 2231, -1, 2181, 2181, 2181, -1, + 2181, 2181, 2181, -1, 2232, 2232, 2232, -1, + 2232, 2232, 2232, -1, 2233, 2233, 2233, -1, + 2233, 2233, 2233, -1, 2234, 2234, 2234, -1, + 2234, 2234, 2234, -1, 2235, 2235, 2235, -1, + 2235, 2235, 2235, -1, 2236, 2236, 2236, -1, + 2236, 2236, 2236, -1, 2237, 2237, 2237, -1, + 2237, 2237, 2237, -1, 2238, 2238, 2238, -1, + 2238, 2238, 2238, -1, 2239, 2239, 2239, -1, + 2239, 2239, 2239, -1, 2240, 2240, 2240, -1, + 2240, 2240, 2240, -1, 2241, 2241, 2241, -1, + 2241, 2241, 2241, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2242, 2242, 2242, -1, + 2242, 2242, 2242, -1, 2243, 2243, 2243, -1, + 2243, 2243, 2243, -1, 2244, 2244, 2244, -1, + 2244, 2244, 2244, -1, 2245, 2245, 2245, -1, + 2245, 2245, 2245, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2246, 2246, 2246, -1, + 2246, 2246, 2246, -1, 2247, 2247, 2247, -1, + 2247, 2247, 2247, -1, 2248, 2248, 2248, -1, + 2248, 2248, 2248, -1, 2249, 2249, 2249, -1, + 2249, 2249, 2249, -1, 2250, 2250, 2250, -1, + 2250, 2250, 2250, -1, 2251, 2251, 2251, -1, + 2251, 2251, 2251, -1, 2252, 2252, 2252, -1, + 2252, 2252, 2252, -1, 2253, 2253, 2253, -1, + 2253, 2253, 2253, -1, 2167, 2167, 2167, -1, + 2167, 2167, 2167, -1, 2254, 2254, 2254, -1, + 2254, 2254, 2254, -1, 2255, 2255, 2255, -1, + 2255, 2255, 2255, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2256, 2256, 2256, -1, 2256, 2256, 2256, -1, + 2257, 2257, 2257, -1, 2257, 2257, 2257, -1, + 2258, 2258, 2258, -1, 2258, 2258, 2258, -1, + 2259, 2259, 2259, -1, 2259, 2259, 2259, -1, + 2260, 2260, 2260, -1, 2260, 2260, 2260, -1, + 2261, 2261, 2261, -1, 2261, 2261, 2261, -1, + 2262, 2262, 2262, -1, 2262, 2262, 2262, -1, + 2263, 2263, 2263, -1, 2263, 2263, 2263, -1, + 2264, 2264, 2264, -1, 2264, 2264, 2264, -1, + 2265, 2265, 2265, -1, 2265, 2265, 2265, -1, + 2260, 2260, 2260, -1, 2260, 2260, 2260, -1, + 2266, 2266, 2266, -1, 2266, 2266, 2266, -1, + 2267, 2267, 2267, -1, 2267, 2267, 2267, -1, + 2268, 2268, 2268, -1, 2268, 2268, 2268, -1, + 2208, 2208, 2208, -1, 2208, 2208, 2208, -1, + 2218, 2218, 2218, -1, 2218, 2218, 2218, -1, + 2217, 2217, 2217, -1, 2217, 2217, 2217, -1, + 2210, 2210, 2210, -1, 2210, 2210, 2210, -1, + 2213, 2213, 2213, -1, 2213, 2213, 2213, -1, + 2211, 2211, 2211, -1, 2211, 2211, 2211, -1, + 2209, 2209, 2209, -1, 2209, 2209, 2209, -1, + 2235, 2235, 2235, -1, 2235, 2235, 2235, -1, + 2198, 2198, 2198, -1, 2198, 2198, 2198, -1, + 2248, 2248, 2248, -1, 2248, 2248, 2248, -1, + 2269, 2269, 2269, -1, 2269, 2269, 2269, -1, + 2237, 2237, 2237, -1, 2237, 2237, 2237, -1, + 2243, 2243, 2243, -1, 2243, 2243, 2243, -1, + 2238, 2238, 2238, -1, 2238, 2238, 2238, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2270, 2270, 2270, -1, 2270, 2270, 2270, -1, + 2207, 2207, 2207, -1, 2207, 2207, 2207, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2215, 2215, 2215, -1, 2215, 2215, 2215, -1, + 2212, 2212, 2212, -1, 2212, 2212, 2212, -1, + 2194, 2194, 2194, -1, 2194, 2194, 2194, -1, + 2271, 2271, 2271, -1, 2271, 2271, 2271, -1, + 2272, 2272, 2272, -1, 2272, 2272, 2272, -1, + 2273, 2273, 2273, -1, 2273, 2273, 2273, -1, + 2186, 2186, 2186, -1, 2186, 2186, 2186, -1, + 2234, 2234, 2234, -1, 2234, 2234, 2234, -1, + 2274, 2274, 2274, -1, 2274, 2274, 2274, -1, + 2181, 2181, 2181, -1, 2181, 2181, 2181, -1, + 2275, 2275, 2275, -1, 2275, 2275, 2275, -1, + 2276, 2276, 2276, -1, 2276, 2276, 2276, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2181, 2181, 2181, -1, 2181, 2181, 2181, -1, + 2254, 2254, 2254, -1, 2254, 2254, 2254, -1, + 2277, 2277, 2277, -1, 2277, 2277, 2277, -1, + 2255, 2255, 2255, -1, 2255, 2255, 2255, -1, + 2278, 2278, 2278, -1, 2278, 2278, 2278, -1, + 2250, 2250, 2250, -1, 2250, 2250, 2250, -1, + 2251, 2251, 2251, -1, 2251, 2251, 2251, -1, + 2167, 2167, 2167, -1, 2167, 2167, 2167, -1, + 2279, 2279, 2279, -1, 2279, 2279, 2279, -1, + 2280, 2280, 2280, -1, 2280, 2280, 2280, -1, + 2281, 2281, 2281, -1, 2281, 2281, 2281, -1, + 2282, 2282, 2282, -1, 2282, 2282, 2282, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2283, 2283, 2283, -1, 2283, 2283, 2283, -1, + 2182, 2182, 2182, -1, 2182, 2182, 2182, -1, + 2284, 2284, 2284, -1, 2284, 2284, 2284, -1, + 2285, 2285, 2285, -1, 2285, 2285, 2285, -1, + 2286, 2286, 2286, -1, 2286, 2286, 2286, -1, + 2186, 2186, 2186, -1, 2186, 2186, 2186, -1, + 2287, 2287, 2287, -1, 2287, 2287, 2287, -1, + 2288, 2288, 2288, -1, 2288, 2288, 2288, -1, + 2188, 2188, 2188, -1, 2188, 2188, 2188, -1, + 2289, 2289, 2289, -1, 2289, 2289, 2289, -1, + 2290, 2290, 2290, -1, 2290, 2290, 2290, -1, + 2291, 2291, 2291, -1, 2291, 2291, 2291, -1, + 2292, 2292, 2292, -1, 2292, 2292, 2292, -1, + 2293, 2293, 2293, -1, 2293, 2293, 2293, -1, + 2294, 2294, 2294, -1, 2294, 2294, 2294, -1, + 2295, 2295, 2295, -1, 2295, 2295, 2295, -1, + 2296, 2296, 2296, -1, 2296, 2296, 2296, -1, + 2297, 2297, 2297, -1, 2297, 2297, 2297, -1, + 2298, 2298, 2298, -1, 2298, 2298, 2298, -1, + 2180, 2180, 2180, -1, 2180, 2180, 2180, -1, + 2299, 2299, 2299, -1, 2299, 2299, 2299, -1, + 2300, 2300, 2300, -1, 2300, 2300, 2300, -1, + 2301, 2301, 2301, -1, 2301, 2301, 2301, -1, + 2302, 2302, 2302, -1, 2302, 2302, 2302, -1, + 2303, 2303, 2303, -1, 2303, 2303, 2303, -1, + 2304, 2304, 2304, -1, 2304, 2304, 2304, -1, + 2180, 2180, 2180, -1, 2180, 2180, 2180, -1, + 2305, 2305, 2305, -1, 2305, 2305, 2305, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2306, 2306, 2306, -1, 2306, 2306, 2306, -1, + 2307, 2307, 2307, -1, 2307, 2307, 2307, -1, + 2308, 2308, 2308, -1, 2308, 2308, 2308, -1, + 2309, 2309, 2309, -1, 2309, 2309, 2309, -1, + 2310, 2310, 2310, -1, 2310, 2310, 2310, -1, + 2311, 2311, 2311, -1, 2311, 2311, 2311, -1, + 2237, 2237, 2237, -1, 2237, 2237, 2237, -1, + 2312, 2312, 2312, -1, 2312, 2312, 2312, -1, + 2198, 2198, 2198, -1, 2198, 2198, 2198, -1, + 2235, 2235, 2235, -1, 2235, 2235, 2235, -1, + 2238, 2238, 2238, -1, 2238, 2238, 2238, -1, + 2243, 2243, 2243, -1, 2243, 2243, 2243, -1, + 2313, 2313, 2313, -1, 2313, 2313, 2313, -1, + 2314, 2314, 2314, -1, 2314, 2314, 2314, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2246, 2246, 2246, -1, 2246, 2246, 2246, -1, + 2248, 2248, 2248, -1, 2248, 2248, 2248, -1, + 2315, 2315, 2315, -1, 2315, 2315, 2315, -1, + 2316, 2316, 2316, -1, 2316, 2316, 2316, -1, + 2317, 2317, 2317, -1, 2317, 2317, 2317, -1, + 2318, 2318, 2318, -1, 2318, 2318, 2318, -1, + 2319, 2319, 2319, -1, 2319, 2319, 2319, -1, + 2320, 2320, 2320, -1, 2320, 2320, 2320, -1, + 2242, 2242, 2242, -1, 2242, 2242, 2242, -1, + 2321, 2321, 2321, -1, 2321, 2321, 2321, -1, + 2322, 2322, 2322, -1, 2322, 2322, 2322, -1, + 2323, 2323, 2323, -1, 2323, 2323, 2323, -1, + 2192, 2192, 2192, -1, 2192, 2192, 2192, -1, + 2193, 2193, 2193, -1, 2193, 2193, 2193, -1, + 2202, 2202, 2202, -1, 2202, 2202, 2202, -1, + 2203, 2203, 2203, -1, 2203, 2203, 2203, -1, + 2200, 2200, 2200, -1, 2200, 2200, 2200, -1, + 2201, 2201, 2201, -1, 2201, 2201, 2201, -1, + 2204, 2204, 2204, -1, 2204, 2204, 2204, -1, + 2205, 2205, 2205, -1, 2205, 2205, 2205, -1, + 2206, 2206, 2206, -1, 2206, 2206, 2206, -1, + 2324, 2324, 2324, -1, 2324, 2324, 2324, -1, + 2216, 2216, 2216, -1, 2216, 2216, 2216, -1, + 2214, 2214, 2214, -1, 2214, 2214, 2214, -1, + 2246, 2246, 2246, -1, 2246, 2246, 2246, -1, + 2255, 2255, 2255, -1, 2255, 2255, 2255, -1, + 2254, 2254, 2254, -1, 2254, 2254, 2254, -1, + 2325, 2325, 2325, -1, 2325, 2325, 2325, -1, + 2326, 2326, 2326, -1, 2326, 2326, 2326, -1, + 2167, 2167, 2167, -1, 2167, 2167, 2167, -1, + 2251, 2251, 2251, -1, 2251, 2251, 2251, -1, + 2250, 2250, 2250, -1, 2250, 2250, 2250, -1, + 2327, 2327, 2327, -1, 2327, 2327, 2327, -1, + 2328, 2328, 2328, -1, 2328, 2328, 2328, -1, + 2180, 2180, 2180, -1, 2180, 2180, 2180, -1, + 2180, 2180, 2180, -1, 2180, 2180, 2180, -1, + 2329, 2329, 2329, -1, 2329, 2329, 2329, -1, + 2330, 2330, 2330, -1, 2330, 2330, 2330, -1, + 2331, 2331, 2331, -1, 2331, 2331, 2331, -1, + 2174, 2174, 2174, -1, 2174, 2174, 2174, -1, + 2175, 2175, 2175, -1, 2175, 2175, 2175, -1, + 2332, 2332, 2332, -1, 2332, 2332, 2332, -1, + 2333, 2333, 2333, -1, 2333, 2333, 2333, -1, + 2334, 2334, 2334, -1, 2334, 2334, 2334, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2335, 2335, 2335, -1, 2335, 2335, 2335, -1, + 2336, 2336, 2336, -1, 2336, 2336, 2336, -1, + 2284, 2284, 2284, -1, 2284, 2284, 2284, -1, + 2337, 2337, 2337, -1, 2337, 2337, 2337, -1, + 2338, 2338, 2338, -1, 2338, 2338, 2338, -1, + 2182, 2182, 2182, -1, 2182, 2182, 2182, -1, + 2339, 2339, 2339, -1, 2339, 2339, 2339, -1, + 2340, 2340, 2340, -1, 2340, 2340, 2340, -1, + 2341, 2341, 2341, -1, 2341, 2341, 2341, -1, + 2342, 2342, 2342, -1, 2342, 2342, 2342, -1, + 900, 900, 900, -1, 900, 900, 900, -1, + 2334, 2334, 2334, -1, 2334, 2334, 2334, -1, + 2333, 2333, 2333, -1, 2333, 2333, 2333, -1, + 2343, 2343, 2343, -1, 2343, 2343, 2343, -1, + 2344, 2344, 2344, -1, 2344, 2344, 2344, -1, + 2345, 2345, 2345, -1, 2345, 2345, 2345, -1, + 2266, 2266, 2266, -1, 2266, 2266, 2266, -1, + 2346, 2346, 2346, -1, 2346, 2346, 2346, -1, + 2221, 2221, 2221, -1, 2221, 2221, 2221, -1, + 2347, 2347, 2347, -1, 2347, 2347, 2347, -1, + 2348, 2348, 2348, -1, 2348, 2348, 2348, -1, + 2316, 2316, 2316, -1, 2316, 2316, 2316, -1, + 1248, 1248, 1248, -1, 1248, 1248, 1248, -1, + 2349, 2349, 2349, -1, 2349, 2349, 2349, -1, + 2350, 2350, 2350, -1, 2350, 2350, 2350, -1, + 2351, 2351, 2351, -1, 2351, 2351, 2351, -1, + 2318, 2318, 2318, -1, 2318, 2318, 2318, -1, + 2324, 2324, 2324, -1, 2324, 2324, 2324, -1, + 2254, 2254, 2254, -1, 2254, 2254, 2254, -1, + 2255, 2255, 2255, -1, 2255, 2255, 2255, -1, + 2246, 2246, 2246, -1, 2246, 2246, 2246, -1, + 2352, 2352, 2352, -1, 2352, 2352, 2352, -1, + 2353, 2353, 2353, -1, 2353, 2353, 2353, -1, + 2243, 2243, 2243, -1, 2243, 2243, 2243, -1, + 2238, 2238, 2238, -1, 2238, 2238, 2238, -1, + 2237, 2237, 2237, -1, 2237, 2237, 2237, -1, + 2251, 2251, 2251, -1, 2251, 2251, 2251, -1, + 2250, 2250, 2250, -1, 2250, 2250, 2250, -1, + 2354, 2354, 2354, -1, 2354, 2354, 2354, -1, + 2355, 2355, 2355, -1, 2355, 2355, 2355, -1, + 2248, 2248, 2248, -1, 2248, 2248, 2248, -1, + 2356, 2356, 2356, -1, 2356, 2356, 2356, -1, + 2357, 2357, 2357, -1, 2357, 2357, 2357, -1, + 2198, 2198, 2198, -1, 2198, 2198, 2198, -1, + 2235, 2235, 2235, -1, 2235, 2235, 2235, -1, + 2358, 2358, 2358, -1, 2358, 2358, 2358, -1, + 2359, 2359, 2359, -1, 2359, 2359, 2359, -1, + 2360, 2360, 2360, -1, 2360, 2360, 2360, -1, + 2361, 2361, 2361, -1, 2361, 2361, 2361, -1, + 2362, 2362, 2362, -1, 2362, 2362, 2362, -1, + 2363, 2363, 2363, -1, 2363, 2363, 2363, -1, + 2364, 2364, 2364, -1, 2364, 2364, 2364, -1, + 2365, 2365, 2365, -1, 2365, 2365, 2365, -1, + 2366, 2366, 2366, -1, 2366, 2366, 2366, -1, + 2367, 2367, 2367, -1, 2367, 2367, 2367, -1, + 2368, 2368, 2368, -1, 2368, 2368, 2368, -1, + 2369, 2369, 2369, -1, 2369, 2369, 2369, -1, + 2370, 2370, 2370, -1, 2370, 2370, 2370, -1, + 2371, 2371, 2371, -1, 2371, 2371, 2371, -1, + 2372, 2372, 2372, -1, 2372, 2372, 2372, -1, + 2373, 2373, 2373, -1, 2373, 2373, 2373, -1, + 2374, 2374, 2374, -1, 2374, 2374, 2374, -1, + 2375, 2375, 2375, -1, 2375, 2375, 2375, -1, + 2376, 2376, 2376, -1, 2376, 2376, 2376, -1, + 2377, 2377, 2377, -1, 2377, 2377, 2377, -1, + 2378, 2378, 2378, -1, 2378, 2378, 2378, -1, + 2379, 2379, 2379, -1, 2379, 2379, 2379, -1, + 2380, 2380, 2380, -1, 2380, 2380, 2380, -1, + 2381, 2381, 2381, -1, 2381, 2381, 2381, -1, + 2382, 2382, 2382, -1, 2382, 2382, 2382, -1, + 2383, 2383, 2383, -1, 2383, 2383, 2383, -1, + 2384, 2384, 2384, -1, 2384, 2384, 2384, -1, + 2385, 2385, 2385, -1, 2385, 2385, 2385, -1, + 2386, 2386, 2386, -1, 2386, 2386, 2386, -1, + 2387, 2387, 2387, -1, 2387, 2387, 2387, -1, + 2388, 2388, 2388, -1, 2388, 2388, 2388, -1, + 2389, 2389, 2389, -1, 2389, 2389, 2389, -1, + 2390, 2390, 2390, -1, 2390, 2390, 2390, -1, + 2391, 2391, 2391, -1, 2391, 2391, 2391, -1, + 2392, 2392, 2392, -1, 2392, 2392, 2392, -1, + 2393, 2393, 2393, -1, 2393, 2393, 2393, -1, + 2394, 2394, 2394, -1, 2394, 2394, 2394, -1, + 2395, 2395, 2395, -1, 2395, 2395, 2395, -1, + 2396, 2396, 2396, -1, 2396, 2396, 2396, -1, + 2397, 2397, 2397, -1, 2397, 2397, 2397, -1, + 2398, 2398, 2398, -1, 2398, 2398, 2398, -1, + 2399, 2399, 2399, -1, 2399, 2399, 2399, -1, + 2400, 2400, 2400, -1, 2400, 2400, 2400, -1, + 2401, 2401, 2401, -1, 2401, 2401, 2401, -1, + 2402, 2402, 2402, -1, 2402, 2402, 2402, -1, + 2403, 2403, 2403, -1, 2403, 2403, 2403, -1, + 2404, 2404, 2404, -1, 2404, 2404, 2404, -1, + 2405, 2405, 2405, -1, 2405, 2405, 2405, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1, + 2169, 2169, 2169, -1, 2169, 2169, 2169, -1 ] + ccw TRUE + solid FALSE + convex TRUE + creaseAngle 0 + + } + + } ] + +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link0-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link0-right.wrl new file mode 100644 index 0000000..320ce16 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link0-right.wrl @@ -0,0 +1,12 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + children [ + Inline { + url "kuka-swiwel.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link1-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link1-right.wrl new file mode 100644 index 0000000..8b1f4b5 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link1-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link1.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link2-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link2-right.wrl new file mode 100644 index 0000000..de49eaa --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link2-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link2.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link3-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link3-right.wrl new file mode 100644 index 0000000..c8227f7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link3-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link3.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link4-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link4-right.wrl new file mode 100644 index 0000000..8cdbb77 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link4-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link4.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link5-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link5-right.wrl new file mode 100644 index 0000000..6ed5cd0 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link5-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 -1.570796 + children [ + Inline { + url "kuka-link5.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link6-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link6-right.wrl new file mode 100644 index 0000000..93c0136 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link6-right.wrl @@ -0,0 +1,13 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + rotation 1 0 0 1.570796 + children [ + Inline { + url "kuka-link6.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4/link7-right.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link7-right.wrl new file mode 100644 index 0000000..4f70805 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4/link7-right.wrl @@ -0,0 +1,12 @@ +#VRML V2.0 utf8 +Transform { + children [ + Transform { + children [ + Inline { + url "kuka-link7.wrl" + } + ] + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.wrl new file mode 100644 index 0000000..d145196 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.wrl @@ -0,0 +1,34 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] + } + DEF package1 Transform{ + translation -0.1 -0.4 0.141 # 0.14, to avoid contact with table: 0.141 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.23 + } + } + ] + } + DEF scene1 Inline { + url "scene1.wrl" + } + ] +} + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.xml new file mode 100644 index 0000000..b2e4bd8 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene1.xml @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.wrl new file mode 100644 index 0000000..c7e4132 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.wrl @@ -0,0 +1,52 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation -0.1 -0.4 0.141 # 0.14, to avoid contact with table: 0.141 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.2 + } + } + ] +} +DEF package2 Transform{ + translation -0.1 -0.6 0.141 # 0.14, to avoid contact with table: 0.141 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.2 + } + } + ] +} + +DEF workspace Group { + children [ + Inline { + url "scene1.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.xml new file mode 100644 index 0000000..1adedbe --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.wrl new file mode 100644 index 0000000..56c7f5b --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.wrl @@ -0,0 +1,52 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation -0.1 -0.4 0.141 # 0.14, to avoid contact with table: 0.141 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.10 + } + } + ] +} +DEF package2 Transform{ + translation -0.1 -0.6 0.141 # 0.14, to avoid contact with table: 0.141 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.10 + } + } + ] +} + +DEF workspace Group { + children [ + Inline { + url "scene1.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.xml new file mode 100644 index 0000000..966f33e --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene2_collision.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.wrl b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.wrl new file mode 100644 index 0000000..035f5f8 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.wrl @@ -0,0 +1,68 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation 0.130165 -0.537904 0.877316 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package2 Transform{ + translation 0.385991 -0.2887 1.10992 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package3 Transform{ + translation 0.45 -0.1 0.55 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 3.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF workspace Group { + children [ + Inline { + url "scene1.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.xml b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.xml new file mode 100644 index 0000000..dd7ba4b --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-lwr4_scene3.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario1-workspace.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario1-workspace.wrl new file mode 100644 index 0000000..dc6601b --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario1-workspace.wrl @@ -0,0 +1,38 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF table1 Transform { + translation 0.50 0 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF table2 Transform { + translation 0.2 -0.6 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF floor Transform { + translation 0 0 -0.035 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.85 0.85 0.85 + } + } + geometry Box { + size 2 2 0.05 + } + } + ] + } + ] +} + diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario1.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario1.wrl new file mode 100644 index 0000000..882466d --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario1.wrl @@ -0,0 +1,68 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation 0.130165 -0.537904 0.877316 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package2 Transform{ + translation 0.385991 -0.2887 1.10992 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package3 Transform{ + translation 0.45 -0.1 0.55 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 3.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF workspace Group { + children [ + Inline { + url "kuka-scenario1-workspace.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario1.xml b/data/models/kuka-lwr4/rlsg/kuka-scenario1.xml new file mode 100644 index 0000000..f1579b7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario1.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd-bottles.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd-bottles.wrl new file mode 100644 index 0000000..ccd4572 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd-bottles.wrl @@ -0,0 +1,98 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform { + scale 0.7 0.7 0.7 + translation 0.130165 -0.537904 0.52 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-red.wrl" + } + ] +} +DEF package2 Transform { + scale 0.7 0.7 0.7 + translation 0.385991 -0.2887 0.52 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-green.wrl" + } + ] +} +DEF package3 Transform { + scale 0.7 0.7 0.7 + translation 0.45 -0.1 0.52 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-blue.wrl" + } + ] +} +#DEF package1 Transform{ +# translation 0.130165 -0.537904 0.877316 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 1.0 0.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.03 +# height 0.10 +# } +# } +# ] +#} +#DEF package2 Transform{ +# translation 0.385991 -0.2887 1.10992 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 1.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.03 +# height 0.10 +# } +# } +# ] +#} +#DEF package3 Transform{ +# translation 0.45 -0.1 0.55 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 3.0 +# } +# } +# geometry Cylinder { +# radius 0.03 +# height 0.10 +# } +# } +# ] +#} +DEF workspace Group { + children [ + Inline { + url "kuka-scenario2-workspace.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.wrl new file mode 100644 index 0000000..b3be18d --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.wrl @@ -0,0 +1,41 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation 0.130165 -0.537904 0.52 + children [ + Inline { + url "cylinder-red.wrl" + } + ] +} +DEF package2 Transform{ + translation 0.385991 -0.2887 0.52 + children [ + Inline { + url "cylinder-green.wrl" + } + ] +} +DEF package3 Transform{ + translation 0.45 -0.1 0.52 + children [ + Inline { + url "cylinder-blue.wrl" + } + ] +} +DEF workspace Group { + children [ + Inline { + url "kuka-scenario2-workspace.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.xml b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.xml new file mode 100644 index 0000000..73ed81d --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2-hd.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2-workspace.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario2-workspace.wrl new file mode 100644 index 0000000..e95ba99 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2-workspace.wrl @@ -0,0 +1,151 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF table1 Transform { + translation 0.50 0 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF table2 Transform { + translation 0.2 -0.6 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF floor Transform { + translation 0 0 -0.025 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.85 0.85 0.85 + } + } + geometry Box { + size 2 2 0.05 + } + } + ] + } + DEF cabinetTop Transform { + translation 0.2 -0.76 0.65 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.8 + diffuseColor 0.5 0.5 0.5 + } + } + geometry Box { + size 0.54 0.22 0.03 + } + } + ] + } + DEF cabinetLeft Transform { + translation 0.455 -0.76 0.5326 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.8 + diffuseColor 0.5 0.5 0.5 + } + } + geometry Box { + size 0.03 0.22 0.2049 + } + } + ] + } + DEF cabinetRight Transform { + translation -0.055 -0.76 0.5326 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.8 + diffuseColor 0.5 0.5 0.5 + } + } + geometry Box { + size 0.03 0.22 0.2049 + } + } + ] + } + DEF cabinetBack Transform { + translation 0.2 -0.855 0.5326 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.8 + diffuseColor 0.5 0.5 0.5 + } + } + geometry Box { + size 0.48 0.03 0.2049 + } + } + ] + } + + +# DEF objectAir Transform { +# translation 0.25 -0.20 0.7 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# transparency 0.5 +# } +# } +# geometry Box { +# size 0.9 0.9 0.5 +# } +# } +# ] +# } + +# DEF SS1 Transform { +# translation 0.5 0.0 0.55 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# transparency 0.5 +# } +# } +# geometry Box { +# size 0.5 0.5 0.1 +# } +# } +# ] +# } + +# DEF SS1 Transform { +# translation 0.2 -0.55 0.55 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# transparency 0.5 +# } +# } +# geometry Box { +# size 0.5 0.4 0.1 +# } +# } +# ] +# } + ] +} + diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2.wrl b/data/models/kuka-lwr4/rlsg/kuka-scenario2.wrl new file mode 100644 index 0000000..80222a7 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2.wrl @@ -0,0 +1,68 @@ +#VRML V2.0 utf8 + +DEF kuka-lwr4-right Transform { + translation 0 0 0 + children [ + Inline { + url "kuka-lwr4/kuka-lwr4-right.wrl" + } + ] +} +DEF package1 Transform{ + translation 0.130165 -0.537904 0.877316 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package2 Transform{ + translation 0.385991 -0.2887 1.10992 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF package3 Transform{ + translation 0.45 -0.1 0.55 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 3.0 + } + } + geometry Cylinder { + radius 0.03 + height 0.10 + } + } + ] +} +DEF workspace Group { + children [ + Inline { + url "kuka-scenario2-workspace.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/kuka-scenario2.xml b/data/models/kuka-lwr4/rlsg/kuka-scenario2.xml new file mode 100644 index 0000000..6bef135 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/kuka-scenario2.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/kuka-lwr4/rlsg/meka-scenario1-hd.wrl b/data/models/kuka-lwr4/rlsg/meka-scenario1-hd.wrl new file mode 100644 index 0000000..40f8b5c --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/meka-scenario1-hd.wrl @@ -0,0 +1,126 @@ +#VRML V2.0 utf8 + +DEF mekabot Group { + children [ + Inline { + url "rlsg/mekabot-torso-rightarm.convex-hd.wrl" + } + ] +} + +#DEF package1 Transform{ +# translation 0.0376622556475922 -0.353289011970628 0.299010842949152 #-0.1 -0.4 0.146 # 0.145, to avoid contact with table: 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 1.0 0.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package2 Transform{ +# translation 0.16 0.0 0.146 #0.04 0.0 0.196 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 1.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package3 Transform{ +# translation 0.25 -0.3 -0.094 #-0.1 0.4 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 1.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} + +DEF package1 Transform { + translation 0.16 -0.35 0.146 # 0.025, to avoid contact with table: 0.026 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-red.wrl" + } + ] +} +DEF package2 Transform { + translation 0.0 -0.2 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-green.wrl" + } + ] +} +DEF package3 Transform { + translation -0.1 0.4 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-blue.wrl" + } + ] +} +#DEF package4 Transform { +# translation 0.13 -0.3 0.146 # 0.025, to avoid contact with table: 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-red-trans.wrl" +# } +# ] +#} +#DEF package5 Transform { +# translation 0.13 -0.2 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-green-trans.wrl" +# } +# ] +#} +#DEF package6 Transform { +# translation 0.13 -0.1 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-blue-trans.wrl" +# } +# ] +#} + +DEF workspace Group { + children [ + Inline { + url "environment.wrl" + } + ] +} diff --git a/data/models/kuka-lwr4/rlsg/scene1.wrl b/data/models/kuka-lwr4/rlsg/scene1.wrl new file mode 100644 index 0000000..cd0122b --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/scene1.wrl @@ -0,0 +1,37 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF table1 Transform { + translation 0.50 0 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF table2 Transform { + translation 0.2 -0.6 0 + children [ + Inline { + url "table.wrl" + } + ] + } + DEF floor Transform { + translation 0 0 -0.025 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.7 + } + } + geometry Box { + size 2 2 0.05 + } + } + ] + } + ] +} + diff --git a/data/models/kuka-lwr4/rlsg/table.wrl b/data/models/kuka-lwr4/rlsg/table.wrl new file mode 100644 index 0000000..33a3ed0 --- /dev/null +++ b/data/models/kuka-lwr4/rlsg/table.wrl @@ -0,0 +1,86 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF table Transform { + translation 0 0 0.405 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.5 0.5 0.5 + } + } + geometry Box { + size 0.54 0.54 0.05 + } + } + Transform { + translation 0.233 0.233 -0.22 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.3 0.3 0.3 + } + } + geometry Box { + size 0.06 0.06 0.387 + } + } + ] + } + Transform { + translation -0.233 0.233 -0.22 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.3 0.3 0.3 + } + } + geometry Box { + size 0.06 0.06 0.387 + } + } + ] + } + Transform { + translation 0.233 -0.233 -0.22 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.3 0.3 0.3 + } + } + geometry Box { + size 0.06 0.06 0.387 + } + } + ] + } + Transform { + translation -0.233 -0.233 -0.22 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.3 0.3 0.3 + } + } + geometry Box { + size 0.06 0.06 0.385 + } + } + ] + } + ] + } + ] +} + diff --git a/data/models/mekabot-convex/bottle-blue-trans.wrl b/data/models/mekabot-convex/bottle-blue-trans.wrl new file mode 100644 index 0000000..3fa62bd --- /dev/null +++ b/data/models/mekabot-convex/bottle-blue-trans.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.5 + diffuseColor 0.2 0.2 0.8 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-blue.wrl b/data/models/mekabot-convex/bottle-blue.wrl new file mode 100644 index 0000000..2239011 --- /dev/null +++ b/data/models/mekabot-convex/bottle-blue.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.2 0.2 0.8 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-green-trans.wrl b/data/models/mekabot-convex/bottle-green-trans.wrl new file mode 100644 index 0000000..ef73d1a --- /dev/null +++ b/data/models/mekabot-convex/bottle-green-trans.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.5 + diffuseColor 0.2 0.8 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-green.wrl b/data/models/mekabot-convex/bottle-green.wrl new file mode 100644 index 0000000..c11fb44 --- /dev/null +++ b/data/models/mekabot-convex/bottle-green.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.2 0.8 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-invisible.wrl b/data/models/mekabot-convex/bottle-invisible.wrl new file mode 100644 index 0000000..ce5972d --- /dev/null +++ b/data/models/mekabot-convex/bottle-invisible.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.8 + diffuseColor 0.8 0.2 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-red-trans.wrl b/data/models/mekabot-convex/bottle-red-trans.wrl new file mode 100644 index 0000000..16ba041 --- /dev/null +++ b/data/models/mekabot-convex/bottle-red-trans.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.5 + diffuseColor 0.8 0.2 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/bottle-red.wrl b/data/models/mekabot-convex/bottle-red.wrl new file mode 100644 index 0000000..32f8036 --- /dev/null +++ b/data/models/mekabot-convex/bottle-red.wrl @@ -0,0 +1,2119 @@ +#VRML V2.0 utf8 + +DEF bottle Transform { + translation 0 0 -0.121 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.8 0.2 0.2 + } + } + geometry IndexedFaceSet { + coord Coordinate { point [ + # points 1532 + -0.031967 0.001448 0.01, -0.031967 0.001448 0.129114, -0.031848 -0.002846 0.01, -0.031848 -0.002846 0.129114, + -0.031837 -0.003222 0.01, -0.031837 -0.003222 0.129114, -0.031709 0.003618 0.01, -0.031709 0.003618 0.129114, + -0.031686 0.001435 0.136608, -0.031627 0.001433 0.007412, -0.031558 -0.003194 0.136608, -0.031498 -0.003188 0.007412, + -0.031416 0.006087 0.01, -0.031416 0.006087 0.129114, -0.03114 0.006034 0.136608, -0.031081 0.006022 0.007412, + -0.031029 -0.007823 0.01, -0.031029 -0.007823 0.129114, -0.030845 0.001397 0.14406, -0.030756 -0.007754 0.136608, + -0.03072 -0.003109 0.14406, -0.030699 -0.00774 0.007412, -0.030629 0.001387 0.005, -0.030579 -0.009181 0.01, + -0.030579 -0.009181 0.129114, -0.030504 -0.003087 0.005, -0.030372 0.009943 0.01, -0.030372 0.009943 0.129114, + -0.030313 0.005873 0.14406, -0.030195 0.010596 0.01, -0.030195 0.010596 0.129114, -0.0301 0.005832 0.005, + -0.02994 -0.007549 0.14406, -0.029929 0.010503 0.136608, -0.029873 0.010484 0.007412, -0.02973 -0.007496 0.005, + -0.029559 -0.012258 0.01, -0.029559 -0.012258 0.129114, -0.029449 0.001334 0.151428, -0.029329 -0.002968 0.151428, + -0.0293 -0.01215 0.136608, -0.029245 -0.012127 0.007412, -0.029135 0.010224 0.14406, -0.029041 0.001316 0.002929, + -0.028941 0.005608 0.151428, -0.02893 0.010153 0.005, -0.028923 -0.002927 0.002929, -0.028584 -0.007207 0.151428, + -0.02854 0.00553 0.002929, -0.028522 -0.011827 0.14406, -0.02833 0.01488 0.01, -0.02833 0.01488 0.129114, + -0.028322 -0.011744 0.005, -0.028189 -0.007107 0.002929, -0.028103 -0.015153 0.01, -0.028103 -0.015153 0.129114, + -0.028081 0.014749 0.136608, -0.028028 0.014721 0.007412, -0.027816 0.009762 0.151428, -0.027733 0.015839 0.01, + -0.027733 0.015839 0.129114, -0.027504 0.001246 0.15867, -0.02746 -0.016431 0.01, -0.02746 -0.016431 0.129114, + -0.027431 0.009627 0.002929, -0.027393 -0.002772 0.15867, -0.027336 0.014358 0.14406, -0.02723 -0.011292 0.151428, + -0.027218 -0.016286 0.136608, -0.027167 -0.016256 0.007412, -0.027144 0.014257 0.005, -0.02703 0.005237 0.15867, + -0.026972 0.001222 0.00134, -0.026863 -0.002718 0.00134, -0.026854 -0.011136 0.002929, -0.026697 -0.006731 0.15867, + -0.026507 0.005136 0.00134, -0.026496 -0.015854 0.14406, -0.02631 -0.015743 0.005, -0.026181 -0.006601 0.00134, + -0.026098 0.013708 0.151428, -0.025979 0.009117 0.15867, -0.025862 0.018846 0.01, -0.025862 0.018846 0.129114, + -0.025737 0.013518 0.002929, -0.025634 0.018681 0.136608, -0.025586 0.018645 0.007412, -0.025477 0.008941 0.00134, + -0.025433 -0.010546 0.15867, -0.025296 -0.015136 0.151428, -0.025024 0.001134 0.165746, -0.024954 0.018185 0.14406, + -0.024949 -0.001561 0.165746, -0.024946 -0.014927 0.002929, -0.024941 -0.010342 0.00134, -0.024922 -0.002522 0.165746, + -0.024853 0.002567 0.165746, -0.024779 0.018057 0.005, -0.024775 -0.020254 0.01, -0.024775 -0.020254 0.129114, + -0.024592 0.004765 0.165746, -0.024563 0.001113 0.000341, -0.024557 -0.020076 0.136608, -0.024516 -0.020527 0.01, + -0.024516 -0.020527 0.129114, -0.024511 -0.020038 0.007412, -0.024463 -0.002476 0.000341, -0.024375 0.012803 0.15867, + -0.024372 -0.00565 0.165746, -0.024289 -0.006124 0.165746, -0.024139 0.004677 0.000341, -0.024089 0.006623 0.165746, + -0.023962 0.021089 0.01, -0.023962 0.021089 0.129114, -0.023905 -0.019543 0.14406, -0.023903 0.012555 0.00134, + -0.023842 -0.006011 0.000341, -0.023824 0.017361 0.151428, -0.023737 -0.019406 0.005, -0.023636 0.008295 0.165746, + -0.023626 -0.014137 0.15867, -0.023495 0.017121 0.002929, -0.023201 0.008142 0.000341, -0.023169 -0.013863 0.00134, + -0.023139 -0.009595 0.165746, -0.022842 0.022411 0.01, -0.022842 0.022411 0.129114, -0.022823 -0.018658 0.151428, + -0.022713 -0.009418 0.000341, -0.022676 0.010501 0.165746, -0.022641 0.022214 0.136608, -0.022599 0.022172 0.007412, + -0.022507 -0.0184 0.002929, -0.022251 0.016215 0.15867, -0.022176 0.011648 0.165746, -0.02204 0.021624 0.14406, + -0.021977 0.000996 0, -0.021888 -0.002215 0, -0.021886 0.021473 0.005, -0.021821 0.015901 0.00134, + -0.021768 0.011433 0.000341, -0.021598 0.004185 0, -0.021562 -0.023645 0.01, -0.021562 -0.023645 0.129114, + -0.021495 -0.012862 0.165746, -0.021372 -0.023437 0.136608, -0.021332 -0.005378 0, -0.021332 -0.023393 0.007412, + -0.021316 -0.017426 0.15867, -0.021219 -0.013255 0.165746, -0.021099 -0.012625 0.000341, -0.021042 0.020645 0.151428, + -0.021031 -0.001314 0.176727, -0.020961 0.002165 0.176727, -0.020904 -0.017089 0.00134, -0.020805 -0.022815 0.14406, + -0.020759 0.007285 0, -0.020751 0.02036 0.002929, -0.020659 -0.022655 0.005, -0.020651 0.014099 0.165746, + -0.020528 -0.004758 0.176727, -0.020322 -0.008427 0, -0.020319 0.005586 0.176727, -0.020244 0.014753 0.165746, + -0.019872 0.014481 0.000341, -0.019863 -0.021782 0.151428, -0.019844 -0.024996 0.01, -0.019844 -0.024996 0.129114, + -0.019653 0.019282 0.15867, -0.019588 -0.021481 0.002929, -0.019477 0.01023 0, -0.019465 -0.008072 0.176727, + -0.019393 -0.015854 0.165746, -0.019336 0.025498 0.01, -0.019336 0.025498 0.129114, -0.019273 0.018909 0.00134, + -0.019272 0.025539 0.01, -0.019272 0.025539 0.129114, -0.019166 0.025274 0.136608, -0.01913 0.025226 0.007412, + -0.019122 0.008854 0.176727, -0.019036 -0.015563 0.000341, -0.018878 -0.011296 0, -0.018732 -0.016553 0.165746, + -0.018657 0.024603 0.14406, -0.018552 -0.020344 0.15867, -0.018526 0.02443 0.005, -0.018193 -0.019951 0.00134, + -0.018067 0.017323 0.165746, -0.017889 -0.026533 0.01, -0.017889 -0.026533 0.129114, -0.01788 0.017543 0.165746, + -0.017871 -0.011166 0.176727, -0.017812 0.023489 0.151428, -0.01778 0.012957 0, -0.017732 -0.0263 0.136608, + -0.017699 -0.02625 0.007412, -0.017673 -0.001104 0.187911, -0.017614 0.00182 0.187911, -0.017566 0.023164 0.002929, + -0.017551 0.01722 0.000341, -0.017404 0.011881 0.176727, -0.017261 -0.025601 0.14406, -0.01725 -0.003998 0.187911, + -0.01714 -0.025422 0.005, -0.017074 0.004694 0.187911, -0.017033 -0.013925 0, -0.016878 -0.018509 0.165746, + -0.016636 0.021938 0.15867, -0.016568 -0.018169 0.000341, -0.01648 -0.024442 0.151428, -0.016357 -0.006783 0.187911, + -0.016314 0.021514 0.00134, -0.016252 -0.024104 0.002929, -0.016069 0.00744 0.187911, -0.01579 -0.013955 0.176727, + -0.015744 -0.019401 0.165746, -0.015704 0.015407 0, -0.015417 0.028041 0.01, -0.015417 0.028041 0.129114, + -0.015392 -0.022829 0.15867, -0.015282 0.027795 0.136608, -0.015253 0.027743 0.007412, -0.015211 0.014583 0.176727, + -0.015136 0.019959 0.165746, -0.015094 -0.022387 0.00134, -0.015017 -0.009383 0.187911, -0.014995 0.000387 0, + -0.014974 0.020064 0.165746, -0.014935 -0.000933 0.199264, -0.014885 0.001538 0.199264, -0.014876 0.027057 0.14406, + -0.014857 0.019592 0.000341, -0.014824 -0.016256 0, -0.014772 0.026867 0.005, -0.014748 -0.002739 0, + -0.014625 0.009984 0.187911, -0.014587 0.003496 0, -0.014578 -0.003379 0.199264, -0.014429 0.003967 0.199264, + -0.014423 -0.028518 0.01, -0.014423 -0.028518 0.129114, -0.014202 0.025832 0.151428, -0.014006 0.025475 0.002929, + -0.014003 -0.020769 0.165746, -0.013856 -0.005746 0, -0.013835 -0.028855 0.01, -0.013835 -0.028855 0.129114, + -0.013823 -0.005732 0.199264, -0.013746 -0.020387 0.000341, -0.013714 -0.028601 0.136608, -0.013705 0.028826 0.01, + -0.013705 0.028826 0.129114, -0.013688 -0.028547 0.007412, -0.013579 0.006288 0.199264, -0.013541 0.006452 0, + -0.01335 -0.027842 0.14406, -0.013293 0.01753 0, -0.013277 -0.016363 0.176727, -0.013268 -0.011726 0.187911, + -0.013265 0.024127 0.15867, -0.013256 -0.027647 0.005, -0.013008 0.02366 0.00134, -0.012827 -0.000801 0.21075, + -0.012784 0.001321 0.21075, -0.012782 0.012255 0.187911, -0.012745 -0.026581 0.151428, -0.012733 0.000328 0.000259, + -0.012691 -0.007929 0.199264, -0.012603 0.016888 0.176727, -0.012569 -0.026214 0.002929, -0.012523 -0.002326 0.000259, + -0.01252 -0.002902 0.21075, -0.012392 0.003407 0.21075, -0.012387 0.002969 0.000259, -0.012359 0.008437 0.199264, + -0.012359 -0.008501 0, -0.012333 -0.021726 0.165746, -0.012299 -0.018241 0, -0.012068 0.02195 0.165746, -0.011904 0.009127 0, + -0.011904 -0.024826 0.15867, -0.011872 -0.004923 0.21075, -0.011846 0.021546 0.000341, -0.011766 -0.004879 0.000259, + -0.011673 -0.024346 0.00134, -0.011662 0.0054 0.21075, -0.011499 0.005479 0.000259, -0.011456 0.022231 0.165746, + -0.011354 -0.000709 0.222336, -0.011316 0.001169 0.222336, -0.011213 -0.00991 0.199264, -0.01117 0.029987 0.01, + -0.01117 0.029987 0.129114, -0.011157 -0.01375 0.187911, -0.011083 -0.002569 0.222336, -0.011072 0.029724 0.136608, + -0.011051 0.029668 0.007412, -0.010969 0.003016 0.222336, -0.0109 -0.00681 0.21075, -0.01083 -0.022587 0.165746, + -0.010802 0.010356 0.199264, -0.010778 0.028935 0.14406, -0.010741 0.001181 0.257334, -0.010712 0.001178 0.257917, + -0.010711 -0.000673 0.257334, -0.010702 0.028732 0.005, -0.010697 -0.001527 0.257334, -0.010668 -0.001523 0.257917, + -0.010631 -0.022171 0.000341, -0.010615 0.007246 0.21075, -0.010599 0.019278 0, -0.010591 0.014191 0.187911, + -0.010589 0.000273 0.001024, -0.010549 0.00116 0.258477, -0.010522 -0.000657 0.233986, -0.010509 -0.004358 0.222336, + -0.010506 -0.001499 0.258477, -0.010494 -0.007219 0.000259, -0.010486 0.001083 0.233986, -0.010453 -0.002419 0.257334, + -0.010414 -0.001934 0.001024, -0.010403 -0.018326 0.176727, -0.010342 0.002846 0.257334, -0.010331 -0.000646 0.245663, + -0.010323 0.00478 0.222336, -0.010321 -0.010885 0, -0.0103 0.002469 0.001024, -0.010297 0.001064 0.245663, + -0.01029 0.027625 0.151428, -0.01027 -0.00238 0.233986, -0.010262 0.001129 0.258983, -0.01022 -0.001459 0.258983, + -0.010165 0.002795 0.233986, -0.010147 0.027243 0.002929, -0.01011 0.003816 0.257334, -0.010108 0.00775 0.000259, + -0.010084 -0.002337 0.245663, -0.010082 0.003805 0.257917, -0.009981 -0.004139 0.257334, -0.009981 0.002744 0.245663, + -0.009954 -0.004128 0.257917, -0.009929 0.003747 0.258477, -0.009865 0.001085 0.259409, -0.009825 -0.001402 0.259409, + -0.009803 -0.004065 0.258477, -0.009784 -0.004057 0.001024, -0.009746 0.011402 0, -0.009743 0.004507 0.257334, + -0.009738 -0.004038 0.233986, -0.009658 0.003645 0.258983, -0.009652 0.018732 0.176727, -0.009648 -0.006028 0.222336, + -0.00963 -0.008511 0.21075, -0.00961 0.025801 0.15867, -0.009566 0.00443 0.233986, -0.009562 0.004556 0.001024, + -0.009562 -0.003965 0.245663, -0.009536 -0.003954 0.258983, -0.009512 -0.019838 0, -0.009487 -0.030562 0.01, + -0.009487 -0.030562 0.129114, -0.009429 -0.01162 0.199264, -0.009425 0.025302 0.00134, -0.009403 -0.030293 0.136608, + -0.009396 0.006414 0.222336, -0.009393 0.004349 0.245663, -0.009386 -0.030236 0.007412, -0.009382 0.001032 0.259731, + -0.009344 -0.001334 0.259731, -0.009286 0.003505 0.259409, -0.009277 0.008894 0.21075, -0.009168 -0.003802 0.259409, + -0.009154 -0.029489 0.14406, -0.009097 -0.005687 0.257334, -0.009089 -0.029282 0.005, -0.00895 0.011993 0.199264, + -0.008941 -0.005586 0.233986, -0.008909 0.006084 0.257334, -0.008843 0.00621 0.257334, -0.008837 0.000972 0.259932, + -0.00883 0.003333 0.259731, -0.008819 0.006193 0.257917, -0.008801 -0.001256 0.259932, -0.008779 -0.005485 0.245663, + -0.008764 -0.009243 0.000259, -0.008744 0.023474 0.165746, -0.008742 -0.015399 0.187911, -0.008739 -0.028154 0.151428, + -0.008727 -0.006003 0.001024, -0.008719 -0.003615 0.259731, -0.008707 0.005944 0.233986, -0.008685 0.006099 0.258477, + -0.008673 0.000224 0.002254, -0.008638 -0.006491 0.257334, -0.008618 -0.027764 0.002929, -0.008615 -0.006474 0.257917, + -0.00859 -0.023466 0.165746, -0.008583 0.023042 0.000341, -0.008549 0.005836 0.245663, -0.00853 -0.001584 0.002254, + -0.008524 -0.007534 0.222336, -0.008484 -0.006375 0.258477, -0.008448 0.005933 0.258983, -0.008437 0.002022 0.002254, + -0.008406 0.006445 0.001024, -0.008386 -0.030817 0.01, -0.008386 -0.030817 0.129114, -0.008318 0.003139 0.259932, + -0.008276 0.009682 0.000259, -0.008261 0.000909 0.26, -0.008253 -0.006202 0.258983, -0.008228 -0.001174 0.26, + -0.008212 -0.003406 0.259932, -0.008212 0.007873 0.222336, -0.008162 -0.026295 0.15867, -0.008122 0.005704 0.259409, + -0.00811 0.015741 0.187911, -0.008098 -0.00998 0.21075, -0.008044 -0.007105 0.257334, -0.008014 -0.003323 0.002254, + -0.008004 -0.025786 0.00134, -0.007934 -0.005962 0.259409, -0.007899 -0.006981 0.233986, -0.007832 -0.012793 0, + -0.007832 0.003732 0.002254, -0.007776 0.002935 0.26, -0.007756 -0.006855 0.245663, -0.00774 0.007423 0.257334, + -0.007724 0.005424 0.259731, -0.007687 0.0103 0.21075, -0.007679 0.020616 0, -0.007677 -0.003184 0.26, + -0.007635 0.023797 0.165746, -0.007624 0.03102 0.01, -0.007624 0.03102 0.129114, -0.00761 0.007296 0.233986, + -0.007546 -0.00567 0.259731, -0.007472 0.007164 0.245663, -0.007426 -0.023923 0.165746, -0.007388 -0.013014 0.199264, + -0.007289 -0.023483 0.000341, -0.007288 -0.007686 0.001024, -0.007276 0.005109 0.259932, -0.007245 -0.019788 0.176727, + -0.007168 -0.008834 0.222336, -0.007163 0.013179 0, -0.007148 -0.004917 0.002254, -0.007108 -0.005341 0.259932, + -0.007084 0.000183 0.003886, -0.007021 0.008214 0.257334, -0.007002 0.008191 0.257917, -0.006968 -0.001294 0.003886, + -0.006895 0.008067 0.258477, -0.006892 0.001652 0.003886, -0.006885 0.005279 0.002254, -0.006882 0.008052 0.001024, + -0.006854 0.013303 0.199264, -0.006804 0.009117 0.222336, -0.006802 0.004776 0.26, -0.006753 -0.008436 0.257334, + -0.006734 -0.008413 0.257917, -0.006708 0.007847 0.258983, -0.006685 0.031294 0.01, -0.006685 0.031294 0.129114, + -0.006651 -0.010863 0.000259, -0.006644 -0.004993 0.26, -0.006642 -0.008186 0.233986, -0.006632 -0.008285 0.258477, + -0.006626 0.031019 0.136608, -0.006613 0.030961 0.007412, -0.006546 -0.002715 0.003886, -0.006522 -0.008038 0.245663, + -0.006522 -0.021011 0, -0.006451 -0.008059 0.258983, -0.00645 0.030196 0.14406, -0.006449 0.007544 0.259409, + -0.006437 0.020065 0.176727, -0.006426 0.008605 0.257334, -0.006405 0.029984 0.005, -0.006398 0.003048 0.003886, + -0.006345 -0.011177 0.21075, -0.006305 0.008449 0.233986, -0.006202 -0.007748 0.259409, -0.006191 0.008296 0.245663, + -0.006158 0.028828 0.151428, -0.006133 0.007175 0.259731, -0.006088 -0.016628 0.187911, -0.006082 0.011191 0.000259, + -0.006073 0.02843 0.002929, -0.005969 -0.006295 0.002254, -0.005907 0.000152 0.005835, -0.005898 -0.007368 0.259731, + -0.005887 0.011425 0.21075, -0.005839 -0.004016 0.003886, -0.005809 -0.001079 0.005835, -0.005777 0.006758 0.259932, + -0.005751 0.026925 0.15867, -0.005746 0.001377 0.005835, -0.00564 0.026404 0.00134, -0.005637 0.006595 0.002254, + -0.005624 0.004312 0.003886, -0.005616 -0.009893 0.222336, -0.005556 -0.006941 0.259932, -0.005531 -0.009033 0.001024, + -0.005458 -0.002263 0.005835, -0.005409 0.016861 0.187911, -0.0054 0.006318 0.26, -0.005334 0.002542 0.005835, + -0.005293 -0.009329 0.257334, -0.005233 0.024497 0.165746, -0.005211 0.010113 0.222336, -0.005204 -0.009168 0.233986, + -0.005194 -0.006488 0.26, -0.005158 0.000677 0.008, -0.005158 0.000134 0.008, -0.005157 -0.000681 0.008, + -0.005145 -0.014052 0.199264, -0.005136 0.024046 0.000341, -0.00511 -0.009002 0.245663, -0.005087 -0.000943 0.008, + -0.005058 0.009307 0.001024, -0.005018 0.001201 0.008, -0.005002 -0.014142 0, -0.004983 0.000654 0.008541, + -0.004982 -0.000658 0.008541, -0.004936 -0.031617 0.01, -0.004936 -0.031617 0.129114, -0.004936 0.009585 0.257334, + -0.004892 -0.031339 0.136608, -0.004883 -0.03128 0.007412, -0.004876 -0.005143 0.003886, -0.004868 -0.003349 0.005835, + -0.004828 0.009371 0.233986, -0.004807 0.001989 0.008, -0.004805 -0.001993 0.008, -0.004762 -0.030507 0.14406, + -0.004758 0.009702 0.257334, -0.004745 0.009675 0.257917, -0.004741 0.009202 0.245663, -0.004729 -0.030293 0.005, + -0.004691 0.000616 0.009029, -0.00469 -0.000619 0.009029, -0.004689 0.003595 0.005835, -0.004673 0.009528 0.258477, + -0.004672 0.002223 0.008, -0.004644 0.001921 0.008541, -0.004642 -0.001925 0.008541, -0.004613 -0.024576 0.165746, + -0.004605 0.005387 0.003886, -0.004596 0.021515 0, -0.004571 0.014249 0.199264, -0.004547 -0.029126 0.151428, + -0.004545 0.009269 0.258983, -0.00453 -0.007399 0.002254, -0.004484 -0.028723 0.002929, -0.004443 -0.00985 0.257334, + -0.004431 -0.009823 0.257917, -0.004419 -0.012069 0.21075, -0.004371 0.001809 0.009029, -0.00437 -0.001812 0.009029, + -0.00437 0.008911 0.259409, -0.004363 -0.009674 0.258477, -0.004297 0.000564 0.009436, -0.004296 -0.000567 0.009436, + -0.004266 0.014381 0, -0.004261 -0.002934 0.008, -0.004247 -0.012008 0.000259, -0.004247 -0.027203 0.15867, + -0.004245 -0.009411 0.258983, -0.004164 -0.026677 0.00134, -0.004156 0.008474 0.259731, -0.004143 0.007622 0.002254, + -0.004128 0.003165 0.008, -0.004126 -0.003168 0.008, -0.004081 -0.009047 0.259409, -0.004066 -0.004288 0.005835, + -0.004004 0.001657 0.009436, -0.004003 -0.00166 0.009436, -0.003988 0.003058 0.008541, -0.003986 -0.003061 0.008541, + -0.003926 0.012238 0.21075, -0.003914 0.007982 0.259932, -0.003911 -0.010683 0.222336, -0.003889 -0.02071 0.176727, + -0.003881 -0.008604 0.259731, -0.003864 -0.024749 0.165746, -0.003839 0.004491 0.005835, -0.003822 0.000502 0.009744, + -0.003821 -0.000505 0.009744, -0.003792 -0.024294 0.000341, -0.003754 0.002878 0.009029, -0.003752 -0.002881 0.009029, + -0.0037 -0.006044 0.003886, -0.003694 -0.01008 0.257334, -0.003659 0.007462 0.26, -0.003655 -0.008104 0.259932, + -0.003624 -0.009899 0.233986, -0.003622 0.012211 0.000259, -0.003612 0.024721 0.165746, -0.003562 0.001474 0.009744, + -0.003561 -0.001476 0.009744, -0.003559 -0.009721 0.245663, -0.003549 -0.003745 0.008, -0.003532 -0.009986 0.001024, + -0.003475 0.010833 0.222336, -0.003439 0.002637 0.009436, -0.003437 -0.00264 0.009436, -0.003417 -0.007576 0.26, + -0.003393 -0.021737 0, -0.003384 0.006227 0.003886, -0.00336 0.003934 0.008, -0.00329 0.000432 0.009935, + -0.00329 -0.000434 0.009935, -0.003274 0.010211 0.257334, -0.003268 -0.017403 0.187911, -0.00322 0.010038 0.233986, + -0.003168 0.004126 0.008, -0.003165 -0.004128 0.008, -0.003162 0.009857 0.245663, -0.003085 -0.005039 0.005835, + -0.003066 0.001269 0.009935, -0.003065 -0.001271 0.009935, -0.003061 0.003986 0.008541, -0.003059 0.002345 0.009744, + -0.003058 -0.003988 0.008541, -0.003057 -0.002348 0.009744, -0.003046 0.020851 0.176727, -0.003012 0.010155 0.001024, + -0.002893 -0.008179 0.002254, -0.002881 0.003752 0.009029, -0.002878 -0.003754 0.009029, -0.002821 0.005192 0.005835, + -0.002762 -0.014707 0.199264, -0.002729 0.000358 0.01, -0.002729 -0.00036 0.01, -0.002695 -0.0044 0.008, + -0.00264 0.003437 0.009436, -0.002637 -0.003439 0.009436, -0.002633 0.002019 0.009935, -0.002632 -0.002021 0.009935, + -0.00256 0.017521 0.187911, -0.002543 0.001052 0.01, -0.002543 -0.001054 0.01, -0.002467 0.008317 0.002254, + -0.002463 0.004534 0.008, -0.002372 -0.012631 0.21075, -0.002363 -0.006681 0.003886, -0.002348 0.003057 0.009744, + -0.002345 -0.003059 0.009744, -0.002195 0.01058 0.257334, -0.002189 0.010551 0.257917, -0.002184 0.001675 0.01, + -0.002183 -0.001677 0.01, -0.002163 0.014807 0.199264, -0.002156 0.010391 0.258477, -0.0021 -0.011181 0.222336, + -0.002097 0.010108 0.258983, -0.002057 0.031934 0.01, -0.002057 0.031934 0.129114, -0.002039 0.031653 0.136608, + -0.002035 0.031594 0.007412, -0.002021 0.002632 0.009935, -0.002019 -0.002633 0.009935, -0.002016 0.009718 0.259409, + -0.002015 0.006794 0.003886, -0.002006 -0.031857 0.01, -0.002006 -0.031857 0.129114, -0.001993 0.004805 0.008, + -0.001989 -0.010604 0.257334, -0.001989 -0.004807 0.008, -0.001985 0.030813 0.14406, -0.001971 0.030597 0.005, + -0.00197 -0.005571 0.005835, -0.001952 -0.014872 0, -0.001946 -0.010361 0.233986, -0.001925 0.004642 0.008541, + -0.001921 -0.004644 0.008541, -0.001918 0.009242 0.259731, -0.00191 -0.010174 0.245663, -0.001895 0.029418 0.151428, + -0.001869 0.029011 0.002929, -0.001858 0.012717 0.21075, -0.001854 -0.010645 0.257334, -0.001849 -0.010616 0.257917, + -0.00182 -0.010455 0.258477, -0.001812 0.00437 0.009029, -0.001809 -0.004371 0.009029, -0.001806 0.008705 0.259932, + -0.001771 -0.01017 0.258983, -0.00177 0.027476 0.15867, -0.001736 0.026944 0.00134, -0.001727 -0.004877 0.008, + -0.001703 -0.009778 0.259409, -0.001689 0.008138 0.26, -0.00168 0.005665 0.005835, -0.001677 0.002183 0.01, + -0.001675 -0.002184 0.01, -0.00166 0.004003 0.009436, -0.001658 -0.012629 0.000259, -0.001657 -0.004004 0.009436, + -0.001645 0.011257 0.222336, -0.001619 -0.009298 0.259731, -0.00161 0.024997 0.165746, -0.001581 0.024537 0.000341, + -0.001557 0.010631 0.257334, -0.001525 -0.008759 0.259932, -0.001524 0.010431 0.233986, -0.001496 0.010243 0.245663, + -0.001476 0.003561 0.009744, -0.001474 -0.003562 0.009744, -0.001468 0.004946 0.008, -0.001426 -0.008188 0.26, + -0.001414 0.021955 0, -0.001378 -0.010502 0.001024, -0.001271 0.003065 0.009935, -0.001269 -0.003066 0.009935, + -0.001229 0.031927 0.01, -0.001229 0.031927 0.129114, -0.001183 0.014953 0, -0.001129 -0.008602 0.002254, + -0.001054 0.002543 0.01, -0.001052 -0.002543 0.01, -0.001004 0.012698 0.000259, -0.000922 -0.007027 0.003886, + -0.000835 0.010559 0.001024, -0.000769 -0.005858 0.005835, -0.000684 0.008648 0.002254, -0.000681 0.005157 0.008, + -0.000677 -0.005158 0.008, -0.000658 0.004982 0.008541, -0.000654 -0.004983 0.008541, -0.000619 0.00469 0.009029, + -0.000616 -0.004691 0.009029, -0.000567 0.004296 0.009436, -0.000564 -0.004297 0.009436, -0.000559 0.007065 0.003886, + -0.000506 -0.025025 0.165746, -0.000505 0.003821 0.009744, -0.000502 -0.003822 0.009744, -0.000466 0.00589 0.005835, + -0.000434 0.00329 0.009935, -0.000432 -0.00329 0.009935, -0.000427 -0.021068 0.176727, -0.00041 0.005157 0.008, + -0.00036 0.002729 0.01, -0.000359 -0.017704 0.187911, -0.000358 -0.002729 0.01, -0.000303 -0.014961 0.199264, + -0.00028 -0.031999 0.01, -0.00028 -0.031999 0.129114, -0.000277 -0.031718 0.136608, -0.000277 -0.031658 0.007412, + -0.00027 -0.030876 0.14406, -0.000268 -0.030659 0.005, -0.000261 -0.012849 0.21075, -0.000258 -0.029478 0.151428, + -0.000254 -0.02907 0.002929, -0.000241 -0.027532 0.15867, -0.000236 -0.026999 0.00134, -0.000231 -0.011374 0.222336, + -0.000219 -0.025048 0.165746, -0.000215 -0.010722 0.257334, -0.000215 -0.024587 0.000341, -0.000214 -0.01054 0.233986, + -0.00021 -0.010349 0.245663, -0.000192 -0.021999 0, 0.00021 0.010349 0.245663, 0.000214 0.01054 0.233986, + 0.000222 0.010771 0.257334, 0.000231 0.011374 0.222336, 0.000261 0.012849 0.21075, 0.000303 0.014961 0.199264, + 0.000358 0.002729 0.01, 0.000359 0.017704 0.187911, 0.00036 -0.002729 0.01, 0.000388 0.008302 0.26, 0.00041 -0.005157 0.008, + 0.000415 0.008881 0.259932, 0.000427 0.021068 0.176727, 0.000432 0.00329 0.009935, 0.000434 -0.00329 0.009935, + 0.000441 0.009428 0.259731, 0.000464 0.009914 0.259409, 0.000466 -0.00589 0.005835, 0.000482 0.010312 0.258983, + 0.000496 0.010601 0.258477, 0.000502 0.003822 0.009744, 0.000503 0.010764 0.257917, 0.000505 -0.003821 0.009744, + 0.000505 0.010794 0.257334, 0.000507 0.024979 0.165746, 0.000559 -0.007065 0.003886, 0.000564 0.004297 0.009436, + 0.000567 -0.004296 0.009436, 0.000616 0.004691 0.009029, 0.000619 -0.00469 0.009029, 0.000654 0.004983 0.008541, + 0.000655 -0.008285 0.26, 0.000658 -0.004982 0.008541, 0.000677 0.005158 0.008, 0.000681 -0.005157 0.008, + 0.000684 -0.008648 0.002254, 0.000701 -0.008863 0.259932, 0.000744 -0.009409 0.259731, 0.000769 0.005858 0.005835, + 0.000783 -0.009894 0.259409, 0.000814 -0.010291 0.258983, 0.000835 -0.010559 0.001024, 0.000837 -0.010579 0.258477, + 0.00085 -0.010743 0.257917, 0.000852 -0.010772 0.257334, 0.000922 0.007027 0.003886, 0.001004 -0.012698 0.000259, + 0.001052 0.002543 0.01, 0.001054 -0.002543 0.01, 0.001129 0.008602 0.002254, 0.001183 -0.014953 0, 0.001269 0.003066 0.009935, + 0.001271 -0.003065 0.009935, 0.001378 0.010502 0.001024, 0.001468 -0.004946 0.008, 0.001474 0.003562 0.009744, + 0.001476 -0.003561 0.009744, 0.001496 -0.010243 0.245663, 0.001524 -0.010431 0.233986, 0.001549 -0.010627 0.257334, + 0.001645 -0.011257 0.222336, 0.001657 0.004004 0.009436, 0.001658 0.012629 0.000259, 0.00166 -0.004003 0.009436, + 0.001675 0.002184 0.01, 0.001677 -0.002183 0.01, 0.00168 -0.005665 0.005835, 0.001727 0.004877 0.008, 0.001798 0.021926 0, + 0.001809 0.004371 0.009029, 0.001812 -0.00437 0.009029, 0.001858 -0.012717 0.21075, 0.00191 0.010174 0.245663, + 0.001921 0.004644 0.008541, 0.001925 -0.004642 0.008541, 0.001946 0.010361 0.233986, 0.001952 0.014872 0, + 0.00197 0.005571 0.005835, 0.00198 0.010537 0.257334, 0.001989 0.004807 0.008, 0.001993 -0.004805 0.008, + 0.002009 0.024506 0.000341, 0.002015 -0.006794 0.003886, 0.002019 0.002633 0.009935, 0.002021 -0.002632 0.009935, + 0.002047 0.024965 0.165746, 0.0021 0.011181 0.222336, 0.002163 -0.014807 0.199264, 0.002183 0.001677 0.01, + 0.002184 -0.001675 0.01, 0.002206 0.02691 0.00134, 0.00225 0.027441 0.15867, 0.002345 0.003059 0.009744, + 0.002348 -0.003057 0.009744, 0.002363 0.006681 0.003886, 0.002372 0.012631 0.21075, 0.002375 0.028974 0.002929, + 0.002409 0.02938 0.151428, 0.002441 0.007945 0.26, 0.002463 -0.004534 0.008, 0.002467 -0.008317 0.002254, + 0.002505 0.030558 0.005, 0.002523 0.030774 0.14406, 0.002543 0.001054 0.01, 0.002543 -0.001052 0.01, + 0.00256 -0.017521 0.187911, 0.002587 0.031553 0.007412, 0.002592 0.031613 0.136608, 0.002611 0.008499 0.259932, + 0.002615 0.031893 0.01, 0.002615 0.031893 0.129114, 0.002632 0.002021 0.009935, 0.002633 -0.002019 0.009935, + 0.002637 0.003439 0.009436, 0.00264 -0.003437 0.009436, 0.002695 0.0044 0.008, 0.002695 -0.007862 0.26, 0.002729 0.00036 0.01, + 0.002729 -0.000358 0.01, 0.002762 0.014707 0.199264, 0.002772 0.009022 0.259731, 0.002821 -0.005192 0.005835, + 0.002878 0.003754 0.009029, 0.002881 -0.003752 0.009029, 0.002883 -0.00841 0.259932, 0.002893 0.008179 0.002254, + 0.002915 0.009487 0.259409, 0.003012 -0.010155 0.001024, 0.003013 -0.021793 0, 0.003032 0.009868 0.258983, + 0.003046 -0.020851 0.176727, 0.003057 0.002348 0.009744, 0.003058 0.003988 0.008541, 0.003059 -0.002345 0.009744, + 0.003061 -0.008928 0.259731, 0.003061 -0.003986 0.008541, 0.003065 0.001271 0.009935, 0.003066 -0.001269 0.009935, + 0.003085 0.005039 0.005835, 0.003116 0.010145 0.258477, 0.003162 -0.009857 0.245663, 0.003165 0.010301 0.257917, + 0.003165 0.004128 0.008, 0.003168 -0.004126 0.008, 0.003173 0.010329 0.257334, 0.003219 -0.009389 0.259409, + 0.00322 -0.010038 0.233986, 0.003268 0.017403 0.187911, 0.00329 0.000434 0.009935, 0.00329 -0.000432 0.009935, + 0.003296 -0.010265 0.257334, 0.003348 -0.009766 0.258983, 0.00336 -0.003934 0.008, 0.003367 -0.024357 0.000341, + 0.003384 -0.006227 0.003886, 0.003431 -0.024813 0.165746, 0.003437 0.00264 0.009436, 0.003439 -0.002637 0.009436, + 0.003442 -0.010039 0.258477, 0.003475 -0.010833 0.222336, 0.003495 -0.010194 0.257917, 0.003504 -0.010222 0.257334, + 0.003532 0.009986 0.001024, 0.003549 0.003745 0.008, 0.003559 0.009721 0.245663, 0.003561 0.001476 0.009744, + 0.003562 -0.001474 0.009744, 0.003618 -0.024773 0.165746, 0.003622 -0.012211 0.000259, 0.003624 0.009899 0.233986, + 0.003692 0.010095 0.257334, 0.003698 -0.026746 0.00134, 0.0037 0.006044 0.003886, 0.003752 0.002881 0.009029, + 0.003754 -0.002878 0.009029, 0.003771 -0.027273 0.15867, 0.003821 0.000505 0.009744, 0.003822 -0.000502 0.009744, + 0.003839 -0.004491 0.005835, 0.003889 0.02071 0.176727, 0.003911 0.010683 0.222336, 0.003926 -0.012238 0.21075, + 0.003981 -0.028797 0.002929, 0.003986 0.003061 0.008541, 0.003988 -0.003058 0.008541, 0.004003 0.00166 0.009436, + 0.004004 -0.001657 0.009436, 0.004037 -0.029201 0.151428, 0.004066 0.004288 0.005835, 0.004126 0.003168 0.008, + 0.004128 -0.003165 0.008, 0.004143 -0.007622 0.002254, 0.004199 -0.030371 0.005, 0.004229 -0.030586 0.14406, + 0.004247 0.012008 0.000259, 0.004261 0.002934 0.008, 0.004266 -0.014381 0, 0.004296 0.000567 0.009436, + 0.004297 -0.000564 0.009436, 0.004336 -0.031361 0.007412, 0.00434 0.007088 0.26, 0.004344 -0.03142 0.136608, + 0.00437 0.001812 0.009029, 0.004371 -0.001809 0.009029, 0.004382 -0.031698 0.01, 0.004382 -0.031698 0.129114, + 0.004419 0.012069 0.21075, 0.004456 -0.031683 0.01, 0.004456 -0.031683 0.129114, 0.00453 0.007399 0.002254, + 0.004566 -0.006945 0.26, 0.004571 -0.014249 0.199264, 0.004605 -0.005387 0.003886, 0.004614 0.024565 0.165746, + 0.004642 0.001925 0.008541, 0.004642 0.007582 0.259932, 0.004644 -0.001921 0.008541, 0.004672 -0.002223 0.008, + 0.004689 -0.003595 0.005835, 0.00469 0.000619 0.009029, 0.004691 -0.000616 0.009029, 0.004741 -0.009202 0.245663, + 0.004805 0.001993 0.008, 0.004807 -0.001989 0.008, 0.004828 -0.009371 0.233986, 0.004868 0.003349 0.005835, + 0.004876 0.005143 0.003886, 0.004884 -0.007429 0.259932, 0.004913 -0.009531 0.257334, 0.004928 0.00805 0.259731, + 0.004971 0.021431 0, 0.004982 0.000658 0.008541, 0.004983 -0.000654 0.008541, 0.005002 0.014142 0, 0.005018 -0.001201 0.008, + 0.005058 -0.009307 0.001024, 0.005087 0.000943 0.008, 0.00511 0.009002 0.245663, 0.005145 0.014052 0.199264, + 0.005157 0.000681 0.008, 0.005158 -0.000134 0.008, 0.005158 -0.000677 0.008, 0.005182 0.008464 0.259409, + 0.005185 -0.007887 0.259731, 0.005204 0.009168 0.233986, 0.005211 -0.010113 0.222336, 0.005221 0.031486 0.01, + 0.005221 0.031486 0.129114, 0.005318 0.009362 0.257334, 0.005334 -0.002542 0.005835, 0.005391 0.008804 0.258983, + 0.005409 -0.016861 0.187911, 0.005452 -0.008293 0.259409, 0.005458 0.002263 0.005835, 0.005531 0.009033 0.001024, + 0.005541 0.009051 0.258477, 0.005556 0.023952 0.000341, 0.005616 0.009893 0.222336, 0.005624 -0.004312 0.003886, + 0.005627 0.00919 0.257917, 0.005637 -0.006595 0.002254, 0.005642 0.009216 0.257334, 0.00566 0.024401 0.165746, + 0.005671 -0.008626 0.258983, 0.005746 -0.001377 0.005835, 0.005809 0.001079 0.005835, 0.00583 -0.008868 0.258477, + 0.005839 0.004016 0.003886, 0.005887 -0.011425 0.21075, 0.005907 -0.000152 0.005835, 0.00592 -0.009004 0.257917, + 0.005936 -0.009029 0.257334, 0.005966 0.005786 0.26, 0.005969 0.006295 0.002254, 0.006082 -0.011191 0.000259, + 0.006088 0.016628 0.187911, 0.006101 0.026302 0.00134, 0.006149 -0.005591 0.26, 0.006154 -0.021122 0, + 0.006191 -0.008296 0.245663, 0.006221 0.026821 0.15867, 0.006305 -0.008449 0.233986, 0.006345 0.011177 0.21075, + 0.006382 0.00619 0.259932, 0.006398 -0.003048 0.003886, 0.006423 -0.008613 0.257334, 0.006437 -0.020065 0.176727, + 0.006522 0.008038 0.245663, 0.006546 0.002715 0.003886, 0.006569 0.028319 0.002929, 0.006578 -0.005981 0.259932, + 0.006642 0.008186 0.233986, 0.006651 0.010863 0.000259, 0.006661 0.028717 0.151428, 0.006755 0.008325 0.257334, + 0.006775 0.006571 0.259731, 0.006804 -0.009117 0.222336, 0.006854 -0.013303 0.199264, 0.006878 -0.023607 0.000341, + 0.006882 -0.008052 0.001024, 0.006885 -0.005279 0.002254, 0.006892 -0.001652 0.003886, 0.006928 0.029867 0.005, + 0.006968 0.001294 0.003886, 0.006977 0.030078 0.14406, 0.006983 -0.006349 0.259731, 0.007007 -0.024049 0.165746, + 0.007084 -0.000183 0.003886, 0.007125 0.00691 0.259409, 0.007148 0.004917 0.002254, 0.007153 0.030841 0.007412, + 0.007163 -0.013179 0, 0.007167 0.030899 0.136608, 0.007168 0.008834 0.222336, 0.007218 0.004121 0.26, 0.00723 0.031172 0.01, + 0.00723 0.031172 0.129114, 0.007245 0.019788 0.176727, 0.007288 0.007686 0.001024, 0.007343 -0.006677 0.259409, + 0.007347 -0.003886 0.26, 0.007388 0.013014 0.199264, 0.007411 0.007187 0.258983, 0.007472 -0.007164 0.245663, + 0.007552 -0.025922 0.00134, 0.00761 -0.007296 0.233986, 0.007618 0.007388 0.258477, 0.007638 -0.023814 0.165746, + 0.007638 -0.006945 0.258983, 0.007677 0.003184 0.26, 0.007687 -0.0103 0.21075, 0.007701 -0.026434 0.15867, + 0.007721 0.004408 0.259932, 0.007736 0.007502 0.257917, 0.007756 0.006855 0.245663, 0.007757 0.007523 0.257334, + 0.007779 -0.007454 0.257334, 0.007832 -0.003732 0.002254, 0.007832 0.012793 0, 0.007852 -0.007139 0.258477, + 0.007859 -0.004157 0.259932, 0.007899 0.006981 0.233986, 0.007973 -0.007249 0.257917, 0.007995 -0.007269 0.257334, + 0.008014 0.003323 0.002254, 0.008016 0.002196 0.26, 0.008038 0.020479 0, 0.008056 0.007125 0.257334, 0.008082 -0.001937 0.26, + 0.008098 0.00998 0.21075, 0.00811 -0.015741 0.187911, 0.008132 -0.027911 0.002929, 0.008197 0.00468 0.259731, + 0.008212 -0.007873 0.222336, 0.008246 -0.028302 0.151428, 0.008276 -0.009682 0.000259, 0.00831 0.000134 0.26, + 0.008343 -0.004413 0.259731, 0.008406 -0.006445 0.001024, 0.008437 -0.002022 0.002254, 0.008524 0.007534 0.222336, + 0.00853 0.001584 0.002254, 0.008549 -0.005836 0.245663, 0.008575 0.002349 0.259932, 0.008576 -0.029436 0.005, + 0.008602 0.023488 0.165746, 0.008619 0.004921 0.259409, 0.008637 -0.029644 0.14406, 0.008646 -0.002072 0.259932, + 0.008673 -0.000224 0.002254, 0.008707 -0.005944 0.233986, 0.008727 0.006003 0.001024, 0.008742 0.015399 0.187911, + 0.008764 0.009243 0.000259, 0.008773 -0.004641 0.259409, 0.008779 0.005485 0.245663, 0.008855 -0.006044 0.257334, + 0.008856 -0.030395 0.007412, 0.008872 -0.030453 0.136608, 0.008889 0.000143 0.259932, 0.008941 0.005586 0.233986, + 0.00895 -0.011993 0.199264, 0.008951 -0.030723 0.01, 0.008951 -0.030723 0.129114, 0.008965 0.005118 0.258983, + 0.008984 0.022888 0.000341, 0.009103 0.002494 0.259731, 0.009125 -0.004827 0.258983, 0.009128 0.005698 0.257334, + 0.009152 0.023317 0.165746, 0.009164 -0.020001 0, 0.009178 -0.0022 0.259731, 0.009216 0.005262 0.258477, + 0.009277 -0.008894 0.21075, 0.009358 0.005343 0.257917, 0.009381 -0.004962 0.258477, 0.009384 0.005357 0.257334, + 0.009393 -0.004349 0.245663, 0.009396 -0.006414 0.222336, 0.009429 0.01162 0.199264, 0.009437 0.000152 0.259731, + 0.009526 -0.005039 0.257917, 0.009552 -0.005052 0.257334, 0.009562 0.003965 0.245663, 0.009562 -0.004556 0.001024, + 0.009566 -0.00443 0.233986, 0.009572 0.002623 0.259409, 0.00963 0.008511 0.21075, 0.009648 0.006028 0.222336, + 0.009652 -0.002313 0.259409, 0.009652 -0.018732 0.176727, 0.009738 0.004038 0.233986, 0.009746 -0.011402 0, + 0.009752 -0.00452 0.257334, 0.009784 0.004057 0.001024, 0.009865 0.025133 0.00134, 0.009903 0.004106 0.257334, + 0.009924 0.00016 0.259409, 0.009957 0.002728 0.258983, 0.009981 -0.002744 0.245663, 0.010039 -0.002406 0.258983, + 0.01006 0.025629 0.15867, 0.010084 0.002337 0.245663, 0.010108 -0.00775 0.000259, 0.010165 -0.002795 0.233986, + 0.010235 0.002804 0.258477, 0.010242 -0.022354 0.000341, 0.01027 0.00238 0.233986, 0.010297 -0.001064 0.245663, + 0.0103 -0.002469 0.001024, 0.01032 -0.002473 0.258477, 0.010321 0.010885 0, 0.010322 0.000166 0.258983, + 0.010323 -0.00478 0.222336, 0.010331 0.000646 0.245663, 0.010383 -0.002851 0.257334, 0.010393 0.002848 0.257917, + 0.010403 0.018326 0.176727, 0.010414 0.001934 0.001024, 0.010421 0.002855 0.257334, 0.010434 -0.022773 0.165746, + 0.010479 -0.002511 0.257917, 0.010482 0.002433 0.257334, 0.010486 -0.001083 0.233986, 0.010494 0.007219 0.000259, + 0.010508 -0.002518 0.257334, 0.010509 0.004358 0.222336, 0.010522 0.000657 0.233986, 0.010589 -0.000273 0.001024, + 0.010591 -0.014191 0.187911, 0.010611 0.000171 0.258477, 0.010615 -0.007246 0.21075, 0.010622 0.027061 0.002929, + 0.010664 -0.001101 0.257334, 0.010716 -0.030065 0.01, 0.010716 -0.030065 0.129114, 0.010734 0.000667 0.257334, + 0.010771 0.027441 0.151428, 0.010775 0.000174 0.257917, 0.010802 -0.010356 0.199264, 0.010804 0.000174 0.257334, + 0.0109 0.00681 0.21075, 0.010934 0.01909 0, 0.010969 -0.003016 0.222336, 0.011083 0.002569 0.222336, + 0.011157 0.01375 0.187911, 0.011203 0.02854 0.005, 0.011213 0.00991 0.199264, 0.011246 -0.024546 0.00134, + 0.011282 0.028742 0.14406, 0.011316 -0.001169 0.222336, 0.011354 0.000709 0.222336, 0.011445 -0.022217 0.165746, + 0.011468 -0.025031 0.15867, 0.011477 0.029854 0.01, 0.011477 0.029854 0.129114, 0.011499 -0.005479 0.000259, + 0.011568 0.02947 0.007412, 0.011589 0.029526 0.136608, 0.011662 -0.0054 0.21075, 0.011692 0.029788 0.01, + 0.011692 0.029788 0.129114, 0.011766 0.004879 0.000259, 0.011872 0.004923 0.21075, 0.011904 -0.009127 0, 0.011978 -0.018453 0, + 0.012109 -0.026429 0.002929, 0.012221 0.021336 0.000341, 0.012279 -0.0268 0.151428, 0.012359 0.008501 0, + 0.012359 -0.008437 0.199264, 0.012363 0.021778 0.165746, 0.012387 -0.002969 0.000259, 0.012392 -0.003407 0.21075, + 0.01245 0.021736 0.165746, 0.01252 0.002902 0.21075, 0.012523 0.002326 0.000259, 0.012603 -0.016888 0.176727, + 0.012691 0.007929 0.199264, 0.012733 -0.000328 0.000259, 0.012771 -0.027874 0.005, 0.012782 -0.012255 0.187911, + 0.012784 -0.001321 0.21075, 0.012827 0.000801 0.21075, 0.012861 -0.028071 0.14406, 0.013187 -0.028782 0.007412, + 0.013212 -0.028836 0.136608, 0.013268 0.011726 0.187911, 0.013277 0.016363 0.176727, 0.013329 -0.029092 0.01, + 0.013329 -0.029092 0.129114, 0.013387 -0.020624 0.000341, 0.013419 0.023429 0.00134, 0.013541 -0.006452 0, + 0.013579 -0.006288 0.199264, 0.013597 0.017295 0, 0.013638 -0.021011 0.165746, 0.013684 0.023891 0.15867, + 0.013823 0.005732 0.199264, 0.013856 0.005746 0, 0.014429 -0.003967 0.199264, 0.014449 0.025226 0.002929, + 0.014537 -0.016513 0, 0.014578 0.003379 0.199264, 0.014587 -0.003496 0, 0.014625 -0.009984 0.187911, + 0.014652 0.02558 0.151428, 0.0147 -0.022647 0.00134, 0.014748 0.002739 0, 0.014885 -0.001538 0.199264, + 0.014935 0.000933 0.199264, 0.014942 -0.020023 0.165746, 0.01499 -0.023094 0.15867, 0.014995 -0.000387 0, + 0.015017 0.009383 0.187911, 0.015197 0.019329 0.000341, 0.015211 -0.014583 0.176727, 0.015239 0.026605 0.005, + 0.015346 0.026793 0.14406, 0.015482 0.019692 0.165746, 0.015735 0.027472 0.007412, 0.015765 0.027524 0.136608, + 0.015766 0.019433 0.165746, 0.01579 0.013955 0.176727, 0.015828 -0.024384 0.002929, 0.015905 0.027768 0.01, + 0.015905 0.027768 0.129114, 0.015971 0.015131 0, 0.01605 -0.024726 0.151428, 0.016069 -0.00744 0.187911, + 0.016248 -0.018455 0.000341, 0.016357 0.006783 0.187911, 0.016552 -0.018801 0.165746, 0.016565 -0.027313 0.01, + 0.016565 -0.027313 0.129114, 0.016688 0.021225 0.00134, 0.016693 -0.025717 0.005, 0.016787 -0.01422 0, + 0.016811 -0.025899 0.14406, 0.017017 0.021644 0.15867, 0.017074 -0.004694 0.187911, 0.017216 0.026883 0.01, + 0.017216 0.026883 0.129114, 0.017237 -0.026555 0.007412, 0.01725 0.003998 0.187911, 0.01727 -0.026605 0.136608, + 0.017404 -0.011881 0.176727, 0.017423 -0.026841 0.01, 0.017423 -0.026841 0.129114, 0.017614 -0.00182 0.187911, + 0.017673 0.001104 0.187911, 0.017841 -0.020265 0.00134, 0.01785 0.016911 0.000341, 0.017871 0.011166 0.176727, + 0.017968 0.022854 0.002929, 0.018004 0.012644 0, 0.018035 -0.01729 0.165746, 0.018184 0.017228 0.165746, + 0.018193 -0.020665 0.15867, 0.01822 0.023174 0.151428, 0.018678 -0.011624 0, 0.018732 0.016558 0.165746, + 0.018762 -0.015893 0.000341, 0.01895 0.024103 0.005, 0.019084 0.024273 0.14406, 0.019113 -0.016191 0.165746, + 0.019122 -0.008854 0.176727, 0.01921 -0.02182 0.002929, 0.019465 0.008072 0.176727, 0.019479 -0.022126 0.151428, + 0.019567 0.024888 0.007412, 0.0196 0.018569 0.00134, 0.019604 0.024935 0.136608, 0.019653 0.009888 0, 0.019778 0.025156 0.01, + 0.019778 0.025156 0.129114, 0.019987 0.018936 0.15867, 0.020122 0.014132 0.000341, 0.020172 -0.008781 0, + 0.02026 -0.023013 0.005, 0.020319 -0.005586 0.176727, 0.020403 -0.023175 0.14406, 0.020499 0.014397 0.165746, + 0.020528 0.004758 0.176727, 0.020602 -0.017452 0.00134, 0.020644 -0.014091 0.165746, 0.020876 -0.012992 0.000341, + 0.020883 0.006921 0, 0.02092 -0.023763 0.007412, 0.020959 -0.023807 0.136608, 0.020961 -0.002165 0.176727, + 0.021008 -0.017796 0.15867, 0.021031 0.001314 0.176727, 0.021104 0.019994 0.002929, 0.021145 -0.024018 0.01, + 0.021145 -0.024018 0.129114, 0.02119 0.013241 0.165746, 0.021235 -0.00575 0, 0.021267 -0.013235 0.165746, + 0.0214 0.020274 0.151428, 0.021668 0.003807 0, 0.021725 -0.023427 0.01, 0.021725 -0.023427 0.129114, 0.021846 -0.002597 0, + 0.021965 0.011051 0.000341, 0.021992 0.000611 0, 0.022095 0.015518 0.00134, 0.022182 -0.01879 0.002929, + 0.022258 0.021087 0.005, 0.022284 0.022871 0.01, 0.022284 0.022871 0.129114, 0.022377 0.011259 0.165746, + 0.022415 0.021236 0.14406, 0.022493 -0.019054 0.151428, 0.022531 0.015824 0.15867, 0.022545 -0.009814 0.000341, + 0.022699 -0.010509 0.165746, 0.022923 -0.014266 0.00134, 0.022968 -0.009998 0.165746, 0.022983 0.021774 0.007412, + 0.023026 0.021815 0.136608, 0.023139 0.009595 0.165746, 0.02323 0.022008 0.01, 0.02323 0.022008 0.129114, + 0.02334 0.007735 0.000341, 0.023375 -0.014548 0.15867, 0.023395 -0.019818 0.005, 0.02356 -0.019958 0.14406, + 0.023733 -0.006427 0.000341, 0.023777 0.00788 0.165746, 0.02379 0.016708 0.002929, 0.024119 0.012135 0.00134, + 0.024124 0.016942 0.151428, 0.024147 -0.006638 0.165746, 0.024157 -0.020463 0.007412, 0.024178 -0.006547 0.165746, + 0.024202 -0.020502 0.136608, 0.024217 0.004255 0.000341, 0.024342 0.005641 0.165746, 0.024416 -0.002903 0.000341, + 0.024417 -0.020684 0.01, 0.024417 -0.020684 0.129114, 0.024579 0.000683 0.000341, 0.024595 0.012375 0.15867, + 0.024671 0.004334 0.165746, 0.024682 -0.015361 0.002929, 0.024756 -0.010777 0.00134, 0.024874 -0.002957 0.165746, + 0.024891 -0.002573 0.165746, 0.024952 0.001557 0.165746, 0.025028 -0.015576 0.151428, 0.02504 0.000696 0.165746, + 0.025091 0.017621 0.005, 0.025245 -0.010989 0.15867, 0.025268 0.017746 0.14406, 0.025629 0.008494 0.00134, + 0.025908 0.018196 0.007412, 0.025957 0.01823 0.136608, 0.025969 0.013066 0.002929, 0.02597 -0.018552 0.01, + 0.02597 -0.018552 0.129114, 0.026031 -0.0162 0.005, 0.026061 -0.007057 0.00134, 0.026135 0.008662 0.15867, + 0.026187 0.018391 0.01, 0.026187 0.018391 0.129114, 0.026215 -0.016315 0.14406, 0.026334 0.013249 0.151428, + 0.026457 0.017939 0.01, 0.026457 0.017939 0.129114, 0.026576 -0.007196 0.15867, 0.026593 0.004672 0.00134, + 0.026655 -0.011603 0.002929, 0.026811 -0.003187 0.00134, 0.026879 -0.016728 0.007412, 0.02693 -0.01676 0.136608, + 0.02699 0.00075 0.00134, 0.027029 -0.011766 0.151428, 0.027117 0.004764 0.15867, 0.027168 -0.016908 0.01, + 0.027168 -0.016908 0.129114, 0.02734 -0.00325 0.15867, 0.027389 0.01378 0.005, 0.027522 0.000765 0.15867, + 0.027582 0.013878 0.14406, 0.027595 0.009146 0.002929, 0.027982 0.009274 0.151428, 0.02806 -0.007598 0.002929, + 0.028112 -0.012237 0.005, 0.028281 0.014229 0.007412, 0.028311 -0.012324 0.14406, 0.028335 0.014256 0.136608, + 0.028454 -0.007705 0.151428, 0.028586 0.014383 0.01, 0.028586 0.014383 0.129114, 0.028633 0.00503 0.002929, + 0.028868 -0.003432 0.002929, 0.029028 -0.012636 0.007412, 0.029034 0.005101 0.151428, 0.02906 0.000808 0.002929, + 0.029083 -0.01266 0.136608, 0.029103 0.009646 0.005, 0.029236 -0.012972 0.01, 0.029236 -0.012972 0.129114, + 0.029273 -0.00348 0.151428, 0.029309 0.009714 0.14406, 0.029341 -0.012772 0.01, 0.029341 -0.012772 0.129114, + 0.029467 0.000819 0.151428, 0.02948 0.012225 0.01, 0.02948 0.012225 0.129114, 0.029594 -0.008014 0.005, + 0.029803 -0.00807 0.14406, 0.030052 0.00996 0.007412, 0.030108 0.009979 0.136608, 0.030198 0.005305 0.005, + 0.030375 0.010067 0.01, 0.030375 0.010067 0.129114, 0.030411 0.005343 0.14406, 0.030446 -0.003619 0.005, + 0.030559 -0.008275 0.007412, 0.030616 -0.008291 0.136608, 0.030648 0.000852 0.005, 0.030661 -0.003645 0.14406, + 0.030865 0.000858 0.14406, 0.030888 -0.008364 0.01, 0.030888 -0.008364 0.129114, 0.031182 0.005478 0.007412, + 0.031188 -0.006811 0.01, 0.031188 -0.006811 0.129114, 0.03124 0.005489 0.136608, 0.031388 0.006048 0.01, + 0.031388 0.006048 0.129114, 0.031438 -0.003737 0.007412, 0.031497 -0.003744 0.136608, 0.031517 0.005537 0.01, + 0.031517 0.005537 0.129114, 0.031647 0.00088 0.007412, 0.031707 0.000881 0.136608, 0.031776 -0.003778 0.01, + 0.031776 -0.003778 0.129114, 0.03193 -0.00039 0.01, 0.03193 -0.00039 0.129114, 0.031988 0.000889 0.01, + 0.031988 0.000889 0.129114] + } + creaseAngle 0.610865 + normal Normal { vector [ + # normals 1402 + 0 0 1, 0.462471 0.807426 0.366311, 0.459381 0.809193 0.3663, 0.468639 0.825538 0.314426, 0.339981 0.866158 0.366311, + 0.319978 0.873769 0.366254, 0.326369 0.891415 0.314426, 0.210244 0.906429 0.366311, 0.171796 0.914531 0.366223, + 0.175195 0.932975 0.314426, 0.076027 0.927381 0.366311, 0.018891 0.930342 0.366206, 0.019243 0.949087 0.314426, + -0.059811 0.928568 0.366311, -0.134542 0.920756 0.366205, -0.137234 0.93931 0.314426, -0.194374 0.909964 0.366311, + -0.284294 0.886037 0.366218, -0.289968 0.903911 0.314426, -0.324795 0.871966 0.366311, -0.426259 0.827144 0.366247, + -0.434792 0.843856 0.314426, -0.448293 0.815383 0.366311, -0.556549 0.745711 0.36629, -0.567756 0.760782 0.314426, + -0.752001 0.548006 0.366311, -0.768484 0.524691 0.36624, -0.784019 0.535211 0.314426, -0.823777 0.432674 0.366311, + -0.844381 0.391034 0.366214, -0.861419 0.398866 0.314426, -0.877997 0.30812 0.366311, -0.897242 0.246681 0.366204, + -0.915321 0.251641 0.314426, -0.913503 0.176999 0.366311, -0.92561 0.095589 0.366208, -0.944256 0.097552 0.314426, + -0.929539 0.042106 0.366311, -0.92871 -0.058095 0.366228, -0.947434 -0.059198 0.314426, -0.925764 -0.093685 0.366311, + -0.90647 -0.210154 0.366262, -0.924769 -0.214333 0.314426, -0.902258 -0.227479 0.366311, -0.859522 -0.356424 0.366311, + -0.876878 -0.363622 0.314426, -0.798467 -0.477773 0.366311, -0.789182 -0.492994 0.366262, -0.805069 -0.502992 0.314426, + -0.720393 -0.588939 0.366311, -0.697289 -0.61617 0.366228, -0.711299 -0.628641 0.314426, -0.626966 -0.687553 0.366311, + -0.586342 -0.722561 0.366208, -0.598127 -0.737144 0.314426, -0.520176 -0.771513 0.366311, -0.459376 -0.80924 0.366204, + -0.468639 -0.825538 0.314426, -0.402299 -0.83903 0.366311, -0.319873 -0.873824 0.366214, -0.326369 -0.891415 0.314426, + -0.275849 -0.888664 0.366311, -0.171664 -0.914549 0.36624, -0.175195 -0.932975 0.314426, 0.127433 -0.921725 0.366311, + 0.134487 -0.920731 0.36629, 0.137234 -0.93931 0.314426, 0.260279 -0.893348 0.366311, 0.28417 -0.886065 0.366247, + 0.289968 -0.903911 0.314426, 0.387578 -0.845931 0.366311, 0.426151 -0.827212 0.366218, 0.434792 -0.843856 0.314426, + 0.506616 -0.780485 0.366311, 0.556528 -0.745769 0.366205, 0.567756 -0.760782 0.314426, 0.614857 -0.698403 0.366311, + 0.671719 -0.643962 0.366206, 0.685233 -0.656957 0.314426, 0.709993 -0.601437 0.366311, 0.768565 -0.524585 0.366223, + 0.784019 -0.535211 0.314426, 0.789997 -0.491652 0.366311, 0.844416 -0.390921 0.366254, 0.861419 -0.398866 0.314426, + 0.853163 -0.371388 0.366311, 0.897213 -0.246645 0.3663, 0.915321 -0.251641 0.314426, 0.930133 0.025858 0.366311, + 0.928716 0.057959 0.366233, 0.947434 0.059198 0.314426, -0.30544 0.952144 -0.011287, -0.144557 0.989432 -0.011287, + -0.144427 0.988542 0.043889, 0.866517 0.494707 -0.066428, 0.921689 0.382204 -0.066401, 0.923669 0.383025 -0.011287, + 0.716265 0.694659 -0.066428, 0.747398 0.661048 -0.066412, 0.749254 0.662186 -0.011287, -0.597062 0.799442 -0.066407, + -0.456795 0.887089 -0.06642, -0.457992 0.888885 -0.011287, -0.81657 0.573412 -0.066428, -0.720111 0.690674 -0.066402, + -0.721797 0.692012 -0.011287, -0.905584 0.418937 -0.066406, -0.823984 0.562707 -0.066423, -0.825855 0.56377 -0.011287, + -0.991809 0.109099 -0.066428, -0.962032 0.264736 -0.066403, -0.964163 0.265069 -0.011287, -0.921688 -0.382203 -0.066428, + -0.972091 -0.22501 -0.066404, -0.974115 -0.22577 -0.011287, -0.623553 -0.778953 -0.066428, -0.747858 -0.660529 -0.066405, + -0.749254 -0.662186 -0.011287, -0.183975 -0.980684 -0.066423, -0.34337 -0.93685 -0.066406, -0.343784 -0.938981 -0.011287, + 0.078679 -0.994684 -0.066428, -0.020026 -0.997592 -0.066402, -0.02027 -0.999731 -0.011287, 0.305016 -0.950028 -0.06642, + 0.143886 -0.987364 -0.066407, 0.144557 -0.989432 -0.011287, 0.54814 -0.833744 -0.066428, 0.457147 -0.886909 -0.066402, + 0.457992 -0.888885 -0.011287, 0.720453 -0.690316 -0.066418, 0.596466 -0.799886 -0.066409, 0.598052 -0.801378 -0.011287, + 0.881998 -0.466547 -0.066428, 0.824143 -0.562476 -0.066402, 0.825855 -0.56377 -0.011287, 0.962184 -0.264179 -0.066416, + 0.905278 -0.419596 -0.06641, 0.907384 -0.42015 -0.011287, 0.997662 0.016067 -0.066428, 0.992516 -0.102486 -0.066401, + 0.994642 -0.102758 -0.011287, 0.971945 0.225637 -0.066414, 0.995874 0.061847 -0.066412, 0.99799 0.062356 -0.011287, + -0.144621 0.987256 -0.066409, -0.202726 0.97698 -0.066428, -0.30464 0.95015 -0.066402, -0.439322 0.89587 -0.066428, + 0.02027 0.999731 -0.011287, 0.020521 0.997581 -0.066418, 0.046608 0.996702 -0.066428, 0.184544 0.982759 -0.011287, + 0.18425 0.980634 -0.066402, 0.293013 0.953798 -0.066428, 0.493646 0.86959 -0.011287, 0.492878 0.86756 -0.066416, + 0.521008 0.850963 -0.066428, 0.630043 0.776478 -0.011287, 0.628733 0.774781 -0.066401, 0.8464 0.52839 -0.066414, + 0.848028 0.529832 -0.011287, 0.020172 0.99489 0.09893, 0.020252 0.998831 0.043889, 0.182363 0.971148 0.153671, + 0.18365 0.978001 0.09893, 0.184378 0.981875 0.043889, 0.33629 0.918514 0.207944, 0.339722 0.927887 0.153671, + 0.342119 0.934434 0.09893, 0.343474 0.938136 0.043889, 0.343784 0.938981 -0.011287, 0.342688 0.937099 -0.06641, + 0.952882 0.220849 0.207944, 0.903536 0.374676 0.207944, 0.912756 0.378499 0.153671, 0.476488 0.839365 0.261583, + 0.482886 0.850635 0.207944, 0.487814 0.859315 0.153671, 0.491256 0.865379 0.09893, 0.493202 0.868807 0.043889, + 0.598127 0.737144 0.314426, 0.608144 0.74949 0.261583, 0.61631 0.759553 0.207944, 0.622599 0.767304 0.153671, + 0.626992 0.772718 0.09893, 0.629476 0.775779 0.043889, 0.924769 0.214333 0.314426, 0.876878 0.363622 0.314426, + 0.891565 0.369712 0.261583, 0.944256 -0.097552 0.314426, 0.960071 -0.099186 0.261583, 0.963302 0.060189 0.261583, + 0.976237 0.060997 0.207944, 0.962606 0.223102 0.153671, 0.919197 0.38117 0.09893, -0.987781 -0.140981 -0.066428, + -0.99799 -0.062356 -0.011287, -0.997092 -0.0623 0.043889, -0.993747 0.102665 0.043889, -0.989826 0.10226 0.09893, + -0.959495 0.263786 0.09893, -0.952772 0.261937 0.153671, -0.896664 0.415186 0.153671, -0.887606 0.410992 0.207944, + -0.807853 0.551482 0.207944, -0.79715 0.544175 0.261583, -0.69671 0.66796 0.261583, -0.685233 0.656957 0.314426, + 0.916456 0.161011 0.366311, 0.940257 0.217923 0.261583, 0.898146 -0.243209 0.366311, 0.923986 -0.109846 0.366311, + 0.925576 -0.095677 0.366271, 0.930651 -0.255856 0.261583, 0.972962 -0.100518 0.207944, 0.986199 0.06162 0.153671, + 0.969398 0.224676 0.0989301, 0.922838 0.38268 0.043889, 0.875846 -0.405547 0.261583, 0.943148 -0.259291 0.207944, + 0.982891 -0.101544 0.153671, 0.993158 0.062054 0.09893, 0.973239 0.225567 0.043889, 0.79715 -0.544175 0.261583, + 0.887606 -0.410992 0.207944, 0.952772 -0.261937 0.153671, 0.989826 -0.10226 0.09893, 0.997092 0.0623 0.043889, + 0.974115 0.22577 -0.011287, 0.962323 0.263671 -0.066428, 0.69671 -0.66796 0.261583, 0.807853 -0.551482 0.207944, + 0.896664 -0.415186 0.153671, 0.959495 -0.263786 0.09893, 0.993747 -0.102665 0.043889, 0.577265 -0.773524 0.261583, + 0.706064 -0.676929 0.207944, 0.816097 -0.557109 0.153671, 0.902991 -0.418116 0.09893, 0.963296 -0.264831 0.043889, + 0.442074 -0.857989 0.261583, 0.585016 -0.783911 0.207944, 0.713269 -0.683836 0.153671, 0.821856 -0.56104 0.09893, + 0.906568 -0.419772 0.043889, 0.964163 -0.265069 -0.011287, 0.970314 -0.232546 -0.066428, 0.294824 -0.91905 0.261583, + 0.44801 -0.869509 0.207944, 0.590986 -0.79191 0.153671, 0.718302 -0.688661 0.0989301, 0.825111 -0.563263 0.043889, + -0.143518 -0.919358 0.366311, -0.018818 -0.930314 0.36628, -0.019243 -0.949087 0.314426, -0.008129 -0.930457 0.366311, + 0.139532 -0.955042 0.261583, 0.298783 -0.93139 0.207944, 0.452581 -0.878382 0.153671, 0.595156 -0.797498 0.09893, + 0.721148 -0.69139 0.043889, -0.019565 -0.964983 0.261583, 0.141406 -0.967866 0.207944, 0.301832 -0.940895 0.153671, + 0.455775 -0.88458 0.09893, 0.597513 -0.800657 0.043889, 0.721797 -0.692012 -0.011287, 0.738263 -0.671234 -0.066428, + -0.17813 -0.948601 0.261583, -0.019828 -0.97794 0.207944, 0.142849 -0.977742 0.153671, 0.303961 -0.947534 0.09893, + 0.45758 -0.888085 0.043889, -0.331835 -0.906344 0.261583, -0.180521 -0.961338 0.207944, -0.02003 -0.987919 0.153671, + 0.143857 -0.984641 0.09893, 0.305166 -0.951287 0.043889, -0.476488 -0.839365 0.261583, -0.33629 -0.918514 0.207944, + -0.182363 -0.971148 0.153671, -0.020172 -0.99489 0.09893, 0.144427 -0.988542 0.043889, 0.30544 -0.952144 -0.011287, + 0.323575 -0.943868 -0.066428, -0.608144 -0.74949 0.261583, -0.482886 -0.850635 0.207944, -0.339722 -0.927887 0.153671, + -0.18365 -0.978001 0.09893, -0.020252 -0.998831 0.043889, -0.723212 -0.63917 0.261583, -0.61631 -0.759553 0.207944, + -0.487814 -0.859315 0.153671, -0.342119 -0.934434 0.09893, -0.184378 -0.981875 0.043889, -0.818552 -0.511416 0.261583, + -0.732923 -0.647753 0.207944, -0.622599 -0.767304 0.153671, -0.491256 -0.865379 0.09893, -0.343474 -0.938136 0.043889, + -0.184544 -0.982759 -0.011287, -0.17116 -0.983001 -0.066428, -0.891565 -0.369712 0.261583, -0.829543 -0.518283 0.207944, + -0.740402 -0.654362 0.153671, -0.626992 -0.772718 0.09893, -0.493202 -0.868807 0.043889, -0.940257 -0.217923 0.261583, + -0.903536 -0.374676 0.207944, -0.838008 -0.523572 0.153671, -0.745626 -0.65898 0.09893, -0.629476 -0.775779 0.043889, + -0.493646 -0.86959 -0.011287, -0.410246 -0.909553 -0.066428, -0.963302 -0.060189 0.261583, -0.952882 -0.220849 0.207944, + -0.912756 -0.378499 0.153671, -0.843921 -0.527266 0.09893, -0.74858 -0.66159 0.043889, -0.630043 -0.776478 -0.011287, + -0.492376 -0.867846 -0.066403, -0.960071 0.099186 0.261583, -0.976237 -0.060997 0.207944, -0.962606 -0.223102 0.153671, + -0.919197 -0.38117 0.09893, -0.847265 -0.529355 0.043889, -0.930651 0.255856 0.261583, -0.972962 0.100518 0.207944, + -0.986199 -0.06162 0.153671, -0.969398 -0.224676 0.0989301, -0.922838 -0.38268 0.043889, -0.848028 -0.529832 -0.011287, + -0.797681 -0.59941 -0.066428, -0.875846 0.405547 0.261583, -0.943148 0.259291 0.207944, -0.982891 0.101544 0.153671, + -0.993158 -0.062054 0.09893, -0.973239 -0.225567 0.043889, -0.923669 -0.383025 -0.011287, -0.84606 -0.528936 -0.066404, + -0.562236 0.741422 0.366311, -0.664197 0.651659 0.366311, -0.671648 0.643994 0.36628, -0.577265 0.773524 0.261583, + -0.706064 0.676929 0.207944, -0.816097 0.557109 0.153671, -0.902991 0.418116 0.09893, -0.963296 0.264831 0.043889, + -0.994642 0.102758 -0.011287, -0.995831 -0.062539 -0.066405, -0.442074 0.857989 0.261583, -0.585016 0.783911 0.207944, + -0.713269 0.683836 0.153671, -0.821856 0.56104 0.09893, -0.906568 0.419772 0.043889, -0.294824 0.91905 0.261583, + -0.44801 0.869509 0.207944, -0.590986 0.79191 0.153671, -0.718302 0.688661 0.0989301, -0.825111 0.563263 0.043889, + -0.907384 0.42015 -0.011287, -0.933517 0.352325 -0.066428, -0.139532 0.955042 0.261583, -0.298783 0.93139 0.207944, + -0.452581 0.878382 0.153671, -0.595156 0.797498 0.09893, -0.721148 0.69139 0.043889, 0.019565 0.964983 0.261583, + -0.141406 0.967866 0.207944, -0.301832 0.940895 0.153671, -0.455775 0.88458 0.09893, -0.597513 0.800657 0.043889, + 0.17813 0.948601 0.261583, 0.019828 0.97794 0.207944, -0.142849 0.977742 0.153671, -0.303961 0.947534 0.09893, + -0.45758 0.888085 0.043889, -0.598052 0.801378 -0.011287, -0.648314 0.75847 -0.066428, 0.331835 0.906344 0.261583, + 0.180521 0.961338 0.207944, 0.02003 0.987919 0.153671, -0.143857 0.984641 0.09893, -0.305166 0.951287 0.043889, + 0.586256 0.722599 0.366271, 0.575105 0.731485 0.366311, 0.711299 0.628641 0.314426, 0.697197 0.61627 0.366233, + 0.675482 0.639954 0.366311, 0.74858 0.66159 0.043889, 0.745626 0.65898 0.09893, 0.740402 0.654362 0.153671, + 0.732923 0.647753 0.207944, 0.723212 0.63917 0.261583, 0.805069 0.502992 0.314426, 0.789144 0.493094 0.366211, + 0.761461 0.534783 0.366311, 0.847265 0.529355 0.043889, 0.843921 0.527266 0.09893, 0.838008 0.523572 0.153671, + 0.829543 0.518283 0.207944, 0.818552 0.511416 0.261583, 0.906513 0.210056 0.366211, 0.883246 0.292732 0.366311, + 0.859522 0.356424 0.366311, 0.831212 0.418214 0.366311, 0.893303 0.449455 0, 0.923728 0.383049 0, 0.949225 0.314599 0, + 0.981938 0.189204 0, 0.984915 0.173039 0, 0.999614 0.02779 0, 0.999926 -0.012201 0, 0.993008 -0.118051 0, + 0.976974 -0.213359 0, 0.965237 -0.261376 0, 0.916894 -0.399131 0, 0.914062 -0.405574 0, 0.849009 -0.528378 0, + 0.813706 -0.581277 0, 0.763029 -0.646364 0, 0.679967 -0.733243 0, 0.660787 -0.750574 0, 0.54446 -0.838787 0, + 0.518574 -0.855033 0, 0.41653 -0.909122 0, 0.335737 -0.941956 0, 0.279722 -0.960081 0, 0.139274 -0.990254 0, + 0.136952 -0.990578 0, -0.008737 -0.999962 0, -0.062854 -0.998023 0, -0.154239 -0.988034 0, -0.262585 -0.964909 0, + -0.296454 -0.955047 0, -0.432351 -0.901705 0, -0.451317 -0.892364 0, -0.559033 -0.829145 0, -0.621774 -0.783197 0, + -0.6738 -0.738914 0, -0.766726 -0.641975 0, -0.774206 -0.632933 0, -0.858112 -0.513463 0, -0.880206 -0.474592 0, + -0.923728 -0.383049 0, -0.95776 -0.28757 0, -0.969657 -0.244471 0, -0.994919 -0.100683 0, -0.996032 -0.089 0, + -0.998976 0.045251 0, -0.993554 0.113357 0, -0.981741 0.190221 0, -0.950372 0.311115 0, -0.943583 0.331137 0, + -0.885313 0.464995 0, -0.868362 0.495931 0, -0.808175 0.588942 0, -0.750676 0.66067 0, -0.713812 0.700337 0, + -0.604235 0.796806 0, -0.602365 0.798221 0, -0.48178 0.876292 0, -0.429376 0.903126 0, -0.349057 0.937101 0, + -0.238681 0.971098 0, -0.208894 0.977938 0, -0.064279 0.997932 0, -0.038463 0.99926 0, 0.081706 0.996656 0, + 0.163571 0.986532 0, 0.22595 0.974139 0, 0.358817 0.933408 0, 0.365377 0.93086 0, 0.497018 0.86774 0, 0.539291 0.84212 0, + 0.618065 0.786127 0, 0.69786 0.716234 0, 0.72594 0.687758 0, 0.818342 0.574731 0, 0.827678 0.561203 0, 0 0 -1, + -0.948289 0.18374 -0.258819, -0.337163 0.905171 -0.258819, 0.218251 0.940946 -0.258819, 0.91688 0.30388 -0.258819, + 0.73703 -0.62434 -0.258819, 0.270191 -0.927367 -0.258819, -0.650841 -0.713736 -0.258819, -0.747826 -0.611367 -0.258819, + -0.892253 -0.369997 -0.258819, -0.258554 0.011712 -0.965926, -0.257504 -0.026059 -0.965926, -0.497459 -0.050341 -0.866025, + -0.484828 -0.122236 -0.866025, -0.685651 -0.172867 -0.707107, -0.653174 -0.270857 -0.707107, -0.799972 -0.33173 -0.5, + -0.743147 -0.444672 -0.5, -0.828872 -0.495967 -0.258819, -0.239078 -0.09914 -0.965926, -0.222096 -0.132894 -0.965926, + -0.429056 -0.256731 -0.866025, -0.387103 -0.316467 -0.866025, -0.547447 -0.447551 -0.707107, -0.476449 -0.522491 -0.707107, + -0.583528 -0.639918 -0.5, -0.484137 -0.718061 -0.5, -0.539984 -0.800893 -0.258819, -0.417619 -0.87098 -0.258819, + -0.200379 -0.163815 -0.965926, -0.3369 -0.369457 -0.866025, -0.395296 -0.586294 -0.707107, -0.374427 -0.7809 -0.5, + -0.286353 -0.922505 -0.258819, -0.174392 -0.191245 -0.965926, -0.144688 -0.214599 -0.965926, -0.279517 -0.414573 -0.866025, + -0.216176 -0.450853 -0.866025, -0.305718 -0.637602 -0.707107, -0.209625 -0.67532 -0.707107, -0.256737 -0.827095 -0.5, + -0.133575 -0.855662 -0.5, -0.148984 -0.954367 -0.258819, -0.008439 -0.965889 -0.258819, -0.111901 -0.233379 -0.965926, + -0.148227 -0.477524 -0.866025, -0.109064 -0.698645 -0.707107, -0.007566 -0.865992 -0.5, 0.132285 -0.956825 -0.258819, + -0.03992 -0.255722 -0.965926, -0.002261 -0.258809 -0.965926, -0.004368 -0.499981 -0.866025, 0.068476 -0.495289 -0.866025, + 0.09684 -0.700444 -0.707107, 0.197793 -0.67888 -0.707107, 0.242246 -0.831455 -0.5, 0.360725 -0.787323 -0.5, + 0.402337 -0.878144 -0.258819, 0.525908 -0.810206 -0.258819, 0.035446 -0.25638 -0.965926, 0.139861 -0.480041 -0.866025, + 0.294531 -0.642846 -0.707107, 0.471516 -0.726411 -0.5, 0.638271 -0.724999 -0.258819, 0.107806 -0.235298 -0.965926, + 0.140917 -0.217094 -0.965926, 0.27223 -0.419393 -0.866025, 0.330393 -0.375287 -0.866025, 0.467247 -0.530736 -0.707107, + 0.539543 -0.457048 -0.707107, 0.660803 -0.559768 -0.5, 0.735264 -0.457589 -0.5, 0.82008 -0.510374 -0.258819, + 0.885652 -0.385531 -0.258819, 0.171024 -0.194263 -0.965926, 0.381515 -0.323182 -0.866025, 0.60034 -0.37362 -0.707107, + 0.794054 -0.345657 -0.5, 0.932347 -0.25247 -0.258819, 0.197486 -0.167291 -0.965926, 0.21974 -0.136754 -0.965926, + 0.424505 -0.264189 -0.866025, 0.458447 -0.199565 -0.866025, 0.648342 -0.282228 -0.707107, 0.682526 -0.184821 -0.707107, + 0.83592 -0.226359 -0.5, 0.85997 -0.102235 -0.5, 0.959172 -0.114029 -0.258819, 0.965553 0.026843 -0.258819, + 0.23731 -0.103303 -0.965926, 0.482618 -0.130688 -0.866026, 0.702162 -0.083475 -0.707107, 0.865691 0.024067 -0.5, + 0.951355 0.167142 -0.258819, 0.257009 -0.030554 -0.965926, 0.258719 0.007193 -0.965926, 0.499807 0.013895 -0.866025, + 0.492458 0.086519 -0.866025, 0.69644 0.122357 -0.707107, 0.671203 0.222455 -0.707107, 0.822053 0.272451 -0.5, + 0.773623 0.389239 -0.5, 0.862864 0.43414 -0.258819, 0.790458 0.555148 -0.258819, 0.254915 0.044786 -0.965926, + 0.474612 0.1573 -0.866025, 0.631661 0.317813 -0.707107, 0.708705 0.497732 -0.5, 0.701204 0.664323 -0.258819, + 0.245677 0.081424 -0.965926, 0.231204 0.116328 -0.965926, 0.446651 0.224727 -0.866026, 0.409171 0.287366 -0.866025, + 0.578655 0.406396 -0.707107, 0.513317 0.486318 -0.707107, 0.628682 0.595616 -0.5, 0.53526 0.680806 -0.5, + 0.597005 0.75934 -0.258819, 0.480083 0.838173 -0.258819, 0.211803 0.148751 -0.965926, 0.36297 0.343879 -0.866025, + 0.437038 0.555875 -0.707107, 0.43043 0.751485 -0.5, 0.352928 0.899141 -0.258819, 0.159967 0.203465 -0.965926, + 0.128638 0.224588 -0.965926, 0.248509 0.43387 -0.866025, 0.182689 0.46543 -0.866025, 0.258361 0.658217 -0.707107, + 0.15977 0.68882 -0.707107, 0.195678 0.843629 -0.5, 0.070759 0.86313 -0.5, 0.078922 0.962696 -0.258819, + -0.062089 0.963928 -0.258819, 0.094567 0.240924 -0.965926, 0.112975 0.487069 -0.866026, 0.057775 0.704743 -0.707107, + -0.055667 0.864234 -0.5, -0.201776 0.944616 -0.258819, 0.021147 0.257954 -0.965926, -0.016637 0.258284 -0.965926, + -0.03214 0.498966 -0.866025, -0.104447 0.488969 -0.866025, -0.147711 0.691507 -0.707107, -0.246821 0.662631 -0.707107, + -0.302292 0.811554 -0.5, -0.417234 0.758891 -0.5, -0.465364 0.846433 -0.258819, -0.583646 0.769655 -0.258819, + -0.054066 0.253109 -0.965926, -0.174529 0.468551 -0.866025, -0.34067 0.619632 -0.707107, -0.523283 0.690054 -0.5, + -0.68949 0.676474 -0.258819, -0.090343 0.24254 -0.965926, -0.124694 0.226801 -0.965926, -0.24089 0.438146 -0.866025, + -0.302118 0.398403 -0.866025, -0.427259 0.563427 -0.707107, -0.504741 0.495213 -0.707107, -0.618179 0.60651 -0.5, + -0.6999 0.510039 -0.5, -0.780637 0.568874 -0.258819, -0.855147 0.44915 -0.258819, -0.156388 0.206229 -0.965926, + -0.356906 0.350169 -0.866025, -0.571466 0.416445 -0.707107, -0.766704 0.402697 -0.5, -0.911431 0.319854 -0.258819, + -0.209171 0.152429 -0.965926, -0.229136 0.12035 -0.965926, -0.442657 0.232497 -0.866025, -0.471791 0.165568 -0.866026, + -0.667214 0.234149 -0.707107, -0.694196 0.134507 -0.707107, -0.850213 0.164736 -0.5, -0.865138 0.039189 -0.5, + -0.964936 0.04371 -0.258819, -0.961018 -0.097252 -0.258819, -0.244217 0.085705 -0.965926, -0.490871 0.095111 -0.866025, + -0.706382 0.031998 -0.707107, -0.861625 -0.087194 -0.5, -0.936616 -0.236141 -0.258819, -0.254093 0.049233 -0.965926, + -0.499488 0.022626 -0.866025, -0.703514 -0.071193 -0.707107, -0.839747 -0.211718 -0.5, -0.670482 -0.548136 -0.5, + -0.606777 -0.363073 -0.707107, -0.461864 -0.191525 -0.866025, -0.250966 -0.063274 -0.965926, 0.118604 -0.857865 -0.5, + -0.006178 -0.70708 -0.707107, -0.07712 -0.494017 -0.866025, -0.076728 -0.247184 -0.965926, 0.572258 -0.650016 -0.5, + 0.384992 -0.593112 -0.707107, 0.208265 -0.454561 -0.866025, 0.072397 -0.248487 -0.965926, 0.852961 0.149856 -0.5, + 0.706834 0.01965 -0.707107, 0.496504 -0.059026 -0.866025, 0.249822 -0.067649 -0.965926, 0.316426 0.806148 -0.5, + 0.351445 0.613585 -0.707107, 0.309033 0.393063 -0.866025, 0.187887 0.178005 -0.965926, -0.180908 0.846919 -0.5, + -0.045452 0.705644 -0.707107, 0.040853 0.498328 -0.866025, 0.05848 0.252126 -0.965926, -0.817167 0.286773 -0.5, + -0.626011 0.328801 -0.707107, -0.404088 0.294471 -0.866025, -0.184748 0.181261 -0.965926, -0.897115 0.246646 0.366538, + -0.90143 0.316344 0.295552, -0.844273 0.390984 0.366516, -0.845764 0.444222 0.295552, -0.768412 0.524642 0.366463, + -0.772071 0.562632 0.295552, -0.426222 0.827073 0.366448, -0.333463 0.895238 0.295552, -0.284259 0.885928 0.366508, + -0.199562 0.93425 0.295552, -0.134523 0.920627 0.366537, -0.061408 0.953351 0.295552, 0.018888 0.930213 0.366533, + 0.078056 0.952133 0.295552, 0.171776 0.914424 0.366499, 0.215856 0.930621 0.295552, 0.319954 0.873703 0.366432, + 0.349055 0.889275 0.295552, 0.697126 0.616207 0.366476, 0.781784 0.549056 0.295552, 0.789039 0.493029 0.366523, + 0.853396 0.429376 0.295552, 0.906393 0.210028 0.366523, 0.940916 0.165308 0.295552, 0.928621 0.057953 0.366476, + 0.954958 0.026548 0.295552, 0.844353 -0.390891 0.366432, 0.811081 -0.504774 0.295552, 0.768475 -0.524524 0.366499, + 0.728942 -0.617489 0.295552, 0.671626 -0.643872 0.366533, 0.631267 -0.717043 0.295552, 0.55645 -0.745664 0.366537, + 0.520137 -0.801315 0.295552, 0.426099 -0.827111 0.366508, 0.397922 -0.868509 0.295552, 0.284146 -0.885989 0.366448, + 0.267226 -0.917191 0.295552, -0.171648 -0.914463 0.366463, -0.283211 -0.912382 0.295552, -0.319832 -0.873712 0.366516, + -0.413037 -0.861423 0.295552, -0.459311 -0.809125 0.366538, -0.534059 -0.792105 0.295552, -0.586262 -0.722463 0.366529, + -0.643699 -0.705904 0.295552, -0.805903 0.587286 0.074938, -0.882824 0.463687 0.074938, -0.87537 0.459772 0.149455, + -0.921131 -0.381972 0.074938, -0.992121 -0.1004 0.074938, -0.711805 0.698368 0.074938, -0.480426 0.873828 0.074938, + -0.348076 0.934466 0.074938, -0.208307 0.975188 0.074938, 0.081476 0.993854 0.074938, 0.225314 0.9714 0.074938, + 0.36435 0.928242 0.074938, 0.616328 0.783916 0.074938, 0.723899 0.685824 0.074938, 0.890791 0.448191 0.074938, + 0.946555 0.313715 0.074938, 0.982146 0.172552 0.074938, 0.990215 -0.117719 0.074938, 0.962523 -0.260641 0.074938, + 0.846622 -0.526892 0.074938, 0.760884 -0.644547 0.074938, 0.658929 -0.748463 0.074938, 0.415359 -0.906566 0.074938, + 0.278935 -0.957382 0.074938, 0.136567 -0.987792 0.074938, -0.153806 -0.985255 0.074938, -0.295621 -0.952362 0.074938, + -0.557461 -0.826814 0.074938, -0.671906 -0.736836 0.074938, -0.77203 -0.631153 0.074938, -0.94093 0.330206 0.074938, + -0.978981 0.189686 0.074938, -0.996167 0.045124 0.074938, -0.96693 -0.243784 0.074938, -0.919794 0.322788 0.223131, + -0.932985 0.327418 0.149455, -0.836478 -0.500518 0.223131, -0.900439 -0.373392 0.223131, -0.913353 -0.378747 0.149455, + -0.937884 0.181723 0.295552, -0.95699 0.185426 0.223131, -0.970715 0.188085 0.149455, -0.882462 -0.365937 0.295552, + -0.819777 -0.490525 0.295552, -0.73962 -0.604658 0.295552, -0.431135 -0.89917 0.074938, -0.427495 -0.891578 0.149455, + -0.293125 -0.94432 0.149455, -0.28898 -0.930969 0.223131, -0.150351 -0.963124 0.223131, -0.147349 -0.943895 0.295552, + -0.008346 -0.95529 0.295552, -0.152507 -0.976936 0.149455, -0.008516 -0.974751 0.223131, 0.130834 -0.946325 0.295552, + 0.134483 -0.920705 0.366357, 0.754459 -0.639104 0.149455, 0.839474 -0.522444 0.149455, 0.827604 -0.515057 0.223131, + 0.893778 -0.389068 0.223131, 0.875933 -0.3813 0.295552, 0.922117 -0.2497 0.295552, 0.906596 -0.394648 0.149455, + 0.940902 -0.254787 0.223131, 0.948646 -0.112778 0.295552, 0.925527 -0.095672 0.366397, 0.996803 0.027712 0.074938, + 0.988387 0.027478 0.149455, 0.973853 0.171095 0.149455, 0.960084 0.168676 0.223131, 0.925293 0.306668 0.223131, + 0.90682 0.300545 0.295552, 0.88327 0.444407 0.149455, 0.809151 0.568276 0.149455, 0.797711 0.560241 0.223131, + 0.707638 0.670419 0.223131, 0.69351 0.657034 0.295552, 0.590454 0.751008 0.295552, 0.816041 0.573115 0.074938, + 0.717787 0.680034 0.149455, 0.602483 0.766307 0.223131, 0.474815 0.828975 0.295552, 0.459374 0.809181 0.366334, + -0.064098 0.995126 0.074938, -0.206548 0.966955 0.149455, -0.345137 0.926576 0.149455, -0.340257 0.913476 0.223131, + -0.469634 0.854199 0.223131, -0.460258 0.837145 0.295552, -0.577242 0.76121 0.295552, -0.476369 0.86645 0.149455, + -0.589002 0.776717 0.223131, -0.681924 0.669051 0.295552, -0.67162 0.643967 0.366377, -0.789131 -0.492962 0.366415, + -0.697212 -0.616102 0.366488, -0.754688 -0.616976 0.223131, -0.848474 -0.507696 0.149455, -0.656813 -0.720285 0.223131, + -0.765511 -0.625824 0.149455, -0.855699 -0.512019 0.074938, -0.544939 -0.808241 0.223131, -0.666232 -0.730615 0.149455, + -0.421451 -0.878972 0.223131, -0.552754 -0.819833 0.149455, -0.018817 -0.930276 0.366377, 0.133499 -0.965604 0.223131, + -0.008639 -0.988731 0.149455, 0.27267 -0.935876 0.223131, 0.135414 -0.979452 0.149455, -0.008712 -0.99715 0.074938, + 0.406029 -0.886202 0.223131, 0.27658 -0.949298 0.149455, 0.530734 -0.81764 0.223131, 0.411852 -0.898911 0.149455, + 0.644127 -0.731651 0.223131, 0.538345 -0.829366 0.149455, 0.743792 -0.630068 0.223131, 0.653365 -0.742144 0.149455, + 0.542929 -0.836428 0.074938, 0.8972 -0.246641 0.366334, 0.967972 -0.115075 0.223131, 0.954396 -0.258441 0.149455, + 0.914316 -0.398008 0.074938, 0.974412 0.027089 0.223131, 0.981855 -0.116725 0.149455, 0.870781 0.438124 0.223131, + 0.938563 0.311066 0.149455, 0.586225 0.722561 0.366397, 0.484487 0.845863 0.223131, 0.611124 0.777297 0.149455, + 0.356166 0.907391 0.223131, 0.491436 0.857994 0.149455, 0.220253 0.949579 0.223131, 0.361274 0.920405 0.149455, + 0.49562 0.8653 0.074938, 0.079646 0.971529 0.223131, 0.223412 0.963198 0.149455, -0.062659 0.972773 0.223131, + 0.080788 0.985463 0.149455, -0.203628 0.953283 0.223131, -0.063557 0.986724 0.149455, -0.556533 0.74569 0.366357, + -0.695816 0.682681 0.223131, -0.597449 0.787857 0.149455, -0.7878 0.574094 0.223131, -0.705795 0.692472 0.149455, + -0.602536 0.794565 0.074938, -0.862993 0.453272 0.223131, -0.799098 0.582328 0.149455, -0.954348 0.04323 0.295552, + -0.925485 0.095576 0.366529, -0.987756 0.044743 0.149455, -0.97379 0.044111 0.223131, -0.950472 -0.096185 0.295552, + -0.928608 -0.058088 0.366488, -0.983744 -0.099552 0.149455, -0.969835 -0.098144 0.223131, -0.926339 -0.23355 0.295552, + -0.906411 -0.210141 0.366415, -0.958766 -0.241725 0.149455, -0.94521 -0.238308 0.223131, -0.845938 -0.52886 -0.068524, + -0.788269 -0.592337 0.166638, -0.910813 -0.377693 0.166638, -0.747755 -0.660438 -0.068437, -0.616196 -0.769762 0.166638, + -0.343325 -0.936727 -0.068337, -0.183969 -0.980654 -0.066878, -0.405405 -0.898821 0.166638, -0.169141 -0.971403 0.166638, + -0.492303 -0.867717 -0.068598, 0.143868 -0.987242 -0.068224, 0.305002 -0.949986 -0.067087, 0.077751 -0.982948 0.166638, + 0.319758 -0.932731 0.166638, -0.020023 -0.997439 -0.068658, 0.596398 -0.799795 -0.068098, 0.720411 -0.690276 -0.067285, + 0.541673 -0.823907 0.166638, 0.729552 -0.663314 0.166638, 0.457076 -0.88677 -0.068705, 0.905184 -0.419552 -0.06796, + 0.962116 -0.26416 -0.067471, 0.871592 -0.461042 0.166638, 0.958865 -0.229802 0.166638, 0.824012 -0.562387 -0.068739, + 0.99578 0.061841 -0.067809, 0.971864 0.225618 -0.067646, 0.98589 0.015878 0.166638, 0.950968 0.26056 0.166638, + 0.992357 -0.102469 -0.06876, 0.856293 0.48887 0.166638, 0.921541 0.382142 -0.068766, 0.84633 0.528346 -0.067646, + 0.747328 0.660986 -0.067809, 0.707814 0.686463 0.166638, 0.51486 0.840922 0.166638, 0.628633 0.774657 -0.06876, + 0.492843 0.867499 -0.067471, 0.342652 0.937001 -0.06796, 0.289556 0.942544 0.166638, 0.046058 0.984942 0.166638, + 0.184221 0.980478 -0.068739, 0.020519 0.997523 -0.067285, -0.144604 0.987144 -0.068098, -0.200334 0.965452 0.166638, + -0.434138 0.8853 0.166638, -0.304592 0.950002 -0.068705, -0.456775 0.887049 -0.067087, -0.596989 0.799344 -0.068224, + -0.640664 0.749521 0.166638, -0.806935 0.566646 0.166638, -0.720001 0.690568 -0.068658, -0.823959 0.562689 -0.066878, + -0.905466 0.418882 -0.068337, -0.922503 0.348168 0.166638, -0.961889 0.264697 -0.068598, -0.980106 0.107812 0.166638, + -0.995694 -0.06253 -0.068437, -0.976126 -0.139317 0.166638, -0.971951 -0.224978 -0.068524, -0.911313 -0.130067 0.39063, + -0.915029 0.100654 0.39063, -0.86125 0.32505 0.39063, -0.753355 0.529022 0.39063, -0.598125 0.699754 0.39063, + -0.405312 0.826517 0.39063, -0.187032 0.901348 0.39063, 0.043 0.919543 0.39063, 0.27033 0.87996 0.39063, + 0.480674 0.785086 0.39063, 0.660816 0.640883 0.39063, 0.799436 0.45641 0.39063, 0.887825 0.243259 0.39063, + 0.920429 0.014824 0.39063, 0.895198 -0.214543 0.39063, 0.813719 -0.43043 0.39063, 0.681111 -0.619271 0.39063, + 0.505706 -0.769201 0.39063, 0.298526 -0.870799 0.39063, 0.072589 -0.917681 0.39063, -0.15791 -0.906903 0.39063, + -0.378487 -0.83914 0.39063, -0.575282 -0.718651 0.39063, -0.735929 -0.553007 0.39063, -0.850336 -0.352615 0.39063, + -0.796871 -0.113733 0.593348, -0.80012 0.088014 0.593348, -0.753095 0.28423 0.593348, -0.65875 0.462588 0.593348, + -0.523013 0.611879 0.593348, -0.354413 0.722724 0.593348, -0.163545 0.788157 0.593348, 0.0376 0.804067 0.593348, + 0.236382 0.769455 0.593348, 0.420312 0.686496 0.593348, 0.577831 0.560401 0.593348, 0.699044 0.399094 0.593348, + 0.776333 0.212711 0.593348, 0.804842 0.012962 0.593348, 0.78278 -0.187601 0.593348, 0.711533 -0.376377 0.593348, + 0.595578 -0.541503 0.593348, 0.4422 -0.672605 0.593348, 0.261037 -0.761445 0.593348, 0.063473 -0.80244 0.593348, + -0.13808 -0.793015 0.593348, -0.330957 -0.733762 0.593348, -0.503038 -0.628404 0.593348, -0.643512 -0.483561 0.593348, + -0.743551 -0.308334 0.593348, -0.639032 -0.091206 0.763753, -0.641638 0.07058 0.763753, -0.603927 0.227932 0.763753, + -0.528269 0.370962 0.763753, -0.419418 0.490682 0.763753, -0.284214 0.579572 0.763753, -0.131151 0.632045 0.763753, + 0.030152 0.644804 0.763753, 0.189561 0.617047 0.763753, 0.337059 0.55052 0.763753, 0.463379 0.449401 0.763753, + 0.560582 0.320045 0.763753, 0.622562 0.170579 0.763753, 0.645425 0.010395 0.763753, 0.627732 -0.150442 0.763753, + 0.570597 -0.301827 0.763753, 0.47761 -0.434246 0.763753, 0.354612 -0.53938 0.763753, 0.209333 -0.610623 0.763753, + 0.050901 -0.643498 0.763753, -0.11073 -0.63594 0.763753, -0.265403 -0.588423 0.763753, -0.4034 -0.503934 0.763753, + -0.51605 -0.38778 0.763753, -0.596274 -0.247261 0.763753, -0.446393 -0.063711 0.892566, -0.448213 0.049304 0.892566, + -0.421871 0.159221 0.892566, -0.36902 0.259134 0.892566, -0.292983 0.342764 0.892566, -0.198536 0.404857 0.892566, + -0.091615 0.441512 0.892566, 0.021063 0.450425 0.892566, 0.132417 0.431036 0.892566, 0.235451 0.384563 0.892566, + 0.323691 0.313927 0.892566, 0.391592 0.223566 0.892566, 0.434888 0.119157 0.892566, 0.450858 0.007261 0.892566, + 0.4385 -0.105091 0.892566, 0.398588 -0.21084 0.892566, 0.333632 -0.303341 0.892566, 0.247713 -0.376782 0.892566, + 0.146229 -0.426548 0.892566, 0.035556 -0.449513 0.892566, -0.07735 -0.444233 0.892566, -0.185396 -0.411041 0.892566, + -0.281793 -0.352021 0.892566, -0.360484 -0.270882 0.892566, -0.416525 -0.172723 0.892566, -0.229444 -0.032747 0.972771, + -0.23038 0.025342 0.972771, -0.21684 0.081839 0.972771, -0.189675 0.133194 0.972771, -0.150592 0.176179 0.972771, + -0.102047 0.208095 0.972771, -0.04709 0.226935 0.972771, 0.010826 0.231516 0.972771, 0.068062 0.22155 0.972771, + 0.121021 0.197664 0.972771, 0.166376 0.161357 0.972771, 0.201277 0.114912 0.972771, 0.223531 0.061246 0.972771, + 0.231739 0.003732 0.972771, 0.225387 -0.054016 0.972771, 0.204873 -0.108371 0.972771, 0.171486 -0.155916 0.972771, + 0.127323 -0.193664 0.972771, 0.075161 -0.219244 0.972771, 0.018276 -0.231048 0.972771, -0.039758 -0.228334 0.972771, + -0.095293 -0.211273 0.972771, -0.14484 -0.180937 0.972771, -0.185287 -0.139232 0.972771, -0.214092 -0.088779 0.972771, + 0.749037 0.515235 -0.416505, 0.777088 0.59677 -0.2, 0.625545 0.65971 -0.416505, 0.674128 0.711255 -0.199167, + 0.474714 0.775352 -0.416505, 0.596154 0.77756 -0.2, 0.511881 0.83565 -0.199167, 0.303136 0.857107 -0.416505, + 0.374593 0.905362 -0.2, 0.327134 0.923691 -0.199445, 0.118309 0.901403 -0.416505, 0.127505 0.971464 -0.2, + -0.071688 0.906303 -0.416505, -0.077691 0.976824 -0.199445, -0.128273 0.971363 -0.2, -0.258553 0.871593 -0.416505, + -0.278901 0.93944 -0.199167, -0.37531 0.905065 -0.2, -0.434117 0.79879 -0.416505, -0.467753 0.861127 -0.199167, + -0.590708 0.691077 -0.416505, -0.59677 0.777088 -0.2, -0.636373 0.745152 -0.199445, -0.721483 0.55316 -0.416505, + -0.77756 0.596154 -0.2, -0.820725 0.391067 -0.416505, -0.8848 0.42113 -0.199445, -0.905362 0.374593 -0.2, + -0.884098 0.211883 -0.416505, -0.953029 0.228185 -0.199167, -0.971464 0.127505 -0.2, -0.908831 0.023439 -0.416505, + -0.979634 0.025477 -0.199167, -0.893844 -0.16603 -0.416505, -0.971363 -0.128273 -0.2, -0.963507 -0.17854 -0.199445, + -0.839792 -0.348243 -0.416505, -0.905065 -0.37531 -0.2, -0.749037 -0.515235 -0.416505, -0.807109 -0.555695 -0.199445, + -0.777088 -0.59677 -0.2, -0.625545 -0.65971 -0.416505, -0.674128 -0.711255 -0.199167, -0.596154 -0.77756 -0.2, + -0.474714 -0.775352 -0.416505, -0.511881 -0.83565 -0.199167, -0.303136 -0.857107 -0.416505, -0.374593 -0.905362 -0.2, + -0.327134 -0.923691 -0.199445, -0.118309 -0.901403 -0.416505, -0.127505 -0.971464 -0.2, 0.071688 -0.906303 -0.416505, + 0.077691 -0.976824 -0.199445, 0.128273 -0.971363 -0.2, 0.258553 -0.871593 -0.416505, 0.278901 -0.93944 -0.199167, + 0.37531 -0.905065 -0.2, 0.434117 -0.79879 -0.416505, 0.467753 -0.861127 -0.199167, 0.590708 -0.691077 -0.416505, + 0.59677 -0.777088 -0.2, 0.636373 -0.745152 -0.199445, 0.721483 -0.55316 -0.416505, 0.77756 -0.596154 -0.2, + 0.820725 -0.391067 -0.416505, 0.8848 -0.42113 -0.199445, 0.905362 -0.374593 -0.2, 0.884098 -0.211883 -0.416505, + 0.953029 -0.228185 -0.199167, 0.971464 -0.127505 -0.2, 0.908831 -0.023439 -0.416505, 0.979634 -0.025477 -0.199167, + 0.893844 0.16603 -0.416505, 0.971363 0.128273 -0.2, 0.963507 0.17854 -0.199445, 0.839792 0.348243 -0.416505, + 0.905065 0.37531 -0.2, 0.807109 0.555695 -0.199445, 0.778009 0.144514 -0.611407, 0.791053 -0.020401 -0.611407, + 0.769525 -0.184425 -0.611407, 0.714365 -0.340388 -0.611407, 0.627984 -0.481474 -0.611407, 0.514157 -0.601518 -0.611407, + 0.377859 -0.695273 -0.611407, 0.225046 -0.758641 -0.611407, 0.062398 -0.788852 -0.611407, -0.102977 -0.784587 -0.611407, + -0.263852 -0.746032 -0.611407, -0.413195 -0.674872 -0.611407, -0.544479 -0.574216 -0.611407, -0.651967 -0.448465 -0.611407, + -0.730961 -0.303113 -0.611407, -0.778009 -0.144514 -0.611407, -0.791053 0.020401 -0.611407, -0.769525 0.184425 -0.611407, + -0.714365 0.340388 -0.611407, -0.627984 0.481474 -0.611407, -0.514157 0.601518 -0.611407, -0.377859 0.695273 -0.611407, + -0.225046 0.758641 -0.611407, -0.062398 0.788852 -0.611407, 0.102977 0.784587 -0.611407, 0.263852 0.746032 -0.611407, + 0.413195 0.674872 -0.611407, 0.544479 0.574216 -0.611407, 0.651967 0.448465 -0.611407, 0.730961 0.303113 -0.611407, + 0.621819 0.115502 -0.774597, 0.632245 -0.016306 -0.774597, 0.615039 -0.1474 -0.774597, 0.570953 -0.272053 -0.774597, + 0.501913 -0.384816 -0.774597, 0.410937 -0.48076 -0.774597, 0.302002 -0.555693 -0.774597, 0.179867 -0.60634 -0.774597, + 0.049871 -0.630486 -0.774597, -0.082304 -0.627077 -0.774597, -0.210882 -0.596262 -0.774597, -0.330244 -0.539388 -0.774597, + -0.435172 -0.458939 -0.774597, -0.521081 -0.358433 -0.774597, -0.584217 -0.242261 -0.774597, -0.621819 -0.115502 -0.774597, + -0.632245 0.016306 -0.774597, -0.615039 0.1474 -0.774597, -0.570953 0.272053 -0.774597, -0.501913 0.384816 -0.774597, + -0.410937 0.48076 -0.774597, -0.302002 0.555693 -0.774597, -0.179867 0.60634 -0.774597, -0.049871 0.630486 -0.774597, + 0.082304 0.627077 -0.774597, 0.210882 0.596262 -0.774597, 0.330244 0.539388 -0.774597, 0.435172 0.458939 -0.774597, + 0.521081 0.358433 -0.774597, 0.584217 0.242261 -0.774597, 0.433378 0.080499 -0.89761, 0.440644 -0.011364 -0.89761, + 0.428652 -0.102731 -0.89761, 0.397926 -0.189608 -0.89761, 0.349809 -0.268198 -0.89761, 0.286403 -0.335067 -0.89761, + 0.21048 -0.387291 -0.89761, 0.125359 -0.422589 -0.89761, 0.034758 -0.439418 -0.89761, -0.057362 -0.437042 -0.89761, + -0.146975 -0.415566 -0.89761, -0.230164 -0.375927 -0.89761, -0.303294 -0.319858 -0.89761, -0.363168 -0.24981 -0.89761, + -0.407171 -0.168844 -0.89761, -0.433378 -0.080499 -0.89761, -0.440644 0.011364 -0.89761, -0.428652 0.102731 -0.89761, + -0.397926 0.189608 -0.89761, -0.349809 0.268198 -0.89761, -0.286403 0.335067 -0.89761, -0.21048 0.387291 -0.89761, + -0.125359 0.422589 -0.89761, -0.034758 0.439418 -0.89761, 0.057362 0.437042 -0.89761, 0.146975 0.415566 -0.89761, + 0.230164 0.375927 -0.89761, 0.303294 0.319858 -0.89761, 0.363168 0.24981 -0.89761, 0.407171 0.168844 -0.89761, + 0.222458 0.041321 -0.974066, 0.226188 -0.005833 -0.974066, 0.220032 -0.052733 -0.974066, 0.20426 -0.097328 -0.974066, + 0.179561 -0.137669 -0.974066, 0.147014 -0.171994 -0.974066, 0.108042 -0.198801 -0.974066, 0.064348 -0.21692 -0.974066, + 0.017842 -0.225559 -0.974066, -0.029445 -0.224339 -0.974066, -0.075444 -0.213315 -0.974066, -0.118146 -0.192968 -0.974066, + -0.155684 -0.164187 -0.974066, -0.186419 -0.128231 -0.974066, -0.209006 -0.08667 -0.974066, -0.222458 -0.041321 -0.974066, + -0.226188 0.005833 -0.974066, -0.220032 0.052733 -0.974066, -0.20426 0.097328 -0.974066, -0.179561 0.137669 -0.974066, + -0.147014 0.171994 -0.974066, -0.108042 0.198801 -0.974066, -0.064348 0.21692 -0.974066, -0.017842 0.225559 -0.974066, + 0.029445 0.224339 -0.974066, 0.075444 0.213315 -0.974066, 0.118146 0.192968 -0.974066, 0.155684 0.164187 -0.974066, + 0.186419 0.128231 -0.974066, 0.209006 0.08667 -0.974066, -0.962942 -0.178435 -0.202249, -0.901309 -0.119022 -0.416505, + -0.978764 0.025455 -0.203403, -0.901403 0.118309 -0.416505, -0.952182 0.227982 -0.203403, -0.840067 0.347578 -0.416505, + -0.884281 0.420883 -0.202249, -0.636 0.744714 -0.202249, -0.553731 0.721045 -0.416505, -0.467338 0.860362 -0.203403, + -0.348243 0.839792 -0.416505, -0.278653 0.938605 -0.203403, -0.119022 0.901309 -0.416505, -0.077645 0.976251 -0.202249, + 0.326942 0.923149 -0.202249, 0.347578 0.840067 -0.416505, 0.511426 0.834907 -0.203403, 0.55316 0.721483 -0.416505, + 0.673529 0.710623 -0.203403, 0.721045 0.553731 -0.416505, 0.806636 0.555369 -0.202249, 0.962942 0.178435 -0.202249, + 0.901309 0.119022 -0.416505, 0.978764 -0.025455 -0.203403, 0.901403 -0.118309 -0.416505, 0.952182 -0.227982 -0.203403, + 0.840067 -0.347578 -0.416505, 0.884281 -0.420883 -0.202249, 0.636 -0.744714 -0.202249, 0.553731 -0.721045 -0.416505, + 0.467338 -0.860362 -0.203403, 0.348243 -0.839792 -0.416505, 0.278653 -0.938605 -0.203403, 0.119022 -0.901309 -0.416505, + 0.077645 -0.976251 -0.202249, -0.326942 -0.923149 -0.202249, -0.347578 -0.840067 -0.416505, -0.511426 -0.834907 -0.203403, + -0.55316 -0.721483 -0.416505, -0.673529 -0.710623 -0.203403, -0.721045 -0.553731 -0.416505, -0.806636 -0.555369 -0.202249, + -0.627603 -0.481971 -0.611407, -0.481474 -0.627984 -0.611407, -0.302534 -0.731201 -0.611407, 0.103598 -0.784506 -0.611407, + 0.303113 -0.730961 -0.611407, 0.481971 -0.627603 -0.611407, 0.731201 -0.302534 -0.611407, 0.784587 -0.102977 -0.611407, + 0.784506 0.103598 -0.611407, 0.627603 0.481971 -0.611407, 0.481474 0.627984 -0.611407, 0.302534 0.731201 -0.611407, + -0.103598 0.784506 -0.611407, -0.303113 0.730961 -0.611407, -0.481971 0.627603 -0.611407, -0.731201 0.302534 -0.611407, + -0.784587 0.102977 -0.611407, -0.784506 -0.103598 -0.611407, -0.501608 -0.385213 -0.774597, -0.384816 -0.501913 -0.774597, + -0.241799 -0.584408 -0.774597, 0.0828 -0.627012 -0.774597, 0.242261 -0.584217 -0.774597, 0.385213 -0.501608 -0.774597, + 0.584408 -0.241799 -0.774597, 0.627077 -0.082304 -0.774597, 0.627012 0.0828 -0.774597, 0.501608 0.385213 -0.774597, + 0.384816 0.501913 -0.774597, 0.241799 0.584408 -0.774597, -0.0828 0.627012 -0.774597, -0.242261 0.584217 -0.774597, + -0.385213 0.501608 -0.774597, -0.584408 0.241799 -0.774597, -0.627077 0.082304 -0.774597, -0.627012 -0.0828 -0.774597, + -0.349597 -0.268475 -0.89761, -0.268198 -0.349809 -0.89761, -0.168522 -0.407304 -0.89761, 0.057708 -0.436997 -0.89761, + 0.168844 -0.407171 -0.89761, 0.268475 -0.349597 -0.89761, 0.407304 -0.168522 -0.89761, 0.437042 -0.057362 -0.89761, + 0.436997 0.057708 -0.89761, 0.349597 0.268475 -0.89761, 0.268198 0.349809 -0.89761, 0.168522 0.407304 -0.89761, + -0.057708 0.436997 -0.89761, -0.168844 0.407171 -0.89761, -0.268475 0.349597 -0.89761, -0.407304 0.168522 -0.89761, + -0.437042 0.057362 -0.89761, -0.436997 -0.057708 -0.89761, -0.179452 -0.137811 -0.974066, -0.137669 -0.179561 -0.974066, + -0.086504 -0.209074 -0.974066, 0.029622 -0.224316 -0.974066, 0.08667 -0.209006 -0.974066, 0.137811 -0.179452 -0.974066, + 0.209074 -0.086504 -0.974066, 0.224339 -0.029445 -0.974066, 0.224316 0.029622 -0.974066, 0.179452 0.137811 -0.974066, + 0.137669 0.179561 -0.974066, 0.086504 0.209074 -0.974066, -0.029622 0.224316 -0.974066, -0.08667 0.209006 -0.974066, + -0.137811 0.179452 -0.974066, -0.209074 0.086504 -0.974066, -0.224339 0.029445 -0.974066, -0.224316 -0.029622 -0.974066] + } + coordIndex [ + 883, 977, 798, -1,798, 977, 1044, -1,798, 1044, 712, -1,712, 1044, 1087, -1,712, + 1087, 608, -1,608, 1087, 1115, -1,608, 1115, 513, -1,513, 1115, 1123, -1,513, 1123, + 466, -1,466, 1123, 1112, -1,466, 1112, 432, -1,1112, 1096, 432, -1,432, 1096, 1081, -1, + 432, 1081, 412, -1,412, 1081, 1039, -1,412, 1039, 410, -1,410, 1039, 967, -1,410, + 967, 426, -1,426, 967, 865, -1,426, 865, 459, -1,459, 865, 776, -1,459, 776, 507, -1, + 507, 776, 694, -1,507, 694, 595, -1,1261, 1258, 1204, -1,1156, 1132, 1084, -1,1029, + 980, 946, -1,852, 791, 779, -1,703, 599, 627, -1,510, 433, 477, -1,386, 288, 351, -1, + 279, 228, 269, -1,163, 159, 201, -1,134, 129, 180, -1,119, 111, 162, -1,100, 96, + 153, -1,90, 92, 152, -1,95, 108, 160, -1,109, 124, 171, -1,144, 149, 192, -1,172, + 183, 215, -1,207, 216, 258, -1,244, 277, 322, -1,300, 397, 444, -1,439, 548, 584, -1, + 922, 934, 897, -1,1073, 1094, 1053, -1,1207, 1239, 1177, -1,1283, 1298, 1264, -1, + 1319, 1343, 1303, -1,1352, 1372, 1333, -1,1385, 1403, 1353, -1,1405, 1420, 1367, -1, + 1438, 1436, 1379, -1,619, 708, 707, -1,1163, 1183, 1170, -1,1102, 1114, 1101, -1, + 478, 528, 539, -1,379, 428, 438, -1,348, 378, 399, -1,303, 323, 340, -1,339, 320, + 337, -1,460, 419, 427, -1,669, 594, 602, -1,811, 762, 765, -1,917, 826, 824, -1,1038, + 995, 988, -1,1103, 1052, 1046, -1,1169, 1143, 1129, -1,1202, 1180, 1164, -1,1227, + 1220, 1195, -1,1209, 1223, 1201, -1,705, 708, 650, -1,650, 708, 619, -1,650, 619, + 614, -1,614, 619, 537, -1,767, 769, 790, -1,839, 845, 911, -1,1004, 1015, 1028, -1, + 1054, 1061, 1102, -1,1114, 1155, 1142, -1,1142, 1155, 1163, -1,770, 707, 768, -1, + 768, 707, 708, -1,768, 708, 767, -1,767, 708, 705, -1,767, 705, 769, -1,862, 770, + 853, -1,853, 770, 768, -1,853, 768, 842, -1,842, 768, 767, -1,842, 767, 839, -1,839, + 767, 790, -1,839, 790, 845, -1,1005, 862, 973, -1,973, 862, 853, -1,973, 853, 947, -1, + 947, 853, 842, -1,947, 842, 936, -1,936, 842, 839, -1,936, 839, 931, -1,931, 839, + 911, -1,931, 911, 937, -1,1290, 1285, 1250, -1,1139, 1005, 1088, -1,1088, 1005, 973, -1, + 1088, 973, 1049, -1,1049, 973, 947, -1,1049, 947, 1024, -1,1024, 947, 936, -1,1024, + 936, 1011, -1,1011, 936, 931, -1,1011, 931, 1004, -1,1004, 931, 937, -1,1004, 937, + 1015, -1,1275, 1139, 1232, -1,1232, 1139, 1088, -1,1232, 1088, 1166, -1,1166, 1088, + 1049, -1,1166, 1049, 1116, -1,1116, 1049, 1024, -1,1116, 1024, 1080, -1,1080, 1024, + 1011, -1,1080, 1011, 1058, -1,1058, 1011, 1004, -1,1058, 1004, 1054, -1,1054, 1004, + 1028, -1,1054, 1028, 1061, -1,1370, 1355, 1318, -1,1367, 1377, 1336, -1,1336, 1377, + 1337, -1,1336, 1337, 1297, -1,1297, 1337, 1290, -1,1297, 1290, 1262, -1,1262, 1290, + 1250, -1,1262, 1250, 1213, -1,320, 307, 337, -1,337, 307, 324, -1,337, 324, 315, -1, + 315, 324, 319, -1,315, 319, 290, -1,290, 319, 298, -1,290, 298, 273, -1,273, 298, + 286, -1,273, 286, 254, -1,254, 286, 275, -1,254, 275, 236, -1,236, 275, 265, -1,236, + 265, 223, -1,223, 265, 269, -1,1436, 1431, 1379, -1,1379, 1431, 1370, -1,1379, 1370, + 1331, -1,1331, 1370, 1318, -1,1331, 1318, 1285, -1,1285, 1290, 1331, -1,1331, 1290, + 1337, -1,1331, 1337, 1379, -1,1379, 1337, 1377, -1,1379, 1377, 1438, -1,1420, 1422, + 1367, -1,1367, 1422, 1434, -1,1367, 1434, 1377, -1,1377, 1434, 1435, -1,1377, 1435, + 1438, -1,1403, 1405, 1353, -1,1353, 1405, 1367, -1,1353, 1367, 1327, -1,1327, 1367, + 1336, -1,1327, 1336, 1296, -1,1296, 1336, 1297, -1,1296, 1297, 1270, -1,1270, 1297, + 1262, -1,1270, 1262, 1231, -1,1231, 1262, 1213, -1,1231, 1213, 1178, -1,1372, 1385, + 1333, -1,1333, 1385, 1353, -1,1333, 1353, 1316, -1,1316, 1353, 1327, -1,1316, 1327, + 1287, -1,1287, 1327, 1296, -1,1287, 1296, 1269, -1,1269, 1296, 1270, -1,1269, 1270, + 1238, -1,1238, 1270, 1231, -1,1238, 1231, 1194, -1,1194, 1231, 1178, -1,1194, 1178, + 1170, -1,1343, 1352, 1303, -1,1303, 1352, 1333, -1,1303, 1333, 1292, -1,1292, 1333, + 1316, -1,1292, 1316, 1281, -1,1281, 1316, 1287, -1,1281, 1287, 1260, -1,1260, 1287, + 1269, -1,1260, 1269, 1237, -1,1237, 1269, 1238, -1,1237, 1238, 1214, -1,1214, 1238, + 1194, -1,1214, 1194, 1189, -1,1189, 1194, 1170, -1,1189, 1170, 1206, -1,1206, 1170, + 1183, -1,1298, 1319, 1264, -1,1264, 1319, 1303, -1,1264, 1303, 1268, -1,1268, 1303, + 1292, -1,1268, 1292, 1257, -1,1257, 1292, 1281, -1,1257, 1281, 1246, -1,1246, 1281, + 1260, -1,1246, 1260, 1230, -1,1230, 1260, 1237, -1,1230, 1237, 1210, -1,1210, 1237, + 1214, -1,1210, 1214, 1201, -1,1201, 1214, 1189, -1,1201, 1189, 1209, -1,1209, 1189, + 1206, -1,1239, 1283, 1177, -1,1177, 1283, 1264, -1,1177, 1264, 1216, -1,1216, 1264, + 1268, -1,1216, 1268, 1226, -1,1226, 1268, 1257, -1,1226, 1257, 1218, -1,1218, 1257, + 1246, -1,1218, 1246, 1200, -1,1200, 1246, 1230, -1,1200, 1230, 1191, -1,1191, 1230, + 1210, -1,1191, 1210, 1195, -1,1195, 1210, 1201, -1,1195, 1201, 1227, -1,1227, 1201, + 1223, -1,1094, 1207, 1053, -1,1053, 1207, 1177, -1,1053, 1177, 1117, -1,1117, 1177, + 1216, -1,1117, 1216, 1148, -1,1148, 1216, 1226, -1,1148, 1226, 1160, -1,1160, 1226, + 1218, -1,1160, 1218, 1165, -1,1165, 1218, 1200, -1,1165, 1200, 1172, -1,1172, 1200, + 1191, -1,1172, 1191, 1186, -1,1186, 1191, 1195, -1,1186, 1195, 1212, -1,1212, 1195, + 1220, -1,934, 1073, 897, -1,897, 1073, 1053, -1,897, 1053, 1018, -1,1018, 1053, 1117, -1, + 1018, 1117, 1064, -1,1064, 1117, 1148, -1,1064, 1148, 1097, -1,1097, 1148, 1160, -1, + 1097, 1160, 1120, -1,1120, 1160, 1165, -1,1120, 1165, 1137, -1,1137, 1165, 1172, -1, + 1137, 1172, 1164, -1,1164, 1172, 1186, -1,1164, 1186, 1202, -1,1202, 1186, 1212, -1, + 586, 737, 743, -1,743, 737, 761, -1,761, 922, 743, -1,743, 922, 897, -1,743, 897, + 872, -1,872, 897, 1018, -1,872, 1018, 978, -1,978, 1018, 1064, -1,978, 1064, 1035, -1, + 1035, 1064, 1097, -1,1035, 1097, 1063, -1,1063, 1097, 1120, -1,1063, 1120, 1092, -1, + 1092, 1120, 1137, -1,1092, 1137, 1129, -1,1129, 1137, 1164, -1,1129, 1164, 1169, -1, + 1169, 1164, 1180, -1,548, 586, 584, -1,584, 586, 743, -1,584, 743, 746, -1,746, 743, + 872, -1,746, 872, 854, -1,854, 872, 978, -1,854, 978, 948, -1,948, 978, 1035, -1, + 948, 1035, 1012, -1,1012, 1035, 1063, -1,1012, 1063, 1048, -1,1048, 1063, 1092, -1, + 1048, 1092, 1090, -1,1090, 1092, 1129, -1,1090, 1129, 1110, -1,1110, 1129, 1143, -1, + 397, 439, 444, -1,444, 439, 584, -1,444, 584, 615, -1,615, 584, 746, -1,615, 746, + 748, -1,748, 746, 854, -1,748, 854, 838, -1,838, 854, 948, -1,838, 948, 926, -1,926, + 948, 1012, -1,926, 1012, 991, -1,991, 1012, 1048, -1,991, 1048, 1046, -1,1046, 1048, + 1090, -1,1046, 1090, 1103, -1,1103, 1090, 1110, -1,277, 300, 322, -1,322, 300, 444, -1, + 322, 444, 487, -1,487, 444, 615, -1,487, 615, 633, -1,633, 615, 748, -1,633, 748, + 755, -1,755, 748, 838, -1,755, 838, 827, -1,827, 838, 926, -1,827, 926, 913, -1,913, + 926, 991, -1,913, 991, 988, -1,988, 991, 1046, -1,988, 1046, 1038, -1,1038, 1046, + 1052, -1,216, 244, 258, -1,258, 244, 322, -1,258, 322, 387, -1,387, 322, 487, -1, + 387, 487, 517, -1,517, 487, 633, -1,517, 633, 646, -1,646, 633, 755, -1,646, 755, + 760, -1,760, 755, 827, -1,760, 827, 825, -1,825, 827, 913, -1,825, 913, 907, -1,907, + 913, 988, -1,907, 988, 928, -1,928, 988, 995, -1,183, 207, 215, -1,215, 207, 258, -1, + 215, 258, 294, -1,294, 258, 387, -1,294, 387, 440, -1,440, 387, 517, -1,440, 517, + 558, -1,558, 517, 646, -1,558, 646, 656, -1,656, 646, 760, -1,656, 760, 764, -1,764, + 760, 825, -1,764, 825, 824, -1,824, 825, 907, -1,824, 907, 917, -1,917, 907, 928, -1, + 149, 172, 192, -1,192, 172, 215, -1,192, 215, 259, -1,259, 215, 294, -1,259, 294, + 362, -1,362, 294, 440, -1,362, 440, 481, -1,481, 440, 558, -1,481, 558, 583, -1,583, + 558, 656, -1,583, 656, 675, -1,675, 656, 764, -1,675, 764, 765, -1,765, 764, 824, -1, + 765, 824, 811, -1,811, 824, 826, -1,124, 144, 171, -1,171, 144, 192, -1,171, 192, + 226, -1,226, 192, 259, -1,226, 259, 291, -1,291, 259, 362, -1,291, 362, 418, -1,418, + 362, 481, -1,418, 481, 502, -1,502, 481, 583, -1,502, 583, 597, -1,597, 583, 675, -1, + 597, 675, 679, -1,679, 675, 765, -1,679, 765, 683, -1,683, 765, 762, -1,108, 109, + 160, -1,160, 109, 171, -1,160, 171, 211, -1,211, 171, 226, -1,211, 226, 268, -1,268, + 226, 291, -1,268, 291, 353, -1,353, 291, 418, -1,353, 418, 445, -1,445, 418, 502, -1, + 445, 502, 512, -1,512, 502, 597, -1,512, 597, 602, -1,602, 597, 679, -1,602, 679, + 669, -1,669, 679, 683, -1,92, 95, 152, -1,152, 95, 160, -1,152, 160, 203, -1,203, + 160, 211, -1,203, 211, 248, -1,248, 211, 268, -1,248, 268, 299, -1,299, 268, 353, -1, + 299, 353, 401, -1,401, 353, 445, -1,401, 445, 467, -1,467, 445, 512, -1,467, 512, + 519, -1,519, 512, 602, -1,519, 602, 556, -1,556, 602, 594, -1,96, 90, 153, -1,153, + 90, 152, -1,153, 152, 197, -1,197, 152, 203, -1,197, 203, 238, -1,238, 203, 248, -1, + 238, 248, 282, -1,282, 248, 299, -1,282, 299, 352, -1,352, 299, 401, -1,352, 401, + 423, -1,423, 401, 467, -1,423, 467, 472, -1,472, 467, 519, -1,472, 519, 509, -1,509, + 519, 556, -1,111, 100, 162, -1,162, 100, 153, -1,162, 153, 198, -1,198, 153, 197, -1, + 198, 197, 229, -1,229, 197, 238, -1,229, 238, 272, -1,272, 238, 282, -1,272, 282, + 316, -1,316, 282, 352, -1,316, 352, 377, -1,377, 352, 423, -1,377, 423, 427, -1,427, + 423, 472, -1,427, 472, 460, -1,460, 472, 509, -1,129, 119, 180, -1,180, 119, 162, -1, + 180, 162, 205, -1,205, 162, 198, -1,205, 198, 230, -1,230, 198, 229, -1,230, 229, + 263, -1,263, 229, 272, -1,263, 272, 295, -1,295, 272, 316, -1,295, 316, 349, -1,349, + 316, 377, -1,349, 377, 384, -1,384, 377, 427, -1,384, 427, 394, -1,394, 427, 419, -1, + 159, 134, 201, -1,201, 134, 180, -1,201, 180, 214, -1,214, 180, 205, -1,214, 205, + 239, -1,239, 205, 230, -1,239, 230, 264, -1,264, 230, 263, -1,264, 263, 289, -1,289, + 263, 295, -1,289, 295, 330, -1,330, 295, 349, -1,330, 349, 357, -1,357, 349, 384, -1, + 357, 384, 374, -1,374, 384, 394, -1,374, 339, 357, -1,357, 339, 337, -1,357, 337, + 330, -1,330, 337, 315, -1,330, 315, 289, -1,289, 315, 290, -1,289, 290, 264, -1,264, + 290, 273, -1,264, 273, 239, -1,239, 273, 254, -1,239, 254, 214, -1,214, 254, 236, -1, + 214, 236, 201, -1,201, 236, 223, -1,201, 223, 163, -1,228, 224, 269, -1,269, 224, + 191, -1,269, 191, 223, -1,223, 191, 188, -1,223, 188, 163, -1,288, 279, 351, -1,351, + 279, 269, -1,351, 269, 312, -1,312, 269, 265, -1,312, 265, 301, -1,301, 265, 275, -1, + 301, 275, 310, -1,310, 275, 286, -1,310, 286, 325, -1,325, 286, 298, -1,325, 298, + 333, -1,333, 298, 319, -1,333, 319, 328, -1,328, 319, 324, -1,328, 324, 305, -1,305, + 324, 307, -1,433, 386, 477, -1,477, 386, 351, -1,477, 351, 417, -1,417, 351, 312, -1, + 417, 312, 376, -1,376, 312, 301, -1,376, 301, 371, -1,371, 301, 310, -1,371, 310, + 365, -1,365, 310, 325, -1,365, 325, 355, -1,355, 325, 333, -1,355, 333, 340, -1,340, + 333, 328, -1,340, 328, 303, -1,303, 328, 305, -1,599, 510, 627, -1,627, 510, 477, -1, + 627, 477, 506, -1,506, 477, 417, -1,506, 417, 457, -1,457, 417, 376, -1,457, 376, + 430, -1,430, 376, 371, -1,430, 371, 414, -1,414, 371, 365, -1,414, 365, 391, -1,391, + 365, 355, -1,391, 355, 366, -1,366, 355, 340, -1,366, 340, 335, -1,335, 340, 323, -1, + 791, 703, 779, -1,779, 703, 627, -1,779, 627, 641, -1,641, 627, 506, -1,641, 506, + 551, -1,551, 506, 457, -1,551, 457, 493, -1,493, 457, 430, -1,493, 430, 458, -1,458, + 430, 414, -1,458, 414, 436, -1,436, 414, 391, -1,436, 391, 399, -1,399, 391, 366, -1, + 399, 366, 348, -1,348, 366, 335, -1,980, 852, 946, -1,946, 852, 779, -1,946, 779, + 774, -1,774, 779, 641, -1,774, 641, 654, -1,654, 641, 551, -1,654, 551, 581, -1,581, + 551, 493, -1,581, 493, 511, -1,511, 493, 458, -1,511, 458, 482, -1,482, 458, 436, -1, + 482, 436, 438, -1,438, 436, 399, -1,438, 399, 379, -1,379, 399, 378, -1,1132, 1029, + 1084, -1,1084, 1029, 946, -1,1084, 946, 914, -1,914, 946, 774, -1,914, 774, 772, -1, + 772, 774, 654, -1,772, 654, 682, -1,682, 654, 581, -1,682, 581, 605, -1,605, 581, + 511, -1,605, 511, 533, -1,533, 511, 482, -1,533, 482, 484, -1,484, 482, 438, -1,484, + 438, 450, -1,450, 438, 428, -1,1258, 1156, 1204, -1,1204, 1156, 1084, -1,1204, 1084, + 1042, -1,1042, 1084, 914, -1,1042, 914, 886, -1,886, 914, 772, -1,886, 772, 771, -1, + 771, 772, 682, -1,771, 682, 701, -1,701, 682, 605, -1,701, 605, 616, -1,616, 605, + 533, -1,616, 533, 539, -1,539, 533, 484, -1,539, 484, 478, -1,478, 484, 450, -1,1275, + 1309, 1306, -1,1306, 1261, 1275, -1,1275, 1261, 1204, -1,1275, 1204, 1139, -1,1139, + 1204, 1042, -1,1139, 1042, 1005, -1,1005, 1042, 886, -1,1005, 886, 862, -1,862, 886, + 771, -1,862, 771, 770, -1,770, 771, 701, -1,770, 701, 707, -1,707, 701, 616, -1,707, + 616, 619, -1,619, 616, 539, -1,619, 539, 537, -1,537, 539, 528, -1,1310, 1348, 1344, -1, + 1102, 1101, 1054, -1,1054, 1101, 1108, -1,1054, 1108, 1058, -1,1058, 1108, 1127, -1, + 1058, 1127, 1080, -1,1080, 1127, 1174, -1,1080, 1174, 1116, -1,1116, 1174, 1234, -1, + 1116, 1234, 1166, -1,1166, 1234, 1274, -1,1166, 1274, 1232, -1,1232, 1274, 1310, -1, + 1232, 1310, 1275, -1,1275, 1310, 1344, -1,1275, 1344, 1309, -1,1340, 1383, 1369, -1, + 1114, 1142, 1101, -1,1101, 1142, 1147, -1,1101, 1147, 1108, -1,1108, 1147, 1175, -1, + 1108, 1175, 1127, -1,1127, 1175, 1228, -1,1127, 1228, 1174, -1,1174, 1228, 1265, -1, + 1174, 1265, 1234, -1,1234, 1265, 1301, -1,1234, 1301, 1274, -1,1274, 1301, 1340, -1, + 1274, 1340, 1310, -1,1310, 1340, 1369, -1,1310, 1369, 1348, -1,1431, 1425, 1370, -1, + 1370, 1425, 1416, -1,1370, 1416, 1355, -1,1355, 1416, 1408, -1,1355, 1408, 1398, -1, + 1163, 1170, 1142, -1,1142, 1170, 1178, -1,1142, 1178, 1147, -1,1147, 1178, 1213, -1, + 1147, 1213, 1175, -1,1175, 1213, 1250, -1,1175, 1250, 1228, -1,1228, 1250, 1285, -1, + 1228, 1285, 1265, -1,1265, 1285, 1318, -1,1265, 1318, 1301, -1,1301, 1318, 1355, -1, + 1301, 1355, 1340, -1,1340, 1355, 1398, -1,1340, 1398, 1383, -1,1480, 1481, 1496, -1, + 1496, 1481, 1497, -1,1496, 1497, 1503, -1,1503, 1497, 1504, -1,1503, 1504, 1518, -1, + 1518, 1504, 1519, -1,1518, 1519, 1522, -1,1522, 1519, 1523, -1,1522, 1523, 1530, -1, + 1530, 1523, 1531, -1,1530, 1531, 1528, -1,1528, 1531, 1529, -1,1528, 1529, 1526, -1, + 1526, 1529, 1527, -1,1526, 1527, 1515, -1,1515, 1527, 1516, -1,1515, 1516, 1512, -1, + 1512, 1516, 1513, -1,1512, 1513, 1493, -1,1493, 1513, 1494, -1,1493, 1494, 1489, -1, + 1489, 1494, 1490, -1,1489, 1490, 1466, -1,1466, 1490, 1467, -1,1466, 1467, 1446, -1, + 1446, 1467, 1447, -1,1446, 1447, 1427, -1,1427, 1447, 1428, -1,1427, 1428, 1388, -1, + 1388, 1428, 1389, -1,1388, 1389, 1381, -1,1381, 1389, 1382, -1,1381, 1382, 1334, -1, + 1334, 1382, 1335, -1,1334, 1335, 1320, -1,1320, 1335, 1321, -1,1320, 1321, 1276, -1, + 1276, 1321, 1277, -1,1276, 1277, 1221, -1,1221, 1277, 1222, -1,1221, 1222, 1149, -1, + 1149, 1222, 1150, -1,1149, 1150, 974, -1,974, 1150, 975, -1,974, 975, 971, -1,971, + 975, 972, -1,971, 972, 749, -1,749, 972, 750, -1,749, 750, 666, -1,666, 750, 667, -1, + 666, 667, 526, -1,526, 667, 527, -1,526, 527, 406, -1,406, 527, 407, -1,406, 407, + 360, -1,360, 407, 361, -1,360, 361, 246, -1,246, 361, 247, -1,246, 247, 240, -1,240, + 247, 241, -1,240, 241, 189, -1,189, 241, 190, -1,189, 190, 166, -1,166, 190, 167, -1, + 166, 167, 142, -1,142, 167, 143, -1,142, 143, 103, -1,103, 143, 104, -1,103, 104, + 98, -1,98, 104, 99, -1,98, 99, 62, -1,62, 99, 63, -1,62, 63, 54, -1,54, 63, 55, -1, + 54, 55, 36, -1,36, 55, 37, -1,36, 37, 23, -1,23, 37, 24, -1,23, 24, 16, -1,16, 24, + 17, -1,16, 17, 4, -1,4, 17, 5, -1,4, 5, 2, -1,2, 5, 3, -1,2, 3, 0, -1,0, 3, 1, -1, + 0, 1, 6, -1,6, 1, 7, -1,6, 7, 12, -1,12, 7, 13, -1,12, 13, 26, -1,26, 13, 27, -1, + 26, 27, 29, -1,29, 27, 30, -1,29, 30, 50, -1,50, 30, 51, -1,50, 51, 59, -1,59, 51, + 60, -1,59, 60, 82, -1,82, 60, 83, -1,82, 83, 112, -1,112, 83, 113, -1,112, 113, 125, -1, + 125, 113, 126, -1,125, 126, 173, -1,173, 126, 174, -1,173, 174, 176, -1,176, 174, + 177, -1,176, 177, 218, -1,218, 177, 219, -1,218, 219, 251, -1,251, 219, 252, -1,251, + 252, 292, -1,292, 252, 293, -1,292, 293, 434, -1,434, 293, 435, -1,434, 435, 463, -1, + 463, 435, 464, -1,463, 464, 658, -1,658, 464, 659, -1,658, 659, 717, -1,717, 659, + 718, -1,717, 718, 876, -1,876, 718, 877, -1,876, 877, 1013, -1,1013, 877, 1014, -1, + 1013, 1014, 1082, -1,1082, 1014, 1083, -1,1082, 1083, 1241, -1,1241, 1083, 1242, -1, + 1241, 1242, 1247, -1,1247, 1242, 1248, -1,1247, 1248, 1312, -1,1312, 1248, 1313, -1, + 1312, 1313, 1328, -1,1328, 1313, 1329, -1,1328, 1329, 1361, -1,1361, 1329, 1362, -1, + 1361, 1362, 1396, -1,1396, 1362, 1397, -1,1396, 1397, 1409, -1,1409, 1397, 1410, -1, + 1409, 1410, 1451, -1,1451, 1410, 1452, -1,1451, 1452, 1455, -1,1455, 1452, 1456, -1, + 1455, 1456, 1480, -1,1480, 1456, 1481, -1,235, 137, 227, -1,227, 137, 136, -1,227, + 136, 237, -1,817, 766, 674, -1,674, 766, 609, -1,674, 609, 523, -1,326, 206, 276, -1, + 276, 206, 182, -1,276, 182, 245, -1,245, 182, 161, -1,245, 161, 235, -1,235, 161, + 146, -1,235, 146, 137, -1,1179, 1252, 1078, -1,1078, 1252, 1157, -1,1078, 1157, 963, -1, + 963, 1157, 1045, -1,963, 1045, 817, -1,817, 1045, 895, -1,817, 895, 766, -1,1280, + 1347, 1251, -1,1251, 1347, 1324, -1,1251, 1324, 1179, -1,1179, 1324, 1289, -1,1179, + 1289, 1252, -1,609, 473, 523, -1,523, 473, 359, -1,523, 359, 424, -1,424, 359, 278, -1, + 424, 278, 326, -1,326, 278, 233, -1,326, 233, 206, -1,280, 217, 347, -1,347, 217, + 257, -1,347, 257, 446, -1,446, 257, 311, -1,446, 311, 565, -1,136, 141, 237, -1,237, + 141, 156, -1,237, 156, 255, -1,255, 156, 170, -1,255, 170, 280, -1,280, 170, 194, -1, + 280, 194, 217, -1,1256, 1360, 1286, -1,1286, 1360, 1374, -1,1286, 1374, 1295, -1, + 1295, 1374, 1387, -1,1295, 1387, 1300, -1,1105, 1282, 1198, -1,1198, 1282, 1314, -1, + 1198, 1314, 1256, -1,1256, 1314, 1342, -1,1256, 1342, 1360, -1,843, 997, 1000, -1, + 1000, 997, 1113, -1,1000, 1113, 1105, -1,1105, 1113, 1229, -1,1105, 1229, 1282, -1, + 311, 431, 565, -1,565, 431, 550, -1,565, 550, 719, -1,719, 550, 713, -1,719, 713, + 843, -1,843, 713, 835, -1,843, 835, 997, -1,1387, 1392, 1300, -1,1300, 1392, 1390, -1, + 1300, 1390, 1291, -1,1291, 1390, 1384, -1,1291, 1384, 1280, -1,1280, 1384, 1365, -1, + 1280, 1365, 1347, -1,6, 12, 15, -1,251, 292, 297, -1,1013, 1082, 1077, -1,1496, 1503, + 1500, -1,1446, 1427, 1421, -1,1221, 1149, 1144, -1,166, 142, 147, -1,103, 98, 105, -1, + 54, 36, 41, -1,141, 136, 101, -1,101, 136, 106, -1,101, 106, 73, -1,73, 106, 79, -1, + 73, 79, 53, -1,53, 79, 74, -1,53, 74, 52, -1,52, 74, 78, -1,52, 78, 69, -1,69, 78, + 105, -1,146, 161, 128, -1,128, 161, 150, -1,128, 150, 123, -1,123, 150, 154, -1,123, + 154, 132, -1,132, 154, 169, -1,132, 169, 158, -1,158, 169, 204, -1,158, 204, 196, -1, + 196, 204, 253, -1,161, 182, 150, -1,150, 182, 181, -1,150, 181, 154, -1,154, 181, + 187, -1,154, 187, 169, -1,169, 187, 213, -1,169, 213, 204, -1,204, 213, 261, -1,204, + 261, 253, -1,253, 261, 367, -1,253, 367, 360, -1,360, 367, 406, -1,206, 233, 209, -1, + 209, 233, 249, -1,209, 249, 225, -1,225, 249, 285, -1,225, 285, 270, -1,270, 285, + 395, -1,270, 395, 375, -1,375, 395, 540, -1,375, 540, 530, -1,530, 540, 752, -1,233, + 278, 249, -1,249, 278, 309, -1,249, 309, 285, -1,285, 309, 421, -1,285, 421, 395, -1, + 395, 421, 555, -1,395, 555, 540, -1,540, 555, 754, -1,540, 754, 752, -1,752, 754, + 966, -1,752, 966, 971, -1,971, 966, 974, -1,473, 609, 590, -1,590, 609, 763, -1,590, + 763, 759, -1,759, 763, 938, -1,759, 938, 949, -1,949, 938, 1118, -1,949, 1118, 1131, -1, + 1131, 1118, 1267, -1,1131, 1267, 1272, -1,1272, 1267, 1330, -1,609, 766, 763, -1, + 763, 766, 920, -1,763, 920, 938, -1,938, 920, 1091, -1,938, 1091, 1118, -1,1118, + 1091, 1253, -1,1118, 1253, 1267, -1,1267, 1253, 1323, -1,1267, 1323, 1330, -1,1330, + 1323, 1375, -1,1330, 1375, 1381, -1,1381, 1375, 1388, -1,1045, 1157, 1193, -1,1193, + 1157, 1278, -1,1193, 1278, 1294, -1,1294, 1278, 1338, -1,1294, 1338, 1354, -1,1354, + 1338, 1394, -1,1354, 1394, 1413, -1,1413, 1394, 1448, -1,1413, 1448, 1461, -1,1461, + 1448, 1484, -1,1157, 1252, 1278, -1,1278, 1252, 1317, -1,1278, 1317, 1338, -1,1338, + 1317, 1371, -1,1338, 1371, 1394, -1,1394, 1371, 1432, -1,1394, 1432, 1448, -1,1448, + 1432, 1475, -1,1448, 1475, 1484, -1,1484, 1475, 1507, -1,1484, 1507, 1512, -1,1512, + 1507, 1515, -1,1289, 1324, 1349, -1,1349, 1324, 1373, -1,1349, 1373, 1404, -1,1404, + 1373, 1433, -1,1404, 1433, 1459, -1,1459, 1433, 1474, -1,1459, 1474, 1498, -1,1498, + 1474, 1506, -1,1498, 1506, 1520, -1,1520, 1506, 1524, -1,1324, 1347, 1373, -1,1373, + 1347, 1402, -1,1373, 1402, 1433, -1,1433, 1402, 1449, -1,1433, 1449, 1474, -1,1474, + 1449, 1483, -1,1474, 1483, 1506, -1,1506, 1483, 1509, -1,1506, 1509, 1524, -1,1524, + 1509, 1514, -1,1524, 1514, 1522, -1,1522, 1514, 1518, -1,1384, 1390, 1426, -1,1426, + 1390, 1429, -1,1426, 1429, 1463, -1,1463, 1429, 1458, -1,1463, 1458, 1482, -1,1482, + 1458, 1472, -1,1482, 1472, 1488, -1,1488, 1472, 1469, -1,1488, 1469, 1476, -1,1476, + 1469, 1443, -1,1390, 1392, 1429, -1,1429, 1392, 1424, -1,1429, 1424, 1458, -1,1458, + 1424, 1442, -1,1458, 1442, 1472, -1,1472, 1442, 1445, -1,1472, 1445, 1469, -1,1469, + 1445, 1439, -1,1469, 1439, 1443, -1,1443, 1439, 1406, -1,1443, 1406, 1409, -1,1409, + 1406, 1396, -1,1387, 1374, 1411, -1,1411, 1374, 1391, -1,1411, 1391, 1418, -1,1418, + 1391, 1393, -1,1418, 1393, 1417, -1,1417, 1393, 1380, -1,1417, 1380, 1395, -1,1395, + 1380, 1350, -1,1395, 1350, 1357, -1,1357, 1350, 1307, -1,1374, 1360, 1391, -1,1391, + 1360, 1364, -1,1391, 1364, 1393, -1,1393, 1364, 1358, -1,1393, 1358, 1380, -1,1380, + 1358, 1341, -1,1380, 1341, 1350, -1,1350, 1341, 1304, -1,1350, 1304, 1307, -1,1307, + 1304, 1244, -1,1307, 1244, 1247, -1,1247, 1244, 1241, -1,1314, 1282, 1302, -1,1302, + 1282, 1254, -1,1302, 1254, 1279, -1,1279, 1254, 1182, -1,1279, 1182, 1219, -1,1219, + 1182, 1056, -1,1219, 1056, 1069, -1,1069, 1056, 868, -1,1069, 868, 873, -1,873, 868, + 661, -1,1282, 1229, 1254, -1,1254, 1229, 1152, -1,1254, 1152, 1182, -1,1182, 1152, + 1043, -1,1182, 1043, 1056, -1,1056, 1043, 863, -1,1056, 863, 868, -1,868, 863, 672, -1, + 868, 672, 661, -1,661, 672, 470, -1,661, 470, 463, -1,463, 470, 434, -1,997, 835, + 848, -1,848, 835, 704, -1,848, 704, 691, -1,691, 704, 499, -1,691, 499, 489, -1,489, + 499, 334, -1,489, 334, 306, -1,306, 334, 234, -1,306, 234, 222, -1,222, 234, 179, -1, + 835, 713, 704, -1,704, 713, 518, -1,704, 518, 499, -1,499, 518, 363, -1,499, 363, + 334, -1,334, 363, 243, -1,334, 243, 234, -1,234, 243, 186, -1,234, 186, 179, -1,179, + 186, 131, -1,179, 131, 125, -1,125, 131, 112, -1,550, 431, 398, -1,398, 431, 283, -1, + 398, 283, 262, -1,262, 283, 212, -1,262, 212, 199, -1,199, 212, 157, -1,199, 157, + 138, -1,138, 157, 97, -1,138, 97, 86, -1,86, 97, 57, -1,431, 311, 283, -1,283, 311, + 232, -1,283, 232, 212, -1,212, 232, 175, -1,212, 175, 157, -1,157, 175, 121, -1,157, + 121, 97, -1,97, 121, 70, -1,97, 70, 57, -1,57, 70, 34, -1,57, 34, 29, -1,29, 34, + 26, -1,217, 194, 164, -1,164, 194, 140, -1,164, 140, 115, -1,115, 140, 87, -1,115, + 87, 64, -1,64, 87, 48, -1,64, 48, 31, -1,31, 48, 22, -1,31, 22, 9, -1,9, 22, 11, -1, + 194, 170, 140, -1,140, 170, 122, -1,140, 122, 87, -1,87, 122, 76, -1,87, 76, 48, -1, + 48, 76, 43, -1,48, 43, 22, -1,22, 43, 25, -1,22, 25, 11, -1,11, 25, 21, -1,11, 21, + 16, -1,16, 21, 23, -1,156, 141, 110, -1,110, 141, 101, -1,110, 101, 72, -1,72, 101, + 73, -1,72, 73, 46, -1,46, 73, 53, -1,46, 53, 35, -1,35, 53, 52, -1,35, 52, 41, -1, + 41, 52, 69, -1,41, 69, 54, -1,105, 98, 69, -1,69, 98, 62, -1,69, 62, 54, -1,142, + 103, 147, -1,147, 103, 105, -1,147, 105, 118, -1,118, 105, 78, -1,118, 78, 93, -1, + 93, 78, 74, -1,93, 74, 94, -1,94, 74, 79, -1,94, 79, 116, -1,116, 79, 106, -1,116, + 106, 137, -1,137, 106, 136, -1,137, 146, 116, -1,116, 146, 128, -1,116, 128, 94, -1, + 94, 128, 123, -1,94, 123, 93, -1,93, 123, 132, -1,93, 132, 118, -1,118, 132, 158, -1, + 118, 158, 147, -1,147, 158, 196, -1,147, 196, 166, -1,360, 246, 253, -1,253, 246, + 240, -1,253, 240, 196, -1,196, 240, 189, -1,196, 189, 166, -1,182, 206, 181, -1,181, + 206, 209, -1,181, 209, 187, -1,187, 209, 225, -1,187, 225, 213, -1,213, 225, 270, -1, + 213, 270, 261, -1,261, 270, 375, -1,261, 375, 367, -1,367, 375, 530, -1,367, 530, + 406, -1,971, 749, 752, -1,752, 749, 666, -1,752, 666, 530, -1,530, 666, 526, -1,530, + 526, 406, -1,1149, 974, 1144, -1,1144, 974, 966, -1,1144, 966, 959, -1,959, 966, + 754, -1,959, 754, 757, -1,757, 754, 555, -1,757, 555, 570, -1,570, 555, 421, -1,570, + 421, 441, -1,441, 421, 309, -1,441, 309, 359, -1,359, 309, 278, -1,359, 473, 441, -1, + 441, 473, 590, -1,441, 590, 570, -1,570, 590, 759, -1,570, 759, 757, -1,757, 759, + 949, -1,757, 949, 959, -1,959, 949, 1131, -1,959, 1131, 1144, -1,1144, 1131, 1272, -1, + 1144, 1272, 1221, -1,1381, 1334, 1330, -1,1330, 1334, 1320, -1,1330, 1320, 1272, -1, + 1272, 1320, 1276, -1,1272, 1276, 1221, -1,1427, 1388, 1421, -1,1421, 1388, 1375, -1, + 1421, 1375, 1366, -1,1366, 1375, 1323, -1,1366, 1323, 1311, -1,1311, 1323, 1253, -1, + 1311, 1253, 1235, -1,1235, 1253, 1091, -1,1235, 1091, 1065, -1,1065, 1091, 920, -1, + 1065, 920, 895, -1,895, 920, 766, -1,895, 1045, 1065, -1,1065, 1045, 1193, -1,1065, + 1193, 1235, -1,1235, 1193, 1294, -1,1235, 1294, 1311, -1,1311, 1294, 1354, -1,1311, + 1354, 1366, -1,1366, 1354, 1413, -1,1366, 1413, 1421, -1,1421, 1413, 1461, -1,1421, + 1461, 1446, -1,1512, 1493, 1484, -1,1484, 1493, 1489, -1,1484, 1489, 1461, -1,1461, + 1489, 1466, -1,1461, 1466, 1446, -1,1252, 1289, 1317, -1,1317, 1289, 1349, -1,1317, + 1349, 1371, -1,1371, 1349, 1404, -1,1371, 1404, 1432, -1,1432, 1404, 1459, -1,1432, + 1459, 1475, -1,1475, 1459, 1498, -1,1475, 1498, 1507, -1,1507, 1498, 1520, -1,1507, + 1520, 1515, -1,1522, 1530, 1524, -1,1524, 1530, 1528, -1,1524, 1528, 1520, -1,1520, + 1528, 1526, -1,1520, 1526, 1515, -1,1503, 1518, 1500, -1,1500, 1518, 1514, -1,1500, + 1514, 1502, -1,1502, 1514, 1509, -1,1502, 1509, 1486, -1,1486, 1509, 1483, -1,1486, + 1483, 1460, -1,1460, 1483, 1449, -1,1460, 1449, 1415, -1,1415, 1449, 1402, -1,1415, + 1402, 1365, -1,1365, 1402, 1347, -1,1365, 1384, 1415, -1,1415, 1384, 1426, -1,1415, + 1426, 1460, -1,1460, 1426, 1463, -1,1460, 1463, 1486, -1,1486, 1463, 1482, -1,1486, + 1482, 1502, -1,1502, 1482, 1488, -1,1502, 1488, 1500, -1,1500, 1488, 1476, -1,1500, + 1476, 1496, -1,1409, 1451, 1443, -1,1443, 1451, 1455, -1,1443, 1455, 1476, -1,1476, + 1455, 1480, -1,1476, 1480, 1496, -1,1392, 1387, 1424, -1,1424, 1387, 1411, -1,1424, + 1411, 1442, -1,1442, 1411, 1418, -1,1442, 1418, 1445, -1,1445, 1418, 1417, -1,1445, + 1417, 1439, -1,1439, 1417, 1395, -1,1439, 1395, 1406, -1,1406, 1395, 1357, -1,1406, + 1357, 1396, -1,1247, 1312, 1307, -1,1307, 1312, 1328, -1,1307, 1328, 1357, -1,1357, + 1328, 1361, -1,1357, 1361, 1396, -1,1082, 1241, 1077, -1,1077, 1241, 1244, -1,1077, + 1244, 1233, -1,1233, 1244, 1304, -1,1233, 1304, 1288, -1,1288, 1304, 1341, -1,1288, + 1341, 1322, -1,1322, 1341, 1358, -1,1322, 1358, 1339, -1,1339, 1358, 1364, -1,1339, + 1364, 1342, -1,1342, 1364, 1360, -1,1342, 1314, 1339, -1,1339, 1314, 1302, -1,1339, + 1302, 1322, -1,1322, 1302, 1279, -1,1322, 1279, 1288, -1,1288, 1279, 1219, -1,1288, + 1219, 1233, -1,1233, 1219, 1069, -1,1233, 1069, 1077, -1,1077, 1069, 873, -1,1077, + 873, 1013, -1,463, 658, 661, -1,661, 658, 717, -1,661, 717, 873, -1,873, 717, 876, -1, + 873, 876, 1013, -1,292, 434, 297, -1,297, 434, 470, -1,297, 470, 479, -1,479, 470, + 672, -1,479, 672, 681, -1,681, 672, 863, -1,681, 863, 857, -1,857, 863, 1043, -1, + 857, 1043, 1023, -1,1023, 1043, 1152, -1,1023, 1152, 1113, -1,1113, 1152, 1229, -1, + 1113, 997, 1023, -1,1023, 997, 848, -1,1023, 848, 857, -1,857, 848, 691, -1,857, + 691, 681, -1,681, 691, 489, -1,681, 489, 479, -1,479, 489, 306, -1,479, 306, 297, -1, + 297, 306, 222, -1,297, 222, 251, -1,125, 173, 179, -1,179, 173, 176, -1,179, 176, + 222, -1,222, 176, 218, -1,222, 218, 251, -1,713, 550, 518, -1,518, 550, 398, -1,518, + 398, 363, -1,363, 398, 262, -1,363, 262, 243, -1,243, 262, 199, -1,243, 199, 186, -1, + 186, 199, 138, -1,186, 138, 131, -1,131, 138, 86, -1,131, 86, 112, -1,29, 50, 57, -1, + 57, 50, 59, -1,57, 59, 86, -1,86, 59, 82, -1,86, 82, 112, -1,12, 26, 15, -1,15, 26, + 34, -1,15, 34, 45, -1,45, 34, 70, -1,45, 70, 84, -1,84, 70, 121, -1,84, 121, 139, -1, + 139, 121, 175, -1,139, 175, 200, -1,200, 175, 232, -1,200, 232, 257, -1,257, 232, + 311, -1,257, 217, 200, -1,200, 217, 164, -1,200, 164, 139, -1,139, 164, 115, -1,139, + 115, 84, -1,84, 115, 64, -1,84, 64, 45, -1,45, 64, 31, -1,45, 31, 15, -1,15, 31, + 9, -1,15, 9, 6, -1,16, 4, 11, -1,11, 4, 2, -1,11, 2, 9, -1,9, 2, 0, -1,9, 0, 6, -1, + 36, 23, 41, -1,41, 23, 21, -1,41, 21, 35, -1,35, 21, 25, -1,35, 25, 46, -1,46, 25, + 43, -1,46, 43, 72, -1,72, 43, 76, -1,72, 76, 110, -1,110, 76, 122, -1,110, 122, 156, -1, + 156, 122, 170, -1,111, 119, 81, -1,129, 134, 107, -1,159, 163, 133, -1,288, 386, + 354, -1,433, 510, 497, -1,599, 703, 690, -1,791, 852, 858, -1,980, 1029, 1047, -1, + 1132, 1156, 1188, -1,1348, 1369, 1401, -1,1383, 1398, 1430, -1,1425, 1431, 1465, -1, + 1436, 1438, 1470, -1,1403, 1385, 1412, -1,1372, 1352, 1378, -1,1343, 1319, 1345, -1, + 1298, 1283, 1299, -1,1239, 1207, 1240, -1,1094, 1073, 1098, -1,548, 439, 415, -1, + 397, 300, 281, -1,277, 244, 220, -1,216, 207, 185, -1,85, 56, 66, -1,24, 37, 40, -1, + 3, 5, 10, -1,174, 126, 130, -1,252, 219, 221, -1,435, 293, 296, -1,659, 464, 469, -1, + 1014, 877, 874, -1,1242, 1083, 1079, -1,1313, 1248, 1245, -1,1397, 1362, 1359, -1, + 1452, 1410, 1407, -1,1497, 1481, 1478, -1,1519, 1504, 1501, -1,1531, 1523, 1517, -1, + 1516, 1527, 1521, -1,1494, 1513, 1508, -1,1447, 1467, 1462, -1,1389, 1428, 1423, -1, + 1335, 1382, 1376, -1,1222, 1277, 1273, -1,975, 1150, 1145, -1,750, 972, 968, -1,407, + 527, 529, -1,247, 361, 364, -1,167, 190, 195, -1,104, 143, 145, -1,63, 99, 102, -1, + 51, 56, 60, -1,60, 56, 85, -1,60, 85, 83, -1,83, 85, 113, -1,33, 30, 27, -1,14, 13, + 7, -1,7, 1, 8, -1,8, 1, 3, -1,5, 17, 19, -1,19, 17, 24, -1,58, 66, 42, -1,42, 66, + 56, -1,42, 56, 33, -1,33, 56, 51, -1,33, 51, 30, -1,89, 67, 49, -1,71, 58, 44, -1, + 44, 58, 42, -1,44, 42, 28, -1,28, 42, 33, -1,28, 33, 14, -1,14, 33, 27, -1,14, 27, + 13, -1,88, 67, 120, -1,120, 67, 89, -1,120, 89, 148, -1,190, 241, 195, -1,195, 241, + 250, -1,195, 250, 256, -1,256, 250, 373, -1,256, 373, 388, -1,388, 373, 552, -1,388, + 552, 568, -1,568, 552, 758, -1,241, 247, 250, -1,250, 247, 364, -1,250, 364, 373, -1, + 373, 364, 536, -1,373, 536, 552, -1,552, 536, 756, -1,552, 756, 758, -1,758, 756, + 942, -1,758, 942, 922, -1,922, 942, 934, -1,1382, 1389, 1376, -1,1376, 1389, 1423, -1, + 1376, 1423, 1414, -1,1414, 1423, 1453, -1,1414, 1453, 1437, -1,1437, 1453, 1464, -1, + 1437, 1464, 1440, -1,1440, 1464, 1457, -1,1428, 1447, 1423, -1,1423, 1447, 1462, -1, + 1423, 1462, 1453, -1,1453, 1462, 1477, -1,1453, 1477, 1464, -1,1464, 1477, 1479, -1, + 1464, 1479, 1457, -1,1457, 1479, 1468, -1,1457, 1468, 1434, -1,1434, 1468, 1435, -1, + 1527, 1529, 1521, -1,1521, 1529, 1525, -1,1521, 1525, 1511, -1,1511, 1525, 1505, -1, + 1511, 1505, 1485, -1,1485, 1505, 1473, -1,1485, 1473, 1450, -1,1450, 1473, 1430, -1, + 1504, 1497, 1501, -1,1501, 1497, 1478, -1,1501, 1478, 1471, -1,1471, 1478, 1441, -1, + 1471, 1441, 1419, -1,1419, 1441, 1386, -1,1419, 1386, 1363, -1,1363, 1386, 1326, -1, + 1481, 1456, 1478, -1,1478, 1456, 1444, -1,1478, 1444, 1441, -1,1441, 1444, 1399, -1, + 1441, 1399, 1386, -1,1386, 1399, 1346, -1,1386, 1346, 1326, -1,1326, 1346, 1284, -1, + 1326, 1284, 1261, -1,1261, 1284, 1258, -1,718, 659, 660, -1,660, 659, 469, -1,660, + 469, 475, -1,475, 469, 302, -1,475, 302, 329, -1,329, 302, 242, -1,329, 242, 260, -1, + 260, 242, 208, -1,464, 435, 469, -1,469, 435, 296, -1,469, 296, 302, -1,302, 296, + 231, -1,302, 231, 242, -1,242, 231, 193, -1,242, 193, 208, -1,208, 193, 168, -1,208, + 168, 191, -1,191, 168, 188, -1,124, 88, 144, -1,144, 88, 120, -1,144, 120, 149, -1, + 149, 120, 148, -1,149, 148, 172, -1,172, 148, 183, -1,207, 183, 185, -1,185, 183, + 148, -1,185, 148, 127, -1,127, 148, 89, -1,127, 89, 77, -1,77, 89, 49, -1,77, 49, + 40, -1,244, 216, 220, -1,220, 216, 185, -1,220, 185, 165, -1,165, 185, 127, -1,165, + 127, 114, -1,114, 127, 77, -1,114, 77, 68, -1,68, 77, 40, -1,68, 40, 55, -1,55, 40, + 37, -1,300, 277, 281, -1,281, 277, 220, -1,281, 220, 210, -1,210, 220, 165, -1,210, + 165, 155, -1,155, 165, 114, -1,155, 114, 102, -1,102, 114, 68, -1,102, 68, 63, -1, + 63, 68, 55, -1,439, 397, 415, -1,415, 397, 281, -1,415, 281, 266, -1,266, 281, 210, -1, + 266, 210, 202, -1,202, 210, 155, -1,202, 155, 145, -1,145, 155, 102, -1,145, 102, + 104, -1,104, 102, 99, -1,143, 167, 145, -1,145, 167, 195, -1,145, 195, 202, -1,202, + 195, 256, -1,202, 256, 266, -1,266, 256, 388, -1,266, 388, 415, -1,415, 388, 568, -1, + 415, 568, 548, -1,922, 761, 758, -1,758, 761, 737, -1,758, 737, 568, -1,568, 737, + 586, -1,568, 586, 548, -1,1073, 934, 1098, -1,1098, 934, 942, -1,1098, 942, 954, -1, + 954, 942, 756, -1,954, 756, 753, -1,753, 756, 536, -1,753, 536, 529, -1,529, 536, + 364, -1,529, 364, 407, -1,407, 364, 361, -1,1207, 1094, 1240, -1,1240, 1094, 1098, -1, + 1240, 1098, 1121, -1,1121, 1098, 954, -1,1121, 954, 960, -1,960, 954, 753, -1,960, + 753, 751, -1,751, 753, 529, -1,751, 529, 667, -1,667, 529, 527, -1,1283, 1239, 1299, -1, + 1299, 1239, 1240, -1,1299, 1240, 1255, -1,1255, 1240, 1121, -1,1255, 1121, 1134, -1, + 1134, 1121, 960, -1,1134, 960, 968, -1,968, 960, 751, -1,968, 751, 750, -1,750, 751, + 667, -1,1319, 1298, 1345, -1,1345, 1298, 1299, -1,1345, 1299, 1315, -1,1315, 1299, + 1255, -1,1315, 1255, 1271, -1,1271, 1255, 1134, -1,1271, 1134, 1145, -1,1145, 1134, + 968, -1,1145, 968, 975, -1,975, 968, 972, -1,1352, 1343, 1378, -1,1378, 1343, 1345, -1, + 1378, 1345, 1356, -1,1356, 1345, 1315, -1,1356, 1315, 1325, -1,1325, 1315, 1271, -1, + 1325, 1271, 1273, -1,1273, 1271, 1145, -1,1273, 1145, 1222, -1,1222, 1145, 1150, -1, + 1385, 1372, 1412, -1,1412, 1372, 1378, -1,1412, 1378, 1400, -1,1400, 1378, 1356, -1, + 1400, 1356, 1368, -1,1368, 1356, 1325, -1,1368, 1325, 1332, -1,1332, 1325, 1273, -1, + 1332, 1273, 1321, -1,1321, 1273, 1277, -1,1321, 1335, 1332, -1,1332, 1335, 1376, -1, + 1332, 1376, 1368, -1,1368, 1376, 1414, -1,1368, 1414, 1400, -1,1400, 1414, 1437, -1, + 1400, 1437, 1412, -1,1412, 1437, 1440, -1,1412, 1440, 1403, -1,1434, 1422, 1457, -1, + 1457, 1422, 1420, -1,1457, 1420, 1440, -1,1440, 1420, 1405, -1,1440, 1405, 1403, -1, + 1438, 1435, 1470, -1,1470, 1435, 1468, -1,1470, 1468, 1491, -1,1491, 1468, 1479, -1, + 1491, 1479, 1499, -1,1499, 1479, 1477, -1,1499, 1477, 1487, -1,1487, 1477, 1462, -1, + 1487, 1462, 1490, -1,1490, 1462, 1467, -1,1431, 1436, 1465, -1,1465, 1436, 1470, -1, + 1465, 1470, 1495, -1,1495, 1470, 1491, -1,1495, 1491, 1510, -1,1510, 1491, 1499, -1, + 1510, 1499, 1508, -1,1508, 1499, 1487, -1,1508, 1487, 1494, -1,1494, 1487, 1490, -1, + 1416, 1425, 1450, -1,1450, 1425, 1465, -1,1450, 1465, 1485, -1,1485, 1465, 1495, -1, + 1485, 1495, 1511, -1,1511, 1495, 1510, -1,1511, 1510, 1521, -1,1521, 1510, 1508, -1, + 1521, 1508, 1516, -1,1516, 1508, 1513, -1,1430, 1398, 1450, -1,1450, 1398, 1408, -1, + 1450, 1408, 1416, -1,1369, 1383, 1401, -1,1401, 1383, 1430, -1,1401, 1430, 1454, -1, + 1454, 1430, 1473, -1,1454, 1473, 1492, -1,1492, 1473, 1505, -1,1492, 1505, 1517, -1, + 1517, 1505, 1525, -1,1517, 1525, 1531, -1,1531, 1525, 1529, -1,1523, 1519, 1517, -1, + 1517, 1519, 1501, -1,1517, 1501, 1492, -1,1492, 1501, 1471, -1,1492, 1471, 1454, -1, + 1454, 1471, 1419, -1,1454, 1419, 1401, -1,1401, 1419, 1363, -1,1401, 1363, 1348, -1, + 1261, 1306, 1326, -1,1326, 1306, 1309, -1,1326, 1309, 1363, -1,1363, 1309, 1344, -1, + 1363, 1344, 1348, -1,1156, 1258, 1188, -1,1188, 1258, 1284, -1,1188, 1284, 1293, -1, + 1293, 1284, 1346, -1,1293, 1346, 1351, -1,1351, 1346, 1399, -1,1351, 1399, 1407, -1, + 1407, 1399, 1444, -1,1407, 1444, 1452, -1,1452, 1444, 1456, -1,1029, 1132, 1047, -1, + 1047, 1132, 1188, -1,1047, 1188, 1224, -1,1224, 1188, 1293, -1,1224, 1293, 1305, -1, + 1305, 1293, 1351, -1,1305, 1351, 1359, -1,1359, 1351, 1407, -1,1359, 1407, 1397, -1, + 1397, 1407, 1410, -1,852, 980, 858, -1,858, 980, 1047, -1,858, 1047, 1060, -1,1060, + 1047, 1224, -1,1060, 1224, 1236, -1,1236, 1224, 1305, -1,1236, 1305, 1308, -1,1308, + 1305, 1359, -1,1308, 1359, 1329, -1,1329, 1359, 1362, -1,703, 791, 690, -1,690, 791, + 858, -1,690, 858, 864, -1,864, 858, 1060, -1,864, 1060, 1071, -1,1071, 1060, 1236, -1, + 1071, 1236, 1245, -1,1245, 1236, 1308, -1,1245, 1308, 1313, -1,1313, 1308, 1329, -1, + 510, 599, 497, -1,497, 599, 690, -1,497, 690, 680, -1,680, 690, 864, -1,680, 864, + 869, -1,869, 864, 1071, -1,869, 1071, 1079, -1,1079, 1071, 1245, -1,1079, 1245, 1242, -1, + 1242, 1245, 1248, -1,386, 433, 354, -1,354, 433, 497, -1,354, 497, 485, -1,485, 497, + 680, -1,485, 680, 671, -1,671, 680, 869, -1,671, 869, 874, -1,874, 869, 1079, -1, + 874, 1079, 1014, -1,1014, 1079, 1083, -1,877, 718, 874, -1,874, 718, 660, -1,874, + 660, 671, -1,671, 660, 475, -1,671, 475, 485, -1,485, 475, 329, -1,485, 329, 354, -1, + 354, 329, 260, -1,354, 260, 288, -1,191, 224, 208, -1,208, 224, 228, -1,208, 228, + 260, -1,260, 228, 279, -1,260, 279, 288, -1,163, 188, 133, -1,133, 188, 168, -1,133, + 168, 151, -1,151, 168, 193, -1,151, 193, 184, -1,184, 193, 231, -1,184, 231, 221, -1, + 221, 231, 296, -1,221, 296, 252, -1,252, 296, 293, -1,134, 159, 107, -1,107, 159, + 133, -1,107, 133, 117, -1,117, 133, 151, -1,117, 151, 135, -1,135, 151, 184, -1,135, + 184, 178, -1,178, 184, 221, -1,178, 221, 177, -1,177, 221, 219, -1,119, 129, 81, -1, + 81, 129, 107, -1,81, 107, 80, -1,80, 107, 117, -1,80, 117, 91, -1,91, 117, 135, -1, + 91, 135, 130, -1,130, 135, 178, -1,130, 178, 174, -1,174, 178, 177, -1,100, 111, + 71, -1,71, 111, 81, -1,71, 81, 58, -1,58, 81, 80, -1,58, 80, 66, -1,66, 80, 91, -1, + 66, 91, 85, -1,85, 91, 130, -1,85, 130, 113, -1,113, 130, 126, -1,61, 90, 96, -1, + 7, 8, 14, -1,14, 8, 18, -1,14, 18, 28, -1,28, 18, 38, -1,28, 38, 44, -1,44, 38, 61, -1, + 44, 61, 71, -1,71, 61, 96, -1,71, 96, 100, -1,65, 95, 92, -1,3, 10, 8, -1,8, 10, + 20, -1,8, 20, 18, -1,18, 20, 39, -1,18, 39, 38, -1,38, 39, 65, -1,38, 65, 61, -1, + 61, 65, 92, -1,61, 92, 90, -1,75, 109, 108, -1,5, 19, 10, -1,10, 19, 32, -1,10, 32, + 20, -1,20, 32, 47, -1,20, 47, 39, -1,39, 47, 75, -1,39, 75, 65, -1,65, 75, 108, -1, + 65, 108, 95, -1,24, 40, 19, -1,19, 40, 49, -1,19, 49, 32, -1,32, 49, 67, -1,32, 67, + 47, -1,47, 67, 88, -1,47, 88, 75, -1,75, 88, 124, -1,75, 124, 109, -1,374, 396, 341, -1, + 374, 394, 396, -1,396, 394, 419, -1,396, 419, 461, -1,594, 669, 557, -1,557, 669, + 684, -1,419, 460, 461, -1,461, 460, 509, -1,461, 509, 557, -1,557, 509, 556, -1,557, + 556, 594, -1,826, 917, 810, -1,810, 917, 927, -1,669, 683, 684, -1,684, 683, 762, -1, + 684, 762, 810, -1,810, 762, 811, -1,810, 811, 826, -1,1052, 1103, 1037, -1,1037, + 1103, 1109, -1,917, 928, 927, -1,927, 928, 995, -1,927, 995, 1037, -1,1037, 995, + 1038, -1,1037, 1038, 1052, -1,1180, 1202, 1168, -1,1168, 1202, 1208, -1,1103, 1110, + 1109, -1,1109, 1110, 1143, -1,1109, 1143, 1168, -1,1168, 1143, 1169, -1,1168, 1169, + 1180, -1,1223, 1209, 1225, -1,1225, 1209, 1203, -1,1202, 1212, 1208, -1,1208, 1212, + 1220, -1,1208, 1220, 1225, -1,1225, 1220, 1227, -1,1225, 1227, 1223, -1,1163, 1161, + 1183, -1,1183, 1161, 1203, -1,1183, 1203, 1206, -1,1206, 1203, 1209, -1,1163, 1155, + 1161, -1,1161, 1155, 1114, -1,1161, 1114, 1100, -1,1028, 1026, 1061, -1,1061, 1026, + 1100, -1,1061, 1100, 1102, -1,1102, 1100, 1114, -1,1028, 1015, 1026, -1,1026, 1015, + 937, -1,1026, 937, 908, -1,790, 788, 845, -1,845, 788, 908, -1,845, 908, 911, -1, + 911, 908, 937, -1,790, 769, 788, -1,788, 769, 705, -1,788, 705, 651, -1,537, 538, + 614, -1,614, 538, 651, -1,614, 651, 650, -1,650, 651, 705, -1,537, 528, 538, -1,538, + 528, 478, -1,538, 478, 451, -1,379, 382, 428, -1,428, 382, 451, -1,428, 451, 450, -1, + 450, 451, 478, -1,379, 378, 382, -1,382, 378, 348, -1,382, 348, 338, -1,348, 335, + 338, -1,338, 335, 323, -1,338, 323, 304, -1,323, 303, 304, -1,304, 303, 305, -1,304, + 305, 308, -1,305, 307, 308, -1,308, 307, 320, -1,308, 320, 341, -1,341, 320, 339, -1, + 341, 339, 374, -1,308, 317, 304, -1,304, 317, 314, -1,304, 314, 338, -1,338, 314, + 342, -1,338, 342, 382, -1,382, 342, 392, -1,382, 392, 451, -1,451, 392, 453, -1,451, + 453, 538, -1,538, 453, 544, -1,538, 544, 651, -1,651, 544, 655, -1,651, 655, 788, -1, + 788, 655, 786, -1,788, 786, 908, -1,908, 786, 906, -1,908, 906, 1026, -1,1026, 906, + 1022, -1,1026, 1022, 1100, -1,1100, 1022, 1093, -1,1100, 1093, 1161, -1,1161, 1093, + 1159, -1,1161, 1159, 1203, -1,1203, 1159, 1192, -1,1203, 1192, 1225, -1,1225, 1192, + 1217, -1,1225, 1217, 1208, -1,1208, 1217, 1197, -1,1208, 1197, 1168, -1,1168, 1197, + 1162, -1,1168, 1162, 1109, -1,1109, 1162, 1106, -1,1109, 1106, 1037, -1,1037, 1106, + 1033, -1,1037, 1033, 927, -1,927, 1033, 925, -1,927, 925, 810, -1,810, 925, 809, -1, + 810, 809, 684, -1,684, 809, 685, -1,684, 685, 557, -1,557, 685, 562, -1,557, 562, + 461, -1,461, 562, 468, -1,461, 468, 396, -1,396, 468, 402, -1,396, 402, 341, -1,341, + 402, 345, -1,341, 345, 308, -1,308, 345, 317, -1,317, 332, 314, -1,314, 332, 331, -1, + 314, 331, 342, -1,342, 331, 350, -1,342, 350, 392, -1,392, 350, 403, -1,392, 403, + 453, -1,453, 403, 462, -1,453, 462, 544, -1,544, 462, 553, -1,544, 553, 655, -1,655, + 553, 657, -1,655, 657, 786, -1,786, 657, 785, -1,786, 785, 906, -1,906, 785, 896, -1, + 906, 896, 1022, -1,1022, 896, 1017, -1,1022, 1017, 1093, -1,1093, 1017, 1089, -1, + 1093, 1089, 1159, -1,1159, 1089, 1151, -1,1159, 1151, 1192, -1,1192, 1151, 1185, -1, + 1192, 1185, 1217, -1,1217, 1185, 1199, -1,1217, 1199, 1197, -1,1197, 1199, 1187, -1, + 1197, 1187, 1162, -1,1162, 1187, 1154, -1,1162, 1154, 1106, -1,1106, 1154, 1095, -1, + 1106, 1095, 1033, -1,1033, 1095, 1030, -1,1033, 1030, 925, -1,925, 1030, 918, -1, + 925, 918, 809, -1,809, 918, 807, -1,809, 807, 685, -1,685, 807, 689, -1,685, 689, + 562, -1,562, 689, 569, -1,562, 569, 468, -1,468, 569, 474, -1,468, 474, 402, -1,402, + 474, 411, -1,402, 411, 345, -1,345, 411, 358, -1,345, 358, 317, -1,317, 358, 332, -1, + 332, 344, 331, -1,331, 344, 343, -1,331, 343, 350, -1,350, 343, 370, -1,350, 370, + 403, -1,403, 370, 416, -1,403, 416, 462, -1,462, 416, 476, -1,462, 476, 553, -1,553, + 476, 561, -1,553, 561, 657, -1,657, 561, 664, -1,657, 664, 785, -1,785, 664, 783, -1, + 785, 783, 896, -1,896, 783, 893, -1,896, 893, 1017, -1,1017, 893, 1009, -1,1017, + 1009, 1089, -1,1089, 1009, 1075, -1,1089, 1075, 1151, -1,1151, 1075, 1133, -1,1151, + 1133, 1185, -1,1185, 1133, 1173, -1,1185, 1173, 1199, -1,1199, 1173, 1184, -1,1199, + 1184, 1187, -1,1187, 1184, 1176, -1,1187, 1176, 1154, -1,1154, 1176, 1141, -1,1154, + 1141, 1095, -1,1095, 1141, 1086, -1,1095, 1086, 1030, -1,1030, 1086, 1019, -1,1030, + 1019, 918, -1,918, 1019, 912, -1,918, 912, 807, -1,807, 912, 806, -1,807, 806, 689, -1, + 689, 806, 693, -1,689, 693, 569, -1,569, 693, 575, -1,569, 575, 474, -1,474, 575, + 483, -1,474, 483, 411, -1,411, 483, 422, -1,411, 422, 358, -1,358, 422, 372, -1,358, + 372, 332, -1,332, 372, 344, -1,344, 369, 343, -1,343, 369, 368, -1,343, 368, 370, -1, + 370, 368, 381, -1,370, 381, 416, -1,416, 381, 429, -1,416, 429, 476, -1,476, 429, + 486, -1,476, 486, 561, -1,561, 486, 571, -1,561, 571, 664, -1,664, 571, 678, -1,664, + 678, 783, -1,783, 678, 782, -1,783, 782, 893, -1,893, 782, 887, -1,893, 887, 1009, -1, + 1009, 887, 996, -1,1009, 996, 1075, -1,1075, 996, 1062, -1,1075, 1062, 1133, -1,1133, + 1062, 1119, -1,1133, 1119, 1173, -1,1173, 1119, 1153, -1,1173, 1153, 1184, -1,1184, + 1153, 1167, -1,1184, 1167, 1176, -1,1176, 1167, 1158, -1,1176, 1158, 1141, -1,1141, + 1158, 1124, -1,1141, 1124, 1086, -1,1086, 1124, 1072, -1,1086, 1072, 1019, -1,1019, + 1072, 1010, -1,1019, 1010, 912, -1,912, 1010, 901, -1,912, 901, 806, -1,806, 901, + 804, -1,806, 804, 693, -1,693, 804, 702, -1,693, 702, 575, -1,575, 702, 585, -1,575, + 585, 483, -1,483, 585, 492, -1,483, 492, 422, -1,422, 492, 437, -1,422, 437, 372, -1, + 372, 437, 390, -1,372, 390, 344, -1,344, 390, 369, -1,369, 383, 368, -1,368, 383, + 380, -1,368, 380, 381, -1,381, 380, 408, -1,381, 408, 429, -1,429, 408, 443, -1,429, + 443, 486, -1,486, 443, 496, -1,486, 496, 571, -1,571, 496, 582, -1,571, 582, 678, -1, + 678, 582, 688, -1,678, 688, 782, -1,782, 688, 778, -1,782, 778, 887, -1,887, 778, + 875, -1,887, 875, 996, -1,996, 875, 982, -1,996, 982, 1062, -1,1062, 982, 1050, -1, + 1062, 1050, 1119, -1,1119, 1050, 1099, -1,1119, 1099, 1153, -1,1153, 1099, 1130, -1, + 1153, 1130, 1167, -1,1167, 1130, 1146, -1,1167, 1146, 1158, -1,1158, 1146, 1135, -1, + 1158, 1135, 1124, -1,1124, 1135, 1107, -1,1124, 1107, 1072, -1,1072, 1107, 1057, -1, + 1072, 1057, 1010, -1,1010, 1057, 994, -1,1010, 994, 901, -1,901, 994, 891, -1,901, + 891, 804, -1,804, 891, 803, -1,804, 803, 702, -1,702, 803, 706, -1,702, 706, 585, -1, + 585, 706, 596, -1,585, 596, 492, -1,492, 596, 503, -1,492, 503, 437, -1,437, 503, + 448, -1,437, 448, 390, -1,390, 448, 413, -1,390, 413, 369, -1,369, 413, 383, -1,1039, + 1081, 1099, -1,1099, 1081, 1096, -1,1099, 1096, 1130, -1,1130, 1096, 1112, -1,1130, + 1112, 1146, -1,1146, 1112, 1123, -1,1146, 1123, 1135, -1,1135, 1123, 1115, -1,1135, + 1115, 1107, -1,1107, 1115, 1087, -1,1107, 1087, 1057, -1,1057, 1087, 1044, -1,1057, + 1044, 994, -1,994, 1044, 977, -1,994, 977, 891, -1,891, 977, 883, -1,891, 883, 803, -1, + 803, 883, 798, -1,803, 798, 706, -1,706, 798, 712, -1,706, 712, 596, -1,596, 712, + 608, -1,596, 608, 503, -1,503, 608, 513, -1,503, 513, 448, -1,448, 513, 466, -1,448, + 466, 413, -1,413, 466, 432, -1,413, 432, 383, -1,383, 432, 412, -1,383, 412, 380, -1, + 380, 412, 410, -1,380, 410, 408, -1,408, 410, 426, -1,408, 426, 443, -1,443, 426, + 459, -1,443, 459, 496, -1,496, 459, 507, -1,496, 507, 582, -1,582, 507, 595, -1,582, + 595, 688, -1,688, 595, 694, -1,688, 694, 778, -1,778, 694, 776, -1,778, 776, 875, -1, + 875, 776, 865, -1,875, 865, 982, -1,982, 865, 967, -1,982, 967, 1050, -1,1050, 967, + 1039, -1,1050, 1039, 1099, -1,696, 721, 745, -1,856, 832, 871, -1,871, 832, 696, -1, + 871, 696, 885, -1,885, 696, 745, -1,815, 775, 832, -1,832, 775, 643, -1,832, 643, + 635, -1,870, 884, 855, -1,855, 884, 885, -1,697, 653, 722, -1,722, 653, 643, -1,722, + 643, 747, -1,747, 643, 775, -1,652, 696, 642, -1,642, 696, 832, -1,642, 832, 634, -1, + 634, 832, 635, -1,831, 855, 814, -1,814, 855, 885, -1,814, 885, 773, -1,773, 885, + 745, -1,532, 574, 576, -1,576, 574, 603, -1,576, 603, 620, -1,603, 618, 620, -1,620, + 618, 636, -1,620, 636, 673, -1,636, 670, 673, -1,673, 670, 692, -1,673, 692, 726, -1, + 726, 692, 729, -1,726, 729, 784, -1,729, 777, 784, -1,784, 777, 801, -1,784, 801, + 833, -1,801, 821, 833, -1,833, 821, 847, -1,833, 847, 888, -1,888, 847, 866, -1,888, + 866, 945, -1,866, 910, 945, -1,945, 910, 919, -1,945, 919, 985, -1,985, 919, 957, -1, + 985, 957, 1016, -1,957, 984, 1016, -1,1016, 984, 990, -1,1016, 990, 1031, -1,990, + 1001, 1031, -1,1031, 1001, 1008, -1,1031, 1008, 1036, -1,1036, 1008, 1007, -1,1036, + 1007, 1032, -1,1007, 1006, 1032, -1,1032, 1006, 1003, -1,1032, 1003, 1020, -1,1020, + 1003, 989, -1,1020, 989, 992, -1,989, 962, 992, -1,992, 962, 956, -1,992, 956, 955, -1, + 956, 930, 955, -1,955, 930, 909, -1,955, 909, 905, -1,905, 909, 882, -1,905, 882, + 844, -1,882, 846, 844, -1,844, 846, 834, -1,844, 834, 805, -1,805, 834, 800, -1,805, + 800, 740, -1,800, 744, 740, -1,740, 744, 728, -1,740, 728, 695, -1,728, 711, 695, -1, + 695, 711, 668, -1,695, 668, 632, -1,632, 668, 645, -1,632, 645, 587, -1,645, 617, + 587, -1,587, 617, 611, -1,587, 611, 543, -1,543, 611, 573, -1,543, 573, 508, -1,573, + 545, 508, -1,508, 545, 534, -1,508, 534, 498, -1,534, 522, 498, -1,498, 522, 514, -1, + 498, 514, 491, -1,491, 514, 515, -1,491, 515, 495, -1,515, 516, 495, -1,495, 516, + 520, -1,495, 520, 505, -1,505, 520, 535, -1,505, 535, 532, -1,532, 535, 566, -1,532, + 566, 574, -1,495, 452, 491, -1,491, 452, 449, -1,491, 449, 498, -1,498, 449, 454, -1, + 498, 454, 508, -1,508, 454, 480, -1,508, 480, 543, -1,543, 480, 501, -1,543, 501, + 587, -1,587, 501, 549, -1,587, 549, 632, -1,632, 549, 610, -1,632, 610, 695, -1,695, + 610, 665, -1,695, 665, 740, -1,740, 665, 736, -1,740, 736, 805, -1,805, 736, 812, -1, + 805, 812, 844, -1,844, 812, 861, -1,844, 861, 905, -1,905, 861, 939, -1,905, 939, + 955, -1,955, 939, 993, -1,955, 993, 992, -1,992, 993, 1034, -1,992, 1034, 1020, -1, + 1020, 1034, 1055, -1,1020, 1055, 1032, -1,1032, 1055, 1070, -1,1032, 1070, 1036, -1, + 1036, 1070, 1074, -1,1036, 1074, 1031, -1,1031, 1074, 1068, -1,1031, 1068, 1016, -1, + 1016, 1068, 1051, -1,1016, 1051, 985, -1,985, 1051, 1025, -1,985, 1025, 945, -1,945, + 1025, 979, -1,945, 979, 888, -1,888, 979, 921, -1,888, 921, 833, -1,833, 921, 849, -1, + 833, 849, 784, -1,784, 849, 792, -1,784, 792, 726, -1,726, 792, 724, -1,726, 724, + 673, -1,673, 724, 647, -1,673, 647, 620, -1,620, 647, 593, -1,620, 593, 576, -1,576, + 593, 531, -1,576, 531, 532, -1,532, 531, 494, -1,532, 494, 505, -1,505, 494, 471, -1, + 505, 471, 495, -1,495, 471, 452, -1,452, 400, 449, -1,449, 400, 393, -1,449, 393, + 454, -1,454, 393, 404, -1,454, 404, 480, -1,480, 404, 425, -1,480, 425, 501, -1,501, + 425, 455, -1,501, 455, 549, -1,549, 455, 500, -1,549, 500, 610, -1,610, 500, 572, -1, + 610, 572, 665, -1,665, 572, 644, -1,665, 644, 736, -1,736, 644, 727, -1,736, 727, + 812, -1,812, 727, 816, -1,812, 816, 861, -1,861, 816, 892, -1,861, 892, 939, -1,939, + 892, 976, -1,939, 976, 993, -1,993, 976, 1040, -1,993, 1040, 1034, -1,1034, 1040, + 1076, -1,1034, 1076, 1055, -1,1055, 1076, 1111, -1,1055, 1111, 1070, -1,1070, 1111, + 1128, -1,1070, 1128, 1074, -1,1074, 1128, 1136, -1,1074, 1136, 1068, -1,1068, 1136, + 1126, -1,1068, 1126, 1051, -1,1051, 1126, 1104, -1,1051, 1104, 1025, -1,1025, 1104, + 1067, -1,1025, 1067, 979, -1,979, 1067, 1027, -1,979, 1027, 921, -1,921, 1027, 958, -1, + 921, 958, 849, -1,849, 958, 867, -1,849, 867, 792, -1,792, 867, 802, -1,792, 802, + 724, -1,724, 802, 720, -1,724, 720, 647, -1,647, 720, 629, -1,647, 629, 593, -1,593, + 629, 554, -1,593, 554, 531, -1,531, 554, 490, -1,531, 490, 494, -1,494, 490, 447, -1, + 494, 447, 471, -1,471, 447, 420, -1,471, 420, 452, -1,452, 420, 400, -1,400, 321, + 393, -1,393, 321, 313, -1,393, 313, 404, -1,404, 313, 327, -1,404, 327, 425, -1,425, + 327, 356, -1,425, 356, 455, -1,455, 356, 405, -1,455, 405, 500, -1,500, 405, 456, -1, + 500, 456, 572, -1,572, 456, 521, -1,572, 521, 644, -1,644, 521, 628, -1,644, 628, + 727, -1,727, 628, 725, -1,727, 725, 816, -1,816, 725, 820, -1,816, 820, 892, -1,892, + 820, 929, -1,892, 929, 976, -1,976, 929, 1021, -1,976, 1021, 1040, -1,1040, 1021, + 1085, -1,1040, 1085, 1076, -1,1076, 1085, 1138, -1,1076, 1138, 1111, -1,1111, 1138, + 1181, -1,1111, 1181, 1128, -1,1128, 1181, 1205, -1,1128, 1205, 1136, -1,1136, 1205, + 1215, -1,1136, 1215, 1126, -1,1126, 1215, 1196, -1,1126, 1196, 1104, -1,1104, 1196, + 1171, -1,1104, 1171, 1067, -1,1067, 1171, 1125, -1,1067, 1125, 1027, -1,1027, 1125, + 1066, -1,1027, 1066, 958, -1,958, 1066, 1002, -1,958, 1002, 867, -1,867, 1002, 894, -1, + 867, 894, 802, -1,802, 894, 808, -1,802, 808, 720, -1,720, 808, 714, -1,720, 714, + 629, -1,629, 714, 604, -1,629, 604, 554, -1,554, 604, 504, -1,554, 504, 490, -1,490, + 504, 442, -1,490, 442, 447, -1,447, 442, 389, -1,447, 389, 420, -1,420, 389, 346, -1, + 420, 346, 400, -1,400, 346, 321, -1,321, 271, 313, -1,313, 271, 267, -1,313, 267, + 327, -1,327, 267, 274, -1,327, 274, 356, -1,356, 274, 287, -1,356, 287, 405, -1,405, + 287, 336, -1,405, 336, 456, -1,456, 336, 409, -1,456, 409, 521, -1,521, 409, 488, -1, + 521, 488, 628, -1,628, 488, 598, -1,628, 598, 725, -1,725, 598, 723, -1,725, 723, + 820, -1,820, 723, 829, -1,820, 829, 929, -1,929, 829, 961, -1,929, 961, 1021, -1, + 1021, 961, 1059, -1,1021, 1059, 1085, -1,1085, 1059, 1140, -1,1085, 1140, 1138, -1, + 1138, 1140, 1211, -1,1138, 1211, 1181, -1,1181, 1211, 1249, -1,1181, 1249, 1205, -1, + 1205, 1249, 1263, -1,1205, 1263, 1215, -1,1215, 1263, 1266, -1,1215, 1266, 1196, -1, + 1196, 1266, 1259, -1,1196, 1259, 1171, -1,1171, 1259, 1243, -1,1171, 1243, 1125, -1, + 1125, 1243, 1190, -1,1125, 1190, 1066, -1,1066, 1190, 1122, -1,1066, 1122, 1002, -1, + 1002, 1122, 1041, -1,1002, 1041, 894, -1,894, 1041, 935, -1,894, 935, 808, -1,808, + 935, 813, -1,808, 813, 714, -1,714, 813, 699, -1,714, 699, 604, -1,604, 699, 567, -1, + 604, 567, 504, -1,504, 567, 465, -1,504, 465, 442, -1,442, 465, 385, -1,442, 385, + 389, -1,389, 385, 318, -1,389, 318, 346, -1,346, 318, 284, -1,346, 284, 321, -1,321, + 284, 271, -1,271, 235, 267, -1,267, 235, 227, -1,267, 227, 274, -1,274, 227, 237, -1, + 274, 237, 287, -1,287, 237, 255, -1,287, 255, 336, -1,336, 255, 280, -1,336, 280, + 409, -1,409, 280, 347, -1,409, 347, 488, -1,488, 347, 446, -1,488, 446, 598, -1,598, + 446, 565, -1,598, 565, 723, -1,723, 565, 719, -1,723, 719, 829, -1,829, 719, 843, -1, + 829, 843, 961, -1,961, 843, 1000, -1,961, 1000, 1059, -1,1059, 1000, 1105, -1,1059, + 1105, 1140, -1,1140, 1105, 1198, -1,1140, 1198, 1211, -1,1211, 1198, 1256, -1,1211, + 1256, 1249, -1,1249, 1256, 1286, -1,1249, 1286, 1263, -1,1263, 1286, 1295, -1,1263, + 1295, 1266, -1,1266, 1295, 1300, -1,1266, 1300, 1259, -1,1259, 1300, 1291, -1,1259, + 1291, 1243, -1,1243, 1291, 1280, -1,1243, 1280, 1190, -1,1190, 1280, 1251, -1,1190, + 1251, 1122, -1,1122, 1251, 1179, -1,1122, 1179, 1041, -1,1041, 1179, 1078, -1,1041, + 1078, 935, -1,935, 1078, 963, -1,935, 963, 813, -1,813, 963, 817, -1,813, 817, 699, -1, + 699, 817, 674, -1,699, 674, 567, -1,567, 674, 523, -1,567, 523, 465, -1,465, 523, + 424, -1,465, 424, 385, -1,385, 424, 326, -1,385, 326, 318, -1,318, 326, 276, -1,318, + 276, 284, -1,284, 276, 245, -1,284, 245, 271, -1,271, 245, 235, -1,1003, 998, 981, -1, + 1003, 1006, 998, -1,998, 1006, 1007, -1,998, 1007, 999, -1,1007, 1008, 999, -1,999, + 1008, 1001, -1,999, 1001, 983, -1,1001, 990, 983, -1,983, 990, 984, -1,983, 984, + 951, -1,984, 957, 951, -1,951, 957, 919, -1,951, 919, 902, -1,919, 910, 902, -1,902, + 910, 866, -1,902, 866, 841, -1,866, 847, 841, -1,841, 847, 821, -1,841, 821, 799, -1, + 821, 801, 799, -1,799, 801, 777, -1,799, 777, 731, -1,777, 729, 731, -1,731, 729, + 692, -1,731, 692, 677, -1,692, 670, 677, -1,677, 670, 636, -1,677, 636, 625, -1,636, + 618, 625, -1,625, 618, 603, -1,625, 603, 580, -1,603, 574, 580, -1,580, 574, 566, -1, + 580, 566, 547, -1,566, 535, 547, -1,547, 535, 520, -1,547, 520, 525, -1,520, 516, + 525, -1,525, 516, 515, -1,525, 515, 524, -1,515, 514, 524, -1,524, 514, 522, -1,524, + 522, 546, -1,522, 534, 546, -1,546, 534, 545, -1,546, 545, 579, -1,545, 573, 579, -1, + 579, 573, 611, -1,579, 611, 623, -1,611, 617, 623, -1,623, 617, 645, -1,623, 645, + 676, -1,645, 668, 676, -1,676, 668, 711, -1,676, 711, 730, -1,711, 728, 730, -1,730, + 728, 744, -1,730, 744, 797, -1,744, 800, 797, -1,797, 800, 834, -1,797, 834, 840, -1, + 834, 846, 840, -1,840, 846, 882, -1,840, 882, 899, -1,882, 909, 899, -1,899, 909, + 930, -1,899, 930, 950, -1,930, 956, 950, -1,950, 956, 962, -1,950, 962, 981, -1,981, + 962, 989, -1,981, 989, 1003, -1,950, 940, 899, -1,899, 940, 889, -1,899, 889, 840, -1, + 840, 889, 836, -1,840, 836, 797, -1,797, 836, 795, -1,797, 795, 730, -1,730, 795, + 732, -1,730, 732, 676, -1,676, 732, 686, -1,676, 686, 623, -1,623, 686, 630, -1,623, + 630, 579, -1,579, 630, 591, -1,579, 591, 546, -1,546, 591, 559, -1,546, 559, 524, -1, + 524, 559, 541, -1,524, 541, 525, -1,525, 541, 542, -1,525, 542, 547, -1,547, 542, + 560, -1,547, 560, 580, -1,580, 560, 592, -1,580, 592, 625, -1,625, 592, 631, -1,625, + 631, 677, -1,677, 631, 687, -1,677, 687, 731, -1,731, 687, 733, -1,731, 733, 799, -1, + 799, 733, 796, -1,799, 796, 841, -1,841, 796, 837, -1,841, 837, 902, -1,902, 837, + 890, -1,902, 890, 951, -1,951, 890, 941, -1,951, 941, 983, -1,983, 941, 970, -1,983, + 970, 999, -1,999, 970, 987, -1,999, 987, 998, -1,998, 987, 986, -1,998, 986, 981, -1, + 981, 986, 969, -1,981, 969, 950, -1,950, 969, 940, -1,940, 923, 889, -1,889, 923, + 880, -1,889, 880, 836, -1,836, 880, 828, -1,836, 828, 795, -1,795, 828, 793, -1,795, + 793, 732, -1,732, 793, 734, -1,732, 734, 686, -1,686, 734, 698, -1,686, 698, 630, -1, + 630, 698, 637, -1,630, 637, 591, -1,591, 637, 606, -1,591, 606, 559, -1,559, 606, + 577, -1,559, 577, 541, -1,541, 577, 563, -1,541, 563, 542, -1,542, 563, 564, -1,542, + 564, 560, -1,560, 564, 578, -1,560, 578, 592, -1,592, 578, 607, -1,592, 607, 631, -1, + 631, 607, 638, -1,631, 638, 687, -1,687, 638, 700, -1,687, 700, 733, -1,733, 700, + 735, -1,733, 735, 796, -1,796, 735, 794, -1,796, 794, 837, -1,837, 794, 830, -1,837, + 830, 890, -1,890, 830, 881, -1,890, 881, 941, -1,941, 881, 924, -1,941, 924, 970, -1, + 970, 924, 953, -1,970, 953, 987, -1,987, 953, 965, -1,987, 965, 986, -1,986, 965, + 964, -1,986, 964, 969, -1,969, 964, 952, -1,969, 952, 940, -1,940, 952, 923, -1,923, + 898, 880, -1,880, 898, 859, -1,880, 859, 828, -1,828, 859, 822, -1,828, 822, 793, -1, + 793, 822, 787, -1,793, 787, 734, -1,734, 787, 738, -1,734, 738, 698, -1,698, 738, + 709, -1,698, 709, 637, -1,637, 709, 648, -1,637, 648, 606, -1,606, 648, 624, -1,606, + 624, 577, -1,577, 624, 600, -1,577, 600, 563, -1,563, 600, 588, -1,563, 588, 564, -1, + 564, 588, 589, -1,564, 589, 578, -1,578, 589, 601, -1,578, 601, 607, -1,607, 601, + 626, -1,607, 626, 638, -1,638, 626, 649, -1,638, 649, 700, -1,700, 649, 710, -1,700, + 710, 735, -1,735, 710, 739, -1,735, 739, 794, -1,794, 739, 789, -1,794, 789, 830, -1, + 830, 789, 823, -1,830, 823, 881, -1,881, 823, 860, -1,881, 860, 924, -1,924, 860, + 900, -1,924, 900, 953, -1,953, 900, 933, -1,953, 933, 965, -1,965, 933, 944, -1,965, + 944, 964, -1,964, 944, 943, -1,964, 943, 952, -1,952, 943, 932, -1,952, 932, 923, -1, + 923, 932, 898, -1,898, 878, 859, -1,859, 878, 850, -1,859, 850, 822, -1,822, 850, + 818, -1,822, 818, 787, -1,787, 818, 780, -1,787, 780, 738, -1,738, 780, 741, -1,738, + 741, 709, -1,709, 741, 715, -1,709, 715, 648, -1,648, 715, 662, -1,648, 662, 624, -1, + 624, 662, 639, -1,624, 639, 600, -1,600, 639, 621, -1,600, 621, 588, -1,588, 621, + 612, -1,588, 612, 589, -1,589, 612, 613, -1,589, 613, 601, -1,601, 613, 622, -1,601, + 622, 626, -1,626, 622, 640, -1,626, 640, 649, -1,649, 640, 663, -1,649, 663, 710, -1, + 710, 663, 716, -1,710, 716, 739, -1,739, 716, 742, -1,739, 742, 789, -1,789, 742, + 781, -1,789, 781, 823, -1,823, 781, 819, -1,823, 819, 860, -1,860, 819, 851, -1,860, + 851, 900, -1,900, 851, 879, -1,900, 879, 933, -1,933, 879, 904, -1,933, 904, 944, -1, + 944, 904, 916, -1,944, 916, 943, -1,943, 916, 915, -1,943, 915, 932, -1,932, 915, + 903, -1,932, 903, 898, -1,898, 903, 878, -1,878, 855, 850, -1,850, 855, 831, -1,850, + 831, 818, -1,818, 831, 814, -1,818, 814, 780, -1,780, 814, 773, -1,780, 773, 741, -1, + 741, 773, 745, -1,741, 745, 715, -1,715, 745, 721, -1,715, 721, 662, -1,662, 721, + 696, -1,662, 696, 639, -1,639, 696, 652, -1,639, 652, 621, -1,621, 652, 642, -1,621, + 642, 612, -1,612, 642, 634, -1,612, 634, 613, -1,613, 634, 635, -1,613, 635, 622, -1, + 622, 635, 643, -1,622, 643, 640, -1,640, 643, 653, -1,640, 653, 663, -1,663, 653, + 697, -1,663, 697, 716, -1,716, 697, 722, -1,716, 722, 742, -1,742, 722, 747, -1,742, + 747, 781, -1,781, 747, 775, -1,781, 775, 819, -1,819, 775, 815, -1,819, 815, 851, -1, + 851, 815, 832, -1,851, 832, 879, -1,879, 832, 856, -1,879, 856, 904, -1,904, 856, + 871, -1,904, 871, 916, -1,916, 871, 885, -1,916, 885, 915, -1,915, 885, 884, -1,915, + 884, 903, -1,903, 884, 870, -1,903, 870, 878, -1,878, 870, 855, -1 + ] + normalPerVertex TRUE + normalIndex [ + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1, + 0, 0, 0, -1,0, 0, 0, -1,0, 0, 0, -1,1, 2, 3, -1,4, 5, 6, -1,7, 8, 9, -1,10, 11, 12, -1, + 13, 14, 15, -1,16, 17, 18, -1,19, 20, 21, -1,22, 23, 24, -1,25, 26, 27, -1,28, 29, + 30, -1,31, 32, 33, -1,34, 35, 36, -1,37, 38, 39, -1,40, 41, 42, -1,43, 44, 45, -1, + 46, 47, 48, -1,49, 50, 51, -1,52, 53, 54, -1,55, 56, 57, -1,58, 59, 60, -1,61, 62, + 63, -1,64, 65, 66, -1,67, 68, 69, -1,70, 71, 72, -1,73, 74, 75, -1,76, 77, 78, -1, + 79, 80, 81, -1,82, 83, 84, -1,85, 86, 87, -1,88, 89, 90, -1,91, 92, 93, -1,94, 95, + 96, -1,97, 98, 99, -1,100, 101, 102, -1,103, 104, 105, -1,106, 107, 108, -1,109, + 110, 111, -1,112, 113, 114, -1,115, 116, 117, -1,118, 119, 120, -1,121, 122, 123, -1, + 124, 125, 126, -1,127, 128, 129, -1,130, 131, 132, -1,133, 134, 135, -1,136, 137, + 138, -1,139, 140, 141, -1,142, 143, 144, -1,145, 92, 146, -1,146, 92, 91, -1,146, + 91, 147, -1,147, 91, 148, -1,149, 150, 151, -1,152, 153, 154, -1,155, 156, 157, -1, + 158, 159, 97, -1,98, 160, 161, -1,161, 160, 94, -1,162, 93, 163, -1,163, 93, 92, -1, + 163, 92, 149, -1,149, 92, 145, -1,149, 145, 150, -1,164, 162, 165, -1,165, 162, 163, -1, + 165, 163, 166, -1,166, 163, 149, -1,166, 149, 152, -1,152, 149, 151, -1,152, 151, + 153, -1,167, 164, 168, -1,168, 164, 165, -1,168, 165, 169, -1,169, 165, 166, -1,169, + 166, 170, -1,170, 166, 152, -1,170, 152, 171, -1,171, 152, 154, -1,171, 154, 172, -1, + 173, 174, 175, -1,176, 167, 177, -1,177, 167, 168, -1,177, 168, 178, -1,178, 168, + 169, -1,178, 169, 179, -1,179, 169, 170, -1,179, 170, 180, -1,180, 170, 171, -1,180, + 171, 155, -1,155, 171, 172, -1,155, 172, 156, -1,181, 176, 182, -1,182, 176, 177, -1, + 182, 177, 183, -1,183, 177, 178, -1,183, 178, 184, -1,184, 178, 179, -1,184, 179, + 185, -1,185, 179, 180, -1,185, 180, 186, -1,186, 180, 155, -1,186, 155, 158, -1,158, + 155, 157, -1,158, 157, 159, -1,187, 188, 189, -1,87, 190, 191, -1,191, 190, 192, -1, + 191, 192, 193, -1,193, 192, 173, -1,193, 173, 194, -1,194, 173, 175, -1,194, 175, + 195, -1,113, 196, 114, -1,114, 196, 197, -1,114, 197, 198, -1,198, 197, 199, -1,198, + 199, 200, -1,200, 199, 201, -1,200, 201, 202, -1,202, 201, 203, -1,202, 203, 204, -1, + 204, 203, 205, -1,204, 205, 206, -1,206, 205, 207, -1,206, 207, 208, -1,208, 207, + 24, -1,89, 209, 90, -1,90, 209, 187, -1,90, 187, 210, -1,210, 187, 189, -1,210, 189, + 174, -1,174, 173, 210, -1,210, 173, 192, -1,210, 192, 90, -1,90, 192, 190, -1,90, + 190, 88, -1,86, 211, 87, -1,87, 211, 212, -1,87, 212, 190, -1,190, 212, 213, -1,190, + 213, 88, -1,83, 85, 84, -1,84, 85, 87, -1,84, 87, 214, -1,214, 87, 191, -1,214, 191, + 215, -1,215, 191, 193, -1,215, 193, 216, -1,216, 193, 194, -1,216, 194, 217, -1,217, + 194, 195, -1,217, 195, 218, -1,80, 82, 81, -1,81, 82, 84, -1,81, 84, 219, -1,219, + 84, 214, -1,219, 214, 220, -1,220, 214, 215, -1,220, 215, 221, -1,221, 215, 216, -1, + 221, 216, 222, -1,222, 216, 217, -1,222, 217, 223, -1,223, 217, 218, -1,223, 218, + 96, -1,77, 79, 78, -1,78, 79, 81, -1,78, 81, 224, -1,224, 81, 219, -1,224, 219, 225, -1, + 225, 219, 220, -1,225, 220, 226, -1,226, 220, 221, -1,226, 221, 227, -1,227, 221, + 222, -1,227, 222, 228, -1,228, 222, 223, -1,228, 223, 229, -1,229, 223, 96, -1,229, + 96, 230, -1,230, 96, 95, -1,74, 76, 75, -1,75, 76, 78, -1,75, 78, 231, -1,231, 78, + 224, -1,231, 224, 232, -1,232, 224, 225, -1,232, 225, 233, -1,233, 225, 226, -1,233, + 226, 234, -1,234, 226, 227, -1,234, 227, 235, -1,235, 227, 228, -1,235, 228, 144, -1, + 144, 228, 229, -1,144, 229, 142, -1,142, 229, 230, -1,71, 73, 72, -1,72, 73, 75, -1, + 72, 75, 236, -1,236, 75, 231, -1,236, 231, 237, -1,237, 231, 232, -1,237, 232, 238, -1, + 238, 232, 233, -1,238, 233, 239, -1,239, 233, 234, -1,239, 234, 240, -1,240, 234, + 235, -1,240, 235, 141, -1,141, 235, 144, -1,141, 144, 139, -1,139, 144, 143, -1,68, + 70, 69, -1,69, 70, 72, -1,69, 72, 241, -1,241, 72, 236, -1,241, 236, 242, -1,242, + 236, 237, -1,242, 237, 243, -1,243, 237, 238, -1,243, 238, 244, -1,244, 238, 239, -1, + 244, 239, 245, -1,245, 239, 240, -1,245, 240, 246, -1,246, 240, 141, -1,246, 141, + 247, -1,247, 141, 140, -1,65, 67, 66, -1,66, 67, 69, -1,66, 69, 248, -1,248, 69, + 241, -1,248, 241, 249, -1,249, 241, 242, -1,249, 242, 250, -1,250, 242, 243, -1,250, + 243, 251, -1,251, 243, 244, -1,251, 244, 252, -1,252, 244, 245, -1,252, 245, 138, -1, + 138, 245, 246, -1,138, 246, 136, -1,136, 246, 247, -1,253, 254, 255, -1,255, 254, + 256, -1,256, 64, 255, -1,255, 64, 66, -1,255, 66, 257, -1,257, 66, 248, -1,257, 248, + 258, -1,258, 248, 249, -1,258, 249, 259, -1,259, 249, 250, -1,259, 250, 260, -1,260, + 250, 251, -1,260, 251, 261, -1,261, 251, 252, -1,261, 252, 135, -1,135, 252, 138, -1, + 135, 138, 133, -1,133, 138, 137, -1,62, 253, 63, -1,63, 253, 255, -1,63, 255, 262, -1, + 262, 255, 257, -1,262, 257, 263, -1,263, 257, 258, -1,263, 258, 264, -1,264, 258, + 259, -1,264, 259, 265, -1,265, 259, 260, -1,265, 260, 266, -1,266, 260, 261, -1,266, + 261, 267, -1,267, 261, 135, -1,267, 135, 268, -1,268, 135, 134, -1,59, 61, 60, -1, + 60, 61, 63, -1,60, 63, 269, -1,269, 63, 262, -1,269, 262, 270, -1,270, 262, 263, -1, + 270, 263, 271, -1,271, 263, 264, -1,271, 264, 272, -1,272, 264, 265, -1,272, 265, + 273, -1,273, 265, 266, -1,273, 266, 132, -1,132, 266, 267, -1,132, 267, 130, -1,130, + 267, 268, -1,56, 58, 57, -1,57, 58, 60, -1,57, 60, 274, -1,274, 60, 269, -1,274, + 269, 275, -1,275, 269, 270, -1,275, 270, 276, -1,276, 270, 271, -1,276, 271, 277, -1, + 277, 271, 272, -1,277, 272, 278, -1,278, 272, 273, -1,278, 273, 129, -1,129, 273, + 132, -1,129, 132, 127, -1,127, 132, 131, -1,53, 55, 54, -1,54, 55, 57, -1,54, 57, + 279, -1,279, 57, 274, -1,279, 274, 280, -1,280, 274, 275, -1,280, 275, 281, -1,281, + 275, 276, -1,281, 276, 282, -1,282, 276, 277, -1,282, 277, 283, -1,283, 277, 278, -1, + 283, 278, 284, -1,284, 278, 129, -1,284, 129, 285, -1,285, 129, 128, -1,50, 52, 51, -1, + 51, 52, 54, -1,51, 54, 286, -1,286, 54, 279, -1,286, 279, 287, -1,287, 279, 280, -1, + 287, 280, 288, -1,288, 280, 281, -1,288, 281, 289, -1,289, 281, 282, -1,289, 282, + 290, -1,290, 282, 283, -1,290, 283, 126, -1,126, 283, 284, -1,126, 284, 124, -1,124, + 284, 285, -1,47, 49, 48, -1,48, 49, 51, -1,48, 51, 291, -1,291, 51, 286, -1,291, + 286, 292, -1,292, 286, 287, -1,292, 287, 293, -1,293, 287, 288, -1,293, 288, 294, -1, + 294, 288, 289, -1,294, 289, 295, -1,295, 289, 290, -1,295, 290, 123, -1,123, 290, + 126, -1,123, 126, 121, -1,121, 126, 125, -1,44, 46, 45, -1,45, 46, 48, -1,45, 48, + 296, -1,296, 48, 291, -1,296, 291, 297, -1,297, 291, 292, -1,297, 292, 298, -1,298, + 292, 293, -1,298, 293, 299, -1,299, 293, 294, -1,299, 294, 300, -1,300, 294, 295, -1, + 300, 295, 301, -1,301, 295, 123, -1,301, 123, 302, -1,302, 123, 122, -1,41, 43, 42, -1, + 42, 43, 45, -1,42, 45, 303, -1,303, 45, 296, -1,303, 296, 304, -1,304, 296, 297, -1, + 304, 297, 305, -1,305, 297, 298, -1,305, 298, 306, -1,306, 298, 299, -1,306, 299, + 307, -1,307, 299, 300, -1,307, 300, 120, -1,120, 300, 301, -1,120, 301, 118, -1,118, + 301, 302, -1,38, 40, 39, -1,39, 40, 42, -1,39, 42, 308, -1,308, 42, 303, -1,308, + 303, 309, -1,309, 303, 304, -1,309, 304, 310, -1,310, 304, 305, -1,310, 305, 311, -1, + 311, 305, 306, -1,311, 306, 312, -1,312, 306, 307, -1,312, 307, 313, -1,313, 307, + 120, -1,313, 120, 314, -1,314, 120, 119, -1,35, 37, 36, -1,36, 37, 39, -1,36, 39, + 315, -1,315, 39, 308, -1,315, 308, 316, -1,316, 308, 309, -1,316, 309, 317, -1,317, + 309, 310, -1,317, 310, 318, -1,318, 310, 311, -1,318, 311, 319, -1,319, 311, 312, -1, + 319, 312, 320, -1,320, 312, 313, -1,320, 313, 321, -1,321, 313, 314, -1,32, 34, 33, -1, + 33, 34, 36, -1,33, 36, 322, -1,322, 36, 315, -1,322, 315, 323, -1,323, 315, 316, -1, + 323, 316, 324, -1,324, 316, 317, -1,324, 317, 325, -1,325, 317, 318, -1,325, 318, + 326, -1,326, 318, 319, -1,326, 319, 117, -1,117, 319, 320, -1,117, 320, 115, -1,115, + 320, 321, -1,29, 31, 30, -1,30, 31, 33, -1,30, 33, 327, -1,327, 33, 322, -1,327, + 322, 328, -1,328, 322, 323, -1,328, 323, 329, -1,329, 323, 324, -1,329, 324, 330, -1, + 330, 324, 325, -1,330, 325, 331, -1,331, 325, 326, -1,331, 326, 332, -1,332, 326, + 117, -1,332, 117, 333, -1,333, 117, 116, -1,26, 28, 27, -1,27, 28, 30, -1,27, 30, + 334, -1,334, 30, 327, -1,334, 327, 335, -1,335, 327, 328, -1,335, 328, 336, -1,336, + 328, 329, -1,336, 329, 337, -1,337, 329, 330, -1,337, 330, 338, -1,338, 330, 331, -1, + 338, 331, 339, -1,339, 331, 332, -1,339, 332, 340, -1,340, 332, 333, -1,340, 112, + 339, -1,339, 112, 114, -1,339, 114, 338, -1,338, 114, 198, -1,338, 198, 337, -1,337, + 198, 200, -1,337, 200, 336, -1,336, 200, 202, -1,336, 202, 335, -1,335, 202, 204, -1, + 335, 204, 334, -1,334, 204, 206, -1,334, 206, 27, -1,27, 206, 208, -1,27, 208, 25, -1, + 23, 341, 24, -1,24, 341, 342, -1,24, 342, 208, -1,208, 342, 343, -1,208, 343, 25, -1, + 20, 22, 21, -1,21, 22, 24, -1,21, 24, 344, -1,344, 24, 207, -1,344, 207, 345, -1, + 345, 207, 205, -1,345, 205, 346, -1,346, 205, 203, -1,346, 203, 347, -1,347, 203, + 201, -1,347, 201, 348, -1,348, 201, 199, -1,348, 199, 349, -1,349, 199, 197, -1,349, + 197, 350, -1,350, 197, 196, -1,17, 19, 18, -1,18, 19, 21, -1,18, 21, 351, -1,351, + 21, 344, -1,351, 344, 352, -1,352, 344, 345, -1,352, 345, 353, -1,353, 345, 346, -1, + 353, 346, 354, -1,354, 346, 347, -1,354, 347, 355, -1,355, 347, 348, -1,355, 348, + 111, -1,111, 348, 349, -1,111, 349, 109, -1,109, 349, 350, -1,14, 16, 15, -1,15, + 16, 18, -1,15, 18, 356, -1,356, 18, 351, -1,356, 351, 357, -1,357, 351, 352, -1,357, + 352, 358, -1,358, 352, 353, -1,358, 353, 359, -1,359, 353, 354, -1,359, 354, 360, -1, + 360, 354, 355, -1,360, 355, 361, -1,361, 355, 111, -1,361, 111, 362, -1,362, 111, + 110, -1,11, 13, 12, -1,12, 13, 15, -1,12, 15, 363, -1,363, 15, 356, -1,363, 356, + 364, -1,364, 356, 357, -1,364, 357, 365, -1,365, 357, 358, -1,365, 358, 366, -1,366, + 358, 359, -1,366, 359, 367, -1,367, 359, 360, -1,367, 360, 108, -1,108, 360, 361, -1, + 108, 361, 106, -1,106, 361, 362, -1,8, 10, 9, -1,9, 10, 12, -1,9, 12, 368, -1,368, + 12, 363, -1,368, 363, 369, -1,369, 363, 364, -1,369, 364, 370, -1,370, 364, 365, -1, + 370, 365, 371, -1,371, 365, 366, -1,371, 366, 372, -1,372, 366, 367, -1,372, 367, + 105, -1,105, 367, 108, -1,105, 108, 103, -1,103, 108, 107, -1,5, 7, 6, -1,6, 7, 9, -1, + 6, 9, 373, -1,373, 9, 368, -1,373, 368, 374, -1,374, 368, 369, -1,374, 369, 375, -1, + 375, 369, 370, -1,375, 370, 376, -1,376, 370, 371, -1,376, 371, 377, -1,377, 371, + 372, -1,377, 372, 378, -1,378, 372, 105, -1,378, 105, 379, -1,379, 105, 104, -1,2, + 4, 3, -1,3, 4, 6, -1,3, 6, 380, -1,380, 6, 373, -1,380, 373, 381, -1,381, 373, 374, -1, + 381, 374, 382, -1,382, 374, 375, -1,382, 375, 383, -1,383, 375, 376, -1,383, 376, + 384, -1,384, 376, 377, -1,384, 377, 102, -1,102, 377, 378, -1,102, 378, 100, -1,100, + 378, 379, -1,181, 385, 386, -1,386, 1, 181, -1,181, 1, 3, -1,181, 3, 176, -1,176, + 3, 380, -1,176, 380, 167, -1,167, 380, 381, -1,167, 381, 164, -1,164, 381, 382, -1, + 164, 382, 162, -1,162, 382, 383, -1,162, 383, 93, -1,93, 383, 384, -1,93, 384, 91, -1, + 91, 384, 102, -1,91, 102, 148, -1,148, 102, 101, -1,387, 388, 389, -1,97, 99, 158, -1, + 158, 99, 390, -1,158, 390, 186, -1,186, 390, 391, -1,186, 391, 185, -1,185, 391, + 392, -1,185, 392, 184, -1,184, 392, 393, -1,184, 393, 183, -1,183, 393, 394, -1,183, + 394, 182, -1,182, 394, 387, -1,182, 387, 181, -1,181, 387, 389, -1,181, 389, 385, -1, + 395, 396, 397, -1,98, 161, 99, -1,99, 161, 398, -1,99, 398, 390, -1,390, 398, 399, -1, + 390, 399, 391, -1,391, 399, 400, -1,391, 400, 392, -1,392, 400, 401, -1,392, 401, + 393, -1,393, 401, 402, -1,393, 402, 394, -1,394, 402, 395, -1,394, 395, 387, -1,387, + 395, 397, -1,387, 397, 388, -1,209, 403, 187, -1,187, 403, 404, -1,187, 404, 188, -1, + 188, 404, 405, -1,188, 405, 406, -1,94, 96, 161, -1,161, 96, 218, -1,161, 218, 398, -1, + 398, 218, 195, -1,398, 195, 399, -1,399, 195, 175, -1,399, 175, 400, -1,400, 175, + 174, -1,400, 174, 401, -1,401, 174, 189, -1,401, 189, 402, -1,402, 189, 188, -1,402, + 188, 395, -1,395, 188, 406, -1,395, 406, 396, -1,407, 407, 408, -1,408, 407, 408, -1, + 408, 408, 409, -1,409, 408, 409, -1,409, 409, 410, -1,410, 409, 410, -1,410, 410, + 411, -1,411, 410, 411, -1,411, 411, 412, -1,412, 411, 412, -1,412, 412, 413, -1,413, + 412, 413, -1,413, 413, 414, -1,414, 413, 414, -1,414, 414, 415, -1,415, 414, 415, -1, + 415, 415, 416, -1,416, 415, 416, -1,416, 416, 417, -1,417, 416, 417, -1,417, 417, + 418, -1,418, 417, 418, -1,418, 418, 419, -1,419, 418, 419, -1,419, 419, 420, -1,420, + 419, 420, -1,420, 420, 421, -1,421, 420, 421, -1,421, 421, 422, -1,422, 421, 422, -1, + 422, 422, 423, -1,423, 422, 423, -1,423, 423, 424, -1,424, 423, 424, -1,424, 424, + 425, -1,425, 424, 425, -1,425, 425, 426, -1,426, 425, 426, -1,426, 426, 427, -1,427, + 426, 427, -1,427, 427, 428, -1,428, 427, 428, -1,428, 428, 429, -1,429, 428, 429, -1, + 429, 429, 430, -1,430, 429, 430, -1,430, 430, 431, -1,431, 430, 431, -1,431, 431, + 432, -1,432, 431, 432, -1,432, 432, 433, -1,433, 432, 433, -1,433, 433, 434, -1,434, + 433, 434, -1,434, 434, 435, -1,435, 434, 435, -1,435, 435, 436, -1,436, 435, 436, -1, + 436, 436, 437, -1,437, 436, 437, -1,437, 437, 438, -1,438, 437, 438, -1,438, 438, + 439, -1,439, 438, 439, -1,439, 439, 440, -1,440, 439, 440, -1,440, 440, 441, -1,441, + 440, 441, -1,441, 441, 442, -1,442, 441, 442, -1,442, 442, 443, -1,443, 442, 443, -1, + 443, 443, 444, -1,444, 443, 444, -1,444, 444, 445, -1,445, 444, 445, -1,445, 445, + 446, -1,446, 445, 446, -1,446, 446, 447, -1,447, 446, 447, -1,447, 447, 448, -1,448, + 447, 448, -1,448, 448, 449, -1,449, 448, 449, -1,449, 449, 450, -1,450, 449, 450, -1, + 450, 450, 451, -1,451, 450, 451, -1,451, 451, 452, -1,452, 451, 452, -1,452, 452, + 453, -1,453, 452, 453, -1,453, 453, 454, -1,454, 453, 454, -1,454, 454, 455, -1,455, + 454, 455, -1,455, 455, 456, -1,456, 455, 456, -1,456, 456, 457, -1,457, 456, 457, -1, + 457, 457, 458, -1,458, 457, 458, -1,458, 458, 459, -1,459, 458, 459, -1,459, 459, + 460, -1,460, 459, 460, -1,460, 460, 461, -1,461, 460, 461, -1,461, 461, 462, -1,462, + 461, 462, -1,462, 462, 463, -1,463, 462, 463, -1,463, 463, 464, -1,464, 463, 464, -1, + 464, 464, 465, -1,465, 464, 465, -1,465, 465, 466, -1,466, 465, 466, -1,466, 466, + 467, -1,467, 466, 467, -1,467, 467, 468, -1,468, 467, 468, -1,468, 468, 469, -1,469, + 468, 469, -1,469, 469, 470, -1,470, 469, 470, -1,470, 470, 471, -1,471, 470, 471, -1, + 471, 471, 472, -1,472, 471, 472, -1,472, 472, 473, -1,473, 472, 473, -1,473, 473, + 474, -1,474, 473, 474, -1,474, 474, 475, -1,475, 474, 475, -1,475, 475, 476, -1,476, + 475, 476, -1,476, 476, 477, -1,477, 476, 477, -1,477, 477, 478, -1,478, 477, 478, -1, + 478, 478, 479, -1,479, 478, 479, -1,479, 479, 480, -1,480, 479, 480, -1,480, 480, + 407, -1,407, 480, 407, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,451, + 452, 482, -1,463, 464, 483, -1,470, 471, 484, -1,408, 409, 485, -1,420, 421, 486, -1, + 427, 428, 487, -1,439, 440, 488, -1,441, 442, 489, -1,444, 445, 490, -1,481, 481, + 491, -1,491, 481, 492, -1,491, 492, 493, -1,493, 492, 494, -1,493, 494, 495, -1,495, + 494, 496, -1,495, 496, 497, -1,497, 496, 498, -1,497, 498, 499, -1,499, 498, 489, -1, + 481, 481, 500, -1,500, 481, 501, -1,500, 501, 502, -1,502, 501, 503, -1,502, 503, + 504, -1,504, 503, 505, -1,504, 505, 506, -1,506, 505, 507, -1,506, 507, 508, -1,508, + 507, 509, -1,481, 481, 501, -1,501, 481, 510, -1,501, 510, 503, -1,503, 510, 511, -1, + 503, 511, 505, -1,505, 511, 512, -1,505, 512, 507, -1,507, 512, 513, -1,507, 513, + 509, -1,509, 513, 514, -1,509, 514, 435, -1,435, 514, 434, -1,481, 481, 515, -1,515, + 481, 516, -1,515, 516, 517, -1,517, 516, 518, -1,517, 518, 519, -1,519, 518, 520, -1, + 519, 520, 521, -1,521, 520, 522, -1,521, 522, 523, -1,523, 522, 524, -1,481, 481, + 516, -1,516, 481, 525, -1,516, 525, 518, -1,518, 525, 526, -1,518, 526, 520, -1,520, + 526, 527, -1,520, 527, 522, -1,522, 527, 528, -1,522, 528, 524, -1,524, 528, 529, -1, + 524, 529, 430, -1,430, 529, 429, -1,481, 481, 530, -1,530, 481, 531, -1,530, 531, + 532, -1,532, 531, 533, -1,532, 533, 534, -1,534, 533, 535, -1,534, 535, 536, -1,536, + 535, 537, -1,536, 537, 538, -1,538, 537, 539, -1,481, 481, 531, -1,531, 481, 540, -1, + 531, 540, 533, -1,533, 540, 541, -1,533, 541, 535, -1,535, 541, 542, -1,535, 542, + 537, -1,537, 542, 543, -1,537, 543, 539, -1,539, 543, 544, -1,539, 544, 423, -1,423, + 544, 422, -1,481, 481, 545, -1,545, 481, 546, -1,545, 546, 547, -1,547, 546, 548, -1, + 547, 548, 549, -1,549, 548, 550, -1,549, 550, 551, -1,551, 550, 552, -1,551, 552, + 553, -1,553, 552, 554, -1,481, 481, 546, -1,546, 481, 555, -1,546, 555, 548, -1,548, + 555, 556, -1,548, 556, 550, -1,550, 556, 557, -1,550, 557, 552, -1,552, 557, 558, -1, + 552, 558, 554, -1,554, 558, 559, -1,554, 559, 416, -1,416, 559, 415, -1,481, 481, + 560, -1,560, 481, 561, -1,560, 561, 562, -1,562, 561, 563, -1,562, 563, 564, -1,564, + 563, 565, -1,564, 565, 566, -1,566, 565, 567, -1,566, 567, 568, -1,568, 567, 569, -1, + 481, 481, 561, -1,561, 481, 570, -1,561, 570, 563, -1,563, 570, 571, -1,563, 571, + 565, -1,565, 571, 572, -1,565, 572, 567, -1,567, 572, 573, -1,567, 573, 569, -1,569, + 573, 574, -1,569, 574, 411, -1,411, 574, 410, -1,481, 481, 575, -1,575, 481, 576, -1, + 575, 576, 577, -1,577, 576, 578, -1,577, 578, 579, -1,579, 578, 580, -1,579, 580, + 581, -1,581, 580, 582, -1,581, 582, 583, -1,583, 582, 584, -1,481, 481, 576, -1,576, + 481, 585, -1,576, 585, 578, -1,578, 585, 586, -1,578, 586, 580, -1,580, 586, 587, -1, + 580, 587, 582, -1,582, 587, 588, -1,582, 588, 584, -1,584, 588, 589, -1,584, 589, + 478, -1,478, 589, 477, -1,481, 481, 590, -1,590, 481, 591, -1,590, 591, 592, -1,592, + 591, 593, -1,592, 593, 594, -1,594, 593, 595, -1,594, 595, 596, -1,596, 595, 597, -1, + 596, 597, 598, -1,598, 597, 599, -1,481, 481, 591, -1,591, 481, 600, -1,591, 600, + 593, -1,593, 600, 601, -1,593, 601, 595, -1,595, 601, 602, -1,595, 602, 597, -1,597, + 602, 603, -1,597, 603, 599, -1,599, 603, 604, -1,599, 604, 473, -1,473, 604, 472, -1, + 481, 481, 605, -1,605, 481, 606, -1,605, 606, 607, -1,607, 606, 608, -1,607, 608, + 609, -1,609, 608, 610, -1,609, 610, 611, -1,611, 610, 612, -1,611, 612, 613, -1,613, + 612, 614, -1,481, 481, 606, -1,606, 481, 615, -1,606, 615, 608, -1,608, 615, 616, -1, + 608, 616, 610, -1,610, 616, 617, -1,610, 617, 612, -1,612, 617, 618, -1,612, 618, + 614, -1,614, 618, 619, -1,614, 619, 466, -1,466, 619, 465, -1,481, 481, 620, -1,620, + 481, 621, -1,620, 621, 622, -1,622, 621, 623, -1,622, 623, 624, -1,624, 623, 625, -1, + 624, 625, 626, -1,626, 625, 627, -1,626, 627, 628, -1,628, 627, 629, -1,481, 481, + 621, -1,621, 481, 630, -1,621, 630, 623, -1,623, 630, 631, -1,623, 631, 625, -1,625, + 631, 632, -1,625, 632, 627, -1,627, 632, 633, -1,627, 633, 629, -1,629, 633, 634, -1, + 629, 634, 459, -1,459, 634, 458, -1,481, 481, 635, -1,635, 481, 636, -1,635, 636, + 637, -1,637, 636, 638, -1,637, 638, 639, -1,639, 638, 640, -1,639, 640, 641, -1,641, + 640, 642, -1,641, 642, 643, -1,643, 642, 644, -1,481, 481, 636, -1,636, 481, 645, -1, + 636, 645, 638, -1,638, 645, 646, -1,638, 646, 640, -1,640, 646, 647, -1,640, 647, + 642, -1,642, 647, 648, -1,642, 648, 644, -1,644, 648, 649, -1,644, 649, 454, -1,454, + 649, 453, -1,481, 481, 650, -1,650, 481, 651, -1,650, 651, 652, -1,652, 651, 653, -1, + 652, 653, 654, -1,654, 653, 655, -1,654, 655, 656, -1,656, 655, 657, -1,656, 657, + 658, -1,658, 657, 659, -1,481, 481, 651, -1,651, 481, 660, -1,651, 660, 653, -1,653, + 660, 661, -1,653, 661, 655, -1,655, 661, 662, -1,655, 662, 657, -1,657, 662, 663, -1, + 657, 663, 659, -1,659, 663, 664, -1,659, 664, 447, -1,447, 664, 446, -1,481, 481, + 665, -1,665, 481, 491, -1,665, 491, 666, -1,666, 491, 493, -1,666, 493, 667, -1,667, + 493, 495, -1,667, 495, 668, -1,668, 495, 497, -1,668, 497, 490, -1,490, 497, 499, -1, + 490, 499, 444, -1,489, 442, 499, -1,499, 442, 443, -1,499, 443, 444, -1,440, 441, + 488, -1,488, 441, 489, -1,488, 489, 669, -1,669, 489, 498, -1,669, 498, 670, -1,670, + 498, 496, -1,670, 496, 671, -1,671, 496, 494, -1,671, 494, 672, -1,672, 494, 492, -1, + 672, 492, 481, -1,481, 492, 481, -1,481, 481, 672, -1,672, 481, 500, -1,672, 500, + 671, -1,671, 500, 502, -1,671, 502, 670, -1,670, 502, 504, -1,670, 504, 669, -1,669, + 504, 506, -1,669, 506, 488, -1,488, 506, 508, -1,488, 508, 439, -1,435, 436, 509, -1, + 509, 436, 437, -1,509, 437, 508, -1,508, 437, 438, -1,508, 438, 439, -1,481, 481, + 510, -1,510, 481, 515, -1,510, 515, 511, -1,511, 515, 517, -1,511, 517, 512, -1,512, + 517, 519, -1,512, 519, 513, -1,513, 519, 521, -1,513, 521, 514, -1,514, 521, 523, -1, + 514, 523, 434, -1,430, 431, 524, -1,524, 431, 432, -1,524, 432, 523, -1,523, 432, + 433, -1,523, 433, 434, -1,428, 429, 487, -1,487, 429, 529, -1,487, 529, 673, -1,673, + 529, 528, -1,673, 528, 674, -1,674, 528, 527, -1,674, 527, 675, -1,675, 527, 526, -1, + 675, 526, 676, -1,676, 526, 525, -1,676, 525, 481, -1,481, 525, 481, -1,481, 481, + 676, -1,676, 481, 530, -1,676, 530, 675, -1,675, 530, 532, -1,675, 532, 674, -1,674, + 532, 534, -1,674, 534, 673, -1,673, 534, 536, -1,673, 536, 487, -1,487, 536, 538, -1, + 487, 538, 427, -1,423, 424, 539, -1,539, 424, 425, -1,539, 425, 538, -1,538, 425, + 426, -1,538, 426, 427, -1,421, 422, 486, -1,486, 422, 544, -1,486, 544, 677, -1,677, + 544, 543, -1,677, 543, 678, -1,678, 543, 542, -1,678, 542, 679, -1,679, 542, 541, -1, + 679, 541, 680, -1,680, 541, 540, -1,680, 540, 481, -1,481, 540, 481, -1,481, 481, + 680, -1,680, 481, 545, -1,680, 545, 679, -1,679, 545, 547, -1,679, 547, 678, -1,678, + 547, 549, -1,678, 549, 677, -1,677, 549, 551, -1,677, 551, 486, -1,486, 551, 553, -1, + 486, 553, 420, -1,416, 417, 554, -1,554, 417, 418, -1,554, 418, 553, -1,553, 418, + 419, -1,553, 419, 420, -1,481, 481, 555, -1,555, 481, 560, -1,555, 560, 556, -1,556, + 560, 562, -1,556, 562, 557, -1,557, 562, 564, -1,557, 564, 558, -1,558, 564, 566, -1, + 558, 566, 559, -1,559, 566, 568, -1,559, 568, 415, -1,411, 412, 569, -1,569, 412, + 413, -1,569, 413, 568, -1,568, 413, 414, -1,568, 414, 415, -1,409, 410, 485, -1,485, + 410, 574, -1,485, 574, 681, -1,681, 574, 573, -1,681, 573, 682, -1,682, 573, 572, -1, + 682, 572, 683, -1,683, 572, 571, -1,683, 571, 684, -1,684, 571, 570, -1,684, 570, + 481, -1,481, 570, 481, -1,481, 481, 684, -1,684, 481, 575, -1,684, 575, 683, -1,683, + 575, 577, -1,683, 577, 682, -1,682, 577, 579, -1,682, 579, 681, -1,681, 579, 581, -1, + 681, 581, 485, -1,485, 581, 583, -1,485, 583, 408, -1,478, 479, 584, -1,584, 479, + 480, -1,584, 480, 583, -1,583, 480, 407, -1,583, 407, 408, -1,481, 481, 585, -1,585, + 481, 590, -1,585, 590, 586, -1,586, 590, 592, -1,586, 592, 587, -1,587, 592, 594, -1, + 587, 594, 588, -1,588, 594, 596, -1,588, 596, 589, -1,589, 596, 598, -1,589, 598, + 477, -1,473, 474, 599, -1,599, 474, 475, -1,599, 475, 598, -1,598, 475, 476, -1,598, + 476, 477, -1,471, 472, 484, -1,484, 472, 604, -1,484, 604, 685, -1,685, 604, 603, -1, + 685, 603, 686, -1,686, 603, 602, -1,686, 602, 687, -1,687, 602, 601, -1,687, 601, + 688, -1,688, 601, 600, -1,688, 600, 481, -1,481, 600, 481, -1,481, 481, 688, -1,688, + 481, 605, -1,688, 605, 687, -1,687, 605, 607, -1,687, 607, 686, -1,686, 607, 609, -1, + 686, 609, 685, -1,685, 609, 611, -1,685, 611, 484, -1,484, 611, 613, -1,484, 613, + 470, -1,466, 467, 614, -1,614, 467, 468, -1,614, 468, 613, -1,613, 468, 469, -1,613, + 469, 470, -1,464, 465, 483, -1,483, 465, 619, -1,483, 619, 689, -1,689, 619, 618, -1, + 689, 618, 690, -1,690, 618, 617, -1,690, 617, 691, -1,691, 617, 616, -1,691, 616, + 692, -1,692, 616, 615, -1,692, 615, 481, -1,481, 615, 481, -1,481, 481, 692, -1,692, + 481, 620, -1,692, 620, 691, -1,691, 620, 622, -1,691, 622, 690, -1,690, 622, 624, -1, + 690, 624, 689, -1,689, 624, 626, -1,689, 626, 483, -1,483, 626, 628, -1,483, 628, + 463, -1,459, 460, 629, -1,629, 460, 461, -1,629, 461, 628, -1,628, 461, 462, -1,628, + 462, 463, -1,481, 481, 630, -1,630, 481, 635, -1,630, 635, 631, -1,631, 635, 637, -1, + 631, 637, 632, -1,632, 637, 639, -1,632, 639, 633, -1,633, 639, 641, -1,633, 641, + 634, -1,634, 641, 643, -1,634, 643, 458, -1,454, 455, 644, -1,644, 455, 456, -1,644, + 456, 643, -1,643, 456, 457, -1,643, 457, 458, -1,452, 453, 482, -1,482, 453, 649, -1, + 482, 649, 693, -1,693, 649, 648, -1,693, 648, 694, -1,694, 648, 647, -1,694, 647, + 695, -1,695, 647, 646, -1,695, 646, 696, -1,696, 646, 645, -1,696, 645, 481, -1,481, + 645, 481, -1,481, 481, 696, -1,696, 481, 650, -1,696, 650, 695, -1,695, 650, 652, -1, + 695, 652, 694, -1,694, 652, 654, -1,694, 654, 693, -1,693, 654, 656, -1,693, 656, + 482, -1,482, 656, 658, -1,482, 658, 451, -1,447, 448, 659, -1,659, 448, 449, -1,659, + 449, 658, -1,658, 449, 450, -1,658, 450, 451, -1,445, 446, 490, -1,490, 446, 664, -1, + 490, 664, 668, -1,668, 664, 663, -1,668, 663, 667, -1,667, 663, 662, -1,667, 662, + 666, -1,666, 662, 661, -1,666, 661, 665, -1,665, 661, 660, -1,665, 660, 481, -1,481, + 660, 481, -1,697, 31, 698, -1,699, 28, 700, -1,701, 25, 702, -1,703, 19, 704, -1, + 705, 16, 706, -1,707, 13, 708, -1,709, 10, 710, -1,711, 7, 712, -1,713, 4, 714, -1, + 715, 397, 716, -1,717, 406, 718, -1,719, 209, 720, -1,721, 88, 722, -1,723, 82, 724, -1, + 725, 79, 726, -1,727, 76, 728, -1,729, 73, 730, -1,731, 70, 732, -1,733, 67, 734, -1, + 735, 61, 736, -1,737, 58, 738, -1,739, 55, 740, -1,741, 52, 742, -1,743, 744, 745, -1, + 446, 445, 746, -1,449, 448, 747, -1,460, 459, 748, -1,463, 462, 749, -1,465, 464, + 750, -1,467, 466, 751, -1,470, 469, 752, -1,472, 471, 753, -1,474, 473, 754, -1,477, + 476, 755, -1,479, 478, 756, -1,408, 407, 757, -1,410, 409, 758, -1,412, 411, 759, -1, + 415, 414, 760, -1,417, 416, 761, -1,420, 419, 762, -1,422, 421, 763, -1,424, 423, + 764, -1,427, 426, 765, -1,429, 428, 766, -1,431, 430, 767, -1,434, 433, 768, -1,436, + 435, 769, -1,439, 438, 770, -1,441, 440, 771, -1,443, 442, 772, -1,455, 744, 456, -1, + 456, 744, 743, -1,456, 743, 457, -1,457, 743, 458, -1,773, 454, 453, -1,774, 452, + 451, -1,451, 450, 775, -1,775, 450, 449, -1,448, 447, 776, -1,776, 447, 446, -1,777, + 745, 778, -1,778, 745, 744, -1,778, 744, 773, -1,773, 744, 455, -1,773, 455, 454, -1, + 779, 780, 781, -1,782, 777, 783, -1,783, 777, 778, -1,783, 778, 784, -1,784, 778, + 773, -1,784, 773, 774, -1,774, 773, 453, -1,774, 453, 452, -1,785, 780, 786, -1,786, + 780, 779, -1,786, 779, 787, -1,438, 437, 770, -1,770, 437, 788, -1,770, 788, 789, -1, + 789, 788, 790, -1,789, 790, 791, -1,791, 790, 792, -1,791, 792, 793, -1,793, 792, + 794, -1,437, 436, 788, -1,788, 436, 769, -1,788, 769, 790, -1,790, 769, 795, -1,790, + 795, 792, -1,792, 795, 796, -1,792, 796, 794, -1,794, 796, 797, -1,794, 797, 64, -1, + 64, 797, 798, -1,423, 422, 764, -1,764, 422, 763, -1,764, 763, 799, -1,799, 763, + 800, -1,799, 800, 801, -1,801, 800, 802, -1,801, 802, 803, -1,803, 802, 804, -1,421, + 420, 763, -1,763, 420, 762, -1,763, 762, 800, -1,800, 762, 805, -1,800, 805, 802, -1, + 802, 805, 806, -1,802, 806, 804, -1,804, 806, 807, -1,804, 807, 212, -1,212, 807, + 808, -1,414, 413, 760, -1,760, 413, 809, -1,760, 809, 810, -1,810, 809, 811, -1,810, + 811, 812, -1,812, 811, 813, -1,812, 813, 814, -1,814, 813, 718, -1,409, 408, 758, -1, + 758, 408, 757, -1,758, 757, 815, -1,815, 757, 816, -1,815, 816, 817, -1,817, 816, + 818, -1,817, 818, 819, -1,819, 818, 820, -1,407, 480, 757, -1,757, 480, 821, -1,757, + 821, 816, -1,816, 821, 822, -1,816, 822, 818, -1,818, 822, 823, -1,818, 823, 820, -1, + 820, 823, 824, -1,820, 824, 1, -1,1, 824, 825, -1,468, 467, 826, -1,826, 467, 751, -1, + 826, 751, 827, -1,827, 751, 828, -1,827, 828, 829, -1,829, 828, 830, -1,829, 830, + 831, -1,831, 830, 832, -1,466, 465, 751, -1,751, 465, 750, -1,751, 750, 828, -1,828, + 750, 833, -1,828, 833, 830, -1,830, 833, 834, -1,830, 834, 832, -1,832, 834, 835, -1, + 832, 835, 342, -1,342, 835, 836, -1,44, 785, 46, -1,46, 785, 786, -1,46, 786, 837, -1, + 837, 786, 787, -1,837, 787, 49, -1,49, 787, 838, -1,52, 838, 742, -1,742, 838, 787, -1, + 742, 787, 839, -1,839, 787, 779, -1,839, 779, 840, -1,840, 779, 781, -1,840, 781, + 746, -1,55, 741, 740, -1,740, 741, 742, -1,740, 742, 841, -1,841, 742, 839, -1,841, + 839, 842, -1,842, 839, 840, -1,842, 840, 843, -1,843, 840, 746, -1,843, 746, 444, -1, + 444, 746, 445, -1,58, 739, 738, -1,738, 739, 740, -1,738, 740, 844, -1,844, 740, + 841, -1,844, 841, 845, -1,845, 841, 842, -1,845, 842, 772, -1,772, 842, 843, -1,772, + 843, 443, -1,443, 843, 444, -1,61, 737, 736, -1,736, 737, 738, -1,736, 738, 846, -1, + 846, 738, 844, -1,846, 844, 847, -1,847, 844, 845, -1,847, 845, 771, -1,771, 845, + 772, -1,771, 772, 441, -1,441, 772, 442, -1,440, 439, 771, -1,771, 439, 770, -1,771, + 770, 847, -1,847, 770, 789, -1,847, 789, 846, -1,846, 789, 791, -1,846, 791, 736, -1, + 736, 791, 793, -1,736, 793, 735, -1,64, 256, 794, -1,794, 256, 848, -1,794, 848, + 793, -1,793, 848, 253, -1,793, 253, 735, -1,67, 798, 734, -1,734, 798, 797, -1,734, + 797, 849, -1,849, 797, 796, -1,849, 796, 850, -1,850, 796, 795, -1,850, 795, 768, -1, + 768, 795, 769, -1,768, 769, 434, -1,434, 769, 435, -1,70, 733, 732, -1,732, 733, + 734, -1,732, 734, 851, -1,851, 734, 849, -1,851, 849, 852, -1,852, 849, 850, -1,852, + 850, 853, -1,853, 850, 768, -1,853, 768, 432, -1,432, 768, 433, -1,73, 731, 730, -1, + 730, 731, 732, -1,730, 732, 854, -1,854, 732, 851, -1,854, 851, 855, -1,855, 851, + 852, -1,855, 852, 767, -1,767, 852, 853, -1,767, 853, 431, -1,431, 853, 432, -1,76, + 729, 728, -1,728, 729, 730, -1,728, 730, 856, -1,856, 730, 854, -1,856, 854, 857, -1, + 857, 854, 855, -1,857, 855, 766, -1,766, 855, 767, -1,766, 767, 429, -1,429, 767, + 430, -1,79, 727, 726, -1,726, 727, 728, -1,726, 728, 858, -1,858, 728, 856, -1,858, + 856, 859, -1,859, 856, 857, -1,859, 857, 765, -1,765, 857, 766, -1,765, 766, 427, -1, + 427, 766, 428, -1,82, 725, 724, -1,724, 725, 726, -1,724, 726, 860, -1,860, 726, + 858, -1,860, 858, 861, -1,861, 858, 859, -1,861, 859, 862, -1,862, 859, 765, -1,862, + 765, 425, -1,425, 765, 426, -1,425, 424, 862, -1,862, 424, 764, -1,862, 764, 861, -1, + 861, 764, 799, -1,861, 799, 860, -1,860, 799, 801, -1,860, 801, 724, -1,724, 801, + 803, -1,724, 803, 723, -1,212, 211, 804, -1,804, 211, 863, -1,804, 863, 803, -1,803, + 863, 85, -1,803, 85, 723, -1,88, 808, 722, -1,722, 808, 807, -1,722, 807, 864, -1, + 864, 807, 806, -1,864, 806, 865, -1,865, 806, 805, -1,865, 805, 866, -1,866, 805, + 762, -1,866, 762, 418, -1,418, 762, 419, -1,209, 721, 720, -1,720, 721, 722, -1,720, + 722, 867, -1,867, 722, 864, -1,867, 864, 868, -1,868, 864, 865, -1,868, 865, 761, -1, + 761, 865, 866, -1,761, 866, 417, -1,417, 866, 418, -1,404, 719, 814, -1,814, 719, + 720, -1,814, 720, 812, -1,812, 720, 867, -1,812, 867, 810, -1,810, 867, 868, -1,810, + 868, 760, -1,760, 868, 761, -1,760, 761, 415, -1,415, 761, 416, -1,718, 406, 814, -1, + 814, 406, 405, -1,814, 405, 404, -1,397, 717, 716, -1,716, 717, 718, -1,716, 718, + 869, -1,869, 718, 813, -1,869, 813, 870, -1,870, 813, 811, -1,870, 811, 759, -1,759, + 811, 809, -1,759, 809, 412, -1,412, 809, 413, -1,411, 410, 759, -1,759, 410, 758, -1, + 759, 758, 870, -1,870, 758, 815, -1,870, 815, 869, -1,869, 815, 817, -1,869, 817, + 716, -1,716, 817, 819, -1,716, 819, 715, -1,1, 386, 820, -1,820, 386, 871, -1,820, + 871, 819, -1,819, 871, 389, -1,819, 389, 715, -1,4, 825, 714, -1,714, 825, 824, -1, + 714, 824, 872, -1,872, 824, 823, -1,872, 823, 873, -1,873, 823, 822, -1,873, 822, + 756, -1,756, 822, 821, -1,756, 821, 479, -1,479, 821, 480, -1,7, 713, 712, -1,712, + 713, 714, -1,712, 714, 874, -1,874, 714, 872, -1,874, 872, 875, -1,875, 872, 873, -1, + 875, 873, 755, -1,755, 873, 756, -1,755, 756, 477, -1,477, 756, 478, -1,10, 711, + 710, -1,710, 711, 712, -1,710, 712, 876, -1,876, 712, 874, -1,876, 874, 877, -1,877, + 874, 875, -1,877, 875, 878, -1,878, 875, 755, -1,878, 755, 475, -1,475, 755, 476, -1, + 13, 709, 708, -1,708, 709, 710, -1,708, 710, 879, -1,879, 710, 876, -1,879, 876, + 880, -1,880, 876, 877, -1,880, 877, 754, -1,754, 877, 878, -1,754, 878, 474, -1,474, + 878, 475, -1,16, 707, 706, -1,706, 707, 708, -1,706, 708, 881, -1,881, 708, 879, -1, + 881, 879, 882, -1,882, 879, 880, -1,882, 880, 753, -1,753, 880, 754, -1,753, 754, + 472, -1,472, 754, 473, -1,19, 705, 704, -1,704, 705, 706, -1,704, 706, 883, -1,883, + 706, 881, -1,883, 881, 884, -1,884, 881, 882, -1,884, 882, 752, -1,752, 882, 753, -1, + 752, 753, 470, -1,470, 753, 471, -1,469, 468, 752, -1,752, 468, 826, -1,752, 826, + 884, -1,884, 826, 827, -1,884, 827, 883, -1,883, 827, 829, -1,883, 829, 704, -1,704, + 829, 831, -1,704, 831, 703, -1,342, 341, 832, -1,832, 341, 885, -1,832, 885, 831, -1, + 831, 885, 22, -1,831, 22, 703, -1,25, 836, 702, -1,702, 836, 835, -1,702, 835, 886, -1, + 886, 835, 834, -1,886, 834, 887, -1,887, 834, 833, -1,887, 833, 749, -1,749, 833, + 750, -1,749, 750, 463, -1,463, 750, 464, -1,28, 701, 700, -1,700, 701, 702, -1,700, + 702, 888, -1,888, 702, 886, -1,888, 886, 889, -1,889, 886, 887, -1,889, 887, 890, -1, + 890, 887, 749, -1,890, 749, 461, -1,461, 749, 462, -1,31, 699, 698, -1,698, 699, + 700, -1,698, 700, 891, -1,891, 700, 888, -1,891, 888, 892, -1,892, 888, 889, -1,892, + 889, 748, -1,748, 889, 890, -1,748, 890, 460, -1,460, 890, 461, -1,34, 697, 782, -1, + 782, 697, 698, -1,782, 698, 777, -1,777, 698, 891, -1,777, 891, 745, -1,745, 891, + 892, -1,745, 892, 743, -1,743, 892, 748, -1,743, 748, 458, -1,458, 748, 459, -1,893, + 37, 894, -1,451, 775, 774, -1,774, 775, 895, -1,774, 895, 784, -1,784, 895, 896, -1, + 784, 896, 783, -1,783, 896, 893, -1,783, 893, 782, -1,782, 893, 894, -1,782, 894, + 34, -1,897, 40, 898, -1,449, 747, 775, -1,775, 747, 899, -1,775, 899, 895, -1,895, + 899, 900, -1,895, 900, 896, -1,896, 900, 897, -1,896, 897, 893, -1,893, 897, 898, -1, + 893, 898, 37, -1,901, 43, 902, -1,448, 776, 747, -1,747, 776, 903, -1,747, 903, 899, -1, + 899, 903, 904, -1,899, 904, 900, -1,900, 904, 901, -1,900, 901, 897, -1,897, 901, + 902, -1,897, 902, 40, -1,446, 746, 776, -1,776, 746, 781, -1,776, 781, 903, -1,903, + 781, 780, -1,903, 780, 904, -1,904, 780, 785, -1,904, 785, 901, -1,901, 785, 44, -1, + 901, 44, 43, -1,905, 906, 907, -1,905, 333, 906, -1,906, 333, 908, -1,906, 908, 909, -1, + 910, 911, 912, -1,912, 911, 913, -1,908, 115, 909, -1,909, 115, 914, -1,909, 914, + 912, -1,912, 914, 314, -1,912, 314, 910, -1,915, 916, 917, -1,917, 916, 918, -1,911, + 302, 913, -1,913, 302, 919, -1,913, 919, 917, -1,917, 919, 121, -1,917, 121, 915, -1, + 920, 921, 922, -1,922, 921, 923, -1,916, 285, 918, -1,918, 285, 924, -1,918, 924, + 922, -1,922, 924, 127, -1,922, 127, 920, -1,925, 926, 927, -1,927, 926, 928, -1,921, + 268, 923, -1,923, 268, 929, -1,923, 929, 927, -1,927, 929, 133, -1,927, 133, 925, -1, + 930, 931, 932, -1,932, 931, 933, -1,926, 247, 928, -1,928, 247, 934, -1,928, 934, + 932, -1,932, 934, 139, -1,932, 139, 930, -1,94, 935, 936, -1,936, 935, 933, -1,936, + 933, 230, -1,230, 933, 931, -1,94, 937, 935, -1,935, 937, 938, -1,935, 938, 939, -1, + 157, 940, 941, -1,941, 940, 939, -1,941, 939, 97, -1,97, 939, 938, -1,157, 942, 940, -1, + 940, 942, 943, -1,940, 943, 944, -1,151, 945, 946, -1,946, 945, 944, -1,946, 944, + 154, -1,154, 944, 943, -1,151, 947, 945, -1,945, 947, 948, -1,945, 948, 949, -1,148, + 950, 951, -1,951, 950, 949, -1,951, 949, 146, -1,146, 949, 948, -1,148, 952, 950, -1, + 950, 952, 953, -1,950, 953, 954, -1,103, 955, 956, -1,956, 955, 954, -1,956, 954, + 379, -1,379, 954, 953, -1,103, 957, 955, -1,955, 957, 958, -1,955, 958, 959, -1,958, + 362, 959, -1,959, 362, 960, -1,959, 960, 961, -1,960, 109, 961, -1,961, 109, 962, -1, + 961, 962, 963, -1,962, 196, 963, -1,963, 196, 964, -1,963, 964, 907, -1,907, 964, + 112, -1,907, 112, 905, -1,963, 965, 961, -1,961, 965, 966, -1,961, 966, 959, -1,959, + 966, 967, -1,959, 967, 955, -1,955, 967, 968, -1,955, 968, 954, -1,954, 968, 969, -1, + 954, 969, 950, -1,950, 969, 970, -1,950, 970, 949, -1,949, 970, 971, -1,949, 971, + 945, -1,945, 971, 972, -1,945, 972, 944, -1,944, 972, 973, -1,944, 973, 940, -1,940, + 973, 974, -1,940, 974, 939, -1,939, 974, 975, -1,939, 975, 935, -1,935, 975, 976, -1, + 935, 976, 933, -1,933, 976, 977, -1,933, 977, 932, -1,932, 977, 978, -1,932, 978, + 928, -1,928, 978, 979, -1,928, 979, 927, -1,927, 979, 980, -1,927, 980, 923, -1,923, + 980, 981, -1,923, 981, 922, -1,922, 981, 982, -1,922, 982, 918, -1,918, 982, 983, -1, + 918, 983, 917, -1,917, 983, 984, -1,917, 984, 913, -1,913, 984, 985, -1,913, 985, + 912, -1,912, 985, 986, -1,912, 986, 909, -1,909, 986, 987, -1,909, 987, 906, -1,906, + 987, 988, -1,906, 988, 907, -1,907, 988, 989, -1,907, 989, 963, -1,963, 989, 965, -1, + 965, 990, 966, -1,966, 990, 991, -1,966, 991, 967, -1,967, 991, 992, -1,967, 992, + 968, -1,968, 992, 993, -1,968, 993, 969, -1,969, 993, 994, -1,969, 994, 970, -1,970, + 994, 995, -1,970, 995, 971, -1,971, 995, 996, -1,971, 996, 972, -1,972, 996, 997, -1, + 972, 997, 973, -1,973, 997, 998, -1,973, 998, 974, -1,974, 998, 999, -1,974, 999, + 975, -1,975, 999, 1000, -1,975, 1000, 976, -1,976, 1000, 1001, -1,976, 1001, 977, -1, + 977, 1001, 1002, -1,977, 1002, 978, -1,978, 1002, 1003, -1,978, 1003, 979, -1,979, + 1003, 1004, -1,979, 1004, 980, -1,980, 1004, 1005, -1,980, 1005, 981, -1,981, 1005, + 1006, -1,981, 1006, 982, -1,982, 1006, 1007, -1,982, 1007, 983, -1,983, 1007, 1008, -1, + 983, 1008, 984, -1,984, 1008, 1009, -1,984, 1009, 985, -1,985, 1009, 1010, -1,985, + 1010, 986, -1,986, 1010, 1011, -1,986, 1011, 987, -1,987, 1011, 1012, -1,987, 1012, + 988, -1,988, 1012, 1013, -1,988, 1013, 989, -1,989, 1013, 1014, -1,989, 1014, 965, -1, + 965, 1014, 990, -1,990, 1015, 991, -1,991, 1015, 1016, -1,991, 1016, 992, -1,992, + 1016, 1017, -1,992, 1017, 993, -1,993, 1017, 1018, -1,993, 1018, 994, -1,994, 1018, + 1019, -1,994, 1019, 995, -1,995, 1019, 1020, -1,995, 1020, 996, -1,996, 1020, 1021, -1, + 996, 1021, 997, -1,997, 1021, 1022, -1,997, 1022, 998, -1,998, 1022, 1023, -1,998, + 1023, 999, -1,999, 1023, 1024, -1,999, 1024, 1000, -1,1000, 1024, 1025, -1,1000, + 1025, 1001, -1,1001, 1025, 1026, -1,1001, 1026, 1002, -1,1002, 1026, 1027, -1,1002, + 1027, 1003, -1,1003, 1027, 1028, -1,1003, 1028, 1004, -1,1004, 1028, 1029, -1,1004, + 1029, 1005, -1,1005, 1029, 1030, -1,1005, 1030, 1006, -1,1006, 1030, 1031, -1,1006, + 1031, 1007, -1,1007, 1031, 1032, -1,1007, 1032, 1008, -1,1008, 1032, 1033, -1,1008, + 1033, 1009, -1,1009, 1033, 1034, -1,1009, 1034, 1010, -1,1010, 1034, 1035, -1,1010, + 1035, 1011, -1,1011, 1035, 1036, -1,1011, 1036, 1012, -1,1012, 1036, 1037, -1,1012, + 1037, 1013, -1,1013, 1037, 1038, -1,1013, 1038, 1014, -1,1014, 1038, 1039, -1,1014, + 1039, 990, -1,990, 1039, 1015, -1,1015, 1040, 1016, -1,1016, 1040, 1041, -1,1016, + 1041, 1017, -1,1017, 1041, 1042, -1,1017, 1042, 1018, -1,1018, 1042, 1043, -1,1018, + 1043, 1019, -1,1019, 1043, 1044, -1,1019, 1044, 1020, -1,1020, 1044, 1045, -1,1020, + 1045, 1021, -1,1021, 1045, 1046, -1,1021, 1046, 1022, -1,1022, 1046, 1047, -1,1022, + 1047, 1023, -1,1023, 1047, 1048, -1,1023, 1048, 1024, -1,1024, 1048, 1049, -1,1024, + 1049, 1025, -1,1025, 1049, 1050, -1,1025, 1050, 1026, -1,1026, 1050, 1051, -1,1026, + 1051, 1027, -1,1027, 1051, 1052, -1,1027, 1052, 1028, -1,1028, 1052, 1053, -1,1028, + 1053, 1029, -1,1029, 1053, 1054, -1,1029, 1054, 1030, -1,1030, 1054, 1055, -1,1030, + 1055, 1031, -1,1031, 1055, 1056, -1,1031, 1056, 1032, -1,1032, 1056, 1057, -1,1032, + 1057, 1033, -1,1033, 1057, 1058, -1,1033, 1058, 1034, -1,1034, 1058, 1059, -1,1034, + 1059, 1035, -1,1035, 1059, 1060, -1,1035, 1060, 1036, -1,1036, 1060, 1061, -1,1036, + 1061, 1037, -1,1037, 1061, 1062, -1,1037, 1062, 1038, -1,1038, 1062, 1063, -1,1038, + 1063, 1039, -1,1039, 1063, 1064, -1,1039, 1064, 1015, -1,1015, 1064, 1040, -1,1040, + 1065, 1041, -1,1041, 1065, 1066, -1,1041, 1066, 1042, -1,1042, 1066, 1067, -1,1042, + 1067, 1043, -1,1043, 1067, 1068, -1,1043, 1068, 1044, -1,1044, 1068, 1069, -1,1044, + 1069, 1045, -1,1045, 1069, 1070, -1,1045, 1070, 1046, -1,1046, 1070, 1071, -1,1046, + 1071, 1047, -1,1047, 1071, 1072, -1,1047, 1072, 1048, -1,1048, 1072, 1073, -1,1048, + 1073, 1049, -1,1049, 1073, 1074, -1,1049, 1074, 1050, -1,1050, 1074, 1075, -1,1050, + 1075, 1051, -1,1051, 1075, 1076, -1,1051, 1076, 1052, -1,1052, 1076, 1077, -1,1052, + 1077, 1053, -1,1053, 1077, 1078, -1,1053, 1078, 1054, -1,1054, 1078, 1079, -1,1054, + 1079, 1055, -1,1055, 1079, 1080, -1,1055, 1080, 1056, -1,1056, 1080, 1081, -1,1056, + 1081, 1057, -1,1057, 1081, 1082, -1,1057, 1082, 1058, -1,1058, 1082, 1083, -1,1058, + 1083, 1059, -1,1059, 1083, 1084, -1,1059, 1084, 1060, -1,1060, 1084, 1085, -1,1060, + 1085, 1061, -1,1061, 1085, 1086, -1,1061, 1086, 1062, -1,1062, 1086, 1087, -1,1062, + 1087, 1063, -1,1063, 1087, 1088, -1,1063, 1088, 1064, -1,1064, 1088, 1089, -1,1064, + 1089, 1040, -1,1040, 1089, 1065, -1,0, 0, 1076, -1,1076, 0, 0, -1,1076, 0, 1077, -1, + 1077, 0, 0, -1,1077, 0, 1078, -1,1078, 0, 0, -1,1078, 0, 1079, -1,1079, 0, 0, -1, + 1079, 0, 1080, -1,1080, 0, 0, -1,1080, 0, 1081, -1,1081, 0, 0, -1,1081, 0, 1082, -1, + 1082, 0, 0, -1,1082, 0, 1083, -1,1083, 0, 0, -1,1083, 0, 1084, -1,1084, 0, 0, -1, + 1084, 0, 1085, -1,1085, 0, 0, -1,1085, 0, 1086, -1,1086, 0, 0, -1,1086, 0, 1087, -1, + 1087, 0, 0, -1,1087, 0, 1088, -1,1088, 0, 0, -1,1088, 0, 1089, -1,1089, 0, 0, -1, + 1089, 0, 1065, -1,1065, 0, 0, -1,1065, 0, 1066, -1,1066, 0, 0, -1,1066, 0, 1067, -1, + 1067, 0, 0, -1,1067, 0, 1068, -1,1068, 0, 0, -1,1068, 0, 1069, -1,1069, 0, 0, -1, + 1069, 0, 1070, -1,1070, 0, 0, -1,1070, 0, 1071, -1,1071, 0, 0, -1,1071, 0, 1072, -1, + 1072, 0, 0, -1,1072, 0, 1073, -1,1073, 0, 0, -1,1073, 0, 1074, -1,1074, 0, 0, -1, + 1074, 0, 1075, -1,1075, 0, 0, -1,1075, 0, 1076, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, + 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1, + 481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, 481, -1,481, 481, + 481, -1,481, 481, 481, -1,1090, 1091, 1092, -1,1092, 1091, 1093, -1,1092, 1093, 1094, -1, + 1093, 1095, 1094, -1,1094, 1095, 1096, -1,1094, 1096, 1097, -1,1096, 1098, 1097, -1, + 1097, 1098, 1099, -1,1097, 1099, 1100, -1,1100, 1099, 1101, -1,1100, 1101, 1102, -1, + 1101, 1103, 1102, -1,1102, 1103, 1104, -1,1102, 1104, 1105, -1,1104, 1106, 1105, -1, + 1105, 1106, 1107, -1,1105, 1107, 1108, -1,1108, 1107, 1109, -1,1108, 1109, 1110, -1, + 1109, 1111, 1110, -1,1110, 1111, 1112, -1,1110, 1112, 1113, -1,1113, 1112, 1114, -1, + 1113, 1114, 1115, -1,1114, 1116, 1115, -1,1115, 1116, 1117, -1,1115, 1117, 1118, -1, + 1117, 1119, 1118, -1,1118, 1119, 1120, -1,1118, 1120, 1121, -1,1121, 1120, 1122, -1, + 1121, 1122, 1123, -1,1122, 1124, 1123, -1,1123, 1124, 1125, -1,1123, 1125, 1126, -1, + 1126, 1125, 1127, -1,1126, 1127, 1128, -1,1127, 1129, 1128, -1,1128, 1129, 1130, -1, + 1128, 1130, 1131, -1,1130, 1132, 1131, -1,1131, 1132, 1133, -1,1131, 1133, 1134, -1, + 1134, 1133, 1135, -1,1134, 1135, 1136, -1,1135, 1137, 1136, -1,1136, 1137, 1138, -1, + 1136, 1138, 1139, -1,1139, 1138, 1140, -1,1139, 1140, 1141, -1,1140, 1142, 1141, -1, + 1141, 1142, 1143, -1,1141, 1143, 1144, -1,1143, 1145, 1144, -1,1144, 1145, 1146, -1, + 1144, 1146, 1147, -1,1147, 1146, 1148, -1,1147, 1148, 1149, -1,1148, 1150, 1149, -1, + 1149, 1150, 1151, -1,1149, 1151, 1152, -1,1152, 1151, 1153, -1,1152, 1153, 1154, -1, + 1153, 1155, 1154, -1,1154, 1155, 1156, -1,1154, 1156, 1157, -1,1156, 1158, 1157, -1, + 1157, 1158, 1159, -1,1157, 1159, 1160, -1,1160, 1159, 1161, -1,1160, 1161, 1162, -1, + 1161, 1163, 1162, -1,1162, 1163, 1164, -1,1162, 1164, 1165, -1,1165, 1164, 1166, -1, + 1165, 1166, 1090, -1,1090, 1166, 1167, -1,1090, 1167, 1091, -1,1162, 1168, 1160, -1, + 1160, 1168, 1169, -1,1160, 1169, 1157, -1,1157, 1169, 1170, -1,1157, 1170, 1154, -1, + 1154, 1170, 1171, -1,1154, 1171, 1152, -1,1152, 1171, 1172, -1,1152, 1172, 1149, -1, + 1149, 1172, 1173, -1,1149, 1173, 1147, -1,1147, 1173, 1174, -1,1147, 1174, 1144, -1, + 1144, 1174, 1175, -1,1144, 1175, 1141, -1,1141, 1175, 1176, -1,1141, 1176, 1139, -1, + 1139, 1176, 1177, -1,1139, 1177, 1136, -1,1136, 1177, 1178, -1,1136, 1178, 1134, -1, + 1134, 1178, 1179, -1,1134, 1179, 1131, -1,1131, 1179, 1180, -1,1131, 1180, 1128, -1, + 1128, 1180, 1181, -1,1128, 1181, 1126, -1,1126, 1181, 1182, -1,1126, 1182, 1123, -1, + 1123, 1182, 1183, -1,1123, 1183, 1121, -1,1121, 1183, 1184, -1,1121, 1184, 1118, -1, + 1118, 1184, 1185, -1,1118, 1185, 1115, -1,1115, 1185, 1186, -1,1115, 1186, 1113, -1, + 1113, 1186, 1187, -1,1113, 1187, 1110, -1,1110, 1187, 1188, -1,1110, 1188, 1108, -1, + 1108, 1188, 1189, -1,1108, 1189, 1105, -1,1105, 1189, 1190, -1,1105, 1190, 1102, -1, + 1102, 1190, 1191, -1,1102, 1191, 1100, -1,1100, 1191, 1192, -1,1100, 1192, 1097, -1, + 1097, 1192, 1193, -1,1097, 1193, 1094, -1,1094, 1193, 1194, -1,1094, 1194, 1092, -1, + 1092, 1194, 1195, -1,1092, 1195, 1090, -1,1090, 1195, 1196, -1,1090, 1196, 1165, -1, + 1165, 1196, 1197, -1,1165, 1197, 1162, -1,1162, 1197, 1168, -1,1168, 1198, 1169, -1, + 1169, 1198, 1199, -1,1169, 1199, 1170, -1,1170, 1199, 1200, -1,1170, 1200, 1171, -1, + 1171, 1200, 1201, -1,1171, 1201, 1172, -1,1172, 1201, 1202, -1,1172, 1202, 1173, -1, + 1173, 1202, 1203, -1,1173, 1203, 1174, -1,1174, 1203, 1204, -1,1174, 1204, 1175, -1, + 1175, 1204, 1205, -1,1175, 1205, 1176, -1,1176, 1205, 1206, -1,1176, 1206, 1177, -1, + 1177, 1206, 1207, -1,1177, 1207, 1178, -1,1178, 1207, 1208, -1,1178, 1208, 1179, -1, + 1179, 1208, 1209, -1,1179, 1209, 1180, -1,1180, 1209, 1210, -1,1180, 1210, 1181, -1, + 1181, 1210, 1211, -1,1181, 1211, 1182, -1,1182, 1211, 1212, -1,1182, 1212, 1183, -1, + 1183, 1212, 1213, -1,1183, 1213, 1184, -1,1184, 1213, 1214, -1,1184, 1214, 1185, -1, + 1185, 1214, 1215, -1,1185, 1215, 1186, -1,1186, 1215, 1216, -1,1186, 1216, 1187, -1, + 1187, 1216, 1217, -1,1187, 1217, 1188, -1,1188, 1217, 1218, -1,1188, 1218, 1189, -1, + 1189, 1218, 1219, -1,1189, 1219, 1190, -1,1190, 1219, 1220, -1,1190, 1220, 1191, -1, + 1191, 1220, 1221, -1,1191, 1221, 1192, -1,1192, 1221, 1222, -1,1192, 1222, 1193, -1, + 1193, 1222, 1223, -1,1193, 1223, 1194, -1,1194, 1223, 1224, -1,1194, 1224, 1195, -1, + 1195, 1224, 1225, -1,1195, 1225, 1196, -1,1196, 1225, 1226, -1,1196, 1226, 1197, -1, + 1197, 1226, 1227, -1,1197, 1227, 1168, -1,1168, 1227, 1198, -1,1198, 1228, 1199, -1, + 1199, 1228, 1229, -1,1199, 1229, 1200, -1,1200, 1229, 1230, -1,1200, 1230, 1201, -1, + 1201, 1230, 1231, -1,1201, 1231, 1202, -1,1202, 1231, 1232, -1,1202, 1232, 1203, -1, + 1203, 1232, 1233, -1,1203, 1233, 1204, -1,1204, 1233, 1234, -1,1204, 1234, 1205, -1, + 1205, 1234, 1235, -1,1205, 1235, 1206, -1,1206, 1235, 1236, -1,1206, 1236, 1207, -1, + 1207, 1236, 1237, -1,1207, 1237, 1208, -1,1208, 1237, 1238, -1,1208, 1238, 1209, -1, + 1209, 1238, 1239, -1,1209, 1239, 1210, -1,1210, 1239, 1240, -1,1210, 1240, 1211, -1, + 1211, 1240, 1241, -1,1211, 1241, 1212, -1,1212, 1241, 1242, -1,1212, 1242, 1213, -1, + 1213, 1242, 1243, -1,1213, 1243, 1214, -1,1214, 1243, 1244, -1,1214, 1244, 1215, -1, + 1215, 1244, 1245, -1,1215, 1245, 1216, -1,1216, 1245, 1246, -1,1216, 1246, 1217, -1, + 1217, 1246, 1247, -1,1217, 1247, 1218, -1,1218, 1247, 1248, -1,1218, 1248, 1219, -1, + 1219, 1248, 1249, -1,1219, 1249, 1220, -1,1220, 1249, 1250, -1,1220, 1250, 1221, -1, + 1221, 1250, 1251, -1,1221, 1251, 1222, -1,1222, 1251, 1252, -1,1222, 1252, 1223, -1, + 1223, 1252, 1253, -1,1223, 1253, 1224, -1,1224, 1253, 1254, -1,1224, 1254, 1225, -1, + 1225, 1254, 1255, -1,1225, 1255, 1226, -1,1226, 1255, 1256, -1,1226, 1256, 1227, -1, + 1227, 1256, 1257, -1,1227, 1257, 1198, -1,1198, 1257, 1228, -1,1228, 1258, 1229, -1, + 1229, 1258, 1259, -1,1229, 1259, 1230, -1,1230, 1259, 1260, -1,1230, 1260, 1231, -1, + 1231, 1260, 1261, -1,1231, 1261, 1232, -1,1232, 1261, 1262, -1,1232, 1262, 1233, -1, + 1233, 1262, 1263, -1,1233, 1263, 1234, -1,1234, 1263, 1264, -1,1234, 1264, 1235, -1, + 1235, 1264, 1265, -1,1235, 1265, 1236, -1,1236, 1265, 1266, -1,1236, 1266, 1237, -1, + 1237, 1266, 1267, -1,1237, 1267, 1238, -1,1238, 1267, 1268, -1,1238, 1268, 1239, -1, + 1239, 1268, 1269, -1,1239, 1269, 1240, -1,1240, 1269, 1270, -1,1240, 1270, 1241, -1, + 1241, 1270, 1271, -1,1241, 1271, 1242, -1,1242, 1271, 1272, -1,1242, 1272, 1243, -1, + 1243, 1272, 1273, -1,1243, 1273, 1244, -1,1244, 1273, 1274, -1,1244, 1274, 1245, -1, + 1245, 1274, 1275, -1,1245, 1275, 1246, -1,1246, 1275, 1276, -1,1246, 1276, 1247, -1, + 1247, 1276, 1277, -1,1247, 1277, 1248, -1,1248, 1277, 1278, -1,1248, 1278, 1249, -1, + 1249, 1278, 1279, -1,1249, 1279, 1250, -1,1250, 1279, 1280, -1,1250, 1280, 1251, -1, + 1251, 1280, 1281, -1,1251, 1281, 1252, -1,1252, 1281, 1282, -1,1252, 1282, 1253, -1, + 1253, 1282, 1283, -1,1253, 1283, 1254, -1,1254, 1283, 1284, -1,1254, 1284, 1255, -1, + 1255, 1284, 1285, -1,1255, 1285, 1256, -1,1256, 1285, 1286, -1,1256, 1286, 1257, -1, + 1257, 1286, 1287, -1,1257, 1287, 1228, -1,1228, 1287, 1258, -1,1258, 481, 1259, -1, + 1259, 481, 481, -1,1259, 481, 1260, -1,1260, 481, 481, -1,1260, 481, 1261, -1,1261, + 481, 481, -1,1261, 481, 1262, -1,1262, 481, 481, -1,1262, 481, 1263, -1,1263, 481, + 481, -1,1263, 481, 1264, -1,1264, 481, 481, -1,1264, 481, 1265, -1,1265, 481, 481, -1, + 1265, 481, 1266, -1,1266, 481, 481, -1,1266, 481, 1267, -1,1267, 481, 481, -1,1267, + 481, 1268, -1,1268, 481, 481, -1,1268, 481, 1269, -1,1269, 481, 481, -1,1269, 481, + 1270, -1,1270, 481, 481, -1,1270, 481, 1271, -1,1271, 481, 481, -1,1271, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1273, -1,1273, 481, 481, -1,1273, 481, 1274, -1,1274, + 481, 481, -1,1274, 481, 1275, -1,1275, 481, 481, -1,1275, 481, 1276, -1,1276, 481, + 481, -1,1276, 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1278, -1,1278, 481, 481, -1, + 1278, 481, 1279, -1,1279, 481, 481, -1,1279, 481, 1280, -1,1280, 481, 481, -1,1280, + 481, 1281, -1,1281, 481, 481, -1,1281, 481, 1282, -1,1282, 481, 481, -1,1282, 481, + 1283, -1,1283, 481, 481, -1,1283, 481, 1284, -1,1284, 481, 481, -1,1284, 481, 1285, -1, + 1285, 481, 481, -1,1285, 481, 1286, -1,1286, 481, 481, -1,1286, 481, 1287, -1,1287, + 481, 481, -1,1287, 481, 1258, -1,1258, 481, 481, -1,1288, 1289, 1126, -1,1288, 1124, + 1289, -1,1289, 1124, 1290, -1,1289, 1290, 1291, -1,1290, 1120, 1291, -1,1291, 1120, + 1292, -1,1291, 1292, 1293, -1,1292, 1117, 1293, -1,1293, 1117, 1294, -1,1293, 1294, + 1113, -1,1294, 1114, 1113, -1,1113, 1114, 1295, -1,1113, 1295, 1296, -1,1295, 1111, + 1296, -1,1296, 1111, 1297, -1,1296, 1297, 1298, -1,1297, 1107, 1298, -1,1298, 1107, + 1299, -1,1298, 1299, 1300, -1,1299, 1104, 1300, -1,1300, 1104, 1301, -1,1300, 1301, + 1100, -1,1301, 1101, 1100, -1,1100, 1101, 1302, -1,1100, 1302, 1303, -1,1302, 1098, + 1303, -1,1303, 1098, 1304, -1,1303, 1304, 1305, -1,1304, 1095, 1305, -1,1305, 1095, + 1306, -1,1305, 1306, 1307, -1,1306, 1091, 1307, -1,1307, 1091, 1308, -1,1307, 1308, + 1165, -1,1308, 1166, 1165, -1,1165, 1166, 1309, -1,1165, 1309, 1310, -1,1309, 1163, + 1310, -1,1310, 1163, 1311, -1,1310, 1311, 1312, -1,1311, 1159, 1312, -1,1312, 1159, + 1313, -1,1312, 1313, 1314, -1,1313, 1156, 1314, -1,1314, 1156, 1315, -1,1314, 1315, + 1152, -1,1315, 1153, 1152, -1,1152, 1153, 1316, -1,1152, 1316, 1317, -1,1316, 1150, + 1317, -1,1317, 1150, 1318, -1,1317, 1318, 1319, -1,1318, 1146, 1319, -1,1319, 1146, + 1320, -1,1319, 1320, 1321, -1,1320, 1143, 1321, -1,1321, 1143, 1322, -1,1321, 1322, + 1139, -1,1322, 1140, 1139, -1,1139, 1140, 1323, -1,1139, 1323, 1324, -1,1323, 1137, + 1324, -1,1324, 1137, 1325, -1,1324, 1325, 1326, -1,1325, 1133, 1326, -1,1326, 1133, + 1327, -1,1326, 1327, 1328, -1,1327, 1130, 1328, -1,1328, 1130, 1329, -1,1328, 1329, + 1126, -1,1126, 1329, 1127, -1,1126, 1127, 1288, -1,1328, 1330, 1326, -1,1326, 1330, + 1331, -1,1326, 1331, 1324, -1,1324, 1331, 1332, -1,1324, 1332, 1139, -1,1139, 1332, + 1177, -1,1139, 1177, 1321, -1,1321, 1177, 1333, -1,1321, 1333, 1319, -1,1319, 1333, + 1334, -1,1319, 1334, 1317, -1,1317, 1334, 1335, -1,1317, 1335, 1152, -1,1152, 1335, + 1172, -1,1152, 1172, 1314, -1,1314, 1172, 1336, -1,1314, 1336, 1312, -1,1312, 1336, + 1337, -1,1312, 1337, 1310, -1,1310, 1337, 1338, -1,1310, 1338, 1165, -1,1165, 1338, + 1197, -1,1165, 1197, 1307, -1,1307, 1197, 1339, -1,1307, 1339, 1305, -1,1305, 1339, + 1340, -1,1305, 1340, 1303, -1,1303, 1340, 1341, -1,1303, 1341, 1100, -1,1100, 1341, + 1192, -1,1100, 1192, 1300, -1,1300, 1192, 1342, -1,1300, 1342, 1298, -1,1298, 1342, + 1343, -1,1298, 1343, 1296, -1,1296, 1343, 1344, -1,1296, 1344, 1113, -1,1113, 1344, + 1187, -1,1113, 1187, 1293, -1,1293, 1187, 1345, -1,1293, 1345, 1291, -1,1291, 1345, + 1346, -1,1291, 1346, 1289, -1,1289, 1346, 1347, -1,1289, 1347, 1126, -1,1126, 1347, + 1182, -1,1126, 1182, 1328, -1,1328, 1182, 1330, -1,1330, 1348, 1331, -1,1331, 1348, + 1349, -1,1331, 1349, 1332, -1,1332, 1349, 1350, -1,1332, 1350, 1177, -1,1177, 1350, + 1207, -1,1177, 1207, 1333, -1,1333, 1207, 1351, -1,1333, 1351, 1334, -1,1334, 1351, + 1352, -1,1334, 1352, 1335, -1,1335, 1352, 1353, -1,1335, 1353, 1172, -1,1172, 1353, + 1202, -1,1172, 1202, 1336, -1,1336, 1202, 1354, -1,1336, 1354, 1337, -1,1337, 1354, + 1355, -1,1337, 1355, 1338, -1,1338, 1355, 1356, -1,1338, 1356, 1197, -1,1197, 1356, + 1227, -1,1197, 1227, 1339, -1,1339, 1227, 1357, -1,1339, 1357, 1340, -1,1340, 1357, + 1358, -1,1340, 1358, 1341, -1,1341, 1358, 1359, -1,1341, 1359, 1192, -1,1192, 1359, + 1222, -1,1192, 1222, 1342, -1,1342, 1222, 1360, -1,1342, 1360, 1343, -1,1343, 1360, + 1361, -1,1343, 1361, 1344, -1,1344, 1361, 1362, -1,1344, 1362, 1187, -1,1187, 1362, + 1217, -1,1187, 1217, 1345, -1,1345, 1217, 1363, -1,1345, 1363, 1346, -1,1346, 1363, + 1364, -1,1346, 1364, 1347, -1,1347, 1364, 1365, -1,1347, 1365, 1182, -1,1182, 1365, + 1212, -1,1182, 1212, 1330, -1,1330, 1212, 1348, -1,1348, 1366, 1349, -1,1349, 1366, + 1367, -1,1349, 1367, 1350, -1,1350, 1367, 1368, -1,1350, 1368, 1207, -1,1207, 1368, + 1237, -1,1207, 1237, 1351, -1,1351, 1237, 1369, -1,1351, 1369, 1352, -1,1352, 1369, + 1370, -1,1352, 1370, 1353, -1,1353, 1370, 1371, -1,1353, 1371, 1202, -1,1202, 1371, + 1232, -1,1202, 1232, 1354, -1,1354, 1232, 1372, -1,1354, 1372, 1355, -1,1355, 1372, + 1373, -1,1355, 1373, 1356, -1,1356, 1373, 1374, -1,1356, 1374, 1227, -1,1227, 1374, + 1257, -1,1227, 1257, 1357, -1,1357, 1257, 1375, -1,1357, 1375, 1358, -1,1358, 1375, + 1376, -1,1358, 1376, 1359, -1,1359, 1376, 1377, -1,1359, 1377, 1222, -1,1222, 1377, + 1252, -1,1222, 1252, 1360, -1,1360, 1252, 1378, -1,1360, 1378, 1361, -1,1361, 1378, + 1379, -1,1361, 1379, 1362, -1,1362, 1379, 1380, -1,1362, 1380, 1217, -1,1217, 1380, + 1247, -1,1217, 1247, 1363, -1,1363, 1247, 1381, -1,1363, 1381, 1364, -1,1364, 1381, + 1382, -1,1364, 1382, 1365, -1,1365, 1382, 1383, -1,1365, 1383, 1212, -1,1212, 1383, + 1242, -1,1212, 1242, 1348, -1,1348, 1242, 1366, -1,1366, 1384, 1367, -1,1367, 1384, + 1385, -1,1367, 1385, 1368, -1,1368, 1385, 1386, -1,1368, 1386, 1237, -1,1237, 1386, + 1267, -1,1237, 1267, 1369, -1,1369, 1267, 1387, -1,1369, 1387, 1370, -1,1370, 1387, + 1388, -1,1370, 1388, 1371, -1,1371, 1388, 1389, -1,1371, 1389, 1232, -1,1232, 1389, + 1262, -1,1232, 1262, 1372, -1,1372, 1262, 1390, -1,1372, 1390, 1373, -1,1373, 1390, + 1391, -1,1373, 1391, 1374, -1,1374, 1391, 1392, -1,1374, 1392, 1257, -1,1257, 1392, + 1287, -1,1257, 1287, 1375, -1,1375, 1287, 1393, -1,1375, 1393, 1376, -1,1376, 1393, + 1394, -1,1376, 1394, 1377, -1,1377, 1394, 1395, -1,1377, 1395, 1252, -1,1252, 1395, + 1282, -1,1252, 1282, 1378, -1,1378, 1282, 1396, -1,1378, 1396, 1379, -1,1379, 1396, + 1397, -1,1379, 1397, 1380, -1,1380, 1397, 1398, -1,1380, 1398, 1247, -1,1247, 1398, + 1277, -1,1247, 1277, 1381, -1,1381, 1277, 1399, -1,1381, 1399, 1382, -1,1382, 1399, + 1400, -1,1382, 1400, 1383, -1,1383, 1400, 1401, -1,1383, 1401, 1242, -1,1242, 1401, + 1272, -1,1242, 1272, 1366, -1,1366, 1272, 1384, -1,1384, 481, 1385, -1,1385, 481, + 481, -1,1385, 481, 1386, -1,1386, 481, 481, -1,1386, 481, 1267, -1,1267, 481, 481, -1, + 1267, 481, 1387, -1,1387, 481, 481, -1,1387, 481, 1388, -1,1388, 481, 481, -1,1388, + 481, 1389, -1,1389, 481, 481, -1,1389, 481, 1262, -1,1262, 481, 481, -1,1262, 481, + 1390, -1,1390, 481, 481, -1,1390, 481, 1391, -1,1391, 481, 481, -1,1391, 481, 1392, -1, + 1392, 481, 481, -1,1392, 481, 1287, -1,1287, 481, 481, -1,1287, 481, 1393, -1,1393, + 481, 481, -1,1393, 481, 1394, -1,1394, 481, 481, -1,1394, 481, 1395, -1,1395, 481, + 481, -1,1395, 481, 1282, -1,1282, 481, 481, -1,1282, 481, 1396, -1,1396, 481, 481, -1, + 1396, 481, 1397, -1,1397, 481, 481, -1,1397, 481, 1398, -1,1398, 481, 481, -1,1398, + 481, 1277, -1,1277, 481, 481, -1,1277, 481, 1399, -1,1399, 481, 481, -1,1399, 481, + 1400, -1,1400, 481, 481, -1,1400, 481, 1401, -1,1401, 481, 481, -1,1401, 481, 1272, -1, + 1272, 481, 481, -1,1272, 481, 1384, -1,1384, 481, 481, -1 + ] + } + } + ] +} diff --git a/data/models/mekabot-convex/environment.original1m.wrl b/data/models/mekabot-convex/environment.original1m.wrl new file mode 100644 index 0000000..53583a8 --- /dev/null +++ b/data/models/mekabot-convex/environment.original1m.wrl @@ -0,0 +1,200 @@ +#VRML V2.0 utf8 + +DEF counter Transform{ + translation 0.0 0.0 0.0 #-0.110 -0.13 0.188 + children[ + # table upper surface + DEF tableSurfaceUp Transform{ + translation 0.0 0.0 0.0 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.40 1.00 0.05 + } + } + ] + } + # table lower surface + DEF tableSurfaceLow Transform{ + translation 0.1475 0.0 -0.24 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.455 1.00 0.05 + } + } + ] + } + # table front wall (towards guests) + DEF tableWallFront Transform{ + translation -0.105 0.0 -0.5725 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.00 1.095 + } + } + ] + } + # table wall block upper<->lower surface right + DEF tableWallBlockRight Transform{ + translation 0.175 0.475 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table wall block upper<->lower surface left + DEF tableWallBlockLeft Transform{ + translation 0.175 -0.475 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table back wall (towards robot) + DEF tableWallBack Transform{ + translation 0.35 0.0 -0.6925 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.00 0.855 + } + } + ] + } + # table back crossbar + DEF tableCrossBarBack Transform{ + translation 0.40 0.0 -0.45 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.05 1.00 0.05 + } + } + ] + } + # safety switch + DEF safetySwitch Transform{ + translation 0.3325 0.425 -0.1675 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.2 0.2 + } + } + geometry Box { + size 0.085 0.15 0.095 + } + } + ] + } + + # robot<->table side block left + DEF robotTableBlockLeft Transform{ + translation 0.675 -0.108 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.6 0.05 0.05 + } + } + ] + } + # robot<->table side block right + DEF robotTableBlockRight Transform{ + translation 0.675 0.158 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.6 0.05 0.05 + } + } + ] + } + # robot base lower part + DEF robotBaseBlock Transform{ + translation 0.77625 0.025 -0.4225 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.1525 0.216 0.105 + } + } + ] + } + # robot base upper part + DEF robotBaseSurface Transform{ + translation 0.77625 0.025 -0.365 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.35 0.24 0.01 + } + } + ] + } + ] +} diff --git a/data/models/mekabot-convex/environment.rightHeight.wrl b/data/models/mekabot-convex/environment.rightHeight.wrl new file mode 100644 index 0000000..f4c4047 --- /dev/null +++ b/data/models/mekabot-convex/environment.rightHeight.wrl @@ -0,0 +1,216 @@ +#VRML V2.0 utf8 + +DEF counter Transform{ + translation 0.0 0.0 0.0 #-0.110 -0.13 0.188 + children[ + # table upper surface + DEF tableSurfaceUp Transform{ + translation 0.0 0.0 0.0 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.40 1.04 0.05 + } + } + ] + } + # table second upper surface (higher) + DEF tableSurfaceUp2 Transform{ + translation -0.065 0.0 0.05 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.27 1.04 0.05 + } + } + ] + } + # table lower surface + DEF tableSurfaceLow Transform{ + translation 0.1575 0.0 -0.24 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.475 1.04 0.05 + } + } + ] + } + # table front wall (towards guests) + DEF tableWallFront Transform{ + translation -0.105 0.0 -0.5725 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.04 1.095 + } + } + ] + } + # table wall block upper<->lower surface right + DEF tableWallBlockRight Transform{ + translation 0.175 0.495 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table wall block upper<->lower surface left + DEF tableWallBlockLeft Transform{ + translation 0.175 -0.495 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table back wall (towards robot) + DEF tableWallBack Transform{ + translation 0.37 0.0 -0.6925 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.04 0.855 + } + } + ] + } + # table back crossbar + DEF tableCrossBarBack Transform{ + translation 0.42 0.0 -0.45 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.05 1.04 0.05 + } + } + ] + } + # safety switch + DEF safetySwitch Transform{ + translation 0.3425 0.435 -0.1625 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.2 0.2 + } + } + geometry Box { + size 0.105 0.17 0.105 + } + } + ] + } + + # robot<->table side block left + DEF robotTableBlockLeft Transform{ + translation 0.685 -0.108 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.58 0.05 0.05 + } + } + ] + } + # robot<->table side block right + DEF robotTableBlockRight Transform{ + translation 0.685 0.158 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.58 0.05 0.05 + } + } + ] + } + # robot base lower part + DEF robotBaseBlock Transform{ + translation 0.77625 0.025 -0.4225 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.1525 0.216 0.105 + } + } + ] + } + # robot base upper part + DEF robotBaseSurface Transform{ + translation 0.77625 0.025 -0.365 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.35 0.24 0.01 + } + } + ] + } + ] +} diff --git a/data/models/mekabot-convex/environment.wrl b/data/models/mekabot-convex/environment.wrl new file mode 100644 index 0000000..d9f2276 --- /dev/null +++ b/data/models/mekabot-convex/environment.wrl @@ -0,0 +1,251 @@ +#VRML V2.0 utf8 + +# a bit larger (side and front) +# 40cm shorter + +DEF counter Transform{ + translation 0.0 0.0 0.0 #-0.110 -0.13 0.188 + children[ + # house wall on the left side of robot + DEF houseWallLeft Transform{ + translation 0.3 -0.545 -0.1 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 1.10 0.05 1.30 + } + } + ] + } + # table upper surface + DEF tableSurfaceUp Transform{ + translation 0.0 0.0 0.0 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.40 1.04 0.05 + } + } + ] + } + # table second upper surface (higher) + DEF tableSurfaceUp2 Transform{ + translation -0.065 0.0 0.05 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.27 1.04 0.05 + } + } + ] + } + # table second upper surface (higher, in real environment!) + DEF tableSurfaceUp3 Transform{ + translation -0.065 0.1385 0.036 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.27 0.763 0.022 #1.04 + } + } + ] + } + # table lower surface + DEF tableSurfaceLow Transform{ + translation 0.1575 0.0 -0.24 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.60 0.40 0.20 + } + } + geometry Box { + size 0.475 1.04 0.05 + } + } + ] + } + # table front wall (towards guests) + DEF tableWallFront Transform{ + translation -0.105 0.0 -0.3725 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.04 0.695 + } + } + ] + } + # table wall block upper<->lower surface right + DEF tableWallBlockRight Transform{ + translation 0.175 0.495 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table wall block upper<->lower surface left + DEF tableWallBlockLeft Transform{ + translation 0.175 -0.495 -0.12 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 0.05 0.19 + } + } + ] + } + # table back wall (towards robot) + DEF tableWallBack Transform{ + translation 0.37 0.0 -0.4925 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.48 0.28 0.10 + } + } + geometry Box { + size 0.05 1.04 0.455 + } + } + ] + } + # table back crossbar + DEF tableCrossBarBack Transform{ + translation 0.42 0.0 -0.45 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.05 1.04 0.05 + } + } + ] + } + # safety switch + DEF safetySwitch Transform{ + translation 0.3425 0.435 -0.1625 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.2 0.2 + } + } + geometry Box { + size 0.105 0.17 0.105 + } + } + ] + } + + # robot<->table side block left + DEF robotTableBlockLeft Transform{ + translation 0.685 -0.108 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.58 0.05 0.05 + } + } + ] + } + # robot<->table side block right + DEF robotTableBlockRight Transform{ + translation 0.685 0.158 -0.5 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.58 0.05 0.05 + } + } + ] + } + # robot base lower part + DEF robotBaseBlock Transform{ + translation 0.77625 0.025 -0.4225 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.1525 0.216 0.105 + } + } + ] + } + # robot base upper part + DEF robotBaseSurface Transform{ + translation 0.77625 0.025 -0.365 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.70 0.50 0.30 + } + } + geometry Box { + size 0.35 0.24 0.01 + } + } + ] + } + ] +} diff --git a/data/models/mekabot-convex/environment_old.wrl b/data/models/mekabot-convex/environment_old.wrl new file mode 100644 index 0000000..c5a0aa9 --- /dev/null +++ b/data/models/mekabot-convex/environment_old.wrl @@ -0,0 +1,152 @@ +#VRML V2.0 utf8 + +PROTO MaterialCounter []{ + Material { + diffuseColor 1 1 1 + } +} + +DEF counter Transform{ + translation -0.098 -0.12 0.188 + children[ + DEF box1 Transform{ + translation 0 0 -0.2465 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.44 1.04 0.533 + } + } + ] + } + + DEF box2 Transform{ + translation 0.285 0 -0.369 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.17 1.00 0.248 + } + } + ] + } + DEF box3 Transform{ + translation 0.3915 0 -0.4715 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.043 1.00 0.043 + } + } + ] + } + DEF box4 Transform{ + translation 0.558 -0.1045 -0.5145 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.29 0.043 0.043 + } + } + ] + } + DEF box5 Transform{ + translation 0.558 0.1545 -0.5145 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.29 0.043 0.043 + } + } + ] + } + DEF box6 Transform{ + translation 0.77625 0.025 -0.443 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.1525 0.216 0.10 + } + } + ] + } + DEF box7 Transform{ + translation 0.77625 0.025 -0.388 + children[ + Shape { + appearance Appearance { + material MaterialCounter {} + } + geometry Box { + size 0.274 0.244 0.01 + } + } + ] + } + DEF robotBase Transform{ + translation 0.756 0.018 -0.348 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0 0 1 + } + } + geometry Box { + size 0.314 0.19 0.07 + } + } + ] + } + DEF robotDistance Transform{ + translation 0.48 0.018 -0.348 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1 0 0 + } + } + geometry Box { + size 0.22 0.01 0.01 + } + } + ] + } + DEF robotClose Transform{ + translation 0.595 0.018 -0.348 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1 1 0 + } + } + geometry Box { + size 0.01 0.01 0.01 + } + } + ] + } + ] +} + + diff --git a/data/models/mekabot-convex/meka-scenario1-hd.wrl b/data/models/mekabot-convex/meka-scenario1-hd.wrl new file mode 100644 index 0000000..40f8b5c --- /dev/null +++ b/data/models/mekabot-convex/meka-scenario1-hd.wrl @@ -0,0 +1,126 @@ +#VRML V2.0 utf8 + +DEF mekabot Group { + children [ + Inline { + url "rlsg/mekabot-torso-rightarm.convex-hd.wrl" + } + ] +} + +#DEF package1 Transform{ +# translation 0.0376622556475922 -0.353289011970628 0.299010842949152 #-0.1 -0.4 0.146 # 0.145, to avoid contact with table: 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 1.0 0.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package2 Transform{ +# translation 0.16 0.0 0.146 #0.04 0.0 0.196 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 1.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package3 Transform{ +# translation 0.25 -0.3 -0.094 #-0.1 0.4 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 1.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} + +DEF package1 Transform { + translation 0.16 -0.35 0.146 # 0.025, to avoid contact with table: 0.026 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-red.wrl" + } + ] +} +DEF package2 Transform { + translation 0.0 -0.2 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-green.wrl" + } + ] +} +DEF package3 Transform { + translation -0.1 0.4 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-blue.wrl" + } + ] +} +#DEF package4 Transform { +# translation 0.13 -0.3 0.146 # 0.025, to avoid contact with table: 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-red-trans.wrl" +# } +# ] +#} +#DEF package5 Transform { +# translation 0.13 -0.2 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-green-trans.wrl" +# } +# ] +#} +#DEF package6 Transform { +# translation 0.13 -0.1 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-blue-trans.wrl" +# } +# ] +#} + +DEF workspace Group { + children [ + Inline { + url "environment.wrl" + } + ] +} diff --git a/data/models/mekabot-convex/meka-scenario1-hd.xml b/data/models/mekabot-convex/meka-scenario1-hd.xml new file mode 100644 index 0000000..db9acdc --- /dev/null +++ b/data/models/mekabot-convex/meka-scenario1-hd.xml @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/meka-scenario1.wrl b/data/models/mekabot-convex/meka-scenario1.wrl new file mode 100644 index 0000000..7f5ed18 --- /dev/null +++ b/data/models/mekabot-convex/meka-scenario1.wrl @@ -0,0 +1,99 @@ +#VRML V2.0 utf8 + +DEF mekabot Group { + children [ + Inline { + url "rlsg/mekabot-torso-rightarm.convex.wrl" + } + ] +} + +DEF package1 Transform{ + translation 0.16 -0.35 0.146 #0.1 -0.4 0.146 # 0.145, to avoid contact with table: 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +DEF package2 Transform{ + translation 0 -0.2 0.196 #-0.05 0.0 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +DEF package3 Transform{ + translation 0.13 -0.2 0.146 #-0.1 0.4 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 1.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +#DEF package1 Transform { +# translation -0.1 -0.4 0.026 # 0.025, to avoid contact with table: 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-red.wrl" +# } +# ] +#} +#DEF package2 Transform { +# translation 0.025 0.0 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-green.wrl" +# } +# ] +#} +#DEF package3 Transform { +# translation 0.15 0.4 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-blue.wrl" +# } +# ] +#} + +DEF workspace Group { + children [ + Inline { + url "environment.wrl" + } + ] +} diff --git a/data/models/mekabot-convex/meka-scenario1.xml b/data/models/mekabot-convex/meka-scenario1.xml new file mode 100644 index 0000000..d7a8495 --- /dev/null +++ b/data/models/mekabot-convex/meka-scenario1.xml @@ -0,0 +1,47 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm-grasp.xml b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm-grasp.xml new file mode 100644 index 0000000..d408edc --- /dev/null +++ b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm-grasp.xml @@ -0,0 +1,549 @@ + + + + Meka Robotics + Humanoid + + + + + 0 + 0 + 180 + + + 0.715 + 0.025 + -0.359 + + + + 0 + 0 + 9.86055 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.1678 + + + + + + + + + + 0 + 0 + 1 + + + 45 + -35 + 201 + + + + + + + + + + + + + -90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 15 + -5 + 241 + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0.1397 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 15 + -5 + 241 + + + + + + + + + + + + + 90 + 0 + 90 + + + 0.2337 + 0 + 0 + + + + + + + + + + + + + 0 + 90 + -90 + + + 0 + -0.18465 + 0 + + + + + + + + + + 0 + 0 + 1 + + 120 + -10 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 40 + -24 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0.03175 + -0.27857 + 0 + + + + + + + + + + 0 + 0 + 1 + + 0 + -85 + 259 + + + + + + + + + + + + + 90 + 0 + 0 + + + -0.00502 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 45 + 0 + 259 + + + + + + + + + + + + + -90 + 0 + 0 + + + 0 + 0.27747 + 0 + + + + + + + + + + 0 + 0 + 1 + + 170 + -10 + 195 + + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 45 + -45 + 195 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 60 + -60 + 195 + + + + + + + + + + + + + + 90 + 0 + 0 + + + 0 + -0.04414 + 0 + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0.06 + 0.10 + + + + + + + + diff --git a/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml new file mode 100644 index 0000000..b56148f --- /dev/null +++ b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml @@ -0,0 +1,549 @@ + + + + Meka Robotics + Humanoid + + + + + 0 + 0 + 180 + + + 0.715 + 0.025 + -0.359 + + + + 0 + 0 + 9.86055 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.1678 + + + + + + + + + + 0 + 0 + 1 + + + 45 + -60 + 201 + + + + + + + + + + + + + -90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 15 + -6 + 241 + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0.1397 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 15 + -6 + 241 + + + + + + + + + + + + + 90 + 0 + 90 + + + 0.2337 + 0 + 0 + + + + + + + + + + + + + 0 + 90 + -90 + + + 0 + -0.18465 + 0 + + + + + + + + + + 0 + 0 + 1 + + 110 + -10 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 40 + -24 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0.03175 + -0.27857 + 0 + + + + + + + + + + 0 + 0 + 1 + + 0 + -85 + 259 + + + + + + + + + + + + + 90 + 0 + 0 + + + -0.00502 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 45 + 0 + 259 + + + + + + + + + + + + + -90 + 0 + 0 + + + 0 + 0.27747 + 0 + + + + + + + + + + 0 + 0 + 1 + + 170 + -10 + 195 + + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 45 + -45 + 195 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 60 + -60 + 195 + + + + + + + + + + + + + + 90 + 0 + 0 + + + 0 + -0.04414 + 0 + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.15 + + + + + + + + diff --git a/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml.original b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml.original new file mode 100644 index 0000000..113b699 --- /dev/null +++ b/data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml.original @@ -0,0 +1,547 @@ + + + + Meka Robotics + Humanoid + + + + + 0 + 0 + 180 + + + 0.59630871 + -0.1018039 + -0.1936401 + + + + + + + + + + + 0 + 0 + 9.86055 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.1678 + + + + + + + + + + 0 + 0 + 1 + + + 85 + -85 + 201 + + + + + + + + + + + + + -90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 27 + -12 + 241 + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0.1397 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 29 + -29 + 241 + + + + + + + + + + + + + 90 + 0 + 90 + + + 0.2337 + 0 + 0 + + + + + + + + + + + + + 0 + 90 + -90 + + + 0 + -0.18465 + 0 + + + + + + + + + + 0 + 0 + 1 + + 200.21607764145762 + -80.216077641457616 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 150.2856528108405 + -24.385652810840504 + 317 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0.03175 + -0.27857 + 0 + + + + + + + + + + 0 + 0 + 1 + + 85.094305072331082 + -85.094305072331082 + 259 + + + + + + + + + + + + + 90 + 0 + 0 + + + -0.00502 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 133.08121223219192 + -0.0812122321919162 + 259 + + + + + + + + + + + + + -90 + 0 + 0 + + + 0 + 0.27747 + 0 + + + + + + + + + + 0 + 0 + 1 + + 198.71635231642557 + -18.716352316425571 + 195 + + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 58.868339132027103 + -58.868339132027103 + 195 + + + + + + + + + + + + + 90 + -90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + 0 + 0 + 1 + + 60.867972898736497 + -60.867972898736497 + 195 + + + + + + + + + + + + + + 90 + 0 + 0 + + + 0 + -0.04414 + 0 + + + + + + + + + + + + + 0 + 0 + 90 + + + 0 + 0 + 0 + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0.15 + + + + + + + diff --git a/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.wrl b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.wrl new file mode 100644 index 0000000..3672de0 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.wrl @@ -0,0 +1,111 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF mekabot Transform { + children [ + DEF T2R3_TJ0_base Transform { + children [ + Inline { + url "mekabot/T2R3/T2R3_TJ0_base.wrl" + } + ] + } + DEF T2R3_TJ1_pan Transform { + children [ + Inline { + url "mekabot/T2R3/T2R3_TJ1_pan.wrl" + } + ] + } + DEF T2R3_TJ2 Transform { + children [ + Inline { + url "mekabot/T2R3/T2R3_TJ2.wrl" + } + ] + } + DEF T2R3_TJ3 Transform { + children [ + Inline { + url "mekabot/T2R3/T2R3_TJ3.wrl" + } + ] + } + DEF A2R3_T4_Chest Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_T4_Chest.wrl" + } + ] + } + DEF A2R3_RT1_shoulderRoll Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_RT1_shoulderRoll.wrl" + } + ] + } + DEF A2R3_RT2_shoulderPitch Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_RT2_shoulderPitch.wrl" + } + ] + } + DEF A2R3_RT3_bicep Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_RT3_bicep.wrl" + } + ] + } + DEF A2R3_RT4_elbow Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_RT4_elbow.wrl" + } + ] + } + DEF A2R3_T5_forearmRoll Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_T5_forearmRoll.wrl" + } + ] + } + DEF A2R3_T6_wristDiff Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_T6_wristDiff.wrl" + } + ] + } + DEF A2R3_T7_wristYaw Transform { + children [ + Inline { + url "mekabot/A2R3/A2R3_T7_wristYaw.wrl" + } + ] + } + DEF RT8 Transform { + children [ + ] + } + DEF H2R3_hand_still Transform { + children [ + Inline { + url "mekabot/H2R3/mekabot-h2r3-right-thumbUp.wrl" + } + ] + } + DEF H2R3_hand_grasp Transform { + children [ + Inline { + url "mekabot/H2R3/mekabot-h2r3-right.wrl" + } + ] + } + ] + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.xml b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.xml new file mode 100644 index 0000000..90cdd94 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex-hd.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.wrl b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.wrl new file mode 100644 index 0000000..4550f81 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.wrl @@ -0,0 +1,111 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF mekabot Transform { + children [ + DEF T2R3_TJ0_base Transform { + children [ + Inline { + url "mekabot.convex/T2R3/T2R3_TJ0_base.wrl" + } + ] + } + DEF T2R3_TJ1_pan Transform { + children [ + Inline { + url "mekabot.convex/T2R3/T2R3_TJ1_pan.wrl" + } + ] + } + DEF T2R3_TJ2 Transform { + children [ + Inline { + url "mekabot.convex/T2R3/T2R3_TJ2.wrl" + } + ] + } + DEF T2R3_TJ3 Transform { + children [ + Inline { + url "mekabot.convex/T2R3/T2R3_TJ3.wrl" + } + ] + } + DEF A2R3_T4_Chest Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_T4_Chest.wrl" + } + ] + } + DEF A2R3_RT1_shoulderRoll Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_RT1_shoulderRoll.wrl" + } + ] + } + DEF A2R3_RT2_shoulderPitch Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_RT2_shoulderPitch.wrl" + } + ] + } + DEF A2R3_RT3_bicep Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_RT3_bicep.wrl" + } + ] + } + DEF A2R3_RT4_elbow Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_RT4_elbow.wrl" + } + ] + } + DEF A2R3_T5_forearmRoll Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_T5_forearmRoll.wrl" + } + ] + } + DEF A2R3_T6_wristDiff Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl" + } + ] + } + DEF A2R3_T7_wristYaw Transform { + children [ + Inline { + url "mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl" + } + ] + } + DEF RT8 Transform { + children [ + ] + } + DEF H2R3_hand_still Transform { + children [ + Inline { + url "mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.wrl" + } + ] + } + DEF H2R3_hand_grasp Transform { + children [ + Inline { + url "mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.grasp.wrl" + } + ] + } + ] + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.xml b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.xml new file mode 100644 index 0000000..38a420e --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot-torso-rightarm.convex.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT1_shoulderRoll.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT1_shoulderRoll.wrl new file mode 100644 index 0000000..ddd4b38 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT1_shoulderRoll.wrl @@ -0,0 +1,3114 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_LT1_shoulderPitch____________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -34.831799 -50.798 -2.54936, + 34.8978 51.111401 47.814098, + 34.924999 47.2118 53.2929, + 34.924999 50.798801 48.2342, + 20.1334 -84.582298 14.4842, + -25.0427 -83.627296 3.95754, + -34.924999 -41.851002 59.5308, + -34.924999 -43.892101 56.603199, + -34.8978 -51.1106 47.814098, + -34.924999 -50.798 41.5, + -18.4002 -84.973602 16.0413, + -34.705399 -32.653 -3.9103601, + -34.7337 -44.428001 -3.65066, + -34.705399 -10.428 -3.9103601, + -34.924999 -50.798 2.9966187e-009, + -33.251801 -60.662498 -1.08779, + -33.2309 -60.662498 1.60465, + -33.347099 -60.178101 1.61026, + 34.8946 51.146099 -3.7660679e-009, + 25.822901 52.798801 53.2071, + 13.2543 41.813999 79.199997, + 34.924999 36.759201 67.185204, + 34.924999 34.838799 69.540901, + 34.924999 33.3522 71.364502, + -34.924999 43.650799 58.181999, + -34.924999 43.851501 56.674999, + -34.924999 48.2514 51.839802, + -34.924999 44.428799 3.1802458e-009, + -34.924999 26.531 66.675003, + -34.924999 42.471901 59.743599, + -34.924999 -2.428 50.889999, + 34.924999 44.368099 55.297798, + 21.396299 -84.582298 12.5438, + 23.652201 -84.128899 8.4597902, + 25.0427 -83.627296 3.95754, + 33.251801 -60.662498 -1.08779, + 33.170502 -60.178101 -3.7862899, + 34.924999 -44.428001 31.5, + 34.924999 50.798801 3.7101207e-009, + 18.6952 -84.582298 16.2985, + 24.030399 -84.582298 6.1389298, + 24.337999 -84.128899 6.2175002, + 23.3533 -84.582298 8.35289, + 7.3708 -85.668198 26.4259, + 16.861799 -85.7164 14.7002, + 6.10114 -85.7164 26.9223, + 5.1419501 -85.7164 27.661699, + 24.578199 4.0692902 93.199997, + 12.4968 21.6455 93.199997, + 12.1275 21.820801 93.199997, + 34.924999 -29.1628 76.199997, + 34.924999 -36.530102 63.995499, + -2.1170299 -85.291 30.605499, + -2.20577 -84.973602 31.0501, + -24.337999 -84.128899 6.2175002, + -23.652201 -84.128899 8.4597902, + -24.030399 -84.582298 6.1389298, + -23.3533 -84.582298 8.35289, + -17.680401 -85.524902 15.4138, + -18.6952 -84.582298 16.2985, + -34.8242 -51.415298 47.449402, + -34.924999 -50.798 48.2342, + -24.811701 -84.128899 3.92103, + -24.498199 -84.582298 3.87148, + -19.4478 -85.291 13.9909, + -20.667601 -85.291 12.1166, + -22.118099 -84.973602 10.3285, + -22.9848 -84.973602 8.2210903, + -23.445299 -85.524902 -0.70415998, + -23.909401 -85.291 1.5168101, + -24.111601 -84.973602 3.81039, + -23.408899 -85.524902 1.48505, + -22.875299 -85.668198 1.45121, + -23.1684 -85.524902 3.66133, + 6.9552202 -85.7164 26.063601, + -21.707399 -85.291 10.1367, + -20.2349 -85.524902 11.8629, + -21.252899 -85.524902 9.9244404, + -32.230202 32.116798 76.199997, + -28.9193 35.127701 76.199997, + -34.924999 32.269402 72.648499, + -34.924999 34.8293 69.558701, + -34.924999 35.642799 68.576797, + -34.924999 39.326599 63.909901, + -32.592098 -51.145302 -12.4654, + -32.1264 -60.178101 -9.0838003, + -33.4151 -51.145302 -10.0531, + -34.059799 -51.145302 -7.5871401, + -34.0494 -32.653 -7.7715402, + -34.0895 -50.798 -7.59375, + -23.353901 -50.798 -25.937099, + -34.8946 -51.145302 41.5, + -34.900398 -51.110901 41.5, + -34.894901 -51.143501 47.77, + -34.8946 -51.145302 3.3269774e-009, + -33.170502 -60.178101 -3.7862899, + -33.368099 -60.178101 -1.09159, + -33.055 -60.662498 -3.7730999, + -34.801498 -51.145302 -2.5471399, + -34.5228 -51.145302 -5.0806999, + -32.755699 -60.178101 -6.4561901, + -27.8519 63.759701 11.7956, + -16.061199 63.750599 39.775902, + -17.4492 42.0215 76.199997, + -13.2543 41.813999 79.199997, + 10.6172 63.056 48.635601, + 17.4492 42.0215 76.199997, + 12.5274 42.166901 79.199997, + 12.9053 42.0201 79.199997, + 10.2971 42.766201 79.199997, + 5.7379398 63.056 50.990898, + 34.6791 51.7528 47.106201, + 34.705601 51.706001 47.147999, + 34.721298 51.6782 47.172901, + 28.3001 52.798801 51.243599, + 30.121401 52.798801 49.7234, + 27.962601 52.798801 51.5252, + 21.492901 40.104099 76.199997, + 12.0683 63.056 47.550999, + 34.924999 42.459 59.7673, + 28.9193 35.127701 76.199997, + 34.924999 43.680599 58.141701, + 34.924999 40.198898 62.774799, + 34.924999 29.745899 75.549896, + 34.924999 32.8307 71.985703, + 34.924999 29.163601 76.199997, + 32.230202 32.116798 76.199997, + 34.5424 51.973999 46.918999, + 34.6036 51.8862 46.9869, + 34.526901 51.9963 46.901699, + 34.810799 -51.464199 47.392399, + 34.924999 -43.892101 56.603199, + 34.924999 -44.428001 54.603199, + 34.924999 -43.650002 58.181999, + 34.924999 -48.250599 51.839802, + 28.9193 -35.1269 76.199997, + 34.924999 -50.798 -3.9344794e-009, + 34.801498 -51.145302 -2.5471399, + 34.924999 -44.428001 -3.2000163e-009, + 34.924999 -48.612999 40.075001, + 34.924999 -50.798 41.5, + 34.924999 -50.798 48.2342, + 34.059799 -51.145302 -7.5871401, + 32.641602 -60.662498 -6.4336901, + 33.055 -60.662498 -3.7730999, + 32.755699 -60.178101 -6.4561901, + 30.7743 51.146099 -16.4492, + 32.2384 51.146099 -13.3536, + 34.726601 51.146099 -3.42027, + -0.90679097 -62.113602 60.971699, + -0.73950499 -84.973602 31.243799, + 0.90679097 -62.113602 60.971699, + 3.6340401 -84.973602 30.666, + 4.47508 -62.113602 60.3545, + 6.1833301 -62.113602 59.745499, + -5.1419501 -85.7164 27.661699, + -6.9552202 -85.7164 26.063601, + -16.861799 -85.7164 14.7002, + -2.0188401 -85.524902 30.1136, + -1.80627 -85.7164 29.0487, + -3.1536601 -85.668198 29.2561, + -3.3260701 -85.524902 29.7621, + -1.9141999 -85.668198 29.589399, + -2.9758501 -85.7164 28.7342, + -22.3848 -85.668198 -4.9301801, + -22.747 -85.668198 -2.82144, + 2.20577 -84.973602 31.0501, + 0.73950499 -84.973602 31.243799, + 0.70975298 -85.291 30.791401, + -0.70975298 -85.291 30.791401, + -0.67683399 -85.524902 30.290899, + -0.64175099 -85.668198 29.7575, + 0.60556799 -85.7164 29.2073, + -0.60556799 -85.7164 29.2073, + 2.9758501 -85.7164 28.7342, + 1.80627 -85.7164 29.0487, + 0.64175099 -85.668198 29.7575, + 0.67683399 -85.524902 30.290899, + 22.4727 -84.582298 10.4941, + 20.667601 -85.291 12.1166, + 21.058701 -84.973602 12.3459, + 22.118099 -84.973602 10.3285, + 28.898199 -60.662498 -16.4853, + 22.2871 -83.627296 -12.0867, + 29.5718 -10.428 -18.5812, + 29.0138 51.146099 -19.3864, + -12.1275 21.7652 93.199997, + -14.198 20.569799 93.199997, + 24.9937 0.00040901714 93.199997, + 24.9126 2.01156 93.199997, + 8.8628702 23.3699 93.199997, + 34.924999 -34.828499 69.558701, + 34.924999 -35.641998 68.576797, + 34.924999 -32.2686 72.648499, + 34.924999 -39.325802 63.909901, + 34.924999 -42.4711 59.743599, + -8.0033903 -61.722198 59.286598, + -9.5670099 -61.722198 58.282501, + -21.396299 -84.582298 12.5438, + -34.721298 -51.677399 47.172901, + -34.813599 -51.4561 47.401199, + -22.4727 -84.582298 10.4941, + -21.058701 -84.973602 12.3459, + -20.1334 -84.582298 14.4842, + -19.8158 -84.973602 14.2557, + -25.108299 -84.128899 -0.75410599, + -25.3421 -83.627296 -0.76112801, + -25.3027 -83.627296 1.6052001, + -25.069201 -84.128899 1.59039, + -24.752399 -84.582298 1.57029, + -18.6066 -85.668198 13.3858, + -19.773701 -85.668198 11.5925, + -17.277399 -85.668198 15.0625, + -19.0406 -85.524902 13.698, + -18.0585 -85.291 15.7434, + -25.3286 -37.797901 76.199997, + -23.2775 -85.524902 -2.8872399, + -24.399799 -84.973602 -0.73282802, + -24.791 -84.582298 -0.74457598, + -23.946699 -85.291 -0.71921802, + -24.3619 -84.973602 1.5455101, + -23.212 -85.291 5.9298501, + -22.558001 -85.291 8.0684099, + -23.6513 -84.973602 6.0420599, + -23.663799 -85.291 3.73962, + -22.3599 -85.7164 -0.671561, + -22.910999 -85.668198 -0.68811202, + -22.1999 -85.7164 -2.7535701, + -19.2981 -85.7164 11.3137, + -18.1591 -85.7164 13.0639, + -4.0941701 -85.7164 28.269199, + 4.0941701 -85.7164 28.269199, + -22.0958 -85.7164 3.4918301, + -22.6404 -85.668198 3.5778799, + -21.673901 -85.7164 5.5369201, + -22.3251 -85.7164 1.4163001, + -17.4032 -17.924101 93.199997, + -6.3355699 -61.722198 60.105999, + -4.47508 -62.113602 60.3545, + -13.2368 -43.531601 76.199997, + -21.806801 -12.1271 93.199997, + -19.981001 -15.0143 93.199997, + -16.021799 -5.8310299 95.739998, + -23.707399 -7.9142799 93.199997, + -22.1308 -11.6147 93.199997, + -17.4032 17.9249 93.199997, + -17.3137 18.0259 93.199997, + -17.8818 17.384701 93.199997, + -13.0611 10.9599 95.739998, + 18.3234 -16.9429 93.199997, + 17.4032 -17.826799 93.199997, + 32.230202 -32.116001 76.199997, + -33.215599 -44.428001 -10.7924, + -33.444199 -50.798 -10.0619, + -32.965099 -32.653 -11.535, + -32.965099 -10.428 -11.535, + -27.5665 -60.178101 -18.8337, + -25.9522 -50.798 -23.3673, + -31.9809 63.798801 0.85500002, + -31.0849 63.798801 1.6068701, + -28.392 63.601101 12.0244, + -28.297899 63.643398 11.9845, + -29.5755 63.452801 9.90942, + -29.139 63.643398 9.7631903, + -34.756802 50.798801 -3.42325, + -34.0494 -10.428 -7.7715402, + -34.1618 -44.428001 -7.2613201, + -34.599701 44.428799 -4.75562, + -34.552799 -50.798 -5.0851202, + -34.560101 50.798801 -4.7497401, + -12.9053 42.0201 79.199997, + 8.0384398 43.2477 79.199997, + -3.9855499 63.056 51.452499, + -2.1975501 63.056 51.7439, + 7.26015 63.373402 49.946201, + 8.8523903 63.373402 49.177601, + 7.4373999 63.056 50.363499, + 9.0688496 63.056 49.576, + -3.5609701 63.798801 49.456299, + 32.820099 61.120499 -2.079, + 32.561501 61.120499 -4.6075802, + 32.704102 61.6049 -2.07165, + 34.8242 51.4161 47.449402, + 34.813599 51.456902 47.401199, + 34.894901 51.144299 47.77, + 34.825001 51.2383 47.703602, + 8.6128998 63.6073 48.7369, + 16.248899 63.373402 41.7729, + 34.8946 -51.145302 41.5, + 34.900398 -51.110901 41.5, + 34.8946 -51.145302 6.7044392e-010, + 33.347099 -60.178101 1.61026, + 33.368099 -60.178101 -1.09159, + 33.2309 -60.662498 1.60465, + 34.901901 -51.1012 47.8237, + 17.277399 -85.668198 15.0625, + 31.595301 -51.145302 -14.8113, + 31.2866 -60.178101 -11.6519, + 32.0145 -60.662498 -9.0521498, + 32.1264 -60.178101 -9.0838003, + 31.177601 -60.662498 -11.6113, + 32.592098 -51.145302 -12.4654, + 30.241899 -60.178101 -14.1437, + 30.1366 -60.662498 -14.0944, + 33.444199 -50.798 -10.0619, + 33.4151 -51.145302 -10.0531, + 25.3421 -83.627296 -0.76112801, + 24.1437 -83.627296 -7.7382998, + 23.316999 -83.627296 -9.9558601, + 28.2549 -44.428001 -20.5284, + 31.9056 -44.428001 -14.2053, + 31.463499 61.120499 -9.5672302, + 32.108398 61.120499 -7.1086402, + 31.3522 61.6049 -9.53339, + 34.705399 -10.428 -3.9103601, + 34.756802 50.798801 -3.42325, + 34.0494 -32.653 -7.7715402, + -1.9071713e-009 -45.499599 76.199997, + 6.3355699 -61.722198 60.105999, + 10.7416 -62.113602 56.818401, + 3.3260701 -85.524902 29.7621, + 3.1536601 -85.668198 29.2561, + 1.9141999 -85.668198 29.589399, + 2.0188401 -85.524902 30.1136, + 3.4878299 -85.291 30.2369, + 2.1170299 -85.291 30.605499, + 5.4491801 -85.668198 28.119499, + 4.3388 -85.668198 28.7633, + 18.0585 -85.291 15.7434, + 18.4002 -84.973602 16.0413, + 19.8158 -84.973602 14.2557, + 19.4478 -85.291 13.9909, + 8.4935503 -84.973602 27.404699, + 8.1518297 -85.291 27.1068, + 17.680401 -85.524902 15.4138, + 21.063 -83.627296 -14.1121, + 3.1231301 -85.7164 -22.1509, + -28.999201 -60.178101 -16.5429, + -30.241899 -60.178101 -14.1437, + -31.2866 -60.178101 -11.6519, + -32.641602 -60.662498 -6.4336901, + -21.302601 -85.7164 -6.8276801, + -21.8276 -85.668198 -6.9959602, + -21.0802 -85.668198 -9.0007801, + 25.069201 -84.128899 1.59039, + 25.108299 -84.128899 -0.75410599, + 25.3027 -83.627296 1.6052001, + 24.752399 -84.582298 1.57029, + 24.811701 -84.128899 3.92103, + 24.498199 -84.582298 3.87148, + 24.111601 -84.973602 3.81039, + 22.558001 -85.291 8.0684099, + 22.9848 -84.973602 8.2210903, + 23.6513 -84.973602 6.0420599, + 23.212 -85.291 5.9298501, + 20.8687 -84.128899 -13.982, + 22.081499 -84.128899 -11.9752, + 29.5718 -32.653 -18.5812, + 29.840599 44.428799 -18.1465, + 25.988501 -51.145302 -23.285801, + 27.5665 -60.178101 -18.8337, + 25.953199 -60.178101 -21.001101, + 27.618999 -51.145302 -21.3267, + 25.862801 -60.662498 -20.927999, + 27.470501 -60.662498 -18.768101, + 28.999201 -60.178101 -16.5429, + 27.3055 -10.428 -21.7754, + 27.643 -50.798 -21.3452, + 23.8125 50.798801 -25.496201, + 23.8382 44.428799 -25.524401, + 26.9974 50.798801 -22.1562, + 24.6957 50.798801 -24.6957, + 25.9543 -44.428001 -23.3694, + 27.3055 -32.653 -21.7754, + 27.0917 44.428799 -22.040701, + 29.039101 50.798801 -19.403299, + 26.9739 51.146099 -22.1369, + 24.578199 -4.06847 93.199997, + 24.9126 -2.01074 93.199997, + 17.049999 0.00040901673 95.739998, + 2.9607 16.791401 95.739998, + 4.9993701 24.489 93.199997, + 10.9595 13.0615 95.739998, + 8.5249996 14.7661 95.739998, + 15.8071 19.3606 93.199997, + 17.4032 17.8276 93.199997, + 17.8818 17.367901 93.199997, + 18.708 16.574301 93.199997, + -34.924999 -33.351398 71.364502, + -34.924999 -36.7584 67.185204, + -34.924999 -47.210999 53.2929, + -34.924999 -34.838001 69.540901, + -7.3708 -85.668198 26.4259, + -6.10114 -85.7164 26.9223, + -4.3388 -85.668198 28.7633, + -5.4491801 -85.668198 28.119499, + -6.4656901 -85.668198 27.335899, + -7.7737498 -85.524902 26.777201, + -21.5823 -85.668198 7.71945, + -21.0632 -85.7164 7.5337701, + -22.208099 -85.668198 5.6733899, + -20.768499 -85.668198 9.6982498, + -22.085699 -85.524902 7.8994899, + -20.268999 -85.7164 9.4649801, + -22.726101 -85.524902 5.8056998, + -12.1275 -21.7644 93.199997, + -21.492901 -40.103298 76.199997, + -10.9595 -13.0606 95.739998, + -14.198 -20.569 93.199997, + -17.3137 -18.025101 93.199997, + -13.0611 -10.9591 95.739998, + 15.8071 -19.3598 93.199997, + 6.4182301 -24.0772 93.199997, + 17.4492 -42.020699 76.199997, + -4.0688801 -24.5954 93.199997, + -17.4492 -42.020699 76.199997, + -5.83144 -16.021299 95.739998, + -6.95367 -24.006399 93.199997, + -9.0289698 -23.2194 93.199997, + -10.7146 -22.580099 93.199997, + -2.77526 -61.722198 61.1507, + -4.5852599 -61.722198 60.730099, + -2.70857 -62.113602 60.765099, + -8.8963299 -44.621399 76.199997, + -4.46978 -45.279499 76.199997, + -0.92911798 -61.722198 61.3624, + -21.806801 12.1279 93.199997, + -19.981001 15.0152 93.199997, + -34.924999 29.163601 76.199997, + -22.1308 11.6155 93.199997, + -14.7657 8.5254097 95.739998, + -23.707399 7.9151001 93.199997, + -31.622801 -50.798 -14.8242, + -32.620499 -50.798 -12.4763, + -31.595301 -51.145302 -14.8113, + -31.9056 -44.428001 -14.2053, + -31.466299 -32.653 -15.1534, + -31.466299 -10.428 -15.1534, + -32.0336 44.428799 -13.9142, + -25.988501 -51.145302 -23.285801, + -27.618999 -51.145302 -21.3267, + -25.953199 -60.178101 -21.001101, + -24.2195 -51.145302 -25.1208, + -32.266499 50.798801 -13.3652, + -32.2384 51.146099 -13.3536, + -29.5718 -32.653 -18.5812, + -30.2349 -50.798 -17.455799, + -30.456301 -50.798 -17.092899, + -30.4298 -51.145302 -17.077999, + -29.101999 -51.145302 -19.2537, + -30.245899 -44.428001 -17.4625, + -32.209999 63.798801 5.792623e-010, + -32.183998 63.798801 -0.296938, + -31.4636 61.120499 -9.5668697, + -30.630699 61.120499 -11.9683, + -7.43683 63.056 50.363602, + -12.5274 42.166901 79.199997, + -10.2971 42.766201 79.199997, + -5.73736 63.056 50.991001, + -5.4500198 63.6073 50.080299, + -5.6009498 63.373402 50.558701, + -3.8912399 63.373402 51.009102, + 1.1547101 43.973301 79.199997, + -9.4747601 63.798801 46.944199, + -6.6388998 63.798801 48.485199, + -6.8544598 63.750599 48.992599, + -8.0938702 63.798801 47.782902, + -5.12328 63.798801 49.044701, + -5.2891698 63.750599 49.570499, + 5.6015301 63.373402 50.558601, + 7.0640302 63.6073 49.4846, + 5.4505901 63.6073 50.080299, + 32.257599 62.065201 -4.56457, + 31.808701 62.065201 -7.0422802, + 32.4464 61.6049 -4.59128, + 31.9949 61.6049 -7.0834999, + 31.554501 62.490002 -6.9860101, + 27.059401 61.120499 -18.688801, + 25.7117 63.798801 -14.9656, + 30.6306 61.120499 -11.9687, + 29.6147 61.120499 -14.2986, + 32.2854 63.608799 -0.64983797, + 32.371101 63.608799 -0.329932, + 8.3576498 63.750599 48.2672, + 31.365999 63.798801 5.2565141e-010, + 32.371101 63.608799 0.329932, + 34.285099 52.265202 46.743698, + 34.409599 52.139 46.8078, + 15.3328 63.373402 43.285099, + 17.0158 63.373402 40.179798, + 28.3922 63.601101 12.024, + 28.721901 63.452801 12.1637, + 11.7797 63.373402 47.201302, + 10.3636 63.373402 48.2598, + 33.542301 52.698799 46.8111, + 33.4594 52.726101 46.848301, + 33.641399 52.6661 46.766602, + 32.974701 52.798199 47.189899, + 32.924999 52.798801 47.2346, + 33.2379 52.7742 46.982899, + 13.4086 63.056 46.332199, + -34.304199 52.2472 46.751598, + -34.901901 51.102001 47.8237, + -34.924999 50.798801 48.2342, + -34.8946 51.146099 -2.7631917e-009, + -34.924999 50.798801 -3.024478e-009, + -34.693001 51.730202 47.125401, + -34.810799 51.465 47.392399, + 19.773701 -85.668198 11.5925, + 19.0406 -85.524902 13.698, + 18.6066 -85.668198 13.3858, + 18.1591 -85.7164 13.0639, + 19.2981 -85.7164 11.3137, + 21.252899 -85.524902 9.9244404, + 20.2349 -85.524902 11.8629, + 21.707399 -85.291 10.1367, + 21.673901 -85.7164 5.5369201, + 22.0958 -85.7164 3.4918301, + 32.965099 -10.428 -11.535, + 32.266499 50.798801 -13.3652, + 32.620499 -50.798 -12.4763, + 32.965099 -32.653 -11.535, + 33.421101 50.798801 -10.1382, + 33.215599 -44.428001 -10.7924, + 34.0895 -50.798 -7.59375, + 34.5228 -51.145302 -5.0806999, + 34.705399 -32.653 -3.9103601, + 34.7337 -44.428001 -3.65066, + 34.831799 -50.798 -2.54936, + 24.5317 -84.128899 -5.4030099, + 24.760099 -83.627296 -5.45332, + 25.1607 -83.627296 -3.12082, + 24.9286 -84.128899 -3.09203, + 23.921 -84.128899 -7.6669202, + 23.1019 -84.128899 -9.8640099, + 31.466299 -10.428 -15.1534, + 30.8011 50.798801 -16.463499, + 31.466299 -32.653 -15.1534, + 32.0336 44.428799 -13.9142, + 31.622801 -50.798 -14.8242, + 34.253899 50.798801 -6.81353, + 34.560101 50.798801 -4.7497401, + 34.224098 51.146099 -6.8076, + 34.599701 44.428799 -4.75562, + 34.0494 -10.428 -7.7715402, + 34.1618 -44.428001 -7.2613201, + 34.552799 -50.798 -5.0851202, + 33.629902 44.428799 -9.4226503, + 33.6021 50.798801 -9.4157, + 33.392101 51.146099 -10.1294, + 13.2368 -43.531601 76.199997, + 4.0688801 -24.601101 93.199997, + 4.9993701 -24.4881 93.199997, + 2.8961904e-009 -17.049601 95.739998, + 1.00639 -24.973 93.199997, + 2.9607 -16.7906 95.739998, + -3.01265 -24.811001 93.199997, + -2.9607 -16.7906 95.739998, + -8.5249996 -14.7653 95.739998, + -5.4252901 -14.9055 95.739998, + -10.1962 -12.151 95.739998, + 7.7093301 -84.582298 28.746901, + 8.7885303 -84.582298 27.6619, + 9.5670099 -61.722198 58.282501, + 11.0061 -61.722198 57.106899, + 25.3286 -37.797901 76.199997, + 9.3371201 -62.113602 57.965801, + 8.0033903 -61.722198 59.286598, + 7.81107 -62.113602 58.945801, + 4.5759902 -85.524902 29.242399, + 4.7985501 -85.291 29.6919, + 4.9997001 -84.973602 30.0982, + 6.2792301 -84.973602 29.3563, + 7.4505701 -84.973602 28.4533, + 6.81916 -85.524902 27.7369, + 7.7737498 -85.524902 26.777201, + 6.4656901 -85.668198 27.335899, + 5.7470798 -85.524902 28.5634, + 7.1508098 -85.291 28.113199, + 6.0265899 -85.291 28.9799, + 24.3619 -84.973602 1.5455101, + 21.8276 -85.668198 -6.9959602, + -24.17 -60.178101 -23.031099, + -22.150999 -60.662498 -24.823299, + -22.2285 -60.178101 -24.910101, + -25.862801 -60.662498 -20.927999, + -24.0858 -60.662498 -22.9508, + -30.1366 -60.662498 -14.0944, + -24.225201 -84.973602 -3.0047901, + 3.20011 -85.668198 -22.6968, + 5.3025198 -85.668198 -22.299601, + 21.802401 -84.582298 -11.8238, + 21.0599 -85.291 -11.4211, + 22.8099 -84.582298 -9.7393599, + 30.2349 -50.798 -17.455799, + 30.245899 -44.428001 -17.4625, + 29.127399 -50.798 -19.2705, + 30.456301 -50.798 -17.092899, + 30.4298 -51.145302 -17.077999, + 29.101999 -51.145302 -19.2537, + 25.9522 -50.798 -23.3673, + 26.0112 -50.798 -23.306101, + 24.6957 -32.653 -24.6957, + 23.353901 -50.798 -25.937099, + 23.3694 -44.428001 -25.9543, + 24.240499 -50.798 -25.142599, + 10.7881 -50.798 -33.201401, + 11.2668 -51.145302 -33.0257, + 15.5316 -60.662498 -29.4217, + 8.8260098 -51.145302 -33.759998, + 8.0285397 -60.178101 -32.4062, + 17.8599 -60.662498 -28.069401, + 13.1474 -60.178101 -30.6882, + 13.6474 -51.145302 -32.115101, + 22.340599 -50.798 -26.844999, + 21.7754 -32.653 -27.3055, + 17.4625 -44.428001 -30.245899, + 18.5812 -10.428 -29.5718, + 18.5812 -32.653 -29.5718, + 1.00639 24.973801 93.199997, + -5.7576199 43.610001 79.199997, + -3.4609301 43.8521 79.199997, + -1.1547101 43.973301 79.199997, + -5.83144 16.0222 95.739998, + 3.8289052e-009 17.0504 95.739998, + -5.4252901 14.9063 95.739998, + -8.5249996 14.7661 95.739998, + -10.9595 13.0615 95.739998, + -10.7146 22.5809 93.199997, + 21.124399 13.3587 93.199997, + 24.267401 -5.9809599 93.199997, + 5.83144 -16.021299 95.739998, + 5.83144 16.0222 95.739998, + -16.021799 5.8318501 95.739998, + -12.1514 -10.1958 95.739998, + -14.7657 -8.5245895 95.739998, + 16.021799 5.8318501 95.739998, + 16.791 -2.96029 95.739998, + 16.791 2.9611101 95.739998, + 14.7657 8.5254097 95.739998, + 13.0611 10.9599 95.739998, + 22.993601 9.79708 93.199997, + 24.267401 5.9817801 93.199997, + -34.924999 -29.7451 75.549896, + -32.230202 -32.116001 76.199997, + -34.924999 -29.1628 76.199997, + -34.924999 -32.829899 71.985703, + -34.924999 -42.458199 59.7673, + -34.924999 -40.198101 62.774799, + -28.9193 -35.1269 76.199997, + -34.924999 -43.679798 58.141701, + -3.6340401 -84.973602 30.666, + -6.1833301 -62.113602 59.745499, + -8.1518297 -85.291 27.1068, + -8.4935503 -84.973602 27.404699, + -8.7885303 -84.582298 27.6619, + -7.7093301 -84.582298 28.746901, + -10.7416 -62.113602 56.818401, + -11.0061 -61.722198 57.106899, + -5.7470798 -85.524902 28.5634, + -6.81916 -85.524902 27.7369, + -7.1508098 -85.291 28.113199, + 12.1275 -21.82 93.199997, + 8.5249996 -14.7653 95.739998, + 12.4968 -21.644699 93.199997, + 8.8628702 -23.369101 93.199997, + 21.492901 -40.103298 76.199997, + -17.049999 0.00040901403 95.739998, + -24.9937 0.00040901665 93.199997, + -24.67 4.0096698 93.199997, + -16.791 2.9611101 95.739998, + -16.791 -2.96029 95.739998, + -24.67 -4.0088501 93.199997, + -20.071199 -60.662498 -26.5333, + -33.6021 50.798801 -9.4157, + -33.392101 51.146099 -10.1294, + -33.421101 50.798801 -10.1382, + -34.253899 50.798801 -6.81353, + -33.629902 44.428799 -9.4226503, + -14.1982 -50.798 -31.890499, + -7.2595801 63.373402 49.946301, + -9.0682802 63.056 49.576099, + -10.7689 63.798801 45.977001, + -11.1197 63.750599 46.402199, + -12.7325 63.6073 45.657501, + -10.363 63.373402 48.259899, + -11.46 63.6073 46.814602, + -14.0156 63.798801 42.398399, + -14.8528 63.798801 41.016602, + -15.3375 63.750599 41.279301, + -16.553499 63.6073 39.984402, + -25.711901 63.798801 -14.9653, + -29.510201 61.6049 -14.2477, + -29.614901 61.120499 -14.2983, + -28.7218 63.452801 12.164, + -29.113001 63.192402 12.3297, + -3.78689 63.6073 50.518501, + -3.6756699 63.750599 49.995602, + -1.96639 63.798801 49.716202, + 3.7874601 63.6073 50.518398, + 2.1981399 63.056 51.7439, + 5.7576199 43.610001 79.199997, + 3.4609301 43.8521 79.199997, + 2.14679 63.373402 51.293499, + 3.98614 63.056 51.452499, + 3.89182 63.373402 51.009102, + -0.38193899 63.373402 51.409199, + -2.08939 63.6073 50.795101, + -2.1461999 63.373402 51.293499, + -2.0288401 63.750599 50.264, + 5.2897301 63.750599 49.570499, + 24.549299 63.192402 -19.9228, + 22.9373 63.192402 -21.7593, + 22.629101 63.452801 -21.4669, + 26.0147 63.192402 -17.9673, + 27.652 62.8689 -16.094999, + 29.8423 63.452801 -9.0742598, + 30.248699 63.192402 -9.1978502, + 27.3246 63.192402 -15.9044, + 28.4713 63.192402 -13.7465, + 27.709801 63.798801 -10.8274, + 24.479099 63.798801 -16.9067, + 26.5926 62.490002 -18.3664, + 26.326401 62.8689 -18.1826, + 26.806801 62.065201 -18.5144, + 27.9317 62.490002 -16.257799, + 30.9207 62.490002 -9.4021902, + 31.1698 62.065201 -9.4779196, + 33.832401 52.5797 46.7141, + 33.798302 52.598099 46.7192, + 29.1131 63.192402 12.3294, + 32.209999 63.798801 2.7584464e-009, + 32.183998 63.798801 -0.296938, + 32.400002 63.608799 -5.8007033e-011, + 31.8099 63.798801 -1.09917, + 29.139099 63.643398 9.7628603, + 29.5756 63.452801 9.90909, + 29.978399 63.192402 10.044, + 34.233799 52.3111 46.725899, + 13.4759 63.750599 44.0438, + 14.9168 63.6073 43.004902, + 13.0503 63.798801 43.693401, + 10.0829 63.6073 47.844101, + 28.2981 63.643398 11.9842, + 27.851999 63.759701 11.7953, + 16.5539 63.6073 39.9842, + 12.733 63.6073 45.657398, + 13.8886 63.6073 44.383598, + 11.4605 63.6073 46.8144, + 13.0879 63.373402 46.011902, + 14.2759 63.373402 44.7024, + -32.371101 63.608799 0.329932, + -32.183998 63.798801 0.296938, + -34.4459 52.097599 46.832901, + -34.569 51.937801 46.945702, + -34.698601 51.723099 47.130199, + 21.5823 -85.668198 7.71945, + 22.726101 -85.524902 5.8056998, + 22.085699 -85.524902 7.8994899, + 22.208099 -85.668198 5.6733899, + 20.768499 -85.668198 9.6982498, + 21.0632 -85.7164 7.5337701, + 20.268999 -85.7164 9.4649801, + 22.450001 -84.973602 -9.5856895, + 2.77526 -61.722198 61.1507, + 4.5852599 -61.722198 60.730099, + 2.70857 -62.113602 60.765099, + 8.8963299 -44.621399 76.199997, + 4.46978 -45.279499 76.199997, + 0.92911798 -61.722198 61.3624, + 22.3848 -85.668198 -4.9301801, + 20.573099 -85.7164 -8.7842798, + 19.6644 -85.7164 -10.6643, + 21.302601 -85.7164 -6.8276801, + 21.846399 -85.7164 -4.8115902, + 22.747 -85.668198 -2.82144, + 23.2775 -85.524902 -2.8872399, + 22.3251 -85.7164 1.4163001, + 22.3599 -85.7164 -0.671561, + 22.1999 -85.7164 -2.7535701, + 23.408899 -85.524902 1.48505, + 22.875299 -85.668198 1.45121, + 22.6404 -85.668198 3.5778799, + 23.1684 -85.524902 3.66133, + 22.910999 -85.668198 -0.68811202, + 23.445299 -85.524902 -0.70415998, + 23.663799 -85.291 3.73962, + 23.909401 -85.291 1.5168101, + 22.9069 -85.524902 -5.0451598, + 24.399799 -84.973602 -0.73282802, + 23.946699 -85.291 -0.71921802, + 24.791 -84.582298 -0.74457598, + 9.7735205 -85.291 -21.873301, + 21.5718 -85.524902 -9.2107, + 22.0331 -85.291 -9.4076595, + 22.3367 -85.524902 -7.1591201, + 20.618999 -85.524902 -11.182, + 21.0802 -85.668198 -9.0007801, + 19.6553 -83.627296 -16.0147, + 22.2285 -60.178101 -24.910101, + 24.2195 -51.145302 -25.1208, + 24.17 -60.178101 -23.031099, + 24.0858 -60.662498 -22.9508, + 17.3423 -85.7164 -14.1301, + 19.0424 -85.668198 -12.7584, + 20.149099 -85.668198 -10.9272, + 15.9492 -85.7164 -15.6856, + 14.4171 -85.7164 -17.1045, + 12.7594 -85.7164 -18.3743, + -27.470501 -60.662498 -18.768101, + -28.898199 -60.662498 -16.4853, + -15.5316 -60.662498 -29.4217, + -10.5857 -60.662498 -31.5406, + -13.1016 -60.662498 -30.581301, + -32.0145 -60.662498 -9.0521498, + -31.177601 -60.662498 -11.6113, + -23.3967 -85.291 -5.1530499, + -23.775299 -85.291 -2.9489801, + -22.9069 -85.524902 -5.0451598, + -22.3367 -85.524902 -7.1591201, + 18.584299 -85.7164 -12.4515, + 1.1833301 -83.627296 -25.325899, + 1.17241 -84.128899 -25.0923, + 19.4865 -85.524902 -13.0559, + 20.2798 -84.973602 -13.5874, + 21.458401 -84.973602 -11.6373, + 19.9032 -85.291 -13.3351, + 20.6049 -84.582298 -13.8053, + 18.9245 -84.973602 -15.4192, + 10.6227 -60.178101 -31.6509, + 5.3629999 -60.662498 -32.834499, + 3.53967 -83.627296 -25.1052, + 7.2566099 -50.798 -34.140701, + 18.1938 -50.798 -29.811701, + 15.5859 -60.178101 -29.524599, + 15.9553 -51.145302 -31.0333, + 17.4524 -50.798 -30.2279, + 13.6593 -50.798 -32.143101, + 14.1982 -50.798 -31.890499, + 10.7924 -44.428001 -33.215599, + 20.1406 44.428799 -28.5327, + 22.1562 50.798801 -26.9974, + 21.7754 -10.428 -27.3055, + 20.5284 -44.428001 -28.2549, + -7.7715402 -32.653 -34.0494, + -15.1534 -32.653 -31.466299, + -28.3216 61.6049 -16.484301, + 24.6742 51.146099 -24.6742, + 24.8435 62.8689 -20.161501, + -4.0688801 24.596201 93.199997, + -2.9607 16.791401 95.739998, + -6.95367 24.007299 93.199997, + -3.01265 24.8118 93.199997, + -8.0384398 43.2477 79.199997, + 10.9595 -13.0606 95.739998, + 18.708 -16.5734 93.199997, + -4.7985501 -85.291 29.6919, + -3.4878299 -85.291 30.2369, + -4.5759902 -85.524902 29.242399, + -6.2792301 -84.973602 29.3563, + -6.0265899 -85.291 28.9799, + -7.4505701 -84.973602 28.4533, + -9.3371201 -62.113602 57.965801, + -4.9997001 -84.973602 30.0982, + -7.81107 -62.113602 58.945801, + -17.8599 -60.662498 -28.069401, + -15.5859 -60.178101 -29.524599, + -32.400002 63.608799 -6.4800948e-010, + -32.5616 61.120499 -4.6072102, + -34.726601 51.146099 -3.42027, + -32.820202 61.120499 -2.07862, + -32.704102 61.6049 -2.07127, + -34.224098 51.146099 -6.8076, + -32.257599 62.065201 -4.5641999, + -31.9949 61.6049 -7.0831299, + -32.4464 61.6049 -4.59091, + -32.108501 61.120499 -7.1082702, + -17.4524 -50.798 -30.2279, + -15.9553 -51.145302 -31.0333, + -17.4625 -44.428001 -30.245899, + -22.340599 -50.798 -26.844999, + -8.61234 63.6073 48.737, + -8.8518295 63.373402 49.1777, + -7.0634699 63.6073 49.484699, + -10.0824 63.6073 47.8442, + -8.3570995 63.750599 48.2673, + -9.7832499 63.750599 47.401199, + -13.4754 63.750599 44.043999, + -13.0498 63.798801 43.693501, + -11.9642 63.798801 44.890099, + -12.3543 63.750599 45.279701, + -10.6167 63.056 48.6357, + -25.3596 52.798801 53.557098, + -26.080601 52.798801 53.010201, + -29.8424 63.452801 -9.0739202, + -31.5546 62.490002 -6.9856501, + -32.371101 63.608799 -0.329932, + -32.2854 63.608799 -0.64983797, + -31.8088 62.065201 -7.0419202, + -31.352301 61.6049 -9.5330296, + -30.5224 61.6049 -11.926, + -14.9163 63.6073 43.005001, + -15.8075 63.6073 41.534, + -13.8881 63.6073 44.383801, + -14.2754 63.373402 44.702599, + -14.4729 63.750599 42.706402, + -26.790899 63.798801 -12.9348, + -27.7099 63.798801 -10.8271, + -34.1688 52.365101 46.709301, + -32.106899 63.798801 0.58485401, + -33.542801 52.700401 46.808399, + -15.3323 63.373402 43.285198, + -33.5289 52.705502 46.8139, + -33.722401 52.632999 46.739399, + -33.832401 52.5797 46.7141, + -33.698799 52.643101 46.7467, + -16.248501 63.373402 41.772999, + -17.015301 63.373402 40.18, + 0.37376699 63.6073 50.9076, + 2.0899701 63.6073 50.795101, + 0.382525 63.373402 51.409199, + -0.37318799 63.6073 50.9077, + 0.364434 63.750599 50.3731, + -0.36386099 63.750599 50.373199, + 6.6394501 63.798801 48.4851, + 8.0944099 63.798801 47.782799, + 6.85502 63.750599 48.992599, + 2.0294099 63.750599 50.264, + 0.354808 63.798801 49.821899, + -0.35424101 63.798801 49.821899, + 29.338301 62.065201 -14.1651, + 30.3447 62.065201 -11.8569, + 30.522301 61.6049 -11.9263, + 32.106899 63.798801 -0.58485401, + 24.2194 63.452801 -19.6551, + 28.3214 61.6049 -16.4846, + 29.51 61.6049 -14.248, + 28.422001 61.120499 -16.5431, + 28.1567 62.065201 -16.3887, + 26.963699 61.6049 -18.6227, + 29.8009 62.8689 -11.6444, + 28.8125 62.8689 -13.9113, + 29.103901 62.490002 -14.052, + 30.1022 62.490002 -11.7622, + 29.448 63.192402 -11.5066, + 30.6112 62.8689 -9.3080597, + 34.100399 52.416698 46.699001, + 33.971401 52.503201 46.694801, + 34.105202 52.413502 46.6991, + 33.9505 52.5159 46.696098, + 25.3286 37.798698 76.199997, + 31.9809 63.798801 0.85500002, + 32.183998 63.798801 0.296938, + 27.3946 63.798801 11.6016, + 32.106899 63.798801 0.58485401, + 10.7694 63.798801 45.976898, + 9.7837896 63.750599 47.401001, + 9.4752998 63.798801 46.944099, + 11.1203 63.750599 46.4021, + 11.9647 63.798801 44.8899, + 12.3548 63.750599 45.279598, + 15.338 63.750599 41.279099, + 15.808 63.6073 41.533901, + 14.4734 63.750599 42.7062, + 16.061701 63.750599 39.7757, + 14.0161 63.798801 42.398201, + 14.8532 63.798801 41.016399, + 15.554 63.798801 39.560699, + 23.8395 -84.973602 -5.2505598, + 23.3967 -85.291 -5.1530499, + 23.775299 -85.291 -2.9489801, + 24.225201 -84.973602 -3.0047901, + 24.221701 -84.582298 -5.3347301, + 24.6136 -84.582298 -3.0529599, + 23.6187 -84.582298 -7.5700302, + 23.246 -84.973602 -7.4505801, + 22.814301 -85.291 -7.3122101, + 13.6649 -85.291 -19.6782, + 13.3788 -85.524902 -19.266199, + 11.9932 -84.973602 -21.261499, + 9.9584703 -84.973602 -22.287201, + 11.7705 -85.291 -20.866699, + 7.1817298 -85.7164 -21.185801, + 7.3587298 -85.668198 -21.708, + 5.1749701 -85.7164 -21.763201, + 11.2614 -85.668198 -19.964199, + 13.0739 -85.668198 -18.827101, + 11.5241 -85.524902 -20.4298, + 9.5689001 -85.524902 -21.4153, + 9.3508101 -85.668198 -20.9272, + 10.9906 -85.7164 -19.483999, + 9.1259003 -85.7164 -20.423901, + -24.9286 -84.128899 -3.09203, + -24.6136 -84.582298 -3.0529599, + -25.1607 -83.627296 -3.12082, + -23.8395 -84.973602 -5.2505598, + -22.814301 -85.291 -7.3122101, + -24.1437 -83.627296 -7.7382998, + -24.760099 -83.627296 -5.45332, + -24.5317 -84.128899 -5.4030099, + -24.221701 -84.582298 -5.3347301, + -19.6644 -85.7164 -10.6643, + -18.584299 -85.7164 -12.4515, + -17.3423 -85.7164 -14.1301, + -9.3508101 -85.668198 -20.9272, + -20.573099 -85.7164 -8.7842798, + -21.846399 -85.7164 -4.8115902, + -15.9492 -85.7164 -15.6856, + -16.3423 -85.668198 -16.072201, + -17.0811 -85.291 -16.7988, + -14.4612 -83.627296 -20.8249, + 1.15759 -84.582298 -24.7752, + 5.4261899 -85.524902 -22.819599, + 7.69138 -85.291 -22.689301, + 7.5303502 -85.524902 -22.2143, + -8.0005703 -60.662498 -32.293301, + -1.1833301 -83.627296 -25.325899, + -5.3629999 -60.662498 -32.834499, + 16.723499 -85.524902 -16.4471, + 16.3423 -85.668198 -16.072201, + 17.7698 -85.668198 -14.4784, + 18.1842 -85.524902 -14.816, + 14.7725 -85.668198 -17.525999, + 15.117 -85.524902 -17.934799, + 15.4403 -85.291 -18.3183, + 17.0811 -85.291 -16.7988, + 18.573099 -85.291 -15.1329, + 3.50702 -84.128899 -24.8736, + 16.34 -83.627296 -19.3857, + 18.076401 -83.627296 -17.777599, + 22.150999 -60.662498 -24.823299, + 20.071199 -60.662498 -26.5333, + 14.4612 -83.627296 -20.8249, + 15.7324 -84.973602 -18.6649, + 13.9235 -84.973602 -20.0506, + 14.1467 -84.582298 -20.372, + 14.3278 -84.128899 -20.632799, + -2.6997199 -60.178101 -33.2766, + 4.4223761e-010 -60.662498 -33.2696, + -2.69031 -60.662498 -33.160702, + 7.7715402 -10.428 -34.0494, + 8.8337002 -50.798 -33.789398, + 7.1057 44.428799 -34.1945, + 7.7715402 -32.653 -34.0494, + 7.2613201 -44.428001 -34.1618, + 20.303699 -51.145302 -28.3794, + 18.177999 -51.145302 -29.785801, + 20.3214 -50.798 -28.4041, + 17.9223 -60.178101 -28.1675, + 20.141399 -60.178101 -26.625999, + 22.3211 -51.145302 -26.8216, + 20.5233 -50.798 -28.248301, + 15.1534 -10.428 -31.466299, + 15.1534 -32.653 -31.466299, + 15.9692 -50.798 -31.060301, + 16.067801 44.428799 -31.009399, + 14.2053 -44.428001 -31.9056, + 11.535 -10.428 -32.965099, + 11.535 -32.653 -32.965099, + 11.2766 -50.798 -33.054401, + 11.6957 44.428799 -32.908501, + -13.1474 -60.178101 -30.6882, + -13.6474 -51.145302 -32.115101, + -3.8164699 -51.145302 -34.685299, + -5.3817501 -60.178101 -32.949299, + -7.2566099 -50.798 -34.140701, + -23.3694 -44.428001 -25.9543, + -21.7754 -32.653 -27.3055, + 23.100201 63.798801 -18.746799, + 31.355 63.798801 -1.4809, + 25.296801 62.065201 -20.5294, + 25.0947 62.490002 -20.3654, + 10.1382 50.798801 -33.421101, + 16.463499 50.798801 -30.8011, + 19.403299 50.798801 -29.039101, + 14.7657 -8.5245895 95.739998, + 13.0611 -10.9591 95.739998, + 21.124399 -13.3578 93.199997, + 16.021799 -5.8310299 95.739998, + 22.993601 -9.7962704 93.199997, + -31.819599 52.798801 48.235298, + -28.922199 52.798801 50.737099, + -21.492901 40.104099 76.199997, + -25.3286 37.798698 76.199997, + -13.4081 63.056 46.332401, + -11.7792 63.373402 47.201401, + -13.0873 63.373402 46.012001, + -12.0677 63.056 47.551102, + -32.924999 52.798801 47.2346, + -33.1693 52.783901 47.032001, + -33.347 52.753799 46.911999, + -30.2488 63.192402 -9.1975002, + -29.448099 63.192402 -11.5062, + -25.6653 63.452801 -17.725599, + -28.1569 62.065201 -16.388399, + -34.010201 52.478802 46.693802, + -33.871101 52.560902 46.7052, + -29.9783 63.192402 10.0444, + -34.030899 52.465302 46.694, + 3.5615301 63.798801 49.456299, + 5.1238298 63.798801 49.044701, + 3.67624 63.750599 49.995602, + 1.96696 63.798801 49.716202, + 28.6236 63.643398 -11.1844, + 29.052299 63.452801 -11.352, + 23.485901 63.759701 -19.059799, + 23.862 63.643398 -19.365, + 12.1855 -84.582298 -21.6024, + 12.3415 -84.128899 -21.878799, + 12.4564 -83.627296 -22.0826, + -19.0424 -85.668198 -12.7584, + -21.063 -83.627296 -14.1121, + -22.2871 -83.627296 -12.0867, + -21.802401 -84.582298 -11.8238, + -20.2798 -84.973602 -13.5874, + -10.343 -83.627296 -23.1478, + -8.1395597 -83.627296 -24.0114, + -22.450001 -84.973602 -9.5856895, + -23.246 -84.973602 -7.4505801, + -21.458401 -84.973602 -11.6373, + -23.1019 -84.128899 -9.8640099, + -23.921 -84.128899 -7.6669202, + -23.316999 -83.627296 -9.9558601, + -22.081499 -84.128899 -11.9752, + -22.8099 -84.582298 -9.7393599, + -23.6187 -84.582298 -7.5700302, + -5.6471 -84.973602 -23.748699, + -7.1817298 -85.7164 -21.185801, + -5.4261899 -85.524902 -22.819599, + -7.3587298 -85.668198 -21.708, + -5.1749701 -85.7164 -21.763201, + -16.34 -83.627296 -19.3857, + -10.1181 -84.582298 -22.644501, + 5.5422201 -85.291 -23.3076, + 3.4080601 -84.973602 -24.171801, + -5.7376299 -84.582298 -24.1294, + -8.0644703 -84.128899 -23.7899, + -7.9625602 -84.582298 -23.4893, + 1.13933 -84.973602 -24.384199, + -1.15759 -84.582298 -24.7752, + -3.50702 -84.128899 -24.8736, + -1.17241 -84.128899 -25.0923, + -3.4626999 -84.582298 -24.559299, + -3.53967 -83.627296 -25.1052, + -5.81106 -84.128899 -24.4382, + -5.86517 -83.627296 -24.6658, + 17.6833 -84.582298 -17.3911, + 15.9847 -84.582298 -18.964199, + 17.404301 -84.973602 -17.116699, + 19.2279 -84.582298 -15.6664, + 16.189199 -84.128899 -19.2069, + 17.909599 -84.128899 -17.6136, + 19.474001 -84.128899 -15.8669, + 2.69031 -60.662498 -33.160702, + 3.65066 -44.428001 -34.7337, + 6.3436699 -50.798 -34.344002, + 3.9103601 -32.653 -34.705399, + 3.9103601 -10.428 -34.705399, + 1.4126198e-009 -44.428001 -34.924999, + -8.8260098 -51.145302 -33.759998, + -6.33815 -51.145302 -34.314201, + -8.0285397 -60.178101 -32.4062, + -10.6227 -60.178101 -31.6509, + -3.9103601 -32.653 -34.705399, + -6.3436699 -50.798 -34.344002, + -3.9103601 -10.428 -34.705399, + -3.8197899 -50.798 -34.7155, + -7.7715402 -10.428 -34.0494, + -7.2613201 -44.428001 -34.1618, + -14.2053 -44.428001 -31.9056, + -13.6593 -50.798 -32.143101, + -10.7881 -50.798 -33.201401, + -8.8337002 -50.798 -33.789398, + -11.2668 -51.145302 -33.0257, + -24.240499 -50.798 -25.142599, + -24.6957 -32.653 -24.6957, + -20.1406 44.428799 -28.5327, + -21.7754 -10.428 -27.3055, + -20.5284 -44.428001 -28.2549, + -27.238199 63.759701 -13.1508, + -28.172501 63.759701 -11.0078, + -28.623699 63.643398 -11.1841, + 23.774 61.6049 -22.553101, + 23.8584 61.120499 -22.633101, + 25.444901 61.6049 -20.649599, + 25.5352 61.120499 -20.7229, + 13.3652 50.798801 -32.266499, + 22.039101 61.120499 -24.408199, + 22.1369 51.146099 -26.9739, + -18.5812 -32.653 -29.5718, + -18.5812 -10.428 -29.5718, + -18.1938 -50.798 -29.811701, + -20.303699 -51.145302 -28.3794, + -17.9223 -60.178101 -28.1675, + -18.177999 -51.145302 -29.785801, + -20.3214 -50.798 -28.4041, + -20.141399 -60.178101 -26.625999, + -22.3211 -51.145302 -26.8216, + -20.5233 -50.798 -28.248301, + -30.1024 62.490002 -11.7619, + -29.104 62.490002 -14.0516, + -29.801001 62.8689 -11.6441, + -29.338499 62.065201 -14.1648, + -30.344801 62.065201 -11.8566, + -31.169901 62.065201 -9.4775696, + -30.9209 62.490002 -9.4018402, + -30.6113 62.8689 -9.3077097, + -24.5495 63.192402 -19.922501, + -27.652201 62.8689 -16.0947, + -28.8127 62.8689 -13.9109, + -27.9319 62.490002 -16.257401, + -26.0149 63.192402 -17.966999, + 27.238001 63.759701 -13.1511, + 28.1724 63.759701 -11.0081, + 26.7908 63.798801 -12.9351, + 26.5597 63.643398 -15.4592, + 27.674299 63.643398 -13.3617, + 26.141001 63.759701 -15.2155, + 24.8878 63.759701 -17.188999, + 25.2864 63.643398 -17.4643, + 26.9575 63.452801 -15.6907, + 25.6651 63.452801 -17.725901, + 28.0888 63.452801 -13.5618, + -18.1842 -85.524902 -14.816, + -18.573099 -85.291 -15.1329, + -17.7698 -85.668198 -14.4784, + -20.618999 -85.524902 -11.182, + -21.5718 -85.524902 -9.2107, + -20.149099 -85.668198 -10.9272, + -19.4865 -85.524902 -13.0559, + -22.0331 -85.291 -9.4076595, + -21.0599 -85.291 -11.4211, + -19.9032 -85.291 -13.3351, + -19.6553 -83.627296 -16.0147, + -18.076401 -83.627296 -17.777599, + -17.909599 -84.128899 -17.6136, + -7.69138 -85.291 -22.689301, + -5.5422201 -85.291 -23.3076, + -7.8369298 -84.973602 -23.1187, + -7.5303502 -85.524902 -22.2143, + 1.0947599 -85.524902 -23.430401, + 3.27474 -85.524902 -23.2262, + 3.34477 -85.291 -23.7229, + 1.06981 -85.668198 -22.8964, + -1.04408 -85.7164 -22.3456, + 1.04408 -85.7164 -22.3456, + -12.7594 -85.7164 -18.3743, + -14.4171 -85.7164 -17.1045, + -9.1259003 -85.7164 -20.423901, + -10.9906 -85.7164 -19.483999, + -11.2614 -85.668198 -19.964199, + -9.5689001 -85.524902 -21.4153, + -16.723499 -85.524902 -16.4471, + -14.7725 -85.668198 -17.525999, + -13.0739 -85.668198 -18.827101, + -16.189199 -84.128899 -19.2069, + -15.7324 -84.973602 -18.6649, + -14.1467 -84.582298 -20.372, + -15.9847 -84.582298 -18.964199, + -12.3415 -84.128899 -21.878799, + -10.2476 -84.128899 -22.934299, + -12.4564 -83.627296 -22.0826, + -12.1855 -84.582298 -21.6024, + -14.3278 -84.128899 -20.632799, + 5.6471 -84.973602 -23.748699, + 3.4626999 -84.582298 -24.559299, + -1.11817 -85.291 -23.9314, + -1.0947599 -85.524902 -23.430401, + 1.11817 -85.291 -23.9314, + -1.13933 -84.973602 -24.384199, + -3.34477 -85.291 -23.7229, + -3.4080601 -84.973602 -24.171801, + 8.1395597 -83.627296 -24.0114, + 5.86517 -83.627296 -24.6658, + 10.5857 -60.662498 -31.5406, + 8.0005703 -60.662498 -32.293301, + 10.343 -83.627296 -23.1478, + 13.1016 -60.662498 -30.581301, + 3.8197899 -50.798 -34.7155, + 5.3817501 -60.178101 -32.949299, + 6.33815 -51.145302 -34.314201, + -3.65066 -44.428001 -34.7337, + 2.3816199 50.798801 -34.807999, + 2.3833699 44.428799 -34.843601, + 3.42325 50.798801 -34.756802, + -1.16906 63.759701 -30.2241, + -32.106899 63.798801 -0.58485401, + -30.2031 63.798801 -1.68402, + 29.076401 63.798801 -1.67729, + -15.1845 63.798801 -25.5502, + -15.5535 63.798801 39.560902, + -13.7691 63.798801 25.5588, + 15.57 63.798801 -27.2185, + 14.817 63.798801 -27.163799, + 16.959999 63.798801 -26.413799, + 15.683 63.798801 -27.163799, + 1.1495301 63.798801 -29.7278, + -1.14987 63.798801 -29.7278, + 1.16872 63.759701 -30.2241, + -26.141199 63.759701 -15.2152, + -25.2866 63.643398 -17.464001, + -7.1057 44.428799 -34.1945, + -7.1024599 50.798801 -34.181599, + -16.067801 44.428799 -31.009399, + -16.463499 50.798801 -30.8011, + -15.1534 -10.428 -31.466299, + -15.9692 -50.798 -31.060301, + -13.3652 50.798801 -32.266499, + -10.1382 50.798801 -33.421101, + -10.7924 -44.428001 -33.215599, + -25.9543 -44.428001 -23.3694, + -26.0112 -50.798 -23.306101, + -23.8382 44.428799 -25.524401, + -26.806999 62.065201 -18.514099, + 14.1508 63.798801 -27.7237, + 3.44205 63.798801 -29.5502, + 15.8349 63.798801 -28.020599, + 15.25 63.798801 -28.1238, + -28.089001 63.452801 -13.5615, + -28.4715 63.192402 -13.7462, + -29.0525 63.452801 -11.3516, + -27.6745 63.643398 -13.3614, + -26.957701 63.452801 -15.6904, + -27.3248 63.192402 -15.9041, + -26.5599 63.643398 -15.4589, + 21.659 62.490002 -23.987101, + 23.6357 62.065201 -22.4219, + 21.833401 62.065201 -24.1803, + 15.5799 63.608799 -28.284901, + 7.1024599 50.798801 -34.181599, + 6.81353 50.798801 -34.253899, + 3.42027 51.146099 -34.726601, + 20.0172 61.6049 -25.945299, + 20.0882 61.120499 -26.037399, + 21.961201 61.6049 -24.321899, + 17.953501 61.6049 -27.413799, + 3.7018099 62.8689 -31.780199, + 1.23628 62.8689 -31.971201, + -3.49986 63.759701 -30.043501, + -5.7143502 63.798801 -29.195999, + 7.9518499 63.798801 -28.667601, + -19.2279 -84.582298 -15.6664, + -19.474001 -84.128899 -15.8669, + -17.6833 -84.582298 -17.3911, + -17.404301 -84.973602 -17.116699, + -18.9245 -84.973602 -15.4192, + -20.6049 -84.582298 -13.8053, + -20.8687 -84.128899 -13.982, + -3.20011 -85.668198 -22.6968, + -5.3025198 -85.668198 -22.299601, + -3.27474 -85.524902 -23.2262, + -1.06981 -85.668198 -22.8964, + -3.1231301 -85.7164 -22.1509, + -13.3788 -85.524902 -19.266199, + -15.4403 -85.291 -18.3183, + -15.117 -85.524902 -17.934799, + -11.7705 -85.291 -20.866699, + -11.5241 -85.524902 -20.4298, + -9.7735205 -85.291 -21.873301, + -9.9584703 -84.973602 -22.287201, + -11.9932 -84.973602 -21.261499, + -13.6649 -85.291 -19.6782, + -13.9235 -84.973602 -20.0506, + 7.9625602 -84.582298 -23.4893, + 5.7376299 -84.582298 -24.1294, + 7.8369298 -84.973602 -23.1187, + 10.1181 -84.582298 -22.644501, + 8.0644703 -84.128899 -23.7899, + 5.81106 -84.128899 -24.4382, + 10.2476 -84.128899 -22.934299, + 1.27442 -51.145302 -34.8713, + 3.8164699 -51.145302 -34.685299, + 1.27553 -50.798 -34.901699, + 2.6997199 -60.178101 -33.2766, + -3.501335e-009 -60.178101 -33.385899, + -1.27442 -51.145302 -34.8713, + 3.145713e-009 -50.798 -34.901699, + -1.27553 -50.798 -34.901699, + -1.26658 61.6049 -32.745098, + -2.3833699 44.428799 -34.843601, + -3.79179 61.6049 -32.5495, + -6.2943501 61.6049 -32.159401, + 1.22164 63.192402 -31.5926, + 3.5555699 63.643398 -30.5247, + 3.60883 63.452801 -30.981899, + 5.9024601 63.643398 -30.159, + 3.4995201 63.759701 -30.0436, + -19.403299 50.798801 -29.039101, + -11.535 -10.428 -32.965099, + -11.2766 -50.798 -33.054401, + -11.535 -32.653 -32.965099, + -11.6957 44.428799 -32.908501, + -27.3055 -32.653 -21.7754, + -27.3055 -10.428 -21.7754, + -27.643 -50.798 -21.3452, + -26.5928 62.490002 -18.3661, + -26.326599 62.8689 -18.182301, + -24.8437 62.8689 -20.1612, + -25.445101 61.6049 -20.6493, + -26.9639 61.6049 -18.6224, + -25.5354 61.120499 -20.722601, + 11.1066 62.065201 -30.6273, + 11.2113 61.120499 -30.915899, + 10.1294 51.146099 -33.392101, + 13.3536 51.146099 -32.2384, + 8.7589598 61.6049 -31.577299, + 11.1716 61.6049 -30.806499, + 16.7055 63.608799 -27.635099, + 23.446899 62.490002 -22.242701, + 23.212099 62.8689 -22.02, + 16.5599 63.798801 -27.512899, + 16.349199 63.798801 -27.7237, + 16.200001 63.608799 -28.0592, + 18.0173 61.120499 -27.511101, + 19.3864 51.146099 -29.0138, + 16.4713 63.608799 -27.869301, + 16.4492 51.146099 -30.7743, + 15.8387 61.120499 -28.820499, + 13.5655 61.120499 -29.9576, + 16.105 63.798801 -27.894699, + 13.5175 61.6049 -29.8517, + 6.0724602 63.192402 -31.027599, + 5.99087 63.452801 -30.610701, + 3.65797 63.192402 -31.4039, + 15.5469 63.798801 -28.097799, + 8.5519304 62.8689 -30.830999, + 15.8998 63.608799 -28.1992, + 1.25884 62.065201 -32.5546, + 8.7080002 62.065201 -31.3936, + 6.31633 61.120499 -32.273602, + 6.8076 51.146099 -34.224098, + 8.79004 61.120499 -31.6894, + -1.24915 62.490002 -32.294498, + -3.7697301 62.065201 -32.3601, + -1.25921 62.065201 -32.5546, + -3.73961 62.490002 -32.101501, + 1.24878 62.490002 -32.294498, + -1.23664 62.8689 -31.971201, + -15.5799 63.608799 -28.284901, + -6.25773 62.065201 -31.9723, + -3.5559199 63.643398 -30.5247, + -3.42027 51.146099 -34.726601, + -1.27107 61.120499 -32.861301, + 2.0805329e-009 51.146099 -34.8946, + -2.3816199 50.798801 -34.807999, + -3.42325 50.798801 -34.756802, + -3.8052499 61.120499 -32.665001, + 5.9574712e-010 50.798801 -34.924999, + -6.81353 50.798801 -34.253899, + -6.8076 51.146099 -34.224098, + -6.31669 61.120499 -32.273602, + -1.20558 63.452801 -31.1681, + 1.20522 63.452801 -31.1681, + -1.222 63.192402 -31.5926, + -1.18779 63.643398 -30.7082, + 1.18744 63.643398 -30.7082, + -20.088499 61.120499 -26.037201, + -19.3864 51.146099 -29.0138, + -24.6742 51.146099 -24.6742, + -22.1369 51.146099 -26.9739, + -22.0394 61.120499 -24.4079, + -23.8587 61.120499 -22.6329, + -23.8125 50.798801 -25.496201, + -24.6957 50.798801 -24.6957, + -22.1562 50.798801 -26.9974, + -27.0917 44.428799 -22.040701, + -26.9974 50.798801 -22.1562, + -28.2549 -44.428001 -20.5284, + -29.840599 44.428799 -18.1465, + -30.8011 50.798801 -16.463499, + -29.127399 -50.798 -19.2705, + -29.5718 -10.428 -18.5812, + -23.7743 61.6049 -22.552799, + 3.79142 61.6049 -32.5495, + 6.2939901 61.6049 -32.1595, + 3.8048799 61.120499 -32.6651, + 3.7693601 62.065201 -32.360199, + 1.2661999 61.6049 -32.745098, + 1.2707 61.120499 -32.861401, + 6.2073698 62.490002 -31.7169, + 6.1452198 62.8689 -31.399401, + 3.7392399 62.490002 -32.101601, + 6.25737 62.065201 -31.972401, + 8.6384201 62.490002 -31.142799, + -6.1455798 62.8689 -31.3993, + -8.6387701 62.490002 -31.1427, + -8.5522804 62.8689 -30.8309, + -6.2077298 62.490002 -31.716801, + -3.7021699 62.8689 -31.780199, + -5.99122 63.452801 -30.6106, + -3.65833 63.192402 -31.4039, + -3.60918 63.452801 -30.981899, + -6.0728102 63.192402 -31.0275, + -5.9028101 63.643398 -30.158899, + -17.9538 61.6049 -27.413601, + -18.017599 61.120499 -27.5109, + -20.0175 61.6049 -25.945101, + -16.105 63.798801 -27.894699, + -15.25 63.798801 -28.1238, + -15.5469 63.798801 -28.097799, + -14.9531 63.798801 -28.097799, + -15.9651 63.798801 -26.9023, + -3.44239 63.798801 -29.5502, + -11.107 62.065201 -30.627199, + -8.7593203 61.6049 -31.5772, + -8.7083502 62.065201 -31.393499, + -16.4492 51.146099 -30.7743, + -15.839 61.120499 -28.820299, + -11.2116 61.120499 -30.915701, + -8.79041 61.120499 -31.689301, + -10.1294 51.146099 -33.392101, + -13.3536 51.146099 -32.2384, + -29.0138 51.146099 -19.3864, + -29.039101 50.798801 -19.403299, + -30.7743 51.146099 -16.4492, + -28.422199 61.120499 -16.542801, + -26.9739 51.146099 -22.1369, + -27.059601 61.120499 -18.688499, + -23.4471 62.490002 -22.242399, + -25.0949 62.490002 -20.365101, + -25.2971 62.065201 -20.5292, + -21.8337 62.065201 -24.180099, + -23.636 62.065201 -22.4216, + -21.659201 62.490002 -23.9869, + -21.9615 61.6049 -24.3216, + -16.4713 63.608799 -27.869301, + -16.856899 63.798801 -26.9986, + -13.5178 61.6049 -29.8515, + -11.172 61.6049 -30.8064, + -15.8998 63.608799 -28.1992, + -13.5658 61.120499 -29.9575, + -16.200001 63.608799 -28.0592, + -16.5599 63.798801 -27.512899, + -15.8349 63.798801 -28.020599, + -16.349199 63.798801 -27.7237, + -16.7309 63.798801 -27.268801, + -23.862301 63.643398 -19.364799, + -24.2197 63.452801 -19.6548, + -23.486099 63.759701 -19.0595, + -22.629299 63.452801 -21.4667, + -24.888 63.759701 -17.1887, + -22.9375 63.192402 -21.759001, + -24.4793 63.798801 -16.906401, + -23.2124 62.8689 -22.0198, + -16.7055 63.608799 -27.635099 ] + + } + coordIndex [ 30, 9, 645, -1, 81, 28, 645, -1, + 27, 9, 30, -1, 38, 528, 315, -1, + 51, 125, 50, -1, 188, 125, 189, -1, + 188, 50, 125, -1, 7, 645, 9, -1, + 7, 9, 61, -1, 16, 207, 200, -1, + 16, 200, 93, -1, 206, 207, 16, -1, + 206, 16, 15, -1, 428, 81, 645, -1, + 12, 0, 264, -1, 12, 268, 0, -1, + 99, 0, 268, -1, 99, 268, 89, -1, + 14, 27, 0, -1, 14, 9, 27, -1, + 505, 264, 0, -1, 505, 0, 27, -1, + 148, 38, 315, -1, 284, 950, 3, -1, + 31, 51, 132, -1, 121, 125, 51, -1, + 121, 51, 31, -1, 39, 130, 562, -1, + 629, 125, 387, -1, 629, 641, 125, -1, + 642, 125, 641, -1, 378, 50, 188, -1, + 390, 7, 61, -1, 8, 93, 61, -1, + 60, 93, 200, -1, 17, 16, 93, -1, + 97, 206, 15, -1, 199, 203, 200, -1, + 59, 200, 203, -1, 204, 10, 59, -1, + 204, 59, 203, -1, 204, 202, 65, -1, + 204, 65, 64, -1, 165, 216, 818, -1, + 403, 228, 211, -1, 80, 81, 428, -1, + 1079, 1077, 50, -1, 1079, 50, 630, -1, + 678, 676, 253, -1, 266, 89, 268, -1, + 13, 264, 267, -1, 13, 12, 264, -1, + 87, 99, 89, -1, 98, 14, 0, -1, + 98, 0, 99, -1, 906, 1542, 691, -1, + 906, 1286, 1542, -1, 456, 628, 851, -1, + 271, 381, 109, -1, 957, 1288, 688, -1, + 1069, 1288, 957, -1, 18, 38, 148, -1, + 18, 733, 284, -1, 1, 3, 38, -1, + 1, 284, 3, -1, 1, 38, 18, -1, + 1, 18, 284, -1, 117, 19, 118, -1, + 190, 49, 108, -1, 48, 108, 49, -1, + 120, 950, 384, -1, 2, 121, 31, -1, + 2, 38, 3, -1, 2, 31, 38, -1, + 2, 3, 950, -1, 2, 950, 120, -1, + 2, 120, 121, -1, 124, 125, 121, -1, + 124, 22, 23, -1, 26, 79, 1083, -1, + 26, 24, 79, -1, 4, 330, 32, -1, + 4, 32, 130, -1, 4, 39, 330, -1, + 4, 130, 39, -1, 178, 42, 130, -1, + 178, 130, 32, -1, 525, 36, 145, -1, + 306, 35, 293, -1, 375, 358, 184, -1, + 168, 150, 169, -1, 329, 330, 39, -1, + 43, 575, 576, -1, 43, 576, 45, -1, + 176, 171, 173, -1, 596, 375, 184, -1, + 47, 189, 125, -1, 47, 125, 642, -1, + 192, 251, 194, -1, 135, 194, 251, -1, + 135, 251, 411, -1, 135, 411, 565, -1, + 377, 630, 50, -1, 377, 50, 378, -1, + 422, 238, 53, -1, 422, 53, 150, -1, + 5, 200, 207, -1, 5, 207, 62, -1, + 5, 62, 200, -1, 6, 645, 7, -1, + 6, 390, 645, -1, 6, 7, 390, -1, + 649, 390, 215, -1, 92, 93, 8, -1, + 92, 9, 14, -1, 92, 61, 9, -1, + 92, 8, 61, -1, 994, 206, 97, -1, + 156, 393, 392, -1, 214, 10, 204, -1, + 214, 204, 64, -1, 654, 59, 10, -1, + 654, 10, 214, -1, 219, 216, 68, -1, + 226, 235, 72, -1, 226, 68, 216, -1, + 226, 216, 165, -1, 248, 427, 430, -1, + 248, 430, 627, -1, 248, 627, 246, -1, + 855, 50, 1077, -1, 855, 251, 50, -1, + 664, 666, 565, -1, 664, 565, 411, -1, + 86, 89, 253, -1, 86, 87, 89, -1, + 434, 338, 84, -1, 339, 84, 338, -1, + 339, 86, 84, -1, 88, 253, 89, -1, + 88, 678, 253, -1, 438, 443, 1469, -1, + 1468, 450, 1469, -1, 11, 268, 12, -1, + 11, 12, 13, -1, 11, 267, 268, -1, + 11, 13, 267, -1, 100, 99, 87, -1, + 94, 14, 98, -1, 94, 92, 14, -1, + 96, 97, 15, -1, 96, 94, 98, -1, + 96, 15, 16, -1, 96, 16, 17, -1, + 96, 17, 93, -1, 1290, 688, 1288, -1, + 457, 853, 458, -1, 457, 851, 853, -1, + 457, 456, 851, -1, 891, 1082, 103, -1, + 104, 1082, 1083, -1, 110, 109, 276, -1, + 110, 271, 109, -1, 491, 489, 729, -1, + 279, 148, 280, -1, 279, 733, 18, -1, + 279, 18, 148, -1, 283, 113, 950, -1, + 283, 284, 733, -1, 283, 733, 113, -1, + 116, 118, 19, -1, 116, 19, 117, -1, + 498, 118, 115, -1, 498, 117, 950, -1, + 498, 115, 117, -1, 106, 108, 117, -1, + 20, 48, 384, -1, 20, 108, 48, -1, + 20, 384, 950, -1, 20, 950, 117, -1, + 20, 117, 108, -1, 126, 384, 385, -1, + 126, 120, 384, -1, 126, 385, 386, -1, + 126, 386, 387, -1, 126, 387, 125, -1, + 126, 124, 23, -1, 21, 22, 124, -1, + 21, 124, 121, -1, 21, 121, 122, -1, + 21, 23, 22, -1, 21, 126, 23, -1, + 21, 122, 120, -1, 21, 120, 126, -1, + 129, 487, 950, -1, 82, 83, 81, -1, + 29, 81, 83, -1, 29, 24, 26, -1, + 29, 79, 24, -1, 29, 83, 79, -1, + 503, 26, 1083, -1, 25, 503, 505, -1, + 25, 26, 503, -1, 25, 505, 27, -1, + 25, 28, 81, -1, 25, 81, 29, -1, + 25, 29, 26, -1, 25, 27, 30, -1, + 25, 645, 28, -1, 25, 30, 645, -1, + 134, 135, 565, -1, 134, 565, 562, -1, + 195, 194, 135, -1, 37, 132, 139, -1, + 37, 31, 132, -1, 37, 38, 31, -1, + 180, 178, 32, -1, 180, 32, 330, -1, + 180, 330, 179, -1, 33, 130, 42, -1, + 33, 41, 130, -1, 33, 42, 41, -1, + 346, 130, 34, -1, 346, 293, 130, -1, + 346, 306, 293, -1, 348, 130, 41, -1, + 348, 34, 130, -1, 348, 41, 349, -1, + 348, 346, 34, -1, 292, 293, 35, -1, + 137, 525, 528, -1, 137, 36, 525, -1, + 137, 292, 36, -1, 137, 290, 292, -1, + 527, 315, 528, -1, 314, 315, 527, -1, + 142, 525, 145, -1, 142, 145, 299, -1, + 142, 299, 305, -1, 144, 35, 306, -1, + 144, 292, 35, -1, 144, 36, 292, -1, + 144, 145, 36, -1, 138, 37, 139, -1, + 138, 38, 37, -1, 138, 528, 38, -1, + 365, 302, 303, -1, 536, 358, 375, -1, + 536, 375, 146, -1, 480, 146, 937, -1, + 477, 939, 937, -1, 185, 146, 375, -1, + 185, 937, 146, -1, 185, 477, 937, -1, + 147, 146, 480, -1, 542, 312, 280, -1, + 542, 280, 148, -1, 332, 39, 562, -1, + 332, 329, 39, -1, 570, 571, 324, -1, + 167, 766, 151, -1, 167, 150, 168, -1, + 167, 151, 150, -1, 395, 393, 155, -1, + 395, 155, 394, -1, 52, 150, 53, -1, + 52, 169, 150, -1, 52, 161, 158, -1, + 52, 170, 169, -1, 52, 158, 170, -1, + 334, 43, 295, -1, 334, 575, 43, -1, + 819, 342, 818, -1, 1245, 1243, 336, -1, + 1245, 990, 820, -1, 326, 45, 576, -1, + 46, 45, 326, -1, 46, 326, 327, -1, + 231, 327, 321, -1, 231, 321, 174, -1, + 231, 46, 327, -1, 231, 174, 175, -1, + 231, 175, 173, -1, 40, 349, 41, -1, + 40, 353, 349, -1, 40, 41, 42, -1, + 40, 42, 353, -1, 352, 353, 42, -1, + 352, 42, 178, -1, 761, 1006, 820, -1, + 511, 295, 44, -1, 511, 762, 512, -1, + 74, 295, 43, -1, 74, 44, 295, -1, + 74, 43, 45, -1, 74, 45, 46, -1, + 74, 511, 44, -1, 74, 762, 511, -1, + 74, 46, 231, -1, 74, 761, 762, -1, + 74, 1006, 761, -1, 183, 303, 308, -1, + 183, 308, 356, -1, 355, 335, 183, -1, + 355, 183, 356, -1, 597, 536, 537, -1, + 597, 537, 539, -1, 638, 47, 642, -1, + 638, 189, 47, -1, 383, 48, 49, -1, + 383, 49, 190, -1, 383, 384, 48, -1, + 193, 50, 251, -1, 193, 131, 132, -1, + 193, 132, 51, -1, 193, 51, 50, -1, + 857, 858, 161, -1, 857, 52, 53, -1, + 857, 161, 52, -1, 651, 53, 238, -1, + 651, 857, 53, -1, 197, 862, 864, -1, + 197, 658, 862, -1, 197, 215, 658, -1, + 406, 415, 419, -1, 406, 215, 197, -1, + 201, 67, 66, -1, 201, 66, 202, -1, + 57, 67, 201, -1, 57, 200, 55, -1, + 57, 201, 200, -1, 223, 67, 57, -1, + 223, 57, 56, -1, 223, 63, 70, -1, + 223, 56, 63, -1, 54, 200, 62, -1, + 54, 55, 200, -1, 54, 62, 63, -1, + 54, 63, 56, -1, 54, 57, 55, -1, + 54, 56, 57, -1, 992, 206, 994, -1, + 340, 994, 97, -1, 340, 97, 100, -1, + 340, 100, 814, -1, 229, 211, 228, -1, + 212, 156, 392, -1, 212, 157, 156, -1, + 212, 229, 157, -1, 58, 212, 392, -1, + 58, 213, 212, -1, 58, 64, 213, -1, + 58, 214, 64, -1, 397, 58, 392, -1, + 397, 214, 58, -1, 655, 200, 59, -1, + 655, 59, 654, -1, 655, 60, 200, -1, + 655, 93, 60, -1, 655, 61, 93, -1, + 655, 390, 61, -1, 655, 215, 390, -1, + 208, 62, 207, -1, 208, 63, 62, -1, + 208, 209, 63, -1, 588, 218, 993, -1, + 220, 209, 218, -1, 220, 219, 69, -1, + 220, 70, 63, -1, 220, 63, 209, -1, + 76, 211, 213, -1, 76, 64, 65, -1, + 76, 213, 64, -1, 222, 67, 223, -1, + 75, 65, 202, -1, 75, 202, 66, -1, + 75, 76, 65, -1, 75, 77, 76, -1, + 75, 66, 67, -1, 75, 67, 222, -1, + 71, 226, 72, -1, 71, 68, 226, -1, + 71, 69, 219, -1, 71, 219, 68, -1, + 224, 220, 69, -1, 224, 70, 220, -1, + 224, 69, 71, -1, 224, 71, 73, -1, + 224, 223, 70, -1, 224, 73, 404, -1, + 227, 226, 165, -1, 233, 71, 72, -1, + 233, 73, 71, -1, 233, 72, 235, -1, + 233, 404, 73, -1, 233, 400, 404, -1, + 234, 235, 227, -1, 234, 227, 1006, -1, + 234, 1006, 74, -1, 234, 74, 231, -1, + 402, 222, 404, -1, 402, 77, 75, -1, + 402, 75, 222, -1, 401, 403, 211, -1, + 401, 211, 76, -1, 401, 76, 77, -1, + 401, 77, 402, -1, 408, 215, 406, -1, + 408, 649, 215, -1, 408, 409, 649, -1, + 644, 409, 645, -1, 644, 649, 409, -1, + 644, 389, 649, -1, 239, 415, 237, -1, + 243, 671, 672, -1, 243, 645, 244, -1, + 243, 672, 645, -1, 635, 560, 634, -1, + 635, 241, 410, -1, 187, 1083, 79, -1, + 187, 79, 246, -1, 187, 104, 1083, -1, + 187, 246, 627, -1, 78, 246, 79, -1, + 78, 428, 246, -1, 78, 80, 428, -1, + 78, 81, 80, -1, 78, 82, 81, -1, + 78, 79, 83, -1, 78, 83, 82, -1, + 247, 428, 427, -1, 247, 427, 248, -1, + 668, 669, 428, -1, 668, 428, 645, -1, + 668, 645, 672, -1, 431, 428, 669, -1, + 250, 854, 411, -1, 250, 411, 251, -1, + 433, 84, 86, -1, 433, 86, 253, -1, + 433, 434, 84, -1, 255, 676, 443, -1, + 255, 443, 433, -1, 255, 433, 254, -1, + 1514, 1469, 443, -1, 1514, 443, 444, -1, + 256, 337, 449, -1, 256, 809, 337, -1, + 256, 585, 809, -1, 448, 449, 337, -1, + 448, 338, 434, -1, 448, 337, 338, -1, + 85, 339, 814, -1, 85, 86, 339, -1, + 85, 87, 86, -1, 85, 814, 100, -1, + 85, 100, 87, -1, 441, 582, 585, -1, + 441, 585, 256, -1, 265, 678, 88, -1, + 265, 89, 266, -1, 265, 88, 89, -1, + 1197, 442, 880, -1, 90, 1066, 880, -1, + 90, 880, 442, -1, 437, 1469, 436, -1, + 437, 438, 1469, -1, 1392, 1394, 1393, -1, + 1392, 1311, 1394, -1, 1174, 1066, 90, -1, + 1174, 90, 442, -1, 1470, 1467, 1394, -1, + 91, 93, 92, -1, 91, 92, 94, -1, + 91, 96, 93, -1, 91, 94, 96, -1, + 95, 97, 96, -1, 95, 96, 98, -1, + 95, 98, 99, -1, 95, 99, 100, -1, + 95, 100, 97, -1, 889, 957, 688, -1, + 262, 909, 1097, -1, 695, 694, 262, -1, + 695, 262, 1097, -1, 101, 909, 261, -1, + 101, 1290, 909, -1, 102, 101, 261, -1, + 102, 1290, 101, -1, 102, 689, 688, -1, + 102, 688, 1290, -1, 690, 694, 917, -1, + 690, 102, 261, -1, 690, 689, 102, -1, + 270, 891, 103, -1, 270, 103, 1082, -1, + 270, 1082, 104, -1, 270, 628, 456, -1, + 270, 186, 628, -1, 270, 187, 186, -1, + 270, 104, 187, -1, 287, 729, 489, -1, + 704, 271, 110, -1, 105, 493, 277, -1, + 105, 277, 108, -1, 105, 108, 106, -1, + 105, 118, 493, -1, 105, 117, 118, -1, + 105, 106, 117, -1, 107, 108, 277, -1, + 107, 277, 276, -1, 107, 276, 109, -1, + 107, 109, 381, -1, 107, 381, 190, -1, + 107, 190, 108, -1, 272, 460, 458, -1, + 272, 458, 853, -1, 708, 621, 622, -1, + 708, 273, 621, -1, 620, 272, 853, -1, + 620, 621, 273, -1, 620, 273, 272, -1, + 469, 705, 704, -1, 469, 704, 110, -1, + 469, 110, 276, -1, 286, 926, 470, -1, + 286, 483, 926, -1, 275, 286, 470, -1, + 275, 277, 493, -1, 275, 493, 286, -1, + 929, 957, 889, -1, 485, 129, 128, -1, + 485, 487, 129, -1, 485, 128, 112, -1, + 485, 113, 733, -1, 485, 112, 113, -1, + 953, 1069, 957, -1, 111, 112, 128, -1, + 111, 113, 112, -1, 111, 128, 950, -1, + 111, 950, 113, -1, 285, 950, 284, -1, + 285, 283, 950, -1, 114, 115, 118, -1, + 114, 118, 116, -1, 114, 117, 115, -1, + 114, 116, 117, -1, 492, 493, 118, -1, + 492, 118, 749, -1, 495, 750, 749, -1, + 500, 749, 118, -1, 500, 118, 498, -1, + 119, 121, 120, -1, 119, 122, 121, -1, + 119, 120, 122, -1, 123, 125, 124, -1, + 123, 126, 125, -1, 123, 124, 126, -1, + 127, 950, 128, -1, 127, 129, 950, -1, + 127, 128, 129, -1, 294, 562, 130, -1, + 294, 130, 293, -1, 294, 289, 290, -1, + 141, 132, 131, -1, 141, 131, 193, -1, + 141, 193, 195, -1, 141, 139, 132, -1, + 141, 140, 139, -1, 141, 134, 562, -1, + 141, 562, 294, -1, 133, 135, 134, -1, + 133, 195, 135, -1, 133, 134, 141, -1, + 133, 141, 195, -1, 510, 295, 511, -1, + 345, 306, 346, -1, 345, 791, 973, -1, + 136, 290, 137, -1, 136, 294, 290, -1, + 136, 137, 528, -1, 136, 528, 138, -1, + 136, 139, 140, -1, 136, 140, 141, -1, + 136, 141, 294, -1, 136, 138, 139, -1, + 526, 314, 527, -1, 298, 299, 145, -1, + 298, 530, 307, -1, 296, 539, 520, -1, + 296, 597, 539, -1, 300, 308, 303, -1, + 300, 298, 307, -1, 300, 307, 308, -1, + 524, 525, 142, -1, 524, 142, 305, -1, + 531, 144, 306, -1, 143, 145, 144, -1, + 143, 298, 145, -1, 143, 530, 298, -1, + 143, 531, 530, -1, 143, 144, 531, -1, + 534, 356, 308, -1, 534, 593, 356, -1, + 309, 375, 596, -1, 309, 374, 375, -1, + 479, 147, 480, -1, 519, 536, 146, -1, + 519, 146, 147, -1, 549, 312, 542, -1, + 549, 147, 479, -1, 549, 522, 519, -1, + 549, 519, 147, -1, 541, 148, 315, -1, + 541, 542, 148, -1, 166, 153, 766, -1, + 166, 766, 167, -1, 765, 154, 318, -1, + 765, 153, 154, -1, 765, 766, 153, -1, + 149, 425, 422, -1, 149, 151, 425, -1, + 149, 422, 150, -1, 149, 150, 151, -1, + 769, 425, 151, -1, 769, 151, 766, -1, + 152, 571, 154, -1, 152, 324, 571, -1, + 152, 154, 153, -1, 152, 166, 324, -1, + 152, 153, 166, -1, 568, 154, 571, -1, + 568, 571, 572, -1, 568, 318, 154, -1, + 573, 332, 562, -1, 569, 321, 327, -1, + 569, 570, 324, -1, 159, 173, 171, -1, + 230, 394, 155, -1, 230, 155, 393, -1, + 230, 393, 156, -1, 230, 173, 159, -1, + 230, 159, 163, -1, 230, 231, 173, -1, + 230, 156, 157, -1, 230, 157, 229, -1, + 162, 158, 161, -1, 162, 159, 171, -1, + 162, 163, 159, -1, 162, 171, 170, -1, + 162, 170, 158, -1, 160, 858, 394, -1, + 160, 161, 858, -1, 160, 162, 161, -1, + 160, 163, 162, -1, 160, 394, 230, -1, + 160, 230, 163, -1, 331, 514, 179, -1, + 331, 179, 330, -1, 591, 356, 593, -1, + 611, 1031, 1032, -1, 164, 165, 818, -1, + 164, 818, 342, -1, 164, 342, 1006, -1, + 164, 1006, 227, -1, 164, 227, 165, -1, + 343, 342, 819, -1, 810, 337, 809, -1, + 815, 814, 339, -1, 1005, 1228, 1001, -1, + 1005, 343, 1228, -1, 325, 324, 166, -1, + 325, 167, 168, -1, 325, 166, 167, -1, + 177, 168, 169, -1, 177, 169, 170, -1, + 177, 325, 168, -1, 177, 323, 325, -1, + 177, 171, 176, -1, 177, 170, 171, -1, + 172, 176, 173, -1, 172, 173, 175, -1, + 172, 175, 176, -1, 322, 174, 321, -1, + 322, 175, 174, -1, 322, 176, 175, -1, + 322, 177, 176, -1, 322, 323, 177, -1, + 181, 178, 180, -1, 181, 352, 178, -1, + 347, 580, 791, -1, 347, 349, 580, -1, + 347, 791, 345, -1, 350, 349, 353, -1, + 350, 580, 349, -1, 515, 179, 514, -1, + 515, 180, 179, -1, 515, 181, 180, -1, + 515, 352, 181, -1, 777, 781, 782, -1, + 777, 782, 517, -1, 777, 761, 820, -1, + 516, 777, 517, -1, 516, 761, 777, -1, + 182, 365, 303, -1, 182, 303, 183, -1, + 182, 364, 365, -1, 182, 335, 364, -1, + 182, 183, 335, -1, 1149, 1152, 355, -1, + 357, 596, 184, -1, 357, 184, 358, -1, + 598, 597, 296, -1, 598, 302, 365, -1, + 598, 296, 302, -1, 361, 359, 362, -1, + 601, 362, 359, -1, 601, 602, 372, -1, + 1049, 1031, 611, -1, 800, 601, 359, -1, + 615, 841, 614, -1, 376, 847, 1183, -1, + 376, 477, 185, -1, 376, 185, 375, -1, + 371, 372, 602, -1, 1188, 847, 841, -1, + 813, 1061, 1162, -1, 813, 811, 866, -1, + 813, 866, 1061, -1, 626, 628, 186, -1, + 626, 186, 187, -1, 626, 187, 627, -1, + 379, 188, 189, -1, 379, 189, 638, -1, + 379, 378, 188, -1, 632, 190, 381, -1, + 632, 383, 190, -1, 640, 629, 387, -1, + 191, 251, 192, -1, 191, 193, 251, -1, + 191, 192, 194, -1, 191, 194, 195, -1, + 191, 195, 193, -1, 196, 237, 415, -1, + 196, 864, 237, -1, 196, 415, 406, -1, + 196, 197, 864, -1, 196, 406, 197, -1, + 652, 237, 864, -1, 652, 651, 238, -1, + 198, 199, 200, -1, 198, 200, 201, -1, + 198, 201, 202, -1, 198, 203, 199, -1, + 198, 202, 204, -1, 198, 204, 203, -1, + 391, 645, 390, -1, 648, 649, 389, -1, + 648, 389, 391, -1, 205, 993, 218, -1, + 205, 992, 993, -1, 205, 206, 992, -1, + 205, 207, 206, -1, 205, 208, 207, -1, + 205, 218, 209, -1, 205, 209, 208, -1, + 210, 211, 229, -1, 210, 229, 212, -1, + 210, 213, 211, -1, 210, 212, 213, -1, + 653, 654, 214, -1, 653, 214, 397, -1, + 656, 658, 215, -1, 656, 215, 655, -1, + 817, 216, 219, -1, 817, 219, 588, -1, + 817, 818, 216, -1, 217, 218, 588, -1, + 217, 588, 219, -1, 217, 220, 218, -1, + 217, 219, 220, -1, 221, 404, 222, -1, + 221, 222, 223, -1, 221, 224, 404, -1, + 221, 223, 224, -1, 225, 235, 226, -1, + 225, 227, 235, -1, 225, 226, 227, -1, + 399, 400, 234, -1, 399, 228, 403, -1, + 399, 229, 228, -1, 399, 230, 229, -1, + 399, 234, 231, -1, 399, 231, 230, -1, + 232, 400, 233, -1, 232, 234, 400, -1, + 232, 233, 235, -1, 232, 235, 234, -1, + 236, 409, 410, -1, 236, 410, 241, -1, + 236, 645, 409, -1, 236, 241, 645, -1, + 631, 552, 412, -1, 631, 555, 552, -1, + 417, 415, 239, -1, 317, 556, 424, -1, + 317, 424, 425, -1, 317, 425, 769, -1, + 317, 769, 768, -1, 421, 239, 237, -1, + 421, 652, 238, -1, 421, 237, 652, -1, + 421, 238, 422, -1, 423, 424, 556, -1, + 423, 417, 239, -1, 423, 239, 421, -1, + 240, 635, 244, -1, 240, 241, 635, -1, + 240, 244, 645, -1, 240, 645, 241, -1, + 242, 243, 244, -1, 242, 244, 635, -1, + 242, 671, 243, -1, 242, 635, 671, -1, + 245, 246, 428, -1, 245, 428, 247, -1, + 245, 248, 246, -1, 245, 247, 248, -1, + 429, 428, 431, -1, 633, 430, 429, -1, + 633, 429, 431, -1, 633, 627, 430, -1, + 633, 671, 635, -1, 249, 855, 854, -1, + 249, 854, 250, -1, 249, 251, 855, -1, + 249, 250, 251, -1, 252, 433, 253, -1, + 252, 254, 433, -1, 252, 253, 676, -1, + 252, 676, 255, -1, 252, 255, 254, -1, + 435, 443, 438, -1, 435, 433, 443, -1, + 440, 1394, 1311, -1, 440, 441, 256, -1, + 440, 256, 449, -1, 440, 449, 1470, -1, + 440, 1470, 1394, -1, 584, 582, 442, -1, + 584, 442, 1197, -1, 584, 1197, 1196, -1, + 693, 1514, 444, -1, 693, 444, 454, -1, + 693, 1515, 1514, -1, 257, 442, 1311, -1, + 257, 1174, 442, -1, 1175, 1174, 257, -1, + 1175, 1311, 1310, -1, 1175, 257, 1311, -1, + 445, 450, 1468, -1, 445, 1470, 450, -1, + 447, 436, 1469, -1, 447, 1469, 450, -1, + 447, 448, 434, -1, 258, 909, 1290, -1, + 258, 1290, 451, -1, 752, 908, 909, -1, + 752, 909, 258, -1, 752, 258, 451, -1, + 1291, 1290, 1288, -1, 259, 1287, 1286, -1, + 259, 1290, 1287, -1, 259, 1286, 451, -1, + 259, 451, 1290, -1, 905, 688, 689, -1, + 263, 261, 909, -1, 263, 909, 262, -1, + 260, 694, 690, -1, 260, 690, 261, -1, + 260, 262, 694, -1, 260, 261, 263, -1, + 260, 263, 262, -1, 916, 690, 917, -1, + 269, 267, 264, -1, 869, 504, 870, -1, + 869, 269, 264, -1, 869, 872, 269, -1, + 869, 264, 505, -1, 869, 505, 504, -1, + 677, 678, 265, -1, 677, 265, 266, -1, + 677, 268, 267, -1, 677, 266, 268, -1, + 677, 267, 269, -1, 677, 269, 872, -1, + 681, 270, 456, -1, 681, 891, 270, -1, + 883, 460, 459, -1, 883, 680, 460, -1, + 883, 459, 468, -1, 883, 468, 465, -1, + 883, 465, 885, -1, 892, 893, 1082, -1, + 1081, 1082, 893, -1, 701, 271, 704, -1, + 701, 381, 271, -1, 461, 460, 272, -1, + 461, 272, 273, -1, 461, 273, 708, -1, + 274, 470, 469, -1, 274, 275, 470, -1, + 274, 469, 276, -1, 274, 276, 277, -1, + 274, 277, 275, -1, 467, 697, 278, -1, + 467, 468, 697, -1, 466, 886, 885, -1, + 466, 889, 682, -1, 466, 929, 889, -1, + 466, 467, 929, -1, 698, 278, 697, -1, + 698, 467, 278, -1, 698, 929, 467, -1, + 475, 280, 312, -1, 475, 474, 280, -1, + 281, 279, 280, -1, 281, 280, 474, -1, + 281, 733, 279, -1, 482, 473, 476, -1, + 482, 732, 733, -1, 482, 733, 281, -1, + 482, 281, 474, -1, 1185, 376, 1183, -1, + 1185, 477, 376, -1, 715, 725, 723, -1, + 717, 945, 944, -1, 727, 313, 932, -1, + 727, 476, 473, -1, 727, 473, 475, -1, + 727, 475, 313, -1, 486, 738, 950, -1, + 486, 950, 487, -1, 490, 491, 736, -1, + 490, 735, 743, -1, 490, 736, 735, -1, + 948, 950, 738, -1, 730, 491, 729, -1, + 730, 736, 491, -1, 720, 1069, 734, -1, + 720, 1214, 1069, -1, 1068, 1214, 478, -1, + 1068, 478, 721, -1, 959, 953, 957, -1, + 959, 965, 953, -1, 484, 1069, 953, -1, + 962, 488, 287, -1, 962, 287, 489, -1, + 282, 284, 283, -1, 282, 285, 284, -1, + 282, 283, 285, -1, 742, 286, 493, -1, + 742, 483, 286, -1, 496, 950, 729, -1, + 496, 729, 287, -1, 496, 287, 488, -1, + 496, 488, 750, -1, 499, 950, 495, -1, + 499, 495, 749, -1, 499, 749, 500, -1, + 288, 289, 294, -1, 288, 294, 292, -1, + 288, 290, 289, -1, 288, 292, 290, -1, + 291, 293, 292, -1, 291, 294, 293, -1, + 291, 292, 294, -1, 509, 514, 331, -1, + 509, 331, 334, -1, 509, 334, 295, -1, + 509, 295, 510, -1, 521, 523, 520, -1, + 301, 520, 305, -1, 301, 302, 296, -1, + 301, 296, 520, -1, 297, 299, 298, -1, + 297, 298, 300, -1, 297, 305, 299, -1, + 297, 301, 305, -1, 297, 302, 301, -1, + 297, 303, 302, -1, 297, 300, 303, -1, + 304, 316, 524, -1, 304, 524, 305, -1, + 304, 547, 316, -1, 304, 523, 522, -1, + 304, 522, 547, -1, 304, 305, 520, -1, + 304, 520, 523, -1, 532, 345, 973, -1, + 532, 306, 345, -1, 532, 531, 306, -1, + 533, 307, 530, -1, 533, 308, 307, -1, + 533, 534, 308, -1, 367, 366, 374, -1, + 367, 374, 309, -1, 367, 362, 601, -1, + 367, 596, 362, -1, 367, 309, 596, -1, + 310, 520, 539, -1, 310, 519, 520, -1, + 538, 536, 519, -1, 538, 310, 539, -1, + 538, 519, 310, -1, 311, 312, 549, -1, + 311, 475, 312, -1, 311, 313, 475, -1, + 311, 549, 479, -1, 311, 932, 313, -1, + 311, 479, 932, -1, 543, 315, 314, -1, + 543, 541, 315, -1, 543, 314, 526, -1, + 544, 316, 547, -1, 544, 524, 316, -1, + 544, 545, 524, -1, 548, 547, 522, -1, + 548, 522, 549, -1, 550, 318, 413, -1, + 550, 765, 318, -1, 550, 412, 552, -1, + 554, 556, 317, -1, 554, 317, 768, -1, + 333, 332, 573, -1, 333, 573, 578, -1, + 333, 578, 575, -1, 566, 568, 572, -1, + 566, 572, 573, -1, 566, 573, 319, -1, + 567, 666, 413, -1, 567, 413, 318, -1, + 567, 318, 568, -1, 564, 319, 573, -1, + 564, 566, 319, -1, 320, 321, 569, -1, + 320, 322, 321, -1, 320, 323, 322, -1, + 320, 569, 324, -1, 320, 324, 325, -1, + 320, 325, 323, -1, 577, 326, 576, -1, + 577, 327, 326, -1, 577, 569, 327, -1, + 328, 330, 329, -1, 328, 331, 330, -1, + 328, 329, 332, -1, 328, 332, 333, -1, + 328, 334, 331, -1, 328, 575, 334, -1, + 328, 333, 575, -1, 790, 580, 787, -1, + 788, 581, 795, -1, 775, 788, 776, -1, + 976, 795, 794, -1, 807, 820, 990, -1, + 798, 355, 1152, -1, 798, 335, 355, -1, + 798, 364, 335, -1, 1013, 792, 1014, -1, + 984, 336, 590, -1, 984, 1245, 336, -1, + 589, 336, 1243, -1, 589, 590, 336, -1, + 987, 792, 981, -1, 1227, 1228, 343, -1, + 1227, 343, 819, -1, 587, 810, 1112, -1, + 587, 338, 337, -1, 587, 337, 810, -1, + 587, 339, 338, -1, 587, 815, 339, -1, + 998, 340, 814, -1, 998, 994, 340, -1, + 1002, 1225, 1003, -1, 1002, 1110, 1225, -1, + 1002, 1001, 1228, -1, 1002, 1228, 1110, -1, + 341, 1006, 342, -1, 341, 1005, 1006, -1, + 341, 342, 343, -1, 341, 343, 1005, -1, + 344, 345, 346, -1, 344, 347, 345, -1, + 344, 346, 348, -1, 344, 348, 349, -1, + 344, 349, 347, -1, 786, 353, 354, -1, + 786, 350, 353, -1, 786, 787, 580, -1, + 786, 580, 350, -1, 757, 782, 783, -1, + 757, 786, 354, -1, 757, 783, 786, -1, + 351, 352, 515, -1, 351, 515, 758, -1, + 351, 353, 352, -1, 351, 354, 353, -1, + 351, 757, 354, -1, 351, 758, 757, -1, + 828, 1148, 1149, -1, 827, 1149, 355, -1, + 827, 355, 356, -1, 827, 356, 591, -1, + 827, 828, 1149, -1, 595, 596, 357, -1, + 595, 357, 358, -1, 595, 358, 536, -1, + 595, 536, 597, -1, 599, 598, 365, -1, + 599, 362, 596, -1, 604, 614, 841, -1, + 604, 841, 369, -1, 363, 798, 802, -1, + 363, 364, 798, -1, 801, 359, 361, -1, + 801, 800, 359, -1, 801, 363, 802, -1, + 801, 361, 363, -1, 360, 361, 362, -1, + 360, 362, 599, -1, 360, 364, 363, -1, + 360, 363, 361, -1, 360, 365, 364, -1, + 360, 599, 365, -1, 373, 374, 366, -1, + 373, 366, 367, -1, 373, 367, 601, -1, + 1050, 614, 800, -1, 605, 604, 369, -1, + 605, 369, 371, -1, 605, 371, 602, -1, + 607, 606, 1059, -1, 607, 1041, 606, -1, + 837, 607, 1059, -1, 837, 613, 607, -1, + 1109, 611, 1032, -1, 1043, 1041, 1044, -1, + 833, 618, 1047, -1, 833, 617, 618, -1, + 843, 615, 614, -1, 368, 841, 847, -1, + 368, 847, 371, -1, 368, 369, 841, -1, + 368, 371, 369, -1, 370, 372, 371, -1, + 370, 601, 372, -1, 370, 374, 373, -1, + 370, 373, 601, -1, 370, 375, 374, -1, + 370, 376, 375, -1, 370, 847, 376, -1, + 370, 371, 847, -1, 1410, 1068, 721, -1, + 812, 813, 1162, -1, 812, 1162, 1015, -1, + 619, 381, 701, -1, 619, 701, 702, -1, + 637, 377, 378, -1, 637, 378, 379, -1, + 637, 630, 377, -1, 637, 379, 638, -1, + 380, 632, 381, -1, 380, 624, 632, -1, + 380, 381, 619, -1, 380, 619, 624, -1, + 382, 383, 632, -1, 382, 632, 640, -1, + 382, 384, 383, -1, 382, 385, 384, -1, + 382, 386, 385, -1, 382, 387, 386, -1, + 382, 640, 387, -1, 646, 645, 391, -1, + 388, 389, 644, -1, 388, 391, 389, -1, + 388, 644, 646, -1, 388, 646, 391, -1, + 650, 390, 649, -1, 650, 391, 390, -1, + 650, 648, 391, -1, 396, 392, 393, -1, + 396, 393, 395, -1, 396, 397, 392, -1, + 396, 660, 397, -1, 659, 394, 858, -1, + 659, 395, 394, -1, 659, 396, 395, -1, + 659, 660, 396, -1, 661, 653, 397, -1, + 661, 397, 660, -1, 657, 862, 658, -1, + 398, 400, 399, -1, 398, 401, 402, -1, + 398, 403, 401, -1, 398, 399, 403, -1, + 398, 404, 400, -1, 398, 402, 404, -1, + 405, 419, 558, -1, 405, 558, 408, -1, + 405, 406, 419, -1, 405, 408, 406, -1, + 407, 409, 408, -1, 407, 408, 558, -1, + 407, 410, 409, -1, 407, 635, 410, -1, + 407, 560, 635, -1, 407, 558, 560, -1, + 559, 560, 558, -1, 663, 854, 631, -1, + 663, 411, 854, -1, 663, 664, 411, -1, + 665, 631, 412, -1, 665, 663, 631, -1, + 665, 412, 550, -1, 665, 550, 413, -1, + 665, 413, 666, -1, 414, 556, 557, -1, + 414, 557, 417, -1, 414, 423, 556, -1, + 414, 417, 423, -1, 418, 419, 415, -1, + 418, 415, 417, -1, 416, 557, 558, -1, + 416, 417, 557, -1, 416, 418, 417, -1, + 416, 558, 419, -1, 416, 419, 418, -1, + 420, 421, 422, -1, 420, 423, 421, -1, + 420, 424, 423, -1, 420, 422, 425, -1, + 420, 425, 424, -1, 426, 427, 428, -1, + 426, 428, 429, -1, 426, 430, 427, -1, + 426, 429, 430, -1, 625, 632, 624, -1, + 625, 633, 632, -1, 625, 627, 633, -1, + 670, 431, 669, -1, 670, 633, 431, -1, + 670, 671, 633, -1, 432, 434, 433, -1, + 432, 433, 435, -1, 432, 436, 447, -1, + 432, 447, 434, -1, 432, 437, 436, -1, + 432, 438, 437, -1, 432, 435, 438, -1, + 439, 440, 1311, -1, 439, 441, 440, -1, + 439, 582, 441, -1, 439, 442, 582, -1, + 439, 1311, 442, -1, 673, 584, 1196, -1, + 673, 1010, 1131, -1, 675, 677, 872, -1, + 675, 443, 676, -1, 675, 444, 443, -1, + 675, 454, 444, -1, 675, 453, 454, -1, + 876, 899, 453, -1, 876, 675, 872, -1, + 876, 453, 675, -1, 1178, 880, 1067, -1, + 1306, 845, 1169, -1, 1471, 445, 1468, -1, + 1471, 1470, 445, -1, 446, 448, 447, -1, + 446, 449, 448, -1, 446, 1470, 449, -1, + 446, 450, 1470, -1, 446, 447, 450, -1, + 683, 686, 886, -1, 683, 886, 682, -1, + 452, 451, 1286, -1, 452, 1286, 896, -1, + 867, 752, 451, -1, 867, 451, 452, -1, + 867, 452, 896, -1, 867, 870, 504, -1, + 897, 896, 1286, -1, 911, 912, 904, -1, + 1180, 1181, 1286, -1, 1320, 1286, 1181, -1, + 900, 453, 899, -1, 900, 454, 453, -1, + 900, 693, 454, -1, 1202, 900, 1203, -1, + 455, 681, 456, -1, 455, 680, 681, -1, + 455, 456, 457, -1, 455, 457, 458, -1, + 455, 458, 460, -1, 455, 460, 680, -1, + 923, 929, 698, -1, 696, 468, 459, -1, + 696, 697, 468, -1, 696, 459, 460, -1, + 696, 460, 461, -1, 696, 461, 708, -1, + 696, 708, 707, -1, 462, 920, 622, -1, + 462, 622, 619, -1, 462, 619, 702, -1, + 462, 702, 703, -1, 462, 703, 920, -1, + 706, 708, 622, -1, 706, 622, 920, -1, + 463, 682, 886, -1, 463, 886, 466, -1, + 463, 466, 682, -1, 464, 885, 465, -1, + 464, 466, 885, -1, 464, 467, 466, -1, + 464, 465, 468, -1, 464, 468, 467, -1, + 471, 469, 470, -1, 471, 470, 926, -1, + 471, 926, 710, -1, 471, 705, 469, -1, + 471, 699, 705, -1, 1101, 699, 471, -1, + 1101, 471, 710, -1, 925, 926, 483, -1, + 925, 483, 957, -1, 472, 473, 482, -1, + 472, 482, 474, -1, 472, 475, 473, -1, + 472, 474, 475, -1, 726, 482, 476, -1, + 726, 476, 727, -1, 726, 945, 481, -1, + 726, 481, 482, -1, 714, 723, 848, -1, + 714, 1221, 1220, -1, 714, 715, 723, -1, + 1184, 724, 939, -1, 1184, 1070, 724, -1, + 1184, 939, 477, -1, 1184, 477, 1185, -1, + 1217, 478, 1214, -1, 1217, 721, 478, -1, + 722, 723, 725, -1, 722, 725, 724, -1, + 936, 932, 479, -1, 936, 479, 480, -1, + 936, 480, 937, -1, 941, 725, 715, -1, + 941, 942, 725, -1, 941, 719, 944, -1, + 933, 720, 734, -1, 933, 945, 717, -1, + 933, 481, 945, -1, 933, 732, 482, -1, + 933, 482, 481, -1, 741, 963, 965, -1, + 741, 965, 959, -1, 956, 957, 483, -1, + 956, 483, 742, -1, 952, 734, 1069, -1, + 952, 1069, 484, -1, 952, 484, 953, -1, + 952, 485, 733, -1, 952, 738, 486, -1, + 952, 487, 485, -1, 952, 486, 487, -1, + 966, 953, 965, -1, 966, 967, 953, -1, + 960, 741, 959, -1, 740, 488, 962, -1, + 740, 750, 488, -1, 740, 747, 750, -1, + 740, 962, 963, -1, 745, 962, 489, -1, + 745, 490, 743, -1, 745, 489, 491, -1, + 745, 491, 490, -1, 748, 493, 492, -1, + 748, 742, 493, -1, 748, 492, 749, -1, + 494, 495, 950, -1, 494, 950, 496, -1, + 494, 750, 495, -1, 494, 496, 750, -1, + 497, 498, 950, -1, 497, 950, 499, -1, + 497, 500, 498, -1, 497, 499, 500, -1, + 501, 1083, 908, -1, 501, 753, 1083, -1, + 501, 908, 752, -1, 501, 752, 753, -1, + 754, 506, 1083, -1, 754, 1083, 753, -1, + 502, 503, 1083, -1, 502, 1083, 507, -1, + 502, 504, 505, -1, 502, 505, 503, -1, + 502, 867, 504, -1, 502, 507, 867, -1, + 755, 1083, 506, -1, 755, 507, 1083, -1, + 755, 867, 507, -1, 755, 506, 754, -1, + 508, 760, 514, -1, 508, 514, 509, -1, + 508, 509, 510, -1, 508, 511, 512, -1, + 508, 510, 511, -1, 508, 512, 762, -1, + 508, 762, 760, -1, 513, 514, 760, -1, + 513, 760, 758, -1, 513, 515, 514, -1, + 513, 758, 515, -1, 759, 761, 516, -1, + 759, 782, 757, -1, 759, 517, 782, -1, + 759, 516, 517, -1, 518, 520, 519, -1, + 518, 521, 520, -1, 518, 519, 522, -1, + 518, 522, 523, -1, 518, 523, 521, -1, + 546, 525, 524, -1, 546, 524, 545, -1, + 546, 543, 526, -1, 546, 526, 527, -1, + 546, 528, 525, -1, 546, 527, 528, -1, + 529, 533, 530, -1, 529, 972, 533, -1, + 529, 530, 531, -1, 529, 531, 532, -1, + 529, 973, 972, -1, 529, 532, 973, -1, + 974, 533, 972, -1, 974, 593, 534, -1, + 974, 534, 533, -1, 535, 537, 536, -1, + 535, 536, 538, -1, 535, 539, 537, -1, + 535, 538, 539, -1, 540, 542, 541, -1, + 540, 541, 543, -1, 540, 545, 544, -1, + 540, 546, 545, -1, 540, 543, 546, -1, + 540, 544, 547, -1, 540, 547, 548, -1, + 540, 549, 542, -1, 540, 548, 549, -1, + 767, 765, 550, -1, 767, 552, 768, -1, + 767, 550, 552, -1, 551, 552, 555, -1, + 551, 555, 554, -1, 551, 768, 552, -1, + 551, 554, 768, -1, 553, 554, 555, -1, + 553, 555, 631, -1, 553, 557, 556, -1, + 553, 556, 554, -1, 553, 558, 557, -1, + 553, 559, 558, -1, 553, 560, 559, -1, + 553, 634, 560, -1, 553, 631, 634, -1, + 561, 565, 564, -1, 561, 564, 573, -1, + 561, 562, 565, -1, 561, 573, 562, -1, + 563, 564, 565, -1, 563, 566, 564, -1, + 563, 565, 666, -1, 563, 666, 567, -1, + 563, 568, 566, -1, 563, 567, 568, -1, + 579, 570, 569, -1, 579, 569, 577, -1, + 579, 572, 571, -1, 579, 571, 570, -1, + 579, 573, 572, -1, 579, 578, 573, -1, + 574, 576, 575, -1, 574, 577, 576, -1, + 574, 575, 578, -1, 574, 578, 579, -1, + 574, 579, 577, -1, 774, 773, 581, -1, + 797, 795, 581, -1, 797, 581, 773, -1, + 772, 820, 805, -1, 772, 774, 778, -1, + 772, 778, 777, -1, 772, 777, 820, -1, + 789, 791, 580, -1, 789, 580, 790, -1, + 785, 776, 790, -1, 970, 776, 788, -1, + 970, 790, 776, -1, 770, 581, 788, -1, + 770, 788, 775, -1, 770, 774, 581, -1, + 980, 981, 792, -1, 763, 593, 974, -1, + 796, 592, 794, -1, 796, 805, 823, -1, + 796, 826, 592, -1, 796, 823, 826, -1, + 983, 984, 590, -1, 983, 590, 1014, -1, + 1012, 1014, 590, -1, 808, 807, 990, -1, + 808, 1022, 807, -1, 988, 1014, 792, -1, + 988, 792, 987, -1, 988, 983, 1014, -1, + 988, 989, 983, -1, 586, 582, 584, -1, + 586, 585, 582, -1, 583, 1131, 1234, -1, + 583, 673, 1131, -1, 583, 584, 673, -1, + 583, 586, 584, -1, 583, 1234, 586, -1, + 1233, 809, 585, -1, 1233, 585, 586, -1, + 1233, 586, 1234, -1, 1115, 811, 813, -1, + 1122, 587, 1112, -1, 1122, 815, 587, -1, + 995, 817, 588, -1, 995, 588, 993, -1, + 995, 993, 1000, -1, 1241, 589, 1243, -1, + 1241, 590, 589, -1, 1241, 1012, 590, -1, + 1026, 1025, 1148, -1, 1026, 1148, 828, -1, + 1026, 826, 823, -1, 825, 827, 591, -1, + 825, 592, 826, -1, 825, 591, 593, -1, + 825, 593, 763, -1, 825, 794, 592, -1, + 825, 763, 794, -1, 594, 596, 595, -1, + 594, 595, 597, -1, 594, 597, 598, -1, + 594, 599, 596, -1, 594, 598, 599, -1, + 600, 601, 800, -1, 600, 800, 605, -1, + 600, 602, 601, -1, 600, 605, 602, -1, + 603, 614, 604, -1, 603, 604, 605, -1, + 603, 800, 614, -1, 603, 605, 800, -1, + 1275, 610, 829, -1, 1275, 1279, 610, -1, + 609, 1041, 607, -1, 609, 829, 610, -1, + 609, 607, 829, -1, 839, 1059, 606, -1, + 839, 1041, 1072, -1, 839, 606, 1041, -1, + 838, 613, 837, -1, 1058, 837, 1059, -1, + 612, 1277, 829, -1, 612, 829, 607, -1, + 612, 607, 613, -1, 612, 834, 1277, -1, + 608, 834, 611, -1, 608, 611, 1109, -1, + 608, 1109, 1276, -1, 608, 1277, 834, -1, + 608, 1276, 1277, -1, 1036, 1109, 1032, -1, + 1280, 1041, 609, -1, 1280, 609, 610, -1, + 1280, 610, 1279, -1, 1048, 1049, 611, -1, + 1048, 611, 834, -1, 835, 834, 612, -1, + 835, 612, 613, -1, 835, 838, 1054, -1, + 835, 613, 838, -1, 1051, 843, 614, -1, + 1051, 1047, 843, -1, 1051, 614, 1050, -1, + 842, 841, 615, -1, 842, 615, 843, -1, + 1186, 837, 1058, -1, 836, 835, 1054, -1, + 616, 617, 833, -1, 616, 1073, 617, -1, + 616, 833, 836, -1, 616, 1054, 1073, -1, + 616, 836, 1054, -1, 1074, 617, 1073, -1, + 1074, 1188, 841, -1, 1074, 1047, 618, -1, + 1074, 618, 617, -1, 1064, 1017, 1015, -1, + 1304, 1306, 879, -1, 1293, 1288, 1069, -1, + 1409, 1410, 712, -1, 1409, 712, 848, -1, + 852, 624, 619, -1, 852, 850, 624, -1, + 852, 620, 853, -1, 852, 621, 620, -1, + 852, 622, 621, -1, 852, 619, 622, -1, + 623, 624, 850, -1, 623, 625, 624, -1, + 623, 850, 851, -1, 623, 626, 627, -1, + 623, 627, 625, -1, 623, 851, 628, -1, + 623, 628, 626, -1, 639, 641, 629, -1, + 639, 629, 640, -1, 1078, 1079, 630, -1, + 1078, 630, 637, -1, 1078, 631, 854, -1, + 1078, 640, 632, -1, 1078, 632, 633, -1, + 1078, 634, 631, -1, 1078, 635, 634, -1, + 1078, 633, 635, -1, 636, 637, 638, -1, + 636, 639, 640, -1, 636, 640, 1078, -1, + 636, 1078, 637, -1, 636, 641, 639, -1, + 636, 642, 641, -1, 636, 638, 642, -1, + 643, 644, 645, -1, 643, 645, 646, -1, + 643, 646, 644, -1, 647, 649, 648, -1, + 647, 650, 649, -1, 647, 648, 650, -1, + 863, 857, 651, -1, 863, 652, 864, -1, + 863, 651, 652, -1, 861, 654, 653, -1, + 861, 653, 661, -1, 861, 655, 654, -1, + 861, 656, 655, -1, 861, 862, 657, -1, + 861, 658, 656, -1, 861, 657, 658, -1, + 860, 660, 659, -1, 860, 661, 660, -1, + 860, 659, 858, -1, 860, 861, 661, -1, + 662, 664, 663, -1, 662, 663, 665, -1, + 662, 666, 664, -1, 662, 665, 666, -1, + 667, 669, 668, -1, 667, 670, 669, -1, + 667, 671, 670, -1, 667, 672, 671, -1, + 667, 668, 672, -1, 865, 1010, 673, -1, + 865, 866, 811, -1, 865, 673, 1196, -1, + 674, 675, 676, -1, 674, 677, 675, -1, + 674, 676, 678, -1, 674, 678, 677, -1, + 679, 1169, 1170, -1, 679, 1306, 1169, -1, + 679, 1170, 1062, -1, 878, 866, 1194, -1, + 878, 1061, 866, -1, 878, 1062, 1061, -1, + 878, 679, 1062, -1, 878, 1306, 679, -1, + 882, 680, 883, -1, 882, 681, 680, -1, + 882, 891, 681, -1, 882, 685, 891, -1, + 884, 886, 686, -1, 884, 686, 685, -1, + 884, 685, 882, -1, 684, 1086, 686, -1, + 684, 903, 904, -1, 684, 904, 1086, -1, + 890, 682, 889, -1, 890, 683, 682, -1, + 890, 903, 684, -1, 890, 686, 683, -1, + 890, 684, 686, -1, 1085, 685, 686, -1, + 1085, 686, 1086, -1, 1085, 891, 685, -1, + 1089, 1083, 1088, -1, 1091, 1320, 1092, -1, + 1205, 896, 897, -1, 687, 889, 688, -1, + 687, 888, 889, -1, 687, 688, 905, -1, + 687, 905, 888, -1, 902, 905, 689, -1, + 902, 689, 690, -1, 902, 690, 916, -1, + 907, 1286, 906, -1, 907, 1180, 1286, -1, + 1299, 906, 691, -1, 1299, 691, 1542, -1, + 692, 693, 900, -1, 692, 900, 1202, -1, + 692, 846, 1515, -1, 692, 1515, 693, -1, + 692, 1094, 846, -1, 692, 1202, 1094, -1, + 1096, 917, 694, -1, 1096, 914, 917, -1, + 1096, 694, 695, -1, 1096, 695, 1097, -1, + 1096, 1083, 914, -1, 915, 911, 916, -1, + 709, 697, 696, -1, 709, 696, 707, -1, + 709, 698, 697, -1, 709, 923, 698, -1, + 919, 705, 699, -1, 919, 703, 705, -1, + 919, 1101, 927, -1, 919, 699, 1101, -1, + 919, 920, 703, -1, 700, 702, 701, -1, + 700, 703, 702, -1, 700, 701, 704, -1, + 700, 704, 705, -1, 700, 705, 703, -1, + 921, 706, 920, -1, 921, 707, 708, -1, + 921, 708, 706, -1, 921, 709, 707, -1, + 921, 923, 709, -1, 928, 922, 927, -1, + 928, 929, 923, -1, 928, 923, 922, -1, + 1100, 1101, 710, -1, 1100, 710, 926, -1, + 1100, 957, 929, -1, 931, 727, 932, -1, + 713, 712, 1410, -1, 713, 1410, 934, -1, + 711, 714, 848, -1, 711, 848, 712, -1, + 711, 934, 1221, -1, 711, 1221, 714, -1, + 711, 712, 713, -1, 711, 713, 934, -1, + 718, 714, 1220, -1, 718, 715, 714, -1, + 718, 719, 941, -1, 718, 941, 715, -1, + 716, 717, 944, -1, 716, 944, 1104, -1, + 716, 933, 717, -1, 716, 1104, 933, -1, + 1222, 719, 718, -1, 1222, 718, 1220, -1, + 1222, 944, 719, -1, 1222, 1104, 944, -1, + 1213, 1214, 720, -1, 1213, 720, 933, -1, + 1219, 1221, 934, -1, 1218, 1410, 721, -1, + 1218, 721, 1217, -1, 1071, 724, 1070, -1, + 1071, 722, 724, -1, 1071, 848, 723, -1, + 1071, 723, 722, -1, 938, 724, 725, -1, + 938, 725, 942, -1, 938, 939, 724, -1, + 943, 945, 726, -1, 943, 931, 942, -1, + 943, 726, 727, -1, 943, 727, 931, -1, + 728, 730, 729, -1, 728, 949, 730, -1, + 728, 729, 950, -1, 728, 950, 949, -1, + 737, 736, 730, -1, 737, 730, 949, -1, + 737, 949, 947, -1, 737, 947, 948, -1, + 731, 732, 933, -1, 731, 733, 732, -1, + 731, 952, 733, -1, 731, 933, 734, -1, + 731, 734, 952, -1, 954, 967, 744, -1, + 954, 744, 743, -1, 954, 953, 967, -1, + 954, 743, 735, -1, 954, 735, 736, -1, + 954, 736, 737, -1, 954, 737, 948, -1, + 954, 948, 738, -1, 954, 738, 952, -1, + 739, 960, 747, -1, 739, 740, 963, -1, + 739, 747, 740, -1, 739, 963, 741, -1, + 739, 741, 960, -1, 958, 956, 742, -1, + 958, 742, 748, -1, 964, 743, 744, -1, + 964, 745, 743, -1, 964, 744, 967, -1, + 964, 962, 745, -1, 746, 747, 960, -1, + 746, 748, 749, -1, 746, 960, 958, -1, + 746, 958, 748, -1, 746, 749, 750, -1, + 746, 750, 747, -1, 751, 752, 867, -1, + 751, 753, 752, -1, 751, 754, 753, -1, + 751, 867, 755, -1, 751, 755, 754, -1, + 756, 757, 758, -1, 756, 759, 757, -1, + 756, 758, 760, -1, 756, 761, 759, -1, + 756, 762, 761, -1, 756, 760, 762, -1, + 975, 763, 974, -1, 975, 976, 794, -1, + 975, 794, 763, -1, 764, 766, 765, -1, + 764, 765, 767, -1, 764, 767, 768, -1, + 764, 769, 766, -1, 764, 768, 769, -1, + 779, 778, 774, -1, 779, 770, 775, -1, + 779, 774, 770, -1, 771, 805, 797, -1, + 771, 772, 805, -1, 771, 797, 773, -1, + 771, 773, 774, -1, 771, 774, 772, -1, + 784, 775, 776, -1, 784, 776, 785, -1, + 784, 777, 778, -1, 784, 781, 777, -1, + 784, 778, 779, -1, 784, 779, 775, -1, + 780, 782, 781, -1, 780, 783, 782, -1, + 780, 781, 784, -1, 780, 784, 785, -1, + 780, 787, 786, -1, 780, 786, 783, -1, + 780, 790, 787, -1, 780, 785, 790, -1, + 969, 970, 788, -1, 969, 788, 795, -1, + 969, 795, 976, -1, 971, 789, 790, -1, + 971, 790, 970, -1, 971, 973, 791, -1, + 971, 791, 789, -1, 1024, 1148, 1025, -1, + 1365, 792, 1013, -1, 1365, 980, 792, -1, + 1107, 1036, 1035, -1, 1107, 1035, 1034, -1, + 793, 794, 795, -1, 793, 796, 794, -1, + 793, 795, 797, -1, 793, 797, 805, -1, + 793, 805, 796, -1, 1033, 1148, 1024, -1, + 1033, 1024, 1034, -1, 1029, 1030, 802, -1, + 1029, 802, 798, -1, 1029, 798, 1152, -1, + 1029, 1152, 1151, -1, 799, 1031, 1049, -1, + 799, 1030, 1031, -1, 799, 1049, 1050, -1, + 799, 1050, 800, -1, 799, 800, 801, -1, + 799, 801, 802, -1, 799, 802, 1030, -1, + 991, 990, 1245, -1, 991, 1245, 984, -1, + 991, 983, 989, -1, 803, 1020, 820, -1, + 806, 1020, 803, -1, 806, 820, 807, -1, + 806, 803, 820, -1, 804, 805, 820, -1, + 804, 820, 1020, -1, 804, 823, 805, -1, + 804, 1020, 823, -1, 1019, 1020, 806, -1, + 1019, 807, 1022, -1, 1019, 806, 807, -1, + 986, 987, 978, -1, 986, 1023, 1022, -1, + 986, 978, 1023, -1, 986, 808, 990, -1, + 986, 1022, 808, -1, 1230, 819, 996, -1, + 1230, 1227, 819, -1, 1230, 1119, 1231, -1, + 1111, 809, 1233, -1, 1111, 810, 809, -1, + 1111, 1112, 810, -1, 1252, 1224, 1009, -1, + 1261, 811, 1115, -1, 1261, 865, 811, -1, + 1261, 1010, 865, -1, 1116, 813, 812, -1, + 1116, 1115, 813, -1, 1116, 812, 1015, -1, + 997, 998, 814, -1, 997, 814, 815, -1, + 997, 815, 1122, -1, 1125, 995, 1000, -1, + 816, 818, 817, -1, 816, 817, 995, -1, + 816, 995, 996, -1, 816, 819, 818, -1, + 816, 996, 819, -1, 1244, 1245, 1352, -1, + 1248, 820, 1006, -1, 1248, 1245, 820, -1, + 1011, 1139, 822, -1, 1011, 1138, 1139, -1, + 1011, 822, 1265, -1, 1242, 1012, 1241, -1, + 1135, 1142, 1126, -1, 1135, 1126, 1238, -1, + 1027, 1265, 822, -1, 1027, 822, 831, -1, + 821, 1038, 1153, -1, 821, 1153, 831, -1, + 821, 831, 822, -1, 821, 822, 1016, -1, + 821, 1016, 1038, -1, 1141, 822, 1139, -1, + 1141, 1016, 822, -1, 1141, 1139, 1142, -1, + 1039, 1038, 1016, -1, 1039, 1017, 1064, -1, + 1039, 1064, 1037, -1, 1021, 823, 1020, -1, + 1021, 1026, 823, -1, 824, 825, 826, -1, + 824, 827, 825, -1, 824, 828, 827, -1, + 824, 826, 1026, -1, 824, 1026, 828, -1, + 1274, 1275, 829, -1, 1274, 829, 1277, -1, + 1273, 1027, 831, -1, 830, 1279, 1275, -1, + 830, 1153, 1279, -1, 830, 831, 1153, -1, + 830, 1273, 831, -1, 830, 1275, 1273, -1, + 1150, 1029, 1151, -1, 832, 1044, 1041, -1, + 832, 1041, 1280, -1, 1042, 1044, 1330, -1, + 1155, 1330, 1044, -1, 1155, 1044, 832, -1, + 1155, 832, 1280, -1, 1046, 833, 1047, -1, + 1046, 1048, 834, -1, 1046, 834, 835, -1, + 1046, 836, 833, -1, 1046, 835, 836, -1, + 1056, 837, 1186, -1, 1056, 838, 837, -1, + 1056, 1053, 1054, -1, 1056, 1054, 838, -1, + 1055, 1186, 1073, -1, 1055, 1073, 1054, -1, + 1060, 1072, 1186, -1, 1060, 1186, 1058, -1, + 1060, 1059, 839, -1, 1060, 839, 1072, -1, + 840, 1074, 841, -1, 840, 841, 842, -1, + 840, 842, 843, -1, 840, 843, 1047, -1, + 840, 1047, 1074, -1, 844, 1167, 1168, -1, + 844, 1168, 1172, -1, 844, 1172, 1167, -1, + 1161, 1015, 1162, -1, 1161, 1064, 1015, -1, + 1389, 1170, 1390, -1, 1065, 1172, 1168, -1, + 1065, 1168, 1164, -1, 1063, 1037, 1064, -1, + 1063, 1375, 1037, -1, 1063, 1377, 1375, -1, + 1308, 1167, 1172, -1, 1464, 880, 1066, -1, + 1464, 1067, 880, -1, 1305, 1169, 845, -1, + 1305, 845, 1306, -1, 1289, 1291, 1288, -1, + 1399, 846, 1094, -1, 1399, 1094, 1313, -1, + 1399, 1515, 846, -1, 1399, 1517, 1515, -1, + 1187, 1183, 847, -1, 1187, 1334, 1183, -1, + 1187, 847, 1188, -1, 1408, 1409, 848, -1, + 1408, 848, 1071, -1, 849, 851, 850, -1, + 849, 850, 852, -1, 849, 853, 851, -1, + 849, 852, 853, -1, 1076, 1078, 854, -1, + 1076, 855, 1077, -1, 1076, 854, 855, -1, + 856, 858, 857, -1, 856, 860, 858, -1, + 856, 857, 863, -1, 856, 863, 860, -1, + 859, 861, 860, -1, 859, 862, 861, -1, + 859, 860, 863, -1, 859, 864, 862, -1, + 859, 863, 864, -1, 1193, 865, 1196, -1, + 1193, 1194, 866, -1, 1193, 866, 865, -1, + 871, 896, 875, -1, 871, 870, 867, -1, + 871, 867, 896, -1, 868, 869, 870, -1, + 868, 870, 871, -1, 868, 871, 875, -1, + 868, 872, 869, -1, 868, 876, 872, -1, + 868, 875, 876, -1, 873, 896, 898, -1, + 873, 898, 875, -1, 873, 875, 896, -1, + 874, 875, 898, -1, 874, 876, 875, -1, + 874, 898, 899, -1, 874, 899, 876, -1, + 877, 1194, 1191, -1, 877, 878, 1194, -1, + 877, 1306, 878, -1, 877, 879, 1306, -1, + 877, 1191, 879, -1, 1190, 1304, 879, -1, + 1190, 879, 1191, -1, 1198, 880, 1178, -1, + 1198, 1197, 880, -1, 881, 882, 883, -1, + 881, 884, 882, -1, 881, 883, 885, -1, + 881, 885, 886, -1, 881, 886, 884, -1, + 887, 889, 888, -1, 887, 890, 889, -1, + 887, 888, 905, -1, 887, 905, 903, -1, + 887, 903, 890, -1, 1087, 891, 1085, -1, + 1087, 893, 892, -1, 1087, 1081, 893, -1, + 1087, 1082, 891, -1, 1087, 892, 1082, -1, + 1090, 904, 912, -1, 1090, 1086, 904, -1, + 1090, 912, 1083, -1, 1090, 1083, 1089, -1, + 894, 1286, 1320, -1, 894, 1091, 1286, -1, + 894, 1320, 1091, -1, 895, 898, 896, -1, + 895, 1205, 898, -1, 895, 896, 1205, -1, + 1206, 897, 1286, -1, 1206, 1205, 897, -1, + 1206, 1286, 1091, -1, 1204, 899, 898, -1, + 1204, 898, 1205, -1, 1204, 900, 899, -1, + 1204, 1203, 900, -1, 901, 916, 911, -1, + 901, 902, 916, -1, 901, 904, 903, -1, + 901, 911, 904, -1, 901, 903, 905, -1, + 901, 905, 902, -1, 1179, 906, 1299, -1, + 1179, 907, 906, -1, 1179, 1180, 907, -1, + 1319, 1092, 1320, -1, 1319, 1323, 1209, -1, + 1098, 909, 908, -1, 1098, 1097, 909, -1, + 1098, 908, 1083, -1, 1098, 1083, 1096, -1, + 910, 912, 911, -1, 910, 911, 915, -1, + 910, 1083, 912, -1, 910, 915, 1083, -1, + 913, 914, 1083, -1, 913, 1083, 915, -1, + 913, 915, 916, -1, 913, 916, 917, -1, + 913, 917, 914, -1, 918, 920, 919, -1, + 918, 921, 920, -1, 918, 927, 922, -1, + 918, 919, 927, -1, 918, 922, 923, -1, + 918, 923, 921, -1, 924, 926, 925, -1, + 924, 1100, 926, -1, 924, 925, 957, -1, + 924, 957, 1100, -1, 1102, 927, 1101, -1, + 1102, 928, 927, -1, 1102, 929, 928, -1, + 1102, 1100, 929, -1, 930, 942, 931, -1, + 930, 938, 942, -1, 930, 936, 938, -1, + 930, 932, 936, -1, 930, 931, 932, -1, + 1103, 933, 1104, -1, 1103, 1213, 933, -1, + 1106, 934, 1410, -1, 1106, 1219, 934, -1, + 935, 936, 937, -1, 935, 938, 936, -1, + 935, 937, 939, -1, 935, 939, 938, -1, + 940, 942, 941, -1, 940, 943, 942, -1, + 940, 941, 944, -1, 940, 944, 945, -1, + 940, 945, 943, -1, 946, 948, 947, -1, + 946, 947, 949, -1, 946, 950, 948, -1, + 946, 949, 950, -1, 951, 952, 953, -1, + 951, 953, 954, -1, 951, 954, 952, -1, + 955, 957, 956, -1, 955, 956, 958, -1, + 955, 959, 957, -1, 955, 960, 959, -1, + 955, 958, 960, -1, 961, 963, 962, -1, + 961, 962, 964, -1, 961, 965, 963, -1, + 961, 966, 965, -1, 961, 967, 966, -1, + 961, 964, 967, -1, 968, 970, 969, -1, + 968, 971, 970, -1, 968, 972, 973, -1, + 968, 973, 971, -1, 968, 974, 972, -1, + 968, 975, 974, -1, 968, 976, 975, -1, + 968, 969, 976, -1, 977, 1023, 978, -1, + 977, 1024, 1023, -1, 977, 1034, 1024, -1, + 977, 981, 1034, -1, 977, 987, 981, -1, + 977, 978, 987, -1, 1366, 980, 1365, -1, + 1366, 1107, 980, -1, 1108, 1109, 1036, -1, + 1108, 1036, 1107, -1, 979, 981, 980, -1, + 979, 980, 1107, -1, 979, 1034, 981, -1, + 979, 1107, 1034, -1, 982, 984, 983, -1, + 982, 991, 984, -1, 982, 983, 991, -1, + 985, 987, 986, -1, 985, 989, 988, -1, + 985, 988, 987, -1, 985, 986, 990, -1, + 985, 990, 991, -1, 985, 991, 989, -1, + 1123, 1122, 1112, -1, 1232, 1231, 1119, -1, + 1008, 1225, 1252, -1, 1008, 1252, 1253, -1, + 1344, 1009, 1224, -1, 999, 993, 992, -1, + 999, 1000, 993, -1, 999, 992, 994, -1, + 999, 994, 998, -1, 1118, 996, 995, -1, + 1118, 995, 1125, -1, 1118, 1230, 996, -1, + 1121, 997, 1122, -1, 1121, 998, 997, -1, + 1121, 999, 998, -1, 1121, 1125, 1000, -1, + 1121, 1000, 999, -1, 1129, 1127, 1248, -1, + 1129, 1248, 1004, -1, 1129, 1004, 1251, -1, + 1129, 1251, 1239, -1, 1350, 1128, 1270, -1, + 1007, 1005, 1001, -1, 1007, 1001, 1002, -1, + 1007, 1002, 1003, -1, 1007, 1003, 1225, -1, + 1007, 1225, 1008, -1, 1250, 1004, 1248, -1, + 1250, 1251, 1004, -1, 1247, 1006, 1005, -1, + 1247, 1248, 1006, -1, 1247, 1005, 1007, -1, + 1247, 1008, 1253, -1, 1247, 1007, 1008, -1, + 1354, 1252, 1009, -1, 1354, 1009, 1344, -1, + 1263, 1131, 1010, -1, 1263, 1010, 1261, -1, + 1134, 1011, 1265, -1, 1134, 1138, 1011, -1, + 1134, 1268, 1138, -1, 1134, 1242, 1268, -1, + 1133, 1012, 1242, -1, 1133, 1013, 1014, -1, + 1133, 1014, 1012, -1, 1133, 1365, 1013, -1, + 1145, 1015, 1017, -1, 1145, 1136, 1116, -1, + 1145, 1116, 1015, -1, 1271, 1126, 1142, -1, + 1271, 1270, 1126, -1, 1271, 1142, 1139, -1, + 1143, 1016, 1141, -1, 1143, 1039, 1016, -1, + 1143, 1017, 1039, -1, 1143, 1145, 1017, -1, + 1018, 1020, 1019, -1, 1018, 1021, 1020, -1, + 1018, 1022, 1023, -1, 1018, 1019, 1022, -1, + 1018, 1023, 1024, -1, 1018, 1024, 1025, -1, + 1018, 1025, 1026, -1, 1018, 1026, 1021, -1, + 1368, 1265, 1027, -1, 1368, 1027, 1273, -1, + 1028, 1029, 1150, -1, 1028, 1030, 1029, -1, + 1028, 1031, 1030, -1, 1028, 1032, 1031, -1, + 1028, 1036, 1032, -1, 1028, 1150, 1036, -1, + 1147, 1148, 1033, -1, 1147, 1034, 1035, -1, + 1147, 1033, 1034, -1, 1147, 1035, 1036, -1, + 1147, 1036, 1150, -1, 1374, 1037, 1375, -1, + 1374, 1153, 1038, -1, 1374, 1039, 1037, -1, + 1374, 1038, 1039, -1, 1329, 1072, 1042, -1, + 1329, 1042, 1330, -1, 1040, 1072, 1041, -1, + 1040, 1042, 1072, -1, 1040, 1041, 1043, -1, + 1040, 1043, 1044, -1, 1040, 1044, 1042, -1, + 1157, 1284, 1330, -1, 1157, 1155, 1156, -1, + 1157, 1330, 1155, -1, 1154, 1372, 1283, -1, + 1154, 1283, 1284, -1, 1154, 1284, 1157, -1, + 1331, 1330, 1284, -1, 1045, 1046, 1047, -1, + 1045, 1048, 1046, -1, 1045, 1049, 1048, -1, + 1045, 1050, 1049, -1, 1045, 1047, 1051, -1, + 1045, 1051, 1050, -1, 1052, 1054, 1053, -1, + 1052, 1055, 1054, -1, 1052, 1186, 1055, -1, + 1052, 1053, 1056, -1, 1052, 1056, 1186, -1, + 1057, 1058, 1059, -1, 1057, 1059, 1060, -1, + 1057, 1060, 1058, -1, 1173, 1162, 1061, -1, + 1173, 1061, 1062, -1, 1173, 1062, 1170, -1, + 1173, 1170, 1389, -1, 1166, 1377, 1063, -1, + 1160, 1063, 1064, -1, 1160, 1064, 1161, -1, + 1160, 1164, 1166, -1, 1160, 1166, 1063, -1, + 1160, 1065, 1164, -1, 1160, 1172, 1065, -1, + 1536, 1537, 1093, -1, 1536, 1093, 1300, -1, + 1448, 1445, 1165, -1, 1448, 1165, 1164, -1, + 1448, 1164, 1168, -1, 1309, 1308, 1172, -1, + 1312, 1464, 1066, -1, 1312, 1066, 1174, -1, + 1177, 1178, 1067, -1, 1177, 1067, 1464, -1, + 1411, 1068, 1410, -1, 1294, 1214, 1068, -1, + 1294, 1069, 1214, -1, 1294, 1068, 1411, -1, + 1294, 1411, 1295, -1, 1294, 1293, 1069, -1, + 1324, 1300, 1093, -1, 1324, 1093, 1322, -1, + 1326, 1070, 1184, -1, 1326, 1071, 1070, -1, + 1326, 1408, 1071, -1, 1403, 1186, 1072, -1, + 1403, 1072, 1329, -1, 1414, 1188, 1074, -1, + 1416, 1073, 1186, -1, 1416, 1074, 1073, -1, + 1416, 1414, 1074, -1, 1075, 1076, 1077, -1, + 1075, 1078, 1076, -1, 1075, 1077, 1079, -1, + 1075, 1079, 1078, -1, 1195, 1198, 1178, -1, + 1195, 1191, 1194, -1, 1387, 1304, 1190, -1, + 1080, 1087, 1088, -1, 1080, 1081, 1087, -1, + 1080, 1082, 1081, -1, 1080, 1083, 1082, -1, + 1080, 1088, 1083, -1, 1084, 1085, 1086, -1, + 1084, 1087, 1085, -1, 1084, 1088, 1087, -1, + 1084, 1089, 1088, -1, 1084, 1086, 1090, -1, + 1084, 1090, 1089, -1, 1201, 1091, 1092, -1, + 1201, 1206, 1091, -1, 1201, 1092, 1319, -1, + 1201, 1319, 1209, -1, 1395, 1313, 1094, -1, + 1211, 1322, 1093, -1, 1211, 1323, 1322, -1, + 1211, 1093, 1537, -1, 1211, 1397, 1396, -1, + 1210, 1200, 1209, -1, 1210, 1396, 1395, -1, + 1210, 1395, 1094, -1, 1210, 1094, 1202, -1, + 1210, 1202, 1200, -1, 1095, 1096, 1097, -1, + 1095, 1097, 1098, -1, 1095, 1098, 1096, -1, + 1099, 1101, 1100, -1, 1099, 1102, 1101, -1, + 1099, 1100, 1102, -1, 1216, 1213, 1103, -1, + 1216, 1104, 1222, -1, 1216, 1103, 1104, -1, + 1105, 1218, 1219, -1, 1105, 1219, 1106, -1, + 1105, 1410, 1218, -1, 1105, 1106, 1410, -1, + 1369, 1107, 1366, -1, 1369, 1108, 1107, -1, + 1369, 1276, 1109, -1, 1369, 1109, 1108, -1, + 1229, 1232, 1224, -1, 1229, 1225, 1110, -1, + 1229, 1110, 1228, -1, 1347, 1111, 1233, -1, + 1347, 1346, 1123, -1, 1347, 1112, 1111, -1, + 1347, 1123, 1112, -1, 1113, 1346, 1119, -1, + 1113, 1123, 1346, -1, 1113, 1119, 1124, -1, + 1113, 1124, 1123, -1, 1114, 1224, 1232, -1, + 1114, 1232, 1119, -1, 1114, 1119, 1346, -1, + 1345, 1114, 1346, -1, 1345, 1344, 1224, -1, + 1345, 1224, 1114, -1, 1260, 1261, 1115, -1, + 1260, 1116, 1136, -1, 1260, 1115, 1116, -1, + 1137, 1238, 1132, -1, 1137, 1135, 1238, -1, + 1137, 1260, 1136, -1, 1137, 1132, 1260, -1, + 1359, 1132, 1238, -1, 1117, 1230, 1118, -1, + 1117, 1124, 1119, -1, 1117, 1119, 1230, -1, + 1117, 1125, 1124, -1, 1117, 1118, 1125, -1, + 1120, 1121, 1122, -1, 1120, 1122, 1123, -1, + 1120, 1123, 1124, -1, 1120, 1124, 1125, -1, + 1120, 1125, 1121, -1, 1237, 1238, 1126, -1, + 1237, 1128, 1239, -1, 1237, 1126, 1270, -1, + 1237, 1270, 1128, -1, 1130, 1127, 1129, -1, + 1130, 1248, 1127, -1, 1130, 1352, 1245, -1, + 1130, 1245, 1248, -1, 1349, 1239, 1128, -1, + 1349, 1129, 1239, -1, 1349, 1128, 1350, -1, + 1349, 1352, 1130, -1, 1349, 1130, 1129, -1, + 1267, 1350, 1270, -1, 1249, 1250, 1248, -1, + 1249, 1254, 1250, -1, 1256, 1362, 1354, -1, + 1256, 1354, 1344, -1, 1255, 1343, 1235, -1, + 1255, 1131, 1263, -1, 1255, 1234, 1131, -1, + 1255, 1235, 1234, -1, 1262, 1132, 1359, -1, + 1262, 1260, 1132, -1, 1264, 1365, 1133, -1, + 1264, 1134, 1265, -1, 1264, 1242, 1134, -1, + 1264, 1133, 1242, -1, 1144, 1142, 1135, -1, + 1144, 1136, 1145, -1, 1144, 1137, 1136, -1, + 1144, 1135, 1137, -1, 1269, 1139, 1138, -1, + 1269, 1271, 1139, -1, 1269, 1138, 1268, -1, + 1140, 1141, 1142, -1, 1140, 1143, 1141, -1, + 1140, 1142, 1144, -1, 1140, 1145, 1143, -1, + 1140, 1144, 1145, -1, 1367, 1368, 1273, -1, + 1146, 1148, 1147, -1, 1146, 1149, 1148, -1, + 1146, 1150, 1151, -1, 1146, 1147, 1150, -1, + 1146, 1152, 1149, -1, 1146, 1151, 1152, -1, + 1376, 1377, 1158, -1, 1376, 1158, 1372, -1, + 1373, 1153, 1374, -1, 1373, 1279, 1153, -1, + 1278, 1372, 1154, -1, 1278, 1155, 1280, -1, + 1278, 1156, 1155, -1, 1278, 1157, 1156, -1, + 1278, 1154, 1157, -1, 1447, 1283, 1372, -1, + 1447, 1372, 1158, -1, 1447, 1158, 1377, -1, + 1378, 1427, 1477, -1, 1378, 1477, 1478, -1, + 1439, 1380, 1381, -1, 1159, 1173, 1172, -1, + 1159, 1172, 1160, -1, 1159, 1160, 1161, -1, + 1159, 1161, 1162, -1, 1159, 1162, 1173, -1, + 1163, 1164, 1165, -1, 1163, 1166, 1164, -1, + 1163, 1165, 1166, -1, 1281, 1165, 1445, -1, + 1281, 1166, 1165, -1, 1281, 1377, 1166, -1, + 1285, 1502, 1297, -1, 1285, 1338, 1502, -1, + 1285, 1454, 1338, -1, 1339, 1340, 1297, -1, + 1339, 1297, 1502, -1, 1314, 1340, 1293, -1, + 1315, 1424, 1386, -1, 1301, 1167, 1308, -1, + 1301, 1168, 1167, -1, 1301, 1448, 1168, -1, + 1450, 1381, 1380, -1, 1506, 1304, 1387, -1, + 1307, 1304, 1506, -1, 1307, 1506, 1511, -1, + 1307, 1169, 1305, -1, 1307, 1170, 1169, -1, + 1307, 1390, 1170, -1, 1307, 1510, 1308, -1, + 1307, 1511, 1510, -1, 1171, 1309, 1172, -1, + 1171, 1389, 1309, -1, 1171, 1172, 1173, -1, + 1171, 1173, 1389, -1, 1463, 1312, 1174, -1, + 1463, 1174, 1175, -1, 1463, 1175, 1310, -1, + 1176, 1178, 1177, -1, 1176, 1177, 1464, -1, + 1176, 1464, 1387, -1, 1176, 1195, 1178, -1, + 1176, 1387, 1195, -1, 1426, 1424, 1316, -1, + 1321, 1179, 1299, -1, 1321, 1299, 1324, -1, + 1321, 1181, 1180, -1, 1321, 1180, 1179, -1, + 1321, 1320, 1181, -1, 1182, 1183, 1334, -1, + 1182, 1334, 1326, -1, 1182, 1326, 1184, -1, + 1182, 1185, 1183, -1, 1182, 1184, 1185, -1, + 1327, 1326, 1334, -1, 1404, 1186, 1403, -1, + 1404, 1416, 1186, -1, 1404, 1418, 1416, -1, + 1475, 1331, 1478, -1, 1333, 1187, 1188, -1, + 1333, 1188, 1414, -1, 1333, 1334, 1187, -1, + 1337, 1481, 1436, -1, 1499, 1502, 1338, -1, + 1189, 1190, 1191, -1, 1189, 1191, 1195, -1, + 1189, 1387, 1190, -1, 1189, 1195, 1387, -1, + 1192, 1194, 1193, -1, 1192, 1195, 1194, -1, + 1192, 1193, 1196, -1, 1192, 1196, 1197, -1, + 1192, 1197, 1198, -1, 1192, 1198, 1195, -1, + 1199, 1209, 1200, -1, 1199, 1201, 1209, -1, + 1199, 1202, 1203, -1, 1199, 1200, 1202, -1, + 1199, 1203, 1204, -1, 1199, 1204, 1205, -1, + 1199, 1205, 1206, -1, 1199, 1206, 1201, -1, + 1207, 1211, 1537, -1, 1207, 1397, 1211, -1, + 1207, 1537, 1539, -1, 1207, 1539, 1541, -1, + 1207, 1541, 1543, -1, 1207, 1543, 1397, -1, + 1208, 1209, 1323, -1, 1208, 1210, 1209, -1, + 1208, 1396, 1210, -1, 1208, 1323, 1211, -1, + 1208, 1211, 1396, -1, 1212, 1216, 1217, -1, + 1212, 1213, 1216, -1, 1212, 1217, 1214, -1, + 1212, 1214, 1213, -1, 1215, 1217, 1216, -1, + 1215, 1218, 1217, -1, 1215, 1219, 1218, -1, + 1215, 1220, 1221, -1, 1215, 1221, 1219, -1, + 1215, 1222, 1220, -1, 1215, 1216, 1222, -1, + 1223, 1224, 1252, -1, 1223, 1229, 1224, -1, + 1223, 1252, 1225, -1, 1223, 1225, 1229, -1, + 1226, 1228, 1227, -1, 1226, 1229, 1228, -1, + 1226, 1227, 1230, -1, 1226, 1230, 1231, -1, + 1226, 1231, 1232, -1, 1226, 1232, 1229, -1, + 1342, 1347, 1233, -1, 1342, 1233, 1234, -1, + 1342, 1234, 1235, -1, 1342, 1235, 1343, -1, + 1358, 1239, 1251, -1, 1358, 1359, 1238, -1, + 1236, 1238, 1237, -1, 1236, 1237, 1239, -1, + 1236, 1358, 1238, -1, 1236, 1239, 1358, -1, + 1240, 1241, 1243, -1, 1240, 1243, 1267, -1, + 1240, 1267, 1268, -1, 1240, 1268, 1242, -1, + 1240, 1242, 1241, -1, 1351, 1350, 1267, -1, + 1351, 1267, 1243, -1, 1351, 1244, 1352, -1, + 1351, 1243, 1245, -1, 1351, 1245, 1244, -1, + 1246, 1248, 1247, -1, 1246, 1249, 1248, -1, + 1246, 1254, 1249, -1, 1246, 1253, 1254, -1, + 1246, 1247, 1253, -1, 1357, 1251, 1250, -1, + 1357, 1358, 1251, -1, 1357, 1250, 1254, -1, + 1357, 1254, 1353, -1, 1355, 1252, 1354, -1, + 1355, 1253, 1252, -1, 1355, 1254, 1253, -1, + 1355, 1353, 1254, -1, 1258, 1343, 1255, -1, + 1258, 1344, 1343, -1, 1258, 1256, 1344, -1, + 1258, 1362, 1256, -1, 1258, 1255, 1263, -1, + 1257, 1262, 1362, -1, 1257, 1263, 1262, -1, + 1257, 1362, 1258, -1, 1257, 1258, 1263, -1, + 1360, 1362, 1262, -1, 1360, 1262, 1359, -1, + 1259, 1261, 1260, -1, 1259, 1260, 1262, -1, + 1259, 1263, 1261, -1, 1259, 1262, 1263, -1, + 1364, 1365, 1264, -1, 1364, 1265, 1368, -1, + 1364, 1264, 1265, -1, 1266, 1268, 1267, -1, + 1266, 1269, 1268, -1, 1266, 1267, 1270, -1, + 1266, 1270, 1271, -1, 1266, 1271, 1269, -1, + 1272, 1367, 1273, -1, 1272, 1275, 1274, -1, + 1272, 1273, 1275, -1, 1272, 1276, 1369, -1, + 1272, 1369, 1367, -1, 1272, 1277, 1276, -1, + 1272, 1274, 1277, -1, 1371, 1372, 1278, -1, + 1371, 1279, 1373, -1, 1371, 1280, 1279, -1, + 1371, 1278, 1280, -1, 1379, 1447, 1377, -1, + 1379, 1281, 1445, -1, 1379, 1377, 1281, -1, + 1282, 1284, 1283, -1, 1282, 1283, 1447, -1, + 1282, 1331, 1284, -1, 1282, 1447, 1331, -1, + 1443, 1331, 1447, -1, 1443, 1478, 1331, -1, + 1434, 1436, 1427, -1, 1434, 1427, 1378, -1, + 1434, 1378, 1380, -1, 1446, 1450, 1380, -1, + 1505, 1439, 1381, -1, 1382, 1423, 1337, -1, + 1382, 1337, 1453, -1, 1422, 1423, 1384, -1, + 1385, 1424, 1422, -1, 1385, 1422, 1384, -1, + 1298, 1285, 1297, -1, 1298, 1386, 1455, -1, + 1298, 1454, 1285, -1, 1298, 1455, 1454, -1, + 1501, 1542, 1286, -1, 1501, 1293, 1340, -1, + 1501, 1286, 1287, -1, 1501, 1288, 1293, -1, + 1501, 1289, 1288, -1, 1501, 1287, 1290, -1, + 1501, 1290, 1291, -1, 1501, 1291, 1289, -1, + 1292, 1314, 1293, -1, 1292, 1293, 1294, -1, + 1292, 1294, 1295, -1, 1292, 1295, 1411, -1, + 1292, 1411, 1314, -1, 1296, 1297, 1340, -1, + 1296, 1340, 1315, -1, 1296, 1298, 1297, -1, + 1296, 1315, 1386, -1, 1296, 1386, 1298, -1, + 1540, 1299, 1542, -1, 1540, 1300, 1324, -1, + 1540, 1324, 1299, -1, 1540, 1536, 1300, -1, + 1540, 1538, 1536, -1, 1302, 1301, 1308, -1, + 1302, 1448, 1301, -1, 1302, 1308, 1510, -1, + 1449, 1448, 1302, -1, 1449, 1302, 1510, -1, + 1449, 1450, 1446, -1, 1457, 1531, 1506, -1, + 1457, 1506, 1387, -1, 1303, 1304, 1307, -1, + 1303, 1307, 1305, -1, 1303, 1306, 1304, -1, + 1303, 1305, 1306, -1, 1391, 1390, 1307, -1, + 1391, 1307, 1308, -1, 1391, 1309, 1389, -1, + 1391, 1308, 1309, -1, 1466, 1463, 1310, -1, + 1466, 1310, 1311, -1, 1466, 1311, 1392, -1, + 1462, 1464, 1312, -1, 1462, 1312, 1463, -1, + 1520, 1313, 1395, -1, 1520, 1399, 1313, -1, + 1317, 1314, 1411, -1, 1317, 1340, 1314, -1, + 1317, 1315, 1340, -1, 1317, 1424, 1315, -1, + 1317, 1316, 1424, -1, 1419, 1426, 1316, -1, + 1419, 1317, 1411, -1, 1419, 1316, 1317, -1, + 1417, 1416, 1418, -1, 1318, 1319, 1320, -1, + 1318, 1320, 1321, -1, 1318, 1322, 1323, -1, + 1318, 1323, 1319, -1, 1318, 1324, 1322, -1, + 1318, 1321, 1324, -1, 1415, 1327, 1334, -1, + 1415, 1419, 1411, -1, 1325, 1408, 1326, -1, + 1325, 1326, 1327, -1, 1325, 1415, 1408, -1, + 1325, 1327, 1415, -1, 1328, 1424, 1426, -1, + 1328, 1425, 1424, -1, 1328, 1426, 1425, -1, + 1430, 1431, 1403, -1, 1430, 1329, 1330, -1, + 1430, 1403, 1329, -1, 1430, 1330, 1331, -1, + 1430, 1331, 1475, -1, 1413, 1333, 1414, -1, + 1413, 1415, 1335, -1, 1332, 1334, 1333, -1, + 1332, 1415, 1334, -1, 1332, 1335, 1415, -1, + 1332, 1413, 1335, -1, 1332, 1333, 1413, -1, + 1480, 1424, 1425, -1, 1336, 1337, 1423, -1, + 1336, 1481, 1337, -1, 1336, 1423, 1480, -1, + 1336, 1480, 1481, -1, 1437, 1453, 1337, -1, + 1437, 1488, 1490, -1, 1437, 1490, 1453, -1, + 1437, 1337, 1436, -1, 1440, 1499, 1338, -1, + 1440, 1338, 1454, -1, 1440, 1454, 1491, -1, + 1500, 1339, 1502, -1, 1500, 1340, 1339, -1, + 1500, 1501, 1340, -1, 1341, 1342, 1343, -1, + 1341, 1343, 1344, -1, 1341, 1344, 1345, -1, + 1341, 1345, 1346, -1, 1341, 1346, 1347, -1, + 1341, 1347, 1342, -1, 1348, 1349, 1350, -1, + 1348, 1350, 1351, -1, 1348, 1352, 1349, -1, + 1348, 1351, 1352, -1, 1361, 1357, 1353, -1, + 1361, 1354, 1362, -1, 1361, 1355, 1354, -1, + 1361, 1353, 1355, -1, 1356, 1358, 1357, -1, + 1356, 1359, 1358, -1, 1356, 1360, 1359, -1, + 1356, 1357, 1361, -1, 1356, 1362, 1360, -1, + 1356, 1361, 1362, -1, 1363, 1365, 1364, -1, + 1363, 1366, 1365, -1, 1363, 1368, 1367, -1, + 1363, 1364, 1368, -1, 1363, 1369, 1366, -1, + 1363, 1367, 1369, -1, 1370, 1372, 1371, -1, + 1370, 1371, 1373, -1, 1370, 1373, 1374, -1, + 1370, 1374, 1375, -1, 1370, 1376, 1372, -1, + 1370, 1375, 1377, -1, 1370, 1377, 1376, -1, + 1442, 1378, 1478, -1, 1442, 1478, 1443, -1, + 1442, 1380, 1378, -1, 1442, 1446, 1380, -1, + 1444, 1379, 1445, -1, 1444, 1447, 1379, -1, + 1433, 1434, 1380, -1, 1433, 1380, 1439, -1, + 1487, 1488, 1435, -1, 1487, 1433, 1439, -1, + 1487, 1435, 1433, -1, 1504, 1381, 1450, -1, + 1504, 1505, 1381, -1, 1452, 1384, 1423, -1, + 1452, 1423, 1382, -1, 1452, 1455, 1384, -1, + 1452, 1382, 1453, -1, 1383, 1384, 1455, -1, + 1383, 1385, 1384, -1, 1383, 1455, 1386, -1, + 1383, 1386, 1424, -1, 1383, 1424, 1385, -1, + 1495, 1531, 1457, -1, 1459, 1387, 1464, -1, + 1459, 1457, 1387, -1, 1388, 1389, 1390, -1, + 1388, 1390, 1391, -1, 1388, 1391, 1389, -1, + 1465, 1392, 1393, -1, 1465, 1466, 1392, -1, + 1465, 1393, 1394, -1, 1465, 1394, 1467, -1, + 1516, 1400, 1461, -1, 1516, 1517, 1400, -1, + 1519, 1520, 1395, -1, 1519, 1396, 1397, -1, + 1519, 1395, 1396, -1, 1519, 1397, 1543, -1, + 1398, 1399, 1520, -1, 1398, 1517, 1399, -1, + 1398, 1400, 1517, -1, 1398, 1520, 1472, -1, + 1398, 1472, 1461, -1, 1398, 1461, 1400, -1, + 1524, 1461, 1472, -1, 1524, 1460, 1461, -1, + 1420, 1406, 1426, -1, 1401, 1428, 1426, -1, + 1401, 1426, 1406, -1, 1405, 1474, 1428, -1, + 1405, 1431, 1474, -1, 1405, 1428, 1401, -1, + 1405, 1401, 1406, -1, 1402, 1403, 1431, -1, + 1402, 1404, 1403, -1, 1402, 1431, 1405, -1, + 1402, 1405, 1406, -1, 1402, 1418, 1404, -1, + 1402, 1420, 1418, -1, 1402, 1406, 1420, -1, + 1407, 1409, 1408, -1, 1407, 1408, 1415, -1, + 1407, 1410, 1409, -1, 1407, 1411, 1410, -1, + 1407, 1415, 1411, -1, 1412, 1413, 1414, -1, + 1412, 1415, 1413, -1, 1412, 1414, 1416, -1, + 1412, 1416, 1417, -1, 1412, 1417, 1418, -1, + 1412, 1426, 1419, -1, 1412, 1419, 1415, -1, + 1412, 1418, 1420, -1, 1412, 1420, 1426, -1, + 1421, 1423, 1422, -1, 1421, 1480, 1423, -1, + 1421, 1422, 1424, -1, 1421, 1424, 1480, -1, + 1483, 1480, 1425, -1, 1483, 1426, 1428, -1, + 1483, 1425, 1426, -1, 1476, 1477, 1427, -1, + 1476, 1427, 1436, -1, 1476, 1436, 1481, -1, + 1482, 1476, 1481, -1, 1482, 1474, 1476, -1, + 1482, 1428, 1474, -1, 1482, 1483, 1428, -1, + 1429, 1431, 1430, -1, 1429, 1474, 1431, -1, + 1429, 1430, 1475, -1, 1429, 1475, 1474, -1, + 1432, 1434, 1433, -1, 1432, 1433, 1435, -1, + 1432, 1436, 1434, -1, 1432, 1437, 1436, -1, + 1432, 1435, 1488, -1, 1432, 1488, 1437, -1, + 1438, 1499, 1486, -1, 1438, 1486, 1529, -1, + 1438, 1529, 1499, -1, 1485, 1529, 1486, -1, + 1485, 1505, 1529, -1, 1485, 1439, 1505, -1, + 1485, 1487, 1439, -1, 1507, 1506, 1531, -1, + 1493, 1440, 1491, -1, 1493, 1499, 1440, -1, + 1525, 1544, 1534, -1, 1525, 1496, 1524, -1, + 1525, 1531, 1495, -1, 1497, 1529, 1531, -1, + 1497, 1531, 1525, -1, 1497, 1525, 1534, -1, + 1498, 1502, 1499, -1, 1441, 1442, 1443, -1, + 1441, 1444, 1445, -1, 1441, 1446, 1442, -1, + 1441, 1443, 1447, -1, 1441, 1447, 1444, -1, + 1441, 1449, 1446, -1, 1441, 1445, 1448, -1, + 1441, 1448, 1449, -1, 1509, 1450, 1449, -1, + 1509, 1504, 1450, -1, 1509, 1449, 1510, -1, + 1528, 1504, 1509, -1, 1451, 1452, 1453, -1, + 1451, 1491, 1454, -1, 1451, 1454, 1455, -1, + 1451, 1455, 1452, -1, 1451, 1453, 1490, -1, + 1451, 1490, 1491, -1, 1456, 1457, 1459, -1, + 1456, 1496, 1495, -1, 1456, 1495, 1457, -1, + 1456, 1459, 1460, -1, 1456, 1524, 1496, -1, + 1456, 1460, 1524, -1, 1458, 1460, 1459, -1, + 1458, 1461, 1460, -1, 1458, 1462, 1463, -1, + 1458, 1516, 1461, -1, 1458, 1464, 1462, -1, + 1458, 1459, 1464, -1, 1458, 1463, 1466, -1, + 1458, 1466, 1516, -1, 1513, 1466, 1465, -1, + 1513, 1465, 1467, -1, 1513, 1468, 1469, -1, + 1513, 1467, 1470, -1, 1513, 1469, 1514, -1, + 1513, 1516, 1466, -1, 1513, 1471, 1468, -1, + 1513, 1470, 1471, -1, 1522, 1472, 1520, -1, + 1522, 1524, 1472, -1, 1473, 1474, 1475, -1, + 1473, 1476, 1474, -1, 1473, 1477, 1476, -1, + 1473, 1478, 1477, -1, 1473, 1475, 1478, -1, + 1479, 1481, 1480, -1, 1479, 1482, 1481, -1, + 1479, 1480, 1483, -1, 1479, 1483, 1482, -1, + 1484, 1485, 1486, -1, 1484, 1487, 1485, -1, + 1484, 1486, 1499, -1, 1484, 1499, 1492, -1, + 1484, 1488, 1487, -1, 1484, 1490, 1488, -1, + 1484, 1492, 1490, -1, 1489, 1491, 1490, -1, + 1489, 1490, 1492, -1, 1489, 1492, 1499, -1, + 1489, 1493, 1491, -1, 1489, 1499, 1493, -1, + 1494, 1495, 1496, -1, 1494, 1496, 1525, -1, + 1494, 1525, 1495, -1, 1533, 1497, 1534, -1, + 1533, 1498, 1499, -1, 1533, 1499, 1529, -1, + 1533, 1529, 1497, -1, 1533, 1501, 1500, -1, + 1533, 1500, 1502, -1, 1533, 1502, 1498, -1, + 1533, 1526, 1542, -1, 1533, 1542, 1501, -1, + 1503, 1505, 1504, -1, 1503, 1504, 1528, -1, + 1503, 1529, 1505, -1, 1503, 1528, 1529, -1, + 1530, 1511, 1506, -1, 1530, 1506, 1507, -1, + 1530, 1507, 1531, -1, 1508, 1509, 1510, -1, + 1508, 1528, 1509, -1, 1508, 1510, 1511, -1, + 1508, 1511, 1530, -1, 1508, 1530, 1528, -1, + 1512, 1513, 1514, -1, 1512, 1514, 1515, -1, + 1512, 1516, 1513, -1, 1512, 1515, 1517, -1, + 1512, 1517, 1516, -1, 1518, 1520, 1519, -1, + 1518, 1522, 1520, -1, 1518, 1519, 1543, -1, + 1518, 1523, 1522, -1, 1518, 1525, 1523, -1, + 1518, 1543, 1544, -1, 1518, 1544, 1525, -1, + 1521, 1522, 1523, -1, 1521, 1524, 1522, -1, + 1521, 1523, 1525, -1, 1521, 1525, 1524, -1, + 1535, 1526, 1533, -1, 1535, 1542, 1526, -1, + 1527, 1529, 1528, -1, 1527, 1528, 1530, -1, + 1527, 1531, 1529, -1, 1527, 1530, 1531, -1, + 1532, 1533, 1534, -1, 1532, 1535, 1533, -1, + 1532, 1537, 1536, -1, 1532, 1536, 1538, -1, + 1532, 1539, 1537, -1, 1532, 1538, 1540, -1, + 1532, 1541, 1539, -1, 1532, 1540, 1542, -1, + 1532, 1542, 1535, -1, 1532, 1543, 1541, -1, + 1532, 1544, 1543, -1, 1532, 1534, 1544, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT2_shoulderPitch.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT2_shoulderPitch.wrl new file mode 100644 index 0000000..8509af8 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT2_shoulderPitch.wrl @@ -0,0 +1,994 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_LT2_shoulderPitch____________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 34.914501 -0.85713398 37.443501, + -55.123402 -74.929001 20.068399, + -13.5655 32.1828 43.793499, + 34.914501 -0.85713398 -37.443298, + -8.6440601 -74.929001 20.0851, + 34.5742 -4.9376402 37.443501, + -37.236301 -74.929001 39.117199, + -69.496597 -46.555698 -29.6327, + -43.880798 -74.929001 35.5919, + -17.753599 -74.929001 35.920898, + -4.1753302 -74.929001 28.2824, + -71.094803 -71.5 -3.4979401, + -23.8277 25.534201 -37.443298, + -23.8277 25.534201 43.793499, + -15.9767 16.571301 53.318501, + -10.5 -18.186501 53.318501, + -69.3563 -45.136799 43.3596, + -1.64037 34.886501 -37.443298, + 23.855499 25.4594 -37.443298, + -8.3766298 -74.929001 20.068399, + -20.6754 28.147499 43.793499, + -17.238899 30.373899 43.793499, + -5.7122102 34.4547 -37.443298, + -9.7055302 33.549301 37.443501, + -5.7122102 34.4547 37.443501, + -5.7679701 34.442101 -37.443298, + -18.219299 14.0685 53.318501, + -66.505402 -37.121399 37.2038, + -66.331902 -36.8596 -37.187401, + -55.389801 -74.929001 20.096901, + -46.224098 -71.599998 -35.662899, + -45.834301 -71.599998 -35.755798, + -48.694901 -74.929001 35.680901, + -52.2178 -74.929001 33.783501, + -44.998199 -74.929001 37.212101, + -46.016998 -74.929001 35.8731, + -41.1656 -74.929001 38.3615, + -21.365601 -74.929001 38.110699, + -69.468697 -46.249599 30.4918, + -69.3582 -45.1366 32.2924, + -13.9066 -74.929001 35.2402, + -17.563299 -74.929001 36.864498, + -69.711098 -49.617802 -37.514702, + -71.094803 -66.5 -3.4979401, + -69.751503 -50.290699 -36.526001, + -1.64037 34.886501 43.793499, + -21.499901 8.2230101 53.318501, + -20.0735 11.2658 53.318501, + -22.9573 1.6802599 53.318501, + -22.468 5.0049701 53.318501, + -13.3937 -18.7209 53.318501, + -15.9767 -16.571301 53.318501, + -4.1810498 -22.635799 53.318501, + -10.5251 -20.4715 53.318501, + -7.4323001 -21.7859 53.318501, + -0.84069097 -23.003401 53.318501, + -22.9573 -1.6802599 53.318501, + -21.499901 -8.2230101 53.318501, + -20.0735 -11.2658 53.318501, + -18.219299 -14.0685 53.318501, + -22.468 -5.0049701 53.318501, + 5.7679701 34.408901 -37.443298, + 6.5146799 34.312 -37.443298, + 10.4858 33.313702 37.443501, + 27.1719 21.941799 37.443501, + 29.5532 18.6108 37.443501, + 27.1719 21.941799 43.793499, + 24.417101 24.971201 43.793499, + -5.7122102 34.4547 43.793499, + -9.7055302 33.549301 43.793499, + -10.5251 20.4715 53.318501, + -7.4323001 21.7859 53.318501, + -17.469299 -71.599998 -35.7159, + -8.1101999 -74.929001 20.096901, + -26.2637 -71.5 -39.117001, + 32.479099 -12.8399 43.793499, + 19.197599 -12.701 53.318501, + 21.326599 27.6574 37.443501, + 17.943001 29.9634 37.443501, + 21.326599 27.6574 -37.443298, + 33.07 11.2307 37.443501, + 33.07 11.2307 -43.793301, + 31.528299 15.024 -37.443298, + 31.528299 15.024 37.443501, + -26.9904 -28.709101 -43.893299, + 34.1572 7.28297 -43.793301, + 34.914501 -0.85713398 -43.793301, + 24.417101 24.971201 37.443501, + 23.855499 25.4594 -43.793301, + 24.417101 24.971201 -43.793301, + -20.6754 28.147499 -37.443298, + -21.3542 27.584801 -37.443298, + -20.579201 28.2099 -43.793301, + -17.238899 30.373899 -37.443298, + -69.3172 -44.755901 32.6782, + -27.752701 -27.0189 -43.893299, + 27.1719 21.941799 -43.793301, + -68.744797 -40.5 36.1544, + -67.952301 -39.304298 -36.664398, + -68.813103 -40.936401 -35.809299, + -32.004101 14.9305 42.442402, + -34.685902 10.8845 41.396599, + -69.133698 -43.215698 43.080299, + -56.108601 -74.929001 20.4394, + -60.9492 -74.929001 24.528, + -60.7672 -74.929001 24.3484, + -29.2498 -74.929001 39.420898, + -33.250801 -74.929001 39.4716, + 2.51759 -22.880699 53.318501, + -25.2745 -74.929001 38.965698, + 5.8222098 -22.2703 53.318501, + 11.9914 -19.6486 53.318501, + 17.1437 -15.3608 53.318501, + 14.7245 -17.6933 53.318501, + -17.351 -11.8297 53.318501, + -69.377701 -45.322701 31.92, + 30.753099 -16.552999 43.793499, + 4.7432399 -71.5 15.1161, + 20.8423 9.7704601 53.318501, + 19.197599 12.701 53.318501, + 29.5532 18.6108 43.793499, + 31.528299 15.024 43.793499, + 33.07 11.2307 43.793499, + 22.773399 -3.3515601 53.318501, + 22.042801 6.63168 53.318501, + 22.042801 -6.63168 53.318501, + 23.0187 2.6050035e-009 53.318501, + 22.773399 3.3515601 53.318501, + 34.5742 -4.9376402 43.793499, + 34.914501 -0.85713398 43.793499, + 34.1572 7.28297 37.443501, + 34.774799 3.2351501 -43.793301, + 34.774799 3.2351501 37.443501, + 34.1572 7.28297 -37.443298, + 34.774799 3.2351501 43.793499, + 34.1572 7.28297 43.793499, + 33.355202 10.1953 -43.793301, + 33.355202 10.1953 -37.443298, + 11.9914 19.6486 53.318501, + 14.3128 31.8575 43.793499, + 17.943001 29.9634 43.793499, + 21.326599 27.6574 43.793499, + -4.1810498 22.635799 53.318501, + -0.84069097 23.003401 53.318501, + 2.45402 34.838699 43.793499, + 13.0933 16.418501 53.318501, + 18.9203 9.1115599 53.318501, + -1.56933 20.941299 53.318501, + -13.3937 18.7209 53.318501, + -23.0187 2.9185676e-010 53.318501, + -22.045601 -71.5 -38.2747, + -22.3344 -71.5 -38.361301, + 21.326599 27.6574 -43.793301, + -38.225498 -71.5 -38.9655, + -42.134399 -71.5 -38.1105, + -59.324699 -71.5 -28.2822, + -62.044498 -71.5 -25.347401, + -56.321899 -71.5 -30.9268, + -69.477898 -46.349499 -30.0907, + -69.446098 -46.010201 -30.940701, + -69.491997 -46.503899 -29.9604, + -69.614197 -48.003799 -39.885799, + -69.389297 -45.4356 -31.872, + -69.357803 -45.1367 -32.2785, + -27.320601 -27.634399 -43.893299, + 31.528299 15.024 -43.793301, + 29.5532 18.6108 -43.793301, + -27.165701 -27.9778 -43.893299, + -69.206398 -43.806099 43.267799, + -69.168602 -43.4888 43.179199, + -68.874298 -41.34 42.076199, + -68.8255 -41.016602 41.775101, + -68.805 -40.883801 41.619301, + -68.765602 -40.631401 -41.195702, + -68.925201 -41.685001 42.3354, + -68.934097 -41.7463 -35.329601, + -69.509697 -46.703899 29.491899, + -69.490196 -46.484001 29.848801, + -67.848602 -71.5 16.0357, + -61.282398 -74.929001 25.966801, + -61.075699 -74.929001 26.4328, + -60.919102 -74.929001 26.634899, + -55.530602 -74.929001 31.539499, + -58.5994 -74.929001 28.9718, + -55.8895 -74.929001 20.285101, + -49.593399 -71.5 -35.240002, + -45.936699 -71.5 -36.864399, + -46.598099 -71.599998 -35.518902, + -46.949501 -71.599998 -35.326302, + -53.067001 -71.5 -33.254002, + -65.7659 -71.5 -19.986099, + -64.4534 -71.5 -22.1525, + -66.526703 -71.5 -18.730301, + -68.243202 -71.5 -15.1159, + -61.099998 -74.929001 24.7346, + -61.327099 -74.929001 25.715, + -61.197899 -74.929001 26.2082, + 18.9203 -9.1115599 53.318501, + 20.8423 -9.7704601 53.318501, + 20.7654 -3.12989 53.318501, + 9.0027399 -21.1852 53.318501, + -2.4242599 -74.929001 26.4328, + 28.604401 -20.038601 43.793499, + 26.0625 -23.248699 43.793499, + 11.4654 -41.487801 43.7743, + 6.0852699 -71.5 11.3466, + 5.8222098 22.2703 53.318501, + 2.51759 22.880699 53.318501, + 17.1437 15.3608 53.318501, + 14.7245 17.6933 53.318501, + 9.0027399 21.1852 53.318501, + 10.4858 33.313702 43.793499, + 6.5146799 34.312 43.793499, + -7.96943 -71.5 -31.539301, + 32.479099 -12.8399 37.443501, + 33.758701 -8.9502697 43.793499, + 5.7237201 -44.1161 -43.534599, + -69.3563 -45.136799 -43.359402, + -34.250198 -71.5 -39.4207, + -69.330002 -44.872898 -32.48, + -69.416496 -45.706299 31.4557, + -69.405998 -45.600399 31.500601, + -69.409698 -45.638 43.268398, + -69.409698 -45.638 -43.2682, + -69.437103 -45.916801 -30.9226, + -69.452103 -46.072701 30.690901, + -69.2472 -44.139599 -33.482899, + -69.2472 -44.139702 33.3862, + -69.282997 -44.450001 43.484501, + -31.895 -41.566898 -43.770901, + -56.591702 -42.0322 -43.747101, + 9.7195196 -41.465 -43.775002, + 0.986655 -41.298901 -43.7808, + 9.8612404 -41.107201 -43.786098, + -56.138802 -41.107201 -43.786098, + -39.638802 -41.107201 -43.786098, + -39.780499 -41.465 -43.775002, + -20.6754 28.147499 -43.793301, + -23.8277 25.534201 -43.793301, + -23.8277 25.534201 37.443501, + -23.899 25.4594 -37.443298, + -26.6525 22.569901 43.793499, + -69.062599 -42.674999 -42.8568, + -68.931297 -41.730099 -42.351601, + -68.844398 -41.1408 -41.901901, + -68.800003 -40.851601 -41.577, + -68.791603 -40.797401 -41.491402, + -68.756401 -40.573299 -41.059502, + -68.750298 -40.5345 -40.9035, + -68.747597 -40.517899 -40.8368, + -31.728701 15.346 -42.5728, + -68.744797 -40.5 -40.618301, + -28.023199 -26.756701 -43.893299, + -28.3244 -26.5303 -43.893299, + 14.3128 31.8575 -43.793301, + 17.943001 29.9634 -43.793301, + -5.7679701 34.442101 -43.793301, + -69.062302 -42.670799 42.858898, + -69.040703 -42.506199 -34.932301, + -69.021599 -42.366299 35.035099, + -68.999496 -42.206501 -42.644402, + -69.041702 -42.513599 -34.794899, + -68.765297 -40.6297 41.195999, + -68.779297 -40.718899 41.3778, + -68.761299 -40.604301 41.144299, + -68.772499 -40.675098 -41.298302, + -68.746696 -40.512001 40.796902, + -68.753899 -40.557098 41.008202, + -68.744797 -40.5 40.6185, + -68.993698 -42.1674 42.617199, + -29.110901 19.295401 43.793499, + -69.0093 -42.277199 42.681301, + -68.93 -41.718498 42.355, + -68.891701 -41.456699 35.635101, + -68.880898 -41.383598 -42.068699, + -68.878502 -41.368 42.102299, + -68.912201 -41.595699 35.476002, + -68.904999 -41.5467 -42.238899, + -69.7323 -49.9011 37.1059, + -70.337601 -71.5 8.4408598, + -69.285698 -71.5 12.3014, + -69.570503 -47.430099 40.7141, + -70.993599 -71.5 4.49371, + -71.246803 -71.5 0.50045198, + -71.246803 -66.5 0.50045198, + -61.293301 -74.929001 25.206301, + -69.585297 -71.5 -11.3464, + -69.935303 -71.5 -9.9204397, + -61.215698 -74.929001 24.962601, + -70.539001 -71.5 -7.4604402, + -61.330799 -74.929001 25.459299, + 7.59481 -71.5 3.4981201, + 7.0390501 -71.5 7.4606199, + -2.2175601 -74.929001 25.966801, + -2.20667 -74.929001 25.206301, + -2.16923 -74.929001 25.459299, + -2.1728899 -74.929001 25.715, + 4.3485999 -71.5 -16.0355, + 3.1891699 -71.5 -18.325399, + -2.3020799 -74.929001 26.2082, + -2.58094 -74.929001 26.634899, + -7.1780801 -74.929001 30.927, + -55.647598 -74.929001 20.1698, + -18.575899 -74.929001 29.674801, + -10.433 -74.929001 33.2542, + -7.6104698 -74.929001 20.285101, + -7.8523598 -74.929001 20.1698, + 34.5742 -4.9376402 -43.793301, + 33.758701 -8.9502697 -37.443298, + 26.0625 -23.248699 -43.793301, + 2.54109 -71.5 -19.605301, + 33.758701 -8.9502697 -43.793301, + -27.002501 -29.461 -43.893299, + -26.972799 -29.0854 -43.893299, + 5.7856898 -71.5 -12.3012, + 6.8376098 -71.5 -8.4406796, + 7.4935598 -71.5 -4.4935298, + 7.74683 -71.5 -0.50027198, + 0.79944301 -40.699402 -43.7925, + -47.4995 -19.1992 -43.893299, + 10.4858 33.313702 -43.793301, + -28.9995 -26.1992 -43.893299, + -69.278801 -44.413101 -43.4384, + -69.284897 -44.466599 33.124901, + -69.263199 -44.2766 -43.405499, + -69.151604 -43.352798 -34.243999, + -69.137001 -43.2379 -34.2066, + -69.167 -43.4758 34.044102, + -69.144203 -43.294601 -43.112999, + -69.195801 -43.709202 33.9156, + -69.221001 -43.918201 -33.565601, + 9.4182301 -42.014198 -43.748001, + 1.10501 -41.566898 -43.770901, + 8.98526 -42.578701 -43.708099, + 9.0609102 -42.480999 -43.715099, + -64.894997 -41.566898 -43.770901, + -48.395 -41.566898 -43.770901, + -56.280499 -41.465 -43.775002, + -65.013298 -41.298901 -43.7808, + -26.6525 22.569901 -43.793301, + -23.899 25.4594 -43.793301, + -26.6525 22.569901 -37.443298, + -51.279202 -23.096399 -43.893299, + -51.124298 -23.4398 -43.893299, + -27.5173 -27.313101 -43.893299, + -50.625999 -19.9485 -43.893299, + -50.347198 -19.695101 -43.893299, + -9.7055302 33.549301 -43.793301, + 5.7679701 34.408901 -43.793301, + 6.5146799 34.312 -43.793301, + -69.090698 -42.8806 34.642899, + -69.098503 -42.939899 42.980301, + -69.105904 -42.996101 -43.0023, + -69.0755 -42.765598 34.651199, + -2.5507801 -74.929001 24.528, + -2.73281 -74.929001 24.3484, + -7.3913999 -74.929001 20.4394, + -2.28426 -74.929001 24.962601, + -2.39996 -74.929001 24.7346, + -4.90065 -71.5 -28.971701, + -2.1073799 -71.5 -26.106701, + 0.38171399 -71.5 -22.9739, + -18.501801 -71.5 -37.211899, + -17.0865 -71.599998 -35.597198, + 1.831 -42.621498 -43.704601, + 2.0595701 -42.8493 -43.684399, + -28.739 -31.771799 -43.893299, + -27.055 -28.3379 -43.893299, + -29.568199 -30.118799 -43.893299, + -27.5741 -30.8393 -43.893299, + 28.604401 -20.038601 -43.793301, + -30.209 -32.027802 -43.893299, + -29.4578 -31.992599 -43.893299, + -29.0914 -31.9048 -43.893299, + -29.8323 -32.033798 -43.893299, + -30.5819 -31.974501 -43.893299, + -47.440399 -42.8493 -43.684399, + -7.09167 -42.0322 -43.747101, + 9.40833 -42.0322 -43.747101, + -23.5917 -42.0322 -43.747101, + -66.215897 -41.678699 -43.765999, + -64.574097 -42.117802 -43.741699, + -64.168999 -42.621498 -43.704601, + -67.6381 -42.995602 -43.663799, + -63.940399 -42.8493 -43.684399, + -29.110901 19.295401 -43.793301, + -51.243599 -20.888 -43.893299, + -50.8708 -20.2349 -43.893299, + -51.077702 -20.5497 -43.893299, + -29.3629 -26.099701 -43.893299, + -28.651501 -26.3435 -43.893299, + -47.8629 -19.099701 -43.893299, + -29.735901 -26.0464 -43.893299, + -49.705898 -19.302401 -43.893299, + -49.353401 -19.169399 -43.893299, + -13.5655 32.1828 -43.793301, + -50.038898 -19.4786 -43.893299, + -17.238899 30.373899 -43.793301, + -48.612499 -19.0404 -43.893299, + -48.235901 -19.0464 -43.893299, + -48.987 -19.0816 -43.893299, + -1.64037 34.886501 -43.793301, + -5.7122102 34.4547 -43.793301, + 2.45402 34.838699 -43.793301, + -11.5477 -71.5 -33.9263, + -16.723 -71.599998 -35.428501, + -11.2822 -71.5 -33.783298, + -14.8051 -71.5 -35.680698, + 11.4654 -41.487801 -43.774101, + 7.4572701 -44.450001 -43.484299, + 3.1655099 -43.610298 -43.6022, + -40.514702 -42.578701 -43.708099, + -31.169001 -42.621498 -43.704601, + -57.014702 -42.578701 -43.708099, + -7.51473 -42.578701 -43.708099, + 1.42589 -42.117802 -43.741699, + -28.097601 -31.379101 -43.893299, + -28.405899 -31.5956 -43.893299, + 11.9644 -40.5 -43.793301, + -27.818899 -31.1257 -43.893299, + -32.192101 -31.0553 -43.893299, + -27.2012 -30.186199 -43.893299, + 30.753099 -16.552999 -43.793301, + 32.479099 -12.8399 -43.793301, + -27.3671 -30.5245 -43.893299, + -27.0791 -29.829901 -43.893299, + -60.980499 -44.1138 -43.534901, + -61.382301 -44.059399 -43.542599, + -61.219898 -44.090599 -43.5382, + -69.282997 -44.450001 -43.484299, + -11.1115 -44.115002 -43.534801, + 5.3884602 -44.115002 -43.534801, + -30.249201 -71.5 -39.471401, + -67.9104 -43.247799 -43.644199, + -51.454399 -22.365101 -43.893299, + -51.389801 -22.7363 -43.893299, + -51.442299 -21.613199 -43.893299, + -51.365799 -21.244301 -43.893299, + -51.472 -21.9888 -43.893299, + 6.9145002 -43.8787 -43.567402, + -49.445301 -24.875 -43.893299, + -31.293301 -31.7307 -43.893299, + -30.945299 -31.875 -43.893299, + -49.793301 -24.7307 -43.893299, + 3.4347 -43.733799 -43.586601, + -27.6115 -44.115002 -43.534801, + 6.1592999 -44.056499 -43.543098, + -60.6115 -44.115002 -43.534801, + 6.5805898 -43.985001 -43.553101, + -43.075199 -44.020199 -43.548199, + -59.575199 -44.020199 -43.548199, + -26.8407 -44.056499 -43.543098, + 6.42483 -44.020199 -43.548199, + -59.840698 -44.056499 -43.543098, + 7.8726101 -43.470501 -43.618999, + 8.3121796 -43.170399 -43.651901, + 7.9398599 -43.431 -43.6236, + -24.503901 -43.041599 -43.665798, + 2.5813401 -43.266899 -43.6422, + 8.49613 -43.041599 -43.665798, + -57.503899 -43.041599 -43.665798, + 9.47367 -42.942001 -43.675701, + -50.692101 -24.0553 -43.893299, + -50.120499 -24.5439 -43.893299, + -50.4217 -24.317499 -43.893299, + -50.927601 -23.761101 -43.893299, + -65.192101 -40.735901 -43.792198, + -46.0653 -43.733799 -43.586601, + -62.5653 -43.733799 -43.586601, + -29.5653 -43.733799 -43.586601, + -62.834499 -43.610298 -43.6022, + -45.408501 -43.958401 -43.556801, + -9.9194098 -43.985001 -43.553101, + 4.0915198 -43.958401 -43.556801, + 7.2456899 -43.773399 -43.581501, + -59.419399 -43.985001 -43.553101, + -61.908501 -43.958401 -43.556801, + -42.254299 -43.773399 -43.581501, + -58.754299 -43.773399 -43.581501, + -41.560101 -43.431 -43.6236, + -58.060101 -43.431 -43.6236, + -58.127399 -43.470501 -43.618999, + -8.5601397 -43.431 -43.6236, + -63.418701 -43.266899 -43.6422, + -46.918701 -43.266899 -43.6422 ] + + } + coordIndex [ 307, 86, 3, -1, 4, 1, 19, -1, + 432, 19, 1, -1, 222, 182, 33, -1, + 222, 183, 182, -1, 8, 302, 303, -1, + 8, 182, 302, -1, 144, 403, 45, -1, + 21, 2, 395, -1, 21, 70, 2, -1, + 23, 2, 69, -1, 23, 395, 2, -1, + 17, 45, 403, -1, 17, 403, 401, -1, + 5, 307, 3, -1, 0, 134, 129, -1, + 0, 132, 134, -1, 0, 3, 132, -1, + 0, 5, 3, -1, 0, 129, 5, -1, + 255, 254, 139, -1, 286, 161, 193, -1, + 286, 287, 161, -1, 218, 432, 1, -1, + 181, 183, 222, -1, 29, 218, 1, -1, + 29, 153, 218, -1, 29, 1, 4, -1, + 54, 222, 107, -1, 301, 10, 204, -1, + 283, 11, 290, -1, 283, 284, 11, -1, + 289, 290, 11, -1, 289, 161, 287, -1, + 43, 284, 161, -1, 43, 11, 284, -1, + 240, 241, 13, -1, 239, 240, 13, -1, + 71, 69, 2, -1, 71, 2, 70, -1, + 14, 13, 241, -1, 14, 241, 26, -1, + 14, 26, 47, -1, 58, 228, 59, -1, + 15, 110, 114, -1, 15, 114, 59, -1, + 61, 403, 144, -1, 93, 21, 395, -1, + 128, 215, 5, -1, 128, 5, 129, -1, + 131, 3, 86, -1, 131, 132, 3, -1, + 135, 127, 134, -1, 119, 120, 66, -1, + 126, 129, 134, -1, 126, 134, 127, -1, + 306, 356, 302, -1, 306, 29, 4, -1, + 306, 302, 29, -1, 306, 4, 19, -1, + 306, 19, 73, -1, 306, 305, 356, -1, + 308, 5, 215, -1, 308, 307, 5, -1, + 347, 395, 23, -1, 28, 250, 251, -1, + 101, 250, 28, -1, 180, 181, 222, -1, + 103, 105, 157, -1, 155, 157, 105, -1, + 30, 29, 302, -1, 30, 302, 187, -1, + 30, 187, 186, -1, 39, 222, 16, -1, + 39, 16, 228, -1, 51, 59, 228, -1, + 34, 36, 222, -1, 6, 107, 222, -1, + 6, 36, 107, -1, 6, 222, 36, -1, + 35, 182, 8, -1, 37, 8, 9, -1, + 37, 35, 8, -1, 37, 9, 41, -1, + 37, 204, 111, -1, 37, 41, 204, -1, + 7, 177, 160, -1, 7, 176, 177, -1, + 7, 160, 284, -1, 7, 284, 176, -1, + 158, 160, 177, -1, 304, 8, 303, -1, + 304, 9, 8, -1, 304, 41, 9, -1, + 304, 301, 204, -1, 300, 10, 301, -1, + 300, 204, 10, -1, 44, 289, 11, -1, + 44, 11, 43, -1, 12, 238, 239, -1, + 91, 20, 90, -1, 91, 13, 20, -1, + 91, 239, 13, -1, 91, 12, 239, -1, + 91, 238, 12, -1, 68, 45, 24, -1, + 68, 25, 69, -1, 148, 20, 13, -1, + 148, 13, 14, -1, 148, 21, 20, -1, + 148, 70, 21, -1, 148, 14, 47, -1, + 113, 204, 112, -1, 113, 111, 204, -1, + 108, 110, 15, -1, 108, 55, 107, -1, + 53, 15, 59, -1, 53, 108, 15, -1, + 53, 228, 16, -1, 53, 16, 222, -1, + 53, 222, 54, -1, 48, 49, 228, -1, + 48, 228, 149, -1, 60, 59, 114, -1, + 211, 139, 63, -1, 211, 210, 139, -1, + 78, 255, 139, -1, 78, 139, 140, -1, + 78, 140, 141, -1, 22, 401, 402, -1, + 22, 17, 401, -1, 22, 24, 45, -1, + 22, 45, 17, -1, 122, 83, 121, -1, + 85, 367, 136, -1, 65, 121, 83, -1, + 65, 120, 121, -1, 65, 83, 82, -1, + 65, 166, 96, -1, 65, 165, 166, -1, + 65, 82, 165, -1, 18, 88, 141, -1, + 18, 141, 67, -1, 87, 67, 66, -1, + 87, 88, 18, -1, 87, 18, 67, -1, + 208, 66, 67, -1, 208, 119, 66, -1, + 74, 151, 73, -1, 74, 19, 432, -1, + 74, 73, 19, -1, 316, 317, 295, -1, + 75, 291, 317, -1, 75, 215, 125, -1, + 79, 152, 255, -1, 79, 255, 78, -1, + 79, 88, 152, -1, 81, 136, 367, -1, + 81, 165, 82, -1, 313, 131, 86, -1, + 92, 90, 20, -1, 92, 20, 21, -1, + 92, 21, 93, -1, 256, 22, 402, -1, + 256, 347, 23, -1, 256, 24, 22, -1, + 256, 23, 69, -1, 256, 69, 25, -1, + 256, 68, 24, -1, 256, 25, 68, -1, + 348, 403, 61, -1, 348, 62, 349, -1, + 348, 61, 62, -1, 320, 349, 62, -1, + 320, 139, 254, -1, 320, 63, 139, -1, + 320, 62, 63, -1, 98, 28, 251, -1, + 169, 228, 47, -1, 270, 241, 341, -1, + 270, 169, 47, -1, 270, 26, 241, -1, + 270, 47, 26, -1, 27, 268, 101, -1, + 27, 101, 28, -1, 27, 98, 268, -1, + 27, 28, 98, -1, 195, 282, 283, -1, + 195, 283, 290, -1, 184, 302, 105, -1, + 184, 105, 103, -1, 184, 187, 302, -1, + 104, 191, 156, -1, 104, 156, 155, -1, + 104, 155, 105, -1, 31, 153, 29, -1, + 31, 29, 30, -1, 154, 30, 186, -1, + 154, 153, 31, -1, 154, 31, 30, -1, + 94, 39, 228, -1, 94, 219, 39, -1, + 94, 228, 323, -1, 32, 33, 182, -1, + 32, 182, 35, -1, 32, 35, 36, -1, + 32, 36, 34, -1, 32, 222, 33, -1, + 32, 34, 222, -1, 109, 36, 35, -1, + 109, 35, 37, -1, 109, 107, 36, -1, + 109, 37, 111, -1, 38, 158, 177, -1, + 38, 177, 222, -1, 38, 222, 225, -1, + 38, 159, 158, -1, 38, 225, 159, -1, + 224, 159, 225, -1, 163, 39, 219, -1, + 163, 162, 39, -1, 115, 222, 39, -1, + 115, 39, 162, -1, 40, 204, 41, -1, + 40, 304, 204, -1, 40, 41, 304, -1, + 203, 112, 204, -1, 203, 202, 112, -1, + 42, 43, 161, -1, 42, 44, 43, -1, + 42, 161, 289, -1, 42, 289, 44, -1, + 143, 45, 68, -1, 143, 144, 45, -1, + 46, 148, 47, -1, 46, 149, 148, -1, + 46, 48, 149, -1, 46, 49, 48, -1, + 46, 47, 228, -1, 46, 228, 49, -1, + 50, 59, 51, -1, 50, 53, 59, -1, + 50, 51, 228, -1, 50, 228, 53, -1, + 52, 53, 54, -1, 52, 108, 53, -1, + 52, 55, 108, -1, 52, 54, 107, -1, + 52, 107, 55, -1, 56, 114, 149, -1, + 56, 60, 114, -1, 56, 149, 228, -1, + 56, 228, 60, -1, 57, 58, 59, -1, + 57, 59, 60, -1, 57, 228, 58, -1, + 57, 60, 228, -1, 212, 62, 61, -1, + 212, 61, 144, -1, 212, 63, 62, -1, + 212, 211, 63, -1, 137, 136, 122, -1, + 137, 122, 135, -1, 124, 127, 135, -1, + 124, 135, 122, -1, 133, 131, 85, -1, + 133, 85, 136, -1, 64, 65, 96, -1, + 64, 87, 66, -1, 64, 96, 87, -1, + 64, 66, 120, -1, 64, 120, 65, -1, + 209, 67, 141, -1, 209, 208, 67, -1, + 142, 143, 68, -1, 142, 69, 71, -1, + 142, 68, 69, -1, 147, 70, 148, -1, + 147, 71, 70, -1, 147, 142, 71, -1, + 146, 119, 208, -1, 146, 149, 114, -1, + 146, 114, 199, -1, 146, 124, 119, -1, + 146, 199, 124, -1, 76, 112, 202, -1, + 198, 112, 76, -1, 198, 75, 125, -1, + 361, 360, 408, -1, 359, 355, 356, -1, + 359, 408, 360, -1, 294, 314, 315, -1, + 294, 315, 316, -1, 294, 316, 295, -1, + 72, 306, 73, -1, 72, 363, 306, -1, + 72, 73, 151, -1, 72, 151, 150, -1, + 72, 362, 363, -1, 72, 150, 362, -1, + 409, 151, 74, -1, 409, 74, 432, -1, + 214, 75, 317, -1, 214, 215, 75, -1, + 116, 292, 291, -1, 116, 291, 75, -1, + 116, 75, 198, -1, 116, 76, 202, -1, + 116, 198, 76, -1, 77, 78, 141, -1, + 77, 79, 78, -1, 77, 141, 88, -1, + 77, 88, 79, -1, 167, 165, 81, -1, + 167, 81, 367, -1, 80, 122, 136, -1, + 80, 136, 81, -1, 80, 81, 82, -1, + 80, 82, 83, -1, 80, 83, 122, -1, + 84, 131, 313, -1, 84, 313, 367, -1, + 84, 85, 131, -1, 84, 367, 85, -1, + 312, 86, 307, -1, 312, 313, 86, -1, + 89, 96, 95, -1, 89, 88, 87, -1, + 89, 87, 96, -1, 252, 152, 88, -1, + 252, 88, 89, -1, 252, 89, 95, -1, + 237, 92, 396, -1, 237, 90, 92, -1, + 237, 238, 91, -1, 237, 91, 90, -1, + 397, 396, 92, -1, 397, 93, 395, -1, + 397, 92, 93, -1, 429, 432, 218, -1, + 429, 94, 323, -1, 429, 219, 94, -1, + 344, 167, 367, -1, 344, 252, 95, -1, + 344, 96, 166, -1, 344, 95, 96, -1, + 242, 352, 260, -1, 99, 245, 244, -1, + 99, 172, 245, -1, 173, 247, 265, -1, + 97, 251, 268, -1, 97, 98, 251, -1, + 97, 268, 98, -1, 259, 271, 260, -1, + 227, 330, 226, -1, 327, 169, 351, -1, + 274, 244, 277, -1, 171, 270, 172, -1, + 171, 172, 99, -1, 171, 99, 244, -1, + 100, 101, 268, -1, 100, 268, 270, -1, + 100, 250, 101, -1, 100, 270, 250, -1, + 174, 270, 275, -1, 257, 351, 270, -1, + 257, 270, 271, -1, 102, 351, 169, -1, + 102, 270, 351, -1, 102, 169, 270, -1, + 279, 282, 195, -1, 179, 279, 195, -1, + 179, 280, 279, -1, 189, 103, 157, -1, + 189, 184, 103, -1, 194, 191, 104, -1, + 194, 104, 105, -1, 194, 105, 302, -1, + 106, 109, 110, -1, 106, 107, 109, -1, + 106, 110, 108, -1, 106, 108, 107, -1, + 200, 110, 109, -1, 200, 109, 111, -1, + 200, 112, 198, -1, 200, 113, 112, -1, + 200, 111, 113, -1, 200, 114, 110, -1, + 200, 199, 114, -1, 221, 222, 115, -1, + 221, 115, 162, -1, 205, 202, 117, -1, + 205, 292, 116, -1, 205, 116, 202, -1, + 299, 117, 202, -1, 299, 205, 117, -1, + 118, 119, 124, -1, 118, 121, 120, -1, + 118, 120, 119, -1, 118, 122, 121, -1, + 118, 124, 122, -1, 123, 124, 199, -1, + 123, 199, 198, -1, 123, 198, 125, -1, + 123, 126, 127, -1, 123, 127, 124, -1, + 123, 128, 129, -1, 123, 129, 126, -1, + 123, 215, 128, -1, 123, 125, 215, -1, + 130, 132, 131, -1, 130, 131, 133, -1, + 130, 134, 132, -1, 130, 135, 134, -1, + 130, 133, 136, -1, 130, 136, 137, -1, + 130, 137, 135, -1, 138, 210, 209, -1, + 138, 139, 210, -1, 138, 140, 139, -1, + 138, 141, 140, -1, 138, 209, 141, -1, + 207, 142, 147, -1, 207, 143, 142, -1, + 207, 144, 143, -1, 207, 212, 144, -1, + 145, 146, 208, -1, 145, 208, 207, -1, + 145, 207, 147, -1, 145, 147, 148, -1, + 145, 148, 149, -1, 145, 149, 146, -1, + 310, 361, 408, -1, 213, 356, 305, -1, + 213, 359, 356, -1, 213, 408, 359, -1, + 461, 150, 151, -1, 461, 151, 409, -1, + 461, 362, 150, -1, 461, 408, 362, -1, + 461, 333, 408, -1, 370, 297, 298, -1, + 370, 314, 297, -1, 370, 298, 310, -1, + 253, 255, 152, -1, 253, 152, 252, -1, + 223, 218, 153, -1, 223, 153, 154, -1, + 223, 154, 186, -1, 223, 155, 156, -1, + 223, 157, 155, -1, 223, 158, 159, -1, + 223, 159, 224, -1, 223, 156, 191, -1, + 223, 189, 157, -1, 223, 160, 158, -1, + 223, 284, 160, -1, 223, 161, 284, -1, + 223, 221, 162, -1, 223, 162, 163, -1, + 223, 193, 161, -1, 223, 192, 193, -1, + 223, 163, 219, -1, 381, 413, 382, -1, + 229, 336, 408, -1, 229, 380, 336, -1, + 233, 466, 318, -1, 233, 235, 466, -1, + 233, 232, 235, -1, 233, 318, 418, -1, + 233, 418, 408, -1, 338, 380, 466, -1, + 338, 235, 232, -1, 338, 232, 236, -1, + 391, 349, 320, -1, 164, 166, 165, -1, + 164, 344, 166, -1, 164, 165, 167, -1, + 164, 167, 344, -1, 248, 251, 249, -1, + 248, 247, 173, -1, 248, 268, 251, -1, + 246, 245, 172, -1, 168, 228, 169, -1, + 168, 227, 228, -1, 168, 169, 227, -1, + 329, 330, 227, -1, 329, 227, 169, -1, + 329, 169, 327, -1, 243, 260, 175, -1, + 243, 175, 277, -1, 170, 171, 244, -1, + 170, 244, 274, -1, 170, 274, 275, -1, + 170, 275, 270, -1, 170, 270, 171, -1, + 263, 172, 270, -1, 263, 270, 264, -1, + 263, 265, 246, -1, 263, 246, 172, -1, + 267, 173, 265, -1, 267, 248, 173, -1, + 267, 268, 248, -1, 267, 264, 270, -1, + 272, 270, 174, -1, 272, 260, 271, -1, + 272, 175, 260, -1, 272, 174, 175, -1, + 276, 174, 275, -1, 276, 277, 175, -1, + 276, 175, 174, -1, 281, 178, 222, -1, + 281, 280, 178, -1, 281, 176, 284, -1, + 281, 222, 177, -1, 281, 177, 176, -1, + 196, 178, 280, -1, 196, 280, 179, -1, + 196, 180, 222, -1, 196, 222, 178, -1, + 196, 181, 180, -1, 196, 179, 195, -1, + 196, 182, 183, -1, 196, 183, 181, -1, + 196, 302, 182, -1, 196, 194, 302, -1, + 188, 187, 184, -1, 188, 184, 189, -1, + 185, 186, 187, -1, 185, 187, 188, -1, + 185, 188, 189, -1, 185, 223, 186, -1, + 185, 189, 223, -1, 190, 191, 194, -1, + 190, 194, 192, -1, 190, 223, 191, -1, + 190, 192, 223, -1, 288, 193, 192, -1, + 288, 192, 194, -1, 288, 286, 193, -1, + 288, 195, 290, -1, 288, 196, 195, -1, + 288, 194, 196, -1, 197, 198, 199, -1, + 197, 199, 200, -1, 197, 200, 198, -1, + 201, 299, 202, -1, 201, 300, 299, -1, + 201, 202, 203, -1, 201, 204, 300, -1, + 201, 203, 204, -1, 293, 292, 205, -1, + 293, 205, 299, -1, 206, 207, 208, -1, + 206, 209, 210, -1, 206, 208, 209, -1, + 206, 210, 211, -1, 206, 211, 212, -1, + 206, 212, 207, -1, 358, 361, 310, -1, + 406, 213, 305, -1, 406, 408, 213, -1, + 454, 461, 409, -1, 365, 333, 461, -1, + 423, 214, 317, -1, 423, 308, 215, -1, + 423, 215, 214, -1, 321, 320, 254, -1, + 216, 409, 432, -1, 216, 432, 431, -1, + 216, 446, 409, -1, 216, 431, 446, -1, + 217, 429, 218, -1, 217, 218, 223, -1, + 217, 219, 429, -1, 217, 223, 219, -1, + 220, 222, 221, -1, 220, 221, 223, -1, + 220, 223, 224, -1, 220, 225, 222, -1, + 220, 224, 225, -1, 324, 330, 328, -1, + 324, 328, 429, -1, 324, 226, 330, -1, + 324, 227, 226, -1, 324, 228, 227, -1, + 324, 323, 228, -1, 326, 327, 351, -1, + 326, 351, 352, -1, 326, 352, 328, -1, + 332, 378, 380, -1, 332, 229, 408, -1, + 332, 380, 229, -1, 230, 381, 380, -1, + 379, 381, 230, -1, 379, 230, 380, -1, + 334, 408, 333, -1, 334, 378, 408, -1, + 231, 408, 236, -1, 231, 236, 232, -1, + 231, 233, 408, -1, 231, 232, 233, -1, + 234, 466, 235, -1, 234, 338, 466, -1, + 234, 235, 338, -1, 337, 338, 236, -1, + 337, 236, 408, -1, 346, 238, 237, -1, + 346, 345, 238, -1, 346, 237, 396, -1, + 340, 238, 345, -1, 340, 239, 238, -1, + 340, 240, 239, -1, 340, 341, 241, -1, + 340, 241, 240, -1, 385, 466, 380, -1, + 385, 388, 466, -1, 385, 387, 388, -1, + 385, 429, 328, -1, 385, 328, 352, -1, + 385, 352, 242, -1, 385, 242, 260, -1, + 385, 260, 243, -1, 385, 243, 277, -1, + 385, 277, 244, -1, 385, 244, 245, -1, + 385, 245, 246, -1, 385, 246, 265, -1, + 385, 265, 247, -1, 385, 247, 248, -1, + 385, 248, 249, -1, 385, 270, 341, -1, + 385, 250, 270, -1, 385, 251, 250, -1, + 385, 249, 251, -1, 435, 387, 345, -1, + 435, 391, 420, -1, 390, 252, 344, -1, + 390, 253, 252, -1, 390, 321, 254, -1, + 390, 254, 255, -1, 390, 255, 253, -1, + 400, 435, 345, -1, 400, 391, 435, -1, + 400, 256, 402, -1, 400, 347, 256, -1, + 368, 420, 391, -1, 368, 391, 344, -1, + 353, 259, 261, -1, 353, 351, 257, -1, + 353, 261, 352, -1, 353, 271, 259, -1, + 353, 257, 271, -1, 258, 259, 260, -1, + 258, 261, 259, -1, 258, 260, 352, -1, + 258, 352, 261, -1, 262, 263, 264, -1, + 262, 264, 267, -1, 262, 265, 263, -1, + 262, 267, 265, -1, 266, 268, 267, -1, + 266, 270, 268, -1, 266, 267, 270, -1, + 269, 271, 270, -1, 269, 272, 271, -1, + 269, 270, 272, -1, 273, 275, 274, -1, + 273, 276, 275, -1, 273, 274, 277, -1, + 273, 277, 276, -1, 278, 279, 280, -1, + 278, 280, 281, -1, 278, 282, 279, -1, + 278, 283, 282, -1, 278, 284, 283, -1, + 278, 281, 284, -1, 285, 287, 286, -1, + 285, 286, 288, -1, 285, 289, 287, -1, + 285, 290, 289, -1, 285, 288, 290, -1, + 296, 291, 292, -1, 296, 292, 293, -1, + 296, 295, 317, -1, 296, 317, 291, -1, + 296, 293, 299, -1, 357, 294, 295, -1, + 357, 295, 296, -1, 357, 297, 314, -1, + 357, 314, 294, -1, 357, 298, 297, -1, + 357, 299, 300, -1, 357, 296, 299, -1, + 357, 310, 298, -1, 357, 358, 310, -1, + 357, 300, 301, -1, 357, 303, 302, -1, + 357, 302, 356, -1, 357, 304, 303, -1, + 357, 301, 304, -1, 405, 406, 305, -1, + 405, 305, 306, -1, 405, 306, 363, -1, + 474, 454, 409, -1, 364, 333, 365, -1, + 364, 414, 333, -1, 311, 312, 307, -1, + 311, 307, 308, -1, 311, 308, 423, -1, + 309, 418, 369, -1, 309, 369, 370, -1, + 309, 408, 418, -1, 309, 310, 408, -1, + 309, 370, 310, -1, 417, 344, 367, -1, + 417, 368, 344, -1, 425, 312, 311, -1, + 425, 311, 423, -1, 425, 367, 313, -1, + 425, 313, 312, -1, 422, 315, 314, -1, + 422, 314, 370, -1, 422, 316, 315, -1, + 422, 317, 316, -1, 422, 423, 317, -1, + 442, 375, 466, -1, 374, 318, 466, -1, + 374, 418, 318, -1, 319, 391, 320, -1, + 319, 320, 321, -1, 319, 390, 391, -1, + 319, 321, 390, -1, 468, 476, 429, -1, + 447, 432, 429, -1, 376, 365, 461, -1, + 322, 429, 323, -1, 322, 323, 324, -1, + 322, 324, 429, -1, 325, 327, 326, -1, + 325, 326, 328, -1, 325, 329, 327, -1, + 325, 328, 330, -1, 325, 330, 329, -1, + 331, 408, 378, -1, 331, 332, 408, -1, + 331, 378, 332, -1, 415, 413, 381, -1, + 415, 381, 379, -1, 415, 333, 414, -1, + 415, 334, 333, -1, 415, 378, 334, -1, + 335, 408, 336, -1, 335, 337, 408, -1, + 335, 336, 380, -1, 335, 380, 338, -1, + 335, 338, 337, -1, 383, 385, 380, -1, + 383, 380, 381, -1, 339, 387, 385, -1, + 339, 345, 387, -1, 339, 340, 345, -1, + 339, 341, 340, -1, 339, 385, 341, -1, + 465, 466, 343, -1, 465, 435, 420, -1, + 437, 387, 435, -1, 342, 343, 466, -1, + 342, 466, 435, -1, 342, 465, 343, -1, + 342, 435, 465, -1, 392, 344, 391, -1, + 392, 390, 344, -1, 394, 400, 345, -1, + 394, 346, 396, -1, 394, 345, 346, -1, + 394, 395, 347, -1, 394, 347, 400, -1, + 399, 391, 400, -1, 399, 403, 348, -1, + 399, 348, 349, -1, 399, 349, 391, -1, + 350, 352, 351, -1, 350, 353, 352, -1, + 350, 351, 353, -1, 354, 356, 355, -1, + 354, 357, 356, -1, 354, 358, 357, -1, + 354, 359, 360, -1, 354, 355, 359, -1, + 354, 360, 361, -1, 354, 361, 358, -1, + 407, 362, 408, -1, 407, 363, 362, -1, + 407, 405, 363, -1, 410, 470, 454, -1, + 410, 454, 474, -1, 412, 382, 413, -1, + 412, 414, 364, -1, 412, 364, 365, -1, + 412, 365, 376, -1, 366, 418, 373, -1, + 366, 417, 418, -1, 366, 373, 417, -1, + 419, 369, 418, -1, 419, 417, 367, -1, + 419, 367, 425, -1, 441, 420, 368, -1, + 441, 368, 417, -1, 441, 417, 375, -1, + 441, 375, 442, -1, 424, 370, 369, -1, + 424, 422, 370, -1, 424, 369, 419, -1, + 424, 419, 425, -1, 371, 466, 375, -1, + 371, 374, 466, -1, 371, 375, 374, -1, + 372, 373, 418, -1, 372, 418, 374, -1, + 372, 417, 373, -1, 372, 375, 417, -1, + 372, 374, 375, -1, 478, 476, 468, -1, + 445, 432, 447, -1, 384, 382, 412, -1, + 384, 412, 376, -1, 384, 461, 460, -1, + 384, 376, 461, -1, 481, 454, 470, -1, + 456, 461, 454, -1, 377, 378, 415, -1, + 377, 415, 379, -1, 377, 380, 378, -1, + 377, 379, 380, -1, 433, 381, 382, -1, + 433, 383, 381, -1, 433, 382, 384, -1, + 433, 460, 483, -1, 433, 384, 460, -1, + 433, 470, 468, -1, 433, 481, 470, -1, + 433, 468, 429, -1, 433, 429, 385, -1, + 433, 385, 383, -1, 386, 388, 387, -1, + 386, 387, 437, -1, 386, 466, 388, -1, + 386, 437, 466, -1, 438, 437, 435, -1, + 389, 391, 390, -1, 389, 392, 391, -1, + 389, 390, 392, -1, 393, 395, 394, -1, + 393, 394, 396, -1, 393, 397, 395, -1, + 393, 396, 397, -1, 398, 399, 400, -1, + 398, 402, 401, -1, 398, 400, 402, -1, + 398, 401, 403, -1, 398, 403, 399, -1, + 404, 406, 405, -1, 404, 405, 407, -1, + 404, 408, 406, -1, 404, 407, 408, -1, + 452, 409, 446, -1, 452, 448, 409, -1, + 439, 474, 409, -1, 439, 409, 448, -1, + 444, 470, 410, -1, 444, 410, 474, -1, + 411, 412, 413, -1, 411, 414, 412, -1, + 411, 413, 415, -1, 411, 415, 414, -1, + 416, 418, 417, -1, 416, 419, 418, -1, + 416, 417, 419, -1, 443, 465, 420, -1, + 443, 420, 441, -1, 421, 423, 422, -1, + 421, 422, 424, -1, 421, 425, 423, -1, + 421, 424, 425, -1, 477, 478, 468, -1, + 477, 444, 474, -1, 453, 476, 450, -1, + 475, 450, 476, -1, 426, 447, 429, -1, + 426, 429, 428, -1, 426, 428, 447, -1, + 427, 447, 428, -1, 427, 476, 453, -1, + 427, 453, 447, -1, 427, 429, 476, -1, + 427, 428, 429, -1, 430, 431, 432, -1, + 430, 432, 445, -1, 430, 446, 431, -1, + 430, 445, 446, -1, 480, 433, 483, -1, + 480, 481, 433, -1, 484, 483, 460, -1, + 434, 435, 466, -1, 434, 466, 438, -1, + 434, 438, 435, -1, 436, 466, 437, -1, + 436, 438, 466, -1, 436, 437, 438, -1, + 473, 439, 448, -1, 473, 474, 439, -1, + 463, 465, 443, -1, 463, 466, 464, -1, + 463, 443, 466, -1, 440, 441, 442, -1, + 440, 443, 441, -1, 440, 442, 466, -1, + 440, 466, 443, -1, 469, 444, 477, -1, + 469, 470, 444, -1, 451, 446, 445, -1, + 451, 445, 447, -1, 451, 447, 453, -1, + 451, 452, 446, -1, 472, 448, 452, -1, + 472, 473, 448, -1, 449, 450, 475, -1, + 449, 452, 451, -1, 449, 472, 452, -1, + 449, 475, 472, -1, 449, 453, 450, -1, + 449, 451, 453, -1, 482, 454, 481, -1, + 482, 456, 454, -1, 482, 458, 456, -1, + 482, 484, 458, -1, 455, 456, 458, -1, + 455, 458, 459, -1, 455, 461, 456, -1, + 455, 459, 461, -1, 457, 458, 484, -1, + 457, 459, 458, -1, 457, 484, 460, -1, + 457, 460, 461, -1, 457, 461, 459, -1, + 462, 463, 464, -1, 462, 465, 463, -1, + 462, 464, 466, -1, 462, 466, 465, -1, + 467, 477, 468, -1, 467, 469, 477, -1, + 467, 468, 470, -1, 467, 470, 469, -1, + 471, 473, 472, -1, 471, 474, 473, -1, + 471, 475, 476, -1, 471, 472, 475, -1, + 471, 477, 474, -1, 471, 476, 478, -1, + 471, 478, 477, -1, 479, 481, 480, -1, + 479, 482, 481, -1, 479, 480, 483, -1, + 479, 483, 484, -1, 479, 484, 482, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT3_bicep.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT3_bicep.wrl new file mode 100644 index 0000000..21e8631 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT3_bicep.wrl @@ -0,0 +1,3332 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_LT3_bicep____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 26.7274 -39.803001 -14.9461, + 6.4479599 37.6008 -203.121, + 1.9 37.6008 -203.121, + 6.3639598 55.400799 -6.3639598, + 25.6078 -39.803001 -18.5893, + 25.471201 -39.803001 -18.505899, + -33.355499 9.4121399 -203.121, + -29.0632 19.9713 -203.121, + -18.374201 37.1008 29.789101, + 26.678699 -39.803001 -7.7123399, + 8.0126495 24.784 -220.078, + 3.80356 55.400799 -8.1567602, + 5.16219 55.400799 -7.3723698, + 2.32937 55.400799 -8.6933403, + 21.4501 -39.803001 -15.3082, + 25.912001 -39.803001 -18.686001, + 26.667101 -39.803001 -18.4907, + 25.756001 -39.803001 -18.6499, + -34.5 0.00013360199 -196.771, + -34.999699 43.338299 -0.148746, + -34.5 -0.027366498 -196.771, + -19.811399 -3.04002 -220.078, + -34.453999 -1.9329799 -203.121, + 5 24.966299 -220.078, + -24.5937 26.1348 -203.121, + -26.977301 23.160999 -203.121, + -17.1308 11.5878 -220.078, + -30.832001 16.5954 -203.121, + -32.2673 13.0647 -203.121, + -13.2018 17.0527 -220.078, + -13.708 16.546499 -220.078, + -34.1357 44.338299 -7.7298899, + -34.7882 44.338299 -3.84431, + 1.93593 50.6008 22.1278, + 25.373699 -39.803001 -5.7410302, + 25.6817 -39.803001 -5.3400002, + 25.452999 -39.803001 -5.5904102, + 25.027901 -39.803001 -7.0430102, + -31.267599 -37.627998 14.5803, + -29.363501 -37.627998 18.1117, + 26.485701 -39.803001 -5.1483102, + 25.5567 -39.803001 -5.45544, + 25.8246 -39.803001 -5.2474499, + 26.146601 -39.803001 -5.1409898, + 26.3165 -39.803001 -5.1301699, + 25.9811 -39.803001 -5.18047, + 32.209 37.1008 15.0214, + 63.312698 0.00013360199 -29.695299, + 8.1108398 44.338299 34.047199, + 6.7000499 43.338299 34.352699, + 9.05867 37.1008 33.8074, + 9.05867 -37.127998 33.8074, + 65.122704 0.00013359841 -35.435902, + 65.122704 -0.027366504 -35.435902, + 61.364498 34.785999 -28.0994, + 65.292503 6.8919902 -172.52499, + 65.292503 23.1738 -137.756, + 65.292503 27.6008 -37.9021, + -18.464199 1.1217 -220.078, + -18.369499 8.8354998 -220.078, + -7.96418 -13.9086 -220.078, + -14.9968 7.9275799 -220.078, + -15.5694 14.1706 -220.078, + -18.652399 -7.9823198 -220.078, + -16.616199 -34.627998 -201.821, + -21.241699 50.6008 -6.4942398, + -21.938801 50.6008 -3.4747701, + -0.784401 55.400799 -8.9657497, + 0.78440201 55.400799 -8.9657497, + -2.32937 55.400799 -8.6933403, + 56.855202 37.4659 -162.558, + 8.1567698 55.400799 -3.80357, + 56.148701 37.563999 -162.563, + -5.32969 55.400799 -3.73189, + 8.6933298 55.400799 -2.32937, + 21.6998 -39.803001 -15.7479, + 21.5919 -39.803001 -15.6163, + 21.828501 -39.803001 -15.8593, + 6.4479599 -37.627998 -203.121, + 26.071699 -39.803001 -18.6968, + 26.386101 -39.803001 -18.641899, + 26.2311 -39.803001 -18.681999, + 26.5327 -39.803001 -18.5776, + 21.4475 -39.803001 -14.8025, + 21.4195 -39.803001 -14.9704, + 21.5035 -39.803001 -14.6417, + 21.4203 -39.803001 -15.1406, + 21.507799 -39.803001 -15.4683, + -19.811399 2.9852901 -220.078, + -34.0867 5.67172 -203.121, + -19.267401 5.95401 -220.078, + -19.9937 -0.027366495 -220.078, + -34.453999 1.87824 -203.121, + -33.355499 -9.4668798 -203.121, + -19.267401 -6.0087399 -220.078, + -34.0867 -5.72645 -203.121, + -17.733 -34.353001 -200.252, + -34.535999 -37.421902 -5.0587802, + -17.4597 -34.627998 -200.22099, + 17.208599 43.338299 30.477301, + 14.707 43.338299 31.760099, + 12.9222 37.1008 32.527199, + 12.1104 43.338299 32.8381, + 26.145901 37.1008 23.267799, + 29.3776 43.338299 19.0252, + 27.7558 43.338299 21.321699, + -17.639 0.00013360711 30.2302, + -17.709299 43.338299 30.1891, + -0.784401 55.400799 8.9657602, + -2.32937 55.400799 8.6933403, + -7.2316198 50.6008 21.0021, + 7.3723698 55.400799 -5.1621799, + -18.4296 44.338299 29.754801, + 5.0726199 -37.127998 34.630501, + 3.9212201 43.338299 34.779598, + -1.1625 50.6008 22.1819, + -4.2383099 50.6008 21.804199, + -6.8675699 0.00013359915 34.319599, + -6.8675699 -0.027366504 34.319599, + -1.12508 0.00013360611 34.981899, + -1.12508 -0.027366508 34.981899, + 1.01797 37.1008 34.985199, + 1.11709 43.338299 34.982201, + 0.301099 44.338299 34.998699, + 23.7439 -39.803001 -14.6325, + 23.3498 -39.803001 -11.4361, + 24.156601 -39.803001 -15.8313, + 21.586 -39.803001 -14.4929, + -29.495001 -37.6035 18.192801, + 1.00342 -37.627998 34.485401, + 1.00792 -37.6035 34.639801, + 1.01002 -37.573502 34.712299, + -3.02666 -37.573502 34.594799, + 65.240501 -28.5408 -36.732399, + 64.408501 -31.531401 -33.427799, + 64.001404 -32.086498 -32.0839, + 64.467903 -31.231899 -33.235001, + 64.502403 -30.926901 -33.045101, + 64.496696 -30.309601 -32.679501, + 64.512001 -30.618601 -32.859501, + 28.6703 37.1008 20.075199, + 33.8302 36.5853 12.7062, + 63.312698 -0.027366504 -29.695299, + 10.2945 0.00013360468 33.451801, + 9.4356604 43.338299 33.704102, + 11.8861 44.338299 32.919899, + 10.2945 -0.0273665 33.451801, + 30.905701 -39.803001 -6.0074501, + 65.292503 -27.628 -37.9021, + 65.231499 -28.694401 -36.826199, + 65.2481 -28.569099 -37.9021, + 58.949501 35.699799 -24.0772, + 59.9146 35.478199 -25.793301, + 58.733601 34.327301 -22.883101, + 60.955101 34.849701 -27.2349, + 62.735001 33.642799 -29.834801, + 63.365101 33.095798 -31.094601, + 65.102203 28.7549 -35.318199, + 65.240501 28.513599 -36.732399, + 63.256302 33.648701 -56.499901, + 65.292503 27.6008 -161.951, + 65.292503 27.6008 -134.271, + 65.292503 27.511 -162.38699, + 65.292503 27.5877 -162.02699, + -34.889702 -37.421902 -1.01519, + -15.9919 -34.627998 -202.214, + -11.2052 -36.050201 -203.121, + -16.3188 -34.627998 -202.041, + -16.1021 -34.353001 -202.466, + -16.795799 -34.353001 -202.02901, + -22.2089 50.6008 -0.387656, + -8.9657497 55.400799 -0.78439897, + -6.4815898 55.400799 -0.56706601, + -8.9657497 55.400799 0.78439498, + 8.1567698 55.400799 3.80356, + 19.427299 50.6008 10.7687, + 8.9657497 55.400799 -0.78439897, + 22.1819 50.6008 -1.1625, + 58.251598 37.128399 -27.1187, + 58.168301 37.161499 -27.117901, + 28.6703 -37.127998 20.075199, + 26.145901 -37.127998 23.267799, + -34.4856 -37.481602 -5.0513902, + -34.426498 -37.532501 -5.0427499, + -34.360298 -37.573502 -5.0330501, + -34.485401 -37.627998 -1.00342, + -31.7208 37.1008 14.7916, + -31.468399 44.338299 15.3212, + -22.374201 0.0001336038 26.9146, + 64.340797 -31.885799 -37.9021, + 65.292503 0.00014385073 -172.96001, + 23.708 -16.6012 -220.078, + 36.977299 -23.2157 -206.55, + 1.9 -37.627998 -203.121, + 25.569401 -14.2254 -220.078, + -17.2694 -34.627998 -200.93401, + -17.3913 -34.627998 -200.58501, + -17.0861 -34.353001 -201.73801, + -17.096901 -34.627998 -201.261, + -16.877501 -34.627998 -201.55901, + -17.365 34.6008 -200.67599, + -17.719299 34.325802 -200.356, + -17.447399 34.6008 -200.315, + -17.477699 34.325802 -201.13901, + -23.868799 26.9601 -203.121, + -17.6278 34.325802 -200.757, + -17.2299 34.6008 -201.02, + 57.744701 -36.501999 -166.132, + 56.507198 -37.415401 -163.33, + 15.6601 0.0001336038 31.301201, + 15.6601 -0.0273665 31.301201, + 15.5107 44.338299 31.375401, + 16.611 37.1008 30.806999, + 27.625099 44.338299 21.490801, + 25.954901 43.338299 23.4807, + 24.975 0.00013360572 24.520399, + 24.975 -0.027366493 24.520399, + 7.3723698 55.400799 5.16219, + 17.7395 50.6008 13.3677, + 2.32937 55.400799 8.6933403, + 0.78440201 55.400799 8.9657602, + 4.9966798 50.6008 21.643, + 7.9601798 50.6008 20.737, + -5.16219 55.400799 7.3723602, + -3.80356 55.400799 8.1567698, + 4.6006799 55.400799 -4.6006899, + -12.7405 50.6008 18.195299, + -10.0842 50.6008 19.7913, + -22.374201 -0.0273665 26.9146, + -21.7082 37.1008 27.454599, + -20.075199 43.338299 28.6703, + 5.0001502 -37.627998 34.1357, + 1.0057 -37.621799 34.563599, + 1.9 -37.627998 34.407001, + 12.7376 -37.627998 32.0625, + 31.0599 -39.803001 -6.0504799, + 16.4814 -37.573502 30.5667, + 5.0330501 -37.573502 34.360298, + 4.6480899 0.00013360172 34.689999, + 5.0726199 37.1008 34.630501, + 4.23279 44.338299 34.743099, + 4.6480899 -0.027366502 34.689999, + 9.0570698 -37.2062 33.801498, + -1.1233701 -37.127998 34.922901, + 1.01797 -37.127998 34.985199, + 1.01519 -37.421902 34.889702, + -12.4227 0.00013359527 32.721199, + -12.6507 43.338299 32.633701, + -14.7916 37.1008 31.7208, + -14.9686 44.338299 31.6376, + -15.2291 43.338299 31.5131, + -17.639 -0.027366508 30.2302, + -11.0091 37.1008 33.223499, + -11.318 44.338299 33.119499, + -9.9905996 43.338299 33.5438, + -3.0504501 37.1008 34.866798, + -3.6343999 44.338299 34.810799, + -3.0504501 -37.127998 34.866798, + -1.69426 43.338299 34.959, + -7.2660799 43.338299 34.237499, + -7.52385 44.338299 34.181702, + -7.07762 37.1008 34.276901, + -4.4946699 43.338299 34.710201, + -21.3981 -37.627998 27.0623, + -22.496901 -37.627998 26.0846, + -27.123699 -37.621799 21.4466, + -29.430099 -37.621799 18.1528, + -27.0623 -37.627998 21.3981, + -24.395201 -37.627998 24.395201, + -29.687599 43.338299 18.5378, + -29.547001 44.338299 18.7609, + -34.955299 0.00013359814 1.76754, + -34.955299 -0.027366498 1.76754, + -34.999901 44.338299 0.089985907, + -34.866798 37.1008 3.0504401, + -34.898701 43.338299 2.6608701, + 64.787201 -30.6856 -162.177, + 64.793701 -30.6558 -162.586, + 65.096199 -29.146 -35.371201, + 65.0942 -29.298 -35.4674, + 65.091797 -28.9946 -35.274601, + 65.222198 -28.3363 -36.313301, + 63.908699 -32.454899 -32.3274, + 64.324898 -31.823 -33.621899, + 64.073303 -31.3176 -31.622, + 64.056396 -31.705799 -31.847799, + 35.448799 -35.730301 10.3946, + 35.448799 35.702999 10.3946, + 33.8302 -36.612499 12.7062, + 25.830799 -37.621799 22.987499, + 31.4548 -39.803001 -6.3164301, + 20.598499 0.00013360335 28.2967, + 20.598499 -0.027366504 28.2967, + 20.075199 37.1008 28.6703, + 16.447001 -37.6035 30.502899, + 65.198502 -28.968599 -162.058, + 65.1744 -28.998501 -162.75301, + 58.805698 35.9925 -24.208599, + 60.148399 34.8368 -25.5068, + 60.0443 35.163898 -25.6423, + 61.062599 34.5224 -27.0651, + 62.062801 33.828098 -28.428801, + 58.580101 35.2798 -23.0432, + 29.8654 44.338299 18.2498, + 59.068199 35.3932 -23.962, + 59.161201 35.077 -23.863899, + 58.656799 34.9617 -22.971901, + 58.7076 34.642799 -22.918699, + 64.052696 30.8995 -31.408899, + 63.4002 31.0345 -29.8769, + 63.4254 32.875999 -30.9482, + 62.845901 34.154099 -134.47301, + 63.203098 33.718102 -128.938, + 63.203098 33.718102 -50.8186, + 65.0942 29.2708 -35.4674, + 65.096199 29.1187 -35.371201, + 63.4939 33.322399 -50.760601, + 63.382702 33.4786 -37.9021, + -9.6108599 16.6325 -220.078, + 16.615101 22.103399 -220.078, + 64.494598 31.5149 -56.080101, + 65.192902 7.0667901 -173.922, + 64.896202 7.2381001 -175.291, + 65.192497 7.6592698 -173.84801, + 65.292503 7.4700999 -172.45, + -0.981372 -24.294701 -220.078, + -3.86287 -23.396799 -220.078, + -2.9549501 -23.6798 -220.078, + -7.9254498 -37.352699 -203.121, + -26.977301 -23.2157 -203.121, + -11.6599 -17.2363 -220.078, + -30.832001 -16.650101 -203.121, + -29.0632 -20.025999 -203.121, + -18.369499 -8.8902397 -220.078, + -32.2673 -13.1194 -203.121, + -34.930698 -37.355 -1.01638, + -9.1980104 -20.596701 -220.078, + -6.6151299 -22.1581 -220.078, + -16.4653 -34.353001 -202.27299, + -6.3639598 55.400799 6.3639598, + 5 23.972601 -220.078, + 10.9814 24.24 -220.078, + -10.6494 17.359699 -220.078, + -6.3639598 55.400799 -6.3639598, + -7.3723698 55.400799 -5.1621799, + -3.80356 55.400799 -8.1567602, + -5.16219 55.400799 -7.3723698, + -6.28932 37.6008 -203.121, + -7.1259899 37.530701 -203.121, + -8.1567698 55.400799 -3.80357, + -8.6933298 55.400799 -2.32937, + -7.1166 37.532299 -203.121, + -0.981372 24.24 -220.078, + 1.98735 24.784 -220.078, + 21.643 50.6008 4.9966898, + 20.737 50.6008 7.9601798, + 8.6933298 55.400799 2.32938, + 8.9657497 55.400799 0.78439498, + 22.1278 50.6008 1.93593, + 34.226501 44.338299 7.3175402, + 26.1052 -37.355 23.2316, + 23.2316 -37.355 26.1052, + 20.020399 -37.421902 28.5921, + 28.5504 -37.481602 19.991199, + -34.2131 -37.621799 -5.0114899, + -34.1357 -37.627998 -5.0001502, + -34.288601 -37.6035 -5.0225401, + -7.1166 -37.559502 -203.121, + -6.28932 -37.627998 -203.121, + -34.594799 -37.573502 3.02666, + -34.639801 -37.6035 -1.00792, + -34.712299 -37.573502 -1.01002, + -32.748901 -37.627998 10.8518, + -32.8955 -37.6035 10.9004, + -32.823101 -37.621799 10.8764, + -31.4076 -37.6035 14.6456, + -31.338499 -37.621799 14.6134, + -31.7208 -37.127998 14.7916, + -29.768299 -37.282501 18.3613, + -29.890699 -37.127998 18.185801, + -32.4874 0.00013360722 13.0218, + -32.271198 43.338299 13.5488, + 64.217903 -32.104401 -33.8158, + 64.350502 -31.8375 -134.382, + 65.292503 1.9058501 -172.92599, + 8.0126495 -24.8388 -220.078, + 5 -25.021 -220.078, + 1.98735 -24.8388 -220.078, + -34.8424 -37.282501 3.04831, + -34.960701 -37.282501 -1.01726, + -34.979 -37.2062 -1.0177799, + -34.904202 -37.127998 1.76605, + -34.985199 -37.127998 -1.01796, + -32.4874 -0.027366508 13.0218, + -33.223499 37.1008 11.0091, + -34.866798 -37.127998 3.0504401, + -9.9288101 19.9695 -220.078, + -21.2003 29.560101 -203.121, + -3.86287 23.3421 -220.078, + -11.5739 18.6807 -220.078, + 58.269199 -35.822498 -167.44501, + 56.989498 -37.1544 -164.384, + 57.1465 -37.053299 -164.733, + 56.722801 -37.326099 -163.791, + 57.775501 -37.2701 -162.549, + 55.9687 -37.577599 -162.577, + 56.148701 -37.563801 -162.563, + 55.2925 -37.600498 -162.931, + 28.305 -39.803001 -15.9711, + 26.8862 -39.803001 -18.258699, + 55.802101 -37.587502 -162.617, + 56.6432 -37.5364 -32.429798, + 56.7061 -37.527599 -32.4706, + 56.801601 -37.5135 -27.5054, + 56.907902 -37.4967 -27.4468, + 61.0425 -35.809502 -30.7995, + 22.1269 44.338299 27.1182, + 25.034599 44.338299 24.459499, + 23.986601 43.338299 25.4881, + 23.2679 37.1008 26.145901, + 21.863501 43.338299 27.3311, + 19.5993 43.338299 28.9977, + 18.938801 44.338299 29.4333, + 15.7065 50.6008 15.7065, + 5.16219 55.400799 7.3723602, + 6.3639598 55.400799 6.3639598, + 13.3677 50.6008 17.7395, + 3.80356 55.400799 8.1567698, + 10.7687 50.6008 19.427299, + 8.9292603 -37.627998 33.324402, + 6.4479599 -37.627998 33.8368, + 5.0114899 -37.621799 34.2131, + 9.4479599 -37.627998 33.152599, + 9.0207596 -37.481602 33.666, + 5.0427399 -37.532501 34.426498, + 5.0513902 -37.481602 34.4856, + 9.0053196 -37.532501 33.608299, + 12.8681 -37.481602 32.391102, + 12.8461 -37.532501 32.335602, + 9.0445604 -37.355 33.754799, + 5.0647202 -37.355 34.5765, + 5.0587802 -37.421902 34.535999, + 9.0339499 -37.421902 33.715199, + 9.05233 -37.282501 33.783798, + 16.5851 -37.355 30.7591, + 12.9021 -37.355 32.476501, + 12.887 -37.421902 32.4384, + 16.565701 -37.421902 30.723, + 16.608101 -37.2062 30.8016, + 12.9199 -37.2062 32.5214, + 12.9132 -37.282501 32.504398, + 15.6407 -37.127998 31.259501, + 16.611 -37.127998 30.806999, + 12.9222 -37.127998 32.527199, + 20.075199 -37.127998 28.6703, + -14.5803 -37.627998 31.267599, + -18.1117 -37.627998 29.363501, + -21.4466 -37.621799 27.123699, + -19.5175 -37.627998 28.3792, + -14.789 -37.2062 31.7152, + -14.7813 -37.282501 31.698601, + -10.9232 -37.573502 32.964298, + -6.9923201 -37.621799 33.863899, + -3.00687 -37.627998 34.368698, + -6.97651 -37.627998 33.787201, + -3.01369 -37.621799 34.446602, + -10.8764 -37.621799 32.823101, + -7.00775 -37.6035 33.938599, + -3.02034 -37.6035 34.522598, + -7.34796 -37.627998 33.687698, + -10.8518 -37.627998 32.748901, + -7.0359402 -37.532501 34.0751, + -7.0224099 -37.573502 34.009602, + -3.0376899 -37.481602 34.720901, + -3.03249 -37.532501 34.661499, + 1.01371 -37.481602 34.838799, + 1.01197 -37.532501 34.779202, + -7.05831 -37.421902 34.183399, + -3.04213 -37.421902 34.771702, + -7.0479999 -37.481602 34.133499, + -12.4024 -37.127998 32.669998, + -12.4227 -0.027366504 32.721199, + -11.0091 -37.127998 33.223499, + -14.7916 -37.127998 31.7208, + -18.374201 -37.127998 29.789101, + -18.370899 -37.2062 29.7838, + -18.3613 -37.282501 29.768299, + -29.7838 -37.2062 18.371, + -29.6644 -37.481602 18.2973, + -31.534 -37.532501 14.7045, + -31.587999 -37.481602 14.7298, + -31.473301 -37.573502 14.6763, + -32.964298 -37.573502 10.9232, + -27.379601 -37.421902 21.649, + -27.339701 -37.481602 21.617399, + -27.4118 -37.355 21.6744, + -29.7078 -37.421902 18.323999, + -29.742701 -37.355 18.3456, + -29.900999 0.00013360329 18.191401, + -29.789101 37.1008 18.374201, + -31.0797 43.338299 16.0952, + -29.900999 -0.0273665 18.191401, + 64.747597 -30.802099 -34.682301, + 63.848701 -32.633099 -32.451, + 63.510799 -31.504801 -30.1653, + 63.534698 -31.9793 -30.404499, + 63.419399 -31.022699 -29.957001, + 64.052696 -30.926701 -31.408899, + 62.037201 0.00013359246 -27.5777, + 59.473301 33.701401 -23.916, + 62.037201 31.8414 -27.5777, + 61.155102 32.474701 -26.3179, + 58.738098 34.018501 -22.865999, + 61.145199 34.183998 -26.909401, + 62.893398 32.565498 -29.2145, + 62.477798 33.440498 -28.9417, + 62.848701 33.115398 -29.509199, + 62.8703 32.006901 -28.956301, + 63.510799 31.4776 -30.1653, + 63.9823 -30.530701 -31.2129, + 19.8333 -37.621799 28.3248, + 22.987499 -37.621799 25.830799, + 23.0382 -37.6035 25.8878, + 19.877001 -37.6035 28.3873, + 31.337999 -39.803001 -6.2069802, + 16.410801 -37.621799 30.435801, + 31.2052 -39.803001 -6.1175499, + 25.9419 -37.573502 23.086399, + 25.8878 -37.6035 23.0382, + 23.204399 -37.421902 26.074499, + 26.074499 -37.421902 23.204399, + 19.9186 -37.573502 28.446699, + 16.513201 -37.532501 30.625601, + 19.991199 -37.481602 28.5504, + 16.5415 -37.481602 30.6782, + 65.292503 -23.499901 -130.905, + 65.184601 -28.725201 -163.439, + 59.288399 34.1152 -23.6749, + 62.118599 32.357601 -27.7465, + 63.5065 32.421001 -30.666901, + 63.534698 31.952 -30.404499, + 64.001404 32.0592 -32.0839, + 63.908699 32.427601 -32.3274, + 63.848701 32.605801 -32.451, + 62.367401 34.667999 -51.212002, + 62.363602 34.671799 -37.9021, + 62.882401 34.080898 -31.8566, + 63.001301 33.9016 -31.7024, + 63.331402 33.5439 -32.959301, + 62.753601 34.250099 -32.0103, + 62.396801 34.638401 -37.9021, + 62.741699 34.272301 -129.118, + 63.4939 33.322399 -128.88, + 63.506901 33.303699 -37.9021, + 63.6152 33.144501 -134.67101, + 62.013199 34.972198 -30.917999, + 62.317402 34.709599 -31.5522, + 58.241798 36.747101 -24.6831, + 31.727301 44.338299 14.7775, + 58.638401 36.267101 -24.354601, + 58.449501 36.5196 -24.5135, + 64.633598 31.1707 -55.816502, + 64.633598 31.1707 -133.936, + 64.408501 31.5042 -33.427799, + 64.747597 30.7749 -34.682301, + 64.467903 31.2047 -33.235001, + 64.056396 31.6786 -31.847799, + 64.512001 30.5914 -32.859501, + 65.091797 28.9674 -35.274601, + 64.502403 30.899599 -33.045101, + 64.073303 31.2904 -31.622, + 64.069199 32.393398 -128.959, + 64.069199 32.393398 -50.839699, + 63.8363 32.797298 -128.88699, + 64.747597 30.856701 -129.93401, + 64.681602 31.042299 -55.694801, + 64.681602 31.042299 -133.814, + 64.747597 30.856701 -51.815201, + 64.781097 30.757799 -55.361, + 63.7006 11.0073 -177.371, + 63.659401 13.8286 -176.86501, + 63.758999 4.82231 -178.08701, + 64.419899 4.7231302 -176.855, + 63.673 -12.9626 -177.032, + 64.347801 -15.0253 -175.315, + 63.6339 -15.3304 -176.55099, + 5.75 21.173599 -220.078, + 19.500401 16.395599 -220.078, + 26.7146 34.325802 -202.09599, + 26.5431 34.6008 -201.881, + 34.378201 26.150999 -206.55, + 26.0047 34.325802 -202.506, + 26.375 34.325802 -202.328, + 13.8629 23.3421 -220.078, + 21.1117 35.8097 -203.121, + 25.9042 34.6008 -202.25, + 26.237499 34.6008 -202.09, + 43.355499 9.4121399 -206.55, + 44.0867 5.67172 -206.55, + 42.2673 13.0647 -206.55, + 19.928801 19.9695 -220.078, + 34.781502 25.8633 -206.55, + 62.726799 24.17 -174.979, + 63.421398 23.282801 -174.42101, + 63.4958 21.892 -174.826, + 64.901497 4.6175098 -175.54201, + 65.195 1.95481 -174.319, + 65.194298 4.5075202 -174.17599, + 65.292503 24.116899 -167.258, + 65.292503 10.0471 -172.043, + 65.292503 21.0595 -169.03799, + 65.292503 21.432501 -168.877, + -14.9968 -14.9562 -220.078, + -17.1308 -11.6425 -220.078, + -15.5694 -14.2254 -220.078, + -13.2018 -17.1075 -220.078, + -11.5739 -18.735399 -220.078, + -21.2003 -29.587299 -203.121, + -17.329901 -34.353001 -201.407, + -17.521601 -34.353001 -201.04401, + -8.1567698 55.400799 3.80356, + -8.6933298 55.400799 2.32938, + -20.446501 50.6008 8.6790304, + -7.3723698 55.400799 5.16219, + -19.0397 50.6008 11.4402, + 59.572899 36.635201 -32.586601, + 20.0439 -37.355 28.6257, + 16.5994 -37.282501 30.7855, + 23.2638 -37.2062 26.1413, + 20.579 -37.127998 28.271999, + 23.2679 -37.127998 26.145901, + 20.0716 -37.2062 28.6653, + 26.1413 -37.2062 23.2638, + 20.0611 -37.282501 28.650299, + 23.2516 -37.282501 26.1276, + 26.1276 -37.282501 23.2516, + -34.720901 -37.481602 3.0376899, + -34.779202 -37.532501 -1.01197, + -34.838799 -37.481602 -1.0137, + -34.446602 -37.621799 3.01368, + -33.8638 -37.621799 6.9923201, + -33.938599 -37.6035 7.00775, + -34.522598 -37.6035 3.02034, + -34.317001 -37.627998 3.3599999, + -34.368698 -37.627998 3.00687, + -34.563599 -37.621799 -1.0057, + -33.7873 -37.627998 6.97651, + -34.0233 43.338299 8.2105999, + -34.572498 43.338299 5.45333, + -34.768002 44.338299 4.02315, + -33.254501 43.338299 10.9149, + -32.991001 44.338299 11.6873, + -21.4554 50.6008 5.74897, + -22.0467 50.6008 2.707, + -24.6101 44.338299 24.8866, + -24.748699 37.1008 24.748699, + -24.403999 43.338299 25.0888, + -21.657101 44.338299 27.4949, + -15.1488 50.6008 16.2451, + -22.311501 43.338299 26.9666, + -17.262199 50.6008 13.9787, + 63.295898 -33.595901 -128.914, + 63.473999 -33.378101 -37.9021, + 63.7798 -32.806599 -32.575298, + 63.616798 -33.137798 -32.8246, + 63.7024 -32.974998 -32.700001, + 62.9739 -34.030899 -32.5662, + 63.523499 -33.294601 -32.948799, + 62.753601 -34.277302 -32.0103, + 64.434502 -31.651699 -129.26199, + 64.502701 -31.4956 -129.356, + 64.524902 -31.442801 -134.151, + 64.407204 -31.714001 -129.224, + 64.413399 -31.728001 -34.581799, + 64.201202 -32.139801 -162.269, + 64.111504 -32.2985 -162.27901, + 59.550301 -36.6763 -37.9021, + 58.6301 -36.664902 -164.63699, + 65.219704 -28.8053 -162.04601, + 65.195198 0.00013546593 -174.35201, + 65.292503 -27.6005 -161.951, + 64.904404 2.00281 -175.68401, + 64.905098 0.00013825612 -175.716, + 65.194901 -2.5216801 -174.297, + 64.1819 -32.0938 -162.84599, + 39.063301 -20.025999 -206.55, + 64.323402 -17.2209 -174.78999, + 26.0123 -34.627998 -202.205, + 21.1117 -35.836899 -203.121, + 26.4863 -34.353001 -202.25999, + 26.337601 -34.627998 -202.02901, + 16.615101 -22.1581 -220.078, + 26.1248 -34.353001 -202.45599, + 12.955 -23.6798 -220.078, + 13.8629 -23.396799 -220.078, + 16.3183 -37.627998 -203.121, + 10.9814 -24.294701 -220.078, + 21.5739 -18.735399 -220.078, + 19.198 -20.596701 -220.078, + 23.201799 -17.1075 -220.078, + 35.131901 -25.5679 -206.55, + 27.1308 -11.6425 -220.078, + -34.0751 -37.532501 7.0359402, + -34.661499 -37.532501 3.03249, + -34.009602 -37.573502 7.0224099, + -33.027802 -37.532501 10.9442, + -34.8125 -37.355 3.0457101, + -34.771702 -37.421902 3.04213, + -34.133499 -37.481602 7.0479898, + -33.084499 -37.481602 10.963, + -31.698601 -37.282501 14.7813, + -34.860699 -37.2062 3.0499101, + -34.276901 -37.127998 7.07762, + -16.814301 34.6008 -201.63, + -17.0159 34.325802 -201.817, + -17.044901 34.6008 -201.34, + -17.2722 34.325802 -201.495, + -7.9254498 37.3255 -203.121, + -9.1980104 20.542 -220.078, + -6.6151299 22.103399 -220.078, + 30.984501 -39.803001 -9.8087702, + 29.529699 -39.803001 -13.5739, + 55.367802 -37.600201 -162.86501, + 28.9422 -39.803001 -14.7851, + 30.0665 -39.803001 -12.3393, + 30.551701 -39.803001 -11.0835, + 27.619301 -39.803001 -17.129601, + 26.785999 -39.803001 -18.383499, + 31.689899 -39.803001 -7.2109599, + 55.7304 -37.5909 -162.64301, + 55.559399 -37.596901 -162.728, + 31.712799 -39.803001 -7.0525298, + 31.3641 -39.803001 -8.5171604, + 56.233601 -37.583599 -37.9021, + 57.573399 -37.364399 -32.8363, + 58.251598 -37.177101 -32.907501, + 58.0261 -37.247101 -32.908001, + 57.931198 -37.273602 -37.9021, + 60.867001 -35.930099 -31.269501, + 62.037201 -31.868601 -27.5777, + 63.0285 -31.325899 -29.162701, + 63.5065 -32.4482 -30.666901, + 63.4254 -32.903301 -30.9482, + 56.427101 -37.5634 -27.7626, + 56.680302 -37.5312 -25.6292, + 31.710199 -39.803001 -6.8924599, + 31.681999 -39.803001 -6.73488, + 57.310699 -37.422199 -27.2736, + 57.1026 -37.462799 -32.679401, + 57.518398 -37.377102 -32.822498, + 57.185501 -37.419701 -162.556, + 60.468102 -36.183102 -31.876301, + 60.542198 -36.139198 -31.7952, + 60.110001 -36.388699 -32.230999, + 60.2295 -36.324299 -32.1376, + 8.9692497 -37.6035 33.473701, + 8.9880104 -37.573502 33.543701, + 5.0225401 -37.6035 34.288601, + 8.9495001 -37.621799 33.400002, + 12.8214 -37.573502 32.273499, + 12.7947 -37.6035 32.2061, + 12.7665 -37.621799 32.135201, + -14.7513 -37.421902 31.634199, + -18.2973 -37.481602 29.6644, + -14.7686 -37.355 31.6714, + -10.9919 -37.355 33.171799, + -10.979 -37.421902 33.132801, + -14.7045 -37.532501 31.534, + -14.7297 -37.481602 31.587999, + -10.963 -37.481602 33.084499, + -10.9442 -37.532501 33.027802, + -18.266001 -37.532501 29.613701, + -21.5389 -37.573502 27.2404, + -18.1528 -37.621799 29.430099, + -18.2309 -37.573502 29.5567, + -11.0014 -37.282501 33.200298, + -7.0665998 -37.355 34.223598, + 1.0172499 -37.282501 34.960701, + -3.0457001 -37.355 34.8125, + 1.01638 -37.355 34.930698, + -3.0483201 -37.282501 34.8424, + 5.0690699 -37.282501 34.606201, + 1.01779 -37.2062 34.979, + 5.0717201 -37.2062 34.624401, + -24.7444 -37.2062 24.7444, + -21.6931 -37.282501 27.435301, + -24.7314 -37.282501 24.7314, + -21.704399 -37.2062 27.449699, + -21.7082 -37.127998 27.454599, + -27.4354 -37.282501 21.6931, + -24.5044 -37.6035 24.5044, + -24.4505 -37.621799 24.4505, + -21.493999 -37.6035 27.1835, + -24.603001 -37.532501 24.603001, + -24.645201 -37.481602 24.645201, + -21.5804 -37.532501 27.2929, + -29.789101 -37.127998 18.374201, + -27.449699 -37.2062 21.704399, + -27.2404 -37.573502 21.5389, + -24.5557 -37.573502 24.5557, + -27.1835 -37.6035 21.493999, + -27.2929 -37.532501 21.5804, + -29.5567 -37.573502 18.2309, + -29.613701 -37.532501 18.266001, + 64.782097 -30.7544 -133.476, + 65.169403 -29.164801 -37.9021, + 65.167 -29.1408 -162.312, + 64.641296 -31.1502 -129.625, + 63.206799 -33.542198 -31.3953, + 62.652599 -33.921398 -30.006901, + 63.365101 -33.123001 -31.094601, + 63.292198 -33.3363 -31.243799, + 64.459396 0.00013360004 -32.489399, + 64.421898 30.0217 -32.395401, + 63.8176 -30.7139 -30.766199, + 64.459396 -0.027366502 -32.489399, + 64.496696 30.282301 -32.679501, + 64.9851 -29.098301 -34.5896, + 64.4953 -29.9599 -32.604599, + 23.1308 -37.532501 25.991899, + 19.957001 -37.532501 28.501499, + 23.086399 -37.573502 25.9419, + 23.1705 -37.481602 26.036501, + 25.991899 -37.532501 23.1308, + 26.036501 -37.481602 23.1705, + 60.279099 34.160099 -25.2857, + 60.3064 33.818501 -25.201099, + 62.146599 33.104698 -28.053699, + 61.202702 33.837799 -26.769199, + 60.2267 34.500801 -25.3876, + 59.228401 34.755901 -23.7834, + 59.270401 34.433899 -23.7206, + 64.686203 30.9958 -34.8242, + 64.626701 31.188499 -51.471901, + 64.606102 31.239201 -51.433998, + 64.479897 31.549299 -51.202, + 64.324898 31.7957 -33.621899, + 64.828598 30.323 -34.396198, + 65.0858 29.4233 -35.563099, + 64.795097 30.550301 -34.539501, + 64.155998 32.213501 -33.912201, + 64.217903 32.077202 -33.8158, + 63.616798 33.1105 -32.8246, + 64.411499 31.690901 -34.564201, + 63.523499 33.2673 -32.948799, + 62.652599 33.8941 -30.006901, + 62.3451 34.003101 -29.289101, + 62.777401 34.232201 -56.3223, + 62.845901 34.154099 -56.354, + 62.777401 34.232201 -134.44099, + 62.741699 34.272301 -50.999199, + 60.867001 35.902802 -31.269501, + 60.9659 35.8349 -31.004601, + 60.98 35.825901 -52.660198, + 60.916 35.869701 -54.513901, + 60.854599 35.911201 -52.937, + 63.370998 33.469799 -162.347, + 63.256302 33.648701 -134.619, + 64.072502 32.387299 -134.582, + 64.072502 32.387299 -56.463001, + 61.9002 35.106602 -51.557701, + 61.847 35.145199 -31.1026, + 61.795101 35.197899 -55.655102, + 58.450001 37.044899 -27.1276, + 58.3876 37.0742 -27.1199, + 58.018398 36.9468 -24.8608, + 33.187199 44.338299 11.118, + 58.135201 37.0965 -26.0882, + 61.864899 34.507198 -28.864401, + 62.310799 34.5812 -30.547899, + 62.439701 34.364601 -30.364599, + 62.168201 34.784 -30.7328, + 64.479897 31.549299 -129.321, + 64.202599 32.140701 -37.9021, + 64.3209 31.900499 -56.292, + 64.369499 31.7971 -37.9021, + 64.300903 31.9422 -129.11301, + 64.3209 31.900499 -134.411, + 64.293602 31.957399 -134.436, + 64.300903 31.9422 -50.993599, + 64.293602 31.957399 -56.3172, + 63.6432 33.1008 -56.550098, + 63.6152 33.144501 -56.5518, + 63.8363 32.797298 -50.768002, + 63.808399 32.842899 -56.5406, + 63.6432 33.1008 -134.66901, + 64.4048 8.0225801 -176.532, + 64.386299 10.7849 -176.13699, + 63.7328 8.1894398 -177.765, + 63.738701 7.5567899 -177.838, + 64.408203 7.4025302 -176.605, + 64.8946 7.8446698 -175.218, + 63.5513 19.488501 -175.52299, + 63.609501 16.655399 -176.24899, + 64.362503 13.5519 -175.63, + 64.333702 16.3256 -175.01199, + 63.735001 -7.95503 -177.79201, + 64.406097 -7.79283 -176.56, + 63.755798 -5.3523302 -178.047, + 63.7071 -10.4968 -177.45, + 40.832001 16.5954 -206.55, + 28.369499 8.8354998 -220.078, + 28.652399 7.9275799 -220.078, + 29.267401 5.95401 -220.078, + 29.811399 2.9852901 -220.078, + 29.9937 -0.027366504 -220.078, + 28.9095 -0.54039699 -220.078, + 25.569401 14.1706 -220.078, + 39.063301 19.9713 -206.55, + 23.201799 17.0527 -220.078, + 21.8741 17.031601 -220.078, + 19.198 20.542 -220.078, + 21.5739 18.6807 -220.078, + 23.708 16.546499 -220.078, + 27.1308 11.5878 -220.078, + 58.238201 35.868801 -167.36501, + 26.814301 34.6008 -201.63, + 16.3183 37.6008 -203.121, + 56.989399 37.154499 -164.384, + 56.717899 37.328999 -163.78101, + 57.775501 37.270401 -162.549, + 57.185501 37.419998 -162.556, + 61.4823 35.4548 -130.078, + 61.398201 35.520401 -133.37, + 60.98 35.825901 -130.77901, + 64.946899 30.2071 -131.771, + 65.292397 27.65 -161.95599, + 65.256104 28.4536 -37.9021, + 62.596199 25.5917 -174.435, + 62.254902 28.5674 -172.88901, + 61.160198 30.321699 -172.597, + 36.977299 23.160999 -206.55, + 35.131901 25.513201 -206.55, + 59.965 34.556499 -168.407, + 59.554798 35.402 -167.16, + 62.1796 34.851101 -162.424, + 62.356201 34.664902 -162.414, + 62.103001 34.915798 -162.42799, + 62.367401 34.667999 -129.33099, + 62.289398 34.7453 -134.16, + 61.9002 35.106602 -129.677, + 62.1036 34.922298 -31.667299, + 61.795101 35.197899 -133.774, + 62.289398 34.7453 -56.040699, + 62.899101 34.0923 -162.383, + 60.8992 31.555 -171.617, + 63.3848 23.837099 -174.237, + 63.2864 25.1992 -173.71201, + 65.292503 22.3316 -168.43201, + 65.292503 25.4517 -166.021, + 65.292503 24.8165 -166.659, + 65.292503 17.8272 -170.13499, + 65.292503 20.0392 -169.41499, + 65.180603 18.2668 -171.561, + 64.862503 15.972 -173.687, + -23.868799 -26.9874 -203.121, + -13.708 -16.6012 -220.078, + -24.5937 -26.1896 -203.121, + -23.8431 -27.0149 -203.121, + -17.657 -34.353001 -200.655, + 59.833401 36.5103 -32.4473, + 60.739201 35.987301 -131.492, + 60.718399 36.000801 -53.6521, + -34.187698 0.00013360308 7.4968901, + -34.276901 37.1008 7.07762, + -34.187698 -0.0273665 7.4968901, + -34.095501 44.338299 7.9053202, + 63.370998 -33.469501 -162.347, + 63.2444 -33.664001 -134.616, + 62.439201 -34.5952 -134.256, + 62.363602 -34.6991 -37.9021, + 61.0425 -35.809502 -37.9021, + 61.014301 -35.8018 -132.826, + 60.879799 -35.894001 -132.55, + 64.151802 -32.238701 -134.53999, + 64.189102 -32.166698 -162.271, + 64.155998 -32.240799 -33.912201, + 63.943501 -32.616501 -128.912, + 63.8834 -32.7188 -134.646, + 63.767899 -32.935299 -33.551899, + 63.980301 -32.552601 -128.924, + 64.897797 -29.646799 -164.68401, + 59.826199 -36.498501 -162.50999, + 59.3442 -36.739601 -162.522, + 58.267799 -36.981602 -163.729, + 58.306599 -37.135502 -162.54201, + 59.3955 -36.720001 -162.521, + 65.180397 -18.395599 -171.522, + 64.846497 -18.828199 -172.91701, + 65.177597 -20.0954 -170.992, + 64.857803 -16.8489 -173.463, + 65.183197 -16.4597 -172.07401, + 65.190804 -9.82127 -173.52699, + 65.292503 4.39533 -172.782, + 64.879097 -12.4243 -174.478, + 65.188599 -12.134 -173.10001, + 64.888 -10.0577 -174.89999, + 64.3703 -12.7024 -175.797, + 64.868896 -14.6986 -173.992, + 65.185997 -14.3571 -172.60899, + 64.389999 -10.2844 -176.217, + 65.292503 -7.2558498 -172.479, + 65.292503 -9.5799599 -172.12601, + 65.292503 -2.4586101 -172.90401, + 65.292503 -4.8789802 -172.741, + 65.292397 -27.649799 -161.95599, + 65.292503 -27.5867 -162.03101, + 63.772999 0.00014198197 -178.259, + 63.770401 2.0922501 -178.22701, + 64.426399 2.0489199 -176.995, + 64.427902 0.00014012471 -177.02699, + 44.453999 -1.9329799 -206.55, + 63.7686 -2.69874 -178.205, + 44.453999 1.87824 -206.55, + 64.900597 -5.1253099 -175.502, + 64.903999 -2.5835199 -175.662, + 65.194 -5.0033698 -174.13499, + 65.192703 -7.4397101 -173.87601, + 64.895203 -7.6199002 -175.245, + 64.417999 -5.2424002 -176.815, + 64.4254 -2.64293 -176.97301, + 34.781502 -25.917999 -206.55, + 63.597599 -33.170502 -162.33099, + 62.356201 -34.6646 -162.414, + 62.540401 -26.146 -174.19, + 62.390701 -27.496201 -173.51401, + 40.832001 -16.650101 -206.55, + 64.184601 -28.1285 -169.82401, + 64.6222 -28.2516 -168.28999, + 63.591599 -17.5676 -176.02699, + 63.548302 -19.625299 -175.48599, + 64.298401 -19.241199 -174.248, + 64.835701 -20.565599 -172.392, + 63.506901 -21.4303 -174.965, + 64.274399 -21.014 -173.72701, + 29.267401 -6.0087399 -220.078, + 28.369499 -8.8902397 -220.078, + 29.811399 -3.04002 -220.078, + 42.2673 -13.1194 -206.55, + 43.355499 -9.4668798 -206.55, + 44.0867 -5.72645 -206.55, + -33.171799 -37.355 10.9919, + -34.223499 -37.355 7.0665898, + -34.252998 -37.282501 7.07267, + -34.183399 -37.421902 7.05831, + -33.132801 -37.421902 10.979, + -31.6714 -37.355 14.7686, + -31.634199 -37.421902 14.7513, + -33.217602 -37.2062 11.0071, + -34.270901 -37.2062 7.0763698, + -33.223499 -37.127998 11.0091, + -33.200298 -37.282501 11.0014, + -31.7152 -37.2062 14.789, + -32.432598 -37.127998 13, + -16.237499 34.6008 -202.09, + -16.5431 34.6008 -201.881, + -16.7146 34.325802 -202.09599, + -16.375 34.325802 -202.328, + -11.2052 36.0229 -203.121, + 57.700802 -37.334702 -27.1695, + 60.730598 -35.992599 -131.985, + 60.787399 -35.983002 -31.4238, + 60.7188 -36.000198 -131.729, + 28.5921 -37.421902 20.020399, + 58.1595 -34.127998 -22.039801, + 32.209 -37.127998 15.0214, + 62.8703 -32.0341 -28.956301, + 56.233501 -37.582401 -27.945601, + 56.103401 -37.5951 -28.068501, + 56.3899 -37.567101 -27.797701, + 56.2948 -37.577599 -32.157101, + 31.5527 -39.803001 -6.44312, + 31.629101 -39.803001 -6.5837998, + 31.863501 -37.621799 14.7795, + 57.036701 -37.474602 -25.6026, + 56.359299 -37.566601 -24.726601, + 57.4095 -36.4883 -22.565001, + 28.446699 -37.573502 19.9186, + -21.649 -37.421902 27.379601, + -21.617399 -37.481602 27.339701, + -18.323999 -37.421902 29.7078, + -18.3456 -37.355 29.742701, + -21.6744 -37.355 27.4118, + -24.6812 -37.421902 24.6812, + -24.710199 -37.355 24.710199, + -14.6456 -37.6035 31.4076, + -18.192801 -37.6035 29.495001, + -14.6763 -37.573502 31.4734, + -14.6134 -37.621799 31.338499, + -10.9004 -37.6035 32.8955, + -7.0763698 -37.2062 34.270901, + -11.0071 -37.2062 33.217701, + -7.07762 -37.127998 34.276901, + -7.07267 -37.282501 34.252998, + -3.0499101 -37.2062 34.860699, + -27.4545 37.1008 21.7082, + -28.103901 43.338299 20.8608, + -27.4545 -37.127998 21.7082, + -26.457899 -37.127998 22.828199, + -24.748699 -37.127998 24.748699, + 64.898399 -30.379499 -132.761, + 64.906303 -30.352699 -132.698, + 64.855003 -30.5261 -133.106, + 65.049599 -29.755699 -35.751801, + 65.187302 -29.074301 -36.740898, + 65.0858 -29.4505 -35.563099, + 64.828598 -30.350201 -34.396198, + 64.795097 -30.577499 -34.539501, + 64.938103 -30.266701 -37.9021, + 65.021896 -29.907801 -35.844501, + 64.972198 -30.111099 -162.13901, + 64.911598 -30.334299 -132.642, + 64.803101 -30.690701 -37.9021, + 64.641296 -31.1502 -51.505901, + 64.666901 -31.082001 -133.854, + 64.771004 -30.7878 -55.401699, + 64.771004 -30.7878 -133.521, + 64.891296 -30.431999 -35.647099, + 64.748802 -30.8528 -129.939, + 63.109699 -33.740002 -31.548401, + 62.554001 -34.162399 -30.183901, + 65.070999 29.6766 -36.225201, + 65.231499 28.6672 -36.826199, + 65.169403 29.1651 -37.9021, + 65.049599 29.7285 -35.751801, + 65.021896 29.880501 -35.844501, + 63.206799 33.514999 -31.3953, + 62.554001 34.135201 -30.183901, + 63.292198 33.309101 -31.243799, + 63.109699 33.7127 -31.548401, + 63.7798 32.7794 -32.575298, + 63.7024 32.9478 -32.700001, + 60.916 35.869701 -132.633, + 60.854599 35.911201 -131.056, + 60.803699 35.945 -54.217999, + 63.458698 33.115898 -163.765, + 63.345798 33.422199 -163.077, + 64.246597 31.8347 -163.45, + 64.111504 32.298801 -162.27901, + 63.597599 33.170799 -162.33099, + 63.808399 32.842899 -134.66, + 64.201202 32.140099 -162.269, + 64.494598 31.5149 -134.19901, + 64.181198 32.096802 -162.839, + 64.189102 32.167 -162.271, + 64.431801 31.654499 -134.276, + 61.377102 35.536598 -52.0783, + 61.398201 35.520401 -55.250599, + 61.4823 35.4548 -51.9585, + 61.3424 35.554501 -30.6623, + 61.377102 35.536598 -130.198, + 61.048 35.7785 -30.7848, + 58.9403 36.7351 -26.7162, + 58.378399 36.941002 -25.8946, + 58.6978 36.906502 -26.9188, + 59.243 36.636501 -27.2931, + 58.611198 36.755901 -25.7038, + 58.887699 36.833401 -27.192301, + 58.819099 36.871399 -27.1728, + 60.823399 35.162399 -27.4175, + 59.760601 35.7757 -25.958099, + 59.6991 36.353802 -27.5103, + 59.262402 36.625702 -27.298599, + 59.5742 36.637798 -37.9021, + 59.3936 36.7211 -32.6824, + 59.240799 36.785599 -32.7342, + 60.3255 36.241901 -162.49699, + 60.792702 35.932301 -162.481, + 60.737099 35.988602 -132.036, + 60.718399 36.000801 -131.771, + 60.787498 35.9557 -132.27499, + 60.542198 36.112 -31.7952, + 60.2295 36.2971 -32.1376, + 59.832401 36.510799 -37.9021, + 60.803699 35.945 -132.33701, + 58.630001 36.665199 -164.63699, + 59.734798 36.405102 -163.614, + 59.119099 36.0905 -165.92799, + 57.722 36.5271 -166.077, + 57.444 36.781502 -165.42799, + 57.1464 37.053699 -164.73199, + 61.289398 35.6031 -162.464, + 61.105598 35.737598 -132.978, + 65.1744 28.9988 -162.75301, + 64.8619 30.0959 -163.87601, + 65.166901 29.1425 -162.30701, + 65.198502 28.968901 -162.058, + 64.822998 30.4515 -163.11, + 65.292503 26.420799 -164.787, + 65.292503 25.957399 -165.427, + 65.184303 28.7377 -163.411, + 64.895798 29.676001 -164.636, + 64.4767 30.2759 -166.05299, + 63.737099 32.025398 -165.67101, + 64.407303 30.888201 -165.17, + 64.332397 31.394699 -164.321, + 63.8577 31.3318 -166.634, + 63.607101 32.6059 -164.735, + 63.1516 26.803499 -172.94501, + 63.028599 28.0457 -172.229, + 62.4175 27.2682 -173.63699, + 62.563801 25.917601 -174.293, + 63.262001 25.5112 -173.576, + 63.7887 26.296301 -172.19099, + 63.8671 25.07 -172.797, + 65.237801 21.8601 -169.83, + 65.176903 20.530399 -170.85001, + 65.292503 22.5338 -168.32001, + 65.292503 23.3552 -167.813, + 65.234901 22.8433 -169.37399, + 64.977203 27.914 -166.96899, + 65.213402 26.943501 -166.20399, + 65.227203 24.824499 -168.153, + 65.184402 15.6022 -172.30099, + 65.190399 10.2999 -173.446, + 64.875504 13.2559 -174.30901, + 64.886299 10.5475 -174.82001, + 60.771999 35.9659 -53.203602, + 60.787399 35.955799 -31.4238, + 60.771999 35.9659 -131.323, + 60.739201 35.987301 -53.373001, + 62.021 -34.998299 -133.964, + 62.055401 -34.9944 -31.6367, + 61.1082 -35.75 -30.4718, + 61.048 -35.805698 -30.7848, + 61.844799 -35.1548 -129.724, + 61.3424 -35.581799 -30.6623, + 60.7882 -35.955002 -132.283, + 58.0135 -36.477798 -23.5054, + 64.863403 -30.0795 -163.908, + 64.822998 -30.4512 -163.11, + 64.617699 -31.211599 -162.21201, + 64.111397 -29.084999 -169.03101, + 64.927597 -29.147699 -165.45, + 64.574402 -29.063299 -167.492, + 65.171997 -21.6502 -170.46899, + 65.292503 -14.0082 -171.196, + 65.292503 -16.0618 -170.655, + 65.292503 -17.9531 -170.09599, + 65.292503 -27.1073 -163.549, + 65.292503 -27.5107 -162.38699, + 65.292503 -27.341101 -162.959, + 65.193298 -28.3897 -164.12199, + 65.292503 -21.804001 -168.703, + 65.292503 -21.0592 -169.03799, + 65.292503 -21.6432 -168.78, + 65.236603 -22.2654 -169.653, + 65.292503 -19.614 -169.55901, + 65.237099 -22.089899 -169.731, + 60.2164 -33.918701 -169.21899, + 26.633101 -34.627998 -201.806, + 34.378201 -26.205799 -206.55, + 60.553699 -32.883701 -170.369, + 62.222801 -28.801701 -172.741, + 63.004299 -28.269501 -172.08701, + 63.579601 -28.836 -170.56, + 61.589199 -32.2962 -169.927, + 60.846901 -31.7761 -171.424, + 61.106201 -30.594801 -172.39301, + 59.138302 -36.063702 -165.98, + 64.664101 -27.376301 -169.03999, + 65.029099 -25.6901 -168.918, + 65.292503 -11.8375 -171.69299, + 65.292503 -23.8659 -137.271, + 65.292503 -25.8002 -134.271, + 65.292503 -27.6005 -129.271, + 65.233597 -23.2206 -169.175, + 65.044197 -24.750099 -169.54201, + 65.292503 -24.2507 -167.14999, + 65.226402 -24.975201 -168.03999, + 65.292503 -24.9601 -166.52299, + 65.292503 -22.6745 -168.239, + 65.292503 -23.4909 -167.72, + 65.230202 -24.1245 -168.63699, + 64.971199 -28.0996 -166.76601, + 64.946098 -28.7582 -165.97701, + 65.200798 -27.986601 -164.80901, + 62.675301 -24.752501 -174.77, + 63.683998 -27.6842 -171.368, + 63.131302 -27.0215 -172.828, + 65.057602 -23.760201 -170.10001, + 64.411003 -23.5986 -172.396, + 64.224998 -22.7754 -173.19299, + 64.766602 -24.287001 -171.00301, + 59.068199 -35.420399 -23.962, + 58.147202 -34.452499 -22.048401, + 32.2061 -37.172798 15.0194, + 32.164398 -37.355 14.9901, + 57.919399 -35.529999 -22.207899, + 57.8312 -35.730301 -22.269699, + 32.130798 -37.421902 14.9666, + 28.6257 -37.355 20.0439, + 57.698502 -36.031502 -22.3626, + 58.686298 -34.050499 -22.792101, + 58.734402 -34.029999 -22.860701, + 59.4729 -33.715199 -23.9154, + 60.5005 -33.015999 -25.382999, + 62.735001 -33.670101 -29.834801, + 62.848701 -33.142601 -29.509199, + 62.893398 -32.5928 -29.2145, + 31.9119 -37.6077 14.8134, + 31.8738 -37.618801 14.7867, + 28.3873 -37.6035 19.877001, + 28.3248 -37.621799 19.8333, + 56.0797 -37.484402 -23.496099, + 55.767502 -37.579601 -23.714701, + 31.926001 -37.6035 14.8232, + 59.243 -36.6637 -27.2931, + 58.887699 -36.8606 -27.192301, + 57.813499 -36.722198 -23.659201, + -26.499001 0.00013359217 22.864799, + -26.3389 43.338299 23.049101, + -27.2512 44.338299 21.962999, + -26.499001 -0.027366493 22.864799, + 64.738701 -30.881001 -51.789902, + 64.748802 -30.8528 -51.819599, + 64.686203 -31.0231 -34.8242, + 64.666901 -31.082001 -55.734299, + 63.001301 -33.928799 -31.7024, + 61.1124 35.7327 -52.434399, + 61.072601 35.761101 -37.9021, + 61.1703 35.690899 -37.9021, + 61.105598 35.737598 -54.859299, + 61.1124 35.7327 -130.554, + 61.147301 35.6334 -29.8594, + 61.133499 35.699299 -30.339899, + 61.527599 35.382999 -30.461901, + 61.073299 35.354301 -28.503901, + 61.229401 35.079201 -28.297501, + 60.668701 35.457298 -27.6112, + 59.583698 36.052898 -26.135, + 64.8312 30.6031 -52.178398, + 58.3811 37.1073 -162.541, + 58.263699 36.985001 -163.71899, + 58.306599 37.1357 -162.54201, + 59.3955 36.720299 -162.521, + 58.964699 36.9021 -32.827702, + 64.787201 30.685801 -162.177, + 64.793404 30.658199 -162.58, + 64.781097 30.757799 -133.48, + 64.617699 31.2118 -162.21201, + 65.207497 27.504499 -165.508, + 64.953903 28.5697 -166.215, + 64.927101 29.156401 -165.438, + 65.292503 27.124201 -163.511, + 65.219704 28.8055 -162.04601, + 65.292503 27.3494 -162.936, + 65.192802 28.412901 -164.07899, + 65.200699 27.9937 -164.798, + 65.292503 26.809401 -164.147, + 63.081501 32.304699 -167.16901, + 64.536102 29.5984 -166.899, + 64.587799 28.8536 -167.709, + 63.238899 31.4772 -168.147, + 64.051201 29.747299 -168.41299, + 63.961201 30.573099 -167.547, + 62.732899 30.3764 -170.536, + 63.490398 29.672701 -169.89101, + 62.8904 29.2367 -171.427, + 62.572899 31.3416 -169.67, + 61.864799 31.007 -171.114, + 63.375999 30.580999 -169.07001, + 62.072399 29.8139 -172.049, + 64.199699 27.906799 -169.992, + 64.630699 28.0886 -168.438, + 64.126198 28.9063 -169.188, + 63.602798 28.598 -170.73801, + 63.701302 27.472601 -171.504, + 61.327702 35.254101 -164.28999, + 60.4333 35.464699 -165.714, + 60.034801 36.0606 -164.48801, + 61.094299 35.603699 -163.47, + 62.308201 34.601002 -163.28999, + 62.4781 34.264702 -164.047, + 61.908401 33.985901 -166.536, + 60.786301 34.770199 -166.881, + 61.636299 34.663101 -165.439, + 62.7019 33.7033 -165.11099, + 62.898602 33.064899 -166.13, + 63.884499 24.7736 -172.92799, + 64.3722 24.599199 -171.966, + 65.0466 24.584299 -169.642, + 65.230797 23.9736 -168.733, + 64.771301 24.104401 -171.092, + 64.742104 25.1798 -170.52901, + 64.264 26.8556 -170.72301, + 64.321098 25.752899 -171.382, + 65.015503 26.405701 -168.373, + 64.996498 27.231701 -167.653, + 64.672798 27.1726 -169.2, + 64.709503 26.2029 -169.897, + 65.031998 25.5229 -169.037, + 65.223 25.616699 -167.522, + 65.218201 26.3484 -166.843, + 65.292503 14.0001 -171.185, + 65.292503 15.2242 -170.884, + 65.292503 12.6312 -171.521, + 65.187698 12.9469 -172.92999, + 62.103001 -34.9156 -162.42799, + 61.6031 -35.3578 -133.592, + 62.1796 -34.8508 -162.424, + 58.949501 -35.727001 -24.0772, + 58.192299 -36.209801 -23.3652, + 58.347301 -35.922298 -23.240499, + 58.805698 -36.019699 -24.208599, + 58.638401 -36.2943 -24.354601, + 61.319099 -33.305901 -168.834, + 62.316898 -32.575401 -168.375, + 62.701199 -30.580999 -170.36099, + 62.857899 -29.488899 -171.241, + 63.4678 -29.8654 -169.72501, + 62.523102 -31.6087 -169.409, + 61.8232 -31.2211 -170.92999, + 62.029598 -30.0779 -171.854, + 65.011597 -26.590099 -168.22099, + 65.222 -25.780899 -167.37801, + 64.992699 -27.377701 -167.513, + 65.292503 -26.5487 -164.589, + 65.292503 -26.803801 -164.157, + 65.2118 -27.103399 -166.015, + 65.205498 -27.6632 -165.289, + 63.363098 -24.153099 -174.125, + 63.9389 -23.7787 -173.328, + 63.421398 -23.282499 -174.42101, + 62.697899 -24.499701 -174.86301, + 63.9268 -24.0093 -173.241, + 63.244301 -25.729799 -173.47701, + 63.346001 -24.395399 -174.035, + 64.311699 -25.9468 -171.27299, + 63.7743 -26.502899 -172.078, + 64.252701 -27.0536 -170.59399, + 64.363998 -24.7948 -171.87399, + 64.736702 -25.3601 -170.424, + 63.854599 -25.277599 -172.702, + 64.703102 -26.386 -169.77299, + 64.797897 -22.963499 -171.592, + 64.4189 -23.380699 -172.48, + 64.813202 -22.2269 -171.86501, + 64.793404 -23.167801 -171.509, + 65.071701 -22.531601 -170.672, + 65.069603 -22.721701 -170.592, + 59.3936 -36.748402 -32.6824, + 58.580101 -35.307098 -23.0432, + 32.192402 -37.265301 15.0097, + 32.203999 -37.2062 15.0178, + 28.6653 -37.2062 20.0716, + 28.650299 -37.282501 20.0611, + 32.188999 -37.282501 15.0073, + 58.069401 -34.998798 -22.1029, + 58.733601 -34.3545 -22.883101, + 62.477798 -33.467701 -28.9417, + 56.613201 -37.503399 -24.544901, + 57.538101 -37.2845 -25.230499, + 56.867401 -37.409698 -24.3613, + 57.2883 -37.394402 -25.4174, + 57.118301 -37.284599 -24.1782, + 57.362202 -37.127602 -23.9984, + 57.5952 -36.939602 -23.8244, + 56.2029 -37.4468 -23.4098, + 58.378399 -36.968201 -25.8946, + 57.7826 -37.144402 -25.0441, + 58.018398 -36.973999 -24.8608, + 58.135201 -37.123699 -26.0882, + 62.882401 -34.108101 -31.8566, + 62.310799 -34.608398 -30.547899, + 62.439701 -34.3918 -30.364599, + 61.553699 35.120602 -29.350599, + 60.4925 35.7318 -27.813999, + 64.854202 30.528999 -54.992298, + 64.803101 30.690901 -37.9021, + 64.868797 30.4809 -133.015, + 64.868797 30.4809 -54.895599, + 64.895798 30.3894 -52.623299, + 64.840202 30.5741 -130.34801, + 64.854202 30.528999 -133.11099, + 64.8312 30.6031 -130.298, + 64.840202 30.5741 -52.228802, + 64.847298 18.6966 -172.955, + 64.300102 19.1068 -174.286, + 61.4035 33.013599 -169.168, + 62.3815 32.295399 -168.69099, + 61.654598 32.016899 -170.202, + 61.1171 33.931999 -168.064, + 60.321701 33.619801 -169.571, + 62.162399 33.1768 -167.649, + 60.635502 32.596401 -170.659, + 63.9543 23.4779 -173.437, + 65.062599 23.3491 -170.306, + 65.2341 23.065599 -169.259, + 65.171997 21.6504 -170.46899, + 65.0597 23.5912 -170.187, + 65.074203 22.283001 -170.77299, + 61.062599 -34.549702 -27.0651, + 60.0443 -35.1912 -25.6423, + 61.864899 -34.534401 -28.864401, + 62.3451 -34.030399 -29.289101, + 62.062801 -33.8554 -28.428801, + 59.9146 -35.505402 -25.793301, + 61.364498 -34.813202 -28.0994, + 60.955101 -34.8769 -27.2349, + 64.335701 -31.374599 -164.356, + 64.246597 -31.8344 -163.45, + 64.411697 -30.8535 -165.224, + 63.347099 -33.418701 -163.08501, + 62.899101 -34.091999 -162.383, + 63.458801 -33.115501 -163.765, + 62.4781 -34.2644 -164.047, + 60.8074 -34.7225 -166.95399, + 61.6483 -34.636299 -165.48599, + 60.448898 -35.437401 -165.763, + 59.580799 -35.354301 -167.23599, + 61.121799 -33.9184 -168.08099, + 59.970798 -34.542702 -168.425, + 65.292503 -25.8002 -165.608, + 65.292503 -25.561501 -165.899, + 65.292503 -26.091 -165.25301, + 65.2173 -26.4765 -166.71201, + 58.450001 -37.072102 -27.1276, + 58.6978 -36.9338 -26.9188, + 58.819099 -36.898602 -27.1728, + 59.833401 -36.537498 -32.4473, + 57.631001 -37.346001 -26.474899, + 57.748402 -37.319901 -27.164301, + 58.488499 -37.1035 -32.907001, + 58.656799 -34.988998 -22.971901, + 58.7076 -34.669998 -22.918699, + 60.3064 -33.845699 -25.201099, + 59.288399 -34.142399 -23.6749, + 62.118599 -32.3848 -27.7465, + 59.270401 -34.461201 -23.7206, + 32.040199 -37.532501 14.9032, + 56.655102 -37.2075 -23.093201, + 31.985399 -37.573502 14.8648, + 57.062199 -36.881699 -22.8081, + 32.0891 -37.481602 14.9374, + 28.501499 -37.532501 19.957001, + 62.013199 -34.999401 -30.917999, + 61.847 -35.172401 -31.1026, + 62.317402 -34.7369 -31.5522, + 62.168201 -34.811199 -30.7328, + 61.527599 -35.410198 -30.461901, + 60.823399 -35.189602 -27.4175, + 59.760601 -35.802898 -25.958099, + 61.049599 35.607201 -29.2766, + 61.009499 35.608898 -29.1203, + 64.931297 30.264 -53.049599, + 64.958397 30.164 -37.9021, + 64.899002 30.3783 -130.78, + 64.895798 30.3894 -130.743, + 64.9151 30.322001 -132.601, + 64.899002 30.3783 -52.660999, + 64.9151 30.322001 -54.4818, + 64.934502 30.252399 -131.226, + 64.972198 30.111401 -162.13901, + 64.931297 30.264 -131.16901, + 64.935799 30.2477 -131.26801, + 64.934502 30.252399 -53.107201, + 64.943298 30.220301 -53.9884, + 64.941002 30.228701 -132.173, + 64.943298 30.220301 -132.108, + 64.941002 30.228701 -54.053699, + 64.946899 30.2071 -53.651798, + 64.935799 30.2477 -53.1488, + 64.428902 23.096399 -172.586, + 64.224998 22.7756 -173.19299, + 64.383499 24.319901 -172.093, + 64.777702 23.843201 -171.215, + 64.803596 22.6966 -171.69501, + 64.813202 22.2271 -171.86501, + 64.267998 21.4676 -173.58701, + 64.832703 21.010201 -172.25101, + 61.1329 -35.651901 -29.7409, + 61.147301 -35.660599 -29.8594, + 62.910198 -33.0214 -166.19299, + 63.744801 -31.9858 -165.73, + 63.084099 -32.2924 -167.18401, + 63.6129 -32.582802 -164.77499, + 62.710602 -33.677898 -165.15401, + 62.165901 -33.1637 -167.66499, + 61.924599 -33.939701 -166.604, + 63.930801 -30.8146 -167.269, + 64.5187 -29.8148 -166.64101, + 64.477699 -30.2659 -166.06599, + 63.859402 -31.320601 -166.64799, + 64.027802 -29.979099 -168.181, + 63.340401 -30.8321 -168.82401, + 63.1926 -31.7402 -167.851, + 61.097 -35.599899 -163.479, + 62.310101 -34.597301 -163.298, + 61.289398 -35.602798 -162.464, + 61.327801 -35.2537 -164.28999, + 60.792702 -35.931999 -162.481, + 60.3255 -36.2416 -162.49699, + 60.034901 -36.0602 -164.48801, + 59.738201 -36.401402 -163.62399, + 58.251598 -37.155602 -27.1187, + 58.3876 -37.101398 -27.1199, + 57.884998 -37.2495 -26.2824, + 58.168301 -37.188702 -27.117901, + 58.964699 -36.929401 -32.827702, + 60.148399 -34.863998 -25.5068, + 59.161201 -35.104301 -23.863899, + 59.228401 -34.7831 -23.7834, + 61.073299 -35.3815 -28.503901, + 60.668701 -35.4846 -27.6112, + 61.229401 -35.1064 -28.297501, + 61.1007 35.605 -29.4757, + 59.726002 36.284 -27.2899, + 59.934399 36.0424 -27.0867, + 59.386299 36.306801 -26.321899, + 60.1749 36.044899 -27.8463, + 60.124699 36.077702 -27.8092, + 59.759899 36.315899 -27.539801, + 59.170799 36.534801 -26.516399, + 60.9739 35.618801 -29.025999, + 60.388 35.909199 -28.055599, + 60.995998 35.611698 -29.0797, + 60.745998 35.708599 -28.547501, + 60.682098 35.738602 -28.434799, + 60.6451 35.758301 -28.379299, + 60.857601 35.6562 -28.7444, + 60.8979 35.609001 -28.7166, + 61.202702 -33.865002 -26.769199, + 60.279099 -34.187302 -25.2857, + 62.146599 -33.131901 -28.053699, + 60.2267 -34.528099 -25.3876, + 61.145199 -34.211201 -26.909401, + 60.1749 -36.072201 -27.8463, + 61.1007 -35.632301 -29.4757, + 61.133499 -35.726501 -30.339899, + 59.759899 -36.343102 -27.539801, + 58.9403 -36.762299 -26.7162, + 59.6991 -36.381001 -27.5103, + 59.404099 -36.564701 -27.3673, + 59.262402 -36.652901 -27.298599, + 60.995998 -35.638901 -29.0797, + 61.009499 -35.6362 -29.1203, + 61.553699 -35.1478 -29.350599, + 60.4925 -35.758999 -27.813999, + 60.388 -35.936401 -28.055599, + 60.9739 -35.646 -29.025999, + 59.386299 -36.334 -26.321899, + 59.726002 -36.311199 -27.2899, + 59.934399 -36.069599 -27.0867, + 59.170799 -36.562 -26.516399, + 59.583698 -36.080101 -26.135, + 58.449501 -36.546902 -24.5135, + 58.611198 -36.783199 -25.7038, + 58.241798 -36.7743 -24.6831, + 60.7584 -35.73 -28.569401, + 60.682098 -35.7658 -28.434799, + 60.6451 -35.7855 -28.379299, + 60.857601 -35.683399 -28.7444, + 60.8979 -35.6362 -28.7166 ] + + } + coordIndex [ 19, 392, 273, -1, 365, 368, 86, -1, + 57, 148, 535, -1, 1265, 535, 148, -1, + 484, 8, 112, -1, 281, 57, 158, -1, + 281, 148, 57, -1, 927, 158, 57, -1, + 17, 727, 126, -1, 17, 4, 368, -1, + 745, 147, 727, -1, 6, 273, 32, -1, + 170, 32, 273, -1, 253, 260, 110, -1, + 120, 258, 257, -1, 0, 727, 147, -1, + 0, 147, 126, -1, 0, 126, 727, -1, + 37, 125, 126, -1, 157, 816, 817, -1, + 157, 281, 158, -1, 56, 57, 535, -1, + 201, 204, 32, -1, 201, 32, 202, -1, + 2, 347, 68, -1, 10, 23, 917, -1, + 1, 917, 23, -1, 1, 23, 347, -1, + 1, 347, 2, -1, 1, 68, 917, -1, + 1, 2, 68, -1, 3, 111, 72, -1, + 3, 72, 917, -1, 3, 12, 111, -1, + 3, 917, 12, -1, 919, 917, 72, -1, + 13, 917, 68, -1, 13, 68, 345, -1, + 13, 111, 12, -1, 181, 216, 630, -1, + 14, 86, 368, -1, 5, 368, 4, -1, + 77, 17, 126, -1, 77, 4, 17, -1, + 77, 5, 4, -1, 77, 368, 5, -1, + 16, 727, 17, -1, 16, 695, 727, -1, + 15, 17, 368, -1, 290, 147, 745, -1, + 185, 365, 86, -1, 707, 335, 164, -1, + 20, 392, 19, -1, 20, 22, 392, -1, + 21, 63, 94, -1, 398, 717, 352, -1, + 30, 204, 399, -1, 397, 399, 204, -1, + 89, 6, 90, -1, 89, 92, 273, -1, + 89, 273, 6, -1, 28, 90, 6, -1, + 28, 32, 27, -1, 28, 6, 32, -1, + 62, 318, 61, -1, 62, 25, 30, -1, + 7, 26, 27, -1, 7, 27, 32, -1, + 7, 32, 25, -1, 7, 25, 62, -1, + 7, 62, 26, -1, 98, 96, 196, -1, + 71, 72, 111, -1, 66, 32, 170, -1, + 66, 200, 202, -1, 107, 112, 8, -1, + 107, 8, 484, -1, 249, 253, 110, -1, + 249, 112, 107, -1, 249, 107, 250, -1, + 249, 247, 253, -1, 249, 248, 247, -1, + 222, 145, 211, -1, 303, 558, 175, -1, + 303, 304, 151, -1, 303, 297, 558, -1, + 303, 151, 297, -1, 116, 110, 260, -1, + 116, 109, 110, -1, 116, 115, 108, -1, + 116, 108, 109, -1, 430, 231, 147, -1, + 245, 441, 779, -1, 113, 51, 49, -1, + 243, 120, 257, -1, 122, 114, 240, -1, + 9, 126, 147, -1, 9, 147, 37, -1, + 9, 37, 126, -1, 85, 38, 372, -1, + 36, 39, 38, -1, 36, 267, 39, -1, + 376, 372, 38, -1, 44, 129, 463, -1, + 270, 624, 187, -1, 136, 285, 135, -1, + 142, 740, 506, -1, 454, 422, 452, -1, + 133, 148, 281, -1, 133, 150, 148, -1, + 133, 149, 150, -1, 1105, 149, 133, -1, + 53, 817, 280, -1, 53, 280, 281, -1, + 516, 310, 155, -1, 516, 539, 310, -1, + 55, 993, 607, -1, 55, 324, 993, -1, + 1208, 56, 535, -1, 367, 387, 368, -1, + 350, 717, 200, -1, 69, 347, 345, -1, + 341, 10, 917, -1, 341, 23, 10, -1, + 319, 911, 341, -1, 921, 919, 72, -1, + 918, 917, 919, -1, 11, 12, 917, -1, + 11, 917, 13, -1, 11, 13, 12, -1, + 225, 111, 13, -1, 225, 13, 339, -1, + 73, 339, 13, -1, 73, 13, 345, -1, + 557, 866, 558, -1, 180, 140, 105, -1, + 87, 77, 126, -1, 87, 86, 14, -1, + 87, 368, 76, -1, 87, 14, 368, -1, + 79, 17, 15, -1, 79, 695, 81, -1, + 79, 15, 368, -1, 79, 368, 193, -1, + 82, 695, 16, -1, 82, 79, 81, -1, + 82, 16, 17, -1, 82, 17, 79, -1, + 1072, 290, 745, -1, 84, 185, 86, -1, + 84, 644, 185, -1, 272, 273, 392, -1, + 667, 662, 979, -1, 699, 387, 318, -1, + 18, 19, 273, -1, 18, 20, 19, -1, + 18, 273, 92, -1, 18, 92, 22, -1, + 18, 22, 20, -1, 91, 90, 63, -1, + 91, 63, 21, -1, 91, 22, 92, -1, + 91, 21, 22, -1, 959, 196, 96, -1, + 391, 272, 392, -1, 390, 392, 22, -1, + 95, 21, 94, -1, 95, 22, 21, -1, + 95, 390, 22, -1, 333, 94, 63, -1, + 333, 334, 94, -1, 329, 97, 164, -1, + 353, 398, 352, -1, 353, 347, 23, -1, + 353, 23, 341, -1, 716, 397, 204, -1, + 342, 318, 62, -1, 342, 62, 399, -1, + 24, 204, 30, -1, 24, 30, 25, -1, + 24, 32, 204, -1, 24, 25, 32, -1, + 59, 27, 26, -1, 59, 28, 27, -1, + 59, 90, 28, -1, 59, 26, 62, -1, + 29, 30, 399, -1, 29, 399, 62, -1, + 29, 62, 30, -1, 182, 96, 98, -1, + 182, 98, 183, -1, 199, 197, 64, -1, + 407, 727, 695, -1, 74, 71, 111, -1, + 74, 176, 921, -1, 74, 921, 71, -1, + 99, 452, 422, -1, 99, 422, 211, -1, + 214, 216, 181, -1, 653, 170, 273, -1, + 622, 187, 624, -1, 622, 651, 187, -1, + 622, 652, 651, -1, 31, 202, 32, -1, + 31, 66, 202, -1, 31, 32, 66, -1, + 251, 107, 484, -1, 227, 249, 110, -1, + 227, 226, 112, -1, 227, 112, 249, -1, + 221, 33, 240, -1, 221, 145, 222, -1, + 428, 211, 422, -1, 428, 222, 211, -1, + 218, 175, 217, -1, 218, 303, 175, -1, + 220, 33, 221, -1, 220, 108, 115, -1, + 220, 115, 33, -1, 104, 512, 303, -1, + 104, 46, 512, -1, 104, 105, 140, -1, + 104, 140, 46, -1, 660, 658, 339, -1, + 660, 624, 270, -1, 660, 270, 1312, -1, + 657, 112, 226, -1, 657, 226, 658, -1, + 760, 525, 294, -1, 429, 430, 147, -1, + 475, 441, 245, -1, 475, 435, 441, -1, + 244, 114, 122, -1, 244, 120, 243, -1, + 783, 113, 244, -1, 239, 49, 240, -1, + 239, 113, 49, -1, 242, 453, 51, -1, + 242, 783, 443, -1, 242, 51, 113, -1, + 242, 113, 783, -1, 262, 117, 118, -1, + 123, 122, 240, -1, 123, 120, 244, -1, + 123, 33, 115, -1, 123, 240, 33, -1, + 455, 456, 42, -1, 34, 38, 85, -1, + 34, 36, 38, -1, 34, 85, 36, -1, + 35, 264, 268, -1, 35, 263, 264, -1, + 35, 458, 263, -1, 35, 42, 456, -1, + 35, 456, 458, -1, 41, 268, 267, -1, + 41, 267, 36, -1, 41, 35, 268, -1, + 41, 42, 35, -1, 41, 37, 147, -1, + 41, 36, 37, -1, 127, 37, 36, -1, + 127, 36, 85, -1, 127, 125, 37, -1, + 127, 87, 126, -1, 800, 802, 128, -1, + 375, 376, 128, -1, 266, 128, 376, -1, + 266, 800, 128, -1, 266, 38, 39, -1, + 266, 376, 38, -1, 266, 39, 267, -1, + 132, 131, 474, -1, 233, 44, 231, -1, + 233, 129, 44, -1, 40, 147, 231, -1, + 40, 44, 147, -1, 40, 231, 44, -1, + 45, 464, 469, -1, 45, 42, 41, -1, + 45, 469, 470, -1, 45, 147, 44, -1, + 45, 41, 147, -1, 45, 455, 42, -1, + 45, 470, 455, -1, 43, 463, 464, -1, + 43, 44, 463, -1, 43, 464, 45, -1, + 43, 45, 44, -1, 500, 270, 187, -1, + 500, 379, 796, -1, 1096, 1312, 270, -1, + 1096, 270, 796, -1, 381, 187, 651, -1, + 649, 653, 273, -1, 1106, 136, 1107, -1, + 134, 136, 135, -1, 134, 1107, 136, -1, + 139, 1106, 817, -1, 1286, 180, 1445, -1, + 1286, 1065, 180, -1, 1294, 512, 287, -1, + 517, 740, 309, -1, 517, 510, 740, -1, + 141, 287, 512, -1, 141, 512, 46, -1, + 141, 46, 140, -1, 47, 309, 740, -1, + 47, 142, 309, -1, 47, 740, 142, -1, + 146, 144, 51, -1, 146, 453, 145, -1, + 146, 51, 453, -1, 50, 51, 144, -1, + 48, 240, 49, -1, 48, 50, 144, -1, + 48, 144, 145, -1, 48, 49, 51, -1, + 48, 51, 50, -1, 48, 145, 221, -1, + 48, 221, 240, -1, 526, 147, 290, -1, + 292, 293, 454, -1, 1005, 148, 150, -1, + 52, 157, 817, -1, 52, 817, 53, -1, + 52, 281, 157, -1, 52, 53, 281, -1, + 54, 154, 868, -1, 54, 1159, 154, -1, + 54, 868, 1328, -1, 54, 1328, 1159, -1, + 152, 154, 1159, -1, 152, 297, 151, -1, + 153, 303, 512, -1, 846, 868, 154, -1, + 844, 548, 547, -1, 844, 547, 842, -1, + 891, 1214, 323, -1, 321, 55, 607, -1, + 321, 323, 324, -1, 321, 324, 55, -1, + 926, 57, 161, -1, 926, 927, 57, -1, + 163, 161, 57, -1, 1346, 57, 56, -1, + 1346, 56, 1208, -1, 1346, 163, 57, -1, + 337, 330, 387, -1, 337, 166, 168, -1, + 60, 318, 387, -1, 60, 387, 330, -1, + 60, 61, 318, -1, 58, 90, 59, -1, + 58, 63, 90, -1, 58, 330, 63, -1, + 58, 61, 60, -1, 58, 60, 330, -1, + 58, 62, 61, -1, 58, 59, 62, -1, + 613, 63, 330, -1, 613, 333, 63, -1, + 328, 199, 64, -1, 328, 198, 199, -1, + 328, 98, 196, -1, 328, 366, 98, -1, + 328, 367, 366, -1, 167, 166, 328, -1, + 167, 328, 64, -1, 169, 64, 197, -1, + 169, 197, 617, -1, 169, 167, 64, -1, + 65, 200, 66, -1, 65, 350, 200, -1, + 65, 66, 350, -1, 171, 66, 170, -1, + 171, 350, 66, -1, 67, 68, 347, -1, + 67, 347, 69, -1, 67, 345, 68, -1, + 67, 69, 345, -1, 586, 341, 911, -1, + 586, 318, 342, -1, 586, 587, 318, -1, + 596, 594, 917, -1, 593, 917, 594, -1, + 593, 319, 341, -1, 593, 341, 917, -1, + 920, 176, 1334, -1, 920, 921, 176, -1, + 70, 72, 71, -1, 70, 921, 72, -1, + 70, 71, 921, -1, 172, 339, 73, -1, + 344, 73, 345, -1, 344, 349, 350, -1, + 344, 350, 172, -1, 344, 172, 73, -1, + 356, 176, 74, -1, 356, 74, 111, -1, + 179, 1336, 358, -1, 177, 1334, 176, -1, + 177, 1336, 1334, -1, 177, 358, 1336, -1, + 418, 216, 215, -1, 418, 419, 630, -1, + 418, 630, 216, -1, 75, 87, 76, -1, + 75, 77, 87, -1, 75, 76, 368, -1, + 75, 368, 77, -1, 78, 193, 695, -1, + 78, 695, 79, -1, 78, 79, 193, -1, + 80, 81, 695, -1, 80, 82, 81, -1, + 80, 695, 82, -1, 746, 1072, 745, -1, + 1071, 290, 1072, -1, 1071, 1303, 290, -1, + 638, 707, 164, -1, 638, 164, 97, -1, + 638, 97, 182, -1, 370, 371, 366, -1, + 643, 644, 84, -1, 643, 84, 646, -1, + 83, 646, 84, -1, 83, 372, 646, -1, + 83, 85, 372, -1, 83, 84, 86, -1, + 83, 127, 85, -1, 83, 86, 87, -1, + 83, 87, 127, -1, 656, 1099, 228, -1, + 189, 673, 976, -1, 1441, 676, 1520, -1, + 664, 667, 979, -1, 383, 673, 189, -1, + 1022, 979, 662, -1, 679, 190, 1003, -1, + 690, 695, 688, -1, 194, 685, 192, -1, + 194, 192, 191, -1, 194, 191, 699, -1, + 88, 89, 90, -1, 88, 90, 91, -1, + 88, 92, 89, -1, 88, 91, 92, -1, + 619, 196, 959, -1, 706, 389, 335, -1, + 706, 388, 389, -1, 706, 335, 707, -1, + 395, 648, 649, -1, 395, 272, 391, -1, + 93, 94, 334, -1, 93, 95, 94, -1, + 93, 334, 389, -1, 93, 389, 390, -1, + 93, 390, 95, -1, 957, 959, 96, -1, + 957, 97, 329, -1, 957, 96, 182, -1, + 957, 182, 97, -1, 206, 200, 717, -1, + 1058, 717, 398, -1, 184, 183, 98, -1, + 184, 98, 366, -1, 184, 366, 371, -1, + 736, 737, 985, -1, 750, 411, 406, -1, + 750, 985, 737, -1, 1061, 752, 1062, -1, + 212, 452, 99, -1, 212, 99, 211, -1, + 212, 210, 452, -1, 102, 145, 453, -1, + 102, 453, 101, -1, 100, 101, 453, -1, + 100, 453, 210, -1, 100, 210, 211, -1, + 100, 102, 101, -1, 100, 211, 145, -1, + 100, 145, 102, -1, 451, 452, 210, -1, + 451, 210, 453, -1, 103, 214, 181, -1, + 213, 214, 103, -1, 213, 105, 104, -1, + 213, 104, 303, -1, 213, 103, 181, -1, + 213, 218, 423, -1, 213, 303, 218, -1, + 213, 180, 105, -1, 213, 181, 180, -1, + 106, 250, 107, -1, 106, 251, 250, -1, + 106, 107, 251, -1, 426, 428, 422, -1, + 224, 108, 220, -1, 224, 109, 108, -1, + 224, 110, 109, -1, 224, 227, 110, -1, + 427, 217, 356, -1, 427, 222, 428, -1, + 427, 224, 220, -1, 427, 111, 225, -1, + 427, 356, 111, -1, 230, 484, 112, -1, + 230, 112, 657, -1, 229, 657, 659, -1, + 757, 131, 130, -1, 757, 237, 131, -1, + 759, 532, 438, -1, 759, 760, 294, -1, + 436, 759, 438, -1, 476, 474, 131, -1, + 476, 435, 475, -1, 476, 131, 237, -1, + 782, 783, 244, -1, 440, 779, 441, -1, + 241, 113, 239, -1, 241, 240, 114, -1, + 241, 114, 244, -1, 241, 244, 113, -1, + 450, 242, 443, -1, 472, 132, 474, -1, + 481, 482, 253, -1, 254, 260, 253, -1, + 1092, 260, 254, -1, 1092, 254, 482, -1, + 1092, 257, 262, -1, 1092, 262, 118, -1, + 256, 262, 257, -1, 256, 258, 123, -1, + 256, 260, 262, -1, 256, 123, 115, -1, + 256, 116, 260, -1, 256, 115, 116, -1, + 261, 117, 262, -1, 261, 118, 117, -1, + 261, 1092, 118, -1, 119, 258, 120, -1, + 119, 123, 258, -1, 119, 120, 123, -1, + 121, 244, 122, -1, 121, 122, 123, -1, + 121, 123, 244, -1, 791, 268, 264, -1, + 124, 126, 125, -1, 124, 127, 126, -1, + 124, 125, 127, -1, 1046, 378, 710, -1, + 1046, 497, 378, -1, 491, 128, 802, -1, + 491, 375, 128, -1, 232, 129, 233, -1, + 232, 757, 130, -1, 232, 463, 129, -1, + 232, 465, 463, -1, 468, 130, 131, -1, + 468, 131, 132, -1, 468, 232, 130, -1, + 468, 465, 232, -1, 468, 132, 472, -1, + 186, 187, 381, -1, 275, 649, 273, -1, + 275, 272, 395, -1, 1113, 673, 1231, -1, + 1113, 1316, 673, -1, 502, 1107, 134, -1, + 502, 134, 1316, -1, 279, 1106, 1105, -1, + 279, 133, 281, -1, 279, 1105, 133, -1, + 282, 134, 135, -1, 282, 135, 742, -1, + 283, 282, 503, -1, 283, 134, 282, -1, + 283, 673, 1316, -1, 283, 1316, 134, -1, + 741, 135, 285, -1, 741, 742, 135, -1, + 519, 507, 818, -1, 137, 285, 136, -1, + 137, 136, 1106, -1, 137, 1106, 139, -1, + 284, 285, 137, -1, 284, 137, 139, -1, + 138, 818, 507, -1, 138, 817, 818, -1, + 138, 139, 817, -1, 138, 507, 284, -1, + 138, 284, 139, -1, 1295, 512, 1294, -1, + 1064, 1294, 1065, -1, 288, 180, 1065, -1, + 288, 1065, 1294, -1, 288, 140, 180, -1, + 288, 141, 140, -1, 288, 287, 141, -1, + 814, 507, 519, -1, 814, 142, 506, -1, + 814, 309, 142, -1, 143, 145, 144, -1, + 143, 146, 145, -1, 143, 144, 146, -1, + 235, 147, 526, -1, 235, 234, 432, -1, + 235, 429, 147, -1, 235, 432, 429, -1, + 521, 528, 522, -1, 421, 422, 454, -1, + 421, 454, 293, -1, 420, 292, 630, -1, + 420, 421, 293, -1, 629, 630, 292, -1, + 629, 292, 454, -1, 680, 1265, 148, -1, + 680, 148, 1005, -1, 1104, 150, 149, -1, + 1104, 149, 1105, -1, 678, 1005, 150, -1, + 678, 150, 1104, -1, 678, 1104, 295, -1, + 296, 678, 295, -1, 299, 151, 304, -1, + 299, 152, 151, -1, 299, 300, 154, -1, + 299, 154, 152, -1, 1160, 152, 1159, -1, + 1160, 297, 152, -1, 305, 303, 306, -1, + 307, 306, 303, -1, 307, 303, 153, -1, + 307, 153, 831, -1, 537, 831, 153, -1, + 537, 153, 512, -1, 301, 154, 300, -1, + 301, 846, 154, -1, 515, 516, 155, -1, + 515, 155, 846, -1, 515, 846, 301, -1, + 515, 301, 513, -1, 518, 517, 309, -1, + 156, 155, 310, -1, 156, 310, 542, -1, + 543, 1130, 1128, -1, 543, 156, 542, -1, + 543, 1128, 156, -1, 845, 846, 155, -1, + 845, 155, 156, -1, 845, 156, 1128, -1, + 159, 857, 313, -1, 861, 556, 941, -1, + 875, 835, 872, -1, 568, 157, 158, -1, + 568, 158, 315, -1, 568, 816, 157, -1, + 314, 158, 838, -1, 314, 315, 158, -1, + 1122, 838, 158, -1, 1122, 158, 927, -1, + 317, 552, 857, -1, 317, 857, 159, -1, + 317, 313, 548, -1, 317, 159, 313, -1, + 553, 548, 844, -1, 553, 317, 548, -1, + 883, 553, 844, -1, 580, 598, 893, -1, + 580, 579, 598, -1, 590, 1483, 601, -1, + 590, 916, 1483, -1, 590, 601, 911, -1, + 590, 911, 319, -1, 312, 313, 857, -1, + 562, 576, 1340, -1, 605, 321, 607, -1, + 160, 926, 161, -1, 160, 161, 163, -1, + 160, 163, 926, -1, 162, 926, 163, -1, + 162, 1346, 926, -1, 162, 163, 1346, -1, + 326, 337, 387, -1, 326, 166, 337, -1, + 326, 328, 166, -1, 326, 327, 328, -1, + 616, 330, 337, -1, 332, 614, 329, -1, + 332, 613, 614, -1, 332, 164, 335, -1, + 332, 329, 164, -1, 165, 168, 166, -1, + 165, 166, 167, -1, 165, 167, 168, -1, + 338, 168, 167, -1, 338, 167, 169, -1, + 338, 337, 168, -1, 338, 169, 617, -1, + 338, 617, 616, -1, 173, 170, 653, -1, + 173, 171, 170, -1, 621, 350, 171, -1, + 621, 339, 172, -1, 621, 172, 350, -1, + 621, 171, 173, -1, 621, 652, 622, -1, + 621, 653, 652, -1, 621, 173, 653, -1, + 589, 917, 916, -1, 589, 596, 917, -1, + 589, 916, 590, -1, 595, 594, 596, -1, + 346, 345, 347, -1, 351, 349, 344, -1, + 351, 347, 353, -1, 865, 866, 557, -1, + 174, 217, 175, -1, 174, 356, 217, -1, + 355, 174, 175, -1, 355, 356, 174, -1, + 355, 175, 558, -1, 355, 558, 866, -1, + 357, 176, 356, -1, 357, 177, 176, -1, + 357, 358, 177, -1, 178, 864, 1336, -1, + 178, 1336, 179, -1, 178, 358, 864, -1, + 178, 179, 358, -1, 632, 1445, 180, -1, + 632, 180, 181, -1, 632, 181, 630, -1, + 1073, 1301, 1303, -1, 1073, 1303, 1071, -1, + 637, 182, 183, -1, 637, 638, 182, -1, + 637, 183, 184, -1, 637, 184, 371, -1, + 645, 185, 644, -1, 645, 370, 366, -1, + 645, 365, 185, -1, 377, 186, 381, -1, + 377, 187, 186, -1, 377, 500, 187, -1, + 377, 379, 500, -1, 393, 377, 381, -1, + 393, 1053, 377, -1, 705, 704, 492, -1, + 487, 796, 379, -1, 188, 228, 659, -1, + 188, 656, 228, -1, 188, 659, 656, -1, + 666, 662, 667, -1, 1538, 1222, 970, -1, + 1538, 970, 668, -1, 671, 1231, 673, -1, + 975, 383, 189, -1, 975, 189, 976, -1, + 1592, 1062, 752, -1, 1229, 1110, 1230, -1, + 1229, 296, 1110, -1, 277, 1230, 1110, -1, + 277, 1231, 1230, -1, 384, 993, 1003, -1, + 384, 1003, 190, -1, 384, 190, 679, -1, + 700, 192, 1413, -1, 700, 191, 192, -1, + 700, 1413, 1258, -1, 700, 699, 191, -1, + 1253, 192, 685, -1, 1253, 1413, 192, -1, + 1250, 690, 1251, -1, 1250, 695, 690, -1, + 1250, 400, 1259, -1, 386, 385, 695, -1, + 386, 695, 193, -1, 386, 368, 387, -1, + 386, 193, 368, -1, 694, 688, 695, -1, + 694, 387, 699, -1, 701, 194, 699, -1, + 701, 1026, 685, -1, 701, 685, 194, -1, + 195, 196, 619, -1, 195, 619, 198, -1, + 195, 328, 196, -1, 195, 198, 328, -1, + 618, 617, 197, -1, 618, 198, 619, -1, + 618, 197, 199, -1, 618, 199, 198, -1, + 1043, 388, 706, -1, 205, 200, 206, -1, + 205, 204, 201, -1, 205, 202, 200, -1, + 205, 201, 202, -1, 203, 716, 204, -1, + 203, 206, 716, -1, 203, 204, 205, -1, + 203, 205, 206, -1, 715, 716, 206, -1, + 715, 206, 717, -1, 1056, 399, 397, -1, + 207, 1259, 677, -1, 207, 402, 695, -1, + 207, 677, 402, -1, 207, 695, 1250, -1, + 207, 1250, 1259, -1, 401, 403, 695, -1, + 401, 695, 402, -1, 405, 695, 406, -1, + 405, 410, 695, -1, 409, 726, 727, -1, + 408, 723, 726, -1, 725, 745, 727, -1, + 725, 720, 745, -1, 725, 730, 720, -1, + 725, 724, 730, -1, 743, 733, 406, -1, + 743, 406, 411, -1, 1523, 985, 1599, -1, + 208, 750, 406, -1, 208, 403, 750, -1, + 208, 406, 695, -1, 208, 695, 403, -1, + 404, 985, 750, -1, 412, 411, 750, -1, + 415, 752, 1061, -1, 415, 1519, 752, -1, + 415, 1224, 1519, -1, 415, 971, 1224, -1, + 209, 211, 210, -1, 209, 212, 211, -1, + 209, 210, 212, -1, 417, 214, 213, -1, + 417, 418, 215, -1, 417, 215, 216, -1, + 417, 216, 214, -1, 417, 213, 423, -1, + 425, 217, 427, -1, 425, 426, 423, -1, + 425, 423, 218, -1, 425, 218, 217, -1, + 219, 220, 221, -1, 219, 427, 220, -1, + 219, 221, 222, -1, 219, 222, 427, -1, + 223, 224, 427, -1, 223, 225, 339, -1, + 223, 427, 225, -1, 223, 339, 658, -1, + 223, 658, 226, -1, 223, 226, 227, -1, + 223, 227, 224, -1, 788, 659, 228, -1, + 788, 229, 659, -1, 788, 228, 1099, -1, + 788, 484, 230, -1, 788, 230, 657, -1, + 788, 657, 229, -1, 431, 231, 430, -1, + 431, 757, 232, -1, 431, 233, 231, -1, + 431, 232, 233, -1, 761, 432, 234, -1, + 761, 525, 760, -1, 761, 526, 525, -1, + 761, 234, 235, -1, 761, 235, 526, -1, + 236, 759, 294, -1, 236, 532, 759, -1, + 236, 294, 531, -1, 236, 531, 532, -1, + 434, 476, 237, -1, 434, 435, 476, -1, + 756, 237, 757, -1, 756, 759, 436, -1, + 756, 434, 237, -1, 756, 436, 434, -1, + 781, 443, 783, -1, 781, 440, 443, -1, + 781, 779, 440, -1, 238, 239, 240, -1, + 238, 240, 241, -1, 238, 241, 239, -1, + 449, 453, 242, -1, 449, 242, 450, -1, + 446, 442, 437, -1, 534, 447, 446, -1, + 534, 446, 437, -1, 534, 438, 532, -1, + 534, 437, 438, -1, 1088, 455, 470, -1, + 485, 459, 484, -1, 486, 1081, 764, -1, + 486, 459, 485, -1, 775, 765, 776, -1, + 775, 764, 765, -1, 1094, 257, 1092, -1, + 1094, 243, 257, -1, 1094, 244, 243, -1, + 1094, 782, 244, -1, 478, 778, 776, -1, + 478, 475, 245, -1, 478, 245, 779, -1, + 478, 779, 778, -1, 467, 468, 472, -1, + 246, 253, 247, -1, 246, 247, 481, -1, + 246, 481, 253, -1, 483, 481, 247, -1, + 483, 247, 248, -1, 483, 248, 249, -1, + 483, 249, 250, -1, 483, 250, 251, -1, + 483, 251, 484, -1, 483, 484, 459, -1, + 252, 253, 482, -1, 252, 254, 253, -1, + 252, 482, 254, -1, 255, 256, 257, -1, + 255, 257, 258, -1, 255, 258, 256, -1, + 259, 260, 1092, -1, 259, 1092, 261, -1, + 259, 262, 260, -1, 259, 261, 262, -1, + 457, 263, 458, -1, 457, 792, 791, -1, + 457, 264, 263, -1, 457, 791, 264, -1, + 772, 771, 795, -1, 265, 791, 800, -1, + 265, 266, 267, -1, 265, 800, 266, -1, + 265, 267, 268, -1, 265, 268, 791, -1, + 789, 378, 497, -1, 789, 497, 495, -1, + 789, 487, 378, -1, 1047, 497, 1046, -1, + 1047, 709, 490, -1, 1047, 1045, 709, -1, + 803, 488, 490, -1, 803, 491, 802, -1, + 494, 488, 803, -1, 494, 794, 1083, -1, + 501, 500, 796, -1, 501, 796, 499, -1, + 269, 270, 500, -1, 269, 500, 499, -1, + 269, 796, 270, -1, 269, 499, 796, -1, + 271, 273, 272, -1, 271, 275, 273, -1, + 271, 272, 275, -1, 274, 395, 649, -1, + 274, 649, 275, -1, 274, 275, 395, -1, + 276, 1110, 804, -1, 276, 804, 1231, -1, + 276, 277, 1110, -1, 276, 1231, 277, -1, + 278, 817, 1106, -1, 278, 1106, 279, -1, + 278, 280, 817, -1, 278, 281, 280, -1, + 278, 279, 281, -1, 810, 503, 282, -1, + 810, 282, 742, -1, 382, 283, 503, -1, + 382, 976, 673, -1, 382, 673, 283, -1, + 505, 1299, 741, -1, 505, 284, 507, -1, + 505, 741, 285, -1, 505, 285, 284, -1, + 511, 512, 1295, -1, 511, 1296, 510, -1, + 511, 1295, 1296, -1, 827, 515, 513, -1, + 286, 1294, 287, -1, 286, 287, 288, -1, + 286, 288, 1294, -1, 524, 526, 290, -1, + 524, 290, 521, -1, 289, 521, 290, -1, + 289, 528, 521, -1, 289, 290, 1303, -1, + 289, 1303, 528, -1, 291, 293, 292, -1, + 291, 420, 293, -1, 291, 292, 420, -1, + 523, 522, 531, -1, 523, 294, 525, -1, + 523, 531, 294, -1, 821, 531, 522, -1, + 821, 522, 528, -1, 533, 529, 362, -1, + 533, 362, 447, -1, 533, 447, 534, -1, + 1263, 1208, 535, -1, 806, 295, 1104, -1, + 806, 1110, 296, -1, 806, 296, 295, -1, + 536, 678, 296, -1, 536, 1229, 981, -1, + 536, 296, 1229, -1, 559, 297, 1160, -1, + 559, 558, 297, -1, 298, 829, 513, -1, + 298, 299, 304, -1, 298, 300, 299, -1, + 298, 304, 305, -1, 298, 305, 829, -1, + 298, 301, 300, -1, 298, 513, 301, -1, + 302, 304, 303, -1, 302, 305, 304, -1, + 302, 303, 305, -1, 830, 305, 306, -1, + 830, 307, 831, -1, 830, 306, 307, -1, + 830, 829, 305, -1, 538, 537, 510, -1, + 538, 517, 827, -1, 538, 510, 517, -1, + 308, 570, 540, -1, 308, 540, 518, -1, + 308, 816, 570, -1, 308, 813, 816, -1, + 308, 814, 813, -1, 308, 518, 309, -1, + 308, 309, 814, -1, 541, 310, 539, -1, + 541, 542, 310, -1, 836, 543, 542, -1, + 551, 938, 550, -1, 545, 943, 941, -1, + 545, 939, 943, -1, 545, 938, 939, -1, + 545, 941, 556, -1, 545, 556, 550, -1, + 549, 548, 313, -1, 549, 550, 556, -1, + 848, 549, 313, -1, 848, 311, 849, -1, + 944, 936, 938, -1, 944, 551, 849, -1, + 944, 938, 551, -1, 944, 849, 311, -1, + 944, 312, 857, -1, 944, 311, 848, -1, + 944, 313, 312, -1, 944, 848, 313, -1, + 1326, 861, 1149, -1, 863, 960, 864, -1, + 1140, 573, 858, -1, 575, 833, 1469, -1, + 575, 1469, 577, -1, 837, 314, 838, -1, + 837, 315, 314, -1, 837, 568, 315, -1, + 316, 552, 317, -1, 316, 553, 552, -1, + 316, 317, 553, -1, 572, 883, 873, -1, + 572, 573, 883, -1, 882, 553, 883, -1, + 882, 885, 554, -1, 1339, 1469, 1475, -1, + 894, 579, 580, -1, 888, 598, 579, -1, + 888, 1013, 598, -1, 888, 889, 1013, -1, + 898, 1012, 1019, -1, 899, 1000, 997, -1, + 1011, 905, 1013, -1, 1011, 1012, 898, -1, + 906, 318, 587, -1, 906, 699, 318, -1, + 592, 590, 319, -1, 592, 319, 593, -1, + 933, 1483, 916, -1, 933, 916, 934, -1, + 1178, 916, 917, -1, 1352, 1342, 1210, -1, + 320, 833, 1340, -1, 320, 1340, 1142, -1, + 320, 834, 833, -1, 320, 835, 834, -1, + 320, 872, 835, -1, 320, 1142, 872, -1, + 599, 900, 928, -1, 599, 901, 900, -1, + 599, 903, 901, -1, 1201, 900, 1200, -1, + 1201, 928, 900, -1, 1485, 601, 1483, -1, + 945, 932, 601, -1, 945, 1360, 932, -1, + 945, 601, 1485, -1, 912, 601, 932, -1, + 912, 932, 913, -1, 908, 1200, 900, -1, + 322, 890, 891, -1, 322, 321, 605, -1, + 322, 891, 323, -1, 322, 323, 321, -1, + 582, 605, 1009, -1, 582, 1009, 1008, -1, + 582, 890, 322, -1, 582, 322, 605, -1, + 948, 1208, 611, -1, 609, 1214, 1396, -1, + 609, 323, 1214, -1, 609, 324, 323, -1, + 609, 993, 324, -1, 1186, 1185, 1123, -1, + 925, 1559, 1561, -1, 925, 1561, 1546, -1, + 1349, 1346, 1208, -1, 1349, 1208, 1189, -1, + 950, 1189, 1208, -1, 1205, 948, 611, -1, + 325, 326, 387, -1, 325, 327, 326, -1, + 325, 387, 367, -1, 325, 328, 327, -1, + 325, 367, 328, -1, 956, 329, 614, -1, + 956, 957, 329, -1, 615, 613, 330, -1, + 615, 330, 616, -1, 331, 613, 332, -1, + 331, 334, 333, -1, 331, 333, 613, -1, + 331, 332, 335, -1, 331, 335, 389, -1, + 331, 389, 334, -1, 336, 616, 337, -1, + 336, 337, 338, -1, 336, 338, 616, -1, + 623, 339, 621, -1, 623, 624, 660, -1, + 623, 660, 339, -1, 340, 341, 586, -1, + 340, 586, 342, -1, 340, 353, 341, -1, + 340, 398, 353, -1, 340, 399, 398, -1, + 340, 342, 399, -1, 343, 344, 345, -1, + 343, 345, 346, -1, 343, 351, 344, -1, + 343, 346, 347, -1, 343, 347, 351, -1, + 348, 350, 349, -1, 348, 349, 351, -1, + 348, 717, 350, -1, 348, 352, 717, -1, + 348, 353, 352, -1, 348, 351, 353, -1, + 867, 359, 866, -1, 1165, 1336, 864, -1, + 1165, 864, 1164, -1, 625, 864, 960, -1, + 625, 1164, 864, -1, 354, 356, 355, -1, + 354, 358, 357, -1, 354, 357, 356, -1, + 354, 864, 358, -1, 354, 867, 864, -1, + 354, 359, 867, -1, 354, 866, 359, -1, + 354, 355, 866, -1, 1446, 635, 1291, -1, + 1446, 1445, 632, -1, 1446, 632, 635, -1, + 1063, 530, 363, -1, 1063, 363, 1534, -1, + 360, 1291, 635, -1, 360, 530, 1063, -1, + 360, 1063, 1291, -1, 1302, 528, 1303, -1, + 1302, 1077, 528, -1, 361, 362, 529, -1, + 361, 529, 530, -1, 361, 530, 360, -1, + 361, 635, 634, -1, 361, 360, 635, -1, + 626, 362, 361, -1, 626, 361, 634, -1, + 626, 447, 362, -1, 631, 629, 454, -1, + 824, 363, 530, -1, 1535, 1534, 363, -1, + 1535, 363, 824, -1, 1535, 824, 823, -1, + 703, 371, 369, -1, 703, 637, 371, -1, + 703, 369, 704, -1, 364, 365, 645, -1, + 364, 645, 366, -1, 364, 366, 367, -1, + 364, 368, 365, -1, 364, 367, 368, -1, + 642, 704, 369, -1, 642, 641, 704, -1, + 642, 370, 645, -1, 642, 371, 370, -1, + 642, 369, 371, -1, 374, 372, 376, -1, + 374, 641, 640, -1, 374, 646, 372, -1, + 374, 640, 646, -1, 373, 492, 704, -1, + 373, 704, 641, -1, 373, 641, 374, -1, + 373, 375, 491, -1, 373, 491, 492, -1, + 373, 376, 375, -1, 373, 374, 376, -1, + 1052, 377, 1053, -1, 1052, 710, 378, -1, + 1052, 378, 487, -1, 1052, 379, 377, -1, + 1052, 487, 379, -1, 380, 381, 651, -1, + 380, 651, 393, -1, 380, 393, 381, -1, + 650, 394, 651, -1, 655, 1311, 1099, -1, + 968, 662, 666, -1, 1226, 1224, 971, -1, + 663, 382, 503, -1, 663, 976, 382, -1, + 1318, 667, 664, -1, 670, 671, 673, -1, + 672, 383, 1231, -1, 672, 1231, 671, -1, + 672, 673, 383, -1, 978, 979, 1022, -1, + 674, 1231, 383, -1, 674, 383, 975, -1, + 606, 384, 679, -1, 606, 679, 682, -1, + 606, 607, 993, -1, 606, 993, 384, -1, + 996, 1018, 992, -1, 584, 686, 585, -1, + 584, 997, 998, -1, 584, 990, 686, -1, + 584, 998, 990, -1, 1020, 1019, 1012, -1, + 1257, 1021, 700, -1, 1257, 700, 1258, -1, + 1233, 1275, 1276, -1, 1029, 585, 686, -1, + 1029, 1040, 585, -1, 692, 688, 694, -1, + 696, 695, 385, -1, 696, 385, 386, -1, + 696, 386, 387, -1, 696, 387, 694, -1, + 698, 1021, 1251, -1, 1037, 906, 905, -1, + 1037, 1011, 1040, -1, 1037, 905, 1011, -1, + 1037, 701, 699, -1, 1037, 699, 906, -1, + 711, 388, 1043, -1, 711, 389, 388, -1, + 711, 390, 389, -1, 711, 395, 391, -1, + 711, 391, 392, -1, 711, 392, 390, -1, + 1042, 1043, 706, -1, 1050, 647, 965, -1, + 1050, 1053, 393, -1, 1050, 393, 651, -1, + 1050, 651, 394, -1, 1050, 650, 647, -1, + 1050, 394, 650, -1, 712, 648, 395, -1, + 712, 964, 648, -1, 712, 395, 711, -1, + 712, 965, 964, -1, 712, 1050, 965, -1, + 396, 718, 399, -1, 396, 399, 1056, -1, + 396, 1056, 718, -1, 714, 397, 716, -1, + 714, 1056, 397, -1, 1055, 717, 1058, -1, + 719, 1058, 398, -1, 719, 398, 399, -1, + 719, 399, 718, -1, 1510, 1259, 400, -1, + 1510, 400, 1250, -1, 1510, 1250, 1512, -1, + 984, 401, 402, -1, 984, 402, 677, -1, + 984, 403, 401, -1, 984, 677, 1594, -1, + 984, 985, 404, -1, 984, 750, 403, -1, + 984, 404, 750, -1, 731, 410, 405, -1, + 731, 405, 406, -1, 731, 406, 733, -1, + 731, 1068, 745, -1, 731, 733, 1068, -1, + 722, 407, 695, -1, 722, 695, 730, -1, + 722, 723, 408, -1, 722, 730, 724, -1, + 722, 408, 726, -1, 722, 726, 409, -1, + 722, 727, 407, -1, 722, 409, 727, -1, + 729, 695, 410, -1, 729, 730, 695, -1, + 729, 410, 731, -1, 734, 749, 750, -1, + 735, 736, 985, -1, 735, 985, 1523, -1, + 973, 972, 971, -1, 1297, 810, 742, -1, + 1293, 1294, 1064, -1, 744, 412, 413, -1, + 744, 411, 412, -1, 744, 743, 411, -1, + 414, 413, 412, -1, 414, 412, 750, -1, + 414, 744, 413, -1, 414, 1074, 744, -1, + 748, 414, 750, -1, 748, 1074, 414, -1, + 1076, 1228, 1402, -1, 1307, 1224, 1634, -1, + 738, 415, 1061, -1, 738, 971, 415, -1, + 738, 973, 971, -1, 416, 418, 417, -1, + 416, 419, 418, -1, 416, 630, 419, -1, + 416, 420, 630, -1, 416, 422, 421, -1, + 416, 421, 420, -1, 416, 426, 422, -1, + 416, 423, 426, -1, 416, 417, 423, -1, + 424, 426, 425, -1, 424, 425, 427, -1, + 424, 428, 426, -1, 424, 427, 428, -1, + 758, 430, 429, -1, 758, 431, 430, -1, + 758, 757, 431, -1, 758, 429, 432, -1, + 758, 432, 761, -1, 433, 435, 434, -1, + 433, 434, 436, -1, 433, 441, 435, -1, + 433, 442, 441, -1, 433, 437, 442, -1, + 433, 436, 438, -1, 433, 438, 437, -1, + 439, 440, 441, -1, 439, 441, 442, -1, + 439, 443, 440, -1, 439, 450, 443, -1, + 439, 445, 450, -1, 439, 446, 445, -1, + 439, 442, 446, -1, 444, 450, 445, -1, + 444, 627, 450, -1, 444, 446, 447, -1, + 444, 445, 446, -1, 444, 447, 626, -1, + 444, 626, 627, -1, 448, 449, 450, -1, + 448, 450, 627, -1, 448, 452, 451, -1, + 448, 627, 631, -1, 448, 451, 453, -1, + 448, 453, 449, -1, 448, 454, 452, -1, + 448, 631, 454, -1, 768, 763, 771, -1, + 770, 1087, 461, -1, 770, 461, 472, -1, + 773, 456, 455, -1, 773, 455, 1088, -1, + 773, 792, 457, -1, 773, 458, 456, -1, + 773, 457, 458, -1, 460, 486, 764, -1, + 460, 459, 486, -1, 460, 764, 775, -1, + 1091, 483, 459, -1, 1091, 1092, 482, -1, + 1091, 459, 460, -1, 1091, 460, 775, -1, + 466, 1088, 470, -1, 1089, 472, 461, -1, + 1089, 467, 472, -1, 1089, 466, 467, -1, + 1089, 461, 1087, -1, 1089, 1088, 466, -1, + 462, 464, 463, -1, 462, 463, 465, -1, + 462, 467, 466, -1, 462, 465, 468, -1, + 462, 468, 467, -1, 462, 469, 464, -1, + 462, 470, 469, -1, 462, 466, 470, -1, + 471, 472, 474, -1, 471, 474, 479, -1, + 471, 770, 472, -1, 471, 479, 769, -1, + 471, 769, 770, -1, 473, 479, 474, -1, + 473, 478, 479, -1, 473, 475, 478, -1, + 473, 474, 476, -1, 473, 476, 475, -1, + 477, 478, 776, -1, 477, 479, 478, -1, + 477, 776, 765, -1, 477, 765, 766, -1, + 477, 769, 479, -1, 477, 766, 769, -1, + 480, 482, 481, -1, 480, 481, 483, -1, + 480, 1091, 482, -1, 480, 483, 1091, -1, + 1084, 789, 495, -1, 1084, 786, 789, -1, + 785, 1084, 1082, -1, 785, 786, 1084, -1, + 785, 1082, 1081, -1, 785, 1081, 486, -1, + 787, 484, 788, -1, 787, 485, 484, -1, + 787, 486, 485, -1, 787, 785, 486, -1, + 799, 792, 772, -1, 799, 772, 795, -1, + 797, 796, 487, -1, 797, 487, 789, -1, + 496, 490, 488, -1, 496, 1047, 490, -1, + 496, 497, 1047, -1, 496, 488, 494, -1, + 489, 803, 490, -1, 489, 491, 803, -1, + 489, 490, 709, -1, 489, 709, 705, -1, + 489, 492, 491, -1, 489, 705, 492, -1, + 801, 494, 803, -1, 801, 794, 494, -1, + 493, 494, 1083, -1, 493, 1083, 1084, -1, + 493, 1084, 495, -1, 493, 496, 494, -1, + 493, 495, 497, -1, 493, 497, 496, -1, + 498, 499, 500, -1, 498, 500, 501, -1, + 498, 501, 499, -1, 1117, 502, 1316, -1, + 1117, 1107, 502, -1, 1116, 1231, 804, -1, + 1116, 804, 1117, -1, 811, 503, 810, -1, + 811, 663, 503, -1, 811, 808, 663, -1, + 504, 1066, 1299, -1, 504, 1299, 505, -1, + 504, 814, 506, -1, 504, 507, 814, -1, + 504, 505, 507, -1, 504, 506, 740, -1, + 504, 740, 1066, -1, 508, 1296, 739, -1, + 508, 510, 1296, -1, 508, 739, 740, -1, + 508, 740, 510, -1, 509, 510, 537, -1, + 509, 511, 510, -1, 509, 537, 512, -1, + 509, 512, 511, -1, 828, 513, 829, -1, + 828, 827, 513, -1, 514, 516, 515, -1, + 514, 515, 827, -1, 514, 827, 517, -1, + 514, 539, 516, -1, 514, 540, 539, -1, + 514, 517, 518, -1, 514, 518, 540, -1, + 815, 814, 519, -1, 815, 519, 818, -1, + 520, 521, 522, -1, 520, 522, 523, -1, + 520, 524, 521, -1, 520, 523, 525, -1, + 520, 526, 524, -1, 520, 525, 526, -1, + 527, 821, 528, -1, 527, 823, 821, -1, + 527, 528, 1077, -1, 527, 1077, 1535, -1, + 527, 1535, 823, -1, 822, 529, 533, -1, + 822, 530, 529, -1, 822, 824, 530, -1, + 820, 531, 821, -1, 820, 532, 531, -1, + 820, 822, 533, -1, 820, 534, 532, -1, + 820, 533, 534, -1, 1264, 535, 1265, -1, + 1264, 1263, 535, -1, 805, 806, 1104, -1, + 1242, 678, 536, -1, 1242, 1233, 1276, -1, + 1242, 536, 981, -1, 1242, 981, 1233, -1, + 826, 831, 537, -1, 826, 537, 538, -1, + 826, 538, 827, -1, 566, 541, 539, -1, + 566, 539, 540, -1, 566, 540, 570, -1, + 566, 565, 541, -1, 832, 1546, 1469, -1, + 832, 1469, 833, -1, 1125, 1546, 832, -1, + 1125, 832, 564, -1, 563, 542, 541, -1, + 563, 836, 542, -1, 563, 541, 565, -1, + 563, 564, 832, -1, 563, 832, 836, -1, + 841, 1130, 543, -1, 841, 543, 836, -1, + 869, 870, 547, -1, 1129, 547, 870, -1, + 1129, 842, 547, -1, 1129, 1131, 842, -1, + 544, 550, 938, -1, 544, 545, 550, -1, + 544, 938, 545, -1, 546, 547, 548, -1, + 546, 548, 549, -1, 546, 869, 547, -1, + 546, 871, 869, -1, 546, 556, 871, -1, + 546, 549, 556, -1, 850, 550, 549, -1, + 850, 549, 848, -1, 850, 551, 550, -1, + 850, 849, 551, -1, 854, 853, 924, -1, + 854, 1133, 855, -1, 1325, 1326, 1149, -1, + 1218, 1170, 1219, -1, 1151, 1182, 924, -1, + 1151, 924, 853, -1, 1151, 853, 852, -1, + 1151, 1149, 1321, -1, 1151, 1325, 1149, -1, + 1151, 1162, 1325, -1, 1151, 852, 1218, -1, + 1139, 857, 552, -1, 1139, 552, 553, -1, + 1139, 554, 885, -1, 1139, 882, 554, -1, + 1139, 553, 882, -1, 1139, 885, 1140, -1, + 555, 1326, 871, -1, 555, 861, 1326, -1, + 555, 871, 556, -1, 555, 556, 861, -1, + 862, 940, 942, -1, 1148, 942, 922, -1, + 1148, 862, 942, -1, 1148, 861, 862, -1, + 1148, 1149, 861, -1, 1158, 960, 863, -1, + 1158, 1172, 960, -1, 1156, 557, 1609, -1, + 1156, 865, 557, -1, 560, 1609, 557, -1, + 560, 557, 558, -1, 560, 558, 559, -1, + 1330, 559, 1160, -1, 1330, 560, 559, -1, + 1330, 1609, 560, -1, 877, 875, 872, -1, + 879, 873, 875, -1, 561, 576, 562, -1, + 561, 575, 576, -1, 561, 833, 575, -1, + 561, 1340, 833, -1, 561, 562, 1340, -1, + 839, 565, 837, -1, 839, 563, 565, -1, + 839, 564, 563, -1, 839, 1125, 564, -1, + 569, 837, 565, -1, 569, 566, 570, -1, + 569, 565, 566, -1, 567, 816, 568, -1, + 567, 568, 837, -1, 567, 837, 569, -1, + 567, 570, 816, -1, 567, 569, 570, -1, + 859, 572, 873, -1, 571, 858, 573, -1, + 571, 859, 858, -1, 571, 572, 859, -1, + 571, 573, 572, -1, 884, 883, 573, -1, + 884, 573, 1140, -1, 884, 1140, 885, -1, + 578, 577, 1469, -1, 578, 1469, 1339, -1, + 574, 576, 575, -1, 574, 575, 577, -1, + 574, 1340, 576, -1, 574, 1339, 1340, -1, + 574, 577, 578, -1, 574, 578, 1339, -1, + 1216, 1214, 891, -1, 953, 1206, 1205, -1, + 887, 579, 894, -1, 887, 888, 579, -1, + 887, 894, 1215, -1, 887, 1215, 1216, -1, + 895, 580, 893, -1, 895, 894, 580, -1, + 581, 1013, 889, -1, 581, 1008, 1013, -1, + 581, 582, 1008, -1, 581, 889, 890, -1, + 581, 890, 582, -1, 897, 898, 1019, -1, + 897, 1019, 1018, -1, 897, 1018, 996, -1, + 897, 996, 1000, -1, 583, 899, 997, -1, + 583, 584, 585, -1, 583, 997, 584, -1, + 583, 585, 1040, -1, 583, 1040, 899, -1, + 1039, 1040, 1029, -1, 904, 903, 598, -1, + 904, 598, 1013, -1, 904, 1013, 905, -1, + 902, 901, 903, -1, 910, 586, 911, -1, + 910, 906, 587, -1, 910, 587, 586, -1, + 588, 589, 590, -1, 588, 590, 592, -1, + 588, 596, 589, -1, 588, 592, 596, -1, + 591, 592, 593, -1, 591, 593, 594, -1, + 591, 594, 595, -1, 591, 595, 596, -1, + 591, 596, 592, -1, 1177, 916, 1178, -1, + 1180, 917, 918, -1, 1187, 1195, 1340, -1, + 1187, 1184, 1195, -1, 1137, 1340, 1195, -1, + 1137, 1143, 1340, -1, 1137, 1195, 1197, -1, + 1194, 1195, 1184, -1, 1351, 1342, 1352, -1, + 1343, 1342, 1351, -1, 1343, 1351, 1192, -1, + 602, 603, 599, -1, 602, 599, 928, -1, + 602, 928, 947, -1, 604, 1569, 892, -1, + 597, 598, 903, -1, 597, 903, 599, -1, + 597, 604, 892, -1, 597, 599, 603, -1, + 597, 603, 604, -1, 597, 893, 598, -1, + 597, 892, 893, -1, 930, 932, 1360, -1, + 929, 1200, 908, -1, 1482, 1483, 933, -1, + 1372, 936, 944, -1, 1378, 1377, 1197, -1, + 600, 911, 601, -1, 600, 601, 912, -1, + 600, 912, 911, -1, 946, 603, 602, -1, + 946, 602, 947, -1, 1486, 603, 946, -1, + 1486, 604, 603, -1, 1486, 1569, 604, -1, + 681, 1009, 605, -1, 681, 606, 682, -1, + 681, 605, 607, -1, 681, 607, 606, -1, + 1207, 1208, 948, -1, 608, 1208, 1382, -1, + 608, 950, 1208, -1, 1212, 608, 1382, -1, + 1212, 950, 608, -1, 949, 1189, 950, -1, + 949, 1393, 1189, -1, 1188, 1349, 1189, -1, + 1395, 609, 1396, -1, 1395, 611, 1208, -1, + 1395, 1208, 993, -1, 1395, 993, 609, -1, + 610, 952, 1205, -1, 610, 1205, 611, -1, + 610, 1395, 952, -1, 610, 611, 1395, -1, + 612, 613, 615, -1, 612, 615, 956, -1, + 612, 614, 613, -1, 612, 956, 614, -1, + 958, 956, 615, -1, 958, 616, 617, -1, + 958, 615, 616, -1, 958, 617, 618, -1, + 958, 618, 619, -1, 958, 619, 959, -1, + 620, 621, 622, -1, 620, 623, 621, -1, + 620, 622, 624, -1, 620, 624, 623, -1, + 1163, 1164, 625, -1, 1163, 625, 960, -1, + 961, 1170, 1168, -1, 961, 1219, 1170, -1, + 961, 1168, 1169, -1, 633, 626, 634, -1, + 633, 627, 626, -1, 633, 631, 627, -1, + 628, 630, 629, -1, 628, 629, 631, -1, + 628, 632, 630, -1, 628, 633, 634, -1, + 628, 631, 633, -1, 628, 635, 632, -1, + 628, 634, 635, -1, 636, 638, 637, -1, + 636, 637, 703, -1, 636, 707, 638, -1, + 636, 708, 707, -1, 636, 703, 708, -1, + 639, 640, 641, -1, 639, 641, 642, -1, + 639, 644, 643, -1, 639, 645, 644, -1, + 639, 642, 645, -1, 639, 643, 646, -1, + 639, 646, 640, -1, 966, 965, 647, -1, + 966, 648, 964, -1, 966, 649, 648, -1, + 966, 647, 650, -1, 966, 650, 651, -1, + 966, 651, 652, -1, 966, 652, 653, -1, + 966, 653, 649, -1, 654, 1311, 655, -1, + 654, 1312, 1311, -1, 654, 1099, 656, -1, + 654, 655, 1099, -1, 654, 657, 658, -1, + 654, 659, 657, -1, 654, 656, 659, -1, + 654, 660, 1312, -1, 654, 658, 660, -1, + 661, 1022, 662, -1, 661, 662, 968, -1, + 661, 968, 1022, -1, 1504, 968, 666, -1, + 1504, 666, 668, -1, 1504, 668, 970, -1, + 1537, 1225, 1222, -1, 1537, 1222, 1538, -1, + 665, 663, 808, -1, 665, 664, 979, -1, + 665, 979, 976, -1, 665, 976, 663, -1, + 1119, 1318, 664, -1, 1119, 664, 665, -1, + 1119, 665, 808, -1, 1463, 666, 667, -1, + 1463, 667, 1318, -1, 1463, 668, 666, -1, + 1463, 1538, 668, -1, 669, 671, 670, -1, + 669, 672, 671, -1, 669, 670, 673, -1, + 669, 673, 672, -1, 675, 978, 1022, -1, + 675, 975, 978, -1, 980, 978, 975, -1, + 980, 976, 979, -1, 684, 1231, 674, -1, + 684, 1501, 1231, -1, 684, 674, 975, -1, + 684, 975, 675, -1, 684, 675, 1022, -1, + 1582, 1233, 981, -1, 986, 984, 1594, -1, + 986, 676, 1441, -1, 986, 1520, 676, -1, + 986, 1441, 1599, -1, 1593, 677, 1259, -1, + 1593, 1594, 677, -1, 988, 1439, 1032, -1, + 988, 989, 1439, -1, 988, 686, 990, -1, + 1241, 1005, 678, -1, 1241, 678, 1242, -1, + 1017, 992, 1018, -1, 1017, 1002, 992, -1, + 683, 682, 679, -1, 683, 679, 1003, -1, + 991, 990, 998, -1, 991, 998, 999, -1, + 995, 1236, 999, -1, 995, 996, 992, -1, + 1004, 683, 1003, -1, 1004, 1016, 683, -1, + 1006, 680, 1005, -1, 1006, 1265, 680, -1, + 1271, 1272, 1266, -1, 1010, 1009, 681, -1, + 1010, 681, 682, -1, 1015, 1010, 682, -1, + 1015, 1020, 1010, -1, 1015, 682, 683, -1, + 1015, 683, 1016, -1, 1256, 1407, 1406, -1, + 1505, 684, 1022, -1, 1505, 1501, 684, -1, + 1255, 1232, 1410, -1, 1025, 1253, 685, -1, + 1025, 685, 1026, -1, 1027, 1028, 1232, -1, + 1027, 1232, 1255, -1, 1027, 1278, 1430, -1, + 1027, 1255, 1278, -1, 1235, 1439, 989, -1, + 1274, 1028, 1416, -1, 1261, 1434, 1432, -1, + 1031, 1029, 686, -1, 1031, 686, 988, -1, + 1031, 988, 1032, -1, 1437, 1032, 1439, -1, + 1423, 1039, 1033, -1, 1423, 1038, 1039, -1, + 1423, 1424, 1038, -1, 1431, 1283, 1432, -1, + 687, 690, 688, -1, 687, 688, 692, -1, + 687, 692, 690, -1, 689, 1251, 690, -1, + 689, 692, 1251, -1, 689, 690, 692, -1, + 691, 1251, 692, -1, 691, 692, 694, -1, + 691, 698, 1251, -1, 691, 694, 699, -1, + 691, 699, 698, -1, 693, 694, 695, -1, + 693, 695, 696, -1, 693, 696, 694, -1, + 697, 1021, 698, -1, 697, 698, 699, -1, + 697, 700, 1021, -1, 697, 699, 700, -1, + 1036, 701, 1037, -1, 1036, 1026, 701, -1, + 1036, 1038, 1026, -1, 702, 703, 704, -1, + 702, 708, 703, -1, 702, 704, 705, -1, + 702, 705, 709, -1, 702, 709, 708, -1, + 1044, 706, 707, -1, 1044, 1042, 706, -1, + 1044, 707, 708, -1, 1044, 709, 1045, -1, + 1044, 708, 709, -1, 1051, 1046, 710, -1, + 1051, 710, 1052, -1, 1049, 711, 1043, -1, + 1049, 712, 711, -1, 1049, 1050, 712, -1, + 1049, 1043, 1051, -1, 713, 1056, 714, -1, + 713, 1055, 1056, -1, 713, 716, 715, -1, + 713, 714, 716, -1, 713, 715, 717, -1, + 713, 717, 1055, -1, 1057, 718, 1056, -1, + 1057, 719, 718, -1, 1057, 1058, 719, -1, + 732, 720, 730, -1, 732, 745, 720, -1, + 732, 731, 745, -1, 721, 723, 722, -1, + 721, 722, 724, -1, 721, 724, 725, -1, + 721, 726, 723, -1, 721, 727, 726, -1, + 721, 725, 727, -1, 728, 730, 729, -1, + 728, 729, 731, -1, 728, 732, 730, -1, + 728, 731, 732, -1, 1070, 733, 743, -1, + 1070, 743, 1069, -1, 1070, 1068, 733, -1, + 1059, 749, 734, -1, 1059, 736, 735, -1, + 1059, 737, 736, -1, 1059, 750, 737, -1, + 1059, 734, 750, -1, 1059, 735, 1523, -1, + 1227, 738, 1061, -1, 1227, 973, 738, -1, + 1292, 1402, 1403, -1, 1285, 1065, 1286, -1, + 1528, 739, 1296, -1, 1528, 740, 739, -1, + 1528, 1066, 740, -1, 1298, 741, 1299, -1, + 1298, 742, 741, -1, 1298, 1297, 742, -1, + 1075, 1069, 743, -1, 1075, 743, 744, -1, + 1075, 745, 1068, -1, 1075, 746, 745, -1, + 1075, 1072, 746, -1, 1075, 744, 1074, -1, + 747, 1074, 748, -1, 747, 749, 1059, -1, + 747, 1059, 1074, -1, 747, 750, 749, -1, + 747, 748, 750, -1, 751, 752, 1519, -1, + 751, 1519, 754, -1, 751, 1592, 752, -1, + 751, 754, 1592, -1, 753, 1519, 1520, -1, + 753, 754, 1519, -1, 753, 1520, 1592, -1, + 753, 1592, 754, -1, 1308, 1519, 1224, -1, + 1308, 1224, 1307, -1, 755, 756, 757, -1, + 755, 757, 758, -1, 755, 760, 759, -1, + 755, 759, 756, -1, 755, 761, 760, -1, + 755, 758, 761, -1, 1079, 763, 1080, -1, + 1079, 794, 795, -1, 1079, 795, 771, -1, + 1079, 771, 763, -1, 1079, 1083, 794, -1, + 762, 1080, 763, -1, 762, 763, 768, -1, + 762, 764, 1081, -1, 762, 1081, 1080, -1, + 762, 765, 764, -1, 762, 766, 765, -1, + 762, 769, 766, -1, 762, 768, 769, -1, + 767, 769, 768, -1, 767, 770, 769, -1, + 767, 1087, 770, -1, 767, 771, 1087, -1, + 767, 768, 771, -1, 774, 1087, 771, -1, + 774, 771, 772, -1, 774, 772, 792, -1, + 1086, 773, 1088, -1, 1086, 1087, 774, -1, + 1086, 792, 773, -1, 1086, 774, 792, -1, + 1093, 775, 776, -1, 1093, 1091, 775, -1, + 1093, 780, 1094, -1, 1093, 776, 778, -1, + 1093, 778, 780, -1, 777, 778, 779, -1, + 777, 780, 778, -1, 777, 779, 781, -1, + 777, 782, 1094, -1, 777, 1094, 780, -1, + 777, 783, 782, -1, 777, 781, 783, -1, + 784, 786, 785, -1, 784, 785, 787, -1, + 784, 788, 1099, -1, 784, 787, 788, -1, + 784, 1099, 1098, -1, 784, 1098, 797, -1, + 784, 789, 786, -1, 784, 797, 789, -1, + 790, 791, 792, -1, 790, 792, 799, -1, + 790, 800, 791, -1, 790, 799, 800, -1, + 793, 795, 794, -1, 793, 799, 795, -1, + 793, 794, 801, -1, 793, 801, 799, -1, + 1097, 1096, 796, -1, 1097, 796, 797, -1, + 1097, 797, 1098, -1, 798, 800, 799, -1, + 798, 799, 801, -1, 798, 802, 800, -1, + 798, 803, 802, -1, 798, 801, 803, -1, + 1102, 804, 1110, -1, 1102, 1117, 804, -1, + 1109, 1107, 1117, -1, 1109, 805, 1104, -1, + 1109, 1110, 806, -1, 1109, 806, 805, -1, + 1111, 1101, 1110, -1, 1111, 1117, 1101, -1, + 807, 1113, 1231, -1, 807, 1231, 1114, -1, + 807, 1114, 1113, -1, 1118, 1231, 1116, -1, + 1118, 1114, 1231, -1, 1120, 808, 811, -1, + 1120, 1119, 808, -1, 809, 810, 1297, -1, + 809, 811, 810, -1, 809, 1120, 811, -1, + 809, 1297, 1495, -1, 809, 1495, 1120, -1, + 812, 813, 814, -1, 812, 814, 815, -1, + 812, 816, 813, -1, 812, 817, 816, -1, + 812, 818, 817, -1, 812, 815, 818, -1, + 819, 820, 821, -1, 819, 822, 820, -1, + 819, 821, 823, -1, 819, 823, 824, -1, + 819, 824, 822, -1, 825, 826, 827, -1, + 825, 828, 829, -1, 825, 827, 828, -1, + 825, 829, 830, -1, 825, 830, 831, -1, + 825, 831, 826, -1, 843, 832, 833, -1, + 843, 833, 834, -1, 843, 835, 875, -1, + 843, 834, 835, -1, 843, 836, 832, -1, + 843, 841, 836, -1, 1124, 837, 838, -1, + 1124, 838, 1122, -1, 1124, 839, 837, -1, + 1124, 1125, 839, -1, 840, 1131, 1130, -1, + 840, 1130, 841, -1, 840, 842, 1131, -1, + 840, 873, 883, -1, 840, 841, 843, -1, + 840, 844, 842, -1, 840, 883, 844, -1, + 840, 875, 873, -1, 840, 843, 875, -1, + 1127, 1129, 870, -1, 1127, 870, 868, -1, + 1127, 845, 1128, -1, 1127, 868, 846, -1, + 1127, 846, 845, -1, 847, 848, 849, -1, + 847, 849, 850, -1, 847, 850, 848, -1, + 1132, 854, 924, -1, 1132, 1133, 854, -1, + 851, 1218, 852, -1, 851, 852, 853, -1, + 851, 853, 854, -1, 851, 854, 855, -1, + 851, 855, 1218, -1, 1134, 855, 1133, -1, + 1134, 1218, 855, -1, 856, 944, 857, -1, + 856, 857, 1139, -1, 856, 1139, 944, -1, + 1136, 944, 1139, -1, 1144, 1140, 858, -1, + 1144, 873, 878, -1, 1144, 859, 873, -1, + 1144, 858, 859, -1, 1144, 878, 877, -1, + 860, 861, 941, -1, 860, 862, 861, -1, + 860, 941, 940, -1, 860, 940, 862, -1, + 1171, 1172, 1158, -1, 1171, 1218, 962, -1, + 1171, 962, 1169, -1, 1171, 1151, 1218, -1, + 1171, 1158, 1151, -1, 1155, 1162, 1151, -1, + 1154, 1158, 863, -1, 1154, 863, 864, -1, + 1154, 864, 867, -1, 1613, 1156, 1609, -1, + 1153, 865, 1156, -1, 1153, 866, 865, -1, + 1153, 867, 866, -1, 1153, 1154, 867, -1, + 1466, 1328, 868, -1, 1466, 870, 869, -1, + 1466, 869, 871, -1, 1466, 868, 870, -1, + 1466, 871, 1326, -1, 1145, 872, 1142, -1, + 1145, 877, 872, -1, 1145, 1144, 877, -1, + 880, 878, 873, -1, 880, 873, 879, -1, + 874, 875, 877, -1, 874, 879, 875, -1, + 874, 877, 879, -1, 876, 877, 878, -1, + 876, 879, 877, -1, 876, 878, 880, -1, + 876, 880, 879, -1, 881, 882, 883, -1, + 881, 883, 884, -1, 881, 885, 882, -1, + 881, 884, 885, -1, 886, 888, 887, -1, + 886, 890, 889, -1, 886, 889, 888, -1, + 886, 887, 1216, -1, 886, 891, 890, -1, + 886, 1216, 891, -1, 1478, 892, 1569, -1, + 1478, 893, 892, -1, 1478, 895, 893, -1, + 1478, 1477, 895, -1, 954, 1215, 894, -1, + 954, 894, 895, -1, 954, 895, 1477, -1, + 954, 1477, 953, -1, 896, 898, 897, -1, + 896, 1011, 898, -1, 896, 1000, 899, -1, + 896, 897, 1000, -1, 896, 899, 1040, -1, + 896, 1040, 1011, -1, 1277, 1026, 1038, -1, + 1277, 1038, 1424, -1, 914, 907, 908, -1, + 914, 900, 901, -1, 914, 908, 900, -1, + 914, 901, 902, -1, 914, 902, 903, -1, + 914, 904, 905, -1, 914, 903, 904, -1, + 914, 913, 907, -1, 914, 905, 906, -1, + 914, 906, 910, -1, 931, 908, 907, -1, + 931, 929, 908, -1, 931, 913, 932, -1, + 931, 907, 913, -1, 909, 910, 911, -1, + 909, 911, 912, -1, 909, 912, 913, -1, + 909, 913, 914, -1, 909, 914, 910, -1, + 915, 934, 916, -1, 915, 916, 1177, -1, + 915, 1177, 934, -1, 1369, 934, 1177, -1, + 1179, 1178, 917, -1, 1179, 917, 1180, -1, + 1333, 1180, 918, -1, 1333, 918, 919, -1, + 1333, 920, 1334, -1, 1333, 919, 921, -1, + 1333, 921, 920, -1, 923, 1150, 1147, -1, + 923, 1148, 922, -1, 923, 1147, 1148, -1, + 1181, 1371, 1167, -1, 1181, 1372, 1371, -1, + 1181, 937, 1372, -1, 1181, 922, 942, -1, + 1181, 923, 922, -1, 1181, 1150, 923, -1, + 1181, 924, 1182, -1, 1181, 1132, 924, -1, + 1553, 1184, 1187, -1, 1553, 1559, 925, -1, + 1553, 1549, 1554, -1, 1553, 925, 1546, -1, + 1341, 1349, 1188, -1, 1341, 1210, 1342, -1, + 1345, 926, 1346, -1, 1345, 927, 926, -1, + 1345, 1122, 927, -1, 1345, 1123, 1122, -1, + 1345, 1186, 1123, -1, 1491, 953, 1477, -1, + 1491, 1206, 953, -1, 1196, 1194, 1192, -1, + 1196, 1353, 1350, -1, 1191, 1343, 1192, -1, + 1191, 1194, 1184, -1, 1191, 1192, 1194, -1, + 1191, 1184, 1190, -1, 1202, 1204, 947, -1, + 1202, 928, 1201, -1, 1202, 947, 928, -1, + 1199, 1200, 929, -1, 1199, 929, 1358, -1, + 1199, 1358, 1366, -1, 1199, 1366, 1367, -1, + 1362, 1358, 929, -1, 1362, 930, 1360, -1, + 1362, 929, 931, -1, 1362, 932, 930, -1, + 1362, 931, 932, -1, 1375, 933, 934, -1, + 1375, 1482, 933, -1, 1375, 934, 1369, -1, + 935, 936, 1372, -1, 935, 1372, 937, -1, + 935, 939, 938, -1, 935, 938, 936, -1, + 935, 940, 941, -1, 935, 942, 940, -1, + 935, 941, 943, -1, 935, 943, 939, -1, + 935, 1181, 942, -1, 935, 937, 1181, -1, + 1373, 1372, 944, -1, 1373, 944, 1136, -1, + 1481, 1359, 1360, -1, 1481, 1360, 945, -1, + 1481, 945, 1485, -1, 1379, 1486, 946, -1, + 1379, 947, 1204, -1, 1379, 946, 947, -1, + 1209, 948, 1205, -1, 1209, 1207, 948, -1, + 1381, 1212, 1382, -1, 1392, 949, 950, -1, + 1392, 1393, 949, -1, 1392, 950, 1212, -1, + 951, 1205, 952, -1, 951, 952, 1395, -1, + 951, 1395, 1205, -1, 1213, 953, 1205, -1, + 1213, 1205, 1395, -1, 1213, 1215, 954, -1, + 1213, 954, 953, -1, 955, 957, 956, -1, + 955, 956, 958, -1, 955, 959, 957, -1, + 955, 958, 959, -1, 1173, 1163, 960, -1, + 1173, 960, 1172, -1, 1220, 1219, 961, -1, + 1220, 962, 1218, -1, 1220, 1169, 962, -1, + 1220, 961, 1169, -1, 963, 964, 965, -1, + 963, 965, 966, -1, 963, 966, 964, -1, + 1400, 970, 1222, -1, 967, 1022, 968, -1, + 967, 1504, 1022, -1, 967, 968, 1504, -1, + 969, 1023, 1504, -1, 969, 1400, 1023, -1, + 969, 970, 1400, -1, 969, 1504, 970, -1, + 1540, 1226, 1537, -1, 1540, 1629, 1226, -1, + 1589, 1226, 971, -1, 1589, 971, 972, -1, + 1589, 972, 973, -1, 1589, 973, 1227, -1, + 1494, 1120, 1495, -1, 974, 975, 976, -1, + 974, 976, 980, -1, 974, 980, 975, -1, + 977, 979, 978, -1, 977, 980, 979, -1, + 977, 978, 980, -1, 1502, 981, 1229, -1, + 1502, 1582, 981, -1, 1234, 1274, 1275, -1, + 1234, 1028, 1274, -1, 1234, 1232, 1028, -1, + 982, 1594, 1592, -1, 982, 986, 1594, -1, + 982, 1592, 1520, -1, 982, 1520, 986, -1, + 983, 985, 984, -1, 983, 984, 986, -1, + 983, 1599, 985, -1, 983, 986, 1599, -1, + 1248, 1235, 989, -1, 987, 989, 988, -1, + 987, 1248, 989, -1, 987, 991, 1248, -1, + 987, 988, 990, -1, 987, 990, 991, -1, + 1237, 999, 1236, -1, 1237, 991, 999, -1, + 1237, 1238, 1248, -1, 1237, 1248, 991, -1, + 1262, 992, 1002, -1, 1262, 995, 992, -1, + 1262, 1236, 995, -1, 1262, 1003, 993, -1, + 1262, 1002, 1003, -1, 1262, 993, 1208, -1, + 1262, 1208, 1263, -1, 994, 996, 995, -1, + 994, 998, 997, -1, 994, 999, 998, -1, + 994, 995, 999, -1, 994, 997, 1000, -1, + 994, 1000, 996, -1, 1001, 1002, 1017, -1, + 1001, 1003, 1002, -1, 1001, 1004, 1003, -1, + 1001, 1017, 1016, -1, 1001, 1016, 1004, -1, + 1240, 1005, 1241, -1, 1240, 1006, 1005, -1, + 1418, 1006, 1240, -1, 1418, 1265, 1006, -1, + 1244, 1245, 1248, -1, 1007, 1008, 1009, -1, + 1007, 1009, 1010, -1, 1007, 1012, 1011, -1, + 1007, 1020, 1012, -1, 1007, 1010, 1020, -1, + 1007, 1013, 1008, -1, 1007, 1011, 1013, -1, + 1014, 1015, 1016, -1, 1014, 1017, 1018, -1, + 1014, 1016, 1017, -1, 1014, 1018, 1019, -1, + 1014, 1019, 1020, -1, 1014, 1020, 1015, -1, + 1252, 1021, 1257, -1, 1252, 1257, 1256, -1, + 1252, 1256, 1406, -1, 1252, 1251, 1021, -1, + 1411, 1407, 1256, -1, 1411, 1586, 1407, -1, + 1503, 1022, 1504, -1, 1503, 1505, 1022, -1, + 1588, 1504, 1023, -1, 1588, 1023, 1400, -1, + 1254, 1253, 1025, -1, 1254, 1025, 1279, -1, + 1254, 1279, 1278, -1, 1254, 1278, 1255, -1, + 1024, 1426, 1279, -1, 1024, 1279, 1025, -1, + 1024, 1277, 1426, -1, 1024, 1025, 1026, -1, + 1024, 1026, 1277, -1, 1260, 1028, 1027, -1, + 1260, 1416, 1028, -1, 1260, 1430, 1434, -1, + 1260, 1027, 1430, -1, 1440, 1266, 1280, -1, + 1440, 1235, 1266, -1, 1440, 1439, 1235, -1, + 1269, 1270, 1415, -1, 1269, 1415, 1261, -1, + 1419, 1274, 1416, -1, 1267, 1261, 1432, -1, + 1267, 1283, 1280, -1, 1267, 1432, 1283, -1, + 1267, 1269, 1261, -1, 1030, 1029, 1031, -1, + 1030, 1033, 1039, -1, 1030, 1039, 1029, -1, + 1034, 1282, 1033, -1, 1034, 1033, 1030, -1, + 1034, 1030, 1031, -1, 1034, 1031, 1032, -1, + 1034, 1032, 1437, -1, 1422, 1033, 1282, -1, + 1422, 1423, 1033, -1, 1436, 1282, 1034, -1, + 1436, 1034, 1437, -1, 1035, 1036, 1037, -1, + 1035, 1038, 1036, -1, 1035, 1039, 1038, -1, + 1035, 1037, 1040, -1, 1035, 1040, 1039, -1, + 1041, 1043, 1042, -1, 1041, 1051, 1043, -1, + 1041, 1044, 1045, -1, 1041, 1042, 1044, -1, + 1041, 1046, 1051, -1, 1041, 1045, 1047, -1, + 1041, 1047, 1046, -1, 1048, 1050, 1049, -1, + 1048, 1049, 1051, -1, 1048, 1051, 1052, -1, + 1048, 1052, 1053, -1, 1048, 1053, 1050, -1, + 1054, 1056, 1055, -1, 1054, 1057, 1056, -1, + 1054, 1055, 1058, -1, 1054, 1058, 1057, -1, + 1521, 1454, 1074, -1, 1521, 1074, 1059, -1, + 1522, 1059, 1523, -1, 1522, 1521, 1059, -1, + 1060, 1227, 1061, -1, 1060, 1061, 1062, -1, + 1060, 1592, 1227, -1, 1060, 1062, 1592, -1, + 1284, 1403, 1401, -1, 1284, 1600, 1601, -1, + 1290, 1063, 1534, -1, 1290, 1291, 1063, -1, + 1290, 1402, 1292, -1, 1290, 1076, 1402, -1, + 1290, 1534, 1076, -1, 1447, 1446, 1291, -1, + 1449, 1064, 1065, -1, 1449, 1065, 1285, -1, + 1449, 1293, 1064, -1, 1449, 1285, 1525, -1, + 1624, 1299, 1066, -1, 1624, 1066, 1528, -1, + 1493, 1401, 1497, -1, 1493, 1284, 1401, -1, + 1493, 1600, 1284, -1, 1067, 1075, 1068, -1, + 1067, 1069, 1075, -1, 1067, 1068, 1070, -1, + 1067, 1070, 1069, -1, 1305, 1071, 1072, -1, + 1305, 1072, 1075, -1, 1305, 1073, 1071, -1, + 1305, 1301, 1073, -1, 1451, 1074, 1454, -1, + 1451, 1075, 1074, -1, 1451, 1305, 1075, -1, + 1460, 1461, 1456, -1, 1309, 1646, 1228, -1, + 1309, 1228, 1076, -1, 1309, 1076, 1534, -1, + 1532, 1306, 1458, -1, 1532, 1535, 1077, -1, + 1532, 1077, 1302, -1, 1532, 1302, 1306, -1, + 1648, 1646, 1309, -1, 1078, 1079, 1080, -1, + 1078, 1081, 1082, -1, 1078, 1080, 1081, -1, + 1078, 1083, 1079, -1, 1078, 1082, 1084, -1, + 1078, 1084, 1083, -1, 1085, 1087, 1086, -1, + 1085, 1086, 1088, -1, 1085, 1089, 1087, -1, + 1085, 1088, 1089, -1, 1090, 1092, 1091, -1, + 1090, 1091, 1093, -1, 1090, 1094, 1092, -1, + 1090, 1093, 1094, -1, 1095, 1312, 1096, -1, + 1095, 1097, 1312, -1, 1095, 1096, 1097, -1, + 1313, 1097, 1098, -1, 1313, 1098, 1099, -1, + 1313, 1099, 1311, -1, 1313, 1312, 1097, -1, + 1100, 1101, 1117, -1, 1100, 1117, 1102, -1, + 1100, 1110, 1101, -1, 1100, 1102, 1110, -1, + 1103, 1104, 1105, -1, 1103, 1109, 1104, -1, + 1103, 1105, 1106, -1, 1103, 1106, 1107, -1, + 1103, 1107, 1109, -1, 1108, 1110, 1109, -1, + 1108, 1109, 1117, -1, 1108, 1111, 1110, -1, + 1108, 1117, 1111, -1, 1112, 1117, 1316, -1, + 1112, 1316, 1315, -1, 1112, 1315, 1117, -1, + 1317, 1316, 1113, -1, 1317, 1113, 1114, -1, + 1317, 1114, 1118, -1, 1317, 1118, 1315, -1, + 1115, 1116, 1117, -1, 1115, 1117, 1315, -1, + 1115, 1118, 1116, -1, 1115, 1315, 1118, -1, + 1465, 1318, 1119, -1, 1465, 1119, 1120, -1, + 1465, 1120, 1494, -1, 1121, 1122, 1123, -1, + 1121, 1124, 1122, -1, 1121, 1125, 1124, -1, + 1121, 1123, 1185, -1, 1121, 1185, 1553, -1, + 1121, 1546, 1125, -1, 1121, 1553, 1546, -1, + 1126, 1127, 1128, -1, 1126, 1129, 1127, -1, + 1126, 1128, 1130, -1, 1126, 1130, 1131, -1, + 1126, 1131, 1129, -1, 1174, 1133, 1132, -1, + 1174, 1134, 1133, -1, 1174, 1132, 1181, -1, + 1174, 1170, 1218, -1, 1174, 1218, 1134, -1, + 1174, 1181, 1167, -1, 1320, 1151, 1321, -1, + 1320, 1182, 1151, -1, 1320, 1322, 1182, -1, + 1135, 1139, 1143, -1, 1135, 1136, 1139, -1, + 1135, 1137, 1197, -1, 1135, 1143, 1137, -1, + 1135, 1197, 1377, -1, 1135, 1377, 1373, -1, + 1135, 1373, 1136, -1, 1138, 1139, 1140, -1, + 1138, 1140, 1144, -1, 1138, 1143, 1139, -1, + 1138, 1144, 1143, -1, 1141, 1142, 1340, -1, + 1141, 1340, 1143, -1, 1141, 1143, 1144, -1, + 1141, 1145, 1142, -1, 1141, 1144, 1145, -1, + 1146, 1148, 1147, -1, 1146, 1321, 1149, -1, + 1146, 1149, 1148, -1, 1146, 1181, 1321, -1, + 1146, 1147, 1150, -1, 1146, 1150, 1181, -1, + 1157, 1151, 1158, -1, 1157, 1155, 1151, -1, + 1152, 1154, 1153, -1, 1152, 1162, 1155, -1, + 1152, 1153, 1156, -1, 1152, 1155, 1157, -1, + 1152, 1613, 1162, -1, 1152, 1156, 1613, -1, + 1152, 1158, 1154, -1, 1152, 1157, 1158, -1, + 1606, 1466, 1326, -1, 1621, 1466, 1616, -1, + 1329, 1159, 1328, -1, 1329, 1160, 1159, -1, + 1329, 1330, 1160, -1, 1329, 1467, 1330, -1, + 1161, 1325, 1162, -1, 1161, 1612, 1325, -1, + 1161, 1162, 1613, -1, 1161, 1613, 1612, -1, + 1474, 1339, 1475, -1, 1474, 1470, 1553, -1, + 1474, 1553, 1339, -1, 1331, 1475, 1469, -1, + 1335, 1176, 1333, -1, 1335, 1164, 1163, -1, + 1335, 1163, 1173, -1, 1335, 1165, 1164, -1, + 1335, 1336, 1165, -1, 1166, 1167, 1371, -1, + 1166, 1371, 1176, -1, 1166, 1176, 1335, -1, + 1166, 1169, 1168, -1, 1166, 1168, 1170, -1, + 1166, 1171, 1169, -1, 1166, 1172, 1171, -1, + 1166, 1173, 1172, -1, 1166, 1335, 1173, -1, + 1166, 1170, 1174, -1, 1166, 1174, 1167, -1, + 1370, 1369, 1177, -1, 1370, 1176, 1371, -1, + 1175, 1333, 1176, -1, 1175, 1370, 1177, -1, + 1175, 1176, 1370, -1, 1175, 1177, 1178, -1, + 1175, 1178, 1179, -1, 1175, 1179, 1180, -1, + 1175, 1180, 1333, -1, 1323, 1181, 1182, -1, + 1323, 1321, 1181, -1, 1323, 1182, 1322, -1, + 1183, 1190, 1184, -1, 1183, 1184, 1553, -1, + 1183, 1553, 1185, -1, 1183, 1185, 1186, -1, + 1183, 1186, 1345, -1, 1183, 1345, 1190, -1, + 1558, 1559, 1553, -1, 1338, 1187, 1340, -1, + 1338, 1553, 1187, -1, 1211, 1341, 1188, -1, + 1211, 1189, 1393, -1, 1211, 1188, 1189, -1, + 1211, 1210, 1341, -1, 1347, 1190, 1345, -1, + 1347, 1191, 1190, -1, 1347, 1343, 1191, -1, + 1364, 1352, 1210, -1, 1364, 1365, 1352, -1, + 1484, 1378, 1350, -1, 1355, 1192, 1351, -1, + 1355, 1196, 1192, -1, 1355, 1353, 1196, -1, + 1193, 1195, 1194, -1, 1193, 1194, 1196, -1, + 1193, 1197, 1195, -1, 1193, 1196, 1350, -1, + 1193, 1378, 1197, -1, 1193, 1350, 1378, -1, + 1357, 1365, 1366, -1, 1357, 1366, 1358, -1, + 1203, 1386, 1204, -1, 1203, 1204, 1202, -1, + 1385, 1203, 1367, -1, 1385, 1386, 1203, -1, + 1198, 1200, 1199, -1, 1198, 1201, 1200, -1, + 1198, 1202, 1201, -1, 1198, 1203, 1202, -1, + 1198, 1199, 1367, -1, 1198, 1367, 1203, -1, + 1376, 1375, 1369, -1, 1376, 1373, 1377, -1, + 1380, 1204, 1386, -1, 1380, 1379, 1204, -1, + 1380, 1386, 1384, -1, 1489, 1209, 1205, -1, + 1489, 1205, 1206, -1, 1489, 1206, 1491, -1, + 1488, 1208, 1207, -1, 1488, 1207, 1209, -1, + 1488, 1382, 1208, -1, 1488, 1209, 1489, -1, + 1388, 1364, 1210, -1, 1388, 1389, 1364, -1, + 1388, 1210, 1211, -1, 1388, 1211, 1393, -1, + 1391, 1381, 1384, -1, 1391, 1212, 1381, -1, + 1391, 1392, 1212, -1, 1397, 1213, 1395, -1, + 1397, 1396, 1214, -1, 1397, 1215, 1213, -1, + 1397, 1214, 1216, -1, 1397, 1216, 1215, -1, + 1217, 1218, 1219, -1, 1217, 1219, 1220, -1, + 1217, 1220, 1218, -1, 1221, 1222, 1225, -1, + 1221, 1400, 1222, -1, 1221, 1225, 1400, -1, + 1223, 1224, 1226, -1, 1223, 1226, 1629, -1, + 1223, 1634, 1224, -1, 1223, 1629, 1634, -1, + 1572, 1629, 1540, -1, 1399, 1225, 1537, -1, + 1399, 1400, 1225, -1, 1399, 1226, 1589, -1, + 1399, 1537, 1226, -1, 1591, 1227, 1592, -1, + 1591, 1589, 1227, -1, 1405, 1646, 1645, -1, + 1405, 1402, 1228, -1, 1405, 1228, 1646, -1, + 1500, 1229, 1230, -1, 1500, 1502, 1229, -1, + 1500, 1230, 1231, -1, 1500, 1231, 1501, -1, + 1584, 1410, 1232, -1, 1584, 1232, 1234, -1, + 1575, 1407, 1586, -1, 1581, 1275, 1233, -1, + 1581, 1234, 1275, -1, 1581, 1233, 1582, -1, + 1581, 1584, 1234, -1, 1246, 1271, 1266, -1, + 1246, 1266, 1235, -1, 1246, 1235, 1248, -1, + 1247, 1236, 1262, -1, 1247, 1237, 1236, -1, + 1247, 1238, 1237, -1, 1247, 1262, 1271, -1, + 1247, 1248, 1238, -1, 1247, 1244, 1248, -1, + 1239, 1240, 1241, -1, 1239, 1418, 1240, -1, + 1239, 1276, 1418, -1, 1239, 1242, 1276, -1, + 1239, 1241, 1242, -1, 1243, 1245, 1244, -1, + 1243, 1271, 1246, -1, 1243, 1247, 1271, -1, + 1243, 1244, 1247, -1, 1243, 1248, 1245, -1, + 1243, 1246, 1248, -1, 1249, 1250, 1251, -1, + 1249, 1251, 1252, -1, 1249, 1512, 1250, -1, + 1249, 1252, 1406, -1, 1249, 1511, 1512, -1, + 1249, 1406, 1511, -1, 1409, 1413, 1253, -1, + 1409, 1253, 1254, -1, 1409, 1255, 1410, -1, + 1409, 1254, 1255, -1, 1412, 1411, 1256, -1, + 1412, 1256, 1257, -1, 1412, 1258, 1413, -1, + 1412, 1257, 1258, -1, 1509, 1259, 1510, -1, + 1509, 1593, 1259, -1, 1414, 1416, 1260, -1, + 1414, 1261, 1415, -1, 1414, 1434, 1261, -1, + 1414, 1260, 1434, -1, 1514, 1415, 1270, -1, + 1514, 1262, 1263, -1, 1514, 1271, 1262, -1, + 1514, 1263, 1264, -1, 1514, 1264, 1265, -1, + 1514, 1265, 1418, -1, 1273, 1266, 1272, -1, + 1273, 1269, 1267, -1, 1273, 1280, 1266, -1, + 1273, 1267, 1280, -1, 1268, 1270, 1269, -1, + 1268, 1272, 1271, -1, 1268, 1273, 1272, -1, + 1268, 1269, 1273, -1, 1268, 1271, 1514, -1, + 1268, 1514, 1270, -1, 1420, 1274, 1419, -1, + 1420, 1276, 1275, -1, 1420, 1275, 1274, -1, + 1420, 1418, 1276, -1, 1427, 1426, 1277, -1, + 1427, 1277, 1424, -1, 1429, 1430, 1278, -1, + 1429, 1278, 1279, -1, 1429, 1279, 1426, -1, + 1438, 1280, 1283, -1, 1438, 1440, 1280, -1, + 1281, 1422, 1282, -1, 1281, 1282, 1436, -1, + 1281, 1425, 1422, -1, 1281, 1431, 1425, -1, + 1281, 1283, 1431, -1, 1281, 1438, 1283, -1, + 1281, 1436, 1438, -1, 1597, 1454, 1521, -1, + 1442, 1288, 1403, -1, 1442, 1403, 1284, -1, + 1442, 1284, 1601, -1, 1442, 1601, 1524, -1, + 1442, 1447, 1288, -1, 1289, 1292, 1403, -1, + 1289, 1403, 1288, -1, 1444, 1285, 1286, -1, + 1444, 1525, 1285, -1, 1444, 1286, 1445, -1, + 1287, 1288, 1447, -1, 1287, 1289, 1288, -1, + 1287, 1291, 1290, -1, 1287, 1447, 1291, -1, + 1287, 1290, 1292, -1, 1287, 1292, 1289, -1, + 1527, 1294, 1293, -1, 1527, 1293, 1449, -1, + 1527, 1295, 1294, -1, 1527, 1296, 1295, -1, + 1527, 1528, 1296, -1, 1450, 1496, 1495, -1, + 1450, 1495, 1297, -1, 1450, 1297, 1298, -1, + 1450, 1298, 1299, -1, 1450, 1299, 1624, -1, + 1492, 1600, 1493, -1, 1492, 1496, 1600, -1, + 1300, 1301, 1305, -1, 1300, 1305, 1306, -1, + 1300, 1306, 1302, -1, 1300, 1303, 1301, -1, + 1300, 1302, 1303, -1, 1304, 1451, 1458, -1, + 1304, 1305, 1451, -1, 1304, 1458, 1306, -1, + 1304, 1306, 1305, -1, 1455, 1460, 1456, -1, + 1533, 1309, 1534, -1, 1631, 1307, 1634, -1, + 1631, 1308, 1307, -1, 1631, 1518, 1519, -1, + 1631, 1519, 1308, -1, 1647, 1648, 1461, -1, + 1457, 1648, 1309, -1, 1457, 1309, 1533, -1, + 1457, 1456, 1461, -1, 1457, 1461, 1648, -1, + 1310, 1311, 1312, -1, 1310, 1312, 1313, -1, + 1310, 1313, 1311, -1, 1314, 1315, 1316, -1, + 1314, 1316, 1317, -1, 1314, 1317, 1315, -1, + 1464, 1463, 1318, -1, 1464, 1318, 1465, -1, + 1319, 1320, 1321, -1, 1319, 1322, 1320, -1, + 1319, 1321, 1323, -1, 1319, 1323, 1322, -1, + 1544, 1616, 1466, -1, 1324, 1325, 1612, -1, + 1324, 1612, 1606, -1, 1324, 1326, 1325, -1, + 1324, 1606, 1326, -1, 1327, 1328, 1466, -1, + 1327, 1329, 1328, -1, 1327, 1467, 1329, -1, + 1327, 1466, 1621, -1, 1327, 1621, 1467, -1, + 1608, 1609, 1330, -1, 1608, 1330, 1467, -1, + 1472, 1469, 1546, -1, 1476, 1331, 1469, -1, + 1476, 1468, 1474, -1, 1476, 1475, 1331, -1, + 1332, 1333, 1334, -1, 1332, 1335, 1333, -1, + 1332, 1334, 1336, -1, 1332, 1336, 1335, -1, + 1562, 1546, 1561, -1, 1337, 1553, 1338, -1, + 1337, 1339, 1553, -1, 1337, 1338, 1340, -1, + 1337, 1340, 1339, -1, 1348, 1349, 1341, -1, + 1348, 1341, 1342, -1, 1348, 1342, 1343, -1, + 1348, 1343, 1347, -1, 1344, 1345, 1346, -1, + 1344, 1347, 1345, -1, 1344, 1348, 1347, -1, + 1344, 1346, 1349, -1, 1344, 1349, 1348, -1, + 1480, 1359, 1481, -1, 1480, 1353, 1359, -1, + 1480, 1350, 1353, -1, 1480, 1484, 1350, -1, + 1354, 1351, 1352, -1, 1354, 1355, 1351, -1, + 1354, 1352, 1365, -1, 1354, 1365, 1357, -1, + 1361, 1359, 1353, -1, 1361, 1354, 1357, -1, + 1361, 1353, 1355, -1, 1361, 1355, 1354, -1, + 1356, 1357, 1358, -1, 1356, 1360, 1359, -1, + 1356, 1359, 1361, -1, 1356, 1361, 1357, -1, + 1356, 1362, 1360, -1, 1356, 1358, 1362, -1, + 1363, 1389, 1385, -1, 1363, 1365, 1364, -1, + 1363, 1364, 1389, -1, 1363, 1366, 1365, -1, + 1363, 1367, 1366, -1, 1363, 1385, 1367, -1, + 1368, 1376, 1369, -1, 1368, 1370, 1371, -1, + 1368, 1369, 1370, -1, 1368, 1371, 1372, -1, + 1368, 1372, 1373, -1, 1368, 1373, 1376, -1, + 1374, 1482, 1375, -1, 1374, 1375, 1376, -1, + 1374, 1484, 1482, -1, 1374, 1376, 1377, -1, + 1374, 1377, 1378, -1, 1374, 1378, 1484, -1, + 1565, 1486, 1379, -1, 1565, 1379, 1380, -1, + 1383, 1380, 1384, -1, 1383, 1384, 1381, -1, + 1383, 1566, 1565, -1, 1383, 1565, 1380, -1, + 1490, 1381, 1382, -1, 1490, 1382, 1488, -1, + 1490, 1383, 1381, -1, 1490, 1566, 1383, -1, + 1390, 1391, 1384, -1, 1390, 1385, 1389, -1, + 1390, 1384, 1386, -1, 1390, 1386, 1385, -1, + 1387, 1389, 1388, -1, 1387, 1390, 1389, -1, + 1387, 1391, 1390, -1, 1387, 1392, 1391, -1, + 1387, 1393, 1392, -1, 1387, 1388, 1393, -1, + 1394, 1395, 1396, -1, 1394, 1396, 1397, -1, + 1394, 1397, 1395, -1, 1398, 1400, 1399, -1, + 1398, 1399, 1589, -1, 1398, 1588, 1400, -1, + 1398, 1589, 1588, -1, 1404, 1497, 1401, -1, + 1404, 1402, 1405, -1, 1404, 1403, 1402, -1, + 1404, 1401, 1403, -1, 1498, 1605, 1494, -1, + 1542, 1497, 1404, -1, 1542, 1405, 1645, -1, + 1542, 1404, 1405, -1, 1585, 1410, 1584, -1, + 1585, 1586, 1411, -1, 1574, 1502, 1500, -1, + 1578, 1579, 1511, -1, 1578, 1406, 1407, -1, + 1578, 1511, 1406, -1, 1578, 1407, 1575, -1, + 1408, 1409, 1410, -1, 1408, 1410, 1585, -1, + 1408, 1585, 1411, -1, 1408, 1411, 1412, -1, + 1408, 1413, 1409, -1, 1408, 1412, 1413, -1, + 1508, 1579, 1577, -1, 1516, 1414, 1415, -1, + 1516, 1515, 1419, -1, 1516, 1419, 1416, -1, + 1516, 1416, 1414, -1, 1516, 1415, 1514, -1, + 1417, 1515, 1514, -1, 1417, 1514, 1418, -1, + 1417, 1419, 1515, -1, 1417, 1418, 1420, -1, + 1417, 1420, 1419, -1, 1421, 1422, 1425, -1, + 1421, 1425, 1427, -1, 1421, 1423, 1422, -1, + 1421, 1424, 1423, -1, 1421, 1427, 1424, -1, + 1433, 1425, 1431, -1, 1433, 1429, 1426, -1, + 1433, 1426, 1427, -1, 1433, 1427, 1425, -1, + 1428, 1430, 1429, -1, 1428, 1431, 1432, -1, + 1428, 1433, 1431, -1, 1428, 1429, 1433, -1, + 1428, 1434, 1430, -1, 1428, 1432, 1434, -1, + 1435, 1436, 1437, -1, 1435, 1438, 1436, -1, + 1435, 1437, 1439, -1, 1435, 1439, 1440, -1, + 1435, 1440, 1438, -1, 1596, 1462, 1597, -1, + 1596, 1518, 1462, -1, 1596, 1599, 1441, -1, + 1596, 1441, 1520, -1, 1448, 1447, 1442, -1, + 1448, 1442, 1524, -1, 1448, 1524, 1525, -1, + 1448, 1525, 1444, -1, 1443, 1444, 1445, -1, + 1443, 1445, 1446, -1, 1443, 1446, 1447, -1, + 1443, 1447, 1448, -1, 1443, 1448, 1444, -1, + 1529, 1449, 1525, -1, 1529, 1527, 1449, -1, + 1626, 1450, 1624, -1, 1626, 1600, 1496, -1, + 1626, 1496, 1450, -1, 1453, 1451, 1454, -1, + 1453, 1458, 1451, -1, 1453, 1455, 1458, -1, + 1452, 1460, 1455, -1, 1452, 1462, 1460, -1, + 1452, 1453, 1454, -1, 1452, 1455, 1453, -1, + 1452, 1597, 1462, -1, 1452, 1454, 1597, -1, + 1531, 1455, 1456, -1, 1531, 1456, 1457, -1, + 1531, 1457, 1533, -1, 1531, 1532, 1458, -1, + 1531, 1458, 1455, -1, 1459, 1461, 1460, -1, + 1459, 1647, 1461, -1, 1459, 1460, 1462, -1, + 1459, 1631, 1647, -1, 1459, 1462, 1518, -1, + 1459, 1518, 1631, -1, 1539, 1538, 1463, -1, + 1539, 1463, 1464, -1, 1637, 1464, 1465, -1, + 1637, 1539, 1464, -1, 1637, 1465, 1494, -1, + 1637, 1540, 1539, -1, 1637, 1494, 1605, -1, + 1637, 1628, 1540, -1, 1543, 1466, 1606, -1, + 1543, 1544, 1466, -1, 1615, 1608, 1467, -1, + 1615, 1467, 1619, -1, 1615, 1616, 1544, -1, + 1618, 1467, 1621, -1, 1618, 1619, 1467, -1, + 1471, 1470, 1474, -1, 1471, 1474, 1468, -1, + 1471, 1469, 1472, -1, 1471, 1476, 1469, -1, + 1471, 1468, 1476, -1, 1548, 1553, 1470, -1, + 1548, 1470, 1471, -1, 1548, 1471, 1472, -1, + 1548, 1549, 1553, -1, 1550, 1472, 1546, -1, + 1550, 1548, 1472, -1, 1473, 1474, 1475, -1, + 1473, 1475, 1476, -1, 1473, 1476, 1474, -1, + 1556, 1554, 1545, -1, 1556, 1545, 1546, -1, + 1556, 1546, 1562, -1, 1555, 1562, 1558, -1, + 1555, 1558, 1553, -1, 1560, 1558, 1562, -1, + 1570, 1491, 1477, -1, 1570, 1568, 1491, -1, + 1570, 1477, 1478, -1, 1570, 1478, 1569, -1, + 1479, 1480, 1481, -1, 1479, 1483, 1482, -1, + 1479, 1482, 1484, -1, 1479, 1484, 1480, -1, + 1479, 1485, 1483, -1, 1479, 1481, 1485, -1, + 1564, 1569, 1486, -1, 1564, 1486, 1565, -1, + 1567, 1491, 1568, -1, 1487, 1488, 1489, -1, + 1487, 1490, 1488, -1, 1487, 1489, 1491, -1, + 1487, 1491, 1567, -1, 1487, 1566, 1490, -1, + 1487, 1567, 1566, -1, 1571, 1572, 1540, -1, + 1571, 1540, 1628, -1, 1499, 1492, 1493, -1, + 1499, 1493, 1497, -1, 1499, 1498, 1494, -1, + 1499, 1494, 1495, -1, 1499, 1495, 1496, -1, + 1499, 1496, 1492, -1, 1541, 1497, 1542, -1, + 1541, 1605, 1498, -1, 1541, 1499, 1497, -1, + 1541, 1498, 1499, -1, 1576, 1500, 1501, -1, + 1576, 1574, 1500, -1, 1576, 1501, 1505, -1, + 1576, 1505, 1577, -1, 1583, 1582, 1502, -1, + 1583, 1502, 1574, -1, 1583, 1575, 1586, -1, + 1583, 1574, 1575, -1, 1506, 1508, 1577, -1, + 1506, 1503, 1504, -1, 1506, 1504, 1588, -1, + 1506, 1505, 1503, -1, 1506, 1577, 1505, -1, + 1590, 1506, 1588, -1, 1590, 1508, 1506, -1, + 1590, 1593, 1509, -1, 1590, 1509, 1508, -1, + 1507, 1508, 1509, -1, 1507, 1509, 1510, -1, + 1507, 1511, 1579, -1, 1507, 1579, 1508, -1, + 1507, 1510, 1512, -1, 1507, 1512, 1511, -1, + 1513, 1514, 1515, -1, 1513, 1515, 1516, -1, + 1513, 1516, 1514, -1, 1517, 1519, 1518, -1, + 1517, 1518, 1596, -1, 1517, 1520, 1519, -1, + 1517, 1596, 1520, -1, 1598, 1597, 1521, -1, + 1598, 1521, 1522, -1, 1598, 1522, 1523, -1, + 1598, 1523, 1599, -1, 1602, 1524, 1601, -1, + 1602, 1525, 1524, -1, 1602, 1529, 1525, -1, + 1623, 1529, 1602, -1, 1526, 1528, 1527, -1, + 1526, 1527, 1529, -1, 1526, 1529, 1623, -1, + 1526, 1624, 1528, -1, 1526, 1623, 1624, -1, + 1530, 1532, 1531, -1, 1530, 1531, 1533, -1, + 1530, 1533, 1534, -1, 1530, 1534, 1535, -1, + 1530, 1535, 1532, -1, 1536, 1537, 1538, -1, + 1536, 1538, 1539, -1, 1536, 1540, 1537, -1, + 1536, 1539, 1540, -1, 1604, 1605, 1541, -1, + 1604, 1541, 1542, -1, 1604, 1542, 1645, -1, + 1604, 1645, 1638, -1, 1610, 1608, 1615, -1, + 1610, 1543, 1606, -1, 1610, 1544, 1543, -1, + 1610, 1615, 1544, -1, 1620, 1615, 1619, -1, + 1551, 1554, 1549, -1, 1551, 1545, 1554, -1, + 1551, 1546, 1545, -1, 1551, 1550, 1546, -1, + 1547, 1549, 1548, -1, 1547, 1548, 1550, -1, + 1547, 1551, 1549, -1, 1547, 1550, 1551, -1, + 1552, 1553, 1554, -1, 1552, 1555, 1553, -1, + 1552, 1554, 1556, -1, 1552, 1556, 1562, -1, + 1552, 1562, 1555, -1, 1557, 1559, 1558, -1, + 1557, 1558, 1560, -1, 1557, 1561, 1559, -1, + 1557, 1562, 1561, -1, 1557, 1560, 1562, -1, + 1563, 1564, 1565, -1, 1563, 1565, 1566, -1, + 1563, 1566, 1567, -1, 1563, 1567, 1568, -1, + 1563, 1569, 1564, -1, 1563, 1570, 1569, -1, + 1563, 1568, 1570, -1, 1630, 1571, 1628, -1, + 1630, 1628, 1627, -1, 1630, 1572, 1571, -1, + 1630, 1629, 1572, -1, 1643, 1638, 1645, -1, + 1573, 1575, 1574, -1, 1573, 1574, 1576, -1, + 1573, 1576, 1577, -1, 1573, 1578, 1575, -1, + 1573, 1577, 1579, -1, 1573, 1579, 1578, -1, + 1580, 1581, 1582, -1, 1580, 1582, 1583, -1, + 1580, 1584, 1581, -1, 1580, 1585, 1584, -1, + 1580, 1586, 1585, -1, 1580, 1583, 1586, -1, + 1587, 1588, 1589, -1, 1587, 1590, 1588, -1, + 1587, 1589, 1591, -1, 1587, 1591, 1592, -1, + 1587, 1593, 1590, -1, 1587, 1592, 1594, -1, + 1587, 1594, 1593, -1, 1595, 1596, 1597, -1, + 1595, 1597, 1598, -1, 1595, 1599, 1596, -1, + 1595, 1598, 1599, -1, 1625, 1600, 1626, -1, + 1625, 1601, 1600, -1, 1625, 1602, 1601, -1, + 1625, 1623, 1602, -1, 1603, 1638, 1653, -1, + 1603, 1653, 1637, -1, 1603, 1604, 1638, -1, + 1603, 1637, 1605, -1, 1603, 1605, 1604, -1, + 1639, 1638, 1643, -1, 1639, 1643, 1627, -1, + 1611, 1606, 1612, -1, 1611, 1610, 1606, -1, + 1607, 1609, 1608, -1, 1607, 1608, 1610, -1, + 1607, 1610, 1611, -1, 1607, 1611, 1612, -1, + 1607, 1613, 1609, -1, 1607, 1612, 1613, -1, + 1614, 1616, 1615, -1, 1614, 1615, 1620, -1, + 1614, 1621, 1616, -1, 1614, 1620, 1621, -1, + 1617, 1619, 1618, -1, 1617, 1620, 1619, -1, + 1617, 1618, 1621, -1, 1617, 1621, 1620, -1, + 1632, 1629, 1630, -1, 1642, 1630, 1627, -1, + 1642, 1627, 1643, -1, 1622, 1624, 1623, -1, + 1622, 1623, 1625, -1, 1622, 1626, 1624, -1, + 1622, 1625, 1626, -1, 1636, 1627, 1628, -1, + 1636, 1628, 1637, -1, 1636, 1639, 1627, -1, + 1651, 1638, 1639, -1, 1633, 1634, 1629, -1, + 1633, 1629, 1632, -1, 1644, 1630, 1642, -1, + 1644, 1647, 1631, -1, 1644, 1632, 1630, -1, + 1644, 1633, 1632, -1, 1644, 1631, 1634, -1, + 1644, 1634, 1633, -1, 1635, 1640, 1639, -1, + 1635, 1639, 1636, -1, 1635, 1636, 1637, -1, + 1635, 1637, 1653, -1, 1635, 1653, 1640, -1, + 1650, 1653, 1638, -1, 1650, 1638, 1651, -1, + 1652, 1639, 1640, -1, 1652, 1651, 1639, -1, + 1652, 1640, 1653, -1, 1641, 1642, 1643, -1, + 1641, 1644, 1642, -1, 1641, 1643, 1645, -1, + 1641, 1645, 1646, -1, 1641, 1647, 1644, -1, + 1641, 1646, 1648, -1, 1641, 1648, 1647, -1, + 1649, 1650, 1651, -1, 1649, 1651, 1652, -1, + 1649, 1653, 1650, -1, 1649, 1652, 1653, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT4_elbow.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT4_elbow.wrl new file mode 100644 index 0000000..2964643 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_LT4_elbow.wrl @@ -0,0 +1,3322 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_LT4_elbow____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 33.096802 -11.1516 -44.513, + 34.924999 49.0998 -36.7043, + 34.924999 51.388302 -34.871498, + -13.3939 55.465 33.835899, + 38.5 55.465 0.00010839496, + 31.6971 -14.6646 -44.513, + 32.393002 -13.0556 -46.417999, + -37.537701 55.465 -8.5540705, + -1.84317 15.1799 -56.707199, + 33.013302 55.465 -33.417801, + 34.924999 54.886501 -31.9491, + -33.4179 55.465 -22.8647, + -36.346001 55.465 -12.6969, + -33.484901 55.465 12.4298, + -38.5 55.465 0.00010839579, + -24.122101 53.865002 -41.410198, + -26.941999 41.7775 -47.8372, + 34.924999 6.3026121e-008 40.395, + 33.297401 -10.5376 -46.417999, + -24.1747 46.548698 42.673, + -21.6812 51.255699 41.5312, + 29.926701 55.465 33.417999, + 34.9244 37.106701 40.459202, + 34.875599 36.381901 40.946201, + 38.258701 46.924999 4.3041801, + -19.333401 55.465 40.510201, + 19.333401 55.465 40.510201, + -22.864901 55.465 38.623501, + 24.5602 45.8018 42.854198, + 22.322201 50.0672 41.8195, + 20.105499 54.107101 40.8396, + 22.864901 55.465 38.623501, + 30.924601 -16.230499 38.490002, + 31.298599 -15.4969 -46.417999, + 34.515701 -5.3312802 -46.417999, + 34.108501 -7.5078402 -44.513, + 33.910099 -8.3580999 38.490002, + 34.670399 -4.2097402 38.490002, + 6.0646601 -34.394402 40.395, + 4.2097402 -34.670399 38.490002, + 4.2056398 -34.639198 40.395, + 23.159599 -26.141701 38.490002, + 29.925699 -18.005699 -44.513, + 8.3580999 -33.910099 38.490002, + 9.0392599 -33.735001 40.395, + 9.3434296 -33.652 -44.513, + -38.473202 46.924999 -1.43725, + -27.869699 39.534901 -48.7995, + -28.236601 38.922401 -48.996799, + -0.61572099 15.279 -56.707199, + -2.62955 12.8804 -57.342201, + -32.834702 34.134102 -49.398102, + -32.696499 34.194901 -49.447701, + -6.9356499 8.4946299 -57.870201, + -34.924999 6.3526983e-008 40.395, + -38.258701 46.924999 4.3041801, + -38.473202 46.924999 1.43747, + -34.924999 55.465 28.1975, + -29.926701 55.465 33.417999, + -33.4179 55.465 29.9053, + -24.0506 54.386501 -41.103298, + -24.073 54.021198 -41.3344, + -27.141701 41.089298 -48.180801, + 34.924999 55.465 -31.452101, + 33.4179 55.465 22.865, + 22.864901 55.465 33.417999, + -12.8809 55.465 30.926399, + -32.596298 55.465 -14.871, + 34.779099 40.768501 38.307499, + 34.924999 47.674198 33.671501, + 34.924999 44.862598 35.544102, + 34.924999 52.416199 30.4097, + 34.924999 55.465 28.1975, + 34.924999 48.7262 32.970798, + 32.322498 55.465 31.146601, + 34.790199 40.293301 38.596298, + 34.782902 41.049301 38.126202, + 34.924999 37.301601 40.3386, + 34.924999 37.210098 40.395, + 34.924999 37.316101 40.329601, + 34.8908 38.2229 39.7981, + -27.139799 41.7845 43.4935, + 26.8508 42.1717 43.4604, + 27.7526 40.9944 43.542599, + -24.5602 45.8018 42.854198, + 25.472 44.212101 43.180801, + 22.805401 55.465 38.662201, + 25.271799 44.5266 43.129002, + 26.0219 43.348301 43.322899, + 34.006302 -7.9577799 -46.417999, + 34.720299 -3.7760601 -44.513, + 34.792099 -3.04391 40.395, + 38.473202 46.924999 1.43747, + 34.726799 34.735401 -47.5014, + 34.733501 30 -47.503899, + 34.346901 -6.0562901 40.946301, + 33.735001 -9.0392599 40.395, + 34.394402 -6.0646601 40.395, + 34.601398 -3.02723 41.4809, + 34.743999 -3.03971 40.946301, + 34.639198 -4.2056398 40.395, + 3.03971 -34.743999 40.946301, + 5.6502399 -34.464901 -44.513, + 26.141701 -23.159599 38.490002, + 28.6089 -20.0322 40.395, + 28.742701 -19.839701 38.490002, + 30.245899 -17.4625 40.395, + 27.803499 -21.1357 -44.513, + 22.4494 -26.754101 40.395, + 16.230499 -30.924601 38.490002, + 12.9271 -32.4445 -44.513, + -31.6971 -14.6646 -44.513, + -33.910099 -8.3580999 38.490002, + -34.108501 -7.5078402 -44.513, + -34.006302 -7.9577799 -46.417999, + 34.205799 -6.0314102 41.4809, + 33.975498 -5.9907999 41.982498, + 33.3241 -8.9291601 41.982498, + 33.549999 -8.9897003 41.4809, + 33.6884 -9.0267696 40.946301, + 32.638802 -11.8796 41.4809, + 32.6395 -12.378 40.395, + 31.6091 -14.7396 40.946301, + 31.6528 -14.7599 40.395, + 32.655399 -12.3846 38.490002, + 32.818802 -11.9451 40.395, + 32.773399 -11.9286 40.946301, + 22.8405 -22.8405 43.521801, + -34.515701 -5.3312802 -46.417999, + -34.720299 -3.7760601 -44.513, + -33.959301 -7.9467902 -46.969299, + -32.8918 -10.4092 -48.005501, + -33.114799 -10.4798 -47.503899, + -34.876801 30 -46.969299, + -38.258701 46.924999 -4.3039598, + -34.924999 6.2868111e-008 -46.417999, + -34.890099 35.5345 -46.861401, + -34.924 35.931198 -46.434502, + -32.965698 34.076302 -49.351002, + 33.790901 30 -48.850201, + 32.301201 34.431198 -49.544102, + 6.5490999 5.802 -58.290901, + 6.99473 5.2561998 -58.290901, + 30.8969 35.714199 -49.561001, + -30.383801 1.2517101 -51.5648, + -15.0933 2.4529099 -56.707199, + -12.9758 2.1087699 -57.342201, + -14.847 3.6594601 -56.707199, + -15.2418 1.23044 -56.707199, + -32.677502 34.2033 -49.454498, + -26.432699 53.865002 -39.974899, + -26.312099 55.465 -38.944401, + -10.9308 0.882429 -57.870201, + -22.864901 55.465 -38.944401, + -34.887699 35.701 -46.847099, + -34.883801 35.638699 -46.894901, + -34.670399 -4.2097402 38.490002, + -34.394402 -6.0646601 40.395, + -34.743999 -3.03971 40.946301, + -34.792099 -3.04391 40.395, + -34.639198 -4.2056398 40.395, + -34.924999 47.707802 33.6572, + -34.924999 51.7076 30.9105, + -34.492699 35.184502 41.9944, + -34.499599 6.3413815e-008 41.982498, + 24.0446 54.199902 -41.231499, + -24.042999 54.229099 -41.213001, + -24.062799 54.066898 -41.309799, + 27.1511 41.062199 -48.193401, + 34.924999 55.465 -21.0737, + 33.4179 55.465 -22.8647, + 33.484901 55.465 -14.358, + 34.924999 55.465 -22.8647, + 38.258701 55.465 4.3041801, + 12.6439 55.465 -31.0366, + 32.3358 55.465 -11.8938, + -12.0949 55.465 -33.085701, + 13.3939 55.465 -33.835701, + 34.876801 6.2713305e-008 40.946301, + 34.8741 36.359798 40.960999, + 34.806301 42.367802 37.268002, + 34.798698 42.232899 37.361698, + 34.886902 43.8083 36.266899, + 34.877899 38.564499 39.597801, + -4.7707601 39.814201 43.57, + 15.6176 39.814201 43.57, + -28.245199 40.385201 43.563599, + -33.356499 34.7929 43.133499, + -33.384201 34.784401 43.117199, + -25.4718 44.213501 43.180099, + -26.1553 43.151299 43.3498, + -22.805401 55.465 38.662201, + -25.2946 44.488701 43.1362, + 34.872299 34.735401 -46.9683, + 34.924999 46.207901 -38.989601, + 34.924999 47.7061 -37.8204, + 32.410801 55.465 -34.037201, + 34.334702 41.4025 -43.118698, + 27.8512 53.865002 -38.999901, + 33.959301 -7.9467902 -46.969299, + 33.2514 -10.523 -46.969299, + -4.2097402 -34.670399 38.490002, + 6.0562901 -34.346901 40.946301, + 24.6957 -24.6957 40.395, + 30.0205 -17.8473 -46.417999, + 5.6465502 -34.441101 -46.417999, + 6.6494098 -34.286201 -46.417999, + 1.33772 -34.899399 -46.417999, + 1.8908 -34.873798 -44.513, + 4.0053201 -34.694599 -46.417999, + 7.4925268e-008 -34.924999 38.490002, + 7.7775802e-008 -34.924999 40.395, + 3.04391 -34.792099 40.395, + 17.4625 -30.245899 40.395, + 19.839701 -28.742701 38.490002, + 22.610001 -26.6185 -44.513, + 16.3538 -30.845699 -46.417999, + 16.3592 -30.856701 -44.513, + 16.684401 -30.681999 -46.417999, + 11.8052 -32.869301 -46.417999, + 9.2544804 -33.676601 -46.417999, + 14.089 -30.214001 43.1446, + 14.7599 -31.6528 40.395, + 12.3846 -32.655399 38.490002, + -14.089 -30.214001 43.1446, + -5.8677201 -33.2775 42.827202, + -12.9271 -32.4445 -44.513, + -30.924601 -16.230499 38.490002, + -31.298599 -15.4969 -46.417999, + -32.348301 -13.0375 -46.969299, + -32.215401 -12.984 -47.503899, + -33.2514 -10.523 -46.969299, + -34.346901 -6.0562901 40.946301, + -33.735001 -9.0392599 40.395, + -33.297401 -10.5376 -46.417999, + -33.096802 -11.1516 -44.513, + -32.393002 -13.0556 -46.417999, + 33.017502 -8.8470001 42.435799, + 8.2174997 -30.6681 43.57, + 31.2673 -14.5802 41.982498, + 30.979601 -14.446 42.435799, + 32.419102 -11.7996 41.982498, + 30.204201 -17.4384 40.946301, + 31.4793 -14.679 41.4809, + 31.7355 0.26886201 43.619999, + 31.6134 0.81519699 43.619999, + 31.3283 36.631802 43.57, + 29.2974 39.130299 43.57, + 31.75 36.112999 43.57, + 16.417999 -28.436701 43.378502, + 16.6688 -28.871099 43.1446, + 18.5273 -26.4597 43.521801, + 18.8339 -26.8976 43.378502, + 20.762899 -24.744301 43.521801, + -33.013401 55.465 -33.417801, + -33.4179 55.465 -33.0019, + -34.924999 55.465 -31.452101, + -28.0054 -12.3057 -51.493999, + -27.0324 -14.3172 -51.493999, + -28.955099 -10.2734 -51.411999, + -28.127899 -12.3595 -51.411999, + -27.1507 -14.3798 -51.411999, + -26.028601 -16.323299 -51.411999, + -34.924301 35.508301 -46.452099, + -34.924099 35.7318 -46.449799, + -34.890099 34.735401 -46.887402, + -34.924702 34.735401 -46.4603, + 30.2194 3.69802 -51.5541, + 30.4387 1.12024 -51.547501, + 30.408701 1.48228 -51.5541, + 30.3978 1.22357 -51.5611, + 26.6819 55.465 -38.692001, + 32.348301 -13.0375 -46.969299, + 31.2554 -15.4755 -46.969299, + 1.0546401 -8.6857204 -58.290901, + -32.3251 34.413799 -49.540501, + -12.764 3.14605 -57.342201, + 10.9308 -0.882429 -57.870201, + 11.6402 6.1092701 -57.342201, + 15.0933 2.4529099 -56.707199, + 15.2418 1.23044 -56.707199, + 11.1109 7.0261102 -57.342201, + 12.0941 5.1528101 -57.342201, + 10.6477 -2.6244299 -57.870201, + 10.402 -3.4727099 -57.870201, + 12.764 -3.14605 -57.342201, + 12.4695 -4.16293 -57.342201, + 10.8244 -1.75913 -57.870201, + 15.2418 -1.23044 -56.707199, + 12.9758 -2.1087699 -57.342201, + 31.9088 34.735401 -49.589001, + 8.2084703 7.2720699 -57.870201, + 31.75 34.8792 -49.5923, + 8.7670097 6.5879798 -57.870201, + 32.283699 34.442402 -49.547798, + 25.7321 55.4342 -39.351299, + 1.84317 15.1799 -56.707199, + 0.615722 15.279 -56.707199, + 5.6356101 11.8768 -57.342201, + 0.529338 13.1354 -57.342201, + 3.0510399 10.5334 -57.870201, + 24.6742 55.140701 -40.221699, + 29.567301 37.167301 -49.389599, + 4.6616502 12.2918 -57.342201, + 30.100401 36.5536 -49.482399, + -30.507999 0.95146197 -51.525101, + -30.438299 1.11999 -51.547401, + -30.300501 2.96105 -51.5541, + -30.4447 2.9751501 -51.493999, + -5.6356101 11.8768 -57.342201, + -4.6616502 12.2918 -57.342201, + 24.3314 54.8988 -40.592999, + -11.6402 6.1092701 -57.342201, + -7.5966902 7.9089999 -57.870201, + -25.687901 55.429001 -39.383701, + -24.6784 55.1381 -40.2206, + -24.5676 55.085701 -40.324402, + 24.7139 55.1651 -40.181, + -13.1034 1.05782 -57.342201, + -15.0933 -2.4529099 -56.707199, + -10.6477 2.6244299 -57.870201, + -8.7495098 6.5193603e-008 -58.290901, + 33.099899 34.032299 -49.291801, + 26.312099 55.465 -38.944401, + 33.140999 34.020901 -49.272099, + 32.836399 34.127998 -49.401402, + 26.441999 53.865002 -39.9687, + -29.643801 55.465 -36.472401, + 1.5845799 -13.0502 -57.342201, + 0.529338 -13.1354 -57.342201, + 2.62955 -12.8804 -57.342201, + 0.44157201 -10.9575 -57.870201, + 1.3218499 -10.8864 -57.870201, + -0.35230801 -8.7424202 -58.290901, + -0.44157299 -10.9575 -57.870201, + 0.35230801 -8.7424202 -58.290901, + 0.26172799 -6.49473 -58.603001, + -0.26172999 -6.49473 -58.603001, + -0.61572099 -15.279 -56.707199, + -0.529338 -13.1354 -57.342201, + -34.882 36.463001 40.8909, + -34.876801 6.2202965e-008 40.946301, + -34.801998 35.954201 41.2701, + -34.577599 35.3312 41.8358, + -34.566898 35.306198 41.859798, + -34.733501 6.5214863e-008 41.4809, + -34.724602 35.6749 41.505199, + -34.1805 34.869202 42.437901, + -34.3423 35.0005 42.228199, + -33.9939 34.7827 42.639, + -34.112598 34.8298 42.516102, + -33.9524 34.7663 42.6819, + -34.924999 47.597698 33.7328, + -32.322498 55.465 31.146601, + -27.743799 39.7449 -48.7318, + -27.423201 40.386501 -48.487801, + 34.768002 35.819 41.3811, + 34.733501 6.5317181e-008 41.4809, + 30.065201 -2.3633599 43.619999, + 18.2111 -26.008101 43.57, + -31.4793 -14.679 41.4809, + -30.214001 -14.089 43.1446, + -32.418999 -11.7996 41.982498, + -30.624901 -14.2806 42.827202, + -31.2673 -14.5802 41.982498, + -32.861 35.037399 43.369301, + -33.111698 34.8927 43.263199, + -33.761101 34.735199 42.851799, + -33.615398 34.741402 42.962502, + -33.7854 34.736801 42.831799, + 34.495899 39.390099 -44.469799, + 34.570099 38.9053 -44.7663, + 34.373798 40.454201 -43.785801, + 30.5611 51.0522 -38.999901, + 34.8894 35.6964 -46.849201, + 34.890099 35.5345 -46.861401, + 34.891899 35.711102 -46.8367, + 34.800701 35.173901 -47.290199, + 38.258701 46.924999 -4.3039598, + 38.258701 55.465 -4.3039598, + 38.473202 46.924999 -1.43725, + 34.4561 42.999298 -41.8335, + 34.481701 43.212101 -41.653599, + 29.6378 55.465 -36.4772, + 34.8237 37.322399 -45.7234, + 34.372299 42.303902 -42.421001, + 34.724899 37.9743 -45.325298, + 34.179798 34.162899 -48.456799, + 34.144901 34.239799 -48.4272, + 34.243698 34.2033 -48.383202, + 34.182201 30 -48.4589, + 33.790901 6.5444596e-008 -48.850201, + 34.042801 34.076302 -48.6143, + 33.6917 -2.5866599 -48.850201, + 34.695599 -3.77321 -46.417999, + 34.182201 6.5954076e-008 -48.4589, + 34.081902 -2.6166201 -48.4589, + 34.499599 30 -48.005501, + 34.499599 6.1610365e-008 -48.005501, + 34.647701 34.735401 -47.715599, + 34.451599 34.413799 -48.085999, + -9.0392599 -33.735001 40.395, + -8.3580999 -33.910099 38.490002, + -6.0646601 -34.394402 40.395, + -9.3434296 -33.652 -44.513, + -1.8908 -34.873798 -44.513, + -3.04391 -34.792099 40.395, + -4.2056398 -34.639198 40.395, + -6.0562901 -34.346901 40.946301, + -3.03971 -34.743999 40.946301, + 13.8771 -29.759399 43.378502, + 11.9451 -32.818802 40.395, + 12.378 -32.6395 40.395, + 6.0314102 -34.205799 41.4809, + 5.9907999 -33.975498 41.982498, + 30.0035 -5.1649499 -51.5541, + 14.847 -3.6594601 -56.707199, + 15.0933 -2.4529099 -56.707199, + 23.2365 -26.0734 -46.417999, + 22.596001 -26.601601 -46.417999, + 29.979 -17.822701 -46.969299, + 28.5662 -20.093 -46.417999, + 28.526699 -20.0653 -46.969299, + 19.381599 -27.6798 42.827202, + 24.560301 -24.560301 41.4809, + 24.394899 -24.394899 41.982498, + 22.4184 -26.717199 40.946301, + 20.0322 -28.6089 40.395, + 17.4384 -30.204201 40.946301, + 19.8346 -28.7348 40.395, + 26.7171 -22.4184 40.946301, + 26.754101 -22.4494 40.395, + 24.6616 -24.6616 40.946301, + 19.5877 -28.890301 -46.417999, + 18.9841 -29.3148 -46.417999, + 21.1724 -27.7756 -46.417999, + 19.599501 -28.907 -44.513, + 14.267 -31.825199 -46.969299, + 14.2867 -31.8692 -46.417999, + 12.9176 -32.421001 -46.417999, + 11.7889 -32.823898 -46.969299, + 11.7405 -32.689098 -47.503899, + -16.417999 -28.436701 43.378502, + -16.6688 -28.871099 43.1446, + -13.8771 -29.759399 43.378502, + -13.6511 -29.275 43.521801, + -11.2305 -30.8557 43.378502, + -8.6283798 -32.2015 43.1446, + -11.4021 -31.327 43.1446, + -8.49856 -31.7171 43.378502, + -22.596001 -26.601601 -46.417999, + -21.1724 -27.7756 -46.417999, + -11.8052 -32.869301 -46.417999, + -9.2544804 -33.676601 -46.417999, + -6.6402302 -34.2388 -46.969299, + -5.6465502 -34.441101 -46.417999, + -4.0053201 -34.694599 -46.417999, + -6.6494098 -34.286201 -46.417999, + -5.6502399 -34.464901 -44.513, + -31.127001 -15.412 -47.503899, + -23.159599 -26.141701 38.490002, + -22.610001 -26.6185 -44.513, + -26.141701 -23.159599 38.490002, + -27.803499 -21.1357 -44.513, + -32.6395 -12.378 40.395, + -31.6528 -14.7599 40.395, + -32.655399 -12.3846 38.490002, + -32.818802 -11.9451 40.395, + -31.6091 -14.7396 40.946301, + -32.773399 -11.9286 40.946301, + 32.1208 -11.691 42.435799, + 30.624901 -14.2806 42.827202, + 31.753 -11.5572 42.827202, + 32.166302 35.632301 43.542599, + 32.562901 35.259499 43.464199, + 33.0784 34.9095 43.278702, + 33.293098 34.814499 43.1698, + 32.849998 35.044701 43.373402, + -30.3347 -2.2524199 43.619999, + -29.806299 -2.43732 43.619999, + -15.6176 -27.630301 43.57, + -15.875 -27.4963 43.57, + 29.5189 -2.4855001 43.619999, + 31.267599 -5.51333 43.57, + 29.6026 -17.091101 42.435799, + 29.8776 -17.2498 41.982498, + 29.2637 -16.895399 42.827202, + 26.428301 -22.1759 41.982498, + 28.452 -19.9223 41.4809, + 30.080099 -17.3668 41.4809, + 28.569401 -20.004499 40.946301, + 28.260401 -19.7882 41.982498, + 26.607401 -22.3263 41.4809, + 26.8976 -18.8339 43.378502, + 26.4597 -18.5273 43.521801, + 24.744301 -20.762899 43.521801, + 11.0477 -30.3533 43.521801, + 10.8591 -29.835199 43.57, + 13.6511 -29.275 43.521801, + -34.916599 45.924 -39.2169, + -34.924999 46.194698 -38.999901, + -34.924999 47.7061 -37.8204, + -34.924999 46.207901 -38.989601, + -32.413502 55.465 -34.034599, + -34.924999 51.860001 -34.485001, + -38.258701 55.465 -4.3039598, + -32.3353 49.123299 -38.999901, + -34.822498 -2.67348 -46.417999, + -34.695599 -3.77321 -46.417999, + -29.382 -17.467699 -48.4589, + -29.045601 -17.267799 -48.850201, + -29.6548 -17.629999 -48.005501, + -31.7041 -12.7779 -48.4589, + -31.341101 -12.6316 -48.850201, + -31.998501 -12.8966 -48.005501, + -30.9174 -15.3082 -48.005501, + -30.6329 -15.1673 -48.4589, + -30.2822 -14.9937 -48.850201, + -29.498699 -8.0969601 -51.493999, + -29.868799 -5.8940301 -51.5541, + -25.9153 -16.252199 -51.493999, + -33.4921 33.966099 -49.072399, + -30.2194 -3.69802 -51.5541, + -30.011101 -5.9221001 -51.493999, + 33.789501 33.9939 -48.848499, + 33.841099 34.002102 -48.807098, + 33.624298 33.9678 -48.980801, + 27.206301 53.865002 -39.452499, + 33.5923 33.966099 -49.003899, + 33.3745 33.975399 -49.146, + 9.6709499 -11.8448 -56.707199, + 4.2543201 -14.6876 -56.707199, + 10.0889 -4.29846 -57.870201, + 9.7102699 -5.0963402 -57.870201, + 4.6616502 -12.2918 -57.342201, + 5.42239 -14.2977 -56.707199, + 3.0510399 -10.5334 -57.870201, + 2.1935599 -10.7448 -57.870201, + 3.65746 -12.627 -57.342201, + 9.1065798 -9.4809599 -57.342201, + 6.57302 -11.3848 -57.342201, + 5.4832001 -9.49718 -57.870201, + 5.6356101 -11.8768 -57.342201, + 11.2213 -28.301399 -51.5541, + 6.1654902 -2.0583401 -58.603001, + 8.0493698 -3.4295199 -58.290901, + 8.2992296 -2.77069 -58.290901, + 6.31112 1.55555 -58.603001, + 13.146 6.448952e-008 -57.342201, + 13.1034 1.05782 -57.342201, + 13.1034 -1.05782 -57.342201, + 12.764 3.14605 -57.342201, + 10.6477 2.6244299 -57.870201, + 12.4695 4.16293 -57.342201, + 12.9758 2.1087699 -57.342201, + 14.847 3.6594601 -56.707199, + 32.5536 34.270599 -49.489601, + 9.7102699 5.0963402 -57.870201, + 9.2686901 5.8611698 -57.870201, + 7.395 4.6763101 -58.290901, + 5.4937401 3.47403 -58.603001, + 8.4952698 2.0939 -58.290901, + 10.402 3.4727099 -57.870201, + 11.6402 -6.1092701 -57.342201, + 6.4158301 -1.04267 -58.603001, + 8.4952698 -2.0939 -58.290901, + 8.6362104 -1.40352 -58.290901, + 6.47892 -0.52303302 -58.603001, + 8.7211399 -0.70404297 -58.290901, + 28.9431 37.929199 -49.249001, + 1.5845799 13.0502 -57.342201, + 2.62955 12.8804 -57.342201, + 28.4184 38.650501 -49.073101, + 3.65746 12.627 -57.342201, + 29.3657 37.399399 -49.3545, + 24.112101 54.602402 -40.9226, + 24.061899 54.449299 -41.0546, + 24.0424 54.284599 -41.176201, + 6.9356499 8.4946299 -57.870201, + 7.5966902 7.9089999 -57.870201, + 4.5027099 4.68782 -58.603001, + 6.0609999 6.3101702 -58.290901, + 4.8653202 4.3102999 -58.603001, + 5.5335898 6.77742 -58.290901, + -0.26172999 6.49473 -58.603001, + -30.4387 -1.12024 -51.547501, + -30.3978 -1.22357 -51.5611, + -3.0510399 10.5334 -57.870201, + -3.65746 12.627 -57.342201, + -5.4832001 9.49718 -57.870201, + -4.70121 9.9076004 -57.870201, + -28.8255 38.084 -49.2145, + -24.0919 54.552799 -40.967701, + 24.1127 54.604401 -40.920898, + -24.326799 54.900799 -40.594601, + -30.000401 36.664101 -49.468498, + -24.493 55.037601 -40.402199, + 24.420401 54.984402 -40.481998, + -12.0941 5.1528101 -57.342201, + -12.4695 4.16293 -57.342201, + -8.2084703 7.2720699 -57.870201, + -25.1227 55.318298 -39.822201, + -30.890499 35.720699 -49.5606, + -31.75 34.8792 -49.5923, + -25.130199 55.319801 -39.816399, + -24.9233 55.253799 -39.991199, + 25.1106 55.314899 -39.832199, + -10.0889 -4.29846 -57.870201, + -12.0941 -5.1528101 -57.342201, + -13.1034 -1.05782 -57.342201, + -10.9308 -0.882429 -57.870201, + -10.9664 6.4345471e-008 -57.870201, + -13.146 6.2771413e-008 -57.342201, + -15.2418 -1.23044 -56.707199, + -15.2914 6.421336e-008 -56.707199, + -8.7211399 -0.70404297 -58.290901, + -8.6362104 -1.40352 -58.290901, + -5.7554598 -3.0207 -58.603001, + -8.6362104 1.40352 -58.290901, + -10.8244 1.75913 -57.870201, + -6.31112 1.55555 -58.603001, + -8.2992296 2.77069 -58.290901, + -8.0493698 3.4295199 -58.290901, + -6.1654902 2.0583401 -58.603001, + -8.4952698 2.0939 -58.290901, + -10.402 3.4727099 -57.870201, + -10.0889 4.29846 -57.870201, + -34.923698 36.2719 -46.408401, + -34.797699 44.9804 -40.046299, + -34.851101 45.297001 -39.757801, + -34.82 37.318802 -45.728699, + -29.754499 51.906799 -38.999901, + -34.3363 41.584202 -42.983299, + -34.391499 42.512699 -42.250099, + 3.05866 -14.9823 -56.707199, + 6.5079899 -33.5569 -48.4589, + 8.9539499 -32.582901 -48.850201, + 9.2417002 -33.630001 -46.969299, + 6.6402302 -34.2388 -46.969299, + 3.99979 -34.646702 -46.969299, + 3.8752501 -33.567902 -48.850201, + 6.4334798 -33.172798 -48.850201, + 3.9565401 -34.271999 -48.005501, + 3.9833601 -34.504398 -47.503899, + 3.92013 -33.956699 -48.4589, + -4.5027099 -4.68782 -58.603001, + -5.1963801 -3.90482 -58.603001, + -6.5490999 -5.802 -58.290901, + -4.8653202 -4.3102999 -58.603001, + -11.4457 -10.14 -56.707199, + -1.84317 -15.1799 -56.707199, + -8.9539499 -32.582901 -48.850201, + -3.75085 -7.9047499 -58.290901, + -3.05866 -14.9823 -56.707199, + -20.038799 -22.920099 -51.5541, + -11.5542 -32.1702 -48.4589, + -11.4219 -31.801901 -48.850201, + -16.230499 -30.924601 38.490002, + -11.6402 -6.1092701 -57.342201, + -34.924999 37.210098 40.395, + -34.895401 36.548401 40.827301, + -34.779598 41.562199 37.805698, + -34.797699 40.0784 38.7243, + -34.817902 39.699299 38.942902, + -34.809101 42.367298 37.2649, + -29.3811 55.465 33.935299, + -34.7915 42.0373 37.493, + -34.885799 38.4268 39.676399, + 27.403099 40.6563 -48.320202, + 27.4221 40.389099 -48.486698, + 26.941999 41.7775 -47.8372, + 27.5623 40.0937 -48.603298, + 24.069 54.038101 -41.325401, + 24.122101 53.865002 -41.410198, + 27.9566 39.371498 -48.858601, + 34.3442 35.5616 41.888802, + 15.6176 -27.630301 43.57, + 13.4181 -28.775299 43.57, + 15.875 -27.4963 43.57, + 16.1507 -27.973801 43.521801, + -27.482201 -1.7677701 43.619999, + -31.3668 -1.33008 43.619999, + -26.2001 55.465 36.447399, + -29.25 2.5 43.619999, + -30.808701 1.9545799 43.619999, + -28.260401 -19.7882 41.982498, + -29.6026 -17.091101 42.435799, + -30.979601 -14.446 42.435799, + -29.8776 -17.2498 41.982498, + -26.008101 -18.2111 43.57, + -22.8405 -22.8405 43.521801, + -21.106501 -25.153799 43.378502, + -23.2185 -23.2185 43.378502, + -28.871099 -16.6688 43.1446, + -32.638802 -11.8796 41.4809, + -33.6884 -9.0267696 40.946301, + -32.536999 35.2813 43.470901, + -32.245998 35.5569 43.527199, + -32.1661 35.6325 43.542599, + -34.182201 6.3216284e-008 42.435799, + -34.309101 6.1636328e-008 42.254601, + -33.6096 6.5281313e-008 42.954102, + -33.790798 6.1519287e-008 42.827202, + -33.576801 34.743 42.991798, + 34.924999 46.194698 -38.999901, + 34.923698 36.2719 -46.408401, + 28.3666 53.342999 -38.999901, + 30.303301 51.3269 -38.999901, + 34.876801 6.2170528e-008 -46.969299, + 34.822498 -2.67348 -46.417999, + 34.924999 6.253871e-008 -46.417999, + 34.733501 6.2990907e-008 -47.503899, + 34.876801 30 -46.969299, + 34.796101 34.735401 -47.313499, + 34.890099 34.735401 -46.887402, + 34.910198 35.929901 -46.665501, + 33.781601 -5.2178898 -48.4589, + 34.3265 -5.3020501 -47.503899, + 33.819901 -7.9141598 -47.503899, + 34.467999 -5.3239102 -46.969299, + 34.095299 -5.2663398 -48.005501, + 34.774399 -2.66979 -46.969299, + 34.631599 -2.6588299 -47.503899, + 34.398399 -2.6409199 -48.005501, + -6.0314102 -34.205799 41.4809, + -5.9907999 -33.975498 41.982498, + 7.8662268e-008 -34.733501 41.4809, + -3.02723 -34.601398 41.4809, + 7.9287062e-008 -34.876801 40.946301, + 3.02723 -34.601398 41.4809, + 7.7397218e-008 -34.499599 41.982498, + 3.00684 -34.368401 41.982498, + 8.49856 -31.7171 43.378502, + 11.2305 -30.8557 43.378502, + 8.6283798 -32.2015 43.1446, + 5.8677201 -33.2775 42.827202, + 7.5215766e-008 -33.790798 42.827202, + 2.9791701 -34.052101 42.435799, + 5.9356699 -33.662899 42.435799, + 8.8470001 -33.017502 42.435799, + 11.8796 -32.638802 41.4809, + 11.7996 -32.418999 41.982498, + 8.9291601 -33.3241 41.982498, + 8.9897003 -33.549999 41.4809, + 11.9286 -32.773399 40.946301, + 9.0267696 -33.6884 40.946301, + 14.679 -31.4793 41.4809, + 14.7396 -31.6091 40.946301, + 33.592098 -7.8608599 -48.005501, + 33.283001 -7.7885299 -48.4589, + 27.6385 -19.4405 -48.850201, + 30.2782 -5.2122402 -51.411999, + 30.5779 -2.9881699 -51.411999, + 33.394798 -5.1581502 -48.850201, + 32.902 -7.6993599 -48.850201, + 25.348301 -24.0116 -46.417999, + 25.129499 -24.1847 -46.969299, + 26.9443 -22.2208 -46.417999, + 25.1642 -24.2181 -46.417999, + 25.3554 -24.0179 -44.513, + 22.7423 -25.518801 -48.4589, + 21.1432 -27.7372 -46.969299, + 18.957899 -29.2743 -46.969299, + 29.8559 -17.7495 -47.503899, + 26.371201 -21.748199 -48.4589, + 26.0693 -21.499201 -48.850201, + 24.629 -23.702999 -48.4589, + 24.8577 -23.923201 -48.005501, + 18.899099 -23.868601 -51.5541, + 22.375999 -21.053499 -51.411999, + 22.481899 -25.2267 -48.850201, + 24.347 -23.4317 -48.850201, + 23.204399 -26.037399 -46.969299, + 26.796499 -22.0989 -47.503899, + 26.907 -22.1901 -46.969299, + 28.409599 -19.9828 -47.503899, + 26.6161 -21.9501 -48.005501, + 25.0263 -24.0854 -47.503899, + 26.185101 -21.971901 42.435799, + 27.3085 -19.121599 43.1446, + 27.6798 -19.381599 42.827202, + 28.000401 -19.6061 42.435799, + 25.153799 -21.106501 43.378502, + 25.538 -21.4289 43.1446, + 23.2185 -23.2185 43.378502, + 21.971901 -26.185101 42.435799, + 22.1759 -26.428301 41.982498, + 19.6061 -28.000401 42.435799, + 19.9223 -28.452 41.4809, + 22.3263 -26.607401 41.4809, + 19.7882 -28.260401 41.982498, + 20.004499 -28.569401 40.946301, + 17.3668 -30.080099 41.4809, + 1.2942801 -33.766102 -48.850201, + 13.9829 -31.191401 -48.4589, + 14.1127 -31.481001 -48.005501, + 11.5542 -32.1702 -48.4589, + 9.1254597 -29.045 -51.5541, + 9.1417599 -33.266399 -48.005501, + 11.6615 -32.469002 -48.005501, + 9.2037401 -33.491901 -47.503899, + 9.0576496 -32.9603 -48.4589, + 6.5684199 -33.868599 -48.005501, + 6.6129498 -34.098202 -47.503899, + -10.8591 -29.835199 43.57, + -13.4181 -28.775299 43.57, + -11.0477 -30.3533 43.521801, + -8.2174997 -30.6681 43.57, + -30.075701 -2.35971 43.619999, + -8.9897003 -33.549999 41.4809, + -19.599501 -28.907 -44.513, + -19.8346 -28.7348 40.395, + -17.4625 -30.245899 40.395, + -19.839701 -28.742701 38.490002, + -27.958599 -19.665701 -48.4589, + -27.6385 -19.4405 -48.850201, + -24.767599 -18.179701 -51.411999, + -9.2417002 -33.630001 -46.969299, + -6.5079899 -33.5569 -48.4589, + -1.2942801 -33.766102 -48.850201, + -29.979 -17.822701 -46.969299, + -29.8559 -17.7495 -47.503899, + -28.526699 -20.0653 -46.969299, + -30.0205 -17.8473 -46.417999, + -31.2554 -15.4755 -46.969299, + -24.394899 -24.394899 41.982498, + -26.428301 -22.1759 41.982498, + -25.3554 -24.0179 -44.513, + -28.742701 -19.839701 38.490002, + -29.925699 -18.005699 -44.513, + -30.245899 -17.4625 40.395, + -28.5662 -20.093 -46.417999, + 29.759399 -13.8771 43.378502, + 30.214001 -14.089 43.1446, + 31.327 -11.4021 43.1446, + 28.436701 -16.417999 43.378502, + 28.871099 -16.6688 43.1446, + 30.3533 -11.0477 43.521801, + 30.8557 -11.2305 43.378502, + 29.275 -13.6511 43.521801, + 31.200701 -8.3601999 43.521801, + 31.7171 -8.49856 43.378502, + 7.8778257e-008 -31.75 43.57, + -8.3601999 -31.200701 43.521801, + 22.4506 -22.4506 43.57, + 20.408501 -24.321899 43.57, + 27.973801 -16.1507 43.521801, + 29.835199 -10.8591 43.57, + 30.6681 -8.2174997 43.57, + 31.684799 -0.56713498 43.619999, + 30.324699 -2.25722 43.619999, + 31.5072 1.07468 43.619999, + 31.3727 1.32065 43.619999, + 31.6898 0.54545897 43.619999, + 31.497601 -1.09471 43.619999, + 27.630301 -15.6176 43.57, + 28.775299 -13.4181 43.57, + 27.4963 -15.875 43.57, + -34.764999 35.0438 -47.409599, + -34.796101 34.735401 -47.313499, + -34.733501 30 -47.503899, + -34.863098 35.487202 -47.019199, + -34.791801 35.165199 -47.302799, + -34.733501 6.1983499e-008 -47.503899, + -34.876801 6.5072356e-008 -46.969299, + -28.692301 -10.1802 -51.5541, + -29.3589 -8.0585899 -51.5541, + -28.829 -10.2286 -51.493999, + -14.5044 -4.8422799 -56.707199, + -14.0677 -5.9937 -56.707199, + -27.8727 -12.2474 -51.5541, + 30.558001 0.75038099 -51.503601, + 30.553499 1.4893399 -51.493999, + 30.5201 0.91436601 -51.520401, + 16.258499 -25.713499 -51.5611, + 8.6864796 -12.5845 -56.707199, + 5.7554598 -3.0207 -58.603001, + 6.31112 -1.55555 -58.603001, + 5.9798698 -2.54778 -58.603001, + 7.7473102 -4.0661001 -58.290901, + 6.0609999 -6.3101702 -58.290901, + 4.5027099 -4.68782 -58.603001, + 6.5490999 -5.802 -58.290901, + 8.7670097 -6.5879798 -57.870201, + 8.2084703 -7.2720699 -57.870201, + 9.8399496 -8.7174397 -57.342201, + 10.5095 -7.8973799 -57.342201, + 9.2686901 -5.8611698 -57.870201, + 7.395 -4.6763101 -58.290901, + 6.5552902 -13.815 -56.707199, + 6.9356499 -8.4946299 -57.870201, + 5.5335898 -6.77742 -58.290901, + 6.22963 -9.0251703 -57.870201, + 7.5966902 -7.9089999 -57.870201, + 8.3141499 -10.183 -57.342201, + 7.4678001 -10.819 -57.342201, + 1.3001699 -6.3686399 -58.603001, + 2.30493 -6.07761 -58.603001, + 2.4342699 -8.4040604 -58.290901, + 1.7501301 -8.57269 -58.290901, + 4.70121 -9.9076004 -57.870201, + 3.1026199 -8.1809397 -58.290901, + 3.8887401 -10.2538 -57.870201, + 4.3747602 -7.5773001 -58.290901, + 2.7865 -5.8724298 -58.603001, + 3.75085 -7.9047499 -58.290901, + -1.0546401 -8.6857204 -58.290901, + -1.3218499 -10.8864 -57.870201, + -1.5845799 -13.0502 -57.342201, + 11.324 -28.560499 -51.411999, + 11.2747 -28.436199 -51.493999, + 9.2090197 -29.311001 -51.411999, + 11.4219 -31.801901 -48.850201, + 13.8228 -30.834299 -48.850201, + 13.3786 -27.657801 -51.411999, + 8.6362104 1.40352 -58.290901, + 8.7495098 6.1771146e-008 -58.290901, + 10.9664 6.5662917e-008 -57.870201, + 10.9308 0.882429 -57.870201, + 10.8244 1.75913 -57.870201, + 8.0493698 3.4295199 -58.290901, + 7.7473102 4.0661001 -58.290901, + 10.0889 4.29846 -57.870201, + 8.2992296 2.77069 -58.290901, + 5.9798698 2.54778 -58.603001, + 6.1654902 2.0583401 -58.603001, + 11.1109 -7.0261102 -57.342201, + 14.5044 -4.8422799 -56.707199, + 12.0941 -5.1528101 -57.342201, + 23.8531 -19.364 -51.411999, + 22.173 -20.862499 -51.5541, + 11.4457 -10.14 -56.707199, + 10.5927 -11.0282 -56.707199, + -0.44157299 10.9575 -57.870201, + -0.35230801 8.7424202 -58.290901, + -0.529338 13.1354 -57.342201, + -1.3218499 10.8864 -57.870201, + -1.5845799 13.0502 -57.342201, + 3.1026199 8.1809397 -58.290901, + 3.8887401 10.2538 -57.870201, + 4.3747602 7.5773001 -58.290901, + 5.4832001 9.49718 -57.870201, + 4.70121 9.9076004 -57.870201, + 3.75085 7.9047499 -58.290901, + 6.22963 9.0251703 -57.870201, + 4.9702902 7.2007098 -58.290901, + 3.69242 5.3494 -58.603001, + 3.25 5.6291599 -58.603001, + 2.7865 5.8724298 -58.603001, + 2.30493 6.07761 -58.603001, + 2.4342699 8.4040699 -58.290901, + 5.7554598 3.0207 -58.603001, + 5.1963801 3.90482 -58.603001, + 4.1108999 5.0349302 -58.603001, + -6.22963 9.0251703 -57.870201, + -4.9702902 7.2007098 -58.290901, + 1.80841 6.2433701 -58.603001, + -3.1026199 8.1809397 -58.290901, + -3.8887401 10.2538 -57.870201, + -3.75085 7.9047499 -58.290901, + -24.18 54.727798 -40.798401, + -24.310499 54.887299 -40.613499, + -29.510599 37.2258 -49.3848, + -24.1619 54.699001 -40.828499, + 24.2451 54.8158 -40.7006, + 24.1369 54.654598 -40.873001, + -9.2686901 5.8611698 -57.870201, + -9.7102699 5.0963402 -57.870201, + -11.1109 7.0261102 -57.342201, + -31.9088 34.735401 -49.589001, + -8.7670097 6.5879798 -57.870201, + -7.395 4.6763101 -58.290901, + -6.5490999 5.802 -58.290901, + -10.402 -3.4727099 -57.870201, + -6.47892 0.52303302 -58.603001, + -6.4158301 -1.04267 -58.603001, + -6.4158301 1.04267 -58.603001, + -6.47892 -0.52303302 -58.603001, + -6.5 6.4936984e-008 -58.603001, + -8.7211399 0.70404297 -58.290901, + -6.1654902 -2.0583401 -58.603001, + -5.9798698 -2.54778 -58.603001, + -6.31112 -1.55555 -58.603001, + -8.2992296 -2.77069 -58.290901, + -8.4952698 -2.0939 -58.290901, + -8.0493698 -3.4295199 -58.290901, + -5.7554598 3.0207 -58.603001, + -5.9798698 2.54778 -58.603001, + -7.7473102 4.0661001 -58.290901, + -34.591499 43.8522 -41.080601, + -34.867901 37.002499 -45.921799, + -34.736301 44.6166 -40.3778, + -34.530102 43.5089 -41.390598, + -33.2374 48.117901 -38.999901, + -32.638802 48.7869 -38.999901, + -34.628502 38.5728 -44.963402, + -34.679798 38.244301 -45.163399, + -30.208799 51.427101 -38.999901, + -34.4571 39.674099 -44.292301, + -34.359402 40.6534 -43.650799, + 6.9809699 -29.6336 -51.5541, + 9.1689196 -29.1833 -51.493999, + 0.37410301 -30.7213 -51.411999, + 4.8220801 -30.2073 -51.493999, + 7.0142102 -29.7747 -51.493999, + 2.6156199 -30.612 -51.411999, + 4.8431702 -30.339399 -51.411999, + 7.0448899 -29.905001 -51.411999, + 2.5918801 -30.334299 -51.5541, + 0.370709 -30.442499 -51.5541, + 0.615722 -15.279 -56.707199, + 1.84317 -15.1799 -56.707199, + 0.372473 -30.5875 -51.493999, + 2.6042299 -30.478701 -51.493999, + 4.7992301 -30.064199 -51.5541, + -6.99473 -5.2561998 -58.290901, + -10.5095 -7.8973799 -57.342201, + -9.8399496 -8.7174397 -57.342201, + -6.0609999 -6.3101702 -58.290901, + -8.2084703 -7.2720699 -57.870201, + -1.85244 -30.388399 -51.5541, + -4.0657101 -30.1721 -51.5541, + -6.2572899 -29.7948 -51.5541, + -6.2870898 -29.936701 -51.493999, + -4.70121 -9.9076004 -57.870201, + -8.4154797 -29.2586 -51.5541, + -14.1127 -31.481001 -48.005501, + -21.1432 -27.7372 -46.969299, + -19.5877 -28.890301 -46.417999, + -18.957899 -29.2743 -46.969299, + -18.9841 -29.3148 -46.417999, + -16.566601 -25.715401 -51.493999, + -18.3123 -24.321699 -51.5541, + -24.6598 -18.1005 -51.493999, + -23.162399 -19.7582 -51.5541, + -21.6584 -21.396299 -51.5541, + -20.4849 -26.8736 -48.850201, + -18.4799 -24.544399 -51.411999, + -18.3995 -24.437599 -51.493999, + -26.0693 -21.499201 -48.850201, + -12.9241 -8.1727104 -56.707199, + -12.2246 -9.1861601 -56.707199, + -13.5398 -7.1062498 -56.707199, + -25.7924 -16.1752 -51.5541, + -24.5429 -18.014799 -51.5541, + -26.904301 -14.2493 -51.5541, + -34.924999 37.316101 40.329601, + -34.890701 38.288601 39.757702, + -34.878601 43.668701 36.365101, + -34.924999 37.301601 40.3386, + -34.924999 44.862598 35.544102, + -38.258701 55.465 4.3041801, + 34.495701 35.203499 41.980202, + 34.587101 35.3438 41.8204, + 34.499599 6.3247334e-008 41.982498, + 34.4174 35.083401 42.1171, + 34.145199 34.972401 42.404499, + 34.245399 34.915001 42.358101, + 29.3811 55.465 33.935299, + 34.116402 34.831799 42.511799, + 33.492401 34.757301 43.049198, + 26.2001 55.465 36.447399, + 29.9247 -0.54296303 43.619999, + -31.017799 -1.7677701 43.619999, + -30.580099 -2.1168101 43.619999, + -31.204599 -1.55872 43.619999, + -30.808701 -1.9545799 43.619999, + -24.321899 -20.408501 43.57, + -22.4506 -22.4506 43.57, + -20.408501 -24.321899 43.57, + -27.630301 -15.6176 43.57, + -27.4963 -15.875 43.57, + 28.434799 2.3633599 43.619999, + -30.0306 0.375054 43.619999, + -28.816999 -0.75 43.619999, + -31.734301 0.27991101 43.619999, + -31.204599 1.55872 43.619999, + -31.017799 1.7677701 43.619999, + -31.192101 36.813499 43.57, + -31.3207 36.6521 43.57, + -28.6089 -20.0322 40.395, + -28.452 -19.9223 41.4809, + -30.204201 -17.4384 40.946301, + -30.080099 -17.3668 41.4809, + -26.7171 -22.4184 40.946301, + -26.754101 -22.4494 40.395, + -26.607401 -22.3263 41.4809, + -28.569401 -20.004499 40.946301, + -26.8976 -18.8339 43.378502, + -28.436701 -16.417999 43.378502, + -26.4597 -18.5273 43.521801, + -24.744301 -20.762899 43.521801, + -29.275 -13.6511 43.521801, + -27.973801 -16.1507 43.521801, + -30.3533 -11.0477 43.521801, + -29.759399 -13.8771 43.378502, + -30.8557 -11.2305 43.378502, + -18.5273 -26.4597 43.521801, + -18.2111 -26.008101 43.57, + -16.1507 -27.973801 43.521801, + -20.762899 -24.744301 43.521801, + -18.8339 -26.8976 43.378502, + -29.2637 -16.895399 42.827202, + -25.153799 -21.106501 43.378502, + -31.7171 -8.49856 43.378502, + 34.730301 44.584702 -40.4072, + 34.9175 36.439201 -46.292198, + 34.848499 37.158901 -45.8232, + 34.884602 45.555698 -39.529499, + 34.645699 44.117599 -40.831402, + 33.365601 47.973801 -38.999901, + 32.611401 48.817402 -38.999901, + 5.6090698 -31.8106 43.521801, + 5.7019 -32.337101 43.378502, + 8.3601999 -31.200701 43.521801, + 5.51333 -31.267599 43.57, + 2.8152499 -32.178398 43.521801, + 4.7707601 -31.3654 43.57, + 2.76719 -31.6292 43.57, + -2.9791701 -34.052101 42.435799, + -2.94507 -33.6623 42.827202, + -5.9356799 -33.662899 42.435799, + -3.00684 -34.368401 41.982498, + 7.8802771e-008 -34.182201 42.435799, + -2.86184 -32.710999 43.378502, + 7.4775848e-008 -32.835899 43.378502, + -2.90556 -33.210602 43.1446, + -5.7019 -32.337101 43.378502, + -5.789 -32.831001 43.1446, + 7.7801467e-008 -32.3013 43.521801, + -2.8152499 -32.178398 43.521801, + 2.90556 -33.210602 43.1446, + 2.86184 -32.710999 43.378502, + 5.789 -32.831001 43.1446, + 2.94507 -33.6623 42.827202, + 7.5390098e-008 -33.337502 43.1446, + 14.446 -30.979601 42.435799, + 14.5802 -31.2673 41.982498, + 16.895399 -29.2637 42.827202, + 17.091101 -29.6026 42.435799, + 17.2498 -29.8776 41.982498, + 11.5572 -31.753 42.827202, + 8.7457199 -32.6395 42.827202, + 11.4021 -31.327 43.1446, + 11.691 -32.1208 42.435799, + 14.2806 -30.624901 42.827202, + 32.216099 -10.1954 -48.850201, + 31.998501 -12.8966 -48.005501, + 31.127001 -15.412 -47.503899, + 32.215401 -12.984 -47.503899, + 33.114799 -10.4798 -47.503899, + 32.8918 -10.4092 -48.005501, + 32.589199 -10.3135 -48.4589, + 29.382 -17.467699 -48.4589, + 27.958599 -19.665701 -48.4589, + 28.2183 -19.848301 -48.005501, + 29.6548 -17.629999 -48.005501, + 30.9174 -15.3082 -48.005501, + 30.6329 -15.1673 -48.4589, + 31.7041 -12.7779 -48.4589, + 29.045601 -17.267799 -48.850201, + 25.202999 -17.571199 -51.411999, + 14.0677 -5.9937 -56.707199, + 30.1464 -5.1895399 -51.493999, + 28.9317 -9.4784498 -51.5541, + 29.5464 -7.34128 -51.5541, + 29.687099 -7.3762398 -51.493999, + 29.816999 -7.4085002 -51.411999, + 31.341101 -12.6316 -48.850201, + 30.2822 -14.9937 -48.850201, + 20.9146 -27.4373 -48.005501, + 22.953501 -25.7558 -48.005501, + 23.1091 -25.930401 -47.503899, + 21.056299 -27.623301 -47.503899, + 15.3749 -26.519899 -51.458, + 15.3156 -26.5546 -51.457802, + 16.592899 -30.5138 -47.503899, + 18.879999 -29.1541 -47.503899, + 16.661301 -30.6397 -46.969299, + 14.2084 -31.6945 -47.503899, + 16.481199 -30.3083 -48.005501, + 18.752899 -28.9578 -48.005501, + 17.187799 -25.304399 -51.493999, + 17.1064 -25.1845 -51.5541, + 18.367599 -28.3629 -48.850201, + 17.263 -25.4151 -51.411999, + 20.4849 -26.8736 -48.850201, + 20.722099 -27.1849 -48.4589, + 18.580299 -28.691299 -48.4589, + 16.3295 -30.029499 -48.4589, + 16.142599 -29.685699 -48.850201, + 15.3618 -26.607401 -51.411999, + 20.688999 -22.5322 -51.493999, + 18.9891 -23.9823 -51.493999, + 19.0721 -24.0872 -51.411999, + 20.779499 -22.630699 -51.411999, + 20.591 -22.4254 -51.5541, + 22.278601 -20.961901 -51.493999, + 21.4289 -25.538 43.1446, + 21.106501 -25.153799 43.378502, + 19.121599 -27.3085 43.1446, + 23.8937 -23.8937 42.827202, + 25.8853 -21.720301 42.827202, + 24.1705 -24.1705 42.435799, + 23.5732 -23.5732 43.1446, + 21.720301 -25.8853 42.827202, + -1.33772 -34.899399 -46.417999, + 1.33588 -34.8512 -46.969299, + 1.33039 -34.708 -47.503899, + 1.32143 -34.4743 -48.005501, + 1.30927 -34.157101 -48.4589, + -1.30927 -34.157101 -48.4589, + -3.99979 -34.646702 -46.969299, + -1.33588 -34.8512 -46.969299, + -1.33039 -34.708 -47.503899, + -21.720301 -25.8853 42.827202, + -21.971901 -26.185101 42.435799, + -21.4289 -25.538 43.1446, + -19.381599 -27.6798 42.827202, + -19.121599 -27.3085 43.1446, + -9.0267696 -33.6884 40.946301, + -25.129499 -24.1847 -46.969299, + -25.1642 -24.2181 -46.417999, + -23.2365 -26.0734 -46.417999, + -25.348301 -24.0116 -46.417999, + -26.9443 -22.2208 -46.417999, + -26.796499 -22.0989 -47.503899, + -26.907 -22.1901 -46.969299, + -28.409599 -19.9828 -47.503899, + -28.2183 -19.848301 -48.005501, + -9.1417599 -33.266399 -48.005501, + -6.6129498 -34.098202 -47.503899, + -9.2037401 -33.491901 -47.503899, + -9.0576496 -32.9603 -48.4589, + -11.6615 -32.469002 -48.005501, + -24.6616 -24.6616 40.946301, + -24.6957 -24.6957 40.395, + -22.4494 -26.754101 40.395, + -20.0322 -28.6089 40.395, + 32.337101 -5.7019 43.378502, + 32.835899 6.594977e-008 43.378502, + 33.2775 -5.8677201 42.827202, + 32.6395 -8.7457199 42.827202, + 32.201599 -8.6283798 43.1446, + 34.052101 -2.9791701 42.435799, + 34.368401 -3.00684 41.982498, + 33.662899 -5.9356799 42.435799, + -4.7707601 -31.3654 43.57, + -5.51333 -31.267599 43.57, + -29.5299 -2.4842801 43.619999, + -2.76719 -31.6292 43.57, + -5.6090698 -31.8106 43.521801, + 31.197599 -1.5674 43.619999, + 31.009899 -1.77561 43.619999, + 24.321899 -20.408501 43.57, + 26.008101 -18.2111 43.57, + 31.360901 -1.33948 43.619999, + 30.5707 -2.1227 43.619999, + 30.799999 -1.96149 43.619999, + 28.959 -2.4830101 43.619999, + 31.606001 -0.836182 43.619999, + 29.7955 -2.43977 43.619999, + 28.1553 -2.2475801 43.619999, + 29.238899 -2.49998 43.619999, + -29.25 -2.5 43.619999, + -27.919901 -2.1168101 43.619999, + -33.592098 -7.8608599 -48.005501, + -34.499599 6.3281682e-008 -48.005501, + -34.3265 -5.3020501 -47.503899, + -34.774399 -2.66979 -46.969299, + -34.467999 -5.3239102 -46.969299, + -34.631599 -2.6588299 -47.503899, + -33.819901 -7.9141598 -47.503899, + -34.095299 -5.2663398 -48.005501, + -34.398399 -2.6409199 -48.005501, + 30.5807 -0.744892 -51.493999, + 30.4447 -2.9751501 -51.493999, + 30.537399 -0.85720998 -51.513401, + 30.438299 -1.11999 -51.547401, + 30.300501 -2.96105 -51.5541, + 30.383801 -1.2517101 -51.5648, + 30.507999 -0.95146197 -51.525101, + 15.2914 6.1412564e-008 -56.707199, + 5.1963801 -3.90482 -58.603001, + 6.99473 -5.2561998 -58.290901, + 5.4937401 -3.47403 -58.603001, + 4.8653202 -4.3102999 -58.603001, + 14.2492 -26.920401 -51.547401, + 7.64568 -13.2427 -56.707199, + 14.1079 -26.938999 -51.5648, + 13.2572 -27.406799 -51.5541, + 3.69242 -5.34939 -58.603001, + 4.1108999 -5.0349302 -58.603001, + 4.9702902 -7.2007098 -58.290901, + 3.25 -5.6291699 -58.603001, + 1.80841 -6.2433701 -58.603001, + -1.80841 -6.2433701 -58.603001, + -2.4342699 -8.4040604 -58.290901, + -1.7501301 -8.57269 -58.290901, + -1.3001699 -6.3686399 -58.603001, + -2.30493 -6.07761 -58.603001, + -3.1026199 -8.1809397 -58.290901, + -0.78348798 -6.45261 -58.603001, + -2.7865 -5.8724298 -58.603001, + -5.4937401 -3.47403 -58.603001, + 0.78348798 -6.45261 -58.603001, + 14.43 -26.8965 -51.525101, + 15.9289 -26.0888 -51.503601, + 16.051901 -25.974001 -51.520401, + 6.47892 0.52303302 -58.603001, + 6.5 6.2862441e-008 -58.603001, + 6.4158301 1.04267 -58.603001, + 8.7211399 0.70404297 -58.290901, + 12.2246 -9.1861601 -56.707199, + 23.6367 -19.188299 -51.5541, + 23.7493 -19.279699 -51.493999, + 1.0546401 8.6857204 -58.290901, + 0.44157201 10.9575 -57.870201, + 1.3218499 10.8864 -57.870201, + 0.35230801 8.7424202 -58.290901, + 2.1935599 10.7448 -57.870201, + 1.7501301 8.57269 -58.290901, + 0.78348798 6.45261 -58.603001, + 1.3001699 6.3686399 -58.603001, + -3.25 5.6291599 -58.603001, + -3.69242 5.3494 -58.603001, + -4.3747602 7.5773001 -58.290901, + -1.80841 6.2433701 -58.603001, + -2.30493 6.07761 -58.603001, + -0.78348798 6.45261 -58.603001, + -2.7865 5.8724298 -58.603001, + 0.26172799 6.49473 -58.603001, + -1.7501301 8.57269 -58.290901, + -1.3001699 6.3686399 -58.603001, + -2.4342699 8.4040699 -58.290901, + -1.0546401 8.6857204 -58.290901, + -2.1935599 10.7448 -57.870201, + -4.5027099 4.68782 -58.603001, + -4.1108999 5.0349302 -58.603001, + -6.0609999 6.3101702 -58.290901, + -5.5335898 6.77742 -58.290901, + -5.1963801 3.90482 -58.603001, + -5.4937401 3.47403 -58.603001, + -6.99473 5.2561998 -58.290901, + -4.8653202 4.3102999 -58.603001, + -12.764 -3.14605 -57.342201, + -10.6477 -2.6244299 -57.870201, + -12.4695 -4.16293 -57.342201, + -12.9758 -2.1087699 -57.342201, + -14.847 -3.6594601 -56.707199, + -10.8244 -1.75913 -57.870201, + -9.2686901 -5.8611698 -57.870201, + -8.7670097 -6.5879798 -57.870201, + -7.395 -4.6763101 -58.290901, + -9.7102699 -5.0963402 -57.870201, + -7.7473102 -4.0661001 -58.290901, + -11.1109 -7.0261102 -57.342201, + -4.9702902 -7.2007098 -58.290901, + -4.3747602 -7.5773001 -58.290901, + -5.5335898 -6.77742 -58.290901, + -3.25 -5.6291699 -58.603001, + -3.69242 -5.34939 -58.603001, + -4.1108999 -5.0349302 -58.603001, + -4.1029401 -30.4484 -51.411999, + -1.8612601 -30.5331 -51.493999, + -1.86941 -30.666599 -51.411999, + -4.0850701 -30.3158 -51.493999, + -3.8752501 -33.567902 -48.850201, + -6.31458 -30.067699 -51.411999, + -6.4334798 -33.172798 -48.850201, + -13.8228 -30.834299 -48.850201, + -10.5789 -28.702299 -51.493999, + -10.6252 -28.827801 -51.411999, + -8.4555502 -29.3979 -51.493999, + -8.4925404 -29.526501 -51.411999, + -10.5288 -28.566299 -51.5541, + -13.9829 -31.191401 -48.4589, + -16.3538 -30.845699 -46.417999, + -16.684401 -30.681999 -46.417999, + -16.3592 -30.856701 -44.513, + -14.267 -31.825199 -46.969299, + -16.661301 -30.6397 -46.969299, + -14.2867 -31.8692 -46.417999, + -14.2084 -31.6945 -47.503899, + -12.9176 -32.421001 -46.417999, + -11.7889 -32.823898 -46.969299, + -11.7405 -32.689098 -47.503899, + -8.6864796 -12.5845 -56.707199, + -6.22963 -9.0251703 -57.870201, + -21.856701 -21.592199 -51.411999, + -24.347 -23.4317 -48.850201, + -23.3745 -19.9391 -51.411999, + -23.272699 -19.852301 -51.493999, + -21.761499 -21.4981 -51.493999, + -20.134199 -23.029301 -51.493999, + -20.2223 -23.129999 -51.411999, + -22.481899 -25.2267 -48.850201, + 33.790901 6.1626494e-008 42.827202, + 33.7896 34.741299 42.825699, + 33.706799 34.734001 42.895302, + 33.878601 34.7491 42.750801, + 33.522202 34.751499 43.0294, + 34.182201 6.142745e-008 42.435799, + 33.939999 34.762901 42.693802, + 31.2115 1.55002 43.619999, + 30.3447 2.2475801 43.619999, + 30.8174 1.94763 43.619999, + 30.5895 2.1108799 43.619999, + 31.0256 1.75989 43.619999, + 28.9811 2.4855001 43.619999, + 28.7045 2.43977 43.619999, + 29.261101 2.49998 43.619999, + 29.817101 2.4348199 43.619999, + 30.086201 2.35601 43.619999, + 28.722 39.814201 43.57, + 29.541 2.4830101 43.619999, + -29.806299 2.43732 43.619999, + -28.9701 2.4842801 43.619999, + -29.5299 2.4842801 43.619999, + -30.3347 2.2524199 43.619999, + -30.580099 2.1168101 43.619999, + -28.722 39.814201 43.57, + -30.075701 2.35971 43.619999, + -31.502399 1.08471 43.619999, + -31.6873 0.55630201 43.619999, + -31.609699 0.82569802 43.619999, + -31.3668 1.33008 43.619999, + -31.75 36.112999 43.57, + -25.8853 -21.720301 42.827202, + -27.6798 -19.381599 42.827202, + -27.3085 -19.121599 43.1446, + -25.538 -21.4289 43.1446, + -28.000401 -19.6061 42.435799, + -26.185101 -21.971901 42.435799, + -24.1705 -24.1705 42.435799, + -23.8937 -23.8937 42.827202, + -23.5732 -23.5732 43.1446, + -32.710999 -2.86184 43.378502, + -32.3013 6.4970692e-008 43.521801, + -32.835899 6.2567018e-008 43.378502, + -32.337101 -5.7019 43.378502, + -33.210602 -2.90555 43.1446, + -33.337502 6.4066825e-008 43.1446, + -33.6623 -2.94507 42.827202, + -34.052101 -2.9791701 42.435799, + -34.368301 -3.00684 41.982498, + -34.601398 -3.02723 41.4809, + -34.205799 -6.0314102 41.4809, + -33.549999 -8.9897003 41.4809, + 28.296801 -11.6201 -51.493999, + 29.0695 -9.5235796 -51.493999, + 29.1966 -9.5652399 -51.411999, + 28.4205 -11.6709 -51.411999, + 28.162701 -11.565 -51.5541, + 27.4928 -13.7144 -51.411999, + -3.9565401 -34.271999 -48.005501, + -1.32143 -34.4743 -48.005501, + -3.92013 -33.956699 -48.4589, + -3.9833601 -34.504398 -47.503899, + -6.5684199 -33.868599 -48.005501, + -17.091101 -29.6026 42.435799, + -16.895399 -29.2637 42.827202, + -19.6061 -28.000401 42.435799, + -17.3668 -30.080099 41.4809, + -11.9451 -32.818802 40.395, + -12.3846 -32.655399 38.490002, + -8.9291601 -33.3241 41.982498, + -8.8470001 -33.017502 42.435799, + -8.7457199 -32.6395 42.827202, + -11.5572 -31.753 42.827202, + -14.2806 -30.624901 42.827202, + -14.5802 -31.2673 41.982498, + -17.2498 -29.8776 41.982498, + -14.446 -30.979601 42.435799, + -11.691 -32.1208 42.435799, + -11.7996 -32.418999 41.982498, + -14.7396 -31.6091 40.946301, + -11.9286 -32.773399 40.946301, + -11.8796 -32.638802 41.4809, + -14.679 -31.4793 41.4809, + -12.378 -32.6395 40.395, + -14.7599 -31.6528 40.395, + -17.4384 -30.204201 40.946301, + -24.8577 -23.923201 -48.005501, + -22.7423 -25.518801 -48.4589, + -24.629 -23.702999 -48.4589, + -26.6161 -21.9501 -48.005501, + -26.371201 -21.748199 -48.4589, + -23.1091 -25.930401 -47.503899, + -21.056299 -27.623301 -47.503899, + -23.204399 -26.037399 -46.969299, + -25.0263 -24.0854 -47.503899, + -22.953501 -25.7558 -48.005501, + -22.3263 -26.607401 41.4809, + -24.560301 -24.560301 41.4809, + -22.1759 -26.428301 41.982498, + -22.4184 -26.717199 40.946301, + -19.7882 -28.260401 41.982498, + -19.9223 -28.452 41.4809, + -20.004499 -28.569401 40.946301, + 32.178398 -2.8152499 43.521801, + 31.8106 -5.6090698 43.521801, + 32.3013 6.2476978e-008 43.521801, + 31.733 -0.29095501 43.619999, + 31.75 -0.011116701 43.619999, + 33.210602 -2.90555 43.1446, + 33.6623 -2.94507 42.827202, + 33.337502 6.429476e-008 43.1446, + 32.710999 -2.86184 43.378502, + 32.831001 -5.789 43.1446, + -34.497299 34.482498 -48.004299, + -34.647701 34.735401 -47.715599, + -34.4734 34.442402 -48.049999, + -34.499599 30 -48.005501, + -33.283001 -7.7885299 -48.4589, + -29.627701 -8.1323795 -51.411999, + -32.216099 -10.1954 -48.850201, + -32.589199 -10.3135 -48.4589, + -30.1423 -5.948 -51.411999, + -32.902 -7.6993599 -48.850201, + -27.8512 53.865002 -38.999901, + -33.394798 -5.1581502 -48.850201, + -34.081902 -2.6166201 -48.4589, + -33.781601 -5.2178898 -48.4589, + -33.6917 -2.5866599 -48.850201, + -30.654301 -0.055089999 -51.458, + -30.5807 0.744892 -51.493999, + -33.459 33.9678 -49.0938, + -33.335999 33.985298 -49.165001, + -33.218498 34.002102 -49.233002, + -30.537399 0.85720998 -51.513401, + 30.617399 0.493628 -51.4772, + 30.624599 -0.444675 -51.473598, + 14.6296 -26.841101 -51.503201, + 13.3203 -27.5373 -51.493999, + 14.9272 -26.743999 -51.473598, + 14.5264 -26.8748 -51.513401, + 15.7362 -26.2686 -51.4772, + 26.4184 -15.6846 -51.411999, + -3.65746 -12.627 -57.342201, + -4.2543201 -14.6876 -56.707199, + -2.62955 -12.8804 -57.342201, + -5.42239 -14.2977 -56.707199, + -4.6616502 -12.2918 -57.342201, + -2.1935599 -10.7448 -57.870201, + -3.0510399 -10.5334 -57.870201, + -3.8887401 -10.2538 -57.870201, + -12.7011 -27.9753 -51.411999, + -14.1393 -26.937 -51.5611, + -16.1891 -25.8004 -51.547401, + -16.2759 -25.6873 -51.5648, + -16.488001 -25.593599 -51.5541, + -6.57302 -11.3848 -57.342201, + -6.5552902 -13.815 -56.707199, + -5.6356101 -11.8768 -57.342201, + -5.4832001 -9.49718 -57.870201, + -8.3141499 -10.183 -57.342201, + -7.4678001 -10.819 -57.342201, + -9.6709499 -11.8448 -56.707199, + -9.1065798 -9.4809599 -57.342201, + -10.5927 -11.0282 -56.707199, + -6.9356499 -8.4946299 -57.870201, + -7.5966902 -7.9089999 -57.870201, + -31.267599 -5.51333 43.57, + -31.200701 -8.3601999 43.521801, + -32.2015 -8.6283798 43.1446, + -32.831001 -5.789 43.1446, + -33.2775 -5.8677201 42.827202, + -31.753 -11.5572 42.827202, + -31.327 -11.4021 43.1446, + -34.182201 30 -48.4589, + -34.321301 34.270599 -48.280499, + -34.182201 6.2203078e-008 -48.4589, + -34.1366 34.127998 -48.512001, + -30.553499 -1.4893399 -51.493999, + -30.558001 -0.75038099 -51.503601, + -30.687099 -1.49586 -51.411999, + -30.5201 -0.91436601 -51.520401, + -30.408701 -1.48228 -51.5541, + -30.3633 -3.7156301 -51.493999, + -30.496099 -3.7318799 -51.411999, + -30.6294 0.37607899 -51.4711, + -30.624599 0.444675 -51.473598, + -30.7145 0.74814999 -51.411999, + -30.6548 0.013644902 -51.457802, + -30.617399 -0.493628 -51.4772, + 30.654699 -1.1009175e-006 -51.457802, + 30.6294 -0.37607899 -51.4711, + 30.654301 0.055090096 -51.458, + 30.654699 -0.013644998 -51.457802, + 30.7145 -0.74814999 -51.411999, + 26.178699 -15.5423 -51.5541, + 24.9743 -17.4118 -51.5541, + 25.093201 -17.494699 -51.493999, + 26.303301 -15.6163 -51.493999, + 12.9241 -8.1727104 -56.707199, + 13.5398 -7.1062498 -56.707199, + 27.243299 -13.5899 -51.5541, + 27.3731 -13.6546 -51.493999, + -18.752899 -28.9578 -48.005501, + -16.3295 -30.029499 -48.4589, + -16.481199 -30.3083 -48.005501, + -18.580299 -28.691299 -48.4589, + -18.879999 -29.1541 -47.503899, + -16.592899 -30.5138 -47.503899, + -20.9146 -27.4373 -48.005501, + -20.722099 -27.1849 -48.4589, + -31.734301 -0.27991101 43.619999, + -32.178398 -2.8152499 43.521801, + -31.8106 -5.6090698 43.521801, + -31.75 6.2830054e-008 43.619999, + -31.609699 -0.82569802 43.619999, + -30.6681 -8.2174997 43.57, + -29.835199 -10.8591 43.57, + -31.6873 -0.55630201 43.619999, + -31.502399 -1.08471 43.619999, + -28.775299 -13.4181 43.57, + -33.017502 -8.8470001 42.435799, + -32.6395 -8.7457199 42.827202, + -33.662899 -5.9356799 42.435799, + -33.975498 -5.9907999 41.982498, + -33.3241 -8.9291601 41.982498, + -32.1208 -11.691 42.435799, + -33.905701 34.020901 -48.749001, + -33.790798 30 -48.850201, + -33.790798 6.2424945e-008 -48.850201, + -33.9389 34.032299 -48.717899, + -33.703499 33.975399 -48.920898, + -33.789101 33.994701 -48.848099, + -26.691299 55.465 -38.685501, + -33.604599 34.338699 -48.734299, + -16.639 -25.8279 -51.411999, + -18.367599 -28.3629 -48.850201, + -16.142599 -29.685699 -48.850201, + -14.4682 -26.888399 -51.520401, + -12.6458 -27.8535 -51.493999, + -12.5859 -27.7215 -51.5541, + -14.2492 -26.920799 -51.547501, + -16.077999 -25.945 -51.525101, + -7.64568 -13.2427 -56.707199, + -16.011101 -26.017599 -51.513401, + -14.8812 -26.7623 -51.4772, + -15.2795 -26.575001 -51.458, + -14.7093 -26.9736 -51.411999, + -14.6453 -26.8561 -51.493999, + -15.3392 -26.541 -51.457802, + -15.6404 -26.337799 -51.4711, + -15.6974 -26.299299 -51.473598, + -15.9303 -26.0902 -51.503201 ] + + } + coordIndex [ 191, 25, 26, -1, 64, 26, 72, -1, + 1051, 14, 56, -1, 3, 191, 26, -1, + 173, 4, 379, -1, 173, 64, 72, -1, + 380, 379, 4, -1, 1061, 1058, 26, -1, + 272, 6, 273, -1, 272, 18, 6, -1, + 96, 125, 18, -1, 0, 6, 18, -1, + 0, 18, 125, -1, 0, 125, 6, -1, + 12, 13, 67, -1, 12, 67, 153, -1, + 46, 56, 14, -1, 46, 14, 505, -1, + 46, 505, 134, -1, 234, 114, 231, -1, + 200, 18, 272, -1, 51, 307, 138, -1, + 51, 52, 307, -1, 10, 2, 196, -1, + 10, 63, 379, -1, 10, 379, 2, -1, + 1, 379, 195, -1, 1, 2, 379, -1, + 1, 195, 196, -1, 1, 196, 2, -1, + 1629, 153, 151, -1, 1629, 12, 153, -1, + 59, 191, 3, -1, 66, 67, 13, -1, + 66, 13, 59, -1, 66, 59, 3, -1, + 66, 3, 26, -1, 15, 591, 166, -1, + 15, 48, 591, -1, 62, 355, 16, -1, + 92, 4, 173, -1, 92, 380, 4, -1, + 171, 64, 173, -1, 20, 25, 191, -1, + 20, 84, 25, -1, 247, 1061, 1414, -1, + 247, 1414, 1404, -1, 186, 682, 1421, -1, + 83, 1414, 1061, -1, 83, 186, 1414, -1, + 86, 82, 83, -1, 86, 1061, 26, -1, + 33, 273, 6, -1, 33, 6, 5, -1, + 124, 6, 125, -1, 43, 44, 38, -1, + 745, 44, 411, -1, 206, 43, 38, -1, + 45, 411, 44, -1, 219, 411, 45, -1, + 223, 411, 219, -1, 223, 219, 110, -1, + 215, 41, 108, -1, 215, 418, 41, -1, + 119, 125, 96, -1, 123, 106, 32, -1, + 123, 33, 5, -1, 123, 32, 33, -1, + 123, 5, 6, -1, 123, 6, 124, -1, + 240, 470, 471, -1, 185, 1414, 186, -1, + 127, 495, 1254, -1, 7, 14, 12, -1, + 7, 12, 256, -1, 7, 505, 14, -1, + 7, 256, 505, -1, 507, 56, 46, -1, + 130, 231, 114, -1, 130, 114, 1270, -1, + 944, 143, 578, -1, 8, 49, 935, -1, + 8, 48, 49, -1, 354, 674, 49, -1, + 937, 591, 48, -1, 937, 8, 935, -1, + 937, 48, 8, -1, 150, 138, 151, -1, + 150, 51, 138, -1, 617, 1304, 1355, -1, + 9, 196, 63, -1, 9, 63, 10, -1, + 9, 10, 196, -1, 706, 198, 383, -1, + 295, 140, 294, -1, 295, 326, 556, -1, + 295, 556, 140, -1, 295, 151, 153, -1, + 327, 256, 1629, -1, 327, 1629, 1520, -1, + 11, 256, 12, -1, 11, 1629, 256, -1, + 11, 12, 1629, -1, 55, 1051, 56, -1, + 55, 660, 1051, -1, 55, 341, 660, -1, + 159, 56, 507, -1, 159, 507, 129, -1, + 57, 13, 12, -1, 57, 59, 13, -1, + 57, 14, 1051, -1, 57, 12, 14, -1, + 57, 353, 59, -1, 65, 26, 64, -1, + 65, 66, 26, -1, 188, 682, 703, -1, + 665, 682, 191, -1, 60, 166, 591, -1, + 61, 15, 166, -1, 61, 16, 355, -1, + 61, 355, 354, -1, 61, 48, 15, -1, + 670, 62, 16, -1, 670, 61, 672, -1, + 670, 16, 61, -1, 24, 17, 92, -1, + 24, 92, 173, -1, 24, 178, 17, -1, + 91, 100, 37, -1, 91, 99, 100, -1, + 91, 92, 17, -1, 91, 17, 178, -1, + 91, 178, 99, -1, 179, 178, 23, -1, + 179, 23, 1058, -1, 98, 99, 178, -1, + 98, 178, 357, -1, 90, 34, 394, -1, + 90, 37, 34, -1, 90, 91, 37, -1, + 89, 18, 200, -1, 89, 34, 35, -1, + 89, 96, 18, -1, 89, 35, 36, -1, + 89, 36, 96, -1, 19, 191, 84, -1, + 19, 20, 191, -1, 19, 84, 20, -1, + 21, 26, 1058, -1, 21, 1058, 74, -1, + 21, 72, 26, -1, 21, 74, 72, -1, + 75, 68, 1058, -1, 79, 173, 70, -1, + 22, 173, 78, -1, 22, 1058, 23, -1, + 22, 78, 1058, -1, 22, 23, 178, -1, + 22, 24, 173, -1, 22, 178, 24, -1, + 30, 26, 25, -1, 30, 25, 84, -1, + 30, 86, 26, -1, 30, 29, 86, -1, + 27, 191, 682, -1, 27, 186, 191, -1, + 27, 682, 186, -1, 88, 82, 86, -1, + 88, 190, 82, -1, 28, 87, 86, -1, + 28, 86, 29, -1, 28, 84, 87, -1, + 28, 30, 84, -1, 28, 29, 30, -1, + 31, 83, 1061, -1, 31, 1061, 86, -1, + 31, 86, 83, -1, 1110, 383, 196, -1, + 377, 399, 706, -1, 139, 525, 391, -1, + 719, 394, 34, -1, 719, 34, 89, -1, + 94, 713, 711, -1, 94, 711, 399, -1, + 204, 42, 421, -1, 204, 33, 32, -1, + 204, 273, 33, -1, 204, 106, 42, -1, + 204, 32, 106, -1, 97, 35, 34, -1, + 97, 36, 35, -1, 97, 34, 37, -1, + 97, 37, 100, -1, 97, 96, 36, -1, + 202, 38, 44, -1, 202, 44, 745, -1, + 202, 729, 101, -1, 102, 206, 38, -1, + 102, 38, 39, -1, 102, 39, 209, -1, + 40, 39, 38, -1, 40, 38, 202, -1, + 40, 202, 101, -1, 212, 209, 39, -1, + 212, 208, 209, -1, 212, 40, 101, -1, + 212, 39, 40, -1, 210, 211, 1206, -1, + 203, 759, 103, -1, 203, 41, 418, -1, + 203, 108, 41, -1, 242, 106, 123, -1, + 105, 42, 106, -1, 105, 421, 42, -1, + 220, 44, 43, -1, 220, 45, 44, -1, + 220, 43, 206, -1, 220, 219, 45, -1, + 439, 438, 110, -1, 439, 110, 219, -1, + 480, 481, 1099, -1, 458, 201, 403, -1, + 236, 235, 234, -1, 233, 114, 234, -1, + 233, 232, 157, -1, 116, 115, 98, -1, + 122, 120, 243, -1, 122, 243, 242, -1, + 122, 242, 123, -1, 237, 117, 116, -1, + 237, 116, 1246, -1, 1261, 238, 358, -1, + 486, 471, 836, -1, 486, 240, 471, -1, + 1060, 1061, 476, -1, 845, 1258, 359, -1, + 504, 505, 256, -1, 128, 113, 157, -1, + 128, 114, 113, -1, 128, 1270, 114, -1, + 135, 46, 134, -1, 135, 507, 46, -1, + 132, 230, 231, -1, 1518, 523, 1515, -1, + 261, 517, 260, -1, 1529, 151, 138, -1, + 521, 1629, 151, -1, 269, 872, 873, -1, + 142, 293, 559, -1, 142, 291, 293, -1, + 142, 141, 291, -1, 142, 559, 560, -1, + 278, 281, 294, -1, 286, 927, 928, -1, + 582, 141, 142, -1, 941, 143, 944, -1, + 574, 965, 964, -1, 574, 964, 311, -1, + 574, 311, 597, -1, 47, 49, 48, -1, + 47, 354, 49, -1, 47, 48, 61, -1, + 47, 61, 354, -1, 297, 49, 674, -1, + 297, 296, 299, -1, 297, 935, 49, -1, + 297, 299, 935, -1, 50, 591, 937, -1, + 50, 588, 591, -1, 50, 937, 1336, -1, + 50, 1336, 588, -1, 146, 318, 148, -1, + 146, 147, 276, -1, 53, 313, 603, -1, + 1340, 53, 954, -1, 1340, 313, 53, -1, + 969, 968, 275, -1, 969, 603, 313, -1, + 149, 150, 275, -1, 149, 52, 51, -1, + 149, 51, 150, -1, 149, 276, 147, -1, + 149, 275, 276, -1, 149, 307, 52, -1, + 602, 53, 603, -1, 602, 954, 53, -1, + 619, 276, 320, -1, 619, 146, 276, -1, + 619, 318, 146, -1, 707, 383, 373, -1, + 707, 706, 383, -1, 271, 383, 198, -1, + 271, 196, 383, -1, 271, 525, 527, -1, + 271, 153, 177, -1, 271, 527, 526, -1, + 271, 170, 196, -1, 271, 177, 171, -1, + 271, 171, 170, -1, 606, 143, 317, -1, + 606, 317, 605, -1, 631, 327, 1520, -1, + 339, 331, 329, -1, 1010, 329, 1011, -1, + 1010, 338, 339, -1, 1010, 339, 329, -1, + 983, 973, 984, -1, 54, 55, 56, -1, + 54, 341, 55, -1, 54, 56, 159, -1, + 54, 159, 341, -1, 156, 128, 157, -1, + 156, 159, 129, -1, 156, 129, 128, -1, + 1446, 232, 1447, -1, 1446, 345, 341, -1, + 1446, 164, 345, -1, 1446, 1445, 164, -1, + 344, 164, 163, -1, 344, 345, 164, -1, + 344, 163, 665, -1, 162, 353, 57, -1, + 162, 57, 1051, -1, 369, 682, 665, -1, + 58, 59, 353, -1, 58, 353, 665, -1, + 58, 191, 59, -1, 58, 665, 191, -1, + 593, 965, 575, -1, 593, 575, 576, -1, + 577, 166, 60, -1, 577, 60, 576, -1, + 592, 576, 60, -1, 592, 593, 576, -1, + 592, 60, 591, -1, 167, 61, 166, -1, + 167, 672, 61, -1, 168, 355, 62, -1, + 168, 62, 670, -1, 172, 63, 196, -1, + 172, 196, 170, -1, 172, 379, 63, -1, + 172, 173, 379, -1, 176, 153, 67, -1, + 176, 177, 153, -1, 175, 64, 171, -1, + 175, 65, 64, -1, 175, 171, 177, -1, + 175, 66, 65, -1, 175, 67, 66, -1, + 175, 176, 67, -1, 1245, 357, 1054, -1, + 1245, 98, 357, -1, 1245, 1246, 116, -1, + 1245, 116, 98, -1, 182, 74, 1058, -1, + 182, 70, 74, -1, 182, 79, 70, -1, + 182, 80, 79, -1, 76, 1058, 68, -1, + 76, 181, 1058, -1, 76, 68, 75, -1, + 69, 74, 70, -1, 69, 73, 74, -1, + 69, 70, 173, -1, 69, 173, 73, -1, + 71, 173, 72, -1, 71, 73, 173, -1, + 71, 72, 74, -1, 71, 74, 73, -1, + 183, 1058, 80, -1, 183, 75, 1058, -1, + 183, 80, 182, -1, 183, 181, 76, -1, + 183, 76, 75, -1, 77, 78, 173, -1, + 77, 173, 79, -1, 77, 1058, 78, -1, + 77, 80, 1058, -1, 77, 79, 80, -1, + 683, 1421, 1418, -1, 683, 1414, 185, -1, + 1078, 1421, 682, -1, 700, 164, 1445, -1, + 1442, 187, 188, -1, 1442, 188, 703, -1, + 81, 82, 190, -1, 81, 83, 82, -1, + 81, 186, 83, -1, 81, 191, 186, -1, + 81, 190, 191, -1, 192, 87, 84, -1, + 192, 190, 88, -1, 192, 84, 191, -1, + 85, 86, 87, -1, 85, 88, 86, -1, + 85, 87, 192, -1, 85, 192, 88, -1, + 1111, 383, 1110, -1, 197, 373, 383, -1, + 197, 383, 385, -1, 704, 379, 705, -1, + 704, 1110, 196, -1, 392, 391, 525, -1, + 392, 525, 271, -1, 392, 271, 198, -1, + 398, 399, 711, -1, 199, 89, 200, -1, + 199, 719, 89, -1, 709, 710, 380, -1, + 709, 90, 394, -1, 709, 91, 90, -1, + 709, 380, 92, -1, 709, 92, 91, -1, + 93, 713, 94, -1, 93, 94, 399, -1, + 93, 377, 713, -1, 93, 399, 377, -1, + 95, 119, 96, -1, 95, 96, 97, -1, + 95, 115, 119, -1, 95, 98, 115, -1, + 95, 99, 98, -1, 95, 100, 99, -1, + 95, 97, 100, -1, 407, 403, 201, -1, + 728, 101, 729, -1, 728, 211, 212, -1, + 728, 212, 101, -1, 205, 102, 209, -1, + 205, 206, 102, -1, 416, 289, 417, -1, + 416, 285, 289, -1, 416, 286, 285, -1, + 416, 927, 286, -1, 757, 421, 107, -1, + 757, 103, 759, -1, 426, 108, 203, -1, + 426, 203, 432, -1, 426, 427, 108, -1, + 431, 432, 203, -1, 431, 203, 103, -1, + 431, 757, 107, -1, 431, 103, 757, -1, + 104, 105, 106, -1, 104, 106, 242, -1, + 104, 242, 490, -1, 104, 490, 431, -1, + 104, 431, 107, -1, 104, 107, 421, -1, + 104, 421, 105, -1, 638, 637, 220, -1, + 638, 220, 206, -1, 435, 427, 436, -1, + 435, 215, 108, -1, 435, 108, 427, -1, + 218, 109, 217, -1, 218, 213, 109, -1, + 214, 436, 427, -1, 429, 428, 213, -1, + 429, 214, 427, -1, 429, 213, 214, -1, + 746, 428, 792, -1, 746, 747, 428, -1, + 222, 213, 428, -1, 222, 428, 747, -1, + 222, 109, 213, -1, 222, 438, 217, -1, + 222, 217, 109, -1, 222, 110, 438, -1, + 222, 223, 110, -1, 448, 1470, 1469, -1, + 461, 451, 1237, -1, 456, 201, 458, -1, + 452, 1464, 1465, -1, 452, 1465, 226, -1, + 651, 1233, 656, -1, 404, 452, 453, -1, + 404, 1464, 452, -1, 457, 402, 453, -1, + 457, 453, 454, -1, 457, 458, 403, -1, + 457, 403, 402, -1, 824, 228, 236, -1, + 111, 236, 228, -1, 465, 227, 830, -1, + 465, 466, 236, -1, 465, 236, 111, -1, + 465, 228, 227, -1, 465, 111, 228, -1, + 465, 830, 1082, -1, 112, 157, 113, -1, + 112, 233, 157, -1, 112, 113, 114, -1, + 112, 114, 233, -1, 118, 120, 119, -1, + 118, 119, 115, -1, 118, 115, 116, -1, + 118, 116, 117, -1, 241, 117, 237, -1, + 241, 237, 470, -1, 241, 118, 117, -1, + 241, 120, 118, -1, 241, 243, 120, -1, + 126, 125, 119, -1, 126, 119, 120, -1, + 126, 120, 122, -1, 1507, 1060, 476, -1, + 121, 122, 123, -1, 121, 124, 125, -1, + 121, 123, 124, -1, 121, 125, 126, -1, + 121, 126, 122, -1, 479, 1264, 1064, -1, + 1263, 1264, 842, -1, 1118, 1263, 842, -1, + 1255, 1254, 495, -1, 846, 839, 856, -1, + 248, 245, 853, -1, 248, 1404, 852, -1, + 844, 127, 1254, -1, 844, 845, 127, -1, + 779, 836, 835, -1, 779, 782, 783, -1, + 779, 780, 486, -1, 779, 486, 836, -1, + 410, 221, 250, -1, 784, 495, 127, -1, + 784, 782, 495, -1, 1200, 1199, 252, -1, + 1200, 1138, 423, -1, 1200, 250, 1138, -1, + 253, 252, 1199, -1, 253, 784, 127, -1, + 253, 1199, 784, -1, 253, 845, 359, -1, + 253, 127, 845, -1, 255, 504, 256, -1, + 500, 627, 505, -1, 993, 503, 327, -1, + 993, 500, 503, -1, 508, 1270, 128, -1, + 508, 129, 507, -1, 508, 128, 129, -1, + 864, 265, 133, -1, 864, 135, 265, -1, + 864, 133, 859, -1, 864, 507, 135, -1, + 514, 230, 132, -1, 514, 459, 230, -1, + 514, 515, 459, -1, 1272, 130, 1270, -1, + 1272, 231, 130, -1, 1272, 132, 231, -1, + 131, 1266, 1517, -1, 131, 1517, 514, -1, + 131, 514, 132, -1, 131, 132, 1272, -1, + 131, 1272, 1266, -1, 1516, 1515, 259, -1, + 1580, 523, 1518, -1, 510, 517, 261, -1, + 510, 261, 262, -1, 520, 1045, 1043, -1, + 520, 262, 261, -1, 520, 1043, 1044, -1, + 861, 133, 265, -1, 861, 859, 133, -1, + 861, 265, 155, -1, 861, 631, 1520, -1, + 861, 155, 631, -1, 137, 505, 627, -1, + 137, 264, 505, -1, 266, 134, 505, -1, + 266, 135, 134, -1, 266, 265, 135, -1, + 136, 155, 265, -1, 136, 265, 264, -1, + 136, 264, 137, -1, 136, 627, 155, -1, + 136, 137, 627, -1, 1627, 1630, 1629, -1, + 1627, 1629, 521, -1, 1527, 521, 151, -1, + 1527, 151, 1529, -1, 1527, 1529, 1528, -1, + 308, 138, 307, -1, 308, 1529, 138, -1, + 519, 319, 1349, -1, 1590, 139, 391, -1, + 1590, 525, 139, -1, 280, 1282, 549, -1, + 280, 267, 269, -1, 280, 269, 1282, -1, + 270, 1282, 269, -1, 325, 556, 326, -1, + 325, 269, 267, -1, 325, 872, 269, -1, + 529, 872, 324, -1, 1149, 200, 272, -1, + 336, 1302, 1305, -1, 336, 1305, 335, -1, + 797, 1000, 531, -1, 553, 294, 140, -1, + 553, 140, 556, -1, 557, 281, 278, -1, + 532, 928, 533, -1, 532, 284, 286, -1, + 532, 286, 928, -1, 546, 565, 284, -1, + 546, 284, 532, -1, 546, 532, 545, -1, + 287, 568, 277, -1, 287, 289, 285, -1, + 550, 287, 277, -1, 550, 289, 287, -1, + 581, 141, 582, -1, 581, 291, 141, -1, + 581, 579, 291, -1, 292, 578, 143, -1, + 292, 579, 578, -1, 292, 143, 606, -1, + 292, 606, 295, -1, 952, 142, 560, -1, + 952, 582, 142, -1, 570, 571, 1320, -1, + 570, 1320, 1318, -1, 570, 299, 296, -1, + 573, 574, 303, -1, 573, 1320, 571, -1, + 573, 300, 1320, -1, 304, 574, 597, -1, + 304, 317, 143, -1, 304, 941, 942, -1, + 304, 143, 941, -1, 304, 942, 298, -1, + 304, 298, 303, -1, 614, 148, 318, -1, + 614, 613, 1578, -1, 144, 306, 307, -1, + 144, 307, 148, -1, 144, 614, 306, -1, + 144, 148, 614, -1, 309, 590, 595, -1, + 309, 595, 310, -1, 962, 310, 595, -1, + 962, 588, 310, -1, 962, 591, 588, -1, + 145, 147, 146, -1, 145, 146, 148, -1, + 145, 149, 147, -1, 145, 148, 307, -1, + 145, 307, 149, -1, 312, 598, 275, -1, + 312, 275, 968, -1, 600, 969, 313, -1, + 589, 954, 602, -1, 589, 595, 590, -1, + 589, 602, 595, -1, 314, 150, 151, -1, + 314, 275, 150, -1, 314, 969, 275, -1, + 314, 603, 969, -1, 314, 151, 295, -1, + 314, 295, 606, -1, 316, 596, 595, -1, + 316, 595, 602, -1, 316, 597, 596, -1, + 610, 611, 615, -1, 321, 611, 979, -1, + 321, 615, 611, -1, 152, 979, 611, -1, + 152, 619, 979, -1, 152, 611, 318, -1, + 152, 318, 619, -1, 323, 153, 271, -1, + 323, 295, 153, -1, 323, 326, 295, -1, + 323, 529, 324, -1, 154, 155, 627, -1, + 154, 627, 631, -1, 154, 631, 155, -1, + 633, 506, 327, -1, 633, 327, 632, -1, + 997, 327, 631, -1, 334, 335, 331, -1, + 334, 907, 906, -1, 334, 331, 339, -1, + 908, 907, 334, -1, 908, 334, 339, -1, + 1035, 1560, 654, -1, 815, 814, 510, -1, + 815, 510, 262, -1, 160, 156, 157, -1, + 160, 159, 156, -1, 160, 157, 232, -1, + 158, 341, 159, -1, 158, 1446, 341, -1, + 158, 232, 1446, -1, 158, 160, 232, -1, + 158, 159, 160, -1, 342, 665, 660, -1, + 342, 341, 345, -1, 346, 342, 345, -1, + 346, 665, 342, -1, 161, 352, 353, -1, + 161, 353, 162, -1, 161, 1051, 352, -1, + 161, 162, 1051, -1, 348, 665, 163, -1, + 348, 700, 699, -1, 348, 163, 164, -1, + 348, 164, 700, -1, 368, 703, 682, -1, + 368, 682, 369, -1, 351, 369, 665, -1, + 1048, 665, 353, -1, 165, 673, 672, -1, + 165, 577, 673, -1, 165, 166, 577, -1, + 165, 167, 166, -1, 165, 672, 167, -1, + 669, 355, 168, -1, 669, 168, 670, -1, + 169, 170, 171, -1, 169, 172, 170, -1, + 169, 171, 173, -1, 169, 173, 172, -1, + 174, 176, 175, -1, 174, 177, 176, -1, + 174, 175, 177, -1, 1057, 675, 1058, -1, + 356, 357, 178, -1, 356, 178, 179, -1, + 356, 179, 1058, -1, 180, 1058, 181, -1, + 180, 182, 1058, -1, 180, 181, 183, -1, + 180, 183, 182, -1, 1257, 359, 1258, -1, + 184, 1421, 683, -1, 184, 683, 185, -1, + 184, 186, 1421, -1, 184, 185, 186, -1, + 1411, 1414, 683, -1, 1427, 682, 698, -1, + 1083, 360, 1082, -1, 1083, 1081, 685, -1, + 696, 682, 365, -1, 366, 187, 1442, -1, + 366, 365, 682, -1, 366, 188, 187, -1, + 366, 682, 188, -1, 702, 351, 699, -1, + 702, 369, 351, -1, 702, 703, 368, -1, + 189, 191, 190, -1, 189, 192, 191, -1, + 189, 190, 192, -1, 372, 373, 197, -1, + 372, 197, 371, -1, 375, 714, 377, -1, + 193, 713, 377, -1, 193, 377, 714, -1, + 193, 712, 713, -1, 193, 714, 712, -1, + 715, 705, 379, -1, 715, 375, 376, -1, + 715, 714, 375, -1, 715, 706, 705, -1, + 194, 195, 379, -1, 194, 379, 704, -1, + 194, 196, 195, -1, 194, 704, 196, -1, + 382, 1109, 1107, -1, 382, 1111, 1109, -1, + 382, 383, 1111, -1, 386, 197, 385, -1, + 386, 371, 197, -1, 386, 707, 371, -1, + 388, 198, 389, -1, 388, 392, 198, -1, + 393, 391, 396, -1, 393, 1590, 391, -1, + 716, 749, 754, -1, 716, 754, 753, -1, + 716, 753, 393, -1, 716, 393, 396, -1, + 400, 398, 389, -1, 400, 389, 198, -1, + 400, 706, 399, -1, 400, 198, 706, -1, + 1150, 200, 1149, -1, 718, 1150, 1151, -1, + 718, 719, 199, -1, 718, 199, 200, -1, + 718, 200, 1150, -1, 1220, 724, 809, -1, + 406, 211, 728, -1, 406, 407, 201, -1, + 406, 1206, 211, -1, 406, 201, 456, -1, + 1120, 225, 1121, -1, 1143, 221, 410, -1, + 413, 729, 202, -1, 413, 414, 729, -1, + 413, 202, 745, -1, 731, 729, 414, -1, + 742, 739, 414, -1, 758, 203, 418, -1, + 758, 759, 203, -1, 750, 765, 929, -1, + 750, 929, 1161, -1, 1196, 768, 530, -1, + 420, 273, 204, -1, 420, 763, 273, -1, + 420, 204, 421, -1, 771, 760, 770, -1, + 767, 776, 777, -1, 1203, 425, 487, -1, + 1203, 786, 425, -1, 789, 786, 790, -1, + 639, 206, 205, -1, 639, 638, 206, -1, + 639, 205, 209, -1, 639, 1207, 643, -1, + 207, 209, 208, -1, 207, 639, 209, -1, + 207, 1207, 639, -1, 207, 1206, 1207, -1, + 207, 210, 1206, -1, 207, 211, 210, -1, + 207, 212, 211, -1, 207, 208, 212, -1, + 434, 213, 218, -1, 434, 1178, 762, -1, + 434, 218, 1178, -1, 434, 436, 214, -1, + 434, 214, 213, -1, 419, 418, 215, -1, + 419, 215, 435, -1, 1180, 1179, 795, -1, + 216, 217, 438, -1, 216, 218, 217, -1, + 216, 438, 1178, -1, 216, 1178, 218, -1, + 440, 439, 219, -1, 440, 220, 637, -1, + 440, 219, 220, -1, 440, 637, 800, -1, + 440, 800, 441, -1, 787, 423, 1138, -1, + 787, 1138, 1139, -1, 787, 790, 786, -1, + 1140, 746, 792, -1, 1140, 792, 790, -1, + 1140, 787, 1139, -1, 1140, 790, 787, -1, + 1145, 221, 1143, -1, 1145, 250, 221, -1, + 1145, 1138, 250, -1, 412, 222, 747, -1, + 412, 411, 223, -1, 412, 223, 222, -1, + 1101, 691, 1219, -1, 1217, 1219, 691, -1, + 445, 1099, 444, -1, 446, 448, 449, -1, + 446, 444, 448, -1, 446, 445, 444, -1, + 446, 806, 445, -1, 224, 443, 1470, -1, + 224, 444, 443, -1, 224, 1470, 448, -1, + 224, 448, 444, -1, 1461, 1470, 443, -1, + 1461, 443, 1219, -1, 1128, 225, 1120, -1, + 1468, 448, 1469, -1, 1468, 225, 1128, -1, + 1468, 1467, 1121, -1, 1468, 1121, 225, -1, + 1481, 1379, 1382, -1, 1481, 657, 1379, -1, + 1481, 1382, 226, -1, 1481, 226, 1465, -1, + 1238, 1237, 451, -1, 1027, 1028, 451, -1, + 817, 454, 453, -1, 1212, 1206, 456, -1, + 1212, 457, 454, -1, 1384, 226, 1382, -1, + 1384, 452, 226, -1, 1369, 1233, 651, -1, + 823, 831, 829, -1, 823, 227, 228, -1, + 823, 228, 824, -1, 823, 829, 830, -1, + 823, 830, 227, -1, 1222, 1223, 1236, -1, + 1222, 1236, 827, -1, 229, 824, 236, -1, + 229, 231, 230, -1, 229, 230, 459, -1, + 229, 459, 824, -1, 229, 234, 231, -1, + 229, 236, 234, -1, 695, 1447, 232, -1, + 695, 232, 233, -1, 468, 1082, 360, -1, + 468, 465, 1082, -1, 467, 233, 234, -1, + 467, 695, 233, -1, 467, 469, 695, -1, + 467, 234, 235, -1, 467, 235, 236, -1, + 467, 236, 466, -1, 833, 836, 471, -1, + 833, 471, 834, -1, 1242, 470, 237, -1, + 1242, 237, 1246, -1, 497, 358, 238, -1, + 497, 238, 1114, -1, 1249, 1264, 479, -1, + 808, 807, 479, -1, 1115, 238, 1261, -1, + 1115, 1114, 238, -1, 482, 1261, 1263, -1, + 482, 1263, 1118, -1, 482, 1115, 1261, -1, + 849, 483, 1501, -1, 840, 1501, 483, -1, + 484, 240, 486, -1, 484, 485, 240, -1, + 239, 485, 243, -1, 239, 240, 485, -1, + 239, 243, 241, -1, 239, 470, 240, -1, + 239, 241, 470, -1, 489, 242, 243, -1, + 489, 243, 485, -1, 489, 490, 242, -1, + 491, 487, 492, -1, 491, 489, 485, -1, + 494, 1255, 495, -1, 494, 846, 1255, -1, + 473, 248, 1504, -1, 473, 474, 1061, -1, + 473, 1061, 248, -1, 244, 853, 1504, -1, + 244, 1504, 248, -1, 244, 248, 853, -1, + 851, 245, 248, -1, 851, 248, 852, -1, + 851, 853, 245, -1, 246, 247, 1404, -1, + 246, 1404, 248, -1, 246, 1061, 247, -1, + 246, 248, 1061, -1, 498, 410, 679, -1, + 498, 679, 677, -1, 249, 252, 679, -1, + 249, 679, 410, -1, 249, 410, 250, -1, + 249, 1200, 252, -1, 249, 250, 1200, -1, + 251, 679, 252, -1, 251, 252, 253, -1, + 251, 359, 679, -1, 251, 253, 359, -1, + 254, 503, 504, -1, 254, 504, 255, -1, + 254, 255, 256, -1, 254, 256, 327, -1, + 254, 327, 503, -1, 502, 500, 505, -1, + 502, 503, 500, -1, 994, 327, 506, -1, + 994, 993, 327, -1, 863, 864, 859, -1, + 516, 517, 510, -1, 513, 259, 260, -1, + 513, 1516, 259, -1, 513, 260, 517, -1, + 258, 870, 1045, -1, 258, 1045, 520, -1, + 258, 520, 261, -1, 518, 259, 1515, -1, + 518, 867, 259, -1, 518, 1515, 523, -1, + 868, 608, 869, -1, 257, 867, 870, -1, + 257, 870, 258, -1, 257, 260, 259, -1, + 257, 259, 867, -1, 257, 261, 260, -1, + 257, 258, 261, -1, 816, 262, 520, -1, + 816, 815, 262, -1, 1229, 814, 1487, -1, + 1229, 1487, 1486, -1, 822, 1228, 1227, -1, + 862, 861, 1520, -1, 263, 264, 265, -1, + 263, 265, 266, -1, 263, 505, 264, -1, + 263, 266, 505, -1, 522, 319, 519, -1, + 522, 519, 523, -1, 522, 1578, 613, -1, + 522, 613, 319, -1, 279, 555, 556, -1, + 279, 556, 325, -1, 279, 267, 280, -1, + 279, 325, 267, -1, 268, 269, 873, -1, + 268, 270, 269, -1, 268, 873, 1282, -1, + 268, 1282, 270, -1, 528, 271, 526, -1, + 528, 526, 1588, -1, 528, 323, 271, -1, + 528, 529, 323, -1, 1148, 272, 273, -1, + 1148, 1149, 272, -1, 1148, 273, 763, -1, + 1361, 1362, 1360, -1, 932, 1196, 530, -1, + 932, 530, 894, -1, 932, 894, 539, -1, + 932, 885, 931, -1, 932, 539, 885, -1, + 634, 330, 531, -1, 634, 1011, 330, -1, + 634, 531, 1000, -1, 895, 894, 530, -1, + 1288, 540, 895, -1, 884, 885, 539, -1, + 884, 880, 882, -1, 538, 902, 534, -1, + 538, 531, 330, -1, 538, 330, 537, -1, + 542, 534, 902, -1, 898, 537, 899, -1, + 898, 901, 902, -1, 274, 335, 1305, -1, + 274, 331, 335, -1, 274, 332, 331, -1, + 274, 899, 537, -1, 274, 537, 332, -1, + 896, 274, 1305, -1, 896, 899, 274, -1, + 891, 892, 1293, -1, 891, 881, 880, -1, + 903, 1293, 892, -1, 652, 1358, 1360, -1, + 337, 1302, 336, -1, 599, 276, 275, -1, + 599, 275, 598, -1, 599, 320, 276, -1, + 599, 625, 320, -1, 1311, 877, 925, -1, + 917, 550, 277, -1, 917, 568, 916, -1, + 917, 277, 568, -1, 552, 561, 562, -1, + 552, 919, 561, -1, 552, 562, 553, -1, + 282, 278, 294, -1, 282, 294, 553, -1, + 282, 557, 278, -1, 554, 549, 919, -1, + 554, 555, 279, -1, 554, 280, 549, -1, + 554, 279, 280, -1, 558, 559, 293, -1, + 558, 281, 557, -1, 558, 294, 281, -1, + 922, 557, 282, -1, 922, 553, 562, -1, + 922, 282, 553, -1, 951, 952, 560, -1, + 951, 924, 925, -1, 951, 623, 1338, -1, + 951, 925, 877, -1, 563, 533, 928, -1, + 563, 926, 533, -1, 1313, 931, 885, -1, + 283, 284, 565, -1, 283, 565, 287, -1, + 283, 287, 285, -1, 283, 286, 284, -1, + 283, 285, 286, -1, 566, 287, 565, -1, + 566, 568, 287, -1, 288, 417, 289, -1, + 288, 289, 550, -1, 288, 550, 1282, -1, + 288, 1279, 417, -1, 288, 1282, 1280, -1, + 288, 1280, 1279, -1, 290, 291, 579, -1, + 290, 579, 292, -1, 290, 293, 291, -1, + 290, 558, 293, -1, 290, 294, 558, -1, + 290, 295, 294, -1, 290, 292, 295, -1, + 572, 674, 673, -1, 572, 570, 296, -1, + 572, 297, 674, -1, 572, 296, 297, -1, + 939, 298, 942, -1, 939, 303, 298, -1, + 939, 573, 303, -1, 939, 300, 573, -1, + 947, 946, 953, -1, 1317, 935, 299, -1, + 1317, 570, 1318, -1, 1317, 299, 570, -1, + 950, 1320, 300, -1, 950, 1321, 1320, -1, + 950, 300, 939, -1, 301, 304, 597, -1, + 301, 317, 304, -1, 301, 597, 316, -1, + 301, 316, 317, -1, 302, 303, 574, -1, + 302, 304, 303, -1, 302, 574, 304, -1, + 586, 614, 1578, -1, 305, 306, 614, -1, + 305, 614, 1577, -1, 305, 1577, 1530, -1, + 305, 307, 306, -1, 305, 308, 307, -1, + 305, 1529, 308, -1, 305, 1530, 1529, -1, + 958, 590, 309, -1, 958, 309, 310, -1, + 958, 310, 588, -1, 959, 590, 958, -1, + 961, 311, 964, -1, 961, 597, 311, -1, + 967, 312, 968, -1, 967, 598, 312, -1, + 1339, 313, 1340, -1, 1339, 600, 313, -1, + 604, 603, 314, -1, 604, 314, 606, -1, + 315, 602, 605, -1, 315, 316, 602, -1, + 315, 605, 317, -1, 315, 317, 316, -1, + 612, 614, 318, -1, 612, 318, 611, -1, + 1348, 1349, 319, -1, 1348, 319, 613, -1, + 982, 976, 623, -1, 982, 623, 951, -1, + 624, 619, 320, -1, 624, 320, 625, -1, + 978, 321, 979, -1, 978, 615, 321, -1, + 978, 977, 615, -1, 322, 323, 324, -1, + 322, 324, 872, -1, 322, 872, 325, -1, + 322, 325, 326, -1, 322, 326, 323, -1, + 999, 632, 327, -1, 999, 327, 997, -1, + 1005, 793, 1002, -1, 1009, 338, 1010, -1, + 1009, 1020, 338, -1, 644, 635, 802, -1, + 328, 1011, 329, -1, 328, 330, 1011, -1, + 328, 329, 331, -1, 328, 331, 332, -1, + 328, 537, 330, -1, 328, 332, 537, -1, + 333, 335, 334, -1, 333, 334, 906, -1, + 333, 336, 335, -1, 333, 337, 336, -1, + 333, 906, 1302, -1, 333, 1302, 337, -1, + 649, 1560, 1035, -1, 650, 338, 1020, -1, + 650, 339, 338, -1, 650, 908, 339, -1, + 650, 1541, 908, -1, 650, 653, 1541, -1, + 1024, 1555, 1358, -1, 1024, 1358, 652, -1, + 1370, 1372, 656, -1, 655, 656, 1233, -1, + 1394, 654, 1038, -1, 1394, 1035, 654, -1, + 1032, 1038, 654, -1, 1032, 1551, 1038, -1, + 1042, 869, 608, -1, 1042, 870, 869, -1, + 1042, 1045, 870, -1, 607, 1354, 608, -1, + 607, 983, 985, -1, 607, 973, 983, -1, + 607, 985, 1355, -1, 607, 1355, 1354, -1, + 658, 608, 1354, -1, 658, 1042, 608, -1, + 340, 660, 341, -1, 340, 342, 660, -1, + 340, 341, 342, -1, 343, 345, 344, -1, + 343, 346, 345, -1, 343, 344, 665, -1, + 343, 665, 346, -1, 347, 350, 665, -1, + 347, 665, 348, -1, 347, 699, 350, -1, + 347, 348, 699, -1, 349, 665, 350, -1, + 349, 351, 665, -1, 349, 350, 699, -1, + 349, 699, 351, -1, 663, 665, 662, -1, + 663, 667, 665, -1, 1050, 353, 352, -1, + 1050, 1048, 353, -1, 1050, 352, 1051, -1, + 671, 354, 355, -1, 671, 355, 669, -1, + 671, 674, 354, -1, 1053, 1058, 675, -1, + 1053, 356, 1058, -1, 1053, 1054, 357, -1, + 1053, 357, 356, -1, 1400, 1058, 1061, -1, + 850, 1261, 358, -1, 850, 358, 497, -1, + 850, 497, 677, -1, 678, 359, 1257, -1, + 678, 679, 359, -1, 678, 1257, 850, -1, + 1610, 1427, 698, -1, 1610, 1075, 1427, -1, + 1079, 1078, 682, -1, 1079, 682, 1427, -1, + 826, 1433, 1432, -1, 826, 1432, 685, -1, + 1434, 1495, 1216, -1, 1434, 825, 1495, -1, + 1434, 1433, 826, -1, 1434, 826, 825, -1, + 688, 364, 360, -1, 688, 360, 1083, -1, + 688, 687, 364, -1, 688, 685, 1432, -1, + 688, 1083, 685, -1, 689, 1091, 1067, -1, + 689, 681, 1071, -1, 689, 1067, 1065, -1, + 689, 1065, 681, -1, 1093, 689, 1071, -1, + 1098, 481, 1064, -1, 1098, 1099, 481, -1, + 690, 1067, 1091, -1, 1104, 1569, 1096, -1, + 1095, 1089, 1093, -1, 1095, 693, 1089, -1, + 1095, 361, 693, -1, 1095, 1096, 1569, -1, + 1095, 1569, 361, -1, 694, 468, 360, -1, + 694, 469, 468, -1, 694, 360, 364, -1, + 694, 364, 362, -1, 694, 695, 469, -1, + 694, 362, 1621, -1, 363, 687, 1102, -1, + 363, 1102, 693, -1, 363, 693, 361, -1, + 363, 1569, 1568, -1, 363, 361, 1569, -1, + 1622, 1621, 362, -1, 1622, 363, 1568, -1, + 1622, 687, 363, -1, 1622, 362, 364, -1, + 1622, 364, 687, -1, 1439, 696, 365, -1, + 1439, 365, 366, -1, 1439, 366, 1442, -1, + 1443, 702, 699, -1, 1443, 1441, 1442, -1, + 367, 368, 369, -1, 367, 369, 702, -1, + 367, 702, 368, -1, 370, 371, 707, -1, + 370, 372, 371, -1, 370, 707, 373, -1, + 370, 373, 372, -1, 374, 376, 375, -1, + 374, 375, 377, -1, 374, 377, 706, -1, + 374, 715, 376, -1, 374, 706, 715, -1, + 378, 715, 379, -1, 378, 710, 715, -1, + 378, 379, 380, -1, 378, 380, 710, -1, + 381, 1107, 385, -1, 381, 382, 1107, -1, + 381, 385, 383, -1, 381, 383, 382, -1, + 1108, 1110, 704, -1, 384, 385, 1107, -1, + 384, 386, 385, -1, 384, 1107, 707, -1, + 384, 707, 386, -1, 387, 389, 390, -1, + 387, 390, 392, -1, 387, 388, 389, -1, + 387, 392, 388, -1, 395, 389, 398, -1, + 395, 390, 389, -1, 395, 396, 391, -1, + 395, 391, 392, -1, 395, 392, 390, -1, + 752, 1590, 393, -1, 752, 1276, 1590, -1, + 752, 393, 753, -1, 721, 394, 719, -1, + 721, 709, 394, -1, 723, 396, 395, -1, + 723, 395, 398, -1, 723, 716, 396, -1, + 723, 398, 711, -1, 723, 711, 722, -1, + 397, 399, 398, -1, 397, 400, 399, -1, + 397, 398, 400, -1, 720, 716, 723, -1, + 408, 724, 1220, -1, 408, 403, 407, -1, + 401, 402, 403, -1, 401, 403, 408, -1, + 401, 408, 1220, -1, 401, 1220, 1464, -1, + 401, 1464, 404, -1, 401, 453, 402, -1, + 401, 404, 453, -1, 405, 456, 1206, -1, + 405, 1206, 406, -1, 405, 406, 456, -1, + 409, 406, 728, -1, 409, 407, 406, -1, + 409, 408, 407, -1, 1129, 1118, 842, -1, + 727, 724, 408, -1, 727, 408, 409, -1, + 727, 409, 728, -1, 1135, 1120, 736, -1, + 1123, 736, 1120, -1, 1123, 731, 737, -1, + 1123, 730, 731, -1, 1142, 1143, 734, -1, + 733, 1143, 410, -1, 733, 410, 498, -1, + 738, 737, 731, -1, 738, 731, 414, -1, + 738, 414, 739, -1, 738, 739, 1142, -1, + 738, 1142, 735, -1, 1133, 1142, 734, -1, + 1133, 735, 1142, -1, 744, 745, 411, -1, + 744, 411, 412, -1, 744, 412, 747, -1, + 743, 414, 413, -1, 743, 742, 414, -1, + 743, 413, 745, -1, 1164, 1453, 927, -1, + 1164, 927, 416, -1, 1164, 416, 1165, -1, + 1163, 1279, 1276, -1, 1163, 1276, 752, -1, + 415, 416, 417, -1, 415, 1165, 416, -1, + 415, 1163, 1165, -1, 415, 417, 1279, -1, + 415, 1279, 1163, -1, 756, 758, 418, -1, + 772, 756, 418, -1, 772, 777, 756, -1, + 772, 761, 1173, -1, 772, 418, 419, -1, + 772, 419, 435, -1, 772, 435, 761, -1, + 1154, 765, 750, -1, 1194, 770, 1186, -1, + 769, 1197, 929, -1, 769, 929, 765, -1, + 769, 765, 771, -1, 1171, 760, 767, -1, + 1171, 767, 777, -1, 766, 760, 771, -1, + 766, 767, 760, -1, 422, 763, 420, -1, + 422, 775, 763, -1, 422, 420, 421, -1, + 422, 421, 757, -1, 774, 422, 757, -1, + 774, 775, 422, -1, 774, 756, 777, -1, + 774, 757, 756, -1, 778, 1203, 487, -1, + 1205, 1200, 423, -1, 1205, 423, 787, -1, + 424, 425, 786, -1, 424, 786, 789, -1, + 424, 432, 492, -1, 424, 426, 432, -1, + 424, 789, 426, -1, 424, 487, 425, -1, + 424, 492, 487, -1, 791, 427, 426, -1, + 791, 426, 789, -1, 791, 792, 428, -1, + 791, 429, 427, -1, 791, 428, 429, -1, + 430, 432, 431, -1, 430, 492, 432, -1, + 430, 431, 490, -1, 430, 490, 492, -1, + 1208, 643, 1207, -1, 1208, 1209, 643, -1, + 433, 434, 762, -1, 433, 762, 761, -1, + 433, 761, 435, -1, 433, 435, 436, -1, + 433, 436, 434, -1, 437, 1178, 438, -1, + 437, 1179, 1178, -1, 437, 438, 439, -1, + 437, 439, 440, -1, 437, 441, 1179, -1, + 437, 440, 441, -1, 1189, 1188, 1181, -1, + 1189, 1181, 1180, -1, 911, 636, 1007, -1, + 799, 795, 1179, -1, 799, 1179, 441, -1, + 799, 441, 800, -1, 912, 636, 911, -1, + 801, 636, 912, -1, 801, 912, 796, -1, + 801, 802, 635, -1, 801, 796, 799, -1, + 1137, 746, 1140, -1, 442, 443, 444, -1, + 442, 444, 1099, -1, 442, 1099, 1101, -1, + 442, 1219, 443, -1, 442, 1101, 1219, -1, + 1436, 1217, 691, -1, 805, 445, 806, -1, + 805, 480, 1099, -1, 805, 1099, 445, -1, + 843, 446, 449, -1, 843, 806, 446, -1, + 1473, 1470, 1461, -1, 1218, 1461, 1219, -1, + 1127, 449, 1128, -1, 1127, 843, 449, -1, + 447, 449, 448, -1, 447, 448, 1468, -1, + 447, 1128, 449, -1, 447, 1468, 1128, -1, + 812, 657, 1481, -1, 812, 1481, 1482, -1, + 810, 1028, 1030, -1, 810, 451, 1028, -1, + 810, 1238, 451, -1, 450, 461, 1223, -1, + 450, 451, 461, -1, 1490, 450, 1223, -1, + 1490, 1027, 451, -1, 1490, 451, 450, -1, + 1385, 452, 1384, -1, 1385, 453, 452, -1, + 1385, 817, 453, -1, 1231, 454, 817, -1, + 1231, 1212, 454, -1, 455, 1212, 456, -1, + 455, 457, 1212, -1, 455, 456, 458, -1, + 455, 458, 457, -1, 818, 1459, 1233, -1, + 818, 1233, 1369, -1, 821, 511, 1229, -1, + 821, 1229, 1228, -1, 821, 1228, 822, -1, + 821, 459, 515, -1, 821, 515, 511, -1, + 821, 824, 459, -1, 460, 1236, 1223, -1, + 460, 1237, 1236, -1, 460, 1223, 461, -1, + 460, 461, 1237, -1, 1235, 1085, 1236, -1, + 1225, 1085, 463, -1, 1225, 463, 831, -1, + 1225, 822, 1227, -1, 1225, 831, 822, -1, + 462, 827, 1236, -1, 462, 1236, 1085, -1, + 462, 1225, 827, -1, 462, 1085, 1225, -1, + 1080, 1082, 830, -1, 1080, 831, 463, -1, + 1080, 463, 1085, -1, 464, 466, 465, -1, + 464, 467, 466, -1, 464, 465, 468, -1, + 464, 468, 469, -1, 464, 469, 467, -1, + 838, 841, 840, -1, 472, 470, 1242, -1, + 472, 471, 470, -1, 472, 834, 471, -1, + 1243, 838, 834, -1, 1243, 841, 838, -1, + 1243, 834, 472, -1, 1243, 472, 1242, -1, + 1502, 1240, 474, -1, 1502, 473, 1504, -1, + 1502, 474, 473, -1, 477, 474, 1240, -1, + 477, 1061, 474, -1, 475, 1507, 476, -1, + 475, 1240, 1507, -1, 475, 477, 1240, -1, + 475, 476, 1061, -1, 475, 1061, 477, -1, + 1248, 479, 807, -1, 1248, 1249, 479, -1, + 1248, 807, 843, -1, 478, 479, 1064, -1, + 478, 808, 479, -1, 478, 805, 808, -1, + 478, 480, 805, -1, 478, 1064, 481, -1, + 478, 481, 480, -1, 1117, 482, 1118, -1, + 1117, 1115, 482, -1, 855, 846, 856, -1, + 1503, 1504, 853, -1, 1503, 849, 1501, -1, + 848, 847, 840, -1, 848, 840, 483, -1, + 848, 483, 849, -1, 781, 485, 484, -1, + 781, 491, 485, -1, 781, 486, 780, -1, + 781, 484, 486, -1, 781, 487, 491, -1, + 781, 778, 487, -1, 488, 490, 489, -1, + 488, 489, 491, -1, 488, 492, 490, -1, + 488, 491, 492, -1, 493, 835, 846, -1, + 493, 846, 494, -1, 493, 779, 835, -1, + 493, 782, 779, -1, 493, 495, 782, -1, + 493, 494, 495, -1, 496, 677, 497, -1, + 496, 498, 677, -1, 496, 497, 1114, -1, + 496, 1114, 733, -1, 496, 733, 498, -1, + 628, 993, 991, -1, 628, 629, 993, -1, + 499, 627, 500, -1, 499, 629, 627, -1, + 499, 500, 993, -1, 499, 993, 629, -1, + 501, 503, 502, -1, 501, 504, 503, -1, + 501, 502, 505, -1, 501, 505, 504, -1, + 992, 506, 633, -1, 992, 994, 506, -1, + 860, 1511, 863, -1, 1267, 863, 1511, -1, + 1274, 863, 1267, -1, 1269, 507, 864, -1, + 1269, 1270, 508, -1, 1269, 508, 507, -1, + 509, 516, 510, -1, 509, 510, 814, -1, + 509, 511, 515, -1, 509, 515, 516, -1, + 509, 814, 1229, -1, 509, 1229, 511, -1, + 512, 1517, 1516, -1, 512, 1516, 513, -1, + 512, 514, 1517, -1, 512, 515, 514, -1, + 512, 516, 515, -1, 512, 517, 516, -1, + 512, 513, 517, -1, 866, 867, 518, -1, + 866, 1349, 868, -1, 866, 519, 1349, -1, + 866, 523, 519, -1, 866, 518, 523, -1, + 1033, 520, 1044, -1, 1033, 816, 520, -1, + 1033, 1391, 816, -1, 1583, 1627, 521, -1, + 1583, 521, 1527, -1, 1579, 1578, 522, -1, + 1579, 523, 1580, -1, 1579, 522, 523, -1, + 524, 525, 1590, -1, 524, 1590, 1588, -1, + 524, 1588, 526, -1, 524, 527, 525, -1, + 524, 526, 527, -1, 1531, 529, 528, -1, + 1531, 528, 1588, -1, 1531, 872, 529, -1, + 875, 895, 530, -1, 875, 1288, 895, -1, + 875, 530, 768, -1, 875, 768, 1183, -1, + 1306, 1288, 1308, -1, 535, 531, 538, -1, + 535, 538, 534, -1, 535, 797, 531, -1, + 535, 543, 797, -1, 879, 545, 532, -1, + 879, 532, 533, -1, 879, 878, 545, -1, + 1285, 879, 888, -1, 1285, 1305, 1304, -1, + 1285, 1304, 951, -1, 1285, 951, 877, -1, + 886, 1313, 885, -1, 886, 926, 1313, -1, + 887, 879, 533, -1, 887, 888, 879, -1, + 887, 533, 926, -1, 1284, 884, 882, -1, + 1284, 1285, 888, -1, 889, 540, 1288, -1, + 889, 542, 540, -1, 889, 534, 542, -1, + 889, 535, 534, -1, 889, 1290, 543, -1, + 889, 543, 535, -1, 536, 537, 898, -1, + 536, 898, 902, -1, 536, 538, 537, -1, + 536, 902, 538, -1, 893, 880, 884, -1, + 893, 891, 880, -1, 893, 539, 894, -1, + 893, 884, 539, -1, 1292, 881, 891, -1, + 1292, 891, 1293, -1, 541, 903, 892, -1, + 541, 892, 895, -1, 541, 895, 540, -1, + 541, 540, 542, -1, 900, 903, 541, -1, + 900, 542, 902, -1, 900, 541, 542, -1, + 904, 901, 897, -1, 1303, 652, 1360, -1, + 1303, 1300, 1301, -1, 1303, 1301, 652, -1, + 910, 543, 1290, -1, 910, 797, 543, -1, + 544, 878, 877, -1, 544, 545, 878, -1, + 544, 546, 545, -1, 544, 565, 546, -1, + 544, 877, 565, -1, 547, 925, 561, -1, + 547, 1311, 925, -1, 547, 561, 1311, -1, + 1310, 877, 1311, -1, 1310, 916, 568, -1, + 1310, 568, 567, -1, 915, 1311, 561, -1, + 915, 561, 919, -1, 918, 919, 549, -1, + 918, 549, 917, -1, 548, 917, 549, -1, + 548, 550, 917, -1, 548, 549, 1282, -1, + 548, 1282, 550, -1, 551, 552, 553, -1, + 551, 555, 554, -1, 551, 919, 552, -1, + 551, 554, 919, -1, 551, 556, 555, -1, + 551, 553, 556, -1, 921, 557, 922, -1, + 921, 924, 951, -1, 921, 559, 558, -1, + 921, 558, 557, -1, 921, 560, 559, -1, + 921, 951, 560, -1, 923, 562, 561, -1, + 923, 922, 562, -1, 923, 561, 925, -1, + 1596, 926, 563, -1, 1596, 563, 928, -1, + 1314, 931, 1313, -1, 564, 565, 877, -1, + 564, 566, 565, -1, 564, 1310, 567, -1, + 564, 877, 1310, -1, 564, 567, 568, -1, + 564, 568, 566, -1, 569, 571, 570, -1, + 569, 570, 572, -1, 569, 573, 571, -1, + 569, 574, 573, -1, 569, 576, 575, -1, + 569, 577, 576, -1, 569, 575, 965, -1, + 569, 965, 574, -1, 569, 673, 577, -1, + 569, 572, 673, -1, 583, 946, 945, -1, + 583, 953, 946, -1, 583, 944, 578, -1, + 583, 945, 944, -1, 583, 578, 579, -1, + 583, 579, 581, -1, 580, 581, 582, -1, + 580, 582, 952, -1, 580, 952, 953, -1, + 580, 583, 581, -1, 580, 953, 583, -1, + 936, 1336, 937, -1, 584, 1329, 934, -1, + 1331, 1329, 584, -1, 1331, 584, 934, -1, + 943, 939, 942, -1, 949, 948, 947, -1, + 949, 947, 953, -1, 1323, 1321, 950, -1, + 1323, 1331, 1322, -1, 585, 1577, 614, -1, + 585, 614, 586, -1, 585, 1578, 1577, -1, + 585, 586, 1578, -1, 587, 1336, 1334, -1, + 587, 1334, 958, -1, 587, 588, 1336, -1, + 587, 958, 588, -1, 1326, 954, 589, -1, + 1326, 589, 590, -1, 1326, 590, 959, -1, + 963, 591, 962, -1, 963, 592, 591, -1, + 963, 593, 592, -1, 963, 965, 593, -1, + 594, 962, 595, -1, 594, 961, 962, -1, + 594, 595, 596, -1, 594, 596, 597, -1, + 594, 597, 961, -1, 970, 600, 1343, -1, + 970, 969, 600, -1, 626, 598, 967, -1, + 626, 599, 598, -1, 626, 625, 599, -1, + 626, 967, 988, -1, 626, 988, 622, -1, + 972, 1343, 600, -1, 972, 600, 1339, -1, + 601, 602, 603, -1, 601, 603, 604, -1, + 601, 605, 602, -1, 601, 606, 605, -1, + 601, 604, 606, -1, 1350, 616, 984, -1, + 1350, 610, 615, -1, 1350, 615, 616, -1, + 1347, 973, 607, -1, 1347, 607, 608, -1, + 1347, 608, 868, -1, 1347, 868, 1349, -1, + 609, 611, 610, -1, 609, 612, 611, -1, + 609, 610, 1350, -1, 609, 1350, 1348, -1, + 609, 1348, 613, -1, 609, 613, 614, -1, + 609, 614, 612, -1, 975, 976, 982, -1, + 975, 615, 977, -1, 975, 616, 615, -1, + 975, 982, 984, -1, 975, 984, 616, -1, + 981, 1304, 617, -1, 981, 951, 1304, -1, + 981, 982, 951, -1, 981, 617, 1355, -1, + 981, 1355, 985, -1, 987, 1338, 623, -1, + 987, 623, 622, -1, 987, 622, 988, -1, + 971, 1342, 988, -1, 971, 1343, 1342, -1, + 971, 970, 1343, -1, 618, 976, 979, -1, + 618, 624, 976, -1, 618, 979, 619, -1, + 618, 619, 624, -1, 620, 623, 976, -1, + 620, 976, 624, -1, 620, 624, 623, -1, + 621, 622, 623, -1, 621, 623, 624, -1, + 621, 624, 625, -1, 621, 625, 626, -1, + 621, 626, 622, -1, 990, 631, 627, -1, + 990, 630, 631, -1, 990, 628, 991, -1, + 990, 627, 629, -1, 990, 629, 628, -1, + 990, 633, 630, -1, 990, 992, 633, -1, + 996, 631, 630, -1, 996, 997, 631, -1, + 996, 632, 999, -1, 996, 633, 632, -1, + 996, 630, 633, -1, 998, 999, 997, -1, + 1014, 634, 1000, -1, 1014, 1011, 634, -1, + 641, 1006, 1007, -1, 641, 635, 644, -1, + 641, 1007, 636, -1, 641, 636, 801, -1, + 641, 801, 635, -1, 1368, 1369, 651, -1, + 1364, 1002, 1365, -1, 1013, 1005, 1002, -1, + 803, 800, 637, -1, 803, 637, 638, -1, + 803, 643, 802, -1, 803, 639, 643, -1, + 803, 638, 639, -1, 640, 793, 1005, -1, + 640, 644, 793, -1, 640, 1005, 1006, -1, + 640, 1006, 641, -1, 640, 641, 644, -1, + 1210, 793, 644, -1, 1210, 644, 1209, -1, + 642, 802, 643, -1, 642, 644, 802, -1, + 642, 643, 1209, -1, 642, 1209, 644, -1, + 1353, 1355, 1304, -1, 1353, 1304, 1015, -1, + 646, 1304, 1362, -1, 646, 1015, 1304, -1, + 646, 648, 1015, -1, 645, 1018, 648, -1, + 645, 1362, 1359, -1, 645, 1359, 1018, -1, + 645, 646, 1362, -1, 645, 648, 646, -1, + 647, 648, 1018, -1, 647, 1015, 648, -1, + 647, 1018, 1019, -1, 647, 1019, 1015, -1, + 1034, 649, 1035, -1, 1034, 1044, 1041, -1, + 1034, 1041, 649, -1, 1017, 1019, 1559, -1, + 1017, 1041, 1016, -1, 1017, 649, 1041, -1, + 1017, 1560, 649, -1, 1017, 1559, 1560, -1, + 1021, 650, 1020, -1, 1021, 653, 650, -1, + 1022, 1023, 1025, -1, 1022, 653, 1021, -1, + 1374, 656, 1372, -1, 1374, 651, 656, -1, + 1374, 1368, 651, -1, 1546, 652, 1301, -1, + 1546, 1024, 652, -1, 1540, 653, 1022, -1, + 1540, 1022, 1025, -1, 1540, 1541, 653, -1, + 1558, 654, 1560, -1, 1558, 1032, 654, -1, + 1234, 655, 1233, -1, 1376, 1633, 1370, -1, + 1376, 1234, 1026, -1, 1376, 655, 1234, -1, + 1376, 1370, 656, -1, 1376, 656, 655, -1, + 1378, 812, 1030, -1, 1378, 1379, 657, -1, + 1378, 657, 812, -1, 1383, 1234, 1386, -1, + 1383, 1026, 1234, -1, 1037, 1038, 1631, -1, + 1037, 1631, 1632, -1, 1037, 1632, 1036, -1, + 1393, 1035, 1394, -1, 1356, 658, 1354, -1, + 1356, 1016, 1041, -1, 1356, 1042, 658, -1, + 659, 660, 665, -1, 659, 665, 1049, -1, + 659, 1051, 660, -1, 659, 1049, 1051, -1, + 1047, 665, 667, -1, 1047, 1049, 665, -1, + 1047, 667, 1048, -1, 661, 662, 665, -1, + 661, 665, 666, -1, 661, 663, 662, -1, + 661, 667, 663, -1, 661, 666, 667, -1, + 664, 665, 1048, -1, 664, 666, 665, -1, + 664, 1048, 667, -1, 664, 667, 666, -1, + 668, 669, 670, -1, 668, 671, 669, -1, + 668, 670, 672, -1, 668, 672, 673, -1, + 668, 673, 674, -1, 668, 674, 671, -1, + 1055, 675, 1057, -1, 1055, 1053, 675, -1, + 1402, 1245, 1054, -1, 1402, 1057, 1059, -1, + 1402, 1054, 1055, -1, 1402, 1055, 1057, -1, + 676, 850, 677, -1, 676, 678, 850, -1, + 676, 677, 679, -1, 676, 679, 678, -1, + 1265, 1262, 680, -1, 1265, 1064, 1264, -1, + 1265, 1610, 1064, -1, 1074, 680, 1262, -1, + 1074, 1265, 680, -1, 1074, 1610, 1265, -1, + 1615, 681, 1065, -1, 1615, 1071, 681, -1, + 697, 698, 682, -1, 697, 682, 696, -1, + 1413, 852, 1404, -1, 1413, 1072, 852, -1, + 1417, 1420, 1072, -1, 1417, 683, 1418, -1, + 1417, 1411, 683, -1, 684, 1420, 1421, -1, + 684, 1421, 1077, -1, 684, 1077, 1420, -1, + 1066, 1098, 1064, -1, 1066, 1069, 1098, -1, + 1068, 1067, 690, -1, 1068, 690, 1069, -1, + 1086, 685, 1081, -1, 1086, 826, 685, -1, + 686, 1102, 687, -1, 686, 687, 688, -1, + 686, 1432, 1102, -1, 686, 688, 1432, -1, + 1090, 1091, 689, -1, 1090, 689, 1093, -1, + 1094, 1616, 1613, -1, 692, 1436, 691, -1, + 692, 1103, 1436, -1, 692, 1091, 1103, -1, + 692, 690, 1091, -1, 1100, 1098, 1069, -1, + 1100, 1069, 690, -1, 1100, 691, 1101, -1, + 1100, 692, 691, -1, 1100, 690, 692, -1, + 1430, 1089, 693, -1, 1430, 693, 1102, -1, + 1448, 694, 1621, -1, 1448, 695, 694, -1, + 1448, 1447, 695, -1, 1438, 696, 1439, -1, + 1438, 697, 696, -1, 1438, 1610, 698, -1, + 1438, 698, 697, -1, 1444, 1443, 699, -1, + 1444, 699, 700, -1, 1444, 700, 1445, -1, + 701, 1443, 1442, -1, 701, 702, 1443, -1, + 701, 1442, 703, -1, 701, 703, 702, -1, + 1566, 1441, 1443, -1, 1566, 1104, 1440, -1, + 1106, 704, 705, -1, 1106, 1108, 704, -1, + 1106, 705, 706, -1, 1106, 706, 707, -1, + 1106, 707, 1107, -1, 708, 710, 709, -1, + 708, 709, 721, -1, 708, 722, 711, -1, + 708, 721, 722, -1, 708, 713, 712, -1, + 708, 711, 713, -1, 708, 712, 714, -1, + 708, 715, 710, -1, 708, 714, 715, -1, + 748, 749, 716, -1, 748, 716, 720, -1, + 748, 720, 718, -1, 748, 718, 1151, -1, + 717, 719, 718, -1, 717, 718, 720, -1, + 717, 721, 719, -1, 717, 722, 721, -1, + 717, 723, 722, -1, 717, 720, 723, -1, + 1116, 1118, 1129, -1, 725, 724, 727, -1, + 725, 809, 724, -1, 725, 1466, 809, -1, + 725, 1467, 1466, -1, 725, 1121, 1467, -1, + 1122, 1121, 725, -1, 1122, 725, 727, -1, + 1122, 730, 1123, -1, 726, 727, 728, -1, + 726, 728, 729, -1, 726, 730, 1122, -1, + 726, 1122, 727, -1, 726, 729, 731, -1, + 726, 731, 730, -1, 1126, 1128, 1120, -1, + 1126, 1120, 1135, -1, 732, 1114, 1113, -1, + 732, 733, 1114, -1, 732, 1133, 734, -1, + 732, 1113, 1133, -1, 732, 734, 1143, -1, + 732, 1143, 733, -1, 1132, 1133, 1113, -1, + 1132, 1125, 1135, -1, 1132, 1129, 1125, -1, + 1132, 1116, 1129, -1, 1134, 735, 1133, -1, + 1134, 1135, 736, -1, 1134, 736, 1123, -1, + 1134, 1123, 737, -1, 1134, 737, 738, -1, + 1134, 738, 735, -1, 1144, 739, 742, -1, + 1144, 742, 741, -1, 1144, 1142, 739, -1, + 1144, 741, 1137, -1, 740, 741, 742, -1, + 740, 742, 743, -1, 740, 745, 744, -1, + 740, 743, 745, -1, 740, 747, 746, -1, + 740, 744, 747, -1, 740, 746, 1137, -1, + 740, 1137, 741, -1, 1157, 763, 1156, -1, + 1157, 1148, 763, -1, 1152, 749, 748, -1, + 1152, 748, 1151, -1, 1152, 754, 749, -1, + 1152, 1146, 754, -1, 1160, 750, 1161, -1, + 1160, 1154, 750, -1, 1167, 754, 1146, -1, + 1451, 1146, 1168, -1, 1451, 1167, 1146, -1, + 751, 1163, 752, -1, 751, 752, 753, -1, + 751, 1167, 1163, -1, 751, 753, 754, -1, + 751, 754, 1167, -1, 755, 756, 757, -1, + 755, 758, 756, -1, 755, 757, 759, -1, + 755, 759, 758, -1, 1187, 770, 760, -1, + 1187, 1186, 770, -1, 1187, 1181, 1188, -1, + 1187, 760, 1171, -1, 1177, 761, 762, -1, + 1177, 1173, 761, -1, 1177, 762, 1178, -1, + 1155, 1156, 763, -1, 1155, 763, 775, -1, + 764, 765, 1154, -1, 764, 1155, 776, -1, + 764, 1154, 1155, -1, 764, 771, 765, -1, + 764, 766, 771, -1, 764, 776, 767, -1, + 764, 767, 766, -1, 1193, 768, 1196, -1, + 1193, 1183, 768, -1, 1185, 1193, 1194, -1, + 1185, 1194, 1186, -1, 1185, 1191, 1537, -1, + 1195, 1197, 769, -1, 1195, 770, 1194, -1, + 1195, 771, 770, -1, 1195, 769, 771, -1, + 1172, 772, 1173, -1, 1172, 777, 772, -1, + 1172, 1171, 777, -1, 773, 775, 774, -1, + 773, 776, 1155, -1, 773, 1155, 775, -1, + 773, 777, 776, -1, 773, 774, 777, -1, + 1202, 1203, 778, -1, 1202, 780, 779, -1, + 1202, 779, 783, -1, 1202, 781, 780, -1, + 1202, 778, 781, -1, 1204, 783, 782, -1, + 1204, 782, 784, -1, 1204, 1202, 783, -1, + 1204, 784, 1199, -1, 785, 786, 1203, -1, + 785, 1203, 1205, -1, 785, 787, 786, -1, + 785, 1205, 787, -1, 788, 789, 790, -1, + 788, 791, 789, -1, 788, 790, 792, -1, + 788, 792, 791, -1, 819, 1367, 1365, -1, + 819, 1002, 793, -1, 819, 1365, 1002, -1, + 819, 793, 1210, -1, 819, 1210, 1211, -1, + 1190, 914, 1191, -1, 1190, 913, 914, -1, + 794, 1180, 795, -1, 794, 1189, 1180, -1, + 794, 913, 1190, -1, 794, 1190, 1189, -1, + 794, 795, 799, -1, 794, 799, 796, -1, + 794, 912, 913, -1, 794, 796, 912, -1, + 1535, 1191, 914, -1, 1535, 1175, 1191, -1, + 1001, 911, 1007, -1, 1001, 1000, 797, -1, + 1001, 797, 910, -1, 1001, 910, 911, -1, + 798, 799, 800, -1, 798, 801, 799, -1, + 798, 802, 801, -1, 798, 800, 803, -1, + 798, 803, 802, -1, 804, 805, 806, -1, + 804, 806, 843, -1, 804, 843, 807, -1, + 804, 807, 808, -1, 804, 808, 805, -1, + 1463, 1498, 1499, -1, 1463, 1499, 1482, -1, + 1478, 809, 1466, -1, 1478, 1220, 809, -1, + 1462, 1216, 1495, -1, 1462, 1461, 1218, -1, + 813, 1030, 812, -1, 813, 810, 1030, -1, + 813, 1238, 810, -1, 811, 812, 1482, -1, + 811, 1482, 1499, -1, 811, 1499, 1238, -1, + 811, 1238, 813, -1, 811, 813, 812, -1, + 1039, 1487, 814, -1, 1039, 814, 815, -1, + 1039, 815, 816, -1, 1039, 816, 1391, -1, + 1232, 1231, 817, -1, 1232, 1385, 1386, -1, + 1232, 817, 1385, -1, 1232, 1386, 1234, -1, + 1457, 1369, 1367, -1, 1457, 818, 1369, -1, + 1457, 1367, 819, -1, 1457, 819, 1211, -1, + 1457, 1459, 818, -1, 820, 821, 822, -1, + 820, 831, 823, -1, 820, 822, 831, -1, + 820, 823, 824, -1, 820, 824, 821, -1, + 1494, 1495, 825, -1, 1494, 1086, 1235, -1, + 1494, 825, 826, -1, 1494, 826, 1086, -1, + 1224, 1222, 827, -1, 1224, 827, 1225, -1, + 828, 830, 829, -1, 828, 1080, 830, -1, + 828, 829, 831, -1, 828, 831, 1080, -1, + 832, 833, 834, -1, 832, 834, 838, -1, + 832, 835, 836, -1, 832, 836, 833, -1, + 832, 838, 839, -1, 832, 839, 846, -1, + 832, 846, 835, -1, 837, 839, 838, -1, + 837, 838, 840, -1, 837, 840, 847, -1, + 837, 856, 839, -1, 837, 847, 856, -1, + 1239, 1501, 840, -1, 1239, 840, 841, -1, + 1239, 841, 1243, -1, 1239, 1243, 1509, -1, + 1250, 842, 1264, -1, 1250, 1264, 1249, -1, + 1250, 1129, 842, -1, 1250, 1130, 1129, -1, + 1251, 1248, 843, -1, 1251, 843, 1127, -1, + 1251, 1130, 1250, -1, 1253, 844, 1254, -1, + 1253, 1258, 845, -1, 1253, 845, 844, -1, + 857, 1256, 1255, -1, 857, 1255, 846, -1, + 857, 846, 855, -1, 1260, 856, 847, -1, + 1260, 847, 848, -1, 1260, 848, 849, -1, + 1260, 850, 1257, -1, 1260, 1257, 1256, -1, + 1260, 1261, 850, -1, 1260, 849, 1503, -1, + 1260, 851, 852, -1, 1260, 1062, 1262, -1, + 1260, 853, 851, -1, 1260, 1503, 853, -1, + 1260, 852, 1072, -1, 1260, 1072, 1062, -1, + 854, 855, 856, -1, 854, 856, 1260, -1, + 854, 1260, 1256, -1, 854, 857, 855, -1, + 854, 1256, 857, -1, 858, 863, 859, -1, + 858, 860, 863, -1, 858, 1511, 860, -1, + 858, 859, 861, -1, 858, 861, 862, -1, + 858, 1520, 1511, -1, 858, 862, 1520, -1, + 1273, 1266, 1272, -1, 1271, 864, 863, -1, + 1271, 1269, 864, -1, 1271, 863, 1274, -1, + 865, 867, 866, -1, 865, 866, 868, -1, + 865, 868, 869, -1, 865, 869, 870, -1, + 865, 870, 867, -1, 1525, 1625, 1583, -1, + 1281, 1276, 1279, -1, 1281, 1277, 1276, -1, + 1281, 1282, 873, -1, 1281, 873, 1277, -1, + 871, 873, 872, -1, 871, 872, 1531, -1, + 871, 1277, 873, -1, 871, 1531, 1277, -1, + 874, 1308, 1288, -1, 874, 1288, 875, -1, + 874, 1183, 1308, -1, 874, 875, 1183, -1, + 876, 877, 878, -1, 876, 1285, 877, -1, + 876, 878, 879, -1, 876, 879, 1285, -1, + 1286, 880, 881, -1, 1286, 882, 880, -1, + 1286, 881, 1292, -1, 1286, 1292, 1285, -1, + 1286, 1284, 882, -1, 883, 885, 884, -1, + 883, 886, 885, -1, 883, 884, 1284, -1, + 883, 926, 886, -1, 883, 887, 926, -1, + 883, 888, 887, -1, 883, 1284, 888, -1, + 1289, 889, 1288, -1, 1289, 1290, 889, -1, + 890, 892, 891, -1, 890, 891, 893, -1, + 890, 893, 894, -1, 890, 895, 892, -1, + 890, 894, 895, -1, 1295, 1305, 1285, -1, + 1295, 1285, 1292, -1, 1295, 896, 1305, -1, + 1295, 904, 897, -1, 1295, 897, 901, -1, + 1295, 901, 898, -1, 1295, 898, 899, -1, + 1295, 899, 896, -1, 905, 903, 900, -1, + 905, 901, 904, -1, 905, 902, 901, -1, + 905, 900, 902, -1, 1294, 1293, 903, -1, + 1294, 904, 1295, -1, 1294, 903, 905, -1, + 1294, 905, 904, -1, 1297, 1546, 1301, -1, + 1297, 1545, 1546, -1, 1299, 1302, 906, -1, + 1299, 906, 1298, -1, 1544, 906, 907, -1, + 1544, 1298, 906, -1, 1544, 1545, 1297, -1, + 1544, 1297, 1298, -1, 1544, 907, 908, -1, + 1544, 908, 1541, -1, 1534, 910, 1290, -1, + 1534, 914, 910, -1, 1534, 1290, 1306, -1, + 1534, 1535, 914, -1, 909, 911, 910, -1, + 909, 912, 911, -1, 909, 913, 912, -1, + 909, 914, 913, -1, 909, 910, 914, -1, + 1312, 1311, 915, -1, 1312, 916, 1310, -1, + 1312, 917, 916, -1, 1312, 918, 917, -1, + 1312, 915, 919, -1, 1312, 919, 918, -1, + 920, 921, 922, -1, 920, 922, 923, -1, + 920, 924, 921, -1, 920, 925, 924, -1, + 920, 923, 925, -1, 1595, 1313, 926, -1, + 1595, 926, 1596, -1, 1162, 928, 927, -1, + 1162, 1596, 928, -1, 1162, 927, 1453, -1, + 1315, 929, 1197, -1, 1315, 1161, 929, -1, + 1315, 1593, 1161, -1, 930, 931, 1314, -1, + 930, 932, 931, -1, 930, 1315, 1197, -1, + 930, 1314, 1315, -1, 930, 1197, 1196, -1, + 930, 1196, 932, -1, 1319, 934, 1317, -1, + 1319, 1322, 1331, -1, 1319, 1331, 934, -1, + 1335, 934, 1329, -1, 1335, 1336, 936, -1, + 933, 1317, 934, -1, 933, 935, 1317, -1, + 933, 1335, 936, -1, 933, 934, 1335, -1, + 933, 937, 935, -1, 933, 936, 937, -1, + 938, 950, 939, -1, 938, 939, 943, -1, + 938, 949, 950, -1, 938, 943, 948, -1, + 938, 948, 949, -1, 940, 942, 941, -1, + 940, 943, 942, -1, 940, 944, 945, -1, + 940, 941, 944, -1, 940, 945, 946, -1, + 940, 946, 947, -1, 940, 947, 948, -1, + 940, 948, 943, -1, 956, 950, 949, -1, + 956, 1323, 950, -1, 956, 1331, 1323, -1, + 956, 951, 1338, -1, 956, 952, 951, -1, + 956, 953, 952, -1, 956, 949, 953, -1, + 955, 1340, 954, -1, 955, 954, 1326, -1, + 1325, 955, 1326, -1, 1325, 1338, 1340, -1, + 1325, 1340, 955, -1, 1330, 1326, 959, -1, + 1330, 1338, 1325, -1, 1330, 956, 1338, -1, + 1330, 1331, 956, -1, 1333, 1335, 1329, -1, + 957, 1334, 1328, -1, 957, 958, 1334, -1, + 957, 959, 958, -1, 957, 1330, 959, -1, + 957, 1328, 1330, -1, 960, 962, 961, -1, + 960, 963, 962, -1, 960, 961, 964, -1, + 960, 964, 965, -1, 960, 965, 963, -1, + 966, 967, 968, -1, 966, 968, 969, -1, + 966, 969, 970, -1, 966, 970, 971, -1, + 966, 988, 967, -1, 966, 971, 988, -1, + 1344, 1338, 1342, -1, 1344, 972, 1339, -1, + 1344, 1343, 972, -1, 1346, 984, 973, -1, + 1346, 1350, 984, -1, 1346, 973, 1347, -1, + 974, 976, 975, -1, 974, 975, 977, -1, + 974, 977, 978, -1, 974, 979, 976, -1, + 974, 978, 979, -1, 980, 982, 981, -1, + 980, 983, 984, -1, 980, 984, 982, -1, + 980, 985, 983, -1, 980, 981, 985, -1, + 986, 1342, 1338, -1, 986, 1338, 987, -1, + 986, 988, 1342, -1, 986, 987, 988, -1, + 989, 990, 991, -1, 989, 992, 990, -1, + 989, 991, 993, -1, 989, 993, 994, -1, + 989, 994, 992, -1, 995, 997, 996, -1, + 995, 998, 997, -1, 995, 996, 999, -1, + 995, 999, 998, -1, 1004, 1014, 1000, -1, + 1004, 1000, 1001, -1, 1004, 1001, 1007, -1, + 1012, 1020, 1009, -1, 1012, 1364, 1020, -1, + 1012, 1002, 1364, -1, 1012, 1013, 1002, -1, + 1003, 1013, 1014, -1, 1003, 1014, 1004, -1, + 1003, 1006, 1005, -1, 1003, 1005, 1013, -1, + 1003, 1007, 1006, -1, 1003, 1004, 1007, -1, + 1008, 1009, 1010, -1, 1008, 1010, 1011, -1, + 1008, 1012, 1009, -1, 1008, 1013, 1012, -1, + 1008, 1011, 1014, -1, 1008, 1014, 1013, -1, + 1352, 1015, 1019, -1, 1352, 1353, 1015, -1, + 1352, 1016, 1356, -1, 1352, 1019, 1017, -1, + 1352, 1017, 1016, -1, 1388, 1358, 1555, -1, + 1388, 1561, 1359, -1, 1562, 1018, 1359, -1, + 1562, 1359, 1561, -1, 1562, 1019, 1018, -1, + 1562, 1559, 1019, -1, 1366, 1020, 1364, -1, + 1366, 1021, 1020, -1, 1366, 1368, 1023, -1, + 1366, 1023, 1022, -1, 1366, 1022, 1021, -1, + 1373, 1025, 1023, -1, 1373, 1023, 1368, -1, + 1373, 1368, 1374, -1, 1554, 1024, 1546, -1, + 1554, 1555, 1024, -1, 1031, 1640, 1648, -1, + 1031, 1648, 1647, -1, 1031, 1647, 1631, -1, + 1031, 1631, 1038, -1, 1031, 1038, 1551, -1, + 1646, 1631, 1647, -1, 1606, 1036, 1632, -1, + 1606, 1396, 1036, -1, 1606, 1484, 1396, -1, + 1375, 1025, 1373, -1, 1375, 1635, 1636, -1, + 1375, 1540, 1025, -1, 1601, 1376, 1026, -1, + 1601, 1026, 1383, -1, 1601, 1383, 1604, -1, + 1489, 1605, 1603, -1, 1489, 1603, 1027, -1, + 1489, 1027, 1490, -1, 1029, 1027, 1603, -1, + 1029, 1030, 1028, -1, 1029, 1028, 1027, -1, + 1381, 1604, 1383, -1, 1381, 1603, 1604, -1, + 1381, 1029, 1603, -1, 1381, 1378, 1030, -1, + 1381, 1030, 1029, -1, 1638, 1031, 1551, -1, + 1638, 1640, 1031, -1, 1387, 1639, 1551, -1, + 1387, 1551, 1032, -1, 1387, 1032, 1558, -1, + 1392, 1391, 1033, -1, 1392, 1034, 1035, -1, + 1392, 1035, 1393, -1, 1392, 1033, 1044, -1, + 1392, 1044, 1034, -1, 1395, 1036, 1396, -1, + 1395, 1037, 1036, -1, 1395, 1394, 1038, -1, + 1395, 1038, 1037, -1, 1390, 1396, 1484, -1, + 1390, 1484, 1485, -1, 1390, 1039, 1391, -1, + 1390, 1485, 1487, -1, 1390, 1487, 1039, -1, + 1040, 1356, 1041, -1, 1040, 1042, 1356, -1, + 1040, 1044, 1043, -1, 1040, 1041, 1044, -1, + 1040, 1043, 1045, -1, 1040, 1045, 1042, -1, + 1046, 1047, 1048, -1, 1046, 1049, 1047, -1, + 1046, 1048, 1050, -1, 1046, 1051, 1049, -1, + 1046, 1050, 1051, -1, 1052, 1054, 1053, -1, + 1052, 1055, 1054, -1, 1052, 1053, 1055, -1, + 1056, 1057, 1058, -1, 1056, 1058, 1059, -1, + 1056, 1059, 1057, -1, 1403, 1058, 1400, -1, + 1403, 1059, 1058, -1, 1403, 1402, 1059, -1, + 1401, 1061, 1060, -1, 1401, 1399, 1061, -1, + 1401, 1060, 1507, -1, 1398, 1400, 1061, -1, + 1398, 1061, 1399, -1, 1073, 1074, 1262, -1, + 1073, 1262, 1062, -1, 1073, 1072, 1420, -1, + 1073, 1062, 1072, -1, 1063, 1064, 1610, -1, + 1063, 1610, 1615, -1, 1063, 1615, 1065, -1, + 1063, 1066, 1064, -1, 1063, 1065, 1067, -1, + 1063, 1067, 1068, -1, 1063, 1069, 1066, -1, + 1063, 1068, 1069, -1, 1070, 1071, 1615, -1, + 1070, 1615, 1616, -1, 1070, 1093, 1071, -1, + 1070, 1616, 1093, -1, 1564, 1440, 1104, -1, + 1564, 1609, 1440, -1, 1564, 1104, 1096, -1, + 1564, 1096, 1094, -1, 1564, 1094, 1613, -1, + 1406, 1414, 1407, -1, 1410, 1072, 1413, -1, + 1410, 1417, 1072, -1, 1415, 1414, 1411, -1, + 1422, 1420, 1417, -1, 1424, 1073, 1420, -1, + 1424, 1610, 1074, -1, 1424, 1074, 1073, -1, + 1424, 1075, 1610, -1, 1424, 1427, 1075, -1, + 1424, 1425, 1427, -1, 1076, 1420, 1077, -1, + 1076, 1424, 1420, -1, 1076, 1426, 1424, -1, + 1076, 1421, 1078, -1, 1076, 1077, 1421, -1, + 1076, 1078, 1079, -1, 1076, 1079, 1427, -1, + 1076, 1427, 1426, -1, 1087, 1080, 1085, -1, + 1087, 1086, 1081, -1, 1087, 1082, 1080, -1, + 1087, 1081, 1083, -1, 1087, 1083, 1082, -1, + 1084, 1085, 1235, -1, 1084, 1235, 1086, -1, + 1084, 1087, 1085, -1, 1084, 1086, 1087, -1, + 1088, 1093, 1089, -1, 1088, 1090, 1093, -1, + 1088, 1089, 1430, -1, 1088, 1430, 1103, -1, + 1088, 1103, 1091, -1, 1088, 1091, 1090, -1, + 1092, 1093, 1616, -1, 1092, 1616, 1094, -1, + 1092, 1095, 1093, -1, 1092, 1096, 1095, -1, + 1092, 1094, 1096, -1, 1097, 1099, 1098, -1, + 1097, 1098, 1100, -1, 1097, 1101, 1099, -1, + 1097, 1100, 1101, -1, 1429, 1102, 1432, -1, + 1429, 1430, 1102, -1, 1431, 1436, 1103, -1, + 1431, 1103, 1430, -1, 1608, 1610, 1438, -1, + 1565, 1569, 1104, -1, 1565, 1104, 1566, -1, + 1619, 1443, 1444, -1, 1105, 1106, 1107, -1, + 1105, 1108, 1106, -1, 1105, 1107, 1109, -1, + 1105, 1110, 1108, -1, 1105, 1109, 1111, -1, + 1105, 1111, 1110, -1, 1112, 1113, 1114, -1, + 1112, 1114, 1115, -1, 1112, 1132, 1113, -1, + 1112, 1116, 1132, -1, 1112, 1115, 1117, -1, + 1112, 1117, 1118, -1, 1112, 1118, 1116, -1, + 1119, 1120, 1121, -1, 1119, 1121, 1122, -1, + 1119, 1123, 1120, -1, 1119, 1122, 1123, -1, + 1124, 1135, 1125, -1, 1124, 1126, 1135, -1, + 1124, 1127, 1128, -1, 1124, 1128, 1126, -1, + 1124, 1125, 1129, -1, 1124, 1129, 1130, -1, + 1124, 1130, 1251, -1, 1124, 1251, 1127, -1, + 1131, 1133, 1132, -1, 1131, 1134, 1133, -1, + 1131, 1132, 1135, -1, 1131, 1135, 1134, -1, + 1136, 1145, 1144, -1, 1136, 1144, 1137, -1, + 1136, 1139, 1138, -1, 1136, 1138, 1145, -1, + 1136, 1140, 1139, -1, 1136, 1137, 1140, -1, + 1141, 1143, 1142, -1, 1141, 1142, 1144, -1, + 1141, 1145, 1143, -1, 1141, 1144, 1145, -1, + 1159, 1157, 1158, -1, 1159, 1168, 1146, -1, + 1159, 1146, 1152, -1, 1147, 1149, 1148, -1, + 1147, 1148, 1157, -1, 1147, 1157, 1159, -1, + 1147, 1151, 1150, -1, 1147, 1150, 1149, -1, + 1147, 1152, 1151, -1, 1147, 1159, 1152, -1, + 1153, 1154, 1160, -1, 1153, 1156, 1155, -1, + 1153, 1155, 1154, -1, 1153, 1160, 1158, -1, + 1153, 1157, 1156, -1, 1153, 1158, 1157, -1, + 1169, 1158, 1160, -1, 1169, 1160, 1454, -1, + 1169, 1168, 1159, -1, 1169, 1159, 1158, -1, + 1538, 1160, 1161, -1, 1538, 1454, 1160, -1, + 1538, 1161, 1593, -1, 1597, 1162, 1453, -1, + 1597, 1596, 1162, -1, 1166, 1165, 1163, -1, + 1166, 1163, 1167, -1, 1450, 1453, 1164, -1, + 1450, 1164, 1165, -1, 1450, 1165, 1166, -1, + 1450, 1167, 1451, -1, 1450, 1166, 1167, -1, + 1452, 1451, 1168, -1, 1452, 1168, 1169, -1, + 1452, 1169, 1454, -1, 1170, 1187, 1171, -1, + 1170, 1172, 1173, -1, 1170, 1171, 1172, -1, + 1170, 1181, 1187, -1, 1170, 1173, 1177, -1, + 1170, 1177, 1181, -1, 1174, 1191, 1175, -1, + 1174, 1537, 1191, -1, 1174, 1175, 1535, -1, + 1174, 1535, 1537, -1, 1176, 1177, 1178, -1, + 1176, 1178, 1179, -1, 1176, 1179, 1180, -1, + 1176, 1180, 1181, -1, 1176, 1181, 1177, -1, + 1182, 1183, 1193, -1, 1182, 1193, 1185, -1, + 1182, 1308, 1183, -1, 1182, 1307, 1308, -1, + 1182, 1185, 1537, -1, 1182, 1537, 1307, -1, + 1184, 1185, 1186, -1, 1184, 1187, 1188, -1, + 1184, 1186, 1187, -1, 1184, 1188, 1189, -1, + 1184, 1189, 1190, -1, 1184, 1191, 1185, -1, + 1184, 1190, 1191, -1, 1192, 1194, 1193, -1, + 1192, 1195, 1194, -1, 1192, 1193, 1196, -1, + 1192, 1196, 1197, -1, 1192, 1197, 1195, -1, + 1198, 1204, 1199, -1, 1198, 1205, 1204, -1, + 1198, 1199, 1200, -1, 1198, 1200, 1205, -1, + 1201, 1203, 1202, -1, 1201, 1202, 1204, -1, + 1201, 1205, 1203, -1, 1201, 1204, 1205, -1, + 1213, 1206, 1212, -1, 1213, 1207, 1206, -1, + 1213, 1208, 1207, -1, 1213, 1214, 1208, -1, + 1456, 1209, 1208, -1, 1456, 1208, 1214, -1, + 1456, 1210, 1209, -1, 1456, 1211, 1210, -1, + 1456, 1457, 1211, -1, 1458, 1212, 1231, -1, + 1458, 1213, 1212, -1, 1458, 1214, 1213, -1, + 1458, 1456, 1214, -1, 1458, 1231, 1459, -1, + 1215, 1434, 1216, -1, 1215, 1435, 1434, -1, + 1215, 1217, 1436, -1, 1215, 1436, 1435, -1, + 1215, 1216, 1462, -1, 1215, 1462, 1218, -1, + 1215, 1219, 1217, -1, 1215, 1218, 1219, -1, + 1477, 1464, 1220, -1, 1477, 1220, 1478, -1, + 1475, 1478, 1466, -1, 1479, 1472, 1463, -1, + 1479, 1463, 1482, -1, 1221, 1491, 1490, -1, + 1221, 1223, 1222, -1, 1221, 1490, 1223, -1, + 1221, 1227, 1491, -1, 1221, 1222, 1224, -1, + 1221, 1225, 1227, -1, 1221, 1224, 1225, -1, + 1226, 1491, 1227, -1, 1226, 1486, 1491, -1, + 1226, 1227, 1228, -1, 1226, 1228, 1229, -1, + 1226, 1229, 1486, -1, 1492, 1606, 1605, -1, + 1492, 1484, 1606, -1, 1230, 1459, 1231, -1, + 1230, 1231, 1232, -1, 1230, 1233, 1459, -1, + 1230, 1234, 1233, -1, 1230, 1232, 1234, -1, + 1496, 1494, 1235, -1, 1496, 1236, 1237, -1, + 1496, 1235, 1236, -1, 1496, 1237, 1238, -1, + 1496, 1238, 1499, -1, 1508, 1501, 1239, -1, + 1508, 1240, 1502, -1, 1508, 1507, 1240, -1, + 1508, 1239, 1509, -1, 1241, 1246, 1506, -1, + 1241, 1506, 1509, -1, 1241, 1242, 1246, -1, + 1241, 1243, 1242, -1, 1241, 1509, 1243, -1, + 1244, 1245, 1402, -1, 1244, 1402, 1506, -1, + 1244, 1246, 1245, -1, 1244, 1506, 1246, -1, + 1247, 1249, 1248, -1, 1247, 1250, 1249, -1, + 1247, 1248, 1251, -1, 1247, 1251, 1250, -1, + 1252, 1253, 1254, -1, 1252, 1254, 1255, -1, + 1252, 1255, 1256, -1, 1252, 1256, 1257, -1, + 1252, 1257, 1258, -1, 1252, 1258, 1253, -1, + 1259, 1261, 1260, -1, 1259, 1260, 1262, -1, + 1259, 1264, 1263, -1, 1259, 1263, 1261, -1, + 1259, 1265, 1264, -1, 1259, 1262, 1265, -1, + 1513, 1267, 1511, -1, 1512, 1520, 1571, -1, + 1512, 1571, 1267, -1, 1512, 1267, 1513, -1, + 1514, 1517, 1266, -1, 1523, 1273, 1274, -1, + 1523, 1266, 1273, -1, 1523, 1514, 1266, -1, + 1522, 1523, 1274, -1, 1624, 1627, 1583, -1, + 1624, 1583, 1625, -1, 1572, 1267, 1571, -1, + 1572, 1274, 1267, -1, 1572, 1522, 1274, -1, + 1268, 1270, 1269, -1, 1268, 1269, 1271, -1, + 1268, 1272, 1270, -1, 1268, 1273, 1272, -1, + 1268, 1274, 1273, -1, 1268, 1271, 1274, -1, + 1582, 1583, 1527, -1, 1275, 1532, 1590, -1, + 1275, 1590, 1276, -1, 1275, 1276, 1277, -1, + 1275, 1277, 1531, -1, 1275, 1531, 1532, -1, + 1278, 1279, 1280, -1, 1278, 1281, 1279, -1, + 1278, 1280, 1282, -1, 1278, 1282, 1281, -1, + 1283, 1285, 1284, -1, 1283, 1286, 1285, -1, + 1283, 1284, 1286, -1, 1287, 1288, 1306, -1, + 1287, 1289, 1288, -1, 1287, 1306, 1290, -1, + 1287, 1290, 1289, -1, 1291, 1292, 1293, -1, + 1291, 1293, 1294, -1, 1291, 1295, 1292, -1, + 1291, 1294, 1295, -1, 1296, 1298, 1297, -1, + 1296, 1299, 1298, -1, 1296, 1301, 1300, -1, + 1296, 1297, 1301, -1, 1296, 1302, 1299, -1, + 1296, 1300, 1303, -1, 1296, 1303, 1360, -1, + 1296, 1360, 1362, -1, 1296, 1362, 1304, -1, + 1296, 1304, 1305, -1, 1296, 1305, 1302, -1, + 1536, 1534, 1306, -1, 1536, 1307, 1537, -1, + 1536, 1306, 1308, -1, 1536, 1308, 1307, -1, + 1309, 1310, 1311, -1, 1309, 1311, 1312, -1, + 1309, 1312, 1310, -1, 1592, 1313, 1595, -1, + 1592, 1314, 1313, -1, 1592, 1315, 1314, -1, + 1592, 1593, 1315, -1, 1316, 1317, 1318, -1, + 1316, 1319, 1317, -1, 1316, 1318, 1320, -1, + 1316, 1320, 1321, -1, 1316, 1322, 1319, -1, + 1316, 1321, 1323, -1, 1316, 1323, 1322, -1, + 1324, 1325, 1326, -1, 1324, 1326, 1330, -1, + 1324, 1330, 1325, -1, 1327, 1328, 1334, -1, + 1327, 1334, 1333, -1, 1327, 1333, 1329, -1, + 1327, 1330, 1328, -1, 1327, 1329, 1331, -1, + 1327, 1331, 1330, -1, 1332, 1333, 1334, -1, + 1332, 1335, 1333, -1, 1332, 1334, 1336, -1, + 1332, 1336, 1335, -1, 1337, 1338, 1344, -1, + 1337, 1344, 1339, -1, 1337, 1340, 1338, -1, + 1337, 1339, 1340, -1, 1341, 1342, 1343, -1, + 1341, 1343, 1344, -1, 1341, 1344, 1342, -1, + 1345, 1346, 1347, -1, 1345, 1349, 1348, -1, + 1345, 1347, 1349, -1, 1345, 1348, 1350, -1, + 1345, 1350, 1346, -1, 1351, 1353, 1352, -1, + 1351, 1354, 1355, -1, 1351, 1355, 1353, -1, + 1351, 1356, 1354, -1, 1351, 1352, 1356, -1, + 1357, 1358, 1388, -1, 1357, 1388, 1359, -1, + 1357, 1360, 1358, -1, 1357, 1361, 1360, -1, + 1357, 1362, 1361, -1, 1357, 1359, 1362, -1, + 1363, 1364, 1365, -1, 1363, 1366, 1364, -1, + 1363, 1365, 1367, -1, 1363, 1368, 1366, -1, + 1363, 1367, 1369, -1, 1363, 1369, 1368, -1, + 1543, 1553, 1554, -1, 1543, 1554, 1546, -1, + 1547, 1635, 1372, -1, 1547, 1372, 1370, -1, + 1547, 1370, 1633, -1, 1371, 1372, 1635, -1, + 1371, 1635, 1375, -1, 1371, 1375, 1373, -1, + 1371, 1374, 1372, -1, 1371, 1373, 1374, -1, + 1542, 1540, 1375, -1, 1542, 1553, 1543, -1, + 1542, 1636, 1553, -1, 1542, 1375, 1636, -1, + 1600, 1633, 1376, -1, 1600, 1376, 1601, -1, + 1600, 1632, 1633, -1, 1377, 1381, 1382, -1, + 1377, 1378, 1381, -1, 1377, 1382, 1379, -1, + 1377, 1379, 1378, -1, 1380, 1382, 1381, -1, + 1380, 1381, 1383, -1, 1380, 1384, 1382, -1, + 1380, 1385, 1384, -1, 1380, 1386, 1385, -1, + 1380, 1383, 1386, -1, 1550, 1551, 1639, -1, + 1557, 1639, 1387, -1, 1557, 1387, 1558, -1, + 1557, 1561, 1388, -1, 1557, 1388, 1555, -1, + 1389, 1390, 1391, -1, 1389, 1391, 1392, -1, + 1389, 1392, 1393, -1, 1389, 1393, 1394, -1, + 1389, 1394, 1395, -1, 1389, 1395, 1396, -1, + 1389, 1396, 1390, -1, 1397, 1398, 1399, -1, + 1397, 1400, 1398, -1, 1397, 1401, 1507, -1, + 1397, 1399, 1401, -1, 1397, 1507, 1506, -1, + 1397, 1506, 1402, -1, 1397, 1403, 1400, -1, + 1397, 1402, 1403, -1, 1612, 1564, 1613, -1, + 1408, 1413, 1404, -1, 1408, 1404, 1414, -1, + 1408, 1414, 1406, -1, 1405, 1406, 1407, -1, + 1405, 1407, 1414, -1, 1405, 1414, 1413, -1, + 1405, 1413, 1408, -1, 1405, 1408, 1406, -1, + 1409, 1410, 1413, -1, 1409, 1415, 1411, -1, + 1409, 1413, 1415, -1, 1409, 1411, 1417, -1, + 1409, 1417, 1410, -1, 1412, 1413, 1414, -1, + 1412, 1414, 1415, -1, 1412, 1415, 1413, -1, + 1416, 1417, 1418, -1, 1416, 1422, 1417, -1, + 1416, 1418, 1421, -1, 1416, 1421, 1422, -1, + 1419, 1421, 1420, -1, 1419, 1422, 1421, -1, + 1419, 1420, 1422, -1, 1423, 1425, 1424, -1, + 1423, 1424, 1426, -1, 1423, 1427, 1425, -1, + 1423, 1426, 1427, -1, 1428, 1430, 1429, -1, + 1428, 1431, 1430, -1, 1428, 1432, 1433, -1, + 1428, 1429, 1432, -1, 1428, 1433, 1434, -1, + 1428, 1434, 1435, -1, 1428, 1435, 1436, -1, + 1428, 1436, 1431, -1, 1437, 1438, 1439, -1, + 1437, 1608, 1438, -1, 1437, 1440, 1609, -1, + 1437, 1609, 1608, -1, 1437, 1566, 1440, -1, + 1437, 1441, 1566, -1, 1437, 1442, 1441, -1, + 1437, 1439, 1442, -1, 1567, 1566, 1443, -1, + 1567, 1443, 1619, -1, 1620, 1444, 1445, -1, + 1620, 1619, 1444, -1, 1620, 1446, 1447, -1, + 1620, 1445, 1446, -1, 1620, 1448, 1621, -1, + 1620, 1447, 1448, -1, 1598, 1597, 1453, -1, + 1598, 1454, 1538, -1, 1449, 1450, 1451, -1, + 1449, 1451, 1452, -1, 1449, 1453, 1450, -1, + 1449, 1598, 1453, -1, 1449, 1452, 1454, -1, + 1449, 1454, 1598, -1, 1455, 1457, 1456, -1, + 1455, 1456, 1458, -1, 1455, 1459, 1457, -1, + 1455, 1458, 1459, -1, 1460, 1461, 1462, -1, + 1460, 1462, 1472, -1, 1460, 1473, 1461, -1, + 1460, 1472, 1473, -1, 1497, 1472, 1462, -1, + 1497, 1462, 1495, -1, 1497, 1498, 1463, -1, + 1497, 1463, 1472, -1, 1480, 1464, 1477, -1, + 1480, 1465, 1464, -1, 1480, 1481, 1465, -1, + 1474, 1466, 1467, -1, 1474, 1475, 1466, -1, + 1474, 1467, 1468, -1, 1474, 1468, 1469, -1, + 1474, 1469, 1470, -1, 1474, 1470, 1473, -1, + 1471, 1473, 1472, -1, 1471, 1472, 1479, -1, + 1471, 1474, 1473, -1, 1471, 1475, 1474, -1, + 1471, 1478, 1475, -1, 1471, 1479, 1478, -1, + 1476, 1477, 1478, -1, 1476, 1478, 1479, -1, + 1476, 1481, 1480, -1, 1476, 1480, 1477, -1, + 1476, 1482, 1481, -1, 1476, 1479, 1482, -1, + 1483, 1485, 1484, -1, 1483, 1484, 1492, -1, + 1483, 1492, 1491, -1, 1483, 1491, 1486, -1, + 1483, 1486, 1487, -1, 1483, 1487, 1485, -1, + 1488, 1489, 1490, -1, 1488, 1490, 1491, -1, + 1488, 1491, 1492, -1, 1488, 1605, 1489, -1, + 1488, 1492, 1605, -1, 1493, 1495, 1494, -1, + 1493, 1494, 1496, -1, 1493, 1498, 1497, -1, + 1493, 1497, 1495, -1, 1493, 1499, 1498, -1, + 1493, 1496, 1499, -1, 1500, 1501, 1508, -1, + 1500, 1508, 1502, -1, 1500, 1503, 1501, -1, + 1500, 1502, 1504, -1, 1500, 1504, 1503, -1, + 1505, 1506, 1507, -1, 1505, 1507, 1508, -1, + 1505, 1509, 1506, -1, 1505, 1508, 1509, -1, + 1510, 1511, 1520, -1, 1510, 1520, 1512, -1, + 1510, 1513, 1511, -1, 1510, 1512, 1513, -1, + 1519, 1514, 1523, -1, 1519, 1518, 1515, -1, + 1519, 1515, 1516, -1, 1519, 1516, 1517, -1, + 1519, 1517, 1514, -1, 1521, 1580, 1518, -1, + 1521, 1518, 1519, -1, 1521, 1519, 1523, -1, + 1628, 1630, 1627, -1, 1573, 1520, 1629, -1, + 1573, 1571, 1520, -1, 1575, 1530, 1577, -1, + 1575, 1585, 1530, -1, 1524, 1580, 1521, -1, + 1524, 1572, 1625, -1, 1524, 1522, 1572, -1, + 1524, 1523, 1522, -1, 1524, 1521, 1523, -1, + 1576, 1625, 1525, -1, 1576, 1525, 1585, -1, + 1576, 1524, 1625, -1, 1576, 1580, 1524, -1, + 1584, 1525, 1583, -1, 1584, 1585, 1525, -1, + 1526, 1527, 1528, -1, 1526, 1582, 1527, -1, + 1526, 1528, 1529, -1, 1526, 1529, 1530, -1, + 1526, 1530, 1585, -1, 1526, 1585, 1582, -1, + 1587, 1531, 1588, -1, 1587, 1532, 1531, -1, + 1587, 1590, 1532, -1, 1587, 1589, 1590, -1, + 1533, 1535, 1534, -1, 1533, 1534, 1536, -1, + 1533, 1537, 1535, -1, 1533, 1536, 1537, -1, + 1594, 1538, 1593, -1, 1594, 1598, 1538, -1, + 1539, 1541, 1540, -1, 1539, 1540, 1542, -1, + 1539, 1542, 1543, -1, 1539, 1544, 1541, -1, + 1539, 1545, 1544, -1, 1539, 1546, 1545, -1, + 1539, 1543, 1546, -1, 1643, 1635, 1547, -1, + 1643, 1547, 1633, -1, 1548, 1639, 1553, -1, + 1548, 1637, 1639, -1, 1548, 1553, 1636, -1, + 1548, 1636, 1637, -1, 1602, 1606, 1632, -1, + 1602, 1632, 1600, -1, 1549, 1639, 1638, -1, + 1549, 1550, 1639, -1, 1549, 1638, 1551, -1, + 1549, 1551, 1550, -1, 1552, 1639, 1557, -1, + 1552, 1553, 1639, -1, 1552, 1554, 1553, -1, + 1552, 1555, 1554, -1, 1552, 1557, 1555, -1, + 1556, 1557, 1558, -1, 1556, 1560, 1559, -1, + 1556, 1558, 1560, -1, 1556, 1561, 1557, -1, + 1556, 1559, 1562, -1, 1556, 1562, 1561, -1, + 1614, 1615, 1610, -1, 1563, 1609, 1564, -1, + 1563, 1564, 1612, -1, 1563, 1614, 1609, -1, + 1563, 1612, 1614, -1, 1618, 1565, 1566, -1, + 1618, 1566, 1567, -1, 1618, 1568, 1569, -1, + 1618, 1569, 1565, -1, 1618, 1622, 1568, -1, + 1618, 1567, 1619, -1, 1570, 1572, 1571, -1, + 1570, 1571, 1573, -1, 1570, 1573, 1572, -1, + 1626, 1625, 1572, -1, 1626, 1572, 1573, -1, + 1626, 1573, 1629, -1, 1574, 1585, 1575, -1, + 1574, 1576, 1585, -1, 1574, 1575, 1577, -1, + 1574, 1577, 1578, -1, 1574, 1578, 1579, -1, + 1574, 1579, 1580, -1, 1574, 1580, 1576, -1, + 1581, 1583, 1582, -1, 1581, 1584, 1583, -1, + 1581, 1582, 1585, -1, 1581, 1585, 1584, -1, + 1586, 1587, 1588, -1, 1586, 1589, 1587, -1, + 1586, 1588, 1590, -1, 1586, 1590, 1589, -1, + 1591, 1593, 1592, -1, 1591, 1594, 1593, -1, + 1591, 1592, 1595, -1, 1591, 1595, 1596, -1, + 1591, 1596, 1597, -1, 1591, 1597, 1598, -1, + 1591, 1598, 1594, -1, 1644, 1635, 1643, -1, + 1644, 1648, 1640, -1, 1599, 1600, 1601, -1, + 1599, 1602, 1600, -1, 1599, 1604, 1603, -1, + 1599, 1601, 1604, -1, 1599, 1603, 1605, -1, + 1599, 1605, 1606, -1, 1599, 1606, 1602, -1, + 1607, 1608, 1609, -1, 1607, 1609, 1614, -1, + 1607, 1610, 1608, -1, 1607, 1614, 1610, -1, + 1611, 1612, 1613, -1, 1611, 1614, 1612, -1, + 1611, 1615, 1614, -1, 1611, 1613, 1616, -1, + 1611, 1616, 1615, -1, 1617, 1618, 1619, -1, + 1617, 1620, 1621, -1, 1617, 1619, 1620, -1, + 1617, 1621, 1622, -1, 1617, 1622, 1618, -1, + 1623, 1624, 1625, -1, 1623, 1625, 1626, -1, + 1623, 1627, 1624, -1, 1623, 1628, 1627, -1, + 1623, 1626, 1629, -1, 1623, 1629, 1630, -1, + 1623, 1630, 1628, -1, 1645, 1631, 1646, -1, + 1645, 1632, 1631, -1, 1645, 1633, 1632, -1, + 1645, 1643, 1633, -1, 1645, 1642, 1643, -1, + 1634, 1635, 1644, -1, 1634, 1636, 1635, -1, + 1634, 1637, 1636, -1, 1634, 1638, 1639, -1, + 1634, 1639, 1637, -1, 1634, 1640, 1638, -1, + 1634, 1644, 1640, -1, 1641, 1643, 1642, -1, + 1641, 1644, 1643, -1, 1641, 1645, 1646, -1, + 1641, 1642, 1645, -1, 1641, 1646, 1647, -1, + 1641, 1647, 1648, -1, 1641, 1648, 1644, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT1_shoulderRoll.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT1_shoulderRoll.wrl new file mode 100644 index 0000000..713a24d --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT1_shoulderRoll.wrl @@ -0,0 +1,3096 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_RT1_shoulderPitch____________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -34.924999 -42.4711 -59.743599, + -34.924999 -43.650002 -58.181999, + -34.924999 -39.325802 -63.909901, + -34.924999 33.3522 -71.364502, + -34.924999 32.8307 -71.985703, + -34.924999 29.745899 -75.549896, + 34.8946 -51.145302 -41.5, + 34.8946 -51.145302 -6.544798e-010, + 34.924999 50.798801 -48.2342, + 34.924999 48.2514 -51.839802, + 21.806801 -12.1271 -93.199997, + 34.5228 -51.145302 5.0806999, + 34.801498 -51.145302 2.5471399, + 34.831799 -50.798 2.54936, + 34.059799 -51.145302 7.5871401, + 32.1264 -60.178101 9.0838003, + 12.1275 -21.7644 -93.199997, + 34.924999 32.269402 -72.648499, + 34.924999 35.642799 -68.576797, + 34.924999 43.892899 -56.603199, + 34.924999 34.8293 -69.558701, + -34.924999 -34.828499 -69.558701, + -34.924999 -35.641998 -68.576797, + -34.924999 -32.2686 -72.648499, + 29.113001 63.192402 -12.3297, + 34.1688 52.365101 -46.709301, + 33.832401 52.5797 -46.7141, + 17.015301 63.373402 -40.18, + 33.722401 52.632999 -46.739399, + 27.8519 63.759701 -11.7956, + 5.4500198 63.6073 -50.080299, + 7.2595801 63.373402 -49.946301, + 7.0634699 63.6073 -49.484699, + -13.0611 10.9599 -95.739998, + -21.124399 13.3587 -93.199997, + -13.2543 41.813999 -79.199997, + 34.8978 -51.1106 -47.814098, + 34.900398 -51.110901 -41.5, + 34.924999 -32.653 2.6677656e-009, + 34.924999 44.428799 1.6182748e-009, + 34.810799 51.465 -47.392399, + 34.901901 51.102001 -47.8237, + -10.6172 63.056 -48.635601, + -17.4492 42.0215 -76.199997, + -34.924999 36.759201 -67.185204, + 9.0289698 -23.2194 -93.199997, + 10.7146 -22.580099 -93.199997, + 22.1308 -11.6147 -93.199997, + 23.707399 -7.9142799 -93.199997, + 13.2543 41.813999 -79.199997, + 17.4492 42.0215 -76.199997, + 9.0682802 63.056 -49.576099, + 34.924999 42.471901 -59.743599, + 34.924999 43.650799 -58.181999, + 34.924999 39.326599 -63.909901, + 33.347099 -60.178101 -1.61026, + 33.2309 -60.662498 -1.60465, + 34.705399 -32.653 3.9103601, + 34.7337 -44.428001 3.65066, + 34.552799 -50.798 5.0851202, + 34.705399 -10.428 3.9103601, + 34.1618 -44.428001 7.2613201, + 34.0494 -32.653 7.7715402, + 34.0895 -50.798 7.59375, + 33.629902 44.428799 9.4226503, + 34.0494 -10.428 7.7715402, + 34.599701 44.428799 4.75562, + 33.444199 -50.798 10.0619, + 33.215599 -44.428001 10.7924, + 32.965099 -32.653 11.535, + 33.4151 -51.145302 10.0531, + 14.7657 -8.5245895 -95.739998, + 32.230202 -32.116001 -76.199997, + 34.924999 -29.7451 -75.549896, + 34.924999 -32.829899 -71.985703, + 34.924999 -33.351398 -71.364502, + 34.924999 -36.7584 -67.185204, + 7.7093301 -84.582298 -28.746901, + 34.924999 -40.198101 -62.774799, + 34.924999 -47.210999 -53.2929, + 34.924999 -42.458199 -59.7673, + 34.924999 -43.679798 -58.141701, + 28.9193 -35.1269 -76.199997, + -10.7416 -62.113602 -56.818401, + 13.2368 -43.531601 -76.199997, + 10.7416 -62.113602 -56.818401, + 17.4492 -42.020699 -76.199997, + 6.3355699 -61.722198 -60.105999, + -12.4968 -21.644699 -93.199997, + -28.9193 -35.1269 -76.199997, + -12.1275 -21.82 -93.199997, + 28.7218 63.452801 -12.164, + 29.139 63.643398 -9.7631903, + 28.297899 63.643398 -11.9845, + 32.106899 63.798801 -0.58485401, + 29.5755 63.452801 -9.90942, + 28.392 63.601101 -12.0244, + 34.010201 52.478802 -46.693802, + 29.9783 63.192402 -10.0444, + 33.871101 52.560902 -46.7052, + 34.030899 52.465302 -46.694, + 13.4754 63.750599 -44.043999, + 12.3543 63.750599 -45.279701, + 13.0498 63.798801 -43.693501, + 10.363 63.373402 -48.259899, + 8.8518295 63.373402 -49.1777, + 9.7832499 63.750599 -47.401199, + 10.0824 63.6073 -47.8442, + 11.1197 63.750599 -46.402199, + 8.61234 63.6073 -48.737, + 9.4747601 63.798801 -46.944199, + 10.7689 63.798801 -45.977001, + 6.6388998 63.798801 -48.485199, + 8.3570995 63.750599 -48.2673, + 6.8544598 63.750599 -48.992599, + 5.2891698 63.750599 -49.570499, + 5.73736 63.056 -50.991001, + 5.6009498 63.373402 -50.558701, + 7.43683 63.056 -50.363602, + -25.822901 52.798801 -53.2071, + -17.8818 17.367901 -93.199997, + -18.708 16.574301 -93.199997, + -17.4032 17.8276 -93.199997, + -32.230202 32.116798 -76.199997, + -12.9053 42.0201 -79.199997, + -10.9595 13.0615 -95.739998, + -15.8071 19.3606 -93.199997, + -12.4968 21.6455 -93.199997, + -12.1275 21.820801 -93.199997, + -16.021799 5.8318501 -95.739998, + -22.993601 9.79708 -93.199997, + 34.924999 -48.612999 -40.075001, + 34.924999 44.428799 -13.2069, + 34.924999 -44.428001 -54.603199, + 34.924999 -44.428001 -27.8944, + 34.924999 -50.798 -48.2342, + 34.924999 -50.798 -2.291769e-009, + 34.4459 52.097599 -46.832901, + 32.371101 63.608799 -0.329932, + 34.304199 52.2472 -46.751598, + 34.693001 51.730202 -47.125401, + 34.698601 51.723099 -47.130199, + 34.569 51.937801 -46.945702, + -34.924999 42.459 -59.7673, + -28.9193 35.127701 -76.199997, + -34.924999 40.198898 -62.774799, + -34.924999 43.680599 -58.141701, + -34.924999 47.2118 -53.2929, + 18.4002 -84.973602 -16.0413, + 18.6952 -84.582298 -16.2985, + 8.4935503 -84.973602 -27.404699, + 6.9552202 -85.7164 -26.063601, + 18.0585 -85.291 -15.7434, + 2.8676825e-009 -17.049601 -95.739998, + 17.049999 0.00040901403 -95.739998, + 16.021799 -5.8310299 -95.739998, + 16.791 -2.96029 -95.739998, + 24.67 -4.0088501 -93.199997, + 24.9937 0.00040901665 -93.199997, + 24.67 4.0096698 -93.199997, + 23.652201 -84.128899 -8.4597902, + 34.8242 -51.415298 -47.449402, + 8.7885303 -84.582298 -27.6619, + 34.894901 -51.143501 -47.77, + 34.721298 -51.677399 -47.172901, + 20.1334 -84.582298 -14.4842, + 21.396299 -84.582298 -12.5438, + 22.118099 -84.973602 -10.3285, + 22.4727 -84.582298 -10.4941, + 31.177601 -60.662498 11.6113, + 10.9595 -13.0606 -95.739998, + 14.198 -20.569 -93.199997, + 8.5249996 -14.7653 -95.739998, + 5.83144 -16.021299 -95.739998, + 17.4032 -17.924101 -93.199997, + 13.0611 -10.9591 -95.739998, + 19.981001 -15.0143 -93.199997, + 17.3137 -18.025101 -93.199997, + 34.924999 -29.1628 -76.199997, + -20.1334 -84.582298 -14.4842, + -7.7093301 -84.582298 -28.746901, + -11.0061 -61.722198 -57.106899, + -25.3286 -37.797901 -76.199997, + 3.6340401 -84.973602 -30.666, + 6.1833301 -62.113602 -59.745499, + 9.5670099 -61.722198 -58.282501, + 11.0061 -61.722198 -57.106899, + 25.3286 -37.797901 -76.199997, + 9.3371201 -62.113602 -57.965801, + 21.492901 -40.103298 -76.199997, + 8.0033903 -61.722198 -59.286598, + 7.81107 -62.113602 -58.945801, + 6.2792301 -84.973602 -29.3563, + -15.8071 -19.3598 -93.199997, + 4.0688801 -24.5954 -93.199997, + 6.95367 -24.006399 -93.199997, + 2.9607 -16.7906 -95.739998, + 3.01265 -24.811001 -93.199997, + 8.8963299 -44.621399 -76.199997, + -29.0138 51.146099 19.3864, + -33.6021 50.798801 9.4157, + -19.2279 -84.582298 15.6664, + -18.9245 -84.973602 15.4192, + -22.9848 -84.973602 -8.2210903, + 12.7325 63.6073 -45.657501, + 11.46 63.6073 -46.814602, + 32.183998 63.798801 -0.296938, + 15.5535 63.798801 -39.560902, + 16.061199 63.750599 -39.775902, + 14.0156 63.798801 -42.398399, + 16.553499 63.6073 -39.984402, + 15.3375 63.750599 -41.279301, + 2.1975501 63.056 -51.7439, + 3.4609301 43.8521 -79.199997, + 5.7576199 43.610001 -79.199997, + 3.9855499 63.056 -51.452499, + 3.8912399 63.373402 -51.009102, + -28.3001 52.798801 -51.243599, + -27.962601 52.798801 -51.5252, + -7.26015 63.373402 -49.946201, + -7.4373999 63.056 -50.363499, + -9.0688496 63.056 -49.576, + -8.6128998 63.6073 -48.7369, + -8.8523903 63.373402 -49.177601, + -10.3636 63.373402 -48.2598, + -7.0640302 63.6073 -49.4846, + -6.85502 63.750599 -48.992599, + 3.5609701 63.798801 -49.456299, + 0.38193899 63.373402 -51.409199, + 2.1461999 63.373402 -51.293499, + -30.6306 61.120499 11.9687, + -30.522301 61.6049 11.9263, + -29.6147 61.120499 14.2986, + -31.463499 61.120499 9.5672302, + -31.3522 61.6049 9.53339, + -34.8978 51.111401 -47.814098, + -34.924999 50.798801 -3.8442707e-009, + -34.8946 51.146099 2.5126157e-009, + -34.924999 50.798801 -48.2342, + -32.371101 63.608799 -0.329932, + 10.2971 42.766201 -79.199997, + -1.1547101 43.973301 -79.199997, + 1.1547101 43.973301 -79.199997, + -24.578199 -4.06847 -93.199997, + 32.704102 61.6049 2.07127, + 32.400002 63.608799 2.8210994e-009, + 34.726601 51.146099 3.42027, + 32.5616 61.120499 4.6072102, + 34.560101 50.798801 4.7497401, + 34.756802 50.798801 3.42325, + 32.820202 61.120499 2.07862, + 34.8946 51.146099 -2.2653499e-009, + 34.924999 50.798801 -3.0729259e-009, + 5.1419501 -85.7164 -27.661699, + 7.3708 -85.668198 -26.4259, + 6.10114 -85.7164 -26.9223, + 7.1508098 -85.291 -28.113199, + 8.1518297 -85.291 -27.1068, + 7.7737498 -85.524902 -26.777201, + 7.4505701 -84.973602 -28.4533, + 21.058701 -84.973602 -12.3459, + 19.8158 -84.973602 -14.2557, + -22.993601 -9.7962704 -93.199997, + -24.267401 -5.9809599 -93.199997, + -16.021799 -5.8310299 -95.739998, + -21.124399 -13.3578 -93.199997, + -13.0611 -10.9591 -95.739998, + 28.9193 35.127701 -76.199997, + 32.230202 32.116798 -76.199997, + 21.8276 -85.668198 6.9959602, + 21.302601 -85.7164 6.8276801, + 22.558001 -85.291 -8.0684099, + 22.9848 -84.973602 -8.2210903, + 23.3533 -84.582298 -8.35289, + 33.055 -60.662498 3.7730999, + 32.755699 -60.178101 6.4561901, + 33.170502 -60.178101 3.7862899, + 33.251801 -60.662498 1.08779, + 33.368099 -60.178101 1.09159, + 32.641602 -60.662498 6.4336901, + 32.0145 -60.662498 9.0521498, + 34.813599 -51.4561 -47.401199, + 25.0427 -83.627296 -3.95754, + 22.726101 -85.524902 -5.8056998, + 23.212 -85.291 -5.9298501, + 23.1684 -85.524902 -3.66133, + 25.3027 -83.627296 -1.6052001, + 7.1024599 50.798801 34.181599, + 13.3536 51.146099 32.2384, + 22.0394 61.120499 24.4079, + 24.6742 51.146099 24.6742, + 23.8125 50.798801 25.496201, + 31.622801 -50.798 14.8242, + 29.5718 -10.428 18.5812, + 29.5718 -32.653 18.5812, + 22.2871 -83.627296 12.0867, + 22.3367 -85.524902 7.1591201, + -18.4002 -84.973602 -16.0413, + -18.6952 -84.582298 -16.2985, + -8.4935503 -84.973602 -27.404699, + 4.47508 -62.113602 -60.3545, + 4.5852599 -61.722198 -60.730099, + 4.7985501 -85.291 -29.6919, + 4.9997001 -84.973602 -30.0982, + -17.909599 -84.128899 17.6136, + -17.6833 -84.582298 17.3911, + -19.474001 -84.128899 15.8669, + -18.1842 -85.524902 14.816, + -34.224098 51.146099 6.8076, + -34.726601 51.146099 3.42027, + -32.108398 61.120499 7.1086402, + -34.560101 50.798801 4.7497401, + 10.1294 51.146099 33.392101, + -20.8687 -84.128899 13.982, + -21.802401 -84.582298 11.8238, + -20.6049 -84.582298 13.8053, + -20.2798 -84.973602 13.5874, + -18.573099 -85.291 15.1329, + -19.9032 -85.291 13.3351, + -22.0331 -85.291 9.4076595, + -21.458401 -84.973602 11.6373, + -21.0599 -85.291 11.4211, + -20.618999 -85.524902 11.182, + -25.0427 -83.627296 -3.95754, + 13.0873 63.373402 -46.012001, + 10.6167 63.056 -48.6357, + 25.3596 52.798801 -53.557098, + 26.080601 52.798801 -53.010201, + 11.7792 63.373402 -47.201401, + 25.711901 63.798801 14.9653, + 26.790899 63.798801 12.9348, + 27.238199 63.759701 13.1508, + 14.9163 63.6073 -43.005001, + 14.4729 63.750599 -42.706402, + 13.8881 63.6073 -44.383801, + 15.8075 63.6073 -41.534, + 16.248501 63.373402 -41.772999, + 29.840599 44.428799 18.1465, + 29.039101 50.798801 19.403299, + 30.245899 -44.428001 17.4625, + 31.466299 -32.653 15.1534, + 31.466299 -10.428 15.1534, + 32.257599 62.065201 4.5641999, + 32.4464 61.6049 4.59091, + 34.224098 51.146099 6.8076, + 33.6021 50.798801 9.4157, + 34.253899 50.798801 6.81353, + 23.8587 61.120499 22.6329, + 25.5354 61.120499 20.722601, + 29.0138 51.146099 19.3864, + 26.9739 51.146099 22.1369, + -3.4609301 43.8521 -79.199997, + -0.382525 63.373402 -51.409199, + -0.37376699 63.6073 -50.9076, + -30.121401 52.798801 -49.7234, + -21.492901 40.104099 -76.199997, + -11.7797 63.373402 -47.201302, + -12.0683 63.056 -47.550999, + -10.0829 63.6073 -47.844101, + -11.4605 63.6073 -46.8144, + -6.6394501 63.798801 -48.4851, + -8.0944099 63.798801 -47.782799, + -9.7837896 63.750599 -47.401001, + -8.3576498 63.750599 -48.2672, + -3.67624 63.750599 -49.995602, + -5.2897301 63.750599 -49.570499, + -3.5615301 63.798801 -49.456299, + -5.1238298 63.798801 -49.044701, + 5.12328 63.798801 -49.044701, + 8.0938702 63.798801 -47.782902, + 11.9642 63.798801 -44.890099, + 2.0288401 63.750599 -50.264, + 1.96639 63.798801 -49.716202, + 3.6756699 63.750599 -49.995602, + 3.78689 63.6073 -50.518501, + 2.08939 63.6073 -50.795101, + 0.37318799 63.6073 -50.9077, + -26.806801 62.065201 18.5144, + -29.338301 62.065201 14.1651, + -30.1022 62.490002 11.7622, + -29.103901 62.490002 14.052, + -29.8009 62.8689 11.6444, + -30.3447 62.065201 11.8569, + -34.5424 51.973999 -46.918999, + -34.526901 51.9963 -46.901699, + -34.409599 52.139 -46.8078, + -34.6791 51.7528 -47.106201, + -34.705601 51.706001 -47.147999, + -34.6036 51.8862 -46.9869, + -34.721298 51.6782 -47.172901, + -31.1698 62.065201 9.4779196, + -31.554501 62.490002 6.9860101, + 1.7398464e-009 17.0504 -95.739998, + -8.5249996 14.7661 -95.739998, + 4.0688801 24.596201 -93.199997, + 3.01265 24.8118 -93.199997, + 8.0384398 43.2477 -79.199997, + -24.578199 4.0692902 -93.199997, + -24.267401 5.9817801 -93.199997, + -16.791 2.9611101 -95.739998, + -16.791 -2.96029 -95.739998, + -22.1369 51.146099 26.9739, + -23.8125 50.798801 25.496201, + -24.6742 51.146099 24.6742, + -25.296801 62.065201 20.5294, + -18.0585 -85.291 -15.7434, + -8.1518297 -85.291 -27.1068, + -2.1170299 -85.291 -30.605499, + -0.70975298 -85.291 -30.791401, + 21.5823 -85.668198 -7.71945, + 22.208099 -85.668198 -5.6733899, + 17.680401 -85.524902 -15.4138, + 18.6066 -85.668198 -13.3858, + 17.277399 -85.668198 -15.0625, + 16.861799 -85.7164 -14.7002, + 5.7470798 -85.524902 -28.5634, + 6.0265899 -85.291 -28.9799, + 6.81916 -85.524902 -27.7369, + 4.3388 -85.668198 -28.7633, + 5.4491801 -85.668198 -28.119499, + 6.4656901 -85.668198 -27.335899, + 22.085699 -85.524902 -7.8994899, + -18.3234 -16.9429 -93.199997, + -10.9595 -13.0606 -95.739998, + -17.4032 -17.826799 -93.199997, + -18.708 -16.5734 -93.199997, + -32.230202 -32.116001 -76.199997, + 23.707399 7.9151001 -93.199997, + 22.3848 -85.668198 4.9301801, + 22.747 -85.668198 2.82144, + 22.3599 -85.7164 0.671561, + 22.0958 -85.7164 -3.4918301, + 22.1999 -85.7164 2.7535701, + 21.5718 -85.524902 9.2107, + 21.0802 -85.668198 9.0007801, + 22.875299 -85.668198 -1.45121, + 22.6404 -85.668198 -3.5778799, + 22.3251 -85.7164 -1.4163001, + 23.663799 -85.291 -3.73962, + 25.1607 -83.627296 3.12082, + 25.3421 -83.627296 0.76112801, + 23.3967 -85.291 5.1530499, + 22.9069 -85.524902 5.0451598, + 20.088499 61.120499 26.037201, + 22.1369 51.146099 26.9739, + 30.2349 -50.798 17.455799, + 30.456301 -50.798 17.092899, + 20.618999 -85.524902 11.182, + 23.921 -84.128899 7.6669202, + 23.316999 -83.627296 9.9558601, + 24.1437 -83.627296 7.7382998, + 24.760099 -83.627296 5.45332, + 23.246 -84.973602 7.4505801, + 22.814301 -85.291 7.3122101, + -19.0424 -85.668198 12.7584, + -19.4865 -85.524902 13.0559, + -21.5718 -85.524902 9.2107, + 0.70975298 -85.291 -30.791401, + 2.20577 -84.973602 -31.0501, + 2.77526 -61.722198 -61.1507, + 4.46978 -45.279499 -76.199997, + -1.9071367e-009 -45.499599 -76.199997, + -4.0688801 -24.601101 -93.199997, + -1.00639 -24.973 -93.199997, + -2.9607 -16.7906 -95.739998, + -17.4492 -42.020699 -76.199997, + -21.492901 -40.103298 -76.199997, + -6.4182301 -24.0772 -93.199997, + -13.2368 -43.531601 -76.199997, + -8.8628702 -23.369101 -93.199997, + -4.9993701 -24.4881 -93.199997, + -5.83144 -16.021299 -95.739998, + -2.77526 -61.722198 -61.1507, + -8.8963299 -44.621399 -76.199997, + -4.46978 -45.279499 -76.199997, + -14.1467 -84.582298 20.372, + -15.9847 -84.582298 18.964199, + -16.189199 -84.128899 19.2069, + 20.573099 -85.7164 8.7842798, + 19.6644 -85.7164 10.6643, + -16.463499 50.798801 30.8011, + -2.3816199 50.798801 34.807999, + 21.063 -83.627296 14.1121, + -8.7885303 -84.582298 -27.6619, + -29.039101 50.798801 19.403299, + -34.756802 50.798801 3.42325, + -34.924999 44.428799 1.5933899e-009, + -34.924999 50.798801 -2.3365925e-009, + -34.924999 44.428799 -13.2069, + -34.924999 -10.428 -25.389999, + -34.924999 44.428799 -43.685902, + -34.924999 -48.250599 -51.839802, + -34.924999 -50.798 -48.2342, + -34.0494 -32.653 7.7715402, + -33.629902 44.428799 9.4226503, + -34.1618 -44.428001 7.2613201, + -34.253899 50.798801 6.81353, + -34.0494 -10.428 7.7715402, + -8.79004 61.120499 31.6894, + -6.31633 61.120499 32.273602, + -8.7589598 61.6049 31.577299, + -22.814301 -85.291 7.3122101, + -22.3367 -85.524902 7.1591201, + -24.9286 -84.128899 3.09203, + -23.246 -84.973602 7.4505801, + -22.450001 -84.973602 9.5856895, + -23.408899 -85.524902 -1.48505, + -22.747 -85.668198 2.82144, + -23.445299 -85.524902 0.70415998, + -24.337999 -84.128899 -6.2175002, + -24.811701 -84.128899 -3.92103, + -23.652201 -84.128899 -8.4597902, + -24.030399 -84.582298 -6.1389298, + -23.3533 -84.582298 -8.35289, + -25.069201 -84.128899 -1.59039, + -21.252899 -85.524902 -9.9244404, + -20.768499 -85.668198 -9.6982498, + 14.2754 63.373402 -44.702599, + 28.922199 52.798801 -50.737099, + 21.492901 40.104099 -76.199997, + 24.4793 63.798801 16.906401, + 22.9375 63.192402 21.759001, + 22.629299 63.452801 21.4667, + 16.856899 63.798801 25.828899, + 32.108501 61.120499 7.1082702, + 31.9949 61.6049 7.0831299, + 17.9538 61.6049 27.413601, + 20.0175 61.6049 25.945101, + 23.7743 61.6049 22.552799, + 21.8337 62.065201 24.180099, + 21.9615 61.6049 24.3216, + 24.8437 62.8689 20.1612, + 24.5495 63.192402 19.922501, + -5.7379398 63.056 -50.990898, + 16.7309 63.798801 27.268801, + 5.7143502 63.798801 29.195999, + -0.354808 63.798801 -49.821899, + -0.364434 63.750599 -50.3731, + 0.36386099 63.750599 -50.373199, + 0.35424101 63.798801 -49.821899, + -1.96696 63.798801 -49.716202, + -2.0294099 63.750599 -50.264, + -28.3214 61.6049 16.4846, + -26.963699 61.6049 18.6227, + -28.422001 61.120499 16.5431, + -28.1567 62.065201 16.3887, + -29.51 61.6049 14.248, + -29.978399 63.192402 -10.044, + -33.832401 52.5797 -46.7141, + -29.1131 63.192402 -12.3294, + -34.233799 52.3111 -46.725899, + -34.285099 52.265202 -46.743698, + -34.8242 51.4161 -47.449402, + -34.813599 51.456902 -47.401199, + -34.894901 51.144299 -47.77, + -34.825001 51.2383 -47.703602, + -32.2854 63.608799 0.64983797, + -30.6112 62.8689 9.3080597, + -30.9207 62.490002 9.4021902, + -32.183998 63.798801 0.296938, + -31.808701 62.065201 7.0422802, + -32.820099 61.120499 2.079, + -32.400002 63.608799 -1.7491808e-010, + -29.8423 63.452801 9.0742598, + -30.248699 63.192402 9.1978502, + 6.95367 24.007299 -93.199997, + 12.5274 42.166901 -79.199997, + -4.9993701 24.489 -93.199997, + -1.00639 24.973801 -93.199997, + -2.9607 16.791401 -95.739998, + -5.7576199 43.610001 -79.199997, + -5.83144 16.0222 -95.739998, + -8.0384398 43.2477 -79.199997, + -8.8628702 23.3699 -93.199997, + -10.2971 42.766201 -79.199997, + -12.5274 42.166901 -79.199997, + -24.9937 0.00040901714 -93.199997, + -24.9126 -2.01074 -93.199997, + -24.9126 2.01156 -93.199997, + -34.924999 29.163601 -76.199997, + -34.924999 -29.1628 -76.199997, + -15.6215 2.7549 -95.739998, + -17.049999 0.00040901673 -95.739998, + -14.7657 8.5254097 -95.739998, + -15.8625 0.00040901706 -95.739998, + -8.5249996 -14.7653 -95.739998, + -14.7657 -8.5245895 -95.739998, + -25.7117 63.798801 14.9656, + -28.8125 62.8689 13.9113, + -25.5352 61.120499 20.7229, + -25.444901 61.6049 20.649599, + -26.9739 51.146099 22.1369, + -27.059401 61.120499 18.688801, + -19.3864 51.146099 29.0138, + 32.106899 63.798801 0.58485401, + 32.183998 63.798801 0.296938, + 29.8424 63.452801 9.0739202, + 28.623699 63.643398 11.1841, + 32.209999 63.798801 7.3932954e-010, + 31.9809 63.798801 0.85500002, + 28.172501 63.759701 11.0078, + 27.7099 63.798801 10.8271, + -6.10114 -85.7164 -26.9223, + -7.3708 -85.668198 -26.4259, + -16.861799 -85.7164 -14.7002, + -19.0406 -85.524902 -13.698, + -19.4478 -85.291 -13.9909, + -20.2349 -85.524902 -11.8629, + -17.680401 -85.524902 -15.4138, + -18.6066 -85.668198 -13.3858, + -17.277399 -85.668198 -15.0625, + -7.7737498 -85.524902 -26.777201, + -2.70857 -62.113602 -60.765099, + -2.20577 -84.973602 -31.0501, + 1.80627 -85.7164 -29.0487, + 0.64175099 -85.668198 -29.7575, + 0.67683399 -85.524902 -30.290899, + 2.9758501 -85.7164 -28.7342, + 3.3260701 -85.524902 -29.7621, + 2.1170299 -85.291 -30.605499, + 3.4878299 -85.291 -30.2369, + 2.0188401 -85.524902 -30.1136, + 4.5759902 -85.524902 -29.242399, + 3.1536601 -85.668198 -29.2561, + 1.9141999 -85.668198 -29.589399, + 19.2981 -85.7164 -11.3137, + 20.268999 -85.7164 -9.4649801, + 18.1591 -85.7164 -13.0639, + 20.2349 -85.524902 -11.8629, + 20.667601 -85.291 -12.1166, + 19.4478 -85.291 -13.9909, + 19.0406 -85.524902 -13.698, + 21.707399 -85.291 -10.1367, + 21.252899 -85.524902 -9.9244404, + 19.773701 -85.668198 -11.5925, + 20.768499 -85.668198 -9.6982498, + 13.7373 7.9316602 -95.739998, + 5.83144 16.0222 -95.739998, + 2.9607 16.791401 -95.739998, + 15.6215 2.7549 -95.739998, + 10.9595 13.0615 -95.739998, + -7.9312501 13.7377 -95.739998, + 14.7657 8.5254097 -95.739998, + 16.791 2.9611101 -95.739998, + 16.021799 5.8318501 -95.739998, + 22.1308 11.6155 -93.199997, + 21.806801 12.1279 -93.199997, + 19.981001 15.0152 -93.199997, + 17.4032 17.9249 -93.199997, + 17.3137 18.0259 -93.199997, + 13.0611 10.9599 -95.739998, + 17.8818 17.384701 -93.199997, + 34.924999 29.163601 -76.199997, + 18.1842 -85.524902 14.816, + 16.3423 -85.668198 16.072201, + 15.9492 -85.7164 15.6856, + 17.3423 -85.7164 14.1301, + 24.498199 -84.582298 -3.87148, + 23.6513 -84.973602 -6.0420599, + 24.030399 -84.582298 -6.1389298, + 24.111601 -84.973602 -3.81039, + 24.337999 -84.128899 -6.2175002, + 24.811701 -84.128899 -3.92103, + 25.069201 -84.128899 -1.59039, + 24.752399 -84.582298 -1.57029, + 24.6136 -84.582298 3.0529599, + 24.5317 -84.128899 5.4030099, + 24.221701 -84.582298 5.3347301, + 24.9286 -84.128899 3.09203, + 23.8395 -84.973602 5.2505598, + 24.791 -84.582298 0.74457598, + 25.108299 -84.128899 0.75410599, + 22.910999 -85.668198 0.68811202, + 23.946699 -85.291 0.71921802, + 23.775299 -85.291 2.9489801, + 24.225201 -84.973602 3.0047901, + 24.399799 -84.973602 0.73282802, + 23.2775 -85.524902 2.8872399, + 23.445299 -85.524902 0.70415998, + 23.909401 -85.291 -1.5168101, + 24.3619 -84.973602 -1.5455101, + 23.408899 -85.524902 -1.48505, + 20.1406 44.428799 28.5327, + 28.898199 -60.662498 16.4853, + 22.081499 -84.128899 11.9752, + 23.1019 -84.128899 9.8640099, + 23.6187 -84.582298 7.5700302, + 21.458401 -84.973602 11.6373, + 21.802401 -84.582298 11.8238, + 19.9032 -85.291 13.3351, + 21.0599 -85.291 11.4211, + 22.8099 -84.582298 9.7393599, + 22.450001 -84.973602 9.5856895, + 22.0331 -85.291 9.4076595, + -22.875299 -85.668198 -1.45121, + -21.673901 -85.7164 -5.5369201, + -22.0958 -85.7164 -3.4918301, + -21.0632 -85.7164 -7.5337701, + -22.3848 -85.668198 4.9301801, + -21.8276 -85.668198 6.9959602, + -20.573099 -85.7164 8.7842798, + -20.149099 -85.668198 10.9272, + -21.0802 -85.668198 9.0007801, + -21.302601 -85.7164 6.8276801, + -21.058701 -84.973602 -12.3459, + -19.8158 -84.973602 -14.2557, + -21.396299 -84.582298 -12.5438, + -20.667601 -85.291 -12.1166, + -22.118099 -84.973602 -10.3285, + -22.4727 -84.582298 -10.4941, + -21.707399 -85.291 -10.1367, + -4.0941701 -85.7164 -28.269199, + -5.1419501 -85.7164 -27.661699, + 4.0941701 -85.7164 -28.269199, + 21.0632 -85.7164 -7.5337701, + -6.9552202 -85.7164 -26.063601, + 21.673901 -85.7164 -5.5369201, + 0.90679097 -62.113602 -60.971699, + -0.92911798 -61.722198 -61.3624, + -0.90679097 -62.113602 -60.971699, + 0.92911798 -61.722198 -61.3624, + 2.70857 -62.113602 -60.765099, + -0.73950499 -84.973602 -31.243799, + 0.73950499 -84.973602 -31.243799, + -8.0033903 -61.722198 -59.286598, + -9.3371201 -62.113602 -57.965801, + -9.5670099 -61.722198 -58.282501, + 20.8687 -84.128899 13.982, + -10.9906 -85.7164 19.483999, + -12.7594 -85.7164 18.3743, + 20.2798 -84.973602 13.5874, + 20.6049 -84.582298 13.8053, + 6.8076 51.146099 34.224098, + 3.8052499 61.120499 32.665001, + -20.5284 -44.428001 28.2549, + -20.5233 -50.798 28.248301, + -21.7754 -10.428 27.3055, + -21.7754 -32.653 27.3055, + -20.1406 44.428799 28.5327, + -19.403299 50.798801 29.039101, + -16.34 -83.627296 19.3857, + -14.3278 -84.128899 20.632799, + -11.535 -10.428 32.965099, + -11.535 -32.653 32.965099, + -10.1294 51.146099 33.392101, + 2.0806619e-009 51.146099 34.8946, + -7.1057 44.428799 34.1945, + -3.42325 50.798801 34.756802, + -7.1024599 50.798801 34.181599, + -6.8076 51.146099 34.224098, + -3.42027 51.146099 34.726601, + -7.7715402 -32.653 34.0494, + -7.7715402 -10.428 34.0494, + -31.177601 -60.662498 11.6113, + -18.076401 -83.627296 17.777599, + -22.150999 -60.662498 24.823299, + -28.2549 -44.428001 20.5284, + -29.5718 -10.428 18.5812, + -33.444199 -50.798 10.0619, + -33.421101 50.798801 10.1382, + -30.7743 51.146099 16.4492, + -32.2384 51.146099 13.3536, + -33.392101 51.146099 10.1294, + -34.705399 -32.653 3.9103601, + -34.7337 -44.428001 3.65066, + -34.705399 -10.428 3.9103601, + -34.552799 -50.798 5.0851202, + -34.599701 44.428799 4.75562, + -3.79142 61.6049 32.5495, + -6.2939901 61.6049 32.1595, + -3.8048799 61.120499 32.6651, + -6.25737 62.065201 31.972401, + -3.7693601 62.065201 32.360199, + -24.6136 -84.582298 3.0529599, + -25.108299 -84.128899 0.75410599, + -22.8099 -84.582298 9.7393599, + -22.081499 -84.128899 11.9752, + -22.6404 -85.668198 -3.5778799, + -22.208099 -85.668198 -5.6733899, + -23.1684 -85.524902 -3.66133, + -21.5823 -85.668198 -7.71945, + -22.085699 -85.524902 -7.8994899, + -24.399799 -84.973602 0.73282802, + -23.909401 -85.291 -1.5168101, + -24.791 -84.582298 0.74457598, + -24.752399 -84.582298 -1.57029, + -19.2981 -85.7164 -11.3137, + -20.268999 -85.7164 -9.4649801, + -18.1591 -85.7164 -13.0639, + -19.773701 -85.668198 -11.5925, + 33.542801 52.700401 -46.808399, + 33.698799 52.643101 -46.7467, + 15.3323 63.373402 -43.285198, + 33.5289 52.705502 -46.8139, + 31.819599 52.798801 -48.235298, + 12.0677 63.056 -47.551102, + 29.0525 63.452801 11.3516, + 3.44239 63.798801 29.5502, + 23.486099 63.759701 19.0595, + 30.2488 63.192402 9.1975002, + 29.448099 63.192402 11.5062, + 30.9209 62.490002 9.4018402, + 30.6113 62.8689 9.3077097, + 31.8088 62.065201 7.0419202, + 31.5546 62.490002 6.9856501, + 32.371101 63.608799 0.329932, + 32.2854 63.608799 0.64983797, + 32.266499 50.798801 13.3652, + 30.8011 50.798801 16.463499, + 30.7743 51.146099 16.4492, + 32.2384 51.146099 13.3536, + 32.0336 44.428799 13.9142, + 32.965099 -10.428 11.535, + 32.620499 -50.798 12.4763, + 33.421101 50.798801 10.1382, + 31.9056 -44.428001 14.2053, + 33.392101 51.146099 10.1294, + 30.5224 61.6049 11.926, + 29.614901 61.120499 14.2983, + 29.510201 61.6049 14.2477, + 30.630699 61.120499 11.9683, + 30.344801 62.065201 11.8566, + 31.169901 62.065201 9.4775696, + 31.352301 61.6049 9.5330296, + 31.4636 61.120499 9.5668697, + 21.659201 62.490002 23.9869, + 23.636 62.065201 22.4216, + 25.0949 62.490002 20.365101, + 16.7055 63.608799 27.635099, + 16.5599 63.798801 27.512899, + 23.2124 62.8689 22.0198, + 23.4471 62.490002 22.242399, + 16.349199 63.798801 27.7237, + 26.9639 61.6049 18.6224, + 26.806999 62.065201 18.514099, + 28.3216 61.6049 16.484301, + 27.059601 61.120499 18.688499, + 25.445101 61.6049 20.6493, + 28.422199 61.120499 16.542801, + 25.2971 62.065201 20.5292, + 27.3248 63.192402 15.9041, + 28.4715 63.192402 13.7462, + 29.801001 62.8689 11.6441, + 30.1024 62.490002 11.7619, + 27.9319 62.490002 16.257401, + 29.338499 62.065201 14.1648, + 29.104 62.490002 14.0516, + 28.1569 62.065201 16.388399, + 28.8127 62.8689 13.9109, + 27.652201 62.8689 16.0947, + 26.5928 62.490002 18.3661, + 26.326599 62.8689 18.182301, + -3.89182 63.373402 -51.009102, + -2.1981399 63.056 -51.7439, + -2.14679 63.373402 -51.293499, + -3.98614 63.056 -51.452499, + -5.6015301 63.373402 -50.558601, + -5.4505901 63.6073 -50.080299, + -3.7874601 63.6073 -50.518398, + -2.0899701 63.6073 -50.795101, + -32.974701 52.798199 -47.189899, + -32.924999 52.798801 -47.2346, + -13.4086 63.056 -46.332199, + -33.4594 52.726101 -46.848301, + -13.0879 63.373402 -46.011902, + -33.2379 52.7742 -46.982899, + -33.542301 52.698799 -46.8111, + -32.183998 63.798801 -0.296938, + -32.209999 63.798801 -2.0661748e-009, + -11.1203 63.750599 -46.4021, + -12.733 63.6073 -45.657398, + 16.115999 63.798801 26.413799, + 31.2806 63.798801 0.375054, + 14.8528 63.798801 -41.016602, + -3.44205 63.798801 29.5502, + -5.99087 63.452801 30.610701, + -29.5756 63.452801 -9.90909, + -29.139099 63.643398 -9.7628603, + -34.100399 52.416698 -46.699001, + -33.971401 52.503201 -46.694801, + -34.105202 52.413502 -46.6991, + -33.9505 52.5159 -46.696098, + -25.3286 37.798698 -76.199997, + -32.4464 61.6049 4.59128, + -32.704102 61.6049 2.07165, + -32.561501 61.120499 4.6075802, + -32.371101 63.608799 0.329932, + -32.257599 62.065201 4.56457, + -31.9949 61.6049 7.0834999, + -27.238001 63.759701 13.1511, + -28.6236 63.643398 11.1844, + -27.709801 63.798801 10.8274, + -32.106899 63.798801 0.58485401, + -28.1724 63.759701 11.0081, + -15.7869 63.798801 27.0933, + -26.7908 63.798801 12.9351, + -6.1452198 62.8689 31.399401, + -6.2073698 62.490002 31.7169, + -6.0724602 63.192402 31.027599, + -3.7392399 62.490002 32.101601, + -3.7018099 62.8689 31.780199, + -27.9317 62.490002 16.257799, + -26.5926 62.490002 18.3664, + -25.0947 62.490002 20.3654, + -1.16872 63.759701 30.2241, + -1.1495301 63.798801 29.7278, + 1.14987 63.798801 29.7278, + -3.5555699 63.643398 30.5247, + -3.4995201 63.759701 30.0436, + -5.9024601 63.643398 30.159, + -15.8387 61.120499 28.820499, + -13.3536 51.146099 32.2384, + -16.4492 51.146099 30.7743, + -17.953501 61.6049 27.413799, + -18.0173 61.120499 27.511101, + -21.659 62.490002 23.987101, + -23.446899 62.490002 22.242701, + -21.961201 61.6049 24.321899, + -23.6357 62.065201 22.4219, + -23.774 61.6049 22.553101, + -21.833401 62.065201 24.1803, + -23.8584 61.120499 22.633101, + -22.039101 61.120499 24.408199, + -20.0882 61.120499 26.037399, + -20.0172 61.6049 25.945299, + -0.60556799 -85.7164 -29.2073, + 0.60556799 -85.7164 -29.2073, + -1.9141999 -85.668198 -29.589399, + -1.80627 -85.7164 -29.0487, + -0.64175099 -85.668198 -29.7575, + -2.9758501 -85.7164 -28.7342, + -2.0188401 -85.524902 -30.1136, + -0.67683399 -85.524902 -30.290899, + 12.1275 21.7652 -93.199997, + 8.5249996 14.7661 -95.739998, + 14.198 20.569799 -93.199997, + 10.7146 22.5809 -93.199997, + 12.9053 42.0201 -79.199997, + 19.0424 -85.668198 12.7584, + 20.149099 -85.668198 10.9272, + 19.4865 -85.524902 13.0559, + 17.7698 -85.668198 14.4784, + 18.584299 -85.7164 12.4515, + 16.463499 50.798801 30.8011, + 17.4625 -44.428001 30.245899, + 16.067801 44.428799 31.009399, + 18.5812 -32.653 29.5718, + 18.5812 -10.428 29.5718, + 19.403299 50.798801 29.039101, + 18.1938 -50.798 29.811701, + 17.4524 -50.798 30.2279, + 30.241899 -60.178101 14.1437, + 30.1366 -60.662498 14.0944, + 31.2866 -60.178101 11.6519, + 30.4298 -51.145302 17.077999, + 31.595301 -51.145302 14.8113, + 32.592098 -51.145302 12.4654, + 27.5665 -60.178101 18.8337, + 28.999201 -60.178101 16.5429, + 29.101999 -51.145302 19.2537, + 27.470501 -60.662498 18.768101, + 25.953199 -60.178101 21.001101, + 25.862801 -60.662498 20.927999, + -22.3599 -85.7164 0.671561, + -22.1999 -85.7164 2.7535701, + -22.910999 -85.668198 0.68811202, + -22.3251 -85.7164 -1.4163001, + -19.6644 -85.7164 10.6643, + -21.846399 -85.7164 4.8115902, + -6.1833301 -62.113602 -59.745499, + -7.81107 -62.113602 -58.945801, + -6.3355699 -61.722198 -60.105999, + -4.5852599 -61.722198 -60.730099, + -4.47508 -62.113602 -60.3545, + -3.6340401 -84.973602 -30.666, + -15.9492 -85.7164 15.6856, + -14.4171 -85.7164 17.1045, + -16.3423 -85.668198 16.072201, + -17.3423 -85.7164 14.1301, + -17.7698 -85.668198 14.4784, + 14.4171 -85.7164 17.1045, + 21.846399 -85.7164 4.8115902, + -18.584299 -85.7164 12.4515, + -6.81353 50.798801 34.253899, + -1.27442 -51.145302 34.8713, + -2.3833699 44.428799 34.843601, + -3.2319952e-011 50.798801 34.924999, + 2.0715731e-009 -44.428001 34.924999, + 3.1457175e-009 -50.798 34.901699, + 1.27442 -51.145302 34.8713, + 16.723499 -85.524902 16.4471, + 3.9103601 -32.653 34.705399, + 1.27553 -50.798 34.901699, + 3.42325 50.798801 34.756802, + 3.9103601 -10.428 34.705399, + 3.42027 51.146099 34.726601, + 3.65066 -44.428001 34.7337, + 2.3833699 44.428799 34.843601, + 2.3816199 50.798801 34.807999, + -18.1938 -50.798 29.811701, + -18.5812 -32.653 29.5718, + -20.3214 -50.798 28.4041, + -17.4625 -44.428001 30.245899, + -18.5812 -10.428 29.5718, + -18.177999 -51.145302 29.785801, + -17.4524 -50.798 30.2279, + -14.4612 -83.627296 20.8249, + -20.141399 -60.178101 26.625999, + -20.303699 -51.145302 28.3794, + -17.9223 -60.178101 28.1675, + -20.071199 -60.662498 26.5333, + -17.8599 -60.662498 28.069401, + -10.7924 -44.428001 33.215599, + -10.1382 50.798801 33.421101, + -11.6957 44.428799 32.908501, + -11.2766 -50.798 33.054401, + -10.7881 -50.798 33.201401, + -16.067801 44.428799 31.009399, + -32.0145 -60.662498 9.0521498, + -19.6553 -83.627296 16.0147, + -24.0858 -60.662498 22.9508, + -25.862801 -60.662498 20.927999, + -28.898199 -60.662498 16.4853, + -27.470501 -60.662498 18.768101, + -21.063 -83.627296 14.1121, + -22.2871 -83.627296 12.0867, + -32.641602 -60.662498 6.4336901, + -25.1607 -83.627296 3.12082, + -34.831799 -50.798 2.54936, + -33.170502 -60.178101 3.7862899, + -29.5718 -32.653 18.5812, + -29.840599 44.428799 18.1465, + -32.965099 -32.653 11.535, + -32.965099 -10.428 11.535, + -33.215599 -44.428001 10.7924, + -32.620499 -50.798 12.4763, + -30.241899 -60.178101 14.1437, + -30.1366 -60.662498 14.0944, + -31.2866 -60.178101 11.6519, + -31.595301 -51.145302 14.8113, + -32.592098 -51.145302 12.4654, + -34.924999 -50.798 3.1437823e-009, + -34.801498 -51.145302 2.5471399, + -25.3027 -83.627296 -1.6052001, + -34.810799 -51.464199 -47.392399, + -23.775299 -85.291 2.9489801, + -23.3967 -85.291 5.1530499, + -23.8395 -84.973602 5.2505598, + -24.225201 -84.973602 3.0047901, + -22.9069 -85.524902 5.0451598, + -23.2775 -85.524902 2.8872399, + -23.946699 -85.291 0.71921802, + -23.921 -84.128899 7.6669202, + -23.1019 -84.128899 9.8640099, + -23.6187 -84.582298 7.5700302, + -24.1437 -83.627296 7.7382998, + -23.316999 -83.627296 9.9558601, + -24.5317 -84.128899 5.4030099, + -24.221701 -84.582298 5.3347301, + -24.760099 -83.627296 5.45332, + -23.212 -85.291 -5.9298501, + -22.558001 -85.291 -8.0684099, + -22.726101 -85.524902 -5.8056998, + -24.111601 -84.973602 -3.81039, + -24.3619 -84.973602 -1.5455101, + -23.663799 -85.291 -3.73962, + -24.498199 -84.582298 -3.87148, + -23.6513 -84.973602 -6.0420599, + 33.1693 52.783901 -47.032001, + 33.347 52.753799 -46.911999, + 25.3286 37.798698 -76.199997, + 32.924999 52.798801 -47.2346, + 13.4081 63.056 -46.332401, + 26.0149 63.192402 17.966999, + 24.2197 63.452801 19.6548, + 23.862301 63.643398 19.364799, + 26.5599 63.643398 15.4589, + 24.888 63.759701 17.1887, + 26.141199 63.759701 15.2152, + 25.2866 63.643398 17.464001, + 27.6745 63.643398 13.3614, + 28.089001 63.452801 13.5615, + 26.957701 63.452801 15.6904, + 25.6653 63.452801 17.725599, + 15.8349 63.798801 28.020599, + 8.6387701 62.490002 31.1427, + -11.9647 63.798801 -44.8899, + -10.7694 63.798801 -45.976898, + -12.3548 63.750599 -45.279598, + -31.365999 63.798801 -1.6174139e-009, + -9.4752998 63.798801 -46.944099, + -29.076401 63.798801 1.67729, + -31.8099 63.798801 -1.09917, + -31.8099 63.798801 1.09917, + -7.9518499 63.798801 28.667601, + -15.445 63.798801 27.257601, + -27.3946 63.798801 -11.6016, + -31.9809 63.798801 -0.85500002, + -27.851999 63.759701 -11.7953, + -32.106899 63.798801 -0.58485401, + -28.2981 63.643398 -11.9842, + -28.3922 63.601101 -12.024, + -28.721901 63.452801 -12.1637, + -14.8532 63.798801 -41.016399, + -15.554 63.798801 -39.560699, + -28.0888 63.452801 13.5618, + -28.4713 63.192402 13.7465, + -27.674299 63.643398 13.3617, + -29.052299 63.452801 11.352, + -29.448 63.192402 11.5066, + -26.141001 63.759701 15.2155, + -26.5597 63.643398 15.4592, + -23.100201 63.798801 18.746799, + -24.479099 63.798801 16.9067, + -24.8878 63.759701 17.188999, + -23.485901 63.759701 19.059799, + -22.9373 63.192402 21.7593, + -23.212099 62.8689 22.02, + -24.2194 63.452801 19.6551, + -25.2864 63.643398 17.4643, + -23.862 63.643398 19.365, + -22.629101 63.452801 21.4669, + -26.0147 63.192402 17.9673, + -27.3246 63.192402 15.9044, + -26.9575 63.452801 15.6907, + -25.6651 63.452801 17.725901, + -27.652 62.8689 16.094999, + -26.326401 62.8689 18.1826, + -24.549299 63.192402 19.9228, + -24.8435 62.8689 20.161501, + -13.5655 61.120499 29.9576, + -11.2113 61.120499 30.915899, + -7.1508098 -85.291 -28.113199, + -6.2792301 -84.973602 -29.3563, + -7.4505701 -84.973602 -28.4533, + -4.9997001 -84.973602 -30.0982, + 15.1534 -32.653 31.466299, + 15.1534 -10.428 31.466299, + 13.3652 50.798801 32.266499, + 10.1382 50.798801 33.421101, + 25.988501 -51.145302 23.285801, + 26.9974 50.798801 22.1562, + 25.9543 -44.428001 23.3694, + 17.8599 -60.662498 28.069401, + 21.7754 -32.653 27.3055, + 20.5284 -44.428001 28.2549, + 21.7754 -10.428 27.3055, + 22.1562 50.798801 26.9974, + 20.303699 -51.145302 28.3794, + 18.177999 -51.145302 29.785801, + 20.3214 -50.798 28.4041, + 17.9223 -60.178101 28.1675, + 20.5233 -50.798 28.248301, + -11.9932 -84.973602 21.261499, + -15.7324 -84.973602 18.6649, + -13.9235 -84.973602 20.0506, + -17.404301 -84.973602 17.116699, + -17.0811 -85.291 16.7988, + 14.7725 -85.668198 17.525999, + 10.9906 -85.7164 19.483999, + 12.7594 -85.7164 18.3743, + 10.343 -83.627296 23.1478, + 15.5316 -60.662498 29.4217, + 8.0644703 -84.128899 23.7899, + 10.2476 -84.128899 22.934299, + -7.2613201 -44.428001 34.1618, + -1.27553 -50.798 34.901699, + -3.65066 -44.428001 34.7337, + -3.9103601 -32.653 34.705399, + -3.9103601 -10.428 34.705399, + -3.8197899 -50.798 34.7155, + -6.3436699 -50.798 34.344002, + -7.2566099 -50.798 34.140701, + -13.6474 -51.145302 32.115101, + -15.9553 -51.145302 31.0333, + -15.5859 -60.178101 29.524599, + -13.6593 -50.798 32.143101, + -13.3652 50.798801 32.266499, + -14.1982 -50.798 31.890499, + -34.059799 -51.145302 7.5871401, + -32.1264 -60.178101 9.0838003, + -32.755699 -60.178101 6.4561901, + -34.5228 -51.145302 5.0806999, + -34.0895 -50.798 7.59375, + -33.4151 -51.145302 10.0531, + -28.999201 -60.178101 16.5429, + -27.3055 -10.428 21.7754, + -27.0917 44.428799 22.040701, + -22.3211 -51.145302 26.8216, + -22.2285 -60.178101 24.910101, + -27.3055 -32.653 21.7754, + -25.9543 -44.428001 23.3694, + -26.9974 50.798801 22.1562, + -30.2349 -50.798 17.455799, + -30.245899 -44.428001 17.4625, + -30.4298 -51.145302 17.077999, + -31.466299 -32.653 15.1534, + -30.456301 -50.798 17.092899, + -32.0336 44.428799 13.9142, + -31.9056 -44.428001 14.2053, + -32.266499 50.798801 13.3652, + -30.8011 50.798801 16.463499, + -31.466299 -10.428 15.1534, + -31.622801 -50.798 14.8242, + -33.347099 -60.178101 -1.61026, + -33.251801 -60.662498 1.08779, + -33.2309 -60.662498 -1.60465, + -33.368099 -60.178101 1.09159, + -33.055 -60.662498 3.7730999, + -25.3421 -83.627296 0.76112801, + 6.2943501 61.6049 32.159401, + 8.7083502 62.065201 31.393499, + 6.25773 62.065201 31.9723, + 6.31669 61.120499 32.273602, + 3.7697301 62.065201 32.3601, + -1.25884 62.065201 32.5546, + -1.24878 62.490002 32.294498, + -1.23628 62.8689 31.971201, + 1.26658 61.6049 32.745098, + 3.79179 61.6049 32.5495, + 1.27107 61.120499 32.861301, + 1.25921 62.065201 32.5546, + -1.2661999 61.6049 32.745098, + -1.2707 61.120499 32.861401, + 15.5799 63.608799 28.284901, + 8.5522804 62.8689 30.8309, + 15.839 61.120499 28.820299, + 16.4492 51.146099 30.7743, + 16.4713 63.608799 27.869301, + 16.105 63.798801 27.894699, + 19.3864 51.146099 29.0138, + 18.017599 61.120499 27.5109, + 11.107 62.065201 30.627199, + 8.7593203 61.6049 31.5772, + 11.2116 61.120499 30.915701, + 8.79041 61.120499 31.689301, + 6.0728102 63.192402 31.0275, + -14.6651 63.798801 28.020599, + -33.798302 52.598099 -46.7192, + -33.641399 52.6661 -46.766602, + -14.0161 63.798801 -42.398201, + -13.0503 63.798801 -43.693401, + -16.5539 63.6073 -39.9842, + -16.061701 63.750599 -39.7757, + -15.338 63.750599 -41.279099, + -17.0158 63.373402 -40.179798, + -16.248899 63.373402 -41.7729, + 15.5469 63.798801 28.097799, + -3.60883 63.452801 30.981899, + -3.65797 63.192402 31.4039, + 1.222 63.192402 31.5926, + -1.22164 63.192402 31.5926, + -1.20522 63.452801 31.1681, + -13.5175 61.6049 29.8517, + -11.1716 61.6049 30.806499, + -16.200001 63.608799 28.0592, + -11.1066 62.065201 30.6273, + -8.7080002 62.065201 31.3936, + -8.6384201 62.490002 31.142799, + -15.5799 63.608799 28.284901, + -8.5519304 62.8689 30.830999, + -6.81916 -85.524902 -27.7369, + -5.4491801 -85.668198 -28.119499, + -6.4656901 -85.668198 -27.335899, + 14.1982 -50.798 31.890499, + 14.2053 -44.428001 31.9056, + 15.9692 -50.798 31.060301, + 11.535 -10.428 32.965099, + 11.6957 44.428799 32.908501, + 11.535 -32.653 32.965099, + 13.6593 -50.798 32.143101, + 10.7881 -50.798 33.201401, + 10.7924 -44.428001 33.215599, + 11.2766 -50.798 33.054401, + 7.1057 44.428799 34.1945, + 6.81353 50.798801 34.253899, + 27.643 -50.798 21.3452, + 26.0112 -50.798 23.306101, + 27.3055 -32.653 21.7754, + 27.618999 -51.145302 21.3267, + 27.3055 -10.428 21.7754, + 28.2549 -44.428001 20.5284, + 27.0917 44.428799 22.040701, + 29.127399 -50.798 19.2705, + 22.2285 -60.178101 24.910101, + 20.071199 -60.662498 26.5333, + 20.141399 -60.178101 26.625999, + 22.3211 -51.145302 26.8216, + 24.17 -60.178101 23.031099, + 18.9245 -84.973602 15.4192, + 17.0811 -85.291 16.7988, + 18.573099 -85.291 15.1329, + 19.2279 -84.582298 15.6664, + 22.150999 -60.662498 24.823299, + 24.0858 -60.662498 22.9508, + 19.6553 -83.627296 16.0147, + 19.474001 -84.128899 15.8669, + 22.340599 -50.798 26.844999, + 24.240499 -50.798 25.142599, + 25.9522 -50.798 23.3673, + 24.2195 -51.145302 25.1208, + 24.6957 -32.653 24.6957, + 23.353901 -50.798 25.937099, + 23.3694 -44.428001 25.9543, + 23.8382 44.428799 25.524401, + 24.6957 -10.428 24.6957, + 24.6957 50.798801 24.6957, + -15.5316 -60.662498 29.4217, + -3.5013177e-009 -60.178101 33.385899, + -15.117 -85.524902 17.934799, + -13.6649 -85.291 19.6782, + -13.3788 -85.524902 19.266199, + -15.4403 -85.291 18.3183, + -16.723499 -85.524902 16.4471, + -14.7725 -85.668198 17.525999, + -13.0739 -85.668198 18.827101, + 7.1817298 -85.7164 21.185801, + 9.1259003 -85.7164 20.423901, + 5.3025198 -85.668198 22.299601, + 5.1749701 -85.7164 21.763201, + 7.3587298 -85.668198 21.708, + 9.3508101 -85.668198 20.9272, + -7.1817298 -85.7164 21.185801, + -9.1259003 -85.7164 20.423901, + 13.1474 -60.178101 30.6882, + 13.1016 -60.662498 30.581301, + 15.5859 -60.178101 29.524599, + 15.9553 -51.145302 31.0333, + 13.6474 -51.145302 32.115101, + 11.2668 -51.145302 33.0257, + -15.1534 -32.653 31.466299, + -15.1534 -10.428 31.466299, + -15.9692 -50.798 31.060301, + -14.2053 -44.428001 31.9056, + -3.8164699 -51.145302 34.685299, + -2.6997199 -60.178101 33.2766, + -8.8337002 -50.798 33.789398, + -22.1562 50.798801 26.9974, + -24.17 -60.178101 23.031099, + -34.900398 -51.110901 -41.5, + -34.8946 -51.145302 -3.6968326e-009, + -34.901901 -51.1012 -47.8237, + -34.8946 -51.145302 -41.5, + 3.7021699 62.8689 31.780199, + 1.23664 62.8689 31.971201, + 6.1455798 62.8689 31.3993, + 1.24915 62.490002 32.294498, + 3.73961 62.490002 32.101501, + 6.2077298 62.490002 31.716801, + 13.5178 61.6049 29.8515, + 11.172 61.6049 30.8064, + 13.5658 61.120499 29.9575, + 15.8998 63.608799 28.1992, + 16.200001 63.608799 28.0592, + -16.349199 63.798801 27.7237, + -16.5599 63.798801 27.512899, + -16.7309 63.798801 27.268801, + -16.4713 63.608799 27.869301, + -16.7055 63.608799 27.635099, + -14.9168 63.6073 -43.004902, + -15.808 63.6073 -41.533901, + -14.4734 63.750599 -42.7062, + -13.8886 63.6073 -44.383598, + -13.4759 63.750599 -44.0438, + -15.3328 63.373402 -43.285099, + -14.2759 63.373402 -44.7024, + 3.65833 63.192402 31.4039, + 5.99122 63.452801 30.6106, + 5.9028101 63.643398 30.158899, + 1.18779 63.643398 30.7082, + 1.20558 63.452801 31.1681, + -1.18744 63.643398 30.7082, + 1.16906 63.759701 30.2241, + 3.60918 63.452801 30.981899, + 3.5559199 63.643398 30.5247, + 3.49986 63.759701 30.043501, + -15.8349 63.798801 28.020599, + -16.105 63.798801 27.894699, + -15.5469 63.798801 28.097799, + -15.8998 63.608799 28.1992, + -4.5759902 -85.524902 -29.242399, + -5.7470798 -85.524902 -28.5634, + -4.3388 -85.668198 -28.7633, + -3.1536601 -85.668198 -29.2561, + -3.3260701 -85.524902 -29.7621, + -3.4878299 -85.291 -30.2369, + -4.7985501 -85.291 -29.6919, + -6.0265899 -85.291 -28.9799, + 8.8260098 -51.145302 33.759998, + 3.8197899 -50.798 34.7155, + 10.6227 -60.178101 31.6509, + 10.5857 -60.662498 31.5406, + 8.1395597 -83.627296 24.0114, + 7.2566099 -50.798 34.140701, + 6.3436699 -50.798 34.344002, + 7.7715402 -32.653 34.0494, + 8.8337002 -50.798 33.789398, + 7.7715402 -10.428 34.0494, + 7.2613201 -44.428001 34.1618, + -12.3415 -84.128899 21.878799, + -12.4564 -83.627296 22.0826, + -10.343 -83.627296 23.1478, + 1.1833301 -83.627296 25.325899, + -2.69031 -60.662498 33.160702, + 4.4224802e-010 -60.662498 33.2696, + 1.06981 -85.668198 22.8964, + 1.04408 -85.7164 22.3456, + 3.1231301 -85.7164 22.1509, + 3.20011 -85.668198 22.6968, + 3.27474 -85.524902 23.2262, + 1.0947599 -85.524902 23.430401, + -11.7705 -85.291 20.866699, + -9.5689001 -85.524902 21.4153, + -7.3587298 -85.668198 21.708, + -9.3508101 -85.668198 20.9272, + -11.2614 -85.668198 19.964199, + -11.5241 -85.524902 20.4298, + 14.4612 -83.627296 20.8249, + 12.4564 -83.627296 22.0826, + 12.3415 -84.128899 21.878799, + 15.7324 -84.973602 18.6649, + 14.1467 -84.582298 20.372, + 17.404301 -84.973602 17.116699, + 13.9235 -84.973602 20.0506, + 15.4403 -85.291 18.3183, + 15.117 -85.524902 17.934799, + 11.5241 -85.524902 20.4298, + 9.5689001 -85.524902 21.4153, + 13.6649 -85.291 19.6782, + 13.3788 -85.524902 19.266199, + 11.2614 -85.668198 19.964199, + 13.0739 -85.668198 18.827101, + 12.1855 -84.582298 21.6024, + 11.9932 -84.973602 21.261499, + 11.7705 -85.291 20.866699, + -5.3817501 -60.178101 32.949299, + -6.33815 -51.145302 34.314201, + -22.340599 -50.798 26.844999, + -24.240499 -50.798 25.142599, + -24.2195 -51.145302 25.1208, + -25.9522 -50.798 23.3673, + -24.6957 -32.653 24.6957, + -23.353901 -50.798 25.937099, + -23.3694 -44.428001 25.9543, + -23.8382 44.428799 25.524401, + -24.6957 -10.428 24.6957, + -24.6957 50.798801 24.6957, + -27.618999 -51.145302 21.3267, + -26.0112 -50.798 23.306101, + -27.643 -50.798 21.3452, + -25.988501 -51.145302 23.285801, + -25.953199 -60.178101 21.001101, + -27.5665 -60.178101 18.8337, + -29.101999 -51.145302 19.2537, + -29.127399 -50.798 19.2705, + 6.33815 -51.145302 34.314201, + 8.0285397 -60.178101 32.4062, + 2.6997199 -60.178101 33.2766, + 3.8164699 -51.145302 34.685299, + -10.1181 -84.582298 22.644501, + -9.9584703 -84.973602 22.287201, + -12.1855 -84.582298 21.6024, + -10.2476 -84.128899 22.934299, + -1.1833301 -83.627296 25.325899, + -5.7376299 -84.582298 24.1294, + -7.9625602 -84.582298 23.4893, + -5.3629999 -60.662498 32.834499, + -8.1395597 -83.627296 24.0114, + -8.0644703 -84.128899 23.7899, + -3.1231301 -85.7164 22.1509, + -5.1749701 -85.7164 21.763201, + -3.20011 -85.668198 22.6968, + -1.04408 -85.7164 22.3456, + -1.06981 -85.668198 22.8964, + 10.1181 -84.582298 22.644501, + 9.9584703 -84.973602 22.287201, + 9.7735205 -85.291 21.873301, + 3.50702 -84.128899 24.8736, + 5.5422201 -85.291 23.3076, + 5.4261899 -85.524902 22.819599, + 7.5303502 -85.524902 22.2143, + 7.69138 -85.291 22.689301, + -5.3025198 -85.668198 22.299601, + 16.189199 -84.128899 19.2069, + 14.3278 -84.128899 20.632799, + 16.34 -83.627296 19.3857, + 15.9847 -84.582298 18.964199, + 18.076401 -83.627296 17.777599, + 17.909599 -84.128899 17.6136, + 17.6833 -84.582298 17.3911, + -10.6227 -60.178101 31.6509, + -8.8260098 -51.145302 33.759998, + -11.2668 -51.145302 33.0257, + -8.0285397 -60.178101 32.4062, + -13.1474 -60.178101 30.6882, + -8.0005703 -60.662498 32.293301, + -10.5857 -60.662498 31.5406, + -13.1016 -60.662498 30.581301, + 5.3629999 -60.662498 32.834499, + 5.3817501 -60.178101 32.949299, + 8.0005703 -60.662498 32.293301, + 5.86517 -83.627296 24.6658, + 2.69031 -60.662498 33.160702, + 3.53967 -83.627296 25.1052, + -1.15759 -84.582298 24.7752, + 1.17241 -84.128899 25.0923, + -1.13933 -84.973602 24.384199, + -3.50702 -84.128899 24.8736, + -3.4626999 -84.582298 24.559299, + -5.81106 -84.128899 24.4382, + -5.86517 -83.627296 24.6658, + -3.53967 -83.627296 25.1052, + -1.17241 -84.128899 25.0923, + 5.7376299 -84.582298 24.1294, + 5.81106 -84.128899 24.4382, + 7.9625602 -84.582298 23.4893, + 7.8369298 -84.973602 23.1187, + 3.4080601 -84.973602 24.171801, + 5.6471 -84.973602 23.748699, + 3.34477 -85.291 23.7229, + 3.4626999 -84.582298 24.559299, + 1.11817 -85.291 23.9314, + 1.13933 -84.973602 24.384199, + 1.15759 -84.582298 24.7752, + -9.7735205 -85.291 21.873301, + -3.27474 -85.524902 23.2262, + -3.4080601 -84.973602 24.171801, + -1.11817 -85.291 23.9314, + -1.0947599 -85.524902 23.430401, + -5.5422201 -85.291 23.3076, + -3.34477 -85.291 23.7229, + -5.6471 -84.973602 23.748699, + -5.4261899 -85.524902 22.819599, + -7.8369298 -84.973602 23.1187, + -7.69138 -85.291 22.689301, + -7.5303502 -85.524902 22.2143 ] + + } + coordIndex [ 252, 249, 13, -1, 158, 652, 178, -1, + 39, 252, 13, -1, 39, 13, 38, -1, + 10, 178, 176, -1, 22, 426, 2, -1, + 22, 2, 145, -1, 0, 1, 2, -1, + 99, 27, 91, -1, 490, 238, 145, -1, + 490, 487, 238, -1, 579, 123, 121, -1, + 132, 133, 19, -1, 6, 278, 163, -1, + 6, 7, 278, -1, 41, 251, 252, -1, + 71, 10, 176, -1, 49, 1070, 935, -1, + 267, 935, 1070, -1, 267, 1070, 9, -1, + 267, 9, 53, -1, 12, 276, 278, -1, + 12, 278, 7, -1, 58, 13, 249, -1, + 58, 59, 13, -1, 275, 14, 15, -1, + 84, 198, 195, -1, 75, 19, 133, -1, + 75, 133, 78, -1, 23, 580, 426, -1, + 23, 22, 580, -1, 491, 2, 1, -1, + 722, 457, 408, -1, 726, 182, 466, -1, + 89, 1, 0, -1, 89, 491, 1, -1, + 89, 182, 491, -1, 89, 0, 2, -1, + 89, 2, 426, -1, 181, 726, 725, -1, + 181, 182, 726, -1, 489, 490, 145, -1, + 489, 145, 2, -1, 489, 2, 491, -1, + 25, 139, 1070, -1, 28, 336, 27, -1, + 206, 139, 25, -1, 206, 25, 94, -1, + 210, 91, 27, -1, 210, 27, 336, -1, + 93, 210, 208, -1, 207, 206, 94, -1, + 207, 872, 206, -1, 102, 334, 204, -1, + 205, 102, 204, -1, 32, 113, 109, -1, + 32, 109, 105, -1, 236, 238, 487, -1, + 236, 487, 237, -1, 34, 579, 121, -1, + 5, 4, 123, -1, 5, 123, 579, -1, + 5, 22, 145, -1, 5, 580, 22, -1, + 5, 579, 580, -1, 3, 123, 4, -1, + 3, 44, 123, -1, 3, 4, 5, -1, + 3, 145, 44, -1, 3, 5, 145, -1, + 1192, 1446, 403, -1, 588, 1109, 381, -1, + 37, 6, 163, -1, 37, 7, 6, -1, + 136, 38, 13, -1, 136, 7, 37, -1, + 136, 13, 12, -1, 136, 12, 7, -1, + 136, 37, 135, -1, 245, 251, 41, -1, + 245, 138, 206, -1, 141, 138, 245, -1, + 8, 41, 252, -1, 8, 9, 1070, -1, + 8, 1070, 41, -1, 8, 252, 39, -1, + 8, 39, 132, -1, 8, 132, 19, -1, + 8, 53, 9, -1, 8, 19, 18, -1, + 8, 18, 53, -1, 124, 575, 573, -1, + 124, 35, 355, -1, 221, 575, 124, -1, + 882, 35, 126, -1, 882, 355, 35, -1, + 162, 135, 163, -1, 413, 414, 151, -1, + 47, 10, 71, -1, 47, 178, 10, -1, + 47, 48, 178, -1, 519, 1070, 49, -1, + 268, 18, 20, -1, 54, 53, 18, -1, + 54, 18, 268, -1, 54, 268, 267, -1, + 427, 645, 652, -1, 56, 440, 286, -1, + 11, 276, 12, -1, 11, 275, 276, -1, + 11, 13, 59, -1, 11, 12, 13, -1, + 11, 14, 275, -1, 11, 59, 63, -1, + 11, 63, 14, -1, 60, 58, 249, -1, + 64, 814, 67, -1, 66, 346, 59, -1, + 66, 60, 249, -1, 61, 63, 59, -1, + 61, 59, 346, -1, 70, 14, 63, -1, + 70, 63, 67, -1, 70, 15, 14, -1, + 70, 953, 15, -1, 70, 67, 813, -1, + 280, 15, 953, -1, 280, 275, 15, -1, + 280, 279, 275, -1, 270, 981, 269, -1, + 86, 87, 84, -1, 86, 46, 189, -1, + 86, 45, 46, -1, 86, 195, 45, -1, + 86, 84, 195, -1, 177, 82, 171, -1, + 187, 189, 171, -1, 187, 171, 82, -1, + 16, 171, 189, -1, 16, 189, 46, -1, + 16, 172, 171, -1, 16, 46, 172, -1, + 17, 18, 19, -1, 17, 19, 75, -1, + 17, 75, 652, -1, 17, 20, 18, -1, + 17, 652, 268, -1, 17, 268, 20, -1, + 76, 78, 82, -1, 76, 75, 78, -1, + 73, 178, 652, -1, 73, 652, 75, -1, + 73, 75, 74, -1, 21, 426, 22, -1, + 21, 23, 426, -1, 21, 22, 23, -1, + 483, 491, 182, -1, 191, 184, 87, -1, + 88, 466, 182, -1, 88, 90, 466, -1, + 88, 585, 90, -1, 708, 203, 709, -1, + 83, 181, 725, -1, 484, 1187, 1192, -1, + 488, 487, 490, -1, 95, 94, 98, -1, + 24, 99, 91, -1, 24, 98, 99, -1, + 24, 91, 95, -1, 24, 95, 98, -1, + 100, 1070, 99, -1, 100, 25, 1070, -1, + 100, 94, 25, -1, 100, 98, 94, -1, + 26, 27, 99, -1, 26, 28, 27, -1, + 26, 99, 1070, -1, 26, 1070, 28, -1, + 791, 792, 336, -1, 791, 336, 28, -1, + 791, 28, 1070, -1, 333, 103, 209, -1, + 29, 94, 93, -1, 29, 93, 208, -1, + 29, 207, 94, -1, 29, 208, 207, -1, + 370, 209, 103, -1, 111, 369, 370, -1, + 111, 370, 102, -1, 107, 105, 109, -1, + 108, 102, 205, -1, 108, 111, 102, -1, + 51, 566, 118, -1, 51, 105, 325, -1, + 229, 242, 228, -1, 114, 113, 32, -1, + 114, 32, 115, -1, 373, 115, 374, -1, + 373, 227, 368, -1, 373, 368, 115, -1, + 30, 374, 115, -1, 30, 115, 32, -1, + 30, 117, 374, -1, 30, 32, 117, -1, + 240, 118, 566, -1, 396, 214, 215, -1, + 31, 118, 117, -1, 31, 51, 118, -1, + 31, 105, 51, -1, 31, 32, 105, -1, + 31, 117, 32, -1, 356, 224, 357, -1, + 130, 34, 583, -1, 130, 398, 579, -1, + 130, 579, 34, -1, 122, 126, 125, -1, + 122, 123, 126, -1, 33, 121, 125, -1, + 33, 125, 583, -1, 33, 34, 121, -1, + 33, 583, 34, -1, 127, 126, 35, -1, + 127, 35, 124, -1, 36, 163, 135, -1, + 36, 37, 163, -1, 36, 135, 37, -1, + 134, 38, 136, -1, 134, 39, 38, -1, + 134, 132, 39, -1, 142, 138, 141, -1, + 40, 41, 1070, -1, 40, 1070, 141, -1, + 40, 245, 41, -1, 40, 141, 245, -1, + 533, 572, 574, -1, 43, 124, 355, -1, + 42, 224, 221, -1, 42, 221, 124, -1, + 42, 124, 43, -1, 42, 357, 224, -1, + 42, 355, 357, -1, 42, 43, 355, -1, + 144, 126, 123, -1, 144, 882, 126, -1, + 144, 44, 145, -1, 144, 123, 44, -1, + 147, 238, 882, -1, 147, 145, 238, -1, + 147, 144, 146, -1, 147, 882, 144, -1, + 616, 408, 457, -1, 614, 926, 615, -1, + 261, 149, 165, -1, 150, 162, 149, -1, + 150, 259, 162, -1, 254, 413, 151, -1, + 411, 258, 152, -1, 411, 413, 254, -1, + 411, 254, 258, -1, 173, 196, 153, -1, + 173, 195, 196, -1, 173, 585, 639, -1, + 173, 45, 195, -1, 173, 172, 46, -1, + 173, 46, 45, -1, 155, 48, 47, -1, + 155, 47, 71, -1, 155, 156, 48, -1, + 157, 48, 156, -1, 157, 158, 178, -1, + 157, 178, 48, -1, 50, 325, 519, -1, + 937, 519, 49, -1, 937, 49, 935, -1, + 937, 50, 519, -1, 937, 325, 50, -1, + 937, 566, 51, -1, 937, 51, 325, -1, + 52, 267, 53, -1, 52, 53, 54, -1, + 52, 54, 267, -1, 159, 643, 427, -1, + 159, 652, 158, -1, 159, 427, 652, -1, + 442, 429, 677, -1, 281, 165, 149, -1, + 281, 149, 162, -1, 281, 163, 56, -1, + 281, 56, 286, -1, 166, 260, 261, -1, + 166, 261, 165, -1, 168, 260, 166, -1, + 168, 281, 273, -1, 168, 166, 281, -1, + 272, 168, 273, -1, 271, 632, 272, -1, + 55, 163, 278, -1, 55, 56, 163, -1, + 55, 278, 56, -1, 277, 56, 278, -1, + 277, 440, 56, -1, 739, 1003, 480, -1, + 1139, 1268, 1138, -1, 1147, 444, 948, -1, + 1147, 948, 682, -1, 57, 59, 58, -1, + 57, 58, 60, -1, 57, 66, 59, -1, + 57, 60, 66, -1, 65, 346, 64, -1, + 65, 63, 61, -1, 65, 61, 346, -1, + 345, 814, 64, -1, 345, 64, 346, -1, + 62, 67, 63, -1, 62, 64, 67, -1, + 62, 63, 65, -1, 62, 65, 64, -1, + 248, 66, 249, -1, 248, 346, 66, -1, + 248, 344, 346, -1, 68, 67, 814, -1, + 68, 813, 67, -1, 68, 69, 813, -1, + 812, 68, 814, -1, 812, 69, 68, -1, + 812, 813, 69, -1, 956, 70, 813, -1, + 956, 953, 70, -1, 169, 280, 953, -1, + 169, 450, 280, -1, 169, 449, 450, -1, + 175, 155, 71, -1, 175, 71, 176, -1, + 175, 173, 639, -1, 72, 177, 178, -1, + 72, 82, 177, -1, 72, 178, 73, -1, + 72, 73, 74, -1, 72, 74, 75, -1, + 72, 76, 82, -1, 72, 75, 76, -1, + 186, 259, 85, -1, 77, 162, 259, -1, + 77, 187, 162, -1, 77, 259, 186, -1, + 77, 186, 187, -1, 80, 82, 78, -1, + 80, 81, 82, -1, 80, 78, 133, -1, + 80, 133, 135, -1, 79, 135, 162, -1, + 79, 162, 187, -1, 79, 80, 135, -1, + 79, 81, 80, -1, 79, 187, 82, -1, + 79, 82, 81, -1, 298, 483, 299, -1, + 298, 179, 1044, -1, 298, 1044, 483, -1, + 1134, 83, 725, -1, 1134, 181, 83, -1, + 1134, 299, 483, -1, 301, 87, 184, -1, + 301, 84, 87, -1, 301, 198, 84, -1, + 301, 459, 198, -1, 188, 85, 259, -1, + 188, 186, 85, -1, 192, 188, 259, -1, + 192, 191, 188, -1, 303, 183, 184, -1, + 303, 184, 191, -1, 303, 191, 192, -1, + 190, 86, 189, -1, 190, 87, 86, -1, + 190, 191, 87, -1, 193, 585, 88, -1, + 193, 89, 426, -1, 193, 182, 89, -1, + 193, 88, 182, -1, 469, 466, 90, -1, + 469, 465, 466, -1, 469, 90, 585, -1, + 197, 461, 463, -1, 197, 153, 196, -1, + 197, 463, 153, -1, 706, 1044, 179, -1, + 706, 709, 1044, -1, 494, 496, 497, -1, + 494, 758, 759, -1, 309, 237, 487, -1, + 309, 487, 485, -1, 1061, 1067, 203, -1, + 513, 203, 1067, -1, 513, 709, 203, -1, + 513, 1044, 709, -1, 513, 511, 1044, -1, + 96, 95, 91, -1, 96, 91, 210, -1, + 96, 210, 93, -1, 92, 93, 94, -1, + 92, 94, 95, -1, 92, 96, 93, -1, + 92, 95, 96, -1, 97, 99, 98, -1, + 97, 100, 99, -1, 97, 98, 100, -1, + 517, 204, 334, -1, 598, 206, 520, -1, + 598, 245, 206, -1, 598, 595, 245, -1, + 211, 208, 210, -1, 101, 334, 102, -1, + 101, 333, 334, -1, 101, 103, 333, -1, + 101, 370, 103, -1, 101, 102, 370, -1, + 331, 1078, 1080, -1, 331, 1080, 600, -1, + 110, 369, 111, -1, 104, 107, 205, -1, + 104, 205, 328, -1, 104, 105, 107, -1, + 104, 325, 105, -1, 104, 328, 325, -1, + 106, 205, 107, -1, 106, 108, 205, -1, + 106, 109, 113, -1, 106, 107, 109, -1, + 106, 113, 369, -1, 106, 369, 110, -1, + 106, 111, 108, -1, 106, 110, 111, -1, + 352, 228, 242, -1, 352, 242, 241, -1, + 216, 374, 117, -1, 216, 229, 374, -1, + 216, 117, 215, -1, 213, 242, 229, -1, + 112, 369, 113, -1, 112, 113, 114, -1, + 112, 368, 369, -1, 112, 115, 368, -1, + 112, 114, 115, -1, 375, 374, 229, -1, + 116, 215, 117, -1, 116, 396, 215, -1, + 116, 240, 396, -1, 116, 117, 118, -1, + 116, 118, 240, -1, 119, 355, 218, -1, + 119, 357, 355, -1, 119, 218, 357, -1, + 223, 221, 224, -1, 363, 361, 226, -1, + 363, 358, 362, -1, 540, 366, 367, -1, + 233, 310, 762, -1, 382, 390, 231, -1, + 382, 231, 378, -1, 876, 549, 547, -1, + 876, 547, 1099, -1, 554, 237, 562, -1, + 554, 882, 238, -1, 389, 562, 239, -1, + 557, 381, 1109, -1, 120, 125, 121, -1, + 120, 122, 125, -1, 120, 121, 123, -1, + 120, 123, 122, -1, 128, 124, 573, -1, + 128, 127, 124, -1, 393, 125, 126, -1, + 393, 126, 127, -1, 393, 127, 128, -1, + 393, 128, 573, -1, 393, 583, 125, -1, + 395, 213, 214, -1, 395, 214, 396, -1, + 395, 242, 213, -1, 129, 398, 130, -1, + 129, 399, 398, -1, 129, 130, 583, -1, + 129, 583, 399, -1, 377, 903, 902, -1, + 591, 1192, 403, -1, 591, 199, 484, -1, + 591, 484, 1192, -1, 592, 544, 199, -1, + 592, 199, 591, -1, 131, 133, 132, -1, + 131, 132, 134, -1, 131, 135, 133, -1, + 131, 136, 135, -1, 131, 134, 136, -1, + 805, 245, 595, -1, 805, 244, 245, -1, + 805, 343, 244, -1, 247, 244, 343, -1, + 137, 138, 142, -1, 137, 139, 206, -1, + 137, 206, 138, -1, 137, 1070, 139, -1, + 137, 142, 1070, -1, 140, 141, 1070, -1, + 140, 1070, 142, -1, 140, 142, 141, -1, + 220, 575, 221, -1, 220, 574, 575, -1, + 220, 533, 574, -1, 220, 856, 533, -1, + 143, 144, 145, -1, 143, 146, 144, -1, + 143, 145, 147, -1, 143, 147, 146, -1, + 148, 149, 261, -1, 148, 261, 152, -1, + 148, 150, 149, -1, 148, 152, 150, -1, + 257, 152, 258, -1, 257, 150, 152, -1, + 257, 259, 150, -1, 713, 418, 253, -1, + 713, 614, 617, -1, 713, 926, 614, -1, + 713, 151, 414, -1, 623, 622, 418, -1, + 623, 713, 617, -1, 623, 418, 713, -1, + 620, 458, 183, -1, 620, 183, 303, -1, + 255, 254, 151, -1, 255, 151, 713, -1, + 255, 713, 253, -1, 630, 411, 152, -1, + 630, 152, 261, -1, 464, 173, 153, -1, + 464, 585, 173, -1, 464, 153, 463, -1, + 424, 193, 426, -1, 586, 266, 265, -1, + 586, 585, 266, -1, 154, 639, 643, -1, + 154, 175, 639, -1, 154, 155, 175, -1, + 154, 156, 155, -1, 154, 158, 157, -1, + 154, 157, 156, -1, 154, 159, 158, -1, + 154, 643, 159, -1, 646, 652, 645, -1, + 646, 647, 652, -1, 431, 716, 410, -1, + 428, 269, 981, -1, 428, 442, 269, -1, + 428, 429, 442, -1, 283, 271, 284, -1, + 283, 410, 409, -1, 672, 677, 429, -1, + 296, 269, 442, -1, 160, 661, 273, -1, + 160, 273, 281, -1, 160, 281, 661, -1, + 161, 162, 163, -1, 161, 163, 281, -1, + 161, 281, 162, -1, 282, 281, 286, -1, + 164, 165, 281, -1, 164, 166, 165, -1, + 164, 281, 166, -1, 659, 273, 661, -1, + 167, 272, 632, -1, 167, 168, 272, -1, + 167, 632, 260, -1, 167, 260, 168, -1, + 312, 1139, 1138, -1, 1141, 1282, 338, -1, + 1141, 338, 350, -1, 1281, 338, 1282, -1, + 1281, 1283, 338, -1, 348, 837, 347, -1, + 348, 347, 350, -1, 290, 350, 347, -1, + 290, 1141, 350, -1, 290, 444, 1147, -1, + 290, 1147, 291, -1, 341, 292, 811, -1, + 815, 292, 813, -1, 815, 811, 292, -1, + 955, 956, 813, -1, 955, 813, 292, -1, + 955, 292, 446, -1, 952, 295, 449, -1, + 952, 449, 169, -1, 952, 169, 953, -1, + 727, 295, 482, -1, 727, 482, 1295, -1, + 170, 175, 177, -1, 170, 171, 172, -1, + 170, 177, 171, -1, 170, 172, 173, -1, + 170, 173, 175, -1, 174, 175, 176, -1, + 174, 177, 175, -1, 174, 176, 178, -1, + 174, 178, 177, -1, 705, 179, 298, -1, + 705, 706, 179, -1, 1133, 1134, 725, -1, + 180, 182, 181, -1, 180, 181, 1134, -1, + 180, 483, 182, -1, 180, 1134, 483, -1, + 300, 184, 183, -1, 300, 301, 184, -1, + 300, 183, 458, -1, 185, 187, 186, -1, + 185, 186, 188, -1, 185, 189, 187, -1, + 185, 190, 189, -1, 185, 188, 191, -1, + 185, 191, 190, -1, 416, 303, 192, -1, + 416, 192, 259, -1, 423, 266, 585, -1, + 423, 585, 193, -1, 423, 193, 424, -1, + 194, 195, 198, -1, 194, 198, 197, -1, + 194, 196, 195, -1, 194, 197, 196, -1, + 460, 197, 198, -1, 460, 461, 197, -1, + 460, 198, 459, -1, 754, 477, 740, -1, + 754, 1019, 306, -1, 754, 740, 755, -1, + 476, 477, 305, -1, 476, 1155, 475, -1, + 476, 1154, 1155, -1, 1461, 475, 1155, -1, + 654, 990, 1158, -1, 940, 447, 689, -1, + 1292, 731, 727, -1, 478, 981, 270, -1, + 1341, 483, 1044, -1, 1026, 1027, 1059, -1, + 760, 544, 232, -1, 760, 199, 544, -1, + 760, 232, 761, -1, 760, 484, 199, -1, + 200, 496, 494, -1, 200, 494, 759, -1, + 200, 762, 496, -1, 200, 759, 762, -1, + 561, 562, 237, -1, 561, 237, 309, -1, + 311, 309, 485, -1, 747, 985, 481, -1, + 747, 1167, 985, -1, 499, 749, 770, -1, + 1213, 733, 732, -1, 313, 306, 1019, -1, + 1156, 476, 305, -1, 1156, 1154, 476, -1, + 1156, 202, 317, -1, 201, 305, 306, -1, + 201, 1156, 305, -1, 201, 202, 1156, -1, + 201, 315, 202, -1, 201, 313, 315, -1, + 201, 306, 313, -1, 1024, 1025, 313, -1, + 1024, 313, 1019, -1, 314, 775, 320, -1, + 314, 320, 315, -1, 316, 202, 315, -1, + 316, 315, 320, -1, 316, 317, 202, -1, + 505, 320, 775, -1, 783, 506, 1051, -1, + 777, 778, 696, -1, 1043, 510, 514, -1, + 774, 1043, 514, -1, 710, 203, 708, -1, + 710, 1061, 203, -1, 710, 781, 1061, -1, + 324, 204, 517, -1, 324, 205, 204, -1, + 324, 328, 205, -1, 326, 327, 519, -1, + 518, 519, 327, -1, 330, 598, 520, -1, + 330, 1078, 331, -1, 599, 598, 330, -1, + 534, 206, 872, -1, 534, 520, 206, -1, + 873, 207, 208, -1, 873, 208, 211, -1, + 873, 209, 370, -1, 873, 333, 209, -1, + 873, 211, 333, -1, 873, 872, 207, -1, + 335, 210, 336, -1, 335, 211, 210, -1, + 335, 333, 211, -1, 524, 344, 247, -1, + 524, 343, 525, -1, 524, 247, 343, -1, + 834, 850, 839, -1, 854, 241, 351, -1, + 854, 352, 241, -1, 212, 214, 213, -1, + 212, 213, 229, -1, 212, 215, 214, -1, + 212, 216, 215, -1, 212, 229, 216, -1, + 217, 357, 218, -1, 217, 354, 357, -1, + 217, 218, 355, -1, 217, 355, 354, -1, + 219, 225, 856, -1, 219, 223, 225, -1, + 219, 856, 220, -1, 219, 221, 223, -1, + 219, 220, 221, -1, 359, 224, 356, -1, + 359, 358, 224, -1, 360, 226, 361, -1, + 360, 367, 226, -1, 222, 358, 363, -1, + 222, 225, 223, -1, 222, 226, 225, -1, + 222, 363, 226, -1, 222, 223, 224, -1, + 222, 224, 358, -1, 365, 226, 367, -1, + 857, 856, 225, -1, 857, 225, 226, -1, + 857, 226, 365, -1, 372, 368, 227, -1, + 372, 227, 373, -1, 537, 353, 541, -1, + 537, 538, 353, -1, 376, 353, 538, -1, + 376, 352, 353, -1, 376, 228, 352, -1, + 376, 229, 228, -1, 376, 375, 229, -1, + 901, 377, 902, -1, 546, 232, 544, -1, + 546, 378, 231, -1, 234, 231, 390, -1, + 234, 233, 231, -1, 230, 231, 233, -1, + 230, 233, 762, -1, 230, 762, 761, -1, + 230, 761, 232, -1, 230, 546, 231, -1, + 230, 232, 546, -1, 888, 310, 233, -1, + 888, 233, 234, -1, 888, 390, 560, -1, + 888, 234, 390, -1, 380, 382, 378, -1, + 380, 588, 381, -1, 380, 901, 588, -1, + 384, 385, 882, -1, 384, 388, 239, -1, + 384, 239, 385, -1, 880, 1099, 547, -1, + 867, 385, 239, -1, 867, 239, 562, -1, + 235, 236, 237, -1, 235, 237, 554, -1, + 235, 238, 236, -1, 235, 554, 238, -1, + 387, 239, 388, -1, 387, 389, 239, -1, + 553, 554, 562, -1, 553, 562, 389, -1, + 553, 389, 882, -1, 641, 583, 393, -1, + 641, 393, 638, -1, 565, 240, 566, -1, + 565, 396, 240, -1, 568, 241, 242, -1, + 568, 242, 395, -1, 568, 351, 241, -1, + 568, 570, 351, -1, 243, 263, 580, -1, + 243, 580, 577, -1, 400, 586, 264, -1, + 400, 243, 577, -1, 400, 264, 263, -1, + 400, 263, 243, -1, 1106, 1109, 588, -1, + 401, 922, 403, -1, 401, 739, 593, -1, + 912, 739, 480, -1, 912, 593, 739, -1, + 404, 377, 590, -1, 404, 903, 377, -1, + 543, 544, 592, -1, 543, 590, 377, -1, + 543, 592, 590, -1, 342, 343, 805, -1, + 250, 244, 247, -1, 250, 251, 245, -1, + 250, 245, 244, -1, 246, 247, 344, -1, + 246, 248, 249, -1, 246, 344, 248, -1, + 246, 250, 247, -1, 246, 251, 250, -1, + 246, 249, 252, -1, 246, 252, 251, -1, + 406, 405, 299, -1, 406, 611, 405, -1, + 406, 299, 1134, -1, 619, 458, 620, -1, + 619, 616, 457, -1, 626, 634, 635, -1, + 626, 635, 409, -1, 421, 632, 271, -1, + 421, 409, 635, -1, 421, 271, 283, -1, + 421, 283, 409, -1, 419, 253, 418, -1, + 419, 255, 253, -1, 420, 258, 254, -1, + 420, 417, 258, -1, 420, 254, 255, -1, + 420, 255, 419, -1, 256, 257, 258, -1, + 256, 258, 417, -1, 256, 417, 416, -1, + 256, 259, 257, -1, 256, 416, 259, -1, + 629, 260, 632, -1, 629, 261, 260, -1, + 629, 630, 261, -1, 471, 469, 585, -1, + 471, 585, 464, -1, 471, 464, 470, -1, + 262, 263, 264, -1, 262, 264, 586, -1, + 262, 586, 265, -1, 262, 580, 263, -1, + 262, 265, 580, -1, 425, 265, 266, -1, + 425, 266, 423, -1, 425, 580, 265, -1, + 425, 426, 580, -1, 649, 640, 935, -1, + 649, 650, 640, -1, 649, 935, 267, -1, + 649, 267, 268, -1, 649, 268, 652, -1, + 436, 410, 283, -1, 436, 283, 285, -1, + 436, 431, 410, -1, 434, 269, 296, -1, + 434, 270, 269, -1, 434, 478, 270, -1, + 433, 434, 296, -1, 658, 284, 271, -1, + 658, 271, 272, -1, 658, 272, 273, -1, + 658, 273, 659, -1, 274, 279, 439, -1, + 274, 276, 275, -1, 274, 275, 279, -1, + 274, 440, 277, -1, 274, 439, 440, -1, + 274, 278, 276, -1, 274, 277, 278, -1, + 451, 439, 279, -1, 451, 280, 450, -1, + 451, 279, 280, -1, 662, 661, 281, -1, + 662, 281, 282, -1, 662, 282, 286, -1, + 662, 286, 663, -1, 681, 436, 285, -1, + 438, 283, 284, -1, 438, 285, 283, -1, + 438, 680, 679, -1, 438, 681, 285, -1, + 438, 679, 681, -1, 438, 284, 658, -1, + 441, 669, 453, -1, 441, 453, 296, -1, + 441, 296, 442, -1, 671, 286, 440, -1, + 671, 663, 286, -1, 664, 670, 680, -1, + 664, 663, 671, -1, 664, 671, 670, -1, + 1150, 682, 948, -1, 287, 1139, 312, -1, + 287, 1274, 1139, -1, 287, 1275, 1274, -1, + 287, 732, 1275, -1, 287, 312, 732, -1, + 288, 312, 1138, -1, 288, 1234, 312, -1, + 288, 1351, 1234, -1, 288, 1138, 1227, -1, + 288, 1227, 1351, -1, 1131, 500, 1254, -1, + 289, 443, 444, -1, 289, 530, 443, -1, + 289, 444, 290, -1, 289, 347, 530, -1, + 289, 290, 347, -1, 527, 443, 530, -1, + 527, 1231, 443, -1, 1304, 291, 1147, -1, + 1278, 1282, 1141, -1, 349, 338, 809, -1, + 349, 809, 838, -1, 349, 350, 338, -1, + 1306, 1141, 290, -1, 1306, 290, 291, -1, + 1306, 291, 1304, -1, 340, 446, 292, -1, + 340, 292, 341, -1, 445, 1283, 959, -1, + 339, 337, 294, -1, 339, 445, 446, -1, + 339, 294, 1283, -1, 339, 1283, 445, -1, + 293, 337, 338, -1, 293, 294, 337, -1, + 293, 338, 1283, -1, 293, 1283, 294, -1, + 683, 295, 952, -1, 683, 482, 295, -1, + 684, 727, 731, -1, 684, 295, 727, -1, + 684, 449, 295, -1, 684, 685, 449, -1, + 693, 447, 433, -1, 693, 296, 453, -1, + 693, 433, 296, -1, 686, 669, 667, -1, + 297, 405, 705, -1, 297, 705, 298, -1, + 297, 299, 405, -1, 297, 298, 299, -1, + 606, 705, 405, -1, 1262, 602, 1263, -1, + 1262, 712, 602, -1, 721, 300, 458, -1, + 721, 459, 301, -1, 721, 301, 300, -1, + 474, 461, 718, -1, 474, 463, 461, -1, + 474, 473, 470, -1, 468, 473, 972, -1, + 468, 465, 469, -1, 468, 971, 465, -1, + 468, 972, 971, -1, 468, 470, 473, -1, + 612, 722, 613, -1, 612, 719, 722, -1, + 612, 718, 719, -1, 302, 620, 303, -1, + 302, 303, 416, -1, 302, 622, 620, -1, + 302, 416, 622, -1, 304, 305, 477, -1, + 304, 477, 754, -1, 304, 306, 305, -1, + 304, 754, 306, -1, 307, 455, 979, -1, + 307, 979, 1313, -1, 307, 317, 455, -1, + 307, 1313, 317, -1, 1157, 317, 1313, -1, + 1157, 1156, 317, -1, 980, 1158, 1160, -1, + 980, 654, 1158, -1, 980, 981, 478, -1, + 1001, 739, 738, -1, 1177, 912, 480, -1, + 1177, 1014, 1013, -1, 743, 1014, 1177, -1, + 748, 1013, 746, -1, 752, 1013, 1336, -1, + 752, 746, 1013, -1, 1201, 484, 760, -1, + 1201, 1031, 484, -1, 885, 561, 309, -1, + 885, 310, 888, -1, 308, 311, 496, -1, + 308, 309, 311, -1, 308, 496, 762, -1, + 308, 885, 309, -1, 308, 762, 310, -1, + 308, 310, 885, -1, 1028, 487, 486, -1, + 1028, 485, 487, -1, 767, 311, 485, -1, + 767, 485, 765, -1, 767, 496, 311, -1, + 767, 766, 496, -1, 1169, 1167, 747, -1, + 750, 747, 481, -1, 750, 1223, 770, -1, + 750, 770, 749, -1, 498, 749, 499, -1, + 498, 500, 1131, -1, 771, 897, 1258, -1, + 1235, 732, 312, -1, 1235, 1213, 732, -1, + 1235, 312, 1234, -1, 776, 313, 1025, -1, + 776, 775, 314, -1, 776, 315, 313, -1, + 776, 314, 315, -1, 318, 320, 321, -1, + 318, 316, 320, -1, 318, 455, 317, -1, + 318, 317, 316, -1, 1057, 1059, 1027, -1, + 504, 1047, 501, -1, 322, 318, 321, -1, + 322, 455, 318, -1, 322, 701, 455, -1, + 322, 456, 701, -1, 502, 1049, 699, -1, + 319, 504, 501, -1, 319, 505, 504, -1, + 319, 501, 502, -1, 319, 502, 456, -1, + 319, 321, 320, -1, 319, 320, 505, -1, + 319, 322, 321, -1, 319, 456, 322, -1, + 1065, 506, 783, -1, 508, 1051, 506, -1, + 508, 506, 965, -1, 694, 506, 777, -1, + 694, 965, 506, -1, 512, 513, 1067, -1, + 1066, 514, 510, -1, 1066, 512, 1067, -1, + 323, 1044, 510, -1, 323, 1043, 1044, -1, + 323, 510, 1043, -1, 503, 1057, 1027, -1, + 1209, 1043, 774, -1, 1209, 503, 1027, -1, + 1209, 774, 503, -1, 1072, 328, 324, -1, + 1069, 324, 517, -1, 1069, 1072, 324, -1, + 795, 519, 325, -1, 795, 326, 519, -1, + 795, 327, 326, -1, 795, 325, 328, -1, + 795, 518, 327, -1, 795, 328, 1072, -1, + 329, 520, 1078, -1, 329, 1078, 330, -1, + 329, 330, 520, -1, 601, 599, 330, -1, + 601, 331, 600, -1, 601, 330, 331, -1, + 1074, 532, 1073, -1, 829, 1229, 832, -1, + 829, 1074, 1075, -1, 829, 520, 534, -1, + 332, 334, 333, -1, 332, 333, 335, -1, + 332, 792, 517, -1, 332, 517, 334, -1, + 332, 336, 792, -1, 332, 335, 336, -1, + 808, 338, 337, -1, 808, 809, 338, -1, + 808, 339, 446, -1, 808, 337, 339, -1, + 808, 446, 340, -1, 808, 340, 341, -1, + 808, 341, 811, -1, 803, 342, 805, -1, + 803, 525, 343, -1, 803, 343, 342, -1, + 816, 524, 824, -1, 816, 344, 524, -1, + 816, 814, 345, -1, 816, 346, 344, -1, + 816, 345, 346, -1, 818, 838, 809, -1, + 818, 819, 838, -1, 528, 530, 347, -1, + 528, 347, 837, -1, 528, 837, 839, -1, + 827, 839, 850, -1, 827, 850, 851, -1, + 836, 837, 348, -1, 836, 349, 838, -1, + 836, 348, 350, -1, 836, 350, 349, -1, + 847, 850, 834, -1, 853, 351, 570, -1, + 853, 854, 351, -1, 859, 353, 352, -1, + 859, 352, 854, -1, 859, 541, 353, -1, + 1239, 882, 1238, -1, 1239, 866, 882, -1, + 1239, 1365, 866, -1, 861, 862, 357, -1, + 861, 357, 354, -1, 861, 355, 882, -1, + 861, 354, 355, -1, 864, 356, 357, -1, + 864, 357, 862, -1, 864, 1365, 870, -1, + 864, 359, 356, -1, 864, 870, 359, -1, + 869, 362, 358, -1, 869, 358, 359, -1, + 869, 359, 870, -1, 869, 1087, 362, -1, + 1090, 873, 370, -1, 1090, 367, 360, -1, + 1090, 360, 361, -1, 1090, 362, 1087, -1, + 1090, 363, 362, -1, 1090, 361, 363, -1, + 364, 541, 859, -1, 364, 859, 858, -1, + 364, 858, 857, -1, 364, 857, 365, -1, + 364, 366, 540, -1, 364, 540, 541, -1, + 364, 367, 366, -1, 364, 365, 367, -1, + 539, 372, 538, -1, 539, 540, 367, -1, + 539, 368, 372, -1, 539, 369, 368, -1, + 539, 370, 369, -1, 539, 1090, 370, -1, + 539, 367, 1090, -1, 371, 372, 373, -1, + 371, 538, 372, -1, 371, 373, 374, -1, + 371, 374, 375, -1, 371, 375, 376, -1, + 371, 376, 538, -1, 545, 377, 901, -1, + 545, 543, 377, -1, 545, 378, 546, -1, + 545, 380, 378, -1, 545, 901, 380, -1, + 379, 380, 381, -1, 379, 382, 380, -1, + 379, 381, 557, -1, 379, 557, 558, -1, + 379, 390, 382, -1, 379, 558, 390, -1, + 1102, 549, 876, -1, 1102, 1238, 549, -1, + 1102, 1245, 1238, -1, 383, 882, 388, -1, + 383, 384, 882, -1, 383, 388, 384, -1, + 881, 547, 549, -1, 551, 385, 867, -1, + 551, 882, 385, -1, 386, 387, 388, -1, + 386, 389, 387, -1, 386, 388, 882, -1, + 386, 882, 389, -1, 555, 882, 554, -1, + 555, 553, 882, -1, 564, 557, 1109, -1, + 564, 892, 557, -1, 868, 867, 562, -1, + 391, 560, 390, -1, 391, 390, 558, -1, + 886, 391, 558, -1, 886, 560, 391, -1, + 895, 1110, 587, -1, 895, 889, 1110, -1, + 571, 393, 573, -1, 571, 569, 393, -1, + 392, 638, 393, -1, 392, 393, 569, -1, + 392, 569, 568, -1, 392, 395, 638, -1, + 392, 568, 395, -1, 394, 638, 395, -1, + 394, 565, 638, -1, 394, 395, 396, -1, + 394, 396, 565, -1, 637, 638, 565, -1, + 397, 398, 399, -1, 397, 399, 578, -1, + 397, 579, 398, -1, 397, 578, 579, -1, + 582, 578, 399, -1, 582, 400, 577, -1, + 582, 399, 583, -1, 582, 586, 400, -1, + 582, 584, 586, -1, 1113, 587, 1110, -1, + 1126, 588, 901, -1, 797, 906, 1372, -1, + 797, 535, 906, -1, 908, 905, 874, -1, + 921, 403, 922, -1, 921, 591, 403, -1, + 923, 922, 401, -1, 923, 401, 593, -1, + 923, 593, 914, -1, 923, 914, 924, -1, + 402, 403, 1446, -1, 402, 1446, 1444, -1, + 1337, 738, 739, -1, 1337, 739, 401, -1, + 1337, 736, 738, -1, 1337, 1437, 737, -1, + 1337, 737, 736, -1, 1337, 402, 1444, -1, + 1337, 401, 403, -1, 1337, 403, 402, -1, + 1249, 1248, 875, -1, 1249, 875, 898, -1, + 1129, 903, 916, -1, 918, 590, 919, -1, + 918, 404, 590, -1, 918, 916, 903, -1, + 918, 903, 404, -1, 800, 799, 796, -1, + 800, 796, 841, -1, 695, 696, 778, -1, + 695, 778, 697, -1, 603, 611, 1263, -1, + 603, 1263, 602, -1, 608, 405, 611, -1, + 608, 606, 405, -1, 608, 611, 603, -1, + 1132, 611, 406, -1, 1132, 406, 1134, -1, + 932, 408, 616, -1, 932, 616, 615, -1, + 974, 613, 1385, -1, 974, 1385, 1135, -1, + 407, 1385, 613, -1, 407, 722, 408, -1, + 407, 613, 722, -1, 407, 408, 932, -1, + 407, 932, 931, -1, 407, 931, 1384, -1, + 407, 1384, 1385, -1, 621, 616, 619, -1, + 714, 626, 409, -1, 714, 410, 716, -1, + 714, 409, 410, -1, 631, 634, 412, -1, + 631, 411, 630, -1, 631, 413, 411, -1, + 631, 412, 413, -1, 627, 412, 634, -1, + 627, 414, 413, -1, 627, 413, 412, -1, + 627, 713, 414, -1, 627, 714, 713, -1, + 415, 622, 416, -1, 415, 416, 417, -1, + 415, 418, 622, -1, 415, 419, 418, -1, + 415, 417, 420, -1, 415, 420, 419, -1, + 633, 632, 421, -1, 633, 421, 635, -1, + 422, 423, 424, -1, 422, 425, 423, -1, + 422, 424, 426, -1, 422, 426, 425, -1, + 636, 643, 639, -1, 636, 650, 643, -1, + 644, 645, 427, -1, 644, 427, 643, -1, + 651, 647, 650, -1, 651, 652, 647, -1, + 432, 981, 716, -1, 432, 428, 981, -1, + 432, 429, 428, -1, 432, 672, 429, -1, + 432, 430, 672, -1, 437, 672, 430, -1, + 437, 431, 436, -1, 437, 716, 431, -1, + 437, 432, 716, -1, 437, 430, 432, -1, + 939, 447, 940, -1, 939, 942, 479, -1, + 939, 433, 447, -1, 939, 434, 433, -1, + 939, 479, 478, -1, 939, 478, 434, -1, + 666, 439, 451, -1, 435, 681, 672, -1, + 435, 436, 681, -1, 435, 672, 437, -1, + 435, 437, 436, -1, 660, 680, 438, -1, + 660, 438, 658, -1, 668, 439, 666, -1, + 668, 440, 439, -1, 668, 671, 440, -1, + 674, 669, 441, -1, 674, 675, 669, -1, + 674, 442, 677, -1, 674, 441, 442, -1, + 676, 680, 670, -1, 676, 670, 675, -1, + 1137, 1136, 1266, -1, 1146, 1147, 682, -1, + 1226, 1351, 1227, -1, 1256, 1254, 500, -1, + 1230, 443, 1231, -1, 1230, 948, 444, -1, + 1230, 444, 443, -1, 1230, 1227, 948, -1, + 526, 1231, 527, -1, 950, 944, 1266, -1, + 1280, 1282, 1278, -1, 954, 446, 445, -1, + 954, 445, 959, -1, 954, 955, 446, -1, + 688, 684, 731, -1, 690, 689, 447, -1, + 690, 447, 693, -1, 448, 685, 686, -1, + 448, 450, 449, -1, 448, 449, 685, -1, + 448, 451, 450, -1, 448, 666, 451, -1, + 448, 686, 667, -1, 448, 667, 666, -1, + 452, 686, 692, -1, 452, 693, 453, -1, + 452, 692, 693, -1, 452, 453, 669, -1, + 452, 669, 686, -1, 982, 978, 979, -1, + 982, 701, 967, -1, 982, 697, 981, -1, + 964, 507, 965, -1, 454, 979, 455, -1, + 454, 455, 701, -1, 454, 982, 979, -1, + 454, 701, 982, -1, 702, 699, 703, -1, + 702, 701, 456, -1, 702, 502, 699, -1, + 702, 456, 502, -1, 707, 607, 710, -1, + 707, 606, 607, -1, 707, 705, 606, -1, + 1382, 712, 1262, -1, 723, 457, 722, -1, + 723, 721, 458, -1, 723, 619, 457, -1, + 723, 458, 619, -1, 720, 459, 721, -1, + 720, 460, 459, -1, 720, 718, 461, -1, + 720, 461, 460, -1, 462, 463, 474, -1, + 462, 474, 470, -1, 462, 464, 463, -1, + 462, 470, 464, -1, 724, 466, 465, -1, + 724, 465, 971, -1, 724, 726, 466, -1, + 467, 468, 469, -1, 467, 470, 468, -1, + 467, 469, 471, -1, 467, 471, 470, -1, + 472, 972, 473, -1, 472, 612, 972, -1, + 472, 473, 474, -1, 472, 474, 718, -1, + 472, 718, 612, -1, 977, 1313, 979, -1, + 977, 1314, 1313, -1, 1153, 1461, 1155, -1, + 1153, 1155, 1411, -1, 741, 475, 1461, -1, + 741, 476, 475, -1, 741, 477, 476, -1, + 741, 740, 477, -1, 741, 1006, 740, -1, + 1415, 1323, 1414, -1, 1415, 728, 1323, -1, + 655, 478, 479, -1, 655, 980, 478, -1, + 655, 479, 942, -1, 655, 942, 656, -1, + 655, 654, 980, -1, 1291, 990, 653, -1, + 1291, 689, 730, -1, 1291, 940, 689, -1, + 1291, 653, 940, -1, 996, 997, 992, -1, + 735, 1437, 1188, -1, 1002, 480, 1003, -1, + 1002, 1332, 480, -1, 1400, 1006, 741, -1, + 1017, 480, 1332, -1, 1017, 1177, 480, -1, + 744, 1177, 1013, -1, 744, 498, 1131, -1, + 744, 749, 498, -1, 744, 748, 749, -1, + 744, 1013, 748, -1, 742, 1014, 743, -1, + 986, 992, 997, -1, 986, 987, 992, -1, + 986, 481, 985, -1, 986, 997, 998, -1, + 986, 750, 481, -1, 960, 482, 683, -1, + 960, 1295, 482, -1, 1165, 746, 752, -1, + 492, 491, 483, -1, 492, 483, 1341, -1, + 1018, 1026, 1059, -1, 1056, 776, 1025, -1, + 1023, 1024, 1019, -1, 756, 484, 1454, -1, + 756, 1187, 484, -1, 757, 484, 1031, -1, + 757, 1454, 484, -1, 764, 1028, 766, -1, + 764, 765, 485, -1, 764, 485, 1028, -1, + 1041, 1028, 486, -1, 1041, 486, 487, -1, + 1041, 487, 488, -1, 1041, 490, 489, -1, + 1041, 488, 490, -1, 1041, 489, 491, -1, + 1041, 492, 1341, -1, 1041, 491, 492, -1, + 493, 494, 497, -1, 493, 497, 1183, -1, + 493, 758, 494, -1, 493, 1183, 758, -1, + 495, 496, 766, -1, 495, 766, 1183, -1, + 495, 497, 496, -1, 495, 1183, 497, -1, + 1181, 1026, 1018, -1, 769, 500, 498, -1, + 769, 498, 499, -1, 769, 499, 770, -1, + 769, 772, 771, -1, 1257, 771, 1258, -1, + 1257, 1256, 500, -1, 1257, 500, 769, -1, + 1257, 769, 771, -1, 1219, 733, 1213, -1, + 1219, 1220, 733, -1, 1046, 501, 1047, -1, + 1046, 1049, 502, -1, 1046, 502, 501, -1, + 773, 1047, 1058, -1, 773, 503, 774, -1, + 773, 1058, 1057, -1, 773, 1057, 503, -1, + 1054, 1058, 1047, -1, 1054, 1047, 504, -1, + 1054, 505, 775, -1, 1054, 504, 505, -1, + 779, 777, 506, -1, 779, 506, 1065, -1, + 698, 699, 1049, -1, 698, 1049, 507, -1, + 698, 507, 964, -1, 1050, 965, 507, -1, + 1050, 508, 965, -1, 1050, 507, 1049, -1, + 1050, 1051, 508, -1, 509, 510, 1044, -1, + 509, 1044, 511, -1, 509, 1066, 510, -1, + 509, 512, 1066, -1, 509, 511, 513, -1, + 509, 513, 512, -1, 785, 514, 1066, -1, + 785, 774, 514, -1, 515, 607, 516, -1, + 515, 516, 781, -1, 515, 710, 607, -1, + 515, 781, 710, -1, 789, 516, 607, -1, + 789, 609, 788, -1, 789, 787, 516, -1, + 780, 781, 516, -1, 780, 697, 778, -1, + 780, 787, 697, -1, 780, 516, 787, -1, + 793, 1069, 517, -1, 793, 517, 792, -1, + 793, 1070, 1069, -1, 794, 519, 518, -1, + 794, 1070, 519, -1, 794, 518, 795, -1, + 596, 796, 799, -1, 597, 1080, 796, -1, + 597, 600, 1080, -1, 1082, 1073, 840, -1, + 1247, 1229, 829, -1, 1247, 829, 534, -1, + 1247, 1084, 1229, -1, 1247, 535, 797, -1, + 522, 532, 1074, -1, 522, 1074, 829, -1, + 1077, 1078, 520, -1, 1077, 520, 829, -1, + 521, 830, 532, -1, 521, 829, 830, -1, + 521, 532, 522, -1, 521, 522, 829, -1, + 523, 534, 872, -1, 523, 872, 871, -1, + 523, 871, 534, -1, 804, 803, 805, -1, + 843, 821, 822, -1, 823, 524, 525, -1, + 823, 824, 524, -1, 823, 525, 803, -1, + 823, 803, 822, -1, 810, 818, 809, -1, + 820, 818, 810, -1, 820, 816, 824, -1, + 820, 810, 816, -1, 1228, 529, 825, -1, + 1228, 530, 529, -1, 1228, 526, 527, -1, + 1228, 527, 530, -1, 1228, 832, 1229, -1, + 1228, 1231, 526, -1, 826, 528, 839, -1, + 826, 825, 529, -1, 826, 529, 530, -1, + 826, 530, 528, -1, 531, 827, 851, -1, + 531, 1073, 532, -1, 531, 851, 1073, -1, + 531, 532, 830, -1, 531, 830, 827, -1, + 835, 838, 819, -1, 835, 819, 847, -1, + 845, 847, 819, -1, 845, 843, 846, -1, + 845, 821, 843, -1, 849, 1073, 851, -1, + 849, 840, 1073, -1, 855, 853, 570, -1, + 855, 570, 572, -1, 855, 572, 533, -1, + 855, 533, 856, -1, 865, 864, 862, -1, + 1094, 534, 871, -1, 1094, 1247, 534, -1, + 1094, 535, 1247, -1, 1094, 906, 535, -1, + 1094, 905, 906, -1, 536, 538, 537, -1, + 536, 539, 538, -1, 536, 540, 539, -1, + 536, 541, 540, -1, 536, 537, 541, -1, + 542, 544, 543, -1, 542, 543, 545, -1, + 542, 546, 544, -1, 542, 545, 546, -1, + 879, 880, 547, -1, 879, 547, 881, -1, + 548, 549, 1238, -1, 548, 881, 549, -1, + 548, 1238, 882, -1, 548, 882, 881, -1, + 550, 880, 882, -1, 550, 882, 551, -1, + 550, 1099, 880, -1, 550, 867, 1099, -1, + 550, 551, 867, -1, 552, 554, 553, -1, + 552, 555, 554, -1, 552, 553, 555, -1, + 556, 557, 892, -1, 556, 892, 886, -1, + 556, 558, 557, -1, 556, 886, 558, -1, + 559, 892, 868, -1, 559, 886, 892, -1, + 559, 868, 562, -1, 559, 562, 886, -1, + 887, 888, 560, -1, 887, 560, 886, -1, + 884, 561, 885, -1, 884, 562, 561, -1, + 884, 886, 562, -1, 563, 564, 1109, -1, + 563, 1109, 1108, -1, 563, 892, 564, -1, + 563, 1108, 892, -1, 890, 892, 1108, -1, + 1093, 868, 892, -1, 1093, 1092, 868, -1, + 1093, 894, 1095, -1, 1093, 895, 894, -1, + 936, 637, 565, -1, 936, 566, 937, -1, + 936, 565, 566, -1, 567, 568, 569, -1, + 567, 570, 568, -1, 567, 569, 571, -1, + 567, 572, 570, -1, 567, 571, 573, -1, + 567, 574, 572, -1, 567, 575, 574, -1, + 567, 573, 575, -1, 576, 582, 577, -1, + 576, 578, 582, -1, 576, 579, 578, -1, + 576, 580, 579, -1, 576, 577, 580, -1, + 581, 582, 583, -1, 581, 584, 582, -1, + 581, 639, 585, -1, 581, 585, 586, -1, + 581, 586, 584, -1, 581, 641, 639, -1, + 581, 583, 641, -1, 1112, 895, 587, -1, + 1112, 587, 1113, -1, 1123, 1106, 588, -1, + 1123, 588, 1126, -1, 589, 919, 590, -1, + 589, 921, 919, -1, 589, 591, 921, -1, + 589, 590, 592, -1, 589, 592, 591, -1, + 909, 875, 1248, -1, 1117, 1129, 916, -1, + 1117, 916, 1358, -1, 1255, 914, 593, -1, + 1255, 593, 912, -1, 1255, 912, 910, -1, + 594, 805, 595, -1, 594, 806, 805, -1, + 594, 802, 806, -1, 594, 799, 802, -1, + 594, 596, 799, -1, 594, 796, 596, -1, + 594, 597, 796, -1, 594, 595, 598, -1, + 594, 598, 599, -1, 594, 600, 597, -1, + 594, 601, 600, -1, 594, 599, 601, -1, + 715, 603, 602, -1, 715, 602, 712, -1, + 715, 787, 788, -1, 715, 697, 787, -1, + 715, 716, 981, -1, 715, 981, 697, -1, + 604, 715, 788, -1, 610, 608, 603, -1, + 610, 788, 609, -1, 610, 604, 788, -1, + 610, 603, 715, -1, 610, 715, 604, -1, + 605, 607, 606, -1, 605, 606, 608, -1, + 605, 789, 607, -1, 605, 609, 789, -1, + 605, 610, 609, -1, 605, 608, 610, -1, + 1261, 1263, 611, -1, 1261, 611, 1132, -1, + 929, 932, 615, -1, 929, 615, 926, -1, + 973, 972, 612, -1, 973, 612, 613, -1, + 973, 613, 974, -1, 624, 614, 615, -1, + 624, 615, 616, -1, 624, 616, 621, -1, + 624, 617, 614, -1, 624, 623, 617, -1, + 618, 619, 620, -1, 618, 621, 619, -1, + 618, 620, 622, -1, 618, 622, 623, -1, + 618, 623, 624, -1, 618, 624, 621, -1, + 625, 634, 626, -1, 625, 627, 634, -1, + 625, 626, 714, -1, 625, 714, 627, -1, + 628, 630, 629, -1, 628, 631, 630, -1, + 628, 629, 632, -1, 628, 632, 633, -1, + 628, 634, 631, -1, 628, 635, 634, -1, + 628, 633, 635, -1, 934, 650, 636, -1, + 934, 638, 637, -1, 934, 636, 639, -1, + 934, 640, 650, -1, 934, 639, 641, -1, + 934, 641, 638, -1, 934, 935, 640, -1, + 934, 637, 936, -1, 642, 643, 650, -1, + 642, 644, 643, -1, 642, 645, 644, -1, + 642, 646, 645, -1, 642, 647, 646, -1, + 642, 650, 647, -1, 648, 650, 649, -1, + 648, 651, 650, -1, 648, 649, 652, -1, + 648, 652, 651, -1, 941, 940, 653, -1, + 941, 990, 654, -1, 941, 653, 990, -1, + 941, 655, 656, -1, 941, 654, 655, -1, + 941, 656, 942, -1, 657, 658, 659, -1, + 657, 660, 658, -1, 657, 659, 661, -1, + 657, 661, 662, -1, 657, 662, 663, -1, + 657, 663, 664, -1, 657, 664, 680, -1, + 657, 680, 660, -1, 665, 666, 667, -1, + 665, 668, 666, -1, 665, 667, 669, -1, + 665, 669, 675, -1, 665, 675, 670, -1, + 665, 670, 671, -1, 665, 671, 668, -1, + 678, 677, 672, -1, 678, 672, 681, -1, + 673, 675, 674, -1, 673, 676, 675, -1, + 673, 674, 677, -1, 673, 677, 678, -1, + 673, 679, 680, -1, 673, 680, 676, -1, + 673, 681, 679, -1, 673, 678, 681, -1, + 1394, 1275, 994, -1, 1394, 994, 991, -1, + 945, 1137, 1266, -1, 945, 1138, 1137, -1, + 1145, 682, 1150, -1, 1145, 1146, 682, -1, + 1140, 1288, 961, -1, 1140, 1300, 1288, -1, + 949, 947, 944, -1, 949, 944, 950, -1, + 1327, 950, 1266, -1, 958, 683, 952, -1, + 958, 954, 959, -1, 958, 960, 683, -1, + 691, 685, 684, -1, 691, 684, 688, -1, + 691, 686, 685, -1, 691, 692, 686, -1, + 687, 731, 730, -1, 687, 688, 731, -1, + 687, 730, 689, -1, 687, 689, 690, -1, + 687, 692, 691, -1, 687, 691, 688, -1, + 687, 693, 692, -1, 687, 690, 693, -1, + 966, 965, 694, -1, 966, 696, 695, -1, + 966, 777, 696, -1, 966, 694, 777, -1, + 966, 695, 697, -1, 966, 982, 967, -1, + 966, 697, 982, -1, 968, 698, 964, -1, + 968, 703, 699, -1, 968, 699, 698, -1, + 700, 967, 701, -1, 700, 701, 702, -1, + 700, 702, 703, -1, 700, 968, 967, -1, + 700, 703, 968, -1, 704, 706, 705, -1, + 704, 705, 707, -1, 704, 708, 709, -1, + 704, 709, 706, -1, 704, 710, 708, -1, + 704, 707, 710, -1, 711, 712, 1382, -1, + 711, 930, 928, -1, 711, 1383, 930, -1, + 711, 1382, 1383, -1, 711, 928, 926, -1, + 711, 926, 713, -1, 711, 713, 714, -1, + 711, 715, 712, -1, 711, 714, 716, -1, + 711, 716, 715, -1, 717, 719, 718, -1, + 717, 718, 720, -1, 717, 720, 721, -1, + 717, 722, 719, -1, 717, 723, 722, -1, + 717, 721, 723, -1, 970, 724, 971, -1, + 970, 1135, 1133, -1, 970, 1133, 725, -1, + 970, 725, 726, -1, 970, 726, 724, -1, + 976, 1314, 977, -1, 976, 729, 1314, -1, + 976, 728, 729, -1, 976, 982, 728, -1, + 1472, 728, 982, -1, 1472, 1407, 1406, -1, + 1472, 1323, 728, -1, 1296, 727, 1295, -1, + 1296, 1292, 727, -1, 1315, 729, 728, -1, + 1315, 728, 1415, -1, 1315, 1314, 729, -1, + 1315, 1415, 1416, -1, 1315, 1416, 1311, -1, + 1289, 1291, 730, -1, 1289, 731, 1292, -1, + 1289, 730, 731, -1, 995, 1275, 732, -1, + 995, 732, 733, -1, 995, 733, 1220, -1, + 995, 986, 998, -1, 1008, 735, 1188, -1, + 1008, 1001, 735, -1, 734, 735, 1001, -1, + 734, 736, 737, -1, 734, 737, 1437, -1, + 734, 1437, 735, -1, 734, 738, 736, -1, + 734, 1001, 738, -1, 1000, 1003, 739, -1, + 1000, 739, 1001, -1, 1004, 1001, 1008, -1, + 1004, 1008, 1009, -1, 1175, 1004, 1009, -1, + 1010, 755, 740, -1, 1010, 740, 1006, -1, + 1010, 1189, 755, -1, 1399, 741, 1461, -1, + 1399, 1400, 741, -1, 1015, 742, 743, -1, + 1015, 1014, 742, -1, 1176, 743, 1177, -1, + 1176, 1015, 743, -1, 911, 1177, 744, -1, + 911, 912, 1177, -1, 911, 744, 1131, -1, + 745, 1223, 750, -1, 745, 750, 986, -1, + 745, 1220, 1223, -1, 745, 995, 1220, -1, + 745, 986, 995, -1, 962, 1295, 960, -1, + 962, 1294, 1295, -1, 962, 961, 1288, -1, + 962, 1288, 1294, -1, 983, 746, 1165, -1, + 983, 1169, 747, -1, 983, 748, 746, -1, + 983, 749, 748, -1, 983, 750, 749, -1, + 983, 747, 750, -1, 751, 752, 1336, -1, + 751, 1336, 1165, -1, 751, 1165, 752, -1, + 1038, 1018, 753, -1, 1184, 758, 1183, -1, + 1184, 1038, 1040, -1, 1184, 1035, 758, -1, + 1184, 1040, 1035, -1, 1055, 753, 1018, -1, + 1055, 1056, 753, -1, 1055, 1018, 1059, -1, + 1037, 1056, 1025, -1, 1037, 753, 1056, -1, + 1037, 1038, 753, -1, 1020, 1019, 754, -1, + 1020, 754, 755, -1, 1020, 755, 1189, -1, + 1020, 1189, 1338, -1, 1182, 766, 1028, -1, + 1182, 1029, 1181, -1, 1182, 1183, 766, -1, + 1449, 1186, 1187, -1, 1449, 1187, 756, -1, + 1449, 756, 1454, -1, 1030, 1454, 757, -1, + 1030, 757, 1031, -1, 1034, 758, 1035, -1, + 1034, 759, 758, -1, 1034, 1033, 759, -1, + 1200, 1033, 1035, -1, 1200, 759, 1033, -1, + 1200, 760, 761, -1, 1200, 1201, 760, -1, + 1200, 761, 762, -1, 1200, 762, 759, -1, + 1039, 1035, 1040, -1, 1039, 1203, 1035, -1, + 1039, 1197, 1203, -1, 763, 765, 764, -1, + 763, 764, 766, -1, 763, 767, 765, -1, + 763, 766, 767, -1, 768, 769, 770, -1, + 768, 772, 769, -1, 768, 1222, 772, -1, + 768, 770, 1223, -1, 768, 1223, 1222, -1, + 899, 772, 1216, -1, 899, 897, 771, -1, + 899, 771, 772, -1, 1215, 772, 1222, -1, + 1215, 1216, 772, -1, 1217, 1249, 900, -1, + 1217, 900, 899, -1, 1217, 899, 1216, -1, + 1214, 1348, 1347, -1, 1048, 782, 1051, -1, + 1048, 1047, 773, -1, 784, 773, 774, -1, + 784, 774, 785, -1, 784, 782, 1048, -1, + 784, 1048, 773, -1, 1053, 1054, 775, -1, + 1053, 775, 776, -1, 1053, 776, 1056, -1, + 1062, 778, 777, -1, 1062, 777, 779, -1, + 1062, 780, 778, -1, 1062, 781, 780, -1, + 1062, 1061, 781, -1, 1062, 779, 1065, -1, + 1064, 1051, 782, -1, 1064, 783, 1051, -1, + 1064, 782, 784, -1, 1064, 784, 785, -1, + 1064, 785, 1066, -1, 1064, 1065, 783, -1, + 786, 788, 787, -1, 786, 789, 788, -1, + 786, 787, 789, -1, 790, 792, 791, -1, + 790, 793, 792, -1, 790, 791, 1070, -1, + 790, 1070, 793, -1, 1071, 1070, 794, -1, + 1071, 795, 1072, -1, 1071, 794, 795, -1, + 1079, 1077, 1075, -1, 1081, 840, 841, -1, + 1081, 1082, 840, -1, 1081, 796, 1080, -1, + 1081, 841, 796, -1, 1375, 797, 1372, -1, + 1375, 1247, 797, -1, 798, 829, 1075, -1, + 798, 1075, 1077, -1, 798, 1077, 829, -1, + 842, 843, 802, -1, 842, 802, 799, -1, + 842, 799, 800, -1, 842, 800, 841, -1, + 801, 843, 822, -1, 801, 802, 843, -1, + 801, 822, 803, -1, 801, 803, 804, -1, + 801, 804, 805, -1, 801, 805, 806, -1, + 801, 806, 802, -1, 807, 809, 808, -1, + 807, 810, 809, -1, 807, 808, 811, -1, + 807, 813, 812, -1, 807, 812, 814, -1, + 807, 815, 813, -1, 807, 811, 815, -1, + 807, 814, 816, -1, 807, 816, 810, -1, + 817, 819, 818, -1, 817, 818, 820, -1, + 817, 845, 819, -1, 817, 821, 845, -1, + 817, 822, 821, -1, 817, 823, 822, -1, + 817, 824, 823, -1, 817, 820, 824, -1, + 831, 1228, 825, -1, 831, 825, 826, -1, + 831, 827, 830, -1, 831, 839, 827, -1, + 831, 826, 839, -1, 828, 830, 829, -1, + 828, 831, 830, -1, 828, 1228, 831, -1, + 828, 829, 832, -1, 828, 832, 1228, -1, + 833, 847, 834, -1, 833, 835, 847, -1, + 833, 837, 836, -1, 833, 836, 838, -1, + 833, 838, 835, -1, 833, 839, 837, -1, + 833, 834, 839, -1, 848, 841, 840, -1, + 848, 840, 849, -1, 848, 842, 841, -1, + 848, 846, 843, -1, 848, 843, 842, -1, + 844, 845, 846, -1, 844, 847, 845, -1, + 844, 846, 848, -1, 844, 848, 849, -1, + 844, 850, 847, -1, 844, 851, 850, -1, + 844, 849, 851, -1, 852, 854, 853, -1, + 852, 853, 855, -1, 852, 855, 856, -1, + 852, 856, 857, -1, 852, 857, 858, -1, + 852, 858, 859, -1, 852, 859, 854, -1, + 860, 862, 861, -1, 860, 865, 862, -1, + 860, 861, 882, -1, 860, 882, 865, -1, + 863, 1365, 864, -1, 863, 864, 865, -1, + 863, 866, 1365, -1, 863, 882, 866, -1, + 863, 865, 882, -1, 1097, 1092, 1096, -1, + 1097, 1099, 867, -1, 1097, 868, 1092, -1, + 1097, 867, 868, -1, 1240, 1103, 1096, -1, + 1088, 1363, 1241, -1, 1088, 1087, 869, -1, + 1088, 869, 870, -1, 1364, 1365, 1239, -1, + 1362, 870, 1365, -1, 1362, 1088, 870, -1, + 1362, 1363, 1088, -1, 1091, 1094, 871, -1, + 1091, 871, 872, -1, 1091, 1095, 1094, -1, + 1091, 872, 873, -1, 1091, 873, 1090, -1, + 1378, 874, 905, -1, 1378, 905, 1094, -1, + 1378, 908, 874, -1, 1378, 875, 909, -1, + 1378, 898, 875, -1, 1378, 1259, 1260, -1, + 877, 876, 1099, -1, 877, 1099, 1100, -1, + 1101, 1102, 876, -1, 1101, 876, 877, -1, + 1101, 877, 1100, -1, 878, 880, 879, -1, + 878, 879, 881, -1, 878, 882, 880, -1, + 878, 881, 882, -1, 883, 884, 885, -1, + 883, 886, 884, -1, 883, 887, 886, -1, + 883, 885, 888, -1, 883, 888, 887, -1, + 893, 892, 890, -1, 893, 889, 895, -1, + 1107, 1110, 889, -1, 1107, 890, 1108, -1, + 1107, 889, 893, -1, 1107, 893, 890, -1, + 891, 1093, 892, -1, 891, 895, 1093, -1, + 891, 892, 893, -1, 891, 893, 895, -1, + 1115, 1119, 1120, -1, 1356, 894, 895, -1, + 1356, 895, 1112, -1, 1356, 1095, 894, -1, + 896, 1258, 897, -1, 896, 1260, 1258, -1, + 896, 898, 1378, -1, 896, 1378, 1260, -1, + 896, 897, 899, -1, 896, 899, 900, -1, + 896, 900, 1249, -1, 896, 1249, 898, -1, + 1127, 901, 902, -1, 1127, 1126, 901, -1, + 1127, 902, 903, -1, 1127, 903, 1129, -1, + 904, 1371, 1372, -1, 904, 908, 1371, -1, + 904, 905, 908, -1, 904, 1372, 906, -1, + 904, 906, 905, -1, 907, 1371, 908, -1, + 907, 908, 1378, -1, 907, 1378, 909, -1, + 907, 1248, 1371, -1, 907, 909, 1248, -1, + 1116, 1128, 1129, -1, 1116, 1129, 1117, -1, + 1116, 1121, 1128, -1, 913, 924, 914, -1, + 1130, 1255, 910, -1, 1130, 911, 1131, -1, + 1130, 910, 912, -1, 1130, 912, 911, -1, + 1357, 1358, 916, -1, 1357, 924, 913, -1, + 1357, 914, 1255, -1, 1357, 913, 914, -1, + 915, 916, 918, -1, 915, 918, 920, -1, + 915, 1357, 916, -1, 915, 920, 1357, -1, + 917, 918, 919, -1, 917, 920, 918, -1, + 917, 921, 922, -1, 917, 919, 921, -1, + 917, 923, 924, -1, 917, 922, 923, -1, + 917, 924, 1357, -1, 917, 1357, 920, -1, + 1386, 1135, 1385, -1, 925, 929, 926, -1, + 925, 926, 928, -1, 925, 928, 929, -1, + 927, 929, 928, -1, 927, 930, 1383, -1, + 927, 928, 930, -1, 927, 1384, 931, -1, + 927, 1383, 1384, -1, 927, 931, 932, -1, + 927, 932, 929, -1, 933, 935, 934, -1, + 933, 934, 936, -1, 933, 937, 935, -1, + 933, 936, 937, -1, 938, 939, 940, -1, + 938, 940, 941, -1, 938, 942, 939, -1, + 938, 941, 942, -1, 1272, 1268, 1139, -1, + 1272, 1273, 1268, -1, 943, 1266, 944, -1, + 943, 945, 1266, -1, 943, 944, 947, -1, + 943, 947, 948, -1, 943, 948, 1227, -1, + 943, 1227, 1138, -1, 943, 1138, 945, -1, + 1279, 1140, 961, -1, 1279, 959, 1283, -1, + 1152, 1145, 1150, -1, 1297, 1145, 1152, -1, + 1297, 1152, 1287, -1, 1297, 1287, 1300, -1, + 946, 949, 1150, -1, 946, 947, 949, -1, + 946, 1150, 948, -1, 946, 948, 947, -1, + 1149, 949, 950, -1, 1149, 950, 1327, -1, + 1149, 1327, 1326, -1, 1149, 1326, 1151, -1, + 1149, 1150, 949, -1, 951, 958, 952, -1, + 951, 952, 953, -1, 951, 955, 954, -1, + 951, 954, 958, -1, 951, 953, 956, -1, + 951, 956, 955, -1, 957, 958, 959, -1, + 957, 960, 958, -1, 957, 959, 1279, -1, + 957, 1279, 961, -1, 957, 961, 962, -1, + 957, 962, 960, -1, 963, 964, 965, -1, + 963, 965, 966, -1, 963, 966, 967, -1, + 963, 967, 968, -1, 963, 968, 964, -1, + 969, 970, 971, -1, 969, 1135, 970, -1, + 969, 971, 972, -1, 969, 972, 973, -1, + 969, 973, 974, -1, 969, 974, 1135, -1, + 975, 976, 977, -1, 975, 979, 978, -1, + 975, 977, 979, -1, 975, 978, 982, -1, + 975, 982, 976, -1, 1310, 1416, 1411, -1, + 1310, 1311, 1416, -1, 1310, 1411, 1155, -1, + 1317, 980, 1160, -1, 1317, 981, 980, -1, + 1317, 982, 981, -1, 1317, 1472, 982, -1, + 1161, 1418, 1162, -1, 1161, 1164, 1418, -1, + 1161, 1392, 1164, -1, 1477, 1501, 1503, -1, + 1425, 1158, 990, -1, 1425, 990, 1424, -1, + 1171, 1169, 983, -1, 1171, 983, 1165, -1, + 989, 1308, 1457, -1, 989, 984, 1308, -1, + 989, 1458, 992, -1, 989, 1457, 1458, -1, + 989, 992, 988, -1, 1502, 1457, 1308, -1, + 1335, 1403, 1308, -1, 1335, 1308, 984, -1, + 1335, 984, 1334, -1, 1166, 1334, 984, -1, + 1166, 985, 1167, -1, 1166, 986, 985, -1, + 1166, 987, 986, -1, 1166, 992, 987, -1, + 1166, 988, 992, -1, 1166, 989, 988, -1, + 1166, 984, 989, -1, 1290, 990, 1291, -1, + 1290, 1424, 990, -1, 1389, 1394, 991, -1, + 1389, 996, 992, -1, 1389, 991, 994, -1, + 1389, 994, 996, -1, 1389, 992, 1458, -1, + 993, 994, 1275, -1, 993, 1275, 995, -1, + 993, 996, 994, -1, 993, 997, 996, -1, + 993, 998, 997, -1, 993, 995, 998, -1, + 1005, 1332, 1002, -1, 999, 1000, 1001, -1, + 999, 1001, 1004, -1, 999, 1002, 1003, -1, + 999, 1003, 1000, -1, 999, 1005, 1002, -1, + 999, 1004, 1005, -1, 1174, 1004, 1175, -1, + 1174, 1494, 1173, -1, 1174, 1175, 1494, -1, + 1174, 1332, 1005, -1, 1174, 1005, 1004, -1, + 1011, 1175, 1009, -1, 1011, 1006, 1400, -1, + 1011, 1010, 1006, -1, 1007, 1009, 1008, -1, + 1007, 1011, 1009, -1, 1007, 1010, 1011, -1, + 1007, 1008, 1188, -1, 1007, 1188, 1189, -1, + 1007, 1189, 1010, -1, 1307, 1011, 1400, -1, + 1307, 1175, 1011, -1, 1492, 1173, 1494, -1, + 1492, 1176, 1173, -1, 1492, 1015, 1176, -1, + 1492, 1016, 1015, -1, 1492, 1336, 1016, -1, + 1012, 1013, 1014, -1, 1012, 1014, 1015, -1, + 1012, 1015, 1016, -1, 1012, 1336, 1013, -1, + 1012, 1016, 1336, -1, 1331, 1017, 1332, -1, + 1331, 1177, 1017, -1, 1180, 1018, 1038, -1, + 1180, 1038, 1184, -1, 1180, 1181, 1018, -1, + 1021, 1023, 1019, -1, 1021, 1019, 1020, -1, + 1021, 1020, 1338, -1, 1021, 1338, 1451, -1, + 1195, 1197, 1039, -1, 1452, 1185, 1023, -1, + 1452, 1023, 1021, -1, 1452, 1021, 1451, -1, + 1022, 1023, 1185, -1, 1022, 1025, 1024, -1, + 1022, 1024, 1023, -1, 1022, 1037, 1025, -1, + 1022, 1185, 1037, -1, 1208, 1029, 1207, -1, + 1208, 1026, 1181, -1, 1208, 1181, 1029, -1, + 1208, 1027, 1026, -1, 1208, 1209, 1027, -1, + 1042, 1182, 1028, -1, 1042, 1029, 1182, -1, + 1042, 1207, 1029, -1, 1042, 1028, 1041, -1, + 1191, 1446, 1192, -1, 1191, 1445, 1446, -1, + 1194, 1454, 1030, -1, 1194, 1030, 1031, -1, + 1194, 1031, 1201, -1, 1194, 1201, 1197, -1, + 1032, 1035, 1033, -1, 1032, 1034, 1035, -1, + 1032, 1033, 1034, -1, 1199, 1035, 1203, -1, + 1199, 1200, 1035, -1, 1036, 1037, 1185, -1, + 1036, 1038, 1037, -1, 1036, 1185, 1195, -1, + 1036, 1195, 1039, -1, 1036, 1040, 1038, -1, + 1036, 1039, 1040, -1, 1340, 1041, 1341, -1, + 1340, 1042, 1041, -1, 1340, 1207, 1042, -1, + 1206, 1044, 1043, -1, 1206, 1341, 1044, -1, + 1206, 1043, 1209, -1, 1233, 1213, 1235, -1, + 1232, 1211, 1233, -1, 1212, 1348, 1214, -1, + 1212, 1214, 1219, -1, 1221, 1215, 1222, -1, + 1221, 1219, 1214, -1, 1045, 1046, 1047, -1, + 1045, 1047, 1048, -1, 1045, 1049, 1046, -1, + 1045, 1050, 1049, -1, 1045, 1051, 1050, -1, + 1045, 1048, 1051, -1, 1052, 1054, 1053, -1, + 1052, 1056, 1055, -1, 1052, 1053, 1056, -1, + 1052, 1057, 1058, -1, 1052, 1058, 1054, -1, + 1052, 1059, 1057, -1, 1052, 1055, 1059, -1, + 1060, 1067, 1061, -1, 1060, 1061, 1062, -1, + 1060, 1065, 1067, -1, 1060, 1062, 1065, -1, + 1063, 1065, 1064, -1, 1063, 1064, 1066, -1, + 1063, 1067, 1065, -1, 1063, 1066, 1067, -1, + 1068, 1069, 1070, -1, 1068, 1070, 1071, -1, + 1068, 1072, 1069, -1, 1068, 1071, 1072, -1, + 1083, 1073, 1082, -1, 1083, 1074, 1073, -1, + 1083, 1075, 1074, -1, 1083, 1079, 1075, -1, + 1076, 1078, 1077, -1, 1076, 1077, 1079, -1, + 1076, 1080, 1078, -1, 1076, 1081, 1080, -1, + 1076, 1082, 1081, -1, 1076, 1083, 1082, -1, + 1076, 1079, 1083, -1, 1352, 1211, 1232, -1, + 1352, 1084, 1247, -1, 1352, 1229, 1084, -1, + 1085, 1348, 1212, -1, 1085, 1212, 1211, -1, + 1085, 1211, 1352, -1, 1085, 1352, 1225, -1, + 1345, 1348, 1085, -1, 1345, 1085, 1225, -1, + 1345, 1225, 1247, -1, 1086, 1096, 1090, -1, + 1086, 1240, 1096, -1, 1086, 1090, 1087, -1, + 1086, 1241, 1240, -1, 1086, 1087, 1088, -1, + 1086, 1088, 1241, -1, 1089, 1090, 1096, -1, + 1089, 1091, 1090, -1, 1089, 1096, 1092, -1, + 1089, 1092, 1093, -1, 1089, 1093, 1095, -1, + 1089, 1095, 1091, -1, 1237, 1378, 1094, -1, + 1237, 1094, 1095, -1, 1237, 1095, 1356, -1, + 1104, 1096, 1103, -1, 1104, 1099, 1097, -1, + 1104, 1097, 1096, -1, 1098, 1100, 1099, -1, + 1098, 1243, 1100, -1, 1098, 1099, 1104, -1, + 1098, 1104, 1243, -1, 1242, 1100, 1243, -1, + 1242, 1101, 1100, -1, 1242, 1245, 1102, -1, + 1242, 1102, 1101, -1, 1244, 1103, 1240, -1, + 1244, 1104, 1103, -1, 1244, 1243, 1104, -1, + 1111, 1110, 1107, -1, 1111, 1124, 1125, -1, + 1111, 1125, 1119, -1, 1105, 1123, 1124, -1, + 1105, 1106, 1123, -1, 1105, 1124, 1111, -1, + 1105, 1111, 1107, -1, 1105, 1107, 1108, -1, + 1105, 1109, 1106, -1, 1105, 1108, 1109, -1, + 1114, 1113, 1110, -1, 1114, 1119, 1115, -1, + 1114, 1110, 1111, -1, 1114, 1111, 1119, -1, + 1355, 1112, 1113, -1, 1355, 1356, 1112, -1, + 1355, 1113, 1114, -1, 1355, 1114, 1115, -1, + 1355, 1115, 1120, -1, 1355, 1121, 1116, -1, + 1355, 1117, 1358, -1, 1355, 1116, 1117, -1, + 1118, 1120, 1119, -1, 1118, 1119, 1125, -1, + 1118, 1125, 1128, -1, 1118, 1128, 1121, -1, + 1118, 1355, 1120, -1, 1118, 1121, 1355, -1, + 1122, 1124, 1123, -1, 1122, 1125, 1124, -1, + 1122, 1123, 1126, -1, 1122, 1126, 1127, -1, + 1122, 1128, 1125, -1, 1122, 1129, 1128, -1, + 1122, 1127, 1129, -1, 1374, 1247, 1375, -1, + 1253, 1255, 1130, -1, 1253, 1131, 1254, -1, + 1253, 1130, 1131, -1, 1387, 1261, 1132, -1, + 1387, 1134, 1133, -1, 1387, 1132, 1134, -1, + 1387, 1133, 1135, -1, 1387, 1135, 1386, -1, + 1265, 1266, 1136, -1, 1265, 1136, 1137, -1, + 1265, 1137, 1138, -1, 1265, 1138, 1270, -1, + 1269, 1273, 1270, -1, 1269, 1138, 1268, -1, + 1269, 1270, 1138, -1, 1397, 1139, 1274, -1, + 1396, 1272, 1139, -1, 1396, 1139, 1397, -1, + 1142, 1306, 1305, -1, 1142, 1305, 1301, -1, + 1142, 1141, 1306, -1, 1277, 1140, 1279, -1, + 1277, 1300, 1140, -1, 1277, 1299, 1300, -1, + 1277, 1278, 1141, -1, 1277, 1141, 1142, -1, + 1277, 1301, 1299, -1, 1277, 1142, 1301, -1, + 1417, 1485, 1285, -1, 1293, 1285, 1485, -1, + 1143, 1285, 1286, -1, 1143, 1286, 1151, -1, + 1143, 1417, 1285, -1, 1143, 1418, 1417, -1, + 1143, 1162, 1418, -1, 1143, 1326, 1162, -1, + 1143, 1151, 1326, -1, 1144, 1146, 1145, -1, + 1144, 1145, 1297, -1, 1144, 1147, 1146, -1, + 1144, 1297, 1147, -1, 1303, 1304, 1147, -1, + 1303, 1147, 1297, -1, 1148, 1150, 1149, -1, + 1148, 1149, 1151, -1, 1148, 1151, 1286, -1, + 1148, 1286, 1287, -1, 1148, 1152, 1150, -1, + 1148, 1287, 1152, -1, 1460, 1153, 1411, -1, + 1460, 1461, 1153, -1, 1402, 1503, 1502, -1, + 1312, 1155, 1154, -1, 1312, 1310, 1155, -1, + 1312, 1154, 1156, -1, 1312, 1156, 1157, -1, + 1312, 1157, 1313, -1, 1319, 1407, 1472, -1, + 1319, 1472, 1317, -1, 1431, 1160, 1158, -1, + 1431, 1158, 1425, -1, 1159, 1317, 1160, -1, + 1159, 1430, 1317, -1, 1159, 1160, 1431, -1, + 1159, 1431, 1430, -1, 1321, 1320, 1317, -1, + 1321, 1317, 1430, -1, 1413, 1414, 1323, -1, + 1470, 1323, 1472, -1, 1470, 1482, 1413, -1, + 1423, 1424, 1420, -1, 1419, 1418, 1164, -1, + 1419, 1164, 1432, -1, 1325, 1161, 1162, -1, + 1325, 1162, 1326, -1, 1325, 1391, 1392, -1, + 1325, 1392, 1161, -1, 1325, 1390, 1391, -1, + 1514, 1501, 1477, -1, 1163, 1164, 1392, -1, + 1163, 1515, 1164, -1, 1163, 1514, 1515, -1, + 1163, 1392, 1501, -1, 1163, 1501, 1514, -1, + 1474, 1432, 1164, -1, 1474, 1164, 1515, -1, + 1168, 1169, 1171, -1, 1172, 1165, 1336, -1, + 1172, 1171, 1165, -1, 1170, 1334, 1166, -1, + 1170, 1166, 1167, -1, 1170, 1168, 1171, -1, + 1170, 1167, 1169, -1, 1170, 1169, 1168, -1, + 1436, 1334, 1170, -1, 1436, 1170, 1171, -1, + 1436, 1171, 1172, -1, 1436, 1172, 1336, -1, + 1178, 1173, 1176, -1, 1178, 1174, 1173, -1, + 1178, 1332, 1174, -1, 1497, 1494, 1175, -1, + 1497, 1175, 1307, -1, 1333, 1176, 1177, -1, + 1333, 1177, 1331, -1, 1333, 1178, 1176, -1, + 1333, 1332, 1178, -1, 1179, 1181, 1180, -1, + 1179, 1183, 1182, -1, 1179, 1182, 1181, -1, + 1179, 1184, 1183, -1, 1179, 1180, 1184, -1, + 1453, 1185, 1452, -1, 1453, 1195, 1185, -1, + 1190, 1186, 1449, -1, 1190, 1187, 1186, -1, + 1190, 1192, 1187, -1, 1439, 1188, 1437, -1, + 1439, 1189, 1188, -1, 1439, 1338, 1189, -1, + 1441, 1445, 1191, -1, 1448, 1439, 1440, -1, + 1448, 1190, 1449, -1, 1448, 1441, 1191, -1, + 1448, 1440, 1441, -1, 1448, 1191, 1192, -1, + 1448, 1192, 1190, -1, 1193, 1194, 1197, -1, + 1193, 1454, 1194, -1, 1193, 1197, 1195, -1, + 1193, 1453, 1454, -1, 1193, 1195, 1453, -1, + 1196, 1197, 1201, -1, 1196, 1201, 1202, -1, + 1196, 1203, 1197, -1, 1196, 1202, 1203, -1, + 1198, 1200, 1199, -1, 1198, 1201, 1200, -1, + 1198, 1202, 1201, -1, 1198, 1199, 1203, -1, + 1198, 1203, 1202, -1, 1342, 1341, 1207, -1, + 1342, 1207, 1340, -1, 1204, 1207, 1341, -1, + 1204, 1341, 1206, -1, 1204, 1206, 1207, -1, + 1205, 1207, 1206, -1, 1205, 1208, 1207, -1, + 1205, 1206, 1209, -1, 1205, 1209, 1208, -1, + 1251, 1249, 1217, -1, 1344, 1366, 1250, -1, + 1344, 1251, 1217, -1, 1344, 1250, 1251, -1, + 1210, 1233, 1211, -1, 1210, 1211, 1212, -1, + 1210, 1213, 1233, -1, 1210, 1219, 1213, -1, + 1210, 1212, 1219, -1, 1346, 1214, 1347, -1, + 1346, 1221, 1214, -1, 1346, 1216, 1215, -1, + 1346, 1215, 1221, -1, 1346, 1217, 1216, -1, + 1346, 1344, 1217, -1, 1218, 1220, 1219, -1, + 1218, 1219, 1221, -1, 1218, 1221, 1222, -1, + 1218, 1222, 1223, -1, 1218, 1223, 1220, -1, + 1224, 1247, 1225, -1, 1224, 1352, 1247, -1, + 1224, 1225, 1352, -1, 1353, 1351, 1226, -1, + 1353, 1226, 1227, -1, 1353, 1228, 1229, -1, + 1353, 1229, 1352, -1, 1353, 1227, 1230, -1, + 1353, 1230, 1231, -1, 1353, 1231, 1228, -1, + 1350, 1352, 1232, -1, 1350, 1232, 1233, -1, + 1350, 1234, 1351, -1, 1350, 1235, 1234, -1, + 1350, 1233, 1235, -1, 1236, 1367, 1366, -1, + 1236, 1366, 1345, -1, 1236, 1247, 1367, -1, + 1236, 1345, 1247, -1, 1377, 1378, 1237, -1, + 1377, 1237, 1356, -1, 1377, 1357, 1255, -1, + 1246, 1238, 1245, -1, 1246, 1239, 1238, -1, + 1246, 1364, 1239, -1, 1361, 1244, 1240, -1, + 1361, 1241, 1363, -1, 1361, 1240, 1241, -1, + 1360, 1242, 1243, -1, 1360, 1243, 1244, -1, + 1360, 1245, 1242, -1, 1360, 1246, 1245, -1, + 1360, 1364, 1246, -1, 1360, 1244, 1361, -1, + 1368, 1367, 1247, -1, 1368, 1247, 1374, -1, + 1252, 1371, 1248, -1, 1252, 1248, 1249, -1, + 1252, 1249, 1251, -1, 1370, 1250, 1366, -1, + 1370, 1251, 1250, -1, 1370, 1252, 1251, -1, + 1370, 1371, 1252, -1, 1379, 1253, 1254, -1, + 1379, 1255, 1253, -1, 1379, 1254, 1256, -1, + 1379, 1256, 1257, -1, 1379, 1377, 1255, -1, + 1379, 1257, 1258, -1, 1379, 1259, 1378, -1, + 1379, 1258, 1260, -1, 1379, 1260, 1259, -1, + 1381, 1261, 1387, -1, 1381, 1262, 1263, -1, + 1381, 1263, 1261, -1, 1381, 1382, 1262, -1, + 1264, 1266, 1265, -1, 1264, 1265, 1270, -1, + 1264, 1327, 1266, -1, 1264, 1328, 1327, -1, + 1264, 1270, 1328, -1, 1456, 1390, 1388, -1, + 1267, 1268, 1273, -1, 1267, 1269, 1268, -1, + 1267, 1273, 1269, -1, 1329, 1388, 1390, -1, + 1329, 1270, 1273, -1, 1329, 1328, 1270, -1, + 1329, 1396, 1388, -1, 1271, 1273, 1272, -1, + 1271, 1272, 1396, -1, 1271, 1329, 1273, -1, + 1271, 1396, 1329, -1, 1398, 1397, 1274, -1, + 1398, 1274, 1275, -1, 1398, 1275, 1394, -1, + 1276, 1278, 1277, -1, 1276, 1277, 1279, -1, + 1276, 1280, 1278, -1, 1276, 1281, 1282, -1, + 1276, 1282, 1280, -1, 1276, 1283, 1281, -1, + 1276, 1279, 1283, -1, 1284, 1286, 1285, -1, + 1284, 1285, 1293, -1, 1284, 1287, 1286, -1, + 1284, 1300, 1287, -1, 1284, 1288, 1300, -1, + 1284, 1294, 1288, -1, 1284, 1293, 1294, -1, + 1422, 1289, 1292, -1, 1422, 1420, 1424, -1, + 1422, 1424, 1290, -1, 1422, 1291, 1289, -1, + 1422, 1290, 1291, -1, 1489, 1422, 1292, -1, + 1489, 1292, 1296, -1, 1489, 1296, 1488, -1, + 1487, 1293, 1485, -1, 1487, 1294, 1293, -1, + 1487, 1295, 1294, -1, 1487, 1296, 1295, -1, + 1487, 1488, 1296, -1, 1302, 1297, 1300, -1, + 1302, 1303, 1297, -1, 1298, 1300, 1299, -1, + 1298, 1299, 1301, -1, 1298, 1302, 1300, -1, + 1298, 1303, 1302, -1, 1298, 1304, 1303, -1, + 1298, 1301, 1305, -1, 1298, 1305, 1306, -1, + 1298, 1306, 1304, -1, 1401, 1497, 1307, -1, + 1401, 1307, 1400, -1, 1467, 1495, 1496, -1, + 1467, 1496, 1497, -1, 1467, 1497, 1401, -1, + 1404, 1502, 1308, -1, 1404, 1402, 1502, -1, + 1404, 1308, 1403, -1, 1505, 1477, 1503, -1, + 1505, 1503, 1402, -1, 1511, 1403, 1466, -1, + 1309, 1311, 1310, -1, 1309, 1310, 1312, -1, + 1309, 1312, 1313, -1, 1309, 1313, 1314, -1, + 1309, 1314, 1315, -1, 1309, 1315, 1311, -1, + 1316, 1317, 1320, -1, 1316, 1320, 1319, -1, + 1316, 1319, 1317, -1, 1318, 1319, 1320, -1, + 1318, 1408, 1407, -1, 1318, 1407, 1319, -1, + 1318, 1320, 1480, -1, 1318, 1480, 1479, -1, + 1318, 1409, 1408, -1, 1318, 1479, 1409, -1, + 1473, 1410, 1528, -1, 1519, 1409, 1479, -1, + 1519, 1410, 1409, -1, 1427, 1480, 1320, -1, + 1427, 1320, 1321, -1, 1427, 1476, 1480, -1, + 1427, 1321, 1430, -1, 1535, 1413, 1482, -1, + 1322, 1413, 1323, -1, 1322, 1323, 1470, -1, + 1322, 1470, 1413, -1, 1421, 1432, 1423, -1, + 1324, 1325, 1326, -1, 1324, 1326, 1327, -1, + 1324, 1327, 1328, -1, 1324, 1390, 1325, -1, + 1324, 1329, 1390, -1, 1324, 1328, 1329, -1, + 1429, 1431, 1425, -1, 1433, 1423, 1432, -1, + 1433, 1434, 1423, -1, 1330, 1331, 1332, -1, + 1330, 1332, 1333, -1, 1330, 1333, 1331, -1, + 1435, 1495, 1466, -1, 1435, 1334, 1436, -1, + 1435, 1335, 1334, -1, 1435, 1466, 1403, -1, + 1435, 1403, 1335, -1, 1491, 1436, 1336, -1, + 1491, 1336, 1492, -1, 1443, 1437, 1337, -1, + 1443, 1337, 1444, -1, 1450, 1338, 1439, -1, + 1450, 1439, 1448, -1, 1450, 1451, 1338, -1, + 1339, 1340, 1341, -1, 1339, 1341, 1342, -1, + 1339, 1342, 1340, -1, 1343, 1366, 1344, -1, + 1343, 1345, 1366, -1, 1343, 1346, 1347, -1, + 1343, 1344, 1346, -1, 1343, 1347, 1348, -1, + 1343, 1348, 1345, -1, 1349, 1350, 1351, -1, + 1349, 1352, 1350, -1, 1349, 1351, 1353, -1, + 1349, 1353, 1352, -1, 1354, 1356, 1355, -1, + 1354, 1377, 1356, -1, 1354, 1357, 1377, -1, + 1354, 1358, 1357, -1, 1354, 1355, 1358, -1, + 1359, 1360, 1361, -1, 1359, 1363, 1362, -1, + 1359, 1361, 1363, -1, 1359, 1364, 1360, -1, + 1359, 1365, 1364, -1, 1359, 1362, 1365, -1, + 1373, 1370, 1366, -1, 1373, 1366, 1367, -1, + 1373, 1367, 1368, -1, 1373, 1368, 1374, -1, + 1369, 1371, 1370, -1, 1369, 1372, 1371, -1, + 1369, 1373, 1374, -1, 1369, 1370, 1373, -1, + 1369, 1375, 1372, -1, 1369, 1374, 1375, -1, + 1376, 1378, 1377, -1, 1376, 1379, 1378, -1, + 1376, 1377, 1379, -1, 1380, 1382, 1381, -1, + 1380, 1384, 1383, -1, 1380, 1383, 1382, -1, + 1380, 1385, 1384, -1, 1380, 1386, 1385, -1, + 1380, 1387, 1386, -1, 1380, 1381, 1387, -1, + 1455, 1456, 1388, -1, 1455, 1388, 1396, -1, + 1455, 1389, 1458, -1, 1455, 1394, 1389, -1, + 1500, 1391, 1390, -1, 1500, 1390, 1456, -1, + 1500, 1392, 1391, -1, 1500, 1501, 1392, -1, + 1393, 1398, 1394, -1, 1393, 1396, 1398, -1, + 1393, 1394, 1455, -1, 1393, 1455, 1396, -1, + 1395, 1396, 1397, -1, 1395, 1397, 1398, -1, + 1395, 1398, 1396, -1, 1462, 1399, 1461, -1, + 1462, 1400, 1399, -1, 1462, 1401, 1400, -1, + 1462, 1467, 1401, -1, 1463, 1505, 1402, -1, + 1463, 1403, 1511, -1, 1463, 1404, 1403, -1, + 1463, 1402, 1404, -1, 1527, 1528, 1410, -1, + 1527, 1506, 1526, -1, 1527, 1522, 1506, -1, + 1405, 1472, 1406, -1, 1405, 1473, 1472, -1, + 1405, 1406, 1407, -1, 1405, 1407, 1408, -1, + 1405, 1410, 1473, -1, 1405, 1408, 1409, -1, + 1405, 1409, 1410, -1, 1481, 1480, 1476, -1, + 1521, 1410, 1519, -1, 1521, 1522, 1527, -1, + 1521, 1527, 1410, -1, 1525, 1482, 1471, -1, + 1525, 1473, 1528, -1, 1525, 1471, 1473, -1, + 1524, 1411, 1416, -1, 1524, 1460, 1411, -1, + 1524, 1533, 1460, -1, 1412, 1414, 1413, -1, + 1412, 1413, 1535, -1, 1412, 1415, 1414, -1, + 1412, 1416, 1415, -1, 1412, 1524, 1416, -1, + 1412, 1535, 1524, -1, 1484, 1485, 1417, -1, + 1484, 1417, 1418, -1, 1484, 1418, 1419, -1, + 1484, 1419, 1432, -1, 1484, 1432, 1421, -1, + 1486, 1423, 1420, -1, 1486, 1421, 1423, -1, + 1486, 1420, 1422, -1, 1486, 1422, 1489, -1, + 1486, 1484, 1421, -1, 1428, 1423, 1434, -1, + 1428, 1424, 1423, -1, 1428, 1425, 1424, -1, + 1428, 1429, 1425, -1, 1426, 1434, 1476, -1, + 1426, 1476, 1427, -1, 1426, 1428, 1434, -1, + 1426, 1429, 1428, -1, 1426, 1427, 1430, -1, + 1426, 1430, 1431, -1, 1426, 1431, 1429, -1, + 1475, 1432, 1474, -1, 1475, 1433, 1432, -1, + 1475, 1476, 1434, -1, 1475, 1434, 1433, -1, + 1493, 1435, 1436, -1, 1493, 1495, 1435, -1, + 1493, 1436, 1491, -1, 1442, 1439, 1437, -1, + 1442, 1437, 1443, -1, 1438, 1440, 1439, -1, + 1438, 1441, 1440, -1, 1438, 1439, 1442, -1, + 1438, 1442, 1443, -1, 1438, 1443, 1444, -1, + 1438, 1445, 1441, -1, 1438, 1444, 1446, -1, + 1438, 1446, 1445, -1, 1447, 1448, 1449, -1, + 1447, 1450, 1448, -1, 1447, 1451, 1450, -1, + 1447, 1452, 1451, -1, 1447, 1453, 1452, -1, + 1447, 1449, 1454, -1, 1447, 1454, 1453, -1, + 1499, 1456, 1455, -1, 1499, 1458, 1457, -1, + 1499, 1455, 1458, -1, 1499, 1457, 1502, -1, + 1499, 1500, 1456, -1, 1468, 1462, 1465, -1, + 1468, 1467, 1462, -1, 1468, 1465, 1509, -1, + 1459, 1461, 1460, -1, 1459, 1462, 1461, -1, + 1459, 1465, 1462, -1, 1459, 1460, 1533, -1, + 1459, 1533, 1465, -1, 1512, 1505, 1463, -1, + 1512, 1463, 1511, -1, 1508, 1531, 1526, -1, + 1464, 1509, 1465, -1, 1464, 1465, 1533, -1, + 1464, 1533, 1531, -1, 1464, 1531, 1508, -1, + 1464, 1508, 1509, -1, 1510, 1466, 1495, -1, + 1510, 1511, 1466, -1, 1510, 1495, 1467, -1, + 1510, 1467, 1468, -1, 1510, 1468, 1509, -1, + 1469, 1482, 1470, -1, 1469, 1471, 1482, -1, + 1469, 1470, 1472, -1, 1469, 1472, 1473, -1, + 1469, 1473, 1471, -1, 1516, 1474, 1515, -1, + 1516, 1475, 1474, -1, 1516, 1481, 1476, -1, + 1516, 1476, 1475, -1, 1520, 1514, 1477, -1, + 1520, 1505, 1523, -1, 1520, 1477, 1505, -1, + 1478, 1479, 1480, -1, 1478, 1480, 1481, -1, + 1478, 1519, 1479, -1, 1478, 1518, 1519, -1, + 1478, 1481, 1516, -1, 1478, 1516, 1518, -1, + 1532, 1535, 1482, -1, 1532, 1482, 1525, -1, + 1483, 1485, 1484, -1, 1483, 1484, 1486, -1, + 1483, 1487, 1485, -1, 1483, 1488, 1487, -1, + 1483, 1489, 1488, -1, 1483, 1486, 1489, -1, + 1490, 1491, 1492, -1, 1490, 1493, 1491, -1, + 1490, 1492, 1494, -1, 1490, 1496, 1495, -1, + 1490, 1495, 1493, -1, 1490, 1494, 1497, -1, + 1490, 1497, 1496, -1, 1498, 1500, 1499, -1, + 1498, 1501, 1500, -1, 1498, 1499, 1502, -1, + 1498, 1503, 1501, -1, 1498, 1502, 1503, -1, + 1504, 1523, 1505, -1, 1504, 1505, 1512, -1, + 1504, 1522, 1523, -1, 1504, 1506, 1522, -1, + 1504, 1512, 1508, -1, 1504, 1526, 1506, -1, + 1504, 1508, 1526, -1, 1507, 1509, 1508, -1, + 1507, 1511, 1510, -1, 1507, 1510, 1509, -1, + 1507, 1512, 1511, -1, 1507, 1508, 1512, -1, + 1513, 1514, 1520, -1, 1513, 1520, 1518, -1, + 1513, 1515, 1514, -1, 1513, 1516, 1515, -1, + 1513, 1518, 1516, -1, 1517, 1519, 1518, -1, + 1517, 1518, 1520, -1, 1517, 1522, 1521, -1, + 1517, 1521, 1519, -1, 1517, 1523, 1522, -1, + 1517, 1520, 1523, -1, 1534, 1533, 1524, -1, + 1534, 1524, 1535, -1, 1530, 1532, 1525, -1, + 1530, 1526, 1531, -1, 1530, 1527, 1526, -1, + 1530, 1528, 1527, -1, 1530, 1525, 1528, -1, + 1529, 1530, 1531, -1, 1529, 1532, 1530, -1, + 1529, 1531, 1533, -1, 1529, 1533, 1534, -1, + 1529, 1535, 1532, -1, 1529, 1534, 1535, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT2_shoulderPitch.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT2_shoulderPitch.wrl new file mode 100644 index 0000000..932d88d --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT2_shoulderPitch.wrl @@ -0,0 +1,944 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_RT2_shoulderPitch____________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 55.123402 -74.929001 -20.068399, + 0.84069097 -23.003401 53.318298, + -2.51759 -22.880699 53.318298, + 11.5477 -71.5 33.9263, + 58.5994 -74.929001 -28.9718, + 69.3563 -45.136799 -43.3596, + 34.250198 -71.5 39.4207, + 8.6440601 -74.929001 -20.0851, + 17.563299 -74.929001 -36.864498, + 13.9066 -74.929001 -35.2402, + 17.753599 -74.929001 -35.920898, + 13.5655 32.1828 -37.443501, + 1.64037 34.886501 43.793301, + -19.197599 -12.701 53.318298, + -20.8423 -9.7704601 53.318298, + -22.773399 -3.3515601 53.318298, + 8.3766298 -74.929001 -20.068399, + 30.249201 -71.5 39.471401, + -5.8222098 -22.2703 53.318298, + -14.7245 -17.6933 53.318298, + 48.694901 -74.929001 -35.680901, + 52.2178 -74.929001 -33.783501, + 44.998199 -74.929001 -37.212101, + 61.075699 -74.929001 -26.4328, + 60.919102 -74.929001 -26.634899, + 7.4323001 -21.7859 53.318298, + 17.0865 -71.599998 35.597198, + 16.723 -71.599998 35.428501, + 14.8051 -71.5 35.680698, + 60.9492 -74.929001 -24.528, + 62.044498 -71.5 25.347401, + 46.016998 -74.929001 -35.8731, + 37.236301 -74.929001 -39.117199, + 41.1656 -74.929001 -38.3615, + 23.8277 25.534201 -43.793499, + 50.384701 -19.725599 -43.893501, + 5.7679701 34.442101 -37.443501, + 5.7679701 34.442101 -43.793499, + 5.7122102 34.4547 43.793301, + 9.7055302 33.549301 43.793301, + 13.5655 32.1828 43.793301, + 17.238899 30.373899 37.443298, + 17.238899 30.373899 43.793301, + 20.6754 28.147499 43.793301, + 69.021599 -42.366299 -35.035099, + 68.765297 -40.6297 41.1959, + -34.5742 -4.9376402 -37.443501, + -34.914501 -0.85713398 -37.443501, + -34.5742 -4.9376402 43.793301, + -34.914501 -0.85713398 -43.793499, + 49.399502 -24.890301 -43.893501, + -0.79944301 -40.699402 -43.792702, + -29.5532 18.6108 43.793301, + 8.1101999 -74.929001 -20.096901, + 26.2637 -71.5 39.117001, + -9.0027399 -21.1852 53.318298, + 4.1810498 22.635799 53.318298, + 0.84069097 23.003401 53.318298, + 69.570503 -47.430099 -40.7141, + 69.7323 -49.9011 -37.1059, + 67.848602 -71.5 -16.0357, + 55.530602 -74.929001 -31.539499, + 43.880798 -74.929001 -35.5919, + 7.8523598 -74.929001 -20.1698, + 69.285698 -71.5 -12.3014, + 68.243202 -71.5 15.1159, + 65.7659 -71.5 19.986099, + 66.526703 -71.5 18.730301, + 61.099998 -74.929001 -24.7346, + 64.4534 -71.5 22.1525, + 25.2745 -74.929001 -38.965698, + 29.2498 -74.929001 -39.420898, + 69.133904 -43.2192 -43.078098, + 26.6525 22.569901 -37.443501, + 29.110901 19.295401 37.443298, + 17.238899 30.373899 -43.793499, + -10.4858 33.313702 -43.793499, + 48.660801 -19.042999 -43.893501, + 5.7122102 34.4547 -43.793499, + 1.64037 34.886501 -43.793499, + 48.284 -19.042999 -43.893501, + -10.4858 33.313702 37.443298, + 20.6754 28.147499 -37.443501, + 21.3542 27.584801 -37.443501, + 20.6754 28.147499 -43.793499, + 20.6754 28.147499 37.443298, + 20.579201 28.2099 -43.793499, + 68.912201 -41.595699 -35.476002, + 68.991203 -42.147301 -42.613098, + 68.875099 -41.345901 42.075001, + 69.090698 -42.8806 -34.642899, + 68.891701 -41.456699 -35.635101, + 68.874603 -41.3423 -42.075699, + 68.911301 -41.5895 -42.269699, + 68.813103 -40.936401 35.809299, + -32.479099 -12.8399 37.443298, + -32.479099 -12.8399 43.793301, + -33.758701 -8.9502697 43.793301, + -33.758701 -8.9502697 -37.443501, + -34.5742 -4.9376402 -43.793499, + -4.7432399 -71.5 -15.1161, + 4.1753302 -74.929001 -28.2824, + -9.8612404 -41.107201 -43.786201, + -33.355202 10.1953 -37.443501, + -33.07 11.2307 37.443298, + -33.07 11.2307 -37.443501, + 29.045401 -26.183901 -43.893501, + -14.3128 31.8575 -43.793499, + -17.943001 29.9634 -43.793499, + 29.410299 -31.983999 -43.893501, + 29.784 -32.0312 -43.893501, + -29.5532 18.6108 -37.443501, + -29.5532 18.6108 37.443298, + -31.528299 15.024 43.793301, + -31.528299 15.024 -37.443501, + -24.417101 24.971201 37.443298, + -27.1719 21.941799 37.443298, + -27.1719 21.941799 43.793301, + -21.326599 27.6574 -37.443501, + -34.774799 3.2351501 43.793301, + -23.0187 1.4208491e-009 53.318298, + -34.914501 -0.85713398 43.793301, + 17.469299 -71.599998 35.7159, + 7.4323001 21.7859 53.318298, + 18.219299 14.0685 53.318298, + 10.5251 20.4715 53.318298, + 13.3937 18.7209 53.318298, + 23.8277 25.534201 43.793301, + 26.6525 22.569901 43.793301, + 15.9767 16.571301 53.318298, + -22.042801 -6.63168 53.318298, + -22.773399 3.3515601 53.318298, + -20.8423 9.7704601 53.318298, + -33.07 11.2307 43.793301, + -34.1572 7.28297 43.793301, + -30.753099 -16.552999 43.793301, + 20.0735 11.2658 53.318298, + 21.499901 8.2230101 53.318298, + 22.9573 1.6802599 53.318298, + 69.405998 -45.600399 -31.500601, + 69.377701 -45.322701 -31.92, + 69.409698 -45.638 -43.268398, + 69.711098 -49.617802 37.514702, + 69.751503 -50.290699 36.526001, + 71.094803 -66.5 3.4979401, + 38.225498 -71.5 38.9655, + 46.224098 -71.599998 35.662899, + 45.936699 -71.5 36.864399, + 42.134399 -71.5 38.1105, + 45.834301 -71.599998 35.755798, + 55.389801 -74.929001 -20.096901, + 49.593399 -71.5 35.240002, + 59.324699 -71.5 28.2822, + 61.197899 -74.929001 -26.2082, + 61.282398 -74.929001 -25.966801, + 70.993599 -71.5 -4.49371, + 70.337601 -71.5 -8.4408598, + 69.614197 -48.003799 39.885799, + -9.7195196 -41.465 -43.7752, + -0.986655 -41.298901 -43.780899, + -10.1059 -42.4804 -43.7071, + 21.365601 -74.929001 -38.110699, + -7.4572701 -44.450001 -43.484501, + 68.8283 -41.035702 -41.786098, + 68.861702 -41.2556 -42.007599, + 68.814903 -40.9478 -41.697399, + 68.834602 -41.076401 41.838001, + 50.899502 -20.273701 -43.893501, + 26.6525 22.569901 -43.793499, + 49.399502 -19.183901 -43.893501, + 9.7055302 33.549301 -43.793499, + 13.5655 32.1828 -43.793499, + -6.5146799 34.312 43.793301, + -2.45402 34.838699 37.443298, + -2.45402 34.838699 43.793301, + -17.1437 15.3608 53.318298, + -19.197599 12.701 53.318298, + -24.417101 24.971201 43.793301, + 69.062401 -42.671101 42.858898, + 69.041702 -42.513599 34.794899, + 69.040703 -42.506199 34.932301, + 69.076797 -42.774899 -42.912601, + 69.085197 -42.8382 42.9389, + 68.931702 -41.733299 42.351002, + 68.934097 -41.7463 35.329601, + 68.981697 -42.079601 42.575802, + 68.890999 -41.452 42.1684, + 29.110901 19.295401 43.793301, + 68.744797 -40.5 -36.1544, + 68.744797 -40.5 36.154301, + 68.744797 -40.5 40.618301, + 34.407501 11.3045 41.490002, + 34.720699 10.832 -41.3853, + 33.038898 13.3693 42.030102, + 66.331902 -36.8596 37.187401, + -7.59481 -71.5 -3.4981201, + 29.045401 -31.890301 -43.893501, + 28.364901 -31.570101 -43.893501, + 26.996099 -29.413099 -43.893501, + 28.695101 -31.7516 -43.893501, + 7.1780801 -74.929001 -30.927, + 18.575899 -74.929001 -29.674801, + 10.433 -74.929001 -33.2542, + 2.4242599 -74.929001 -26.4328, + -28.604401 -20.038601 -43.793499, + 2.58094 -74.929001 -26.634899, + -26.0625 -23.248699 -43.793499, + 31.2498 -31.7516 -43.893501, + 30.534599 -31.983999 -43.893501, + 30.8995 -31.890301 -43.893501, + -34.1572 7.28297 -43.793499, + -33.355202 10.1953 -43.793499, + -34.774799 3.2351501 -43.793499, + -34.1572 7.28297 -37.443501, + -33.07 11.2307 -43.793499, + 27.0667 -28.291 -43.893501, + 26.996099 -28.6611 -43.893501, + -31.528299 15.024 -43.793499, + 28.695101 -26.322599 -43.893501, + 27.545401 -27.273701 -43.893501, + 27.3435 -27.591801 -43.893501, + -27.1719 21.941799 -43.793499, + -29.5532 18.6108 -43.793499, + 28.060101 -26.725599 -43.893501, + -24.417101 24.971201 -43.793499, + -21.326599 27.6574 -43.793499, + 27.7855 -26.9835 -43.893501, + 28.364901 -26.504101 -43.893501, + 29.410299 -26.0902 -43.893501, + 27.1831 -27.932699 -43.893501, + 22.045601 -71.5 38.2747, + 18.501801 -71.5 37.211899, + 1.56933 -20.941299 53.318298, + -1.56933 -20.941299 53.318298, + 4.1810498 -22.635799 53.318298, + 20.0735 -11.2658 53.318298, + 20.7654 3.12989 53.318298, + 22.468 5.0049701 53.318298, + -22.042801 6.63168 53.318298, + 17.351 -11.8297 53.318298, + 69.3172 -44.755901 -32.6782, + 69.357803 -45.1367 32.2785, + 69.389297 -45.4356 31.872, + 69.3582 -45.1366 -32.2924, + 69.3563 -45.136799 43.359402, + 69.330002 -44.872898 32.48, + 10.5251 -20.4715 53.318298, + 15.9767 -16.571301 53.318298, + 18.219299 -14.0685 53.318298, + 13.3937 -18.7209 53.318298, + 22.468 -5.0049701 53.318298, + 21.499901 -8.2230101 53.318298, + 22.9573 -1.6802599 53.318298, + 69.167 -43.4758 -34.044102, + 69.137001 -43.2379 34.2066, + 69.437103 -45.916801 30.9226, + 69.416496 -45.706299 -31.4557, + 69.452103 -46.072701 -30.690901, + 56.321899 -71.5 30.9268, + 61.327099 -74.929001 -25.715, + 71.094803 -71.5 3.4979401, + 71.246803 -71.5 -0.50045198, + 58.127399 -43.470501 -43.619202, + -1.42589 -42.117802 -43.741901, + -9.0609102 -42.480999 -43.715302, + 8.6273899 -43.470501 -43.619202, + 68.750504 -40.535702 -40.926601, + 68.754204 -40.559299 41.015202, + 68.747597 -40.517502 40.834099, + 68.745399 -40.503601 -40.716999, + 49.749802 -24.7516 -43.893501, + 49.749802 -19.322599 -43.893501, + 47.545399 -19.183901 -43.893501, + 49.034599 -19.0902 -43.893501, + 30.160801 -32.0312 -43.893501, + 26.972401 -29.0371 -43.893501, + 48.660801 -25.0312 -43.893501, + 45.683102 -23.1415 -43.893501, + -5.7679701 34.408901 -43.793499, + -5.7679701 34.408901 -37.443501, + -2.45402 34.838699 -43.793499, + -6.5146799 34.312 -43.793499, + 47.910301 -19.0902 -43.893501, + -2.51759 22.880699 53.318298, + -5.8222098 22.2703 53.318298, + -10.4858 33.313702 43.793301, + 66.505402 -37.121399 -37.2038, + 63.628502 -32.780998 -37.443501, + 68.744797 -40.5 -40.6185, + 67.952301 -39.304298 36.664398, + -7.74683 -71.5 0.50027198, + 2.2175601 -74.929001 -25.966801, + -7.0390501 -71.5 -7.4606199, + -6.0852699 -71.5 -11.3466, + 2.1728899 -74.929001 -25.715, + 2.3020799 -74.929001 -26.2082, + 27.7855 -31.0907 -43.893501, + 27.545401 -30.800501 -43.893501, + -11.9644 -40.5 -43.793499, + 28.060101 -31.3486 -43.893501, + 27.1831 -30.1415 -43.893501, + -30.753099 -16.552999 -43.793499, + -32.479099 -12.8399 -43.793499, + 27.3435 -30.482401 -43.893501, + 27.0667 -29.783199 -43.893501, + -33.758701 -8.9502697 -43.793499, + -7.4572701 -44.450001 43.484299, + 22.3344 -71.5 38.361301, + -11.9914 -19.6486 53.318298, + -9.4208498 -42.980999 43.671902, + -26.0625 -23.248699 43.793301, + -17.1437 -15.3608 53.318298, + 69.282997 -44.450001 40.618301, + 69.2472 -44.139599 33.482899, + 69.278801 -44.413399 43.438, + 69.195801 -43.709202 -33.9156, + 69.170799 -43.506001 -43.184898, + 69.221001 -43.918201 33.565601, + 69.2472 -44.139702 -33.3862, + 69.206703 -43.806099 43.269402, + 69.151604 -43.352798 34.243999, + 69.113503 -43.054699 43.025002, + 69.2323 -44.012901 43.336601, + 69.282997 -44.450001 43.484299, + 69.477898 -46.349499 30.0907, + 69.446098 -46.010201 30.940701, + 69.409698 -45.638 43.2682, + 69.468697 -46.249599 -30.4918, + 69.496597 -46.555698 29.6327, + 69.509697 -46.703899 -29.491899, + 71.246803 -66.5 -0.50045198, + 69.491997 -46.503899 29.9604, + 69.490196 -46.484001 -29.848801, + 55.8895 -74.929001 -20.285101, + 46.949501 -71.599998 35.326302, + 53.067001 -71.5 33.254002, + 56.108601 -74.929001 -20.4394, + 55.647598 -74.929001 -20.1698, + 46.598099 -71.599998 35.518902, + 60.7672 -74.929001 -24.3484, + 61.293301 -74.929001 -25.206301, + 61.330799 -74.929001 -25.459299, + 61.215698 -74.929001 -24.962601, + 70.539001 -71.5 7.4604402, + 69.935303 -71.5 9.9204397, + 69.585297 -71.5 11.3464, + 65.227997 -40.5242 -43.785099, + 15.395 -41.566898 -43.771099, + -1.10501 -41.566898 -43.771099, + 6.7804799 -41.465 -43.7752, + 62.834499 -43.610298 -43.602299, + 13.3345 -43.610298 -43.602299, + -3.1655099 -43.610298 -43.602299, + -7.8726101 -43.470501 -43.619202, + 68.791 -40.793598 -41.491901, + 68.794296 -40.814701 -41.526402, + 68.794098 -40.813099 41.523998, + 68.765503 -40.630798 -41.195999, + 68.756798 -40.5756 -41.066601, + 68.772003 -40.6721 -41.292702, + 68.7686 -40.650501 41.2491, + 51.2617 -20.932699 -43.893501, + 51.101299 -20.591801 -43.893501, + 50.659302 -19.9835 -43.893501, + 51.378201 -21.291 -43.893501, + 51.448799 -21.6611 -43.893501, + 51.472401 -22.0371 -43.893501, + 50.079899 -19.504101 -43.893501, + 51.448799 -22.413099 -43.893501, + 50.384701 -24.3486 -43.893501, + 50.079899 -24.570101 -43.893501, + 51.2617 -23.1415 -43.893501, + 51.378201 -22.783199 -43.893501, + 50.899502 -23.800501 -43.893501, + 50.659302 -24.0907 -43.893501, + 51.101299 -23.482401 -43.893501, + 30.534599 -26.0902 -43.893501, + 46.045399 -20.273701 -43.893501, + 29.784 -26.042999 -43.893501, + 28.847401 -29.2971 -43.893501, + -11.9914 19.6486 53.318298, + -9.0027399 21.1852 53.318298, + -14.7245 17.6933 53.318298, + -21.326599 27.6574 43.793301, + -17.943001 29.9634 43.793301, + -14.3128 31.8575 43.793301, + 2.20667 -74.929001 -25.206301, + 2.16923 -74.929001 -25.459299, + -5.7856898 -71.5 12.3012, + -6.8376098 -71.5 8.4406796, + -7.4935598 -71.5 4.4935298, + -3.1891699 -71.5 18.325399, + -28.604401 -20.038601 43.793301, + -4.3485999 -71.5 16.0355, + 2.28426 -74.929001 -24.962601, + 7.96943 -71.5 31.539301, + 11.2822 -71.5 33.783298, + 7.6104698 -74.929001 -20.285101, + -2.54109 -71.5 19.605301, + 2.39996 -74.929001 -24.7346, + 2.73281 -74.929001 -24.3484, + 7.3913999 -74.929001 -20.4394, + 69.282997 -44.450001 -43.447498, + 69.261497 -44.262199 33.202599, + 69.282997 -44.450001 -43.484501, + 69.282997 -44.450001 -40.6185, + 69.284897 -44.466599 -33.124901, + 65.015999 -41.2906 -43.781101, + 39.638802 -41.107201 -43.786201, + 6.6387601 -41.107201 -43.786201, + 65.192101 -40.735901 -43.7924, + 56.138802 -41.107201 -43.786201, + 15.5133 -41.298901 -43.780899, + 29.110901 19.295401 -43.793499, + 23.5917 -42.0322 -43.7472, + -9.40833 -42.0322 -43.7472, + 15.0741 -42.117802 -43.741901, + 56.280499 -41.465 -43.7752, + 65.013298 -41.298901 -43.780899, + 64.894997 -41.566898 -43.771099, + 39.780499 -41.465 -43.7752, + -11.4654 -41.487801 -43.7743, + 46.918701 -43.266899 -43.6423, + 63.418701 -43.266899 -43.6423, + 58.060101 -43.431 -43.623798, + 41.560101 -43.431 -43.623798, + 8.5601397 -43.431 -43.623798, + 9.2543097 -43.773399 -43.581699, + -7.2456899 -43.773399 -43.581699, + -3.43469 -43.733799 -43.5868, + 58.754299 -43.773399 -43.581699, + 62.5653 -43.733799 -43.5868, + 33.250801 -74.929001 -39.4716, + 25.754299 -43.773399 -43.581699, + -8.3121796 -43.170399 -43.6521, + -8.49613 -43.041599 -43.666, + -2.5813401 -43.266899 -43.6423, + -7.9398599 -43.431 -43.623798, + 57.503899 -43.041599 -43.666, + 63.536301 -43.172798 -43.651901, + 2.1073799 -71.5 26.106701, + 4.90065 -71.5 28.971701, + -11.4654 -41.487801 43.774101, + -0.38171399 -71.5 22.9739, + 2.5507801 -74.929001 -24.528, + 48.0741 -42.117802 -43.741901, + 56.591702 -42.0322 -43.7472, + 64.574097 -42.117802 -43.741901, + 66.489998 -41.931499 -43.753101, + 67.081497 -42.480099 -43.705399, + 68.149002 -43.4702 -43.619202, + -1.831 -42.621498 -43.7048, + 64.168999 -42.621498 -43.7048, + 57.014702 -42.578701 -43.708302, + -8.98526 -42.578701 -43.708302, + 47.440399 -42.8493 -43.684601, + 31.169001 -42.621498 -43.7048, + -2.0595701 -42.8493 -43.684601, + 63.940399 -42.8493 -43.684601, + -9.47367 -42.942001 -43.6758 ] + + } + coordIndex [ 62, 201, 202, -1, 144, 261, 330, -1, + 47, 121, 212, -1, 60, 64, 153, -1, + 60, 153, 141, -1, 0, 17, 16, -1, + 6, 17, 0, -1, 6, 0, 150, -1, + 7, 0, 16, -1, 7, 150, 0, -1, + 432, 404, 5, -1, 432, 5, 141, -1, + 200, 101, 421, -1, 200, 421, 202, -1, + 9, 202, 421, -1, 10, 161, 62, -1, + 10, 62, 202, -1, 31, 62, 161, -1, + 78, 79, 12, -1, 78, 12, 38, -1, + 321, 187, 136, -1, 285, 81, 385, -1, + 280, 12, 79, -1, 49, 47, 212, -1, + 15, 121, 48, -1, 15, 120, 121, -1, + 311, 442, 19, -1, 311, 13, 392, -1, + 308, 19, 442, -1, 308, 55, 19, -1, + 117, 52, 176, -1, 74, 128, 187, -1, + 231, 442, 28, -1, 18, 17, 2, -1, + 18, 19, 55, -1, 1, 2, 17, -1, + 1, 18, 2, -1, 1, 234, 18, -1, + 1, 17, 6, -1, 1, 6, 234, -1, + 97, 15, 48, -1, 135, 392, 13, -1, + 3, 28, 442, -1, 3, 442, 396, -1, + 27, 3, 396, -1, 27, 28, 3, -1, + 61, 4, 153, -1, 61, 21, 141, -1, + 61, 141, 4, -1, 61, 62, 31, -1, + 24, 153, 4, -1, 24, 4, 141, -1, + 243, 141, 5, -1, 243, 5, 404, -1, + 260, 261, 144, -1, 147, 326, 148, -1, + 145, 6, 150, -1, 145, 148, 326, -1, + 145, 326, 6, -1, 25, 6, 326, -1, + 25, 234, 6, -1, 63, 150, 7, -1, + 63, 7, 16, -1, 63, 16, 53, -1, + 63, 53, 122, -1, 152, 29, 30, -1, + 152, 30, 326, -1, 8, 421, 161, -1, + 8, 9, 421, -1, 8, 202, 9, -1, + 8, 161, 10, -1, 8, 10, 202, -1, + 33, 141, 22, -1, 35, 84, 34, -1, + 35, 367, 84, -1, 80, 280, 79, -1, + 80, 282, 280, -1, 83, 34, 84, -1, + 83, 127, 34, -1, 83, 43, 127, -1, + 39, 123, 40, -1, 39, 40, 170, -1, + 57, 38, 12, -1, 57, 12, 174, -1, + 125, 40, 123, -1, 11, 75, 171, -1, + 11, 40, 75, -1, 11, 171, 170, -1, + 11, 170, 40, -1, 86, 84, 367, -1, + 86, 367, 75, -1, 41, 75, 40, -1, + 41, 86, 75, -1, 88, 44, 181, -1, + 88, 185, 44, -1, 356, 187, 166, -1, + 356, 360, 187, -1, 173, 174, 12, -1, + 173, 12, 280, -1, 76, 385, 81, -1, + 76, 107, 385, -1, 99, 49, 198, -1, + 102, 412, 159, -1, 102, 159, 158, -1, + 102, 421, 298, -1, 102, 158, 421, -1, + 50, 270, 410, -1, 14, 135, 13, -1, + 14, 96, 135, -1, 130, 13, 311, -1, + 130, 14, 13, -1, 130, 131, 120, -1, + 130, 120, 15, -1, 130, 15, 97, -1, + 130, 97, 96, -1, 130, 96, 14, -1, + 108, 227, 225, -1, 108, 385, 107, -1, + 108, 384, 385, -1, 116, 112, 52, -1, + 116, 52, 117, -1, 116, 221, 112, -1, + 73, 128, 74, -1, 73, 168, 34, -1, + 73, 127, 128, -1, 73, 34, 127, -1, + 193, 187, 190, -1, 54, 53, 16, -1, + 54, 16, 17, -1, 54, 18, 55, -1, + 54, 17, 18, -1, 233, 19, 18, -1, + 233, 18, 234, -1, 233, 311, 19, -1, + 290, 135, 96, -1, 20, 21, 61, -1, + 20, 61, 31, -1, 20, 31, 33, -1, + 20, 33, 22, -1, 20, 141, 21, -1, + 20, 22, 141, -1, 23, 141, 153, -1, + 23, 153, 24, -1, 23, 24, 141, -1, + 140, 141, 243, -1, 59, 155, 156, -1, + 59, 261, 155, -1, 59, 156, 64, -1, + 59, 330, 261, -1, 256, 257, 141, -1, + 143, 260, 144, -1, 151, 326, 147, -1, + 246, 25, 326, -1, 249, 234, 25, -1, + 249, 25, 246, -1, 397, 27, 396, -1, + 397, 63, 27, -1, 397, 401, 63, -1, + 26, 63, 122, -1, 26, 27, 63, -1, + 26, 122, 231, -1, 26, 231, 28, -1, + 26, 28, 27, -1, 339, 68, 29, -1, + 339, 29, 152, -1, 342, 68, 153, -1, + 67, 68, 342, -1, 69, 30, 29, -1, + 69, 29, 68, -1, 69, 326, 30, -1, + 335, 326, 151, -1, 70, 71, 432, -1, + 70, 432, 33, -1, 70, 31, 161, -1, + 70, 33, 31, -1, 162, 432, 71, -1, + 162, 428, 432, -1, 32, 432, 141, -1, + 32, 141, 33, -1, 32, 33, 432, -1, + 363, 34, 168, -1, 363, 35, 34, -1, + 363, 367, 35, -1, 273, 37, 170, -1, + 273, 78, 37, -1, 36, 170, 37, -1, + 36, 39, 170, -1, 36, 38, 39, -1, + 36, 78, 38, -1, 36, 37, 78, -1, + 56, 38, 57, -1, 56, 39, 38, -1, + 56, 123, 39, -1, 42, 40, 125, -1, + 42, 41, 40, -1, 42, 43, 86, -1, + 42, 86, 41, -1, 126, 127, 43, -1, + 126, 43, 42, -1, 126, 42, 125, -1, + 85, 86, 43, -1, 85, 43, 83, -1, + 180, 44, 185, -1, 180, 181, 44, -1, + 186, 166, 187, -1, 186, 87, 93, -1, + 72, 181, 316, -1, 318, 404, 316, -1, + 90, 316, 181, -1, 253, 316, 90, -1, + 165, 355, 356, -1, 268, 190, 187, -1, + 268, 187, 267, -1, 268, 269, 190, -1, + 45, 187, 360, -1, 45, 267, 187, -1, + 45, 360, 267, -1, 188, 269, 288, -1, + 192, 74, 187, -1, 192, 187, 193, -1, + 281, 76, 81, -1, 281, 282, 76, -1, + 46, 47, 49, -1, 46, 49, 99, -1, + 46, 48, 121, -1, 46, 121, 47, -1, + 46, 99, 305, -1, 46, 305, 98, -1, + 46, 97, 48, -1, 46, 98, 97, -1, + 51, 410, 102, -1, 51, 102, 298, -1, + 275, 49, 212, -1, 275, 212, 216, -1, + 275, 198, 49, -1, 106, 107, 76, -1, + 209, 50, 410, -1, 209, 270, 50, -1, + 110, 410, 51, -1, 110, 51, 298, -1, + 222, 220, 217, -1, 222, 217, 114, -1, + 105, 114, 217, -1, 113, 52, 112, -1, + 113, 104, 133, -1, 113, 105, 104, -1, + 113, 114, 105, -1, 132, 113, 133, -1, + 132, 176, 52, -1, 132, 52, 113, -1, + 134, 133, 103, -1, 134, 213, 212, -1, + 118, 383, 384, -1, 118, 384, 108, -1, + 118, 108, 225, -1, 118, 225, 224, -1, + 307, 122, 53, -1, 307, 53, 54, -1, + 307, 55, 308, -1, 307, 54, 55, -1, + 283, 123, 56, -1, 283, 56, 57, -1, + 283, 57, 174, -1, 251, 252, 235, -1, + 403, 404, 318, -1, 242, 140, 243, -1, + 58, 59, 64, -1, 58, 64, 60, -1, + 58, 60, 141, -1, 58, 330, 59, -1, + 58, 329, 330, -1, 58, 141, 332, -1, + 58, 332, 329, -1, 327, 141, 257, -1, + 327, 332, 141, -1, 157, 330, 326, -1, + 157, 144, 330, -1, 338, 151, 147, -1, + 248, 235, 249, -1, 337, 68, 339, -1, + 337, 153, 68, -1, 337, 61, 153, -1, + 337, 201, 62, -1, 337, 62, 61, -1, + 337, 63, 401, -1, 337, 150, 63, -1, + 154, 153, 64, -1, 154, 64, 156, -1, + 343, 260, 143, -1, 65, 342, 345, -1, + 65, 67, 342, -1, 65, 326, 67, -1, + 65, 157, 326, -1, 65, 345, 157, -1, + 66, 68, 67, -1, 66, 69, 68, -1, + 66, 67, 326, -1, 66, 326, 69, -1, + 450, 404, 432, -1, 424, 423, 450, -1, + 415, 421, 348, -1, 459, 70, 161, -1, + 459, 71, 70, -1, 459, 162, 71, -1, + 413, 404, 450, -1, 413, 316, 404, -1, + 413, 72, 316, -1, 413, 181, 72, -1, + 413, 88, 181, -1, 413, 93, 88, -1, + 413, 92, 93, -1, 413, 164, 92, -1, + 413, 355, 165, -1, 413, 168, 73, -1, + 413, 288, 269, -1, 413, 73, 74, -1, + 413, 74, 192, -1, 413, 192, 288, -1, + 362, 346, 410, -1, 362, 413, 346, -1, + 271, 171, 75, -1, 271, 75, 367, -1, + 272, 76, 282, -1, 272, 106, 76, -1, + 77, 79, 78, -1, 77, 78, 273, -1, + 77, 80, 79, -1, 77, 282, 80, -1, + 77, 272, 282, -1, 77, 273, 272, -1, + 172, 285, 284, -1, 172, 283, 174, -1, + 172, 284, 283, -1, 172, 81, 285, -1, + 172, 281, 81, -1, 175, 117, 176, -1, + 175, 177, 117, -1, 124, 136, 187, -1, + 124, 187, 128, -1, 82, 83, 84, -1, + 82, 85, 83, -1, 82, 84, 86, -1, + 82, 86, 85, -1, 182, 187, 321, -1, + 182, 185, 187, -1, 182, 321, 90, -1, + 182, 90, 181, -1, 184, 87, 186, -1, + 184, 93, 87, -1, 184, 88, 93, -1, + 184, 185, 88, -1, 89, 164, 166, -1, + 89, 166, 186, -1, 89, 186, 164, -1, + 254, 90, 321, -1, 254, 253, 90, -1, + 91, 164, 186, -1, 91, 92, 164, -1, + 91, 186, 93, -1, 91, 93, 92, -1, + 94, 356, 166, -1, 94, 166, 165, -1, + 94, 165, 356, -1, 189, 190, 269, -1, + 189, 269, 188, -1, 194, 193, 190, -1, + 95, 290, 96, -1, 95, 302, 290, -1, + 95, 96, 97, -1, 95, 97, 98, -1, + 95, 98, 305, -1, 95, 305, 302, -1, + 195, 290, 302, -1, 206, 297, 298, -1, + 206, 204, 297, -1, 206, 298, 421, -1, + 304, 305, 99, -1, 304, 99, 198, -1, + 301, 195, 302, -1, 301, 204, 293, -1, + 100, 293, 204, -1, 100, 295, 293, -1, + 100, 204, 295, -1, 205, 421, 101, -1, + 205, 101, 200, -1, 409, 412, 102, -1, + 409, 102, 410, -1, 274, 110, 196, -1, + 274, 410, 110, -1, 211, 134, 103, -1, + 211, 213, 134, -1, 211, 104, 105, -1, + 211, 133, 104, -1, 211, 103, 133, -1, + 214, 215, 211, -1, 214, 105, 217, -1, + 214, 211, 105, -1, 218, 107, 106, -1, + 218, 108, 107, -1, 218, 227, 108, -1, + 218, 106, 272, -1, 109, 298, 196, -1, + 109, 110, 298, -1, 109, 196, 110, -1, + 111, 112, 221, -1, 111, 221, 222, -1, + 111, 113, 112, -1, 111, 222, 114, -1, + 111, 114, 113, -1, 226, 221, 224, -1, + 115, 221, 116, -1, 115, 224, 221, -1, + 115, 117, 177, -1, 115, 116, 117, -1, + 115, 177, 383, -1, 115, 383, 118, -1, + 115, 118, 224, -1, 119, 131, 134, -1, + 119, 121, 120, -1, 119, 120, 131, -1, + 119, 212, 121, -1, 119, 134, 212, -1, + 230, 231, 122, -1, 230, 122, 307, -1, + 129, 123, 283, -1, 129, 136, 124, -1, + 129, 125, 123, -1, 129, 126, 125, -1, + 129, 127, 126, -1, 129, 128, 127, -1, + 129, 124, 128, -1, 237, 129, 283, -1, + 237, 252, 138, -1, 237, 136, 129, -1, + 237, 137, 136, -1, 238, 130, 311, -1, + 238, 131, 130, -1, 238, 176, 132, -1, + 238, 132, 133, -1, 238, 134, 131, -1, + 238, 133, 134, -1, 388, 392, 135, -1, + 388, 135, 389, -1, 390, 135, 290, -1, + 390, 389, 135, -1, 323, 235, 248, -1, + 323, 321, 136, -1, 323, 136, 137, -1, + 323, 249, 246, -1, 323, 251, 235, -1, + 323, 137, 237, -1, 323, 237, 138, -1, + 323, 138, 252, -1, 139, 141, 140, -1, + 139, 140, 242, -1, 139, 242, 326, -1, + 139, 326, 256, -1, 139, 256, 141, -1, + 325, 327, 257, -1, 142, 143, 144, -1, + 142, 144, 157, -1, 142, 343, 143, -1, + 142, 157, 343, -1, 149, 148, 145, -1, + 149, 145, 150, -1, 146, 147, 148, -1, + 146, 338, 147, -1, 146, 148, 149, -1, + 146, 337, 338, -1, 146, 150, 337, -1, + 146, 149, 150, -1, 334, 335, 151, -1, + 334, 151, 338, -1, 258, 152, 326, -1, + 258, 326, 335, -1, 258, 339, 152, -1, + 259, 342, 153, -1, 259, 153, 154, -1, + 259, 155, 261, -1, 259, 156, 155, -1, + 259, 154, 156, -1, 344, 157, 345, -1, + 344, 343, 157, -1, 349, 421, 158, -1, + 349, 158, 159, -1, 349, 159, 412, -1, + 425, 265, 426, -1, 262, 424, 450, -1, + 262, 265, 425, -1, 262, 425, 424, -1, + 264, 454, 421, -1, 264, 421, 415, -1, + 160, 421, 454, -1, 160, 454, 459, -1, + 160, 161, 421, -1, 160, 459, 161, -1, + 353, 428, 162, -1, 353, 162, 459, -1, + 353, 426, 265, -1, 163, 164, 413, -1, + 163, 413, 165, -1, 163, 166, 164, -1, + 163, 165, 166, -1, 167, 362, 363, -1, + 167, 413, 362, -1, 167, 363, 168, -1, + 167, 168, 413, -1, 169, 170, 171, -1, + 169, 171, 271, -1, 169, 273, 170, -1, + 169, 271, 273, -1, 279, 281, 172, -1, + 279, 173, 280, -1, 279, 174, 173, -1, + 279, 172, 174, -1, 382, 175, 176, -1, + 382, 176, 238, -1, 382, 238, 283, -1, + 382, 383, 177, -1, 382, 177, 175, -1, + 178, 180, 185, -1, 178, 185, 182, -1, + 178, 182, 180, -1, 179, 181, 180, -1, + 179, 182, 181, -1, 179, 180, 182, -1, + 183, 185, 184, -1, 183, 184, 186, -1, + 183, 187, 185, -1, 183, 186, 187, -1, + 287, 288, 192, -1, 287, 192, 194, -1, + 289, 188, 288, -1, 289, 287, 194, -1, + 289, 189, 188, -1, 289, 190, 189, -1, + 289, 194, 190, -1, 191, 192, 193, -1, + 191, 193, 194, -1, 191, 194, 192, -1, + 292, 301, 293, -1, 292, 195, 301, -1, + 294, 290, 195, -1, 294, 195, 292, -1, + 199, 196, 298, -1, 199, 298, 197, -1, + 199, 274, 196, -1, 299, 197, 298, -1, + 299, 199, 197, -1, 303, 297, 204, -1, + 303, 204, 301, -1, 303, 304, 198, -1, + 303, 198, 275, -1, 303, 199, 299, -1, + 303, 275, 274, -1, 303, 274, 199, -1, + 394, 205, 200, -1, 394, 201, 337, -1, + 394, 337, 401, -1, 394, 202, 201, -1, + 394, 200, 202, -1, 394, 295, 205, -1, + 394, 294, 295, -1, 203, 295, 204, -1, + 203, 205, 295, -1, 203, 204, 206, -1, + 203, 206, 421, -1, 203, 421, 205, -1, + 207, 270, 209, -1, 207, 274, 270, -1, + 207, 209, 274, -1, 208, 209, 410, -1, + 208, 410, 274, -1, 208, 274, 209, -1, + 210, 211, 215, -1, 210, 216, 212, -1, + 210, 215, 216, -1, 210, 212, 213, -1, + 210, 213, 211, -1, 229, 215, 214, -1, + 229, 216, 215, -1, 229, 217, 220, -1, + 229, 214, 217, -1, 229, 220, 226, -1, + 229, 275, 216, -1, 228, 227, 218, -1, + 228, 218, 272, -1, 228, 272, 378, -1, + 219, 226, 220, -1, 219, 221, 226, -1, + 219, 220, 222, -1, 219, 222, 221, -1, + 223, 224, 225, -1, 223, 226, 224, -1, + 223, 225, 227, -1, 223, 227, 228, -1, + 223, 275, 229, -1, 223, 229, 226, -1, + 223, 378, 275, -1, 223, 228, 378, -1, + 309, 230, 307, -1, 309, 442, 231, -1, + 309, 231, 230, -1, 309, 308, 442, -1, + 232, 311, 233, -1, 232, 238, 311, -1, + 232, 249, 238, -1, 232, 233, 234, -1, + 232, 234, 249, -1, 239, 249, 235, -1, + 239, 235, 252, -1, 239, 252, 237, -1, + 236, 237, 283, -1, 236, 283, 238, -1, + 236, 239, 237, -1, 236, 238, 249, -1, + 236, 249, 239, -1, 398, 394, 399, -1, + 240, 404, 406, -1, 240, 243, 404, -1, + 240, 245, 243, -1, 240, 406, 323, -1, + 240, 323, 245, -1, 241, 242, 243, -1, + 241, 243, 245, -1, 241, 326, 242, -1, + 241, 245, 326, -1, 244, 326, 245, -1, + 244, 245, 323, -1, 244, 246, 326, -1, + 244, 323, 246, -1, 247, 248, 249, -1, + 247, 249, 323, -1, 247, 323, 248, -1, + 312, 403, 323, -1, 312, 323, 406, -1, + 250, 252, 251, -1, 250, 323, 252, -1, + 250, 251, 323, -1, 322, 318, 317, -1, + 320, 316, 253, -1, 320, 253, 254, -1, + 320, 322, 317, -1, 320, 254, 321, -1, + 255, 256, 326, -1, 255, 326, 325, -1, + 255, 257, 256, -1, 255, 325, 257, -1, + 331, 326, 330, -1, 336, 258, 335, -1, + 336, 339, 258, -1, 341, 342, 259, -1, + 341, 260, 343, -1, 341, 261, 260, -1, + 341, 259, 261, -1, 347, 348, 421, -1, + 347, 421, 419, -1, 350, 262, 450, -1, + 350, 351, 265, -1, 350, 265, 262, -1, + 263, 415, 416, -1, 263, 264, 415, -1, + 263, 416, 454, -1, 263, 454, 264, -1, + 352, 265, 351, -1, 352, 353, 265, -1, + 352, 428, 353, -1, 352, 429, 428, -1, + 457, 459, 454, -1, 359, 360, 356, -1, + 266, 267, 360, -1, 266, 360, 358, -1, + 266, 268, 267, -1, 266, 269, 268, -1, + 266, 413, 269, -1, 266, 358, 413, -1, + 368, 410, 372, -1, 368, 366, 410, -1, + 370, 410, 270, -1, 370, 270, 374, -1, + 375, 374, 372, -1, 276, 277, 367, -1, + 276, 367, 374, -1, 276, 270, 274, -1, + 276, 374, 270, -1, 377, 367, 277, -1, + 377, 271, 367, -1, 377, 378, 272, -1, + 377, 273, 271, -1, 377, 272, 273, -1, + 379, 274, 275, -1, 379, 275, 378, -1, + 379, 276, 274, -1, 379, 277, 276, -1, + 379, 377, 277, -1, 278, 279, 280, -1, + 278, 281, 279, -1, 278, 280, 282, -1, + 278, 282, 281, -1, 381, 283, 284, -1, + 381, 382, 283, -1, 381, 285, 385, -1, + 381, 284, 285, -1, 286, 288, 287, -1, + 286, 289, 288, -1, 286, 287, 289, -1, + 387, 390, 290, -1, 387, 290, 294, -1, + 387, 294, 394, -1, 291, 292, 293, -1, + 291, 294, 292, -1, 291, 293, 295, -1, + 291, 295, 294, -1, 296, 298, 297, -1, + 296, 299, 298, -1, 296, 297, 303, -1, + 296, 303, 299, -1, 300, 301, 302, -1, + 300, 303, 301, -1, 300, 304, 303, -1, + 300, 302, 305, -1, 300, 305, 304, -1, + 444, 394, 401, -1, 444, 399, 394, -1, + 306, 307, 308, -1, 306, 308, 309, -1, + 306, 309, 307, -1, 310, 398, 442, -1, + 310, 392, 398, -1, 310, 442, 311, -1, + 310, 311, 392, -1, 393, 392, 388, -1, + 393, 388, 394, -1, 405, 403, 312, -1, + 405, 312, 406, -1, 313, 403, 318, -1, + 313, 318, 322, -1, 313, 322, 403, -1, + 314, 323, 403, -1, 314, 403, 322, -1, + 314, 322, 323, -1, 315, 316, 320, -1, + 315, 320, 317, -1, 315, 318, 316, -1, + 315, 317, 318, -1, 319, 320, 321, -1, + 319, 322, 320, -1, 319, 321, 323, -1, + 319, 323, 322, -1, 324, 325, 326, -1, + 324, 326, 331, -1, 324, 327, 325, -1, + 324, 332, 327, -1, 324, 331, 332, -1, + 328, 330, 329, -1, 328, 331, 330, -1, + 328, 329, 332, -1, 328, 332, 331, -1, + 333, 335, 334, -1, 333, 336, 335, -1, + 333, 338, 337, -1, 333, 334, 338, -1, + 333, 337, 339, -1, 333, 339, 336, -1, + 340, 342, 341, -1, 340, 341, 343, -1, + 340, 343, 344, -1, 340, 345, 342, -1, + 340, 344, 345, -1, 448, 419, 418, -1, + 448, 410, 346, -1, 448, 347, 419, -1, + 448, 346, 413, -1, 448, 415, 348, -1, + 448, 348, 347, -1, 420, 349, 412, -1, + 420, 412, 418, -1, 420, 421, 349, -1, + 445, 454, 416, -1, 445, 453, 454, -1, + 438, 436, 435, -1, 438, 435, 459, -1, + 431, 350, 450, -1, 431, 450, 432, -1, + 431, 433, 429, -1, 431, 351, 350, -1, + 431, 352, 351, -1, 431, 429, 352, -1, + 437, 426, 353, -1, 437, 436, 426, -1, + 437, 353, 459, -1, 451, 457, 454, -1, + 354, 355, 413, -1, 354, 413, 359, -1, + 354, 356, 355, -1, 354, 359, 356, -1, + 357, 413, 358, -1, 357, 359, 413, -1, + 357, 358, 360, -1, 357, 360, 359, -1, + 365, 410, 366, -1, 365, 364, 410, -1, + 361, 363, 362, -1, 361, 362, 410, -1, + 361, 410, 364, -1, 361, 365, 366, -1, + 361, 364, 365, -1, 361, 367, 363, -1, + 361, 374, 367, -1, 361, 366, 368, -1, + 361, 372, 374, -1, 361, 368, 372, -1, + 369, 374, 410, -1, 369, 410, 370, -1, + 369, 370, 374, -1, 371, 372, 410, -1, + 371, 410, 375, -1, 371, 375, 372, -1, + 373, 410, 374, -1, 373, 375, 410, -1, + 373, 374, 375, -1, 376, 378, 377, -1, + 376, 379, 378, -1, 376, 377, 379, -1, + 380, 382, 381, -1, 380, 384, 383, -1, + 380, 383, 382, -1, 380, 385, 384, -1, + 380, 381, 385, -1, 386, 387, 394, -1, + 386, 388, 389, -1, 386, 394, 388, -1, + 386, 389, 390, -1, 386, 390, 387, -1, + 391, 398, 392, -1, 391, 392, 393, -1, + 391, 394, 398, -1, 391, 393, 394, -1, + 395, 396, 442, -1, 395, 442, 441, -1, + 395, 441, 401, -1, 395, 401, 397, -1, + 395, 397, 396, -1, 443, 442, 398, -1, + 443, 398, 399, -1, 443, 399, 444, -1, + 400, 444, 401, -1, 400, 401, 441, -1, + 400, 441, 444, -1, 402, 404, 403, -1, + 402, 403, 405, -1, 402, 406, 404, -1, + 402, 405, 406, -1, 407, 411, 410, -1, + 407, 418, 411, -1, 407, 410, 448, -1, + 407, 448, 418, -1, 408, 409, 410, -1, + 408, 410, 411, -1, 408, 412, 409, -1, + 408, 418, 412, -1, 408, 411, 418, -1, + 449, 413, 450, -1, 449, 448, 413, -1, + 439, 423, 438, -1, 439, 450, 423, -1, + 414, 415, 448, -1, 414, 448, 446, -1, + 414, 446, 445, -1, 414, 416, 415, -1, + 414, 445, 416, -1, 417, 418, 419, -1, + 417, 420, 418, -1, 417, 419, 421, -1, + 417, 421, 420, -1, 422, 438, 423, -1, + 422, 436, 438, -1, 422, 423, 424, -1, + 422, 424, 425, -1, 422, 425, 426, -1, + 422, 426, 436, -1, 427, 432, 428, -1, + 427, 433, 432, -1, 427, 428, 429, -1, + 427, 429, 433, -1, 430, 431, 432, -1, + 430, 432, 433, -1, 430, 433, 431, -1, + 434, 435, 436, -1, 434, 436, 437, -1, + 434, 459, 435, -1, 434, 437, 459, -1, + 458, 438, 459, -1, 458, 439, 438, -1, + 458, 450, 439, -1, 440, 441, 442, -1, + 440, 442, 443, -1, 440, 444, 441, -1, + 440, 443, 444, -1, 447, 453, 445, -1, + 447, 445, 446, -1, 447, 446, 448, -1, + 452, 453, 447, -1, 452, 447, 448, -1, + 452, 448, 449, -1, 452, 450, 458, -1, + 452, 449, 450, -1, 456, 457, 451, -1, + 456, 452, 458, -1, 456, 453, 452, -1, + 456, 454, 453, -1, 456, 451, 454, -1, + 455, 457, 456, -1, 455, 456, 458, -1, + 455, 459, 457, -1, 455, 458, 459, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT3_bicep.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT3_bicep.wrl new file mode 100644 index 0000000..2860607 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT3_bicep.wrl @@ -0,0 +1,3306 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_RT3_bicep____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 56.855202 -37.4384 -162.558, + 8.1567698 -55.400799 -3.80357, + -34.0233 -43.338299 8.2105999, + -22.2089 -50.6008 -0.387656, + -34.5 -0.00013393405 -196.771, + -34.453999 -1.90574 -203.121, + 62.439201 -34.567902 -134.256, + 8.6933298 -55.400799 -2.32937, + -19.9937 -0.00013393897 -220.078, + -30.832001 -16.622801 -203.121, + 63.548302 -19.598101 -175.48599, + -0.981372 -24.2675 -220.078, + -34.7882 -44.338299 -3.84431, + -33.223499 -37.1008 11.0091, + -33.254501 -43.338299 10.9149, + -22.0467 -50.6008 2.707, + -21.4554 -50.6008 5.74897, + -20.446501 -50.6008 8.6790304, + -21.241699 -50.6008 -6.4942398, + -21.938801 -50.6008 -3.4747701, + -17.4597 -34.6008 -200.22099, + -34.1357 -44.338299 -7.7298899, + -13.708 16.5737 -220.078, + 40.832001 16.622601 -206.55, + 26.0123 -34.6008 -202.205, + 8.1567698 -55.400799 3.80356, + 19.427299 -50.6008 10.7687, + 59.970798 -34.515499 -168.425, + 60.8074 -34.695301 -166.95399, + 57.744701 -36.474701 -166.132, + 62.356201 -34.637402 -162.414, + 62.103001 -34.888302 -162.42799, + 65.122704 -0.00013394319 -35.435902, + 65.169403 -29.1376 -37.9021, + -20.075199 -43.338299 28.6703, + 7.3723698 -55.400799 5.16219, + 1.98735 24.8113 -220.078, + -7.1166 37.559502 -203.121, + 5.2604699 23.9771 -220.078, + -6.6151299 22.1306 -220.078, + -12.3871 16.1702 -220.078, + -19.811399 3.0125201 -220.078, + -19.267401 5.9812398 -220.078, + -29.0632 -19.9988 -203.121, + -26.977301 -23.188499 -203.121, + -19.267401 -5.9815102 -220.078, + -33.355499 -9.43964 -203.121, + -34.0867 -5.6992202 -203.121, + -32.2673 -13.0922 -203.121, + 64.835701 -20.538401 -172.392, + 64.298401 -19.214001 -174.248, + 26.4863 -34.325802 -202.25999, + 26.337601 -34.6008 -202.02901, + 43.355499 -9.43964 -206.55, + 42.2673 -13.0922 -206.55, + 5 -24.993799 -220.078, + 1.98735 -24.8116 -220.078, + 6.4479599 -37.6008 -203.121, + -8.9657497 -55.400799 -0.78439897, + -34.955299 -0.00013394265 1.76754, + -34.572498 -43.338299 5.45333, + -34.866798 -37.1008 3.0504401, + -34.898701 -43.338299 2.6608701, + -34.768002 -44.338299 4.02315, + -6.6151299 -22.130899 -220.078, + -9.1980104 -20.5695 -220.078, + -16.4653 -34.325802 -202.27299, + -17.733 -34.325802 -200.252, + -34.2131 37.621799 -5.0114899, + -7.1259899 37.557899 -203.121, + -34.288601 37.6035 -5.0225401, + -5.7574601 37.627998 -199.46001, + -34.485401 37.627998 -1.00342, + -34.1357 37.627998 -5.0001502, + -28.4062 37.627998 -19.5525, + -31.7208 -37.1008 14.7916, + -31.468399 -44.338299 15.3212, + 27.1308 11.615 -220.078, + 3.5 22.499901 -220.078, + 62.254902 28.5947 -172.88901, + 62.4175 27.2955 -173.63699, + 36.977299 23.1882 -206.55, + 39.063301 19.998501 -206.55, + 63.028599 28.072901 -172.229, + 65.292503 27.628 -37.9021, + 65.292503 27.628 -81.8367, + 65.256104 28.480801 -37.9021, + 58.269199 -35.7952 -167.44501, + 59.580799 -35.327 -167.23599, + 59.138302 -36.036499 -165.98, + 26.633101 -34.6008 -201.806, + 34.226501 -44.338299 7.3175402, + 20.737 -50.6008 7.9601798, + 58.580101 -35.2798 -23.0432, + 61.327801 -35.226501 -164.28999, + 60.448898 -35.410099 -165.763, + 61.6483 -34.6091 -165.48599, + 62.310101 -34.57 -163.298, + 60.034901 -36.033001 -164.48801, + 56.148701 -37.536499 -162.563, + 57.1465 -37.0261 -164.733, + 56.989498 -37.127201 -164.384, + 56.722801 -37.298901 -163.791, + 58.6301 -36.6376 -164.63699, + 59.738201 -36.3741 -163.62399, + 65.167 -29.113501 -162.312, + 65.198502 -28.941401 -162.058, + 64.802498 -30.6633 -133.37199, + 64.782097 -30.7271 -133.476, + 64.938103 -30.2395 -37.9021, + 63.347099 -33.391499 -163.08501, + 62.4781 -34.237099 -164.047, + 63.370998 -33.442299 -162.347, + -22.374201 -0.00013393206 26.9146, + -24.403999 -43.338299 25.0888, + -22.374201 0.027366202 26.9146, + -21.7082 -37.1008 27.454599, + -21.657101 -44.338299 27.4949, + -22.311501 -43.338299 26.9666, + 62.037201 -31.8414 -27.5777, + 62.037201 -0.00013394016 -27.5777, + 58.733601 -34.327301 -22.883101, + 59.4729 -33.688 -23.9154, + 60.5005 -32.9888 -25.382999, + 59.288399 -34.1152 -23.6749, + 62.363602 -34.671799 -37.9021, + 62.899101 -34.0648 -162.383, + 62.021 -34.971001 -133.964, + 63.312698 0.027366206 -29.695299, + 63.4002 31.0618 -29.8769, + 64.421898 30.049 -32.395401, + 64.459396 0.027366193 -32.489399, + 64.512001 30.618601 -32.859501, + 64.459396 -0.00013393408 -32.489399, + 64.502403 -30.899599 -33.045101, + 64.512001 -30.5914 -32.859501, + 65.102203 28.782101 -35.318199, + 65.122704 0.027366195 -35.435902, + 64.496696 30.309601 -32.679501, + 65.021896 -29.880501 -35.844501, + -15.1488 -50.6008 16.2451, + -9.9905996 -43.338299 33.5438, + -11.0091 -37.1008 33.223499, + -12.4227 -0.0001339383 32.721199, + -11.0091 37.127998 33.223499, + 5.16219 -55.400799 7.3723602, + 15.7065 -50.6008 15.7065, + 13.3677 -50.6008 17.7395, + 17.7395 -50.6008 13.3677, + 6.3639598 -55.400799 6.3639598, + -1.1625 -50.6008 22.1819, + 62.697899 -24.4725 -174.86301, + 63.5513 19.515699 -175.52299, + 63.609501 16.682699 -176.24899, + 63.659401 13.8558 -176.86501, + 63.1516 26.830799 -172.94501, + 62.563801 25.944799 -174.293, + 63.770401 2.1194799 -178.22701, + -24.5937 26.1621 -203.121, + -32.2673 13.0919 -203.121, + -17.1308 11.615 -220.078, + -15.5694 14.1979 -220.078, + -18.652399 7.9548202 -220.078, + -18.369499 8.8627396 -220.078, + -30.832001 16.622601 -203.121, + -12.2089 -16.66 -220.078, + -14.9968 -14.9289 -220.078, + -18.369499 -8.8629999 -220.078, + -19.811399 -3.01279 -220.078, + -15.5694 -14.1981 -220.078, + -17.1308 -11.6153 -220.078, + 65.292503 -21.615999 -168.78, + 65.292503 -21.032 -169.03799, + 65.177597 -20.0681 -170.992, + 64.846497 -18.801001 -172.91701, + 63.7686 -2.6715 -178.205, + 63.6339 -15.3032 -176.55099, + 64.347801 -14.9981 -175.315, + 63.673 -12.9353 -177.032, + 63.591599 -17.5404 -176.02699, + 64.323402 -17.193701 -174.78999, + 35.131901 -25.540701 -206.55, + 16.615101 -22.130899 -220.078, + 4.7395301 -23.977301 -220.078, + -3.86287 -23.3696 -220.078, + 8.0126495 -24.8116 -220.078, + 21.1117 -35.8097 -203.121, + 26.1248 -34.325802 -202.45599, + 10.9814 -24.2675 -220.078, + -11.4229 -14.5005 -220.078, + 44.0867 -5.6992202 -206.55, + 29.267401 -5.9815102 -220.078, + 20.598499 -0.00013392963 28.2967, + 24.975 -0.0001339333 24.520399, + 25.034599 -44.338299 24.459499, + -34.187698 -0.00013392836 7.4968901, + -34.187698 0.027366199 7.4968901, + -34.095501 -44.338299 7.9053202, + -34.276901 -37.1008 7.07762, + -7.9254498 -37.3255 -203.121, + -15.9919 -34.6008 -202.214, + -16.1021 -34.325802 -202.466, + -11.2052 -36.0229 -203.121, + -16.3188 -34.6008 -202.041, + -16.616199 -34.6008 -201.821, + -16.795799 -34.325802 -202.02901, + -1.6 37.627998 -197.521, + -4.7998099 37.627998 -202.091, + 8.0126495 24.8113 -220.078, + 10.9814 24.2672 -220.078, + 12.955 23.6523 -220.078, + -34.639801 37.6035 -1.00792, + -31.267599 37.627998 14.5803, + -34.312901 37.627998 -2.9748499, + -29.430099 37.621799 18.1528, + -17.719299 34.353001 -200.356, + -17.447399 34.627998 -200.315, + -2.9549501 23.6523 -220.078, + -3.86287 23.369301 -220.078, + -0.981372 24.2672 -220.078, + -32.4874 -0.00013394348 13.0218, + -32.4874 0.027366199 13.0218, + -32.991001 -44.338299 11.6873, + -32.271198 -43.338299 13.5488, + -29.687599 -43.338299 18.5378, + -29.547001 -44.338299 18.7609, + -27.4545 -37.1008 21.7082, + -28.103901 -43.338299 20.8608, + 19.5993 -43.338299 28.9977, + 20.075199 -37.1008 28.6703, + 33.8302 -36.5853 12.7062, + 22.080099 18.201599 -220.078, + 25.569401 14.1979 -220.078, + 23.201799 17.08 -220.078, + 23.708 16.5737 -220.078, + 19.928801 19.9967 -220.078, + 21.5739 18.707899 -220.078, + 19.198 20.569201 -220.078, + 59.3442 36.767101 -162.522, + 57.775501 37.2976 -162.549, + 61.160198 30.3489 -172.597, + 62.072399 29.8412 -172.049, + 63.490398 29.6999 -169.89101, + 63.602798 28.625299 -170.73801, + 63.375999 30.608299 -169.07001, + 62.732899 30.403601 -170.536, + 62.8904 29.263901 -171.427, + 64.051201 29.7745 -168.41299, + 64.126198 28.9335 -169.188, + 64.813202 -22.1996 -171.86501, + 64.274399 -20.986799 -173.72701, + 65.292503 0.027366204 -37.9021, + 65.292503 -27.573299 -37.9021, + 65.292503 27.5382 -162.38699, + 65.292397 27.677299 -161.95599, + 22.1819 -50.6008 -1.1625, + 8.9657497 -55.400799 0.78439498, + 59.228401 -34.755901 -23.7834, + 59.270401 -34.433899 -23.7206, + 58.7076 -34.642799 -22.918699, + 58.656799 -34.9617 -22.971901, + 59.161201 -35.077 -23.863899, + 61.106201 -30.5676 -172.39301, + 63.6129 -32.555599 -164.77499, + 62.710602 -33.6507 -165.15401, + 63.744801 -31.958599 -165.73, + 57.775501 -37.242901 -162.549, + 57.185501 -37.392502 -162.556, + 8.9657497 -55.400799 -0.78439897, + 58.3811 -37.0798 -162.541, + 58.267799 -36.954399 -163.729, + 58.306599 -37.1082 -162.54201, + 64.335701 -31.347401 -164.356, + 64.477699 -30.2386 -166.06599, + 64.411697 -30.8262 -165.224, + 64.855003 -30.498899 -133.106, + -29.363501 37.627998 18.1117, + -19.2076 37.627998 25.915199, + -24.748699 -37.1008 24.748699, + -24.6101 -44.338299 24.8866, + -26.499001 -0.00013393382 22.864799, + -26.499001 0.027366204 22.864799, + -27.2512 -44.338299 21.962999, + -26.3389 -43.338299 23.049101, + 60.3064 -33.818501 -25.201099, + 62.118599 -32.357601 -27.7465, + 32.209 -37.1008 15.0214, + 58.686298 -34.0233 -22.792101, + 29.8654 -44.338299 18.2498, + 58.1595 -34.1008 -22.039801, + 62.753601 -34.250099 -32.0103, + 62.9739 -34.003601 -32.5662, + 62.055401 -34.967098 -31.6367, + 63.510799 31.504801 -30.1653, + 64.052696 30.926701 -31.408899, + 63.9823 -30.5035 -31.2129, + 64.073303 -31.2904 -31.622, + 64.4953 -29.932699 -32.604599, + 64.496696 -30.282301 -32.679501, + 65.049599 -29.7285 -35.751801, + 65.187302 -29.0471 -36.740898, + 65.198502 28.996099 -162.058, + 65.091797 28.9946 -35.274601, + 65.169403 29.192301 -37.9021, + 65.166901 29.169701 -162.30701, + -18.374201 -37.1008 29.789101, + -17.639 -0.00013393546 30.2302, + -17.709299 -43.338299 30.1891, + -4.2383099 -50.6008 21.804199, + -2.32937 -55.400799 8.6933403, + -11.318 -44.338299 33.119499, + -7.52385 -44.338299 34.181702, + -7.3723698 -55.400799 5.16219, + -19.0397 -50.6008 11.4402, + -17.262199 -50.6008 13.9787, + -6.3639598 -55.400799 6.3639598, + -8.1567698 -55.400799 3.80356, + -8.6933298 -55.400799 2.32938, + 0.78440201 -55.400799 8.9657602, + -7.07762 -37.1008 34.276901, + -7.2660799 -43.338299 34.237499, + -6.8675699 0.027366208 34.319599, + -4.4946699 -43.338299 34.710201, + -6.8675699 -0.0001339427 34.319599, + 4.6480899 -0.00013392881 34.689999, + 1.93593 -50.6008 22.1278, + 7.9601798 -50.6008 20.737, + 10.7687 -50.6008 19.427299, + 3.80356 -55.400799 8.1567698, + 2.32937 -55.400799 8.6933403, + 10.2945 -0.00013392828 33.451801, + 10.2945 0.0273662 33.451801, + 36.977299 -23.188499 -206.55, + 39.063301 -19.9988 -206.55, + 40.832001 -16.622801 -206.55, + 63.421398 -23.255301 -174.42101, + 63.506901 -21.403099 -174.965, + 63.4958 21.919201 -174.826, + 64.300102 19.1341 -174.286, + 64.862503 15.9992 -173.687, + 64.333702 16.3528 -175.01199, + 63.421398 23.309999 -174.42101, + 64.199699 27.934 -169.992, + 63.701302 27.4998 -171.504, + 64.847298 18.723801 -172.955, + 63.738701 7.5840201 -177.838, + 63.758999 4.8495402 -178.08701, + 64.386299 10.8122 -176.13699, + 63.7006 11.0345 -177.371, + 63.7328 8.2166796 -177.765, + 64.4048 8.0498104 -176.532, + 64.362503 13.5791 -175.63, + 63.772999 0.027374508 -178.259, + 64.426399 2.07616 -176.995, + 16.615101 22.1306 -220.078, + -12.0801 18.201599 -220.078, + -13.2018 17.08 -220.078, + -34.426498 37.532501 -5.0427499, + -34.4856 37.481602 -5.0513902, + -34.360298 37.573502 -5.0330501, + -34.535999 37.421902 -5.0587802, + -26.977301 23.1882 -203.121, + -29.0632 19.998501 -203.121, + -34.0867 5.6989498 -203.121, + -33.355499 9.4393797 -203.121, + -11.5739 -18.708099 -220.078, + -23.868799 -26.9601 -203.121, + -24.5937 -26.1623 -203.121, + 65.171997 -21.6229 -170.46899, + 65.071701 -22.5044 -170.672, + 63.755798 -5.3250999 -178.047, + 23.708 -16.573999 -220.078, + 21.5739 -18.708099 -220.078, + 27.1308 -11.6153 -220.078, + 25.569401 -14.1981 -220.078, + 19.198 -20.5695 -220.078, + 13.8629 -23.3696 -220.078, + 44.453999 -1.90574 -206.55, + 29.811399 -3.01279 -220.078, + -8.1567698 -55.400799 -3.80357, + -8.6933298 -55.400799 -2.32937, + -6.3639598 -55.400799 -6.3639598, + -7.3723698 -55.400799 -5.1621799, + -7.1166 -37.532299 -203.121, + -6.4815898 -55.400799 0.56706202, + -8.9657497 -55.400799 0.78439498, + -0.784401 -55.400799 8.9657602, + 4.6006799 -55.400799 -4.6006899, + 8.6933298 -55.400799 2.32938, + 2.32937 -55.400799 -8.6933403, + 7.3723698 -55.400799 -5.1621799, + 5.16219 -55.400799 -7.3723698, + 6.3639598 -55.400799 -6.3639598, + 3.80356 -55.400799 -8.1567602, + 0.78440201 -55.400799 -8.9657497, + 16.3183 -37.6008 -203.121, + -3.80356 -55.400799 -8.1567602, + -0.784401 -55.400799 -8.9657497, + -2.32937 -55.400799 -8.6933403, + -5.16219 -55.400799 -7.3723698, + -6.28932 -37.6008 -203.121, + -34.889702 37.421902 -1.01519, + -17.2694 -34.6008 -200.93401, + -17.657 -34.325802 -200.655, + -17.3913 -34.6008 -200.58501, + -17.329901 -34.325802 -201.407, + -17.096901 -34.6008 -201.261, + -16.877501 -34.6008 -201.55901, + -17.0861 -34.325802 -201.73801, + -17.521601 -34.325802 -201.04401, + -21.2003 -29.560101 -203.121, + 44.287701 37.627998 -173.05701, + -0.2 37.627998 -199.946, + -3.75877 37.627998 -180.13901, + -6.28932 37.627998 -202.93401, + -6.28932 37.627998 -203.121, + 56.989399 37.181801 -164.384, + 56.717899 37.356201 -163.78101, + -34.368698 37.627998 3.00687, + -34.563599 37.621799 -1.0057, + -32.748901 37.627998 10.8518, + -27.4545 37.127998 21.7082, + -16.375 34.353001 -202.328, + -11.5739 18.707899 -220.078, + -9.9288101 19.9967 -220.078, + -9.1980104 20.569201 -220.078, + -29.900999 -0.00013393581 18.191401, + -29.789101 -37.1008 18.374201, + -31.0797 -43.338299 16.0952, + -29.900999 0.027366195 18.191401, + 59.5742 36.665001 -37.9021, + 57.946701 37.269299 -37.9021, + 58.306599 37.162998 -162.54201, + 61.795101 35.225101 -55.655102, + 64.073303 31.3176 -31.622, + 56.239201 37.583099 -37.9021, + 17.208599 -43.338299 30.477301, + 18.938801 -44.338299 29.4333, + 14.707 -43.338299 31.760099, + 12.9222 -37.1008 32.527199, + 12.1104 -43.338299 32.8381, + 35.448799 35.730301 10.3946, + 58.734402 -34.0028 -22.860701, + 35.448799 -35.702999 10.3946, + 59.3955 36.747501 -162.521, + 59.826199 36.526001 -162.50999, + 62.572899 31.368799 -169.67, + 62.3815 32.322601 -168.69099, + 35.131901 25.5404 -206.55, + 61.864799 31.034201 -171.114, + 65.200798 -27.9594 -164.80901, + 65.292503 -27.08 -163.549, + 64.927597 -29.120501 -165.45, + 65.292503 -25.7729 -129.271, + 65.292503 -22.647301 -168.239, + 65.292503 -23.463699 -167.72, + 65.233597 -23.1933 -169.175, + 65.236603 -22.238199 -169.653, + 65.069603 -22.6945 -170.592, + 64.797897 -22.936199 -171.592, + 65.292503 -24.932899 -166.52299, + 65.292503 -24.223499 -167.14999, + 65.205498 -27.6359 -165.289, + 65.292503 -26.5215 -164.589, + 65.292503 22.358801 -168.43201, + 65.292503 24.8438 -166.659, + 65.292503 24.1441 -167.258, + 60.2295 -36.2971 -32.1376, + 59.3955 -36.692799 -162.521, + 59.240799 -36.785599 -32.7342, + 21.643 -50.6008 4.9966898, + 58.949501 -35.699799 -24.0772, + 59.068199 -35.3932 -23.962, + 60.792702 -35.9048 -162.481, + 61.097 -35.572601 -163.479, + 60.553699 -32.856499 -170.369, + 60.2164 -33.891499 -169.21899, + 60.846901 -31.7488 -171.424, + 34.781502 -25.8908 -206.55, + 34.378201 -26.178499 -206.55, + 63.859402 -31.293301 -166.64799, + 63.930801 -30.787399 -167.269, + 61.589199 -32.269001 -169.927, + 63.1926 -31.712999 -167.851, + 62.165901 -33.136501 -167.66499, + 61.319099 -33.278599 -168.834, + 61.121799 -33.891201 -168.08099, + 62.316898 -32.548199 -168.375, + 61.924599 -33.912498 -166.604, + 62.910198 -32.994202 -166.19299, + 63.084099 -32.265202 -167.18401, + 64.793701 -30.628599 -162.586, + 64.787201 -30.6583 -162.177, + 64.822998 -30.423901 -163.11, + 64.771004 -30.7605 -55.401699, + 64.771004 -30.7605 -133.521, + 64.641296 -31.122999 -51.505901, + 64.906303 -30.325399 -132.698, + 64.911598 -30.3071 -132.642, + 64.898399 -30.3522 -132.761, + 64.972198 -30.0839 -162.13901, + 64.1819 -32.066601 -162.84599, + 64.246597 -31.807199 -163.45, + 64.111504 -32.271301 -162.27901, + 63.458801 -33.088299 -163.765, + 63.943501 -32.589298 -128.912, + 63.8834 -32.691502 -134.646, + 64.151802 -32.211399 -134.53999, + 63.980301 -32.525299 -128.924, + 63.312698 -0.00013393981 -29.695299, + 63.510799 -31.4776 -30.1653, + 62.8703 -32.006901 -28.956301, + 63.534698 -31.952 -30.404499, + 63.419399 -30.995501 -29.957001, + 63.8176 -30.686701 -30.766199, + 64.052696 -30.8995 -31.408899, + 63.0285 -31.298599 -29.162701, + 61.202702 -33.837799 -26.769199, + 60.279099 -34.160099 -25.2857, + 60.2267 -34.500801 -25.3876, + 27.7558 -43.338299 21.321699, + 29.3776 -43.338299 19.0252, + 28.6703 -37.1008 20.075199, + 28.6703 0.0273662 20.075199, + 63.295898 -33.568699 -128.914, + 63.597599 -33.143299 -162.33099, + 63.2444 -33.636799 -134.616, + 63.473999 -33.3508 -37.9021, + 62.882401 -34.080898 -31.8566, + 64.056396 -31.6786 -31.847799, + 64.467903 -31.2047 -33.235001, + 62.310799 -34.5812 -30.547899, + 61.202702 33.865002 -26.769199, + 61.145199 34.211201 -26.909401, + 60.148399 34.863998 -25.5068, + 59.473301 33.728699 -23.916, + 61.155102 32.501999 -26.3179, + 60.2267 34.528099 -25.3876, + 62.118599 32.3848 -27.7465, + 62.146599 33.131901 -28.053699, + 62.037201 31.868601 -27.5777, + 62.8703 32.0341 -28.956301, + 64.793404 30.6854 -162.58, + 65.0942 29.298 -35.4674, + 65.096199 29.146 -35.371201, + 65.240501 28.5408 -36.732399, + -10.0842 -50.6008 19.7913, + -7.2316198 -50.6008 21.0021, + -3.80356 -55.400799 8.1567698, + -5.16219 -55.400799 7.3723602, + -12.7405 -50.6008 18.195299, + -18.4296 -44.338299 29.754801, + 15.6601 -0.00013394021 31.301201, + 15.5107 -44.338299 31.375401, + 16.611 -37.1008 30.806999, + -3.0504501 -37.1008 34.866798, + -3.6343999 -44.338299 34.810799, + 5.0726199 -37.1008 34.630501, + 62.675301 -24.7253 -174.77, + 63.346001 -24.3682 -174.035, + 63.363098 -24.1259 -174.125, + 64.321098 25.7801 -171.382, + 63.7887 26.323601 -172.19099, + 64.264 26.8829 -170.72301, + 63.2864 25.2264 -173.71201, + 63.3848 23.8643 -174.237, + 63.8671 25.0973 -172.797, + 63.262001 25.538401 -173.576, + 62.726799 24.197201 -174.979, + 62.596199 25.6189 -174.435, + 64.267998 21.494801 -173.58701, + 64.832703 21.0375 -172.25101, + 65.176903 20.5576 -170.85001, + 65.180603 18.2941 -171.561, + 65.2341 23.0928 -169.259, + 65.171997 21.6777 -170.46899, + 65.234901 22.870501 -169.37399, + 65.230797 24.000799 -168.733, + 65.292503 23.3825 -167.813, + 65.292503 21.4597 -168.877, + 65.292503 20.066401 -169.41499, + 65.237801 21.8873 -169.83, + 65.292503 22.5611 -168.32001, + 65.292503 -21.7768 -168.703, + 65.292503 21.0867 -169.03799, + 65.292503 24.027399 -131.771, + 65.292503 23.201 -127.756, + 65.292503 -3.97263 -131.771, + 64.896202 7.2653399 -175.291, + 64.901497 4.6447401 -175.54201, + 64.419899 4.75036 -176.855, + 64.408203 7.42976 -176.605, + 64.8946 7.8719001 -175.218, + 65.192497 7.6865101 -173.84801, + 64.427902 0.027372705 -177.02699, + 64.904404 2.03004 -175.68401, + 13.8629 23.369301 -220.078, + 26.375 34.353001 -202.328, + -34.453999 1.90548 -203.121, + -34.5 0.027366197 -196.771, + -34.999699 -43.338299 -0.148746, + -34.999901 -44.338299 0.0899859, + -13.2018 -17.0802 -220.078, + -23.8431 -26.9876 -203.121, + -13.708 -16.573999 -220.078, + -12.0801 -18.2019 -220.078, + 65.292503 -17.9258 -170.09599, + 65.292503 -19.5868 -169.55901, + 65.180397 -18.368401 -171.522, + 65.237099 -22.0627 -169.731, + 64.857803 -16.821699 -173.463, + 64.3703 -12.6752 -175.797, + 63.7071 -10.4695 -177.45, + 63.735001 -7.9278002 -177.79201, + 65.292503 -11.8103 -171.69299, + 65.292503 6.91922 -172.52499, + 65.292503 7.4973302 -172.45, + 65.192902 7.0940199 -173.922, + 65.194298 4.53475 -174.17599, + 65.292503 17.8545 -170.13499, + 65.292503 4.4225602 -172.782, + 44.453999 1.90548 -206.55, + -34.838799 37.481602 -1.0137, + -34.276901 37.127998 7.07762, + -34.979 37.2062 -1.0177799, + 6.4479599 37.627998 -203.121, + 5 24.9935 -220.078, + 6.4479599 37.627998 -202.93401, + 1.9 37.627998 -203.121, + -3 37.627998 -202.746, + -34.522598 37.6035 3.02034, + -29.789101 37.127998 18.374201, + -29.6644 37.481602 18.2973, + -17.6278 34.353001 -200.757, + -17.365 34.627998 -200.67599, + -17.2722 34.353001 -201.495, + -17.044901 34.627998 -201.34, + -17.0159 34.353001 -201.817, + -17.2299 34.627998 -201.02, + -17.477699 34.353001 -201.13901, + -21.2003 29.587299 -203.121, + -23.868799 26.9874 -203.121, + -16.5431 34.627998 -201.881, + -16.814301 34.627998 -201.63, + -7.9254498 37.352699 -203.121, + -11.2052 36.050201 -203.121, + -16.237499 34.627998 -202.09, + -16.7146 34.353001 -202.09599, + 60.110001 36.388699 -32.230999, + 59.832401 36.538101 -37.9021, + 57.1026 37.462799 -32.679401, + 58.251598 37.177101 -32.907501, + 58.382702 37.138599 -37.9021, + 58.0261 37.247101 -32.908001, + 57.310699 37.422199 -27.2736, + 58.488499 37.1035 -32.907001, + 61.1082 35.75 -30.4718, + 62.013199 34.999401 -30.917999, + 61.133499 35.726501 -30.339899, + 61.3424 35.581799 -30.6623, + 60.468102 36.183102 -31.876301, + 60.2295 36.324299 -32.1376, + 60.542198 36.139198 -31.7952, + 59.3936 36.748402 -32.6824, + 59.760601 35.802898 -25.958099, + 63.534698 31.9793 -30.404499, + 62.848701 33.142601 -29.509199, + 62.893398 32.5928 -29.2145, + 63.5065 32.4482 -30.666901, + 62.1036 34.949501 -31.667299, + 61.847 35.172401 -31.1026, + 61.9002 35.1339 -51.557701, + 62.289398 34.772499 -56.040699, + 61.9002 35.1339 -129.677, + -15.4845 37.627998 26.9128, + -6.97651 37.627998 33.787201, + 30.5179 37.627998 -47.157799, + 31.1227 37.627998 -144.34, + 16.521999 37.627998 -197.42799, + 25.954901 -43.338299 23.4807, + 26.145901 -37.1008 23.267799, + 27.625099 -44.338299 21.490801, + 15.6601 0.0273662 31.301201, + 64.822998 30.478701 -163.11, + 62.103001 34.9431 -162.42799, + 61.795101 35.225101 -133.774, + 61.4823 35.482101 -130.078, + 61.377102 35.563801 -130.198, + 61.1171 33.959202 -168.064, + 62.162399 33.203999 -167.649, + 59.965 34.583698 -168.407, + 61.908401 34.0131 -166.536, + 62.898602 33.092098 -166.13, + 63.8577 31.358999 -166.634, + 63.238899 31.504499 -168.147, + 63.961201 30.600401 -167.547, + 63.081501 32.332001 -167.16901, + 63.737099 32.052601 -165.67101, + 64.407303 30.915501 -165.17, + 64.4767 30.303101 -166.05299, + 62.289398 34.772499 -134.16, + 64.332397 31.4219 -164.321, + 64.246597 31.862 -163.45, + 63.607101 32.633099 -164.735, + 62.7019 33.730499 -165.11099, + 64.069199 32.4207 -128.959, + 64.072502 32.414501 -56.463001, + 64.069199 32.4207 -50.839699, + 58.630001 36.692402 -164.63699, + 58.263699 37.012299 -163.71899, + 57.722 36.554401 -166.077, + 57.444 36.808701 -165.42799, + 57.1464 37.080898 -164.73199, + 58.238201 35.896 -167.36501, + 60.4333 35.491901 -165.714, + 59.554798 35.429199 -167.16, + 60.786301 34.797401 -166.881, + 59.119099 36.117699 -165.92799, + 61.636299 34.690399 -165.439, + 60.635502 32.6236 -170.659, + 60.8992 31.582199 -171.617, + 61.654598 32.044201 -170.202, + 61.4035 33.040901 -169.168, + 60.321701 33.647099 -169.571, + 34.781502 25.890499 -206.55, + 65.292503 26.448099 -164.787, + 65.292503 -27.5595 -162.03101, + 65.292503 -26.7766 -164.157, + 65.292503 -27.573299 -134.271, + 65.292503 -27.573299 -161.951, + 65.292503 -27.313801 -162.959, + 65.292503 -27.4834 -162.38699, + 65.292397 -27.622499 -161.95599, + 65.184601 -28.698 -163.439, + 65.1744 -28.971201 -162.75301, + 65.219704 -28.778 -162.04601, + 65.193298 -28.362499 -164.12199, + 64.897797 -29.6196 -164.68401, + 64.863403 -30.0522 -163.908, + 64.311699 -25.9196 -171.27299, + 63.854599 -25.250401 -172.702, + 65.044197 -24.7229 -169.54201, + 64.736702 -25.332899 -170.424, + 65.029099 -25.6628 -168.918, + 65.057602 -23.732901 -170.10001, + 65.230202 -24.0972 -168.63699, + 65.226402 -24.947901 -168.03999, + 64.411003 -23.571301 -172.396, + 64.793404 -23.140499 -171.509, + 64.766602 -24.259701 -171.00301, + 64.4189 -23.3535 -172.48, + 64.363998 -24.7675 -171.87399, + 63.9268 -23.9821 -173.241, + 63.9389 -23.751499 -173.328, + 64.224998 -22.7481 -173.19299, + 64.664101 -27.3491 -169.03999, + 64.703102 -26.3587 -169.77299, + 64.184601 -28.101299 -169.82401, + 64.252701 -27.0264 -170.59399, + 64.574402 -29.035999 -167.492, + 64.6222 -28.2243 -168.28999, + 64.971199 -28.0723 -166.76601, + 64.946098 -28.731001 -165.97701, + 64.5187 -29.7876 -166.64101, + 64.027802 -29.951799 -168.181, + 64.111397 -29.057699 -169.03101, + 65.292503 25.9846 -165.427, + 65.031998 25.5501 -169.037, + 65.227203 24.8517 -168.153, + 65.223 25.6439 -167.522, + 64.709503 26.230101 -169.897, + 65.184303 28.7649 -163.411, + 65.1744 29.025999 -162.75301, + 64.895798 29.7033 -164.636, + 64.8619 30.1231 -163.87601, + 65.292503 27.1514 -163.511, + 65.192802 28.440201 -164.07899, + 65.292503 26.836599 -164.147, + 65.292503 27.376699 -162.936, + 65.219704 28.8328 -162.04601, + 65.292503 27.614901 -162.02699, + 65.292503 27.628 -161.951, + 65.292503 25.479 -166.021, + 59.3936 -36.7211 -32.6824, + 58.251598 -37.128399 -27.1187, + 22.1278 -50.6008 1.93593, + 58.168301 -37.161499 -27.117901, + 58.964699 -36.9021 -32.827702, + 58.450001 -37.044899 -27.1276, + 60.668701 -35.457298 -27.6112, + 61.014301 -35.774601 -132.826, + 64.666901 -31.0548 -133.854, + 64.641296 -31.122999 -129.625, + 64.748802 -30.8256 -129.939, + 64.803101 -30.663401 -37.9021, + 64.747597 -30.7749 -34.682301, + 64.795097 -30.550301 -34.539501, + 64.891296 -30.4048 -35.647099, + 64.738701 -30.8538 -51.789902, + 64.666901 -31.0548 -55.734299, + 64.748802 -30.8256 -51.819599, + 64.686203 -30.9958 -34.8242, + 64.350502 -31.810301 -134.382, + 64.340797 -31.858601 -37.9021, + 64.189102 -32.1395 -162.271, + 64.201202 -32.112598 -162.269, + 64.617699 -31.184299 -162.21201, + -7.0763698 37.2062 34.270901, + -7.07762 37.127998 34.276901, + -24.645201 37.481602 24.645201, + -21.704399 37.2062 27.449699, + -21.7082 37.127998 27.454599, + -24.748699 37.127998 24.748699, + -26.457899 37.127998 22.828199, + 61.6031 -35.330601 -133.592, + 61.289398 -35.5756 -162.464, + 62.1796 -34.823601 -162.424, + 61.844799 -35.127499 -129.724, + 62.013199 -34.972198 -30.917999, + 61.847 -35.145199 -31.1026, + 62.168201 -34.784 -30.7328, + 62.317402 -34.709599 -31.5522, + 64.217903 -32.077202 -33.8158, + 64.155998 -32.213501 -33.912201, + 63.523499 -33.2673 -32.948799, + 63.767899 -32.9081 -33.551899, + 63.908699 -32.427601 -32.3274, + 64.001404 -32.0592 -32.0839, + 64.408501 -31.5042 -33.427799, + 64.324898 -31.7957 -33.621899, + 60.148399 -34.8368 -25.5068, + 60.0443 35.1912 -25.6423, + 61.062599 34.549702 -27.0651, + 59.9146 35.505402 -25.793301, + 65.096199 -29.1187 -35.371201, + 65.091797 -28.9674 -35.274601, + 64.9851 -29.0711 -34.5896, + 64.828598 -30.323 -34.396198, + 65.240501 -28.513599 -36.732399, + 65.0858 -29.4233 -35.563099, + 65.231499 -28.6672 -36.826199, + 65.0942 -29.2708 -35.4674, + 65.222198 -28.309099 -36.313301, + 65.292503 -27.6008 -37.9021, + 65.2481 -28.5418 -37.9021, + 64.494598 31.542101 -134.19901, + 64.201202 32.167301 -162.269, + 65.070999 29.7038 -36.225201, + 65.0858 29.4505 -35.563099, + 65.231499 28.694401 -36.826199, + -3.0504501 37.127998 34.866798, + 1.01797 -37.1008 34.985199, + -1.1233701 37.127998 34.922901, + 1.11709 -43.338299 34.982201, + 3.9212201 -43.338299 34.779598, + 4.6480899 0.027366193 34.689999, + -1.12508 -0.00013393155 34.981899, + -1.69426 -43.338299 34.959, + 0.301099 -44.338299 34.998699, + -1.12508 0.027366206 34.981899, + 8.1108398 -44.338299 34.047199, + 6.7000499 -43.338299 34.352699, + 4.23279 -44.338299 34.743099, + 9.05867 -37.1008 33.8074, + 9.4356604 -43.338299 33.704102, + 11.8861 -44.338299 32.919899, + 9.05867 37.127998 33.8074, + 4.9966798 -50.6008 21.643, + 62.222801 -28.774401 -172.741, + 63.579601 -28.8088 -170.56, + 62.701199 -30.553801 -170.36099, + 62.523102 -31.5814 -169.409, + 61.8232 -31.193899 -170.92999, + 62.029598 -30.050699 -171.854, + 62.857899 -29.4617 -171.241, + 63.4678 -29.8381 -169.72501, + 63.340401 -30.804899 -168.82401, + 63.131302 -26.994301 -172.828, + 62.540401 -26.1187 -174.19, + 62.390701 -27.469 -173.51401, + 63.244301 -25.702499 -173.47701, + 63.004299 -28.2423 -172.08701, + 63.7743 -26.4757 -172.078, + 63.683998 -27.657 -171.368, + 65.0597 23.618401 -170.187, + 65.0466 24.6115 -169.642, + 64.742104 25.207001 -170.52901, + 64.803596 22.723801 -171.69501, + 64.813202 22.254299 -171.86501, + 65.062599 23.376301 -170.306, + 65.074203 22.3102 -170.77299, + 64.383499 24.347099 -172.093, + 64.428902 23.1236 -172.586, + 64.777702 23.870399 -171.215, + 64.771301 24.131599 -171.092, + 64.3722 24.626499 -171.966, + 64.224998 22.8029 -173.19299, + 63.9543 23.505199 -173.437, + 63.884499 24.8008 -172.92799, + 64.875504 13.2832 -174.30901, + 65.184402 15.6294 -172.30099, + 64.886299 10.5748 -174.82001, + 65.292503 12.6584 -171.521, + 65.292503 15.2514 -170.884, + 65.292503 10.0744 -172.043, + 65.292503 14.0274 -171.185, + 65.187698 12.9741 -172.92999, + 65.190399 10.3271 -173.446, + 65.195198 0.027368007 -174.35201, + 64.905098 0.027370805 -175.716, + 65.195 1.98204 -174.319, + 65.292503 1.93308 -172.92599, + 26.5431 34.627998 -201.881, + 26.814301 34.627998 -201.63, + 26.7146 34.353001 -202.09599, + 34.378201 26.178301 -206.55, + 25.9042 34.627998 -202.25, + 26.237499 34.627998 -202.09, + 21.1117 35.836899 -203.121, + 26.0047 34.353001 -202.506, + 65.185997 -14.3299 -172.60899, + 65.292503 -13.981 -171.196, + 65.292503 -16.034599 -170.655, + 65.183197 -16.432501 -172.07401, + 64.868896 -14.6713 -173.992, + 64.900597 -5.0980802 -175.502, + 64.417999 -5.2151699 -176.815, + 64.4254 -2.6157 -176.97301, + 64.903999 -2.5562899 -175.662, + 65.192703 -7.4124799 -173.87601, + 64.888 -10.0304 -174.89999, + 64.389999 -10.2571 -176.217, + 64.406097 -7.7655902 -176.56, + 64.895203 -7.59267 -175.245, + 64.879097 -12.3971 -174.478, + 65.190804 -9.7940397 -173.52699, + 65.188599 -12.1068 -173.10001, + 65.292503 -4.8517499 -172.741, + 65.292503 -9.5527296 -172.12601, + 65.292503 -7.2286201 -172.479, + 65.292503 0.027376398 -172.96001, + 65.292503 -2.43137 -172.90401, + 65.194 -4.97614 -174.13499, + 65.194901 -2.4944501 -174.297, + 29.267401 5.9812398 -220.078, + 44.0867 5.6989498 -206.55, + 43.355499 9.4393797 -206.55, + 42.2673 13.0919 -206.55, + 28.369499 8.8627396 -220.078, + 29 -0.00013393749 -220.078, + 23.201799 -17.0802 -220.078, + 28.369499 -8.8629999 -220.078, + 29.9937 -0.00013393949 -220.078, + 29.811399 3.0125201 -220.078, + 28.652399 7.9548202 -220.078, + 22.3871 -15.6496 -220.078, + 19.432699 -16.1705 -220.078, + -31.587999 37.481602 14.7298, + -32.964298 37.573502 10.9232, + -33.027802 37.532501 10.9442, + -31.534 37.532501 14.7045, + -33.223499 37.127998 11.0091, + -34.009602 37.573502 7.0224099, + -34.594799 37.573502 3.02666, + -34.779202 37.532501 -1.01197, + -34.712299 37.573502 -1.01002, + -34.930698 37.355 -1.01638, + -34.904202 37.127998 1.76605, + -34.866798 37.127998 3.0504401, + -34.985199 37.127998 -1.01796, + -34.955299 0.0273662 1.76754, + -34.133499 37.481602 7.0479898, + -34.720901 37.481602 3.0376899, + -34.771702 37.421902 3.04213, + -34.661499 37.532501 3.03249, + -34.0751 37.532501 7.0359402, + -33.084499 37.481602 10.963, + 56.148701 37.591301 -162.563, + 16.3183 37.627998 -203.121, + -33.8638 37.621799 6.9923201, + -34.446602 37.621799 3.01368, + -33.7873 37.627998 6.97651, + -33.938599 37.6035 7.00775, + -32.823101 37.621799 10.8764, + -33.132801 37.421902 10.979, + -27.449699 37.2062 21.704399, + -27.339701 37.481602 21.617399, + -24.6812 37.421902 24.6812, + -29.742701 37.355 18.3456, + -31.6714 37.355 14.7686, + -27.379601 37.421902 21.649, + -29.7078 37.421902 18.323999, + -27.4118 37.355 21.6744, + -31.634199 37.421902 14.7513, + -31.4076 37.6035 14.6456, + -31.338499 37.621799 14.6134, + -32.8955 37.6035 10.9004, + -29.5567 37.573502 18.2309, + -31.473301 37.573502 14.6763, + -29.495001 37.6035 18.192801, + -29.613701 37.532501 18.266001, + -24.5557 37.573502 24.5557, + -27.2929 37.532501 21.5804, + -27.2404 37.573502 21.5389, + -24.603001 37.532501 24.603001, + -21.5804 37.532501 27.2929, + 57.573399 37.364399 -32.8363, + 57.185501 37.447201 -162.556, + 57.518398 37.377102 -32.822498, + 55.2925 37.627998 -162.931, + 55.398701 37.627399 -30.5196, + 60.1749 36.072201 -27.8463, + 59.934399 36.069599 -27.0867, + 59.583698 36.080101 -26.135, + 61.398201 35.5476 -55.250599, + 61.4823 35.482101 -51.9585, + 61.398201 35.5476 -133.37, + 61.377102 35.563801 -52.0783, + 61.1124 35.759998 -52.434399, + 61.1703 35.718201 -37.9021, + 60.718399 36.028 -131.771, + 60.737099 36.0159 -53.917, + 60.718399 36.028 -53.6521, + 56.2355 37.5783 -25.097401, + 56.6544 37.545502 -25.600401, + 56.613201 37.503399 -24.544901, + 56.0797 37.484402 -23.496099, + 58.251598 37.155602 -27.1187, + 58.964699 36.929401 -32.827702, + 59.726002 36.311199 -27.2899, + 59.6991 36.381001 -27.5103, + 59.404099 36.564701 -27.3673, + 58.135201 37.123699 -26.0882, + 57.118301 37.284599 -24.1782, + 56.867401 37.409698 -24.3613, + 57.538101 37.2845 -25.230499, + 57.631001 37.346001 -26.474899, + 57.748402 37.319901 -27.164301, + 57.700802 37.334702 -27.1695, + 57.884998 37.2495 -26.2824, + 57.2883 37.394402 -25.4174, + 58.168301 37.188702 -27.117901, + 57.036701 37.474602 -25.6026, + 62.062801 33.8554 -28.428801, + 62.477798 33.467701 -28.9417, + 64.111504 32.326 -162.27901, + 64.181198 32.124001 -162.839, + 63.949902 32.625999 -134.618, + 64.072502 32.414501 -134.582, + 63.808399 32.870098 -134.66, + 63.8363 32.8246 -128.88699, + 64.431801 31.6817 -134.276, + 64.189102 32.194199 -162.271, + 64.056396 31.705799 -31.847799, + 64.502403 30.9268 -33.045101, + 62.882401 34.108101 -31.8566, + 63.7024 32.974998 -32.700001, + 63.206799 33.542198 -31.3953, + 63.109699 33.740002 -31.548401, + 63.4254 32.903301 -30.9482, + 63.848701 32.633099 -32.451, + 63.7798 32.806599 -32.575298, + 64.217903 32.104401 -33.8158, + -7.34796 37.627998 33.687698, + -3.0499101 37.2062 34.860699, + -3.0483201 37.282501 34.8424, + -3.0457001 37.355 34.8125, + -7.00775 37.6035 33.938599, + 9.4479599 37.627998 33.152599, + 12.7376 37.627998 32.0625, + 8.9292603 37.627998 33.324402, + 24.975 0.027366202 24.520399, + 23.986601 -43.338299 25.4881, + 23.2679 -37.1008 26.145901, + 22.1269 -44.338299 27.1182, + 21.863501 -43.338299 27.3311, + 20.598499 0.027366199 28.2967, + 61.327702 35.2813 -164.28999, + 60.034801 36.087799 -164.48801, + 59.734798 36.432301 -163.614, + 62.363602 34.6991 -37.9021, + 62.317402 34.7369 -31.5522, + 62.356201 34.692101 -162.414, + 62.1796 34.8783 -162.424, + 62.308201 34.628201 -163.28999, + 62.845901 34.181301 -134.47301, + 63.345798 33.449402 -163.077, + 63.458698 33.143101 -163.765, + 62.4781 34.292 -164.047, + 65.2173 -26.4492 -166.71201, + 64.992699 -27.350401 -167.513, + 65.011597 -26.562901 -168.22099, + 65.2118 -27.0762 -166.015, + 65.222 -25.7537 -167.37801, + 65.292503 -26.0637 -165.25301, + 65.292503 -25.7729 -165.608, + 65.292503 -25.5343 -165.899, + 64.996498 27.2589 -167.653, + 65.218201 26.375601 -166.843, + 65.213402 26.970699 -166.20399, + 65.015503 26.432899 -168.373, + 64.630699 28.115801 -168.438, + 64.672798 27.1999 -169.2, + 64.953903 28.597 -166.215, + 65.207497 27.5317 -165.508, + 65.200699 28.021 -164.798, + 64.977203 27.941299 -166.96899, + 64.927101 29.183599 -165.438, + 64.587799 28.8808 -167.709, + 64.536102 29.6257 -166.899, + 60.879799 -35.866798 -132.55, + 60.542198 -36.112 -31.7952, + 58.887699 -36.833401 -27.192301, + 58.819099 -36.871399 -27.1728, + 59.243 -36.636501 -27.2931, + 61.3424 -35.554501 -30.6623, + 59.6991 -36.353802 -27.5103, + 59.262402 -36.625702 -27.298599, + 59.697201 -36.5756 -32.5201, + 58.3876 -37.0742 -27.1199, + 59.833401 -36.5103 -32.4473, + 59.549099 -36.646599 -32.5993, + 59.550301 -36.648998 -37.9021, + 58.638401 -36.267101 -24.354601, + 58.805698 -35.9925 -24.208599, + 59.760601 -35.7757 -25.958099, + 61.229401 -35.079201 -28.297501, + 60.955101 -34.849701 -27.2349, + 61.864899 -34.507198 -28.864401, + 61.062599 -34.5224 -27.0651, + 61.364498 -34.785999 -28.0994, + 60.0443 -35.163898 -25.6423, + 59.9146 -35.478199 -25.793301, + 60.823399 -35.162399 -27.4175, + 64.434502 -31.624399 -129.26199, + 64.413399 -31.700701 -34.581799, + 64.407204 -31.6868 -129.224, + 64.502701 -31.4683 -129.356, + 64.524902 -31.415501 -134.151, + -24.7314 37.282501 24.7314, + -24.710199 37.355 24.710199, + -24.7444 37.2062 24.7444, + -27.4354 37.282501 21.6931, + -27.0623 37.627998 21.3981, + -24.4505 37.621799 24.4505, + -24.5044 37.6035 24.5044, + -22.496901 37.627998 26.0846, + -24.395201 37.627998 24.395201, + -27.123699 37.621799 21.4466, + -27.1835 37.6035 21.493999, + -26.83 37.627998 21.659201, + -10.8764 37.621799 32.823101, + -14.6456 37.6035 31.4076, + -18.370899 37.2062 29.7838, + -7.07267 37.282501 34.252998, + -7.0665998 37.355 34.223598, + 62.439701 -34.364601 -30.364599, + 63.001301 -33.9016 -31.7024, + 63.616798 -33.1105 -32.8246, + 62.062801 -33.828098 -28.428801, + 61.145199 -34.183998 -26.909401, + 62.145 -33.1185 -28.060801, + 62.146599 -33.104599 -28.053699, + 62.3451 -34.003101 -29.289101, + 61.364498 34.813202 -28.0994, + 60.955101 34.8769 -27.2349, + 60.823399 35.189602 -27.4175, + 64.946899 30.234301 -131.771, + -31.7152 37.2062 14.789, + -31.698601 37.282501 14.7813, + -33.217602 37.2062 11.0071, + -31.7208 37.127998 14.7916, + -32.432598 37.127998 13, + -29.890699 37.127998 18.185801, + -29.7838 37.2062 18.371, + -29.768299 37.282501 18.3613, + -34.270901 37.2062 7.0763698, + -33.200298 37.282501 11.0014, + -34.8424 37.282501 3.04831, + -34.860699 37.2062 3.0499101, + -34.960701 37.282501 -1.01726, + 55.982601 37.604198 -162.575, + 55.985802 37.603901 -31.826799, + 56.068802 37.597801 -162.56599, + 58.656799 34.988998 -22.971901, + 59.161201 35.104301 -23.863899, + 59.228401 34.7831 -23.7834, + 60.3064 33.845699 -25.201099, + 60.279099 34.187302 -25.2857, + 58.7076 34.669998 -22.918699, + 59.288399 34.142399 -23.6749, + 59.270401 34.461201 -23.7206, + 55.2925 37.627998 -28.3792, + 55.358299 37.6278 -29.819, + 55.2925 37.627998 -37.9021, + 61.1329 35.651901 -29.7409, + 61.147301 35.660599 -29.8594, + 59.759899 36.343102 -27.539801, + 60.737099 36.0159 -132.036, + 61.105598 35.764801 -132.978, + 61.072601 35.7883 -37.9021, + 61.1124 35.759998 -130.554, + 60.98 35.8531 -130.77901, + 55.767502 37.579601 -23.714701, + 56.359299 37.566601 -24.726601, + 56.088299 37.589802 -24.9207, + 55.789001 37.6157 -28.4851, + 55.945 37.606701 -31.7745, + 55.424801 37.627102 -29.369301, + 55.812599 37.614498 -162.614, + 56.060799 37.5984 -28.1166, + 56.103401 37.5951 -28.068501, + 55.4953 37.6259 -30.9184, + 55.646301 37.6217 -162.681, + 55.4809 37.626202 -162.77901, + 58.450001 37.072102 -27.1276, + 58.6978 36.9338 -26.9188, + 58.3876 37.101398 -27.1199, + 59.833401 36.537498 -32.4473, + 59.262402 36.652901 -27.298599, + 57.062199 36.881699 -22.8081, + 59.170799 36.562 -26.516399, + 59.386299 36.334 -26.321899, + 56.2029 37.4468 -23.4098, + 31.9499 37.591999 14.8399, + 56.655102 37.2075 -23.093201, + 32.0042 37.561001 14.878, + 28.446699 37.573502 19.9186, + 32.113201 37.449402 14.9543, + 32.088001 37.480202 14.9366, + 32.062698 37.511002 14.9189, + 58.347301 35.922298 -23.240499, + 58.805698 36.019699 -24.208599, + 58.949501 35.727001 -24.0772, + 57.698502 36.031502 -22.3626, + 59.068199 35.420399 -23.962, + 58.580101 35.307098 -23.0432, + 57.8312 35.730301 -22.269699, + 57.919399 35.529999 -22.207899, + 61.864899 34.534401 -28.864401, + 62.439701 34.3918 -30.364599, + 62.310799 34.608398 -30.547899, + 62.168201 34.811199 -30.7328, + 61.527599 35.410198 -30.461901, + 61.1007 35.632301 -29.4757, + 62.652599 33.921398 -30.006901, + 62.554001 34.162399 -30.183901, + 63.292198 33.3363 -31.243799, + 63.365101 33.123001 -31.094601, + 62.735001 33.670101 -29.834801, + 62.3451 34.030399 -29.289101, + 64.369499 31.824301 -37.9021, + 64.479897 31.5765 -129.321, + 64.202599 32.1679 -37.9021, + 64.001404 32.086498 -32.0839, + 63.908699 32.454899 -32.3274, + 64.324898 31.823 -33.621899, + 64.686203 31.0231 -34.8242, + 64.795097 30.577499 -34.539501, + 64.467903 31.231899 -33.235001, + 64.828598 30.350201 -34.396198, + 65.049599 29.755699 -35.751801, + 64.408501 31.531401 -33.427799, + 64.747597 30.802099 -34.682301, + 65.021896 29.907801 -35.844501, + 63.523499 33.294601 -32.948799, + 63.001301 33.928799 -31.7024, + 63.616798 33.137798 -32.8246, + 64.155998 32.240799 -33.912201, + 43.771099 37.627998 -19.5525, + 42.3172 37.627998 -5.5167098, + 52.145199 37.627998 -19.5525, + 55.2925 37.627998 -24.0473, + 31.1227 37.627998 15.7011, + 55.667099 37.6227 -24.415001, + 31.8361 37.6241 14.7603, + 20.698601 37.627998 21.659201, + 13.4051 37.627998 23.125601, + 20.698601 37.627998 13.9053, + 15.5649 37.627998 26.8664, + 30.569599 37.627998 -0.38233599, + -7.0479999 37.481602 34.133499, + -6.9923201 37.621799 33.863899, + 25.0089 37.627998 23.6989, + 32.154202 37.377998 14.983, + 26.145901 37.127998 23.267799, + 60.792702 35.959499 -162.481, + 61.094299 35.630901 -163.47, + 60.3255 36.2691 -162.49699, + 61.289398 35.630299 -162.464, + 62.481602 34.574501 -129.26601, + 62.367401 34.695202 -129.33099, + 62.741699 34.2995 -50.999199, + 62.396801 34.665699 -37.9021, + 62.741699 34.2995 -129.118, + 62.777401 34.259499 -134.44099, + 62.777401 34.259499 -56.3223, + 62.753601 34.277302 -32.0103, + 62.845901 34.181301 -56.354, + 60.9659 -35.8349 -31.004601, + 61.048 -35.7785 -30.7848, + 60.867001 -35.902802 -31.269501, + 61.0425 -35.782299 -37.9021, + 60.730598 -35.965401 -131.985, + 60.787399 -35.955799 -31.4238, + 60.7882 -35.9277 -132.283, + 60.7188 -35.973 -131.729, + 60.3255 -36.214401 -162.49699, + 58.135201 -37.0965 -26.0882, + 58.9403 -36.7351 -26.7162, + 58.6978 -36.906502 -26.9188, + 31.727301 -44.338299 14.7775, + 59.583698 -36.052898 -26.135, + 58.449501 -36.5196 -24.5135, + 61.073299 -35.354301 -28.503901, + -10.8518 37.627998 32.748901, + -10.9004 37.6035 32.8955, + -21.617399 37.481602 27.339701, + -21.6744 37.355 27.4118, + -21.6931 37.282501 27.435301, + -21.649 37.421902 27.379601, + -18.1528 37.621799 29.430099, + -14.6134 37.621799 31.338499, + -14.5803 37.627998 31.267599, + -18.1117 37.627998 29.363501, + -21.3981 37.627998 27.0623, + -21.4466 37.621799 27.123699, + -18.2309 37.573502 29.5567, + -18.266001 37.532501 29.613701, + -18.192801 37.6035 29.495001, + -21.5389 37.573502 27.2404, + -21.493999 37.6035 27.1835, + -14.7916 37.127998 31.7208, + -12.4024 37.127998 32.669998, + -11.0071 37.2062 33.217701, + -14.789 37.2062 31.7152, + -12.4227 0.0273662 32.721199, + -12.6507 -43.338299 32.633701, + -14.7916 -37.1008 31.7208, + -14.9686 -44.338299 31.6376, + -15.2291 -43.338299 31.5131, + -17.639 0.027366206 30.2302, + -18.374201 37.127998 29.789101, + -7.05831 37.421902 34.183399, + 63.848701 -32.605801 -32.451, + 63.365101 -33.095798 -31.094601, + 62.652599 -33.8941 -30.006901, + 63.206799 -33.514999 -31.3953, + 63.7798 -32.7794 -32.575298, + 63.7024 -32.9478 -32.700001, + 63.109699 -33.7127 -31.548401, + 63.292198 -33.309101 -31.243799, + 62.554001 -34.135201 -30.183901, + 62.848701 -33.115398 -29.509199, + 62.477798 -33.440498 -28.9417, + 62.735001 -33.642799 -29.834801, + 63.4254 -32.875999 -30.9482, + 63.5065 -32.421001 -30.666901, + 62.893398 -32.565498 -29.2145, + 64.606102 31.2665 -51.433998, + 64.479897 31.5765 -51.202, + 64.494598 31.542101 -56.080101, + 64.411499 31.718201 -34.564201, + 64.787201 30.7131 -162.177, + 64.747597 30.8839 -129.93401, + -34.223499 37.355 7.0665898, + -34.8125 37.355 3.0457101, + -34.183399 37.421902 7.05831, + -34.252998 37.282501 7.07267, + -33.171799 37.355 10.9919, + 32.209 37.127998 15.0214, + 58.147202 34.452499 -22.048401, + 58.733601 34.3545 -22.883101, + 58.1595 34.127998 -22.039801, + 58.738098 34.045799 -22.865999, + 28.6703 37.127998 20.075199, + 28.6653 37.2062 20.0716, + 33.8302 36.612499 12.7062, + 60.995998 35.638901 -29.0797, + 60.388 35.936401 -28.055599, + 61.009499 35.6362 -29.1203, + 60.9739 35.646 -29.025999, + 60.771999 35.993099 -53.203602, + 60.771999 35.993099 -131.323, + 60.916 35.896999 -54.513901, + 60.787399 35.983002 -31.4238, + 60.98 35.8531 -52.660198, + 58.887699 36.8606 -27.192301, + 58.9403 36.762299 -26.7162, + 58.819099 36.898602 -27.1728, + 59.243 36.6637 -27.2931, + 61.048 35.805698 -30.7848, + 58.018398 36.973999 -24.8608, + 57.7826 37.144402 -25.0441, + 58.378399 36.968201 -25.8946, + 58.611198 36.783199 -25.7038, + 58.241798 36.7743 -24.6831, + 57.362202 37.127602 -23.9984, + 57.5952 36.939602 -23.8244, + 31.9118 37.606899 14.8132, + 31.939501 37.597801 14.8327, + 28.400499 37.596901 19.8862, + 58.0135 36.477798 -23.5054, + 57.4095 36.4883 -22.565001, + 57.813499 36.722198 -23.659201, + 58.192299 36.209801 -23.3652, + 58.638401 36.2943 -24.354601, + 58.449501 36.546902 -24.5135, + 61.073299 35.3815 -28.503901, + 61.229401 35.1064 -28.297501, + 60.668701 35.4846 -27.6112, + 61.553699 35.1478 -29.350599, + 60.4925 35.758999 -27.813999, + 64.300903 31.9695 -129.11301, + 64.3209 31.9277 -134.411, + 64.3209 31.9277 -56.292, + 64.300903 31.9695 -50.993599, + 64.293602 31.9846 -134.436, + 64.293602 31.9846 -56.3172, + 19.788401 37.627998 28.2607, + 31.7994 37.627998 14.7346, + 28.2607 37.627998 19.788401, + 18.996901 37.627998 28.749001, + 5.0717201 37.2062 34.624401, + 1.0172499 37.282501 34.960701, + 1.01779 37.2062 34.979, + 1.01797 37.127998 34.985199, + 5.0726199 37.127998 34.630501, + -3.01369 37.621799 34.446602, + 1.00342 37.627998 34.485401, + -3.00687 37.627998 34.368698, + 16.373699 37.627998 30.367001, + 12.7665 37.621799 32.135201, + 28.501499 37.532501 19.957001, + 23.2679 37.127998 26.145901, + 15.6407 37.127998 31.259501, + 16.611 37.127998 30.806999, + 63.6432 33.128101 -56.550098, + 63.808399 32.870098 -56.5406, + 63.8363 32.8246 -50.768002, + 63.6152 33.1717 -134.67101, + 63.6432 33.128101 -134.66901, + 63.6152 33.1717 -56.5518, + 63.331402 33.571098 -32.959301, + 58.018398 -36.9468 -24.8608, + 58.241798 -36.747101 -24.6831, + 33.187199 -44.338299 11.118, + 58.611198 -36.755901 -25.7038, + 58.378399 -36.940899 -25.8946, + 61.147301 -35.6334 -29.8594, + 61.527599 -35.382999 -30.461901, + 61.133499 -35.699299 -30.339899, + -10.9442 37.532501 33.027802, + -14.7045 37.532501 31.534, + -14.6763 37.573502 31.4734, + -10.9232 37.573502 32.964298, + -7.0359402 37.532501 34.0751, + -7.0224099 37.573502 34.009602, + -18.323999 37.421902 29.7078, + -10.979 37.421902 33.132801, + -18.2973 37.481602 29.6644, + -14.7297 37.481602 31.587999, + -10.963 37.481602 33.084499, + -14.7686 37.355 31.6714, + -14.7813 37.282501 31.698601, + -18.3613 37.282501 29.768299, + -18.3456 37.355 29.742701, + -14.7513 37.421902 31.634199, + -10.9919 37.355 33.171799, + -11.0014 37.282501 33.200298, + 64.946899 30.234301 -53.651798, + 64.943298 30.247601 -132.108, + 64.931297 30.2913 -131.16901, + 64.895798 30.416599 -130.743, + 64.854202 30.5562 -133.11099, + 64.8312 30.630301 -130.298, + 64.868797 30.508101 -133.015, + 64.972198 30.138599 -162.13901, + 64.681602 31.0695 -133.814, + 64.781097 30.785 -55.361, + 64.781097 30.785 -133.48, + 64.747597 30.8839 -51.815201, + 58.069401 34.998798 -22.1029, + 60.7584 35.73 -28.569401, + 60.6451 35.7855 -28.379299, + 60.857601 35.683399 -28.7444, + 60.682098 35.7658 -28.434799, + 60.8979 35.6362 -28.7166, + 60.854599 35.9384 -131.056, + 60.867001 35.930099 -31.269501, + 60.916 35.896999 -132.633, + 60.854599 35.9384 -52.937, + 60.803699 35.972198 -132.33701, + 60.7929 35.979401 -132.3, + 60.7929 35.979401 -54.180901, + 22.987499 37.621799 25.830799, + 25.7724 37.627998 22.935499, + 22.935499 37.627998 25.7724, + 23.0382 37.6035 25.8878, + 19.8333 37.621799 28.3248, + 28.3318 37.619801 19.8381, + 28.3248 37.621799 19.8333, + 31.8706 37.620399 14.7844, + 28.3873 37.6035 19.877001, + 25.8878 37.6035 23.0382, + 25.830799 37.621799 22.987499, + 8.9692497 37.6035 33.473701, + 1.01519 37.421902 34.889702, + -3.04213 37.421902 34.771702, + 5.0690699 37.282501 34.606201, + 1.01638 37.355 34.930698, + 5.0647202 37.355 34.5765, + 9.05233 37.282501 33.783798, + 12.9021 37.355 32.476501, + -3.02666 37.573502 34.594799, + 20.020399 37.421902 28.5921, + 16.5851 37.355 30.7591, + 26.074499 37.421902 23.204399, + 23.204399 37.421902 26.074499, + 28.6145 37.3773 20.0361, + 28.5921 37.421902 20.020399, + 28.5504 37.481602 19.991199, + 23.1308 37.532501 25.991899, + 23.086399 37.573502 25.9419, + 23.1705 37.481602 26.036501, + 25.9419 37.573502 23.086399, + 25.991899 37.532501 23.1308, + 26.036501 37.481602 23.1705, + 23.2516 37.282501 26.1276, + 20.0439 37.355 28.6257, + 23.2316 37.355 26.1052, + 26.1052 37.355 23.2316, + 20.0716 37.2062 28.6653, + 20.579 37.127998 28.271999, + 20.075199 37.127998 28.6703, + 23.2638 37.2062 26.1413, + 20.0611 37.282501 28.650299, + 16.5994 37.282501 30.7855, + 28.650299 37.282501 20.0611, + 26.1413 37.2062 23.2638, + 28.663601 37.214699 20.070499, + 26.1276 37.282501 23.2516, + 28.6257 37.355 20.0439, + 32.184299 37.299 15.0041, + 32.191799 37.265099 15.0093, + 32.2019 37.218899 15.0164, + 32.202801 37.214802 15.017, + 12.9199 37.2062 32.5214, + 16.608101 37.2062 30.8016, + 12.9222 37.127998 32.527199, + 12.9132 37.282501 32.504398, + 9.0570698 37.2062 33.801498, + 63.4939 33.349602 -50.760601, + 63.506901 33.330898 -37.9021, + 63.4939 33.349602 -128.88, + 63.597599 33.198002 -162.33099, + 63.370998 33.497002 -162.347, + 62.899101 34.119499 -162.383, + 61.553699 -35.120602 -29.350599, + 61.049599 -35.607201 -29.2766, + 61.009499 -35.608898 -29.1203, + 64.935799 30.2749 -53.1488, + 64.931297 30.2913 -53.049599, + 64.943298 30.247601 -53.9884, + 64.899002 30.4055 -52.660999, + 64.895798 30.416599 -52.623299, + 64.958397 30.1912 -37.9021, + 64.9151 30.349199 -54.4818, + 64.899002 30.4055 -130.78, + 64.9151 30.349199 -132.601, + 64.840202 30.601299 -52.228802, + 64.8312 30.630301 -52.178398, + 64.803101 30.718201 -37.9021, + 64.854202 30.5562 -54.992298, + 64.868797 30.508101 -54.895599, + 64.626701 31.215799 -129.591, + 64.617699 31.2391 -162.21201, + 64.633598 31.197901 -55.816502, + 64.633598 31.197901 -133.936, + 64.626701 31.215799 -51.471901, + 64.681602 31.0695 -55.694801, + 16.447001 37.6035 30.502899, + 19.877001 37.6035 28.3873, + 16.410801 37.621799 30.435801, + 12.7947 37.6035 32.2061, + 19.9186 37.573502 28.446699, + 16.4814 37.573502 30.5667, + 9.0053196 37.532501 33.608299, + 12.8214 37.573502 32.273499, + 8.9880104 37.573502 33.543701, + 5.0114899 37.621799 34.2131, + 8.9495001 37.621799 33.400002, + 1.9 37.627998 34.407001, + 5.0001502 37.627998 34.1357, + 6.4479599 37.627998 33.8368, + 9.0339499 37.421902 33.715199, + 5.0587802 37.421902 34.535999, + 9.0207596 37.481602 33.666, + 9.0445604 37.355 33.754799, + 1.01197 37.532501 34.779202, + -3.03249 37.532501 34.661499, + -3.0376899 37.481602 34.720901, + 1.01371 37.481602 34.838799, + 5.0513902 37.481602 34.4856, + 5.0427399 37.532501 34.426498, + 5.0330501 37.573502 34.360298, + 1.00792 37.6035 34.639801, + 1.0057 37.621799 34.563599, + -3.02034 37.6035 34.522598, + 1.01002 37.573502 34.712299, + 5.0225401 37.6035 34.288601, + 16.5415 37.481602 30.6782, + 16.565701 37.421902 30.723, + 19.991199 37.481602 28.5504, + 16.513201 37.532501 30.625601, + 19.957001 37.532501 28.501499, + 12.8461 37.532501 32.335602, + 12.8681 37.481602 32.391102, + 12.887 37.421902 32.4384, + 63.256302 33.6759 -56.499901, + 63.382702 33.505901 -37.9021, + 63.203098 33.745399 -50.8186, + 63.256302 33.6759 -134.619, + 63.203098 33.745399 -128.938, + 60.4925 -35.7318 -27.813999, + 61.1007 -35.605 -29.4757, + 59.726002 -36.284 -27.2899, + 59.386299 -36.306801 -26.321899, + 59.934399 -36.0424 -27.0867, + 60.1749 -36.044899 -27.8463, + 60.124699 -36.077702 -27.8092, + 59.759899 -36.315899 -27.539801, + 59.170799 -36.534801 -26.516399, + 60.9739 -35.618801 -29.025999, + 60.388 -35.909199 -28.055599, + 60.995998 -35.611698 -29.0797, + 60.745998 -35.708599 -28.547501, + 60.682098 -35.738602 -28.434799, + 60.6451 -35.758301 -28.379299, + 60.857601 -35.6562 -28.7444, + 60.8979 -35.609001 -28.7166 ] + + } + coordIndex [ 395, 185, 188, -1, 380, 199, 383, -1, + 53, 190, 179, -1, 558, 334, 54, -1, + 377, 613, 190, -1, 377, 621, 352, -1, + 945, 946, 153, -1, 349, 621, 945, -1, + 612, 190, 613, -1, 99, 392, 395, -1, + 391, 395, 392, -1, 268, 255, 256, -1, + 9, 170, 43, -1, 46, 601, 47, -1, + 5, 47, 601, -1, 14, 961, 2, -1, + 14, 2, 197, -1, 6, 125, 816, -1, + 6, 126, 125, -1, 139, 500, 105, -1, + 732, 844, 735, -1, 335, 54, 53, -1, + 335, 53, 336, -1, 175, 377, 352, -1, + 341, 946, 947, -1, 341, 947, 568, -1, + 11, 383, 199, -1, 11, 199, 184, -1, + 183, 185, 11, -1, 183, 11, 184, -1, + 168, 47, 5, -1, 168, 5, 8, -1, + 332, 374, 333, -1, 373, 334, 333, -1, + 373, 333, 374, -1, 0, 267, 1, -1, + 0, 99, 267, -1, 0, 1, 99, -1, + 390, 392, 99, -1, 390, 99, 1, -1, + 7, 1, 267, -1, 7, 267, 268, -1, + 7, 390, 1, -1, 63, 601, 15, -1, + 63, 15, 197, -1, 196, 2, 961, -1, + 196, 197, 2, -1, 12, 20, 21, -1, + 12, 9, 43, -1, 12, 21, 19, -1, + 12, 48, 9, -1, 12, 601, 46, -1, + 12, 46, 48, -1, 313, 76, 17, -1, + 313, 17, 316, -1, 222, 17, 76, -1, + 222, 14, 197, -1, 16, 197, 15, -1, + 16, 222, 197, -1, 16, 17, 222, -1, + 18, 380, 19, -1, 58, 19, 380, -1, + 3, 15, 601, -1, 3, 601, 12, -1, + 3, 12, 19, -1, 3, 19, 58, -1, + 3, 385, 15, -1, 3, 58, 385, -1, + 4, 5, 601, -1, 4, 601, 600, -1, + 4, 600, 599, -1, 598, 4, 599, -1, + 598, 5, 4, -1, 598, 8, 5, -1, + 37, 69, 68, -1, 37, 68, 415, -1, + 73, 415, 68, -1, 73, 68, 419, -1, + 641, 356, 22, -1, 225, 76, 313, -1, + 225, 314, 282, -1, 225, 313, 314, -1, + 77, 232, 82, -1, 52, 395, 186, -1, + 26, 288, 148, -1, 26, 148, 35, -1, + 30, 6, 816, -1, 30, 126, 6, -1, + 103, 89, 98, -1, 103, 29, 89, -1, + 114, 115, 812, -1, 121, 288, 259, -1, + 287, 288, 121, -1, 541, 516, 129, -1, + 541, 540, 516, -1, 120, 540, 123, -1, + 120, 516, 540, -1, 300, 735, 844, -1, + 300, 106, 735, -1, 300, 105, 106, -1, + 811, 812, 115, -1, 551, 117, 550, -1, + 140, 550, 117, -1, 149, 35, 148, -1, + 388, 268, 256, -1, 388, 7, 268, -1, + 388, 390, 7, -1, 855, 557, 1427, -1, + 10, 53, 179, -1, 10, 336, 53, -1, + 10, 179, 50, -1, 151, 558, 54, -1, + 151, 54, 335, -1, 370, 613, 377, -1, + 370, 377, 175, -1, 157, 352, 621, -1, + 157, 621, 346, -1, 345, 621, 349, -1, + 345, 346, 621, -1, 348, 349, 945, -1, + 78, 954, 40, -1, 39, 40, 356, -1, + 39, 78, 40, -1, 39, 422, 645, -1, + 161, 361, 22, -1, 161, 22, 356, -1, + 41, 168, 8, -1, 41, 8, 598, -1, + 41, 598, 363, -1, 41, 40, 168, -1, + 189, 40, 954, -1, 189, 168, 40, -1, + 167, 170, 9, -1, 167, 9, 48, -1, + 250, 336, 10, -1, 250, 10, 50, -1, + 369, 174, 173, -1, 180, 174, 50, -1, + 180, 50, 179, -1, 178, 612, 611, -1, + 178, 190, 612, -1, 181, 477, 478, -1, + 479, 375, 478, -1, 951, 54, 334, -1, + 951, 334, 373, -1, 57, 395, 400, -1, + 56, 383, 11, -1, 56, 400, 383, -1, + 56, 11, 185, -1, 681, 148, 288, -1, + 62, 601, 63, -1, 60, 63, 197, -1, + 968, 970, 62, -1, 968, 63, 60, -1, + 67, 20, 12, -1, 67, 12, 367, -1, + 44, 12, 43, -1, 44, 367, 12, -1, + 13, 961, 14, -1, 13, 222, 961, -1, + 13, 14, 222, -1, 317, 15, 385, -1, + 317, 16, 15, -1, 317, 316, 17, -1, + 317, 17, 16, -1, 202, 184, 199, -1, + 65, 66, 365, -1, 410, 365, 66, -1, + 404, 380, 18, -1, 404, 18, 19, -1, + 404, 20, 67, -1, 404, 199, 380, -1, + 404, 402, 199, -1, 404, 21, 20, -1, + 404, 19, 21, -1, 158, 358, 215, -1, + 158, 215, 641, -1, 158, 22, 361, -1, + 158, 641, 22, -1, 221, 961, 222, -1, + 428, 76, 225, -1, 227, 225, 282, -1, + 227, 631, 225, -1, 948, 954, 77, -1, + 81, 82, 232, -1, 23, 77, 82, -1, + 23, 82, 80, -1, 23, 80, 156, -1, + 23, 947, 948, -1, 23, 948, 77, -1, + 569, 568, 947, -1, 569, 947, 23, -1, + 569, 23, 156, -1, 241, 81, 448, -1, + 247, 695, 1109, -1, 247, 244, 695, -1, + 699, 1109, 695, -1, 251, 586, 85, -1, + 251, 842, 252, -1, 843, 732, 729, -1, + 843, 844, 732, -1, 843, 252, 842, -1, + 585, 85, 586, -1, 781, 254, 85, -1, + 781, 85, 585, -1, 779, 86, 254, -1, + 24, 186, 187, -1, 24, 52, 186, -1, + 24, 187, 52, -1, 90, 395, 52, -1, + 90, 29, 395, -1, 90, 52, 479, -1, + 90, 89, 29, -1, 90, 479, 476, -1, + 90, 476, 27, -1, 90, 27, 88, -1, + 25, 92, 26, -1, 25, 26, 35, -1, + 25, 388, 92, -1, 25, 35, 388, -1, + 470, 388, 256, -1, 470, 92, 388, -1, + 91, 470, 1308, -1, 1311, 1124, 288, -1, + 1311, 288, 26, -1, 1311, 26, 92, -1, + 471, 288, 1124, -1, 471, 472, 288, -1, + 815, 31, 816, -1, 486, 27, 476, -1, + 264, 96, 488, -1, 264, 111, 96, -1, + 264, 504, 111, -1, 28, 488, 96, -1, + 28, 486, 488, -1, 28, 88, 27, -1, + 28, 27, 486, -1, 95, 98, 89, -1, + 95, 89, 88, -1, 95, 88, 28, -1, + 95, 28, 96, -1, 271, 787, 255, -1, + 271, 255, 268, -1, 104, 103, 98, -1, + 104, 98, 474, -1, 104, 474, 1307, -1, + 100, 395, 29, -1, 100, 29, 103, -1, + 100, 101, 395, -1, 97, 30, 816, -1, + 97, 816, 31, -1, 97, 126, 30, -1, + 97, 111, 126, -1, 97, 815, 474, -1, + 97, 31, 815, -1, 765, 764, 875, -1, + 765, 869, 757, -1, 765, 875, 869, -1, + 481, 764, 763, -1, 797, 495, 108, -1, + 806, 495, 793, -1, 806, 108, 495, -1, + 277, 1315, 674, -1, 808, 311, 320, -1, + 808, 141, 311, -1, 118, 811, 115, -1, + 279, 140, 117, -1, 279, 117, 118, -1, + 279, 118, 114, -1, 279, 114, 812, -1, + 279, 282, 314, -1, 279, 314, 140, -1, + 281, 812, 813, -1, 258, 121, 259, -1, + 258, 518, 284, -1, 536, 123, 540, -1, + 442, 230, 286, -1, 291, 126, 526, -1, + 292, 125, 821, -1, 292, 816, 125, -1, + 292, 127, 816, -1, 539, 541, 667, -1, + 132, 1260, 1054, -1, 132, 302, 1260, -1, + 131, 297, 836, -1, 131, 133, 297, -1, + 514, 133, 131, -1, 514, 130, 294, -1, + 514, 131, 130, -1, 514, 294, 129, -1, + 514, 129, 509, -1, 135, 837, 836, -1, + 137, 836, 32, -1, 137, 32, 842, -1, + 835, 32, 836, -1, 835, 842, 32, -1, + 840, 300, 844, -1, 33, 139, 105, -1, + 33, 105, 300, -1, 33, 300, 139, -1, + 849, 86, 779, -1, 849, 545, 86, -1, + 143, 1336, 1337, -1, 34, 117, 551, -1, + 34, 551, 1342, -1, 34, 811, 117, -1, + 34, 1342, 811, -1, 144, 1333, 1336, -1, + 144, 1334, 1333, -1, 144, 142, 141, -1, + 144, 808, 1334, -1, 144, 141, 808, -1, + 549, 550, 140, -1, 147, 1074, 437, -1, + 147, 145, 149, -1, 318, 867, 325, -1, + 328, 35, 149, -1, 328, 388, 35, -1, + 328, 149, 145, -1, 324, 557, 855, -1, + 322, 850, 808, -1, 322, 320, 311, -1, + 883, 757, 869, -1, 559, 558, 151, -1, + 155, 80, 83, -1, 155, 156, 80, -1, + 155, 83, 343, -1, 155, 343, 562, -1, + 152, 153, 946, -1, 338, 153, 152, -1, + 590, 157, 346, -1, 154, 351, 348, -1, + 154, 945, 153, -1, 154, 348, 945, -1, + 38, 626, 209, -1, 38, 219, 626, -1, + 38, 39, 219, -1, 38, 78, 39, -1, + 36, 626, 219, -1, 36, 219, 69, -1, + 36, 69, 37, -1, 36, 37, 415, -1, + 36, 415, 626, -1, 208, 209, 626, -1, + 596, 38, 209, -1, 596, 78, 38, -1, + 425, 422, 39, -1, 425, 39, 356, -1, + 218, 219, 39, -1, 218, 39, 645, -1, + 159, 164, 163, -1, 362, 361, 161, -1, + 362, 164, 966, -1, 42, 364, 159, -1, + 42, 159, 163, -1, 42, 363, 364, -1, + 42, 41, 363, -1, 162, 356, 40, -1, + 162, 40, 41, -1, 162, 161, 356, -1, + 162, 42, 163, -1, 162, 41, 42, -1, + 169, 43, 170, -1, 169, 44, 43, -1, + 604, 184, 65, -1, 604, 65, 365, -1, + 604, 367, 44, -1, 604, 44, 169, -1, + 45, 168, 167, -1, 45, 46, 47, -1, + 45, 47, 168, -1, 45, 48, 46, -1, + 45, 167, 48, -1, 172, 607, 583, -1, + 609, 607, 172, -1, 609, 583, 457, -1, + 610, 174, 180, -1, 754, 336, 250, -1, + 249, 369, 459, -1, 49, 50, 174, -1, + 49, 250, 50, -1, 49, 249, 250, -1, + 49, 174, 369, -1, 49, 369, 249, -1, + 927, 175, 352, -1, 934, 924, 611, -1, + 177, 178, 611, -1, 177, 611, 924, -1, + 177, 924, 610, -1, 177, 610, 180, -1, + 372, 478, 375, -1, 372, 181, 478, -1, + 873, 181, 332, -1, 182, 479, 187, -1, + 182, 375, 479, -1, 51, 52, 187, -1, + 51, 187, 479, -1, 51, 479, 52, -1, + 191, 53, 54, -1, 191, 54, 951, -1, + 191, 190, 53, -1, 55, 56, 185, -1, + 55, 400, 56, -1, 55, 57, 400, -1, + 55, 185, 395, -1, 55, 395, 57, -1, + 399, 58, 380, -1, 399, 385, 58, -1, + 679, 1071, 194, -1, 679, 194, 681, -1, + 680, 679, 681, -1, 228, 437, 1074, -1, + 1072, 1074, 194, -1, 59, 970, 601, -1, + 59, 601, 62, -1, 59, 62, 970, -1, + 198, 60, 197, -1, 623, 196, 961, -1, + 623, 968, 60, -1, 623, 198, 196, -1, + 623, 60, 198, -1, 61, 62, 63, -1, + 61, 63, 968, -1, 61, 968, 62, -1, + 407, 204, 199, -1, 203, 202, 199, -1, + 203, 199, 204, -1, 203, 66, 201, -1, + 64, 65, 184, -1, 64, 66, 65, -1, + 64, 201, 66, -1, 64, 184, 202, -1, + 64, 202, 201, -1, 205, 410, 66, -1, + 205, 66, 203, -1, 205, 203, 204, -1, + 403, 67, 367, -1, 403, 404, 67, -1, + 207, 412, 629, -1, 207, 71, 213, -1, + 207, 213, 413, -1, 644, 218, 645, -1, + 644, 69, 219, -1, 70, 68, 69, -1, + 70, 69, 644, -1, 70, 211, 419, -1, + 70, 419, 68, -1, 70, 965, 211, -1, + 70, 359, 965, -1, 216, 215, 358, -1, + 216, 359, 70, -1, 216, 70, 644, -1, + 216, 644, 634, -1, 357, 216, 358, -1, + 357, 359, 216, -1, 414, 415, 73, -1, + 414, 73, 213, -1, 414, 213, 71, -1, + 414, 71, 207, -1, 414, 207, 629, -1, + 72, 418, 981, -1, 72, 981, 213, -1, + 72, 419, 418, -1, 72, 73, 419, -1, + 72, 213, 73, -1, 74, 674, 413, -1, + 74, 413, 213, -1, 74, 277, 674, -1, + 74, 213, 277, -1, 223, 222, 76, -1, + 223, 76, 75, -1, 1172, 961, 221, -1, + 1171, 75, 76, -1, 1171, 223, 75, -1, + 1171, 221, 223, -1, 1171, 1172, 221, -1, + 1171, 76, 428, -1, 421, 631, 227, -1, + 421, 281, 813, -1, 421, 282, 281, -1, + 432, 239, 1007, -1, 977, 1007, 417, -1, + 977, 1024, 1007, -1, 866, 864, 331, -1, + 866, 863, 864, -1, 192, 1076, 229, -1, + 234, 81, 232, -1, 234, 448, 81, -1, + 235, 232, 77, -1, 235, 236, 232, -1, + 235, 596, 237, -1, 235, 77, 954, -1, + 235, 78, 596, -1, 235, 954, 78, -1, + 913, 690, 723, -1, 913, 723, 915, -1, + 79, 83, 80, -1, 79, 246, 83, -1, + 79, 241, 246, -1, 79, 81, 241, -1, + 79, 82, 81, -1, 79, 80, 82, -1, + 240, 241, 448, -1, 245, 446, 244, -1, + 245, 246, 241, -1, 243, 83, 246, -1, + 243, 343, 83, -1, 683, 1576, 542, -1, + 683, 542, 1477, -1, 461, 746, 745, -1, + 728, 252, 843, -1, 728, 843, 729, -1, + 744, 456, 745, -1, 587, 586, 251, -1, + 84, 251, 85, -1, 84, 85, 254, -1, + 84, 254, 86, -1, 84, 86, 545, -1, + 84, 545, 842, -1, 84, 842, 251, -1, + 772, 301, 779, -1, 780, 254, 781, -1, + 778, 779, 254, -1, 87, 88, 89, -1, + 87, 89, 90, -1, 87, 90, 88, -1, + 1446, 91, 1308, -1, 1446, 1311, 92, -1, + 1446, 92, 470, -1, 1446, 470, 91, -1, + 260, 259, 288, -1, 260, 288, 261, -1, + 93, 288, 472, -1, 93, 261, 288, -1, + 93, 472, 261, -1, 263, 504, 264, -1, + 263, 265, 272, -1, 94, 95, 96, -1, + 94, 97, 474, -1, 94, 474, 98, -1, + 94, 98, 95, -1, 94, 96, 111, -1, + 94, 111, 97, -1, 468, 104, 1307, -1, + 102, 395, 101, -1, 102, 99, 395, -1, + 102, 267, 99, -1, 270, 101, 100, -1, + 270, 102, 101, -1, 270, 100, 103, -1, + 270, 267, 102, -1, 270, 103, 104, -1, + 270, 104, 468, -1, 452, 763, 762, -1, + 734, 105, 500, -1, 734, 500, 738, -1, + 734, 735, 106, -1, 734, 106, 105, -1, + 274, 272, 265, -1, 274, 738, 272, -1, + 274, 737, 738, -1, 480, 265, 490, -1, + 480, 274, 265, -1, 492, 500, 108, -1, + 492, 108, 806, -1, 796, 837, 530, -1, + 796, 797, 139, -1, 107, 275, 797, -1, + 107, 797, 108, -1, 107, 500, 275, -1, + 107, 108, 500, -1, 109, 500, 139, -1, + 109, 139, 797, -1, 109, 498, 500, -1, + 109, 797, 498, -1, 502, 272, 806, -1, + 502, 263, 272, -1, 502, 504, 263, -1, + 110, 525, 126, -1, 110, 504, 525, -1, + 110, 126, 111, -1, 110, 111, 504, -1, + 112, 526, 126, -1, 112, 126, 525, -1, + 112, 525, 526, -1, 506, 825, 525, -1, + 113, 115, 114, -1, 113, 118, 115, -1, + 113, 114, 118, -1, 116, 117, 811, -1, + 116, 118, 117, -1, 116, 811, 118, -1, + 283, 812, 281, -1, 283, 282, 279, -1, + 119, 120, 123, -1, 119, 123, 285, -1, + 119, 516, 120, -1, 119, 285, 516, -1, + 124, 284, 285, -1, 124, 258, 284, -1, + 124, 121, 258, -1, 124, 285, 123, -1, + 124, 287, 121, -1, 124, 442, 287, -1, + 522, 230, 523, -1, 522, 286, 230, -1, + 443, 230, 442, -1, 122, 536, 1374, -1, + 122, 1374, 442, -1, 122, 123, 536, -1, + 122, 442, 124, -1, 122, 124, 123, -1, + 290, 821, 125, -1, 290, 125, 126, -1, + 290, 126, 291, -1, 817, 127, 292, -1, + 817, 816, 127, -1, 830, 519, 261, -1, + 830, 261, 472, -1, 293, 541, 129, -1, + 293, 667, 541, -1, 293, 129, 294, -1, + 1185, 1235, 1236, -1, 1185, 534, 1235, -1, + 128, 129, 516, -1, 128, 509, 129, -1, + 128, 516, 509, -1, 138, 294, 130, -1, + 138, 302, 132, -1, 138, 131, 836, -1, + 138, 130, 131, -1, 434, 132, 1054, -1, + 434, 294, 138, -1, 434, 138, 132, -1, + 295, 297, 133, -1, 295, 133, 514, -1, + 134, 530, 837, -1, 134, 837, 135, -1, + 134, 529, 530, -1, 134, 135, 296, -1, + 134, 296, 529, -1, 298, 296, 135, -1, + 298, 836, 297, -1, 298, 135, 836, -1, + 136, 545, 302, -1, 136, 836, 137, -1, + 136, 842, 545, -1, 136, 137, 842, -1, + 136, 302, 138, -1, 136, 138, 836, -1, + 299, 139, 300, -1, 299, 796, 139, -1, + 299, 837, 796, -1, 303, 779, 301, -1, + 303, 849, 779, -1, 848, 545, 849, -1, + 307, 551, 1339, -1, 1338, 1339, 1337, -1, + 1341, 1342, 307, -1, 1341, 307, 306, -1, + 315, 140, 314, -1, 315, 549, 140, -1, + 315, 317, 385, -1, 315, 548, 549, -1, + 315, 385, 309, -1, 315, 309, 548, -1, + 310, 311, 141, -1, 310, 1337, 1339, -1, + 310, 141, 142, -1, 310, 143, 1337, -1, + 310, 1336, 143, -1, 310, 144, 1336, -1, + 310, 142, 144, -1, 436, 553, 437, -1, + 327, 437, 553, -1, 327, 147, 437, -1, + 327, 145, 147, -1, 327, 328, 145, -1, + 146, 194, 1074, -1, 146, 1074, 147, -1, + 146, 148, 681, -1, 146, 681, 194, -1, + 146, 149, 148, -1, 146, 147, 149, -1, + 150, 318, 325, -1, 150, 325, 858, -1, + 386, 388, 328, -1, 386, 309, 385, -1, + 386, 318, 150, -1, 386, 308, 309, -1, + 386, 150, 308, -1, 556, 322, 311, -1, + 556, 150, 858, -1, 556, 850, 322, -1, + 556, 311, 308, -1, 556, 308, 150, -1, + 879, 333, 334, -1, 560, 151, 335, -1, + 560, 559, 151, -1, 342, 1101, 1102, -1, + 342, 248, 1101, -1, 342, 243, 248, -1, + 342, 343, 243, -1, 337, 946, 341, -1, + 337, 152, 946, -1, 570, 571, 338, -1, + 570, 338, 152, -1, 570, 152, 337, -1, + 340, 153, 338, -1, 340, 154, 153, -1, + 340, 351, 154, -1, 567, 155, 562, -1, + 567, 569, 156, -1, 567, 156, 155, -1, + 581, 900, 573, -1, 350, 345, 349, -1, + 350, 901, 592, -1, 353, 352, 157, -1, + 353, 157, 590, -1, 210, 596, 209, -1, + 354, 915, 237, -1, 354, 237, 596, -1, + 423, 356, 641, -1, 423, 641, 640, -1, + 360, 158, 361, -1, 360, 358, 158, -1, + 622, 358, 360, -1, 1180, 164, 159, -1, + 1180, 966, 164, -1, 1180, 159, 364, -1, + 160, 362, 161, -1, 160, 162, 163, -1, + 160, 161, 162, -1, 160, 163, 164, -1, + 160, 164, 362, -1, 165, 168, 189, -1, + 165, 604, 168, -1, 165, 189, 184, -1, + 165, 184, 604, -1, 166, 167, 168, -1, + 166, 168, 604, -1, 166, 604, 169, -1, + 166, 170, 167, -1, 166, 169, 170, -1, + 603, 365, 410, -1, 907, 592, 901, -1, + 368, 369, 173, -1, 368, 173, 609, -1, + 368, 609, 457, -1, 368, 457, 456, -1, + 171, 172, 583, -1, 171, 583, 609, -1, + 171, 609, 172, -1, 608, 609, 173, -1, + 608, 173, 174, -1, 608, 174, 610, -1, + 926, 370, 175, -1, 926, 175, 927, -1, + 176, 178, 177, -1, 176, 179, 190, -1, + 176, 190, 178, -1, 176, 180, 179, -1, + 176, 177, 180, -1, 371, 181, 372, -1, + 371, 374, 332, -1, 371, 332, 181, -1, + 262, 477, 181, -1, 262, 181, 873, -1, + 376, 375, 182, -1, 376, 183, 184, -1, + 376, 185, 183, -1, 376, 186, 395, -1, + 376, 187, 186, -1, 376, 182, 187, -1, + 376, 188, 185, -1, 376, 395, 188, -1, + 376, 956, 955, -1, 376, 184, 189, -1, + 376, 954, 956, -1, 376, 189, 954, -1, + 378, 377, 190, -1, 378, 190, 191, -1, + 378, 191, 951, -1, 382, 399, 380, -1, + 397, 398, 400, -1, 397, 400, 395, -1, + 397, 395, 394, -1, 393, 395, 391, -1, + 289, 442, 286, -1, 289, 287, 442, -1, + 1075, 229, 228, -1, 1075, 228, 1074, -1, + 1075, 192, 229, -1, 1075, 1076, 192, -1, + 193, 194, 1071, -1, 193, 1071, 1072, -1, + 193, 1072, 194, -1, 1073, 1074, 1072, -1, + 195, 197, 196, -1, 195, 198, 197, -1, + 195, 196, 198, -1, 406, 199, 402, -1, + 406, 407, 199, -1, 200, 201, 202, -1, + 200, 202, 203, -1, 200, 203, 201, -1, + 408, 204, 407, -1, 408, 205, 204, -1, + 408, 410, 205, -1, 206, 413, 412, -1, + 206, 412, 207, -1, 206, 207, 413, -1, + 978, 977, 417, -1, 978, 208, 626, -1, + 978, 209, 208, -1, 978, 210, 209, -1, + 978, 918, 596, -1, 978, 596, 210, -1, + 630, 419, 211, -1, 630, 211, 965, -1, + 630, 965, 963, -1, 420, 212, 981, -1, + 995, 212, 420, -1, 214, 1148, 1143, -1, + 214, 995, 999, -1, 214, 212, 995, -1, + 214, 999, 1149, -1, 214, 1149, 1148, -1, + 276, 981, 212, -1, 276, 213, 981, -1, + 276, 277, 213, -1, 276, 214, 1143, -1, + 276, 212, 214, -1, 633, 641, 215, -1, + 633, 215, 216, -1, 633, 216, 634, -1, + 646, 645, 422, -1, 217, 219, 218, -1, + 217, 644, 219, -1, 217, 218, 644, -1, + 220, 221, 222, -1, 220, 222, 223, -1, + 220, 223, 221, -1, 1173, 428, 631, -1, + 1173, 1171, 428, -1, 429, 631, 428, -1, + 429, 427, 631, -1, 224, 428, 225, -1, + 224, 427, 428, -1, 224, 225, 631, -1, + 224, 631, 427, -1, 226, 227, 282, -1, + 226, 282, 421, -1, 226, 421, 227, -1, + 649, 444, 430, -1, 663, 444, 1028, -1, + 663, 430, 444, -1, 238, 1028, 444, -1, + 238, 432, 1028, -1, 655, 1028, 432, -1, + 655, 1041, 1028, -1, 431, 653, 432, -1, + 433, 671, 685, -1, 433, 670, 671, -1, + 1044, 539, 667, -1, 1044, 533, 539, -1, + 1534, 437, 228, -1, 1534, 229, 1076, -1, + 1534, 228, 229, -1, 1551, 1427, 866, -1, + 1549, 866, 331, -1, 1549, 1551, 866, -1, + 1549, 331, 865, -1, 1377, 523, 230, -1, + 1377, 230, 443, -1, 231, 232, 236, -1, + 231, 234, 232, -1, 231, 236, 234, -1, + 233, 236, 448, -1, 233, 448, 234, -1, + 233, 234, 236, -1, 724, 236, 235, -1, + 724, 448, 236, -1, 724, 237, 915, -1, + 724, 235, 237, -1, 724, 915, 723, -1, + 701, 1576, 683, -1, 694, 244, 446, -1, + 694, 695, 244, -1, 703, 697, 692, -1, + 703, 701, 697, -1, 1083, 684, 685, -1, + 709, 432, 238, -1, 709, 238, 444, -1, + 709, 239, 432, -1, 709, 417, 1007, -1, + 709, 1007, 239, -1, 449, 241, 240, -1, + 449, 446, 245, -1, 449, 245, 241, -1, + 449, 240, 448, -1, 242, 248, 243, -1, + 242, 247, 248, -1, 242, 244, 247, -1, + 242, 245, 244, -1, 242, 246, 245, -1, + 242, 243, 246, -1, 1108, 247, 1109, -1, + 1108, 248, 247, -1, 1108, 1101, 248, -1, + 730, 732, 735, -1, 450, 762, 462, -1, + 450, 452, 762, -1, 727, 462, 463, -1, + 727, 730, 451, -1, 727, 450, 462, -1, + 727, 451, 450, -1, 455, 461, 745, -1, + 455, 745, 456, -1, 750, 249, 459, -1, + 750, 754, 250, -1, 750, 250, 249, -1, + 758, 757, 883, -1, 761, 462, 762, -1, + 743, 1091, 756, -1, 743, 746, 1093, -1, + 743, 1093, 1091, -1, 453, 587, 251, -1, + 453, 251, 252, -1, 453, 252, 728, -1, + 453, 583, 587, -1, 453, 455, 583, -1, + 466, 578, 577, -1, 466, 782, 582, -1, + 466, 582, 578, -1, 253, 254, 780, -1, + 253, 778, 254, -1, 253, 780, 778, -1, + 783, 468, 1122, -1, 785, 256, 255, -1, + 785, 470, 256, -1, 785, 255, 787, -1, + 785, 787, 786, -1, 1132, 471, 1124, -1, + 1132, 1124, 1125, -1, 257, 258, 259, -1, + 257, 259, 260, -1, 257, 260, 261, -1, + 257, 518, 258, -1, 257, 261, 519, -1, + 257, 519, 518, -1, 485, 486, 476, -1, + 872, 482, 477, -1, 872, 477, 262, -1, + 872, 262, 873, -1, 487, 485, 482, -1, + 489, 263, 264, -1, 489, 264, 488, -1, + 489, 490, 265, -1, 489, 265, 263, -1, + 266, 267, 270, -1, 266, 270, 271, -1, + 266, 268, 267, -1, 266, 271, 268, -1, + 269, 271, 270, -1, 269, 270, 468, -1, + 269, 787, 271, -1, 269, 468, 787, -1, + 493, 806, 272, -1, 493, 272, 738, -1, + 493, 738, 500, -1, 273, 481, 763, -1, + 273, 737, 274, -1, 273, 480, 481, -1, + 273, 274, 480, -1, 273, 763, 452, -1, + 273, 452, 737, -1, 828, 796, 530, -1, + 792, 496, 806, -1, 1135, 806, 496, -1, + 499, 797, 275, -1, 499, 275, 500, -1, + 503, 804, 506, -1, 503, 506, 525, -1, + 508, 823, 825, -1, 508, 506, 804, -1, + 1316, 1457, 1067, -1, 1146, 276, 1143, -1, + 1146, 277, 276, -1, 1146, 1315, 277, -1, + 278, 279, 812, -1, 278, 812, 283, -1, + 278, 283, 279, -1, 280, 281, 282, -1, + 280, 282, 283, -1, 280, 283, 281, -1, + 511, 516, 285, -1, 512, 1358, 1357, -1, + 512, 1357, 529, -1, 512, 529, 296, -1, + 1162, 284, 518, -1, 1162, 285, 284, -1, + 1162, 511, 285, -1, 1162, 1358, 511, -1, + 521, 286, 522, -1, 521, 288, 287, -1, + 521, 681, 288, -1, 521, 287, 289, -1, + 521, 289, 286, -1, 528, 290, 291, -1, + 528, 824, 1157, -1, 528, 291, 824, -1, + 528, 1157, 531, -1, 528, 821, 290, -1, + 527, 291, 526, -1, 527, 824, 291, -1, + 527, 525, 825, -1, 527, 825, 824, -1, + 819, 817, 292, -1, 819, 292, 821, -1, + 665, 667, 293, -1, 665, 293, 294, -1, + 665, 294, 434, -1, 537, 533, 534, -1, + 537, 534, 1185, -1, 515, 295, 514, -1, + 515, 512, 296, -1, 515, 297, 295, -1, + 515, 298, 297, -1, 515, 296, 298, -1, + 839, 837, 299, -1, 839, 300, 840, -1, + 839, 299, 300, -1, 1569, 1477, 1473, -1, + 1257, 1362, 1256, -1, 304, 303, 301, -1, + 304, 301, 772, -1, 304, 772, 1477, -1, + 544, 1260, 302, -1, 544, 302, 545, -1, + 847, 849, 303, -1, 847, 1477, 1566, -1, + 847, 304, 1477, -1, 847, 303, 304, -1, + 305, 1342, 551, -1, 305, 307, 1342, -1, + 305, 551, 307, -1, 1340, 1341, 306, -1, + 1340, 307, 1339, -1, 1340, 306, 307, -1, + 547, 309, 308, -1, 547, 548, 309, -1, + 547, 310, 1339, -1, 547, 308, 311, -1, + 547, 311, 310, -1, 312, 314, 313, -1, + 312, 315, 314, -1, 312, 313, 316, -1, + 312, 316, 317, -1, 312, 317, 315, -1, + 554, 553, 436, -1, 329, 318, 386, -1, + 329, 386, 328, -1, 329, 867, 318, -1, + 319, 808, 320, -1, 319, 323, 808, -1, + 319, 320, 322, -1, 319, 322, 323, -1, + 321, 322, 808, -1, 321, 808, 323, -1, + 321, 323, 322, -1, 857, 556, 858, -1, + 853, 851, 858, -1, 862, 557, 324, -1, + 862, 324, 855, -1, 862, 855, 854, -1, + 862, 853, 858, -1, 862, 854, 853, -1, + 862, 325, 867, -1, 862, 858, 325, -1, + 440, 439, 1549, -1, 440, 1549, 865, -1, + 326, 327, 553, -1, 326, 553, 865, -1, + 326, 865, 867, -1, 326, 328, 327, -1, + 326, 867, 329, -1, 326, 329, 328, -1, + 330, 331, 864, -1, 330, 864, 865, -1, + 330, 865, 331, -1, 868, 332, 333, -1, + 868, 333, 879, -1, 868, 873, 332, -1, + 878, 334, 558, -1, 878, 879, 334, -1, + 753, 560, 335, -1, 753, 335, 336, -1, + 753, 336, 754, -1, 897, 337, 341, -1, + 897, 896, 570, -1, 897, 570, 337, -1, + 344, 338, 571, -1, 344, 340, 338, -1, + 339, 899, 351, -1, 339, 351, 340, -1, + 339, 340, 344, -1, 339, 900, 899, -1, + 339, 573, 900, -1, 339, 344, 573, -1, + 566, 567, 562, -1, 566, 895, 898, -1, + 565, 897, 341, -1, 565, 898, 897, -1, + 565, 341, 568, -1, 563, 342, 1102, -1, + 563, 1102, 770, -1, 563, 562, 343, -1, + 563, 343, 342, -1, 890, 889, 575, -1, + 890, 344, 571, -1, 890, 573, 344, -1, + 890, 571, 888, -1, 576, 581, 575, -1, + 903, 900, 581, -1, 589, 353, 590, -1, + 589, 595, 353, -1, 591, 345, 350, -1, + 591, 346, 345, -1, 591, 590, 346, -1, + 591, 350, 592, -1, 347, 349, 348, -1, + 347, 350, 349, -1, 347, 348, 351, -1, + 347, 901, 350, -1, 347, 351, 899, -1, + 347, 899, 901, -1, 594, 927, 352, -1, + 594, 352, 353, -1, 594, 928, 927, -1, + 594, 353, 595, -1, 597, 915, 354, -1, + 597, 354, 596, -1, 355, 425, 356, -1, + 355, 356, 423, -1, 355, 423, 425, -1, + 424, 425, 423, -1, 964, 357, 358, -1, + 964, 358, 622, -1, 964, 965, 359, -1, + 964, 359, 357, -1, 401, 622, 360, -1, + 401, 360, 361, -1, 401, 361, 362, -1, + 401, 362, 966, -1, 624, 363, 598, -1, + 624, 364, 363, -1, 624, 1180, 364, -1, + 605, 604, 365, -1, 605, 365, 603, -1, + 366, 367, 604, -1, 366, 604, 603, -1, + 366, 403, 367, -1, 366, 603, 403, -1, + 593, 907, 904, -1, 593, 592, 907, -1, + 458, 456, 744, -1, 458, 368, 456, -1, + 458, 369, 368, -1, 458, 459, 369, -1, + 922, 583, 607, -1, 932, 613, 370, -1, + 932, 370, 926, -1, 935, 614, 936, -1, + 616, 617, 593, -1, 616, 593, 904, -1, + 940, 583, 922, -1, 950, 371, 372, -1, + 950, 951, 373, -1, 950, 373, 374, -1, + 950, 374, 371, -1, 950, 372, 375, -1, + 950, 375, 376, -1, 950, 376, 955, -1, + 952, 621, 377, -1, 952, 377, 378, -1, + 952, 378, 951, -1, 379, 380, 383, -1, + 379, 383, 382, -1, 379, 382, 380, -1, + 381, 382, 383, -1, 381, 399, 382, -1, + 381, 383, 400, -1, 381, 400, 399, -1, + 384, 385, 399, -1, 384, 399, 397, -1, + 384, 386, 385, -1, 384, 388, 386, -1, + 384, 397, 388, -1, 387, 390, 388, -1, + 387, 397, 390, -1, 387, 388, 397, -1, + 389, 390, 397, -1, 389, 391, 392, -1, + 389, 392, 390, -1, 389, 393, 391, -1, + 389, 397, 394, -1, 389, 394, 395, -1, + 389, 395, 393, -1, 396, 398, 397, -1, + 396, 397, 399, -1, 396, 400, 398, -1, + 396, 399, 400, -1, 1176, 623, 961, -1, + 973, 401, 966, -1, 973, 622, 401, -1, + 409, 406, 402, -1, 409, 403, 603, -1, + 409, 402, 404, -1, 409, 404, 403, -1, + 405, 407, 406, -1, 405, 408, 407, -1, + 405, 406, 409, -1, 405, 410, 408, -1, + 405, 603, 410, -1, 405, 409, 603, -1, + 411, 1269, 1009, -1, 411, 677, 1269, -1, + 411, 1009, 978, -1, 678, 411, 978, -1, + 678, 677, 411, -1, 678, 629, 412, -1, + 678, 412, 413, -1, 678, 413, 674, -1, + 628, 415, 414, -1, 628, 626, 415, -1, + 628, 414, 629, -1, 416, 978, 417, -1, + 416, 712, 978, -1, 416, 417, 709, -1, + 416, 709, 712, -1, 980, 981, 418, -1, + 980, 418, 419, -1, 980, 419, 630, -1, + 962, 630, 963, -1, 983, 420, 981, -1, + 983, 996, 995, -1, 983, 995, 420, -1, + 985, 631, 421, -1, 985, 421, 813, -1, + 632, 991, 986, -1, 632, 986, 1000, -1, + 1002, 1003, 1000, -1, 1002, 1000, 986, -1, + 1002, 986, 809, -1, 639, 641, 633, -1, + 647, 646, 422, -1, 647, 640, 637, -1, + 647, 423, 640, -1, 647, 424, 423, -1, + 647, 422, 425, -1, 647, 425, 424, -1, + 643, 636, 644, -1, 643, 647, 637, -1, + 426, 428, 427, -1, 426, 429, 428, -1, + 426, 427, 429, -1, 1218, 649, 430, -1, + 1218, 430, 663, -1, 650, 1007, 1024, -1, + 650, 654, 1007, -1, 652, 432, 653, -1, + 652, 655, 432, -1, 1038, 653, 431, -1, + 1038, 432, 1007, -1, 1038, 431, 432, -1, + 1375, 523, 1377, -1, 1543, 1482, 1236, -1, + 1015, 670, 433, -1, 1015, 685, 686, -1, + 1015, 433, 685, -1, 1015, 686, 1016, -1, + 1030, 1197, 658, -1, 1196, 658, 1197, -1, + 656, 1219, 658, -1, 656, 1391, 1219, -1, + 662, 1389, 1391, -1, 662, 1020, 1288, -1, + 662, 1022, 1020, -1, 1040, 1025, 1034, -1, + 1040, 1034, 1035, -1, 1222, 1407, 1013, -1, + 1406, 1013, 1407, -1, 664, 1410, 1013, -1, + 664, 1013, 1406, -1, 1166, 1410, 664, -1, + 1166, 664, 833, -1, 666, 1044, 667, -1, + 1439, 707, 1050, -1, 1062, 1256, 1362, -1, + 1253, 1417, 1052, -1, 1253, 707, 1439, -1, + 1053, 434, 1054, -1, 1053, 665, 434, -1, + 1241, 1055, 1242, -1, 1081, 670, 657, -1, + 1081, 657, 1242, -1, 1081, 1055, 1297, -1, + 1081, 1242, 1055, -1, 435, 1024, 977, -1, + 435, 1211, 1024, -1, 435, 977, 1211, -1, + 1592, 674, 1315, -1, 1280, 674, 1278, -1, + 1280, 678, 674, -1, 1431, 1069, 1432, -1, + 1436, 682, 554, -1, 1436, 554, 436, -1, + 1436, 436, 437, -1, 1436, 437, 1534, -1, + 438, 1549, 439, -1, 438, 439, 440, -1, + 438, 553, 682, -1, 438, 682, 1549, -1, + 438, 865, 553, -1, 438, 440, 865, -1, + 441, 442, 1374, -1, 441, 1374, 1377, -1, + 441, 443, 442, -1, 441, 1377, 443, -1, + 698, 697, 701, -1, 698, 773, 699, -1, + 447, 722, 689, -1, 447, 694, 446, -1, + 1077, 1088, 718, -1, 691, 692, 689, -1, + 691, 716, 718, -1, 696, 689, 692, -1, + 696, 447, 689, -1, 696, 694, 447, -1, + 696, 692, 697, -1, 445, 444, 649, -1, + 445, 649, 1288, -1, 673, 685, 671, -1, + 673, 1083, 685, -1, 672, 1080, 700, -1, + 672, 700, 1083, -1, 1079, 709, 444, -1, + 1079, 444, 445, -1, 1079, 445, 1288, -1, + 715, 690, 913, -1, 715, 716, 690, -1, + 711, 978, 712, -1, 710, 913, 978, -1, + 710, 717, 913, -1, 710, 978, 711, -1, + 721, 446, 449, -1, 721, 447, 446, -1, + 721, 722, 447, -1, 720, 448, 724, -1, + 720, 449, 448, -1, 720, 721, 449, -1, + 1107, 1109, 699, -1, 1107, 699, 773, -1, + 731, 732, 730, -1, 736, 450, 451, -1, + 736, 730, 735, -1, 736, 451, 730, -1, + 736, 737, 452, -1, 736, 452, 450, -1, + 1094, 727, 463, -1, 1094, 461, 455, -1, + 1094, 728, 727, -1, 1094, 453, 728, -1, + 1094, 455, 453, -1, 454, 583, 455, -1, + 454, 455, 456, -1, 454, 457, 583, -1, + 454, 456, 457, -1, 742, 751, 749, -1, + 742, 743, 756, -1, 748, 744, 749, -1, + 748, 459, 458, -1, 748, 458, 744, -1, + 748, 750, 459, -1, 882, 758, 883, -1, + 460, 1096, 1093, -1, 460, 461, 1094, -1, + 460, 1094, 1096, -1, 460, 746, 461, -1, + 460, 1093, 746, -1, 1092, 462, 761, -1, + 1092, 463, 462, -1, 1092, 1094, 463, -1, + 760, 765, 757, -1, 464, 579, 581, -1, + 464, 582, 579, -1, 464, 581, 576, -1, + 464, 576, 582, -1, 768, 577, 885, -1, + 768, 466, 577, -1, 1100, 770, 1102, -1, + 465, 782, 466, -1, 465, 769, 782, -1, + 465, 466, 768, -1, 465, 768, 769, -1, + 776, 1107, 773, -1, 776, 1105, 1107, -1, + 725, 766, 1099, -1, 725, 777, 782, -1, + 725, 782, 766, -1, 1111, 1113, 467, -1, + 1111, 1300, 1113, -1, 1111, 467, 1307, -1, + 1120, 467, 1113, -1, 1120, 1307, 467, -1, + 1120, 468, 1307, -1, 1120, 1122, 468, -1, + 469, 787, 468, -1, 469, 468, 783, -1, + 1119, 469, 783, -1, 1119, 787, 469, -1, + 1119, 1308, 470, -1, 1119, 470, 785, -1, + 1310, 1113, 1309, -1, 1310, 1308, 1119, -1, + 1131, 471, 1132, -1, 1131, 472, 471, -1, + 1131, 830, 472, -1, 1131, 1129, 830, -1, + 1133, 1132, 1125, -1, 1133, 789, 1126, -1, + 1133, 1125, 789, -1, 473, 1305, 1307, -1, + 473, 815, 1305, -1, 473, 1307, 474, -1, + 473, 474, 815, -1, 1110, 1305, 815, -1, + 475, 485, 476, -1, 475, 482, 485, -1, + 475, 477, 482, -1, 475, 478, 477, -1, + 475, 479, 478, -1, 475, 476, 479, -1, + 483, 490, 487, -1, 483, 480, 490, -1, + 483, 481, 480, -1, 876, 875, 764, -1, + 876, 764, 481, -1, 876, 481, 483, -1, + 871, 482, 872, -1, 871, 487, 482, -1, + 871, 483, 487, -1, 871, 876, 483, -1, + 484, 486, 485, -1, 484, 485, 487, -1, + 484, 488, 486, -1, 484, 489, 488, -1, + 484, 487, 490, -1, 484, 490, 489, -1, + 491, 500, 492, -1, 491, 493, 500, -1, + 491, 492, 806, -1, 491, 806, 493, -1, + 799, 496, 792, -1, 799, 793, 800, -1, + 494, 793, 495, -1, 494, 800, 793, -1, + 494, 495, 797, -1, 494, 797, 800, -1, + 801, 1135, 496, -1, 801, 496, 799, -1, + 822, 823, 1135, -1, 803, 823, 804, -1, + 803, 1135, 823, -1, 1138, 1136, 806, -1, + 1138, 806, 1135, -1, 497, 498, 797, -1, + 497, 797, 499, -1, 497, 500, 498, -1, + 497, 499, 500, -1, 501, 502, 806, -1, + 501, 806, 805, -1, 501, 805, 804, -1, + 501, 804, 503, -1, 501, 503, 525, -1, + 501, 525, 504, -1, 501, 504, 502, -1, + 505, 825, 506, -1, 505, 508, 825, -1, + 505, 506, 508, -1, 507, 804, 823, -1, + 507, 508, 804, -1, 507, 823, 508, -1, + 1151, 1067, 1282, -1, 1151, 1316, 1067, -1, + 1151, 1282, 1315, -1, 1318, 1320, 1140, -1, + 1318, 1140, 1319, -1, 810, 811, 1342, -1, + 810, 1342, 1153, -1, 1317, 1005, 809, -1, + 1465, 1319, 810, -1, 1465, 810, 1153, -1, + 513, 509, 516, -1, 513, 514, 509, -1, + 510, 511, 1358, -1, 510, 1358, 512, -1, + 510, 514, 513, -1, 510, 515, 514, -1, + 510, 512, 515, -1, 510, 516, 511, -1, + 510, 513, 516, -1, 1160, 519, 830, -1, + 517, 518, 519, -1, 517, 1162, 518, -1, + 517, 519, 1160, -1, 517, 1160, 1162, -1, + 520, 681, 521, -1, 520, 521, 522, -1, + 520, 522, 523, -1, 520, 523, 1375, -1, + 520, 1375, 681, -1, 524, 526, 525, -1, + 524, 527, 526, -1, 524, 525, 527, -1, + 1115, 1302, 815, -1, 1115, 1300, 1302, -1, + 1115, 819, 1450, -1, 820, 531, 1558, -1, + 820, 1558, 1450, -1, 820, 821, 528, -1, + 820, 528, 531, -1, 1349, 825, 823, -1, + 827, 530, 529, -1, 827, 828, 530, -1, + 827, 529, 1357, -1, 827, 1357, 1356, -1, + 1156, 531, 1157, -1, 1156, 1558, 531, -1, + 532, 539, 533, -1, 532, 533, 537, -1, + 1188, 1187, 539, -1, 1188, 539, 532, -1, + 1188, 532, 537, -1, 831, 534, 832, -1, + 831, 833, 1233, -1, 831, 1233, 1235, -1, + 831, 1235, 534, -1, 1043, 533, 1044, -1, + 1043, 534, 533, -1, 1043, 832, 534, -1, + 535, 1374, 536, -1, 535, 1190, 1374, -1, + 535, 536, 540, -1, 535, 540, 1190, -1, + 1186, 537, 1185, -1, 1186, 1188, 537, -1, + 538, 1187, 1190, -1, 538, 539, 1187, -1, + 538, 1190, 540, -1, 538, 541, 539, -1, + 538, 540, 541, -1, 841, 837, 839, -1, + 1363, 542, 1576, -1, 1363, 1477, 542, -1, + 1472, 1477, 1569, -1, 1568, 1569, 1473, -1, + 543, 848, 1260, -1, 543, 1260, 544, -1, + 543, 545, 848, -1, 543, 544, 545, -1, + 1264, 1566, 1257, -1, 1264, 847, 1566, -1, + 546, 548, 547, -1, 546, 550, 549, -1, + 546, 549, 548, -1, 546, 547, 1339, -1, + 546, 1339, 551, -1, 546, 551, 550, -1, + 552, 682, 553, -1, 552, 554, 682, -1, + 552, 553, 554, -1, 555, 850, 556, -1, + 555, 857, 850, -1, 555, 556, 857, -1, + 859, 850, 857, -1, 861, 557, 862, -1, + 861, 1427, 557, -1, 861, 866, 1427, -1, + 874, 873, 868, -1, 874, 869, 875, -1, + 880, 558, 559, -1, 880, 878, 558, -1, + 880, 559, 740, -1, 880, 740, 882, -1, + 752, 751, 740, -1, 752, 740, 559, -1, + 752, 559, 560, -1, 752, 560, 753, -1, + 561, 566, 562, -1, 561, 895, 566, -1, + 561, 562, 563, -1, 561, 886, 895, -1, + 561, 770, 886, -1, 561, 563, 770, -1, + 564, 898, 565, -1, 564, 566, 898, -1, + 564, 567, 566, -1, 564, 565, 568, -1, + 564, 568, 569, -1, 564, 569, 567, -1, + 884, 885, 577, -1, 884, 889, 893, -1, + 892, 570, 896, -1, 892, 571, 570, -1, + 892, 888, 571, -1, 572, 890, 575, -1, + 572, 573, 890, -1, 572, 575, 581, -1, + 572, 581, 573, -1, 574, 575, 889, -1, + 574, 576, 575, -1, 574, 889, 884, -1, + 574, 884, 577, -1, 574, 577, 578, -1, + 574, 578, 582, -1, 574, 582, 576, -1, + 584, 579, 582, -1, 584, 581, 579, -1, + 584, 580, 581, -1, 619, 581, 580, -1, + 619, 903, 581, -1, 619, 904, 903, -1, + 619, 582, 782, -1, 619, 583, 940, -1, + 619, 584, 582, -1, 619, 580, 584, -1, + 619, 585, 586, -1, 619, 782, 781, -1, + 619, 781, 585, -1, 619, 587, 583, -1, + 619, 586, 587, -1, 618, 910, 595, -1, + 618, 595, 589, -1, 618, 589, 617, -1, + 618, 620, 910, -1, 588, 589, 590, -1, + 588, 590, 591, -1, 588, 591, 592, -1, + 588, 617, 589, -1, 588, 592, 593, -1, + 588, 593, 617, -1, 909, 928, 594, -1, + 909, 594, 595, -1, 909, 943, 928, -1, + 909, 595, 910, -1, 914, 915, 597, -1, + 917, 918, 978, -1, 917, 914, 597, -1, + 919, 596, 918, -1, 919, 597, 596, -1, + 919, 917, 597, -1, 969, 598, 599, -1, + 969, 624, 598, -1, 969, 599, 600, -1, + 969, 600, 601, -1, 969, 601, 970, -1, + 602, 603, 604, -1, 602, 604, 605, -1, + 602, 605, 603, -1, 606, 607, 609, -1, + 606, 922, 607, -1, 606, 609, 922, -1, + 921, 936, 614, -1, 921, 614, 922, -1, + 923, 609, 608, -1, 923, 922, 609, -1, + 923, 610, 924, -1, 923, 608, 610, -1, + 931, 934, 611, -1, 931, 611, 612, -1, + 931, 612, 613, -1, 931, 613, 932, -1, + 933, 932, 926, -1, 933, 929, 935, -1, + 942, 928, 943, -1, 942, 939, 929, -1, + 938, 935, 929, -1, 938, 929, 939, -1, + 938, 614, 935, -1, 938, 922, 614, -1, + 938, 940, 922, -1, 615, 617, 616, -1, + 615, 618, 617, -1, 615, 620, 618, -1, + 615, 940, 620, -1, 615, 619, 940, -1, + 615, 616, 904, -1, 615, 904, 619, -1, + 911, 910, 620, -1, 911, 620, 940, -1, + 953, 945, 621, -1, 953, 621, 952, -1, + 959, 962, 975, -1, 972, 964, 622, -1, + 972, 622, 973, -1, 1179, 968, 623, -1, + 1179, 623, 1176, -1, 1179, 1180, 624, -1, + 1179, 624, 969, -1, 625, 978, 626, -1, + 625, 626, 628, -1, 625, 628, 978, -1, + 627, 628, 629, -1, 627, 978, 628, -1, + 627, 629, 678, -1, 627, 678, 978, -1, + 1181, 978, 1209, -1, 1181, 1209, 1207, -1, + 1181, 1207, 1182, -1, 1214, 978, 1009, -1, + 982, 980, 630, -1, 982, 630, 962, -1, + 982, 962, 996, -1, 982, 996, 983, -1, + 989, 1169, 1175, -1, 989, 1177, 1169, -1, + 1174, 1173, 631, -1, 1174, 631, 985, -1, + 998, 960, 1000, -1, 957, 993, 991, -1, + 957, 991, 632, -1, 957, 632, 1000, -1, + 957, 1000, 960, -1, 1004, 1002, 809, -1, + 1004, 809, 1005, -1, 638, 633, 634, -1, + 638, 639, 633, -1, 638, 644, 636, -1, + 638, 634, 644, -1, 635, 636, 643, -1, + 635, 643, 637, -1, 635, 638, 636, -1, + 635, 639, 638, -1, 635, 637, 640, -1, + 635, 640, 641, -1, 635, 641, 639, -1, + 642, 643, 644, -1, 642, 644, 645, -1, + 642, 645, 646, -1, 642, 646, 647, -1, + 642, 647, 643, -1, 648, 1389, 661, -1, + 648, 1218, 1389, -1, 648, 649, 1218, -1, + 648, 661, 1288, -1, 648, 1288, 649, -1, + 1042, 650, 1024, -1, 1042, 654, 650, -1, + 1042, 1038, 654, -1, 1042, 1025, 1040, -1, + 1042, 1024, 1204, -1, 1042, 1204, 1025, -1, + 651, 652, 653, -1, 651, 655, 652, -1, + 651, 653, 1038, -1, 651, 1038, 655, -1, + 1008, 1007, 654, -1, 1008, 654, 1038, -1, + 1037, 655, 1038, -1, 1037, 1041, 655, -1, + 1542, 1543, 1284, -1, 1238, 1237, 1284, -1, + 1238, 1284, 1543, -1, 1238, 1543, 1236, -1, + 1193, 1272, 1208, -1, 1193, 1214, 1009, -1, + 1011, 1379, 1380, -1, 1011, 1197, 1029, -1, + 1012, 1222, 1013, -1, 1012, 1379, 1011, -1, + 1012, 1029, 1222, -1, 1012, 1011, 1029, -1, + 659, 670, 1015, -1, 659, 1019, 1391, -1, + 659, 1391, 656, -1, 659, 656, 658, -1, + 1017, 1019, 659, -1, 1017, 659, 1015, -1, + 1031, 658, 1219, -1, 1031, 1030, 658, -1, + 1243, 1242, 657, -1, 1243, 658, 1196, -1, + 1243, 659, 658, -1, 1243, 657, 670, -1, + 1243, 670, 659, -1, 660, 661, 1389, -1, + 660, 1389, 662, -1, 660, 1288, 661, -1, + 660, 662, 1288, -1, 1385, 662, 1391, -1, + 1385, 1382, 1021, -1, 1385, 1022, 662, -1, + 1385, 1021, 1022, -1, 1018, 1019, 1201, -1, + 687, 1017, 1016, -1, 1217, 663, 1028, -1, + 1217, 1218, 663, -1, 1223, 1026, 1502, -1, + 1223, 1025, 1026, -1, 1223, 1034, 1025, -1, + 1039, 1035, 1032, -1, 1039, 1040, 1035, -1, + 1039, 1032, 1217, -1, 1220, 1225, 1226, -1, + 1232, 664, 1406, -1, 1232, 1233, 833, -1, + 1232, 833, 664, -1, 1249, 666, 1059, -1, + 1249, 1044, 666, -1, 846, 1576, 1046, -1, + 846, 1046, 1052, -1, 1051, 846, 1052, -1, + 1049, 1555, 1441, -1, 1438, 1049, 1441, -1, + 1438, 1439, 1050, -1, 1438, 1050, 1049, -1, + 1268, 1062, 1362, -1, 1268, 1253, 1439, -1, + 668, 665, 1053, -1, 668, 1059, 666, -1, + 668, 667, 665, -1, 668, 666, 667, -1, + 1254, 1255, 1059, -1, 1254, 1059, 668, -1, + 1254, 668, 1053, -1, 1061, 1062, 1268, -1, + 1247, 1061, 1057, -1, 669, 670, 1081, -1, + 669, 1081, 1080, -1, 669, 671, 670, -1, + 669, 1080, 672, -1, 669, 672, 1083, -1, + 669, 673, 671, -1, 669, 1083, 673, -1, + 1206, 1207, 1209, -1, 1277, 1278, 674, -1, + 1277, 674, 1592, -1, 1063, 1282, 675, -1, + 1063, 1315, 1282, -1, 1430, 675, 1282, -1, + 1430, 1063, 675, -1, 676, 1269, 677, -1, + 676, 1280, 1269, -1, 676, 677, 678, -1, + 676, 678, 1280, -1, 1070, 1069, 1431, -1, + 1070, 1431, 1592, -1, 1433, 1226, 1227, -1, + 1433, 1227, 1525, -1, 1285, 1071, 679, -1, + 1285, 679, 680, -1, 1285, 680, 681, -1, + 1285, 681, 1375, -1, 1533, 1534, 1076, -1, + 1435, 1549, 682, -1, 1435, 682, 1436, -1, + 774, 701, 683, -1, 774, 698, 701, -1, + 774, 773, 698, -1, 774, 683, 1477, -1, + 774, 1477, 772, -1, 1084, 684, 1083, -1, + 1084, 1088, 1077, -1, 1084, 1557, 1088, -1, + 1289, 684, 1084, -1, 1289, 685, 684, -1, + 1289, 686, 685, -1, 1289, 1016, 686, -1, + 1289, 687, 1016, -1, 1289, 1492, 1490, -1, + 1289, 1201, 1019, -1, 1289, 1019, 1017, -1, + 1289, 1017, 687, -1, 688, 691, 689, -1, + 688, 716, 691, -1, 688, 689, 722, -1, + 688, 690, 716, -1, 688, 723, 690, -1, + 688, 722, 723, -1, 704, 692, 691, -1, + 704, 703, 692, -1, 704, 718, 1088, -1, + 704, 691, 718, -1, 693, 695, 694, -1, + 693, 694, 696, -1, 693, 696, 697, -1, + 693, 697, 698, -1, 693, 699, 695, -1, + 693, 698, 699, -1, 1291, 700, 1080, -1, + 1291, 1083, 700, -1, 1443, 1297, 1055, -1, + 702, 701, 703, -1, 702, 1576, 701, -1, + 702, 1046, 1576, -1, 1087, 1555, 1046, -1, + 1087, 702, 703, -1, 1087, 1046, 702, -1, + 1087, 704, 1088, -1, 1087, 703, 704, -1, + 705, 1050, 707, -1, 705, 1048, 1050, -1, + 705, 707, 1048, -1, 706, 1048, 707, -1, + 706, 1052, 1048, -1, 706, 707, 1253, -1, + 706, 1253, 1052, -1, 1295, 1085, 1557, -1, + 1295, 1557, 1294, -1, 1556, 1555, 1557, -1, + 708, 709, 1079, -1, 708, 717, 710, -1, + 708, 1078, 717, -1, 708, 1079, 1078, -1, + 708, 710, 711, -1, 708, 712, 709, -1, + 708, 711, 712, -1, 713, 913, 717, -1, + 713, 715, 913, -1, 713, 717, 715, -1, + 714, 716, 715, -1, 714, 1078, 1077, -1, + 714, 717, 1078, -1, 714, 715, 717, -1, + 714, 1077, 718, -1, 714, 718, 716, -1, + 719, 721, 720, -1, 719, 723, 722, -1, + 719, 722, 721, -1, 719, 724, 723, -1, + 719, 720, 724, -1, 1104, 1105, 777, -1, + 1104, 777, 725, -1, 1104, 725, 1099, -1, + 726, 727, 728, -1, 726, 728, 729, -1, + 726, 730, 727, -1, 726, 731, 730, -1, + 726, 729, 732, -1, 726, 732, 731, -1, + 733, 735, 734, -1, 733, 736, 735, -1, + 733, 737, 736, -1, 733, 738, 737, -1, + 733, 734, 738, -1, 1095, 1096, 1094, -1, + 739, 751, 742, -1, 739, 758, 882, -1, + 739, 756, 758, -1, 739, 742, 756, -1, + 739, 740, 751, -1, 739, 882, 740, -1, + 741, 743, 742, -1, 741, 744, 745, -1, + 741, 749, 744, -1, 741, 742, 749, -1, + 741, 745, 746, -1, 741, 746, 743, -1, + 747, 748, 749, -1, 747, 750, 748, -1, + 747, 749, 751, -1, 747, 751, 752, -1, + 747, 752, 753, -1, 747, 754, 750, -1, + 747, 753, 754, -1, 1090, 1092, 761, -1, + 1090, 761, 760, -1, 755, 756, 1091, -1, + 755, 760, 757, -1, 755, 1091, 1090, -1, + 755, 1090, 760, -1, 755, 757, 758, -1, + 755, 758, 756, -1, 759, 760, 761, -1, + 759, 762, 763, -1, 759, 761, 762, -1, + 759, 763, 764, -1, 759, 764, 765, -1, + 759, 765, 760, -1, 1098, 769, 1100, -1, + 1098, 782, 769, -1, 1098, 766, 782, -1, + 1098, 1099, 766, -1, 767, 769, 768, -1, + 767, 1100, 769, -1, 767, 768, 885, -1, + 767, 770, 1100, -1, 767, 885, 886, -1, + 767, 886, 770, -1, 1106, 1104, 1099, -1, + 1106, 1101, 1108, -1, 771, 772, 779, -1, + 771, 779, 776, -1, 771, 776, 773, -1, + 771, 773, 774, -1, 771, 774, 772, -1, + 775, 1105, 776, -1, 775, 777, 1105, -1, + 775, 779, 778, -1, 775, 776, 779, -1, + 775, 778, 780, -1, 775, 780, 781, -1, + 775, 781, 782, -1, 775, 782, 777, -1, + 1304, 1300, 1111, -1, 1304, 1305, 1110, -1, + 1114, 1300, 1117, -1, 1114, 1117, 1309, -1, + 1121, 1119, 783, -1, 1121, 783, 1122, -1, + 784, 785, 786, -1, 784, 1119, 785, -1, + 784, 786, 787, -1, 784, 787, 1119, -1, + 788, 1113, 1310, -1, 788, 1310, 1119, -1, + 788, 1120, 1113, -1, 788, 1119, 1120, -1, + 1632, 1116, 1631, -1, 1632, 1309, 1117, -1, + 1632, 1117, 1116, -1, 1312, 789, 1125, -1, + 1312, 1624, 789, -1, 1128, 1126, 1558, -1, + 1128, 1352, 1163, -1, 1128, 1156, 1352, -1, + 1128, 1558, 1156, -1, 1314, 1126, 789, -1, + 1314, 1558, 1126, -1, 1314, 789, 1624, -1, + 790, 815, 1302, -1, 790, 1110, 815, -1, + 790, 1302, 1110, -1, 791, 799, 792, -1, + 791, 792, 806, -1, 791, 793, 799, -1, + 791, 806, 793, -1, 794, 800, 797, -1, + 794, 797, 801, -1, 794, 801, 800, -1, + 795, 797, 796, -1, 795, 801, 797, -1, + 795, 796, 828, -1, 795, 828, 801, -1, + 798, 799, 800, -1, 798, 800, 801, -1, + 798, 801, 799, -1, 829, 801, 828, -1, + 829, 1135, 801, -1, 829, 822, 1135, -1, + 829, 1344, 822, -1, 802, 1136, 1135, -1, + 802, 1135, 803, -1, 802, 803, 804, -1, + 802, 804, 805, -1, 802, 806, 1136, -1, + 802, 805, 806, -1, 1137, 1138, 1135, -1, + 1064, 1065, 1154, -1, 1064, 808, 850, -1, + 1343, 1155, 1508, -1, 1343, 1508, 1281, -1, + 807, 1334, 808, -1, 807, 1154, 1334, -1, + 807, 808, 1064, -1, 807, 1064, 1154, -1, + 987, 1140, 1320, -1, 987, 1320, 1317, -1, + 987, 1317, 809, -1, 987, 809, 986, -1, + 1141, 810, 1319, -1, 1141, 812, 811, -1, + 1141, 811, 810, -1, 1141, 813, 812, -1, + 1141, 985, 813, -1, 1147, 1146, 1143, -1, + 1325, 1146, 1326, -1, 1325, 1324, 1315, -1, + 1325, 1315, 1146, -1, 1462, 1343, 1281, -1, + 1462, 1281, 1456, -1, 1328, 1330, 1005, -1, + 1328, 1005, 1317, -1, 1161, 1162, 1160, -1, + 814, 1115, 815, -1, 814, 815, 816, -1, + 814, 819, 1115, -1, 814, 816, 817, -1, + 814, 817, 819, -1, 818, 1450, 819, -1, + 818, 820, 1450, -1, 818, 819, 821, -1, + 818, 821, 820, -1, 1348, 823, 822, -1, + 1348, 1349, 823, -1, 1348, 822, 1344, -1, + 1158, 1157, 824, -1, 1158, 824, 825, -1, + 1158, 825, 1349, -1, 826, 828, 827, -1, + 826, 829, 828, -1, 826, 1344, 829, -1, + 826, 1345, 1344, -1, 826, 1356, 1345, -1, + 826, 827, 1356, -1, 1159, 830, 1129, -1, + 1159, 1160, 830, -1, 1355, 1345, 1356, -1, + 1165, 831, 832, -1, 1165, 832, 1043, -1, + 1165, 1166, 833, -1, 1165, 833, 831, -1, + 834, 842, 835, -1, 834, 841, 842, -1, + 834, 835, 836, -1, 834, 836, 837, -1, + 834, 837, 841, -1, 838, 839, 840, -1, + 838, 841, 839, -1, 838, 842, 841, -1, + 838, 843, 842, -1, 838, 844, 843, -1, + 838, 840, 844, -1, 1471, 1477, 1472, -1, + 845, 1361, 1576, -1, 845, 1051, 1252, -1, + 845, 1252, 1360, -1, 845, 1360, 1361, -1, + 845, 1576, 846, -1, 845, 846, 1051, -1, + 1572, 1257, 1566, -1, 1263, 1264, 1257, -1, + 1261, 847, 1264, -1, 1261, 848, 849, -1, + 1261, 849, 847, -1, 1261, 1260, 848, -1, + 852, 850, 859, -1, 852, 1064, 850, -1, + 1426, 859, 858, -1, 1426, 858, 851, -1, + 1426, 852, 859, -1, 1426, 851, 853, -1, + 1426, 1425, 1064, -1, 1426, 1064, 852, -1, + 1426, 853, 854, -1, 1426, 854, 855, -1, + 1426, 855, 1427, -1, 856, 857, 858, -1, + 856, 858, 859, -1, 856, 859, 857, -1, + 860, 861, 862, -1, 860, 864, 863, -1, + 860, 865, 864, -1, 860, 863, 866, -1, + 860, 866, 861, -1, 860, 867, 865, -1, + 860, 862, 867, -1, 881, 868, 879, -1, + 881, 874, 868, -1, 881, 883, 869, -1, + 881, 869, 874, -1, 870, 871, 872, -1, + 870, 872, 873, -1, 870, 873, 874, -1, + 870, 874, 875, -1, 870, 875, 876, -1, + 870, 876, 871, -1, 877, 879, 878, -1, + 877, 878, 880, -1, 877, 881, 879, -1, + 877, 880, 882, -1, 877, 882, 883, -1, + 877, 883, 881, -1, 894, 885, 884, -1, + 894, 884, 893, -1, 894, 886, 885, -1, + 894, 895, 886, -1, 887, 888, 892, -1, + 887, 892, 893, -1, 887, 893, 889, -1, + 887, 890, 888, -1, 887, 889, 890, -1, + 891, 893, 892, -1, 891, 895, 894, -1, + 891, 894, 893, -1, 891, 892, 896, -1, + 891, 896, 897, -1, 891, 898, 895, -1, + 891, 897, 898, -1, 906, 899, 900, -1, + 906, 900, 903, -1, 906, 903, 905, -1, + 906, 901, 899, -1, 906, 907, 901, -1, + 902, 903, 904, -1, 902, 905, 903, -1, + 902, 906, 905, -1, 902, 904, 907, -1, + 902, 907, 906, -1, 908, 909, 910, -1, + 908, 943, 909, -1, 908, 910, 911, -1, + 908, 911, 940, -1, 908, 941, 943, -1, + 908, 940, 941, -1, 912, 978, 913, -1, + 912, 917, 978, -1, 912, 914, 917, -1, + 912, 913, 915, -1, 912, 915, 914, -1, + 916, 918, 917, -1, 916, 919, 918, -1, + 916, 917, 919, -1, 920, 921, 922, -1, + 920, 922, 923, -1, 920, 936, 921, -1, + 920, 923, 924, -1, 920, 924, 934, -1, + 920, 934, 936, -1, 925, 933, 926, -1, + 925, 927, 928, -1, 925, 926, 927, -1, + 925, 928, 942, -1, 925, 929, 933, -1, + 925, 942, 929, -1, 930, 931, 932, -1, + 930, 932, 933, -1, 930, 934, 931, -1, + 930, 933, 935, -1, 930, 936, 934, -1, + 930, 935, 936, -1, 937, 938, 939, -1, + 937, 940, 938, -1, 937, 941, 940, -1, + 937, 939, 942, -1, 937, 943, 941, -1, + 937, 942, 943, -1, 944, 946, 945, -1, + 944, 945, 953, -1, 944, 953, 954, -1, + 944, 947, 946, -1, 944, 954, 948, -1, + 944, 948, 947, -1, 949, 951, 950, -1, + 949, 952, 951, -1, 949, 953, 952, -1, + 949, 954, 953, -1, 949, 950, 955, -1, + 949, 956, 954, -1, 949, 955, 956, -1, + 976, 959, 975, -1, 976, 1367, 984, -1, + 976, 984, 993, -1, 976, 993, 957, -1, + 976, 960, 959, -1, 976, 957, 960, -1, + 958, 996, 962, -1, 958, 962, 959, -1, + 958, 998, 996, -1, 958, 959, 960, -1, + 958, 960, 998, -1, 1170, 1176, 961, -1, + 1170, 1177, 1176, -1, 1170, 961, 1172, -1, + 974, 962, 963, -1, 974, 975, 962, -1, + 974, 964, 972, -1, 974, 963, 965, -1, + 974, 965, 964, -1, 1366, 1367, 973, -1, + 1366, 973, 966, -1, 1366, 966, 1180, -1, + 967, 968, 1179, -1, 967, 1179, 969, -1, + 967, 970, 968, -1, 967, 969, 970, -1, + 971, 972, 973, -1, 971, 973, 1367, -1, + 971, 975, 974, -1, 971, 974, 972, -1, + 971, 976, 975, -1, 971, 1367, 976, -1, + 1183, 977, 978, -1, 1183, 978, 1181, -1, + 1183, 1211, 977, -1, 1212, 1214, 1208, -1, + 1213, 1209, 978, -1, 1213, 978, 1214, -1, + 979, 981, 980, -1, 979, 980, 982, -1, + 979, 983, 981, -1, 979, 982, 983, -1, + 1369, 1177, 989, -1, 1369, 984, 1367, -1, + 1369, 993, 984, -1, 1369, 989, 993, -1, + 1142, 1175, 1174, -1, 1142, 1174, 985, -1, + 1142, 985, 1141, -1, 1142, 1140, 992, -1, + 990, 986, 991, -1, 990, 987, 986, -1, + 990, 992, 1140, -1, 990, 1140, 987, -1, + 988, 989, 1175, -1, 988, 990, 991, -1, + 988, 992, 990, -1, 988, 1175, 1142, -1, + 988, 1142, 992, -1, 988, 991, 993, -1, + 988, 993, 989, -1, 994, 995, 996, -1, + 994, 996, 998, -1, 994, 999, 995, -1, + 994, 998, 999, -1, 997, 999, 998, -1, + 997, 998, 1000, -1, 997, 1000, 1003, -1, + 997, 1003, 1149, -1, 997, 1149, 999, -1, + 1001, 1003, 1002, -1, 1001, 1002, 1004, -1, + 1001, 1149, 1003, -1, 1001, 1145, 1149, -1, + 1001, 1331, 1145, -1, 1001, 1330, 1331, -1, + 1001, 1005, 1330, -1, 1001, 1004, 1005, -1, + 1006, 1038, 1007, -1, 1006, 1007, 1008, -1, + 1006, 1008, 1038, -1, 1194, 1193, 1009, -1, + 1194, 1009, 1269, -1, 1010, 1208, 1214, -1, + 1010, 1193, 1208, -1, 1010, 1214, 1193, -1, + 1244, 1197, 1011, -1, 1244, 1011, 1380, -1, + 1412, 1379, 1012, -1, 1412, 1013, 1410, -1, + 1412, 1012, 1013, -1, 1014, 1015, 1016, -1, + 1014, 1016, 1017, -1, 1014, 1017, 1015, -1, + 1200, 1018, 1201, -1, 1200, 1391, 1019, -1, + 1200, 1019, 1018, -1, 1198, 1288, 1020, -1, + 1198, 1021, 1382, -1, 1198, 1020, 1022, -1, + 1198, 1022, 1021, -1, 1383, 1198, 1382, -1, + 1202, 1289, 1490, -1, 1384, 1202, 1490, -1, + 1023, 1204, 1024, -1, 1023, 1205, 1204, -1, + 1023, 1024, 1211, -1, 1023, 1211, 1205, -1, + 1203, 1025, 1204, -1, 1203, 1026, 1025, -1, + 1203, 1502, 1026, -1, 1501, 1502, 1275, -1, + 1216, 1217, 1032, -1, 1216, 1032, 1394, -1, + 1027, 1028, 1041, -1, 1027, 1217, 1028, -1, + 1027, 1041, 1039, -1, 1027, 1039, 1217, -1, + 1388, 1216, 1394, -1, 1388, 1389, 1216, -1, + 1221, 1222, 1029, -1, 1221, 1029, 1197, -1, + 1221, 1197, 1030, -1, 1221, 1030, 1031, -1, + 1221, 1031, 1219, -1, 1221, 1219, 1388, -1, + 1396, 1404, 1407, -1, 1396, 1407, 1222, -1, + 1393, 1032, 1035, -1, 1393, 1394, 1032, -1, + 1033, 1034, 1223, -1, 1033, 1223, 1225, -1, + 1033, 1225, 1397, -1, 1033, 1397, 1393, -1, + 1033, 1035, 1034, -1, 1033, 1393, 1035, -1, + 1400, 1225, 1223, -1, 1036, 1037, 1038, -1, + 1036, 1040, 1039, -1, 1036, 1041, 1037, -1, + 1036, 1039, 1041, -1, 1036, 1038, 1042, -1, + 1036, 1042, 1040, -1, 1230, 1404, 1220, -1, + 1230, 1220, 1226, -1, 1230, 1226, 1433, -1, + 1230, 1521, 1229, -1, 1230, 1433, 1521, -1, + 1234, 1284, 1237, -1, 1228, 1520, 1284, -1, + 1228, 1284, 1234, -1, 1228, 1229, 1521, -1, + 1228, 1521, 1520, -1, 1405, 1232, 1406, -1, + 1405, 1228, 1234, -1, 1409, 1410, 1166, -1, + 1246, 1240, 1239, -1, 1246, 1247, 1057, -1, + 1246, 1058, 1240, -1, 1246, 1057, 1058, -1, + 1250, 1043, 1044, -1, 1250, 1044, 1249, -1, + 1250, 1165, 1043, -1, 1250, 1239, 1165, -1, + 1250, 1246, 1239, -1, 1045, 1049, 1052, -1, + 1045, 1555, 1049, -1, 1045, 1052, 1046, -1, + 1045, 1046, 1555, -1, 1047, 1048, 1052, -1, + 1047, 1052, 1049, -1, 1047, 1050, 1048, -1, + 1047, 1049, 1050, -1, 1418, 1417, 1253, -1, + 1414, 1252, 1051, -1, 1414, 1052, 1417, -1, + 1414, 1051, 1052, -1, 1259, 1053, 1054, -1, + 1259, 1254, 1053, -1, 1259, 1054, 1260, -1, + 1266, 1058, 1267, -1, 1266, 1443, 1055, -1, + 1266, 1055, 1241, -1, 1266, 1241, 1240, -1, + 1266, 1240, 1058, -1, 1056, 1057, 1061, -1, + 1056, 1267, 1058, -1, 1056, 1058, 1057, -1, + 1056, 1268, 1267, -1, 1056, 1061, 1268, -1, + 1248, 1059, 1255, -1, 1248, 1249, 1059, -1, + 1060, 1061, 1247, -1, 1060, 1255, 1256, -1, + 1060, 1248, 1255, -1, 1060, 1247, 1248, -1, + 1060, 1256, 1062, -1, 1060, 1062, 1061, -1, + 1279, 1592, 1431, -1, 1279, 1277, 1592, -1, + 1429, 1592, 1315, -1, 1429, 1315, 1063, -1, + 1429, 1063, 1430, -1, 1066, 1510, 1508, -1, + 1066, 1508, 1155, -1, 1066, 1155, 1154, -1, + 1066, 1154, 1065, -1, 1424, 1064, 1425, -1, + 1424, 1065, 1064, -1, 1424, 1066, 1065, -1, + 1424, 1510, 1066, -1, 1600, 1457, 1456, -1, + 1600, 1456, 1281, -1, 1608, 1282, 1067, -1, + 1608, 1067, 1457, -1, 1068, 1069, 1070, -1, + 1068, 1070, 1591, -1, 1068, 1432, 1069, -1, + 1068, 1591, 1432, -1, 1594, 1070, 1592, -1, + 1594, 1591, 1070, -1, 1421, 1501, 1273, -1, + 1421, 1496, 1501, -1, 1270, 1194, 1269, -1, + 1523, 1525, 1504, -1, 1434, 1071, 1285, -1, + 1434, 1072, 1071, -1, 1434, 1073, 1072, -1, + 1434, 1074, 1073, -1, 1434, 1075, 1074, -1, + 1434, 1076, 1075, -1, 1434, 1533, 1076, -1, + 1287, 1077, 1078, -1, 1287, 1084, 1077, -1, + 1287, 1289, 1084, -1, 1287, 1078, 1079, -1, + 1287, 1079, 1288, -1, 1293, 1291, 1080, -1, + 1293, 1081, 1297, -1, 1293, 1080, 1081, -1, + 1082, 1083, 1291, -1, 1082, 1291, 1557, -1, + 1082, 1084, 1083, -1, 1082, 1557, 1084, -1, + 1298, 1557, 1085, -1, 1298, 1085, 1295, -1, + 1298, 1295, 1296, -1, 1086, 1557, 1555, -1, + 1086, 1555, 1087, -1, 1086, 1088, 1557, -1, + 1086, 1087, 1088, -1, 1089, 1090, 1091, -1, + 1089, 1092, 1090, -1, 1089, 1091, 1093, -1, + 1089, 1094, 1092, -1, 1089, 1095, 1094, -1, + 1089, 1093, 1096, -1, 1089, 1096, 1095, -1, + 1097, 1099, 1098, -1, 1097, 1106, 1099, -1, + 1097, 1098, 1100, -1, 1097, 1101, 1106, -1, + 1097, 1102, 1101, -1, 1097, 1100, 1102, -1, + 1103, 1105, 1104, -1, 1103, 1104, 1106, -1, + 1103, 1107, 1105, -1, 1103, 1106, 1108, -1, + 1103, 1108, 1109, -1, 1103, 1109, 1107, -1, + 1301, 1110, 1302, -1, 1301, 1304, 1110, -1, + 1306, 1111, 1307, -1, 1306, 1304, 1111, -1, + 1112, 1113, 1300, -1, 1112, 1300, 1114, -1, + 1112, 1309, 1113, -1, 1112, 1114, 1309, -1, + 1451, 1115, 1450, -1, 1451, 1300, 1115, -1, + 1451, 1116, 1117, -1, 1451, 1117, 1300, -1, + 1451, 1631, 1116, -1, 1118, 1120, 1119, -1, + 1118, 1119, 1121, -1, 1118, 1122, 1120, -1, + 1118, 1121, 1122, -1, 1447, 1309, 1632, -1, + 1123, 1313, 1312, -1, 1123, 1124, 1311, -1, + 1123, 1311, 1313, -1, 1123, 1125, 1124, -1, + 1123, 1312, 1125, -1, 1628, 1624, 1312, -1, + 1130, 1133, 1126, -1, 1130, 1126, 1128, -1, + 1127, 1128, 1163, -1, 1127, 1159, 1129, -1, + 1127, 1163, 1159, -1, 1127, 1130, 1128, -1, + 1127, 1129, 1131, -1, 1127, 1131, 1132, -1, + 1127, 1132, 1133, -1, 1127, 1133, 1130, -1, + 1134, 1135, 1136, -1, 1134, 1137, 1135, -1, + 1134, 1136, 1138, -1, 1134, 1138, 1137, -1, + 1139, 1319, 1140, -1, 1139, 1141, 1319, -1, + 1139, 1140, 1142, -1, 1139, 1142, 1141, -1, + 1150, 1143, 1148, -1, 1150, 1147, 1143, -1, + 1144, 1145, 1331, -1, 1144, 1331, 1326, -1, + 1144, 1326, 1146, -1, 1144, 1146, 1147, -1, + 1144, 1148, 1149, -1, 1144, 1149, 1145, -1, + 1144, 1150, 1148, -1, 1144, 1147, 1150, -1, + 1322, 1316, 1151, -1, 1322, 1152, 1316, -1, + 1322, 1151, 1315, -1, 1454, 1316, 1152, -1, + 1458, 1317, 1320, -1, 1329, 1152, 1322, -1, + 1329, 1454, 1152, -1, 1335, 1334, 1464, -1, + 1335, 1153, 1342, -1, 1335, 1465, 1153, -1, + 1335, 1464, 1465, -1, 1469, 1464, 1334, -1, + 1469, 1334, 1154, -1, 1469, 1154, 1155, -1, + 1468, 1469, 1155, -1, 1468, 1155, 1343, -1, + 1350, 1156, 1157, -1, 1350, 1352, 1156, -1, + 1350, 1157, 1158, -1, 1350, 1158, 1349, -1, + 1354, 1160, 1159, -1, 1354, 1161, 1160, -1, + 1354, 1358, 1162, -1, 1354, 1162, 1161, -1, + 1354, 1159, 1163, -1, 1354, 1163, 1355, -1, + 1346, 1345, 1355, -1, 1346, 1163, 1352, -1, + 1346, 1355, 1163, -1, 1164, 1165, 1239, -1, + 1164, 1166, 1165, -1, 1164, 1239, 1409, -1, + 1164, 1409, 1166, -1, 1167, 1477, 1471, -1, + 1167, 1566, 1477, -1, 1167, 1471, 1470, -1, + 1167, 1470, 1566, -1, 1565, 1572, 1566, -1, + 1565, 1568, 1473, -1, 1579, 1257, 1572, -1, + 1579, 1362, 1257, -1, 1579, 1576, 1361, -1, + 1476, 1473, 1477, -1, 1168, 1169, 1177, -1, + 1168, 1177, 1170, -1, 1168, 1172, 1171, -1, + 1168, 1170, 1172, -1, 1168, 1171, 1173, -1, + 1168, 1173, 1174, -1, 1168, 1175, 1169, -1, + 1168, 1174, 1175, -1, 1368, 1179, 1176, -1, + 1368, 1176, 1177, -1, 1368, 1177, 1369, -1, + 1178, 1180, 1179, -1, 1178, 1366, 1180, -1, + 1178, 1179, 1368, -1, 1178, 1368, 1366, -1, + 1210, 1181, 1182, -1, 1210, 1183, 1181, -1, + 1210, 1211, 1183, -1, 1210, 1182, 1207, -1, + 1546, 1371, 1189, -1, 1546, 1189, 1482, -1, + 1184, 1189, 1186, -1, 1184, 1185, 1236, -1, + 1184, 1186, 1185, -1, 1184, 1236, 1482, -1, + 1184, 1482, 1189, -1, 1191, 1186, 1189, -1, + 1191, 1190, 1187, -1, 1191, 1187, 1188, -1, + 1191, 1188, 1186, -1, 1372, 1189, 1371, -1, + 1372, 1374, 1190, -1, 1372, 1190, 1191, -1, + 1372, 1191, 1189, -1, 1372, 1373, 1374, -1, + 1192, 1271, 1272, -1, 1192, 1272, 1193, -1, + 1192, 1193, 1194, -1, 1192, 1270, 1271, -1, + 1192, 1194, 1270, -1, 1195, 1196, 1197, -1, + 1195, 1197, 1244, -1, 1195, 1243, 1196, -1, + 1195, 1244, 1243, -1, 1381, 1379, 1485, -1, + 1381, 1485, 1487, -1, 1484, 1485, 1379, -1, + 1484, 1379, 1412, -1, 1493, 1288, 1198, -1, + 1493, 1492, 1289, -1, 1493, 1198, 1383, -1, + 1199, 1202, 1391, -1, 1199, 1391, 1200, -1, + 1199, 1200, 1201, -1, 1199, 1201, 1289, -1, + 1199, 1289, 1202, -1, 1386, 1391, 1202, -1, + 1386, 1202, 1384, -1, 1274, 1203, 1204, -1, + 1274, 1204, 1205, -1, 1274, 1275, 1502, -1, + 1274, 1502, 1203, -1, 1274, 1207, 1206, -1, + 1274, 1208, 1272, -1, 1274, 1206, 1209, -1, + 1274, 1210, 1207, -1, 1274, 1205, 1211, -1, + 1274, 1211, 1210, -1, 1274, 1212, 1208, -1, + 1274, 1213, 1214, -1, 1274, 1209, 1213, -1, + 1274, 1214, 1212, -1, 1505, 1501, 1496, -1, + 1215, 1216, 1389, -1, 1215, 1217, 1216, -1, + 1215, 1389, 1218, -1, 1215, 1218, 1217, -1, + 1390, 1388, 1219, -1, 1390, 1219, 1391, -1, + 1398, 1404, 1396, -1, 1398, 1220, 1404, -1, + 1398, 1397, 1225, -1, 1398, 1225, 1220, -1, + 1395, 1388, 1394, -1, 1395, 1221, 1388, -1, + 1395, 1222, 1221, -1, 1395, 1396, 1222, -1, + 1399, 1223, 1502, -1, 1399, 1400, 1223, -1, + 1224, 1226, 1225, -1, 1224, 1225, 1400, -1, + 1224, 1227, 1226, -1, 1224, 1400, 1227, -1, + 1401, 1227, 1400, -1, 1401, 1525, 1227, -1, + 1401, 1504, 1525, -1, 1403, 1229, 1228, -1, + 1403, 1228, 1405, -1, 1403, 1404, 1230, -1, + 1403, 1230, 1229, -1, 1231, 1233, 1232, -1, + 1231, 1232, 1405, -1, 1231, 1405, 1234, -1, + 1231, 1235, 1233, -1, 1231, 1236, 1235, -1, + 1231, 1234, 1237, -1, 1231, 1238, 1236, -1, + 1231, 1237, 1238, -1, 1411, 1409, 1239, -1, + 1411, 1239, 1240, -1, 1411, 1240, 1241, -1, + 1411, 1241, 1242, -1, 1411, 1242, 1243, -1, + 1411, 1243, 1244, -1, 1411, 1244, 1380, -1, + 1245, 1247, 1246, -1, 1245, 1249, 1248, -1, + 1245, 1248, 1247, -1, 1245, 1250, 1249, -1, + 1245, 1246, 1250, -1, 1416, 1418, 1253, -1, + 1251, 1414, 1415, -1, 1251, 1360, 1252, -1, + 1251, 1252, 1414, -1, 1251, 1415, 1416, -1, + 1251, 1362, 1360, -1, 1251, 1416, 1253, -1, + 1251, 1268, 1362, -1, 1251, 1253, 1268, -1, + 1262, 1254, 1259, -1, 1262, 1256, 1255, -1, + 1262, 1255, 1254, -1, 1262, 1257, 1256, -1, + 1262, 1263, 1257, -1, 1258, 1259, 1260, -1, + 1258, 1260, 1261, -1, 1258, 1263, 1262, -1, + 1258, 1262, 1259, -1, 1258, 1264, 1263, -1, + 1258, 1261, 1264, -1, 1265, 1266, 1267, -1, + 1265, 1443, 1266, -1, 1265, 1553, 1443, -1, + 1265, 1439, 1553, -1, 1265, 1267, 1268, -1, + 1265, 1268, 1439, -1, 1420, 1269, 1280, -1, + 1420, 1271, 1270, -1, 1420, 1272, 1271, -1, + 1420, 1270, 1269, -1, 1420, 1421, 1273, -1, + 1420, 1274, 1272, -1, 1420, 1275, 1274, -1, + 1420, 1273, 1501, -1, 1420, 1501, 1275, -1, + 1276, 1278, 1277, -1, 1276, 1277, 1279, -1, + 1276, 1280, 1278, -1, 1276, 1420, 1280, -1, + 1276, 1279, 1431, -1, 1276, 1431, 1420, -1, + 1506, 1432, 1591, -1, 1506, 1584, 1432, -1, + 1509, 1510, 1424, -1, 1601, 1281, 1508, -1, + 1601, 1600, 1281, -1, 1601, 1508, 1602, -1, + 1428, 1430, 1282, -1, 1428, 1282, 1608, -1, + 1514, 1457, 1600, -1, 1514, 1608, 1457, -1, + 1283, 1497, 1496, -1, 1283, 1421, 1497, -1, + 1283, 1496, 1421, -1, 1422, 1431, 1499, -1, + 1585, 1615, 1523, -1, 1585, 1614, 1615, -1, + 1585, 1586, 1614, -1, 1527, 1521, 1433, -1, + 1519, 1531, 1542, -1, 1519, 1542, 1284, -1, + 1519, 1284, 1520, -1, 1540, 1376, 1546, -1, + 1539, 1434, 1285, -1, 1539, 1376, 1540, -1, + 1539, 1375, 1376, -1, 1539, 1285, 1375, -1, + 1537, 1529, 1516, -1, 1537, 1536, 1529, -1, + 1286, 1287, 1288, -1, 1286, 1289, 1287, -1, + 1286, 1288, 1493, -1, 1286, 1493, 1289, -1, + 1290, 1293, 1294, -1, 1290, 1291, 1293, -1, + 1290, 1294, 1557, -1, 1290, 1557, 1291, -1, + 1292, 1294, 1293, -1, 1292, 1295, 1294, -1, + 1292, 1296, 1295, -1, 1292, 1293, 1297, -1, + 1292, 1297, 1298, -1, 1292, 1298, 1296, -1, + 1621, 1297, 1443, -1, 1621, 1298, 1297, -1, + 1621, 1623, 1557, -1, 1621, 1557, 1298, -1, + 1442, 1555, 1553, -1, 1442, 1553, 1439, -1, + 1554, 1553, 1555, -1, 1299, 1300, 1304, -1, + 1299, 1304, 1301, -1, 1299, 1302, 1300, -1, + 1299, 1301, 1302, -1, 1303, 1305, 1304, -1, + 1303, 1304, 1306, -1, 1303, 1307, 1305, -1, + 1303, 1306, 1307, -1, 1448, 1446, 1308, -1, + 1448, 1309, 1447, -1, 1448, 1308, 1310, -1, + 1448, 1310, 1309, -1, 1445, 1313, 1311, -1, + 1445, 1311, 1446, -1, 1627, 1628, 1312, -1, + 1627, 1312, 1313, -1, 1627, 1447, 1632, -1, + 1627, 1313, 1445, -1, 1627, 1445, 1447, -1, + 1625, 1450, 1558, -1, 1640, 1558, 1314, -1, + 1640, 1635, 1558, -1, 1640, 1314, 1624, -1, + 1323, 1322, 1315, -1, 1323, 1315, 1324, -1, + 1453, 1461, 1462, -1, 1453, 1328, 1461, -1, + 1453, 1454, 1328, -1, 1455, 1316, 1454, -1, + 1455, 1457, 1316, -1, 1460, 1461, 1328, -1, + 1460, 1328, 1317, -1, 1460, 1317, 1458, -1, + 1466, 1318, 1319, -1, 1466, 1319, 1465, -1, + 1466, 1320, 1318, -1, 1466, 1458, 1320, -1, + 1321, 1329, 1322, -1, 1321, 1323, 1324, -1, + 1321, 1322, 1323, -1, 1321, 1324, 1325, -1, + 1321, 1325, 1326, -1, 1321, 1326, 1331, -1, + 1321, 1331, 1329, -1, 1327, 1328, 1454, -1, + 1327, 1454, 1329, -1, 1327, 1330, 1328, -1, + 1327, 1331, 1330, -1, 1327, 1329, 1331, -1, + 1332, 1333, 1334, -1, 1332, 1334, 1335, -1, + 1332, 1336, 1333, -1, 1332, 1337, 1336, -1, + 1332, 1338, 1337, -1, 1332, 1339, 1338, -1, + 1332, 1340, 1339, -1, 1332, 1341, 1340, -1, + 1332, 1342, 1341, -1, 1332, 1335, 1342, -1, + 1459, 1343, 1462, -1, 1459, 1468, 1343, -1, + 1351, 1344, 1345, -1, 1351, 1348, 1344, -1, + 1351, 1345, 1346, -1, 1351, 1346, 1352, -1, + 1347, 1349, 1348, -1, 1347, 1350, 1349, -1, + 1347, 1348, 1351, -1, 1347, 1352, 1350, -1, + 1347, 1351, 1352, -1, 1353, 1354, 1355, -1, + 1353, 1356, 1357, -1, 1353, 1355, 1356, -1, + 1353, 1357, 1358, -1, 1353, 1358, 1354, -1, + 1562, 1472, 1569, -1, 1359, 1361, 1360, -1, + 1359, 1579, 1361, -1, 1359, 1360, 1362, -1, + 1359, 1362, 1579, -1, 1480, 1572, 1475, -1, + 1480, 1576, 1364, -1, 1480, 1363, 1576, -1, + 1480, 1477, 1363, -1, 1478, 1364, 1576, -1, + 1481, 1480, 1364, -1, 1481, 1364, 1478, -1, + 1365, 1367, 1366, -1, 1365, 1366, 1368, -1, + 1365, 1369, 1367, -1, 1365, 1368, 1369, -1, + 1544, 1482, 1543, -1, 1370, 1371, 1546, -1, + 1370, 1372, 1371, -1, 1370, 1373, 1372, -1, + 1370, 1374, 1373, -1, 1370, 1376, 1375, -1, + 1370, 1546, 1376, -1, 1370, 1377, 1374, -1, + 1370, 1375, 1377, -1, 1378, 1380, 1379, -1, + 1378, 1379, 1381, -1, 1378, 1411, 1380, -1, + 1378, 1381, 1487, -1, 1378, 1487, 1411, -1, + 1486, 1412, 1487, -1, 1486, 1484, 1412, -1, + 1494, 1385, 1491, -1, 1494, 1382, 1385, -1, + 1494, 1383, 1382, -1, 1494, 1493, 1383, -1, + 1489, 1384, 1490, -1, 1489, 1491, 1385, -1, + 1489, 1385, 1391, -1, 1489, 1386, 1384, -1, + 1489, 1391, 1386, -1, 1498, 1523, 1504, -1, + 1498, 1585, 1523, -1, 1387, 1389, 1388, -1, + 1387, 1388, 1390, -1, 1387, 1391, 1389, -1, + 1387, 1390, 1391, -1, 1392, 1394, 1393, -1, + 1392, 1395, 1394, -1, 1392, 1396, 1395, -1, + 1392, 1393, 1397, -1, 1392, 1397, 1398, -1, + 1392, 1398, 1396, -1, 1503, 1400, 1399, -1, + 1503, 1401, 1400, -1, 1503, 1399, 1502, -1, + 1503, 1504, 1401, -1, 1402, 1404, 1403, -1, + 1402, 1403, 1405, -1, 1402, 1405, 1406, -1, + 1402, 1406, 1407, -1, 1402, 1407, 1404, -1, + 1408, 1410, 1409, -1, 1408, 1409, 1411, -1, + 1408, 1412, 1410, -1, 1408, 1487, 1412, -1, + 1408, 1411, 1487, -1, 1413, 1415, 1414, -1, + 1413, 1416, 1415, -1, 1413, 1414, 1417, -1, + 1413, 1417, 1418, -1, 1413, 1418, 1416, -1, + 1419, 1420, 1431, -1, 1419, 1421, 1420, -1, + 1419, 1497, 1421, -1, 1419, 1431, 1422, -1, + 1419, 1499, 1497, -1, 1419, 1422, 1499, -1, + 1610, 1506, 1591, -1, 1423, 1424, 1425, -1, + 1423, 1509, 1424, -1, 1423, 1426, 1427, -1, + 1423, 1425, 1426, -1, 1423, 1427, 1551, -1, + 1423, 1551, 1512, -1, 1423, 1512, 1509, -1, + 1607, 1428, 1608, -1, 1607, 1429, 1430, -1, + 1607, 1430, 1428, -1, 1607, 1592, 1429, -1, + 1515, 1529, 1530, -1, 1518, 1515, 1530, -1, + 1518, 1613, 1515, -1, 1518, 1530, 1531, -1, + 1524, 1615, 1613, -1, 1524, 1613, 1518, -1, + 1583, 1499, 1431, -1, 1583, 1431, 1432, -1, + 1583, 1432, 1584, -1, 1588, 1614, 1586, -1, + 1588, 1584, 1506, -1, 1526, 1433, 1525, -1, + 1526, 1527, 1433, -1, 1535, 1434, 1539, -1, + 1535, 1533, 1434, -1, 1541, 1542, 1531, -1, + 1541, 1535, 1539, -1, 1548, 1435, 1436, -1, + 1548, 1436, 1534, -1, 1548, 1549, 1435, -1, + 1618, 1513, 1516, -1, 1550, 1537, 1516, -1, + 1550, 1516, 1513, -1, 1550, 1548, 1537, -1, + 1550, 1512, 1551, -1, 1437, 1438, 1441, -1, + 1437, 1441, 1442, -1, 1437, 1439, 1438, -1, + 1437, 1442, 1439, -1, 1440, 1441, 1555, -1, + 1440, 1442, 1441, -1, 1440, 1555, 1442, -1, + 1620, 1443, 1553, -1, 1620, 1621, 1443, -1, + 1444, 1445, 1446, -1, 1444, 1447, 1445, -1, + 1444, 1446, 1448, -1, 1444, 1448, 1447, -1, + 1560, 1558, 1635, -1, 1449, 1450, 1625, -1, + 1449, 1451, 1450, -1, 1449, 1625, 1631, -1, + 1449, 1631, 1451, -1, 1634, 1624, 1628, -1, + 1634, 1560, 1635, -1, 1452, 1454, 1453, -1, + 1452, 1455, 1454, -1, 1452, 1453, 1462, -1, + 1452, 1462, 1456, -1, 1452, 1456, 1457, -1, + 1452, 1457, 1455, -1, 1467, 1458, 1466, -1, + 1467, 1468, 1459, -1, 1467, 1461, 1460, -1, + 1467, 1460, 1458, -1, 1467, 1462, 1461, -1, + 1467, 1459, 1462, -1, 1463, 1465, 1464, -1, + 1463, 1466, 1465, -1, 1463, 1467, 1466, -1, + 1463, 1468, 1467, -1, 1463, 1464, 1469, -1, + 1463, 1469, 1468, -1, 1563, 1566, 1470, -1, + 1563, 1470, 1471, -1, 1563, 1471, 1472, -1, + 1563, 1472, 1562, -1, 1567, 1566, 1562, -1, + 1567, 1562, 1569, -1, 1574, 1572, 1565, -1, + 1574, 1476, 1573, -1, 1574, 1565, 1473, -1, + 1574, 1473, 1476, -1, 1571, 1475, 1572, -1, + 1571, 1573, 1475, -1, 1474, 1480, 1475, -1, + 1474, 1476, 1477, -1, 1474, 1477, 1480, -1, + 1474, 1475, 1573, -1, 1474, 1573, 1476, -1, + 1578, 1478, 1576, -1, 1580, 1579, 1572, -1, + 1580, 1572, 1481, -1, 1580, 1481, 1478, -1, + 1580, 1478, 1578, -1, 1479, 1572, 1480, -1, + 1479, 1481, 1572, -1, 1479, 1480, 1481, -1, + 1545, 1546, 1482, -1, 1545, 1482, 1544, -1, + 1483, 1485, 1484, -1, 1483, 1484, 1486, -1, + 1483, 1487, 1485, -1, 1483, 1486, 1487, -1, + 1488, 1489, 1490, -1, 1488, 1491, 1489, -1, + 1488, 1490, 1492, -1, 1488, 1492, 1493, -1, + 1488, 1493, 1494, -1, 1488, 1494, 1491, -1, + 1495, 1504, 1505, -1, 1495, 1498, 1504, -1, + 1495, 1496, 1497, -1, 1495, 1505, 1496, -1, + 1495, 1497, 1499, -1, 1495, 1499, 1498, -1, + 1582, 1498, 1499, -1, 1582, 1585, 1498, -1, + 1582, 1499, 1583, -1, 1500, 1502, 1501, -1, + 1500, 1503, 1502, -1, 1500, 1504, 1503, -1, + 1500, 1505, 1504, -1, 1500, 1501, 1505, -1, + 1589, 1506, 1610, -1, 1589, 1588, 1506, -1, + 1593, 1594, 1592, -1, 1603, 1602, 1596, -1, + 1603, 1597, 1604, -1, 1603, 1596, 1597, -1, + 1507, 1510, 1596, -1, 1507, 1596, 1602, -1, + 1507, 1508, 1510, -1, 1507, 1602, 1508, -1, + 1511, 1509, 1512, -1, 1511, 1510, 1509, -1, + 1511, 1596, 1510, -1, 1598, 1511, 1512, -1, + 1598, 1596, 1511, -1, 1598, 1513, 1618, -1, + 1598, 1512, 1550, -1, 1598, 1550, 1513, -1, + 1609, 1514, 1600, -1, 1609, 1608, 1514, -1, + 1612, 1515, 1613, -1, 1612, 1516, 1529, -1, + 1612, 1529, 1515, -1, 1612, 1618, 1516, -1, + 1517, 1518, 1531, -1, 1517, 1527, 1524, -1, + 1517, 1524, 1518, -1, 1517, 1519, 1520, -1, + 1517, 1531, 1519, -1, 1517, 1520, 1521, -1, + 1517, 1521, 1527, -1, 1522, 1523, 1615, -1, + 1522, 1615, 1524, -1, 1522, 1525, 1523, -1, + 1522, 1526, 1525, -1, 1522, 1524, 1527, -1, + 1522, 1527, 1526, -1, 1616, 1614, 1588, -1, + 1616, 1597, 1617, -1, 1528, 1536, 1535, -1, + 1528, 1530, 1529, -1, 1528, 1529, 1536, -1, + 1528, 1535, 1541, -1, 1528, 1531, 1530, -1, + 1528, 1541, 1531, -1, 1532, 1534, 1533, -1, + 1532, 1533, 1535, -1, 1532, 1535, 1536, -1, + 1532, 1548, 1534, -1, 1532, 1536, 1537, -1, + 1532, 1537, 1548, -1, 1538, 1539, 1540, -1, + 1538, 1541, 1539, -1, 1538, 1542, 1541, -1, + 1538, 1543, 1542, -1, 1538, 1544, 1543, -1, + 1538, 1545, 1544, -1, 1538, 1540, 1546, -1, + 1538, 1546, 1545, -1, 1547, 1549, 1548, -1, + 1547, 1548, 1550, -1, 1547, 1551, 1549, -1, + 1547, 1550, 1551, -1, 1552, 1553, 1554, -1, + 1552, 1620, 1553, -1, 1552, 1554, 1620, -1, + 1622, 1620, 1554, -1, 1622, 1554, 1555, -1, + 1622, 1555, 1556, -1, 1622, 1557, 1623, -1, + 1622, 1556, 1557, -1, 1559, 1625, 1558, -1, + 1559, 1558, 1560, -1, 1638, 1624, 1634, -1, + 1629, 1634, 1628, -1, 1629, 1625, 1559, -1, + 1629, 1560, 1634, -1, 1629, 1559, 1560, -1, + 1561, 1562, 1566, -1, 1561, 1566, 1563, -1, + 1561, 1563, 1562, -1, 1564, 1565, 1566, -1, + 1564, 1566, 1567, -1, 1564, 1568, 1565, -1, + 1564, 1569, 1568, -1, 1564, 1567, 1569, -1, + 1570, 1571, 1572, -1, 1570, 1573, 1571, -1, + 1570, 1572, 1574, -1, 1570, 1574, 1573, -1, + 1575, 1576, 1579, -1, 1575, 1578, 1576, -1, + 1575, 1579, 1578, -1, 1577, 1578, 1579, -1, + 1577, 1579, 1580, -1, 1577, 1580, 1578, -1, + 1581, 1582, 1583, -1, 1581, 1583, 1584, -1, + 1581, 1586, 1585, -1, 1581, 1585, 1582, -1, + 1581, 1584, 1588, -1, 1581, 1588, 1586, -1, + 1587, 1604, 1597, -1, 1587, 1589, 1604, -1, + 1587, 1597, 1616, -1, 1587, 1588, 1589, -1, + 1587, 1616, 1588, -1, 1605, 1604, 1589, -1, + 1605, 1589, 1610, -1, 1605, 1610, 1609, -1, + 1590, 1607, 1610, -1, 1590, 1610, 1591, -1, + 1590, 1592, 1607, -1, 1590, 1593, 1592, -1, + 1590, 1591, 1594, -1, 1590, 1594, 1593, -1, + 1595, 1597, 1596, -1, 1595, 1596, 1598, -1, + 1595, 1598, 1618, -1, 1595, 1617, 1597, -1, + 1595, 1618, 1617, -1, 1599, 1609, 1600, -1, + 1599, 1600, 1601, -1, 1599, 1601, 1602, -1, + 1599, 1603, 1604, -1, 1599, 1602, 1603, -1, + 1599, 1604, 1605, -1, 1599, 1605, 1609, -1, + 1606, 1607, 1608, -1, 1606, 1608, 1609, -1, + 1606, 1610, 1607, -1, 1606, 1609, 1610, -1, + 1611, 1612, 1613, -1, 1611, 1615, 1614, -1, + 1611, 1613, 1615, -1, 1611, 1616, 1617, -1, + 1611, 1614, 1616, -1, 1611, 1617, 1618, -1, + 1611, 1618, 1612, -1, 1619, 1621, 1620, -1, + 1619, 1620, 1622, -1, 1619, 1623, 1621, -1, + 1619, 1622, 1623, -1, 1637, 1640, 1624, -1, + 1637, 1624, 1638, -1, 1639, 1638, 1634, -1, + 1630, 1631, 1625, -1, 1630, 1625, 1629, -1, + 1626, 1628, 1627, -1, 1626, 1629, 1628, -1, + 1626, 1630, 1629, -1, 1626, 1631, 1630, -1, + 1626, 1632, 1631, -1, 1626, 1627, 1632, -1, + 1633, 1634, 1635, -1, 1633, 1639, 1634, -1, + 1633, 1635, 1640, -1, 1633, 1640, 1639, -1, + 1636, 1637, 1638, -1, 1636, 1638, 1639, -1, + 1636, 1640, 1637, -1, 1636, 1639, 1640, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT4_elbow.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT4_elbow.wrl new file mode 100644 index 0000000..e42b943 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_RT4_elbow.wrl @@ -0,0 +1,3318 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_LT4_elbow____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -7.5603069e-008 55.465 -40.510201, + 37.537701 55.465 8.5540705, + 33.4179 55.465 22.8647, + 38.258701 46.924999 4.3039598, + 38.473202 46.924999 -0.00010839443, + 38.473202 46.924999 1.43725, + 33.4179 55.465 33.0019, + 34.924999 55.465 31.452101, + 33.013401 55.465 33.417801, + 34.924999 51.860001 34.485001, + 27.141701 41.089298 48.180801, + 26.941999 41.7775 47.8372, + 13.3939 55.465 -33.835899, + 34.924999 47.597698 -33.7328, + 34.924999 47.707802 -33.6572, + 34.924999 55.465 -28.1975, + 38.5 55.465 -0.00010839621, + 34.924999 51.7076 -30.9105, + -22.864901 55.465 -33.417999, + -12.6439 55.465 31.0366, + -13.3939 55.465 33.835701, + -33.4179 55.465 -22.865, + 33.910099 -8.3580999 -38.490002, + 33.096802 -11.1516 44.513, + 34.924999 6.3526983e-008 -40.395, + 38.473202 46.924999 -1.43747, + -34.924999 55.465 21.0737, + -33.484901 55.465 14.358, + -34.924999 55.465 22.8647, + -33.4179 55.465 22.8647, + -38.258701 46.924999 4.3039598, + -34.695599 -3.77321 46.417999, + -33.910099 -8.3580999 -38.490002, + -34.108501 -7.5078402 44.513, + -34.006302 -7.9577799 46.417999, + 27.869699 39.534901 48.7995, + 32.596298 55.465 14.871, + 36.346001 55.465 12.6969, + 22.864901 55.465 38.944401, + 12.0949 55.465 33.085701, + 12.8809 55.465 -30.926399, + 33.484901 55.465 -12.4298, + -32.3358 55.465 11.8938, + 25.130199 55.319801 39.816399, + 25.1227 55.318298 39.822201, + 25.3554 -24.0179 44.513, + 23.159599 -26.141701 -38.490002, + 22.610001 -26.6185 44.513, + 19.333401 55.465 -40.510201, + 33.4179 55.465 -29.9053, + 22.864901 55.465 -38.623501, + -34.806301 42.367802 -37.268002, + -22.322201 50.0672 -41.8195, + -20.105499 54.107101 -40.8396, + -24.5602 45.8018 -42.854198, + 25.4718 44.213501 -43.180099, + 33.2514 -10.523 46.969299, + 33.959301 -7.9467902 46.969299, + 32.348301 -13.0375 46.969299, + 33.297401 -10.5376 46.417999, + 34.515701 -5.3312802 46.417999, + 34.720299 -3.7760601 44.513, + 34.108501 -7.5078402 44.513, + 34.006302 -7.9577799 46.417999, + 33.6884 -9.0267696 -40.946301, + 33.735001 -9.0392599 -40.395, + 34.695599 -3.77321 46.417999, + 34.467999 -5.3239102 46.969299, + 34.3265 -5.3020501 47.503899, + 31.6971 -14.6646 44.513, + 32.393002 -13.0556 46.417999, + 34.205799 -6.0314102 -41.4809, + 34.601398 -3.02723 -41.4809, + 33.975498 -5.9907999 -41.982498, + 33.549999 -8.9897003 -41.4809, + 34.639198 -4.2056398 -40.395, + 34.670399 -4.2097402 -38.490002, + 34.394402 -6.0646601 -40.395, + 34.792099 -3.04391 -40.395, + 34.346901 -6.0562901 -40.946301, + 34.743999 -3.03971 -40.946301, + 34.887699 35.701 46.847099, + 34.924702 34.735401 46.4603, + -34.923698 36.2719 46.408401, + -38.473202 46.924999 -0.0001083969, + -38.473202 46.924999 1.43725, + -38.5 55.465 -0.00010839704, + -33.959301 -7.9467902 46.969299, + -33.096802 -11.1516 44.513, + -33.297401 -10.5376 46.417999, + -26.441999 53.865002 39.9687, + -25.7321 55.4342 39.351299, + 34.3363 41.584202 42.983299, + 34.736301 44.6166 40.3778, + 34.591499 43.8522 41.080601, + 34.924999 46.207901 38.989601, + 32.413502 55.465 34.034599, + 34.924999 47.7061 37.8204, + 34.797699 44.9804 40.046299, + 24.326799 54.900799 40.594601, + 24.493 55.037601 40.402199, + 24.310499 54.887299 40.613499, + 24.6784 55.1381 40.2206, + -25.1106 55.314899 39.832199, + 24.9233 55.253799 39.991199, + 25.687901 55.429001 39.383701, + 6.9356499 8.4946299 57.870201, + 30.890499 35.720699 49.5606, + 31.75 34.8792 49.5923, + 1.84317 15.1799 56.707199, + 28.236601 38.922401 48.996799, + 5.4832001 9.49718 57.870201, + 6.22963 9.0251703 57.870201, + 4.2056398 -34.639198 -40.395, + 16.230499 -30.924601 -38.490002, + 6.0646601 -34.394402 -40.395, + 12.3846 -32.655399 -38.490002, + 25.348301 -24.0116 46.417999, + 25.1642 -24.2181 46.417999, + 29.6548 -17.629999 48.005501, + 22.4494 -26.754101 -40.395, + 19.9223 -28.452 -41.4809, + 26.141701 -23.159599 -38.490002, + 28.742701 -19.839701 -38.490002, + 28.6089 -20.0322 -40.395, + 27.803499 -21.1357 44.513, + 30.0205 -17.8473 46.417999, + 30.245899 -17.4625 -40.395, + 30.924601 -16.230499 -38.490002, + 29.925699 -18.005699 44.513, + 31.298599 -15.4969 46.417999, + 28.5662 -20.093 46.417999, + 31.2554 -15.4755 46.969299, + 29.979 -17.822701 46.969299, + 33.114799 -10.4798 47.503899, + 32.215401 -12.984 47.503899, + 31.127001 -15.412 47.503899, + 33.819901 -7.9141598 47.503899, + 34.095299 -5.2663398 48.005501, + 26.1553 43.151299 -43.3498, + 27.139799 41.7845 -43.4935, + 28.245199 40.385201 -43.563599, + -26.8508 42.1717 -43.4604, + 24.1747 46.548698 -42.673, + 24.5602 45.8018 -42.854198, + 21.6812 51.255699 -41.5312, + 22.805401 55.465 -38.662201, + 29.926701 55.465 -33.417999, + 34.797699 40.0784 -38.7243, + -22.1759 -26.428301 -41.982498, + -34.924999 47.674198 -33.671501, + -34.924999 48.7262 -32.970798, + -34.924999 52.416199 -30.4097, + -34.924999 44.862598 -35.544102, + -34.782902 41.049301 -38.126202, + -34.798698 42.232899 -37.361698, + -34.779099 40.768501 -38.307499, + -34.790199 40.293301 -38.596298, + -22.864901 55.465 -38.623501, + -27.7526 40.9944 -43.542599, + -34.877899 38.564499 -39.597801, + -34.886902 43.8083 -36.266899, + -34.924999 37.301601 -40.3386, + -34.924999 37.210098 -40.395, + -34.924999 37.316101 -40.329601, + -38.258701 55.465 -4.3041801, + -34.8908 38.2229 -39.7981, + 32.322498 55.465 -31.146601, + 32.6395 -12.378 -40.395, + 31.6528 -14.7599 -40.395, + 32.655399 -12.3846 -38.490002, + 32.818802 -11.9451 -40.395, + 32.773399 -11.9286 -40.946301, + 31.6091 -14.7396 -40.946301, + 34.309101 6.1636328e-008 -42.254601, + 34.368301 -3.00684 -41.982498, + 34.3423 35.0005 -42.228199, + 34.924099 35.7318 46.449799, + 34.890099 35.5345 46.861401, + 34.924 35.931198 46.434502, + 38.258701 55.465 4.3039598, + 34.924301 35.508301 46.452099, + 34.774399 -2.66979 46.969299, + 34.924999 6.2868111e-008 46.417999, + 34.822498 -2.67348 46.417999, + 34.631599 -2.6588299 47.503899, + 34.497299 34.482498 48.004299, + 34.499599 30 48.005501, + 34.321301 34.270599 48.280499, + 34.1366 34.127998 48.512001, + 34.4734 34.442402 48.049999, + 34.182201 30 48.4589, + 34.499599 6.3281682e-008 48.005501, + -34.726799 34.735401 47.5014, + -34.733501 30 47.503899, + -33.140999 34.020901 49.272099, + -33.099899 34.032299 49.291801, + -34.924999 54.886501 31.9491, + -34.924999 55.465 31.452101, + -33.013302 55.465 33.417801, + -38.473202 46.924999 -1.43747, + -32.348301 -13.0375 46.969299, + -34.467999 -5.3239102 46.969299, + -30.924601 -16.230499 -38.490002, + -31.6971 -14.6646 44.513, + -32.393002 -13.0556 46.417999, + -31.298599 -15.4969 46.417999, + -34.3442 35.5616 -41.888802, + -34.8741 36.359798 -40.960999, + -34.768002 35.819 -41.3811, + -34.875599 36.381901 -40.946201, + -34.924999 6.3026121e-008 -40.395, + -34.9244 37.106701 -40.459202, + -38.258701 46.924999 -4.3041801, + 0.61572099 15.279 56.707199, + -24.2451 54.8158 40.7006, + -24.3314 54.8988 40.592999, + 34.628502 38.5728 44.963402, + 34.4571 39.674099 44.292301, + 30.208799 51.427101 38.999901, + 34.359402 40.6534 43.650799, + 34.82 37.318802 45.728699, + 34.867901 37.002499 45.921799, + 34.679798 38.244301 45.163399, + 32.3353 49.123299 38.999901, + 32.638802 48.7869 38.999901, + 29.643801 55.465 36.472401, + 34.530102 43.5089 41.390598, + 34.391499 42.512699 42.250099, + 34.916599 45.924 39.2169, + 34.924999 46.194698 38.999901, + 33.2374 48.117901 38.999901, + 34.851101 45.297001 39.757801, + 34.923698 36.2719 46.408401, + 24.5676 55.085701 40.324402, + 8.2084703 7.2720699 57.870201, + 31.9088 34.735401 49.589001, + 7.5966902 7.9089999 57.870201, + 8.7670097 6.5879798 57.870201, + 6.5490999 5.802 58.290901, + 6.0609999 6.3101702 58.290901, + 24.18 54.727798 40.798401, + 24.1619 54.699001 40.828499, + 24.0919 54.552799 40.967701, + -27.6385 -19.4405 48.850201, + -27.958599 -19.665701 48.4589, + -26.0693 -21.499201 48.850201, + -4.2056398 -34.639198 -40.395, + -32.562901 35.259499 -43.464199, + -32.166302 35.632301 -43.542599, + -6.6494098 -34.286201 46.417999, + 5.6502399 -34.464901 44.513, + 4.2097402 -34.670399 -38.490002, + 19.599501 -28.907 44.513, + 19.8346 -28.7348 -40.395, + 20.0322 -28.6089 -40.395, + 20.004499 -28.569401 -40.946301, + 17.4625 -30.245899 -40.395, + 19.839701 -28.742701 -38.490002, + 14.7599 -31.6528 -40.395, + 6.0562901 -34.346901 -40.946301, + 19.7882 -28.260401 -41.982498, + 24.6957 -24.6957 -40.395, + 26.754101 -22.4494 -40.395, + 21.971901 -26.185101 -42.435799, + 26.7171 -22.4184 -40.946301, + 22.596001 -26.601601 46.417999, + 23.2365 -26.0734 46.417999, + 21.1724 -27.7756 46.417999, + 29.627701 -8.1323795 51.411999, + 29.382 -17.467699 48.4589, + 32.8918 -10.4092 48.005501, + 34.398399 -2.6409199 48.005501, + 33.283001 -7.7885299 48.4589, + 33.592098 -7.8608599 48.005501, + 33.4921 33.966099 49.072399, + -25.472 44.212101 -43.180801, + 25.2946 44.488701 -43.1362, + -25.271799 44.5266 -43.129002, + -26.0219 43.348301 -43.322899, + -22.805401 55.465 -38.662201, + 38.258701 46.924999 -4.3041801, + -22.3263 -26.607401 -41.4809, + -16.230499 -30.924601 -38.490002, + -20.0322 -28.6089 -40.395, + -19.839701 -28.742701 -38.490002, + -26.141701 -23.159599 -38.490002, + -23.159599 -26.141701 -38.490002, + -22.4494 -26.754101 -40.395, + -22.610001 -26.6185 44.513, + -18.5273 -26.4597 -43.521801, + -18.8339 -26.8976 -43.378502, + -21.106501 -25.153799 -43.378502, + -24.6957 -24.6957 -40.395, + -22.4184 -26.717199 -40.946301, + -21.971901 -26.185101 -42.435799, + -21.4289 -25.538 -43.1446, + -31.6898 0.54545897 -43.619999, + -31.7355 0.26886201 -43.619999, + -34.145199 34.972401 -42.404499, + -29.926701 55.465 -33.417999, + -19.333401 55.465 -40.510201, + -32.322498 55.465 -31.146601, + -34.924999 55.465 -28.1975, + -32.849998 35.044701 -43.373402, + 32.418999 -11.7996 -41.982498, + 32.638802 -11.8796 -41.4809, + 33.3241 -8.9291601 -41.982498, + 31.2673 -14.5802 -41.982498, + 34.817902 39.699299 -38.942902, + 34.779598 41.562199 -37.805698, + 30.080099 -17.3668 -41.4809, + 28.452 -19.9223 -41.4809, + 28.569401 -20.004499 -40.946301, + 30.204201 -17.4384 -40.946301, + 31.4793 -14.679 -41.4809, + 34.876801 6.5072356e-008 46.969299, + 26.691299 55.465 38.685501, + -34.891899 35.711102 46.8367, + -34.8894 35.6964 46.849201, + -34.924999 6.253871e-008 46.417999, + -34.822498 -2.67348 46.417999, + -34.774399 -2.66979 46.969299, + -34.631599 -2.6588299 47.503899, + -34.499599 6.1610365e-008 48.005501, + -34.733501 6.2990907e-008 47.503899, + -34.647701 34.735401 47.715599, + -34.499599 30 48.005501, + -34.451599 34.413799 48.085999, + -33.790901 30 48.850201, + -34.081902 -2.6166201 48.4589, + -33.790901 6.5444596e-008 48.850201, + -33.394798 -5.1581502 48.850201, + -33.6917 -2.5866599 48.850201, + -32.902 -7.6993599 48.850201, + -34.924999 46.207901 38.989601, + -34.924999 49.0998 36.7043, + -34.924999 51.388302 34.871498, + -32.410801 55.465 34.037201, + -34.924999 47.7061 37.8204, + -38.258701 55.465 4.3039598, + -34.884602 45.555698 39.529499, + -34.924999 46.194698 38.999901, + -28.3666 53.342999 38.999901, + -34.720299 -3.7760601 44.513, + -34.515701 -5.3312802 46.417999, + -33.114799 -10.4798 47.503899, + -33.2514 -10.523 46.969299, + -32.215401 -12.984 47.503899, + -29.045601 -17.267799 48.850201, + -34.398399 -2.6409199 48.005501, + -34.3265 -5.3020501 47.503899, + -32.655399 -12.3846 -38.490002, + -24.394899 -24.394899 -41.982498, + -24.560301 -24.560301 -41.4809, + -24.6616 -24.6616 -40.946301, + -30.245899 -17.4625 -40.395, + -31.6528 -14.7599 -40.395, + -30.979601 -14.446 -42.435799, + -31.2673 -14.5802 -41.982498, + -32.301201 34.431198 49.544102, + -7.395 4.6763101 58.290901, + -24.069 54.038101 41.325401, + -24.420401 54.984402 40.481998, + -24.6742 55.140701 40.221699, + -24.7139 55.1651 40.181, + 29.510599 37.2258 49.3848, + 30.000401 36.664101 49.468498, + 7.395 4.6763101 58.290901, + -6.31112 -1.55555 58.603001, + -5.1963801 3.90482 58.603001, + -5.7554598 3.0207 58.603001, + 4.8653202 4.3102999 58.603001, + 6.99473 5.2561998 58.290901, + 4.1108999 5.0349302 58.603001, + 5.5335898 6.77742 58.290901, + 4.9702902 7.2007098 58.290901, + 0.529338 13.1354 57.342201, + -24.112101 54.602402 40.9226, + -24.061899 54.449299 41.0546, + -24.1127 54.604401 40.920898, + -24.1369 54.654598 40.873001, + -28.4184 38.650501 49.073101, + -24.122101 53.865002 41.410198, + -1.84317 15.1799 56.707199, + -0.615722 15.279 56.707199, + -16.3538 -30.845699 46.417999, + -16.684401 -30.681999 46.417999, + -16.3592 -30.856701 44.513, + -19.599501 -28.907 44.513, + -18.9841 -29.3148 46.417999, + 2.9791701 -34.052101 -42.435799, + 3.00684 -34.368401 -41.982498, + -7.9170832e-008 -33.790798 -42.827202, + -7.89965e-008 -33.337502 -43.1446, + -2.90556 -33.210602 -43.1446, + -8.6283798 -32.2015 -43.1446, + -16.1507 -27.973801 -43.521801, + 3.03971 -34.743999 -40.946301, + 3.02723 -34.601398 -41.4809, + -3.03971 -34.743999 -40.946301, + -7.5099535e-008 -34.876801 -40.946301, + -31.267599 -5.51333 -43.57, + -33.293098 34.814499 -43.1698, + -32.835899 6.594977e-008 -43.378502, + -33.0784 34.9095 -43.278702, + -7.946133e-008 -34.924999 -38.490002, + -7.6610796e-008 -34.924999 -40.395, + 9.3434296 -33.652 44.513, + 8.3580999 -33.910099 -38.490002, + 9.0392599 -33.735001 -40.395, + 5.6465502 -34.441101 46.417999, + 1.8908 -34.873798 44.513, + 4.0053201 -34.694599 46.417999, + 3.04391 -34.792099 -40.395, + -23.8531 -19.364 51.411999, + 4.0657101 -30.1721 51.5541, + 12.9176 -32.421001 46.417999, + 12.9271 -32.4445 44.513, + 11.8052 -32.869301 46.417999, + 26.9443 -22.2208 46.417999, + 28.409599 -19.9828 47.503899, + 29.8559 -17.7495 47.503899, + 28.526699 -20.0653 46.969299, + 16.3538 -30.845699 46.417999, + 16.684401 -30.681999 46.417999, + 14.2867 -31.8692 46.417999, + 16.3592 -30.856701 44.513, + 11.9451 -32.818802 -40.395, + 12.378 -32.6395 -40.395, + 24.560301 -24.560301 -41.4809, + 22.4184 -26.717199 -40.946301, + 22.3263 -26.607401 -41.4809, + 24.6616 -24.6616 -40.946301, + 22.1759 -26.428301 -41.982498, + 24.394899 -24.394899 -41.982498, + 26.607401 -22.3263 -41.4809, + 25.129499 -24.1847 46.969299, + 26.796499 -22.0989 47.503899, + 26.907 -22.1901 46.969299, + 18.9841 -29.3148 46.417999, + 19.5877 -28.890301 46.417999, + 27.6385 -19.4405 48.850201, + 29.045601 -17.267799 48.850201, + 28.692301 -10.1802 51.5541, + 29.498699 -8.0969601 51.493999, + 31.7041 -12.7779 48.4589, + 32.589199 -10.3135 48.4589, + 31.998501 -12.8966 48.005501, + 31.341101 -12.6316 48.850201, + 32.216099 -10.1954 48.850201, + 30.2822 -14.9937 48.850201, + 30.6329 -15.1673 48.4589, + 30.9174 -15.3082 48.005501, + 34.081902 -2.6166201 48.4589, + 29.868799 -5.8940301 51.5541, + 30.011101 -5.9221001 51.493999, + 29.3589 -8.0585899 51.5541, + 14.847 3.6594601 56.707199, + -0.26172799 -6.49473 58.603001, + -0.78348798 -6.45261 58.603001, + 34.1805 34.869202 -42.437901, + 26.2001 55.465 -36.447399, + 34.566898 35.306198 -41.859798, + 34.492699 35.184502 -41.9944, + 34.577599 35.3312 -41.8358, + 34.499599 6.3413815e-008 -41.982498, + 34.724602 35.6749 -41.505199, + 34.733501 6.5214863e-008 -41.4809, + -19.8346 -28.7348 -40.395, + -17.4625 -30.245899 -40.395, + -28.2183 -19.848301 48.005501, + -29.925699 -18.005699 44.513, + -28.742701 -19.839701 -38.490002, + -27.803499 -21.1357 44.513, + -29.979 -17.822701 46.969299, + -30.0205 -17.8473 46.417999, + -31.2554 -15.4755 46.969299, + -28.5662 -20.093 46.417999, + -28.526699 -20.0653 46.969299, + -28.409599 -19.9828 47.503899, + -25.348301 -24.0116 46.417999, + -25.1642 -24.2181 46.417999, + -26.9443 -22.2208 46.417999, + -25.3554 -24.0179 44.513, + -19.5877 -28.890301 46.417999, + -18.957899 -29.2743 46.969299, + -25.153799 -21.106501 -43.378502, + -32.337101 -5.7019 -43.378502, + -31.360901 -1.33948 -43.619999, + -31.497601 -1.09471 -43.619999, + -20.408501 -24.321899 -43.57, + -20.762899 -24.744301 -43.521801, + -23.2185 -23.2185 -43.378502, + -21.720301 -25.8853 -42.827202, + -29.817101 2.4348199 -43.619999, + -30.3447 2.2475801 -43.619999, + -30.086201 2.35601 -43.619999, + -30.8174 1.94763 -43.619999, + -30.5895 2.1108799 -43.619999, + -31.5072 1.07468 -43.619999, + -31.2115 1.55002 -43.619999, + -31.0256 1.75989 -43.619999, + -31.3727 1.32065 -43.619999, + -31.75 36.112999 -43.57, + -31.3283 36.631802 -43.57, + -29.2974 39.130299 -43.57, + -29.3811 55.465 -33.935299, + -33.492401 34.757301 -43.049198, + -26.2001 55.465 -36.447399, + 31.3207 36.6521 -43.57, + 31.192101 36.813499 -43.57, + 19.381599 -27.6798 -42.827202, + 18.5273 -26.4597 -43.521801, + 28.260401 -19.7882 -41.982498, + 27.6798 -19.381599 -42.827202, + 23.8937 -23.8937 -42.827202, + 21.720301 -25.8853 -42.827202, + 34.924999 44.862598 -35.544102, + 34.809101 42.367298 -37.2649, + 34.7915 42.0373 -37.493, + 34.733501 30 47.503899, + 34.647701 34.735401 47.715599, + 34.733501 6.1983499e-008 47.503899, + 34.876801 30 46.969299, + 34.796101 34.735401 47.313499, + 34.890099 34.735401 46.887402, + 34.883801 35.638699 46.894901, + 29.754499 51.906799 38.999901, + 33.789101 33.994701 48.848099, + 33.703499 33.975399 48.920898, + 33.604599 34.338699 48.734299, + -34.890099 35.5345 46.861401, + -34.876801 6.2170528e-008 46.969299, + -34.910198 35.929901 46.665501, + -33.841099 34.002102 48.807098, + -27.206301 53.865002 39.452499, + -33.789501 33.9939 48.848499, + -34.182201 30 48.4589, + -34.182201 6.5954076e-008 48.4589, + -34.144901 34.239799 48.4272, + -34.042801 34.076302 48.6143, + -27.8512 53.865002 38.999901, + -34.179798 34.162899 48.456799, + -34.243698 34.2033 48.383202, + -33.365601 47.973801 38.999901, + -29.6378 55.465 36.4772, + -34.495899 39.390099 44.469799, + -34.373798 40.454201 43.785801, + -30.5611 51.0522 38.999901, + -34.670399 -4.2097402 -38.490002, + -34.792099 -3.04391 -40.395, + -32.216099 -10.1954 48.850201, + -30.9174 -15.3082 48.005501, + -31.998501 -12.8966 48.005501, + -31.127001 -15.412 47.503899, + -31.7041 -12.7779 48.4589, + -30.6329 -15.1673 48.4589, + -29.382 -17.467699 48.4589, + -29.6548 -17.629999 48.005501, + -29.8559 -17.7495 47.503899, + -33.592098 -7.8608599 48.005501, + -34.095299 -5.2663398 48.005501, + -33.819901 -7.9141598 47.503899, + -32.8918 -10.4092 48.005501, + -33.781601 -5.2178898 48.4589, + -33.283001 -7.7885299 48.4589, + -32.589199 -10.3135 48.4589, + -34.639198 -4.2056398 -40.395, + -34.394402 -6.0646601 -40.395, + -33.735001 -9.0392599 -40.395, + -32.773399 -11.9286 -40.946301, + -32.818802 -11.9451 -40.395, + -31.6091 -14.7396 -40.946301, + -32.6395 -12.378 -40.395, + -33.549999 -8.9897003 -41.4809, + -33.6884 -9.0267696 -40.946301, + -32.638802 -11.8796 -41.4809, + -8.7670097 6.5879798 57.870201, + -26.941999 41.7775 47.8372, + -27.1511 41.062199 48.193401, + 3.8887401 10.2538 57.870201, + 5.6356101 11.8768 57.342201, + 4.70121 9.9076004 57.870201, + 4.6616502 12.2918 57.342201, + 3.75085 7.9047499 58.290901, + 3.1026199 8.1809397 58.290901, + 5.9798698 2.54778 58.603001, + 5.7554598 3.0207 58.603001, + 5.4937401 3.47403 58.603001, + 5.1963801 3.90482 58.603001, + 8.2992296 2.77069 58.290901, + 8.0493698 3.4295199 58.290901, + 6.1654902 2.0583401 58.603001, + 10.6477 2.6244299 57.870201, + 10.402 3.4727099 57.870201, + 12.764 3.14605 57.342201, + 9.2686901 5.8611698 57.870201, + 7.7473102 4.0661001 58.290901, + 10.0889 4.29846 57.870201, + 12.4695 4.16293 57.342201, + 8.2992296 -2.77069 58.290901, + 15.0933 -2.4529099 56.707199, + -4.8653202 -4.3102999 58.603001, + -5.4937401 -3.47403 58.603001, + -2.7865 -5.8724298 58.603001, + -2.30493 -6.07761 58.603001, + -6.31112 1.55555 58.603001, + -6.4158301 1.04267 58.603001, + -5.9798698 2.54778 58.603001, + -5.4937401 3.47403 58.603001, + -6.1654902 2.0583401 58.603001, + 3.0510399 10.5334 57.870201, + 3.65746 12.627 57.342201, + 2.62955 12.8804 57.342201, + -29.567301 37.167301 49.389599, + -29.3657 37.399399 49.3545, + -28.9431 37.929199 49.249001, + 0.78348798 6.45261 58.603001, + 1.80841 6.2433701 58.603001, + -6.47892 0.52303302 58.603001, + 24.042999 54.229099 41.213001, + 24.0506 54.386501 41.103298, + -24.0424 54.284599 41.176201, + -24.0446 54.199902 41.231499, + 24.062799 54.066898 41.309799, + 24.073 54.021198 41.3344, + 24.122101 53.865002 41.410198, + 28.8255 38.084 49.2145, + -12.9176 -32.421001 46.417999, + -12.9271 -32.4445 44.513, + -14.2867 -31.8692 46.417999, + -11.8052 -32.869301 46.417999, + -26.796499 -22.0989 47.503899, + -26.907 -22.1901 46.969299, + -24.347 -23.4317 48.850201, + -22.375999 -21.053499 51.411999, + -6.6402302 -34.2388 46.969299, + -9.2417002 -33.630001 46.969299, + -11.7889 -32.823898 46.969299, + -11.7405 -32.689098 47.503899, + -14.267 -31.825199 46.969299, + -16.661301 -30.6397 46.969299, + 15.6176 -27.630301 -43.57, + -7.961075e-008 -32.835899 -43.378502, + 2.90556 -33.210602 -43.1446, + -5.8677201 -33.2775 -42.827202, + -2.94507 -33.6623 -42.827202, + -13.6511 -29.275 -43.521801, + -11.2305 -30.8557 -43.378502, + -5.7019 -32.337101 -43.378502, + -5.789 -32.831001 -43.1446, + -2.86184 -32.710999 -43.378502, + -8.49856 -31.7171 -43.378502, + -19.6061 -28.000401 -42.435799, + -19.381599 -27.6798 -42.827202, + -17.091101 -29.6026 -42.435799, + -19.9223 -28.452 -41.4809, + -19.7882 -28.260401 -41.982498, + -20.004499 -28.569401 -40.946301, + -3.00684 -34.368401 -41.982498, + -2.9791701 -34.052101 -42.435799, + -7.5583827e-008 -34.182201 -42.435799, + -7.698938e-008 -34.499599 -41.982498, + -7.572433e-008 -34.733501 -41.4809, + -6.0314102 -34.205799 -41.4809, + -3.02723 -34.601398 -41.4809, + -9.0392599 -33.735001 -40.395, + -9.3434296 -33.652 44.513, + -6.0646601 -34.394402 -40.395, + -8.3580999 -33.910099 -38.490002, + -9.2544804 -33.676601 46.417999, + -6.0562901 -34.346901 -40.946301, + -12.378 -32.6395 -40.395, + -11.9451 -32.818802 -40.395, + -14.7599 -31.6528 -40.395, + -12.3846 -32.655399 -38.490002, + -31.684799 -0.56713498 -43.619999, + -32.178398 -2.8152499 -43.521801, + -32.710999 -2.86184 -43.378502, + -31.8106 -5.6090698 -43.521801, + -32.3013 6.2476978e-008 -43.521801, + -31.733 -0.29095501 -43.619999, + -31.75 -0.011116701 -43.619999, + -32.831001 -5.789 -43.1446, + -33.2775 -5.8677201 -42.827202, + -33.210602 -2.90555 -43.1446, + -34.601398 -3.02723 -41.4809, + -34.205799 -6.0314102 -41.4809, + -34.346901 -6.0562901 -40.946301, + -34.743999 -3.03971 -40.946301, + -34.876801 6.2713305e-008 -40.946301, + -31.753 -11.5572 -42.827202, + -30.624901 -14.2806 -42.827202, + -14.0677 -5.9937 56.707199, + -15.0933 -2.4529099 56.707199, + -4.0053201 -34.694599 46.417999, + -1.33772 -34.899399 46.417999, + -1.8908 -34.873798 44.513, + -3.99979 -34.646702 46.969299, + -3.04391 -34.792099 -40.395, + -4.2097402 -34.670399 -38.490002, + -5.6502399 -34.464901 44.513, + -5.6465502 -34.441101 46.417999, + -1.33039 -34.708 47.503899, + 1.33588 -34.8512 46.969299, + 1.33772 -34.899399 46.417999, + -1.33588 -34.8512 46.969299, + 1.33039 -34.708 47.503899, + -1.3001699 -6.3686399 58.603001, + -1.80841 -6.2433701 58.603001, + -3.1026199 -8.1809397 58.290901, + -0.615722 -15.279 56.707199, + -0.370709 -30.442499 51.5541, + 3.05866 -14.9823 56.707199, + 6.2572899 -29.7948 51.5541, + 1.8612601 -30.5331 51.493999, + 1.85244 -30.388399 51.5541, + -0.372473 -30.5875 51.493999, + 18.580299 -28.691299 48.4589, + 11.9286 -32.773399 -40.946301, + 23.204399 -26.037399 46.969299, + 18.879999 -29.1541 47.503899, + 21.1432 -27.7372 46.969299, + 21.056299 -27.623301 47.503899, + 18.957899 -29.2743 46.969299, + 18.752899 -28.9578 48.005501, + 14.0677 -5.9937 56.707199, + 12.4695 -4.16293 57.342201, + 14.5044 -4.8422799 56.707199, + 14.847 -3.6594601 56.707199, + 12.764 -3.14605 57.342201, + 10.6477 -2.6244299 57.870201, + 10.402 -3.4727099 57.870201, + 11.4457 -10.14 56.707199, + 23.162399 -19.7582 51.5541, + 25.9153 -16.252199 51.493999, + 24.767599 -18.179701 51.411999, + 26.028601 -16.323299 51.411999, + 24.6598 -18.1005 51.493999, + 26.6161 -21.9501 48.005501, + 27.958599 -19.665701 48.4589, + 28.2183 -19.848301 48.005501, + 28.0054 -12.3057 51.493999, + 28.829 -10.2286 51.493999, + 27.8727 -12.2474 51.5541, + 27.0324 -14.3172 51.493999, + 28.127899 -12.3595 51.411999, + 28.955099 -10.2734 51.411999, + 27.1507 -14.3798 51.411999, + 33.394798 -5.1581502 48.850201, + 33.781601 -5.2178898 48.4589, + 30.1423 -5.948 51.411999, + 32.902 -7.6993599 48.850201, + 33.790798 6.2424945e-008 48.850201, + 33.6917 -2.5866599 48.850201, + 34.182201 6.2203078e-008 48.4589, + 33.790798 30 48.850201, + 33.905701 34.020901 48.749001, + 33.9389 34.032299 48.717899, + 15.0933 2.4529099 56.707199, + 30.438299 1.11999 51.547401, + 30.383801 1.2517101 51.5648, + 30.4447 2.9751501 51.493999, + 26.312099 55.465 38.944401, + 8.0493698 -3.4295199 58.290901, + 9.7102699 -5.0963402 57.870201, + 10.0889 -4.29846 57.870201, + 12.0941 -5.1528101 57.342201, + 11.6402 -6.1092701 57.342201, + 10.5095 -7.8973799 57.342201, + 33.9939 34.7827 -42.639, + 34.112598 34.8298 -42.516102, + 34.882 36.463001 -40.8909, + 34.895401 36.548401 -40.827301, + 34.876801 6.2202965e-008 -40.946301, + 34.801998 35.954201 -41.2701, + -26.8976 -18.8339 -43.378502, + -26.4597 -18.5273 -43.521801, + -27.4963 -15.875 -43.57, + -27.630301 -15.6176 -43.57, + -31.7171 -8.49856 -43.378502, + -32.201599 -8.6283798 -43.1446, + -29.835199 -10.8591 -43.57, + -30.3533 -11.0477 -43.521801, + -28.775299 -13.4181 -43.57, + -31.606001 -0.836182 -43.619999, + -30.6681 -8.2174997 -43.57, + -31.200701 -8.3601999 -43.521801, + -24.321899 -20.408501 -43.57, + -22.4506 -22.4506 -43.57, + -31.197599 -1.5674 -43.619999, + -26.008101 -18.2111 -43.57, + -24.744301 -20.762899 -43.521801, + -22.8405 -22.8405 -43.521801, + -33.522202 34.751499 -43.0294, + -33.706799 34.734001 -42.895302, + -33.337502 6.429476e-008 -43.1446, + -33.7896 34.741299 -42.825699, + -33.878601 34.7491 -42.750801, + 34.052101 -2.9791701 -42.435799, + 13.6511 -29.275 -43.521801, + 16.1507 -27.973801 -43.521801, + 30.580099 -2.1168101 -43.619999, + 18.2111 -26.008101 -43.57, + 15.875 -27.4963 -43.57, + 19.6061 -28.000401 -42.435799, + 22.8405 -22.8405 -43.521801, + 22.4506 -22.4506 -43.57, + 20.408501 -24.321899 -43.57, + 29.6026 -17.091101 -42.435799, + 29.2637 -16.895399 -42.827202, + 29.8776 -17.2498 -41.982498, + 30.979601 -14.446 -42.435799, + 25.538 -21.4289 -43.1446, + 26.185101 -21.971901 -42.435799, + 28.000401 -19.6061 -42.435799, + 26.428301 -22.1759 -41.982498, + 25.8853 -21.720301 -42.827202, + 24.1705 -24.1705 -42.435799, + 21.106501 -25.153799 -43.378502, + 18.8339 -26.8976 -43.378502, + 21.4289 -25.538 -43.1446, + 20.762899 -24.744301 -43.521801, + 23.2185 -23.2185 -43.378502, + 23.5732 -23.5732 -43.1446, + 34.885799 38.4268 -39.676399, + 34.878601 43.668701 -36.365101, + 34.791801 35.165199 47.302799, + 34.764999 35.0438 47.409599, + 27.8512 53.865002 38.999901, + 34.863098 35.487202 47.019199, + -34.872299 34.735401 46.9683, + -34.800701 35.173901 47.290199, + -34.796101 34.735401 47.313499, + -34.890099 34.735401 46.887402, + -34.876801 30 46.969299, + -33.624298 33.9678 48.980801, + -26.6819 55.465 38.692001, + -26.312099 55.465 38.944401, + -13.1034 -1.05782 57.342201, + -12.9758 -2.1087699 57.342201, + -13.146 6.448952e-008 57.342201, + -15.2418 -1.23044 56.707199, + -12.764 -3.14605 57.342201, + -14.5044 -4.8422799 56.707199, + -14.847 -3.6594601 56.707199, + -32.611401 48.817402 38.999901, + -34.334702 41.4025 43.118698, + -34.570099 38.9053 44.7663, + -28.4205 -11.6709 51.411999, + -30.2822 -14.9937 48.850201, + -31.341101 -12.6316 48.850201, + -27.4928 -13.7144 51.411999, + -29.0695 -9.5235796 51.493999, + -28.9317 -9.4784498 51.5541, + -28.162701 -11.565 51.5541, + -28.296801 -11.6201 51.493999, + -29.1966 -9.5652399 51.411999, + -27.3085 -19.121599 -43.1446, + -25.538 -21.4289 -43.1446, + -23.5732 -23.5732 -43.1446, + -23.8937 -23.8937 -42.827202, + -24.1705 -24.1705 -42.435799, + -28.000401 -19.6061 -42.435799, + -26.185101 -21.971901 -42.435799, + -26.428301 -22.1759 -41.982498, + -25.8853 -21.720301 -42.827202, + -27.6798 -19.381599 -42.827202, + -29.2637 -16.895399 -42.827202, + -29.6026 -17.091101 -42.435799, + -29.8776 -17.2498 -41.982498, + -31.4793 -14.679 -41.4809, + -32.283699 34.442402 49.547798, + -32.836399 34.127998 49.401402, + -30.2194 3.69802 51.5541, + -32.5536 34.270599 49.489601, + -5.4832001 9.49718 57.870201, + -30.8969 35.714199 49.561001, + -30.100401 36.5536 49.482399, + -31.75 34.8792 49.5923, + -31.9088 34.735401 49.589001, + -3.25 5.6291599 58.603001, + -3.8887401 10.2538 57.870201, + -3.75085 7.9047499 58.290901, + -4.70121 9.9076004 57.870201, + -5.6356101 11.8768 57.342201, + -4.6616502 12.2918 57.342201, + -4.3747602 7.5773001 58.290901, + -27.5623 40.0937 48.603298, + -27.403099 40.6563 48.320202, + -27.9566 39.371498 48.858601, + -27.4221 40.389099 48.486698, + 27.743799 39.7449 48.7318, + 27.423201 40.386501 48.487801, + 6.4158301 1.04267 58.603001, + 6.31112 1.55555 58.603001, + 6.47892 0.52303302 58.603001, + 8.6362104 1.40352 58.290901, + 8.4952698 2.0939 58.290901, + 11.6402 6.1092701 57.342201, + 9.7102699 5.0963402 57.870201, + 11.1109 7.0261102 57.342201, + 12.0941 5.1528101 57.342201, + 32.3251 34.413799 49.540501, + 8.7495098 6.5193603e-008 58.290901, + 8.7211399 0.70404297 58.290901, + 6.5 6.4936984e-008 58.603001, + 13.1034 -1.05782 57.342201, + 12.9758 -2.1087699 57.342201, + 10.9308 -0.882429 57.870201, + 10.8244 -1.75913 57.870201, + 13.1034 1.05782 57.342201, + 10.9664 6.4345471e-008 57.870201, + 13.146 6.2771413e-008 57.342201, + 10.9308 0.882429 57.870201, + 15.2418 1.23044 56.707199, + 12.9758 2.1087699 57.342201, + 10.8244 1.75913 57.870201, + -8.7211399 -0.70404297 58.290901, + -6.4158301 -1.04267 58.603001, + -8.6362104 -1.40352 58.290901, + -6.47892 -0.52303302 58.603001, + -6.5 6.2862441e-008 58.603001, + -8.7495098 6.1771146e-008 58.290901, + -10.8244 -1.75913 57.870201, + -10.9308 -0.882429 57.870201, + -5.9798698 -2.54778 58.603001, + -5.1963801 -3.90482 58.603001, + -6.1654902 -2.0583401 58.603001, + -5.7554598 -3.0207 58.603001, + -3.69242 -5.34939 58.603001, + -4.5027099 -4.68782 58.603001, + -3.25 -5.6291699 58.603001, + -4.1108999 -5.0349302 58.603001, + -8.6362104 1.40352 58.290901, + -11.6402 6.1092701 57.342201, + -11.1109 7.0261102 57.342201, + -9.2686901 5.8611698 57.870201, + -10.0889 4.29846 57.870201, + -12.0941 5.1528101 57.342201, + -9.7102699 5.0963402 57.870201, + -8.2992296 2.77069 58.290901, + -8.0493698 3.4295199 58.290901, + -7.7473102 4.0661001 58.290901, + 1.7501301 8.57269 58.290901, + 2.4342699 8.4040699 58.290901, + 1.3218499 10.8864 57.870201, + 1.0546401 8.6857204 58.290901, + 2.1935599 10.7448 57.870201, + 1.5845799 13.0502 57.342201, + 0.35230801 8.7424202 58.290901, + -3.0510399 10.5334 57.870201, + -3.65746 12.627 57.342201, + -2.62955 12.8804 57.342201, + 3.25 5.6291599 58.603001, + 1.3001699 6.3686399 58.603001, + 2.30493 6.07761 58.603001, + 4.5027099 4.68782 58.603001, + 3.69242 5.3494 58.603001, + 2.7865 5.8724298 58.603001, + 4.3747602 7.5773001 58.290901, + -18.879999 -29.1541 47.503899, + -16.592899 -30.5138 47.503899, + -24.629 -23.702999 48.4589, + -26.6161 -21.9501 48.005501, + -26.371201 -21.748199 48.4589, + -21.1432 -27.7372 46.969299, + -23.2365 -26.0734 46.417999, + -25.129499 -24.1847 46.969299, + -22.596001 -26.601601 46.417999, + -21.1724 -27.7756 46.417999, + -3.9833601 -34.504398 47.503899, + -2.5918801 -30.334299 51.5541, + -14.2084 -31.6945 47.503899, + -9.2090197 -29.311001 51.411999, + -8.9539499 -32.582901 48.850201, + -11.324 -28.560499 51.411999, + 13.4181 -28.775299 -43.57, + 30.3347 -2.2524199 -43.619999, + -11.0477 -30.3533 -43.521801, + -8.3601999 -31.200701 -43.521801, + -2.8152499 -32.178398 -43.521801, + -19.121599 -27.3085 -43.1446, + -16.417999 -28.436701 -43.378502, + -13.8771 -29.759399 -43.378502, + -17.4384 -30.204201 -40.946301, + -17.3668 -30.080099 -41.4809, + -8.9897003 -33.549999 -41.4809, + -9.0267696 -33.6884 -40.946301, + -11.9286 -32.773399 -40.946301, + -14.7396 -31.6091 -40.946301, + -14.089 -30.214001 -43.1446, + -11.4021 -31.327 -43.1446, + -16.895399 -29.2637 -42.827202, + -16.6688 -28.871099 -43.1446, + -11.5572 -31.753 -42.827202, + -14.2806 -30.624901 -42.827202, + 32.245998 35.5569 -43.527199, + 30.624901 -14.2806 -42.827202, + -33.017502 -8.8470001 -42.435799, + -32.6395 -8.7457199 -42.827202, + -32.1208 -11.691 -42.435799, + -33.3241 -8.9291601 -41.982498, + -33.975498 -5.9907999 -41.982498, + -32.419102 -11.7996 -41.982498, + -33.662899 -5.9356799 -42.435799, + -30.438299 -1.11999 51.547401, + -30.383801 -1.2517101 51.5648, + 3.0510399 -10.5334 57.870201, + 2.62955 -12.8804 57.342201, + 0.61572099 -15.279 56.707199, + 1.84317 -15.1799 56.707199, + -3.75085 -7.9047499 58.290901, + -3.8887401 -10.2538 57.870201, + 5.42239 -14.2977 56.707199, + 3.65746 -12.627 57.342201, + 4.6616502 -12.2918 57.342201, + 4.2543201 -14.6876 56.707199, + 12.5859 -27.7215 51.5541, + 1.2942801 -33.766102 48.850201, + 1.86941 -30.666599 51.411999, + 1.30927 -34.157101 48.4589, + -0.37410301 -30.7213 51.411999, + 6.5079899 -33.5569 48.4589, + 3.8752501 -33.567902 48.850201, + 16.661301 -30.6397 46.969299, + 16.592899 -30.5138 47.503899, + 11.7405 -32.689098 47.503899, + 11.7889 -32.823898 46.969299, + 14.267 -31.825199 46.969299, + 8.9897003 -33.549999 -41.4809, + 9.0267696 -33.6884 -40.946301, + 6.0314102 -34.205799 -41.4809, + 5.9907999 -33.975498 -41.982498, + 22.953501 -25.7558 48.005501, + 23.1091 -25.930401 47.503899, + 20.9146 -27.4373 48.005501, + 25.0263 -24.0854 47.503899, + 12.9241 -8.1727104 56.707199, + 12.2246 -9.1861601 56.707199, + 11.1109 -7.0261102 57.342201, + 13.5398 -7.1062498 56.707199, + 24.5429 -18.014799 51.5541, + 25.7924 -16.1752 51.5541, + 26.904301 -14.2493 51.5541, + 14.2492 -26.920799 51.547501, + 14.1393 -26.937 51.5611, + 8.6864796 -12.5845 56.707199, + 21.761499 -21.4981 51.493999, + 21.6584 -21.396299 51.5541, + 23.272699 -19.852301 51.493999, + 20.4849 -26.8736 48.850201, + 20.722099 -27.1849 48.4589, + 18.3995 -24.437599 51.493999, + 20.134199 -23.029301 51.493999, + 20.2223 -23.129999 51.411999, + 18.4799 -24.544399 51.411999, + 20.038799 -22.920099 51.5541, + 18.3123 -24.321699 51.5541, + 24.8577 -23.923201 48.005501, + 30.496099 -3.7318799 51.411999, + 33.218498 34.002102 49.233002, + 33.335999 33.985298 49.165001, + 33.459 33.9678 49.0938, + 32.965698 34.076302 49.351002, + 26.432699 53.865002 39.974899, + 5.9798698 -2.54778 58.603001, + 7.395 -4.6763101 58.290901, + 9.2686901 -5.8611698 57.870201, + 7.7473102 -4.0661001 58.290901, + 5.1963801 -3.90482 58.603001, + 5.4937401 -3.47403 58.603001, + 5.7554598 -3.0207 58.603001, + 9.6709499 -11.8448 56.707199, + 10.5927 -11.0282 56.707199, + 2.1935599 -10.7448 57.870201, + 2.4342699 -8.4040604 58.290901, + 4.8653202 -4.3102999 58.603001, + 4.5027099 -4.68782 58.603001, + -23.7493 -19.279699 51.493999, + -25.202999 -17.571199 51.411999, + -26.4184 -15.6846 51.411999, + -10.5095 -7.8973799 57.342201, + -29.759399 -13.8771 -43.378502, + -30.8557 -11.2305 -43.378502, + -29.275 -13.6511 -43.521801, + -27.973801 -16.1507 -43.521801, + -28.436701 -16.417999 -43.378502, + -28.871099 -16.6688 -43.1446, + -30.214001 -14.089 -43.1446, + -31.327 -11.4021 -43.1446, + -33.939999 34.762901 -42.693802, + -34.116402 34.831799 -42.511799, + -33.790901 6.1626494e-008 -42.827202, + -34.245399 34.915001 -42.358101, + -34.052101 -2.9791701 -42.435799, + -33.6623 -2.94507 -42.827202, + 33.761101 34.735199 -42.851799, + 33.7854 34.736801 -42.831799, + 33.615398 34.741402 -42.962502, + 33.9865 6.5608447e-008 -42.6315, + 33.9524 34.7663 -42.6819, + 34.182201 6.3216284e-008 -42.435799, + 33.790798 6.1519287e-008 -42.827202, + 11.0477 -30.3533 -43.521801, + 10.8591 -29.835199 -43.57, + -7.6585131e-008 -32.3013 -43.521801, + -7.5608341e-008 -31.75 -43.57, + -29.261101 2.49998 -43.619999, + 15.6176 39.814201 -43.57, + -4.7707601 39.814201 -43.57, + -28.722 39.814201 -43.57, + 26.8976 -18.8339 -43.378502, + 27.3085 -19.121599 -43.1446, + 25.153799 -21.106501 -43.378502, + 26.4597 -18.5273 -43.521801, + 24.744301 -20.762899 -43.521801, + 34.924999 37.301601 -40.3386, + 34.890701 38.288601 -39.757702, + 29.3811 55.465 -33.935299, + 34.924999 37.316101 -40.329601, + 34.924999 37.210098 -40.395, + 38.258701 55.465 -4.3041801, + -30.507999 -0.95146197 51.525101, + -33.5923 33.966099 49.003899, + -33.3745 33.975399 49.146, + -30.5807 -0.744892 51.493999, + -30.3978 1.22357 51.5611, + -30.408701 1.48228 51.5541, + -15.2914 6.1412564e-008 56.707199, + -30.4387 1.12024 51.547501, + -8.2084703 -7.2720699 57.870201, + -9.1065798 -9.4809599 57.342201, + -7.5966902 -7.9089999 57.870201, + -6.0609999 -6.3101702 58.290901, + -6.5490999 -5.802 58.290901, + -6.99473 -5.2561998 58.290901, + -7.395 -4.6763101 58.290901, + -8.7670097 -6.5879798 57.870201, + -34.4561 42.999298 41.8335, + -34.481701 43.212101 41.653599, + -34.645699 44.117599 40.831402, + -34.730301 44.584702 40.4072, + -34.9175 36.439201 46.292198, + -30.204201 -17.4384 -40.946301, + -28.6089 -20.0322 -40.395, + -26.7171 -22.4184 -40.946301, + -26.754101 -22.4494 -40.395, + -12.9758 2.1087699 57.342201, + -15.0933 2.4529099 56.707199, + -14.847 3.6594601 56.707199, + -15.2418 1.23044 56.707199, + -2.7865 5.8724298 58.603001, + -3.1026199 8.1809397 58.290901, + 8.7211399 -0.70404297 58.290901, + 6.47892 -0.52303302 58.603001, + 8.6362104 -1.40352 58.290901, + -10.6477 2.6244299 57.870201, + -10.402 3.4727099 57.870201, + -8.4952698 2.0939 58.290901, + -12.764 3.14605 57.342201, + -12.4695 4.16293 57.342201, + -10.9308 0.882429 57.870201, + -8.7211399 0.70404297 58.290901, + -10.9664 6.5662917e-008 57.870201, + -10.8244 1.75913 57.870201, + -13.1034 1.05782 57.342201, + -0.26172799 6.49473 58.603001, + 0.26172999 6.49473 58.603001, + -0.78348798 6.45261 58.603001, + -0.44157201 10.9575 57.870201, + -0.35230801 8.7424202 58.290901, + 0.44157299 10.9575 57.870201, + -0.529338 13.1354 57.342201, + -1.3218499 10.8864 57.870201, + -1.5845799 13.0502 57.342201, + -1.7501301 8.57269 58.290901, + -2.1935599 10.7448 57.870201, + -1.0546401 8.6857204 58.290901, + -18.752899 -28.9578 48.005501, + -18.580299 -28.691299 48.4589, + -18.367599 -28.3629 48.850201, + -20.4849 -26.8736 48.850201, + -22.481899 -25.2267 48.850201, + -21.056299 -27.623301 47.503899, + -23.204399 -26.037399 46.969299, + -9.6709499 -11.8448 56.707199, + -8.3141499 -10.183 57.342201, + -11.2747 -28.436199 51.493999, + -16.258499 -25.713499 51.5611, + -8.6864796 -12.5845 56.707199, + -18.899099 -23.868601 51.5541, + -17.263 -25.4151 51.411999, + -17.1064 -25.1845 51.5541, + -3.92013 -33.956699 48.4589, + -6.5079899 -33.5569 48.4589, + -3.9565401 -34.271999 48.005501, + -6.4334798 -33.172798 48.850201, + -3.8752501 -33.567902 48.850201, + -1.2942801 -33.766102 48.850201, + -1.30927 -34.157101 48.4589, + -1.32143 -34.4743 48.005501, + -9.1417599 -33.266399 48.005501, + -9.2037401 -33.491901 47.503899, + -9.0576496 -32.9603 48.4589, + -6.5684199 -33.868599 48.005501, + -6.6129498 -34.098202 47.503899, + -4.8431702 -30.339399 51.411999, + -2.6042299 -30.478701 51.493999, + -2.6156199 -30.612 51.411999, + -9.1254597 -29.045 51.5541, + -13.9829 -31.191401 48.4589, + -11.5542 -32.1702 48.4589, + -11.6615 -32.469002 48.005501, + -14.1127 -31.481001 48.005501, + -11.4219 -31.801901 48.850201, + -13.8228 -30.834299 48.850201, + -16.3295 -30.029499 48.4589, + -16.142599 -29.685699 48.850201, + -16.481199 -30.3083 48.005501, + 8.2174997 -30.6681 -43.57, + 2.94507 -33.6623 -42.827202, + -14.5802 -31.2673 -41.982498, + -14.446 -30.979601 -42.435799, + -11.7996 -32.418999 -41.982498, + -17.2498 -29.8776 -41.982498, + -14.679 -31.4793 -41.4809, + -11.8796 -32.638802 -41.4809, + -8.8470001 -33.017502 -42.435799, + -11.691 -32.1208 -42.435799, + -8.9291601 -33.3241 -41.982498, + -8.7457199 -32.6395 -42.827202, + -5.9356699 -33.662899 -42.435799, + -5.9907999 -33.975498 -41.982498, + 32.536999 35.2813 -43.470901, + 32.861 35.037399 -43.369301, + 29.759399 -13.8771 -43.378502, + 28.436701 -16.417999 -43.378502, + 28.871099 -16.6688 -43.1446, + 30.214001 -14.089 -43.1446, + -30.1464 -5.1895399 51.493999, + -30.300501 -2.96105 51.5541, + -30.0035 -5.1649499 51.5541, + -30.4447 -2.9751501 51.493999, + -30.5779 -2.9881699 51.411999, + -30.2782 -5.2122402 51.411999, + -29.816999 -7.4085002 51.411999, + -29.687099 -7.3762398 51.493999, + -29.5464 -7.34128 51.5541, + -0.35230801 -8.7424202 58.290901, + 0.44157299 -10.9575 57.870201, + 1.3218499 -10.8864 57.870201, + 1.5845799 -13.0502 57.342201, + 0.529338 -13.1354 57.342201, + -0.44157201 -10.9575 57.870201, + -0.529338 -13.1354 57.342201, + -2.1935599 -10.7448 57.870201, + -1.5845799 -13.0502 57.342201, + -1.3218499 -10.8864 57.870201, + -3.65746 -12.627 57.342201, + -3.0510399 -10.5334 57.870201, + -1.0546401 -8.6857204 58.290901, + -1.7501301 -8.57269 58.290901, + -2.4342699 -8.4040604 58.290901, + -4.9702902 -7.2007098 58.290901, + -6.9356499 -8.4946299 57.870201, + -5.5335898 -6.77742 58.290901, + 12.6458 -27.8535 51.493999, + 8.4154797 -29.2586 51.5541, + 10.5288 -28.566299 51.5541, + 10.5789 -28.702299 51.493999, + 9.2544804 -33.676601 46.417999, + 6.6494098 -34.286201 46.417999, + 3.9565401 -34.271999 48.005501, + 3.92013 -33.956699 48.4589, + 1.32143 -34.4743 48.005501, + 6.31458 -30.067699 51.411999, + 6.4334798 -33.172798 48.850201, + 4.1029401 -30.4484 51.411999, + 4.0850701 -30.3158 51.493999, + 6.2870898 -29.936701 51.493999, + 8.4555502 -29.3979 51.493999, + 14.1127 -31.481001 48.005501, + 14.2084 -31.6945 47.503899, + 16.481199 -30.3083 48.005501, + 11.6615 -32.469002 48.005501, + 16.3295 -30.029499 48.4589, + 18.367599 -28.3629 48.850201, + 14.679 -31.4793 -41.4809, + 11.8796 -32.638802 -41.4809, + 14.7396 -31.6091 -40.946301, + 17.3668 -30.080099 -41.4809, + 17.4384 -30.204201 -40.946301, + 11.7996 -32.418999 -41.982498, + 8.9291601 -33.3241 -41.982498, + 16.1891 -25.8004 51.547401, + 16.2759 -25.6873 51.5648, + 16.488001 -25.593599 51.5541, + 24.347 -23.4317 48.850201, + 22.7423 -25.518801 48.4589, + 22.481899 -25.2267 48.850201, + 24.629 -23.702999 48.4589, + 21.856701 -21.592199 51.411999, + 26.0693 -21.499201 48.850201, + 23.3745 -19.9391 51.411999, + 26.371201 -21.748199 48.4589, + 30.687099 -1.49586 51.411999, + 30.654301 -0.055089999 51.458, + 30.5807 0.744892 51.493999, + 30.3633 -3.7156301 51.493999, + 30.2194 -3.69802 51.5541, + 15.2418 -1.23044 56.707199, + 30.6294 0.37607899 51.4711, + 30.624599 0.444675 51.473598, + 30.7145 0.74814999 51.411999, + 30.6548 0.013644902 51.457802, + 32.696499 34.194901 49.447701, + 32.677502 34.2033 49.454498, + 30.300501 2.96105 51.5541, + 32.834702 34.134102 49.398102, + 4.70121 -9.9076004 57.870201, + 3.8887401 -10.2538 57.870201, + 6.57302 -11.3848 57.342201, + 5.4832001 -9.49718 57.870201, + 5.6356101 -11.8768 57.342201, + 7.64568 -13.2427 56.707199, + 6.5552902 -13.815 56.707199, + 8.2084703 -7.2720699 57.870201, + 6.5490999 -5.802 58.290901, + 6.0609999 -6.3101702 58.290901, + 6.99473 -5.2561998 58.290901, + 8.7670097 -6.5879798 57.870201, + 9.8399496 -8.7174397 57.342201, + 9.1065798 -9.4809599 57.342201, + 1.7501301 -8.57269 58.290901, + 1.80841 -6.2433701 58.603001, + 4.9702902 -7.2007098 58.290901, + 4.1108999 -5.0349302 58.603001, + 4.3747602 -7.5773001 58.290901, + 6.9356499 -8.4946299 57.870201, + 5.5335898 -6.77742 58.290901, + 6.22963 -9.0251703 57.870201, + 7.5966902 -7.9089999 57.870201, + 8.3141499 -10.183 57.342201, + 7.4678001 -10.819 57.342201, + -11.4457 -10.14 56.707199, + -22.173 -20.862499 51.5541, + -23.6367 -19.188299 51.5541, + -12.2246 -9.1861601 56.707199, + -10.5927 -11.0282 56.707199, + -9.8399496 -8.7174397 57.342201, + -26.178699 -15.5423 51.5541, + -12.9241 -8.1727104 56.707199, + -24.9743 -17.4118 51.5541, + -25.093201 -17.494699 51.493999, + -26.303301 -15.6163 51.493999, + -13.5398 -7.1062498 56.707199, + -27.243299 -13.5899 51.5541, + -27.3731 -13.6546 51.493999, + -34.499599 6.3247334e-008 -41.982498, + -34.182201 6.142745e-008 -42.435799, + -34.4174 35.083401 -42.1171, + -34.495701 35.203499 -41.980202, + -34.368401 -3.00684 -41.982498, + -34.733501 6.5317181e-008 -41.4809, + -34.587101 35.3438 -41.8204, + 5.6090698 -31.8106 -43.521801, + 5.7019 -32.337101 -43.378502, + 8.3601999 -31.200701 -43.521801, + 2.8152499 -32.178398 -43.521801, + 2.86184 -32.710999 -43.378502, + 8.49856 -31.7171 -43.378502, + 11.2305 -30.8557 -43.378502, + 16.6688 -28.871099 -43.1446, + 16.417999 -28.436701 -43.378502, + 19.121599 -27.3085 -43.1446, + 13.8771 -29.759399 -43.378502, + 14.089 -30.214001 -43.1446, + -30.624599 -0.444675 51.473598, + -30.558001 0.75038099 51.503601, + -30.5201 0.91436601 51.520401, + -30.537399 -0.85720998 51.513401, + -30.617399 0.493628 51.4772, + -30.553499 1.4893399 51.493999, + -10.6477 -2.6244299 57.870201, + -8.4952698 -2.0939 58.290901, + -12.4695 -4.16293 57.342201, + -10.402 -3.4727099 57.870201, + -8.0493698 -3.4295199 58.290901, + -8.2992296 -2.77069 58.290901, + -9.7102699 -5.0963402 57.870201, + -11.6402 -6.1092701 57.342201, + -11.1109 -7.0261102 57.342201, + -9.2686901 -5.8611698 57.870201, + -12.0941 -5.1528101 57.342201, + -10.0889 -4.29846 57.870201, + -7.7473102 -4.0661001 58.290901, + -34.8237 37.322399 45.7234, + -34.724899 37.9743 45.325298, + -34.372299 42.303902 42.421001, + -34.848499 37.158901 45.8232, + -30.303301 51.3269 38.999901, + -28.452 -19.9223 -41.4809, + -30.080099 -17.3668 -41.4809, + -28.260401 -19.7882 -41.982498, + -28.569401 -20.004499 -40.946301, + -26.607401 -22.3263 -41.4809, + -1.80841 6.2433701 58.603001, + -2.4342699 8.4040699 58.290901, + -1.3001699 6.3686399 58.603001, + -2.30493 6.07761 58.603001, + -6.5490999 5.802 58.290901, + -4.8653202 4.3102999 58.603001, + -6.99473 5.2561998 58.290901, + -8.2084703 7.2720699 57.870201, + -5.5335898 6.77742 58.290901, + -4.1108999 5.0349302 58.603001, + -4.5027099 4.68782 58.603001, + -6.0609999 6.3101702 58.290901, + -4.9702902 7.2007098 58.290901, + -3.69242 5.3494 58.603001, + -6.22963 9.0251703 57.870201, + -6.9356499 8.4946299 57.870201, + -7.5966902 7.9089999 57.870201, + 6.31112 -1.55555 58.603001, + 8.4952698 -2.0939 58.290901, + 6.1654902 -2.0583401 58.603001, + 6.4158301 -1.04267 58.603001, + -22.953501 -25.7558 48.005501, + -24.8577 -23.923201 48.005501, + -25.0263 -24.0854 47.503899, + -23.1091 -25.930401 47.503899, + -22.7423 -25.518801 48.4589, + -20.9146 -27.4373 48.005501, + -20.722099 -27.1849 48.4589, + -17.187799 -25.304399 51.493999, + -6.5552902 -13.815 56.707199, + -5.42239 -14.2977 56.707199, + -11.2213 -28.301399 51.5541, + -4.6616502 -12.2918 57.342201, + -20.688999 -22.5322 51.493999, + -18.9891 -23.9823 51.493999, + -20.591 -22.4254 51.5541, + -20.779499 -22.630699 51.411999, + -22.278601 -20.961901 51.493999, + -19.0721 -24.0872 51.411999, + -3.05866 -14.9823 56.707199, + -4.2543201 -14.6876 56.707199, + -2.62955 -12.8804 57.342201, + -1.84317 -15.1799 56.707199, + -7.0142102 -29.7747 51.493999, + -9.1689196 -29.1833 51.493999, + -7.0448899 -29.905001 51.411999, + -6.9809699 -29.6336 51.5541, + -4.8220801 -30.2073 51.493999, + -4.7992301 -30.064199 51.5541, + 5.51333 -31.267599 -43.57, + 4.7707601 -31.3654 -43.57, + 29.806299 -2.43732 -43.619999, + 2.76719 -31.6292 -43.57, + 8.7457199 -32.6395 -42.827202, + 8.8470001 -33.017502 -42.435799, + 5.9356799 -33.662899 -42.435799, + 5.8677201 -33.2775 -42.827202, + 8.6283798 -32.2015 -43.1446, + 5.789 -32.831001 -43.1446, + 11.5572 -31.753 -42.827202, + 11.4021 -31.327 -43.1446, + 33.6096 6.5281313e-008 -42.954102, + 33.356499 34.7929 -43.133499, + 33.384201 34.784401 -43.117199, + 33.111698 34.8927 -43.263199, + 33.576801 34.743 -42.991798, + 30.808701 -1.9545799 -43.619999, + 31.017799 -1.7677701 -43.619999, + 24.321899 -20.408501 -43.57, + 26.008101 -18.2111 -43.57, + 27.973801 -16.1507 -43.521801, + 29.275 -13.6511 -43.521801, + 30.3533 -11.0477 -43.521801, + 27.630301 -15.6176 -43.57, + 27.4963 -15.875 -43.57, + 30.8557 -11.2305 -43.378502, + 33.337502 6.4066825e-008 -43.1446, + 32.835899 6.2567018e-008 -43.378502, + -5.4832001 -9.49718 57.870201, + -4.70121 -9.9076004 57.870201, + -4.3747602 -7.5773001 58.290901, + -6.22963 -9.0251703 57.870201, + -5.6356101 -11.8768 57.342201, + -6.57302 -11.3848 57.342201, + -7.4678001 -10.819 57.342201, + 14.7093 -26.9736 51.411999, + 15.2795 -26.575001 51.458, + 6.6129498 -34.098202 47.503899, + 9.2417002 -33.630001 46.969299, + 9.2037401 -33.491901 47.503899, + 6.6402302 -34.2388 46.969299, + 9.1417599 -33.266399 48.005501, + 6.5684199 -33.868599 48.005501, + 3.9833601 -34.504398 47.503899, + 3.99979 -34.646702 46.969299, + 9.0576496 -32.9603 48.4589, + 8.9539499 -32.582901 48.850201, + 11.5542 -32.1702 48.4589, + 8.4925404 -29.526501 51.411999, + 13.8228 -30.834299 48.850201, + 16.142599 -29.685699 48.850201, + 12.7011 -27.9753 51.411999, + 13.9829 -31.191401 48.4589, + 11.4219 -31.801901 48.850201, + 10.6252 -28.827801 51.411999, + 15.6404 -26.337799 51.4711, + 15.3392 -26.541 51.457802, + 16.639 -25.8279 51.411999, + 16.077999 -25.945 51.525101, + 14.4682 -26.888399 51.520401, + 30.617399 -0.493628 51.4772, + 2.7865 -5.8724298 58.603001, + 3.75085 -7.9047499 58.290901, + 3.1026199 -8.1809397 58.290901, + 2.30493 -6.07761 58.603001, + 3.25 -5.6291699 58.603001, + 3.69242 -5.34939 58.603001, + 0.78348798 -6.45261 58.603001, + 1.3001699 -6.3686399 58.603001, + 1.0546401 -8.6857204 58.290901, + 0.26172999 -6.49473 58.603001, + 0.35230801 -8.7424202 58.290901, + 33.210602 -2.90555 -43.1446, + 33.6623 -2.94507 -42.827202, + 32.6395 -8.7457199 -42.827202, + 33.017502 -8.8470001 -42.435799, + 33.662899 -5.9356799 -42.435799, + 33.2775 -5.8677201 -42.827202, + 32.2015 -8.6283798 -43.1446, + 32.1208 -11.691 -42.435799, + 31.753 -11.5572 -42.827202, + 31.327 -11.4021 -43.1446, + 14.446 -30.979601 -42.435799, + 11.691 -32.1208 -42.435799, + 14.5802 -31.2673 -41.982498, + 14.2806 -30.624901 -42.827202, + 17.091101 -29.6026 -42.435799, + 17.2498 -29.8776 -41.982498, + 16.895399 -29.2637 -42.827202, + -4.7707601 -31.3654 -43.57, + -2.76719 -31.6292 -43.57, + -5.6090698 -31.8106 -43.521801, + -5.51333 -31.267599 -43.57, + 29.25 2.5 -43.619999, + -29.541 2.4830101 -43.619999, + 28.424299 2.35971 -43.619999, + 29.683001 0.75 -43.619999, + -30.654699 -1.1009175e-006 51.457802, + -30.6294 -0.37607899 51.4711, + -30.654301 0.055090096 51.458, + -30.654699 -0.013644998 51.457802, + -30.7145 -0.74814999 51.411999, + -15.3749 -26.519899 51.458, + -15.3156 -26.5546 51.457802, + -13.3786 -27.657801 51.411999, + -15.3618 -26.607401 51.411999, + -14.2492 -26.920401 51.547401, + -7.64568 -13.2427 56.707199, + -14.1079 -26.938999 51.5648, + -13.2572 -27.406799 51.5541, + -15.9289 -26.0888 51.503601, + -16.051901 -25.974001 51.520401, + -14.43 -26.8965 51.525101, + 28.9701 -2.4842801 -43.619999, + -29.238899 -2.49998 -43.619999, + 29.25 -2.5 -43.619999, + 29.5299 -2.4842801 -43.619999, + 30.075701 -2.35971 -43.619999, + 15.9303 -26.0902 51.503201, + 15.6974 -26.299299 51.473598, + 16.566601 -25.715401 51.493999, + 16.011101 -26.017599 51.513401, + 14.8812 -26.7623 51.4772, + 14.6453 -26.8561 51.493999, + 30.553499 -1.4893399 51.493999, + 30.558001 -0.75038099 51.503601, + 30.507999 0.95146197 51.525101, + 30.537399 0.85720998 51.513401, + 32.831001 -5.789 -43.1446, + 31.7171 -8.49856 -43.378502, + -8.2174997 -30.6681 -43.57, + -29.7955 -2.43977 -43.619999, + -29.5189 -2.4855001 -43.619999, + -31.009899 -1.77561 -43.619999, + -31.6134 0.81519699 -43.619999, + -29.996099 -0.43969601 -43.619999, + 31.204599 -1.55872 -43.619999, + 26.997601 1.08471 -43.619999, + 30.580099 2.1168101 -43.619999, + 29.806299 2.43732 -43.619999, + 29.5299 2.4842801 -43.619999, + 30.808701 1.9545799 -43.619999, + 30.3347 2.2524199 -43.619999, + 30.075701 2.35971 -43.619999, + 28.722 39.814201 -43.57, + 31.3668 1.33008 -43.619999, + 31.017799 1.7677701 -43.619999, + 31.204599 1.55872 -43.619999, + 31.502399 1.08471 -43.619999, + 31.6873 0.55630201 -43.619999, + 31.609699 0.82569802 -43.619999, + 31.75 6.2830054e-008 -43.619999, + 31.75 36.112999 -43.57, + 32.1661 35.6325 -43.542599, + 32.3013 6.4970692e-008 -43.521801, + -14.6296 -26.841101 51.503201, + -14.9272 -26.743999 51.473598, + -15.7362 -26.2686 51.4772, + -14.5264 -26.8748 51.513401, + -13.3203 -27.5373 51.493999, + 31.609699 -0.82569802 -43.619999, + 31.734301 0.27991101 -43.619999, + 31.3668 -1.33008 -43.619999, + 31.502399 -1.08471 -43.619999, + 28.775299 -13.4181 -43.57, + 29.835199 -10.8591 -43.57, + 30.6681 -8.2174997 -43.57, + 31.8106 -5.6090698 -43.521801, + 31.6873 -0.55630201 -43.619999, + 31.267599 -5.51333 -43.57, + 31.200701 -8.3601999 -43.521801, + 32.178398 -2.8152499 -43.521801, + 31.734301 -0.27991101 -43.619999, + 32.337101 -5.7019 -43.378502, + 32.710999 -2.86184 -43.378502, + 30.4387 -1.12024 51.547501, + 30.408701 -1.48228 51.5541, + 30.3978 -1.22357 51.5611, + 30.5201 -0.91436601 51.520401, + 15.2914 6.421336e-008 56.707199, + -10.8591 -29.835199 -43.57, + -13.4181 -28.775299 -43.57, + -15.6176 -27.630301 -43.57, + -30.5707 -2.1227 -43.619999, + -30.065201 -2.3633599 -43.619999, + -30.799999 -1.96149 -43.619999, + -30.324699 -2.25722 -43.619999, + -15.875 -27.4963 -43.57, + -18.2111 -26.008101 -43.57 ] + + } + coordIndex [ 180, 7, 9, -1, 165, 21, 303, -1, + 165, 27, 21, -1, 301, 303, 21, -1, + 48, 0, 301, -1, 91, 38, 839, -1, + 91, 764, 38, -1, 1, 180, 16, -1, + 1, 7, 180, -1, 97, 180, 9, -1, + 53, 280, 301, -1, 53, 301, 0, -1, + 53, 0, 48, -1, 53, 48, 144, -1, + 317, 226, 7, -1, 317, 38, 764, -1, + 40, 41, 49, -1, 15, 49, 41, -1, + 15, 17, 167, -1, 15, 167, 49, -1, + 171, 65, 59, -1, 522, 187, 192, -1, + 340, 165, 86, -1, 213, 165, 212, -1, + 90, 839, 196, -1, 90, 91, 839, -1, + 37, 7, 1, -1, 37, 1, 16, -1, + 37, 16, 15, -1, 37, 15, 41, -1, + 37, 38, 317, -1, 5, 16, 180, -1, + 5, 184, 25, -1, 5, 183, 184, -1, + 8, 7, 226, -1, 219, 226, 528, -1, + 105, 764, 91, -1, 105, 1066, 764, -1, + 105, 91, 103, -1, 904, 1066, 105, -1, + 1111, 1112, 141, -1, 1111, 141, 1110, -1, + 830, 528, 226, -1, 830, 226, 317, -1, + 13, 518, 167, -1, 12, 40, 49, -1, + 12, 301, 40, -1, 18, 301, 21, -1, + 18, 40, 301, -1, 63, 59, 65, -1, + 61, 184, 66, -1, 58, 136, 132, -1, + 58, 135, 136, -1, 127, 123, 124, -1, + 127, 124, 314, -1, 24, 281, 25, -1, + 24, 775, 281, -1, 838, 839, 38, -1, + 838, 38, 20, -1, 838, 20, 27, -1, + 838, 27, 29, -1, 28, 165, 340, -1, + 28, 340, 198, -1, 85, 340, 86, -1, + 31, 202, 322, -1, 2, 317, 7, -1, + 2, 7, 37, -1, 2, 37, 317, -1, + 39, 20, 38, -1, 39, 19, 20, -1, + 3, 5, 180, -1, 3, 183, 5, -1, + 3, 180, 82, -1, 3, 82, 183, -1, + 4, 25, 16, -1, 4, 16, 5, -1, + 4, 5, 25, -1, 6, 9, 7, -1, + 6, 8, 9, -1, 6, 7, 8, -1, + 96, 8, 226, -1, 96, 97, 9, -1, + 96, 9, 8, -1, 231, 96, 226, -1, + 43, 105, 103, -1, 579, 580, 10, -1, + 579, 10, 11, -1, 894, 10, 580, -1, + 894, 11, 10, -1, 626, 11, 894, -1, + 626, 894, 893, -1, 626, 362, 579, -1, + 626, 579, 11, -1, 262, 45, 118, -1, + 262, 118, 267, -1, 47, 268, 120, -1, + 152, 165, 303, -1, 152, 151, 165, -1, + 150, 153, 165, -1, 150, 165, 151, -1, + 164, 153, 161, -1, 164, 165, 153, -1, + 146, 12, 49, -1, 146, 140, 139, -1, + 146, 48, 301, -1, 146, 301, 12, -1, + 146, 141, 140, -1, 1602, 141, 462, -1, + 1602, 462, 511, -1, 1602, 1110, 141, -1, + 414, 113, 252, -1, 414, 398, 113, -1, + 1148, 474, 1146, -1, 298, 683, 504, -1, + 249, 504, 683, -1, 54, 53, 144, -1, + 54, 144, 278, -1, 54, 278, 280, -1, + 277, 278, 144, -1, 277, 144, 146, -1, + 14, 167, 17, -1, 14, 13, 167, -1, + 1123, 518, 13, -1, 1123, 13, 14, -1, + 1123, 15, 16, -1, 1123, 14, 17, -1, + 1123, 17, 15, -1, 1123, 16, 25, -1, + 1123, 25, 281, -1, 42, 40, 18, -1, + 42, 19, 39, -1, 42, 27, 20, -1, + 42, 20, 19, -1, 42, 21, 27, -1, + 42, 18, 21, -1, 67, 57, 63, -1, + 67, 137, 57, -1, 22, 65, 77, -1, + 22, 77, 62, -1, 22, 63, 65, -1, + 22, 62, 63, -1, 79, 77, 65, -1, + 756, 272, 192, -1, 23, 171, 59, -1, + 70, 132, 130, -1, 70, 58, 132, -1, + 70, 171, 23, -1, 70, 59, 58, -1, + 70, 23, 59, -1, 313, 314, 124, -1, + 169, 127, 314, -1, 169, 128, 127, -1, + 169, 130, 128, -1, 73, 71, 74, -1, + 73, 1533, 1534, -1, 78, 24, 25, -1, + 78, 25, 184, -1, 78, 80, 775, -1, + 78, 775, 24, -1, 78, 184, 61, -1, + 78, 61, 76, -1, 233, 179, 180, -1, + 233, 222, 528, -1, 526, 183, 82, -1, + 275, 317, 764, -1, 189, 830, 317, -1, + 189, 317, 759, -1, 189, 756, 191, -1, + 189, 759, 756, -1, 326, 328, 343, -1, + 326, 343, 833, -1, 195, 196, 839, -1, + 195, 839, 1126, -1, 542, 343, 328, -1, + 338, 28, 198, -1, 338, 838, 29, -1, + 338, 29, 28, -1, 83, 340, 534, -1, + 83, 342, 340, -1, 83, 534, 343, -1, + 26, 27, 165, -1, 26, 165, 28, -1, + 26, 29, 27, -1, 26, 28, 29, -1, + 30, 85, 320, -1, 30, 340, 85, -1, + 30, 320, 534, -1, 30, 534, 340, -1, + 200, 86, 165, -1, 200, 165, 213, -1, + 345, 33, 34, -1, 345, 34, 202, -1, + 345, 569, 33, -1, 345, 31, 344, -1, + 345, 202, 31, -1, 87, 34, 347, -1, + 87, 202, 34, -1, 89, 347, 34, -1, + 89, 34, 570, -1, 89, 570, 572, -1, + 321, 31, 322, -1, 321, 344, 31, -1, + 321, 320, 85, -1, 201, 348, 347, -1, + 201, 347, 89, -1, 201, 89, 205, -1, + 201, 205, 477, -1, 206, 477, 205, -1, + 206, 205, 204, -1, 206, 476, 477, -1, + 352, 205, 572, -1, 32, 33, 569, -1, + 32, 569, 570, -1, 32, 34, 33, -1, + 32, 570, 34, -1, 874, 90, 196, -1, + 880, 878, 103, -1, 880, 103, 91, -1, + 880, 91, 881, -1, 101, 215, 241, -1, + 109, 214, 377, -1, 109, 110, 214, -1, + 35, 214, 110, -1, 35, 893, 214, -1, + 35, 110, 626, -1, 35, 626, 893, -1, + 36, 38, 37, -1, 36, 39, 38, -1, + 36, 41, 40, -1, 36, 37, 41, -1, + 36, 40, 42, -1, 36, 42, 39, -1, + 228, 226, 92, -1, 220, 226, 219, -1, + 220, 92, 226, -1, 220, 219, 218, -1, + 225, 231, 226, -1, 225, 94, 231, -1, + 230, 96, 231, -1, 230, 233, 180, -1, + 102, 107, 104, -1, 102, 234, 107, -1, + 363, 100, 234, -1, 44, 104, 107, -1, + 44, 103, 104, -1, 44, 43, 103, -1, + 108, 105, 43, -1, 108, 44, 107, -1, + 108, 43, 44, -1, 375, 240, 237, -1, + 375, 112, 376, -1, 111, 112, 107, -1, + 367, 234, 100, -1, 367, 107, 234, -1, + 367, 111, 107, -1, 367, 583, 111, -1, + 582, 583, 367, -1, 625, 362, 626, -1, + 627, 110, 628, -1, 627, 626, 110, -1, + 115, 409, 1273, -1, 115, 251, 252, -1, + 115, 1273, 251, -1, 115, 252, 113, -1, + 114, 259, 257, -1, 114, 427, 259, -1, + 408, 428, 419, -1, 116, 419, 428, -1, + 117, 45, 420, -1, 117, 118, 45, -1, + 122, 45, 262, -1, 122, 420, 45, -1, + 46, 262, 267, -1, 46, 120, 262, -1, + 46, 267, 47, -1, 46, 47, 120, -1, + 266, 47, 267, -1, 266, 268, 47, -1, + 253, 268, 441, -1, 422, 423, 133, -1, + 422, 453, 119, -1, 422, 136, 453, -1, + 422, 132, 136, -1, 422, 133, 132, -1, + 129, 123, 127, -1, 271, 134, 137, -1, + 1078, 907, 620, -1, 163, 212, 165, -1, + 142, 139, 140, -1, 145, 144, 48, -1, + 145, 48, 146, -1, 147, 146, 49, -1, + 147, 49, 167, -1, 50, 462, 141, -1, + 50, 141, 146, -1, 50, 146, 462, -1, + 289, 288, 971, -1, 284, 971, 288, -1, + 284, 389, 971, -1, 284, 285, 389, -1, + 560, 471, 559, -1, 51, 160, 161, -1, + 51, 155, 160, -1, 507, 51, 161, -1, + 507, 155, 51, -1, 507, 1366, 209, -1, + 507, 299, 1095, -1, 507, 209, 208, -1, + 507, 212, 163, -1, 52, 280, 53, -1, + 52, 54, 280, -1, 52, 53, 54, -1, + 55, 146, 139, -1, 55, 139, 277, -1, + 55, 277, 146, -1, 176, 1103, 461, -1, + 309, 148, 310, -1, 56, 137, 134, -1, + 56, 57, 137, -1, 56, 58, 59, -1, + 56, 59, 63, -1, 56, 63, 57, -1, + 56, 134, 135, -1, 56, 135, 58, -1, + 60, 76, 61, -1, 60, 77, 76, -1, + 60, 61, 66, -1, 60, 66, 67, -1, + 60, 62, 77, -1, 60, 63, 62, -1, + 60, 67, 63, -1, 64, 74, 71, -1, + 64, 71, 79, -1, 64, 79, 65, -1, + 64, 65, 171, -1, 64, 171, 172, -1, + 64, 172, 306, -1, 64, 306, 74, -1, + 270, 119, 453, -1, 68, 137, 67, -1, + 68, 138, 137, -1, 68, 272, 138, -1, + 68, 185, 272, -1, 182, 66, 184, -1, + 182, 67, 66, -1, 182, 68, 67, -1, + 182, 185, 68, -1, 173, 306, 172, -1, + 173, 169, 314, -1, 170, 171, 70, -1, + 170, 70, 169, -1, 69, 70, 130, -1, + 69, 130, 169, -1, 69, 169, 70, -1, + 72, 775, 80, -1, 72, 468, 775, -1, + 72, 80, 79, -1, 72, 79, 71, -1, + 72, 71, 73, -1, 72, 73, 175, -1, + 800, 73, 1534, -1, 800, 175, 73, -1, + 466, 468, 72, -1, 466, 72, 175, -1, + 466, 176, 464, -1, 307, 73, 74, -1, + 307, 1533, 73, -1, 307, 74, 306, -1, + 75, 76, 77, -1, 75, 78, 76, -1, + 75, 77, 79, -1, 75, 79, 80, -1, + 75, 80, 78, -1, 81, 528, 527, -1, + 81, 233, 528, -1, 81, 527, 233, -1, + 181, 526, 82, -1, 181, 82, 180, -1, + 178, 527, 526, -1, 178, 179, 233, -1, + 178, 233, 527, -1, 530, 317, 275, -1, + 1064, 764, 1062, -1, 1064, 275, 764, -1, + 190, 192, 187, -1, 319, 343, 534, -1, + 319, 833, 343, -1, 327, 328, 326, -1, + 194, 834, 325, -1, 194, 325, 326, -1, + 546, 838, 338, -1, 546, 343, 542, -1, + 546, 542, 838, -1, 1144, 342, 83, -1, + 1144, 83, 343, -1, 84, 85, 86, -1, + 84, 86, 200, -1, 84, 321, 85, -1, + 84, 200, 321, -1, 211, 200, 213, -1, + 563, 202, 87, -1, 563, 87, 347, -1, + 88, 572, 205, -1, 88, 205, 89, -1, + 88, 89, 572, -1, 323, 350, 325, -1, + 356, 472, 476, -1, 1365, 209, 1366, -1, + 576, 572, 570, -1, 876, 360, 91, -1, + 876, 91, 90, -1, 876, 90, 874, -1, + 873, 881, 91, -1, 873, 91, 360, -1, + 873, 938, 881, -1, 578, 881, 938, -1, + 1174, 377, 214, -1, 1174, 214, 385, -1, + 384, 1174, 385, -1, 384, 1176, 1174, -1, + 381, 241, 215, -1, 366, 101, 241, -1, + 223, 219, 528, -1, 223, 228, 92, -1, + 223, 92, 220, -1, 93, 231, 94, -1, + 93, 98, 231, -1, 93, 94, 222, -1, + 93, 222, 98, -1, 227, 94, 225, -1, + 227, 222, 94, -1, 227, 228, 222, -1, + 95, 97, 96, -1, 95, 96, 230, -1, + 95, 180, 97, -1, 95, 230, 180, -1, + 232, 231, 98, -1, 232, 222, 233, -1, + 232, 98, 222, -1, 99, 100, 363, -1, + 99, 363, 101, -1, 99, 367, 100, -1, + 99, 101, 366, -1, 99, 366, 367, -1, + 216, 215, 101, -1, 216, 101, 363, -1, + 365, 234, 102, -1, 365, 103, 878, -1, + 365, 104, 103, -1, 365, 102, 104, -1, + 236, 904, 105, -1, 236, 105, 108, -1, + 236, 902, 904, -1, 236, 108, 237, -1, + 106, 107, 112, -1, 106, 108, 107, -1, + 106, 237, 108, -1, 106, 375, 237, -1, + 106, 112, 375, -1, 906, 897, 907, -1, + 924, 1164, 1165, -1, 373, 368, 238, -1, + 372, 239, 240, -1, 372, 373, 239, -1, + 950, 109, 377, -1, 950, 110, 109, -1, + 950, 628, 110, -1, 950, 614, 628, -1, + 961, 111, 583, -1, 961, 376, 112, -1, + 961, 112, 111, -1, 623, 379, 617, -1, + 387, 283, 388, -1, 392, 399, 664, -1, + 392, 664, 663, -1, 983, 291, 984, -1, + 983, 292, 291, -1, 397, 984, 291, -1, + 394, 1222, 393, -1, 394, 644, 1371, -1, + 669, 701, 702, -1, 404, 304, 248, -1, + 853, 349, 1082, -1, 334, 566, 567, -1, + 260, 398, 399, -1, 260, 399, 1033, -1, + 260, 113, 398, -1, 260, 115, 113, -1, + 425, 114, 257, -1, 425, 427, 114, -1, + 418, 116, 259, -1, 418, 419, 116, -1, + 410, 428, 408, -1, 410, 409, 115, -1, + 410, 115, 260, -1, 429, 116, 428, -1, + 429, 259, 116, -1, 437, 118, 117, -1, + 437, 267, 118, -1, 437, 117, 420, -1, + 742, 422, 119, -1, 742, 119, 270, -1, + 255, 120, 268, -1, 255, 268, 253, -1, + 255, 253, 258, -1, 1293, 257, 259, -1, + 1292, 1545, 261, -1, 1292, 256, 1293, -1, + 512, 1376, 517, -1, 431, 262, 120, -1, + 431, 256, 432, -1, 431, 120, 255, -1, + 431, 255, 256, -1, 121, 261, 432, -1, + 121, 432, 256, -1, 121, 1292, 261, -1, + 121, 256, 1292, -1, 434, 432, 261, -1, + 435, 434, 819, -1, 263, 125, 420, -1, + 263, 420, 122, -1, 263, 124, 125, -1, + 263, 265, 313, -1, 263, 313, 124, -1, + 263, 122, 262, -1, 131, 123, 129, -1, + 131, 124, 123, -1, 131, 125, 124, -1, + 131, 423, 420, -1, 131, 420, 125, -1, + 131, 133, 423, -1, 126, 127, 128, -1, + 126, 129, 127, -1, 126, 128, 130, -1, + 126, 131, 129, -1, 126, 130, 132, -1, + 126, 132, 133, -1, 126, 133, 131, -1, + 448, 135, 134, -1, 448, 134, 271, -1, + 448, 136, 135, -1, 448, 453, 136, -1, + 274, 137, 138, -1, 274, 271, 137, -1, + 456, 752, 1061, -1, 751, 138, 272, -1, + 751, 274, 138, -1, 279, 139, 142, -1, + 279, 277, 139, -1, 279, 142, 280, -1, + 159, 140, 141, -1, 159, 142, 140, -1, + 159, 141, 1112, -1, 159, 280, 142, -1, + 159, 158, 280, -1, 143, 146, 144, -1, + 143, 144, 145, -1, 143, 145, 146, -1, + 1120, 462, 146, -1, 1120, 146, 147, -1, + 1120, 176, 461, -1, 1120, 464, 176, -1, + 1120, 148, 309, -1, 1120, 310, 148, -1, + 1120, 147, 167, -1, 470, 283, 387, -1, + 482, 484, 293, -1, 968, 969, 482, -1, + 968, 482, 293, -1, 1081, 244, 415, -1, + 1081, 1082, 349, -1, 1081, 349, 244, -1, + 286, 293, 484, -1, 286, 1148, 293, -1, + 487, 861, 860, -1, 492, 291, 292, -1, + 149, 658, 282, -1, 149, 282, 354, -1, + 149, 354, 353, -1, 149, 654, 658, -1, + 149, 295, 654, -1, 863, 295, 149, -1, + 863, 149, 353, -1, 1592, 683, 298, -1, + 157, 507, 160, -1, 157, 156, 507, -1, + 302, 150, 151, -1, 302, 151, 152, -1, + 302, 153, 150, -1, 302, 152, 303, -1, + 302, 161, 153, -1, 302, 507, 161, -1, + 154, 155, 507, -1, 154, 507, 156, -1, + 154, 156, 157, -1, 154, 160, 155, -1, + 154, 157, 160, -1, 509, 403, 508, -1, + 509, 799, 507, -1, 509, 248, 304, -1, + 509, 249, 248, -1, 509, 504, 249, -1, + 509, 505, 504, -1, 509, 506, 505, -1, + 509, 1112, 506, -1, 509, 280, 158, -1, + 509, 159, 1112, -1, 509, 158, 159, -1, + 509, 301, 280, -1, 509, 507, 301, -1, + 207, 1366, 507, -1, 207, 507, 1095, -1, + 166, 160, 507, -1, 166, 164, 161, -1, + 166, 161, 160, -1, 162, 507, 163, -1, + 162, 165, 164, -1, 162, 163, 165, -1, + 162, 164, 166, -1, 162, 166, 507, -1, + 1610, 462, 1611, -1, 1235, 462, 1236, -1, + 1472, 1236, 462, -1, 1537, 1533, 307, -1, + 1478, 1482, 1481, -1, 827, 1120, 167, -1, + 827, 167, 518, -1, 168, 169, 173, -1, + 168, 171, 170, -1, 168, 170, 169, -1, + 168, 172, 171, -1, 168, 173, 172, -1, + 315, 173, 314, -1, 315, 812, 308, -1, + 315, 308, 306, -1, 315, 306, 173, -1, + 174, 466, 175, -1, 174, 800, 1103, -1, + 174, 175, 800, -1, 174, 1103, 176, -1, + 174, 176, 466, -1, 177, 179, 178, -1, + 177, 180, 179, -1, 177, 181, 180, -1, + 177, 526, 181, -1, 177, 178, 526, -1, + 316, 185, 182, -1, 316, 183, 526, -1, + 316, 184, 183, -1, 316, 182, 184, -1, + 523, 522, 192, -1, 523, 185, 316, -1, + 523, 192, 272, -1, 523, 272, 185, -1, + 525, 523, 316, -1, 758, 759, 317, -1, + 758, 530, 757, -1, 186, 522, 830, -1, + 186, 830, 190, -1, 186, 187, 522, -1, + 186, 190, 187, -1, 188, 830, 189, -1, + 188, 190, 830, -1, 188, 189, 191, -1, + 188, 191, 756, -1, 188, 756, 192, -1, + 188, 192, 190, -1, 532, 833, 319, -1, + 193, 834, 194, -1, 193, 194, 326, -1, + 193, 833, 834, -1, 193, 326, 833, -1, + 535, 536, 838, -1, 1384, 195, 1126, -1, + 1384, 196, 195, -1, 1384, 874, 196, -1, + 544, 542, 328, -1, 333, 1559, 331, -1, + 333, 1245, 1559, -1, 1386, 921, 925, -1, + 1386, 925, 1385, -1, 199, 338, 198, -1, + 197, 198, 340, -1, 197, 340, 337, -1, + 197, 199, 198, -1, 197, 337, 338, -1, + 197, 338, 199, -1, 545, 338, 342, -1, + 545, 546, 338, -1, 551, 321, 200, -1, + 551, 200, 211, -1, 551, 344, 321, -1, + 210, 212, 507, -1, 210, 507, 208, -1, + 565, 566, 334, -1, 245, 244, 349, -1, + 245, 471, 966, -1, 555, 477, 560, -1, + 555, 201, 477, -1, 555, 348, 201, -1, + 558, 349, 557, -1, 558, 245, 349, -1, + 558, 559, 471, -1, 558, 471, 245, -1, + 351, 350, 323, -1, 351, 202, 563, -1, + 351, 322, 202, -1, 351, 323, 322, -1, + 203, 476, 206, -1, 203, 356, 476, -1, + 473, 356, 1146, -1, 473, 472, 356, -1, + 357, 356, 203, -1, 357, 204, 205, -1, + 357, 205, 352, -1, 357, 206, 204, -1, + 357, 203, 206, -1, 871, 872, 359, -1, + 1362, 207, 1095, -1, 1362, 1363, 1366, -1, + 1362, 1366, 207, -1, 691, 208, 209, -1, + 691, 209, 1365, -1, 691, 210, 208, -1, + 691, 551, 211, -1, 691, 212, 210, -1, + 691, 213, 212, -1, 691, 211, 213, -1, + 693, 1090, 1089, -1, 693, 1091, 1090, -1, + 1005, 359, 872, -1, 1005, 1002, 359, -1, + 937, 938, 873, -1, 891, 385, 214, -1, + 891, 214, 893, -1, 616, 381, 215, -1, + 616, 617, 381, -1, 616, 215, 216, -1, + 616, 216, 363, -1, 613, 628, 614, -1, + 613, 366, 628, -1, 217, 218, 219, -1, + 217, 219, 223, -1, 217, 220, 218, -1, + 217, 223, 220, -1, 221, 528, 222, -1, + 221, 223, 528, -1, 221, 222, 228, -1, + 221, 228, 223, -1, 224, 225, 226, -1, + 224, 227, 225, -1, 224, 226, 228, -1, + 224, 228, 227, -1, 229, 230, 231, -1, + 229, 231, 232, -1, 229, 233, 230, -1, + 229, 232, 233, -1, 364, 363, 234, -1, + 364, 234, 365, -1, 597, 236, 238, -1, + 597, 902, 236, -1, 597, 238, 368, -1, + 235, 236, 237, -1, 235, 238, 236, -1, + 235, 237, 240, -1, 235, 240, 239, -1, + 235, 373, 238, -1, 235, 239, 373, -1, + 918, 898, 906, -1, 932, 933, 605, -1, + 920, 921, 1386, -1, 1413, 620, 1421, -1, + 1413, 610, 620, -1, 608, 1160, 935, -1, + 608, 1164, 620, -1, 608, 935, 1164, -1, + 958, 372, 240, -1, 958, 240, 375, -1, + 958, 375, 374, -1, 958, 620, 907, -1, + 589, 368, 373, -1, 585, 961, 583, -1, + 960, 961, 585, -1, 960, 586, 957, -1, + 960, 585, 586, -1, 1170, 1421, 620, -1, + 242, 241, 381, -1, 242, 243, 628, -1, + 242, 366, 241, -1, 242, 628, 366, -1, + 380, 379, 243, -1, 380, 242, 381, -1, + 380, 243, 242, -1, 624, 362, 625, -1, + 383, 623, 617, -1, 383, 362, 624, -1, + 383, 624, 623, -1, 622, 243, 379, -1, + 622, 379, 623, -1, 622, 628, 243, -1, + 632, 668, 671, -1, 632, 671, 639, -1, + 642, 963, 962, -1, 642, 631, 641, -1, + 390, 387, 642, -1, 390, 470, 387, -1, + 390, 389, 285, -1, 390, 285, 470, -1, + 246, 966, 635, -1, 246, 415, 244, -1, + 246, 245, 966, -1, 246, 244, 245, -1, + 964, 635, 966, -1, 636, 1445, 415, -1, + 636, 415, 246, -1, 636, 246, 635, -1, + 704, 972, 707, -1, 1034, 1033, 399, -1, + 1034, 399, 392, -1, 645, 394, 1371, -1, + 645, 1222, 394, -1, 296, 861, 292, -1, + 296, 292, 983, -1, 1645, 397, 1646, -1, + 985, 984, 397, -1, 662, 392, 663, -1, + 662, 391, 392, -1, 662, 393, 1222, -1, + 662, 1222, 391, -1, 250, 670, 669, -1, + 250, 669, 702, -1, 250, 671, 670, -1, + 250, 637, 671, -1, 250, 702, 703, -1, + 247, 669, 672, -1, 247, 672, 400, -1, + 247, 400, 700, -1, 247, 701, 669, -1, + 247, 700, 701, -1, 681, 404, 248, -1, + 681, 249, 683, -1, 681, 248, 249, -1, + 1008, 843, 1130, -1, 552, 334, 567, -1, + 552, 852, 858, -1, 1247, 1246, 334, -1, + 1247, 552, 858, -1, 1247, 334, 552, -1, + 699, 707, 972, -1, 699, 637, 250, -1, + 699, 250, 703, -1, 411, 251, 1273, -1, + 413, 251, 411, -1, 413, 252, 251, -1, + 413, 414, 252, -1, 706, 406, 407, -1, + 706, 407, 414, -1, 973, 712, 1450, -1, + 1262, 1250, 460, -1, 1262, 460, 709, -1, + 1012, 717, 416, -1, 1256, 1450, 712, -1, + 426, 259, 427, -1, 426, 418, 259, -1, + 440, 425, 257, -1, 440, 257, 258, -1, + 440, 258, 253, -1, 440, 253, 441, -1, + 741, 270, 443, -1, 741, 742, 270, -1, + 1026, 1030, 426, -1, 1026, 425, 440, -1, + 254, 256, 255, -1, 254, 1293, 256, -1, + 254, 257, 1293, -1, 254, 258, 257, -1, + 254, 255, 258, -1, 1291, 1293, 259, -1, + 1291, 259, 429, -1, 1032, 428, 410, -1, + 1032, 260, 1033, -1, 1032, 410, 260, -1, + 806, 261, 1545, -1, 806, 512, 517, -1, + 806, 434, 261, -1, 433, 262, 431, -1, + 433, 265, 263, -1, 433, 263, 262, -1, + 264, 517, 819, -1, 264, 819, 434, -1, + 264, 806, 517, -1, 264, 434, 806, -1, + 436, 514, 312, -1, 436, 265, 433, -1, + 436, 313, 265, -1, 436, 312, 313, -1, + 721, 268, 266, -1, 721, 266, 267, -1, + 721, 267, 437, -1, 723, 441, 268, -1, + 723, 268, 721, -1, 723, 721, 724, -1, + 457, 729, 444, -1, 457, 730, 729, -1, + 457, 445, 456, -1, 749, 443, 451, -1, + 749, 738, 443, -1, 269, 450, 753, -1, + 269, 753, 752, -1, 269, 456, 445, -1, + 269, 752, 456, -1, 748, 449, 450, -1, + 748, 269, 445, -1, 748, 450, 269, -1, + 452, 270, 453, -1, 452, 451, 443, -1, + 452, 443, 270, -1, 447, 448, 271, -1, + 447, 271, 274, -1, 447, 753, 450, -1, + 454, 272, 756, -1, 454, 751, 272, -1, + 273, 751, 753, -1, 273, 274, 751, -1, + 273, 753, 447, -1, 273, 447, 274, -1, + 1311, 1312, 602, -1, 458, 917, 760, -1, + 1315, 757, 530, -1, 1315, 530, 275, -1, + 1315, 275, 1064, -1, 1528, 606, 709, -1, + 1528, 605, 606, -1, 276, 278, 277, -1, + 276, 277, 279, -1, 276, 280, 278, -1, + 276, 279, 280, -1, 465, 1120, 467, -1, + 465, 467, 468, -1, 774, 1120, 1122, -1, + 774, 1122, 1123, -1, 774, 281, 775, -1, + 774, 1123, 281, -1, 520, 310, 1120, -1, + 657, 282, 658, -1, 657, 659, 282, -1, + 294, 284, 288, -1, 294, 659, 284, -1, + 294, 282, 659, -1, 294, 354, 282, -1, + 294, 288, 293, -1, 675, 283, 470, -1, + 675, 388, 283, -1, 675, 631, 388, -1, + 469, 285, 284, -1, 469, 470, 285, -1, + 469, 284, 659, -1, 483, 474, 1148, -1, + 483, 286, 484, -1, 483, 1148, 286, -1, + 970, 289, 971, -1, 970, 968, 289, -1, + 287, 293, 288, -1, 287, 968, 293, -1, + 287, 288, 289, -1, 287, 289, 968, -1, + 1434, 1185, 962, -1, 788, 402, 787, -1, + 788, 680, 402, -1, 788, 488, 680, -1, + 779, 489, 792, -1, 1591, 683, 1592, -1, + 290, 1646, 397, -1, 290, 492, 1646, -1, + 290, 397, 291, -1, 290, 291, 492, -1, + 493, 492, 292, -1, 493, 292, 861, -1, + 493, 861, 487, -1, 793, 777, 778, -1, + 793, 487, 777, -1, 793, 493, 487, -1, + 793, 778, 792, -1, 355, 293, 1148, -1, + 355, 1407, 354, -1, 355, 294, 293, -1, + 355, 354, 294, -1, 494, 295, 863, -1, + 494, 861, 296, -1, 494, 654, 295, -1, + 494, 655, 654, -1, 494, 983, 655, -1, + 494, 296, 983, -1, 497, 496, 1112, -1, + 499, 1592, 502, -1, 499, 1112, 496, -1, + 297, 298, 504, -1, 297, 504, 1592, -1, + 297, 1592, 298, -1, 1093, 1095, 299, -1, + 1093, 299, 507, -1, 300, 301, 507, -1, + 300, 507, 302, -1, 300, 303, 301, -1, + 300, 302, 303, -1, 405, 403, 509, -1, + 405, 509, 304, -1, 405, 304, 404, -1, + 510, 511, 462, -1, 510, 462, 1610, -1, + 998, 1611, 462, -1, 998, 462, 1235, -1, + 1471, 462, 1473, -1, 1471, 1472, 462, -1, + 802, 805, 804, -1, 802, 804, 513, -1, + 305, 306, 308, -1, 305, 308, 1537, -1, + 305, 307, 306, -1, 305, 1537, 307, -1, + 813, 1537, 308, -1, 813, 308, 812, -1, + 516, 819, 517, -1, 817, 514, 436, -1, + 817, 435, 819, -1, 826, 1120, 309, -1, + 826, 309, 310, -1, 826, 310, 520, -1, + 311, 312, 514, -1, 311, 514, 812, -1, + 311, 314, 313, -1, 311, 313, 312, -1, + 311, 315, 314, -1, 311, 812, 315, -1, + 524, 316, 526, -1, 524, 525, 316, -1, + 521, 522, 523, -1, 531, 317, 530, -1, + 531, 758, 317, -1, 318, 319, 534, -1, + 318, 534, 532, -1, 318, 532, 319, -1, + 533, 325, 834, -1, 533, 534, 320, -1, + 533, 321, 322, -1, 533, 320, 321, -1, + 533, 322, 323, -1, 533, 323, 325, -1, + 836, 533, 834, -1, 324, 325, 350, -1, + 324, 350, 539, -1, 324, 326, 325, -1, + 324, 327, 326, -1, 324, 328, 327, -1, + 324, 544, 328, -1, 324, 539, 544, -1, + 837, 838, 536, -1, 329, 331, 1559, -1, + 329, 535, 331, -1, 329, 1559, 535, -1, + 541, 539, 331, -1, 541, 331, 535, -1, + 541, 535, 838, -1, 541, 838, 542, -1, + 1129, 1152, 875, -1, 1129, 1130, 1152, -1, + 1129, 875, 874, -1, 1129, 874, 1384, -1, + 330, 331, 539, -1, 330, 333, 331, -1, + 330, 539, 350, -1, 330, 350, 565, -1, + 330, 565, 333, -1, 332, 1246, 1245, -1, + 332, 1245, 333, -1, 332, 333, 565, -1, + 332, 334, 1246, -1, 332, 565, 334, -1, + 844, 1385, 925, -1, 335, 342, 338, -1, + 335, 338, 339, -1, 335, 340, 342, -1, + 335, 339, 340, -1, 336, 338, 337, -1, + 336, 339, 338, -1, 336, 337, 340, -1, + 336, 340, 339, -1, 341, 342, 1144, -1, + 341, 1144, 1143, -1, 341, 545, 342, -1, + 341, 1143, 545, -1, 1402, 1144, 343, -1, + 1402, 343, 546, -1, 1402, 546, 549, -1, + 550, 344, 551, -1, 550, 345, 344, -1, + 550, 569, 345, -1, 554, 567, 564, -1, + 554, 348, 555, -1, 346, 563, 347, -1, + 346, 564, 563, -1, 346, 347, 348, -1, + 346, 348, 554, -1, 346, 554, 564, -1, + 851, 557, 349, -1, 851, 349, 853, -1, + 562, 565, 350, -1, 562, 350, 351, -1, + 562, 351, 563, -1, 574, 352, 572, -1, + 574, 357, 352, -1, 574, 573, 357, -1, + 866, 863, 353, -1, 866, 353, 354, -1, + 866, 354, 1407, -1, 1147, 355, 1148, -1, + 1147, 1407, 355, -1, 1145, 573, 872, -1, + 1145, 1146, 356, -1, 1145, 356, 357, -1, + 1145, 357, 573, -1, 690, 551, 691, -1, + 869, 693, 1089, -1, 358, 871, 359, -1, + 358, 870, 871, -1, 358, 359, 1002, -1, + 358, 1002, 693, -1, 358, 869, 870, -1, + 358, 693, 869, -1, 577, 1005, 872, -1, + 577, 872, 573, -1, 1162, 873, 360, -1, + 1162, 360, 876, -1, 1423, 878, 880, -1, + 361, 578, 938, -1, 361, 1414, 578, -1, + 361, 938, 944, -1, 361, 944, 610, -1, + 361, 610, 1414, -1, 890, 579, 362, -1, + 890, 362, 383, -1, 890, 383, 891, -1, + 879, 616, 363, -1, 879, 363, 364, -1, + 879, 365, 878, -1, 879, 364, 365, -1, + 584, 366, 613, -1, 584, 582, 367, -1, + 584, 367, 366, -1, 593, 592, 587, -1, + 899, 898, 918, -1, 598, 588, 587, -1, + 598, 587, 592, -1, 598, 368, 589, -1, + 598, 589, 588, -1, 598, 597, 368, -1, + 599, 595, 600, -1, 599, 598, 592, -1, + 732, 731, 911, -1, 596, 918, 917, -1, + 596, 917, 458, -1, 596, 904, 600, -1, + 710, 709, 606, -1, 1138, 604, 1397, -1, + 1138, 1137, 604, -1, 603, 1135, 932, -1, + 928, 932, 605, -1, 928, 1078, 620, -1, + 928, 1528, 1078, -1, 928, 605, 1528, -1, + 928, 603, 932, -1, 928, 604, 1137, -1, + 928, 1137, 603, -1, 1013, 605, 933, -1, + 1013, 933, 1488, -1, 1267, 932, 1135, -1, + 923, 620, 1164, -1, 923, 1164, 924, -1, + 369, 1386, 929, -1, 369, 929, 920, -1, + 369, 920, 1386, -1, 1418, 1413, 1421, -1, + 370, 1414, 610, -1, 370, 610, 1413, -1, + 370, 1413, 1414, -1, 371, 610, 944, -1, + 371, 944, 609, -1, 371, 609, 610, -1, + 943, 609, 944, -1, 611, 609, 943, -1, + 590, 373, 372, -1, 590, 589, 373, -1, + 590, 372, 958, -1, 959, 958, 374, -1, + 959, 375, 376, -1, 959, 374, 375, -1, + 959, 376, 961, -1, 946, 957, 586, -1, + 1173, 950, 377, -1, 1173, 377, 1174, -1, + 954, 1176, 617, -1, 378, 617, 379, -1, + 378, 379, 380, -1, 378, 381, 617, -1, + 378, 380, 381, -1, 382, 383, 617, -1, + 382, 891, 383, -1, 382, 617, 1176, -1, + 382, 1176, 384, -1, 382, 384, 385, -1, + 382, 385, 891, -1, 630, 676, 632, -1, + 630, 675, 676, -1, 630, 631, 675, -1, + 638, 671, 637, -1, 638, 639, 671, -1, + 638, 1204, 639, -1, 386, 631, 642, -1, + 386, 642, 387, -1, 386, 388, 631, -1, + 386, 387, 388, -1, 485, 971, 389, -1, + 485, 389, 390, -1, 486, 642, 962, -1, + 486, 390, 642, -1, 486, 485, 390, -1, + 965, 966, 471, -1, 965, 471, 633, -1, + 1433, 1184, 635, -1, 1433, 635, 964, -1, + 1446, 1184, 1183, -1, 1446, 1183, 1193, -1, + 1210, 1199, 1200, -1, 1453, 976, 1198, -1, + 1453, 975, 976, -1, 1463, 391, 1222, -1, + 1463, 392, 391, -1, 1463, 1034, 392, -1, + 1640, 1639, 397, -1, 1640, 397, 1645, -1, + 647, 393, 662, -1, 647, 662, 661, -1, + 647, 394, 393, -1, 647, 395, 394, -1, + 652, 1549, 982, -1, 652, 644, 394, -1, + 652, 394, 395, -1, 651, 647, 646, -1, + 651, 395, 647, -1, 651, 652, 395, -1, + 1232, 993, 396, -1, 1232, 651, 646, -1, + 1232, 396, 651, -1, 653, 396, 993, -1, + 653, 651, 396, -1, 648, 397, 1639, -1, + 648, 1639, 980, -1, 648, 985, 397, -1, + 992, 985, 993, -1, 1226, 658, 654, -1, + 1226, 654, 656, -1, 1224, 1226, 656, -1, + 401, 407, 700, -1, 401, 700, 400, -1, + 401, 414, 407, -1, 401, 398, 414, -1, + 401, 399, 398, -1, 401, 664, 399, -1, + 666, 400, 672, -1, 666, 664, 401, -1, + 666, 401, 400, -1, 988, 1231, 1234, -1, + 674, 990, 989, -1, 674, 632, 676, -1, + 674, 668, 632, -1, 677, 402, 680, -1, + 677, 786, 787, -1, 677, 787, 402, -1, + 679, 680, 488, -1, 679, 404, 681, -1, + 684, 782, 685, -1, 684, 488, 782, -1, + 684, 679, 488, -1, 684, 686, 679, -1, + 797, 508, 403, -1, 797, 404, 679, -1, + 797, 679, 686, -1, 797, 403, 405, -1, + 797, 405, 404, -1, 1001, 685, 782, -1, + 855, 856, 845, -1, 855, 846, 1249, -1, + 855, 845, 846, -1, 1243, 1249, 846, -1, + 697, 707, 699, -1, 697, 706, 707, -1, + 697, 406, 706, -1, 697, 407, 406, -1, + 697, 700, 407, -1, 697, 698, 700, -1, + 1272, 419, 1029, -1, 1272, 408, 419, -1, + 1272, 1273, 409, -1, 1272, 409, 410, -1, + 1272, 410, 408, -1, 1502, 706, 413, -1, + 1502, 413, 411, -1, 1502, 411, 1273, -1, + 412, 414, 413, -1, 412, 706, 414, -1, + 412, 413, 706, -1, 708, 704, 707, -1, + 713, 712, 973, -1, 1253, 1012, 1010, -1, + 714, 1012, 416, -1, 714, 416, 715, -1, + 714, 1010, 1012, -1, 1080, 415, 1445, -1, + 1080, 1081, 415, -1, 1280, 416, 717, -1, + 1280, 715, 416, -1, 417, 419, 418, -1, + 417, 418, 426, -1, 417, 426, 1030, -1, + 417, 1029, 419, -1, 417, 1030, 1029, -1, + 439, 437, 420, -1, 439, 420, 423, -1, + 421, 742, 438, -1, 421, 423, 422, -1, + 421, 422, 742, -1, 421, 439, 423, -1, + 421, 438, 439, -1, 740, 438, 742, -1, + 424, 425, 1026, -1, 424, 1026, 426, -1, + 424, 427, 425, -1, 424, 426, 427, -1, + 1053, 719, 726, -1, 720, 428, 1032, -1, + 720, 429, 428, -1, 720, 1291, 429, -1, + 430, 431, 432, -1, 430, 433, 431, -1, + 430, 432, 434, -1, 430, 434, 435, -1, + 430, 436, 433, -1, 430, 435, 817, -1, + 430, 817, 436, -1, 1038, 721, 437, -1, + 1038, 740, 1060, -1, 1038, 438, 740, -1, + 1038, 437, 439, -1, 1038, 439, 438, -1, + 725, 440, 441, -1, 725, 441, 723, -1, + 725, 1026, 440, -1, 735, 1043, 1040, -1, + 727, 444, 729, -1, 727, 745, 444, -1, + 768, 727, 729, -1, 1075, 1058, 1050, -1, + 739, 1305, 737, -1, 1304, 737, 1305, -1, + 442, 741, 443, -1, 442, 443, 738, -1, + 442, 738, 737, -1, 442, 1304, 741, -1, + 442, 737, 1304, -1, 746, 745, 1045, -1, + 747, 449, 748, -1, 747, 451, 449, -1, + 747, 749, 451, -1, 744, 444, 745, -1, + 744, 748, 445, -1, 744, 445, 457, -1, + 744, 457, 444, -1, 446, 448, 447, -1, + 446, 450, 449, -1, 446, 447, 450, -1, + 446, 449, 451, -1, 446, 451, 452, -1, + 446, 453, 448, -1, 446, 452, 453, -1, + 755, 751, 454, -1, 755, 454, 756, -1, + 1310, 456, 1061, -1, 1310, 1311, 456, -1, + 455, 1311, 602, -1, 455, 456, 1311, -1, + 455, 602, 730, -1, 455, 730, 457, -1, + 455, 457, 456, -1, 1318, 1066, 904, -1, + 1318, 760, 1319, -1, 1318, 458, 760, -1, + 1318, 904, 596, -1, 1318, 596, 458, -1, + 1585, 1062, 1584, -1, 763, 1584, 1062, -1, + 763, 1319, 1584, -1, 1156, 907, 1078, -1, + 1156, 1078, 1427, -1, 1069, 1332, 1041, -1, + 1333, 1334, 1075, -1, 459, 460, 1250, -1, + 459, 1250, 1528, -1, 459, 709, 460, -1, + 459, 1528, 709, -1, 772, 1120, 461, -1, + 772, 461, 1103, -1, 1100, 1473, 462, -1, + 1099, 462, 1120, -1, 1099, 1120, 1102, -1, + 1099, 1100, 462, -1, 463, 464, 1120, -1, + 463, 1120, 465, -1, 463, 466, 464, -1, + 463, 468, 466, -1, 463, 465, 468, -1, + 776, 467, 1120, -1, 776, 1120, 774, -1, + 776, 468, 467, -1, 776, 775, 468, -1, + 986, 469, 659, -1, 986, 470, 469, -1, + 986, 991, 675, -1, 986, 675, 470, -1, + 480, 633, 471, -1, 480, 471, 560, -1, + 480, 560, 479, -1, 478, 476, 472, -1, + 478, 472, 473, -1, 478, 474, 483, -1, + 478, 483, 479, -1, 478, 1146, 474, -1, + 478, 473, 1146, -1, 475, 479, 560, -1, + 475, 477, 476, -1, 475, 560, 477, -1, + 475, 476, 478, -1, 475, 478, 479, -1, + 634, 483, 969, -1, 634, 479, 483, -1, + 634, 633, 480, -1, 634, 480, 479, -1, + 481, 482, 969, -1, 481, 969, 483, -1, + 481, 484, 482, -1, 481, 483, 484, -1, + 967, 971, 485, -1, 967, 485, 486, -1, + 967, 962, 1185, -1, 967, 486, 962, -1, + 859, 869, 1089, -1, 859, 868, 869, -1, + 859, 1089, 1088, -1, 859, 1088, 777, -1, + 859, 487, 860, -1, 859, 777, 487, -1, + 781, 782, 488, -1, 781, 488, 788, -1, + 784, 785, 1086, -1, 490, 785, 786, -1, + 490, 786, 677, -1, 490, 489, 779, -1, + 490, 677, 683, -1, 490, 683, 1591, -1, + 780, 785, 490, -1, 780, 490, 779, -1, + 791, 792, 489, -1, 791, 489, 490, -1, + 791, 490, 1591, -1, 491, 1646, 492, -1, + 491, 1643, 1646, -1, 491, 1591, 1643, -1, + 491, 790, 1591, -1, 794, 491, 492, -1, + 794, 790, 491, -1, 794, 492, 493, -1, + 794, 493, 793, -1, 862, 861, 494, -1, + 862, 494, 863, -1, 495, 1552, 1592, -1, + 495, 1592, 499, -1, 495, 499, 496, -1, + 495, 496, 497, -1, 495, 1112, 1552, -1, + 495, 497, 1112, -1, 498, 502, 1112, -1, + 498, 1112, 499, -1, 498, 499, 502, -1, + 500, 1592, 504, -1, 500, 504, 503, -1, + 500, 503, 1592, -1, 501, 502, 1592, -1, + 501, 1592, 503, -1, 501, 503, 504, -1, + 501, 504, 505, -1, 501, 505, 506, -1, + 501, 506, 1112, -1, 501, 1112, 502, -1, + 1092, 507, 799, -1, 1092, 1093, 507, -1, + 795, 509, 508, -1, 795, 796, 509, -1, + 795, 508, 797, -1, 798, 799, 509, -1, + 798, 509, 796, -1, 1605, 510, 1610, -1, + 1605, 511, 510, -1, 1605, 1602, 511, -1, + 1373, 1105, 801, -1, 1474, 1475, 809, -1, + 1474, 809, 804, -1, 821, 1376, 1375, -1, + 821, 802, 513, -1, 821, 1375, 802, -1, + 1546, 1376, 512, -1, 1546, 512, 806, -1, + 999, 811, 1239, -1, 999, 813, 811, -1, + 999, 1537, 813, -1, 823, 804, 809, -1, + 823, 513, 804, -1, 823, 821, 513, -1, + 816, 515, 811, -1, 816, 812, 514, -1, + 816, 514, 817, -1, 1114, 1239, 811, -1, + 1114, 811, 515, -1, 818, 814, 1114, -1, + 818, 1114, 515, -1, 818, 819, 516, -1, + 818, 515, 816, -1, 822, 517, 1376, -1, + 825, 814, 818, -1, 825, 818, 516, -1, + 825, 516, 517, -1, 825, 517, 822, -1, + 1121, 827, 518, -1, 1121, 518, 1123, -1, + 519, 827, 826, -1, 519, 826, 520, -1, + 519, 1120, 827, -1, 519, 520, 1120, -1, + 829, 522, 521, -1, 829, 523, 525, -1, + 829, 521, 523, -1, 829, 830, 522, -1, + 831, 525, 524, -1, 831, 829, 525, -1, + 831, 524, 526, -1, 831, 526, 527, -1, + 831, 528, 830, -1, 831, 527, 528, -1, + 529, 530, 758, -1, 529, 531, 530, -1, + 529, 758, 531, -1, 835, 833, 532, -1, + 835, 533, 836, -1, 835, 532, 534, -1, + 835, 534, 533, -1, 537, 535, 1559, -1, + 537, 536, 535, -1, 537, 837, 536, -1, + 1557, 537, 1559, -1, 1557, 837, 537, -1, + 538, 541, 543, -1, 538, 539, 541, -1, + 538, 543, 544, -1, 538, 544, 539, -1, + 540, 541, 542, -1, 540, 543, 541, -1, + 540, 542, 544, -1, 540, 544, 543, -1, + 841, 844, 925, -1, 841, 846, 844, -1, + 1390, 929, 1386, -1, 1390, 1389, 929, -1, + 1134, 1267, 1135, -1, 847, 545, 1143, -1, + 847, 546, 545, -1, 847, 1141, 546, -1, + 1140, 1400, 546, -1, 1140, 546, 1141, -1, + 848, 548, 549, -1, 848, 546, 1400, -1, + 848, 549, 546, -1, 849, 548, 848, -1, + 547, 549, 548, -1, 547, 1402, 549, -1, + 547, 548, 849, -1, 547, 849, 1402, -1, + 568, 569, 550, -1, 568, 550, 551, -1, + 568, 551, 690, -1, 556, 567, 554, -1, + 556, 552, 567, -1, 556, 852, 552, -1, + 556, 557, 851, -1, 556, 851, 852, -1, + 553, 554, 555, -1, 553, 557, 556, -1, + 553, 556, 554, -1, 553, 559, 558, -1, + 553, 558, 557, -1, 553, 560, 559, -1, + 553, 555, 560, -1, 561, 562, 563, -1, + 561, 563, 564, -1, 561, 566, 565, -1, + 561, 565, 562, -1, 561, 567, 566, -1, + 561, 564, 567, -1, 865, 863, 866, -1, + 1405, 866, 1407, -1, 689, 688, 576, -1, + 689, 569, 568, -1, 689, 568, 690, -1, + 689, 570, 569, -1, 689, 576, 570, -1, + 571, 572, 576, -1, 571, 576, 577, -1, + 571, 577, 573, -1, 571, 574, 572, -1, + 571, 573, 574, -1, 575, 576, 688, -1, + 575, 577, 576, -1, 575, 688, 1004, -1, + 575, 1004, 1003, -1, 575, 1005, 577, -1, + 575, 1003, 1005, -1, 940, 873, 1162, -1, + 1167, 1152, 1130, -1, 1167, 1130, 842, -1, + 1167, 842, 1165, -1, 1422, 878, 1423, -1, + 1415, 578, 1414, -1, 1415, 881, 578, -1, + 888, 1421, 882, -1, 888, 884, 885, -1, + 892, 580, 579, -1, 892, 579, 890, -1, + 892, 894, 580, -1, 581, 583, 582, -1, + 581, 582, 584, -1, 581, 613, 612, -1, + 581, 584, 613, -1, 581, 585, 583, -1, + 581, 586, 585, -1, 581, 612, 946, -1, + 581, 946, 586, -1, 896, 587, 588, -1, + 896, 593, 587, -1, 896, 907, 897, -1, + 896, 588, 589, -1, 896, 899, 593, -1, + 896, 589, 590, -1, 896, 958, 907, -1, + 896, 590, 958, -1, 591, 899, 595, -1, + 591, 595, 599, -1, 591, 599, 592, -1, + 591, 592, 593, -1, 591, 593, 899, -1, + 594, 595, 899, -1, 594, 899, 918, -1, + 594, 918, 596, -1, 594, 600, 595, -1, + 594, 596, 600, -1, 901, 902, 597, -1, + 901, 597, 598, -1, 901, 598, 599, -1, + 903, 599, 600, -1, 903, 600, 904, -1, + 903, 901, 599, -1, 733, 601, 767, -1, + 1155, 907, 1156, -1, 765, 601, 1427, -1, + 765, 1070, 767, -1, 765, 767, 601, -1, + 1426, 732, 911, -1, 1426, 733, 732, -1, + 1426, 601, 733, -1, 1426, 1427, 601, -1, + 909, 602, 1312, -1, 909, 911, 731, -1, + 909, 730, 602, -1, 909, 731, 730, -1, + 915, 918, 906, -1, 915, 906, 913, -1, + 1136, 1135, 603, -1, 1136, 603, 1137, -1, + 922, 928, 620, -1, 922, 929, 928, -1, + 922, 920, 929, -1, 922, 620, 923, -1, + 930, 604, 928, -1, 930, 1397, 604, -1, + 711, 606, 605, -1, 711, 605, 1013, -1, + 711, 1264, 710, -1, 711, 710, 606, -1, + 934, 932, 1267, -1, 1265, 1488, 933, -1, + 1265, 934, 1267, -1, 607, 1160, 608, -1, + 607, 611, 1160, -1, 607, 608, 620, -1, + 607, 609, 611, -1, 607, 620, 610, -1, + 607, 610, 609, -1, 942, 1160, 611, -1, + 942, 611, 943, -1, 942, 1159, 1160, -1, + 949, 946, 612, -1, 949, 612, 613, -1, + 949, 613, 614, -1, 949, 614, 950, -1, + 951, 948, 1173, -1, 951, 618, 948, -1, + 951, 1169, 618, -1, 886, 879, 885, -1, + 886, 887, 879, -1, 615, 616, 879, -1, + 615, 887, 616, -1, 615, 879, 887, -1, + 953, 616, 887, -1, 953, 617, 616, -1, + 953, 954, 617, -1, 619, 957, 946, -1, + 956, 948, 618, -1, 956, 619, 946, -1, + 956, 957, 619, -1, 956, 618, 1169, -1, + 956, 1169, 1170, -1, 956, 620, 958, -1, + 956, 1170, 620, -1, 621, 622, 623, -1, + 621, 623, 624, -1, 621, 624, 625, -1, + 621, 625, 626, -1, 621, 626, 627, -1, + 621, 627, 628, -1, 621, 628, 622, -1, + 629, 631, 630, -1, 629, 630, 632, -1, + 629, 641, 631, -1, 629, 639, 641, -1, + 629, 632, 639, -1, 1182, 1193, 1183, -1, + 1182, 1219, 1563, -1, 1182, 1563, 1193, -1, + 1182, 1218, 1219, -1, 1431, 965, 633, -1, + 1431, 634, 969, -1, 1431, 633, 634, -1, + 1444, 1184, 1446, -1, 1444, 635, 1184, -1, + 1444, 636, 635, -1, 1444, 1445, 636, -1, + 1133, 1350, 1188, -1, 1133, 1351, 1350, -1, + 1133, 1188, 1134, -1, 1347, 1080, 1445, -1, + 1347, 1348, 1080, -1, 1202, 972, 704, -1, + 1023, 1210, 1200, -1, 1023, 1209, 1210, -1, + 1207, 972, 1206, -1, 1207, 637, 699, -1, + 1207, 699, 972, -1, 1207, 638, 637, -1, + 1207, 1204, 638, -1, 1208, 1453, 1198, -1, + 1208, 1198, 1199, -1, 1208, 1199, 1210, -1, + 640, 639, 1204, -1, 640, 1204, 1214, -1, + 640, 641, 639, -1, 974, 1220, 963, -1, + 974, 640, 1214, -1, 974, 641, 640, -1, + 974, 963, 642, -1, 974, 642, 641, -1, + 1562, 1217, 977, -1, 1562, 1219, 1217, -1, + 1562, 1563, 1219, -1, 1189, 1617, 1562, -1, + 1189, 1562, 977, -1, 1189, 977, 975, -1, + 1189, 1211, 1439, -1, 643, 805, 802, -1, + 643, 979, 805, -1, 978, 801, 1105, -1, + 978, 1105, 1106, -1, 978, 802, 801, -1, + 978, 643, 802, -1, 978, 979, 643, -1, + 1107, 644, 652, -1, 1107, 652, 982, -1, + 1107, 1371, 644, -1, 1107, 1370, 1371, -1, + 1466, 1222, 645, -1, 1466, 645, 1371, -1, + 1233, 1232, 646, -1, 1233, 646, 647, -1, + 1233, 647, 661, -1, 649, 993, 985, -1, + 649, 653, 993, -1, 649, 648, 980, -1, + 649, 985, 648, -1, 981, 649, 980, -1, + 981, 653, 649, -1, 981, 1550, 1549, -1, + 981, 1588, 1550, -1, 650, 652, 651, -1, + 650, 651, 653, -1, 650, 1549, 652, -1, + 650, 981, 1549, -1, 650, 653, 981, -1, + 994, 654, 655, -1, 994, 656, 654, -1, + 994, 655, 983, -1, 994, 1224, 656, -1, + 987, 657, 658, -1, 987, 658, 1226, -1, + 987, 659, 657, -1, 987, 986, 659, -1, + 996, 993, 1232, -1, 660, 666, 1234, -1, + 660, 1233, 661, -1, 660, 1234, 1233, -1, + 660, 662, 663, -1, 660, 661, 662, -1, + 660, 663, 664, -1, 660, 664, 666, -1, + 665, 672, 989, -1, 665, 989, 988, -1, + 665, 988, 1234, -1, 665, 666, 672, -1, + 665, 1234, 666, -1, 667, 674, 989, -1, + 667, 668, 674, -1, 667, 669, 670, -1, + 667, 670, 671, -1, 667, 671, 668, -1, + 667, 672, 669, -1, 667, 989, 672, -1, + 673, 991, 990, -1, 673, 990, 674, -1, + 673, 675, 991, -1, 673, 676, 675, -1, + 673, 674, 676, -1, 1109, 1552, 1112, -1, + 682, 683, 677, -1, 682, 677, 680, -1, + 678, 680, 679, -1, 678, 679, 681, -1, + 678, 682, 680, -1, 678, 681, 683, -1, + 678, 683, 682, -1, 1006, 1004, 1364, -1, + 1006, 685, 1001, -1, 1097, 684, 685, -1, + 1097, 686, 684, -1, 1097, 685, 1006, -1, + 1097, 797, 686, -1, 687, 1004, 688, -1, + 687, 1364, 1004, -1, 687, 688, 689, -1, + 687, 689, 690, -1, 687, 1365, 1364, -1, + 687, 691, 1365, -1, 687, 690, 691, -1, + 692, 782, 1091, -1, 692, 1001, 782, -1, + 692, 1002, 1001, -1, 692, 693, 1002, -1, + 692, 1091, 693, -1, 694, 845, 856, -1, + 694, 856, 1358, -1, 694, 1358, 1357, -1, + 694, 1357, 1395, -1, 694, 1395, 845, -1, + 1242, 843, 1008, -1, 695, 1243, 846, -1, + 695, 846, 841, -1, 695, 841, 843, -1, + 695, 843, 1242, -1, 695, 1242, 1243, -1, + 696, 698, 697, -1, 696, 697, 699, -1, + 696, 701, 700, -1, 696, 700, 698, -1, + 696, 702, 701, -1, 696, 703, 702, -1, + 696, 699, 703, -1, 1276, 708, 1501, -1, + 1276, 1275, 1022, -1, 1276, 1022, 1201, -1, + 1276, 1201, 1202, -1, 1276, 704, 708, -1, + 1276, 1202, 704, -1, 705, 707, 706, -1, + 705, 708, 707, -1, 705, 706, 1502, -1, + 705, 1502, 1501, -1, 705, 1501, 708, -1, + 718, 973, 1209, -1, 718, 713, 973, -1, + 718, 1209, 1023, -1, 718, 717, 713, -1, + 1281, 1269, 715, -1, 1281, 715, 1280, -1, + 1449, 1260, 1448, -1, 1263, 1262, 709, -1, + 1263, 710, 1264, -1, 1263, 709, 710, -1, + 1014, 1440, 1260, -1, 1014, 711, 1013, -1, + 1014, 1264, 711, -1, 1014, 1490, 1440, -1, + 1011, 1256, 712, -1, 1011, 717, 1012, -1, + 1011, 712, 713, -1, 1011, 713, 717, -1, + 1016, 1322, 1009, -1, 1016, 1017, 1322, -1, + 1325, 1322, 1017, -1, 1325, 1017, 1327, -1, + 1019, 1270, 1268, -1, 1019, 1047, 1327, -1, + 1019, 1268, 1517, -1, 1509, 1493, 1268, -1, + 1512, 1509, 1268, -1, 1018, 1010, 714, -1, + 1018, 1016, 1010, -1, 1018, 1269, 1270, -1, + 1018, 715, 1269, -1, 1018, 714, 715, -1, + 1438, 1211, 1448, -1, 1438, 1439, 1211, -1, + 1438, 1448, 1260, -1, 1438, 1260, 1440, -1, + 1025, 1279, 1021, -1, 1286, 1499, 1497, -1, + 1287, 726, 719, -1, 1287, 1285, 726, -1, + 1027, 726, 1285, -1, 716, 1280, 717, -1, + 716, 717, 718, -1, 716, 1021, 1279, -1, + 716, 1279, 1280, -1, 716, 1023, 1021, -1, + 716, 718, 1023, -1, 1578, 1298, 1516, -1, + 1037, 1053, 726, -1, 1288, 719, 1053, -1, + 1288, 1287, 719, -1, 1300, 1301, 1053, -1, + 1290, 720, 1032, -1, 1290, 1291, 720, -1, + 1036, 724, 721, -1, 1036, 721, 1038, -1, + 1036, 1037, 724, -1, 722, 723, 724, -1, + 722, 725, 723, -1, 722, 724, 1037, -1, + 722, 1037, 726, -1, 722, 726, 1027, -1, + 722, 1026, 725, -1, 722, 1027, 1026, -1, + 1051, 735, 1050, -1, 1051, 1305, 739, -1, + 1051, 1043, 735, -1, 1051, 739, 1043, -1, + 1042, 769, 1041, -1, 1042, 768, 769, -1, + 1042, 727, 768, -1, 1042, 1045, 745, -1, + 1042, 745, 727, -1, 728, 768, 729, -1, + 728, 729, 730, -1, 728, 730, 731, -1, + 728, 731, 732, -1, 728, 732, 733, -1, + 728, 767, 768, -1, 728, 733, 767, -1, + 734, 1050, 735, -1, 734, 1075, 1050, -1, + 734, 735, 1040, -1, 734, 1040, 1333, -1, + 734, 1333, 1075, -1, 1048, 1298, 1059, -1, + 1055, 1050, 1058, -1, 1303, 1056, 1301, -1, + 1303, 1305, 1051, -1, 1303, 1055, 1056, -1, + 1057, 1515, 1288, -1, 736, 737, 738, -1, + 736, 739, 737, -1, 736, 1044, 1043, -1, + 736, 1043, 739, -1, 736, 738, 749, -1, + 736, 749, 746, -1, 736, 1045, 1044, -1, + 736, 746, 1045, -1, 1306, 1060, 740, -1, + 1306, 741, 1304, -1, 1306, 742, 741, -1, + 1306, 740, 742, -1, 743, 744, 745, -1, + 743, 745, 746, -1, 743, 747, 748, -1, + 743, 748, 744, -1, 743, 746, 749, -1, + 743, 749, 747, -1, 750, 755, 1061, -1, + 750, 751, 755, -1, 750, 1061, 752, -1, + 750, 752, 753, -1, 750, 753, 751, -1, + 1307, 1061, 755, -1, 754, 755, 756, -1, + 754, 1315, 1308, -1, 754, 1308, 1307, -1, + 754, 1307, 755, -1, 754, 757, 1315, -1, + 754, 758, 757, -1, 754, 756, 759, -1, + 754, 759, 758, -1, 916, 1319, 760, -1, + 916, 760, 917, -1, 916, 762, 1319, -1, + 916, 1637, 762, -1, 761, 762, 1637, -1, + 761, 1637, 1584, -1, 761, 1319, 762, -1, + 761, 1584, 1319, -1, 1314, 1315, 1064, -1, + 1065, 1319, 763, -1, 1065, 763, 1062, -1, + 1065, 1062, 764, -1, 1065, 764, 1066, -1, + 1067, 1070, 765, -1, 1067, 765, 1427, -1, + 766, 767, 1070, -1, 766, 1070, 1069, -1, + 766, 768, 767, -1, 766, 769, 768, -1, + 766, 1041, 769, -1, 766, 1069, 1041, -1, + 770, 1041, 1332, -1, 770, 1332, 1333, -1, + 770, 1040, 1041, -1, 770, 1333, 1040, -1, + 1077, 1009, 1322, -1, 1077, 1322, 1521, -1, + 771, 1102, 1120, -1, 771, 1120, 772, -1, + 771, 1103, 1102, -1, 771, 772, 1103, -1, + 773, 774, 775, -1, 773, 775, 776, -1, + 773, 776, 774, -1, 1354, 1080, 1348, -1, + 1087, 778, 777, -1, 1087, 777, 1088, -1, + 1087, 792, 778, -1, 1087, 779, 792, -1, + 1087, 780, 779, -1, 1087, 1086, 785, -1, + 1087, 785, 780, -1, 1085, 781, 788, -1, + 1085, 788, 784, -1, 1085, 1091, 782, -1, + 1085, 782, 781, -1, 1085, 784, 1086, -1, + 783, 785, 784, -1, 783, 787, 786, -1, + 783, 786, 785, -1, 783, 788, 787, -1, + 783, 784, 788, -1, 789, 1591, 790, -1, + 789, 791, 1591, -1, 789, 792, 791, -1, + 789, 793, 792, -1, 789, 790, 794, -1, + 789, 794, 793, -1, 1094, 796, 795, -1, + 1094, 795, 797, -1, 1094, 798, 796, -1, + 1094, 799, 798, -1, 1094, 1092, 799, -1, + 1094, 797, 1097, -1, 1470, 1472, 1471, -1, + 1531, 1103, 800, -1, 1531, 800, 1534, -1, + 1104, 1473, 1100, -1, 1104, 1469, 1473, -1, + 1104, 1099, 1102, -1, 1104, 1531, 1469, -1, + 1377, 1373, 801, -1, 1377, 801, 802, -1, + 1377, 802, 1375, -1, 803, 804, 805, -1, + 803, 1474, 804, -1, 803, 805, 979, -1, + 803, 979, 1474, -1, 1544, 806, 1545, -1, + 1544, 1546, 806, -1, 808, 809, 1475, -1, + 808, 1475, 1476, -1, 1477, 1482, 1478, -1, + 1477, 1478, 1116, -1, 1477, 1117, 1476, -1, + 1477, 1116, 1117, -1, 807, 1117, 824, -1, + 807, 824, 823, -1, 807, 1476, 1117, -1, + 807, 808, 1476, -1, 807, 823, 809, -1, + 807, 809, 808, -1, 810, 816, 811, -1, + 810, 812, 816, -1, 810, 811, 813, -1, + 810, 813, 812, -1, 1238, 1239, 1114, -1, + 1115, 1114, 814, -1, 1115, 824, 1117, -1, + 1115, 814, 825, -1, 1115, 825, 824, -1, + 815, 816, 817, -1, 815, 818, 816, -1, + 815, 817, 819, -1, 815, 819, 818, -1, + 820, 1376, 821, -1, 820, 822, 1376, -1, + 820, 823, 824, -1, 820, 821, 823, -1, + 820, 824, 825, -1, 820, 825, 822, -1, + 1119, 826, 827, -1, 1119, 827, 1121, -1, + 1119, 1120, 826, -1, 828, 830, 829, -1, + 828, 831, 830, -1, 828, 829, 831, -1, + 832, 834, 833, -1, 832, 833, 835, -1, + 832, 836, 834, -1, 832, 835, 836, -1, + 1379, 1559, 1127, -1, 1125, 837, 1557, -1, + 1125, 838, 837, -1, 1125, 1126, 839, -1, + 1125, 839, 838, -1, 840, 925, 926, -1, + 840, 841, 925, -1, 840, 926, 1165, -1, + 840, 1165, 842, -1, 840, 843, 841, -1, + 840, 1130, 843, -1, 840, 842, 1130, -1, + 1387, 1385, 844, -1, 1387, 845, 1395, -1, + 1387, 844, 846, -1, 1387, 846, 845, -1, + 1139, 1083, 1351, -1, 1139, 1393, 1083, -1, + 1139, 1137, 1138, -1, 1266, 1134, 1188, -1, + 1266, 1267, 1134, -1, 1142, 847, 1143, -1, + 1142, 1141, 847, -1, 1399, 848, 1400, -1, + 1399, 849, 848, -1, 1399, 1402, 849, -1, + 850, 853, 857, -1, 850, 851, 853, -1, + 850, 857, 858, -1, 850, 852, 851, -1, + 850, 858, 852, -1, 1359, 1358, 856, -1, + 1359, 856, 857, -1, 1359, 857, 853, -1, + 1359, 853, 1082, -1, 1359, 1082, 1356, -1, + 854, 856, 855, -1, 854, 857, 856, -1, + 854, 858, 857, -1, 854, 1247, 858, -1, + 854, 1248, 1247, -1, 854, 855, 1249, -1, + 854, 1249, 1248, -1, 867, 859, 860, -1, + 867, 868, 859, -1, 867, 860, 861, -1, + 867, 861, 862, -1, 867, 862, 863, -1, + 867, 863, 865, -1, 864, 865, 866, -1, + 864, 866, 1405, -1, 864, 868, 867, -1, + 864, 867, 865, -1, 864, 870, 869, -1, + 864, 869, 868, -1, 864, 871, 870, -1, + 864, 1405, 871, -1, 1404, 871, 1405, -1, + 1404, 872, 871, -1, 1404, 1145, 872, -1, + 936, 937, 873, -1, 936, 873, 940, -1, + 1150, 1151, 876, -1, 1150, 876, 874, -1, + 1150, 875, 1152, -1, 1150, 874, 875, -1, + 1161, 1162, 876, -1, 1161, 876, 1151, -1, + 877, 878, 1422, -1, 877, 879, 878, -1, + 877, 885, 879, -1, 877, 888, 885, -1, + 877, 1422, 888, -1, 1424, 1423, 880, -1, + 1424, 880, 881, -1, 1424, 881, 1415, -1, + 1153, 882, 1421, -1, 1153, 1421, 1170, -1, + 1153, 1154, 884, -1, 1153, 888, 882, -1, + 1153, 884, 888, -1, 1410, 1170, 1179, -1, + 1410, 1153, 1170, -1, 883, 885, 884, -1, + 883, 884, 1154, -1, 883, 1409, 952, -1, + 883, 1154, 1409, -1, 883, 886, 885, -1, + 883, 887, 886, -1, 883, 952, 953, -1, + 883, 953, 887, -1, 1420, 1421, 888, -1, + 1420, 888, 1422, -1, 889, 890, 891, -1, + 889, 892, 890, -1, 889, 891, 893, -1, + 889, 893, 894, -1, 889, 894, 892, -1, + 895, 896, 897, -1, 895, 897, 906, -1, + 895, 906, 898, -1, 895, 898, 899, -1, + 895, 899, 896, -1, 900, 902, 901, -1, + 900, 901, 903, -1, 900, 904, 902, -1, + 900, 903, 904, -1, 905, 913, 906, -1, + 905, 1155, 913, -1, 905, 906, 907, -1, + 905, 907, 1155, -1, 910, 1155, 911, -1, + 910, 913, 1155, -1, 1157, 911, 1155, -1, + 1157, 1426, 911, -1, 908, 909, 1312, -1, + 908, 1312, 1637, -1, 908, 1637, 914, -1, + 908, 914, 913, -1, 908, 913, 910, -1, + 908, 911, 909, -1, 908, 910, 911, -1, + 912, 913, 914, -1, 912, 915, 913, -1, + 912, 916, 917, -1, 912, 917, 918, -1, + 912, 918, 915, -1, 912, 914, 1637, -1, + 912, 1637, 916, -1, 919, 921, 920, -1, + 919, 920, 922, -1, 919, 923, 924, -1, + 919, 922, 923, -1, 919, 925, 921, -1, + 919, 926, 925, -1, 919, 924, 1165, -1, + 919, 1165, 926, -1, 927, 928, 929, -1, + 927, 930, 928, -1, 927, 929, 1389, -1, + 927, 1389, 1397, -1, 927, 1397, 930, -1, + 931, 933, 932, -1, 931, 932, 934, -1, + 931, 1265, 933, -1, 931, 934, 1265, -1, + 1166, 935, 1160, -1, 1166, 1164, 935, -1, + 941, 936, 940, -1, 941, 938, 937, -1, + 941, 937, 936, -1, 941, 944, 938, -1, + 939, 940, 1162, -1, 939, 1162, 1159, -1, + 939, 941, 940, -1, 939, 942, 943, -1, + 939, 1159, 942, -1, 939, 943, 944, -1, + 939, 944, 941, -1, 945, 949, 948, -1, + 945, 946, 949, -1, 945, 948, 956, -1, + 945, 956, 946, -1, 947, 1173, 948, -1, + 947, 948, 949, -1, 947, 950, 1173, -1, + 947, 949, 950, -1, 1172, 1169, 951, -1, + 1172, 1179, 1170, -1, 1172, 951, 1173, -1, + 1178, 1179, 1175, -1, 1178, 952, 1409, -1, + 1178, 953, 952, -1, 1178, 954, 953, -1, + 1178, 1176, 954, -1, 1178, 1175, 1176, -1, + 955, 957, 956, -1, 955, 956, 958, -1, + 955, 958, 959, -1, 955, 960, 957, -1, + 955, 961, 960, -1, 955, 959, 961, -1, + 1180, 1220, 1218, -1, 1180, 1434, 962, -1, + 1180, 962, 963, -1, 1180, 963, 1220, -1, + 1181, 1218, 1182, -1, 1181, 1180, 1218, -1, + 1430, 1433, 964, -1, 1430, 965, 1431, -1, + 1430, 964, 966, -1, 1430, 966, 965, -1, + 1186, 967, 1185, -1, 1186, 969, 968, -1, + 1186, 1431, 969, -1, 1186, 968, 970, -1, + 1186, 970, 971, -1, 1186, 971, 967, -1, + 1192, 1194, 1191, -1, 1492, 1266, 1188, -1, + 1569, 1194, 1436, -1, 1443, 1350, 1347, -1, + 1443, 1347, 1445, -1, 1197, 1206, 972, -1, + 1197, 972, 1202, -1, 1205, 1198, 976, -1, + 1205, 1196, 1198, -1, 1205, 1206, 1196, -1, + 1205, 1213, 1214, -1, 1456, 1209, 973, -1, + 1456, 973, 1450, -1, 1452, 975, 1453, -1, + 1452, 1189, 975, -1, 1452, 1211, 1189, -1, + 1215, 1220, 974, -1, 1215, 974, 1214, -1, + 1216, 976, 975, -1, 1216, 1205, 976, -1, + 1216, 1213, 1205, -1, 1216, 975, 977, -1, + 1216, 977, 1217, -1, 1575, 1106, 1221, -1, + 1575, 978, 1106, -1, 1575, 979, 978, -1, + 1575, 1474, 979, -1, 1638, 980, 1639, -1, + 1638, 981, 980, -1, 1638, 1588, 981, -1, + 1548, 982, 1549, -1, 1548, 1107, 982, -1, + 1548, 1108, 1107, -1, 1462, 1295, 1034, -1, + 1462, 1034, 1463, -1, 995, 983, 984, -1, + 995, 994, 983, -1, 995, 984, 985, -1, + 995, 985, 992, -1, 1227, 991, 986, -1, + 1227, 986, 987, -1, 1227, 987, 1226, -1, + 1228, 1231, 988, -1, 1228, 1225, 1231, -1, + 1228, 989, 990, -1, 1228, 988, 989, -1, + 1228, 990, 991, -1, 1228, 991, 1227, -1, + 997, 992, 993, -1, 997, 993, 996, -1, + 997, 1224, 994, -1, 997, 995, 992, -1, + 997, 994, 995, -1, 1230, 996, 1232, -1, + 1230, 1231, 1225, -1, 1230, 1224, 997, -1, + 1230, 997, 996, -1, 1612, 998, 1235, -1, + 1612, 1611, 998, -1, 1538, 1537, 999, -1, + 1538, 999, 1539, -1, 1240, 999, 1239, -1, + 1240, 1539, 999, -1, 1000, 1006, 1001, -1, + 1000, 1001, 1002, -1, 1000, 1003, 1004, -1, + 1000, 1004, 1006, -1, 1000, 1002, 1005, -1, + 1000, 1005, 1003, -1, 1096, 1006, 1364, -1, + 1096, 1097, 1006, -1, 1244, 1242, 1124, -1, + 1244, 1124, 1382, -1, 1244, 1382, 1127, -1, + 1244, 1559, 1245, -1, 1244, 1127, 1559, -1, + 1007, 1242, 1008, -1, 1007, 1124, 1242, -1, + 1007, 1008, 1130, -1, 1007, 1130, 1124, -1, + 1529, 1528, 1250, -1, 1076, 1527, 1252, -1, + 1076, 1009, 1077, -1, 1076, 1016, 1009, -1, + 1076, 1010, 1016, -1, 1076, 1253, 1010, -1, + 1076, 1252, 1253, -1, 1254, 1256, 1011, -1, + 1254, 1012, 1253, -1, 1254, 1011, 1012, -1, + 1258, 1450, 1256, -1, 1258, 1449, 1450, -1, + 1261, 1014, 1260, -1, 1261, 1264, 1014, -1, + 1487, 1013, 1488, -1, 1487, 1014, 1013, -1, + 1487, 1490, 1014, -1, 1046, 1047, 1019, -1, + 1046, 1019, 1517, -1, 1271, 1268, 1270, -1, + 1271, 1512, 1268, -1, 1015, 1017, 1016, -1, + 1015, 1016, 1018, -1, 1015, 1327, 1017, -1, + 1015, 1018, 1270, -1, 1015, 1019, 1327, -1, + 1015, 1270, 1019, -1, 1020, 1025, 1021, -1, + 1020, 1022, 1275, -1, 1020, 1275, 1025, -1, + 1020, 1201, 1022, -1, 1020, 1200, 1201, -1, + 1020, 1023, 1200, -1, 1020, 1021, 1023, -1, + 1496, 1272, 1029, -1, 1496, 1029, 1497, -1, + 1500, 1024, 1275, -1, 1503, 1499, 1286, -1, + 1503, 1500, 1499, -1, 1503, 1024, 1500, -1, + 1278, 1503, 1504, -1, 1278, 1024, 1503, -1, + 1278, 1279, 1025, -1, 1278, 1025, 1275, -1, + 1278, 1275, 1024, -1, 1284, 1030, 1026, -1, + 1284, 1026, 1027, -1, 1284, 1027, 1285, -1, + 1028, 1497, 1029, -1, 1028, 1286, 1497, -1, + 1028, 1284, 1286, -1, 1028, 1029, 1030, -1, + 1028, 1030, 1284, -1, 1510, 1285, 1287, -1, + 1514, 1288, 1515, -1, 1031, 1295, 1290, -1, + 1031, 1290, 1032, -1, 1031, 1032, 1033, -1, + 1031, 1033, 1034, -1, 1031, 1034, 1295, -1, + 1035, 1037, 1036, -1, 1035, 1053, 1037, -1, + 1035, 1300, 1053, -1, 1035, 1060, 1300, -1, + 1035, 1038, 1060, -1, 1035, 1036, 1038, -1, + 1039, 1041, 1040, -1, 1039, 1042, 1041, -1, + 1039, 1040, 1043, -1, 1039, 1043, 1044, -1, + 1039, 1044, 1045, -1, 1039, 1045, 1042, -1, + 1326, 1048, 1345, -1, 1326, 1517, 1516, -1, + 1326, 1046, 1517, -1, 1326, 1297, 1298, -1, + 1326, 1298, 1048, -1, 1326, 1327, 1047, -1, + 1326, 1047, 1046, -1, 1074, 1345, 1048, -1, + 1074, 1058, 1075, -1, 1074, 1059, 1058, -1, + 1074, 1048, 1059, -1, 1049, 1050, 1055, -1, + 1049, 1055, 1303, -1, 1049, 1051, 1050, -1, + 1049, 1303, 1051, -1, 1052, 1288, 1053, -1, + 1052, 1057, 1288, -1, 1052, 1053, 1301, -1, + 1052, 1301, 1056, -1, 1052, 1056, 1057, -1, + 1054, 1056, 1055, -1, 1054, 1057, 1056, -1, + 1054, 1058, 1059, -1, 1054, 1055, 1058, -1, + 1054, 1059, 1298, -1, 1054, 1298, 1578, -1, + 1054, 1578, 1515, -1, 1054, 1515, 1057, -1, + 1302, 1300, 1060, -1, 1302, 1060, 1306, -1, + 1582, 1310, 1061, -1, 1582, 1061, 1307, -1, + 1316, 1308, 1315, -1, 1063, 1064, 1062, -1, + 1309, 1062, 1585, -1, 1309, 1063, 1062, -1, + 1309, 1314, 1064, -1, 1309, 1064, 1063, -1, + 1320, 1319, 1065, -1, 1320, 1066, 1318, -1, + 1320, 1065, 1066, -1, 1073, 1067, 1427, -1, + 1073, 1427, 1078, -1, 1073, 1072, 1070, -1, + 1073, 1070, 1067, -1, 1329, 1078, 1330, -1, + 1329, 1331, 1078, -1, 1068, 1332, 1069, -1, + 1068, 1331, 1332, -1, 1068, 1069, 1070, -1, + 1068, 1070, 1072, -1, 1068, 1072, 1331, -1, + 1071, 1078, 1331, -1, 1071, 1331, 1072, -1, + 1071, 1073, 1078, -1, 1071, 1072, 1073, -1, + 1079, 1330, 1078, -1, 1324, 1342, 1339, -1, + 1324, 1345, 1342, -1, 1344, 1345, 1074, -1, + 1344, 1075, 1334, -1, 1344, 1074, 1075, -1, + 1343, 1344, 1334, -1, 1335, 1527, 1076, -1, + 1335, 1076, 1077, -1, 1336, 1077, 1521, -1, + 1336, 1335, 1077, -1, 1520, 1339, 1523, -1, + 1520, 1521, 1322, -1, 1524, 1338, 1079, -1, + 1524, 1078, 1528, -1, 1524, 1079, 1078, -1, + 1341, 1330, 1079, -1, 1341, 1079, 1338, -1, + 1341, 1343, 1330, -1, 1355, 1081, 1080, -1, + 1355, 1080, 1354, -1, 1355, 1082, 1081, -1, + 1355, 1356, 1082, -1, 1349, 1354, 1348, -1, + 1349, 1083, 1393, -1, 1349, 1351, 1083, -1, + 1353, 1354, 1349, -1, 1353, 1393, 1357, -1, + 1353, 1349, 1393, -1, 1084, 1085, 1086, -1, + 1084, 1086, 1087, -1, 1084, 1087, 1088, -1, + 1084, 1089, 1090, -1, 1084, 1088, 1089, -1, + 1084, 1090, 1091, -1, 1084, 1091, 1085, -1, + 1361, 1093, 1092, -1, 1361, 1092, 1094, -1, + 1361, 1095, 1093, -1, 1361, 1362, 1095, -1, + 1361, 1096, 1364, -1, 1361, 1094, 1097, -1, + 1361, 1097, 1096, -1, 1098, 1100, 1099, -1, + 1098, 1104, 1100, -1, 1098, 1099, 1104, -1, + 1101, 1102, 1103, -1, 1101, 1104, 1102, -1, + 1101, 1103, 1531, -1, 1101, 1531, 1104, -1, + 1369, 1105, 1373, -1, 1369, 1373, 1372, -1, + 1369, 1106, 1105, -1, 1369, 1221, 1106, -1, + 1369, 1457, 1221, -1, 1368, 1466, 1371, -1, + 1368, 1372, 1466, -1, 1368, 1369, 1372, -1, + 1465, 1466, 1372, -1, 1460, 1108, 1573, -1, + 1460, 1370, 1107, -1, 1460, 1107, 1108, -1, + 1572, 1573, 1108, -1, 1572, 1108, 1548, -1, + 1551, 1552, 1109, -1, 1551, 1110, 1602, -1, + 1551, 1111, 1110, -1, 1551, 1112, 1111, -1, + 1551, 1109, 1112, -1, 1604, 1602, 1605, -1, + 1604, 1599, 1602, -1, 1113, 1238, 1114, -1, + 1113, 1114, 1115, -1, 1113, 1116, 1478, -1, + 1113, 1478, 1238, -1, 1113, 1117, 1116, -1, + 1113, 1115, 1117, -1, 1118, 1120, 1119, -1, + 1118, 1119, 1121, -1, 1118, 1122, 1120, -1, + 1118, 1123, 1122, -1, 1118, 1121, 1123, -1, + 1381, 1382, 1124, -1, 1381, 1124, 1130, -1, + 1381, 1130, 1131, -1, 1381, 1129, 1384, -1, + 1381, 1131, 1129, -1, 1383, 1126, 1125, -1, + 1383, 1125, 1557, -1, 1383, 1384, 1126, -1, + 1383, 1379, 1127, -1, 1383, 1127, 1382, -1, + 1128, 1130, 1129, -1, 1128, 1131, 1130, -1, + 1128, 1129, 1131, -1, 1392, 1395, 1357, -1, + 1392, 1357, 1393, -1, 1132, 1139, 1351, -1, + 1132, 1351, 1133, -1, 1132, 1133, 1134, -1, + 1132, 1134, 1135, -1, 1132, 1135, 1136, -1, + 1132, 1136, 1137, -1, 1132, 1137, 1139, -1, + 1394, 1138, 1397, -1, 1394, 1139, 1138, -1, + 1394, 1393, 1139, -1, 1401, 1400, 1140, -1, + 1401, 1140, 1141, -1, 1401, 1141, 1142, -1, + 1401, 1142, 1143, -1, 1401, 1144, 1402, -1, + 1401, 1143, 1144, -1, 1406, 1146, 1145, -1, + 1406, 1145, 1404, -1, 1406, 1407, 1147, -1, + 1406, 1148, 1146, -1, 1406, 1147, 1148, -1, + 1149, 1151, 1150, -1, 1149, 1161, 1151, -1, + 1149, 1152, 1167, -1, 1149, 1150, 1152, -1, + 1149, 1167, 1166, -1, 1149, 1166, 1161, -1, + 1411, 1153, 1410, -1, 1411, 1154, 1153, -1, + 1411, 1409, 1154, -1, 1417, 1418, 1421, -1, + 1419, 1413, 1418, -1, 1419, 1424, 1415, -1, + 1428, 1155, 1156, -1, 1428, 1157, 1155, -1, + 1428, 1156, 1427, -1, 1428, 1426, 1157, -1, + 1158, 1160, 1159, -1, 1158, 1166, 1160, -1, + 1158, 1161, 1166, -1, 1158, 1159, 1162, -1, + 1158, 1162, 1161, -1, 1163, 1165, 1164, -1, + 1163, 1164, 1166, -1, 1163, 1167, 1165, -1, + 1163, 1166, 1167, -1, 1168, 1170, 1169, -1, + 1168, 1172, 1170, -1, 1168, 1169, 1172, -1, + 1171, 1172, 1173, -1, 1171, 1173, 1174, -1, + 1171, 1175, 1179, -1, 1171, 1179, 1172, -1, + 1171, 1174, 1176, -1, 1171, 1176, 1175, -1, + 1177, 1179, 1178, -1, 1177, 1178, 1409, -1, + 1177, 1410, 1179, -1, 1177, 1409, 1410, -1, + 1435, 1434, 1180, -1, 1435, 1180, 1181, -1, + 1435, 1182, 1183, -1, 1435, 1181, 1182, -1, + 1435, 1183, 1184, -1, 1435, 1184, 1433, -1, + 1432, 1185, 1434, -1, 1432, 1186, 1185, -1, + 1432, 1431, 1186, -1, 1187, 1192, 1191, -1, + 1187, 1188, 1350, -1, 1187, 1350, 1443, -1, + 1187, 1443, 1192, -1, 1187, 1492, 1188, -1, + 1187, 1191, 1492, -1, 1190, 1191, 1194, -1, + 1190, 1194, 1569, -1, 1615, 1436, 1193, -1, + 1615, 1193, 1563, -1, 1615, 1563, 1560, -1, + 1567, 1617, 1189, -1, 1567, 1189, 1439, -1, + 1565, 1191, 1190, -1, 1565, 1190, 1569, -1, + 1565, 1491, 1492, -1, 1565, 1492, 1191, -1, + 1442, 1192, 1443, -1, 1442, 1446, 1193, -1, + 1442, 1193, 1436, -1, 1442, 1436, 1194, -1, + 1442, 1194, 1192, -1, 1195, 1196, 1206, -1, + 1195, 1206, 1197, -1, 1195, 1199, 1198, -1, + 1195, 1198, 1196, -1, 1195, 1200, 1199, -1, + 1195, 1201, 1200, -1, 1195, 1202, 1201, -1, + 1195, 1197, 1202, -1, 1203, 1214, 1204, -1, + 1203, 1205, 1214, -1, 1203, 1206, 1205, -1, + 1203, 1204, 1207, -1, 1203, 1207, 1206, -1, + 1455, 1453, 1208, -1, 1455, 1209, 1456, -1, + 1455, 1210, 1209, -1, 1455, 1208, 1210, -1, + 1454, 1448, 1211, -1, 1454, 1211, 1452, -1, + 1212, 1214, 1213, -1, 1212, 1215, 1214, -1, + 1212, 1216, 1217, -1, 1212, 1213, 1216, -1, + 1212, 1219, 1218, -1, 1212, 1217, 1219, -1, + 1212, 1218, 1220, -1, 1212, 1220, 1215, -1, + 1459, 1221, 1457, -1, 1459, 1575, 1221, -1, + 1464, 1463, 1222, -1, 1464, 1222, 1466, -1, + 1294, 1542, 1290, -1, 1294, 1290, 1295, -1, + 1223, 1224, 1230, -1, 1223, 1230, 1225, -1, + 1223, 1226, 1224, -1, 1223, 1227, 1226, -1, + 1223, 1225, 1228, -1, 1223, 1228, 1227, -1, + 1229, 1231, 1230, -1, 1229, 1230, 1232, -1, + 1229, 1232, 1233, -1, 1229, 1234, 1231, -1, + 1229, 1233, 1234, -1, 1485, 1235, 1236, -1, + 1485, 1612, 1235, -1, 1485, 1236, 1472, -1, + 1620, 1482, 1477, -1, 1620, 1554, 1599, -1, + 1624, 1628, 1623, -1, 1480, 1628, 1483, -1, + 1480, 1483, 1479, -1, 1480, 1623, 1628, -1, + 1237, 1479, 1483, -1, 1237, 1478, 1479, -1, + 1237, 1238, 1478, -1, 1237, 1239, 1238, -1, + 1237, 1240, 1239, -1, 1237, 1483, 1539, -1, + 1237, 1539, 1240, -1, 1241, 1243, 1242, -1, + 1241, 1242, 1244, -1, 1241, 1245, 1246, -1, + 1241, 1244, 1245, -1, 1241, 1246, 1247, -1, + 1241, 1247, 1248, -1, 1241, 1249, 1243, -1, + 1241, 1248, 1249, -1, 1255, 1258, 1256, -1, + 1255, 1259, 1258, -1, 1255, 1250, 1262, -1, + 1255, 1262, 1259, -1, 1255, 1529, 1250, -1, + 1251, 1253, 1252, -1, 1251, 1254, 1253, -1, + 1251, 1529, 1255, -1, 1251, 1256, 1254, -1, + 1251, 1255, 1256, -1, 1251, 1252, 1527, -1, + 1251, 1527, 1529, -1, 1257, 1258, 1259, -1, + 1257, 1449, 1258, -1, 1257, 1260, 1449, -1, + 1257, 1261, 1260, -1, 1257, 1259, 1262, -1, + 1257, 1262, 1263, -1, 1257, 1263, 1264, -1, + 1257, 1264, 1261, -1, 1489, 1488, 1265, -1, + 1489, 1266, 1492, -1, 1489, 1265, 1267, -1, + 1489, 1267, 1266, -1, 1581, 1268, 1493, -1, + 1581, 1517, 1268, -1, 1282, 1269, 1281, -1, + 1282, 1270, 1269, -1, 1282, 1271, 1270, -1, + 1506, 1512, 1271, -1, 1506, 1271, 1282, -1, + 1498, 1273, 1272, -1, 1498, 1272, 1496, -1, + 1498, 1502, 1273, -1, 1274, 1501, 1500, -1, + 1274, 1500, 1275, -1, 1274, 1276, 1501, -1, + 1274, 1275, 1276, -1, 1277, 1279, 1278, -1, + 1277, 1280, 1279, -1, 1277, 1281, 1280, -1, + 1277, 1282, 1281, -1, 1277, 1506, 1282, -1, + 1277, 1278, 1504, -1, 1277, 1504, 1506, -1, + 1283, 1286, 1284, -1, 1283, 1510, 1286, -1, + 1283, 1284, 1285, -1, 1283, 1285, 1510, -1, + 1505, 1503, 1286, -1, 1505, 1286, 1510, -1, + 1508, 1510, 1287, -1, 1508, 1493, 1509, -1, + 1508, 1287, 1288, -1, 1508, 1514, 1493, -1, + 1508, 1288, 1514, -1, 1494, 1493, 1514, -1, + 1577, 1515, 1578, -1, 1289, 1291, 1290, -1, + 1289, 1290, 1542, -1, 1289, 1292, 1293, -1, + 1289, 1293, 1291, -1, 1289, 1545, 1292, -1, + 1289, 1542, 1545, -1, 1541, 1542, 1294, -1, + 1541, 1295, 1462, -1, 1541, 1294, 1295, -1, + 1296, 1326, 1516, -1, 1296, 1297, 1326, -1, + 1296, 1516, 1298, -1, 1296, 1298, 1297, -1, + 1299, 1301, 1300, -1, 1299, 1300, 1302, -1, + 1299, 1303, 1301, -1, 1299, 1304, 1305, -1, + 1299, 1305, 1303, -1, 1299, 1306, 1304, -1, + 1299, 1302, 1306, -1, 1518, 1307, 1308, -1, + 1518, 1582, 1307, -1, 1518, 1308, 1316, -1, + 1518, 1309, 1585, -1, 1518, 1314, 1309, -1, + 1634, 1311, 1310, -1, 1634, 1310, 1582, -1, + 1634, 1312, 1311, -1, 1634, 1637, 1312, -1, + 1634, 1635, 1637, -1, 1313, 1315, 1314, -1, + 1313, 1316, 1315, -1, 1313, 1314, 1518, -1, + 1313, 1518, 1316, -1, 1317, 1318, 1319, -1, + 1317, 1319, 1320, -1, 1317, 1320, 1318, -1, + 1321, 1322, 1325, -1, 1321, 1325, 1324, -1, + 1321, 1520, 1322, -1, 1321, 1324, 1339, -1, + 1321, 1339, 1520, -1, 1323, 1345, 1324, -1, + 1323, 1324, 1325, -1, 1323, 1326, 1345, -1, + 1323, 1325, 1327, -1, 1323, 1327, 1326, -1, + 1328, 1329, 1330, -1, 1328, 1330, 1343, -1, + 1328, 1332, 1331, -1, 1328, 1331, 1329, -1, + 1328, 1333, 1332, -1, 1328, 1334, 1333, -1, + 1328, 1343, 1334, -1, 1522, 1336, 1521, -1, + 1522, 1524, 1528, -1, 1526, 1527, 1335, -1, + 1526, 1335, 1336, -1, 1526, 1522, 1528, -1, + 1526, 1336, 1522, -1, 1337, 1338, 1524, -1, + 1337, 1341, 1338, -1, 1337, 1523, 1339, -1, + 1337, 1524, 1523, -1, 1337, 1339, 1342, -1, + 1337, 1342, 1341, -1, 1340, 1341, 1342, -1, + 1340, 1343, 1341, -1, 1340, 1344, 1343, -1, + 1340, 1342, 1345, -1, 1340, 1345, 1344, -1, + 1346, 1348, 1347, -1, 1346, 1349, 1348, -1, + 1346, 1347, 1350, -1, 1346, 1350, 1351, -1, + 1346, 1351, 1349, -1, 1352, 1354, 1353, -1, + 1352, 1355, 1354, -1, 1352, 1356, 1355, -1, + 1352, 1353, 1357, -1, 1352, 1357, 1358, -1, + 1352, 1358, 1359, -1, 1352, 1359, 1356, -1, + 1360, 1362, 1361, -1, 1360, 1363, 1362, -1, + 1360, 1364, 1365, -1, 1360, 1361, 1364, -1, + 1360, 1366, 1363, -1, 1360, 1365, 1366, -1, + 1535, 1531, 1534, -1, 1367, 1369, 1368, -1, + 1367, 1457, 1369, -1, 1367, 1371, 1370, -1, + 1367, 1368, 1371, -1, 1367, 1458, 1457, -1, + 1367, 1460, 1458, -1, 1367, 1370, 1460, -1, + 1468, 1372, 1373, -1, 1468, 1465, 1372, -1, + 1468, 1373, 1377, -1, 1468, 1377, 1378, -1, + 1543, 1541, 1467, -1, 1543, 1467, 1468, -1, + 1543, 1468, 1378, -1, 1374, 1375, 1376, -1, + 1374, 1376, 1546, -1, 1374, 1377, 1375, -1, + 1374, 1378, 1377, -1, 1374, 1546, 1543, -1, + 1374, 1543, 1378, -1, 1590, 1572, 1548, -1, + 1553, 1552, 1551, -1, 1553, 1551, 1599, -1, + 1553, 1599, 1554, -1, 1593, 1592, 1552, -1, + 1556, 1383, 1557, -1, 1556, 1379, 1383, -1, + 1556, 1559, 1379, -1, 1556, 1558, 1559, -1, + 1380, 1382, 1381, -1, 1380, 1383, 1382, -1, + 1380, 1381, 1384, -1, 1380, 1384, 1383, -1, + 1388, 1385, 1387, -1, 1388, 1386, 1385, -1, + 1388, 1390, 1386, -1, 1396, 1387, 1395, -1, + 1396, 1388, 1387, -1, 1396, 1397, 1389, -1, + 1396, 1389, 1390, -1, 1396, 1390, 1388, -1, + 1391, 1392, 1393, -1, 1391, 1393, 1394, -1, + 1391, 1395, 1392, -1, 1391, 1396, 1395, -1, + 1391, 1394, 1397, -1, 1391, 1397, 1396, -1, + 1398, 1399, 1400, -1, 1398, 1400, 1401, -1, + 1398, 1402, 1399, -1, 1398, 1401, 1402, -1, + 1403, 1404, 1405, -1, 1403, 1406, 1404, -1, + 1403, 1405, 1407, -1, 1403, 1407, 1406, -1, + 1408, 1410, 1409, -1, 1408, 1411, 1410, -1, + 1408, 1409, 1411, -1, 1412, 1414, 1413, -1, + 1412, 1413, 1419, -1, 1412, 1415, 1414, -1, + 1412, 1419, 1415, -1, 1416, 1418, 1417, -1, + 1416, 1419, 1418, -1, 1416, 1421, 1420, -1, + 1416, 1417, 1421, -1, 1416, 1422, 1423, -1, + 1416, 1420, 1422, -1, 1416, 1423, 1424, -1, + 1416, 1424, 1419, -1, 1425, 1427, 1426, -1, + 1425, 1428, 1427, -1, 1425, 1426, 1428, -1, + 1429, 1430, 1431, -1, 1429, 1431, 1432, -1, + 1429, 1433, 1430, -1, 1429, 1432, 1434, -1, + 1429, 1434, 1435, -1, 1429, 1435, 1433, -1, + 1561, 1560, 1563, -1, 1568, 1569, 1436, -1, + 1568, 1436, 1615, -1, 1570, 1565, 1569, -1, + 1570, 1617, 1567, -1, 1437, 1566, 1567, -1, + 1437, 1565, 1566, -1, 1437, 1439, 1438, -1, + 1437, 1567, 1439, -1, 1437, 1440, 1490, -1, + 1437, 1438, 1440, -1, 1437, 1490, 1491, -1, + 1437, 1491, 1565, -1, 1441, 1442, 1443, -1, + 1441, 1445, 1444, -1, 1441, 1443, 1445, -1, + 1441, 1444, 1446, -1, 1441, 1446, 1442, -1, + 1447, 1448, 1454, -1, 1447, 1449, 1448, -1, + 1447, 1450, 1449, -1, 1447, 1456, 1450, -1, + 1447, 1454, 1456, -1, 1451, 1452, 1453, -1, + 1451, 1454, 1452, -1, 1451, 1453, 1455, -1, + 1451, 1455, 1456, -1, 1451, 1456, 1454, -1, + 1574, 1457, 1458, -1, 1574, 1459, 1457, -1, + 1574, 1458, 1460, -1, 1574, 1460, 1573, -1, + 1574, 1575, 1459, -1, 1461, 1462, 1463, -1, + 1461, 1463, 1464, -1, 1461, 1466, 1465, -1, + 1461, 1464, 1466, -1, 1461, 1467, 1541, -1, + 1461, 1541, 1462, -1, 1461, 1468, 1467, -1, + 1461, 1465, 1468, -1, 1484, 1469, 1531, -1, + 1484, 1531, 1530, -1, 1484, 1470, 1471, -1, + 1484, 1472, 1470, -1, 1484, 1485, 1472, -1, + 1484, 1471, 1473, -1, 1484, 1473, 1469, -1, + 1594, 1475, 1474, -1, 1594, 1476, 1475, -1, + 1594, 1474, 1575, -1, 1594, 1477, 1476, -1, + 1594, 1620, 1477, -1, 1622, 1478, 1481, -1, + 1622, 1479, 1478, -1, 1622, 1480, 1479, -1, + 1622, 1623, 1480, -1, 1621, 1622, 1481, -1, + 1621, 1481, 1482, -1, 1621, 1482, 1620, -1, + 1627, 1628, 1624, -1, 1587, 1483, 1628, -1, + 1587, 1539, 1483, -1, 1587, 1536, 1539, -1, + 1632, 1484, 1530, -1, 1632, 1485, 1484, -1, + 1632, 1612, 1485, -1, 1632, 1629, 1612, -1, + 1486, 1487, 1488, -1, 1486, 1488, 1489, -1, + 1486, 1491, 1490, -1, 1486, 1490, 1487, -1, + 1486, 1492, 1491, -1, 1486, 1489, 1492, -1, + 1580, 1581, 1493, -1, 1580, 1493, 1494, -1, + 1580, 1494, 1514, -1, 1495, 1496, 1497, -1, + 1495, 1498, 1496, -1, 1495, 1497, 1499, -1, + 1495, 1499, 1500, -1, 1495, 1500, 1501, -1, + 1495, 1501, 1502, -1, 1495, 1502, 1498, -1, + 1511, 1504, 1503, -1, 1511, 1503, 1505, -1, + 1511, 1506, 1504, -1, 1511, 1512, 1506, -1, + 1511, 1505, 1510, -1, 1507, 1508, 1509, -1, + 1507, 1510, 1508, -1, 1507, 1511, 1510, -1, + 1507, 1509, 1512, -1, 1507, 1512, 1511, -1, + 1513, 1514, 1515, -1, 1513, 1515, 1577, -1, + 1513, 1580, 1514, -1, 1513, 1577, 1580, -1, + 1579, 1578, 1516, -1, 1579, 1516, 1517, -1, + 1579, 1517, 1581, -1, 1583, 1518, 1585, -1, + 1583, 1582, 1518, -1, 1519, 1521, 1520, -1, + 1519, 1522, 1521, -1, 1519, 1520, 1523, -1, + 1519, 1523, 1524, -1, 1519, 1524, 1522, -1, + 1525, 1527, 1526, -1, 1525, 1526, 1528, -1, + 1525, 1529, 1527, -1, 1525, 1528, 1529, -1, + 1586, 1536, 1587, -1, 1586, 1530, 1531, -1, + 1586, 1531, 1535, -1, 1586, 1632, 1530, -1, + 1532, 1534, 1533, -1, 1532, 1535, 1534, -1, + 1532, 1536, 1586, -1, 1532, 1586, 1535, -1, + 1532, 1533, 1537, -1, 1532, 1537, 1538, -1, + 1532, 1538, 1539, -1, 1532, 1539, 1536, -1, + 1540, 1542, 1541, -1, 1540, 1541, 1543, -1, + 1540, 1544, 1545, -1, 1540, 1545, 1542, -1, + 1540, 1546, 1544, -1, 1540, 1543, 1546, -1, + 1547, 1550, 1590, -1, 1547, 1590, 1548, -1, + 1547, 1549, 1550, -1, 1547, 1548, 1549, -1, + 1589, 1550, 1588, -1, 1589, 1590, 1550, -1, + 1596, 1602, 1599, -1, 1598, 1599, 1551, -1, + 1598, 1551, 1602, -1, 1606, 1599, 1604, -1, + 1606, 1608, 1599, -1, 1606, 1610, 1608, -1, + 1619, 1620, 1599, -1, 1619, 1599, 1608, -1, + 1595, 1593, 1552, -1, 1595, 1552, 1553, -1, + 1595, 1553, 1554, -1, 1595, 1554, 1620, -1, + 1555, 1556, 1557, -1, 1555, 1558, 1556, -1, + 1555, 1557, 1559, -1, 1555, 1559, 1558, -1, + 1614, 1615, 1560, -1, 1614, 1560, 1561, -1, + 1614, 1563, 1562, -1, 1614, 1561, 1563, -1, + 1614, 1562, 1617, -1, 1564, 1566, 1565, -1, + 1564, 1565, 1570, -1, 1564, 1567, 1566, -1, + 1564, 1570, 1567, -1, 1616, 1569, 1568, -1, + 1616, 1570, 1569, -1, 1616, 1568, 1615, -1, + 1616, 1617, 1570, -1, 1571, 1572, 1590, -1, + 1571, 1573, 1572, -1, 1571, 1574, 1573, -1, + 1571, 1575, 1574, -1, 1571, 1594, 1575, -1, + 1571, 1590, 1594, -1, 1626, 1627, 1624, -1, + 1576, 1577, 1578, -1, 1576, 1578, 1579, -1, + 1576, 1580, 1577, -1, 1576, 1581, 1580, -1, + 1576, 1579, 1581, -1, 1636, 1634, 1582, -1, + 1636, 1582, 1583, -1, 1636, 1584, 1637, -1, + 1636, 1585, 1584, -1, 1636, 1583, 1585, -1, + 1631, 1586, 1587, -1, 1631, 1632, 1586, -1, + 1631, 1587, 1628, -1, 1642, 1588, 1638, -1, + 1642, 1589, 1588, -1, 1642, 1590, 1589, -1, + 1642, 1643, 1591, -1, 1642, 1591, 1592, -1, + 1642, 1592, 1593, -1, 1642, 1620, 1594, -1, + 1642, 1594, 1590, -1, 1642, 1595, 1620, -1, + 1642, 1593, 1595, -1, 1600, 1596, 1599, -1, + 1600, 1601, 1602, -1, 1600, 1602, 1596, -1, + 1597, 1599, 1598, -1, 1597, 1600, 1599, -1, + 1597, 1601, 1600, -1, 1597, 1602, 1601, -1, + 1597, 1598, 1602, -1, 1603, 1604, 1605, -1, + 1603, 1606, 1604, -1, 1603, 1605, 1610, -1, + 1603, 1610, 1606, -1, 1607, 1608, 1610, -1, + 1607, 1610, 1619, -1, 1607, 1619, 1608, -1, + 1609, 1610, 1611, -1, 1609, 1619, 1610, -1, + 1609, 1611, 1612, -1, 1609, 1630, 1619, -1, + 1609, 1612, 1629, -1, 1609, 1629, 1630, -1, + 1613, 1615, 1614, -1, 1613, 1616, 1615, -1, + 1613, 1614, 1617, -1, 1613, 1617, 1616, -1, + 1618, 1620, 1619, -1, 1618, 1621, 1620, -1, + 1618, 1619, 1630, -1, 1618, 1630, 1626, -1, + 1618, 1623, 1622, -1, 1618, 1622, 1621, -1, + 1618, 1624, 1623, -1, 1618, 1626, 1624, -1, + 1625, 1627, 1626, -1, 1625, 1628, 1627, -1, + 1625, 1630, 1629, -1, 1625, 1626, 1630, -1, + 1625, 1631, 1628, -1, 1625, 1629, 1632, -1, + 1625, 1632, 1631, -1, 1633, 1635, 1634, -1, + 1633, 1634, 1636, -1, 1633, 1637, 1635, -1, + 1633, 1636, 1637, -1, 1644, 1638, 1639, -1, + 1644, 1642, 1638, -1, 1644, 1639, 1640, -1, + 1644, 1640, 1645, -1, 1641, 1643, 1642, -1, + 1641, 1642, 1644, -1, 1641, 1644, 1645, -1, + 1641, 1646, 1643, -1, 1641, 1645, 1646, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T4_Chest.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T4_Chest.wrl new file mode 100644 index 0000000..0547bbf --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T4_Chest.wrl @@ -0,0 +1,1190 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_T4_Chest_____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -72.9375 92.5 -182.939, + -72.9375 53.099998 -182.939, + -72.9375 -92.650002 -182.939, + -72.9375 5.8687522e-009 -182.939, + 47.380699 -104.775 0.79991102, + 71.1875 -95.25 -86.919197, + 71.1875 -95.25 -147.72099, + -20.637501 95.25 -183.104, + -61.912498 95.25 -183.104, + -73.037498 -91.450798 -129.61099, + -73.037498 -92.179398 -128.79601, + -73.037498 -88.727699 -128.99001, + -73.037498 -90.178902 -129.901, + -73.037498 -88.535797 -128.591, + -73.037498 -88.437401 -128.16, + -73.037498 -88.474503 -128.37801, + -73.037498 -88.620598 -128.79601, + -73.037498 -89.520103 -128.44701, + -73.037498 -89.003502 -126.542, + -73.037498 -90.400002 -125.964, + -73.037498 -90.178902 -125.976, + -73.037498 -90.621101 -125.976, + -72.9375 -92.5 1.12421, + -72.9375 92.5 1.12421, + -73.037498 -91.052299 -126.075, + -73.037498 -90.8395 -126.013, + -73.037498 -91.256897 -126.159, + 73.037498 -89.753601 -177.155, + 70.8451 -95.25 -56.9711, + 71.1875 -95.25 -69.685898, + 58.6105 93.5 24.434299, + -7.5685601 -107.775 -42.6651, + 45.447399 -104.775 -13.4208, + 43.856499 -104.775 -17.9498, + 43.476501 -104.775 -18.851601, + -5.4644799 -107.775 -30.9219, + -7.4660602 -107.775 -42.273499, + 46.571999 -104.775 -8.7541504, + 47.218601 -104.775 -3.9976299, + -8.9042902 107.775 -44.1143, + -29.606199 107.775 -34.534901, + -12.8153 107.775 -43.645901, + -27.7391 107.775 -36.0518, + -25.7945 107.775 -37.4678, + -73.037498 -91.052299 -129.80299, + -73.037498 -91.796501 -129.33501, + -73.037498 -91.631401 -129.483, + -73.037498 -92.072304 -128.99001, + -73.037498 -92.264198 -128.591, + -73.037498 -91.3899 -128.168, + -73.037498 -91.197197 -128.569, + -73.037498 -91.631401 -126.395, + -73.037498 -91.450798 -126.267, + -73.037498 -91.796501 -126.542, + -73.037498 -92.072304 -126.888, + -73.037498 -91.944099 -126.707, + -73.037498 -92.179398 -127.082, + -61.912498 -92.610001 -183.26401, + -73.037498 -89.960503 -129.864, + -73.037498 -89.543098 -129.718, + -73.037498 -89.003502 -129.33501, + -73.037498 -89.168602 -129.483, + -73.037498 -89.349197 -129.61099, + -73.037498 -89.747704 -129.80299, + -73.037498 -88.855904 -129.17, + -72.9375 93.5 -182.939, + -73.037498 -88.437401 -127.718, + -73.037498 -88.425003 -127.939, + -73.037498 -88.535797 -127.287, + -73.037498 -88.474503 -127.499, + -73.037498 -88.727699 -126.888, + -73.037498 -88.620598 -127.082, + -73.037498 -88.855904 -126.707, + -73.037498 -89.349197 -126.267, + -73.037498 -89.168602 -126.395, + -73.037498 -89.747704 -126.075, + -73.037498 -89.543098 -126.159, + -73.037498 -89.960503 -126.013, + -70.997101 95.25 3.4826801, + -72.9375 93.5 0.89420998, + -71.1875 95.25 0.89420998, + -71.481796 93.5 10.7348, + -72.571602 93.5 5.8680601, + -72.574097 92.5 6.0644002, + -72.574097 -92.5 6.0644002, + -69.713501 -92.5 15.5216, + -71.491699 92.5 10.8982, + -71.491699 -92.5 10.8982, + -69.713501 92.5 15.5216, + -69.806801 95.25 10.2282, + -64.1782 93.5 23.6698, + 73.037498 91.7155 -179.412, + 73.037498 91.872101 -179.255, + 73.037498 92.0103 -179.082, + 73.037498 -90.731598 -179.886, + 73.037498 -90.511497 -179.911, + 73.037498 -92.371902 -128.049, + 73.037498 -92.371902 -178.049, + 71.068199 92.5 -34.528702, + 73.037498 92.224403 -178.69501, + 73.037498 92.128197 -178.895, + 73.037498 92.347 -178.27, + 46.841 104.775 -7.1762199, + -5.4644799 107.775 -30.9219, + -5.4572401 -107.775 -30.1012, + 47.056702 -104.775 5.5892301, + 43.73 -102.775 25.909599, + 38.0639 -104.775 28.2257, + 44.303699 -102.775 24.9158, + 68.700203 93.5 -17.336201, + 63.7076 -95.25 -0.496609, + -8.2300596 107.775 -43.670898, + -8.5490799 107.775 -43.920101, + -7.9556899 107.775 -43.373199, + -9.6849899 107.775 -44.3186, + 71.1875 95.25 -182.939, + -10.0898 107.775 -44.323399, + -9.2862997 107.775 -44.248299, + -10.49 107.775 -44.262402, + -15.1047 107.775 -42.907398, + -5.4267802 107.775 -30.5119, + -13.8359 107.775 -40.5084, + -13.0406 107.775 -40.438801, + -73.037498 -90.621101 -129.901, + -73.037498 -91.256897 -129.718, + -73.037498 -90.400002 -129.914, + -73.037498 -90.8395 -129.864, + -73.037498 -92.375 -127.939, + -73.037498 -92.3255 -127.499, + -73.037498 -92.264198 -127.287, + -73.037498 -91.944099 -129.17, + -73.037498 -92.3255 -128.37801, + -73.037498 -92.362602 -127.718, + -73.037498 -92.362602 -128.16, + -8.5490799 -107.775 -43.920101, + -7.9556899 -107.775 -43.373199, + -13.0406 -107.775 -40.438801, + -7.7332201 -107.775 -43.034901, + -5.4267802 -107.775 -30.5119, + -10.49 -107.775 -44.262402, + -15.1047 -107.775 -42.907398, + -12.8153 -107.775 -43.645901, + -20.2302 -107.775 -27.656601, + -10.8919 -107.775 -39.436901, + -71.1875 -95.25 -114.221, + 20.637501 -95.089996 -183.26401, + -61.912498 -95.089996 -183.26401, + 61.912498 -92.610001 -183.26401, + 72.9375 92.5 -182.939, + 72.9375 -92.650002 -182.939, + -20.637501 -92.610001 -183.26401, + -71.1875 -95.25 -77.465797, + -72.9375 -93.5 -182.939, + -67.278 92.5 19.8351, + -64.237503 92.5 23.745701, + -70.840401 95.25 5.6119699, + -47.326698 104.775 2.3996999, + -45.8368 95.25 41.376499, + -62.8792 95.25 22.4972, + -66.5075 95.25 17.4793, + -65.782799 95.25 18.7626, + -67.239502 93.5 19.7325, + -69.691597 93.5 15.3897, + -68.108704 95.25 14.6434, + 73.037498 90.730103 -179.886, + 73.037498 90.510002 -179.911, + 73.037498 91.155098 -179.76401, + 73.037498 90.288498 -179.911, + 73.037498 91.542198 -179.55, + 73.037498 90.945999 -179.83701, + 73.037498 91.354698 -179.668, + 73.037498 -91.306396 -127.48, + 73.037498 -90.730103 -175.992, + 73.037498 -91.156502 -179.763, + 73.037498 -90.947502 -179.836, + 73.037498 -91.543503 -179.549, + 73.037498 -91.356003 -179.66701, + 73.037498 -92.371803 -177.827, + 73.037498 -91.356003 -79.667, + 72.465797 -93.5 -52.168301, + 69.0597 -95.25 -33.0257, + 69.312103 -95.25 -34.889702, + 70.7183 -95.25 -52.262501, + 66.973 -95.25 -17.617701, + 68.718002 -92.5 -17.129101, + 71.068199 -92.5 -34.528702, + 68.718002 92.5 -17.129101, + 65.432404 -92.5 0.118224, + 68.700203 -93.5 -17.336201, + 71.052002 -93.5 -34.701599, + -7.5685601 107.775 -42.6651, + 44.437698 104.775 -16.458401, + 45.874802 104.775 -11.8782, + -7.4660602 107.775 -42.273499, + -7.7332201 107.775 -43.034901, + 43.476501 104.775 -18.851601, + 71.1875 95.25 -77.465797, + 47.326698 104.775 -2.4005799, + 71.1875 95.25 -147.72099, + 72.9375 93.5 -182.939, + 70.8451 95.25 -56.9711, + 70.7183 95.25 -52.262501, + 47.326698 104.775 2.3996999, + 71.1875 95.25 -69.685898, + 72.465797 93.5 -52.168301, + 69.0597 95.25 -33.0257, + 71.052002 93.5 -34.701599, + 66.973 95.25 -17.617701, + 69.312103 95.25 -34.889702, + 44.968201 -104.775 14.9473, + 46.249699 -104.775 10.3212, + 43.476501 -104.775 18.8508, + -5.5550098 -107.775 -29.7012, + 44.046902 -102.775 25.430099, + 61.220901 92.5 17.1632, + 61.212601 93.5 16.8894, + 65.432404 92.5 0.11822401, + 65.417198 93.5 -0.122605, + 59.034698 92.5 23.681999, + 61.212601 -93.5 16.8894, + 65.417198 -93.5 -0.122605, + 61.220901 -92.5 17.1632, + 59.034698 -92.5 23.681999, + 59.5257 -95.25 16.423901, + 62.724201 -95.25 3.4826801, + -17.351801 107.775 -42.048901, + -5.4572401 107.775 -30.1012, + 46.841 104.775 7.1753402, + 62.724201 95.25 3.4826801, + 63.7076 95.25 -0.496609, + -34.095901 95.25 51.482899, + -27.705099 107.775 -27.002701, + -9.3254604 107.775 -36.723701, + -13.0406 107.775 -31.417999, + -30.866899 104.775 35.9552, + -40.284599 95.25 46.799301, + -9.2862997 -107.775 -44.248299, + -8.2300596 -107.775 -43.670898, + -8.9042902 -107.775 -44.1143, + -20.674299 -107.775 -20.354, + -21.7213 -107.775 -19.719801, + -28.707001 -107.775 -29.1513, + -22.6301 -107.775 -25.6429, + -28.707001 -107.775 -30.742001, + -20.637501 -95.089996 -183.26401, + -61.912498 -95.25 -183.104, + 61.912498 92.610001 -183.26401, + 61.912498 95.089996 -183.26401, + 61.912498 95.25 -183.104, + -31.390499 -107.775 -32.921501, + -33.339901 -107.775 -30.8999, + -33.086899 -107.775 -31.216, + -17.351801 -107.775 -42.048901, + -23.7777 -107.775 -38.778999, + -25.7945 -107.775 -37.4678, + -21.694401 -107.775 -39.9818, + -19.550501 -107.775 -41.0728, + -27.7391 -107.775 -36.0518, + -29.606199 -107.775 -34.534901, + -72.9375 -93.5 0.89420998, + -64.237503 82.25 23.745701, + -64.237503 -5.94759e-009 23.745701, + -67.278 -92.5 19.8351, + -67.239502 -93.5 19.7325, + -65.782799 -95.25 18.7626, + 44.128502 102.775 25.282801, + 53.564499 95.25 30.722601, + 20.1476 -104.775 42.890701, + -37.4729 104.775 29.005699, + -38.0639 104.775 28.2257, + -34.3461 104.775 32.647999, + -32.876499 107.775 -27.602699, + -44.437698 104.775 16.4575, + -43.476501 104.775 18.8508, + -33.402401 107.775 -28.214899, + -33.164398 107.775 -27.8873, + 73.037498 -90.290001 -79.910797, + 72.9375 -92.5 -69.5811, + 72.475998 92.5 -52.029701, + 72.475998 -92.5 -52.029701, + 73.037498 92.2976 -178.48599, + 73.037498 92.371803 -178.05, + 73.037498 92.371902 -177.82899, + 73.037498 92.371902 -77.828903, + -7.2895498 -107.775 -28.081699, + -6.9008899 -107.775 -28.2178, + 24.383499 -104.775 40.632301, + -21.338699 -107.775 -19.872101, + 49.287601 -95.25 37.198898, + 46.332699 -95.25 40.6409, + -21.694401 107.775 -39.9818, + -23.7777 107.775 -38.778999, + -19.550501 107.775 -41.0728, + -5.7174401 107.775 -29.3228, + -5.9400501 107.775 -28.976299, + 38.0639 104.775 28.2257, + 44.437698 104.775 16.4575, + 43.476501 104.775 18.8508, + -5.5550098 107.775 -29.7012, + 45.874802 104.775 11.8774, + 59.5257 95.25 16.423901, + 56.9953 95.25 23.7609, + 44.367001 102.775 24.7598, + -20.209101 95.25 58.348999, + -33.086899 107.775 -31.216, + -47.326698 104.775 -2.4005799, + -31.390499 107.775 -32.921501, + -33.751598 107.775 -29.7687, + 14.1861 104.775 45.213799, + -23.7103 107.775 -19.9559, + -24.0466 107.775 -20.1936, + -27.070999 104.775 38.893501, + -22.9972 104.775 41.432701, + -18.6875 104.775 43.5467, + -71.1875 -95.25 0.89420998, + -22.535101 -107.775 -19.613001, + -22.1238 -107.775 -19.632601, + -62.8792 -95.25 22.4972, + -45.8368 -95.25 41.376499, + 71.1875 -95.25 -182.939, + -9.6849899 -107.775 -44.3186, + -20.637501 95.089996 -183.26401, + -20.637501 92.610001 -183.26401, + -61.912498 95.089996 -183.26401, + 20.637501 95.089996 -183.26401, + -71.481796 -93.5 10.7348, + -69.691597 -93.5 15.3897, + -59.5509 71.173599 28.9375, + 52.612801 92.5 35.818802, + 48.452999 92.5 41.2934, + 55.0826 93.5 31.5933, + 56.153999 92.5 29.9251, + -33.7047 107.775 -28.9631, + -33.584099 107.775 -28.576599, + -45.874802 104.775 11.8774, + -33.761002 107.775 -29.364, + -46.841 104.775 7.1753402, + 73.037498 -92.224998 -178.694, + 73.037498 -92.347198 -178.269, + 73.037498 -92.128899 -178.894, + 73.037498 -92.297997 -178.485, + 73.037498 -90.945999 -76.040802, + 73.037498 -91.155098 -76.113899, + 73.037498 -92.0112 -79.0811, + 73.037498 -91.018204 -77.132599, + 73.037498 -90.730103 -75.9916, + 73.037498 -91.542198 -76.327698, + 73.037498 -91.354698 -76.2099, + 73.037498 -91.7155 -76.465698, + 73.037498 -92.371803 -77.827301, + 73.037498 -92.2976 -77.391403, + 73.037498 -92.371902 -78.048798, + 73.037498 -92.347 -77.6073, + 73.037498 -92.128197 -76.982803, + 73.037498 -92.0103 -76.795303, + 72.9375 -93.5 -69.685898, + 73.037498 -92.224403 -77.182297, + 73.037498 -91.872101 -76.6222, + 73.037498 -88.671097 -76.9842, + 73.037498 -90.288498 -75.967003, + 73.037498 90.290001 -75.966904, + 73.037498 -90.510002 -75.966904, + 73.037498 90.731598 -75.991898, + 72.9375 92.5 -69.5811, + 73.037498 92.2976 -78.486397, + 73.037498 92.371803 -128.05, + 73.037498 89.445297 -76.2099, + 73.037498 92.224998 -177.18401, + 73.037498 91.873199 -76.623398, + 73.037498 91.306396 -178.39799, + 73.037498 92.297997 -77.392899, + 73.037498 92.347198 -77.608803, + 73.037498 92.128899 -76.9842, + 73.037498 92.224998 -77.1838, + 73.037498 92.0112 -76.7966, + -6.2167702 -107.775 -28.671301, + -5.7174401 -107.775 -29.3228, + -5.9400501 -107.775 -28.976299, + -6.54 -107.775 -28.416201, + 35.429199 -104.775 31.469299, + 39.568401 88.900002 49.664299, + 39.568401 93.5 49.664299, + 32.063702 -104.775 34.8922, + 45.485699 88.900002 44.308701, + 48.452999 -92.5 41.2934, + 44.232201 -95.25 43.087601, + 55.0826 -93.5 31.5933, + 50.522499 -95.25 35.328999, + 53.564499 -95.25 30.722601, + 50.684502 -93.5 38.253101, + 56.9953 -95.25 23.7609, + 58.6105 -93.5 24.434299, + 56.153999 -92.5 29.9251, + 52.612801 -92.5 35.818802, + 6.3836398 -104.775 46.955101, + 25.962 93.5 57.949699, + 18.4879 -88.900002 60.7486, + 16.597 95.25 59.4016, + 9.5390301 104.775 46.417, + 17.978399 95.25 59.074402, + 18.4879 93.5 60.7486, + -27.3687 95.25 55.3531, + -20.7819 93.5 60.002602, + -20.7819 88.900002 60.002602, + -33.5382 107.775 -30.547001, + -33.339901 107.775 -30.8999, + -71.1875 95.25 -182.939, + -33.676701 107.775 -30.166599, + 18.6875 104.775 43.5467, + -22.944099 107.775 -19.6616, + -22.1238 107.775 -19.632601, + -22.535101 107.775 -19.613001, + -23.339399 107.775 -19.776899, + -9.5390301 104.775 46.417, + -14.1861 104.775 45.213799, + -33.676701 -107.775 -30.166599, + -33.5382 -107.775 -30.547001, + -47.056702 -104.775 -5.5901098, + -47.380699 -104.775 -0.80079001, + -71.1875 -95.25 -182.939, + -33.751598 -107.775 -29.7687, + -33.761002 -107.775 -29.364, + -22.944099 -107.775 -19.6616, + -33.164398 -107.775 -27.8873, + -36.471802 -104.775 30.254801, + -33.402401 -107.775 -28.214899, + -38.0639 -104.775 28.2257, + 20.637501 -95.25 -183.104, + -20.637501 -95.25 -183.104, + 61.912498 -95.089996 -183.26401, + 61.912498 -95.25 -183.104, + -10.0898 -107.775 -44.323399, + -70.840401 -95.25 5.6119699, + -70.997101 -95.25 3.4826801, + -72.571602 -93.5 5.8680601, + -47.218601 -104.775 3.9967501, + -51.706402 6 37.627499, + -51.706402 71 37.627499, + -59.5509 5.8263502 28.9375, + -46.855 92.650002 42.858101, + -41.426201 93.5 48.125599, + -47.135799 93.5 42.549099, + -48.355999 -92.5 41.339001, + -47.135799 -93.5 42.549099, + -46.855 -92.650002 42.858101, + -46.855 -88.900002 42.858101, + -59.5509 -71.173599 28.9375, + -64.237503 -92.5 23.745701, + -64.1782 -93.5 23.6698, + -46.855 88.900002 42.858101, + -48.355999 92.5 41.339001, + -51.706402 -71 37.627499, + 50.4897 95.25 35.3787, + 37.4729 104.775 29.005699, + 43.828701 102.775 25.773199, + 44.232201 95.25 43.087601, + 38.478001 95.25 48.295601, + 45.485699 93.5 44.308701, + 30.781099 95.25 53.4426, + 25.2465 95.25 56.352699, + 32.115898 95.25 52.7407, + 73.037498 -91.873199 -179.254, + 73.037498 -91.716599 -179.411, + 72.9375 -93.5 -182.939, + 73.037498 -92.0112 -179.08099, + 73.037498 90.511497 -75.967003, + 73.037498 90.947502 -76.041298, + 73.037498 91.156502 -76.114502, + 41.310299 -88.900002 48.087799, + 39.568401 -93.5 49.664299, + 40.197498 88.900002 49.095001, + 45.485699 -93.5 44.308701, + -13.0911 -88.900002 62.135502, + -40.197498 -88.900002 49.0555, + -40.197498 88.900002 49.0555, + -13.0911 88.900002 62.135502, + 17.978399 -95.25 59.074402, + 10.4262 -95.25 60.862999, + 15.7051 -104.775 44.7089, + 11.1013 -104.775 46.068401, + -0.168318 -102.775 50.857601, + 2.70927 -95.25 61.690102, + 0.40630499 -102.775 50.843201, + -5.4126401 -104.775 47.0769, + 5.4126401 -104.775 47.0769, + 5.4126401 104.775 47.0769, + -30.733999 88.900002 55.431999, + -35.062199 -88.900002 52.941898, + -35.062199 88.900002 52.941898, + -35.062199 93.5 52.941898, + 22.9972 104.775 41.432701, + 27.070999 104.775 38.893501, + 30.866899 104.775 35.9552, + -21.7213 107.775 -19.719801, + -21.338699 107.775 -19.872101, + -33.7047 -107.775 -28.9631, + -46.571999 -104.775 8.7532597, + -12.7303 -95.25 60.4231, + -12.6509 -104.775 45.667198, + -20.209101 -95.25 58.348999, + -7.9658799 -104.775 46.7127, + -13.0911 -93.5 62.135502, + -5.0504198 -95.25 61.542702, + -0.74048698 -102.775 50.802601, + -35.062199 -93.5 52.941898, + -41.426201 -93.5 48.125599, + -21.584801 -104.775 42.185699, + -27.3687 -95.25 55.3531, + -17.2061 -104.775 44.153, + -23.7103 -107.775 -19.9559, + -23.339399 -107.775 -19.776899, + -29.634899 -104.775 36.9772, + -25.741899 -104.775 39.785599, + -24.0466 -107.775 -20.1936, + -32.876499 -107.775 -27.602699, + -33.2239 -104.775 33.789398, + -40.284599 -95.25 46.799301, + -37.734798 -95.25 48.729, + -34.095901 -95.25 51.482899, + 46.332699 95.25 40.6409, + 44.679501 95.25 42.566601, + 50.684502 93.5 38.253101, + 49.287601 95.25 37.198898, + 34.3461 104.775 32.647999, + 73.037498 91.543503 -76.328598, + 73.037498 91.716599 -76.466698, + 72.9375 93.5 -69.685898, + 73.037498 91.356003 -76.210701, + 33.0261 93.5 54.235401, + 33.0261 -88.900002 54.235401, + 34.2906 -88.900002 53.351898, + 33.0261 88.900002 54.235401, + 33.368 -95.25 51.865898, + 32.115898 -95.25 52.7407, + 38.478001 -95.25 48.295601, + 28.369101 -104.775 37.957001, + -5.1935501 -88.900002 63.2868, + -5.1935501 -93.5 63.2868, + 2.7860501 -88.900002 63.4384, + 10.7216 -93.5 62.587898, + 2.7860501 -93.5 63.4384, + 0.57375503 102.775 50.825901, + 10.4262 95.25 60.862999, + -0.57375503 102.775 50.825901, + -7.0947199e-009 102.775 50.8606, + -5.4126401 104.775 47.0769, + -12.7303 95.25 60.4231, + -13.0911 93.5 62.135502, + -4.2434101 88.900002 63.304901, + -5.1935501 88.900002 63.2868, + -28.1443 -88.900002 56.921799, + -29.8561 -88.900002 55.937099, + -28.1443 -93.5 56.921799, + -28.1443 93.5 56.921799, + -20.7819 -93.5 60.002602, + -6.9008899 107.775 -28.2178, + -6.54 107.775 -28.416201, + -6.2167702 107.775 -28.671301, + -20.9865 107.775 -20.085501, + -43.856499 -104.775 17.9489, + -33.584099 -107.775 -28.576599, + -43.476501 -104.775 18.8508, + -45.447399 -104.775 13.42, + -69.806801 -95.25 10.2282, + -68.108704 -95.25 14.6434, + 30.733999 -88.900002 55.440601, + 33.0261 -93.5 54.235401, + 18.4879 -93.5 60.7486, + 25.2465 -95.25 56.352699, + 2.7860501 93.5 63.4384, + 2.70927 95.25 61.690102, + -5.0504198 95.25 61.542702, + -5.1935501 93.5 63.2868, + 10.7216 93.5 62.587898, + 10.7216 88.900002 62.587898, + 2.7860501 88.900002 63.4384, + -2.2434101 88.900002 63.342899, + 2.2434101 -88.900002 63.428101, + 25.962 -88.900002 57.949699, + 29.8561 88.900002 55.902199, + 25.962 88.900002 57.949699, + 25.962 -93.5 57.949699, + 23.2994 -88.900002 58.9468 ] + + } + coordIndex [ 323, 65, 406, -1, 2, 152, 125, -1, + 80, 406, 65, -1, 84, 22, 259, -1, + 84, 23, 22, -1, 137, 319, 34, -1, + 429, 463, 319, -1, 25, 259, 22, -1, + 276, 172, 369, -1, 202, 226, 227, -1, + 38, 37, 319, -1, 32, 319, 37, -1, + 326, 85, 87, -1, 326, 262, 85, -1, + 8, 406, 116, -1, 8, 116, 248, -1, + 8, 323, 406, -1, 194, 195, 115, -1, + 0, 65, 323, -1, 0, 323, 1, -1, + 0, 125, 65, -1, 0, 2, 125, -1, + 0, 1, 2, -1, 3, 1, 323, -1, + 3, 2, 1, -1, 146, 152, 2, -1, + 146, 3, 323, -1, 146, 2, 3, -1, + 247, 248, 115, -1, 247, 115, 199, -1, + 247, 199, 148, -1, 149, 148, 463, -1, + 149, 463, 429, -1, 59, 62, 65, -1, + 11, 16, 65, -1, 17, 50, 52, -1, + 17, 58, 50, -1, 79, 80, 65, -1, + 79, 65, 67, -1, 83, 23, 84, -1, + 83, 79, 23, -1, 83, 82, 79, -1, + 89, 82, 81, -1, 21, 25, 22, -1, + 26, 52, 259, -1, 27, 369, 172, -1, + 355, 5, 463, -1, 355, 29, 5, -1, + 204, 98, 278, -1, 301, 266, 330, -1, + 301, 215, 300, -1, 33, 34, 319, -1, + 33, 319, 32, -1, 36, 32, 37, -1, + 36, 138, 137, -1, 325, 326, 87, -1, + 6, 319, 463, -1, 6, 463, 5, -1, + 4, 5, 29, -1, 4, 6, 5, -1, + 4, 29, 28, -1, 4, 105, 138, -1, + 4, 138, 38, -1, 4, 38, 319, -1, + 4, 319, 6, -1, 4, 182, 105, -1, + 4, 28, 182, -1, 181, 105, 182, -1, + 7, 248, 323, -1, 7, 323, 8, -1, + 7, 8, 248, -1, 120, 194, 232, -1, + 120, 226, 202, -1, 305, 406, 80, -1, + 305, 80, 156, -1, 42, 43, 406, -1, + 9, 152, 46, -1, 124, 58, 125, -1, + 124, 9, 46, -1, 124, 44, 152, -1, + 124, 152, 9, -1, 10, 152, 48, -1, + 10, 47, 152, -1, 10, 48, 47, -1, + 130, 152, 47, -1, 130, 124, 46, -1, + 130, 129, 55, -1, 130, 50, 58, -1, + 130, 58, 124, -1, 130, 55, 52, -1, + 53, 52, 55, -1, 53, 55, 259, -1, + 56, 129, 259, -1, 128, 259, 129, -1, + 128, 132, 259, -1, 561, 264, 564, -1, + 419, 152, 146, -1, 61, 65, 62, -1, + 64, 16, 11, -1, 64, 11, 65, -1, + 12, 65, 125, -1, 12, 58, 65, -1, + 12, 125, 58, -1, 13, 65, 16, -1, + 13, 15, 65, -1, 13, 16, 15, -1, + 14, 15, 16, -1, 14, 16, 64, -1, + 14, 67, 65, -1, 14, 65, 15, -1, + 14, 64, 58, -1, 14, 58, 17, -1, + 14, 52, 67, -1, 14, 17, 52, -1, + 72, 18, 79, -1, 72, 69, 67, -1, + 74, 79, 18, -1, 74, 18, 72, -1, + 77, 20, 23, -1, 77, 23, 79, -1, + 77, 25, 20, -1, 77, 26, 25, -1, + 77, 52, 26, -1, 77, 74, 72, -1, + 77, 67, 52, -1, 77, 72, 67, -1, + 155, 82, 89, -1, 162, 89, 81, -1, + 162, 163, 89, -1, 19, 20, 25, -1, + 19, 25, 21, -1, 19, 21, 22, -1, + 19, 22, 23, -1, 19, 23, 20, -1, + 24, 259, 25, -1, 24, 26, 259, -1, + 24, 25, 26, -1, 170, 199, 168, -1, + 174, 27, 172, -1, 174, 369, 27, -1, + 167, 174, 95, -1, 167, 148, 199, -1, + 167, 199, 165, -1, 167, 463, 148, -1, + 167, 95, 463, -1, 167, 168, 369, -1, + 167, 369, 174, -1, 175, 463, 176, -1, + 351, 355, 463, -1, 351, 97, 177, -1, + 179, 28, 29, -1, 179, 29, 355, -1, + 179, 182, 28, -1, 361, 355, 345, -1, + 198, 199, 115, -1, 526, 204, 278, -1, + 526, 283, 199, -1, 282, 281, 199, -1, + 282, 199, 283, -1, 280, 369, 168, -1, + 192, 102, 115, -1, 197, 115, 102, -1, + 197, 198, 115, -1, 197, 120, 202, -1, + 30, 301, 330, -1, 30, 215, 301, -1, + 30, 218, 215, -1, 30, 330, 331, -1, + 30, 331, 218, -1, 206, 98, 204, -1, + 206, 186, 98, -1, 201, 206, 204, -1, + 229, 217, 207, -1, 229, 207, 227, -1, + 228, 300, 215, -1, 228, 215, 217, -1, + 228, 217, 229, -1, 31, 36, 137, -1, + 31, 32, 36, -1, 31, 33, 32, -1, + 31, 137, 34, -1, 31, 34, 33, -1, + 35, 36, 37, -1, 35, 138, 36, -1, + 35, 37, 38, -1, 35, 38, 138, -1, + 211, 213, 107, -1, 106, 107, 213, -1, + 434, 87, 84, -1, 434, 325, 87, -1, + 434, 84, 259, -1, 180, 183, 105, -1, + 180, 105, 181, -1, 39, 112, 115, -1, + 113, 194, 115, -1, 117, 112, 39, -1, + 117, 39, 115, -1, 103, 197, 102, -1, + 103, 120, 197, -1, 40, 406, 306, -1, + 40, 42, 406, -1, 40, 306, 42, -1, + 118, 116, 406, -1, 118, 406, 41, -1, + 118, 117, 116, -1, 119, 41, 406, -1, + 119, 118, 41, -1, 291, 42, 306, -1, + 291, 194, 117, -1, 291, 43, 42, -1, + 291, 406, 43, -1, 298, 226, 120, -1, + 122, 232, 194, -1, 126, 44, 124, -1, + 126, 152, 44, -1, 45, 46, 152, -1, + 45, 152, 130, -1, 45, 130, 46, -1, + 131, 47, 48, -1, 131, 130, 47, -1, + 131, 48, 152, -1, 131, 152, 133, -1, + 49, 52, 50, -1, 49, 130, 52, -1, + 49, 50, 130, -1, 51, 259, 52, -1, + 51, 52, 53, -1, 51, 53, 259, -1, + 54, 55, 129, -1, 54, 129, 56, -1, + 54, 259, 55, -1, 54, 56, 259, -1, + 237, 134, 319, -1, 136, 143, 243, -1, + 136, 243, 252, -1, 57, 146, 323, -1, + 57, 323, 150, -1, 57, 150, 146, -1, + 244, 146, 150, -1, 246, 247, 148, -1, + 63, 58, 64, -1, 63, 62, 59, -1, + 63, 59, 65, -1, 63, 65, 58, -1, + 60, 61, 62, -1, 60, 62, 63, -1, + 60, 63, 64, -1, 60, 65, 61, -1, + 60, 64, 65, -1, 66, 79, 67, -1, + 66, 67, 69, -1, 66, 69, 79, -1, + 68, 71, 79, -1, 68, 79, 69, -1, + 68, 72, 71, -1, 68, 69, 72, -1, + 70, 79, 71, -1, 70, 71, 72, -1, + 70, 72, 79, -1, 73, 76, 79, -1, + 73, 79, 74, -1, 73, 77, 76, -1, + 73, 74, 77, -1, 75, 79, 76, -1, + 75, 76, 77, -1, 75, 77, 79, -1, + 78, 82, 155, -1, 78, 80, 79, -1, + 78, 79, 82, -1, 78, 156, 80, -1, + 78, 155, 156, -1, 86, 162, 81, -1, + 86, 81, 82, -1, 86, 82, 83, -1, + 86, 84, 87, -1, 86, 83, 84, -1, + 88, 85, 262, -1, 88, 162, 86, -1, + 88, 87, 85, -1, 88, 86, 87, -1, + 153, 154, 161, -1, 153, 88, 262, -1, + 153, 161, 162, -1, 153, 162, 88, -1, + 447, 261, 262, -1, 265, 266, 301, -1, + 334, 155, 89, -1, 272, 89, 163, -1, + 272, 163, 273, -1, 272, 334, 89, -1, + 90, 441, 158, -1, 90, 158, 161, -1, + 90, 161, 154, -1, 90, 450, 441, -1, + 90, 154, 450, -1, 160, 161, 158, -1, + 160, 269, 273, -1, 93, 199, 100, -1, + 93, 92, 199, -1, 91, 168, 199, -1, + 91, 199, 92, -1, 91, 92, 93, -1, + 91, 93, 100, -1, 91, 100, 280, -1, + 91, 280, 168, -1, 173, 176, 463, -1, + 173, 463, 174, -1, 94, 463, 95, -1, + 94, 174, 463, -1, 94, 95, 174, -1, + 338, 174, 172, -1, 338, 177, 97, -1, + 338, 97, 463, -1, 96, 463, 97, -1, + 96, 351, 463, -1, 96, 97, 351, -1, + 185, 98, 186, -1, 279, 179, 355, -1, + 279, 185, 179, -1, 279, 278, 98, -1, + 279, 98, 185, -1, 99, 100, 199, -1, + 99, 280, 100, -1, 99, 199, 280, -1, + 101, 199, 281, -1, 101, 280, 199, -1, + 101, 281, 280, -1, 191, 115, 195, -1, + 191, 192, 115, -1, 193, 102, 192, -1, + 193, 103, 102, -1, 193, 194, 120, -1, + 193, 120, 103, -1, 109, 207, 217, -1, + 109, 206, 207, -1, 109, 186, 206, -1, + 203, 204, 526, -1, 208, 206, 201, -1, + 208, 202, 227, -1, 208, 201, 202, -1, + 104, 138, 105, -1, 104, 212, 138, -1, + 393, 392, 331, -1, 210, 224, 223, -1, + 210, 110, 224, -1, 210, 104, 105, -1, + 210, 212, 104, -1, 210, 105, 183, -1, + 210, 183, 110, -1, 108, 213, 211, -1, + 108, 388, 213, -1, 376, 212, 211, -1, + 376, 107, 377, -1, 376, 211, 107, -1, + 376, 138, 212, -1, 376, 284, 138, -1, + 379, 377, 107, -1, 379, 385, 382, -1, + 288, 106, 213, -1, 288, 107, 106, -1, + 288, 379, 107, -1, 390, 388, 108, -1, + 390, 108, 211, -1, 216, 187, 186, -1, + 216, 186, 109, -1, 216, 109, 217, -1, + 216, 221, 187, -1, 220, 188, 187, -1, + 220, 110, 183, -1, 220, 183, 188, -1, + 220, 187, 221, -1, 220, 224, 110, -1, + 111, 117, 194, -1, 111, 112, 117, -1, + 111, 194, 113, -1, 111, 115, 112, -1, + 111, 113, 115, -1, 114, 117, 115, -1, + 114, 116, 117, -1, 114, 115, 248, -1, + 114, 248, 116, -1, 225, 291, 117, -1, + 225, 117, 118, -1, 225, 118, 119, -1, + 225, 119, 406, -1, 557, 298, 120, -1, + 557, 232, 233, -1, 557, 120, 232, -1, + 297, 295, 265, -1, 485, 542, 398, -1, + 335, 122, 306, -1, 335, 232, 122, -1, + 335, 305, 156, -1, 121, 291, 306, -1, + 121, 306, 122, -1, 121, 194, 291, -1, + 121, 122, 194, -1, 123, 124, 125, -1, + 123, 126, 124, -1, 123, 125, 152, -1, + 123, 152, 126, -1, 127, 128, 129, -1, + 127, 129, 130, -1, 127, 130, 131, -1, + 127, 132, 128, -1, 127, 131, 133, -1, + 127, 133, 152, -1, 127, 152, 259, -1, + 127, 259, 132, -1, 238, 134, 237, -1, + 238, 319, 134, -1, 135, 252, 320, -1, + 135, 320, 237, -1, 135, 136, 252, -1, + 135, 319, 137, -1, 135, 237, 319, -1, + 135, 143, 136, -1, 135, 284, 143, -1, + 135, 137, 138, -1, 135, 138, 284, -1, + 139, 431, 320, -1, 139, 320, 141, -1, + 139, 419, 431, -1, 139, 141, 419, -1, + 140, 320, 252, -1, 140, 141, 320, -1, + 140, 252, 419, -1, 140, 419, 141, -1, + 316, 240, 479, -1, 416, 252, 243, -1, + 416, 243, 425, -1, 416, 419, 250, -1, + 142, 243, 143, -1, 142, 242, 243, -1, + 142, 143, 284, -1, 142, 284, 242, -1, + 513, 239, 316, -1, 513, 284, 239, -1, + 513, 242, 284, -1, 426, 561, 425, -1, + 426, 264, 561, -1, 144, 152, 419, -1, + 144, 151, 152, -1, 144, 419, 418, -1, + 144, 418, 151, -1, 145, 150, 429, -1, + 145, 429, 244, -1, 145, 244, 150, -1, + 245, 419, 146, -1, 245, 146, 244, -1, + 245, 431, 419, -1, 147, 429, 150, -1, + 147, 150, 246, -1, 147, 246, 148, -1, + 147, 148, 149, -1, 147, 149, 429, -1, + 322, 150, 323, -1, 322, 246, 150, -1, + 314, 151, 418, -1, 314, 259, 152, -1, + 314, 152, 151, -1, 327, 450, 154, -1, + 260, 154, 153, -1, 260, 327, 154, -1, + 260, 262, 261, -1, 260, 153, 262, -1, + 395, 582, 580, -1, 268, 158, 270, -1, + 268, 160, 158, -1, 268, 269, 160, -1, + 274, 273, 269, -1, 336, 156, 155, -1, + 336, 155, 334, -1, 336, 335, 156, -1, + 157, 158, 441, -1, 157, 441, 235, -1, + 157, 270, 158, -1, 157, 235, 270, -1, + 440, 235, 441, -1, 440, 489, 235, -1, + 230, 235, 489, -1, 230, 311, 235, -1, + 230, 312, 311, -1, 159, 161, 160, -1, + 159, 163, 162, -1, 159, 162, 161, -1, + 159, 273, 163, -1, 159, 160, 273, -1, + 164, 167, 165, -1, 164, 169, 167, -1, + 164, 165, 199, -1, 164, 199, 169, -1, + 166, 168, 167, -1, 166, 167, 169, -1, + 166, 170, 168, -1, 166, 199, 170, -1, + 166, 169, 199, -1, 171, 172, 276, -1, + 171, 338, 172, -1, 171, 276, 178, -1, + 171, 178, 338, -1, 462, 173, 174, -1, + 462, 174, 338, -1, 462, 175, 176, -1, + 462, 176, 173, -1, 462, 463, 175, -1, + 343, 351, 177, -1, 343, 177, 338, -1, + 343, 338, 178, -1, 343, 178, 276, -1, + 343, 276, 344, -1, 366, 276, 369, -1, + 189, 179, 185, -1, 189, 180, 181, -1, + 189, 181, 182, -1, 189, 182, 179, -1, + 189, 188, 183, -1, 189, 183, 180, -1, + 184, 185, 186, -1, 184, 186, 187, -1, + 184, 187, 188, -1, 184, 188, 189, -1, + 184, 189, 185, -1, 277, 279, 355, -1, + 277, 355, 361, -1, 277, 361, 360, -1, + 367, 369, 280, -1, 373, 364, 283, -1, + 190, 192, 191, -1, 190, 193, 192, -1, + 190, 194, 193, -1, 190, 195, 194, -1, + 190, 191, 195, -1, 196, 203, 526, -1, + 196, 202, 203, -1, 196, 198, 197, -1, + 196, 199, 198, -1, 196, 526, 199, -1, + 196, 197, 202, -1, 200, 202, 201, -1, + 200, 203, 202, -1, 200, 201, 204, -1, + 200, 204, 203, -1, 205, 207, 206, -1, + 205, 206, 208, -1, 205, 227, 207, -1, + 205, 208, 227, -1, 209, 210, 223, -1, + 209, 223, 390, -1, 209, 390, 211, -1, + 209, 211, 212, -1, 209, 212, 210, -1, + 387, 213, 388, -1, 387, 288, 213, -1, + 289, 385, 379, -1, 289, 379, 288, -1, + 214, 215, 218, -1, 214, 218, 221, -1, + 214, 221, 216, -1, 214, 217, 215, -1, + 214, 216, 217, -1, 222, 221, 218, -1, + 222, 392, 391, -1, 222, 331, 392, -1, + 222, 218, 331, -1, 219, 220, 221, -1, + 219, 222, 391, -1, 219, 221, 222, -1, + 219, 391, 390, -1, 219, 390, 223, -1, + 219, 223, 224, -1, 219, 224, 220, -1, + 478, 267, 568, -1, 478, 479, 240, -1, + 456, 381, 457, -1, 292, 225, 406, -1, + 292, 291, 225, -1, 294, 557, 523, -1, + 299, 227, 226, -1, 299, 226, 298, -1, + 299, 300, 228, -1, 299, 229, 227, -1, + 299, 228, 229, -1, 302, 265, 301, -1, + 302, 297, 265, -1, 414, 546, 413, -1, + 401, 313, 312, -1, 401, 312, 230, -1, + 401, 230, 489, -1, 412, 335, 310, -1, + 412, 557, 233, -1, 412, 313, 414, -1, + 231, 233, 232, -1, 231, 232, 335, -1, + 231, 412, 233, -1, 231, 335, 412, -1, + 234, 271, 270, -1, 234, 270, 235, -1, + 234, 235, 311, -1, 234, 310, 271, -1, + 234, 311, 310, -1, 236, 237, 320, -1, + 236, 238, 237, -1, 236, 320, 319, -1, + 236, 319, 238, -1, 287, 316, 239, -1, + 287, 240, 316, -1, 287, 239, 284, -1, + 287, 284, 285, -1, 287, 286, 267, -1, + 287, 267, 478, -1, 287, 478, 240, -1, + 241, 243, 242, -1, 241, 242, 513, -1, + 241, 425, 243, -1, 241, 513, 425, -1, + 422, 513, 316, -1, 514, 425, 513, -1, + 428, 244, 429, -1, 428, 245, 244, -1, + 428, 431, 245, -1, 324, 247, 246, -1, + 324, 246, 322, -1, 324, 323, 248, -1, + 324, 248, 247, -1, 251, 250, 419, -1, + 249, 416, 250, -1, 249, 258, 416, -1, + 249, 250, 251, -1, 249, 419, 258, -1, + 249, 251, 419, -1, 257, 419, 254, -1, + 257, 258, 419, -1, 256, 419, 252, -1, + 256, 255, 419, -1, 256, 252, 416, -1, + 253, 254, 419, -1, 253, 419, 255, -1, + 253, 255, 256, -1, 253, 257, 254, -1, + 253, 256, 416, -1, 253, 416, 258, -1, + 253, 258, 257, -1, 433, 434, 259, -1, + 433, 259, 314, -1, 445, 444, 505, -1, + 438, 327, 260, -1, 438, 260, 261, -1, + 438, 261, 447, -1, 263, 447, 262, -1, + 263, 448, 447, -1, 263, 262, 326, -1, + 263, 326, 564, -1, 263, 564, 264, -1, + 317, 263, 264, -1, 317, 448, 263, -1, + 317, 264, 426, -1, 318, 448, 317, -1, + 318, 515, 516, -1, 443, 505, 444, -1, + 443, 448, 318, -1, 443, 516, 505, -1, + 443, 318, 516, -1, 454, 265, 295, -1, + 454, 266, 265, -1, 452, 330, 266, -1, + 452, 521, 330, -1, 452, 266, 454, -1, + 329, 521, 457, -1, 329, 383, 384, -1, + 329, 457, 383, -1, 329, 384, 393, -1, + 533, 568, 267, -1, 533, 267, 286, -1, + 533, 286, 535, -1, 528, 381, 456, -1, + 579, 395, 580, -1, 579, 528, 395, -1, + 275, 269, 268, -1, 275, 274, 269, -1, + 275, 268, 270, -1, 275, 270, 271, -1, + 275, 271, 310, -1, 275, 310, 335, -1, + 333, 272, 273, -1, 333, 273, 274, -1, + 333, 334, 272, -1, 333, 275, 335, -1, + 333, 274, 275, -1, 474, 489, 440, -1, + 341, 345, 355, -1, 352, 350, 355, -1, + 356, 355, 350, -1, 356, 350, 351, -1, + 358, 344, 276, -1, 358, 276, 366, -1, + 359, 361, 345, -1, 363, 277, 360, -1, + 363, 526, 278, -1, 363, 278, 279, -1, + 363, 279, 277, -1, 365, 367, 280, -1, + 365, 283, 364, -1, 365, 280, 281, -1, + 365, 281, 282, -1, 365, 282, 283, -1, + 371, 283, 526, -1, 371, 373, 283, -1, + 374, 526, 368, -1, 466, 526, 362, -1, + 466, 467, 526, -1, 378, 284, 376, -1, + 378, 285, 284, -1, 378, 535, 286, -1, + 378, 287, 285, -1, 378, 286, 287, -1, + 470, 383, 457, -1, 470, 457, 381, -1, + 470, 381, 380, -1, 469, 470, 380, -1, + 389, 288, 387, -1, 389, 393, 384, -1, + 389, 289, 288, -1, 389, 385, 289, -1, + 554, 499, 501, -1, 554, 547, 403, -1, + 481, 539, 540, -1, 481, 540, 502, -1, + 290, 406, 291, -1, 290, 292, 406, -1, + 290, 291, 292, -1, 492, 523, 557, -1, + 492, 491, 456, -1, 293, 298, 557, -1, + 293, 557, 294, -1, 293, 297, 298, -1, + 293, 295, 297, -1, 293, 294, 295, -1, + 453, 295, 294, -1, 453, 294, 523, -1, + 453, 454, 295, -1, 296, 298, 297, -1, + 296, 299, 298, -1, 296, 300, 299, -1, + 296, 301, 300, -1, 296, 302, 301, -1, + 296, 297, 302, -1, 545, 413, 546, -1, + 545, 485, 411, -1, 399, 408, 308, -1, + 399, 308, 398, -1, 459, 490, 408, -1, + 459, 408, 399, -1, 459, 395, 528, -1, + 410, 485, 398, -1, 410, 411, 485, -1, + 402, 403, 547, -1, 303, 414, 313, -1, + 303, 313, 401, -1, 303, 546, 414, -1, + 303, 401, 402, -1, 303, 547, 546, -1, + 303, 402, 547, -1, 304, 306, 406, -1, + 304, 406, 405, -1, 304, 405, 306, -1, + 307, 406, 305, -1, 307, 305, 335, -1, + 407, 335, 306, -1, 407, 306, 405, -1, + 407, 307, 335, -1, 407, 406, 307, -1, + 493, 557, 412, -1, 493, 308, 408, -1, + 493, 398, 308, -1, 493, 410, 398, -1, + 309, 412, 310, -1, 309, 311, 312, -1, + 309, 310, 311, -1, 309, 312, 313, -1, + 309, 313, 412, -1, 394, 316, 479, -1, + 394, 484, 316, -1, 394, 482, 484, -1, + 420, 416, 425, -1, 420, 421, 418, -1, + 435, 418, 421, -1, 435, 421, 496, -1, + 435, 314, 418, -1, 435, 433, 314, -1, + 560, 425, 561, -1, 510, 509, 513, -1, + 510, 513, 422, -1, 315, 483, 422, -1, + 315, 422, 316, -1, 315, 484, 483, -1, + 315, 316, 484, -1, 498, 499, 508, -1, + 498, 508, 510, -1, 498, 510, 422, -1, + 424, 317, 426, -1, 424, 515, 318, -1, + 424, 318, 317, -1, 430, 429, 319, -1, + 430, 319, 320, -1, 430, 320, 431, -1, + 321, 322, 323, -1, 321, 323, 324, -1, + 321, 324, 322, -1, 563, 325, 434, -1, + 563, 564, 326, -1, 563, 326, 325, -1, + 437, 450, 327, -1, 437, 327, 438, -1, + 446, 438, 447, -1, 446, 451, 438, -1, + 449, 505, 440, -1, 449, 445, 505, -1, + 520, 457, 521, -1, 328, 329, 393, -1, + 328, 521, 329, -1, 328, 330, 521, -1, + 328, 331, 330, -1, 328, 393, 331, -1, + 460, 528, 456, -1, 460, 456, 491, -1, + 460, 491, 490, -1, 332, 334, 333, -1, + 332, 333, 335, -1, 332, 336, 334, -1, + 332, 335, 336, -1, 473, 440, 505, -1, + 473, 474, 440, -1, 340, 338, 463, -1, + 464, 339, 463, -1, 464, 462, 339, -1, + 337, 462, 338, -1, 337, 339, 462, -1, + 337, 338, 340, -1, 337, 463, 339, -1, + 337, 340, 463, -1, 342, 355, 347, -1, + 342, 341, 355, -1, 342, 345, 341, -1, + 357, 355, 354, -1, 357, 348, 355, -1, + 357, 356, 351, -1, 357, 347, 348, -1, + 357, 342, 347, -1, 357, 351, 343, -1, + 357, 343, 344, -1, 357, 345, 342, -1, + 357, 359, 345, -1, 357, 344, 358, -1, + 357, 358, 359, -1, 346, 347, 355, -1, + 346, 355, 348, -1, 346, 348, 347, -1, + 349, 351, 350, -1, 349, 350, 352, -1, + 349, 355, 351, -1, 349, 352, 355, -1, + 353, 354, 355, -1, 353, 355, 356, -1, + 353, 357, 354, -1, 353, 356, 357, -1, + 465, 358, 366, -1, 465, 359, 358, -1, + 465, 360, 361, -1, 465, 361, 359, -1, + 465, 466, 362, -1, 465, 363, 360, -1, + 465, 362, 526, -1, 465, 526, 363, -1, + 525, 364, 373, -1, 525, 365, 364, -1, + 525, 465, 366, -1, 525, 367, 365, -1, + 525, 374, 368, -1, 525, 373, 374, -1, + 525, 366, 369, -1, 525, 369, 367, -1, + 525, 368, 526, -1, 370, 526, 373, -1, + 370, 371, 526, -1, 370, 373, 371, -1, + 372, 373, 526, -1, 372, 526, 374, -1, + 372, 374, 373, -1, 375, 376, 377, -1, + 375, 378, 376, -1, 375, 377, 379, -1, + 375, 379, 382, -1, 375, 382, 535, -1, + 375, 535, 378, -1, 530, 469, 380, -1, + 530, 528, 531, -1, 530, 380, 381, -1, + 530, 381, 528, -1, 534, 535, 382, -1, + 534, 382, 385, -1, 471, 383, 470, -1, + 471, 384, 383, -1, 471, 385, 389, -1, + 471, 389, 384, -1, 471, 534, 385, -1, + 471, 469, 534, -1, 386, 387, 388, -1, + 386, 389, 387, -1, 386, 390, 391, -1, + 386, 388, 390, -1, 386, 391, 392, -1, + 386, 392, 393, -1, 386, 393, 389, -1, + 472, 554, 501, -1, 472, 547, 554, -1, + 537, 501, 502, -1, 537, 502, 540, -1, + 537, 472, 501, -1, 537, 536, 472, -1, + 396, 539, 567, -1, 396, 567, 582, -1, + 477, 567, 539, -1, 477, 539, 481, -1, + 477, 394, 479, -1, 477, 481, 482, -1, + 477, 482, 394, -1, 544, 485, 545, -1, + 400, 395, 459, -1, 400, 459, 399, -1, + 400, 582, 395, -1, 400, 573, 574, -1, + 400, 396, 582, -1, 400, 574, 539, -1, + 400, 539, 396, -1, 397, 398, 542, -1, + 397, 399, 398, -1, 397, 400, 399, -1, + 397, 542, 573, -1, 397, 573, 400, -1, + 553, 401, 489, -1, 553, 402, 401, -1, + 553, 489, 486, -1, 553, 403, 402, -1, + 553, 554, 403, -1, 404, 405, 406, -1, + 404, 406, 407, -1, 404, 407, 405, -1, + 494, 408, 490, -1, 494, 493, 408, -1, + 409, 411, 410, -1, 409, 410, 493, -1, + 409, 493, 412, -1, 409, 413, 545, -1, + 409, 545, 411, -1, 409, 414, 413, -1, + 409, 412, 414, -1, 415, 419, 416, -1, + 415, 420, 419, -1, 415, 416, 420, -1, + 417, 418, 419, -1, 417, 419, 420, -1, + 417, 420, 418, -1, 495, 425, 560, -1, + 495, 420, 425, -1, 495, 421, 420, -1, + 495, 496, 421, -1, 500, 422, 483, -1, + 500, 498, 422, -1, 500, 483, 503, -1, + 423, 514, 515, -1, 423, 515, 424, -1, + 423, 425, 514, -1, 423, 426, 425, -1, + 423, 424, 426, -1, 507, 508, 499, -1, + 507, 554, 552, -1, 507, 499, 554, -1, + 512, 513, 509, -1, 504, 507, 552, -1, + 504, 518, 507, -1, 504, 473, 505, -1, + 504, 487, 473, -1, 427, 428, 429, -1, + 427, 429, 430, -1, 427, 431, 428, -1, + 427, 430, 431, -1, 432, 434, 433, -1, + 432, 563, 434, -1, 432, 496, 563, -1, + 432, 435, 496, -1, 432, 433, 435, -1, + 436, 451, 450, -1, 436, 450, 437, -1, + 436, 438, 451, -1, 436, 437, 438, -1, + 439, 440, 441, -1, 439, 449, 440, -1, + 439, 441, 450, -1, 439, 450, 449, -1, + 442, 443, 444, -1, 442, 444, 445, -1, + 442, 446, 447, -1, 442, 447, 448, -1, + 442, 448, 443, -1, 442, 449, 450, -1, + 442, 445, 449, -1, 442, 450, 451, -1, + 442, 451, 446, -1, 522, 521, 452, -1, + 522, 453, 523, -1, 522, 452, 454, -1, + 522, 454, 453, -1, 455, 456, 457, -1, + 455, 457, 520, -1, 455, 492, 456, -1, + 455, 523, 492, -1, 455, 520, 523, -1, + 458, 459, 528, -1, 458, 528, 460, -1, + 458, 490, 459, -1, 458, 460, 490, -1, + 461, 463, 462, -1, 461, 464, 463, -1, + 461, 462, 464, -1, 527, 465, 525, -1, + 527, 467, 466, -1, 527, 466, 465, -1, + 527, 526, 467, -1, 566, 469, 530, -1, + 566, 568, 533, -1, 566, 534, 469, -1, + 468, 470, 469, -1, 468, 471, 470, -1, + 468, 469, 471, -1, 475, 547, 472, -1, + 475, 472, 536, -1, 488, 473, 487, -1, + 488, 489, 474, -1, 488, 474, 473, -1, + 549, 547, 475, -1, 549, 475, 536, -1, + 575, 539, 574, -1, 577, 537, 540, -1, + 476, 568, 567, -1, 476, 567, 477, -1, + 476, 478, 568, -1, 476, 479, 478, -1, + 476, 477, 479, -1, 480, 502, 503, -1, + 480, 482, 481, -1, 480, 481, 502, -1, + 480, 503, 483, -1, 480, 483, 484, -1, + 480, 484, 482, -1, 571, 546, 547, -1, + 541, 542, 485, -1, 541, 485, 544, -1, + 551, 553, 486, -1, 551, 504, 552, -1, + 551, 487, 504, -1, 551, 488, 487, -1, + 551, 486, 489, -1, 551, 489, 488, -1, + 556, 494, 490, -1, 556, 490, 491, -1, + 556, 491, 492, -1, 556, 492, 557, -1, + 558, 557, 493, -1, 558, 493, 494, -1, + 558, 494, 556, -1, 562, 495, 560, -1, + 562, 496, 495, -1, 562, 563, 496, -1, + 497, 499, 498, -1, 497, 498, 500, -1, + 497, 501, 499, -1, 497, 502, 501, -1, + 497, 503, 502, -1, 497, 500, 503, -1, + 517, 518, 504, -1, 517, 505, 516, -1, + 517, 504, 505, -1, 506, 507, 518, -1, + 506, 518, 512, -1, 506, 508, 507, -1, + 506, 512, 509, -1, 506, 509, 510, -1, + 506, 510, 508, -1, 511, 513, 512, -1, + 511, 515, 514, -1, 511, 514, 513, -1, + 511, 516, 515, -1, 511, 517, 516, -1, + 511, 512, 518, -1, 511, 518, 517, -1, + 519, 520, 521, -1, 519, 521, 522, -1, + 519, 523, 520, -1, 519, 522, 523, -1, + 524, 525, 526, -1, 524, 526, 527, -1, + 524, 527, 525, -1, 565, 531, 528, -1, + 565, 528, 579, -1, 529, 530, 531, -1, + 529, 566, 530, -1, 529, 531, 565, -1, + 529, 565, 566, -1, 532, 566, 533, -1, + 532, 534, 566, -1, 532, 533, 535, -1, + 532, 535, 534, -1, 548, 549, 536, -1, + 548, 536, 537, -1, 548, 537, 577, -1, + 548, 577, 576, -1, 538, 540, 539, -1, + 538, 539, 575, -1, 538, 577, 540, -1, + 538, 575, 577, -1, 570, 544, 571, -1, + 570, 542, 541, -1, 570, 541, 544, -1, + 570, 573, 542, -1, 543, 544, 545, -1, + 543, 571, 544, -1, 543, 545, 546, -1, + 543, 546, 571, -1, 572, 571, 547, -1, + 572, 548, 576, -1, 572, 547, 549, -1, + 572, 549, 548, -1, 550, 551, 552, -1, + 550, 553, 551, -1, 550, 552, 554, -1, + 550, 554, 553, -1, 555, 556, 557, -1, + 555, 557, 558, -1, 555, 558, 556, -1, + 559, 560, 561, -1, 559, 562, 560, -1, + 559, 563, 562, -1, 559, 561, 564, -1, + 559, 564, 563, -1, 581, 565, 579, -1, + 581, 566, 565, -1, 581, 582, 567, -1, + 581, 567, 568, -1, 581, 568, 566, -1, + 569, 570, 571, -1, 569, 571, 572, -1, + 569, 573, 570, -1, 569, 574, 573, -1, + 569, 575, 574, -1, 569, 572, 576, -1, + 569, 576, 577, -1, 569, 577, 575, -1, + 578, 579, 580, -1, 578, 581, 579, -1, + 578, 580, 582, -1, 578, 582, 581, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T5_forearmRoll.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T5_forearmRoll.wrl new file mode 100644 index 0000000..41aeb00 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T5_forearmRoll.wrl @@ -0,0 +1,4350 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_T5_forearmRoll_______________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 15.3695 37.887199 -219.01199, + 7.8225398 41.887199 -54.847198, + -4.1622901 41.887199 -59.209301, + 22.808201 22.915001 7.9190798, + 40.913502 0.179903 -53.247501, + 22.808201 -22.915001 7.9190798, + 15.7644 37.834301 -219.01199, + -6.3769898 41.887199 -57.350899, + -0.062833406 38.461201 -222.01199, + -5.3509302 41.887199 -58.376999, + -22.808201 -22.915001 7.9190798, + -21.419201 -22.915001 11.142, + -22.808201 22.915001 7.9190798, + 43.702801 20.5147 -63.1474, + 1.44555 -41.887199 -60.198101, + -8.2080379e-007 -41.887199 -60.3246, + 5.3509302 -41.887199 -58.376999, + 4.1622901 -41.887199 -59.209301, + -34.8965 21.422001 -47.552299, + -34.8922 21.5298 -57, + -8.2185073e-007 41.887199 -60.3246, + -1.44555 41.887199 -60.198101, + 1.44555 41.887199 -60.198101, + -2.8471701 41.887199 -59.822498, + 6.3769898 41.887199 -57.350899, + 5.3509302 41.887199 -58.376999, + 4.1622901 41.887199 -59.209301, + 2.8471701 41.887199 -59.822498, + 7.20929 41.887199 -56.1623, + 15.5687 37.873901 -219.01199, + 15.9532 37.769001 -219.01199, + -9.0086098 41.766602 -52, + -15.5687 37.873901 -219.01199, + -7.8225398 41.887199 -54.847198, + -15.3695 37.887199 -219.01199, + 38.253799 28.338301 -200.01199, + 18.6341 37.689201 -1.05687, + 9.0086098 41.766602 -52, + 38.253799 28.338301 -65.012299, + -35.229198 20.9146 -48.339199, + -36.730701 18.1896 -49.537899, + -21.399799 25.215 11.1333, + -21.419201 22.915001 11.142, + -22.683901 25.215 8.2684698, + -21.399799 -25.215 11.1333, + 44.049999 21.576401 -176.50101, + 43.902 -20.5147 -63.972, + 43.702801 -20.5147 -63.1474, + 43.631802 -21.4589 -63.170601, + -20.799999 33.887199 4.2253499, + -21.2283 33.887199 1.16851, + 8.3245697 41.887199 -52, + 8.3245697 41.887199 -3.7339696e-008, + 8.6718702 41.8568 -52, + 8.5401201 41.8568 -53.505901, + 9.0086098 -41.766602 -4.1237708e-008, + -8.1981001 -41.887199 -53.445499, + -2.8471701 -41.887199 -59.822498, + -4.1622901 -41.887199 -59.209301, + -15.3695 -37.887199 -219.01199, + -36.737598 18.0938 -49.3386, + -38.263802 14.6956 -51.011398, + -38.2579 14.6171 -50.813999, + -26.1751 31.557301 -218.01199, + -26.837601 30.9958 -57, + 8.7090101 37.501999 -222.01199, + 14.452 29.6672 -229.812, + -8.9124804 41.7924 -4.0542723e-008, + -8.9124804 41.7924 -52, + -8.5401201 41.8568 -53.505901, + 32.839699 -3.2488301 -229.812, + -19.561899 -25.215 14.1194, + -21.266199 -25.215 11.4312, + -19.5777 -22.915001 14.1294, + -36.2146 19.222401 -218.01199, + -40.756699 3.57301 -53.094002, + -40.913502 -0.179574 -53.247501, + -39.8563 -9.6162205 -173.48801, + -40.186401 -7.6606698 -52.535599, + -40.723301 -3.9339499 -53.061298, + -40.961201 -0.18063401 -53.437901, + -19.649099 -33.887199 8.1190395, + -23.634001 -25.215 4.9353199, + -22.683901 -25.215 8.2684698, + 44.049999 21.667601 -176.795, + 38.253799 -28.338301 -200.01199, + 43.705502 -22.368601 -65.012299, + 43.851398 -21.4589 -64.079803, + 44.049999 -19.226101 -178.25301, + 44.049999 -19.8426 -176.767, + 44.049999 18.3992 -177.60001, + 44.049999 16.7847 -176.91, + 43.902 20.5147 -63.972, + 18.972099 36.887199 4.6276002, + 43.420399 22.379601 -63.239799, + 23.634001 25.215 4.9353199, + 43.631802 21.4589 -63.170601, + 20.732 33.887199 4.7104201, + 43.073898 23.253799 -63.3531, + 43.925701 21.4533 -65.012299, + 43.925201 20.5147 -64.0681, + 42.780499 24.0597 -64.250504, + 18.8085 37.134201 4.5876999, + -9.0086098 41.766602 -3.8784215e-008, + 8.1981001 41.887199 1.44555, + 8.1981001 41.887199 -53.445499, + 43.631802 -22.379601 -64.114799, + 43.702801 -22.379601 -65.012299, + 9.0086098 -41.766602 -52, + 18.4034 -37.766602 1.6848, + 17.954 -37.766602 4.3792601, + 18.7661 -37.619301 -1.06436, + 38.253799 -28.338301 -65.012299, + 18.450701 -37.766602 -1.04646, + -6.3769898 -41.887199 -57.350899, + -7.20929 -41.887199 -56.1623, + -5.3509302 -41.887199 -58.376999, + -7.8225398 -41.887199 -54.847198, + -1.44555 -41.887199 -60.198101, + 2.8471701 -41.887199 -59.822498, + 15.5687 -37.873901 -219.01199, + 7.20929 -41.887199 -56.1623, + 15.3695 -37.887199 -219.01199, + -8.6718702 -41.8568 -4.830564e-008, + -8.3245697 -41.887199 -52, + -8.5401201 -41.8568 -53.505901, + -8.3245697 -41.887199 -4.1682149e-008, + -18.010099 -33.887199 11.2979, + -40.885201 3.06633 -121.536, + -40.884998 3.06879 -99.487701, + -37.247898 17.134701 -99.031998, + 39.0597 27.840799 -200.01199, + 39.757401 27.242599 -200.01199, + -16.104401 37.7048 -218, + 41 7.1211707e-006 -219.01199, + 37.915298 15.6021 -219.01199, + 22.9814 -15.9955 -232.01199, + -28.607201 29.3706 -218, + -8.1981001 41.887199 -53.445499, + -7.20929 41.887199 -56.1623, + 8.8717499 41.766602 1.56433, + 18.1325 37.689201 4.4227901, + 18.5863 37.689201 1.70155, + 9.0086098 41.766602 -4.2863203e-008, + 8.6718702 41.8568 -5.0669478e-008, + 19.5777 -22.915001 14.1294, + 19.561899 -25.215 14.1194, + 19.5777 22.915001 14.1294, + -34.1693 -22.6597 -218.01199, + -34.1693 -22.6597 -219.01199, + -32.8153 -24.579599 -57, + -34.8922 21.5298 -218, + -36.2146 19.222401 -219.01199, + -35.255699 20.929399 -57, + -34.8922 21.5298 -110.667, + -39.255199 11.8334 -218.01199, + -39.6017 10.6163 -173.48801, + -40.884998 3.06879 -173.48801, + -39.255199 -11.8334 -218.01199, + -26.869699 -18.8111 -230.01199, + -27.0336 -18.9258 -229.812, + -36.938702 -17.7913 -173.537, + -34.8922 -21.5298 -57, + -34.8922 -21.5298 -218, + -36.937599 -17.7936 -173.48801, + -37.247898 17.134701 -151.032, + -37.9753 15.4557 -173.537, + -39.6017 -10.6163 -173.48801, + -23.634001 25.215 4.9353199, + -40.254799 7.29497 -52.602501, + -40.8032 3.59409 -53.2845, + -39.8563 9.61623 -173.48801, + -40.769501 -3.95715 -53.251801, + -40.990002 -0.18162701 -53.632, + -40.217899 -7.9699898 -99.1241, + -36.547001 -18.474701 -49.153702, + -40.1861 -8.1287498 -173.48801, + -40.187401 -8.1225405 -151.411, + -40.259998 -7.7544899 -173.97, + 44.049999 20.3367 -179.633, + 44.049999 20.8514 -179.298, + 44.049999 20.604401 -179.48199, + 44.049999 21.5632 -178.308, + 44.049999 21.2686 -178.847, + 44.049999 21.0739 -179.08501, + 44.049999 21.4326 -178.586, + 44.049999 21.722 -177.09801, + 44.049999 21.658701 -178.015, + 43.925201 -20.5147 -200.95599, + 43.925701 -21.4533 -200.01199, + 43.705502 -22.368601 -200.01199, + 43.702801 -22.379601 -200.01199, + 43.925201 -21.4589 -200.01199, + 44.049999 -21.7328 -177.215, + 43.925701 -21.4533 -65.012299, + 43.925201 -21.4589 -65.012299, + 44.049999 -19.940399 -179.787, + 44.049999 19.4512 -179.87801, + 44.049999 19.143499 -179.886, + 44.049999 19.755699 -179.83299, + 44.049999 20.052401 -179.75101, + 39.255199 11.8334 -219.01199, + 43.073898 22.379601 -202.616, + 39.0597 -27.840799 -200.01199, + 39.711399 -27.196699 -200.755, + 39.501499 -26.986799 -202.064, + 39.2062 -27.222601 -202.144, + 44.049999 -20.504499 -179.543, + 44.049999 -18.4251 -179.75101, + 44.049999 -19.334 -179.886, + 44.049999 -19.6402 -179.855, + 44.049999 -20.23 -179.683, + 44.049999 -20.9921 -179.16901, + 44.049999 -20.7598 -179.371, + 44.049999 -21.735001 -177.52299, + 44.049999 -21.3738 -178.688, + 44.049999 -21.626499 -178.12801, + 44.049999 -21.6994 -177.82899, + 44 -20.5147 -200.01199, + 43.925201 -20.5147 -64.0681, + 44.049999 -4.1655202 -64.799797, + 44.049999 -21.1978 -178.94099, + 44.049999 -21.517401 -178.416, + 44.049999 -4.6900401 -66.822701, + 44.049999 -21.615499 -176.612, + 17.5221 37.5397 7.1451502, + 43.338299 23.253799 -65.012299, + 43.271801 23.253799 -64.172203, + 42.840801 24.0597 -65.012299, + 43.705502 22.368601 -65.012299, + 43.702801 22.379601 -65.012299, + 43.631802 22.379601 -64.114799, + 43.851398 21.4589 -64.079803, + 43.925201 21.4589 -65.012299, + 42.242599 24.757401 -65.012299, + -19.0229 36.887199 4.3233099, + -20.732 33.887199 4.7104201, + 39.757401 -27.242599 -200.01199, + 42.201 -24.715799 -200.685, + 8.3245697 -41.887199 -52, + 8.1981001 -41.887199 -53.445499, + 8.6718702 -41.8568 -52, + 8.5401201 -41.8568 -53.505901, + 39.005798 -27.840799 -64.396698, + 39.0597 -27.840799 -65.012299, + 39.757401 -27.242599 -65.012299, + 39.711399 -27.196699 -64.269302, + 18.718 -37.619301 1.7136101, + 6.3769898 -41.887199 -57.350899, + -8.4653301 -41.766602 3.08113, + -18.4034 -37.766602 1.6848, + -8.8717499 -41.766602 1.56433, + -9.0086098 -41.766602 -3.7857106e-008, + -18.2609 -37.619301 4.4541302, + -18.538401 -37.4193 4.5218, + -17.954 -37.766602 4.3792601, + -32.425499 -25.0674 -45.400902, + -34.589401 -22.0131 -47.730499, + -20.799999 -33.887199 4.2253499, + -21.2283 -33.887199 1.16851, + -19.0229 -36.887199 4.3233099, + -18.972099 -36.887199 4.6276002, + -19.447001 -36.887199 1.78035, + -24.792299 -32.6549 -218, + -19.002399 -37.4193 1.73964, + -19.2479 -37.172798 1.76212, + -14.5361 -36.887199 12.9724, + -15.1466 -36.887199 12.3262, + -16.798201 -36.887199 9.9587898, + -9.0086098 -41.766602 -52, + -8.6718702 -41.8568 -52, + -15.9532 -37.769001 -219.01199, + -15.5687 -37.873901 -219.01199, + -22.9814 -15.9955 -232.01199, + -41 -0.051116895 -98.990799, + 15.9532 -37.769001 -219.01199, + 11.3765 30.976999 -229.812, + 8.1842098 31.969 -229.812, + 14.3644 29.4874 -230.01199, + 38.0886 28.338301 -200.94901, + 38.2122 28.338301 -200.48801, + 19.557501 36.034801 -219.01199, + 32.7999 0.089630201 -230.01199, + 32.640701 -3.22914 -230.01199, + 28 7.1284803e-006 -232.01199, + 32.8214 3.4282601 -229.812, + 32.999901 0.090175889 -229.812, + 32.622501 3.40748 -230.01199, + 32.306198 6.7311602 -229.812, + 40.221401 7.9520798 -219.01199, + 26.972099 -18.664 -230.01199, + 27.1366 -18.7778 -229.812, + 17.532301 -27.9575 -229.812, + 14.6139 -29.5877 -229.812, + 31.7987 -25.8813 -219.01199, + 32.342499 -6.5545001 -229.812, + 32.1465 -6.51477 -230.01199, + 27.8563 2.83272 -232.01199, + 27.8563 -2.83271 -232.01199, + 24.481701 -13.5884 -232.01199, + -29.998501 27.948 -57, + -28.607201 29.3706 -57, + -29.1255 28.8566 -218.01199, + -31.990801 25.643499 -57, + -31.7987 25.8813 -218.01199, + -31.990801 25.643499 -164.33299, + -30.250299 27.6514 -43.3111, + -32.8153 24.579599 -57, + -34.1693 22.6597 -219.01199, + -31.990801 25.643499 -218, + -34.1693 22.6597 -218.01199, + -32.708599 24.697201 -45.672798, + -34.874401 21.533501 -47.753899, + -34.8288 21.6322 -47.958302, + -32.644402 24.8062 -45.880402, + -19.447001 36.887199 1.78035, + 1.7545 25.215 24.078501, + 1.75472 22.915001 24.08, + 1.7545 -25.215 24.078501, + 1.75472 -22.915001 24.08, + 1.73297 -25.215 24.0816, + -19.410299 -25.215 14.3584, + -14.7013 22.915001 19.152, + -14.7013 -22.915001 19.152, + -11.7695 -22.915001 21.0809, + -1.75473 -22.915001 24.08, + 5.2258 -25.215 23.566799, + 5.1631899 -25.215 23.5853, + 8.5858698 -25.215 22.5576, + 21.399799 -25.215 11.1333, + 21.266199 -25.215 11.4312, + 17.3225 22.915001 16.818399, + 19.410299 -25.215 14.3584, + 17.3225 -22.915001 16.818399, + 21.419201 22.915001 11.142, + 21.419201 -22.915001 11.142, + 21.399799 25.215 11.1333, + 22.683901 25.215 8.2684698, + 4.5043101 -41.766602 7.8016901, + -8.2409758e-007 -41.887199 8.3245697, + -6.4389 -36.887199 18.391001, + -28.607201 -29.3706 -218, + -24.9802 -21.563601 -229.812, + -28.8971 15.9361 -229.812, + -12.331 25.1385 -232.01199, + -32.8214 -3.4282401 -229.812, + -40.885201 3.06633 -173.536, + -40.804901 3.99505 -218.01199, + -30.1064 -13.0172 -230.01199, + -28.635 -15.9962 -230.01199, + -28.809601 -16.0937 -229.812, + -30.2899 -13.0965 -229.812, + -24.481701 -13.5884 -232.01199, + -36.2146 -19.222401 -218.01199, + -35.255699 -20.9293 -57, + -36.2146 -19.222401 -219.01199, + -37.2789 -17.067101 -121.903, + -37.2789 -17.067101 -173.903, + -37.3069 -17.0058 -173.851, + -37.373699 16.858299 -173.48801, + -38.351299 14.4975 -173.48801, + -39.830898 -9.7210903 -173.793, + -40.320499 7.3780298 -52.9884, + -39.463001 11.0818 -52.1642, + -39.447102 11.022 -51.968201, + -40.297401 7.3379302 -52.793499, + -40.8307 3.6138101 -53.478901, + -40.7369 4.3808198 -53.578201, + -40.838799 3.63199 -53.675098, + -40.1861 8.1287699 -99.487701, + -40.1861 8.1287699 -173.48801, + -40.1866 8.1264696 -121.535, + -40.7967 -3.9788699 -53.446201, + -40.2285 -7.70577 -52.726601, + -40.2481 -7.81601 -99.027, + -17.897499 -37.172798 7.2982502, + -18.777901 -37.172798 4.5802202, + -18.082701 -36.887199 7.3737502, + -18.0425 -36.887199 7.4547, + -34.661098 -21.7999 -47.323799, + -20.732 -33.887199 4.7104201, + -36.538502 -18.5723 -49.353199, + -34.637001 -21.913099 -47.525799, + -40.194302 -8.0883198 -99.297096, + -40.198299 -8.0684404 -99.252098, + -40.190701 -8.1060896 -173.633, + -40.195499 -8.0822401 -173.69701, + -40.194302 -8.0883198 -151.297, + -40.1866 -8.1264496 -121.535, + -40.187401 -8.1225405 -99.411003, + -40.1861 -8.1287498 -99.487701, + -40.1866 -8.1264496 -173.535, + -40.239498 -7.8601599 -173.92799, + -40.248199 -7.8155499 -173.94901, + -40.248199 -7.8155499 -121.949, + 44.049999 21.717501 -177.713, + 43.925201 21.4589 -200.01199, + 43.925701 21.4533 -200.01199, + 44 20.5147 -200.01199, + 44.049999 21.738701 -177.40601, + 38.845901 -27.840799 -201.22501, + 39.520199 -27.222601 -201.47, + 39.692902 -27.1782 -201.054, + 39.005798 -27.840799 -200.62801, + 22.975599 -33.9576 -219.01199, + 38.0886 -28.338301 -200.94901, + 19.557501 -36.034801 -219.01199, + 38.2122 -28.338301 -200.48801, + 44.049999 0.10840001 -65.495201, + 44.049999 0.19956701 -65.7892, + 44.049999 -0.178326 -64.951797, + 44.049999 -2.89589 -63.971802, + 44.049999 -3.18694 -64.071999, + 44.049999 -2.5947399 -63.9081, + 44.049999 -3.7212901 -64.375298, + 44.049999 -3.95649 -64.573799, + 44.049999 -3.46347 -64.2071, + 44.049999 -4.4927802 -65.319801, + 44.049999 -4.34519 -65.049698, + 44 -20.5147 -65.012299, + 44.049999 -4.7233801 -66.209198, + 44.049999 -4.60607 -65.606003, + 44.049999 -4.6833301 -65.903999, + 44.049999 -4.7256298 -66.516998, + 44.049999 -21.692699 -176.91, + 44.049999 -1.09865 -64.151604, + 44.049999 -0.58894497 -64.494698, + 44.049999 -0.83321702 -64.307404, + 44.049999 -1.6766599 -63.9431, + 44.049999 -1.38123 -64.029503, + 44.049999 -0.36954001 -64.710602, + 44.049999 -0.018204004 -65.214699, + 44.049999 -1.9804699 -63.8937, + 44.049999 -2.2880499 -63.882, + 44.049999 -2.62059 -65.608704, + 44 20.5147 -65.012299, + 39.711399 27.196699 -64.269302, + 39.757401 27.242599 -65.012299, + 39.0597 27.840799 -65.012299, + -8.8717499 41.766602 1.56433, + -18.5863 37.689201 1.70155, + -18.6341 37.689201 -1.05687, + -20.6036 35.446999 -218, + -24.792299 32.6549 -218, + -19.0769 37.353298 1.74646, + -19.1259 37.353298 -1.08476, + -27.4126 30.488501 -40.9039, + -18.892599 37.5397 -1.07153, + -18.844101 37.5397 1.72515, + -29.990801 27.9403 -43.3563, + -19.279301 37.134201 1.76499, + -30.1654 27.7677 -43.5224, + 6.3769898 41.887199 5.3509302, + 7.20929 41.887199 4.1622901, + 8.1488895 41.8568 2.96595, + 7.8225398 41.887199 2.8471701, + 8.5401201 41.8568 1.50586, + 7.5100598 41.8568 4.3359399, + 8.4653301 41.766602 3.08113, + 9.4268799 36.887199 17.0431, + 8.8717499 -41.766602 1.56433, + 19.002399 -37.4193 1.73964, + 39.692902 -27.1782 -63.970402, + 6.7859302 -37.897202 -222.01199, + 10.5851 -37.0163 -222.01199, + 15.7644 -37.834301 -219.01199, + -7.8225398 -41.887199 2.8471701, + -8.1488895 -41.8568 2.96595, + -7.5100598 -41.8568 4.3359399, + -7.20929 -41.887199 4.1622901, + -8.1981001 -41.887199 1.44555, + -8.5401201 -41.8568 1.50586, + -14.9915 -37.172798 12.2, + -16.6262 -37.172798 9.8568096, + -14.8003 -37.4193 12.0444, + -16.414101 -37.4193 9.7311001, + -17.112301 -37.766602 6.9780302, + -17.4048 -37.619301 7.0973301, + -17.6693 -37.4193 7.2051702, + -15.8967 -37.766602 9.4243402, + -16.168501 -37.619301 9.5854702, + -13.0293 -37.172798 14.2766, + -26.1751 -31.557301 -218.01199, + -26.837601 -30.9958 -57, + -18.7661 -37.619301 -1.06436, + -20.6036 -35.446999 -218, + -19.0513 -37.4193 -1.08053, + -18.450701 -37.766602 -1.04646, + -18.718 -37.619301 1.7136101, + -16.104401 -37.7048 -218, + -29.9904 -27.941099 -43.3559, + -29.922501 -28.005501 -42.996201, + -32.358898 -25.177401 -45.608799, + -28.607201 -29.3706 -110.667, + -27.0392 -30.820101 -40.548698, + -28.607201 -29.3706 -164.33299, + -31.7987 -25.8813 -218.01199, + -29.998501 -27.948 -57, + -31.7987 -25.8813 -219.01199, + -31.990801 -25.643499 -57, + -31.990801 -25.643499 -110.667, + -31.990801 -25.643499 -218, + 14.811 -23.761999 -232.01199, + 17.426001 -27.788 -230.01199, + 14.5253 -29.4084 -230.01199, + -17.139 -22.141701 -232.01199, + -19.2911 -20.294201 -232.01199, + -26.1751 -31.557301 -219.01199, + -22.6705 -23.9802 -229.812, + -22.5331 -23.8349 -230.01199, + -20.0061 -25.992201 -230.01199, + -38.118698 15.0985 -99.003899, + -38.0313 15.3174 -99.134804, + 29.1255 -28.8566 -219.01199, + 26.1751 -31.557301 -219.01199, + -8.3085098 26.701401 -232.01199, + 9.7245502 26.257099 -232.01199, + 11.3075 30.789301 -230.01199, + 12.331 25.1385 -232.01199, + 22.975599 33.9576 -219.01199, + -11.4756 30.726999 -230.01199, + 26.735001 8.3085098 -232.01199, + 32.110401 6.6903601 -230.01199, + 26.7159 8.3821802 -232.01199, + 27.4268 5.6363702 -232.01199, + 31.268801 9.9045897 -230.01199, + 25.730801 11.042 -232.01199, + 31.459499 9.9649897 -229.812, + 25.730801 -11.042 -232.01199, + 34.1693 -22.6597 -219.01199, + 43.073898 -22.379601 -202.616, + 42.601002 -24.0597 -201.517, + 42.119701 -24.634399 -201.36301, + 41.986801 -24.501499 -202.064, + 42.3069 -24.0597 -202.222, + 42.1782 -24.6929 -201.054, + 42.780499 -24.0597 -200.774, + 43.271801 -23.253799 -200.85201, + 43.073898 -23.253799 -201.67101, + 42.749599 -23.253799 -202.44901, + 26.735001 -8.3085003 -232.01199, + 27.4268 -5.6363502 -232.01199, + 26.7159 -8.3821602 -232.01199, + -8.6223297 41.861198 -4.9215469e-008, + -8.3245697 41.887199 -52, + -8.6223297 41.861198 -52, + -8.3245697 41.887199 -4.0556191e-008, + -8.6718702 41.8568 -52, + -8.6718702 41.8568 -3.9005961e-008, + -8.1981001 41.887199 1.44555, + -8.5401201 41.8568 1.50586, + -11.7638 -25.215 21.0721, + -7.1385002 -33.887199 20.0156, + -13.2638 -33.887199 16.615499, + -13.1641 -36.887199 14.4243, + -15.8614 -33.887199 14.157, + -14.5451 -25.215 19.270901, + -17.154499 -25.215 16.9897, + 1.73297 25.215 24.0816, + 8.38587 36.887199 17.636101, + 5.1631899 25.215 23.5853, + -19.561899 25.215 14.1194, + -21.266199 25.215 11.4312, + -19.5777 22.915001 14.1294, + -17.3225 22.915001 16.818399, + -17.154499 25.215 16.9897, + -17.3225 -22.915001 16.818399, + -19.410299 25.215 14.3584, + -11.7695 22.915001 21.0809, + -5.2270999 -22.915001 23.571199, + -5.2270999 22.915001 23.571199, + -8.48701 -25.215 22.603001, + -8.5858698 -25.215 22.5576, + -1.75473 22.915001 24.08, + 7.1385002 -33.887199 20.0156, + 11.7638 -25.215 21.0721, + 11.6359 -25.215 21.1549, + 14.7013 -22.915001 19.152, + 17.154499 -25.215 16.9897, + 14.5451 -25.215 19.270901, + 14.7013 22.915001 19.152, + 17.154499 25.215 16.9897, + 12.6707 -37.619301 13.8836, + 12.8632 -37.4193 14.0946, + 12.4577 -37.766602 13.6502, + 14.5361 -36.887199 12.9724, + 15.8614 -33.887199 14.157, + 15.1466 -36.887199 12.3262, + 18.010099 -33.887199 11.2979, + 19.561899 25.215 14.1194, + 19.410299 25.215 14.3584, + 21.266199 25.215 11.4312, + 1.50585 -41.8568 8.5401201, + 2.96595 -41.8568 8.1488895, + -8.2664377e-007 -36.887199 19.528299, + 3.08113 -41.766602 8.4653301, + -38.351299 -14.4975 -99.487701, + -39.055302 -12.4773 -98.998901, + -38.900002 -12.9533 -57, + -38.963902 -12.7599 -99.027, + -38.949799 -12.8029 -99.048798, + -29.1255 -28.8566 -218.01199, + -28.607201 -29.3706 -57, + -29.8349 -28.122499 -43.208, + -29.1255 -28.8566 -219.01199, + -30.177 12.8525 -230.01199, + -30.361099 12.9308 -229.812, + -26.7159 8.3821802 -232.01199, + -18.905701 20.625 -232.01199, + -14.811 23.761999 -232.01199, + -22.975599 33.9576 -219.01199, + -31.268801 -9.9045801 -230.01199, + -32.306198 -6.7311401 -229.812, + -31.459499 -9.9649696 -229.812, + -40.9995 0.20605101 -173.94501, + -40.999802 0.128438 -173.972, + -41 -0.050265696 -173.985, + -32.839699 3.2488401 -229.812, + -39.0107 -12.6162 -98.989799, + -39.179199 -12.0828 -151.438, + -37.3568 -16.895901 -173.67799, + -37.3251 -16.965799 -173.804, + -37.373699 -16.858299 -173.48801, + -37.372799 -16.8605 -151.44, + -37.372101 -16.862 -173.537, + -37.363499 -16.8811 -173.64, + -36.507702 -18.6598 -49.555199, + -38.116501 -15.1041 -121.97, + -38.118698 -15.0985 -99.003899, + -36.938702 17.7913 -173.537, + -36.9394 17.790001 -151.439, + -36.937599 17.7936 -173.48801, + -36.9757 17.714399 -173.765, + -37.215302 17.2054 -99.005096, + -37.992199 15.4142 -121.697, + -38.007702 15.3758 -99.210899, + -37.915298 15.6021 -218.01199, + -37.9767 15.4523 -151.411, + -37.9767 15.4523 -99.411003, + -37.9743 15.4581 -99.487701, + -37.372799 16.8605 -99.4403, + -36.9394 17.790001 -99.438904, + -38.313 14.5984 -173.793, + -38.309299 14.6082 -151.17101, + -38.332001 14.5486 -99.264, + -38.332001 14.5486 -151.26401, + -38.341301 14.5241 -173.64999, + -38.341301 14.5241 -121.65, + -38.349899 14.5013 -173.537, + -38.8577 12.9392 -51.7906, + -39.791302 -9.8819704 -121.927, + -39.791302 -9.8819704 -173.927, + -40.367199 7.1757398 -99.252296, + -40.614399 5.6096702 -99.487701, + -40.636299 5.4492402 -151.12399, + -39.803501 9.8325396 -99.076401, + -39.855801 -9.6184998 -151.44, + -39.8549 -9.6223698 -173.564, + -39.855801 -9.6184998 -99.4403, + -39.849701 -9.6438398 -173.64999, + -40.748798 -4.3822699 -53.5895, + -39.355499 -11.4577 -52.060799, + -40.029701 -8.7110596 -52.905399, + -40.250999 -7.7478499 -52.9216, + -39.3405 -11.3959 -51.8647, + -38.1152 -15.0765 -50.868599, + -38.1106 -14.9961 -50.671001, + -40.928398 -2.4224601 -151.004, + -40.804501 -3.9988699 -53.642502, + -40.207401 -8.0229502 -151.18201, + -40.198299 -8.0684404 -151.252, + -40.207401 -8.0229502 -99.181999, + -40.205002 -8.0348101 -173.778, + -40.2159 -7.9802599 -173.842, + -40.2159 -7.9802599 -121.842, + -40.217499 -7.97223 -121.849, + -40.230999 -7.9038301 -99.072403, + -40.303699 -7.52421 -150.99899, + -40.303699 -7.52421 -98.998901, + -41 -0.0515453 -121.985, + 43.902 20.5147 -201.05299, + 43.702801 20.5147 -201.877, + 43.925201 20.5147 -200.95599, + 40.804901 3.99505 -219.01199, + 43.631802 22.379601 -200.91, + 43.631802 21.4589 -201.854, + 43.851398 21.4589 -200.94501, + 43.705502 22.368601 -200.01199, + 43.702801 22.379601 -200.01199, + 43.073898 23.253799 -201.67101, + 42.749599 23.253799 -202.44901, + 43.420399 22.379601 -201.785, + 42.780499 24.0597 -200.774, + 43.271801 23.253799 -200.85201, + 42.242599 24.757401 -200.01199, + 42.840801 24.0597 -200.01199, + 43.338299 23.253799 -200.01199, + 43.631802 -21.4589 -201.854, + 43.631802 -22.379601 -200.91, + 43.851398 -21.4589 -200.94501, + 43.420399 -22.379601 -201.785, + 40.221401 -7.9520702 -219.01199, + 39.255199 -11.8334 -219.01199, + 40.804901 -3.9950399 -219.01199, + 43.702801 -20.5147 -201.877, + 43.902 -20.5147 -201.05299, + 11.7695 22.915001 21.0809, + 11.6359 25.215 21.1549, + 11.7695 -22.915001 21.0809, + 11.7638 25.215 21.0721, + 14.5451 25.215 19.270901, + 17.738501 37.353298 7.2333999, + 18.082701 36.887199 7.3737502, + 16.478399 37.353298 9.7692299, + 19.0769 37.353298 1.74646, + 39.005798 27.840799 -64.396698, + 39.692902 27.1782 -63.970402, + 18.844101 37.5397 1.72515, + 42.1782 24.6929 -63.970402, + 18.611 37.353298 4.5395198, + 18.384001 37.5397 4.4841399, + -19.649099 33.887199 8.1190395, + -18.010099 33.887199 11.2979, + 5.3509302 41.887199 6.3769898, + 42.840801 -24.0597 -65.012299, + 42.242599 -24.757401 -200.01199, + 42.242599 -24.757401 -65.012299, + 42.840801 -24.0597 -200.01199, + 43.338299 -23.253799 -65.012299, + 43.338299 -23.253799 -200.01199, + 8.5401201 -41.8568 1.50586, + 8.3245697 -41.887199 -4.5287937e-008, + 8.6718702 -41.8568 -3.7971752e-008, + 7.8225398 -41.887199 -54.847198, + 4.3359399 -41.8568 7.5100598, + 18.777901 -37.172798 4.5802202, + 19.2479 -37.172798 1.76212, + 42.1782 -24.6929 -63.970402, + 18.538401 -37.4193 4.5218, + 42.780499 -24.0597 -64.250504, + 8.3081303 -31.730301 -230.01199, + 11.4756 -30.726999 -230.01199, + 8.3587904 -31.9238 -229.812, + 11.5456 -30.9144 -229.812, + -4.1622901 -41.887199 7.20929, + -4.3359399 -41.8568 7.5100598, + -6.3769898 -41.887199 5.3509302, + -5.3509302 -41.887199 6.3769898, + -5.5741701 -41.8568 6.6430402, + -14.5788 -37.619301 11.8642, + -4.5043101 -41.766602 7.8016901, + -6.901 -41.766602 5.7906199, + -14.3338 -37.766602 11.6647, + -7.8016901 -41.766602 4.5043101, + -6.6430402 -41.8568 5.5741701, + -12.4577 -37.766602 13.6502, + -5.7906299 -41.766602 6.901, + -10.7825 -37.172798 16.0413, + -12.8632 -37.4193 14.0946, + -12.6707 -37.619301 13.8836, + -10.4856 -37.619301 15.5997, + -7.9358301 -37.766602 16.689699, + -10.3094 -37.766602 15.3375, + -1.50585 -41.8568 8.5401201, + -2.8471701 -41.887199 7.8225398, + -1.44555 -41.887199 8.1981001, + -2.96595 -41.8568 8.1488895, + -3.08113 -41.766602 8.4653301, + -20.625 -18.8909 -232.01199, + -24.8288 -21.432899 -230.01199, + -17.3792 -28.052799 -229.812, + -20.128099 -26.1507 -229.812, + -22.975599 -33.9576 -219.01199, + -19.557501 -36.034801 -219.01199, + -8.7090101 -37.501999 -222.01199, + -15.7644 -37.834301 -219.01199, + -14.3644 -29.487301 -230.01199, + -14.452 -29.667101 -229.812, + -17.273899 -27.882799 -230.01199, + -12.331 -25.1385 -232.01199, + -9.7245502 -26.257099 -232.01199, + -2.3492301 24.355101 -232.01199, + 5.0862298 -32.605701 -229.812, + 2.91712 -38.389301 -222.01199, + 0.062833607 -38.461201 -222.01199, + -40.949299 2.03883 -173.48801, + -40.949299 2.03883 -164.33299, + -40.949299 2.03883 -99.487701, + -40.923599 2.5025599 -150.99001, + -41 0.048994698 -98.989998, + -41 -0.00043804335 -98.9897, + -40.885502 3.06248 -151.411, + -38.309299 14.6082 -99.171501, + -38.2537 14.7531 -121.927, + -38.242901 14.7811 -99.031998, + -38.2374 14.7953 -173.948, + -38.242901 14.7811 -151.032, + -38.2537 14.7531 -173.927, + -38.2696 14.7118 -173.903, + -38.271999 14.7056 -151.076, + -38.271999 14.7056 -99.076401, + -38.090099 15.1706 -99.029999, + -38.034199 15.3102 -121.849, + -38.0602 15.2455 -99.072403, + -37.372799 16.8605 -151.44, + -37.2789 17.067101 -173.903, + -37.2789 17.067101 -121.903, + 22.663 -23.711399 -230.01199, + 20.1479 -25.8825 -230.01199, + 19.2911 -20.294201 -232.01199, + 24.945601 -21.2969 -230.01199, + 25.0977 -21.4268 -229.812, + 22.801201 -23.8559 -229.812, + 20.2707 -26.0403 -229.812, + 19.9335 -19.618401 -232.01199, + 21.245199 -18.2384 -232.01199, + 0.98163402 38.487499 -222.01199, + 4.8703098 38.190701 -222.01199, + 4.90797 32.632999 -229.812, + 1.58136 32.962101 -229.812, + -2.91712 38.389301 -222.01199, + -1.76147 32.952999 -229.812, + 20.0061 25.992201 -230.01199, + 17.273899 27.882799 -230.01199, + 17.3792 28.0529 -229.812, + 21.245199 18.2384 -232.01199, + 24.4902 -2.2955301 -232.01199, + 25.2677 -2.1066101 -232.01199, + 39.692902 27.1782 -201.054, + 42.201 24.715799 -200.685, + 39.711399 27.196699 -200.755, + 39.005798 27.840799 -200.62801, + 38.845901 27.840799 -201.22501, + 42.119701 24.634399 -201.36301, + 42.1782 24.6929 -201.054, + 42.601002 24.0597 -201.517, + -14.6139 29.5877 -229.812, + -15.9532 37.769001 -219.01199, + -14.5253 29.4084 -230.01199, + -19.557501 36.034801 -219.01199, + -8.3587904 31.9238 -229.812, + -11.5456 30.9144 -229.812, + -15.7644 37.834301 -219.01199, + -8.3081303 31.7304 -230.01199, + -10.5851 37.0163 -222.01199, + -6.7859302 37.897301 -222.01199, + -5.0862298 32.605701 -229.812, + 36.2146 19.222401 -219.01199, + 30.2899 13.0966 -229.812, + 30.1064 13.0172 -230.01199, + 27.0336 18.9258 -229.812, + 26.869699 18.8111 -230.01199, + 34.1693 22.6597 -219.01199, + 28.809601 16.0938 -229.812, + 28.635 15.9962 -230.01199, + 31.7987 25.8813 -219.01199, + 41.986801 24.501499 -202.064, + 42.3069 24.0597 -202.222, + 30.361099 -12.9308 -229.812, + 28.722 -15.8395 -230.01199, + 28.8971 -15.9361 -229.812, + 30.177 -12.8525 -230.01199, + 36.2146 -19.222401 -219.01199, + 37.915298 -15.6021 -219.01199, + 31.5135 -9.7929001 -229.812, + 31.3225 -9.7335501 -230.01199, + -6.3769898 41.887199 5.3509302, + -7.5100598 41.8568 4.3359399, + -7.20929 41.887199 4.1622901, + -7.8225398 41.887199 2.8471701, + -8.1488895 41.8568 2.96595, + -6.6430402 41.8568 5.5741701, + -8.1258898 37.5397 17.089399, + -3.08113 41.766602 8.4653301, + -5.5741701 41.8568 6.6430402, + -9.4268799 -36.887199 17.0431, + -10.2909 -33.887199 18.6038, + -8.38587 -36.887199 17.636101, + -10.894 -36.887199 16.2073, + -1.7545 25.215 24.078501, + -1.73297 25.215 24.0816, + 8.48701 25.215 22.603001, + 7.1385002 33.887199 20.0156, + 5.2258 25.215 23.566799, + 8.5858698 25.215 22.5576, + 10.2909 33.887199 18.6038, + 8.5890398 22.915001 22.5644, + 5.2270999 22.915001 23.571199, + 8.48701 -25.215 22.603001, + 8.5890398 -22.915001 22.5644, + 5.2270999 -22.915001 23.571199, + 7.0268202 33.887199 20.065599, + -5.1631899 25.215 23.5853, + -11.7638 25.215 21.0721, + -14.5451 25.215 19.270901, + -8.5890398 22.915001 22.5644, + -8.5858698 25.215 22.5576, + -8.48701 25.215 22.603001, + -8.5890398 -22.915001 22.5644, + -11.6359 25.215 21.1549, + -11.6359 -25.215 21.1549, + 10.2909 -33.887199 18.6038, + 12.1507 -36.887199 15.2203, + 13.2638 -33.887199 16.615499, + 13.1641 -36.887199 14.4243, + 13.0293 -37.172798 14.2766, + 18.082701 -36.887199 7.3737502, + 14.9915 -37.172798 12.2, + 16.798201 -36.887199 9.9587898, + 17.897499 -37.172798 7.2982502, + 18.0425 -36.887199 7.4547, + 20.732 -33.887199 4.7104201, + 18.972099 -36.887199 4.6276002, + 19.649099 -33.887199 8.1190395, + 22.683901 -25.215 8.2684698, + 43.271801 -23.253799 -64.172203, + 23.634001 -25.215 4.9353199, + 43.073898 -23.253799 -63.3531, + 43.420399 -22.379601 -63.239799, + 10.894 36.887199 16.2073, + 13.2638 33.887199 16.615499, + 19.649099 33.887199 8.1190395, + 18.0425 36.887199 7.4547, + 17.9268 37.134201 7.3101702, + 2.87869 -36.887199 19.315001, + 3.5638399 -33.887199 20.9596, + 7.0268202 -33.887199 20.065599, + -8.2983934e-007 -33.887199 21.260401, + -7.0268202 -33.887199 20.065599, + -5.1631899 -25.215 23.5853, + -1.7545 -25.215 24.078501, + -1.73297 -25.215 24.0816, + 8.0715103 -37.619301 16.975, + 7.9358301 -37.766602 16.689699, + 10.3094 -37.766602 15.3375, + 10.4856 -37.619301 15.5997, + -38.863499 -13.0626 -121.488, + -38.863499 -13.0626 -99.487701, + -38.891701 -12.9783 -99.210899, + -39.0555 -12.4768 -121.976, + -38.9375 -12.8403 -151.069, + -38.959202 -12.7744 -121.943, + -38.9375 -12.8403 -99.069298, + -37.915298 -15.6021 -218.01199, + -38.007702 -15.3758 -99.210899, + -38.0313 -15.3173 -99.134804, + -37.9837 -15.435 -99.3358, + -37.985001 -15.4318 -99.325699, + -37.9743 -15.4581 -99.487701, + -38.271999 -14.7055 -99.076401, + -38.283699 -14.6751 -99.102097, + -28.722 15.8395 -230.01199, + -32.7999 -0.089615889 -230.01199, + -27.8563 -2.83271 -232.01199, + -32.622501 -3.40746 -230.01199, + -32.999901 -0.090161696 -229.812, + -28 7.1240297e-006 -232.01199, + -32.1465 6.5147901 -230.01199, + -32.640701 3.2291501 -230.01199, + -32.342499 6.5545101 -229.812, + -31.5135 9.7929201 -229.812, + -31.3225 9.7335701 -230.01199, + -27.4268 5.6363702 -232.01199, + -27.8563 2.83272 -232.01199, + -31.7987 25.8813 -219.01199, + -17.139 22.141701 -232.01199, + -17.426001 27.788 -230.01199, + -17.532301 27.9575 -229.812, + -39.179199 12.0828 -151.438, + -40.896099 2.91728 -99.134804, + -40.8937 2.95103 -99.171097, + -41 0.045997705 -173.98599, + -41 0.050335802 -150.99001, + -41 0.050542593 -173.985, + -40.932201 -2.3573 -173.94901, + -38.2938 -14.6488 -121.851, + -38.294601 -14.6467 -99.126099, + -39.0406 -12.5233 -150.99001, + -39.0555 -12.4768 -173.976, + -39.038898 -12.5286 -121.986, + -39.038898 -12.5286 -173.98599, + -39.0406 -12.5233 -98.990303, + -39.024899 -12.5721 -121.986, + -38.9939 -12.668 -98.9991, + -39.081299 -12.3957 -173.952, + -39.063999 -12.4501 -121.972, + -39.063999 -12.4501 -173.972, + -39.089401 -12.3702 -151.032, + -39.179199 -12.0828 -99.438301, + -37.3251 -16.965799 -121.804, + -37.3657 -16.8762 -99.351402, + -37.372799 -16.8605 -99.4403, + -37.354198 -16.9016 -99.278603, + -37.363499 -16.8811 -121.64, + -37.3568 -16.895901 -121.678, + -38.147301 -15.0261 -98.990601, + -38.148998 -15.0218 -98.989799, + -38.182598 -14.9362 -121.986, + -38.146999 -15.027 -121.985, + -38.165699 -14.9793 -98.989304, + -38.184101 -14.9323 -98.990097, + -38.146999 -15.027 -173.985, + -38.182598 -14.9362 -173.98599, + -37.0751 17.5054 -173.94901, + -37.071098 17.513901 -151.03, + -36.964298 17.738199 -151.252, + -36.958199 17.7509 -173.69701, + -36.958199 17.7509 -121.697, + -36.964298 17.738199 -99.252098, + -37.2127 17.210899 -173.972, + -37.215302 17.2054 -151.005, + -37.2215 17.1919 -173.965, + -36.701599 18.2756 -49.7397, + -37.033699 17.5928 -173.899, + -37.068401 17.5196 -121.943, + -37.071098 17.513901 -99.029999, + -37.068401 17.5196 -173.94299, + -40.377998 -7.1147799 -164.33299, + -40.367199 -7.1757302 -99.252296, + -40.377602 -7.1170902 -99.4403, + -40.3591 -7.2210302 -173.793, + -40.3708 -7.1553998 -173.67799, + -40.367199 -7.1757302 -151.252, + -40.3773 -7.1187501 -173.537, + -40.377998 -7.1147799 -173.48801, + -40.3769 -7.1210198 -173.564, + -40.377602 -7.1170902 -151.44, + -38.347301 14.5082 -173.58501, + -38.344398 14.5159 -151.351, + -38.350498 14.4997 -99.4403, + -38.349899 14.5013 -121.537, + -38.350498 14.4997 -151.44, + -38.347301 14.5082 -121.585, + -38.344398 14.5159 -99.351402, + -38.351299 14.4975 -99.487701, + -38.351299 14.4975 -121.488, + -38.863499 13.0626 -99.487701, + -39.803501 -9.83253 -99.076401, + -39.8419 -9.6760101 -173.72301, + -39.803101 -9.8343897 -121.9, + -39.803101 -9.8343897 -173.89999, + -39.820599 -9.7633696 -151.134, + -39.833801 -9.7093401 -151.198, + -39.8181 -9.7735395 -173.851, + -39.8181 -9.7735395 -121.851, + -39.820599 -9.7633696 -99.134003, + -40.653702 5.3178401 -121.939, + -40.651001 5.3384099 -151.049, + -40.700199 4.9493799 -121.965, + -40.7001 4.9500499 -99.010101, + -40.688202 5.0469398 -98.990303, + -40.735802 4.6471 -99.252602, + -40.305801 7.51296 -99.0009, + -40.2948 7.5717201 -98.990303, + -40.3591 7.2210398 -173.793, + -40.377998 7.11479 -99.487701, + -40.377602 7.1170998 -99.4403, + -40.329601 7.3840899 -173.927, + -40.3242 7.41365 -151.032, + -40.616001 5.5983701 -99.390503, + -40.615002 5.60567 -99.438904, + -40.651001 5.3384099 -99.048798, + -40.187401 8.1225595 -151.411, + -40.2612 -7.7485199 -99.003899, + -40.2612 -7.7485199 -151.004, + -40.2948 -7.5717101 -98.990303, + -40.253799 -7.7865 -53.118599, + -40.275799 -7.6721702 -150.991, + -40.275902 -7.6715899 -173.985, + -40.305801 -7.5129499 -218, + -40.2938 -7.5771699 -173.98599, + -40.9282 -2.4258001 -121.972, + -40.928398 -2.4224601 -99.004303, + -40.884998 -3.0687799 -173.48801, + -40.804901 -3.9950399 -218.01199, + -40.884998 -3.0687799 -164.33299, + -40.884998 -3.0687799 -99.487701, + -40.884998 -3.0687799 -110.667, + -40.2234 -7.9423299 -173.873, + -40.230999 -7.9038301 -151.07201, + -40.229698 -7.9103899 -173.899, + -40.217499 -7.97223 -173.849, + -40.221401 -7.9520702 -219.01199, + -40.999298 -0.242884 -99.0485, + -40.9995 -0.20830201 -99.030296, + -18.0425 36.887199 7.4547, + -18.082701 36.887199 7.3737502, + -18.8085 37.134201 4.5876999, + -18.972099 36.887199 4.6276002, + -13.2638 33.887199 16.615499, + 4.5043101 41.766602 7.8016901, + 5.5741701 41.8568 6.6430402, + 16.054701 37.689201 9.5180302, + 16.277399 37.5397 9.6500502, + 17.2824 37.689201 7.0474, + 6.901 41.766602 5.7906199, + 7.8016901 41.766602 4.5043101, + 6.6430402 41.8568 5.5741701, + 14.4763 37.689201 11.7807, + 5.7906299 41.766602 6.901, + 4.3359399 41.8568 7.5100598, + 4.1622901 41.887199 7.20929, + 1.44555 41.887199 8.1981001, + 2.8471701 41.887199 7.8225398, + 2.96595 41.8568 8.1488895, + 7.8225398 -41.887199 2.8471701, + 8.1488895 -41.8568 2.96595, + 8.4653301 -41.766602 3.08113, + 4.1622901 -41.887199 7.20929, + 2.8471701 -41.887199 7.8225398, + 1.44555 -41.887199 8.1981001, + 8.1981001 -41.887199 1.44555, + 18.2609 -37.619301 4.4541302, + -8.1941404 -37.4193 17.232901, + -10.6449 -37.4193 15.8368, + -8.3000002 -37.172798 17.455601, + -8.0715103 -37.619301 16.975, + -11.3075 -30.789301 -230.01199, + -8.1842098 -31.969 -229.812, + -11.3765 -30.976999 -229.812, + -4.2399802 -27.677099 -232.01199, + -1.41818 -27.9641 -232.01199, + -8.1346102 -31.775299 -230.01199, + -7.01827 -27.106199 -232.01199, + 4.2399802 -27.677099 -232.01199, + 1.41818 -27.9641 -232.01199, + 17.139 -22.141701 -232.01199, + 12.331 -25.1385 -232.01199, + 7.01827 -27.106199 -232.01199, + 9.7245502 -26.257099 -232.01199, + 5.0553999 -32.4081 -230.01199, + -8.2587439e-007 -26.25 -232.01199, + -17.334 -14.222 -232.01199, + 19.1001 -16.9072 -232.01199, + -19.9335 -4.77601 -232.01199, + -18.9662 17.472099 -232.01199, + -18.7057 17.990801 -232.01199, + -26.735001 -8.3085003 -232.01199, + -26.735001 8.3085098 -232.01199, + -27.4268 -5.6363502 -232.01199, + -26.0842 0.94056302 -232.01199, + -25.4151 -1.6069601 -232.01199, + -26.7159 -8.3821602 -232.01199, + -25.730801 -11.042 -232.01199, + -32.110401 -6.6903501 -230.01199, + -21.245199 -18.2384 -232.01199, + -23.354601 -2.49576 -232.01199, + -18.7057 -17.990801 -232.01199, + -19.9335 -19.618401 -232.01199, + -14.811 -23.761999 -232.01199, + -1.58136 -32.962101 -229.812, + 1.75079 -32.753201 -230.01199, + -1.57178 -32.762299 -230.01199, + 1.76147 -32.9529 -229.812, + -0.98163497 -38.487499 -222.01199, + -4.8703098 -38.190701 -222.01199, + -4.90797 -32.632999 -229.812, + -4.8782201 -32.4352 -230.01199, + -40.9417 2.1865301 -151.13699, + -40.940899 2.2012801 -173.85201, + -40.923599 2.5025599 -98.990303, + -40.8881 3.0276401 -99.296997, + -40.885502 3.06248 -99.411003, + -40.889599 3.00741 -99.252098, + -40.912201 2.6821799 -99.003899, + -38.2938 14.6488 -121.851, + -38.283901 14.6746 -121.873, + -38.294601 14.6467 -99.126099, + -38.298801 14.6357 -99.137398, + -38.283901 14.6746 -173.873, + -38.2938 14.6488 -173.851, + -38.298801 14.6357 -151.13699, + -38.214802 14.8537 -99.005096, + -38.248402 14.7668 -51.211102, + -38.084301 15.1851 -173.939, + -38.090099 15.1706 -151.03, + -38.0602 15.2455 -151.07201, + -38.057701 15.2517 -173.899, + -38.018799 15.3484 -173.804, + -38.018799 15.3484 -121.804, + -38.0313 15.3174 -151.13499, + -38.034199 15.3102 -173.849, + -37.992199 15.4142 -173.69701, + -37.915298 15.6021 -219.01199, + -37.372101 16.862 -173.537, + -37.3657 16.876301 -99.351402, + -37.291698 17.039 -57, + 7.01827 27.106199 -232.01199, + 8.1346102 31.775299 -230.01199, + -5.0553999 32.4081 -230.01199, + -7.01827 27.106199 -232.01199, + -9.7245502 26.257099 -232.01199, + -1.75079 32.753201 -230.01199, + 1.76767 25.6066 -232.01199, + 24.8288 21.432899 -230.01199, + 15.242 18.9986 -232.01199, + 2.3815701 24.875 -232.01199, + 17.296499 16.080099 -232.01199, + 39.2062 27.222601 -202.144, + 39.520199 27.222601 -201.47, + 39.501499 26.986799 -202.064, + 22.6705 23.9802 -229.812, + 29.1255 28.8566 -219.01199, + 26.1751 31.557301 -219.01199, + 22.5331 23.8349 -230.01199, + 20.128099 26.1507 -229.812, + 24.9802 21.563601 -229.812, + -2.8471701 41.887199 7.8225398, + -1.44555 41.887199 8.1981001, + -1.50585 41.8568 8.5401201, + -2.96595 41.8568 8.1488895, + -8.3138355e-007 41.887199 8.3245697, + -4.3359399 41.8568 7.5100598, + -4.1622901 41.887199 7.20929, + -5.3509302 41.887199 6.3769898, + -1.56433 41.766602 8.8717499, + -5.4424701 37.689201 17.8529, + 6.4389 36.887199 18.391001, + 8.3135595 37.134201 17.4841, + -7.1385002 33.887199 20.0156, + 16.6262 -37.172798 9.8568096, + 12.1507 36.887199 15.2203, + 13.1641 36.887199 14.4243, + 14.6771 37.5397 11.9441, + 18.010099 33.887199 11.2979, + 15.8614 33.887199 14.157, + 3.26789 -36.887199 19.2272, + 5.69449 -36.887199 18.6796, + -3.5638399 -33.887199 20.9596, + -5.69449 -36.887199 18.6796, + -2.84922 -37.172798 19.117201, + -2.87869 -36.887199 19.315001, + -5.6361799 -37.172798 18.4884, + -3.26789 -36.887199 19.2272, + -8.3211398e-007 -41.8568 8.6718702, + -1.56433 -41.766602 8.8717499, + -2.72421 -37.766602 18.2784, + -5.3888898 -37.766602 17.6772, + -5.48103 -37.619301 17.979401, + -5.5643001 -37.4193 18.2526, + 5.48102 -37.619301 17.979401, + -37.9753 -15.4557 -173.537, + -37.9949 -15.4075 -121.711, + -37.9753 -15.4557 -121.537, + -38.098499 -15.1494 -51.068501, + -37.0751 -17.5054 -173.94901, + -37.247898 -17.134701 -151.032, + -37.2215 -17.1919 -121.965, + -37.247898 -17.134701 -99.031998, + -37.215302 -17.205299 -99.005096, + -37.2127 -17.210899 -173.972, + -37.2215 -17.1919 -173.965, + -37.18 -17.281401 -173.985, + -37.173698 -17.295099 -150.989, + -37.215302 -17.205299 -151.005, + -37.101601 -17.4492 -173.97, + -37.137199 -17.373301 -98.990601, + -37.104198 -17.443701 -151.004, + -37.137199 -17.373301 -150.991, + -37.1436 -17.3596 -173.987, + -37.1436 -17.3596 -121.987, + -37.173698 -17.295099 -98.988899, + -38.202202 -14.886 -150.99899, + -38.212601 -14.8593 -173.972, + -38.202202 -14.886 -98.998901, + -38.214802 -14.8537 -99.005096, + -36.9394 -17.790001 -151.439, + -36.9394 -17.790001 -99.438904, + -37.0033 -17.6567 -99.134804, + -37.2677 -17.0916 -218, + -24.945601 21.2969 -230.01199, + -22.9814 15.9955 -232.01199, + -26.972099 18.664 -230.01199, + -27.1366 18.7778 -229.812, + -19.2911 20.294201 -232.01199, + -22.801201 23.856001 -229.812, + -25.0977 21.4268 -229.812, + -29.1255 28.8566 -219.01199, + -26.1751 31.557301 -219.01199, + -20.2707 26.0403 -229.812, + -20.1479 25.8825 -230.01199, + -39.089401 12.3702 -151.032, + -39.113201 12.2947 -121.9, + -39.087502 12.3762 -121.946, + -39.089401 12.3702 -99.031998, + -40.946201 2.1005299 -151.25301, + -40.944801 2.1273501 -173.76401, + -40.943802 2.1466 -173.793, + -40.943802 2.1466 -121.793, + -40.946201 2.1005299 -99.252602, + -40.889099 3.0139699 -173.711, + -40.885899 3.0571201 -173.586, + -40.8881 3.0276401 -151.297, + -40.889599 3.00741 -151.252, + -40.904598 2.7957799 -151.049, + -40.904598 2.7957799 -99.048798, + -40.906799 2.7633901 -121.945, + -40.9011 2.8466401 -121.899, + -40.8988 2.8794601 -121.873, + -40.901901 2.8351099 -99.069298, + -40.9011 2.8466401 -173.899, + -40.901901 2.8351099 -151.069, + -40.996799 0.51599002 -173.48801, + -40.996799 0.51599002 -151.48801, + -40.9981 0.39791799 -173.804, + -40.998501 0.354085 -173.851, + -40.997799 0.427158 -173.765, + -40.997501 0.45480001 -173.72301, + -40.998001 0.40808499 -173.793, + -40.999001 0.293268 -151.076, + -40.999298 0.242294 -173.927, + -40.999001 0.29142699 -173.89999, + -40.999001 0.293268 -99.076401, + -40.998501 0.35623199 -151.12601, + -40.998501 -0.356343 -173.849, + -40.999001 -0.29331899 -173.899, + -38.283901 -14.6746 -173.873, + -38.2696 -14.7118 -173.903, + -38.283901 -14.6746 -121.873, + -38.2696 -14.7118 -121.903, + -38.298801 -14.6357 -151.13699, + -38.298801 -14.6357 -99.137398, + -38.313 -14.5984 -173.793, + -38.2938 -14.6488 -173.851, + -38.309299 -14.6082 -151.17101, + -38.309299 -14.6082 -99.171501, + -38.341301 -14.5241 -121.65, + -38.332001 -14.5486 -99.264, + -38.332001 -14.5486 -151.26401, + -38.350498 -14.4997 -151.44, + -38.341301 -14.5241 -173.64999, + -38.350498 -14.4997 -99.4403, + -38.349098 -14.5034 -173.564, + -38.351299 -14.4975 -173.48801, + -38.351299 -14.4975 -164.33299, + -38.867199 -13.0516 -173.586, + -38.863499 -13.0626 -173.48801, + -38.870899 -13.0406 -151.343, + -38.870899 -13.0406 -99.342796, + -38.867199 -13.0516 -121.586, + -38.863499 -13.0626 -164.33299, + -38.863499 -13.0626 -151.48801, + -38.959202 -12.7744 -173.94299, + -39.145 -12.193 -173.804, + -39.1115 -12.3 -99.072197, + -39.123501 -12.2618 -99.102097, + -39.081299 -12.3957 -57, + -39.089401 -12.3702 -99.031998, + -39.163799 -12.1325 -99.264, + -39.178101 -12.0864 -121.564, + -39.178101 -12.0864 -173.564, + -37.311199 -16.9963 -99.134003, + -37.291698 -17.039 -57, + -37.3069 -17.0058 -121.851, + -37.324902 -16.9662 -99.171501, + -37.18 17.281401 -173.985, + -37.173698 17.295099 -150.989, + -37.178001 17.2857 -173.98599, + -37.101601 17.4492 -173.97, + -37.137199 17.373301 -98.990601, + -37.1436 17.3596 -121.987, + -37.173698 17.295099 -98.988899, + -37.2677 17.0916 -57, + -37.104198 17.443701 -99.003899, + -37.1436 17.3596 -173.987, + -37.137199 17.373301 -150.991, + -37.104198 17.443701 -151.004, + -37.001598 17.660299 -121.838, + -37.0033 17.6567 -99.134804, + -37.0387 17.5823 -99.069298, + -37.0387 17.5823 -151.069, + -37.001598 17.660299 -173.838, + -36.976101 17.7136 -99.210899, + -36.976101 17.7136 -151.211, + -40.338402 -7.3358402 -173.89999, + -40.349602 -7.2741799 -121.851, + -40.349602 -7.2741799 -173.851, + -40.742298 -4.5897102 -173.537, + -38.914799 12.909 -151.12399, + -38.936199 12.8442 -173.903, + -38.9375 12.8403 -151.069, + -38.911499 12.9189 -173.842, + -38.891701 12.9784 -99.210899, + -38.880901 13.0108 -121.711, + -38.914799 12.909 -99.1241, + -38.891701 12.9784 -151.211, + -39.024899 12.5721 -173.98599, + -39.841801 -9.6763802 -99.252296, + -39.833801 -9.7093401 -99.197601, + -39.8419 -9.6760101 -121.723, + -39.849701 -9.6438398 -121.65, + -39.8452 -9.6623402 -99.278603, + -39.8549 -9.6223698 -121.564, + -39.6068 -10.5973 -173.62399, + -39.786301 -9.9021101 -151.036, + -39.786301 -9.9021101 -99.036201, + -40.7649 4.3846202 -57, + -40.655701 5.3024802 -151.03, + -40.655701 5.3024802 -99.029999, + -40.662998 5.24611 -99.010902, + -40.653702 5.3178401 -173.939, + -40.688202 5.0469398 -150.99001, + -40.681801 5.0982599 -98.989304, + -40.687099 5.05549 -173.98599, + -40.742298 4.5897198 -173.537, + -40.741501 4.5971799 -151.39, + -40.7425 4.5882702 -99.438499, + -40.7425 4.5882702 -151.438, + -40.741501 4.5970201 -173.58501, + -40.724602 4.7443199 -99.126099, + -40.729401 4.7027702 -173.804, + -40.739601 4.6139498 -121.65, + -40.7402 4.6086302 -99.342598, + -40.741501 4.5971799 -99.390198, + -40.735901 4.6465001 -121.723, + -40.739601 4.6139498 -173.64999, + -40.735901 4.6465001 -173.72301, + -40.303699 7.52422 -150.99899, + -40.305801 7.51296 -173.974, + -40.303699 7.52422 -98.998901, + -40.2938 7.5771899 -173.98599, + -40.285301 7.6220498 -121.986, + -40.285301 7.6220498 -173.98599, + -40.2938 7.5771899 -121.986, + -40.377998 7.11479 -164.33299, + -40.614799 5.6072202 -173.536, + -40.377998 7.11479 -151.48801, + -40.3708 7.1554098 -173.67799, + -40.367199 7.1757398 -151.252, + -40.329601 7.3840899 -121.927, + -40.338402 7.3358598 -173.89999, + -40.349602 7.2742 -173.851, + -40.614799 5.6072202 -121.536, + -40.622799 5.5490499 -151.25301, + -40.629101 5.5027599 -151.18201, + -40.622799 5.5490499 -99.252602, + -40.629101 5.5027599 -99.181999, + -40.620998 5.5622001 -121.697, + -40.630501 5.4920602 -173.804, + -40.634899 5.45963 -173.842, + -40.620998 5.5622001 -173.69701, + -40.639999 5.4215698 -121.873, + -40.639999 5.4215698 -173.873, + -40.645199 5.3823099 -151.07201, + -40.645199 5.3823099 -99.072403, + -40.636299 5.4492402 -99.1241, + -39.602402 10.6138 -121.537, + -39.6017 10.6163 -99.487701, + -39.6124 10.5764 -99.297096, + -39.613998 10.5705 -121.697, + -39.602402 10.6138 -173.537, + -39.6077 10.594 -173.633, + -39.698799 10.2474 -173.97, + -40.190701 8.1061001 -173.633, + -40.1866 8.1264696 -173.535, + -40.195499 8.0822601 -173.69701, + -40.285301 -7.6220398 -121.986, + -40.275799 -7.6721702 -98.990601, + -40.2938 -7.5771699 -121.986, + -40.285301 -7.6220398 -173.98599, + -40.9981 -0.397744 -173.804, + -40.997501 -0.45420399 -173.72301, + -15.8614 33.887199 14.157, + -15.1466 36.887199 12.3262, + 10.4119 37.689201 15.49, + 12.756 37.5397 13.9772, + 12.5815 37.689201 13.786, + 1.50585 41.8568 8.5401201, + -8.3242134e-007 41.8568 8.6718702, + 6.6430402 -41.8568 5.5741701, + 5.3509302 -41.887199 6.3769898, + 6.3769898 -41.887199 5.3509302, + 5.5741701 -41.8568 6.6430402, + 7.20929 -41.887199 4.1622901, + 7.5100598 -41.8568 4.3359399, + 5.7906299 -41.766602 6.901, + 6.901 -41.766602 5.7906199, + 7.8016901 -41.766602 4.5043101, + 2.3815701 -24.875 -232.01199, + 2.1066201 -25.2677 -232.01199, + 19.6339 -19.9335 -232.01199, + -2.0887201 -24.8738 -232.01199, + -40.997898 0.41956401 -151.19701, + -40.997101 0.49105999 -173.64, + -40.997101 0.49105999 -121.64, + -40.996799 0.51599002 -99.487701, + -40.999802 0.13179301 -151.004, + -40.9995 0.209829 -151.03101, + -40.9995 0.209829 -99.030998, + -40.999901 0.100311 -173.976, + -40.949001 2.0451601 -121.564, + -40.947899 2.0671999 -121.65, + -40.9492 2.0411899 -99.4403, + -40.949001 2.0451601 -173.564, + -40.9492 2.0411899 -151.44, + -40.947899 2.0671999 -173.64999, + -40.937 2.27248 -121.906, + -40.937199 2.26844 -99.072304, + -40.937599 2.2611899 -99.076401, + -40.9394 2.2284901 -99.102203, + -40.940899 2.2012801 -121.852, + -40.9417 2.1865301 -99.137398, + -40.9175 2.59991 -98.989799, + -40.922699 2.5169699 -173.98599, + -40.911999 2.6855299 -173.97099, + -40.906799 2.7633901 -173.94501, + -40.917301 2.6029 -173.985, + -40.911999 2.6855299 -121.971, + -40.9175 2.59991 -150.99001, + -38.202202 14.886 -98.998901, + -38.184101 14.9323 -98.990097, + -38.212601 14.8594 -121.972, + -38.182598 14.9362 -173.98599, + -38.212601 14.8594 -173.972, + -37.3568 16.895901 -173.67799, + -37.3657 16.876301 -151.351, + -37.363499 16.8811 -173.64, + -37.2677 17.0916 -218, + -37.312698 16.993099 -151.13699, + -37.3069 17.0058 -173.851, + -37.295399 17.031 -173.873, + -37.295399 17.031 -121.873, + -37.312698 16.993099 -99.137398, + -37.3251 16.9659 -173.804, + -37.3251 16.9659 -121.804, + 1.41818 27.9641 -232.01199, + 4.8782201 32.4352 -230.01199, + 1.57178 32.762299 -230.01199, + 4.2399802 27.677099 -232.01199, + -1.41818 27.9641 -232.01199, + -4.2399802 27.677099 -232.01199, + 18.905701 20.625 -232.01199, + 19.2911 20.294201 -232.01199, + 17.139 22.141701 -232.01199, + 19.6339 19.9335 -232.01199, + 22.9814 15.9955 -232.01199, + 24.481701 13.5885 -232.01199, + 19.9335 19.618401 -232.01199, + 18.9986 17.992001 -232.01199, + 8.3085098 26.701401 -232.01199, + 14.811 23.761999 -232.01199, + -5.69449 36.887199 18.6796, + -7.0268202 33.887199 20.065599, + -6.4389 36.887199 18.391001, + -3.5638399 33.887199 20.9596, + -8.2927312e-007 33.887199 21.260401, + 3.26789 36.887199 19.2272, + 5.69449 36.887199 18.6796, + 3.5638399 33.887199 20.9596, + -9.4268799 36.887199 17.0431, + -10.2909 33.887199 18.6038, + -8.38587 36.887199 17.636101, + -8.3135595 37.134201 17.4841, + 16.168501 -37.619301 9.5854702, + 14.8003 -37.4193 12.0444, + 14.5788 -37.619301 11.8642, + 16.414101 -37.4193 9.7311001, + 14.3338 -37.766602 11.6647, + 15.8967 -37.766602 9.4243402, + 17.112301 -37.766602 6.9780302, + 17.4048 -37.619301 7.0973301, + 17.6693 -37.4193 7.2051702, + 15.016 37.134201 12.2199, + 16.798201 36.887199 9.9587898, + 16.653299 37.134201 9.8729095, + 15.1466 36.887199 12.3262, + 14.8583 37.353298 12.0916, + 13.0506 37.134201 14.3, + 14.5361 36.887199 12.9724, + 8.3000002 -37.172798 17.455601, + 6.4389 -36.887199 18.391001, + 8.38587 -36.887199 17.636101, + 8.1941404 -37.4193 17.232901, + 9.4268799 -36.887199 17.0431, + 10.6449 -37.4193 15.8368, + 10.7825 -37.172798 16.0413, + 10.894 -36.887199 16.2073, + 2.72421 -37.766602 18.2784, + 5.3888898 -37.766602 17.6772, + 1.56433 -41.766602 8.8717499, + -8.2494535e-007 -41.766602 9.0086098, + -8.2472019e-007 -37.766602 18.480301, + 5.5643001 -37.4193 18.2526, + 5.6361799 -37.172798 18.4884, + 2.84922 -37.172798 19.117201, + -38.018799 -15.3484 -173.804, + -38.018799 -15.3484 -121.804, + -37.9949 -15.4075 -173.711, + -37.915298 -15.6021 -219.01199, + -38.116501 -15.1041 -173.97, + -38.034199 -15.3101 -173.849, + -38.058399 -15.2499 -99.0755, + -38.034199 -15.3101 -121.849, + -37.071098 -17.513901 -99.029999, + -37.104198 -17.443701 -99.003899, + -37.2677 -17.0916 -57, + -38.242901 -14.7811 -151.032, + -38.214802 -14.8537 -151.005, + -38.242901 -14.7811 -99.031998, + -38.2374 -14.7953 -173.948, + -38.2537 -14.7531 -173.927, + -38.2537 -14.7531 -121.927, + -36.958199 -17.7509 -121.697, + -37.036598 -17.5867 -151.07201, + -37.036598 -17.5867 -99.072403, + -37.0369 -17.586 -173.903, + -37.071098 -17.513901 -151.03, + -37.0644 -17.528 -173.939, + -36.976101 -17.7136 -151.211, + -37.0033 -17.6567 -151.13499, + -36.976101 -17.7136 -99.210899, + -36.9757 -17.714399 -173.765, + -37.003101 -17.657101 -173.842, + -36.964298 -17.738199 -99.252098, + -36.964298 -17.738199 -151.252, + -36.958199 -17.7509 -173.69701, + -20.625 18.8909 -232.01199, + -21.245199 18.2384 -232.01199, + -22.663 23.711399 -230.01199, + -19.9335 19.618401 -232.01199, + -19.6339 19.9335 -232.01199, + -24.481701 13.5885 -232.01199, + -25.730801 11.042 -232.01199, + -40.617599 -5.5868101 -173.633, + -39.178101 12.0864 -121.564, + -39.178101 12.0864 -173.564, + -39.1516 12.1719 -99.197601, + -39.179199 12.0828 -99.438301, + -39.144901 12.1934 -99.171501, + -39.153702 12.1652 -121.765, + -40.8937 2.9504099 -173.804, + -40.892101 2.97262 -173.778, + -40.8988 2.8794601 -173.873, + -40.8937 2.95103 -151.17101, + -40.999901 -0.10005 -173.97701, + -41 -0.051545307 -173.985, + -41 7.1313016e-006 -219.01199, + -40.999802 -0.1345 -121.97, + -40.9995 -0.212331 -173.94299, + -40.9995 -0.212331 -121.943, + -40.999802 -0.1345 -173.97, + -40.999901 -0.10105399 -98.998901, + -40.999901 -0.101054 -150.99899, + -40.9282 -2.4258001 -173.972, + -40.926498 -2.4540401 -98.998802, + -40.9235 -2.5037701 -150.99001, + -40.926498 -2.4540401 -150.99899, + -38.936199 -12.8442 -173.903, + -39.009399 -12.6201 -173.985, + -38.9939 -12.668 -150.99899, + -39.0107 -12.6162 -150.99001, + -38.983299 -12.7004 -173.97, + -39.024899 -12.5721 -173.98599, + -39.132599 -12.2328 -151.12601, + -39.131901 -12.2349 -173.851, + -39.113201 -12.2947 -173.89999, + -39.132599 -12.2328 -99.126099, + -39.113201 -12.2947 -121.9, + -39.144901 -12.1934 -151.17101, + -39.147999 -12.1834 -173.793, + -39.153702 -12.1651 -173.765, + -39.136101 -12.2216 -151.13699, + -39.153702 -12.1651 -121.765, + -39.144901 -12.1934 -99.171501, + -39.136101 -12.2216 -99.137398, + -40.329601 -7.3840699 -173.927, + -40.7425 -4.5883002 -99.4384, + -40.724602 -4.7444301 -151.12601, + -40.725498 -4.73663 -173.841, + -40.7211 -4.7742901 -151.10201, + -40.7001 -4.9499998 -173.965, + -40.706902 -4.89358 -173.94501, + -38.959202 12.7744 -173.94299, + -38.867199 13.0516 -173.586, + -38.880901 13.0108 -173.711, + -38.870899 13.0406 -151.343, + -38.867199 13.0516 -121.586, + -38.863499 13.0626 -173.48801, + -38.870899 13.0406 -99.342796, + -39.063999 12.4501 -173.972, + -39.063999 12.4501 -121.972, + -39.0555 12.4768 -121.976, + -39.087502 12.3762 -173.94501, + -38.993999 12.6675 -173.97701, + -39.009399 12.6201 -173.985, + -38.983299 12.7004 -173.97, + -39.0107 12.6162 -150.99001, + -38.9939 12.668 -98.9991, + -39.081299 12.3957 -57, + -39.0107 12.6162 -98.989799, + -38.9939 12.668 -150.99899, + -38.963902 12.76 -151.02699, + -39.602402 -10.6138 -173.537, + -39.650501 -10.4325 -173.873, + -39.660702 -10.3938 -173.903, + -39.6605 -10.3946 -99.072403, + -39.680801 -10.3166 -99.029999, + -39.659302 -10.3992 -151.075, + -39.683201 -10.3075 -173.94901, + -39.698799 -10.2473 -121.97, + -39.683201 -10.3075 -121.949, + -39.676899 -10.3317 -121.939, + -39.676899 -10.3317 -173.939, + -39.7435 -10.0725 -173.98599, + -39.700298 -10.2415 -151.004, + -39.698799 -10.2473 -173.97, + -40.662998 5.2460098 -173.965, + -40.676102 5.1437302 -150.99001, + -40.681801 5.0982599 -150.989, + -40.676102 5.1437302 -98.989799, + -40.675701 5.1466999 -173.985, + -40.662998 5.24611 -151.011, + -40.665199 5.2288399 -173.97099, + -40.7164 4.8141198 -99.072304, + -40.708801 4.8780999 -99.036201, + -40.7211 4.7743902 -151.10201, + -40.724602 4.7443199 -151.12601, + -40.7211 4.7743902 -99.102203, + -40.716499 4.8134198 -121.903, + -40.725498 4.7363901 -173.84, + -40.2612 7.7485399 -151.004, + -40.259998 7.7544999 -173.97, + -40.275902 7.6715999 -173.985, + -40.275799 7.6721802 -150.991, + -40.275799 7.6721802 -98.990601, + -40.205002 8.0348301 -173.778, + -40.2159 7.9802799 -173.842, + -40.198299 8.06845 -151.252, + -40.207401 8.0229702 -151.18201, + -40.3773 7.1187701 -173.537, + -40.377602 7.1170998 -151.44, + -40.377998 7.11479 -173.48801, + -40.3769 7.1210299 -173.564, + -40.305801 7.51296 -218, + -40.337399 7.34131 -99.072197, + -40.3242 7.41365 -99.031998, + -40.323898 7.4148698 -53.185299, + -40.338402 7.3358598 -121.9, + -40.349998 7.2719402 -99.126099, + -40.349602 7.2742 -121.851, + -39.791302 9.8819904 -121.927, + -39.803101 9.8344002 -121.9, + -39.786301 9.9021301 -151.036, + -39.791302 9.8819904 -173.927, + -39.786301 9.9021301 -99.036201, + -39.855801 9.6185102 -151.44, + -39.8549 9.6223898 -173.564, + -39.803101 9.8344002 -173.89999, + -39.849701 9.6438599 -121.65, + -39.632099 10.5022 -99.171204, + -39.624599 10.5305 -99.210899, + -39.624401 10.5314 -173.765, + -39.624401 10.5314 -121.765, + -39.632198 10.5019 -173.804, + -39.613998 10.5705 -173.69701, + -39.255199 11.8334 -219.01199, + -39.658798 10.4011 -173.899, + -40.996799 -0.515975 -173.48801, + -40.997101 -0.49105501 -151.336, + -40.933601 -2.33286 -151.036, + -40.932201 -2.35746 -99.026497, + -40.932201 -2.35746 -151.02699, + -40.933601 -2.33286 -99.036201, + -40.917198 -2.60502 -150.991, + -40.998001 -0.40807599 -151.18201, + -40.9981 -0.39817199 -151.17101, + -13.0506 37.134201 14.3, + -14.5361 36.887199 12.9724, + -13.1641 36.887199 14.4243, + -10.894 36.887199 16.2073, + -18.611 37.353298 4.5395198, + -15.016 37.134201 12.2199, + -16.798201 36.887199 9.9587898, + -10.4119 37.689201 15.49, + -5.7906299 41.766602 6.901, + -4.5043101 41.766602 7.8016901, + -8.0147305 37.689201 16.8556, + 10.6867 37.353298 15.8988, + 10.8001 37.134201 16.0676, + 12.9136 37.353298 14.1498, + 10.5563 37.5397 15.7049, + 8.2262497 37.353298 17.300501, + 5.64539 37.134201 18.5186, + -40.998402 0.36752799 -99.136803, + -40.998501 0.35623199 -99.125999, + -40.998402 0.36752799 -151.13699, + -40.997898 0.41956401 -99.196999, + -40.999901 0.100154 -98.998802, + -40.999802 0.13179301 -99.004303, + -40.999901 0.100311 -121.976, + -41 0.050542604 -121.985, + -41 0.050335802 -98.990196, + -41 7.1290742e-006 -57, + -40.926498 2.4541399 -98.998901, + -40.932201 2.35747 -99.026703, + -40.929401 2.4051099 -99.010101, + -40.922699 2.5169699 -57, + -40.922699 2.5169699 -218, + -38.146999 15.027 -121.985, + -38.182598 14.9362 -121.986, + -38.146999 15.027 -173.985, + -38.165699 14.9793 -98.989304, + -38.147301 15.0262 -98.990601, + -38.116501 15.1041 -121.97, + -38.116501 15.1041 -173.97, + -3.26789 36.887199 19.2272, + -5.64539 37.134201 18.5186, + -5.5179501 37.5397 18.1005, + -5.5861001 37.353298 18.3241, + -2.8538699 37.134201 19.1485, + -2.87869 36.887199 19.315001, + -8.3450527e-007 36.887199 19.528299, + 2.8538699 37.134201 19.1485, + 2.87869 36.887199 19.315001, + -2.7512901 37.689201 18.460199, + -8.2261101e-007 41.766602 9.0086098, + -2.7894499 37.5397 18.7162, + -8.2467113e-007 -37.4193 19.0819, + -8.2790194e-007 -37.619301 18.796301, + 2.7707801 -37.619301 18.591, + 2.81288 -37.4193 18.8734, + -8.3467893e-007 -37.172798 19.3284, + -2.81288 -37.4193 18.8734, + -2.7707801 -37.619301 18.591, + -38.0602 -15.2454 -151.07201, + -38.057701 -15.2516 -173.899, + -38.084301 -15.1851 -173.939, + -38.058399 -15.2499 -151.075, + -38.090099 -15.1706 -151.03, + -38.0602 -15.2454 -99.072403, + -38.090099 -15.1706 -99.029999, + -40.644299 -5.3889999 -173.899, + -40.639999 -5.4214702 -173.873, + -40.615002 -5.60572 -173.549, + -39.153702 12.1652 -173.765, + -39.081299 12.3957 -218, + -39.113201 12.2947 -173.89999, + -38.911499 -12.9189 -173.842, + -38.914799 -12.909 -151.12399, + -38.914799 -12.909 -99.1241, + -40.349998 -7.2719302 -99.126099, + -40.3242 -7.41364 -99.031998, + -40.3242 -7.41364 -151.032, + -40.329601 -7.3840699 -121.927, + -40.337399 -7.34129 -99.072197, + -40.338402 -7.3358402 -121.9, + -40.741501 -4.5970402 -173.58501, + -40.7425 -4.5883002 -151.438, + -40.725899 -4.7332101 -99.136803, + -40.724602 -4.7444301 -99.125999, + -38.949799 12.8029 -99.048798, + -38.959202 12.7744 -121.943, + -38.963902 12.76 -99.027, + -38.9375 12.8403 -99.069298, + -38.900002 12.9533 -57, + -39.0555 12.4768 -173.976, + -39.038898 12.5287 -121.986, + -39.0406 12.5234 -98.990303, + -39.0247 12.5728 -98.989304, + -39.0247 12.5728 -150.989, + -39.038898 12.5287 -173.98599, + -39.0406 12.5234 -150.99001, + -39.255199 -11.8334 -219.01199, + -39.659302 -10.3992 -99.0755, + -39.650398 -10.4331 -151.103, + -39.7687 -9.9725904 -151.00999, + -39.763699 -9.9925404 -173.972, + -39.780399 -9.9258499 -173.948, + -39.780399 -9.9258499 -121.948, + -39.700298 -10.2415 -99.003899, + -39.720798 -10.1616 -98.989799, + -39.7449 -10.0671 -98.990303, + -39.7449 -10.0671 -150.99001, + -39.7234 -10.1516 -173.987, + -39.7234 -10.1516 -121.987, + -39.732101 -10.1174 -98.989304, + -39.763699 -9.9925404 -121.972, + -40.062199 -8.7189398 -57, + -39.7687 -9.9725904 -99.010101, + -40.716499 4.8134198 -173.903, + -40.804901 3.99505 -219.01199, + -40.707699 4.8873401 -151.032, + -40.707699 4.8873401 -99.031998, + -40.700199 4.9493799 -173.965, + -40.708801 4.8780999 -151.036, + -40.707199 4.8913398 -173.94501, + -40.7113 4.8569999 -173.927, + -40.248199 7.8155699 -121.949, + -40.2612 7.7485399 -99.003899, + -40.2481 7.81603 -99.027, + -40.239498 7.8601799 -173.92799, + -40.248199 7.8155699 -173.94901, + -40.229698 7.9104099 -173.899, + -40.2159 7.9802799 -121.842, + -40.194302 8.0883303 -99.297096, + -40.194302 8.0883303 -151.297, + -40.187401 8.1225595 -99.411003, + -40.198299 8.06845 -99.252098, + -39.7687 9.9726105 -151.00999, + -39.763699 9.9925499 -121.972, + -39.7687 9.9726105 -99.010101, + -39.780399 9.9258699 -173.948, + -39.780399 9.9258699 -121.948, + -39.732101 10.1174 -98.989304, + -39.698799 10.2474 -121.97, + -39.720798 10.1616 -98.989799, + -39.700298 10.2415 -99.003899, + -39.7449 10.0671 -150.99001, + -39.763699 9.9925499 -173.972, + -39.7449 10.0671 -98.990303, + -39.7435 10.0725 -173.98599, + -39.7234 10.1516 -173.987, + -39.7234 10.1516 -121.987, + -39.8549 9.6223898 -121.564, + -39.841801 9.6763897 -99.252296, + -39.849701 9.6438599 -173.64999, + -39.650398 10.4331 -99.1026, + -39.683201 10.3076 -173.94901, + -39.659302 10.3992 -151.075, + -39.650398 10.4331 -151.103, + -40.998501 -0.353322 -99.123398, + -40.9981 -0.39817199 -99.171402, + -40.998501 -0.356343 -121.849, + -40.999001 -0.29331899 -121.899, + -40.999001 -0.28677499 -99.072701, + -40.996799 -0.515975 -121.488, + -40.996799 -0.515975 -164.33299, + -40.996799 -0.515975 -99.487701, + -40.9394 -2.22839 -99.102303, + -40.937 -2.2727799 -121.906, + -40.937599 -2.26124 -99.076401, + -40.941502 -2.1900401 -99.134003, + -40.949299 -2.03882 -99.487701, + -40.940899 -2.20051 -173.851, + -40.941502 -2.1900401 -151.134, + -40.937 -2.2727799 -173.90601, + -40.949001 -2.04514 -173.564, + -40.949299 -2.03882 -173.48801, + -40.920399 -2.5538299 -173.98599, + -40.9118 -2.68823 -121.97, + -40.917198 -2.60502 -98.990799, + -40.9118 -2.68823 -173.97, + -40.885502 -3.0624599 -99.411003, + -40.885201 -3.0664201 -121.535, + -40.885201 -3.0664201 -173.535, + -40.892101 -2.9731901 -121.778, + -40.8881 -3.02773 -151.297, + -40.889599 -3.00717 -173.72301, + -40.8881 -3.02773 -99.297203, + -40.886501 -3.04917 -173.62399, + -40.885899 -3.0572701 -173.58501, + -40.885899 -3.0572701 -121.585, + -10.6867 37.353298 15.8988, + -10.5563 37.5397 15.7049, + -10.8001 37.134201 16.0676, + -8.2262497 37.353298 17.300501, + -16.653299 37.134201 9.8729095, + -17.9268 37.134201 7.3101702, + -17.738501 37.353298 7.2333999, + -6.901 41.766602 5.7906199, + 5.4424701 37.689201 17.8529, + 1.56433 41.766602 8.8717499, + 3.08113 41.766602 8.4653301, + 8.0147305 37.689201 16.8556, + 8.1258898 37.5397 17.089399, + 2.7894499 37.5397 18.7162, + 5.5179501 37.5397 18.1005, + 2.7512901 37.689201 18.460199, + 5.5861001 37.353298 18.3241, + -8.3373925e-007 37.689201 18.664101, + -40.933102 2.3420501 -151.032, + -40.934799 2.3115499 -173.927, + -40.932201 2.35672 -173.94901, + -40.928101 2.4277899 -173.972, + -40.937 2.27248 -173.90601, + -40.933102 2.3420501 -99.031998, + -40.928101 2.4277899 -121.972, + -8.2980688e-007 37.353298 19.156601, + -8.3164207e-007 37.5397 18.922899, + -2.8239 37.353298 18.947399, + -8.3196892e-007 37.134201 19.360001, + 2.8239 37.353298 18.947399, + -40.630402 -5.4929299 -99.171402, + -40.636002 -5.4514799 -121.849, + -40.630402 -5.4929299 -151.17101, + -40.621899 -5.55551 -173.711, + -40.622799 -5.5490599 -151.25301, + -40.636002 -5.4514799 -173.849, + -40.619999 -5.5694799 -173.679, + -40.639999 -5.4214702 -121.873, + -40.636398 -5.4484801 -99.123398, + -40.688099 -5.0479398 -173.985, + -39.136101 12.2216 -151.13699, + -39.136101 12.2216 -99.137398, + -39.123501 12.2619 -99.102097, + -39.123501 12.2619 -151.10201, + -39.145 12.1931 -121.804, + -39.145 12.1931 -173.804, + -39.131901 12.235 -173.851, + -38.880901 -13.0107 -173.711, + -38.893902 -12.9717 -121.778, + -38.880901 -13.0107 -121.711, + -38.893902 -12.9717 -173.778, + -38.878601 -13.0176 -121.697, + -38.878601 -13.0176 -173.69701, + -39.081299 -12.3957 -218, + -40.739601 -4.6139398 -121.65, + -39.6124 -10.5764 -151.297, + -39.602402 -10.6138 -121.537, + -39.6017 -10.6163 -99.487701, + -40.2234 7.9423499 -121.873, + -40.2234 7.9423499 -173.873, + -40.217499 7.97225 -173.849, + -40.230999 7.9038401 -151.07201, + -40.217899 7.9699998 -99.1241, + -40.217499 7.97225 -121.849, + -40.230999 7.9038401 -99.072403, + -40.207401 8.0229702 -99.181999, + -40.305801 7.51296 -57, + -39.846802 9.6557198 -99.296501, + -39.855801 9.6185102 -99.4403, + -40.062199 8.7189503 -57, + -39.8452 9.6623497 -99.278603, + -39.820599 9.7633801 -99.134003, + -39.8181 9.7735596 -121.851, + -39.830898 9.7210999 -173.793, + -40.221401 7.9520798 -219.01199, + -39.833801 9.7093496 -151.198, + -39.8419 9.6760302 -121.723, + -39.833801 9.7093496 -99.197601, + -39.8419 9.6760302 -173.72301, + -39.820599 9.7633801 -151.134, + -39.8181 9.7735596 -173.851, + -39.6605 10.3946 -99.072403, + -39.680801 10.3166 -99.029999, + -39.683201 10.3076 -121.949, + -39.659302 10.3992 -99.0755, + -39.458599 11.1364 -52.362202, + -40.999599 -0.18254299 -53.827999, + -40.997799 -0.428215 -121.765, + -40.997101 -0.49105501 -99.3358, + -40.997799 -0.428215 -173.765, + -40.997501 -0.45480999 -99.252602, + -40.997799 -0.42734301 -99.211098, + -40.998001 -0.40807599 -99.181999, + -40.9492 -2.04128 -151.44, + -40.9492 -2.04128 -99.439598, + -40.943802 -2.14659 -173.793, + -40.922699 -2.5169599 -218, + -40.922699 -2.5169599 -98.989899, + -40.920399 -2.5538299 -121.986, + -40.922699 -2.5169599 -173.98599, + -40.9235 -2.5037701 -98.990196, + -17.2824 37.689201 7.0474, + -16.054701 37.689201 9.5180302, + -17.5221 37.5397 7.1451502, + -7.8016901 41.766602 4.5043101, + -8.4653301 41.766602 3.08113, + -18.1325 37.689201 4.4227901, + -18.384001 37.5397 4.4841399, + -14.6771 37.5397 11.9441, + -12.9136 37.353298 14.1498, + -14.8583 37.353298 12.0916, + -12.756 37.5397 13.9772, + -14.4763 37.689201 11.7807, + -16.277399 37.5397 9.6500502, + -12.5815 37.689201 13.786, + -16.478399 37.353298 9.7692299, + -40.614799 -5.60712 -173.537, + -40.377998 -7.1147799 -99.487701, + -40.619999 -5.5694799 -121.679, + -40.615002 -5.60572 -121.549, + -40.614799 -5.60712 -121.537, + -40.614399 -5.6096601 -99.487701, + -40.305801 -7.5129499 -57, + -40.645802 -5.37779 -99.069099, + -40.650902 -5.3390002 -99.0485, + -40.645802 -5.37779 -151.069, + -40.6754 -5.14923 -121.985, + -40.665901 -5.2235398 -99.002998, + -40.6754 -5.1488099 -98.990799, + -40.677399 -5.13343 -121.987, + -40.6754 -5.14923 -173.985, + -40.677399 -5.13343 -173.987, + -40.896099 -2.9175301 -151.13499, + -40.8988 -2.87936 -173.873, + -40.8937 -2.95086 -173.804, + -40.892101 -2.9731901 -173.778, + -40.922699 -2.5169599 -57, + -40.736599 -4.6403298 -99.264, + -40.7374 -4.6333199 -99.278198, + -39.613998 -10.5704 -173.69701, + -39.650398 -10.4331 -99.1026, + -39.632198 -10.5019 -121.804, + -39.632198 -10.5019 -173.804, + -39.624401 -10.5313 -173.765, + -40.943802 -2.14659 -121.793, + -40.944401 -2.1351199 -99.196999, + -40.616001 -5.5983901 -99.390602, + -40.622799 -5.5490599 -99.252602, + -40.615002 -5.60567 -99.438904, + -40.6549 -5.3087101 -121.943, + -40.655399 -5.3047099 -99.030296, + -40.664902 -5.2315202 -121.97, + -40.653702 -5.3179302 -121.939, + -40.664902 -5.2315202 -173.97, + -40.6549 -5.3087101 -173.94299, + -40.653702 -5.3179302 -173.939, + -40.688099 -5.0479398 -121.985, + -40.687901 -5.0494699 -98.989998, + -40.9016 -2.8394499 -173.903, + -40.906898 -2.7618699 -151.03, + -40.910801 -2.7035301 -151.011, + -40.905998 -2.7751701 -173.939, + -40.910801 -2.7035301 -99.010803, + -40.7374 -4.6333199 -151.278, + -40.739601 -4.6139398 -173.64999, + -40.804901 -3.9950399 -219.01199, + -39.629501 -10.512 -99.181999, + -39.624599 -10.5305 -99.210899, + -39.350101 -11.5141 -52.258999, + -39.632099 -10.5022 -99.171204, + -39.617699 -10.5565 -121.723, + -39.613998 -10.5704 -121.697, + -39.617699 -10.5565 -173.72301, + -39.624401 -10.5313 -121.765, + -39.6124 -10.5764 -99.297096, + -40.946201 -2.1002901 -121.723, + -40.944801 -2.1275401 -173.765, + -40.946201 -2.1002901 -173.72301, + -40.944801 -2.1275401 -121.765, + -40.946899 -2.0866799 -99.278198, + -40.947899 -2.0671999 -121.65, + -40.947899 -2.0671999 -173.64999, + -40.7001 -4.9500999 -151.00999, + -40.698002 -4.9672999 -99.004303, + -40.697601 -4.9706302 -121.972, + -40.697601 -4.9706302 -173.972, + -40.9011 -2.8466899 -121.899, + -40.896099 -2.9175301 -99.135201, + -40.901501 -2.8401599 -99.072701, + -40.8988 -2.87936 -121.873, + -40.9011 -2.8466899 -173.899, + -40.904598 -2.79583 -121.928, + -40.9016 -2.8394499 -121.903, + -40.904598 -2.79583 -173.92799, + -40.905998 -2.7751701 -121.939, + -40.906898 -2.7618699 -99.030296, + -40.7328 -4.67349 -151.21001, + -40.735901 -4.6465101 -173.72301, + -40.729401 -4.7030201 -173.804, + -40.729401 -4.7030201 -121.804, + -40.7328 -4.67349 -99.210098, + -40.735901 -4.6465101 -121.723, + -40.708801 -4.8782001 -151.036, + -40.7159 -4.81845 -173.90601, + -40.7159 -4.81845 -121.906, + -40.7211 -4.7742901 -99.102303, + -40.707401 -4.8898201 -99.030998, + -40.7001 -4.9500999 -99.010201, + -40.707401 -4.8898201 -151.03101, + -40.708801 -4.8782001 -99.036201, + -40.7649 -4.3846102 -57 ] + + } + coordIndex [ 28, 0, 816, -1, 6, 37, 30, -1, + 13, 96, 337, -1, 5, 337, 914, -1, + 433, 4, 5, -1, 433, 13, 4, -1, + 95, 337, 96, -1, 95, 97, 337, -1, + 921, 337, 97, -1, 733, 1110, 119, -1, + 275, 85, 108, -1, 113, 108, 85, -1, + 765, 119, 1110, -1, 15, 119, 118, -1, + 1, 28, 105, -1, 1, 0, 28, -1, + 29, 816, 0, -1, 29, 1, 105, -1, + 29, 0, 1, -1, 68, 842, 31, -1, + 23, 21, 816, -1, 23, 816, 2, -1, + 23, 139, 549, -1, 23, 1211, 105, -1, + 23, 549, 1211, -1, 9, 2, 816, -1, + 9, 139, 23, -1, 9, 23, 2, -1, + 335, 914, 337, -1, 562, 72, 563, -1, + 168, 76, 43, -1, 168, 43, 236, -1, + 44, 72, 11, -1, 3, 337, 5, -1, + 3, 5, 4, -1, 3, 13, 337, -1, + 3, 4, 13, -1, 47, 5, 914, -1, + 47, 433, 5, -1, 93, 921, 97, -1, + 132, 131, 438, -1, 104, 456, 144, -1, + 122, 120, 733, -1, 465, 275, 108, -1, + 1154, 15, 118, -1, 1796, 2038, 368, -1, + 312, 236, 49, -1, 312, 49, 50, -1, + 61, 40, 1173, -1, 153, 313, 19, -1, + 25, 816, 26, -1, 53, 37, 6, -1, + 53, 6, 29, -1, 65, 29, 6, -1, + 65, 6, 277, -1, 276, 6, 30, -1, + 276, 277, 6, -1, 276, 30, 66, -1, + 138, 139, 33, -1, 34, 139, 820, -1, + 34, 33, 139, -1, 821, 820, 8, -1, + 821, 8, 816, -1, 7, 816, 8, -1, + 7, 9, 816, -1, 7, 8, 820, -1, + 7, 820, 139, -1, 7, 139, 9, -1, + 703, 70, 134, -1, 35, 37, 36, -1, + 35, 30, 37, -1, 35, 280, 30, -1, + 35, 131, 280, -1, 42, 11, 72, -1, + 42, 72, 562, -1, 721, 236, 43, -1, + 664, 82, 373, -1, 79, 82, 76, -1, + 12, 43, 76, -1, 12, 76, 10, -1, + 83, 76, 82, -1, 83, 10, 76, -1, + 83, 44, 11, -1, 83, 42, 43, -1, + 83, 11, 42, -1, 83, 43, 12, -1, + 83, 12, 10, -1, 80, 79, 76, -1, + 398, 209, 218, -1, 111, 113, 85, -1, + 111, 85, 112, -1, 92, 96, 13, -1, + 92, 13, 433, -1, 92, 433, 100, -1, + 409, 91, 187, -1, 48, 47, 914, -1, + 48, 914, 916, -1, 48, 916, 918, -1, + 219, 87, 419, -1, 422, 419, 424, -1, + 712, 921, 93, -1, 52, 105, 104, -1, + 52, 104, 144, -1, 52, 144, 53, -1, + 240, 733, 120, -1, 240, 120, 242, -1, + 55, 108, 113, -1, 339, 765, 1110, -1, + 14, 119, 15, -1, 14, 1154, 119, -1, + 14, 15, 1154, -1, 17, 119, 1154, -1, + 17, 1154, 16, -1, 248, 16, 1154, -1, + 248, 733, 119, -1, 248, 119, 17, -1, + 248, 17, 16, -1, 251, 252, 123, -1, + 272, 117, 56, -1, 272, 56, 125, -1, + 498, 149, 160, -1, 1162, 1796, 368, -1, + 18, 40, 236, -1, 18, 236, 312, -1, + 18, 312, 40, -1, 60, 236, 40, -1, + 60, 40, 61, -1, 649, 61, 1173, -1, + 649, 2037, 61, -1, 845, 844, 842, -1, + 837, 31, 842, -1, 837, 441, 31, -1, + 154, 153, 19, -1, 154, 19, 313, -1, + 39, 313, 153, -1, 39, 312, 313, -1, + 20, 816, 21, -1, 20, 22, 816, -1, + 20, 21, 23, -1, 20, 23, 22, -1, + 27, 26, 816, -1, 27, 816, 22, -1, + 27, 22, 23, -1, 27, 23, 105, -1, + 24, 25, 26, -1, 24, 26, 27, -1, + 24, 28, 816, -1, 24, 816, 25, -1, + 24, 105, 28, -1, 24, 27, 105, -1, + 54, 29, 105, -1, 54, 53, 29, -1, + 817, 816, 29, -1, 817, 29, 65, -1, + 281, 66, 30, -1, 281, 30, 280, -1, + 517, 276, 66, -1, 103, 68, 31, -1, + 103, 31, 441, -1, 547, 842, 68, -1, + 32, 138, 33, -1, 32, 33, 34, -1, + 32, 69, 138, -1, 32, 842, 547, -1, + 32, 547, 69, -1, 32, 845, 842, -1, + 32, 34, 820, -1, 32, 820, 845, -1, + 701, 70, 703, -1, 38, 35, 36, -1, + 38, 36, 142, -1, 38, 438, 131, -1, + 38, 131, 35, -1, 141, 1094, 720, -1, + 143, 142, 36, -1, 143, 36, 37, -1, + 143, 37, 53, -1, 143, 53, 144, -1, + 717, 141, 720, -1, 717, 142, 141, -1, + 717, 438, 38, -1, 717, 38, 142, -1, + 579, 710, 708, -1, 257, 163, 149, -1, + 1266, 1615, 164, -1, 1862, 1867, 1082, -1, + 355, 149, 163, -1, 1012, 39, 153, -1, + 1012, 152, 631, -1, 1012, 40, 312, -1, + 1012, 312, 39, -1, 1012, 1362, 1186, -1, + 1012, 1173, 40, -1, 1012, 1186, 1173, -1, + 41, 43, 42, -1, 41, 42, 562, -1, + 41, 721, 43, -1, 41, 562, 721, -1, + 170, 173, 80, -1, 2021, 2018, 1736, -1, + 2021, 1736, 2037, -1, 666, 82, 664, -1, + 78, 373, 82, -1, 81, 44, 83, -1, + 81, 72, 44, -1, 81, 127, 72, -1, + 198, 209, 398, -1, 106, 87, 48, -1, + 106, 48, 918, -1, 244, 237, 245, -1, + 244, 203, 237, -1, 244, 112, 85, -1, + 244, 85, 203, -1, 238, 402, 535, -1, + 45, 187, 84, -1, 45, 84, 409, -1, + 45, 409, 187, -1, 46, 433, 47, -1, + 46, 219, 433, -1, 46, 47, 48, -1, + 46, 48, 87, -1, 46, 87, 219, -1, + 194, 419, 87, -1, 194, 87, 195, -1, + 208, 184, 187, -1, 208, 209, 200, -1, + 208, 200, 184, -1, 88, 91, 409, -1, + 88, 409, 89, -1, 88, 208, 91, -1, + 225, 711, 720, -1, 225, 720, 1094, -1, + 719, 720, 711, -1, 923, 712, 93, -1, + 923, 93, 102, -1, 923, 719, 711, -1, + 923, 102, 719, -1, 435, 409, 84, -1, + 101, 102, 93, -1, 101, 228, 234, -1, + 694, 228, 695, -1, 694, 234, 228, -1, + 315, 49, 236, -1, 315, 50, 49, -1, + 315, 312, 50, -1, 445, 64, 446, -1, + 445, 63, 64, -1, 51, 105, 52, -1, + 51, 52, 53, -1, 51, 54, 105, -1, + 51, 53, 54, -1, 915, 918, 917, -1, + 915, 106, 918, -1, 732, 108, 55, -1, + 732, 55, 460, -1, 1107, 110, 1559, -1, + 1107, 460, 110, -1, 109, 110, 460, -1, + 109, 55, 113, -1, 109, 460, 55, -1, + 1112, 1559, 110, -1, 124, 56, 117, -1, + 124, 125, 56, -1, 57, 1154, 118, -1, + 57, 118, 58, -1, 57, 58, 1154, -1, + 116, 1154, 58, -1, 116, 58, 118, -1, + 783, 120, 122, -1, 471, 249, 251, -1, + 471, 123, 470, -1, 471, 251, 123, -1, + 268, 127, 81, -1, 268, 81, 378, -1, + 59, 1154, 115, -1, 59, 272, 1154, -1, + 59, 115, 117, -1, 59, 117, 272, -1, + 487, 269, 252, -1, 501, 149, 498, -1, + 342, 498, 160, -1, 157, 346, 368, -1, + 129, 1162, 368, -1, 62, 364, 168, -1, + 62, 168, 236, -1, 62, 236, 60, -1, + 62, 60, 61, -1, 363, 2037, 1736, -1, + 363, 61, 2037, -1, 363, 62, 61, -1, + 363, 364, 62, -1, 279, 281, 280, -1, + 286, 134, 70, -1, 201, 289, 288, -1, + 201, 135, 202, -1, 690, 202, 135, -1, + 133, 441, 837, -1, 1278, 1277, 137, -1, + 1278, 63, 445, -1, 1278, 137, 446, -1, + 1278, 446, 64, -1, 1278, 64, 63, -1, + 811, 291, 294, -1, 283, 286, 70, -1, + 302, 137, 1277, -1, 818, 65, 277, -1, + 818, 817, 65, -1, 824, 66, 281, -1, + 824, 281, 519, -1, 824, 519, 1205, -1, + 278, 517, 66, -1, 278, 824, 823, -1, + 278, 66, 824, -1, 67, 68, 103, -1, + 67, 547, 68, -1, 67, 548, 547, -1, + 67, 103, 439, -1, 67, 439, 550, -1, + 67, 550, 548, -1, 545, 138, 69, -1, + 545, 69, 547, -1, 295, 701, 702, -1, + 295, 70, 701, -1, 295, 283, 70, -1, + 458, 1094, 141, -1, 73, 563, 72, -1, + 73, 321, 563, -1, 71, 72, 127, -1, + 71, 127, 321, -1, 71, 73, 72, -1, + 71, 321, 73, -1, 566, 321, 557, -1, + 556, 323, 557, -1, 319, 327, 560, -1, + 588, 146, 332, -1, 147, 590, 332, -1, + 983, 598, 1346, -1, 2120, 1346, 598, -1, + 2120, 1862, 158, -1, 943, 1588, 623, -1, + 943, 623, 991, -1, 943, 991, 948, -1, + 150, 492, 257, -1, 150, 149, 501, -1, + 150, 501, 492, -1, 341, 494, 495, -1, + 606, 1183, 152, -1, 612, 1862, 1082, -1, + 2117, 1082, 1069, -1, 350, 160, 149, -1, + 350, 149, 355, -1, 1269, 355, 164, -1, + 1269, 1588, 355, -1, 354, 355, 163, -1, + 1517, 152, 1183, -1, 1517, 631, 152, -1, + 1517, 1362, 165, -1, 639, 1186, 640, -1, + 639, 1173, 1186, -1, 74, 153, 152, -1, + 74, 1012, 153, -1, 74, 152, 1012, -1, + 1835, 648, 1183, -1, 1035, 1036, 1034, -1, + 1035, 1677, 1036, -1, 1627, 155, 2037, -1, + 1627, 2037, 1688, -1, 366, 173, 170, -1, + 366, 368, 2038, -1, 366, 2038, 173, -1, + 75, 76, 168, -1, 75, 80, 76, -1, + 75, 170, 80, -1, 75, 168, 169, -1, + 75, 169, 170, -1, 1744, 2021, 2037, -1, + 1896, 2018, 2021, -1, 171, 2021, 1746, -1, + 171, 1746, 2026, -1, 156, 1450, 2037, -1, + 77, 1877, 176, -1, 77, 657, 1877, -1, + 77, 176, 1082, -1, 77, 1082, 657, -1, + 172, 373, 78, -1, 172, 82, 79, -1, + 172, 78, 82, -1, 172, 80, 173, -1, + 172, 79, 80, -1, 2162, 2074, 1066, -1, + 2162, 2117, 1377, -1, 2088, 668, 2038, -1, + 377, 81, 261, -1, 377, 378, 81, -1, + 380, 261, 81, -1, 380, 82, 666, -1, + 380, 83, 82, -1, 380, 81, 83, -1, + 383, 387, 177, -1, 178, 1069, 1082, -1, + 181, 184, 200, -1, 186, 84, 187, -1, + 186, 435, 84, -1, 186, 399, 435, -1, + 188, 703, 134, -1, 188, 134, 682, -1, + 188, 398, 218, -1, 188, 682, 398, -1, + 699, 188, 218, -1, 216, 217, 218, -1, + 214, 218, 217, -1, 214, 729, 191, -1, + 196, 211, 218, -1, 199, 398, 200, -1, + 685, 289, 201, -1, 407, 406, 405, -1, + 407, 85, 275, -1, 407, 275, 406, -1, + 407, 203, 85, -1, 401, 514, 206, -1, + 401, 535, 402, -1, 204, 238, 237, -1, + 204, 402, 238, -1, 246, 737, 462, -1, + 86, 106, 107, -1, 86, 107, 214, -1, + 86, 214, 195, -1, 86, 195, 87, -1, + 86, 87, 106, -1, 221, 88, 89, -1, + 221, 208, 88, -1, 221, 215, 218, -1, + 221, 218, 212, -1, 223, 412, 415, -1, + 223, 89, 409, -1, 223, 221, 89, -1, + 90, 187, 91, -1, 90, 91, 208, -1, + 90, 208, 187, -1, 232, 231, 96, -1, + 232, 96, 92, -1, 232, 92, 100, -1, + 232, 100, 435, -1, 227, 228, 101, -1, + 227, 101, 93, -1, 227, 93, 97, -1, + 227, 97, 98, -1, 94, 95, 96, -1, + 94, 96, 231, -1, 94, 97, 95, -1, + 94, 98, 97, -1, 94, 227, 98, -1, + 94, 231, 227, -1, 99, 399, 233, -1, + 99, 435, 399, -1, 99, 233, 232, -1, + 99, 232, 435, -1, 432, 100, 433, -1, + 432, 435, 100, -1, 718, 102, 101, -1, + 718, 719, 102, -1, 718, 101, 234, -1, + 437, 694, 132, -1, 437, 234, 694, -1, + 437, 132, 438, -1, 1088, 236, 721, -1, + 440, 103, 441, -1, 440, 439, 103, -1, + 455, 456, 104, -1, 455, 104, 105, -1, + 455, 105, 1211, -1, 455, 1211, 1101, -1, + 728, 107, 106, -1, 728, 106, 915, -1, + 728, 214, 107, -1, 728, 729, 214, -1, + 536, 537, 729, -1, 536, 238, 535, -1, + 726, 739, 737, -1, 726, 246, 245, -1, + 726, 737, 246, -1, 241, 108, 732, -1, + 241, 242, 120, -1, 241, 120, 465, -1, + 241, 465, 108, -1, 731, 733, 240, -1, + 731, 241, 732, -1, 247, 110, 109, -1, + 247, 1112, 110, -1, 247, 111, 112, -1, + 247, 112, 244, -1, 247, 113, 111, -1, + 247, 109, 113, -1, 877, 1115, 340, -1, + 877, 340, 928, -1, 126, 119, 765, -1, + 126, 470, 123, -1, 126, 746, 470, -1, + 126, 765, 746, -1, 114, 115, 1154, -1, + 114, 1154, 116, -1, 114, 117, 115, -1, + 114, 116, 118, -1, 114, 124, 117, -1, + 114, 118, 119, -1, 114, 119, 126, -1, + 114, 126, 124, -1, 463, 120, 783, -1, + 463, 465, 120, -1, 463, 464, 465, -1, + 782, 463, 783, -1, 121, 122, 733, -1, + 121, 783, 122, -1, 121, 733, 248, -1, + 121, 248, 783, -1, 764, 746, 765, -1, + 555, 321, 127, -1, 555, 557, 321, -1, + 255, 251, 249, -1, 255, 249, 476, -1, + 376, 265, 254, -1, 376, 377, 261, -1, + 264, 488, 254, -1, 264, 254, 265, -1, + 603, 494, 264, -1, 603, 264, 265, -1, + 270, 123, 252, -1, 270, 252, 269, -1, + 270, 125, 124, -1, 270, 272, 125, -1, + 270, 126, 123, -1, 270, 124, 126, -1, + 267, 127, 268, -1, 267, 268, 472, -1, + 267, 555, 127, -1, 271, 269, 487, -1, + 273, 1145, 159, -1, 500, 492, 501, -1, + 500, 499, 492, -1, 769, 160, 159, -1, + 769, 342, 160, -1, 769, 509, 342, -1, + 769, 159, 1145, -1, 790, 616, 274, -1, + 787, 1485, 1796, -1, 1792, 2038, 1796, -1, + 1792, 1796, 1485, -1, 1792, 790, 274, -1, + 1792, 1641, 2038, -1, 1792, 274, 1641, -1, + 128, 346, 1162, -1, 128, 1162, 129, -1, + 128, 368, 346, -1, 128, 129, 368, -1, + 794, 1511, 1513, -1, 803, 1173, 512, -1, + 1182, 166, 1183, -1, 1185, 640, 1186, -1, + 130, 165, 1362, -1, 130, 633, 165, -1, + 130, 1362, 633, -1, 516, 517, 278, -1, + 831, 131, 132, -1, 831, 132, 830, -1, + 831, 280, 131, -1, 829, 132, 694, -1, + 829, 830, 132, -1, 839, 133, 837, -1, + 839, 610, 442, -1, 839, 441, 133, -1, + 839, 442, 441, -1, 683, 134, 286, -1, + 683, 289, 685, -1, 683, 682, 134, -1, + 287, 522, 288, -1, 847, 135, 848, -1, + 847, 690, 135, -1, 527, 201, 288, -1, + 527, 288, 522, -1, 527, 848, 135, -1, + 527, 135, 201, -1, 443, 610, 1278, -1, + 809, 1126, 1480, -1, 827, 1536, 297, -1, + 136, 299, 290, -1, 136, 1480, 299, -1, + 136, 815, 1480, -1, 404, 813, 514, -1, + 810, 290, 291, -1, 810, 291, 811, -1, + 810, 815, 136, -1, 810, 136, 290, -1, + 513, 811, 294, -1, 513, 206, 514, -1, + 529, 294, 291, -1, 529, 291, 860, -1, + 529, 860, 862, -1, 863, 702, 530, -1, + 298, 297, 284, -1, 298, 284, 283, -1, + 301, 446, 137, -1, 301, 137, 302, -1, + 314, 305, 309, -1, 304, 309, 305, -1, + 868, 1211, 549, -1, 868, 1214, 1211, -1, + 2057, 550, 439, -1, 544, 138, 545, -1, + 544, 549, 139, -1, 544, 139, 138, -1, + 296, 283, 295, -1, 296, 865, 541, -1, + 296, 298, 283, -1, 296, 541, 298, -1, + 140, 456, 458, -1, 140, 458, 141, -1, + 140, 141, 142, -1, 140, 142, 143, -1, + 140, 144, 456, -1, 140, 143, 144, -1, + 324, 900, 899, -1, 317, 319, 560, -1, + 320, 927, 925, -1, 320, 317, 558, -1, + 320, 319, 317, -1, 568, 324, 899, -1, + 722, 721, 562, -1, 565, 1089, 1462, -1, + 565, 566, 557, -1, 565, 557, 323, -1, + 565, 323, 322, -1, 929, 930, 325, -1, + 880, 320, 558, -1, 890, 560, 327, -1, + 576, 886, 889, -1, 926, 327, 925, -1, + 887, 560, 890, -1, 586, 588, 332, -1, + 330, 146, 588, -1, 330, 335, 591, -1, + 913, 330, 588, -1, 580, 581, 710, -1, + 920, 885, 710, -1, 920, 710, 581, -1, + 145, 332, 146, -1, 145, 147, 332, -1, + 145, 146, 330, -1, 145, 591, 147, -1, + 145, 330, 591, -1, 336, 337, 921, -1, + 336, 921, 591, -1, 589, 590, 147, -1, + 589, 147, 591, -1, 933, 595, 338, -1, + 584, 1476, 1557, -1, 584, 1475, 1476, -1, + 1477, 1557, 1476, -1, 1477, 1107, 1559, -1, + 1232, 340, 1115, -1, 596, 1331, 598, -1, + 596, 598, 937, -1, 596, 1334, 1331, -1, + 596, 1340, 1334, -1, 148, 257, 149, -1, + 148, 149, 150, -1, 148, 150, 257, -1, + 1244, 381, 665, -1, 1244, 598, 1331, -1, + 1244, 665, 2120, -1, 1244, 2120, 598, -1, + 485, 772, 773, -1, 508, 342, 509, -1, + 507, 772, 263, -1, 507, 494, 341, -1, + 507, 483, 494, -1, 343, 606, 152, -1, + 343, 152, 308, -1, 343, 308, 1273, -1, + 960, 606, 961, -1, 960, 1183, 606, -1, + 964, 1273, 308, -1, 964, 451, 1277, -1, + 964, 304, 451, -1, 964, 308, 309, -1, + 964, 309, 304, -1, 151, 308, 152, -1, + 151, 152, 153, -1, 151, 313, 308, -1, + 151, 153, 154, -1, 151, 154, 313, -1, + 613, 1862, 612, -1, 613, 1588, 1862, -1, + 345, 2117, 955, -1, 345, 612, 1082, -1, + 345, 1082, 2117, -1, 1833, 1069, 2068, -1, + 1833, 2117, 1069, -1, 1755, 1835, 1183, -1, + 1755, 1183, 960, -1, 1755, 155, 1627, -1, + 1755, 1450, 156, -1, 1755, 2037, 155, -1, + 1755, 156, 2037, -1, 1880, 346, 157, -1, + 1880, 1396, 1404, -1, 1880, 157, 368, -1, + 2005, 1862, 1588, -1, 988, 1346, 2120, -1, + 988, 2120, 158, -1, 988, 158, 1862, -1, + 349, 159, 160, -1, 349, 160, 350, -1, + 349, 273, 159, -1, 351, 355, 1588, -1, + 351, 350, 355, -1, 351, 1588, 613, -1, + 161, 164, 1615, -1, 161, 1615, 1269, -1, + 161, 1269, 164, -1, 357, 358, 1269, -1, + 357, 1269, 1595, -1, 625, 991, 623, -1, + 162, 163, 257, -1, 162, 354, 163, -1, + 162, 257, 354, -1, 626, 354, 257, -1, + 626, 381, 1244, -1, 626, 164, 355, -1, + 626, 1266, 164, -1, 1353, 989, 358, -1, + 1512, 1800, 1183, -1, 1512, 1183, 1513, -1, + 1184, 1183, 359, -1, 1184, 1517, 1183, -1, + 1010, 165, 633, -1, 1010, 1517, 165, -1, + 635, 512, 1173, -1, 637, 1183, 166, -1, + 637, 166, 1182, -1, 2069, 2068, 1017, -1, + 1024, 2068, 1069, -1, 1024, 1017, 2068, -1, + 644, 1173, 792, -1, 360, 1677, 1035, -1, + 360, 1835, 1677, -1, 360, 648, 1835, -1, + 651, 1082, 1867, -1, 167, 1862, 2120, -1, + 167, 1692, 1862, -1, 167, 2120, 1692, -1, + 367, 1396, 368, -1, 367, 1736, 1396, -1, + 365, 168, 364, -1, 365, 169, 168, -1, + 365, 366, 170, -1, 365, 170, 169, -1, + 1060, 1396, 1736, -1, 1060, 1736, 653, -1, + 370, 171, 2026, -1, 370, 2021, 171, -1, + 656, 1877, 657, -1, 656, 658, 1877, -1, + 1391, 1877, 658, -1, 372, 373, 172, -1, + 372, 172, 173, -1, 372, 173, 2038, -1, + 372, 2038, 668, -1, 662, 1877, 2120, -1, + 662, 1066, 1877, -1, 174, 1066, 676, -1, + 174, 671, 1066, -1, 174, 676, 675, -1, + 174, 675, 671, -1, 478, 376, 254, -1, + 175, 380, 666, -1, 175, 381, 380, -1, + 175, 666, 665, -1, 175, 665, 381, -1, + 382, 626, 257, -1, 382, 381, 626, -1, + 382, 262, 259, -1, 672, 1082, 386, -1, + 391, 176, 1877, -1, 391, 1082, 176, -1, + 391, 177, 387, -1, 384, 1066, 671, -1, + 384, 383, 1066, -1, 389, 383, 177, -1, + 389, 177, 391, -1, 389, 1066, 383, -1, + 389, 390, 1877, -1, 389, 1877, 1066, -1, + 1068, 1069, 178, -1, 1068, 178, 1064, -1, + 1080, 392, 1082, -1, 393, 1064, 178, -1, + 393, 394, 1064, -1, 393, 178, 1082, -1, + 393, 1082, 392, -1, 678, 2074, 1069, -1, + 678, 1458, 2074, -1, 1065, 2074, 1458, -1, + 1757, 1937, 1926, -1, 179, 200, 398, -1, + 179, 181, 200, -1, 179, 398, 181, -1, + 180, 398, 184, -1, 180, 181, 398, -1, + 180, 184, 181, -1, 182, 398, 187, -1, + 182, 185, 398, -1, 182, 187, 184, -1, + 182, 184, 185, -1, 183, 184, 398, -1, + 183, 398, 185, -1, 183, 185, 184, -1, + 395, 186, 187, -1, 395, 399, 186, -1, + 395, 187, 398, -1, 396, 687, 399, -1, + 396, 399, 395, -1, 698, 729, 537, -1, + 698, 191, 729, -1, 705, 703, 188, -1, + 705, 188, 699, -1, 704, 703, 705, -1, + 189, 218, 214, -1, 189, 214, 192, -1, + 189, 699, 218, -1, 189, 192, 699, -1, + 190, 214, 191, -1, 190, 192, 214, -1, + 190, 191, 698, -1, 190, 699, 192, -1, + 190, 698, 699, -1, 193, 194, 195, -1, + 193, 195, 214, -1, 193, 419, 194, -1, + 193, 424, 419, -1, 193, 214, 424, -1, + 210, 218, 209, -1, 210, 196, 218, -1, + 210, 211, 196, -1, 213, 212, 218, -1, + 197, 198, 398, -1, 197, 398, 199, -1, + 197, 199, 200, -1, 197, 200, 209, -1, + 197, 209, 198, -1, 691, 201, 202, -1, + 691, 685, 201, -1, 691, 202, 690, -1, + 403, 203, 407, -1, 403, 402, 204, -1, + 403, 237, 203, -1, 403, 204, 237, -1, + 205, 401, 206, -1, 205, 533, 401, -1, + 205, 206, 513, -1, 205, 513, 533, -1, + 532, 535, 401, -1, 532, 401, 533, -1, + 426, 435, 427, -1, 426, 430, 435, -1, + 207, 209, 208, -1, 207, 208, 221, -1, + 207, 210, 209, -1, 207, 211, 210, -1, + 207, 221, 212, -1, 207, 212, 213, -1, + 207, 218, 211, -1, 207, 213, 218, -1, + 222, 424, 214, -1, 222, 215, 221, -1, + 222, 217, 216, -1, 222, 214, 217, -1, + 222, 218, 215, -1, 222, 216, 218, -1, + 413, 412, 433, -1, 413, 433, 219, -1, + 413, 219, 419, -1, 416, 412, 419, -1, + 416, 415, 412, -1, 421, 419, 422, -1, + 220, 415, 419, -1, 220, 419, 418, -1, + 220, 418, 415, -1, 434, 433, 412, -1, + 434, 412, 223, -1, 434, 223, 409, -1, + 434, 409, 431, -1, 224, 221, 223, -1, + 224, 424, 222, -1, 224, 222, 221, -1, + 423, 415, 418, -1, 423, 223, 415, -1, + 423, 418, 421, -1, 423, 424, 224, -1, + 423, 224, 223, -1, 707, 885, 884, -1, + 707, 884, 886, -1, 707, 576, 708, -1, + 707, 886, 576, -1, 919, 885, 920, -1, + 1093, 225, 1094, -1, 1093, 711, 225, -1, + 226, 228, 227, -1, 226, 227, 231, -1, + 226, 399, 696, -1, 226, 696, 695, -1, + 226, 695, 228, -1, 226, 231, 230, -1, + 226, 230, 399, -1, 229, 230, 231, -1, + 229, 232, 233, -1, 229, 231, 232, -1, + 229, 233, 399, -1, 229, 399, 230, -1, + 436, 234, 437, -1, 436, 716, 718, -1, + 436, 718, 234, -1, 1086, 1088, 721, -1, + 235, 1088, 1087, -1, 235, 450, 315, -1, + 235, 1087, 450, -1, 235, 315, 236, -1, + 235, 236, 1088, -1, 452, 453, 455, -1, + 452, 1101, 723, -1, 452, 455, 1101, -1, + 457, 455, 453, -1, 725, 245, 237, -1, + 725, 726, 245, -1, 725, 237, 238, -1, + 725, 238, 536, -1, 239, 731, 240, -1, + 239, 241, 731, -1, 239, 240, 242, -1, + 239, 242, 241, -1, 243, 244, 245, -1, + 243, 245, 246, -1, 243, 247, 244, -1, + 243, 461, 247, -1, 243, 246, 462, -1, + 243, 462, 461, -1, 738, 1112, 247, -1, + 738, 247, 461, -1, 1574, 583, 1575, -1, + 784, 248, 1154, -1, 784, 783, 248, -1, + 743, 275, 465, -1, 467, 249, 471, -1, + 467, 468, 249, -1, 753, 468, 754, -1, + 753, 249, 468, -1, 753, 476, 249, -1, + 753, 479, 476, -1, 469, 470, 746, -1, + 469, 746, 754, -1, 469, 754, 468, -1, + 756, 745, 750, -1, 481, 472, 758, -1, + 767, 1235, 1237, -1, 767, 750, 745, -1, + 250, 251, 255, -1, 250, 255, 488, -1, + 250, 252, 251, -1, 250, 487, 252, -1, + 250, 488, 487, -1, 253, 254, 488, -1, + 253, 488, 255, -1, 253, 477, 478, -1, + 253, 478, 254, -1, 253, 476, 477, -1, + 253, 255, 476, -1, 256, 492, 265, -1, + 256, 265, 262, -1, 256, 262, 382, -1, + 256, 257, 492, -1, 256, 382, 257, -1, + 258, 259, 262, -1, 258, 262, 380, -1, + 258, 382, 259, -1, 258, 380, 382, -1, + 260, 261, 380, -1, 260, 380, 262, -1, + 260, 376, 261, -1, 260, 262, 265, -1, + 260, 265, 376, -1, 486, 263, 772, -1, + 486, 507, 263, -1, 486, 488, 264, -1, + 486, 264, 494, -1, 486, 494, 483, -1, + 491, 265, 492, -1, 491, 603, 265, -1, + 602, 494, 603, -1, 497, 603, 499, -1, + 266, 554, 555, -1, 266, 555, 267, -1, + 266, 267, 472, -1, 266, 472, 481, -1, + 266, 481, 554, -1, 473, 472, 268, -1, + 473, 478, 475, -1, 473, 268, 378, -1, + 777, 271, 773, -1, 777, 1119, 271, -1, + 775, 271, 1119, -1, 775, 774, 272, -1, + 775, 269, 271, -1, 775, 272, 270, -1, + 775, 270, 269, -1, 489, 773, 271, -1, + 489, 271, 487, -1, 1155, 1154, 272, -1, + 1155, 272, 774, -1, 506, 509, 769, -1, + 510, 1149, 778, -1, 1152, 1157, 1121, -1, + 1156, 1155, 774, -1, 352, 1143, 1145, -1, + 352, 1145, 273, -1, 352, 273, 349, -1, + 679, 274, 616, -1, 679, 1641, 274, -1, + 973, 1790, 1789, -1, 1486, 1487, 615, -1, + 1303, 785, 1302, -1, 786, 1485, 787, -1, + 786, 785, 1303, -1, 786, 1303, 1485, -1, + 791, 1162, 346, -1, 791, 346, 1291, -1, + 1172, 794, 1173, -1, 1172, 1511, 794, -1, + 801, 511, 1173, -1, 801, 1173, 803, -1, + 801, 1803, 511, -1, 801, 803, 1176, -1, + 1175, 801, 1176, -1, 808, 503, 1126, -1, + 808, 1126, 809, -1, 293, 406, 275, -1, + 293, 275, 743, -1, 293, 743, 504, -1, + 1188, 277, 276, -1, 1188, 276, 517, -1, + 1188, 818, 277, -1, 515, 1191, 843, -1, + 518, 278, 823, -1, 518, 516, 278, -1, + 832, 279, 280, -1, 832, 280, 831, -1, + 832, 519, 281, -1, 832, 281, 279, -1, + 526, 297, 1536, -1, 520, 843, 1191, -1, + 520, 1191, 344, -1, 520, 344, 838, -1, + 967, 610, 839, -1, 967, 838, 966, -1, + 524, 297, 526, -1, 524, 287, 297, -1, + 524, 522, 287, -1, 681, 683, 685, -1, + 282, 286, 283, -1, 282, 287, 286, -1, + 282, 283, 284, -1, 282, 284, 297, -1, + 282, 297, 287, -1, 285, 683, 286, -1, + 285, 286, 287, -1, 285, 287, 288, -1, + 285, 288, 289, -1, 285, 289, 683, -1, + 852, 690, 847, -1, 854, 1536, 1535, -1, + 525, 522, 523, -1, 525, 527, 522, -1, + 525, 523, 526, -1, 826, 827, 1480, -1, + 826, 1480, 1133, -1, 859, 291, 290, -1, + 859, 860, 291, -1, 859, 290, 299, -1, + 859, 299, 528, -1, 292, 813, 404, -1, + 292, 808, 813, -1, 292, 503, 808, -1, + 292, 404, 406, -1, 292, 406, 293, -1, + 292, 504, 503, -1, 292, 293, 504, -1, + 814, 1480, 815, -1, 814, 809, 1480, -1, + 534, 294, 529, -1, 534, 513, 294, -1, + 534, 533, 513, -1, 864, 702, 863, -1, + 864, 295, 702, -1, 864, 865, 296, -1, + 864, 296, 295, -1, 542, 827, 297, -1, + 542, 297, 298, -1, 542, 1480, 827, -1, + 542, 299, 1480, -1, 542, 528, 299, -1, + 542, 298, 541, -1, 449, 446, 301, -1, + 449, 301, 451, -1, 300, 301, 302, -1, + 300, 451, 301, -1, 300, 302, 1277, -1, + 300, 1277, 451, -1, 303, 314, 451, -1, + 303, 451, 304, -1, 303, 305, 314, -1, + 303, 304, 305, -1, 310, 308, 313, -1, + 306, 450, 451, -1, 306, 314, 450, -1, + 306, 451, 314, -1, 307, 309, 308, -1, + 307, 314, 309, -1, 307, 308, 310, -1, + 307, 313, 314, -1, 307, 310, 313, -1, + 311, 313, 312, -1, 311, 314, 313, -1, + 311, 312, 315, -1, 311, 315, 450, -1, + 311, 450, 314, -1, 1776, 1216, 873, -1, + 870, 550, 2057, -1, 546, 549, 544, -1, + 552, 877, 928, -1, 551, 900, 324, -1, + 551, 324, 556, -1, 316, 317, 560, -1, + 316, 558, 317, -1, 316, 560, 1548, -1, + 316, 1548, 558, -1, 318, 327, 319, -1, + 318, 319, 320, -1, 318, 925, 327, -1, + 318, 320, 925, -1, 931, 927, 320, -1, + 931, 325, 930, -1, 931, 880, 325, -1, + 931, 320, 880, -1, 891, 1548, 560, -1, + 567, 563, 321, -1, 567, 321, 566, -1, + 567, 1462, 722, -1, 567, 565, 1462, -1, + 894, 565, 322, -1, 894, 1089, 565, -1, + 894, 323, 556, -1, 894, 322, 323, -1, + 894, 556, 324, -1, 894, 324, 568, -1, + 571, 928, 929, -1, 571, 552, 928, -1, + 573, 325, 880, -1, 892, 897, 570, -1, + 892, 570, 929, -1, 892, 929, 325, -1, + 892, 325, 573, -1, 326, 890, 327, -1, + 326, 888, 890, -1, 326, 327, 926, -1, + 326, 926, 888, -1, 328, 889, 888, -1, + 328, 576, 889, -1, 901, 576, 328, -1, + 901, 328, 888, -1, 578, 586, 332, -1, + 578, 332, 333, -1, 905, 583, 907, -1, + 905, 1575, 583, -1, 587, 588, 586, -1, + 329, 913, 914, -1, 329, 330, 913, -1, + 329, 914, 335, -1, 329, 335, 330, -1, + 331, 590, 581, -1, 331, 332, 590, -1, + 331, 333, 332, -1, 331, 581, 578, -1, + 331, 578, 333, -1, 1225, 581, 590, -1, + 1225, 920, 581, -1, 334, 591, 335, -1, + 334, 336, 591, -1, 334, 335, 337, -1, + 334, 337, 336, -1, 934, 338, 1475, -1, + 934, 1475, 584, -1, 934, 933, 338, -1, + 734, 1475, 338, -1, 734, 1109, 1108, -1, + 734, 593, 1109, -1, 734, 595, 593, -1, + 734, 338, 595, -1, 1234, 339, 1110, -1, + 1234, 765, 339, -1, 1239, 1232, 1115, -1, + 1229, 928, 340, -1, 1229, 340, 1232, -1, + 924, 925, 927, -1, 1821, 1584, 924, -1, + 1327, 1244, 1331, -1, 936, 596, 937, -1, + 939, 978, 981, -1, 618, 983, 1346, -1, + 618, 1346, 981, -1, 1839, 938, 598, -1, + 599, 598, 983, -1, 599, 600, 598, -1, + 944, 1244, 945, -1, 1591, 945, 1244, -1, + 1591, 1592, 945, -1, 627, 1589, 1830, -1, + 627, 1830, 1244, -1, 1598, 1265, 1244, -1, + 604, 507, 341, -1, 604, 497, 498, -1, + 604, 508, 507, -1, 604, 603, 497, -1, + 604, 498, 342, -1, 604, 342, 508, -1, + 604, 341, 495, -1, 951, 606, 343, -1, + 951, 343, 1273, -1, 951, 1273, 1272, -1, + 959, 2026, 1755, -1, 959, 1755, 960, -1, + 609, 344, 1191, -1, 609, 965, 966, -1, + 609, 838, 344, -1, 609, 966, 838, -1, + 1136, 1620, 1191, -1, 1136, 1622, 1620, -1, + 1138, 1139, 956, -1, 1138, 956, 962, -1, + 1138, 607, 1622, -1, 1138, 961, 607, -1, + 1138, 962, 961, -1, 1142, 1143, 611, -1, + 954, 345, 955, -1, 954, 612, 345, -1, + 1625, 1835, 1755, -1, 1797, 1291, 346, -1, + 1797, 346, 1880, -1, 1797, 1302, 785, -1, + 347, 368, 1396, -1, 347, 1880, 368, -1, + 347, 1396, 1880, -1, 1333, 1334, 1340, -1, + 1647, 1342, 2005, -1, 1350, 1862, 2005, -1, + 1350, 2005, 1660, -1, 348, 349, 350, -1, + 348, 350, 351, -1, 348, 611, 1143, -1, + 348, 613, 611, -1, 348, 351, 613, -1, + 348, 1143, 352, -1, 348, 352, 349, -1, + 621, 1269, 358, -1, 621, 358, 989, -1, + 624, 625, 623, -1, 624, 1588, 1269, -1, + 624, 1269, 625, -1, 994, 621, 989, -1, + 353, 355, 354, -1, 353, 626, 355, -1, + 353, 354, 626, -1, 1267, 1266, 626, -1, + 1267, 626, 1595, -1, 356, 357, 1595, -1, + 356, 1595, 1353, -1, 356, 358, 357, -1, + 356, 1353, 358, -1, 1263, 1588, 1002, -1, + 1001, 1588, 1589, -1, 1001, 1002, 1588, -1, + 804, 1184, 359, -1, 804, 359, 1183, -1, + 804, 640, 1185, -1, 1006, 1517, 632, -1, + 1371, 632, 1517, -1, 1356, 1010, 633, -1, + 806, 1362, 1517, -1, 806, 1521, 1362, -1, + 638, 1173, 639, -1, 638, 635, 1173, -1, + 638, 637, 1182, -1, 1008, 1372, 1012, -1, + 1008, 1012, 641, -1, 1015, 1363, 1362, -1, + 1842, 1069, 2074, -1, 1027, 1183, 648, -1, + 1027, 646, 1183, -1, 643, 644, 792, -1, + 1033, 1173, 644, -1, 1031, 648, 360, -1, + 1031, 360, 1035, -1, 1284, 1994, 1688, -1, + 1394, 651, 1867, -1, 1394, 1395, 651, -1, + 361, 1082, 1043, -1, 361, 1038, 1082, -1, + 361, 1043, 1038, -1, 362, 364, 363, -1, + 362, 365, 364, -1, 362, 363, 1736, -1, + 362, 366, 365, -1, 362, 1736, 367, -1, + 362, 368, 366, -1, 362, 367, 368, -1, + 1891, 2026, 1721, -1, 1738, 652, 1736, -1, + 1428, 652, 1431, -1, 1055, 653, 1736, -1, + 1733, 1425, 1731, -1, 1733, 2026, 1880, -1, + 1733, 1880, 1425, -1, 1733, 1431, 1430, -1, + 1733, 1430, 1057, -1, 1733, 1057, 1058, -1, + 1733, 1058, 1418, -1, 1733, 1721, 2026, -1, + 1745, 1746, 2021, -1, 1745, 2021, 2020, -1, + 369, 1896, 2021, -1, 369, 2021, 371, -1, + 369, 371, 1896, -1, 1454, 370, 2026, -1, + 1454, 371, 2021, -1, 1454, 2021, 370, -1, + 1454, 1896, 371, -1, 1454, 1062, 1896, -1, + 1042, 1038, 1043, -1, 663, 372, 668, -1, + 663, 373, 372, -1, 663, 664, 373, -1, + 374, 676, 1066, -1, 374, 394, 676, -1, + 1063, 1064, 394, -1, 1063, 374, 1066, -1, + 1063, 394, 374, -1, 1072, 2088, 1760, -1, + 1072, 1760, 1761, -1, 1074, 2162, 668, -1, + 1074, 2117, 2162, -1, 1942, 668, 2088, -1, + 375, 377, 376, -1, 375, 376, 478, -1, + 375, 478, 473, -1, 375, 378, 377, -1, + 375, 473, 378, -1, 379, 380, 381, -1, + 379, 381, 382, -1, 379, 382, 380, -1, + 670, 386, 387, -1, 670, 672, 386, -1, + 670, 387, 383, -1, 670, 383, 384, -1, + 670, 384, 671, -1, 673, 1082, 672, -1, + 385, 386, 1082, -1, 385, 1082, 391, -1, + 385, 387, 386, -1, 385, 391, 387, -1, + 388, 390, 389, -1, 388, 389, 391, -1, + 388, 1877, 390, -1, 388, 391, 1877, -1, + 1079, 392, 1080, -1, 1079, 393, 392, -1, + 1079, 676, 394, -1, 1079, 394, 393, -1, + 1635, 679, 616, -1, 1923, 1315, 1922, -1, + 397, 395, 398, -1, 397, 396, 395, -1, + 686, 687, 396, -1, 686, 396, 397, -1, + 686, 398, 682, -1, 686, 397, 398, -1, + 688, 696, 399, -1, 688, 399, 687, -1, + 700, 698, 537, -1, 700, 530, 702, -1, + 400, 401, 402, -1, 400, 402, 403, -1, + 400, 514, 401, -1, 400, 404, 514, -1, + 400, 405, 406, -1, 400, 406, 404, -1, + 400, 407, 405, -1, 400, 403, 407, -1, + 408, 409, 435, -1, 408, 431, 409, -1, + 408, 435, 431, -1, 410, 435, 430, -1, + 410, 431, 435, -1, 410, 430, 431, -1, + 411, 419, 412, -1, 411, 413, 419, -1, + 411, 412, 413, -1, 414, 419, 415, -1, + 414, 416, 419, -1, 414, 415, 416, -1, + 417, 418, 419, -1, 417, 419, 421, -1, + 417, 421, 418, -1, 420, 421, 422, -1, + 420, 423, 421, -1, 420, 422, 424, -1, + 420, 424, 423, -1, 709, 710, 885, -1, + 709, 885, 707, -1, 459, 919, 1778, -1, + 459, 559, 885, -1, 459, 885, 919, -1, + 425, 429, 430, -1, 425, 426, 427, -1, + 425, 430, 426, -1, 425, 427, 435, -1, + 425, 435, 429, -1, 428, 430, 429, -1, + 428, 431, 430, -1, 428, 432, 433, -1, + 428, 433, 434, -1, 428, 434, 431, -1, + 428, 435, 432, -1, 428, 429, 435, -1, + 715, 436, 437, -1, 715, 438, 717, -1, + 715, 437, 438, -1, 715, 716, 436, -1, + 1772, 721, 722, -1, 2058, 439, 440, -1, + 2058, 2057, 439, -1, 2058, 440, 448, -1, + 2058, 448, 2059, -1, 447, 440, 441, -1, + 447, 448, 440, -1, 447, 441, 442, -1, + 447, 442, 610, -1, 447, 610, 443, -1, + 447, 1278, 445, -1, 447, 443, 1278, -1, + 444, 445, 446, -1, 444, 447, 445, -1, + 444, 448, 447, -1, 444, 446, 449, -1, + 444, 450, 1087, -1, 444, 1087, 1770, -1, + 444, 2059, 448, -1, 444, 1770, 2059, -1, + 444, 451, 450, -1, 444, 449, 451, -1, + 1097, 453, 452, -1, 1097, 457, 453, -1, + 1097, 452, 723, -1, 454, 456, 455, -1, + 454, 455, 457, -1, 454, 458, 456, -1, + 454, 457, 458, -1, 1096, 458, 457, -1, + 1096, 1094, 458, -1, 1096, 457, 1097, -1, + 1102, 1101, 1211, -1, 1962, 1090, 1100, -1, + 1218, 559, 459, -1, 1218, 459, 1778, -1, + 727, 725, 536, -1, 727, 536, 729, -1, + 730, 732, 460, -1, 730, 460, 1107, -1, + 730, 1107, 1106, -1, 1105, 730, 1106, -1, + 736, 738, 461, -1, 736, 462, 737, -1, + 736, 461, 462, -1, 742, 782, 1130, -1, + 742, 464, 463, -1, 742, 463, 782, -1, + 742, 465, 464, -1, 742, 743, 465, -1, + 741, 504, 743, -1, 741, 1127, 504, -1, + 741, 1129, 1127, -1, 466, 468, 467, -1, + 466, 469, 468, -1, 466, 470, 469, -1, + 466, 471, 470, -1, 466, 467, 471, -1, + 748, 756, 754, -1, 748, 745, 756, -1, + 748, 754, 746, -1, 748, 746, 747, -1, + 474, 758, 472, -1, 474, 749, 758, -1, + 474, 472, 473, -1, 474, 473, 475, -1, + 480, 474, 475, -1, 480, 749, 474, -1, + 480, 477, 476, -1, 480, 476, 479, -1, + 480, 478, 477, -1, 480, 475, 478, -1, + 752, 479, 753, -1, 752, 480, 479, -1, + 752, 749, 480, -1, 757, 481, 758, -1, + 757, 878, 554, -1, 757, 554, 481, -1, + 757, 1115, 878, -1, 761, 767, 1237, -1, + 761, 750, 767, -1, 761, 1237, 1238, -1, + 766, 745, 764, -1, 766, 767, 745, -1, + 482, 483, 507, -1, 482, 486, 483, -1, + 482, 507, 486, -1, 484, 772, 485, -1, + 484, 486, 772, -1, 484, 485, 773, -1, + 484, 487, 488, -1, 484, 488, 486, -1, + 484, 773, 489, -1, 484, 489, 487, -1, + 490, 491, 492, -1, 490, 603, 491, -1, + 490, 492, 499, -1, 490, 499, 603, -1, + 493, 495, 494, -1, 493, 494, 602, -1, + 493, 604, 495, -1, 493, 602, 604, -1, + 496, 498, 497, -1, 496, 497, 499, -1, + 496, 499, 500, -1, 496, 501, 498, -1, + 496, 500, 501, -1, 502, 503, 504, -1, + 502, 504, 1127, -1, 502, 1126, 503, -1, + 502, 1127, 1126, -1, 1148, 1149, 506, -1, + 1148, 506, 769, -1, 505, 506, 1149, -1, + 505, 1149, 510, -1, 505, 509, 506, -1, + 505, 510, 509, -1, 771, 507, 508, -1, + 771, 508, 509, -1, 771, 509, 510, -1, + 771, 772, 507, -1, 771, 510, 778, -1, + 1117, 1119, 777, -1, 779, 778, 1149, -1, + 779, 1149, 780, -1, 1196, 1197, 826, -1, + 1196, 826, 1133, -1, 1151, 1130, 782, -1, + 1489, 973, 1789, -1, 1489, 1486, 615, -1, + 614, 615, 1487, -1, 614, 1487, 1310, -1, + 1494, 785, 786, -1, 972, 1790, 973, -1, + 972, 1791, 1790, -1, 969, 1299, 1796, -1, + 969, 1796, 970, -1, 1163, 970, 1796, -1, + 800, 1167, 1173, -1, 800, 797, 799, -1, + 796, 794, 1513, -1, 796, 797, 794, -1, + 798, 799, 797, -1, 798, 797, 1183, -1, + 1802, 1173, 511, -1, 1802, 511, 1803, -1, + 1179, 1180, 512, -1, 1179, 512, 635, -1, + 802, 803, 512, -1, 802, 512, 1180, -1, + 812, 811, 513, -1, 812, 514, 813, -1, + 812, 513, 514, -1, 1187, 1188, 517, -1, + 1192, 821, 1527, -1, 1192, 1527, 1529, -1, + 1190, 515, 843, -1, 1190, 1191, 515, -1, + 1204, 1206, 1194, -1, 1539, 516, 518, -1, + 1539, 517, 516, -1, 1539, 1187, 517, -1, + 1540, 518, 823, -1, 1540, 1539, 518, -1, + 1203, 519, 832, -1, 1203, 1205, 519, -1, + 1199, 1203, 832, -1, 841, 520, 838, -1, + 841, 837, 842, -1, 841, 843, 520, -1, + 521, 523, 522, -1, 521, 522, 524, -1, + 521, 526, 523, -1, 521, 524, 526, -1, + 857, 690, 852, -1, 857, 835, 690, -1, + 857, 856, 835, -1, 851, 854, 1535, -1, + 855, 857, 852, -1, 849, 525, 526, -1, + 849, 526, 1536, -1, 849, 1536, 854, -1, + 849, 848, 527, -1, 849, 527, 525, -1, + 861, 859, 528, -1, 861, 542, 865, -1, + 861, 528, 542, -1, 538, 700, 537, -1, + 539, 529, 862, -1, 539, 534, 529, -1, + 539, 863, 530, -1, 539, 862, 863, -1, + 539, 530, 700, -1, 539, 700, 538, -1, + 531, 532, 533, -1, 531, 533, 534, -1, + 531, 535, 532, -1, 531, 536, 535, -1, + 531, 537, 536, -1, 531, 538, 537, -1, + 531, 534, 539, -1, 531, 539, 538, -1, + 540, 541, 865, -1, 540, 865, 542, -1, + 540, 542, 541, -1, 1468, 1102, 1211, -1, + 1468, 1211, 1208, -1, 1468, 1208, 1209, -1, + 871, 874, 1214, -1, 871, 1774, 874, -1, + 1210, 873, 1209, -1, 1808, 1955, 1806, -1, + 1552, 1543, 1806, -1, 1552, 1806, 1955, -1, + 1775, 1776, 873, -1, 872, 1216, 1776, -1, + 872, 1955, 1808, -1, 872, 1953, 1955, -1, + 872, 1776, 1953, -1, 869, 868, 549, -1, + 869, 549, 550, -1, 869, 550, 870, -1, + 543, 544, 545, -1, 543, 546, 544, -1, + 543, 547, 548, -1, 543, 545, 547, -1, + 543, 549, 546, -1, 543, 550, 549, -1, + 543, 548, 550, -1, 876, 551, 556, -1, + 876, 900, 551, -1, 876, 572, 900, -1, + 876, 571, 572, -1, 876, 552, 571, -1, + 876, 877, 552, -1, 553, 554, 878, -1, + 553, 555, 554, -1, 553, 878, 876, -1, + 553, 876, 556, -1, 553, 556, 557, -1, + 553, 557, 555, -1, 1545, 558, 1548, -1, + 1545, 880, 558, -1, 882, 885, 559, -1, + 882, 559, 891, -1, 1217, 891, 559, -1, + 1217, 559, 1218, -1, 883, 891, 560, -1, + 883, 560, 887, -1, 561, 562, 563, -1, + 561, 563, 567, -1, 561, 722, 562, -1, + 561, 567, 722, -1, 564, 566, 565, -1, + 564, 567, 566, -1, 564, 565, 567, -1, + 893, 568, 899, -1, 893, 894, 568, -1, + 569, 929, 570, -1, 569, 571, 929, -1, + 569, 570, 897, -1, 569, 897, 571, -1, + 898, 571, 897, -1, 898, 572, 571, -1, + 898, 900, 572, -1, 879, 573, 880, -1, + 879, 892, 573, -1, 574, 926, 1571, -1, + 574, 1571, 901, -1, 574, 888, 926, -1, + 574, 901, 888, -1, 903, 579, 901, -1, + 903, 578, 579, -1, 903, 586, 578, -1, + 903, 904, 586, -1, 903, 901, 1576, -1, + 575, 901, 579, -1, 575, 576, 901, -1, + 575, 579, 708, -1, 575, 708, 576, -1, + 577, 579, 578, -1, 577, 710, 579, -1, + 577, 580, 710, -1, 577, 581, 580, -1, + 577, 578, 581, -1, 1554, 907, 583, -1, + 1554, 583, 1555, -1, 582, 1555, 583, -1, + 582, 584, 1557, -1, 582, 1557, 1555, -1, + 582, 1574, 935, -1, 582, 583, 1574, -1, + 582, 935, 934, -1, 582, 934, 584, -1, + 1558, 1557, 1477, -1, 1558, 1477, 1559, -1, + 585, 907, 587, -1, 585, 904, 905, -1, + 585, 905, 907, -1, 585, 586, 904, -1, + 585, 587, 586, -1, 908, 587, 907, -1, + 908, 588, 587, -1, 908, 913, 588, -1, + 912, 913, 906, -1, 912, 739, 915, -1, + 1222, 920, 1225, -1, 1222, 1225, 1568, -1, + 1224, 590, 589, -1, 1224, 1225, 590, -1, + 1224, 589, 591, -1, 1224, 591, 921, -1, + 592, 1234, 1110, -1, 592, 1110, 1109, -1, + 592, 1109, 593, -1, 592, 1579, 1234, -1, + 592, 593, 595, -1, 592, 595, 1579, -1, + 1227, 926, 925, -1, 594, 924, 927, -1, + 594, 1821, 924, -1, 594, 927, 1231, -1, + 594, 1231, 1821, -1, 1236, 1237, 1235, -1, + 1578, 595, 933, -1, 1578, 933, 1240, -1, + 1578, 1579, 595, -1, 1325, 1244, 1327, -1, + 1341, 1340, 596, -1, 1341, 596, 936, -1, + 1338, 937, 598, -1, 1338, 598, 938, -1, + 2000, 938, 1839, -1, 2000, 2001, 938, -1, + 597, 981, 1346, -1, 597, 1346, 939, -1, + 597, 939, 981, -1, 986, 2005, 978, -1, + 986, 978, 939, -1, 942, 598, 600, -1, + 942, 1839, 598, -1, 941, 600, 599, -1, + 941, 942, 600, -1, 941, 983, 1342, -1, + 941, 599, 983, -1, 1243, 943, 948, -1, + 1259, 1269, 1255, -1, 947, 944, 1242, -1, + 947, 1244, 944, -1, 999, 996, 1244, -1, + 999, 1244, 1000, -1, 1264, 1244, 1265, -1, + 1264, 1000, 1244, -1, 628, 627, 1244, -1, + 950, 1244, 976, -1, 950, 976, 1318, -1, + 1268, 1595, 1604, -1, 601, 602, 603, -1, + 601, 603, 604, -1, 601, 604, 602, -1, + 605, 961, 606, -1, 605, 606, 951, -1, + 605, 951, 1622, -1, 605, 607, 961, -1, + 605, 1622, 607, -1, 617, 1880, 2026, -1, + 617, 2026, 959, -1, 617, 959, 958, -1, + 617, 958, 955, -1, 608, 1191, 1620, -1, + 608, 609, 1191, -1, 608, 965, 609, -1, + 608, 1274, 965, -1, 608, 1620, 1274, -1, + 1279, 1278, 610, -1, 1279, 610, 967, -1, + 953, 956, 1139, -1, 953, 1139, 954, -1, + 1144, 954, 1139, -1, 1144, 1142, 611, -1, + 1144, 612, 954, -1, 1144, 611, 613, -1, + 1144, 613, 612, -1, 968, 1755, 1627, -1, + 968, 1625, 1755, -1, 1626, 1627, 1688, -1, + 1287, 1159, 1797, -1, 1636, 1302, 1797, -1, + 1636, 614, 1310, -1, 1636, 615, 614, -1, + 1636, 1489, 615, -1, 1636, 973, 1489, -1, + 1636, 1635, 616, -1, 1636, 616, 790, -1, + 1636, 790, 972, -1, 1636, 1797, 1880, -1, + 1636, 955, 2117, -1, 1636, 617, 955, -1, + 1636, 1880, 617, -1, 1332, 2005, 1588, -1, + 1332, 1333, 2005, -1, 1336, 2005, 1333, -1, + 1336, 1333, 1340, -1, 980, 978, 2005, -1, + 980, 2005, 1652, -1, 982, 618, 981, -1, + 982, 980, 1652, -1, 1650, 983, 618, -1, + 1650, 618, 982, -1, 1650, 982, 1652, -1, + 987, 1655, 2005, -1, 1663, 1664, 1346, -1, + 1657, 1655, 987, -1, 619, 988, 1862, -1, + 619, 1862, 1350, -1, 619, 1350, 988, -1, + 1349, 988, 1350, -1, 620, 625, 1269, -1, + 620, 1269, 621, -1, 620, 994, 625, -1, + 620, 621, 994, -1, 622, 623, 1588, -1, + 622, 624, 623, -1, 622, 1588, 624, -1, + 993, 991, 625, -1, 993, 625, 994, -1, + 1352, 1353, 1595, -1, 1352, 948, 991, -1, + 1352, 1244, 948, -1, 1352, 1595, 626, -1, + 1352, 626, 1244, -1, 998, 1589, 627, -1, + 998, 1001, 1589, -1, 998, 627, 628, -1, + 998, 996, 999, -1, 998, 628, 1244, -1, + 629, 631, 1517, -1, 629, 1006, 631, -1, + 629, 1517, 1006, -1, 630, 631, 1006, -1, + 630, 1006, 641, -1, 630, 1012, 631, -1, + 630, 641, 1012, -1, 1373, 632, 1371, -1, + 1373, 1006, 632, -1, 1013, 1517, 1016, -1, + 1013, 1371, 1517, -1, 1361, 1356, 633, -1, + 1361, 633, 1362, -1, 1365, 1366, 1358, -1, + 805, 806, 1517, -1, 634, 638, 1182, -1, + 634, 635, 638, -1, 634, 1182, 1179, -1, + 634, 1179, 635, -1, 636, 1183, 637, -1, + 636, 637, 638, -1, 636, 638, 639, -1, + 636, 639, 640, -1, 636, 640, 804, -1, + 636, 804, 1183, -1, 1007, 641, 1006, -1, + 1007, 1008, 641, -1, 1004, 1015, 1016, -1, + 1004, 1358, 1366, -1, 1004, 1366, 1363, -1, + 1004, 1363, 1015, -1, 1369, 1015, 1362, -1, + 1665, 1069, 1842, -1, 1019, 2069, 1017, -1, + 1019, 2074, 2069, -1, 1375, 1022, 1376, -1, + 1025, 1069, 1021, -1, 1025, 1021, 1022, -1, + 1171, 1170, 643, -1, 1171, 643, 792, -1, + 642, 643, 1170, -1, 642, 646, 643, -1, + 642, 1170, 1183, -1, 642, 1183, 646, -1, + 645, 644, 643, -1, 645, 643, 646, -1, + 647, 1033, 644, -1, 647, 644, 645, -1, + 647, 645, 646, -1, 1028, 646, 1027, -1, + 1028, 647, 646, -1, 1028, 1033, 647, -1, + 1030, 1027, 648, -1, 1030, 648, 1031, -1, + 1854, 1173, 1034, -1, 1854, 1034, 1036, -1, + 1854, 649, 1173, -1, 1854, 2037, 649, -1, + 1854, 1688, 2037, -1, 1040, 651, 1039, -1, + 1040, 1043, 1082, -1, 1040, 1082, 651, -1, + 650, 651, 1395, -1, 650, 1395, 1039, -1, + 650, 1039, 651, -1, 1045, 1039, 1395, -1, + 1699, 1700, 1869, -1, 1699, 1869, 1705, -1, + 1050, 1049, 1396, -1, 1061, 1398, 1396, -1, + 1407, 1404, 1396, -1, 1051, 1396, 1409, -1, + 1717, 1409, 1396, -1, 1882, 1396, 1049, -1, + 1882, 1714, 1396, -1, 1420, 1422, 1733, -1, + 2012, 1726, 2026, -1, 1739, 1431, 652, -1, + 1739, 652, 1738, -1, 1056, 652, 1428, -1, + 1056, 1736, 652, -1, 1056, 1055, 1736, -1, + 1432, 653, 1055, -1, 1432, 1060, 653, -1, + 1735, 1736, 2018, -1, 1735, 2018, 1052, -1, + 1735, 1052, 1418, -1, 1735, 1418, 1058, -1, + 1442, 654, 1439, -1, 1442, 1880, 1400, -1, + 1442, 1439, 1880, -1, 1435, 1436, 1396, -1, + 1435, 1060, 1432, -1, 1445, 1396, 1436, -1, + 1445, 654, 1442, -1, 1434, 1439, 654, -1, + 1434, 654, 1445, -1, 1434, 1445, 1436, -1, + 1901, 1755, 2026, -1, 655, 2021, 1744, -1, + 655, 2023, 2021, -1, 655, 1744, 2023, -1, + 2029, 2021, 2023, -1, 659, 657, 1082, -1, + 659, 1082, 1038, -1, 1392, 656, 657, -1, + 1392, 658, 656, -1, 1392, 657, 659, -1, + 1392, 659, 1390, -1, 1392, 1391, 658, -1, + 1389, 659, 1038, -1, 1389, 1390, 659, -1, + 660, 663, 668, -1, 660, 1066, 663, -1, + 660, 668, 2162, -1, 660, 2162, 1066, -1, + 661, 1066, 662, -1, 661, 663, 1066, -1, + 661, 662, 2120, -1, 661, 664, 663, -1, + 661, 2120, 665, -1, 661, 665, 666, -1, + 661, 666, 664, -1, 1067, 1068, 1064, -1, + 974, 1643, 1761, -1, 974, 1759, 1935, -1, + 974, 1761, 1759, -1, 1644, 2088, 1072, -1, + 667, 1761, 1643, -1, 667, 1643, 1072, -1, + 667, 1072, 1761, -1, 1932, 2088, 2038, -1, + 1076, 668, 1942, -1, 1076, 1074, 668, -1, + 674, 671, 675, -1, 669, 670, 671, -1, + 669, 671, 674, -1, 669, 674, 673, -1, + 669, 672, 670, -1, 669, 673, 672, -1, + 1081, 1082, 673, -1, 1081, 674, 675, -1, + 1081, 673, 674, -1, 1081, 675, 676, -1, + 1081, 676, 1079, -1, 677, 1458, 678, -1, + 677, 1070, 1458, -1, 677, 678, 1069, -1, + 677, 1069, 1070, -1, 1642, 1641, 679, -1, + 1642, 679, 1635, -1, 1639, 1084, 2038, -1, + 680, 681, 685, -1, 680, 685, 686, -1, + 680, 686, 682, -1, 680, 682, 683, -1, + 680, 683, 681, -1, 684, 685, 691, -1, + 684, 686, 685, -1, 684, 691, 693, -1, + 684, 687, 686, -1, 684, 688, 687, -1, + 684, 693, 696, -1, 684, 696, 688, -1, + 689, 690, 835, -1, 689, 835, 693, -1, + 689, 691, 690, -1, 689, 693, 691, -1, + 692, 835, 834, -1, 692, 834, 829, -1, + 692, 693, 835, -1, 692, 694, 695, -1, + 692, 829, 694, -1, 692, 695, 696, -1, + 692, 696, 693, -1, 697, 699, 698, -1, + 697, 698, 700, -1, 697, 702, 701, -1, + 697, 700, 702, -1, 697, 701, 703, -1, + 697, 703, 704, -1, 697, 705, 699, -1, + 697, 704, 705, -1, 706, 707, 708, -1, + 706, 709, 707, -1, 706, 708, 710, -1, + 706, 710, 709, -1, 713, 711, 1093, -1, + 713, 923, 711, -1, 713, 1564, 923, -1, + 713, 1093, 1223, -1, 922, 712, 923, -1, + 922, 921, 712, -1, 1566, 713, 1223, -1, + 1566, 1564, 713, -1, 714, 716, 715, -1, + 714, 715, 717, -1, 714, 718, 716, -1, + 714, 719, 718, -1, 714, 717, 720, -1, + 714, 720, 719, -1, 1085, 1086, 721, -1, + 1085, 721, 1772, -1, 1463, 722, 1462, -1, + 1463, 1772, 722, -1, 1091, 1097, 723, -1, + 1091, 723, 1101, -1, 1091, 1101, 1100, -1, + 1098, 1223, 1093, -1, 1098, 1466, 1223, -1, + 1963, 1464, 1090, -1, 1963, 1090, 1962, -1, + 1104, 1962, 1100, -1, 724, 726, 725, -1, + 724, 725, 727, -1, 724, 739, 726, -1, + 724, 915, 739, -1, 724, 728, 915, -1, + 724, 729, 728, -1, 724, 727, 729, -1, + 1111, 730, 1105, -1, 1111, 731, 732, -1, + 1111, 732, 730, -1, 1111, 1110, 733, -1, + 1111, 733, 731, -1, 1473, 1111, 1105, -1, + 1472, 1475, 734, -1, 1472, 734, 1108, -1, + 1561, 1112, 738, -1, 735, 736, 737, -1, + 735, 738, 736, -1, 735, 737, 739, -1, + 735, 739, 912, -1, 735, 1561, 738, -1, + 735, 909, 1561, -1, 735, 906, 909, -1, + 735, 912, 906, -1, 740, 1128, 1129, -1, + 740, 1129, 741, -1, 740, 1130, 1128, -1, + 740, 742, 1130, -1, 740, 743, 742, -1, + 740, 741, 743, -1, 744, 764, 745, -1, + 744, 746, 764, -1, 744, 747, 746, -1, + 744, 745, 748, -1, 744, 748, 747, -1, + 759, 758, 749, -1, 759, 749, 752, -1, + 759, 752, 755, -1, 762, 755, 756, -1, + 762, 756, 750, -1, 762, 760, 759, -1, + 762, 759, 755, -1, 762, 750, 761, -1, + 751, 752, 753, -1, 751, 753, 754, -1, + 751, 755, 752, -1, 751, 754, 756, -1, + 751, 756, 755, -1, 1114, 1115, 757, -1, + 1114, 757, 758, -1, 1114, 758, 759, -1, + 1114, 759, 760, -1, 1116, 1114, 760, -1, + 1116, 761, 1238, -1, 1116, 760, 762, -1, + 1116, 762, 761, -1, 1116, 1238, 1239, -1, + 763, 764, 765, -1, 763, 766, 764, -1, + 763, 765, 1234, -1, 763, 1234, 1235, -1, + 763, 1235, 767, -1, 763, 767, 766, -1, + 1123, 780, 1149, -1, 1123, 1117, 780, -1, + 1125, 1152, 1121, -1, 1125, 1151, 1152, -1, + 1479, 1480, 1126, -1, 768, 769, 1145, -1, + 768, 1145, 1148, -1, 768, 1148, 769, -1, + 770, 772, 771, -1, 770, 771, 778, -1, + 770, 773, 772, -1, 770, 777, 773, -1, + 770, 778, 777, -1, 1118, 1156, 774, -1, + 1118, 775, 1119, -1, 1118, 774, 775, -1, + 776, 777, 778, -1, 776, 1117, 777, -1, + 776, 778, 779, -1, 776, 780, 1117, -1, + 776, 779, 780, -1, 1140, 1138, 1622, -1, + 781, 1136, 1191, -1, 781, 1191, 1196, -1, + 781, 1134, 1136, -1, 781, 1196, 1134, -1, + 1153, 782, 783, -1, 1153, 1151, 782, -1, + 1153, 783, 784, -1, 1153, 784, 1154, -1, + 1785, 1305, 1313, -1, 1493, 785, 1494, -1, + 1493, 1797, 785, -1, 1493, 1495, 1797, -1, + 1501, 1796, 1499, -1, 1501, 1289, 1796, -1, + 1492, 786, 787, -1, 1492, 1494, 786, -1, + 1492, 787, 1796, -1, 1492, 1796, 1289, -1, + 1160, 1796, 1503, -1, 1160, 1797, 788, -1, + 1160, 1503, 1797, -1, 1497, 1796, 1975, -1, + 1973, 788, 1797, -1, 1973, 1160, 788, -1, + 789, 972, 790, -1, 789, 1791, 972, -1, + 789, 790, 1792, -1, 789, 1792, 1791, -1, + 1292, 1162, 791, -1, 1292, 791, 1291, -1, + 1293, 1633, 970, -1, 1293, 970, 1163, -1, + 1293, 1163, 1292, -1, 1295, 1796, 1299, -1, + 1295, 1164, 1796, -1, 1502, 1796, 1164, -1, + 1502, 1164, 1507, -1, 1168, 792, 1173, -1, + 1168, 1173, 1167, -1, 1168, 1171, 792, -1, + 793, 794, 797, -1, 793, 797, 800, -1, + 793, 1173, 794, -1, 793, 800, 1173, -1, + 1166, 1167, 800, -1, 795, 796, 1513, -1, + 795, 797, 796, -1, 795, 1513, 1183, -1, + 795, 1183, 797, -1, 1169, 799, 798, -1, + 1169, 1183, 1170, -1, 1169, 798, 1183, -1, + 1169, 800, 799, -1, 1169, 1166, 800, -1, + 1804, 1183, 1800, -1, 1804, 1803, 801, -1, + 1804, 801, 1175, -1, 1181, 1177, 1176, -1, + 1181, 802, 1180, -1, 1181, 1176, 803, -1, + 1181, 803, 802, -1, 1181, 1183, 1177, -1, + 1515, 1185, 1523, -1, 1515, 804, 1185, -1, + 1515, 1184, 804, -1, 1524, 1523, 1185, -1, + 1520, 805, 1517, -1, 1520, 1521, 806, -1, + 1520, 806, 805, -1, 807, 808, 809, -1, + 807, 810, 811, -1, 807, 811, 812, -1, + 807, 813, 808, -1, 807, 812, 813, -1, + 807, 809, 814, -1, 807, 815, 810, -1, + 807, 814, 815, -1, 819, 821, 816, -1, + 819, 1527, 821, -1, 819, 816, 817, -1, + 819, 817, 818, -1, 1526, 818, 1188, -1, + 1526, 819, 818, -1, 1526, 1527, 819, -1, + 846, 820, 821, -1, 846, 845, 820, -1, + 1189, 1190, 843, -1, 1189, 843, 846, -1, + 1189, 821, 1192, -1, 1189, 846, 821, -1, + 822, 1204, 1533, -1, 822, 1540, 823, -1, + 822, 1533, 1540, -1, 822, 1205, 1204, -1, + 822, 823, 824, -1, 822, 824, 1205, -1, + 825, 1535, 1537, -1, 825, 1537, 1194, -1, + 825, 851, 1535, -1, 825, 1194, 851, -1, + 1193, 1539, 1196, -1, 1538, 826, 1197, -1, + 1538, 1536, 827, -1, 1538, 827, 826, -1, + 828, 834, 1199, -1, 828, 830, 829, -1, + 828, 829, 834, -1, 828, 831, 830, -1, + 828, 832, 831, -1, 828, 1199, 832, -1, + 833, 856, 1199, -1, 833, 1199, 834, -1, + 833, 835, 856, -1, 833, 834, 835, -1, + 1200, 1199, 856, -1, 836, 837, 841, -1, + 836, 841, 838, -1, 836, 839, 837, -1, + 836, 838, 967, -1, 836, 967, 839, -1, + 840, 841, 842, -1, 840, 843, 841, -1, + 840, 842, 844, -1, 840, 844, 845, -1, + 840, 845, 846, -1, 840, 846, 843, -1, + 853, 852, 847, -1, 853, 847, 848, -1, + 853, 848, 849, -1, 853, 849, 854, -1, + 850, 1206, 855, -1, 850, 1194, 1206, -1, + 850, 851, 1194, -1, 850, 855, 852, -1, + 850, 852, 853, -1, 850, 854, 851, -1, + 850, 853, 854, -1, 1202, 855, 1206, -1, + 1202, 1200, 856, -1, 1202, 856, 857, -1, + 1202, 857, 855, -1, 858, 860, 859, -1, + 858, 859, 861, -1, 858, 862, 860, -1, + 858, 863, 862, -1, 858, 864, 863, -1, + 858, 865, 864, -1, 858, 861, 865, -1, + 1215, 1468, 1209, -1, 1215, 873, 1216, -1, + 1215, 1209, 873, -1, 866, 1214, 868, -1, + 866, 871, 1214, -1, 866, 868, 871, -1, + 867, 871, 868, -1, 867, 868, 869, -1, + 867, 869, 870, -1, 867, 2056, 871, -1, + 867, 2057, 2056, -1, 867, 870, 2057, -1, + 1959, 1774, 871, -1, 1959, 871, 2056, -1, + 1213, 1214, 874, -1, 1807, 1216, 872, -1, + 1807, 872, 1808, -1, 1979, 1808, 1806, -1, + 1212, 873, 1210, -1, 1212, 1775, 873, -1, + 1212, 1213, 874, -1, 1212, 874, 1774, -1, + 1212, 1774, 1775, -1, 875, 877, 876, -1, + 875, 876, 878, -1, 875, 1115, 877, -1, + 875, 878, 1115, -1, 1544, 892, 879, -1, + 1544, 880, 1545, -1, 1544, 879, 880, -1, + 881, 882, 891, -1, 881, 891, 883, -1, + 881, 884, 885, -1, 881, 885, 882, -1, + 881, 886, 884, -1, 881, 883, 887, -1, + 881, 888, 889, -1, 881, 889, 886, -1, + 881, 890, 888, -1, 881, 887, 890, -1, + 1547, 1548, 891, -1, 1547, 891, 1217, -1, + 1542, 897, 892, -1, 1542, 1219, 897, -1, + 1542, 892, 1544, -1, 1550, 1769, 1089, -1, + 1550, 899, 896, -1, 1550, 893, 899, -1, + 1550, 896, 897, -1, 1550, 897, 1219, -1, + 1550, 1089, 894, -1, 1550, 894, 893, -1, + 895, 897, 896, -1, 895, 898, 897, -1, + 895, 896, 899, -1, 895, 899, 900, -1, + 895, 900, 898, -1, 1573, 901, 1571, -1, + 1573, 1576, 901, -1, 902, 904, 903, -1, + 902, 903, 1576, -1, 902, 1576, 1575, -1, + 902, 905, 904, -1, 902, 1575, 905, -1, + 910, 909, 906, -1, 910, 906, 913, -1, + 910, 913, 908, -1, 1220, 907, 1554, -1, + 1220, 908, 907, -1, 1220, 1561, 909, -1, + 1220, 909, 910, -1, 1220, 910, 908, -1, + 911, 913, 912, -1, 911, 914, 913, -1, + 911, 912, 915, -1, 911, 916, 914, -1, + 911, 915, 917, -1, 911, 918, 916, -1, + 911, 917, 918, -1, 1221, 919, 920, -1, + 1221, 920, 1222, -1, 1221, 1778, 919, -1, + 1779, 1566, 1223, -1, 1563, 1224, 921, -1, + 1563, 921, 922, -1, 1563, 923, 1564, -1, + 1563, 922, 923, -1, 1226, 925, 924, -1, + 1226, 1227, 925, -1, 1226, 924, 1584, -1, + 1570, 1571, 926, -1, 1570, 926, 1227, -1, + 1228, 1231, 927, -1, 1228, 928, 1229, -1, + 1228, 929, 928, -1, 1228, 930, 929, -1, + 1228, 931, 930, -1, 1228, 927, 931, -1, + 1822, 1232, 1239, -1, 932, 1240, 933, -1, + 932, 1582, 1240, -1, 932, 1572, 1582, -1, + 932, 934, 935, -1, 932, 933, 934, -1, + 932, 935, 1574, -1, 932, 1574, 1572, -1, + 1319, 950, 1318, -1, 1319, 1601, 1598, -1, + 1339, 936, 937, -1, 1339, 937, 1338, -1, + 1339, 1341, 936, -1, 2003, 938, 2001, -1, + 2003, 1338, 938, -1, 985, 939, 1346, -1, + 985, 986, 939, -1, 940, 1342, 1647, -1, + 940, 941, 1342, -1, 940, 942, 941, -1, + 940, 1647, 1838, -1, 940, 1838, 1839, -1, + 940, 1839, 942, -1, 1241, 1588, 943, -1, + 1241, 943, 1243, -1, 1586, 1242, 944, -1, + 1586, 944, 945, -1, 1586, 945, 1592, -1, + 1586, 1592, 1590, -1, 1826, 1589, 1588, -1, + 1245, 1255, 1269, -1, 1245, 1269, 1607, -1, + 1248, 1595, 1269, -1, 1249, 1253, 1261, -1, + 1249, 1261, 1595, -1, 1249, 1595, 1248, -1, + 1252, 1269, 1259, -1, 1252, 1259, 1253, -1, + 1258, 1259, 1255, -1, 1260, 1261, 1253, -1, + 1260, 1253, 1259, -1, 946, 1242, 1243, -1, + 946, 947, 1242, -1, 946, 1243, 948, -1, + 946, 948, 1244, -1, 946, 1244, 947, -1, + 1262, 1263, 1002, -1, 1262, 1002, 1264, -1, + 949, 1598, 1244, -1, 949, 1244, 950, -1, + 949, 1319, 1598, -1, 949, 950, 1319, -1, + 1610, 1595, 1268, -1, 1621, 1622, 951, -1, + 1621, 951, 1272, -1, 1621, 1272, 1271, -1, + 1617, 1621, 1271, -1, 952, 958, 956, -1, + 952, 956, 953, -1, 952, 953, 954, -1, + 952, 954, 955, -1, 952, 955, 958, -1, + 963, 962, 956, -1, 963, 956, 958, -1, + 957, 958, 959, -1, 957, 960, 961, -1, + 957, 959, 960, -1, 957, 961, 962, -1, + 957, 962, 963, -1, 957, 963, 958, -1, + 1276, 1273, 964, -1, 1276, 964, 1277, -1, + 1280, 965, 1274, -1, 1280, 1274, 1618, -1, + 1280, 966, 965, -1, 1280, 967, 966, -1, + 1280, 1279, 967, -1, 1832, 2117, 1987, -1, + 1682, 1835, 1836, -1, 1282, 1994, 1284, -1, + 1282, 1836, 1994, -1, 1624, 968, 1627, -1, + 1624, 1625, 968, -1, 1993, 1688, 1994, -1, + 1286, 1797, 1495, -1, 1286, 1287, 1797, -1, + 1505, 1300, 1797, -1, 1298, 1299, 969, -1, + 1298, 969, 970, -1, 1298, 970, 1633, -1, + 1311, 1636, 1310, -1, 1311, 1305, 1636, -1, + 1311, 1313, 1305, -1, 971, 972, 973, -1, + 971, 973, 1636, -1, 971, 1636, 972, -1, + 1638, 1636, 1315, -1, 1638, 1315, 1923, -1, + 1638, 1923, 1639, -1, 2048, 1937, 1757, -1, + 2048, 1757, 1636, -1, 2048, 1636, 2117, -1, + 2048, 974, 1935, -1, 2048, 1643, 974, -1, + 2048, 2117, 1944, -1, 1317, 1601, 1319, -1, + 975, 1318, 976, -1, 975, 1323, 1318, -1, + 1321, 1325, 1324, -1, 1321, 1323, 975, -1, + 1321, 975, 976, -1, 1321, 976, 1244, -1, + 1321, 1244, 1325, -1, 1330, 1332, 1588, -1, + 2004, 1337, 1338, -1, 2004, 1338, 2003, -1, + 977, 981, 978, -1, 977, 978, 980, -1, + 977, 980, 981, -1, 979, 981, 980, -1, + 979, 982, 981, -1, 979, 980, 982, -1, + 1649, 983, 1650, -1, 1649, 1342, 983, -1, + 984, 1346, 987, -1, 984, 987, 2005, -1, + 984, 985, 1346, -1, 984, 2005, 986, -1, + 984, 986, 985, -1, 1659, 1660, 2005, -1, + 1659, 2005, 1343, -1, 1654, 2005, 1655, -1, + 1654, 1343, 2005, -1, 1656, 1657, 1345, -1, + 1656, 1346, 1664, -1, 1656, 1345, 1346, -1, + 1347, 987, 1346, -1, 1347, 1657, 987, -1, + 1348, 988, 1349, -1, 1348, 1346, 988, -1, + 1348, 1663, 1346, -1, 1354, 989, 1353, -1, + 1354, 1352, 992, -1, 1354, 994, 989, -1, + 1354, 992, 994, -1, 990, 1352, 991, -1, + 990, 992, 1352, -1, 990, 991, 993, -1, + 990, 993, 994, -1, 990, 994, 992, -1, + 1600, 1601, 1317, -1, 1600, 1317, 1588, -1, + 1599, 1588, 1263, -1, 1599, 1600, 1588, -1, + 995, 1244, 996, -1, 995, 996, 998, -1, + 995, 998, 1244, -1, 997, 998, 999, -1, + 997, 999, 1000, -1, 997, 1002, 1001, -1, + 997, 1001, 998, -1, 997, 1264, 1002, -1, + 997, 1000, 1264, -1, 1003, 1016, 1517, -1, + 1003, 1517, 1358, -1, 1003, 1004, 1016, -1, + 1003, 1358, 1004, -1, 1005, 1006, 1373, -1, + 1005, 1007, 1006, -1, 1005, 1008, 1007, -1, + 1005, 1372, 1008, -1, 1005, 1373, 1372, -1, + 1011, 1517, 1010, -1, 1009, 1010, 1356, -1, + 1009, 1356, 1355, -1, 1009, 1011, 1010, -1, + 1009, 1355, 1517, -1, 1009, 1517, 1011, -1, + 1360, 1356, 1361, -1, 1368, 1369, 1362, -1, + 1368, 1362, 1012, -1, 1368, 1012, 1372, -1, + 1370, 1371, 1013, -1, 1370, 1013, 1016, -1, + 1014, 1016, 1015, -1, 1014, 1015, 1369, -1, + 1014, 1370, 1016, -1, 1014, 1369, 1370, -1, + 1374, 1376, 1069, -1, 1374, 1069, 1665, -1, + 1847, 1666, 2162, -1, 1026, 1017, 1024, -1, + 1026, 1019, 1017, -1, 1026, 1022, 1019, -1, + 1026, 1025, 1022, -1, 1018, 1375, 1840, -1, + 1018, 1022, 1375, -1, 1018, 1840, 2074, -1, + 1018, 1019, 1022, -1, 1018, 2074, 1019, -1, + 1020, 1022, 1021, -1, 1020, 1376, 1022, -1, + 1020, 1021, 1069, -1, 1020, 1069, 1376, -1, + 1023, 1024, 1069, -1, 1023, 1069, 1025, -1, + 1023, 1026, 1024, -1, 1023, 1025, 1026, -1, + 1032, 1027, 1030, -1, 1032, 1028, 1027, -1, + 1032, 1033, 1028, -1, 1029, 1030, 1031, -1, + 1029, 1033, 1032, -1, 1029, 1032, 1030, -1, + 1029, 1034, 1173, -1, 1029, 1173, 1033, -1, + 1029, 1035, 1034, -1, 1029, 1031, 1035, -1, + 1676, 1036, 1677, -1, 1678, 1854, 1036, -1, + 1678, 1036, 1676, -1, 1680, 1688, 1681, -1, + 1037, 1395, 1877, -1, 1037, 1877, 1045, -1, + 1037, 1045, 1395, -1, 1388, 1045, 1877, -1, + 1388, 1038, 1042, -1, 1388, 1389, 1038, -1, + 1044, 1039, 1045, -1, 1044, 1043, 1040, -1, + 1044, 1040, 1039, -1, 1041, 1042, 1043, -1, + 1041, 1043, 1044, -1, 1041, 1044, 1045, -1, + 1041, 1388, 1042, -1, 1041, 1045, 1388, -1, + 2008, 2120, 2009, -1, 2008, 1692, 2120, -1, + 1393, 1862, 1692, -1, 1402, 1396, 1709, -1, + 1402, 1050, 1396, -1, 1401, 1050, 1402, -1, + 1046, 1400, 1398, -1, 1046, 1061, 1400, -1, + 1046, 1398, 1061, -1, 1047, 1400, 1061, -1, + 1047, 1061, 1443, -1, 1047, 1442, 1400, -1, + 1047, 1443, 1442, -1, 1406, 1396, 1413, -1, + 1406, 1407, 1396, -1, 1412, 1413, 1396, -1, + 1412, 1396, 1051, -1, 1713, 1396, 1714, -1, + 1713, 1717, 1396, -1, 1048, 1882, 1049, -1, + 1048, 1883, 1882, -1, 1048, 1049, 1050, -1, + 1048, 1401, 1883, -1, 1048, 1050, 1401, -1, + 1415, 1416, 1880, -1, 1410, 1719, 1880, -1, + 1410, 1880, 1416, -1, 1414, 1051, 1409, -1, + 1414, 1409, 1416, -1, 1414, 1412, 1051, -1, + 1419, 1418, 1052, -1, 1419, 1052, 2018, -1, + 1722, 1721, 1733, -1, 1722, 1733, 1422, -1, + 1053, 2018, 1724, -1, 1423, 1422, 1420, -1, + 1423, 1053, 1724, -1, 1423, 2018, 1053, -1, + 1423, 1419, 2018, -1, 1423, 1420, 1419, -1, + 1054, 1428, 1431, -1, 1054, 1427, 1428, -1, + 1054, 1431, 1733, -1, 1054, 1733, 1427, -1, + 1426, 1055, 1056, -1, 1426, 1432, 1055, -1, + 1426, 1425, 1432, -1, 1730, 1426, 1056, -1, + 1730, 1056, 1428, -1, 1429, 1058, 1057, -1, + 1429, 1735, 1058, -1, 1429, 1057, 1430, -1, + 1059, 1396, 1060, -1, 1059, 1435, 1396, -1, + 1059, 1060, 1435, -1, 1440, 1432, 1425, -1, + 1440, 1425, 1880, -1, 1440, 1439, 1434, -1, + 1444, 1061, 1396, -1, 1444, 1396, 1445, -1, + 1444, 1443, 1061, -1, 1448, 1449, 1752, -1, + 1448, 2037, 1447, -1, 1753, 1755, 1756, -1, + 1452, 1911, 1904, -1, 1452, 1755, 1911, -1, + 2035, 1452, 1904, -1, 1906, 1905, 2037, -1, + 1906, 2035, 1904, -1, 1895, 1896, 1062, -1, + 1895, 1062, 1454, -1, 1455, 1727, 1895, -1, + 1457, 1064, 1063, -1, 1457, 1067, 1064, -1, + 1457, 2074, 1065, -1, 1457, 1065, 1458, -1, + 1457, 1066, 2074, -1, 1457, 1063, 1066, -1, + 1459, 1068, 1067, -1, 1459, 1069, 1068, -1, + 1459, 1070, 1069, -1, 1459, 1458, 1070, -1, + 1459, 1067, 1457, -1, 1071, 1072, 1643, -1, + 1071, 1643, 1644, -1, 1071, 1644, 1072, -1, + 1927, 1932, 2038, -1, 1073, 1944, 2117, -1, + 1073, 1075, 1944, -1, 1073, 2117, 1074, -1, + 1073, 1074, 1075, -1, 1077, 1075, 1074, -1, + 1077, 1074, 1076, -1, 1077, 1944, 1075, -1, + 1943, 1076, 1942, -1, 1943, 1944, 1077, -1, + 1943, 1077, 1076, -1, 1078, 1079, 1080, -1, + 1078, 1081, 1079, -1, 1078, 1080, 1082, -1, + 1078, 1082, 1081, -1, 1083, 1639, 1923, -1, + 1083, 1084, 1639, -1, 1083, 2038, 1084, -1, + 1083, 1924, 2038, -1, 1083, 1923, 1924, -1, + 1957, 1085, 1772, -1, 1957, 1086, 1085, -1, + 1957, 1770, 1087, -1, 1957, 1087, 1088, -1, + 1957, 1088, 1086, -1, 1768, 1462, 1089, -1, + 1768, 1089, 1769, -1, 1099, 1100, 1090, -1, + 1099, 1091, 1100, -1, 1099, 1090, 1464, -1, + 1099, 1097, 1091, -1, 1099, 1464, 1466, -1, + 1092, 1098, 1093, -1, 1092, 1096, 1098, -1, + 1092, 1093, 1094, -1, 1092, 1094, 1096, -1, + 1095, 1096, 1097, -1, 1095, 1098, 1096, -1, + 1095, 1097, 1099, -1, 1095, 1466, 1098, -1, + 1095, 1099, 1466, -1, 1781, 1218, 1778, -1, + 1103, 1100, 1101, -1, 1103, 1104, 1100, -1, + 1103, 1101, 1102, -1, 1467, 1102, 1468, -1, + 1467, 1103, 1102, -1, 1467, 1104, 1103, -1, + 1467, 1962, 1104, -1, 1474, 1105, 1106, -1, + 1474, 1473, 1105, -1, 1474, 1107, 1477, -1, + 1474, 1106, 1107, -1, 1470, 1472, 1108, -1, + 1470, 1108, 1109, -1, 1470, 1109, 1110, -1, + 1470, 1110, 1111, -1, 1470, 1473, 1471, -1, + 1470, 1111, 1473, -1, 1560, 1559, 1112, -1, + 1560, 1112, 1561, -1, 1113, 1115, 1114, -1, + 1113, 1114, 1116, -1, 1113, 1239, 1115, -1, + 1113, 1116, 1239, -1, 1122, 1117, 1123, -1, + 1122, 1157, 1156, -1, 1122, 1156, 1118, -1, + 1122, 1119, 1117, -1, 1122, 1118, 1119, -1, + 1120, 1125, 1121, -1, 1120, 1121, 1157, -1, + 1120, 1131, 1125, -1, 1120, 1157, 1122, -1, + 1120, 1122, 1123, -1, 1120, 1149, 1131, -1, + 1120, 1123, 1149, -1, 1124, 1125, 1131, -1, + 1124, 1131, 1479, -1, 1124, 1479, 1126, -1, + 1124, 1126, 1127, -1, 1124, 1129, 1128, -1, + 1124, 1127, 1129, -1, 1124, 1128, 1130, -1, + 1124, 1130, 1151, -1, 1124, 1151, 1125, -1, + 1481, 1131, 1149, -1, 1481, 1479, 1131, -1, + 1481, 1149, 1147, -1, 1481, 1133, 1480, -1, + 1146, 1141, 1136, -1, 1146, 1136, 1134, -1, + 1146, 1134, 1147, -1, 1132, 1196, 1133, -1, + 1132, 1134, 1196, -1, 1132, 1133, 1481, -1, + 1132, 1147, 1134, -1, 1132, 1481, 1147, -1, + 1135, 1136, 1141, -1, 1135, 1141, 1140, -1, + 1135, 1622, 1136, -1, 1135, 1140, 1622, -1, + 1137, 1139, 1138, -1, 1137, 1138, 1140, -1, + 1137, 1140, 1141, -1, 1137, 1143, 1142, -1, + 1137, 1144, 1139, -1, 1137, 1142, 1144, -1, + 1137, 1145, 1143, -1, 1137, 1146, 1147, -1, + 1137, 1141, 1146, -1, 1137, 1148, 1145, -1, + 1137, 1147, 1149, -1, 1137, 1149, 1148, -1, + 1150, 1152, 1151, -1, 1150, 1151, 1153, -1, + 1150, 1153, 1154, -1, 1150, 1154, 1155, -1, + 1150, 1155, 1156, -1, 1150, 1157, 1152, -1, + 1150, 1156, 1157, -1, 1784, 1785, 1313, -1, + 1784, 1313, 1312, -1, 1784, 1312, 1792, -1, + 1488, 1312, 1487, -1, 1488, 1792, 1312, -1, + 1500, 1159, 1501, -1, 1158, 1159, 1287, -1, + 1158, 1501, 1159, -1, 1158, 1287, 1501, -1, + 1288, 1289, 1501, -1, 1288, 1501, 1287, -1, + 1491, 1492, 1289, -1, 1498, 1499, 1796, -1, + 1498, 1796, 1497, -1, 1974, 1797, 1159, -1, + 1974, 1159, 1500, -1, 1976, 1160, 1973, -1, + 1976, 1796, 1160, -1, 1972, 1973, 1797, -1, + 1161, 1162, 1292, -1, 1161, 1292, 1163, -1, + 1161, 1796, 1162, -1, 1161, 1163, 1796, -1, + 1296, 1507, 1164, -1, 1296, 1164, 1295, -1, + 1296, 1505, 1507, -1, 1165, 1167, 1166, -1, + 1165, 1168, 1167, -1, 1165, 1169, 1170, -1, + 1165, 1166, 1169, -1, 1165, 1170, 1171, -1, + 1165, 1171, 1168, -1, 1509, 1172, 1173, -1, + 1509, 1173, 1510, -1, 1509, 1511, 1172, -1, + 1801, 1173, 1802, -1, 1801, 1510, 1173, -1, + 1174, 1804, 1175, -1, 1174, 1175, 1176, -1, + 1174, 1176, 1177, -1, 1174, 1177, 1183, -1, + 1174, 1183, 1804, -1, 1178, 1180, 1179, -1, + 1178, 1181, 1180, -1, 1178, 1179, 1182, -1, + 1178, 1182, 1183, -1, 1178, 1183, 1181, -1, + 1516, 1184, 1515, -1, 1516, 1517, 1184, -1, + 1522, 1524, 1185, -1, 1522, 1185, 1186, -1, + 1522, 1186, 1362, -1, 1522, 1362, 1521, -1, + 1519, 1517, 1523, -1, 1519, 1520, 1517, -1, + 1528, 1188, 1187, -1, 1528, 1526, 1188, -1, + 1528, 1187, 1539, -1, 1530, 1190, 1189, -1, + 1530, 1191, 1190, -1, 1530, 1192, 1529, -1, + 1530, 1189, 1192, -1, 1530, 1539, 1193, -1, + 1530, 1196, 1191, -1, 1530, 1193, 1196, -1, + 1532, 1533, 1204, -1, 1532, 1204, 1194, -1, + 1532, 1194, 1537, -1, 1532, 1537, 1534, -1, + 1195, 1197, 1196, -1, 1195, 1538, 1197, -1, + 1195, 1196, 1539, -1, 1195, 1539, 1538, -1, + 1198, 1203, 1199, -1, 1198, 1199, 1200, -1, + 1198, 1202, 1203, -1, 1198, 1200, 1202, -1, + 1201, 1203, 1202, -1, 1201, 1204, 1205, -1, + 1201, 1205, 1203, -1, 1201, 1206, 1204, -1, + 1201, 1202, 1206, -1, 1815, 1468, 1215, -1, + 1207, 1209, 1208, -1, 1207, 1210, 1209, -1, + 1207, 1208, 1211, -1, 1207, 1212, 1210, -1, + 1207, 1213, 1212, -1, 1207, 1211, 1214, -1, + 1207, 1214, 1213, -1, 1814, 1815, 1215, -1, + 1814, 1215, 1216, -1, 1814, 1216, 1807, -1, + 1813, 1545, 1548, -1, 1813, 1811, 1545, -1, + 1782, 1217, 1218, -1, 1782, 1547, 1217, -1, + 1782, 1218, 1781, -1, 1782, 1781, 1968, -1, + 1551, 1219, 1542, -1, 1551, 1550, 1219, -1, + 1551, 1543, 1552, -1, 1551, 1542, 1543, -1, + 1556, 1220, 1554, -1, 1556, 1561, 1220, -1, + 1567, 1778, 1221, -1, 1567, 1221, 1222, -1, + 1567, 1779, 1778, -1, 1567, 1222, 1568, -1, + 1465, 1223, 1466, -1, 1465, 1779, 1223, -1, + 1565, 1224, 1563, -1, 1565, 1225, 1224, -1, + 1565, 1568, 1225, -1, 1583, 1226, 1584, -1, + 1583, 1227, 1226, -1, 1583, 1570, 1227, -1, + 1233, 1228, 1229, -1, 1233, 1231, 1228, -1, + 1233, 1229, 1232, -1, 1230, 1821, 1231, -1, + 1230, 1822, 1821, -1, 1230, 1232, 1822, -1, + 1230, 1233, 1232, -1, 1230, 1231, 1233, -1, + 1580, 1234, 1579, -1, 1580, 1235, 1234, -1, + 1580, 1236, 1235, -1, 1580, 1581, 1236, -1, + 1823, 1236, 1581, -1, 1823, 1238, 1237, -1, + 1823, 1237, 1236, -1, 1823, 1239, 1238, -1, + 1823, 1822, 1239, -1, 1819, 1578, 1240, -1, + 1819, 1240, 1582, -1, 1587, 1588, 1241, -1, + 1587, 1242, 1586, -1, 1587, 1243, 1242, -1, + 1587, 1241, 1243, -1, 1829, 1244, 1830, -1, + 1829, 1591, 1244, -1, 1825, 1588, 1590, -1, + 1825, 1826, 1588, -1, 1606, 1255, 1245, -1, + 1606, 1245, 1607, -1, 1246, 1269, 1251, -1, + 1246, 1248, 1269, -1, 1246, 1251, 1248, -1, + 1254, 1253, 1249, -1, 1254, 1249, 1251, -1, + 1247, 1248, 1251, -1, 1247, 1251, 1249, -1, + 1247, 1249, 1248, -1, 1250, 1251, 1269, -1, + 1250, 1269, 1252, -1, 1250, 1252, 1253, -1, + 1250, 1253, 1254, -1, 1250, 1254, 1251, -1, + 1257, 1258, 1255, -1, 1257, 1606, 1594, -1, + 1257, 1255, 1606, -1, 1256, 1257, 1594, -1, + 1256, 1258, 1257, -1, 1256, 1259, 1258, -1, + 1256, 1260, 1259, -1, 1256, 1594, 1595, -1, + 1256, 1261, 1260, -1, 1256, 1595, 1261, -1, + 1597, 1263, 1262, -1, 1597, 1599, 1263, -1, + 1597, 1264, 1265, -1, 1597, 1262, 1264, -1, + 1597, 1265, 1598, -1, 1602, 1615, 1266, -1, + 1602, 1266, 1267, -1, 1613, 1267, 1595, -1, + 1613, 1595, 1610, -1, 1613, 1602, 1267, -1, + 1611, 1269, 1615, -1, 1611, 1612, 1269, -1, + 1609, 1610, 1268, -1, 1609, 1268, 1604, -1, + 1605, 1607, 1269, -1, 1605, 1269, 1612, -1, + 1270, 1618, 1617, -1, 1270, 1276, 1618, -1, + 1270, 1271, 1272, -1, 1270, 1617, 1271, -1, + 1270, 1272, 1273, -1, 1270, 1273, 1276, -1, + 1619, 1618, 1274, -1, 1619, 1274, 1620, -1, + 1275, 1276, 1277, -1, 1275, 1618, 1276, -1, + 1275, 1277, 1278, -1, 1275, 1278, 1279, -1, + 1275, 1279, 1280, -1, 1275, 1280, 1618, -1, + 1668, 2117, 2155, -1, 1668, 2150, 2117, -1, + 1831, 2107, 2117, -1, 1831, 2117, 1832, -1, + 1281, 1284, 1682, -1, 1281, 1682, 1836, -1, + 1281, 1282, 1284, -1, 1281, 1836, 1282, -1, + 1283, 1284, 1688, -1, 1283, 1682, 1284, -1, + 1283, 1688, 1680, -1, 1283, 1680, 1682, -1, + 1834, 1835, 1625, -1, 1628, 1626, 1688, -1, + 1628, 1688, 1993, -1, 1285, 1287, 1286, -1, + 1285, 1289, 1288, -1, 1285, 1288, 1287, -1, + 1285, 1286, 1495, -1, 1285, 1495, 1491, -1, + 1285, 1491, 1289, -1, 1290, 1291, 1797, -1, + 1290, 1797, 1631, -1, 1290, 1292, 1291, -1, + 1290, 1293, 1292, -1, 1290, 1633, 1293, -1, + 1290, 1631, 1633, -1, 1632, 1797, 1300, -1, + 1632, 1298, 1633, -1, 1632, 1300, 1298, -1, + 1294, 1301, 1300, -1, 1294, 1300, 1505, -1, + 1294, 1299, 1301, -1, 1294, 1295, 1299, -1, + 1294, 1296, 1295, -1, 1294, 1505, 1296, -1, + 1297, 1299, 1298, -1, 1297, 1298, 1300, -1, + 1297, 1301, 1299, -1, 1297, 1300, 1301, -1, + 1483, 1302, 1636, -1, 1483, 1636, 1307, -1, + 1483, 1303, 1302, -1, 1483, 1307, 1482, -1, + 1483, 1485, 1303, -1, 1483, 1484, 1485, -1, + 1304, 1636, 1305, -1, 1304, 1308, 1636, -1, + 1304, 1305, 1785, -1, 1304, 1785, 1482, -1, + 1304, 1482, 1308, -1, 1306, 1482, 1307, -1, + 1306, 1308, 1482, -1, 1306, 1307, 1636, -1, + 1306, 1636, 1308, -1, 1309, 1310, 1487, -1, + 1309, 1311, 1310, -1, 1309, 1487, 1312, -1, + 1309, 1312, 1313, -1, 1309, 1313, 1311, -1, + 1314, 1315, 1636, -1, 1314, 1636, 1460, -1, + 1314, 1922, 1315, -1, 1314, 1765, 1922, -1, + 1314, 1460, 1765, -1, 1461, 1636, 1757, -1, + 1640, 1636, 1638, -1, 1645, 1643, 2048, -1, + 1949, 1947, 2048, -1, 1316, 1323, 1588, -1, + 1316, 1588, 1317, -1, 1316, 1318, 1323, -1, + 1316, 1319, 1318, -1, 1316, 1317, 1319, -1, + 1320, 1324, 1323, -1, 1320, 1321, 1324, -1, + 1320, 1323, 1321, -1, 1322, 1323, 1324, -1, + 1322, 1324, 1330, -1, 1322, 1588, 1323, -1, + 1322, 1330, 1588, -1, 1328, 1330, 1324, -1, + 1328, 1325, 1327, -1, 1328, 1324, 1325, -1, + 1326, 1327, 1331, -1, 1326, 1331, 1330, -1, + 1326, 1328, 1327, -1, 1326, 1330, 1328, -1, + 1329, 1330, 1331, -1, 1329, 1332, 1330, -1, + 1329, 1333, 1332, -1, 1329, 1331, 1334, -1, + 1329, 1334, 1333, -1, 1335, 2005, 1336, -1, + 1335, 2004, 2005, -1, 1335, 1337, 2004, -1, + 1335, 1338, 1337, -1, 1335, 1339, 1338, -1, + 1335, 1336, 1340, -1, 1335, 1340, 1341, -1, + 1335, 1341, 1339, -1, 1651, 1342, 1649, -1, + 1651, 2005, 1342, -1, 1661, 1343, 1654, -1, + 1661, 1659, 1343, -1, 1661, 1656, 1664, -1, + 1344, 1346, 1345, -1, 1344, 1345, 1657, -1, + 1344, 1347, 1346, -1, 1344, 1657, 1347, -1, + 1662, 1348, 1349, -1, 1662, 1350, 1660, -1, + 1662, 1349, 1350, -1, 1662, 1663, 1348, -1, + 1351, 1353, 1352, -1, 1351, 1354, 1353, -1, + 1351, 1352, 1354, -1, 1357, 1355, 1356, -1, + 1357, 1517, 1355, -1, 1364, 1356, 1360, -1, + 1364, 1357, 1356, -1, 1364, 1365, 1358, -1, + 1364, 1517, 1357, -1, 1364, 1358, 1517, -1, + 1359, 1360, 1361, -1, 1359, 1361, 1362, -1, + 1359, 1362, 1363, -1, 1359, 1365, 1364, -1, + 1359, 1364, 1360, -1, 1359, 1363, 1366, -1, + 1359, 1366, 1365, -1, 1367, 1369, 1368, -1, + 1367, 1371, 1370, -1, 1367, 1370, 1369, -1, + 1367, 1368, 1372, -1, 1367, 1372, 1373, -1, + 1367, 1373, 1371, -1, 1845, 1374, 1665, -1, + 1845, 1840, 1375, -1, 1845, 1375, 1376, -1, + 1845, 1376, 1374, -1, 1846, 2162, 1377, -1, + 1846, 1847, 2162, -1, 1846, 1377, 2117, -1, + 2090, 2162, 1666, -1, 1849, 2157, 2162, -1, + 1991, 2137, 2117, -1, 1991, 2117, 2083, -1, + 1671, 2155, 2117, -1, 1671, 2154, 2155, -1, + 1379, 1672, 1380, -1, 1379, 1835, 1672, -1, + 1379, 1381, 1835, -1, 1378, 1380, 1384, -1, + 1378, 1384, 1385, -1, 1378, 1385, 1381, -1, + 1378, 1381, 1379, -1, 1378, 1379, 1380, -1, + 1853, 1384, 1380, -1, 1853, 1854, 1384, -1, + 1853, 1380, 1672, -1, 1674, 1381, 1385, -1, + 1674, 1383, 1678, -1, 1674, 1678, 1675, -1, + 1674, 1835, 1381, -1, 1382, 1678, 1383, -1, + 1382, 1854, 1678, -1, 1382, 1384, 1854, -1, + 1382, 1385, 1384, -1, 1382, 1383, 1674, -1, + 1382, 1674, 1385, -1, 1855, 1860, 1835, -1, + 1386, 1684, 1835, -1, 1386, 1835, 1860, -1, + 1685, 1690, 1672, -1, 1685, 1672, 1835, -1, + 1691, 1852, 1672, -1, 1691, 1672, 1690, -1, + 1686, 1690, 1684, -1, 1686, 1684, 1386, -1, + 1686, 1386, 1860, -1, 1689, 1858, 1688, -1, + 1689, 1690, 1686, -1, 1387, 1389, 1388, -1, + 1387, 1390, 1389, -1, 1387, 1877, 1391, -1, + 1387, 1388, 1877, -1, 1387, 1391, 1392, -1, + 1387, 1392, 1390, -1, 2091, 1393, 1692, -1, + 2091, 1862, 1393, -1, 2094, 1862, 2095, -1, + 1696, 1869, 1700, -1, 1696, 2120, 1869, -1, + 1702, 1862, 1694, -1, 1697, 1694, 1864, -1, + 1697, 1864, 1863, -1, 1697, 1702, 1694, -1, + 1868, 1394, 1867, -1, 1868, 1395, 1394, -1, + 1878, 1395, 1868, -1, 1878, 1877, 1395, -1, + 1873, 1703, 1862, -1, 1873, 1862, 1705, -1, + 1399, 1711, 1709, -1, 1399, 1709, 1396, -1, + 1399, 1396, 1398, -1, 1397, 1398, 1400, -1, + 1397, 1400, 1711, -1, 1397, 1399, 1398, -1, + 1397, 1711, 1399, -1, 1706, 1711, 1400, -1, + 1706, 1400, 1880, -1, 1403, 1710, 1880, -1, + 1403, 1883, 1401, -1, 1403, 1880, 1883, -1, + 1708, 1401, 1402, -1, 1708, 1402, 1709, -1, + 1708, 1710, 1403, -1, 1708, 1403, 1401, -1, + 1879, 1880, 1719, -1, 1408, 1404, 1407, -1, + 1408, 1880, 1404, -1, 1408, 1415, 1880, -1, + 1405, 1413, 1415, -1, 1405, 1406, 1413, -1, + 1405, 1407, 1406, -1, 1405, 1408, 1407, -1, + 1405, 1415, 1408, -1, 1716, 1416, 1409, -1, + 1716, 1410, 1416, -1, 1716, 1719, 1410, -1, + 1716, 1409, 1717, -1, 1411, 1413, 1412, -1, + 1411, 1412, 1414, -1, 1411, 1415, 1413, -1, + 1411, 1416, 1415, -1, 1411, 1414, 1416, -1, + 1417, 1733, 1418, -1, 1417, 1418, 1419, -1, + 1417, 1420, 1733, -1, 1417, 1419, 1420, -1, + 1723, 1422, 1724, -1, 1723, 1722, 1422, -1, + 1421, 1724, 1422, -1, 1421, 1422, 1423, -1, + 1421, 1423, 1724, -1, 1888, 1724, 2018, -1, + 1424, 1731, 1425, -1, 1424, 1425, 1426, -1, + 1424, 1730, 1731, -1, 1424, 1426, 1730, -1, + 1732, 1428, 1427, -1, 1732, 1730, 1428, -1, + 1732, 1427, 1733, -1, 1737, 1429, 1430, -1, + 1737, 1430, 1431, -1, 1737, 1431, 1739, -1, + 1737, 1735, 1429, -1, 1437, 1435, 1432, -1, + 1437, 1432, 1440, -1, 1433, 1440, 1434, -1, + 1433, 1436, 1435, -1, 1433, 1434, 1436, -1, + 1433, 1435, 1437, -1, 1433, 1437, 1440, -1, + 1438, 1880, 1439, -1, 1438, 1440, 1880, -1, + 1438, 1439, 1440, -1, 1441, 1442, 1443, -1, + 1441, 1443, 1444, -1, 1441, 1445, 1442, -1, + 1441, 1444, 1445, -1, 1741, 1747, 2024, -1, + 1741, 2023, 1744, -1, 1741, 2024, 2023, -1, + 1743, 1901, 2026, -1, 1743, 2026, 1747, -1, + 1908, 1755, 1901, -1, 1908, 1899, 1909, -1, + 1914, 2021, 2029, -1, 1915, 2026, 1746, -1, + 1446, 1450, 1449, -1, 1446, 2037, 1450, -1, + 1446, 1447, 2037, -1, 1446, 1448, 1447, -1, + 1446, 1449, 1448, -1, 1750, 1448, 1752, -1, + 1750, 2037, 1448, -1, 1451, 1450, 1755, -1, + 1754, 1752, 1449, -1, 1754, 1449, 1450, -1, + 1754, 1450, 1451, -1, 1754, 1451, 1755, -1, + 1919, 1916, 1752, -1, 1919, 1753, 1756, -1, + 1917, 1452, 2035, -1, 1917, 1756, 1755, -1, + 1917, 1755, 1452, -1, 1725, 1727, 1455, -1, + 1725, 2026, 1726, -1, 1725, 1455, 2026, -1, + 1453, 1895, 1454, -1, 1453, 1455, 1895, -1, + 1453, 1454, 2026, -1, 1453, 2026, 1455, -1, + 1456, 1457, 1458, -1, 1456, 1458, 1459, -1, + 1456, 1459, 1457, -1, 2051, 1645, 2048, -1, + 1763, 2048, 1941, -1, 2139, 2088, 2140, -1, + 2041, 1765, 1460, -1, 2041, 1460, 1636, -1, + 2041, 1636, 1461, -1, 2041, 1461, 1757, -1, + 2041, 1757, 1758, -1, 1767, 1463, 1462, -1, + 1767, 1462, 1768, -1, 1954, 1552, 1955, -1, + 1771, 1772, 1463, -1, 1771, 1463, 1767, -1, + 2066, 1774, 1959, -1, 1780, 1464, 1963, -1, + 1780, 1779, 1465, -1, 1780, 1466, 1464, -1, + 1780, 1465, 1466, -1, 1961, 1962, 1467, -1, + 1961, 1815, 1967, -1, 1961, 1467, 1468, -1, + 1961, 1468, 1815, -1, 1469, 1470, 1471, -1, + 1469, 1472, 1470, -1, 1469, 1471, 1473, -1, + 1469, 1473, 1474, -1, 1469, 1476, 1475, -1, + 1469, 1475, 1472, -1, 1469, 1477, 1476, -1, + 1469, 1474, 1477, -1, 1478, 1480, 1479, -1, + 1478, 1481, 1480, -1, 1478, 1479, 1481, -1, + 1786, 1482, 1785, -1, 1786, 1483, 1482, -1, + 1786, 1484, 1483, -1, 1786, 1485, 1484, -1, + 1786, 1792, 1485, -1, 1788, 1487, 1486, -1, + 1788, 1488, 1487, -1, 1788, 1489, 1789, -1, + 1788, 1486, 1489, -1, 1788, 1792, 1488, -1, + 1490, 1492, 1491, -1, 1490, 1493, 1494, -1, + 1490, 1494, 1492, -1, 1490, 1495, 1493, -1, + 1490, 1491, 1495, -1, 1496, 1497, 1975, -1, + 1496, 1975, 1974, -1, 1496, 1498, 1497, -1, + 1496, 1499, 1498, -1, 1496, 1974, 1500, -1, + 1496, 1501, 1499, -1, 1496, 1500, 1501, -1, + 1508, 1502, 1507, -1, 1508, 1506, 1797, -1, + 1508, 1797, 1503, -1, 1508, 1503, 1796, -1, + 1508, 1796, 1502, -1, 1504, 1505, 1797, -1, + 1504, 1797, 1506, -1, 1504, 1507, 1505, -1, + 1504, 1508, 1507, -1, 1504, 1506, 1508, -1, + 1799, 1509, 1510, -1, 1799, 1510, 1801, -1, + 1799, 1511, 1509, -1, 1799, 1800, 1512, -1, + 1799, 1513, 1511, -1, 1799, 1512, 1513, -1, + 1514, 1515, 1523, -1, 1514, 1516, 1515, -1, + 1514, 1523, 1517, -1, 1514, 1517, 1516, -1, + 1518, 1520, 1519, -1, 1518, 1521, 1520, -1, + 1518, 1522, 1521, -1, 1518, 1519, 1523, -1, + 1518, 1523, 1524, -1, 1518, 1524, 1522, -1, + 1525, 1527, 1526, -1, 1525, 1526, 1528, -1, + 1525, 1529, 1527, -1, 1525, 1530, 1529, -1, + 1525, 1528, 1539, -1, 1525, 1539, 1530, -1, + 1531, 1533, 1532, -1, 1531, 1532, 1534, -1, + 1531, 1535, 1536, -1, 1531, 1537, 1535, -1, + 1531, 1534, 1537, -1, 1531, 1536, 1538, -1, + 1531, 1538, 1539, -1, 1531, 1540, 1533, -1, + 1531, 1539, 1540, -1, 1541, 1805, 1806, -1, + 1541, 1544, 1805, -1, 1541, 1542, 1544, -1, + 1541, 1806, 1543, -1, 1541, 1543, 1542, -1, + 1810, 1805, 1544, -1, 1810, 1544, 1545, -1, + 1810, 1545, 1811, -1, 1546, 1547, 1782, -1, + 1546, 1548, 1547, -1, 1546, 1813, 1548, -1, + 1546, 1812, 1813, -1, 1546, 1782, 1812, -1, + 1549, 1769, 1550, -1, 1549, 1550, 1551, -1, + 1549, 1954, 1769, -1, 1549, 1551, 1552, -1, + 1549, 1552, 1954, -1, 1553, 1554, 1555, -1, + 1553, 1556, 1554, -1, 1553, 1555, 1557, -1, + 1553, 1557, 1558, -1, 1553, 1558, 1559, -1, + 1553, 1559, 1560, -1, 1553, 1560, 1561, -1, + 1553, 1561, 1556, -1, 1562, 1563, 1564, -1, + 1562, 1565, 1563, -1, 1562, 1564, 1566, -1, + 1562, 1566, 1779, -1, 1562, 1779, 1567, -1, + 1562, 1567, 1568, -1, 1562, 1568, 1565, -1, + 1569, 1571, 1570, -1, 1569, 1570, 1583, -1, + 1569, 1582, 1572, -1, 1569, 1583, 1582, -1, + 1569, 1573, 1571, -1, 1569, 1574, 1575, -1, + 1569, 1572, 1574, -1, 1569, 1575, 1576, -1, + 1569, 1576, 1573, -1, 1818, 1823, 1581, -1, + 1818, 1581, 1819, -1, 1577, 1579, 1578, -1, + 1577, 1578, 1819, -1, 1577, 1580, 1579, -1, + 1577, 1581, 1580, -1, 1577, 1819, 1581, -1, + 1820, 1819, 1582, -1, 1820, 1583, 1584, -1, + 1820, 1582, 1583, -1, 1820, 1584, 1821, -1, + 1585, 1586, 1590, -1, 1585, 1587, 1586, -1, + 1585, 1590, 1588, -1, 1585, 1588, 1587, -1, + 1828, 1830, 1589, -1, 1828, 1589, 1826, -1, + 1827, 1825, 1590, -1, 1827, 1592, 1591, -1, + 1827, 1590, 1592, -1, 1827, 1591, 1829, -1, + 1593, 1594, 1606, -1, 1593, 1606, 1604, -1, + 1593, 1595, 1594, -1, 1593, 1604, 1595, -1, + 1596, 1597, 1598, -1, 1596, 1599, 1597, -1, + 1596, 1600, 1599, -1, 1596, 1598, 1601, -1, + 1596, 1601, 1600, -1, 1614, 1615, 1602, -1, + 1614, 1602, 1613, -1, 1603, 1609, 1604, -1, + 1603, 1612, 1609, -1, 1603, 1605, 1612, -1, + 1603, 1604, 1606, -1, 1603, 1606, 1607, -1, + 1603, 1607, 1605, -1, 1608, 1610, 1609, -1, + 1608, 1612, 1611, -1, 1608, 1609, 1612, -1, + 1608, 1613, 1610, -1, 1608, 1614, 1613, -1, + 1608, 1611, 1615, -1, 1608, 1615, 1614, -1, + 1616, 1617, 1618, -1, 1616, 1618, 1619, -1, + 1616, 1619, 1620, -1, 1616, 1621, 1617, -1, + 1616, 1620, 1622, -1, 1616, 1622, 1621, -1, + 1669, 1668, 2155, -1, 1669, 2157, 1849, -1, + 1623, 2117, 1833, -1, 1623, 1988, 2117, -1, + 1623, 1833, 1988, -1, 2156, 2157, 1669, -1, + 2156, 1669, 2155, -1, 1989, 1832, 1987, -1, + 1629, 1625, 1624, -1, 1629, 1834, 1625, -1, + 1629, 1627, 1626, -1, 1629, 1624, 1627, -1, + 1629, 1626, 1628, -1, 1998, 1836, 1835, -1, + 1996, 1628, 1993, -1, 1996, 1834, 1629, -1, + 1996, 1629, 1628, -1, 1630, 1631, 1797, -1, + 1630, 1797, 1632, -1, 1630, 1633, 1631, -1, + 1630, 1632, 1633, -1, 1634, 1642, 1635, -1, + 1634, 1640, 1642, -1, 1634, 1635, 1636, -1, + 1634, 1636, 1640, -1, 1637, 1638, 1639, -1, + 1637, 1640, 1638, -1, 1637, 1639, 2038, -1, + 1637, 2038, 1641, -1, 1637, 1641, 1642, -1, + 1637, 1642, 1640, -1, 2087, 2048, 1947, -1, + 2113, 1941, 2048, -1, 1646, 1644, 1643, -1, + 1646, 1643, 1645, -1, 2052, 2088, 1644, -1, + 2052, 1645, 2051, -1, 2052, 1644, 1646, -1, + 2052, 1646, 1645, -1, 1950, 2048, 1944, -1, + 1950, 1949, 2048, -1, 1837, 1838, 1647, -1, + 1837, 1647, 2005, -1, 1648, 1649, 1650, -1, + 1648, 1651, 1649, -1, 1648, 1650, 1652, -1, + 1648, 2005, 1651, -1, 1648, 1652, 2005, -1, + 1653, 1654, 1655, -1, 1653, 1661, 1654, -1, + 1653, 1656, 1661, -1, 1653, 1655, 1657, -1, + 1653, 1657, 1656, -1, 1658, 1660, 1659, -1, + 1658, 1659, 1661, -1, 1658, 1662, 1660, -1, + 1658, 1663, 1662, -1, 1658, 1664, 1663, -1, + 1658, 1661, 1664, -1, 1843, 1665, 1842, -1, + 1843, 1845, 1665, -1, 2089, 2152, 2162, -1, + 2089, 2162, 2090, -1, 2006, 1666, 1847, -1, + 2006, 2090, 1666, -1, 2151, 2150, 1849, -1, + 1667, 2150, 1668, -1, 1667, 1849, 2150, -1, + 1667, 1668, 1669, -1, 1667, 1669, 1849, -1, + 2160, 2137, 2134, -1, 2160, 2154, 1671, -1, + 1670, 2117, 2137, -1, 1670, 1671, 2117, -1, + 1670, 2137, 2160, -1, 1670, 2160, 1671, -1, + 1851, 1672, 1852, -1, 1851, 1853, 1672, -1, + 1673, 1674, 1675, -1, 1673, 1676, 1677, -1, + 1673, 1677, 1835, -1, 1673, 1835, 1674, -1, + 1673, 1678, 1676, -1, 1673, 1675, 1678, -1, + 1857, 1855, 1681, -1, 1857, 1681, 1688, -1, + 1857, 1688, 1858, -1, 1679, 1680, 1681, -1, + 1679, 1681, 1855, -1, 1679, 1855, 1835, -1, + 1679, 1835, 1682, -1, 1679, 1682, 1680, -1, + 1683, 1684, 1690, -1, 1683, 1690, 1685, -1, + 1683, 1835, 1684, -1, 1683, 1685, 1835, -1, + 1859, 1686, 1860, -1, 1859, 1858, 1689, -1, + 1859, 1689, 1686, -1, 1687, 1688, 1854, -1, + 1687, 1689, 1688, -1, 1687, 1854, 1852, -1, + 1687, 1690, 1689, -1, 1687, 1852, 1691, -1, + 1687, 1691, 1690, -1, 2007, 1692, 2008, -1, + 2007, 2091, 1692, -1, 1693, 1864, 1694, -1, + 1693, 2094, 1864, -1, 1693, 1694, 1862, -1, + 1693, 1862, 2094, -1, 1695, 1700, 1863, -1, + 1695, 1696, 1700, -1, 1695, 1863, 2120, -1, + 1695, 2120, 1696, -1, 1701, 1863, 1700, -1, + 1701, 1697, 1863, -1, 1701, 1702, 1697, -1, + 1698, 1700, 1699, -1, 1698, 1699, 1705, -1, + 1698, 1701, 1700, -1, 1698, 1702, 1701, -1, + 1698, 1705, 1862, -1, 1698, 1862, 1702, -1, + 1866, 1862, 1703, -1, 1866, 1867, 1862, -1, + 1872, 1703, 1873, -1, 1872, 1876, 1866, -1, + 1872, 1866, 1703, -1, 1874, 1873, 1869, -1, + 1704, 1705, 1869, -1, 1704, 1873, 1705, -1, + 1704, 1869, 1873, -1, 1712, 1711, 1706, -1, + 1712, 1880, 1710, -1, 1712, 1706, 1880, -1, + 1707, 1708, 1709, -1, 1707, 1710, 1708, -1, + 1707, 1709, 1711, -1, 1707, 1712, 1710, -1, + 1707, 1711, 1712, -1, 1885, 1883, 1880, -1, + 1718, 1717, 1713, -1, 1718, 1713, 1714, -1, + 1884, 1714, 1882, -1, 1884, 1718, 1714, -1, + 1884, 1879, 1718, -1, 1715, 1716, 1717, -1, + 1715, 1717, 1718, -1, 1715, 1718, 1879, -1, + 1715, 1879, 1719, -1, 1715, 1719, 1716, -1, + 1889, 2018, 2016, -1, 1889, 1888, 2018, -1, + 1720, 1891, 1721, -1, 1720, 1888, 1891, -1, + 1720, 1721, 1722, -1, 1720, 1722, 1723, -1, + 1720, 1723, 1724, -1, 1720, 1724, 1888, -1, + 1893, 1726, 2012, -1, 1728, 1725, 1726, -1, + 1728, 1727, 1725, -1, 1728, 1726, 1893, -1, + 1728, 1893, 2017, -1, 1897, 1895, 1727, -1, + 1897, 1727, 1728, -1, 1897, 1728, 2017, -1, + 1897, 2017, 2018, -1, 1729, 1731, 1730, -1, + 1729, 1730, 1732, -1, 1729, 1733, 1731, -1, + 1729, 1732, 1733, -1, 1734, 1736, 1735, -1, + 1734, 1735, 1737, -1, 1734, 1738, 1736, -1, + 1734, 1739, 1738, -1, 1734, 1737, 1739, -1, + 1742, 1901, 1743, -1, 1742, 1744, 1902, -1, + 1742, 1902, 1901, -1, 1740, 1741, 1744, -1, + 1740, 1744, 1742, -1, 1740, 1742, 1743, -1, + 1740, 1747, 1741, -1, 1740, 1743, 1747, -1, + 1900, 1909, 1899, -1, 1900, 1902, 1744, -1, + 1900, 1744, 2037, -1, 1900, 2037, 1909, -1, + 1903, 2037, 1905, -1, 1903, 1909, 2037, -1, + 1910, 1911, 1755, -1, 1910, 1755, 1908, -1, + 1913, 1914, 1748, -1, 1913, 1746, 1745, -1, + 1913, 1745, 2020, -1, 1913, 1915, 1746, -1, + 1913, 1748, 1915, -1, 2032, 2024, 1747, -1, + 2032, 1747, 2026, -1, 2028, 1915, 1748, -1, + 2028, 1914, 2029, -1, 2028, 1748, 1914, -1, + 1749, 1752, 1916, -1, 1749, 1750, 1752, -1, + 1749, 1916, 2037, -1, 1749, 2037, 1750, -1, + 1751, 1919, 1752, -1, 1751, 1753, 1919, -1, + 1751, 1752, 1754, -1, 1751, 1755, 1753, -1, + 1751, 1754, 1755, -1, 1918, 1756, 1917, -1, + 1918, 1919, 1756, -1, 2034, 2035, 1906, -1, + 2034, 1906, 2037, -1, 1921, 2044, 2038, -1, + 1921, 1922, 1765, -1, 2040, 1927, 2038, -1, + 2040, 1757, 1926, -1, 2040, 1758, 1757, -1, + 2040, 2041, 1758, -1, 1762, 1935, 1759, -1, + 1762, 1760, 2088, -1, 1762, 2088, 1930, -1, + 1762, 1759, 1761, -1, 1762, 1761, 1760, -1, + 1929, 1935, 1762, -1, 1929, 1762, 1930, -1, + 2097, 1931, 2088, -1, 2097, 2088, 2131, -1, + 2045, 1932, 1937, -1, 1934, 1935, 1929, -1, + 1934, 1929, 1931, -1, 1938, 2051, 2048, -1, + 1938, 2048, 1763, -1, 1940, 1763, 1941, -1, + 1940, 2114, 2088, -1, 1940, 1938, 1763, -1, + 1948, 1942, 2088, -1, 1948, 2088, 2139, -1, + 1764, 1765, 2041, -1, 1764, 2041, 2044, -1, + 1764, 1921, 1765, -1, 1764, 2044, 1921, -1, + 2063, 1953, 2066, -1, 2061, 2062, 1771, -1, + 2061, 1953, 2063, -1, 1766, 1767, 1768, -1, + 1766, 1771, 1767, -1, 1766, 2061, 1771, -1, + 1766, 1954, 2061, -1, 1766, 1768, 1769, -1, + 1766, 1769, 1954, -1, 1958, 2059, 1770, -1, + 1958, 1770, 1957, -1, 1956, 1772, 1771, -1, + 1956, 1771, 2062, -1, 1956, 1957, 1772, -1, + 1773, 1774, 2066, -1, 1773, 2066, 1953, -1, + 1773, 1775, 1774, -1, 1773, 1953, 1776, -1, + 1773, 1776, 1775, -1, 1777, 1781, 1778, -1, + 1777, 1780, 1781, -1, 1777, 1778, 1779, -1, + 1777, 1779, 1780, -1, 1964, 1780, 1963, -1, + 1964, 1781, 1780, -1, 1964, 1968, 1781, -1, + 1964, 1966, 1968, -1, 1981, 1812, 1782, -1, + 1981, 1782, 1968, -1, 1783, 1785, 1784, -1, + 1783, 1786, 1785, -1, 1783, 1784, 1792, -1, + 1783, 1792, 1786, -1, 1787, 1788, 1789, -1, + 1787, 1789, 1790, -1, 1787, 1790, 1791, -1, + 1787, 1791, 1792, -1, 1787, 1792, 1788, -1, + 1793, 1796, 1976, -1, 1793, 1795, 1796, -1, + 1793, 1976, 1795, -1, 1794, 1976, 1975, -1, + 1794, 1795, 1976, -1, 1794, 1975, 1796, -1, + 1794, 1796, 1795, -1, 1971, 1797, 1974, -1, + 1971, 1972, 1797, -1, 1798, 1800, 1799, -1, + 1798, 1799, 1801, -1, 1798, 1801, 1802, -1, + 1798, 1802, 1803, -1, 1798, 1804, 1800, -1, + 1798, 1803, 1804, -1, 1809, 1806, 1805, -1, + 1809, 1805, 1810, -1, 1809, 1979, 1806, -1, + 1816, 1979, 1978, -1, 1816, 1814, 1807, -1, + 1816, 1807, 1808, -1, 1816, 1808, 1979, -1, + 1980, 1979, 1809, -1, 1980, 1810, 1811, -1, + 1980, 1809, 1810, -1, 1980, 1812, 1981, -1, + 1980, 1813, 1812, -1, 1980, 1811, 1813, -1, + 1969, 1815, 1814, -1, 1969, 1967, 1815, -1, + 1969, 1814, 1816, -1, 1969, 1816, 1978, -1, + 1817, 1818, 1819, -1, 1817, 1819, 1820, -1, + 1817, 1820, 1821, -1, 1817, 1821, 1822, -1, + 1817, 1822, 1823, -1, 1817, 1823, 1818, -1, + 1824, 1826, 1825, -1, 1824, 1825, 1827, -1, + 1824, 1828, 1826, -1, 1824, 1827, 1829, -1, + 1824, 1829, 1830, -1, 1824, 1830, 1828, -1, + 1983, 1989, 1987, -1, 1983, 1990, 1989, -1, + 2077, 1831, 1832, -1, 2077, 1832, 1989, -1, + 2077, 2107, 1831, -1, 1986, 1988, 2099, -1, + 2071, 1988, 1833, -1, 2071, 1833, 2068, -1, + 1997, 1835, 1834, -1, 1997, 1998, 1835, -1, + 1997, 1834, 1996, -1, 1995, 1994, 1836, -1, + 1995, 1836, 1998, -1, 2085, 2142, 2048, -1, + 2085, 2141, 2142, -1, 2085, 2139, 2141, -1, + 2145, 2113, 2048, -1, 2112, 1941, 2113, -1, + 2002, 1838, 1837, -1, 2002, 1839, 1838, -1, + 2002, 2000, 1839, -1, 2002, 1837, 2005, -1, + 1844, 1840, 1845, -1, 1844, 2074, 1840, -1, + 1841, 1842, 2074, -1, 1841, 1843, 1842, -1, + 1841, 2074, 1844, -1, 1841, 1845, 1843, -1, + 1841, 1844, 1845, -1, 2116, 1847, 1846, -1, + 2116, 2006, 1847, -1, 2116, 1846, 2117, -1, + 1848, 2152, 2151, -1, 1848, 2151, 1849, -1, + 1848, 2162, 2152, -1, 1848, 1849, 2162, -1, + 1850, 1851, 1852, -1, 1850, 1853, 1851, -1, + 1850, 1852, 1854, -1, 1850, 1854, 1853, -1, + 1861, 1860, 1855, -1, 1861, 1855, 1857, -1, + 1856, 1857, 1858, -1, 1856, 1858, 1859, -1, + 1856, 1859, 1860, -1, 1856, 1860, 1861, -1, + 1856, 1861, 1857, -1, 2124, 2095, 1862, -1, + 2124, 1862, 2091, -1, 2092, 1863, 1864, -1, + 2092, 1864, 2094, -1, 2092, 2120, 1863, -1, + 1865, 1876, 1878, -1, 1865, 1866, 1876, -1, + 1865, 1867, 1866, -1, 1865, 1868, 1867, -1, + 1865, 1878, 1868, -1, 1870, 1874, 1869, -1, + 1870, 1869, 2120, -1, 1875, 1874, 1870, -1, + 1875, 1870, 2120, -1, 1871, 1872, 1873, -1, + 1871, 1873, 1874, -1, 1871, 1874, 1875, -1, + 1871, 1876, 1872, -1, 1871, 2120, 1877, -1, + 1871, 1875, 2120, -1, 1871, 1877, 1878, -1, + 1871, 1878, 1876, -1, 1886, 1880, 1879, -1, + 1886, 1885, 1880, -1, 1886, 1879, 1884, -1, + 1881, 1882, 1883, -1, 1881, 1884, 1882, -1, + 1881, 1883, 1885, -1, 1881, 1885, 1886, -1, + 1881, 1886, 1884, -1, 1887, 1891, 1888, -1, + 1887, 1888, 1889, -1, 1887, 1889, 2016, -1, + 1887, 2013, 1891, -1, 1887, 2016, 2013, -1, + 1890, 1891, 2013, -1, 1890, 2013, 1892, -1, + 1890, 2026, 1891, -1, 1890, 1892, 2026, -1, + 2011, 1892, 2013, -1, 2011, 2012, 2026, -1, + 2011, 2026, 1892, -1, 2015, 1893, 2012, -1, + 2015, 2017, 1893, -1, 1894, 1896, 1895, -1, + 1894, 1895, 1897, -1, 1894, 2018, 1896, -1, + 1894, 1897, 2018, -1, 1898, 1899, 1908, -1, + 1898, 1900, 1899, -1, 1898, 1908, 1901, -1, + 1898, 1901, 1902, -1, 1898, 1902, 1900, -1, + 1912, 1909, 1903, -1, 1912, 1904, 1911, -1, + 1912, 1903, 1905, -1, 1912, 1906, 1904, -1, + 1912, 1905, 1906, -1, 1907, 1908, 1909, -1, + 1907, 1910, 1908, -1, 1907, 1911, 1910, -1, + 1907, 1912, 1911, -1, 1907, 1909, 1912, -1, + 2022, 1913, 2020, -1, 2022, 1914, 1913, -1, + 2022, 2021, 1914, -1, 2030, 1915, 2028, -1, + 2030, 2026, 1915, -1, 2036, 2037, 1916, -1, + 2036, 1917, 2035, -1, 2036, 1918, 1917, -1, + 2036, 1916, 1919, -1, 2036, 1919, 1918, -1, + 1920, 1922, 1921, -1, 1920, 1923, 1922, -1, + 1920, 1921, 2038, -1, 1920, 1924, 1923, -1, + 1920, 2038, 1924, -1, 2042, 2040, 2038, -1, + 1925, 2040, 1926, -1, 1925, 1927, 2040, -1, + 1925, 1932, 1927, -1, 1925, 1926, 1937, -1, + 1925, 1937, 1932, -1, 1928, 1931, 1929, -1, + 1928, 1929, 1930, -1, 1928, 2088, 1931, -1, + 1928, 1930, 2088, -1, 2096, 1931, 2097, -1, + 2096, 1934, 1931, -1, 2096, 2047, 1934, -1, + 2046, 1932, 2045, -1, 2046, 2088, 1932, -1, + 2046, 2131, 2088, -1, 1933, 1935, 1934, -1, + 1933, 1934, 2047, -1, 1933, 2048, 1935, -1, + 1933, 2047, 2048, -1, 2129, 2133, 2048, -1, + 1936, 2045, 1937, -1, 1936, 2133, 2045, -1, + 1936, 1937, 2048, -1, 1936, 2048, 2133, -1, + 2050, 2051, 1938, -1, 2050, 1940, 2088, -1, + 2050, 1938, 1940, -1, 1939, 1940, 1941, -1, + 1939, 2114, 1940, -1, 1939, 1941, 2112, -1, + 1939, 2112, 2114, -1, 1951, 1942, 1948, -1, + 1951, 1943, 1942, -1, 1951, 1944, 1943, -1, + 1951, 1950, 1944, -1, 1945, 2139, 2087, -1, + 1945, 1948, 2139, -1, 1945, 2087, 1948, -1, + 1946, 2087, 1947, -1, 1946, 1948, 2087, -1, + 1946, 1947, 1949, -1, 1946, 1949, 1950, -1, + 1946, 1950, 1951, -1, 1946, 1951, 1948, -1, + 1952, 1953, 2061, -1, 1952, 2061, 1954, -1, + 1952, 1955, 1953, -1, 1952, 1954, 1955, -1, + 2067, 1956, 2062, -1, 2067, 2065, 1958, -1, + 2067, 1958, 1957, -1, 2067, 1957, 1956, -1, + 2055, 1958, 2065, -1, 2055, 2059, 1958, -1, + 2064, 2054, 2065, -1, 2064, 2066, 1959, -1, + 2064, 1959, 2056, -1, 2064, 2056, 2054, -1, + 1960, 1962, 1961, -1, 1960, 1963, 1962, -1, + 1960, 1961, 1967, -1, 1960, 1967, 1966, -1, + 1960, 1964, 1963, -1, 1960, 1966, 1964, -1, + 1965, 1966, 1967, -1, 1965, 1978, 1981, -1, + 1965, 1968, 1966, -1, 1965, 1981, 1968, -1, + 1965, 1967, 1969, -1, 1965, 1969, 1978, -1, + 1970, 1972, 1971, -1, 1970, 1973, 1972, -1, + 1970, 1974, 1975, -1, 1970, 1971, 1974, -1, + 1970, 1975, 1976, -1, 1970, 1976, 1973, -1, + 1977, 1978, 1979, -1, 1977, 1979, 1980, -1, + 1977, 1981, 1978, -1, 1977, 1980, 1981, -1, + 1984, 1987, 1986, -1, 1982, 1990, 1983, -1, + 1982, 2162, 1990, -1, 1982, 2099, 2162, -1, + 1982, 1986, 2099, -1, 1982, 1984, 1986, -1, + 1982, 1983, 1987, -1, 1982, 1987, 1984, -1, + 1985, 1986, 1987, -1, 1985, 1988, 1986, -1, + 1985, 1987, 2117, -1, 1985, 2117, 1988, -1, + 2070, 2099, 1988, -1, 2070, 1988, 2071, -1, + 2073, 2069, 2074, -1, 2082, 2083, 2117, -1, + 2082, 2117, 2105, -1, 2075, 2077, 1989, -1, + 2075, 1989, 1990, -1, 2075, 1990, 2162, -1, + 2075, 2162, 2076, -1, 2108, 1991, 2083, -1, + 2108, 2137, 1991, -1, 2081, 2108, 2083, -1, + 2081, 2109, 2108, -1, 1992, 1993, 1994, -1, + 1992, 1994, 1995, -1, 1992, 1996, 1993, -1, + 1992, 1997, 1996, -1, 1992, 1998, 1997, -1, + 1992, 1995, 1998, -1, 2086, 2048, 2087, -1, + 2086, 2085, 2048, -1, 2110, 2048, 2142, -1, + 2110, 2145, 2048, -1, 1999, 2001, 2000, -1, + 1999, 2000, 2002, -1, 1999, 2003, 2001, -1, + 1999, 2004, 2003, -1, 1999, 2005, 2004, -1, + 1999, 2002, 2005, -1, 2115, 2090, 2006, -1, + 2115, 2006, 2116, -1, 2126, 2091, 2007, -1, + 2126, 2007, 2008, -1, 2126, 2120, 2119, -1, + 2126, 2008, 2009, -1, 2126, 2009, 2120, -1, + 2093, 2092, 2094, -1, 2010, 2012, 2011, -1, + 2010, 2015, 2012, -1, 2010, 2016, 2015, -1, + 2010, 2013, 2016, -1, 2010, 2011, 2013, -1, + 2014, 2015, 2016, -1, 2014, 2017, 2015, -1, + 2014, 2016, 2018, -1, 2014, 2018, 2017, -1, + 2019, 2020, 2021, -1, 2019, 2021, 2022, -1, + 2019, 2022, 2020, -1, 2031, 2029, 2023, -1, + 2031, 2023, 2024, -1, 2031, 2024, 2032, -1, + 2025, 2032, 2026, -1, 2025, 2026, 2030, -1, + 2025, 2030, 2032, -1, 2027, 2028, 2029, -1, + 2027, 2030, 2028, -1, 2027, 2029, 2031, -1, + 2027, 2032, 2030, -1, 2027, 2031, 2032, -1, + 2033, 2035, 2034, -1, 2033, 2036, 2035, -1, + 2033, 2034, 2037, -1, 2033, 2037, 2036, -1, + 2043, 2038, 2044, -1, 2043, 2042, 2038, -1, + 2039, 2041, 2040, -1, 2039, 2040, 2042, -1, + 2039, 2042, 2043, -1, 2039, 2044, 2041, -1, + 2039, 2043, 2044, -1, 2132, 2045, 2133, -1, + 2132, 2046, 2045, -1, 2132, 2131, 2046, -1, + 2128, 2048, 2047, -1, 2128, 2129, 2048, -1, + 2128, 2047, 2096, -1, 2049, 2050, 2088, -1, + 2049, 2051, 2050, -1, 2049, 2088, 2052, -1, + 2049, 2052, 2051, -1, 2053, 2065, 2054, -1, + 2053, 2055, 2065, -1, 2053, 2054, 2056, -1, + 2053, 2056, 2057, -1, 2053, 2057, 2058, -1, + 2053, 2058, 2059, -1, 2053, 2059, 2055, -1, + 2060, 2062, 2061, -1, 2060, 2061, 2063, -1, + 2060, 2064, 2065, -1, 2060, 2063, 2066, -1, + 2060, 2066, 2064, -1, 2060, 2067, 2062, -1, + 2060, 2065, 2067, -1, 2072, 2071, 2068, -1, + 2072, 2068, 2069, -1, 2072, 2069, 2073, -1, + 2100, 2099, 2070, -1, 2100, 2070, 2071, -1, + 2100, 2071, 2072, -1, 2100, 2072, 2073, -1, + 2100, 2074, 2162, -1, 2100, 2073, 2074, -1, + 2106, 2117, 2107, -1, 2106, 2105, 2117, -1, + 2102, 2079, 2103, -1, 2102, 2162, 2079, -1, + 2102, 2076, 2162, -1, 2104, 2075, 2076, -1, + 2104, 2076, 2102, -1, 2104, 2107, 2077, -1, + 2104, 2077, 2075, -1, 2136, 2137, 2108, -1, + 2080, 2109, 2081, -1, 2080, 2079, 2162, -1, + 2080, 2162, 2109, -1, 2078, 2103, 2079, -1, + 2078, 2079, 2080, -1, 2078, 2080, 2081, -1, + 2078, 2105, 2103, -1, 2078, 2082, 2105, -1, + 2078, 2083, 2082, -1, 2078, 2081, 2083, -1, + 2084, 2139, 2085, -1, 2084, 2085, 2086, -1, + 2084, 2087, 2139, -1, 2084, 2086, 2087, -1, + 2147, 2140, 2088, -1, 2147, 2088, 2114, -1, + 2153, 2089, 2090, -1, 2153, 2090, 2115, -1, + 2153, 2152, 2089, -1, 2123, 2124, 2091, -1, + 2123, 2091, 2126, -1, 2121, 2093, 2119, -1, + 2121, 2092, 2093, -1, 2121, 2120, 2092, -1, + 2125, 2119, 2093, -1, 2125, 2126, 2119, -1, + 2125, 2094, 2095, -1, 2125, 2093, 2094, -1, + 2125, 2095, 2124, -1, 2130, 2096, 2097, -1, + 2130, 2128, 2096, -1, 2130, 2097, 2131, -1, + 2098, 2162, 2099, -1, 2098, 2100, 2162, -1, + 2098, 2099, 2100, -1, 2101, 2102, 2103, -1, + 2101, 2104, 2102, -1, 2101, 2103, 2105, -1, + 2101, 2105, 2106, -1, 2101, 2106, 2107, -1, + 2101, 2107, 2104, -1, 2135, 2108, 2109, -1, + 2135, 2136, 2108, -1, 2135, 2109, 2162, -1, + 2144, 2140, 2147, -1, 2144, 2110, 2142, -1, + 2144, 2145, 2110, -1, 2146, 2113, 2145, -1, + 2111, 2112, 2113, -1, 2111, 2113, 2146, -1, + 2111, 2146, 2147, -1, 2111, 2114, 2112, -1, + 2111, 2147, 2114, -1, 2149, 2153, 2115, -1, + 2149, 2115, 2116, -1, 2149, 2117, 2150, -1, + 2149, 2116, 2117, -1, 2118, 2119, 2120, -1, + 2118, 2120, 2121, -1, 2118, 2121, 2119, -1, + 2122, 2124, 2123, -1, 2122, 2125, 2124, -1, + 2122, 2123, 2126, -1, 2122, 2126, 2125, -1, + 2127, 2129, 2128, -1, 2127, 2128, 2130, -1, + 2127, 2130, 2131, -1, 2127, 2131, 2132, -1, + 2127, 2133, 2129, -1, 2127, 2132, 2133, -1, + 2159, 2160, 2134, -1, 2159, 2136, 2135, -1, + 2159, 2134, 2137, -1, 2159, 2137, 2136, -1, + 2159, 2135, 2162, -1, 2138, 2139, 2140, -1, + 2138, 2140, 2144, -1, 2138, 2141, 2139, -1, + 2138, 2142, 2141, -1, 2138, 2144, 2142, -1, + 2143, 2145, 2144, -1, 2143, 2146, 2145, -1, + 2143, 2144, 2147, -1, 2143, 2147, 2146, -1, + 2148, 2149, 2150, -1, 2148, 2150, 2151, -1, + 2148, 2151, 2152, -1, 2148, 2152, 2153, -1, + 2148, 2153, 2149, -1, 2161, 2154, 2160, -1, + 2161, 2155, 2154, -1, 2161, 2156, 2155, -1, + 2161, 2157, 2156, -1, 2161, 2162, 2157, -1, + 2158, 2160, 2159, -1, 2158, 2161, 2160, -1, + 2158, 2159, 2162, -1, 2158, 2162, 2161, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl new file mode 100644 index 0000000..72eeacc --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T6_wristDiff.wrl @@ -0,0 +1,2472 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_T6_wristDiff_________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.80751598 -26.9685 4.93436, + -13.2551 -23.405001 19.901699, + -4.7444301 -26.9685 1.57809, + 3.99389 -26.9685 3.0081301, + -11.0937 -12.8814 -36.380501, + -13.578 -23.2192 19.901699, + -15.3274 -22.1035 19.901699, + -15.3011 -22.065599 20.0082, + -11.5085 -23.3465 22.407499, + -17.647499 -20.2733 19.901699, + -16.9564 -20.820499 20.0082, + -18.5427 -19.4849 19.901699, + -18.5109 -19.4515 20.0082, + -17.888599 -20.5501 18.837799, + -16.9856 -20.856199 19.901699, + -18.584499 -19.948601 18.837799, + -13.9835 -23.405001 18.837799, + -17.0457 -21.278601 18.837799, + -15.412 -22.490101 18.837799, + 10.405 -23.405001 22.3918, + 10.1221 -23.405001 22.407499, + -0.396819 -26.9685 -4.98423, + -4.93436 -26.9685 -0.80751598, + 4.5196199 -26.9685 -2.1384599, + -12.34 -11.693 -36.380501, + 2.7333601 -14.9554 -36.4305, + -19.301701 -19.3134 -7.30404, + -19.563299 -19.048401 6.5714002, + -25.922899 7.1759701 19.901699, + -24.469801 11.0562 20.0082, + -25.2493 9.1371098 20.0082, + -25.878401 7.16365 20.0082, + 19.8493 -18.750099 -5.6475902, + 19.563299 -19.048401 -6.5714002, + 19.854799 -18.744301 -5.6296701, + 20.520399 -18.013201 -2.1951201, + 20.049999 -18.5354 18.593599, + 19.965 -18.6269 5.2252598, + 19.6618 -18.946699 6.2707, + 20.4788 -18.060499 2.55407, + 20.789301 -17.6733 18.593599, + -19.9895 -17.997601 19.901699, + -21.343901 -16.9638 18.837799, + -20.02 -18.5077 18.837799, + -19.9552 -17.9667 20.0082, + -22.574499 -15.3426 18.7174, + -23.655399 -13.617 18.7174, + -23.628901 -13.6018 18.837799, + -22.583 -15.3484 18.593599, + -23.664301 -13.6222 18.593599, + -27.2498 -1.47857 -18.593599, + 10.4059 23.405001 22.3929, + 10.1221 23.405001 22.407499, + -8.5249996 26.549 6.7236394e-010, + -7.2965698 26.549 -6.12255, + -14.063 23.405001 -18.593599, + -25.2927 9.1528196 19.901699, + -24.5119 11.0752 19.901699, + -22.479601 14.686 20.0082, + -23.5448 12.9095 20.0082, + -21.549999 16.075399 19.901699, + 15.2702 21.301201 -21.901699, + 15.2745 7.4625802 -36.380501, + 14.4411 8.9695902 -36.380501, + 26.287201 7.1624298 -18.837799, + 26.087999 8.0261497 -18.7174, + -17.0648 -21.302401 18.7174, + -18.6054 -19.971001 18.7174, + -14.0472 -23.405001 18.703899, + -15.4293 -22.515301 18.7174, + -14.0214 -23.405001 18.7717, + -14.06 -23.405001 18.6423, + -14.063 -23.405001 18.593599, + 18.884001 -19.722 8.3246803, + 18.999901 -19.6087 -8.0419703, + 19.226299 -19.3885 -7.5004802, + 19.301701 -19.3134 7.30404, + 18.843 -19.7612 -8.4172096, + 14.06 -23.405001 -18.6423, + 16.178301 -21.996099 12.8129, + 15.6544 -22.371901 -13.4479, + 3.2582099 -14.6433 -36.4305, + 9.6895103 -13.9683 -36.380501, + 14.4127 -9.0151701 -36.380501, + 11.1702 -23.405001 -22.2663, + 11.123 -23.405001 -22.2831, + 10.4059 -23.405001 -22.3929, + 10.1221 -23.405001 -22.407499, + 10.6799 -23.405001 -22.3678, + 11.0207 -23.405001 -22.309999, + 10.5866 -23.405001 -22.3836, + -14.063 -23.405001 -15.1042, + 0.71324199 -14.6433 -36.4305, + 2.4414301 -15.0477 -36.4305, + 1.69314 -16.915501 -36.380501, + -18.843 -19.7612 8.4172096, + -19.226299 -19.3885 7.5004802, + -18.884001 -19.722 -8.3246803, + -21.367901 -16.9828 18.7174, + -20.0424 -18.5285 18.7174, + -19.965 -18.6269 -5.2252598, + -19.854799 -18.744301 5.6296701, + -19.6618 -18.946699 -6.2707, + -11.3912 -23.401199 22.407499, + -11.3478 -23.405001 22.407499, + -27.229 -2.0355201 18.593599, + -27.229 -2.0355201 -18.593599, + -27.2188 -2.03475 18.7174, + -27.2498 -1.47857 18.593599, + -27.001499 -4.05971 18.593599, + -11.6775 6.7558899 36.4305, + -10.5145 7.5260201 36.4305, + -26.933901 4.4179602 -18.593599, + -23.628901 13.6018 18.837799, + -24.577101 11.8025 18.837799, + -23.5853 12.9317 19.901699, + -22.518299 14.7112 19.901699, + -15.9564 5.8645401 36.380501, + -26.672001 3.1008401 20.0082, + 18.6124 19.9785 -18.593599, + 22.7187 -15.0549 -18.837799, + 21.9842 -14.0696 -22.106199, + 16.7999 -2.6008101 -36.380501, + 16.976801 -0.88785398 -36.380501, + 12.3478 8.1340799 -36.4305, + 20.101101 -18.48 -4.6747799, + 20.1453 -18.431801 4.4804802, + 20.6231 -17.895599 -0.63535303, + 20.6348 -17.882 -0.331945, + 20.628099 -17.889799 0.62401599, + 20.576099 -17.9496 1.59078, + 20.5987 -17.9237 -1.26543, + 22.574499 -15.3426 -18.7174, + 20.789301 -17.6733 -18.593599, + 11.1691 -23.405001 22.2656, + 10.6194 -23.405001 22.3799, + -1.76191 16.9084 36.380501, + -3.8561299 -13.7782 36.4305, + -22.479601 -14.686 20.0082, + -15.244 -7.5246201 36.380501, + -21.549999 -16.075399 19.901699, + -21.317301 -16.4032 19.901699, + -22.5492 -15.3254 18.837799, + -22.518299 -14.7112 19.901699, + -21.280701 -16.375099 20.0082, + -26.8778 6.6595424e-011 -19.901699, + -25.4266 -9.9523602 18.593599, + -25.358101 -10.1099 18.593599, + -24.6047 -11.8157 18.7174, + -24.614 -11.8202 18.593599, + -25.4266 -9.9523602 -18.593599, + -25.358101 -10.1099 -18.593599, + -26.831699 1.03567 -20.0082, + -26.672001 3.1008401 -20.0082, + -26.623699 -6.0613098 -18.593599, + -26.097799 -8.0291796 -18.593599, + -26.3536 -5.1475601 -20.0082, + -26.736401 -2.8670299 -19.901699, + -26.8778 -1.03745 -19.901699, + -27.188299 -2.03247 -18.837799, + -26.831699 -1.03567 -20.0082, + -26.672001 -3.1008401 -20.0082, + -25.4266 9.9523602 -18.593599, + -25.4266 9.9523602 18.593599, + -26.623699 6.0613098 -18.593599, + -13.2551 23.405001 -19.901699, + -1.654 26.549 9.38029, + 1.4671798e-009 26.549 9.5249996, + -4.7624998 26.549 8.2488899, + -3.25774 26.549 8.9505701, + -11.3478 23.405001 22.407499, + 4.7624998 26.549 8.2488899, + 10.6799 23.405001 22.3678, + 1.654 26.549 9.38029, + 11.0207 23.405001 22.309999, + 10.5866 23.405001 22.3836, + -6.12255 26.549 7.2965698, + -6.12255 26.549 -7.2965698, + 14.0015 23.405001 -18.8092, + 15.412 22.490101 -18.837799, + -14.063 23.405001 18.593599, + -9.5249996 26.549 3.9216777e-010, + -11.4573 23.378401 22.407499, + -22.5492 15.3254 18.837799, + -21.317301 16.4032 19.901699, + 13.915 22.196899 -21.901699, + 19.6036 17.2325 -22.106199, + 12.34 11.693 -36.380501, + 13.4596 10.3846 -36.380501, + 19.6502 17.2735 -22.0082, + 20.940399 15.7613 -21.901699, + 12.3036 7.8310699 -36.4305, + 3.00776 -14.8195 -36.4305, + 22.583 15.3484 -18.593599, + 22.036501 14.1031 -22.0082, + 21.8375 14.4703 -21.901699, + 20.9035 15.7336 -22.0082, + 20.854 15.6963 -22.106199, + 21.9842 14.0696 -22.106199, + 22.9879 12.3619 -22.106199, + 23.0425 12.3913 -22.0082, + 26.908701 4.3313498 -18.837799, + 25.738701 4.9438601 -21.901699, + 26.9611 4.0536399 -18.837799, + 26.5839 6.0522399 -18.837799, + 27.2498 1.47857 -18.593599, + 27.229 2.0355201 -18.593599, + 25.4266 9.9523602 -18.593599, + 25.417101 9.9486103 -18.7174, + 25.358101 10.1099 -18.593599, + 23.958099 10.6269 -21.901699, + 24.577101 11.8025 -18.837799, + 23.0832 12.4132 -21.901699, + 25.388599 9.9374704 -18.837799, + 25.287001 6.8898201 -21.901699, + 26.058701 8.0171604 -18.837799, + 25.2896 6.8814998 -21.901699, + 24.651501 8.76404 -22.0082, + 24.695 8.7795 -21.901699, + 25.2451 6.86938 -22.0082, + 25.1852 6.8530898 -22.106199, + 24.593 8.7432604 -22.106199, + 23.915899 10.6082 -22.0082, + 23.8592 10.5831 -22.106199, + 26.039499 2.9777501 -21.901699, + -15.6717 -22.3594 13.4267, + -17.636299 -20.845301 10.7177, + -18.6124 -19.9785 18.593599, + -9.6768398 -13.9771 36.380501, + 22.5492 -15.3254 -18.837799, + 20.0424 -18.5285 -18.7174, + 6.6793599 -15.6329 -36.380501, + 8.2266397 -14.8769 -36.380501, + 14.0015 -23.405001 18.8092, + -22.583 -15.3484 -18.593599, + 3.81073 -13.9185 -36.4305, + 3.6644599 -14.1875 -36.4305, + 15.2508 -7.5107999 -36.380501, + 3.4788301 -14.431 -36.4305, + 3.9142301 -13.6303 -36.4305, + 12.2138 7.5383601 -36.4305, + -15.3011 -22.065599 -20.0082, + -11.5085 -23.3465 -22.407499, + -21.317301 -16.4032 -19.901699, + -19.9552 -17.9667 -20.0082, + -21.343901 -16.9638 -18.837799, + -7.1219201 -26.9685 2.36889, + -17.510201 -20.9513 -10.9224, + -8.2735996 -14.8508 -36.380501, + -9.7335901 -13.9376 -36.380501, + 2.1388299 -15.0945 -36.4305, + -18.4076 -20.1674 -9.3310099, + -17.8715 -20.6439 -10.3206, + -18.191999 -20.362101 9.7446003, + -18.6124 -19.9785 -18.593599, + -18.4123 -20.163099 9.32162, + -20.789301 -17.6733 -18.593599, + -21.367901 -16.9828 -18.7174, + -20.0424 -18.5285 -18.7174, + -11.4333 -23.3899 22.407499, + -26.736401 2.8670299 19.901699, + -27.264099 1.3696825e-009 18.837799, + -26.933901 4.4179602 18.593599, + -27.2188 2.03475 18.7174, + -27.294701 1.0538337e-009 18.7174, + -27.188299 2.03247 18.837799, + -26.991301 4.0581799 18.7174, + -27.0903 2.90464 18.837799, + -27.305 -1.1863781e-009 18.593599, + -27.305 8.8106739e-010 -18.593599, + -26.831699 1.03567 20.0082, + -26.8778 1.03745 19.901699, + -27.0903 -2.90464 18.837799, + -8.2870598 14.8433 36.380501, + -6.7428699 15.6056 36.380501, + -24.6047 11.8157 18.7174, + -16.980301 0.81882101 36.380501, + -26.398899 5.1564102 19.901699, + -26.717899 3.1061699 19.901699, + -26.3536 5.1475601 20.0082, + -26.9611 4.0536399 18.837799, + -26.271099 5.6990299 19.901699, + 17.0648 21.302401 -18.7174, + 17.071301 21.3104 -18.593599, + 17.0457 21.278601 -18.837799, + 18.6124 19.9785 18.593599, + 17.0648 21.302401 18.7174, + 17.071301 21.3104 18.593599, + 14.0355 23.405001 -18.7386, + 26.1903 0.99449301 -21.901699, + 22.9879 -12.3619 -22.106199, + 25.931999 2.9654601 -22.106199, + 16.9795 0.834216 -36.380501, + 25.632401 4.92345 -22.106199, + 25.6933 4.9351501 -22.0082, + 25.993601 2.9725101 -22.0082, + 12.2957 8.7424498 -36.4305, + 12.3451 8.4402599 -36.4305, + 12.2008 9.0335703 -36.4305, + 15.9511 5.8790002 -36.380501, + 16.464001 4.2350898 -36.380501, + 16.808001 2.54773 -36.380501, + 11.1691 23.405001 -22.2656, + 20.3923 -18.158001 -3.1654501, + 20.400101 -18.1493 -3.1212499, + 20.049999 -18.5354 -18.593599, + 20.2374 -18.330601 -4.0440202, + 20.335699 -18.2215 3.5165701, + 21.3759 -16.989201 -18.593599, + 21.3759 -16.989201 18.593599, + 22.583 -15.3484 -18.593599, + 11.3489 -23.405001 22.2061, + 11.5673 -23.405001 22.0975, + 5.1294899 -16.207701 36.380501, + 11.3762 -23.405001 22.1926, + 10.9328 -23.405001 22.322001, + 11.0823 -23.405001 22.2943, + 10.6808 -23.405001 22.368601, + -1.5094399 -26.9685 7.35221, + 18.584499 -19.948601 18.837799, + 20.02 -18.5077 18.837799, + 19.022301 -19.509199 18.837799, + 20.9879 -17.379 18.837799, + 18.6054 -19.971001 18.7174, + 20.0424 -18.5285 18.7174, + 21.367901 -16.9828 18.7174, + 21.343901 -16.9638 18.837799, + 22.5492 -15.3254 18.837799, + 17.0457 21.278601 18.837799, + -0.042266 16.999901 36.380501, + -23.664301 -13.6222 -18.593599, + -22.574499 -15.3426 -18.7174, + -22.5492 -15.3254 -18.837799, + -21.549999 -16.075399 -19.901699, + -21.280701 -16.375099 -20.0082, + -24.469801 -11.0562 -20.0082, + -24.6047 -11.8157 -18.7174, + -25.417101 -9.9486103 -18.7174, + -24.614 -11.8202 -18.593599, + -23.655399 -13.617 -18.7174, + -26.933901 -4.4179602 -18.593599, + -27.001499 -4.05971 -18.593599, + -27.2188 -2.03475 -18.7174, + -26.271099 -5.6990299 -19.901699, + -25.878401 -7.16365 -20.0082, + -26.087999 8.0261497 -18.7174, + -26.058701 8.0171604 -18.837799, + -26.613701 6.0590301 -18.7174, + -26.5839 6.0522399 18.837799, + -26.058701 8.0171604 18.837799, + -25.417101 9.9486103 18.7174, + -25.388599 9.9374704 18.837799, + -26.2915 7.3044901 18.593599, + -26.097799 8.0291796 18.593599, + -26.097799 8.0291796 -18.593599, + -26.2915 7.3044901 -18.593599, + -26.623699 6.0613098 18.593599, + -26.613701 6.0590301 18.7174, + -26.087999 8.0261497 18.7174, + -17.888599 20.5501 -18.837799, + 3.25774 26.549 -8.9505701, + 13.9835 23.405001 -18.837799, + 8.2488899 26.549 -4.7624998, + 8.3954897 26.549 -1.48035, + 8.9505701 26.549 -3.25774, + -9.38029 26.549 -1.654, + -15.3274 22.1035 -19.901699, + -13.578 23.2192 -19.901699, + -15.3011 22.065599 -20.0082, + -13.9835 23.405001 -18.837799, + -8.2488899 26.549 -4.7624998, + -8.9505701 26.549 -3.25774, + -15.4293 22.515301 -18.7174, + -17.0648 21.302401 -18.7174, + -17.0457 21.278601 -18.837799, + -15.412 22.490101 -18.837799, + -15.4351 22.5238 -18.593599, + -17.071301 21.3104 -18.593599, + -14.06 23.405001 -18.6423, + -14.0472 23.405001 -18.703899, + -14.0214 23.405001 -18.7717, + -26.271099 5.6990299 -19.901699, + -26.5839 6.0522399 -18.837799, + -26.398899 5.1564102 -19.901699, + -25.922899 7.1759701 -19.901699, + -26.3536 5.1475601 -20.0082, + -25.2927 9.1528196 -19.901699, + -8.9505701 26.549 3.25774, + -9.38029 26.549 1.654, + -13.2551 23.405001 19.901699, + -13.578 23.2192 19.901699, + -11.4732 23.3713 22.4058, + -11.4614 23.377701 22.4042, + -11.4477 23.384199 22.4048, + -11.4354 23.389099 22.407499, + -11.427 23.392099 22.407499, + -11.3879 23.4018 22.407499, + -7.2965698 26.549 6.12255, + -8.2488899 26.549 4.7624998, + -19.9552 17.9667 20.0082, + -21.280701 16.375099 20.0082, + -13.469 10.3723 36.380501, + -19.9895 17.997601 19.901699, + -21.343901 16.9638 18.837799, + 12.9399 23.405001 20.348801, + 15.2702 21.301201 21.901699, + 11.0412 12.9264 36.380501, + 16.771999 19.999001 -22.106199, + 15.2071 21.213301 -22.106199, + 11.0937 12.8814 -36.380501, + 16.811899 20.046499 -22.0082, + 15.2433 21.2637 -22.0082, + 18.240299 18.6695 -22.106199, + 20.9879 17.379 -18.837799, + 19.6849 17.3039 -21.901699, + 21.343901 16.9638 -18.837799, + 3.9725299 -13.3297 -36.4305, + 20.789301 17.6733 -18.593599, + 21.3759 16.989201 -18.593599, + 21.367901 16.9828 -18.7174, + 20.0424 18.5285 -18.7174, + 20.049999 18.5354 -18.593599, + 21.3759 16.989201 18.593599, + 24.6047 11.8157 -18.7174, + 24.614 11.8202 -18.593599, + 23.664301 13.6222 -18.593599, + 22.7187 15.0549 -18.837799, + 22.075399 14.1279 -21.901699, + 22.5492 15.3254 -18.837799, + 23.628901 13.6018 -18.837799, + 22.574499 15.3426 -18.7174, + 23.655399 13.617 -18.7174, + 26.097799 8.0291796 -18.593599, + 27.2498 1.47857 18.593599, + 27.229 2.0355201 18.593599, + -2.86129 -14.8945 36.4305, + -5.04883 -16.233 36.380501, + -6.6651902 -15.6389 36.380501, + 3.46346 -16.6434 36.380501, + 6.7428699 -15.6056 36.380501, + -1.37041 -15.0089 36.4305, + -11.0412 -12.9264 36.380501, + 20.789301 17.6733 18.593599, + 20.049999 18.5354 18.593599, + 22.583 15.3484 18.593599, + 23.664301 13.6222 18.593599, + 22.7187 15.0549 18.837799, + 22.574499 15.3426 18.7174, + 14.0214 -23.405001 -18.7717, + 14.0472 -23.405001 -18.703899, + 13.9835 -23.405001 -18.837799, + 15.412 -22.490101 -18.837799, + 12.9399 -23.405001 -20.348801, + 11.7952 -23.405001 -21.901699, + 13.5546 -22.305401 -22.106199, + 13.6108 -22.3979 -21.901699, + 13.915 -22.196899 -21.901699, + 11.4022 -23.405001 -22.1835, + 11.3768 -23.405001 -22.1926, + 11.5114 -23.405001 -22.129801, + 5.06354 -16.228399 -36.380501, + 3.3957701 -16.6574 -36.380501, + 1.5094399 -26.9685 -7.35221, + 7.1219201 -26.9685 -2.36889, + 15.4293 -22.515301 18.7174, + 14.0416 -23.405001 18.721901, + 14.0355 -23.405001 18.7386, + 14.0576 -23.405001 18.658199, + 17.0648 -21.302401 18.7174, + 17.0457 -21.278601 18.837799, + 17.0648 -21.302401 -18.7174, + 15.4293 -22.515301 -18.7174, + 18.6054 -19.971001 -18.7174, + 17.510201 -20.9513 10.9224, + 17.0284 -21.3447 -11.6594, + 16.368 -21.8552 -12.5696, + 16.868099 -21.4716 11.89, + 17.071301 -21.3104 -18.593599, + 17.071301 -21.3104 18.593599, + -18.5427 -19.4849 -19.901699, + -20.02 -18.5077 -18.837799, + -18.5109 -19.4515 -20.0082, + -19.9895 -17.997601 -19.901699, + -18.6054 -19.971001 -18.7174, + -16.9856 -20.856199 -19.901699, + -16.9564 -20.820499 -20.0082, + -17.647499 -20.2733 -19.901699, + -17.888599 -20.5501 -18.837799, + -18.584499 -19.948601 -18.837799, + -16.178301 -21.996099 -12.8129, + -15.6544 -22.371901 13.4479, + -15.4351 -22.5238 18.593599, + -14.8866 -22.889999 14.2932, + -14.063 -23.405001 -18.593599, + -14.6576 -23.0373 -14.5279, + -6.7287202 -15.6117 -36.380501, + -11.4573 -23.378401 -22.407499, + 1.23809 -14.9554 -36.4305, + -5.11479 -16.212299 -36.380501, + -1.74657 -16.91 -36.380501, + 1.83263 -15.0945 -36.4305, + -0.026853301 -17 -36.380501, + -3.44837 -16.646601 -36.380501, + 1.53002 -15.0477 -36.4305, + -11.3478 -23.405001 -22.407499, + -20.335699 -18.2215 -3.5165701, + -21.3759 -16.989201 -18.593599, + -20.4788 -18.060499 -2.55407, + -20.400101 -18.1493 3.1212499, + -20.049999 -18.5354 -18.593599, + -11.4419 -23.3866 22.4058, + -11.4563 -23.380301 22.4041, + -13.2467 -23.405001 19.913401, + -11.4573 -23.378401 22.407499, + -11.4792 -23.367701 22.407499, + -8.21315 -14.8844 36.380501, + -11.4354 -23.389099 22.407499, + -11.4678 -23.374399 22.4048, + -27.229 2.0355201 -18.593599, + -27.001499 4.05971 -18.593599, + -27.001499 4.05971 18.593599, + -27.229 2.0355201 18.593599, + -27.2498 1.47857 -18.593599, + -27.2498 1.47857 18.593599, + -26.991301 4.0581799 -18.7174, + -26.9611 4.0536399 -18.837799, + -26.736401 -2.8670299 19.901699, + -27.188299 -2.03247 18.837799, + -26.8778 -1.03745 19.901699, + -26.717899 -3.1061699 19.901699, + -26.831699 -1.03567 20.0082, + -25.417101 -9.9486103 18.7174, + -26.991301 -4.0581799 18.7174, + -26.9611 -4.0536399 18.837799, + -26.933901 -4.4179602 18.593599, + -25.358101 10.1099 18.593599, + -25.358101 10.1099 -18.593599, + -23.664301 13.6222 18.593599, + -24.614 11.8202 18.593599, + -23.655399 13.617 18.7174, + -23.664301 13.6222 -18.593599, + -22.574499 15.3426 18.7174, + -22.583 15.3484 18.593599, + -22.583 15.3484 -18.593599, + -14.4493 8.9564896 36.380501, + -15.2812 7.44873 36.380501, + 19.022301 19.509199 -18.837799, + 18.6054 19.971001 -18.7174, + 20.02 18.5077 -18.837799, + 18.2966 18.7645 -21.901699, + 18.584499 19.948601 -18.837799, + 16.8416 20.0819 -21.901699, + 18.316 18.746901 -21.901699, + 18.283701 18.7139 -22.0082, + 27.229 -2.0355201 -18.593599, + 27.001499 -4.05971 -18.593599, + 27.2498 -1.47857 -18.593599, + 27.294701 -3.5481504e-010 -18.7174, + 27.188299 -2.03247 -18.837799, + 27.264099 2.9409926e-011 -18.837799, + 27.2188 -2.03475 -18.7174, + 27.305 -3.7394352e-010 -18.593599, + 27.2188 2.03475 -18.7174, + 27.188299 2.03247 -18.837799, + 26.144199 -0.99274099 -22.0082, + 25.993601 -2.9725101 -22.0082, + 26.039499 -2.9777501 -21.901699, + 26.1903 -0.99449301 -21.901699, + 25.931999 -2.9654601 -22.106199, + 26.082199 -0.99038702 -22.106199, + 26.144199 0.99274099 -22.0082, + 26.082199 0.99038702 -22.106199, + 23.0832 -12.4132 -21.901699, + 22.075399 -14.1279 -21.901699, + 23.0425 -12.3913 -22.0082, + 23.915899 -10.6082 -22.0082, + 23.958099 -10.6269 -21.901699, + -16.7999 2.6008101 -36.380501, + -16.976801 0.88785398 -36.380501, + 19.6036 -17.2325 -22.106199, + 12.303 -11.7319 -36.380501, + 13.4267 -10.427 -36.380501, + 19.022301 -19.509199 -18.837799, + 21.367901 -16.9828 -18.7174, + 20.9035 -15.7336 -22.0082, + 20.854 -15.6963 -22.106199, + 22.036501 -14.1031 -22.0082, + 21.8375 -14.4703 -21.901699, + 16.771999 -19.999001 -22.106199, + 18.240299 -18.6695 -22.106199, + 11.0529 -12.9164 -36.380501, + 15.2071 -21.213301 -22.106199, + 16.8416 -20.0819 -21.901699, + 18.2966 -18.7645 -21.901699, + 18.283701 -18.7139 -22.0082, + 16.811899 -20.046499 -22.0082, + 18.584499 -19.948601 -18.837799, + 17.0457 -21.278601 -18.837799, + 15.2702 -21.301201 -21.901699, + 15.2433 -21.2637 -22.0082, + 23.958099 -10.6269 21.901699, + 23.664301 -13.6222 -18.593599, + 22.583 -15.3484 18.593599, + 13.9835 -23.405001 18.837799, + 12.8858 -23.405001 20.424601, + 12.3506 -11.6818 36.380501, + 19.6849 -17.3039 21.901699, + 16.811899 20.046499 22.0082, + 16.771999 19.999001 22.106199, + 18.240299 18.6695 22.106199, + -10.9065 10.1843 36.4305, + -10.3006 10.2596 36.4305, + -10.6065 10.2452 36.4305, + -5.1294899 16.207701 36.380501, + -11.1938 10.0783 36.4305, + -3.46346 16.6434 36.380501, + -10.9186 8.7616196 36.4305, + 11.5114 23.405001 22.129801, + -24.577101 -11.8025 18.837799, + -24.469801 -11.0562 20.0082, + -23.5853 -12.9317 19.901699, + -23.5448 -12.9095 20.0082, + -23.5853 -12.9317 -19.901699, + -23.5448 -12.9095 -20.0082, + -24.577101 -11.8025 -18.837799, + -23.628901 -13.6018 -18.837799, + -22.518299 -14.7112 -19.901699, + -22.479601 -14.686 -20.0082, + -24.5119 -11.0752 -19.901699, + -25.2493 -9.1371098 -20.0082, + -26.9611 -4.0536399 -18.837799, + -26.398899 -5.1564102 -19.901699, + -26.613701 -6.0590301 -18.7174, + -26.991301 -4.0581799 -18.7174, + -26.717899 -3.1061699 -19.901699, + -27.0903 -2.90464 -18.837799, + -20.0424 18.5285 -18.7174, + -18.6054 19.971001 -18.7174, + 3.25774 26.549 8.9505701, + -3.25774 26.549 -8.9505701, + -1.654 26.549 -9.38029, + -4.7624998 26.549 -8.2488899, + 1.654 26.549 -9.38029, + 12.8858 23.405001 -20.424601, + 13.6108 22.3979 -21.901699, + 7.3828702 26.549 4.2624998, + 5.4797602 26.549 6.53053, + 14.0576 23.405001 -18.658199, + 9.38029 26.549 -1.654, + 14.0416 23.405001 -18.721901, + 14.063 23.405001 -18.593599, + 15.4293 22.515301 -18.7174, + 15.4351 22.5238 -18.593599, + -18.5109 19.4515 20.0082, + -14.0416 23.405001 18.721901, + -15.4351 22.5238 18.593599, + -14.0576 23.405001 18.658199, + -18.5427 19.4849 19.901699, + -17.647499 20.2733 19.901699, + -16.9856 20.856199 19.901699, + -21.3759 16.989201 18.593599, + -21.3759 16.989201 -18.593599, + -18.6124 19.9785 -18.593599, + -20.049999 18.5354 -18.593599, + -20.789301 17.6733 -18.593599, + -22.574499 15.3426 -18.7174, + 9.5249996 26.549 -8.9990115e-010, + 14.063 23.405001 18.593599, + 15.4351 22.5238 18.593599, + 8.2488899 26.549 4.7624998, + 13.9835 23.405001 18.837799, + 15.412 22.490101 18.837799, + 11.7485 23.405001 21.9557, + 7.2965698 26.549 6.12255, + 6.12255 26.549 7.2965698, + 11.7952 23.405001 21.901699, + 11.6886 23.405001 22.007401, + 13.915 22.196899 21.901699, + 13.6108 22.3979 21.901699, + 15.2433 21.2637 22.0082, + 11.8522 23.3244 22.0082, + 11.8731 23.365601 21.901699, + 13.5869 22.3584 -22.0082, + 13.5546 22.305401 -22.106199, + 11.8731 23.365601 -21.901699, + 11.7952 23.405001 -21.901699, + 7.2965698 26.549 -6.12255, + 12.0626 9.3067799 -36.4305, + 25.358101 10.1099 18.593599, + 25.4266 9.9523602 18.593599, + 26.623699 6.0613098 -18.593599, + 27.001499 4.05971 -18.593599, + 26.613701 6.0590301 -18.7174, + 26.991301 4.0581799 -18.7174, + 26.2915 7.3044901 18.593599, + 26.2915 7.3044901 -18.593599, + 26.097799 8.0291796 18.593599, + 26.623699 6.0613098 18.593599, + 26.933901 4.4179602 -18.593599, + 27.001499 4.05971 18.593599, + 26.933901 4.4179602 18.593599, + 26.908701 4.3313498 18.837799, + 26.613701 6.0590301 18.7174, + 26.991301 4.0581799 18.7174, + 23.8592 -10.5831 -22.106199, + 15.9324 -5.9293599 -36.380501, + 26.908701 -4.3313498 -18.837799, + 26.9611 -4.0536399 -18.837799, + 26.991301 -4.0581799 -18.7174, + 23.655399 -13.617 -18.7174, + 23.628901 -13.6018 -18.837799, + 25.4266 -9.9523602 18.593599, + 27.2498 -1.47857 18.593599, + 27.229 -2.0355201 18.593599, + -3.56443 -14.3146 36.4305, + -3.12449 -14.738 36.4305, + -3.3607099 -14.5432 36.4305, + -14.4046 -9.0282297 36.380501, + -13.4173 -10.4392 36.380501, + -12.2923 -11.743 36.380501, + 1.76191 -16.9084 36.380501, + 0.042266 -16.999901 36.380501, + -0.82321203 -14.738 36.4305, + 8.2870598 -14.8433 36.380501, + 11.1054 -12.8713 36.380501, + 20.0424 18.5285 18.7174, + 18.6054 19.971001 18.7174, + 22.5492 15.3254 18.837799, + 11.8522 -23.3244 -22.0082, + 11.6417 -23.405001 -22.0478, + 11.8241 -23.2691 -22.106199, + 11.6886 -23.405001 -22.007401, + 11.7485 -23.405001 -21.9557, + 13.5869 -22.3584 -22.0082, + 11.8731 -23.365601 -21.901699, + 14.063 -23.405001 15.1042, + 14.063 -23.405001 -15.1042, + 14.063 -23.405001 18.593599, + -17.0284 -21.3447 11.6594, + -17.071301 -21.3104 18.593599, + -16.868099 -21.4716 -11.89, + -16.368 -21.8552 12.5696, + -17.071301 -21.3104 -18.593599, + -17.0648 -21.302401 -18.7174, + -15.4351 -22.5238 -18.593599, + -17.0457 -21.278601 -18.837799, + -14.0576 -23.405001 -18.658199, + -11.4354 -23.389099 -22.407499, + -11.4333 -23.3899 -22.407499, + -11.3912 -23.401199 -22.407499, + -20.5987 -17.9237 1.26543, + -20.628099 -17.889799 -0.62401599, + -20.576099 -17.9496 -1.59078, + -20.520399 -18.013201 2.1951201, + -20.6348 -17.882 0.331945, + -21.3759 -16.989201 18.593599, + -20.789301 -17.6733 18.593599, + -20.157301 -18.4184 4.4145298, + -20.1453 -18.431801 -4.4804802, + -20.2374 -18.330601 4.0440202, + -20.101101 -18.48 4.6747799, + -20.049999 -18.5354 18.593599, + -27.188299 2.03247 -18.837799, + -27.0903 2.90464 -18.837799, + -26.717899 3.1061699 -19.901699, + -27.2188 2.03475 -18.7174, + -26.736401 2.8670299 -19.901699, + -26.8778 1.03745 -19.901699, + -27.264099 1.2345204e-009 -18.837799, + -27.294701 -1.265771e-009 -18.7174, + -26.2915 -7.3044901 18.593599, + -26.087999 -8.0261497 18.7174, + -26.097799 -8.0291796 18.593599, + -26.613701 -6.0590301 18.7174, + -26.623699 -6.0613098 18.593599, + -26.2915 -7.3044901 -18.593599, + -23.655399 13.617 -18.7174, + -24.614 11.8202 -18.593599, + -12.3111 8.6992798 36.4305, + -12.2213 8.9919901 36.4305, + -12.3553 8.3962698 36.4305, + -16.467899 4.22016 36.380501, + -16.810301 2.53249 36.380501, + -11.7034 9.7419901 36.4305, + -12.0878 9.26756 36.4305, + -11.4615 9.9297199 36.4305, + -11.9138 9.5195303 36.4305, + -9.7462196 13.9288 36.380501, + -11.1054 12.8713 36.380501, + -12.3506 11.6818 36.380501, + -12.2083 7.4967799 36.4305, + -15.9271 -5.94381 36.380501, + -16.797501 -2.61604 36.380501, + -12.3526 8.0900898 36.4305, + -16.976 -0.90324497 36.380501, + -16.446699 -4.302 36.380501, + -12.3032 7.7879 36.4305, + -26.672001 -3.1008401 20.0082, + 11.0823 23.405001 -22.2943, + 10.9328 23.405001 -22.322001, + 10.6808 23.405001 -22.368601, + 11.3489 23.405001 -22.2061, + 9.9545803 10.2299 -36.4305, + -1.69314 16.915501 -36.380501, + -25.2493 9.1371098 -20.0082, + -25.878401 7.16365 -20.0082, + -17.647499 20.2733 -19.901699, + -16.9856 20.856199 -19.901699, + -18.5427 19.4849 -19.901699, + -18.584499 19.948601 -18.837799, + -16.9795 -0.834216 -36.380501, + 10.8991 6.3460302 -36.4305, + 10.616 8.9726 -36.4305, + 19.6849 -17.3039 -21.901699, + 18.316 -18.746901 -21.901699, + 20.02 -18.5077 -18.837799, + 19.6502 -17.2735 -22.0082, + 20.9879 -17.379 -18.837799, + 21.343901 -16.9638 -18.837799, + 20.940399 -15.7613 -21.901699, + 14.4493 -8.9564896 36.380501, + 25.388599 -9.9374704 18.837799, + 25.417101 -9.9486103 18.7174, + 26.097799 -8.0291796 18.593599, + 25.287001 -6.8898201 21.901699, + 24.695 -8.7795 21.901699, + 9.7462196 -13.9288 36.380501, + 15.2702 -21.301201 21.901699, + 15.412 -22.490101 18.837799, + 13.6108 -22.3979 21.901699, + 13.5546 -22.305401 22.106199, + 15.2071 -21.213301 22.106199, + 15.2433 -21.2637 22.0082, + 13.915 -22.196899 21.901699, + 18.283701 -18.7139 22.0082, + 16.771999 -19.999001 22.106199, + 16.811899 -20.046499 22.0082, + 18.240299 -18.6695 22.106199, + 18.2966 -18.7645 21.901699, + 18.316 -18.746901 21.901699, + 16.8416 -20.0819 21.901699, + 13.871 3.5622699 36.4305, + -0.38326299 -14.3146 36.4305, + 19.6036 -17.2325 22.106199, + 13.469 -10.3723 36.380501, + 21.8375 14.4703 21.901699, + 22.075399 14.1279 21.901699, + 21.9842 14.0696 22.106199, + 22.036501 14.1031 22.0082, + 19.022301 19.509199 18.837799, + 19.6502 17.2735 22.0082, + 19.6036 17.2325 22.106199, + 20.940399 15.7613 21.901699, + 20.9035 15.7336 22.0082, + 20.854 15.6963 22.106199, + -0.58698398 -14.5432 36.4305, + -1.08641 -14.8945 36.4305, + 6.6651902 15.6389 36.380501, + 13.1601 6.6629901 36.4305, + 11.6417 23.405001 22.0478, + 23.915899 -10.6082 22.0082, + 24.651501 -8.76404 22.0082, + -25.2927 -9.1528196 19.901699, + -24.5119 -11.0752 19.901699, + -25.388599 -9.9374704 18.837799, + -25.2493 -9.1371098 20.0082, + -26.058701 -8.0171604 18.837799, + -26.058701 -8.0171604 -18.837799, + -25.2927 -9.1528196 -19.901699, + -25.922899 -7.1759701 -19.901699, + -26.087999 -8.0261497 -18.7174, + -26.5839 -6.0522399 -18.837799, + -25.388599 -9.9374704 -18.837799, + -11.4419 23.3866 -22.4058, + -11.4563 23.380301 -22.4041, + -13.2467 23.405001 -19.913401, + -11.3478 23.405001 -22.407499, + -15.3011 22.065599 20.0082, + -16.9564 20.820499 20.0082, + -11.498 23.3549 22.407499, + -11.4792 23.367701 22.407499, + -15.412 22.490101 18.837799, + -14.0015 23.405001 18.8092, + -14.0355 23.405001 18.7386, + -15.4293 22.515301 18.7174, + -15.3274 22.1035 19.901699, + -13.9835 23.405001 18.837799, + -18.584499 19.948601 18.837799, + -18.6124 19.9785 18.593599, + -17.071301 21.3104 18.593599, + -17.0648 21.302401 18.7174, + -17.888599 20.5501 18.837799, + -17.0457 21.278601 18.837799, + -21.343901 16.9638 -18.837799, + -21.367901 16.9828 -18.7174, + -20.02 18.5077 -18.837799, + -21.549999 16.075399 -19.901699, + -22.5492 15.3254 -18.837799, + -21.317301 16.4032 -19.901699, + -22.479601 14.686 -20.0082, + -22.518299 14.7112 -19.901699, + 14.0472 23.405001 18.703899, + 14.0214 23.405001 18.7717, + 8.9505701 26.549 3.25774, + 9.38029 26.549 1.654, + 14.06 23.405001 18.6423, + 15.4293 22.515301 18.7174, + 13.5546 22.305401 22.106199, + 9.6768398 13.9771 36.380501, + 15.2071 21.213301 22.106199, + 13.5869 22.3584 22.0082, + 8.21315 14.8844 36.380501, + 11.8241 23.2691 22.106199, + 11.8241 23.2691 -22.106199, + 26.287201 7.1624298 18.837799, + 26.5839 6.0522399 18.837799, + 26.058701 8.0171604 18.837799, + 26.087999 8.0261497 18.7174, + 24.6047 11.8157 18.7174, + 25.417101 9.9486103 18.7174, + 24.614 11.8202 18.593599, + 23.655399 13.617 18.7174, + 23.628901 13.6018 18.837799, + 22.9879 12.3619 22.106199, + 24.577101 11.8025 18.837799, + 25.388599 9.9374704 18.837799, + 25.6933 -4.9351501 -22.0082, + 25.358101 -10.1099 18.593599, + 25.4266 -9.9523602 -18.593599, + 24.577101 -11.8025 -18.837799, + 24.6047 -11.8157 -18.7174, + 25.358101 -10.1099 -18.593599, + 24.614 -11.8202 -18.593599, + 26.9611 4.0536399 18.837799, + 27.294701 5.6533017e-010 18.7174, + 27.188299 -2.03247 18.837799, + 27.264099 -1.4559648e-009 18.837799, + 27.305 -8.6206386e-010 18.593599, + 27.2188 2.03475 18.7174, + 27.188299 2.03247 18.837799, + -2.27915 -15.0787 36.4305, + -1.66855 -15.0787 36.4305, + -2.5772901 -15.0089 36.4305, + -1.97385 -15.1022 36.4305, + -3.3806601 -16.6605 36.380501, + -1.67781 -16.917 36.380501, + 20.9879 17.379 18.837799, + 21.367901 16.9828 18.7174, + 21.343901 16.9638 18.837799, + 20.02 18.5077 18.837799, + 19.6849 17.3039 21.901699, + 25.287001 6.8898201 21.901699, + 25.2896 6.8814998 21.901699, + 15.4351 -22.5238 -18.593599, + 15.4351 -22.5238 18.593599, + 17.866199 -20.645399 -10.3151, + 17.636299 -20.845301 -10.7177, + 17.8715 -20.6439 10.3206, + 18.4123 -20.163099 -9.32162, + 18.191999 -20.362101 -9.7446003, + 18.4076 -20.1674 9.3310099, + 18.6124 -19.9785 -18.593599, + 18.6124 -19.9785 18.593599, + -13.578 -23.2192 -19.901699, + -15.3274 -22.1035 -19.901699, + -26.271099 -5.6990299 19.901699, + -26.398899 -5.1564102 19.901699, + -26.5839 -6.0522399 18.837799, + -25.922899 -7.1759701 19.901699, + -26.3536 -5.1475601 20.0082, + -25.878401 -7.16365 20.0082, + -24.577101 11.8025 -18.837799, + -23.628901 13.6018 -18.837799, + -23.5853 12.9317 -19.901699, + -24.6047 11.8157 -18.7174, + -24.5119 11.0752 -19.901699, + -25.388599 9.9374704 -18.837799, + -25.417101 9.9486103 -18.7174, + 10.5645 10.2586 -36.4305, + 10.2584 10.2677 -36.4305, + 1.74657 16.91 -36.380501, + 3.44837 16.646601 -36.380501, + -8.2266397 14.8769 -36.380501, + -11.1875 6.4663501 -36.4305, + 8.8993597 9.6441803 -36.4305, + 11.4249 9.9579697 -36.4305, + 8.2735996 14.8508 -36.380501, + 9.7335901 13.9376 -36.380501, + 11.1547 10.1019 -36.4305, + 11.67 9.7744598 -36.4305, + 10.8656 10.2029 -36.4305, + 11.8843 9.5556898 -36.4305, + -11.0529 12.9164 -36.380501, + -13.4887 6.4663501 -36.4305, + -9.6895103 13.9683 -36.380501, + -16.9564 20.820499 -20.0082, + -11.5085 23.3465 -22.407499, + -11.4333 23.3899 -22.407499, + -11.3912 23.401199 -22.407499, + -11.4573 23.378401 -22.407499, + -11.4792 23.367701 -22.407499, + -11.4354 23.389099 -22.407499, + -11.4678 23.374399 -22.4048, + -13.9287 6.0429401 -36.4305, + -14.3015 5.2112699 -36.4305, + -16.4506 4.2870798 -36.380501, + -15.2508 7.5107999 -36.380501, + -14.4127 9.0151701 -36.380501, + -15.9324 5.9293599 -36.380501, + -24.469801 11.0562 -20.0082, + -14.2204 5.5065198 -36.4305, + -23.5448 12.9095 -20.0082, + -16.464001 -4.2350898 -36.380501, + -16.808001 -2.54773 -36.380501, + 26.933901 -4.4179602 -18.593599, + 26.623699 -6.0613098 18.593599, + 26.623699 -6.0613098 -18.593599, + 26.2915 -7.3044901 18.593599, + 23.0425 -12.3913 22.0082, + 22.9879 -12.3619 22.106199, + 21.9842 -14.0696 22.106199, + 23.664301 -13.6222 18.593599, + 24.614 -11.8202 18.593599, + 22.574499 -15.3426 18.7174, + 26.933901 -4.4179602 18.593599, + 27.001499 -4.05971 18.593599, + 27.2188 -2.03475 18.7174, + 26.1903 -0.99449301 21.901699, + 26.1903 0.99449301 21.901699, + 15.9271 5.94381 36.380501, + 13.5869 -22.3584 22.0082, + 11.8241 -23.2691 22.106199, + 20.9035 -15.7336 22.0082, + 19.6502 -17.2735 22.0082, + 20.940399 -15.7613 21.901699, + 20.854 -15.6963 22.106199, + 22.036501 -14.1031 22.0082, + 21.8375 -14.4703 21.901699, + 18.2966 18.7645 21.901699, + 18.283701 18.7139 22.0082, + 16.8416 20.0819 21.901699, + 18.316 18.746901 21.901699, + 18.584499 19.948601 18.837799, + -0.010432499 -13.4829 36.4305, + 3.3806601 16.6605 36.380501, + 12.8723 6.7677798 36.4305, + 5.04883 16.233 36.380501, + 11.123 23.405001 22.2831, + 1.67781 16.917 36.380501, + 12.572 6.8274298 36.4305, + 11.1702 23.405001 22.2663, + -9.9961395 10.2271 36.4305, + 11.3768 23.405001 22.1926, + 11.4022 23.405001 22.1835, + 10.405 23.405001 -22.3918, + 10.6194 23.405001 -22.3799, + 7.3727004e-011 26.549 -9.5249996, + 10.1221 23.405001 -22.407499, + 0.026853301 17 -36.380501, + -20.0424 18.5285 18.7174, + -18.6054 19.971001 18.7174, + -20.02 18.5077 18.837799, + -20.049999 18.5354 18.593599, + -21.367901 16.9828 18.7174, + -20.789301 17.6733 18.593599, + -19.9552 17.9667 -20.0082, + -13.4267 10.427 -36.380501, + -12.303 11.7319 -36.380501, + -18.5109 19.4515 -20.0082, + -21.280701 16.375099 -20.0082, + -19.9895 17.997601 -19.901699, + 11.6891 23.405001 -22.007401, + 11.724 23.405001 -21.9799, + 11.8522 23.3244 -22.0082, + 6.12255 26.549 -7.2965698, + 11.5673 23.405001 -22.0975, + 5.11479 16.212299 -36.380501, + 6.7287202 15.6117 -36.380501, + 11.6066 23.405001 -22.072399, + 11.3762 23.405001 -22.1926, + 4.7624998 26.549 -8.2488899, + 23.915899 10.6082 22.0082, + 24.695 8.7795 21.901699, + 23.958099 10.6269 21.901699, + 23.8592 10.5831 22.106199, + 23.0425 12.3913 22.0082, + 23.0832 12.4132 21.901699, + 25.1852 -6.8530898 -22.106199, + 24.593 -8.7432604 -22.106199, + 24.651501 -8.76404 -22.0082, + 16.4506 -4.2870798 -36.380501, + 25.632401 -4.92345 -22.106199, + 25.738701 -4.9438601 -21.901699, + 26.087999 -8.0261497 -18.7174, + 25.417101 -9.9486103 -18.7174, + 26.097799 -8.0291796 -18.593599, + 25.388599 -9.9374704 -18.837799, + 26.287201 -7.1624298 -18.837799, + 26.2915 -7.3044901 -18.593599, + 26.613701 -6.0590301 -18.7174, + 26.5839 -6.0522399 -18.837799, + 26.039499 2.9777501 21.901699, + 25.738701 4.9438601 21.901699, + 25.1852 6.8530898 22.106199, + 24.593 8.7432604 22.106199, + 24.651501 8.76404 22.0082, + 25.2451 6.86938 22.0082, + 14.8141 -22.9354 -14.3646, + 14.6576 -23.0373 14.5279, + 14.063 -23.405001 -18.593599, + 14.8866 -22.889999 -14.2932, + -11.4728 -23.3715 -22.4058, + -11.4477 -23.384199 -22.4048, + -11.4792 -23.367701 -22.407499, + -11.4614 -23.377701 -22.4042, + -13.2551 -23.405001 -19.901699, + -13.9835 -23.405001 -18.837799, + -12.9415 6.7372799 -36.4305, + -12.3381 6.8304901 -36.4305, + -12.6434 6.8070502 -36.4305, + -13.2255 6.6228199 -36.4305, + -3.3957701 16.6574 -36.380501, + -5.06354 16.228399 -36.380501, + -6.6793599 15.6329 -36.380501, + -15.9511 -5.8790002 -36.380501, + -14.2666 4.30053 -36.4305, + 0.96368998 -14.8195 -36.4305, + -14.3249 4.60112 -36.4305, + 2.53455 -13.6123 -36.4305, + -12.8034 4.24159 -36.4305, + -14.3366 4.9070902 -36.4305, + -11.6616 5.15554 -36.4305, + -14.0951 5.7859302 -36.4305, + -13.725 6.2715302 -36.4305, + -10.9512 6.2715302 -36.4305, + 26.287201 -7.1624298 18.837799, + 26.058701 -8.0171604 18.837799, + 26.087999 -8.0261497 18.7174, + 25.2896 -6.8814998 21.901699, + 23.628901 -13.6018 18.837799, + 24.6047 -11.8157 18.7174, + 24.577101 -11.8025 18.837799, + 23.655399 -13.617 18.7174, + 23.0832 -12.4132 21.901699, + 22.075399 -14.1279 21.901699, + 22.7187 -15.0549 18.837799, + 26.082199 -0.99038702 22.106199, + 15.9564 -5.8645401 36.380501, + 24.593 -8.7432604 22.106199, + 23.8592 -10.5831 22.106199, + 15.2812 -7.44873 36.380501, + 14.0483 3.8119199 36.4305, + 14.1853 4.08571 36.4305, + 14.279 4.3772202 36.4305, + 13.4284 6.5155001 36.4305, + 13.6711 6.3287802 36.4305, + 13.4173 10.4392 36.380501, + 12.2923 11.743 36.380501, + 11.7952 -23.405001 21.901699, + 11.8731 -23.365601 21.901699, + 13.0658 5.00737 36.4305, + 0.012954999 -12.8728 36.4305, + -3.73087 -14.0576 36.4305, + -10.2052 8.9949398 36.4305, + 12.2661 6.8405299 36.4305, + 25.287001 -6.8898201 -21.901699, + 25.2451 -6.86938 -22.0082, + 24.695 -8.7795 -21.901699, + 25.2896 -6.8814998 -21.901699, + 26.058701 -8.0171604 -18.837799, + 25.931999 2.9654601 22.106199, + 26.144199 0.99274099 22.0082, + 26.082199 0.99038702 22.106199, + 25.993601 2.9725101 22.0082, + 25.632401 4.92345 22.106199, + 25.6933 4.9351501 22.0082, + -14.0355 -23.405001 -18.7386, + -14.0416 -23.405001 -18.721901, + -5.6124802 -26.9685 -4.9833202, + -14.0015 -23.405001 -18.8092, + -15.4293 -22.515301 -18.7174, + -15.412 -22.490101 -18.837799, + -14.4411 -8.9695902 -36.380501, + -15.2745 -7.4625802 -36.380501, + 26.908701 -4.3313498 18.837799, + 26.9611 -4.0536399 18.837799, + 26.5839 -6.0522399 18.837799, + 26.613701 -6.0590301 18.7174, + 26.991301 -4.0581799 18.7174, + 26.039499 -2.9777501 21.901699, + 26.144199 -0.99274099 22.0082, + 25.738701 -4.9438601 21.901699, + 25.993601 -2.9725101 22.0082, + 14.3271 4.6796198 36.4305, + 16.976 0.90324497 36.380501, + 16.980301 -0.81882101 36.380501, + 14.0574 5.8559699 36.4305, + 13.8824 6.1072102 36.4305, + 14.4046 9.0282297 36.380501, + 15.244 7.5246201 36.380501, + 11.6891 -23.405001 22.007401, + 11.8522 -23.3244 22.0082, + 11.6066 -23.405001 22.072399, + 11.724 -23.405001 21.9799, + 5.6124802 -26.9685 4.9833202, + -13.8312 3.49984 -36.4305, + 0.492621 -14.431 -36.4305, + -13.4596 -10.3846 -36.380501, + -13.6106 3.2875099 -36.4305, + -14.1631 4.0123501 -36.4305, + 0.30699599 -14.1875 -36.4305, + -14.0168 3.74335 -36.4305, + 25.632401 -4.92345 22.106199, + 25.2451 -6.86938 22.0082, + 25.1852 -6.8530898 22.106199, + 25.6933 -4.9351501 22.0082, + 16.467899 -4.22016 36.380501, + 16.810301 -2.53249 36.380501, + 25.931999 -2.9654601 22.106199, + 14.2831 5.28862 36.4305, + 14.1921 5.5809598 36.4305, + 16.446699 4.302 36.380501, + 14.3285 4.9858098 36.4305, + 16.797501 2.61604 36.380501 ] + + } + coordIndex [ 318, 1204, 311, -1, 318, 246, 2, -1, + 91, 246, 72, -1, 721, 945, 104, -1, + 170, 329, 52, -1, 170, 136, 329, -1, + 441, 719, 12, -1, 441, 12, 10, -1, + 656, 388, 181, -1, 674, 171, 859, -1, + 0, 318, 2, -1, 0, 1204, 318, -1, + 20, 721, 104, -1, 20, 104, 318, -1, + 463, 467, 1204, -1, 3, 0, 2, -1, + 3, 1204, 0, -1, 498, 502, 749, -1, + 485, 481, 4, -1, 24, 4, 481, -1, + 234, 48, 49, -1, 11, 43, 15, -1, + 8, 441, 10, -1, 8, 228, 441, -1, + 14, 6, 10, -1, 545, 544, 59, -1, + 30, 31, 117, -1, 44, 12, 719, -1, + 154, 775, 774, -1, 152, 578, 810, -1, + 161, 810, 1013, -1, 805, 1005, 385, -1, + 175, 329, 1048, -1, 213, 208, 65, -1, + 432, 65, 208, -1, 17, 18, 6, -1, + 17, 6, 14, -1, 16, 5, 6, -1, + 16, 6, 18, -1, 16, 1, 5, -1, + 16, 246, 1, -1, 512, 1, 246, -1, + 512, 5, 1, -1, 23, 463, 1204, -1, + 23, 462, 463, -1, 23, 1204, 3, -1, + 603, 604, 1204, -1, 22, 2, 246, -1, + 22, 246, 1178, -1, 22, 3, 2, -1, + 22, 23, 3, -1, 1182, 1207, 627, -1, + 334, 627, 1207, -1, 577, 385, 1005, -1, + 504, 87, 462, -1, 504, 1178, 749, -1, + 504, 462, 1178, -1, 242, 485, 4, -1, + 242, 4, 249, -1, 254, 26, 509, -1, + 92, 4, 24, -1, 92, 249, 4, -1, + 1206, 24, 1207, -1, 1206, 92, 24, -1, + 506, 755, 48, -1, 506, 48, 234, -1, + 67, 15, 43, -1, 67, 66, 17, -1, + 96, 27, 26, -1, 102, 509, 26, -1, + 102, 26, 27, -1, 761, 27, 96, -1, + 7, 10, 6, -1, 7, 8, 10, -1, + 514, 6, 5, -1, 514, 7, 6, -1, + 514, 8, 7, -1, 514, 5, 512, -1, + 514, 515, 228, -1, 514, 228, 8, -1, + 9, 12, 11, -1, 9, 10, 12, -1, + 9, 14, 10, -1, 9, 11, 15, -1, + 9, 15, 14, -1, 108, 268, 269, -1, + 107, 268, 108, -1, 281, 279, 31, -1, + 119, 443, 421, -1, 287, 652, 668, -1, + 287, 283, 652, -1, 129, 128, 309, -1, + 305, 33, 75, -1, 305, 472, 230, -1, + 308, 309, 128, -1, 37, 38, 34, -1, + 37, 34, 305, -1, 612, 329, 136, -1, + 396, 136, 170, -1, 274, 182, 880, -1, + 1163, 111, 1162, -1, 46, 149, 49, -1, + 41, 11, 12, -1, 41, 12, 44, -1, + 41, 43, 11, -1, 41, 42, 43, -1, + 41, 44, 144, -1, 98, 43, 42, -1, + 98, 48, 755, -1, 142, 98, 42, -1, + 340, 154, 774, -1, 146, 772, 150, -1, + 155, 772, 775, -1, 155, 150, 772, -1, + 338, 49, 149, -1, 1124, 1183, 335, -1, + 764, 383, 385, -1, 156, 1013, 1012, -1, + 156, 161, 1013, -1, 167, 170, 52, -1, + 398, 167, 646, -1, 398, 168, 167, -1, + 55, 181, 378, -1, 28, 281, 31, -1, + 28, 31, 30, -1, 56, 30, 57, -1, + 56, 28, 30, -1, 56, 349, 28, -1, + 542, 660, 543, -1, 540, 543, 665, -1, + 661, 543, 660, -1, 617, 859, 171, -1, + 617, 171, 1053, -1, 1047, 174, 1048, -1, + 412, 187, 409, -1, 197, 198, 188, -1, + 63, 188, 198, -1, 415, 428, 190, -1, + 692, 204, 65, -1, 199, 62, 63, -1, + 199, 63, 198, -1, 223, 62, 199, -1, + 223, 199, 200, -1, 215, 213, 65, -1, + 220, 219, 293, -1, 220, 293, 300, -1, + 13, 14, 15, -1, 13, 17, 14, -1, + 13, 15, 67, -1, 13, 67, 17, -1, + 71, 72, 246, -1, 71, 491, 72, -1, + 70, 16, 18, -1, 70, 246, 16, -1, + 69, 17, 66, -1, 69, 18, 17, -1, + 69, 70, 18, -1, 69, 491, 71, -1, + 494, 91, 72, -1, 19, 721, 20, -1, + 19, 135, 721, -1, 19, 20, 318, -1, + 19, 318, 135, -1, 960, 962, 957, -1, + 76, 75, 33, -1, 76, 33, 38, -1, + 232, 192, 82, -1, 232, 82, 454, -1, + 232, 454, 730, -1, 585, 83, 121, -1, + 79, 954, 80, -1, 597, 596, 472, -1, + 478, 957, 962, -1, 478, 473, 957, -1, + 478, 962, 323, -1, 478, 323, 468, -1, + 478, 79, 476, -1, 478, 954, 79, -1, + 21, 1178, 462, -1, 21, 22, 1178, -1, + 21, 462, 23, -1, 21, 23, 22, -1, + 244, 24, 481, -1, 244, 1207, 24, -1, + 244, 334, 1207, -1, 25, 93, 192, -1, + 25, 231, 460, -1, 25, 460, 93, -1, + 25, 232, 231, -1, 25, 192, 232, -1, + 85, 462, 89, -1, 85, 89, 94, -1, + 1113, 242, 249, -1, 227, 67, 761, -1, + 227, 761, 96, -1, 497, 498, 495, -1, + 97, 26, 254, -1, 97, 96, 26, -1, + 101, 102, 27, -1, 101, 27, 761, -1, + 523, 269, 268, -1, 523, 522, 269, -1, + 50, 106, 108, -1, 50, 108, 269, -1, + 109, 106, 341, -1, 532, 533, 272, -1, + 532, 272, 107, -1, 532, 107, 109, -1, + 264, 268, 107, -1, 264, 261, 265, -1, + 137, 1162, 790, -1, 110, 1162, 111, -1, + 110, 790, 1162, -1, 785, 790, 110, -1, + 525, 383, 764, -1, 348, 281, 28, -1, + 348, 28, 349, -1, 115, 57, 59, -1, + 114, 57, 115, -1, 29, 30, 117, -1, + 29, 57, 30, -1, 29, 117, 545, -1, + 29, 545, 59, -1, 29, 59, 57, -1, + 781, 117, 31, -1, 781, 31, 279, -1, + 276, 118, 270, -1, 280, 266, 267, -1, + 712, 561, 937, -1, 556, 561, 712, -1, + 555, 1025, 1014, -1, 906, 287, 668, -1, + 651, 652, 283, -1, 651, 179, 288, -1, + 185, 644, 179, -1, 325, 324, 40, -1, + 325, 40, 309, -1, 130, 309, 40, -1, + 130, 129, 309, -1, 130, 39, 35, -1, + 573, 229, 587, -1, 290, 83, 237, -1, + 290, 121, 83, -1, 1090, 705, 240, -1, + 301, 300, 293, -1, 191, 240, 239, -1, + 191, 1090, 240, -1, 299, 298, 62, -1, + 299, 220, 300, -1, 299, 221, 220, -1, + 299, 62, 223, -1, 299, 223, 221, -1, + 989, 409, 187, -1, 989, 987, 409, -1, + 591, 82, 590, -1, 591, 454, 82, -1, + 598, 456, 599, -1, 304, 305, 35, -1, + 304, 35, 39, -1, 304, 39, 307, -1, + 32, 33, 305, -1, 32, 305, 34, -1, + 32, 38, 33, -1, 32, 34, 38, -1, + 961, 472, 305, -1, 961, 305, 75, -1, + 961, 75, 74, -1, 961, 74, 77, -1, + 961, 77, 962, -1, 131, 35, 305, -1, + 131, 130, 35, -1, 932, 601, 709, -1, + 132, 709, 601, -1, 469, 323, 319, -1, + 469, 468, 323, -1, 36, 38, 37, -1, + 36, 76, 38, -1, 36, 126, 307, -1, + 36, 125, 126, -1, 36, 962, 76, -1, + 36, 307, 39, -1, 36, 305, 125, -1, + 36, 37, 305, -1, 36, 324, 323, -1, + 36, 323, 962, -1, 36, 40, 324, -1, + 36, 39, 130, -1, 36, 130, 40, -1, + 613, 274, 614, -1, 394, 182, 274, -1, + 394, 613, 395, -1, 394, 274, 613, -1, + 148, 149, 46, -1, 148, 46, 47, -1, + 148, 47, 618, -1, 141, 41, 144, -1, + 141, 42, 41, -1, 141, 142, 42, -1, + 99, 43, 98, -1, 99, 67, 43, -1, + 99, 761, 67, -1, 718, 138, 144, -1, + 718, 44, 719, -1, 718, 144, 44, -1, + 139, 1162, 137, -1, 620, 138, 621, -1, + 620, 618, 47, -1, 143, 47, 142, -1, + 143, 620, 47, -1, 143, 138, 620, -1, + 143, 144, 138, -1, 45, 47, 46, -1, + 45, 142, 47, -1, 45, 49, 48, -1, + 45, 46, 49, -1, 45, 48, 98, -1, + 45, 98, 142, -1, 151, 146, 150, -1, + 330, 331, 234, -1, 330, 234, 49, -1, + 330, 49, 338, -1, 623, 335, 1183, -1, + 623, 1183, 1182, -1, 623, 1182, 627, -1, + 153, 385, 577, -1, 153, 764, 385, -1, + 153, 577, 578, -1, 153, 578, 152, -1, + 767, 152, 145, -1, 342, 769, 159, -1, + 342, 159, 635, -1, 342, 106, 50, -1, + 342, 341, 106, -1, 342, 269, 769, -1, + 342, 50, 269, -1, 344, 1012, 1124, -1, + 344, 156, 1012, -1, 634, 161, 156, -1, + 634, 635, 159, -1, 369, 370, 165, -1, + 51, 167, 52, -1, 51, 175, 167, -1, + 51, 52, 329, -1, 51, 329, 175, -1, + 169, 396, 170, -1, 169, 168, 396, -1, + 173, 171, 646, -1, 173, 646, 167, -1, + 173, 174, 1047, -1, 173, 167, 175, -1, + 53, 388, 398, -1, 387, 398, 388, -1, + 176, 396, 168, -1, 176, 168, 398, -1, + 640, 686, 360, -1, 640, 177, 53, -1, + 640, 53, 398, -1, 640, 398, 646, -1, + 1080, 801, 360, -1, 1080, 360, 686, -1, + 1079, 801, 1080, -1, 361, 179, 644, -1, + 666, 668, 652, -1, 666, 667, 668, -1, + 371, 177, 370, -1, 371, 181, 388, -1, + 371, 388, 53, -1, 371, 53, 177, -1, + 54, 177, 998, -1, 54, 370, 177, -1, + 54, 998, 875, -1, 54, 875, 165, -1, + 54, 165, 370, -1, 180, 656, 181, -1, + 376, 55, 378, -1, 376, 181, 55, -1, + 384, 804, 805, -1, 351, 349, 56, -1, + 351, 56, 57, -1, 351, 114, 350, -1, + 351, 57, 114, -1, 58, 400, 116, -1, + 58, 401, 400, -1, 58, 544, 401, -1, + 58, 59, 544, -1, 58, 115, 59, -1, + 58, 116, 115, -1, 889, 377, 662, -1, + 889, 662, 888, -1, 60, 116, 400, -1, + 60, 400, 184, -1, 60, 183, 116, -1, + 60, 184, 183, -1, 403, 183, 184, -1, + 894, 665, 543, -1, 894, 543, 661, -1, + 664, 894, 661, -1, 673, 669, 646, -1, + 673, 646, 171, -1, 673, 171, 674, -1, + 680, 859, 912, -1, 677, 671, 678, -1, + 677, 405, 671, -1, 410, 411, 551, -1, + 410, 551, 553, -1, 61, 551, 411, -1, + 61, 411, 185, -1, 61, 185, 179, -1, + 284, 551, 61, -1, 284, 61, 179, -1, + 284, 179, 651, -1, 189, 196, 197, -1, + 189, 553, 552, -1, 189, 190, 196, -1, + 991, 187, 188, -1, 991, 989, 187, -1, + 687, 62, 298, -1, 687, 63, 62, -1, + 687, 188, 63, -1, 687, 991, 188, -1, + 687, 298, 191, -1, 419, 430, 428, -1, + 419, 428, 415, -1, 419, 193, 430, -1, + 195, 196, 190, -1, 195, 190, 428, -1, + 195, 428, 427, -1, 202, 216, 204, -1, + 202, 219, 216, -1, 699, 434, 206, -1, + 562, 203, 693, -1, 562, 563, 203, -1, + 211, 208, 213, -1, 211, 423, 208, -1, + 425, 193, 444, -1, 425, 444, 445, -1, + 425, 430, 193, -1, 695, 65, 432, -1, + 695, 692, 65, -1, 222, 200, 212, -1, + 222, 223, 200, -1, 218, 213, 215, -1, + 64, 204, 216, -1, 64, 216, 215, -1, + 64, 65, 204, -1, 64, 215, 65, -1, + 224, 570, 295, -1, 224, 203, 563, -1, + 224, 202, 203, -1, 224, 295, 202, -1, + 739, 741, 491, -1, 739, 69, 66, -1, + 739, 491, 69, -1, 739, 66, 67, -1, + 739, 67, 227, -1, 68, 70, 69, -1, + 68, 246, 70, -1, 68, 69, 71, -1, + 68, 71, 246, -1, 492, 72, 491, -1, + 492, 494, 72, -1, 317, 135, 318, -1, + 921, 920, 445, -1, 73, 74, 75, -1, + 73, 75, 76, -1, 73, 77, 74, -1, + 73, 962, 77, -1, 73, 76, 962, -1, + 452, 463, 453, -1, 732, 463, 462, -1, + 732, 453, 463, -1, 737, 467, 463, -1, + 737, 954, 467, -1, 78, 463, 449, -1, + 78, 1109, 463, -1, 78, 449, 471, -1, + 953, 80, 954, -1, 953, 78, 471, -1, + 953, 1109, 78, -1, 451, 456, 598, -1, + 451, 597, 471, -1, 451, 598, 597, -1, + 465, 1204, 467, -1, 465, 466, 1204, -1, + 233, 603, 1204, -1, 233, 1204, 466, -1, + 475, 476, 79, -1, 475, 79, 80, -1, + 475, 80, 953, -1, 461, 93, 460, -1, + 461, 85, 94, -1, 501, 87, 504, -1, + 501, 94, 90, -1, 581, 580, 238, -1, + 581, 83, 585, -1, 81, 580, 590, -1, + 81, 238, 580, -1, 81, 192, 238, -1, + 81, 590, 82, -1, 81, 82, 192, -1, + 236, 237, 83, -1, 236, 83, 581, -1, + 236, 581, 238, -1, 84, 458, 462, -1, + 84, 462, 85, -1, 84, 461, 458, -1, + 84, 85, 461, -1, 86, 462, 87, -1, + 86, 90, 462, -1, 86, 87, 501, -1, + 86, 501, 90, -1, 88, 89, 462, -1, + 88, 462, 90, -1, 88, 94, 89, -1, + 88, 90, 94, -1, 493, 91, 494, -1, + 493, 246, 91, -1, 486, 481, 485, -1, + 255, 253, 227, -1, 255, 227, 254, -1, + 748, 498, 749, -1, 748, 495, 498, -1, + 1126, 92, 1206, -1, 1126, 249, 92, -1, + 1126, 1206, 1210, -1, 1126, 1128, 192, -1, + 250, 192, 93, -1, 250, 1126, 192, -1, + 250, 497, 1126, -1, 250, 94, 501, -1, + 250, 93, 461, -1, 250, 461, 94, -1, + 95, 227, 96, -1, 95, 96, 97, -1, + 95, 254, 227, -1, 95, 97, 254, -1, + 756, 98, 755, -1, 756, 761, 99, -1, + 756, 99, 98, -1, 759, 761, 508, -1, + 100, 761, 509, -1, 100, 101, 761, -1, + 100, 509, 102, -1, 100, 102, 101, -1, + 103, 512, 246, -1, 103, 259, 512, -1, + 103, 318, 104, -1, 103, 246, 318, -1, + 103, 104, 945, -1, 103, 945, 944, -1, + 103, 944, 436, -1, 103, 436, 259, -1, + 437, 259, 436, -1, 437, 435, 515, -1, + 260, 270, 118, -1, 527, 107, 272, -1, + 527, 528, 261, -1, 527, 261, 264, -1, + 527, 264, 107, -1, 970, 795, 969, -1, + 105, 106, 109, -1, 105, 109, 107, -1, + 105, 108, 106, -1, 105, 107, 108, -1, + 534, 532, 109, -1, 534, 340, 774, -1, + 534, 341, 340, -1, 534, 109, 341, -1, + 616, 785, 110, -1, 616, 111, 1163, -1, + 616, 110, 111, -1, 787, 880, 879, -1, + 787, 879, 788, -1, 112, 356, 164, -1, + 112, 164, 347, -1, 262, 356, 112, -1, + 262, 112, 519, -1, 524, 347, 525, -1, + 524, 112, 347, -1, 524, 519, 112, -1, + 357, 356, 262, -1, 357, 262, 266, -1, + 357, 266, 280, -1, 357, 280, 348, -1, + 275, 350, 114, -1, 113, 114, 115, -1, + 113, 539, 275, -1, 113, 275, 114, -1, + 113, 541, 539, -1, 113, 115, 116, -1, + 113, 183, 541, -1, 113, 116, 183, -1, + 779, 117, 781, -1, 779, 545, 117, -1, + 782, 118, 276, -1, 782, 279, 118, -1, + 782, 781, 279, -1, 278, 118, 279, -1, + 278, 260, 118, -1, 278, 280, 267, -1, + 278, 267, 265, -1, 278, 265, 260, -1, + 708, 555, 1014, -1, 547, 119, 421, -1, + 547, 283, 119, -1, 328, 906, 671, -1, + 328, 671, 405, -1, 285, 443, 119, -1, + 285, 119, 283, -1, 285, 283, 287, -1, + 568, 926, 1091, -1, 568, 123, 569, -1, + 558, 707, 566, -1, 120, 573, 710, -1, + 120, 229, 573, -1, 120, 132, 229, -1, + 120, 710, 709, -1, 120, 709, 132, -1, + 586, 573, 587, -1, 586, 585, 121, -1, + 586, 121, 290, -1, 704, 290, 237, -1, + 704, 237, 705, -1, 292, 123, 124, -1, + 292, 571, 569, -1, 292, 569, 123, -1, + 297, 124, 191, -1, 297, 191, 298, -1, + 297, 292, 124, -1, 297, 301, 292, -1, + 122, 1090, 191, -1, 122, 1091, 1090, -1, + 122, 124, 123, -1, 122, 191, 124, -1, + 122, 568, 1091, -1, 122, 123, 568, -1, + 589, 590, 580, -1, 582, 472, 596, -1, + 306, 125, 305, -1, 306, 126, 125, -1, + 306, 307, 126, -1, 127, 308, 128, -1, + 127, 131, 308, -1, 127, 128, 129, -1, + 127, 129, 130, -1, 127, 130, 131, -1, + 133, 131, 305, -1, 133, 308, 131, -1, + 133, 305, 230, -1, 310, 132, 601, -1, + 583, 818, 229, -1, 583, 229, 132, -1, + 583, 310, 308, -1, 583, 132, 310, -1, + 583, 133, 230, -1, 583, 308, 133, -1, + 313, 438, 311, -1, 134, 311, 438, -1, + 134, 438, 316, -1, 134, 318, 311, -1, + 134, 316, 318, -1, 720, 316, 438, -1, + 720, 721, 135, -1, 720, 135, 317, -1, + 327, 326, 325, -1, 327, 325, 1023, -1, + 327, 1023, 1145, -1, 840, 469, 319, -1, + 724, 605, 855, -1, 723, 830, 826, -1, + 723, 439, 1202, -1, 321, 839, 319, -1, + 321, 319, 323, -1, 1157, 609, 406, -1, + 1157, 406, 1155, -1, 615, 396, 395, -1, + 615, 395, 613, -1, 615, 136, 396, -1, + 615, 612, 136, -1, 147, 146, 151, -1, + 147, 338, 149, -1, 147, 151, 338, -1, + 791, 795, 970, -1, 791, 137, 790, -1, + 791, 139, 137, -1, 619, 621, 139, -1, + 619, 139, 791, -1, 717, 621, 138, -1, + 717, 139, 621, -1, 717, 138, 718, -1, + 717, 1162, 139, -1, 140, 142, 141, -1, + 140, 143, 142, -1, 140, 141, 144, -1, + 140, 144, 143, -1, 768, 159, 769, -1, + 768, 158, 159, -1, 768, 145, 158, -1, + 768, 767, 145, -1, 160, 810, 161, -1, + 160, 152, 810, -1, 160, 145, 152, -1, + 160, 158, 145, -1, 531, 772, 146, -1, + 531, 146, 147, -1, 531, 148, 618, -1, + 531, 618, 864, -1, 531, 149, 148, -1, + 531, 147, 149, -1, 625, 332, 331, -1, + 337, 150, 155, -1, 337, 151, 150, -1, + 337, 338, 151, -1, 337, 872, 624, -1, + 766, 152, 767, -1, 766, 153, 152, -1, + 766, 764, 153, -1, 629, 1124, 335, -1, + 629, 344, 1124, -1, 632, 154, 340, -1, + 632, 775, 154, -1, 343, 156, 344, -1, + 870, 632, 871, -1, 870, 155, 775, -1, + 870, 775, 632, -1, 870, 337, 155, -1, + 870, 872, 337, -1, 631, 634, 156, -1, + 631, 156, 343, -1, 631, 343, 871, -1, + 157, 159, 158, -1, 157, 634, 159, -1, + 157, 158, 160, -1, 157, 161, 634, -1, + 157, 160, 161, -1, 386, 346, 976, -1, + 386, 804, 384, -1, 386, 384, 346, -1, + 162, 535, 536, -1, 977, 354, 162, -1, + 977, 162, 536, -1, 163, 162, 354, -1, + 163, 350, 535, -1, 163, 535, 162, -1, + 353, 163, 354, -1, 353, 350, 163, -1, + 355, 164, 356, -1, 355, 347, 164, -1, + 367, 369, 165, -1, 367, 875, 1000, -1, + 367, 165, 875, -1, 166, 167, 168, -1, + 166, 168, 169, -1, 166, 170, 167, -1, + 166, 169, 170, -1, 638, 173, 1047, -1, + 638, 1053, 171, -1, 638, 171, 173, -1, + 172, 174, 173, -1, 172, 173, 175, -1, + 172, 1048, 174, -1, 172, 175, 1048, -1, + 397, 396, 176, -1, 397, 176, 398, -1, + 997, 875, 998, -1, 641, 998, 177, -1, + 641, 177, 640, -1, 1074, 1080, 686, -1, + 178, 288, 179, -1, 178, 179, 361, -1, + 178, 362, 288, -1, 178, 361, 362, -1, + 364, 362, 686, -1, 364, 288, 362, -1, + 365, 378, 181, -1, 365, 181, 371, -1, + 382, 346, 384, -1, 382, 383, 525, -1, + 382, 525, 347, -1, 776, 540, 665, -1, + 776, 665, 972, -1, 655, 656, 180, -1, + 655, 180, 181, -1, 655, 181, 376, -1, + 655, 376, 377, -1, 655, 377, 889, -1, + 393, 182, 394, -1, 393, 880, 182, -1, + 393, 391, 880, -1, 883, 398, 387, -1, + 390, 885, 880, -1, 390, 886, 885, -1, + 1063, 541, 183, -1, 1063, 183, 403, -1, + 1063, 660, 542, -1, 1063, 542, 541, -1, + 402, 403, 184, -1, 402, 184, 400, -1, + 404, 669, 673, -1, 404, 681, 678, -1, + 682, 185, 411, -1, 682, 644, 185, -1, + 408, 987, 683, -1, 408, 682, 411, -1, + 408, 683, 682, -1, 186, 187, 412, -1, + 186, 188, 187, -1, 186, 412, 553, -1, + 186, 553, 189, -1, 186, 197, 188, -1, + 186, 189, 197, -1, 414, 552, 548, -1, + 414, 189, 552, -1, 414, 415, 190, -1, + 414, 190, 189, -1, 416, 191, 239, -1, + 416, 687, 191, -1, 416, 239, 238, -1, + 416, 238, 192, -1, 416, 192, 1128, -1, + 418, 193, 419, -1, 418, 444, 193, -1, + 418, 422, 444, -1, 194, 196, 195, -1, + 194, 195, 427, -1, 194, 197, 196, -1, + 194, 198, 197, -1, 194, 200, 199, -1, + 194, 199, 198, -1, 194, 212, 200, -1, + 194, 427, 212, -1, 294, 293, 219, -1, + 294, 219, 202, -1, 294, 202, 295, -1, + 201, 203, 202, -1, 201, 202, 204, -1, + 201, 204, 692, -1, 201, 693, 203, -1, + 201, 692, 693, -1, 691, 699, 206, -1, + 691, 206, 562, -1, 691, 562, 693, -1, + 205, 561, 562, -1, 205, 562, 206, -1, + 205, 937, 561, -1, 205, 433, 937, -1, + 205, 206, 434, -1, 205, 434, 433, -1, + 424, 445, 920, -1, 424, 425, 445, -1, + 424, 920, 209, -1, 424, 208, 423, -1, + 424, 209, 208, -1, 429, 211, 212, -1, + 429, 212, 427, -1, 429, 423, 211, -1, + 207, 208, 209, -1, 207, 209, 689, -1, + 207, 432, 208, -1, 207, 689, 432, -1, + 688, 209, 920, -1, 688, 689, 209, -1, + 1167, 576, 575, -1, 1096, 576, 1167, -1, + 1096, 1167, 1169, -1, 210, 212, 211, -1, + 210, 222, 212, -1, 210, 211, 213, -1, + 210, 213, 218, -1, 210, 218, 222, -1, + 214, 215, 216, -1, 214, 218, 215, -1, + 214, 216, 219, -1, 214, 219, 218, -1, + 217, 218, 219, -1, 217, 219, 220, -1, + 217, 220, 221, -1, 217, 222, 218, -1, + 217, 221, 223, -1, 217, 223, 222, -1, + 289, 224, 563, -1, 289, 570, 224, -1, + 289, 563, 559, -1, 225, 491, 741, -1, + 225, 490, 491, -1, 225, 741, 489, -1, + 225, 489, 490, -1, 226, 227, 253, -1, + 226, 739, 227, -1, 226, 247, 739, -1, + 226, 253, 252, -1, 226, 252, 247, -1, + 440, 438, 313, -1, 440, 313, 439, -1, + 715, 228, 515, -1, 715, 515, 435, -1, + 715, 441, 228, -1, 947, 444, 422, -1, + 947, 422, 442, -1, 727, 947, 948, -1, + 1086, 922, 846, -1, 819, 229, 818, -1, + 819, 587, 229, -1, 815, 583, 230, -1, + 815, 230, 472, -1, 815, 472, 582, -1, + 450, 463, 452, -1, 455, 450, 452, -1, + 455, 456, 451, -1, 455, 451, 450, -1, + 459, 460, 231, -1, 729, 462, 459, -1, + 729, 459, 231, -1, 729, 232, 730, -1, + 729, 231, 232, -1, 736, 463, 1109, -1, + 828, 603, 233, -1, 828, 233, 466, -1, + 477, 475, 953, -1, 477, 953, 471, -1, + 477, 472, 961, -1, 477, 473, 478, -1, + 243, 333, 334, -1, 243, 332, 333, -1, + 243, 245, 332, -1, 257, 331, 332, -1, + 257, 332, 245, -1, 257, 234, 331, -1, + 257, 506, 234, -1, 235, 237, 236, -1, + 235, 705, 237, -1, 235, 238, 239, -1, + 235, 236, 238, -1, 235, 240, 705, -1, + 235, 239, 240, -1, 963, 964, 1113, -1, + 241, 242, 1113, -1, 241, 1113, 964, -1, + 241, 485, 242, -1, 241, 964, 485, -1, + 482, 245, 243, -1, 482, 244, 481, -1, + 482, 334, 244, -1, 482, 243, 334, -1, + 480, 245, 482, -1, 480, 257, 245, -1, + 480, 258, 257, -1, 483, 254, 509, -1, + 483, 509, 258, -1, 483, 480, 488, -1, + 483, 258, 480, -1, 746, 246, 493, -1, + 746, 1178, 246, -1, 746, 1177, 1178, -1, + 745, 743, 483, -1, 745, 964, 1181, -1, + 742, 252, 254, -1, 742, 247, 252, -1, + 742, 254, 483, -1, 742, 483, 743, -1, + 742, 739, 247, -1, 747, 495, 748, -1, + 248, 497, 495, -1, 248, 1126, 497, -1, + 248, 249, 1126, -1, 248, 1113, 249, -1, + 248, 495, 1113, -1, 500, 497, 250, -1, + 500, 250, 501, -1, 251, 252, 253, -1, + 251, 254, 252, -1, 251, 253, 255, -1, + 251, 255, 254, -1, 256, 509, 752, -1, + 256, 752, 506, -1, 256, 506, 257, -1, + 256, 258, 509, -1, 256, 257, 258, -1, + 505, 759, 508, -1, 754, 755, 506, -1, + 758, 505, 509, -1, 758, 759, 505, -1, + 517, 514, 512, -1, 517, 512, 511, -1, + 516, 259, 437, -1, 516, 517, 511, -1, + 516, 512, 259, -1, 516, 437, 515, -1, + 271, 270, 260, -1, 271, 260, 265, -1, + 271, 265, 261, -1, 271, 261, 528, -1, + 520, 266, 262, -1, 520, 262, 519, -1, + 263, 264, 265, -1, 263, 521, 523, -1, + 263, 267, 266, -1, 263, 265, 267, -1, + 263, 266, 520, -1, 263, 520, 521, -1, + 263, 523, 268, -1, 263, 268, 264, -1, + 765, 519, 524, -1, 765, 269, 522, -1, + 765, 769, 269, -1, 530, 797, 794, -1, + 530, 276, 270, -1, 530, 270, 271, -1, + 530, 271, 528, -1, 530, 794, 276, -1, + 529, 969, 797, -1, 529, 272, 533, -1, + 529, 527, 272, -1, 273, 787, 785, -1, + 273, 614, 274, -1, 273, 785, 614, -1, + 273, 274, 880, -1, 273, 880, 787, -1, + 538, 535, 350, -1, 538, 350, 275, -1, + 538, 275, 539, -1, 780, 790, 785, -1, + 780, 276, 794, -1, 780, 782, 276, -1, + 786, 789, 401, -1, 786, 401, 544, -1, + 277, 278, 279, -1, 277, 280, 278, -1, + 277, 348, 280, -1, 277, 279, 281, -1, + 277, 281, 348, -1, 420, 547, 421, -1, + 420, 548, 547, -1, 420, 419, 548, -1, + 550, 551, 284, -1, 550, 284, 547, -1, + 282, 283, 547, -1, 282, 547, 284, -1, + 282, 651, 283, -1, 282, 284, 651, -1, + 286, 287, 906, -1, 286, 906, 328, -1, + 726, 443, 285, -1, 726, 1042, 849, -1, + 726, 328, 1042, -1, 726, 286, 328, -1, + 726, 285, 287, -1, 726, 287, 286, -1, + 649, 651, 288, -1, 649, 288, 364, -1, + 650, 666, 652, -1, 565, 926, 568, -1, + 560, 708, 707, -1, 560, 707, 558, -1, + 560, 555, 708, -1, 560, 561, 556, -1, + 567, 558, 566, -1, 567, 559, 558, -1, + 567, 289, 559, -1, 567, 570, 289, -1, + 574, 586, 290, -1, 574, 704, 575, -1, + 574, 290, 704, -1, 291, 292, 301, -1, + 291, 301, 293, -1, 291, 571, 292, -1, + 291, 294, 295, -1, 291, 293, 294, -1, + 291, 295, 570, -1, 291, 570, 571, -1, + 296, 297, 298, -1, 296, 299, 300, -1, + 296, 298, 299, -1, 296, 300, 301, -1, + 296, 301, 297, -1, 302, 801, 981, -1, + 302, 981, 798, -1, 302, 360, 801, -1, + 302, 798, 360, -1, 1004, 577, 1005, -1, + 303, 305, 304, -1, 303, 306, 305, -1, + 303, 304, 307, -1, 303, 307, 306, -1, + 602, 309, 308, -1, 602, 308, 310, -1, + 602, 310, 601, -1, 602, 325, 309, -1, + 602, 1023, 325, -1, 314, 313, 311, -1, + 314, 311, 1204, -1, 312, 1202, 439, -1, + 312, 439, 313, -1, 312, 313, 314, -1, + 312, 1204, 1202, -1, 312, 314, 1204, -1, + 315, 316, 720, -1, 315, 720, 317, -1, + 315, 318, 316, -1, 315, 317, 318, -1, + 1144, 327, 1145, -1, 1144, 1037, 327, -1, + 842, 855, 605, -1, 838, 319, 839, -1, + 838, 840, 319, -1, 827, 469, 840, -1, + 827, 828, 469, -1, 835, 724, 826, -1, + 1031, 723, 1202, -1, 1031, 830, 723, -1, + 322, 326, 606, -1, 322, 325, 326, -1, + 320, 606, 839, -1, 320, 839, 321, -1, + 320, 322, 606, -1, 320, 323, 324, -1, + 320, 321, 323, -1, 320, 324, 325, -1, + 320, 325, 322, -1, 1034, 606, 326, -1, + 1034, 326, 327, -1, 1034, 327, 1037, -1, + 1158, 604, 1159, -1, 1158, 1204, 604, -1, + 1040, 328, 405, -1, 1040, 1042, 328, -1, + 611, 1048, 329, -1, 611, 1051, 1048, -1, + 611, 329, 612, -1, 611, 1163, 1164, -1, + 611, 1049, 1051, -1, 611, 1164, 1049, -1, + 857, 859, 617, -1, 908, 1155, 406, -1, + 908, 406, 909, -1, 1151, 855, 842, -1, + 865, 791, 970, -1, 865, 619, 791, -1, + 339, 331, 330, -1, 339, 625, 331, -1, + 339, 330, 338, -1, 626, 332, 625, -1, + 626, 333, 332, -1, 626, 627, 334, -1, + 626, 334, 333, -1, 628, 335, 623, -1, + 628, 624, 872, -1, 628, 629, 335, -1, + 336, 338, 337, -1, 336, 337, 624, -1, + 336, 339, 338, -1, 336, 624, 625, -1, + 336, 625, 339, -1, 633, 340, 341, -1, + 633, 632, 340, -1, 633, 341, 342, -1, + 633, 342, 635, -1, 869, 343, 344, -1, + 869, 871, 343, -1, 869, 344, 629, -1, + 345, 354, 977, -1, 345, 976, 346, -1, + 345, 977, 976, -1, 345, 346, 382, -1, + 345, 382, 347, -1, 345, 347, 355, -1, + 345, 355, 354, -1, 358, 348, 349, -1, + 358, 357, 348, -1, 358, 350, 353, -1, + 358, 351, 350, -1, 358, 349, 351, -1, + 352, 353, 354, -1, 352, 354, 355, -1, + 352, 355, 356, -1, 352, 356, 357, -1, + 352, 357, 358, -1, 352, 358, 353, -1, + 637, 373, 374, -1, 637, 662, 377, -1, + 637, 377, 373, -1, 637, 663, 662, -1, + 895, 809, 808, -1, 895, 637, 809, -1, + 1052, 1053, 638, -1, 996, 368, 1000, -1, + 996, 995, 368, -1, 359, 637, 374, -1, + 359, 809, 637, -1, 807, 809, 359, -1, + 807, 359, 374, -1, 639, 641, 640, -1, + 642, 640, 360, -1, 642, 1056, 640, -1, + 642, 1055, 1056, -1, 642, 360, 798, -1, + 642, 798, 799, -1, 643, 361, 644, -1, + 643, 685, 686, -1, 643, 686, 362, -1, + 643, 362, 361, -1, 904, 669, 903, -1, + 648, 904, 666, -1, 648, 649, 364, -1, + 648, 646, 904, -1, 363, 686, 640, -1, + 363, 364, 686, -1, 363, 640, 646, -1, + 363, 646, 648, -1, 363, 648, 364, -1, + 379, 365, 371, -1, 379, 378, 365, -1, + 366, 374, 375, -1, 366, 369, 367, -1, + 366, 375, 369, -1, 366, 367, 1000, -1, + 366, 1000, 368, -1, 366, 807, 374, -1, + 366, 368, 995, -1, 366, 995, 807, -1, + 380, 369, 375, -1, 380, 370, 369, -1, + 380, 371, 370, -1, 380, 379, 371, -1, + 372, 374, 373, -1, 372, 375, 374, -1, + 372, 377, 376, -1, 372, 373, 377, -1, + 372, 376, 378, -1, 372, 378, 379, -1, + 372, 380, 375, -1, 372, 379, 380, -1, + 381, 383, 382, -1, 381, 382, 384, -1, + 381, 385, 383, -1, 381, 805, 385, -1, + 381, 384, 805, -1, 975, 386, 976, -1, + 975, 1009, 804, -1, 975, 804, 386, -1, + 975, 973, 1011, -1, 975, 1011, 1009, -1, + 653, 657, 402, -1, 653, 789, 788, -1, + 659, 892, 891, -1, 659, 885, 892, -1, + 392, 391, 393, -1, 882, 886, 398, -1, + 882, 398, 883, -1, 654, 883, 387, -1, + 654, 388, 656, -1, 654, 387, 388, -1, + 389, 390, 880, -1, 389, 886, 390, -1, + 389, 880, 391, -1, 389, 391, 392, -1, + 389, 392, 393, -1, 389, 393, 394, -1, + 389, 394, 395, -1, 389, 395, 396, -1, + 389, 396, 397, -1, 389, 398, 886, -1, + 389, 397, 398, -1, 399, 402, 400, -1, + 399, 400, 401, -1, 399, 653, 402, -1, + 399, 401, 789, -1, 399, 789, 653, -1, + 1061, 403, 402, -1, 1061, 1063, 403, -1, + 1061, 402, 657, -1, 670, 669, 404, -1, + 670, 404, 678, -1, 670, 678, 671, -1, + 675, 404, 673, -1, 675, 681, 404, -1, + 679, 405, 677, -1, 679, 1040, 405, -1, + 679, 607, 1040, -1, 608, 909, 406, -1, + 608, 406, 609, -1, 608, 607, 679, -1, + 608, 679, 909, -1, 407, 987, 408, -1, + 407, 409, 987, -1, 407, 411, 410, -1, + 407, 408, 411, -1, 407, 412, 409, -1, + 407, 553, 412, -1, 407, 410, 553, -1, + 413, 415, 414, -1, 413, 414, 548, -1, + 413, 419, 415, -1, 413, 548, 419, -1, + 811, 687, 416, -1, 811, 416, 1128, -1, + 417, 418, 419, -1, 417, 420, 421, -1, + 417, 419, 420, -1, 417, 421, 443, -1, + 417, 443, 442, -1, 417, 442, 422, -1, + 417, 422, 418, -1, 431, 423, 429, -1, + 431, 424, 423, -1, 431, 425, 424, -1, + 431, 430, 425, -1, 426, 427, 428, -1, + 426, 429, 427, -1, 426, 428, 430, -1, + 426, 430, 431, -1, 426, 431, 429, -1, + 952, 1102, 915, -1, 690, 692, 695, -1, + 690, 695, 697, -1, 696, 695, 432, -1, + 696, 432, 689, -1, 702, 917, 915, -1, + 1089, 575, 704, -1, 1089, 1167, 575, -1, + 1092, 566, 707, -1, 1092, 565, 566, -1, + 1092, 926, 565, -1, 929, 576, 1096, -1, + 1099, 708, 1014, -1, 938, 937, 433, -1, + 938, 433, 434, -1, 938, 434, 699, -1, + 938, 933, 939, -1, 942, 715, 435, -1, + 942, 436, 944, -1, 942, 437, 436, -1, + 942, 435, 437, -1, 941, 720, 438, -1, + 941, 438, 440, -1, 856, 439, 723, -1, + 856, 440, 439, -1, 856, 941, 440, -1, + 716, 719, 441, -1, 716, 441, 715, -1, + 725, 442, 443, -1, 725, 947, 442, -1, + 725, 443, 726, -1, 852, 727, 948, -1, + 852, 948, 950, -1, 447, 444, 947, -1, + 447, 947, 727, -1, 447, 445, 444, -1, + 447, 921, 445, -1, 446, 846, 922, -1, + 446, 727, 846, -1, 446, 447, 727, -1, + 446, 922, 921, -1, 446, 921, 447, -1, + 851, 609, 1157, -1, 448, 449, 463, -1, + 448, 463, 450, -1, 448, 450, 451, -1, + 448, 471, 449, -1, 448, 451, 471, -1, + 734, 452, 453, -1, 734, 455, 452, -1, + 734, 453, 732, -1, 733, 730, 454, -1, + 733, 455, 734, -1, 733, 591, 599, -1, + 733, 454, 591, -1, 733, 599, 456, -1, + 733, 456, 455, -1, 457, 462, 458, -1, + 457, 459, 462, -1, 457, 460, 459, -1, + 457, 461, 460, -1, 457, 458, 461, -1, + 731, 732, 462, -1, 731, 462, 729, -1, + 735, 737, 463, -1, 735, 463, 736, -1, + 464, 466, 465, -1, 464, 828, 466, -1, + 464, 467, 954, -1, 464, 465, 467, -1, + 464, 954, 478, -1, 464, 478, 468, -1, + 464, 468, 469, -1, 464, 469, 828, -1, + 470, 471, 597, -1, 470, 477, 471, -1, + 470, 597, 472, -1, 470, 472, 477, -1, + 956, 957, 473, -1, 956, 473, 477, -1, + 956, 477, 961, -1, 474, 476, 475, -1, + 474, 475, 477, -1, 474, 478, 476, -1, + 474, 477, 478, -1, 479, 488, 480, -1, + 479, 481, 486, -1, 479, 486, 488, -1, + 479, 482, 481, -1, 479, 480, 482, -1, + 487, 483, 488, -1, 487, 745, 483, -1, + 484, 485, 964, -1, 484, 964, 745, -1, + 484, 486, 485, -1, 484, 745, 487, -1, + 484, 488, 486, -1, 484, 487, 488, -1, + 740, 489, 741, -1, 740, 742, 489, -1, + 744, 489, 742, -1, 744, 490, 489, -1, + 744, 491, 490, -1, 744, 492, 491, -1, + 744, 493, 494, -1, 744, 746, 493, -1, + 744, 494, 492, -1, 496, 1113, 495, -1, + 496, 495, 747, -1, 1112, 496, 747, -1, + 1112, 1113, 496, -1, 503, 497, 500, -1, + 503, 502, 498, -1, 503, 498, 497, -1, + 499, 500, 501, -1, 499, 749, 502, -1, + 499, 502, 503, -1, 499, 503, 500, -1, + 499, 504, 749, -1, 499, 501, 504, -1, + 507, 505, 508, -1, 507, 752, 509, -1, + 507, 509, 505, -1, 751, 506, 752, -1, + 751, 754, 506, -1, 753, 507, 508, -1, + 753, 752, 507, -1, 753, 508, 761, -1, + 760, 509, 761, -1, 760, 758, 509, -1, + 510, 511, 512, -1, 510, 512, 516, -1, + 510, 516, 511, -1, 513, 515, 514, -1, + 513, 516, 515, -1, 513, 514, 517, -1, + 513, 517, 516, -1, 518, 519, 765, -1, + 518, 520, 519, -1, 518, 521, 520, -1, + 518, 765, 522, -1, 518, 522, 523, -1, + 518, 523, 521, -1, 763, 524, 525, -1, + 763, 765, 524, -1, 763, 525, 764, -1, + 966, 529, 533, -1, 966, 969, 529, -1, + 966, 533, 967, -1, 526, 528, 527, -1, + 526, 527, 529, -1, 526, 530, 528, -1, + 526, 797, 530, -1, 526, 529, 797, -1, + 771, 531, 864, -1, 771, 864, 866, -1, + 771, 772, 531, -1, 771, 866, 967, -1, + 773, 533, 532, -1, 773, 967, 533, -1, + 773, 534, 774, -1, 773, 532, 534, -1, + 773, 771, 967, -1, 777, 538, 540, -1, + 777, 540, 776, -1, 777, 536, 535, -1, + 777, 535, 538, -1, 777, 977, 536, -1, + 537, 538, 539, -1, 537, 540, 538, -1, + 537, 539, 541, -1, 537, 541, 542, -1, + 537, 542, 543, -1, 537, 543, 540, -1, + 784, 780, 785, -1, 784, 786, 544, -1, + 784, 544, 545, -1, 784, 545, 779, -1, + 793, 790, 780, -1, 793, 780, 794, -1, + 546, 547, 548, -1, 546, 550, 547, -1, + 546, 548, 552, -1, 546, 552, 550, -1, + 549, 551, 550, -1, 549, 550, 552, -1, + 549, 553, 551, -1, 549, 552, 553, -1, + 554, 555, 560, -1, 554, 713, 1025, -1, + 554, 1025, 555, -1, 554, 560, 556, -1, + 554, 712, 713, -1, 554, 556, 712, -1, + 557, 558, 559, -1, 557, 560, 558, -1, + 557, 561, 560, -1, 557, 562, 561, -1, + 557, 563, 562, -1, 557, 559, 563, -1, + 564, 566, 565, -1, 564, 567, 566, -1, + 564, 568, 569, -1, 564, 565, 568, -1, + 564, 570, 567, -1, 564, 569, 571, -1, + 564, 571, 570, -1, 572, 573, 586, -1, + 572, 586, 574, -1, 572, 710, 573, -1, + 572, 929, 710, -1, 572, 574, 575, -1, + 572, 576, 929, -1, 572, 575, 576, -1, + 986, 683, 987, -1, 1130, 578, 577, -1, + 1130, 577, 1004, -1, 1130, 810, 578, -1, + 1134, 991, 1131, -1, 1134, 984, 991, -1, + 579, 594, 589, -1, 579, 816, 594, -1, + 579, 589, 580, -1, 579, 580, 581, -1, + 579, 581, 585, -1, 579, 585, 816, -1, + 814, 593, 594, -1, 814, 594, 816, -1, + 814, 815, 582, -1, 814, 582, 596, -1, + 814, 596, 593, -1, 817, 818, 583, -1, + 817, 583, 815, -1, 584, 816, 585, -1, + 584, 819, 816, -1, 584, 585, 586, -1, + 584, 586, 587, -1, 584, 587, 819, -1, + 588, 589, 594, -1, 588, 594, 595, -1, + 588, 590, 589, -1, 588, 591, 590, -1, + 588, 599, 591, -1, 588, 595, 599, -1, + 592, 594, 593, -1, 592, 595, 594, -1, + 592, 593, 596, -1, 592, 596, 597, -1, + 592, 597, 598, -1, 592, 598, 599, -1, + 592, 599, 595, -1, 600, 1141, 821, -1, + 600, 860, 1143, -1, 600, 1143, 1141, -1, + 600, 825, 860, -1, 600, 821, 825, -1, + 1136, 825, 821, -1, 927, 1022, 932, -1, + 927, 928, 711, -1, 822, 821, 1141, -1, + 822, 1022, 927, -1, 822, 927, 711, -1, + 822, 711, 823, -1, 1021, 601, 932, -1, + 1021, 932, 1022, -1, 1021, 602, 601, -1, + 1021, 1023, 602, -1, 1189, 935, 1027, -1, + 861, 860, 825, -1, 1214, 1148, 861, -1, + 832, 840, 836, -1, 832, 827, 840, -1, + 832, 836, 835, -1, 829, 604, 603, -1, + 829, 603, 828, -1, 829, 1159, 604, -1, + 837, 724, 835, -1, 837, 605, 724, -1, + 837, 843, 605, -1, 844, 820, 1151, -1, + 844, 605, 843, -1, 844, 842, 605, -1, + 1033, 839, 606, -1, 1033, 606, 1034, -1, + 1156, 851, 1157, -1, 923, 1198, 1199, -1, + 923, 847, 1198, -1, 1039, 1040, 607, -1, + 1039, 608, 609, -1, 1039, 607, 608, -1, + 1039, 609, 851, -1, 610, 611, 612, -1, + 610, 613, 614, -1, 610, 614, 785, -1, + 610, 612, 615, -1, 610, 615, 613, -1, + 610, 785, 616, -1, 610, 616, 1163, -1, + 610, 1163, 611, -1, 1046, 858, 857, -1, + 1046, 617, 1053, -1, 1046, 857, 617, -1, + 1154, 1155, 908, -1, 1150, 1151, 820, -1, + 1150, 820, 1019, -1, 863, 864, 618, -1, + 863, 619, 865, -1, 863, 618, 620, -1, + 863, 620, 621, -1, 863, 621, 619, -1, + 622, 628, 623, -1, 622, 624, 628, -1, + 622, 625, 624, -1, 622, 626, 625, -1, + 622, 623, 627, -1, 622, 627, 626, -1, + 868, 628, 872, -1, 868, 629, 628, -1, + 868, 869, 629, -1, 630, 631, 871, -1, + 630, 871, 632, -1, 630, 632, 633, -1, + 630, 634, 631, -1, 630, 635, 634, -1, + 630, 633, 635, -1, 636, 663, 637, -1, + 636, 637, 895, -1, 636, 895, 894, -1, + 636, 664, 663, -1, 636, 894, 664, -1, + 1050, 638, 1047, -1, 1050, 1052, 638, -1, + 1002, 1000, 875, -1, 1002, 875, 874, -1, + 1001, 1002, 874, -1, 1001, 875, 997, -1, + 876, 639, 640, -1, 876, 640, 1056, -1, + 876, 998, 641, -1, 876, 641, 639, -1, + 800, 642, 799, -1, 800, 1055, 642, -1, + 684, 643, 644, -1, 684, 685, 643, -1, + 684, 644, 682, -1, 684, 682, 1073, -1, + 645, 646, 669, -1, 645, 904, 646, -1, + 645, 669, 904, -1, 647, 649, 648, -1, + 647, 666, 650, -1, 647, 648, 666, -1, + 647, 651, 649, -1, 647, 652, 651, -1, + 647, 650, 652, -1, 658, 657, 653, -1, + 878, 653, 788, -1, 878, 658, 653, -1, + 878, 659, 658, -1, 878, 788, 879, -1, + 878, 885, 659, -1, 884, 883, 654, -1, + 884, 656, 655, -1, 884, 654, 656, -1, + 884, 889, 890, -1, 884, 655, 889, -1, + 884, 890, 892, -1, 887, 1061, 657, -1, + 887, 657, 658, -1, 887, 659, 891, -1, + 887, 658, 659, -1, 1064, 660, 1063, -1, + 1064, 661, 660, -1, 1064, 664, 661, -1, + 1062, 888, 662, -1, 1062, 662, 663, -1, + 1062, 663, 664, -1, 1062, 664, 1064, -1, + 897, 665, 894, -1, 897, 972, 665, -1, + 900, 973, 972, -1, 900, 972, 897, -1, + 1070, 895, 808, -1, 1070, 808, 1068, -1, + 1070, 1069, 898, -1, 905, 667, 666, -1, + 905, 666, 904, -1, 905, 668, 667, -1, + 905, 906, 668, -1, 902, 903, 669, -1, + 902, 669, 670, -1, 902, 671, 906, -1, + 902, 670, 671, -1, 676, 674, 859, -1, + 676, 859, 680, -1, 672, 673, 674, -1, + 672, 675, 673, -1, 672, 674, 676, -1, + 672, 676, 680, -1, 672, 680, 681, -1, + 672, 681, 675, -1, 910, 677, 678, -1, + 910, 679, 677, -1, 910, 909, 679, -1, + 910, 680, 912, -1, 910, 678, 681, -1, + 910, 681, 680, -1, 913, 682, 683, -1, + 913, 1073, 682, -1, 913, 683, 986, -1, + 1072, 685, 684, -1, 1072, 684, 1073, -1, + 1072, 1074, 686, -1, 1072, 686, 685, -1, + 812, 687, 811, -1, 812, 991, 687, -1, + 919, 689, 688, -1, 919, 925, 917, -1, + 919, 688, 920, -1, 919, 917, 696, -1, + 919, 696, 689, -1, 916, 917, 925, -1, + 916, 925, 1082, -1, 924, 925, 919, -1, + 924, 922, 1086, -1, 698, 690, 697, -1, + 698, 699, 691, -1, 698, 692, 690, -1, + 698, 693, 692, -1, 698, 691, 693, -1, + 694, 697, 695, -1, 694, 695, 696, -1, + 694, 702, 697, -1, 694, 696, 917, -1, + 694, 917, 702, -1, 700, 697, 702, -1, + 700, 699, 698, -1, 700, 698, 697, -1, + 703, 938, 699, -1, 703, 933, 938, -1, + 703, 699, 700, -1, 703, 700, 702, -1, + 701, 702, 915, -1, 701, 915, 1102, -1, + 701, 1102, 933, -1, 701, 933, 703, -1, + 701, 703, 702, -1, 1088, 704, 705, -1, + 1088, 1089, 704, -1, 1088, 705, 1090, -1, + 706, 1092, 707, -1, 706, 1100, 1092, -1, + 706, 1099, 1100, -1, 706, 707, 708, -1, + 706, 708, 1099, -1, 930, 932, 709, -1, + 930, 709, 710, -1, 930, 710, 929, -1, + 1095, 823, 711, -1, 1095, 711, 928, -1, + 1095, 1017, 823, -1, 1016, 1099, 1014, -1, + 1026, 713, 712, -1, 1026, 1025, 713, -1, + 1026, 712, 937, -1, 936, 1027, 935, -1, + 936, 1028, 1027, -1, 936, 939, 1028, -1, + 714, 715, 942, -1, 714, 716, 715, -1, + 714, 941, 1162, -1, 714, 942, 941, -1, + 714, 1162, 717, -1, 714, 717, 718, -1, + 714, 718, 719, -1, 714, 719, 716, -1, + 943, 721, 720, -1, 943, 720, 941, -1, + 943, 945, 721, -1, 722, 723, 826, -1, + 722, 856, 723, -1, 722, 855, 856, -1, + 722, 724, 855, -1, 722, 826, 724, -1, + 949, 947, 725, -1, 949, 726, 849, -1, + 949, 725, 726, -1, 845, 846, 727, -1, + 845, 727, 852, -1, 845, 852, 853, -1, + 728, 729, 730, -1, 728, 731, 729, -1, + 728, 732, 731, -1, 728, 730, 733, -1, + 728, 734, 732, -1, 728, 733, 734, -1, + 1108, 735, 736, -1, 1108, 736, 1109, -1, + 1108, 954, 737, -1, 1108, 737, 735, -1, + 959, 960, 957, -1, 738, 739, 742, -1, + 738, 742, 740, -1, 738, 741, 739, -1, + 738, 740, 741, -1, 1180, 742, 743, -1, + 1180, 744, 742, -1, 1180, 743, 745, -1, + 1180, 745, 1181, -1, 1180, 1177, 746, -1, + 1180, 746, 744, -1, 1115, 1112, 747, -1, + 1115, 747, 748, -1, 1115, 748, 749, -1, + 1115, 963, 1113, -1, 1115, 749, 1178, -1, + 750, 751, 752, -1, 750, 752, 753, -1, + 750, 754, 751, -1, 750, 755, 754, -1, + 750, 756, 755, -1, 750, 761, 756, -1, + 750, 753, 761, -1, 757, 759, 758, -1, + 757, 758, 760, -1, 757, 761, 759, -1, + 757, 760, 761, -1, 762, 763, 764, -1, + 762, 765, 763, -1, 762, 764, 766, -1, + 762, 766, 767, -1, 762, 767, 768, -1, + 762, 768, 769, -1, 762, 769, 765, -1, + 968, 967, 866, -1, 968, 865, 970, -1, + 770, 772, 771, -1, 770, 771, 773, -1, + 770, 773, 774, -1, 770, 774, 775, -1, + 770, 775, 772, -1, 974, 776, 972, -1, + 974, 777, 776, -1, 974, 977, 777, -1, + 778, 784, 779, -1, 778, 780, 784, -1, + 778, 779, 781, -1, 778, 781, 782, -1, + 778, 782, 780, -1, 783, 784, 785, -1, + 783, 786, 784, -1, 783, 787, 788, -1, + 783, 785, 787, -1, 783, 788, 789, -1, + 783, 789, 786, -1, 796, 790, 793, -1, + 796, 795, 791, -1, 796, 791, 790, -1, + 792, 793, 794, -1, 792, 969, 795, -1, + 792, 795, 796, -1, 792, 796, 793, -1, + 792, 797, 969, -1, 792, 794, 797, -1, + 803, 1058, 979, -1, 803, 1119, 1121, -1, + 803, 1121, 998, -1, 803, 998, 876, -1, + 803, 876, 1058, -1, 980, 798, 981, -1, + 980, 799, 798, -1, 980, 800, 799, -1, + 980, 1058, 1055, -1, 980, 1055, 800, -1, + 988, 1077, 986, -1, 1076, 990, 981, -1, + 1076, 981, 801, -1, 1076, 1077, 988, -1, + 1076, 988, 990, -1, 1076, 801, 1079, -1, + 802, 979, 990, -1, 802, 984, 1118, -1, + 802, 991, 984, -1, 802, 990, 991, -1, + 802, 1118, 1119, -1, 802, 803, 979, -1, + 802, 1119, 803, -1, 994, 996, 1000, -1, + 994, 1000, 982, -1, 1123, 1001, 997, -1, + 1123, 982, 1000, -1, 993, 994, 982, -1, + 1008, 804, 1009, -1, 1008, 805, 804, -1, + 1008, 1005, 805, -1, 1132, 1130, 1004, -1, + 806, 807, 995, -1, 806, 995, 1068, -1, + 806, 1068, 808, -1, 806, 808, 809, -1, + 806, 809, 807, -1, 1127, 1013, 810, -1, + 1127, 810, 1130, -1, 1129, 811, 1128, -1, + 1129, 812, 811, -1, 1129, 1131, 991, -1, + 1129, 991, 812, -1, 813, 815, 814, -1, + 813, 814, 816, -1, 813, 817, 815, -1, + 813, 818, 817, -1, 813, 819, 818, -1, + 813, 816, 819, -1, 824, 825, 1136, -1, + 824, 1136, 1138, -1, 1018, 1143, 860, -1, + 1020, 1019, 820, -1, 1020, 820, 844, -1, + 1140, 822, 1141, -1, 1140, 1022, 822, -1, + 1137, 1136, 821, -1, 1137, 821, 822, -1, + 1137, 822, 823, -1, 1137, 823, 1017, -1, + 1137, 1017, 1187, -1, 1185, 935, 1189, -1, + 1185, 1026, 935, -1, 1213, 1214, 861, -1, + 1213, 824, 1138, -1, 1213, 861, 825, -1, + 1213, 825, 824, -1, 1174, 1221, 1223, -1, + 831, 835, 826, -1, 831, 832, 835, -1, + 831, 826, 830, -1, 833, 828, 827, -1, + 833, 829, 828, -1, 833, 827, 832, -1, + 1030, 1159, 829, -1, 1030, 830, 1031, -1, + 1030, 831, 830, -1, 1030, 832, 831, -1, + 1030, 833, 832, -1, 1030, 829, 833, -1, + 834, 835, 836, -1, 834, 837, 835, -1, + 834, 838, 839, -1, 834, 839, 1033, -1, + 834, 836, 840, -1, 834, 840, 838, -1, + 834, 843, 837, -1, 834, 1033, 843, -1, + 841, 1151, 842, -1, 841, 842, 844, -1, + 841, 844, 1151, -1, 1035, 843, 1033, -1, + 1035, 844, 843, -1, 1035, 1020, 844, -1, + 848, 845, 853, -1, 848, 846, 845, -1, + 848, 847, 923, -1, 848, 1086, 846, -1, + 854, 1198, 847, -1, 854, 1156, 1198, -1, + 854, 848, 853, -1, 854, 847, 848, -1, + 854, 851, 1156, -1, 1085, 1086, 848, -1, + 1085, 848, 923, -1, 1041, 849, 1042, -1, + 1041, 949, 849, -1, 1041, 950, 949, -1, + 850, 1039, 851, -1, 850, 950, 1041, -1, + 850, 1041, 1039, -1, 850, 853, 852, -1, + 850, 852, 950, -1, 850, 854, 853, -1, + 850, 851, 854, -1, 1043, 855, 1151, -1, + 1043, 1162, 941, -1, 1043, 856, 855, -1, + 1043, 941, 856, -1, 1045, 858, 1046, -1, + 1045, 1154, 858, -1, 1045, 1049, 1164, -1, + 1045, 1164, 1154, -1, 911, 1154, 908, -1, + 911, 857, 858, -1, 911, 858, 1154, -1, + 911, 912, 859, -1, 911, 859, 857, -1, + 1149, 1150, 1019, -1, 1149, 1018, 860, -1, + 1149, 1019, 1018, -1, 1149, 860, 861, -1, + 1149, 861, 1148, -1, 862, 864, 863, -1, + 862, 863, 865, -1, 862, 866, 864, -1, + 862, 968, 866, -1, 862, 865, 968, -1, + 867, 869, 868, -1, 867, 870, 871, -1, + 867, 871, 869, -1, 867, 872, 870, -1, + 867, 868, 872, -1, 873, 874, 875, -1, + 873, 875, 1001, -1, 873, 1001, 874, -1, + 1057, 876, 1056, -1, 1057, 1058, 876, -1, + 877, 878, 879, -1, 877, 885, 878, -1, + 877, 879, 880, -1, 877, 880, 885, -1, + 881, 882, 883, -1, 881, 883, 884, -1, + 881, 885, 886, -1, 881, 886, 882, -1, + 881, 892, 885, -1, 881, 884, 892, -1, + 1060, 1061, 887, -1, 1060, 888, 1062, -1, + 1060, 889, 888, -1, 1060, 890, 889, -1, + 1060, 887, 891, -1, 1060, 891, 892, -1, + 1060, 892, 890, -1, 893, 897, 894, -1, + 893, 898, 897, -1, 893, 1070, 898, -1, + 893, 894, 895, -1, 893, 895, 1070, -1, + 896, 897, 898, -1, 896, 900, 897, -1, + 896, 898, 1069, -1, 896, 1069, 900, -1, + 899, 900, 1069, -1, 899, 1069, 1066, -1, + 899, 1066, 1007, -1, 899, 1007, 1011, -1, + 899, 1011, 973, -1, 899, 973, 900, -1, + 901, 903, 902, -1, 901, 904, 903, -1, + 901, 905, 904, -1, 901, 906, 905, -1, + 901, 902, 906, -1, 907, 908, 909, -1, + 907, 909, 910, -1, 907, 911, 908, -1, + 907, 910, 912, -1, 907, 912, 911, -1, + 1078, 1073, 913, -1, 1078, 986, 1077, -1, + 1078, 913, 986, -1, 1078, 1080, 1074, -1, + 951, 916, 1082, -1, 951, 952, 916, -1, + 914, 952, 915, -1, 914, 916, 952, -1, + 914, 915, 917, -1, 914, 917, 916, -1, + 918, 919, 920, -1, 918, 924, 919, -1, + 918, 920, 921, -1, 918, 921, 922, -1, + 918, 922, 924, -1, 1084, 1085, 923, -1, + 1084, 923, 1199, -1, 1084, 1199, 1029, -1, + 1083, 925, 924, -1, 1083, 1082, 925, -1, + 1083, 924, 1086, -1, 1166, 1091, 926, -1, + 1166, 926, 1092, -1, 1166, 1167, 1089, -1, + 931, 927, 932, -1, 931, 928, 927, -1, + 1094, 1095, 928, -1, 1094, 929, 1096, -1, + 1094, 930, 929, -1, 1094, 928, 931, -1, + 1094, 932, 930, -1, 1094, 931, 932, -1, + 1098, 1099, 1016, -1, 1098, 1017, 1095, -1, + 1098, 1016, 1017, -1, 1101, 1028, 939, -1, + 1101, 939, 933, -1, 1101, 1171, 1028, -1, + 1101, 933, 1102, -1, 934, 935, 1026, -1, + 934, 936, 935, -1, 934, 1026, 937, -1, + 934, 937, 938, -1, 934, 938, 939, -1, + 934, 939, 936, -1, 940, 941, 942, -1, + 940, 943, 941, -1, 940, 942, 944, -1, + 940, 944, 945, -1, 940, 945, 943, -1, + 946, 948, 947, -1, 946, 947, 949, -1, + 946, 950, 948, -1, 946, 949, 950, -1, + 1104, 1029, 1221, -1, 1104, 1084, 1029, -1, + 1104, 1105, 1084, -1, 1106, 952, 951, -1, + 1106, 1174, 1175, -1, 1106, 1082, 1105, -1, + 1106, 951, 1082, -1, 1106, 1175, 1102, -1, + 1106, 1102, 952, -1, 1110, 1109, 953, -1, + 1110, 953, 954, -1, 1110, 954, 1108, -1, + 955, 956, 961, -1, 955, 961, 959, -1, + 955, 957, 956, -1, 955, 959, 957, -1, + 958, 960, 959, -1, 958, 959, 961, -1, + 958, 962, 960, -1, 958, 961, 962, -1, + 1114, 1112, 1115, -1, 1116, 1115, 1178, -1, + 1116, 963, 1115, -1, 1116, 964, 963, -1, + 1116, 1181, 964, -1, 965, 966, 967, -1, + 965, 967, 968, -1, 965, 969, 966, -1, + 965, 970, 969, -1, 965, 968, 970, -1, + 971, 972, 973, -1, 971, 974, 972, -1, + 971, 973, 975, -1, 971, 975, 976, -1, + 971, 976, 977, -1, 971, 977, 974, -1, + 978, 990, 979, -1, 978, 979, 1058, -1, + 978, 1058, 980, -1, 978, 981, 990, -1, + 978, 980, 981, -1, 1120, 1133, 993, -1, + 1120, 982, 1123, -1, 1120, 993, 982, -1, + 983, 984, 1134, -1, 983, 1118, 984, -1, + 983, 1134, 1133, -1, 983, 1133, 1120, -1, + 983, 1120, 1118, -1, 985, 986, 987, -1, + 985, 988, 986, -1, 985, 987, 989, -1, + 985, 990, 988, -1, 985, 989, 991, -1, + 985, 991, 990, -1, 992, 1133, 1067, -1, + 992, 993, 1133, -1, 992, 994, 993, -1, + 992, 1068, 995, -1, 992, 1067, 1068, -1, + 992, 995, 996, -1, 992, 996, 994, -1, + 1122, 1123, 997, -1, 1122, 998, 1121, -1, + 1122, 997, 998, -1, 999, 1123, 1000, -1, + 999, 1001, 1123, -1, 999, 1000, 1002, -1, + 999, 1002, 1001, -1, 1003, 1133, 1132, -1, + 1003, 1067, 1133, -1, 1003, 1066, 1067, -1, + 1003, 1007, 1066, -1, 1003, 1132, 1007, -1, + 1010, 1132, 1004, -1, 1010, 1004, 1005, -1, + 1010, 1005, 1008, -1, 1006, 1007, 1132, -1, + 1006, 1008, 1009, -1, 1006, 1010, 1008, -1, + 1006, 1132, 1010, -1, 1006, 1009, 1011, -1, + 1006, 1011, 1007, -1, 1125, 1012, 1013, -1, + 1125, 1013, 1127, -1, 1125, 1124, 1012, -1, + 1024, 1014, 1025, -1, 1024, 1016, 1014, -1, + 1015, 1017, 1016, -1, 1015, 1187, 1017, -1, + 1015, 1016, 1024, -1, 1015, 1024, 1187, -1, + 1186, 1137, 1187, -1, 1036, 1018, 1019, -1, + 1036, 1019, 1020, -1, 1036, 1144, 1143, -1, + 1036, 1143, 1018, -1, 1036, 1020, 1035, -1, + 1036, 1037, 1144, -1, 1142, 1021, 1022, -1, + 1142, 1022, 1140, -1, 1142, 1145, 1023, -1, + 1142, 1023, 1021, -1, 1188, 1024, 1025, -1, + 1188, 1187, 1024, -1, 1188, 1025, 1026, -1, + 1188, 1026, 1185, -1, 1216, 1217, 1153, -1, + 1195, 1172, 1194, -1, 1195, 1146, 1172, -1, + 1190, 1172, 1146, -1, 1190, 1171, 1172, -1, + 1190, 1189, 1027, -1, 1190, 1027, 1028, -1, + 1190, 1028, 1171, -1, 1152, 1151, 1150, -1, + 1220, 1043, 1151, -1, 1220, 1154, 1164, -1, + 1220, 1221, 1029, -1, 1220, 1029, 1199, -1, + 1201, 1159, 1030, -1, 1201, 1030, 1031, -1, + 1201, 1031, 1202, -1, 1032, 1033, 1034, -1, + 1032, 1035, 1033, -1, 1032, 1036, 1035, -1, + 1032, 1034, 1037, -1, 1032, 1037, 1036, -1, + 1038, 1040, 1039, -1, 1038, 1039, 1041, -1, + 1038, 1042, 1040, -1, 1038, 1041, 1042, -1, + 1161, 1162, 1043, -1, 1161, 1043, 1220, -1, + 1044, 1045, 1046, -1, 1044, 1047, 1048, -1, + 1044, 1049, 1045, -1, 1044, 1050, 1047, -1, + 1044, 1048, 1051, -1, 1044, 1051, 1049, -1, + 1044, 1052, 1050, -1, 1044, 1053, 1052, -1, + 1044, 1046, 1053, -1, 1054, 1056, 1055, -1, + 1054, 1057, 1056, -1, 1054, 1055, 1058, -1, + 1054, 1058, 1057, -1, 1059, 1061, 1060, -1, + 1059, 1060, 1062, -1, 1059, 1063, 1061, -1, + 1059, 1064, 1063, -1, 1059, 1062, 1064, -1, + 1065, 1067, 1066, -1, 1065, 1068, 1067, -1, + 1065, 1066, 1069, -1, 1065, 1070, 1068, -1, + 1065, 1069, 1070, -1, 1071, 1072, 1073, -1, + 1071, 1073, 1078, -1, 1071, 1074, 1072, -1, + 1071, 1078, 1074, -1, 1075, 1077, 1076, -1, + 1075, 1078, 1077, -1, 1075, 1076, 1079, -1, + 1075, 1079, 1080, -1, 1075, 1080, 1078, -1, + 1081, 1105, 1082, -1, 1081, 1082, 1083, -1, + 1081, 1084, 1105, -1, 1081, 1085, 1084, -1, + 1081, 1086, 1085, -1, 1081, 1083, 1086, -1, + 1087, 1089, 1088, -1, 1087, 1166, 1089, -1, + 1087, 1088, 1090, -1, 1087, 1090, 1091, -1, + 1087, 1091, 1166, -1, 1168, 1097, 1169, -1, + 1168, 1100, 1097, -1, 1168, 1092, 1100, -1, + 1168, 1166, 1092, -1, 1093, 1095, 1094, -1, + 1093, 1096, 1169, -1, 1093, 1094, 1096, -1, + 1093, 1169, 1097, -1, 1093, 1099, 1098, -1, + 1093, 1098, 1095, -1, 1093, 1100, 1099, -1, + 1093, 1097, 1100, -1, 1173, 1171, 1101, -1, + 1173, 1102, 1175, -1, 1173, 1101, 1102, -1, + 1103, 1105, 1104, -1, 1103, 1106, 1105, -1, + 1103, 1104, 1221, -1, 1103, 1221, 1174, -1, + 1103, 1174, 1106, -1, 1107, 1108, 1109, -1, + 1107, 1109, 1110, -1, 1107, 1110, 1108, -1, + 1111, 1113, 1112, -1, 1111, 1112, 1114, -1, + 1111, 1115, 1113, -1, 1111, 1114, 1115, -1, + 1179, 1116, 1178, -1, 1179, 1181, 1116, -1, + 1117, 1119, 1118, -1, 1117, 1118, 1120, -1, + 1117, 1121, 1119, -1, 1117, 1122, 1121, -1, + 1117, 1120, 1123, -1, 1117, 1123, 1122, -1, + 1209, 1183, 1124, -1, 1209, 1124, 1125, -1, + 1209, 1126, 1210, -1, 1209, 1125, 1127, -1, + 1209, 1128, 1126, -1, 1209, 1129, 1128, -1, + 1209, 1127, 1130, -1, 1209, 1131, 1129, -1, + 1209, 1132, 1133, -1, 1209, 1130, 1132, -1, + 1209, 1133, 1134, -1, 1209, 1134, 1131, -1, + 1135, 1138, 1136, -1, 1135, 1186, 1138, -1, + 1135, 1136, 1137, -1, 1135, 1137, 1186, -1, + 1191, 1185, 1189, -1, 1191, 1138, 1186, -1, + 1191, 1213, 1138, -1, 1139, 1140, 1141, -1, + 1139, 1142, 1140, -1, 1139, 1141, 1143, -1, + 1139, 1143, 1144, -1, 1139, 1144, 1145, -1, + 1139, 1145, 1142, -1, 1218, 1195, 1217, -1, + 1218, 1146, 1195, -1, 1218, 1190, 1146, -1, + 1147, 1148, 1214, -1, 1147, 1214, 1216, -1, + 1147, 1149, 1148, -1, 1147, 1150, 1149, -1, + 1147, 1152, 1150, -1, 1147, 1216, 1153, -1, + 1147, 1153, 1152, -1, 1193, 1220, 1151, -1, + 1193, 1151, 1152, -1, 1193, 1152, 1153, -1, + 1193, 1153, 1217, -1, 1193, 1217, 1195, -1, + 1197, 1155, 1154, -1, 1197, 1154, 1220, -1, + 1197, 1198, 1156, -1, 1197, 1157, 1155, -1, + 1197, 1156, 1157, -1, 1203, 1204, 1158, -1, + 1203, 1158, 1159, -1, 1203, 1159, 1201, -1, + 1160, 1162, 1161, -1, 1160, 1161, 1220, -1, + 1160, 1163, 1162, -1, 1160, 1164, 1163, -1, + 1160, 1220, 1164, -1, 1165, 1167, 1166, -1, + 1165, 1166, 1168, -1, 1165, 1169, 1167, -1, + 1165, 1168, 1169, -1, 1170, 1172, 1171, -1, + 1170, 1171, 1173, -1, 1170, 1194, 1172, -1, + 1170, 1223, 1194, -1, 1170, 1174, 1223, -1, + 1170, 1175, 1174, -1, 1170, 1173, 1175, -1, + 1176, 1178, 1177, -1, 1176, 1179, 1178, -1, + 1176, 1177, 1180, -1, 1176, 1180, 1181, -1, + 1176, 1181, 1179, -1, 1211, 1182, 1183, -1, + 1211, 1183, 1209, -1, 1211, 1207, 1182, -1, + 1184, 1185, 1191, -1, 1184, 1191, 1186, -1, + 1184, 1186, 1187, -1, 1184, 1187, 1188, -1, + 1184, 1188, 1185, -1, 1192, 1191, 1189, -1, + 1192, 1189, 1190, -1, 1192, 1190, 1218, -1, + 1215, 1213, 1191, -1, 1215, 1191, 1192, -1, + 1215, 1192, 1218, -1, 1222, 1220, 1193, -1, + 1222, 1194, 1223, -1, 1222, 1195, 1194, -1, + 1222, 1193, 1195, -1, 1196, 1198, 1197, -1, + 1196, 1197, 1220, -1, 1196, 1199, 1198, -1, + 1196, 1220, 1199, -1, 1200, 1201, 1202, -1, + 1200, 1203, 1201, -1, 1200, 1202, 1204, -1, + 1200, 1204, 1203, -1, 1205, 1206, 1207, -1, + 1205, 1207, 1211, -1, 1205, 1210, 1206, -1, + 1205, 1211, 1210, -1, 1208, 1209, 1210, -1, + 1208, 1210, 1211, -1, 1208, 1211, 1209, -1, + 1212, 1214, 1213, -1, 1212, 1213, 1215, -1, + 1212, 1216, 1214, -1, 1212, 1217, 1216, -1, + 1212, 1218, 1217, -1, 1212, 1215, 1218, -1, + 1219, 1221, 1220, -1, 1219, 1220, 1222, -1, + 1219, 1223, 1221, -1, 1219, 1222, 1223, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl new file mode 100644 index 0000000..4d54ff5 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/A2R3_T7_wristYaw.wrl @@ -0,0 +1,890 @@ +#VRML V2.0 utf8 + + +DEF solid_A2R3_T7_wristYaw__________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -20 -45.5 -4.7230601, + -20 -45.5 17.8153, + -20 -42.613098 22.3468, + -20 -43.316601 21.946501, + -20 -45.434502 18.622101, + 5.0757098 19.6036 18.3351, + 7.6999202 -45.5 -14.4439, + 5.5142798 -45.5 -16.629601, + 20 -45.434502 18.622101, + 20 -44.920601 20.1516, + -20 -44.920601 20.1516, + -20 -45.239601 19.4077, + 20 -45.239601 19.4077, + 20 -43.946301 21.437901, + -20 -43.946301 21.437901, + 20 -43.316601 21.946501, + 20 -44.485699 20.834299, + -20 -44.485699 20.834299, + 8.9179802 18.1805 18.3351, + 7.0329299 18.9895 18.3351, + 10.7115 17.184999 18.3351, + -11.1936 -45.5 14.0546, + -1.91514 -45.5 17.8153, + -5 -45.5 8.6603498, + -17.958799 -45.5 2.15378, + -20 -45.5 10.7453, + -16.906099 -45.5 0.65027398, + 20 -43.316601 -21.946301, + -20 -43.316601 -21.946301, + 20 -45.5 -17.8151, + -20 -45.5 -17.8151, + -20 -45.434502 -18.621901, + -7.0329299 18.9895 18.3351, + -5.0757098 19.6036 18.3351, + 7.4409399 -3.7327299 -34.0425, + 0.75244403 8.1826801 -34.0425, + 16.5116 2.81569 -31.342501, + 18.201 3.3123801 -29.2925, + -7.5128002 -24.351801 -30.779699, + -6 -24.3554 -30.7904, + 16.142099 4.4717002 -31.342501, + 8.49473 -7.2915802 -34.0425, + -1.90526 9.1499996 -34.0425, + -1.59604 11.4553 -34.0425, + -5.0797801 17.7889 -29.2925, + 6.3445501 15.5019 -31.342501, + 7.4967999 16.913 -29.2925, + 5.3218398 13.0031 -34.0425, + -12.3951 16.013201 18.3351, + -10.7115 17.184999 18.3351, + -8.9179802 18.1805 18.3351, + -7.49681 16.913 -29.2925, + 3.0664101 20.0165 18.3351, + 13.9516 14.6771 18.3351, + 12.3951 16.013201 18.3351, + 15.3649 13.1903 18.3351, + 13.9516 14.6771 21.8351, + 15.3649 13.1903 21.8351, + 9.7690601 15.7104 -29.2925, + 7.8803 14.7805 -31.342501, + 6.6100402 12.398 -34.0425, + 16.7118 1.13079 -31.342501, + 13.8501 2.36182 -34.0425, + 16.7404 -0.56571603 -31.342501, + 10.3454 -9.5066099 -34.0425, + 8.2199402 -11.3945 -34.0425, + 20 -45.5 17.8153, + 20 -45.5 14.6404, + 18.929399 -45.5 10.7453, + 20 -45.5 10.7453, + 18.929399 -45.5 17.8153, + 11.2702 -45.5 14.1189, + 20 -45.5 6.8769398, + -8.5673504 -45.5 13.3509, + 17.323 -45.5 1.00472, + 20 -45.5 -11.8219, + 20 -44.485699 -20.834101, + 20 -43.946301 -21.4377, + -20 -44.485699 -20.834101, + -20 -43.946301 -21.4377, + 20 -45.239601 -19.407499, + 20 -44.920601 -20.1514, + 20 -45.434502 -18.621901, + -20 -45.239601 -19.407499, + -20 -44.920601 -20.1514, + -20.25 -9.2539642e-007 21.8351, + -19.321301 6.0620999 21.8351, + -19.321301 6.0620999 18.3351, + -18.6089 7.9857101 21.8351, + -19.9632 -42.187698 22.5452, + 20.146099 2.04866 18.3351, + 19.835501 4.0762901 18.3351, + 19.321301 6.0620999 18.3351, + 10.7115 17.184999 21.8351, + 12.3951 16.013201 21.8351, + 3.0664101 20.0165 21.8351, + -8.1679201 -3.2548299 -34.0425, + -8.3702402 -4.5711298 -34.0425, + -8.49473 -7.2915802 -34.0425, + 1.65729 -13.9519 -34.0425, + 0.237298 -14.048 -34.0425, + -13.9516 14.6771 18.3351, + -5.3218398 -13.0031 -34.0425, + -20 -42.613098 -22.3466, + 12.5079 6.3997002 -34.0425, + 13.5401 3.75089 -34.0425, + 13.0911 5.10147 -34.0425, + -18.6089 7.9857101 18.3351, + -5.7579799 12.8159 -34.0425, + -6.86449 15.2788 -31.342501, + -15.2974 10.4039 -29.2925, + -16.5919 8.1827602 -29.2925, + -5.2835398 15.8949 -31.342501, + -4.43187 13.3327 -34.0425, + 2.5646501 18.3214 -29.2925, + 5.0797801 17.7889 -29.2925, + 4.74369 16.064199 -31.342501, + -3.64838 16.347799 -31.342501, + -9.7690601 15.7104 -29.2925, + -8.375 14.5059 -31.342501, + -11.8527 14.2044 -29.2925, + -1.02564 20.224001 18.3351, + 1.02565 20.224001 21.8351, + -1.02564 20.224001 21.8351, + 1.02565 20.224001 18.3351, + -3.0664101 20.0165 21.8351, + -3.0664101 20.0165 18.3351, + -2.5646501 18.3214 -29.2925, + 16.5919 8.1827602 -29.2925, + 15.2974 10.4039 -29.2925, + 14.9115 7.62954 -31.342501, + 15.6069 6.08182 -31.342501, + 17.566099 5.8036098 -29.2925, + 18.6089 7.9857101 18.3351, + 13.7074 12.4241 -29.2925, + 10.9636 8.7865105 -34.0425, + 11.7962 7.6322699 -34.0425, + 14.0631 9.0989599 -31.342501, + 13.0704 10.475 -31.342501, + 12.0473 -7.2294998 -34.0425, + 9 -26.8146 -29.7136, + 7.81215 -25.1703 -30.480301, + 14.042 -0.47452801 -34.0425, + 14.0179 0.94850999 -34.0425, + 11.0768 -5.125 -34.0425, + 10.2909 -6.8102999 -34.0425, + 3.0602801 -13.7127 -34.0425, + -19.835501 4.0762901 21.8351, + -20.146099 2.04866 21.8351, + -18.201 3.3123801 29.2927, + -17.566099 5.8036098 29.2927, + -12.3951 16.013201 21.8351, + -10.7115 17.184999 21.8351, + -8.9179802 18.1805 21.8351, + -14.2148 8.8601503 31.342699, + -11.9235 7.4319501 34.042702, + -15.0382 7.3765998 31.342699, + -16.5919 8.1827602 29.2927, + -13.9516 14.6771 21.8351, + -15.3649 13.1903 18.3351, + -19.7556 -41.628899 22.805799, + -18.410999 -1.81262 29.2927, + -18.484501 0.75718999 29.2927, + -13.888 -2.1275599 34.042702, + -13.1754 -4.8796401 34.042702, + -14.032 -0.71162099 34.042702, + -13.6015 -3.5216701 34.042702, + -16.556801 -2.5364201 31.342699, + -16.7285 -0.84837198 31.342699, + 16.620501 11.5682 21.8351, + 17.7055 9.8273602 18.3351, + 16.620501 11.5682 18.3351, + 8.9179802 18.1805 21.8351, + 3.0619077e-007 18.5 29.2927, + 3.07432e-007 16.75 31.342699, + -10.7964 -5.6863699 -34.0425, + -10.9441 -5.87744 -34.0425, + -13.0911 -5.10147 -34.0425, + -13.5401 -3.75089 -34.0425, + -13.7074 12.4241 -29.2925, + -2.5954001 -13.8082 -34.0425, + -1.18513 -13.9999 -34.0425, + -3.9790399 -13.4748 -34.0425, + -7.83041 -11.6656 -34.0425, + -7.4393501 -24.129999 -30.8531, + -6.6100402 -12.398 -34.0425, + 19.6868 -41.495098 -22.868, + 19.7556 -41.628899 -22.805599, + 16.5973 -2.2564199 -31.342501, + 13.9219 -1.8926899 -34.0425, + 13.659 -3.29144 -34.0425, + 13.256 -4.6564202 -34.0425, + 12.7169 -5.9736099 -34.0425, + 5.51545 -29.9804 -28.2374, + -13.659 3.29144 -34.0425, + -15.8034 5.55124 -31.342501, + -11.1236 12.5231 -31.342501, + -12.3335 11.3335 -31.342501, + -10.3454 9.5066099 -34.0425, + -12.0473 7.2294998 -34.0425, + -13.4168 10.0276 -31.342501, + -14.3624 8.6188002 -31.342501, + -13.256 4.6564202 -34.0425, + -12.7169 5.9736099 -34.0425, + -15.1607 7.1215601 -31.342501, + 2.5954001 13.8082 -34.0425, + 3.0941601 16.4617 -31.342501, + 1.18513 13.9999 -34.0425, + 3.9790399 13.4748 -34.0425, + -0.28289801 16.747601 -31.342501, + 1.4128799 16.6903 -31.342501, + 3.0781251e-007 18.5 -29.2925, + -1.65729 13.9519 -34.0425, + -3.0602801 13.7127 -34.0425, + -0.237297 14.048 -34.0425, + -1.97577 16.633101 -31.342501, + 10.6943 12.8917 -31.342501, + 8.9704304 10.8136 -34.0425, + 10.0184 9.8505898 -34.0425, + 11.9436 11.7436 -31.342501, + 7.83041 11.6656 -34.0425, + 9.3351803 13.9074 -31.342501, + 11.8527 14.2044 -29.2925, + 5.7579799 -12.8159 -34.0425, + 9.3305302 -10.5045 -34.0425, + 11.2541 -8.4112101 -34.0425, + 4.43187 -13.3327 -34.0425, + 7.0250001 -12.1677 -34.0425, + 7.51267 -24.3904 -30.7798, + -11.7962 -7.6322598 -34.0425, + -12.5079 -6.3997002 -34.0425, + -13.9219 1.8927 -34.0425, + -18.201 3.3123801 -29.2925, + -16.283899 3.92396 -31.342501, + -17.566099 5.8036098 -29.2925, + -20.146099 2.04866 18.3351, + -19.835501 4.0762901 18.3351, + -14.032 0.71162301 34.042702, + -16.7285 0.84837401 31.342699, + -16.556801 2.5364201 31.342699, + -13.1754 4.8796401 34.042702, + -15.7073 5.8173599 31.342699, + -12.6142 6.1875401 34.042702, + -13.888 2.1275599 34.042702, + -13.6015 3.5216701 34.042702, + -16.2153 4.1984301 31.342699, + -5.0797801 17.7889 29.2927, + -2.5646501 18.3214 29.2927, + -3.3717501 16.407101 31.342699, + -5.0757098 19.6036 21.8351, + -7.0329299 18.9895 21.8351, + -9.7690601 15.7104 29.2927, + -7.49681 16.913 29.2927, + -12.1403 11.5402 31.342699, + -10.1833 9.6799803 34.042702, + -10.9105 12.7092 31.342699, + -11.1104 8.60009 34.042702, + -13.2455 10.2528 31.342699, + -13.7074 12.4241 29.2927, + -11.8527 14.2044 29.2927, + -4.2060499 13.4057 34.042702, + -5.0143299 15.9818 31.342699, + -6.6054602 15.3925 31.342699, + -8.1288099 14.6453 31.342699, + -8.0263205 11.5317 34.042702, + -9.5687399 13.7478 31.342699, + -9.1517801 10.6606 34.042702, + -6.81849 12.2846 34.042702, + -5.5407 12.9114 34.042702, + -16.620501 11.5682 21.8351, + -15.2974 10.4039 29.2927, + -17.7055 9.8273602 21.8351, + -15.3649 13.1903 21.8351, + -16.620501 11.5682 18.3351, + -17.7055 9.8273602 18.3351, + -11.9235 -7.4319401 34.042702, + -19.6868 -41.495098 22.8682, + -12.6142 -6.1875401 34.042702, + -9.4092503 -4.5960398 34.042702, + -0.275666 1.56338 34.042702, + 20.146099 2.04866 21.8351, + 7.0329299 18.9895 21.8351, + 5.0757098 19.6036 21.8351, + -1.42141 13.9779 34.042702, + -1.6945699 16.664101 31.342699, + -2.8282399 13.7624 34.042702, + -11.2302 -35.662701 -25.5877, + -10.331 -34.8969 -25.944799, + 20 -42.613098 -22.3466, + 20.25 -9.2385847e-007 18.3351, + -9.0785303 -32.314899 -27.1488, + -19.7997 -41.6973 -22.773701, + -20.25 -9.2439001e-007 18.3351, + -10.0184 -9.8506002 -34.0425, + -10.9636 -8.7865105 -34.0425, + -8.9704304 -10.8136 -34.0425, + -8.2199402 11.3945 -34.0425, + -7.0250001 12.1677 -34.0425, + -11.2541 8.4112101 -34.0425, + -9.3305302 10.5045 -34.0425, + -9.7995701 13.5842 -31.342501, + -14.0179 -0.94851202 -34.0425, + -13.8501 -2.36182 -34.0425, + -16.5116 -2.81569 -31.342501, + -11.2302 -35.662701 25.5879, + -9.6050596 -33.853802 26.4314, + -9 -26.8146 29.7138, + -10.1833 -9.6799898 34.042702, + -11.1104 -8.60009 34.042702, + -7.5128002 -24.351801 30.7799, + -7.6950798 -24.9023 30.597601, + 19.321301 6.0620999 21.8351, + 19.835501 4.0762901 21.8351, + 11.8527 14.2044 29.2927, + 9.7690601 15.7104 29.2927, + 10.9105 12.7092 31.342699, + 20 -42.569599 -22.366899, + 8.3991604 -26.149 -30.024, + -7.81215 -25.1703 -30.480301, + -19.6106 -41.383801 -22.9198, + -19.582701 -41.3522 -22.934601, + -9 -26.8146 -29.7136, + -7.6950798 -24.9023 -30.597401, + -8.1832104 -25.807501 -30.183201, + 6 -25.1703 -30.480301, + 7.8789501 -25.3085 -30.415899, + -19.964199 -42.244701 -22.5184, + -19.9312 -42.049599 -22.6094, + -20 -42.569599 -22.366899, + -19.9949 -42.426701 -22.4335, + -18.410999 -1.81262 -29.2925, + -16.7404 0.565718 -31.342501, + -14.042 0.474527 -34.0425, + -16.5973 2.2564199 -31.342501, + -16.7118 -1.13079 -31.342501, + -18.484501 0.75718999 -29.2925, + 20 -42.613098 22.3468, + 20.25 -9.2357379e-007 21.8351, + 19.9949 -42.426701 22.433701, + -19.968599 -42.243698 22.5191, + -20 -42.569599 22.3671, + 11.1104 -8.60009 34.042702, + 18.410999 -1.81262 29.2927, + 19.964199 -42.244701 22.5186, + -10.8553 -4.83252 34.042702, + -1.42141 -13.9779 34.042702, + -2.8282399 -13.7624 34.042702, + 10.1833 9.6799803 34.042702, + 19.9632 -42.187698 -22.545, + 19.8559 -41.824299 -22.7145, + 18.410999 -1.81262 -29.2925, + 19.968599 -42.243698 -22.5189, + 18.484501 0.75718999 -29.2925, + 3.0564783e-007 -14.05 34.042702, + 10.1833 -9.6799898 34.042702, + 18.201 3.3123801 29.2927, + 18.484501 0.75718999 29.2927, + 9.6024599 -5.3165698 34.042702, + 14.032 0.71162301 34.042702, + -1.81954 11.0802 34.042702, + 13.6015 3.5216701 34.042702, + 16.556801 2.5364201 31.342699, + 16.7285 0.84837401 31.342699, + 11.1104 8.60009 34.042702, + 12.1403 11.5402 31.342699, + 13.7074 12.4241 29.2927, + 14.032 -0.71162099 34.042702, + 16.556801 -2.5364201 31.342699, + 16.7285 -0.84837198 31.342699, + 13.1754 -4.8796401 34.042702, + 12.6142 -6.1875401 34.042702, + 13.6015 -3.5216701 34.042702, + 11.9235 -7.4319401 34.042702, + 19.6106 -41.383801 22.92, + 13.888 -2.1275599 34.042702, + 19.9312 -42.049599 22.6096, + 20 -42.569599 22.3671, + 19.582701 -41.3522 22.934799, + 19.7997 -41.6973 22.773899, + -5.5407 -12.9114 34.042702, + -8.0263205 -11.5317 34.042702, + -9.1517801 -10.6606 34.042702, + -7.4393501 -24.129999 30.8533, + -6.81849 -12.2846 34.042702, + 7.4967999 16.913 29.2927, + 5.0797801 17.7889 29.2927, + 2.5646501 18.3214 29.2927, + 3.0709478e-007 14.05 34.042702, + 2.8282399 -13.7624 34.042702, + 6.81849 -12.2846 34.042702, + 9.1517801 -10.6606 34.042702, + 8.0263205 -11.5317 34.042702, + 5.5407 -12.9114 34.042702, + 7.51267 -24.3904 30.780001, + 4.2060499 -13.4057 34.042702, + 1.42141 -13.9779 34.042702, + -4.2060499 -13.4057 34.042702, + 13.888 2.1275599 34.042702, + 16.2153 4.1984301 31.342699, + 13.1754 4.8796401 34.042702, + 17.7055 9.8273602 21.8351, + 15.7073 5.8173599 31.342699, + 17.566099 5.8036098 29.2927, + 18.6089 7.9857101 21.8351, + 14.2148 8.8601503 31.342699, + 13.2455 10.2528 31.342699, + 11.9235 7.4319501 34.042702, + 12.6142 6.1875401 34.042702, + 15.0382 7.3765998 31.342699, + 15.2974 10.4039 29.2927, + 16.5919 8.1827602 29.2927, + 10.331 -34.8969 25.945, + -19.8559 -41.824299 22.714701, + 11.2302 -35.662701 25.5879, + 7.8789501 -25.3085 30.4161, + 9 -26.8146 29.7138, + 7.81215 -25.1703 30.480499, + 8.5836802 -26.353399 29.9289, + -7.81215 -25.1703 30.480499, + -8.1832104 -25.807501 30.183399, + 6.6054602 15.3925 31.342699, + 8.1288099 14.6453 31.342699, + 9.5687399 13.7478 31.342699, + 8.0263205 11.5317 34.042702, + 9.1517801 10.6606 34.042702, + 5.0143299 15.9818 31.342699, + 2.8282399 13.7624 34.042702, + 4.2060499 13.4057 34.042702, + 3.3717501 16.407101 31.342699, + 1.6945699 16.664101 31.342699, + 1.42141 13.9779 34.042702, + 5.5407 12.9114 34.042702, + 6.81849 12.2846 34.042702 ] + + } + coordIndex [ 85, 339, 89, -1, 85, 340, 339, -1, + 85, 1, 4, -1, 22, 8, 4, -1, + 22, 4, 1, -1, 25, 85, 292, -1, + 25, 1, 85, -1, 15, 337, 336, -1, + 3, 15, 336, -1, 10, 17, 85, -1, + 107, 234, 87, -1, 236, 87, 234, -1, + 281, 172, 19, -1, 281, 5, 282, -1, + 281, 19, 5, -1, 37, 90, 352, -1, + 66, 337, 8, -1, 289, 337, 29, -1, + 289, 90, 337, -1, 289, 352, 90, -1, + 0, 292, 30, -1, 0, 25, 292, -1, + 0, 30, 25, -1, 21, 22, 1, -1, + 21, 1, 25, -1, 162, 85, 89, -1, + 2, 340, 85, -1, 2, 85, 3, -1, + 2, 336, 340, -1, 2, 3, 336, -1, + 14, 85, 17, -1, 14, 3, 85, -1, + 14, 15, 3, -1, 11, 85, 4, -1, + 11, 10, 85, -1, 11, 4, 8, -1, + 276, 418, 310, -1, 64, 186, 228, -1, + 39, 228, 322, -1, 115, 114, 5, -1, + 115, 19, 46, -1, 115, 5, 19, -1, + 52, 5, 114, -1, 52, 282, 5, -1, + 52, 95, 282, -1, 52, 122, 95, -1, + 91, 132, 92, -1, 91, 37, 132, -1, + 91, 90, 37, -1, 79, 78, 292, -1, + 7, 30, 29, -1, 7, 6, 30, -1, + 26, 30, 6, -1, 26, 74, 23, -1, + 75, 29, 337, -1, 75, 74, 26, -1, + 75, 26, 6, -1, 75, 7, 29, -1, + 75, 6, 7, -1, 70, 8, 22, -1, + 70, 66, 8, -1, 70, 22, 71, -1, + 31, 30, 292, -1, 31, 292, 83, -1, + 84, 292, 78, -1, 84, 83, 292, -1, + 12, 11, 8, -1, 12, 8, 337, -1, + 9, 17, 10, -1, 9, 16, 17, -1, + 9, 10, 11, -1, 9, 11, 12, -1, + 9, 337, 16, -1, 9, 12, 337, -1, + 13, 15, 14, -1, 13, 337, 15, -1, + 13, 16, 337, -1, 13, 17, 16, -1, + 13, 14, 17, -1, 33, 127, 44, -1, + 249, 33, 250, -1, 249, 125, 33, -1, + 153, 49, 152, -1, 153, 50, 49, -1, + 48, 152, 49, -1, 48, 120, 101, -1, + 158, 48, 101, -1, 350, 63, 352, -1, + 61, 37, 352, -1, 61, 352, 63, -1, + 40, 132, 37, -1, 40, 131, 132, -1, + 47, 220, 208, -1, 47, 60, 220, -1, + 144, 34, 35, -1, 144, 35, 220, -1, + 144, 97, 34, -1, 202, 42, 35, -1, + 214, 208, 220, -1, 214, 220, 35, -1, + 214, 35, 42, -1, 214, 42, 43, -1, + 51, 44, 112, -1, 133, 92, 132, -1, + 58, 59, 46, -1, 58, 20, 54, -1, + 55, 57, 169, -1, 55, 169, 171, -1, + 222, 58, 54, -1, 18, 19, 172, -1, + 18, 172, 20, -1, 18, 46, 19, -1, + 18, 58, 46, -1, 18, 20, 58, -1, + 93, 54, 20, -1, 93, 94, 54, -1, + 93, 20, 172, -1, 142, 61, 63, -1, + 225, 186, 64, -1, 288, 289, 27, -1, + 28, 288, 27, -1, 28, 103, 288, -1, + 28, 79, 292, -1, 28, 292, 103, -1, + 73, 22, 21, -1, 73, 71, 22, -1, + 73, 21, 25, -1, 73, 23, 74, -1, + 73, 25, 26, -1, 73, 26, 23, -1, + 24, 25, 30, -1, 24, 30, 26, -1, + 24, 26, 25, -1, 77, 27, 289, -1, + 77, 28, 27, -1, 77, 79, 28, -1, + 82, 289, 29, -1, 82, 29, 30, -1, + 82, 30, 31, -1, 82, 31, 83, -1, + 147, 236, 235, -1, 32, 250, 33, -1, + 32, 153, 250, -1, 32, 50, 153, -1, + 32, 51, 50, -1, 32, 33, 44, -1, + 32, 44, 51, -1, 126, 33, 125, -1, + 126, 127, 33, -1, 88, 274, 107, -1, + 88, 271, 274, -1, 88, 157, 271, -1, + 151, 158, 259, -1, 151, 152, 48, -1, + 151, 48, 158, -1, 258, 259, 158, -1, + 306, 418, 276, -1, 312, 91, 92, -1, + 312, 92, 311, -1, 307, 308, 276, -1, + 307, 276, 310, -1, 252, 250, 153, -1, + 409, 169, 57, -1, 409, 57, 365, -1, + 173, 122, 123, -1, 65, 228, 227, -1, + 98, 144, 181, -1, 98, 97, 144, -1, + 96, 35, 34, -1, 96, 34, 97, -1, + 96, 202, 35, -1, 100, 228, 39, -1, + 100, 184, 181, -1, 100, 39, 184, -1, + 36, 61, 62, -1, 36, 62, 40, -1, + 36, 37, 61, -1, 36, 40, 37, -1, + 110, 274, 273, -1, 38, 39, 322, -1, + 38, 184, 39, -1, 38, 322, 295, -1, + 38, 295, 184, -1, 102, 176, 181, -1, + 141, 228, 186, -1, 141, 322, 228, -1, + 141, 324, 322, -1, 105, 40, 62, -1, + 105, 106, 131, -1, 105, 131, 40, -1, + 41, 146, 181, -1, 41, 181, 144, -1, + 41, 144, 146, -1, 298, 43, 42, -1, + 298, 42, 202, -1, 298, 214, 43, -1, + 117, 44, 127, -1, 117, 112, 44, -1, + 210, 211, 114, -1, 45, 115, 46, -1, + 45, 116, 115, -1, 45, 46, 59, -1, + 45, 59, 60, -1, 45, 60, 47, -1, + 45, 47, 208, -1, 45, 208, 116, -1, + 118, 51, 119, -1, 118, 48, 49, -1, + 118, 120, 48, -1, 118, 49, 50, -1, + 118, 50, 51, -1, 109, 119, 51, -1, + 109, 51, 112, -1, 109, 112, 113, -1, + 159, 110, 273, -1, 159, 158, 101, -1, + 124, 52, 114, -1, 124, 114, 211, -1, + 124, 122, 52, -1, 129, 171, 170, -1, + 129, 134, 55, -1, 129, 55, 171, -1, + 138, 134, 129, -1, 138, 129, 137, -1, + 56, 94, 313, -1, 56, 365, 57, -1, + 56, 313, 365, -1, 53, 222, 54, -1, + 53, 55, 134, -1, 53, 134, 222, -1, + 53, 54, 94, -1, 53, 94, 56, -1, + 53, 57, 55, -1, 53, 56, 57, -1, + 217, 218, 220, -1, 221, 59, 58, -1, + 221, 58, 222, -1, 221, 60, 59, -1, + 221, 220, 60, -1, 143, 62, 61, -1, + 143, 61, 142, -1, 143, 105, 62, -1, + 143, 218, 105, -1, 143, 220, 218, -1, + 188, 142, 63, -1, 188, 63, 350, -1, + 224, 225, 64, -1, 224, 65, 227, -1, + 224, 64, 228, -1, 224, 228, 65, -1, + 145, 146, 144, -1, 325, 324, 141, -1, + 187, 186, 192, -1, 294, 177, 176, -1, + 67, 66, 70, -1, 67, 70, 69, -1, + 67, 337, 66, -1, 67, 75, 337, -1, + 72, 75, 67, -1, 72, 67, 69, -1, + 68, 69, 70, -1, 68, 70, 71, -1, + 68, 72, 69, -1, 68, 73, 74, -1, + 68, 71, 73, -1, 68, 74, 75, -1, + 68, 75, 72, -1, 76, 289, 81, -1, + 76, 77, 289, -1, 76, 84, 78, -1, + 76, 81, 84, -1, 76, 78, 79, -1, + 76, 79, 77, -1, 80, 81, 289, -1, + 80, 289, 82, -1, 80, 82, 83, -1, + 80, 83, 84, -1, 80, 84, 81, -1, + 148, 85, 162, -1, 148, 147, 235, -1, + 148, 292, 85, -1, 148, 235, 292, -1, + 150, 157, 88, -1, 242, 237, 344, -1, + 242, 344, 266, -1, 161, 162, 89, -1, + 86, 107, 87, -1, 86, 88, 107, -1, + 86, 87, 236, -1, 86, 236, 147, -1, + 86, 147, 150, -1, 86, 150, 88, -1, + 270, 257, 258, -1, 270, 271, 157, -1, + 164, 308, 344, -1, 164, 344, 237, -1, + 412, 306, 276, -1, 412, 304, 305, -1, + 412, 305, 306, -1, 412, 89, 339, -1, + 412, 276, 160, -1, 412, 161, 89, -1, + 412, 167, 161, -1, 412, 164, 166, -1, + 419, 418, 306, -1, 280, 337, 90, -1, + 280, 90, 91, -1, 280, 91, 312, -1, + 359, 387, 266, -1, 359, 266, 344, -1, + 393, 382, 309, -1, 393, 309, 310, -1, + 403, 133, 170, -1, 403, 311, 92, -1, + 403, 92, 133, -1, 314, 94, 93, -1, + 314, 313, 94, -1, 314, 93, 172, -1, + 284, 387, 174, -1, 284, 174, 173, -1, + 247, 248, 284, -1, 247, 284, 173, -1, + 247, 125, 249, -1, 247, 123, 125, -1, + 247, 173, 123, -1, 386, 95, 122, -1, + 386, 122, 173, -1, 386, 282, 95, -1, + 175, 202, 96, -1, 175, 96, 97, -1, + 175, 97, 98, -1, 175, 181, 176, -1, + 175, 98, 181, -1, 99, 181, 146, -1, + 99, 100, 181, -1, 99, 146, 228, -1, + 99, 228, 100, -1, 179, 200, 110, -1, + 179, 120, 196, -1, 179, 110, 159, -1, + 179, 101, 120, -1, 179, 159, 101, -1, + 108, 109, 113, -1, 182, 102, 181, -1, + 182, 184, 102, -1, 185, 102, 184, -1, + 185, 295, 294, -1, 185, 176, 102, -1, + 185, 294, 176, -1, 328, 288, 103, -1, + 328, 103, 292, -1, 104, 106, 105, -1, + 104, 105, 218, -1, 104, 218, 136, -1, + 104, 136, 137, -1, 104, 137, 130, -1, + 104, 131, 106, -1, 104, 130, 131, -1, + 195, 234, 204, -1, 195, 204, 202, -1, + 111, 204, 234, -1, 111, 274, 110, -1, + 111, 234, 107, -1, 111, 107, 274, -1, + 297, 113, 214, -1, 297, 214, 298, -1, + 297, 108, 113, -1, 297, 119, 109, -1, + 297, 109, 108, -1, 201, 110, 200, -1, + 201, 111, 110, -1, 201, 204, 111, -1, + 203, 202, 204, -1, 213, 113, 112, -1, + 213, 112, 117, -1, 213, 214, 113, -1, + 206, 210, 114, -1, 206, 114, 115, -1, + 206, 115, 116, -1, 206, 116, 208, -1, + 207, 208, 214, -1, 207, 214, 210, -1, + 215, 127, 211, -1, 215, 117, 127, -1, + 215, 213, 117, -1, 300, 118, 119, -1, + 300, 119, 297, -1, 300, 196, 120, -1, + 300, 120, 118, -1, 121, 123, 122, -1, + 121, 122, 124, -1, 121, 125, 123, -1, + 121, 126, 125, -1, 121, 124, 211, -1, + 121, 211, 127, -1, 121, 127, 126, -1, + 128, 137, 129, -1, 128, 130, 137, -1, + 128, 132, 131, -1, 128, 131, 130, -1, + 128, 129, 170, -1, 128, 133, 132, -1, + 128, 170, 133, -1, 219, 222, 134, -1, + 219, 134, 138, -1, 135, 136, 218, -1, + 135, 137, 136, -1, 135, 138, 137, -1, + 135, 218, 219, -1, 135, 219, 138, -1, + 189, 142, 188, -1, 139, 186, 225, -1, + 139, 192, 186, -1, 139, 225, 192, -1, + 226, 146, 225, -1, 226, 228, 146, -1, + 140, 141, 186, -1, 140, 325, 141, -1, + 140, 186, 317, -1, 140, 317, 325, -1, + 191, 189, 190, -1, 191, 142, 189, -1, + 191, 143, 142, -1, 191, 144, 220, -1, + 191, 220, 143, -1, 191, 192, 225, -1, + 191, 145, 144, -1, 191, 225, 146, -1, + 191, 146, 145, -1, 230, 291, 177, -1, + 230, 177, 294, -1, 231, 194, 202, -1, + 231, 202, 301, -1, 178, 177, 291, -1, + 335, 292, 235, -1, 149, 245, 150, -1, + 149, 150, 147, -1, 149, 148, 162, -1, + 149, 147, 148, -1, 239, 245, 149, -1, + 239, 162, 238, -1, 239, 149, 162, -1, + 241, 157, 150, -1, 241, 156, 157, -1, + 241, 150, 245, -1, 241, 242, 156, -1, + 256, 266, 254, -1, 256, 242, 266, -1, + 155, 256, 257, -1, 155, 242, 256, -1, + 261, 260, 248, -1, 261, 252, 262, -1, + 251, 259, 265, -1, 251, 152, 151, -1, + 251, 151, 259, -1, 251, 153, 152, -1, + 251, 252, 153, -1, 255, 265, 259, -1, + 255, 266, 265, -1, 154, 257, 270, -1, + 154, 155, 257, -1, 154, 157, 156, -1, + 154, 270, 157, -1, 154, 156, 242, -1, + 154, 242, 155, -1, 272, 258, 158, -1, + 272, 270, 258, -1, 272, 159, 273, -1, + 272, 158, 159, -1, 277, 308, 164, -1, + 277, 160, 276, -1, 277, 412, 160, -1, + 277, 164, 412, -1, 168, 161, 167, -1, + 168, 237, 238, -1, 168, 165, 237, -1, + 168, 238, 162, -1, 168, 162, 161, -1, + 163, 164, 237, -1, 163, 237, 165, -1, + 163, 166, 164, -1, 163, 412, 166, -1, + 163, 167, 412, -1, 163, 168, 167, -1, + 163, 165, 168, -1, 278, 279, 359, -1, + 278, 359, 344, -1, 353, 382, 393, -1, + 356, 337, 280, -1, 357, 359, 279, -1, + 400, 169, 409, -1, 400, 403, 170, -1, + 400, 171, 169, -1, 400, 170, 171, -1, + 384, 172, 281, -1, 384, 314, 172, -1, + 285, 248, 260, -1, 285, 284, 248, -1, + 285, 266, 387, -1, 429, 173, 174, -1, + 429, 386, 173, -1, 429, 174, 387, -1, + 302, 301, 202, -1, 302, 202, 175, -1, + 302, 175, 176, -1, 302, 176, 177, -1, + 302, 177, 178, -1, 302, 178, 291, -1, + 197, 200, 179, -1, 197, 179, 196, -1, + 197, 298, 200, -1, 197, 198, 298, -1, + 180, 181, 184, -1, 180, 182, 181, -1, + 180, 184, 182, -1, 183, 184, 295, -1, + 183, 295, 185, -1, 183, 185, 184, -1, + 349, 328, 291, -1, 349, 287, 193, -1, + 349, 317, 186, -1, 349, 193, 317, -1, + 349, 186, 187, -1, 349, 188, 350, -1, + 349, 189, 188, -1, 349, 190, 189, -1, + 349, 191, 190, -1, 349, 187, 192, -1, + 349, 192, 191, -1, 290, 317, 193, -1, + 290, 193, 287, -1, 327, 291, 328, -1, + 327, 302, 291, -1, 327, 303, 302, -1, + 319, 320, 291, -1, 233, 194, 231, -1, + 233, 231, 333, -1, 233, 202, 194, -1, + 233, 195, 202, -1, 233, 234, 195, -1, + 299, 196, 300, -1, 299, 197, 196, -1, + 299, 198, 197, -1, 299, 298, 198, -1, + 199, 200, 298, -1, 199, 201, 200, -1, + 199, 298, 202, -1, 199, 202, 203, -1, + 199, 204, 201, -1, 199, 203, 204, -1, + 205, 210, 206, -1, 205, 207, 210, -1, + 205, 206, 208, -1, 205, 208, 207, -1, + 209, 211, 210, -1, 209, 215, 211, -1, + 209, 210, 214, -1, 209, 214, 215, -1, + 212, 214, 213, -1, 212, 215, 214, -1, + 212, 213, 215, -1, 216, 218, 217, -1, + 216, 219, 218, -1, 216, 217, 220, -1, + 216, 220, 221, -1, 216, 221, 222, -1, + 216, 222, 219, -1, 223, 225, 224, -1, + 223, 226, 225, -1, 223, 224, 227, -1, + 223, 227, 228, -1, 223, 228, 226, -1, + 229, 291, 230, -1, 229, 230, 294, -1, + 229, 319, 291, -1, 229, 294, 319, -1, + 332, 231, 301, -1, 332, 333, 231, -1, + 232, 333, 335, -1, 232, 234, 233, -1, + 232, 233, 333, -1, 232, 335, 235, -1, + 232, 236, 234, -1, 232, 235, 236, -1, + 243, 237, 242, -1, 243, 238, 237, -1, + 243, 239, 238, -1, 243, 245, 239, -1, + 243, 244, 245, -1, 240, 242, 241, -1, + 240, 243, 242, -1, 240, 244, 243, -1, + 240, 241, 245, -1, 240, 245, 244, -1, + 246, 248, 247, -1, 246, 261, 248, -1, + 246, 252, 261, -1, 246, 247, 249, -1, + 246, 249, 250, -1, 246, 250, 252, -1, + 263, 251, 265, -1, 263, 265, 267, -1, + 263, 262, 252, -1, 263, 252, 251, -1, + 253, 254, 266, -1, 253, 266, 255, -1, + 253, 256, 254, -1, 253, 257, 256, -1, + 253, 258, 257, -1, 253, 259, 258, -1, + 253, 255, 259, -1, 268, 266, 285, -1, + 268, 285, 260, -1, 268, 261, 262, -1, + 268, 260, 261, -1, 268, 262, 263, -1, + 268, 263, 267, -1, 264, 265, 266, -1, + 264, 267, 265, -1, 264, 266, 268, -1, + 264, 268, 267, -1, 269, 271, 270, -1, + 269, 270, 272, -1, 269, 272, 273, -1, + 269, 273, 274, -1, 269, 274, 271, -1, + 275, 276, 308, -1, 275, 308, 277, -1, + 275, 277, 276, -1, 354, 373, 341, -1, + 354, 393, 373, -1, 416, 373, 393, -1, + 416, 310, 418, -1, 416, 393, 310, -1, + 396, 278, 344, -1, 396, 279, 278, -1, + 396, 357, 279, -1, 355, 280, 312, -1, + 355, 356, 280, -1, 422, 313, 314, -1, + 422, 315, 313, -1, 385, 281, 282, -1, + 385, 384, 281, -1, 385, 282, 386, -1, + 283, 387, 284, -1, 283, 285, 387, -1, + 283, 284, 285, -1, 286, 349, 291, -1, + 286, 287, 349, -1, 286, 291, 290, -1, + 286, 290, 287, -1, 316, 288, 328, -1, + 316, 352, 289, -1, 316, 289, 288, -1, + 321, 290, 291, -1, 321, 291, 320, -1, + 321, 317, 290, -1, 329, 328, 292, -1, + 329, 292, 335, -1, 329, 335, 330, -1, + 293, 294, 295, -1, 293, 319, 294, -1, + 293, 295, 322, -1, 293, 322, 319, -1, + 296, 297, 298, -1, 296, 298, 299, -1, + 296, 300, 297, -1, 296, 299, 300, -1, + 334, 332, 301, -1, 334, 330, 335, -1, + 334, 301, 302, -1, 334, 302, 303, -1, + 334, 327, 330, -1, 334, 303, 327, -1, + 342, 356, 368, -1, 338, 337, 356, -1, + 338, 356, 342, -1, 338, 342, 343, -1, + 367, 342, 368, -1, 417, 305, 304, -1, + 417, 306, 305, -1, 417, 304, 412, -1, + 417, 419, 306, -1, 381, 308, 307, -1, + 381, 344, 308, -1, 381, 309, 382, -1, + 381, 310, 309, -1, 381, 307, 310, -1, + 346, 396, 382, -1, 402, 311, 403, -1, + 402, 312, 311, -1, 402, 355, 312, -1, + 364, 365, 313, -1, 364, 313, 315, -1, + 421, 314, 384, -1, 421, 422, 314, -1, + 424, 315, 422, -1, 424, 364, 315, -1, + 351, 328, 349, -1, 351, 316, 328, -1, + 351, 352, 316, -1, 323, 317, 321, -1, + 323, 325, 317, -1, 318, 320, 319, -1, + 318, 321, 320, -1, 318, 319, 322, -1, + 318, 323, 321, -1, 318, 322, 324, -1, + 318, 325, 323, -1, 318, 324, 325, -1, + 326, 327, 328, -1, 326, 328, 329, -1, + 326, 330, 327, -1, 326, 329, 330, -1, + 331, 333, 332, -1, 331, 332, 334, -1, + 331, 335, 333, -1, 331, 334, 335, -1, + 376, 336, 337, -1, 376, 337, 338, -1, + 376, 338, 343, -1, 376, 412, 339, -1, + 376, 340, 336, -1, 376, 339, 340, -1, + 372, 341, 373, -1, 372, 354, 341, -1, + 372, 370, 371, -1, 366, 368, 358, -1, + 366, 358, 371, -1, 361, 356, 355, -1, + 406, 363, 424, -1, 375, 343, 342, -1, + 375, 376, 343, -1, 375, 342, 367, -1, + 369, 371, 370, -1, 377, 373, 416, -1, + 383, 396, 344, -1, 383, 344, 381, -1, + 345, 353, 396, -1, 345, 396, 346, -1, + 345, 382, 353, -1, 345, 346, 382, -1, + 425, 384, 385, -1, 347, 363, 364, -1, + 347, 424, 363, -1, 347, 364, 424, -1, + 423, 424, 422, -1, 348, 349, 350, -1, + 348, 351, 349, -1, 348, 350, 352, -1, + 348, 352, 351, -1, 395, 396, 353, -1, + 395, 353, 393, -1, 395, 393, 388, -1, + 390, 393, 354, -1, 390, 391, 393, -1, + 390, 357, 396, -1, 390, 354, 372, -1, + 390, 371, 358, -1, 390, 372, 371, -1, + 398, 399, 360, -1, 398, 355, 402, -1, + 398, 361, 355, -1, 362, 358, 368, -1, + 362, 368, 356, -1, 362, 356, 361, -1, + 397, 357, 390, -1, 397, 390, 358, -1, + 397, 406, 387, -1, 397, 387, 359, -1, + 397, 359, 357, -1, 397, 360, 399, -1, + 397, 398, 360, -1, 397, 361, 398, -1, + 397, 358, 362, -1, 397, 362, 361, -1, + 405, 363, 406, -1, 405, 364, 363, -1, + 405, 409, 365, -1, 405, 365, 364, -1, + 374, 366, 371, -1, 374, 375, 367, -1, + 374, 367, 368, -1, 374, 368, 366, -1, + 378, 369, 370, -1, 378, 371, 369, -1, + 378, 372, 373, -1, 378, 370, 372, -1, + 378, 373, 377, -1, 378, 374, 371, -1, + 378, 375, 374, -1, 378, 417, 413, -1, + 378, 413, 412, -1, 378, 412, 376, -1, + 378, 376, 375, -1, 415, 377, 416, -1, + 415, 417, 378, -1, 415, 378, 377, -1, + 379, 382, 396, -1, 379, 383, 382, -1, + 379, 396, 383, -1, 380, 381, 382, -1, + 380, 382, 383, -1, 380, 383, 381, -1, + 420, 421, 384, -1, 420, 384, 425, -1, + 428, 385, 386, -1, 428, 425, 385, -1, + 428, 386, 429, -1, 430, 429, 387, -1, + 430, 387, 406, -1, 430, 406, 424, -1, + 394, 395, 388, -1, 394, 393, 392, -1, + 394, 388, 393, -1, 389, 391, 390, -1, + 389, 392, 393, -1, 389, 393, 391, -1, + 389, 394, 392, -1, 389, 395, 394, -1, + 389, 396, 395, -1, 389, 390, 396, -1, + 407, 397, 399, -1, 407, 406, 397, -1, + 401, 399, 398, -1, 401, 407, 399, -1, + 401, 408, 407, -1, 401, 398, 402, -1, + 410, 400, 409, -1, 410, 401, 402, -1, + 410, 408, 401, -1, 410, 403, 400, -1, + 410, 402, 403, -1, 404, 405, 406, -1, + 404, 406, 407, -1, 404, 407, 408, -1, + 404, 409, 405, -1, 404, 410, 409, -1, + 404, 408, 410, -1, 411, 417, 412, -1, + 411, 412, 413, -1, 411, 413, 417, -1, + 414, 415, 416, -1, 414, 417, 415, -1, + 414, 416, 418, -1, 414, 418, 419, -1, + 414, 419, 417, -1, 431, 420, 425, -1, + 431, 421, 420, -1, 432, 421, 431, -1, + 432, 422, 421, -1, 432, 423, 422, -1, + 432, 424, 423, -1, 432, 430, 424, -1, + 427, 425, 428, -1, 427, 431, 425, -1, + 426, 427, 428, -1, 426, 428, 429, -1, + 426, 429, 430, -1, 426, 431, 427, -1, + 426, 430, 432, -1, 426, 432, 431, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/hand-grasp.blend b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/hand-grasp.blend new file mode 100644 index 0000000000000000000000000000000000000000..3e7cc25c23bda0849c24f843ffddf1a9e5ba7a1c GIT binary patch literal 515768 zcmeF44PYHro%Sb9+6F{H5RD)jkyncX1*#Genxr2PJ_<++1XgL&_R<8>BqnJ|5h22= z^<#k*(1-{<@PyzlevKOY16{(t(8 zfqeU)zI~tX|MR}jxBq+$krKHvWHF_7>7r|%fZxBuze_xb)m z@B6>>?f;A==T2O3QDLHY-FxDv&D-A zcTAk$zIUYM^4}9R(N&DX%z+*w~2ROCk0=i&2_P?D2+?%%l(@#HhVsPD+ z#lGhlxclzWi68&?@si`5%kn+Jv`HoWEC)AC%v-n9LU)lX z$A9+AiN_w>kvRs;0pYRWyWV}HJ2$j`qObqzi4Wg?@5I{P4b#s5d&Bns#y53M487&X zlKsy9|KJBVP1qQ)XO;`h0o)JRHgA2uapT`k+;r22CO+`Nk4|j-n>(jn|L@7$Kl|PK z-kw)ndBZNpz$1@*qc{da7nlR=Sn#b^y=&siw{DF4-TIzSb3pq=E2rHU*wgm^7hd?L ziAyirFtN7p9TV$@ZixGyW8kel`W#&^B1*yrqfI-qaxucuZ2?`hkA z;gar&{(-l|&y}l(ChU3X+G{2TFTXAx3zuKBm2D&%}A>U9eOC+iTOI&%<@x)As-7fV=PhTs#KY=Qb^@xpJcOvf<*h)V9yplMcA? zruR==dg*1Ze_M-veCefY<1ujQr9H*h!rc6&^Paf)&;+}l!p&;GYD zz-^t=tFGEOv3z-9+HTLuel2HyPu>1820G&JckFwbr1z8kPY2}vKK0+S?upw!$F6<9 zXZ_#Xm)`f=wr|f>s|O}7zBu3BnXgKxd-C>g>ryDJi5<}2{}y*103Kl9pK-=Hx#wMu zD(&;I{GPo1TU)!k`zNgb>44=OeO0e>n1kucd;0co{c`r%Zrsr?7lKu2_%+TI!;x?~Qk!J#lpu{nB0hTjQRtZO6Jv^qiWR#x*+*{PIlWkw<<%+osV0(Tw4! zF8bAPKDgBIxYxdJ)$3lf(q`kw+|J&$g}G}w23B=;7y9R3+Of7UFtEO7?qFwOple|6 zrG=isE8Kf?mvjsa7W$Xr)zuwqJLazL80?t4ws&=*dtmO`!et#Rdk2qR)!VbaFf_Nn zdteP;JI24(di=Tb=5}`UtUh{8f5$-IF)OGoN-#?$&G zZSi!d_w#W*8)xG6Mi)23KYbNbnsmPO&2hb*7x<~?`geXI^?Lnp`(h5KTBeKS+gIEV`$}ge zD=%Z-#z~_q$9DY0&09N%+V73~$IWIw7{_vq>-6iv`V`#cjxM5zaV*EU5g*6;7&kmS z9mjHv+wS97pW-mb<*^*&m~Ym{xF|Zzjn$fBJ6Vo#EXVrD!?P7P$GymY{HdF_e0KVN zWqGb=*lugD#j`x)H~V%n-IXZ##L4p}eTUn-vE8Q;nA z%y#&GV}6+zE}!KYzuCvLUaohkc$Q~8>u0@ecUJr+S9k~8>*lTh!tF22AM0VeTuAXT z92+T$UgWlbnwq!8BPELJqY1mij(?0Fh3%Wuky+reS7dMZjN{buHtZV8xL>$8tle|! zGvc>(FGAecTjOctlWE4ACI996yf7|dvD;leoDMffkv(mHSX)~c?HBDEy>0d(@v~%= zsW(`E>O~K>ZQ7d6h^O}AA^x2`bHaXMKd@hhUWk5Sf5ojIzI$Ob-1(5!WVnS~=UzP6 zzw!6An7PjLbN$r69PxesGAGt2E&IAcHPP(oz$mJl8t2W( z?cZyCzuXob9~Q~v(S4AI_J)jcni;WsUbKEWzzroX|1npsjjXYKCvV63r!Br<-lFB_ zEL%R<+uJ>`ym#fLg;j(0F}1vQRU3bHyu8L`w(#VqTc1rsp6}%wICb z=CjvxV6eaUva+_kYU7udy`-?^;yZnw_zLrrb)d~WF)z$h`~Jui^T)b4&0fz{>-yK1 zm8KGTEOLT)eJCp7v3Z;vDnDyf9BA&qbb?zhZ!&3D*o|qTrY4kwkiTMjd!}W~!cgtO>2G{lPaxl5ds*PV( z_L9Pui{DgYJY^joGEdA4^E7r4^2Ge9cFbu#2Ue}??i*a*TUiHJ8^1fo)4?V3-p~COPz()UFFHi)lhBx61TkSj>e^aA9G`3u5Iu4lR1U#UEm8z1MX%8l>epF*DgK3KWn@H~E(d179eCw|Uk{(`D@ z%G2eAt~H&5Q{UfJ8h=5&yy`~OZGOAk60F?50UI(;%nS3xqRbze({MZ_*0Zc3QEhyc zLn&U35Bu%TzUxjto|ObYZ+RMa1C8fxcphiYi?H4C{7zil&f`QEJ;-XBTi@1l$cw>s z?nR!*`HnA8>O2nLXFYzJc^+rXecBoe3Qh%aer;BCc>Haa)lgoo^@k!4oK9ugQ;FgD z<#NOETdGctzi#)-12<#~{T+k7{iTZU^m?`NXSr{Zmg2j$j=reu(?_Xxj7{J?&H<@c zvw`E63eO)V|aid!B3=L5EjdY*q{gAHc)xE+&-=OKB1gzx*e zIl=gK+mg;hJ}bQFOCA?y)?r2;Q>S z!Uyxjyf9DgFGHS~zc6m6JoUI={)L4m;cDYg8!S|#rnqGn`aB&Gw6iW?L*|KjVV;JL zK%SVtFm$K&T-`O$*WFR>$NZhgV}^f?{Ys!?kMYobG7lsVU z+2>at@ALSdHS%)-c~72BcKmO@u1U5X9Ed4d;LkMQc_e&iJ{)p8Uh-#Md(hhV#=oIS zHgD;giJe}%Zr1SDD6%IW&-&(>@oAq$zxu}fd7t^}meE_^5XYQyc~|rGr=K$aWk-E3 ze*gAm7vB5Pmlm2|dGcfP8Eey*ezW&}S6{QmTg+XqoW1^PSJ!ne-eQbD=jye(UghKG zFJII;Z|Kw82EP8S7K^|8!;jB@=WCa29sKwkwz@WKU3byd%}f66i}P=N&F8EQ^Z)jq zwf9bpJl6cZw#T-(HWW`)z4Vjat*#BNtDoFDzi05g=9bT$;+B8zJ+()jwdJ?l{`usO zf8uf1-gD-Cv2Wc2cYl4X^#`}keBkF#-L~zAukBxO*zdn}|A{}WUGT!XO)b@~f3@wm z98KrPua9|GJWi51DEBoRKX06WLUYsSAKmi*zH-x++W+|F78?_+>sRmGa3be9tqC^q z3~g%fjDX5PGcJFT;=OQM*YZEXGOBWKR%XA+CE z^B~y|#&VinYInSfc0}&?Th^Z1sJ`JQH@DvcYyVdtdBpv+&UZ8e^l_|6J&= z*9cp*^xW1S_wmM#*`s5QJ@&Zp{c<>~|3>FwxjSBqX~PMAI^Va)Pus2phs)Vr*JZFB zKXD7NcJA=)3YSN=@!jZvW}xE`#M5H{|13pW-mb z<*^*&Hv2f%$GGsi43=Zun2%$9j7wgZ(db@eImXq$26p*OIEXTM`AIJI>Hx>^=E|29HH{#=1ALE8+r{h?Taoc?y>tkFLy*Hla@>q^><35h{ zF>cYUbR5euZjRqxSRdo=nvsrUImWg7IM%1QbUs;*aT|Rc>tkFL{dFpzEXTM}AIJI_ zch`(`9Lq6ohmT`@j9WD8%=q*v^T~3IV>#AG9-ghZIqpSz=BIAnR-oN`hvm5)Hu&+* z*KN5L&+?2Pp||{$@!@vDc$R1Un2%$KyX*b-5$2!e8Q<_azy3a+%WWzV&+?3K_wlTk z?GLwS_8-eLe#FPKUM{y(Jj*kF%*VI;Df2&4qWvt-_=Xex`ulk1ZF`A$mS=psk7vEi zU#WPOXZ(ndXT5B9sd$!W{Fsk#=X&^dkC$ja%QL>=^?v<*JeON4p5+De;?2Mmx^b3#<%-;)=U5F zD7F5+JmW_^v))eM{!;NQ&-gJP-|nYucd2-mXMBS{PG-FvzwC!_{IWdb`9ABNQ)>U~ z_CK3k;dZ|~o+p^I0QqM0RtT=dpjj<2tCW?xdPAe=<3FK5%F$>gROKd!=(xW!pL9IG(cOZ(4}< z`SXF%tpT(3+0)niffiq%J$##sb=PNe8lR8G`DA~6w%g86syQTnX4jW|mHFD@mSOn{ zA6Ao%biM@+OYJ#K|FR$0FKi+EE9T*w-SycE9^!j7j%%VHJ!ov#h@RwE`aVB>rJr&; zC-Z&Q2%YV#OW-HKe>g4TMaNe?IXP>pyF3@&22D9t0Dr-fx@e8N2(4dJwaKG!d z@pMG+dKNNI%nS3>)P_7Ue_`yoi_coL_*_dCti2V zcT)r1zsNi>FU(W>X~+}v$2vIGdb%HF75XdwIZL(iXHIFUY(1vEK2LnL&d6Dhr)?>PFB2V@T$I)cJi)3Dy zr}49pC+07`1osP~;{MM4s@<+zDCZ*oL?zY6pEISUCK}*o|I_`xJ$Ww@=E;A2OcmyK z$Gk944d)HKL78CQt zyf9BqZ$O@yzc5tmIWXu{5x%`kt~P$@l$M%q)&q$=CH=Hdx>!ui6Z676wfoNn%wHI) z_3T|Y*tf32qw(Z;oLcjyIvy8Po=J>wa<4vpJG2U%{p#RFG2f;@b$fgb>F&liznR8w>G6; zipj>4z0UJnJm1xRA^gPiVBz<2+x>Zdo(D@-z0mJi-{W4~e}DT%ADK^{@9Jzv{hYR) z=l2`uW16flYu?&D?5brP&#R1O#jkkZBGlo}cMWe(bJhY9uW^0i^Ia<})}8O-H1mAd zqFIMT_AKv_sy_%pE&Bai`LzZWJwwQTVLz~6xOn!LI~BDpimvkK9orW4-S^yWzdPlv zMP~WrlzHO$F5?4Tfj7s6?3`oUg6PWkwb>NEDQ#?ZV2>GfZqu%JeNxFWzSVDiXyZ71 zgf)d6mj83J^~73XtNr@XZ}eHwZ_D8sdXMMv!|xw?UZ2h2 zdC>2=UQX5X{8-_pDLt)5hKVU0c0C9^0wj*rXimvk-V)ta@W zXXZ8A&X0BL&F$?zx7ae$ka_OynQ8IvUCNxFv}S!wFKZ#mJXs#?ejluFrhC)ge~y1P z{bO^y9PUrZb_0GZgGWvA@3$P}Ua)WL_za!%BN$UOa zGLM_tp3k_G;r+X} zt*+>J`F-9e_=)jEq*TA~{U8@%zqtMUrf4X-KDs0*n1#uHvAzi(=C;W7wC=|hme{kH z{lb1=ztDs1FSPn)?s#iOVtWyP#1**5J#Blq(U0%j5mda-lyUNX|28LKzql;k6Wvt% zk?0y<9}8wp&H45$y}ek!=sr_fb?iy6v0vB^>=(9?{YBnWr`*4k>X#d9&0~6mtatvr zb7O1ZDeD)z{+~SA_5Tew-(X`p^?1><)7Sr>{+;Ts|Nr*C;`;x^!S(;I*~Rt$cdS^{ z+PmS?+s414>;IoTf5(<%@6q-D-~Ge#`G+*?`v2vfZ)<+{vh?-;`+Tmu)wQ8@mB0S~ z9Dn`)k6-vtTQ|Ir*GZ= z;UCv7IH7*(*Z*_-7H>;LO-aH&mR|Nn=D%=OMwfBk>TygQeg$}8r_O)ik1-}rfMXdV37&hv!+^Bb=# z*yyhl;OD&Lvj4X`4z|y8*ScN!j2U;$_<9J>*Pi|5u64OTimq|n$EI!W*@E}4aBQzP zwi?@cb8as-{k9*seBGGu_a1odiS~@YFFa@AsTOaKE==s-I=ceFMtM08+g2y*m$0Ug z%UQ-VS;n>(+ih|GWH-?A>729~ZfNe6kMY5b{bsx-ZjIdMbUrLE_G>JbKiMV4^1}1m zEVsL-VeYLRo7_TpoWkQ4-Yf9@^vfHgr@p`_txVU z_5=Hc{mTBr>Yd=cn>=o5bA0GSsRSh8OMaf;YZ{w}-?WO(!yhldA z*tK*!+%uW?*`#Mmd$b=c06l-Db+7w zO(B=FjAycp^^1KkPY=#_^X~s$KK9#Xi9Nf()4iXw@1BzncjK~ngmHhz{TugpEX(~M zf4{@;TY2664*z+b<@x)ECAIwC^`x4w`yNd0?>1kH{Sv3+SAsWQm9f8K<%ub`U&e9! z&5pk$*x%i0o^8?oFHv#E>}h@gzQEoazQe`Z_pW}r^XGK;`{L7U8scY0Wx-3yd|A%I z2R?V$=X7ob<$n4PYkFpw{lb1=zi{d7FY=x`P4-LH{?0~q@)2_Ky+7xC!!Wid>lgdJ zg3RwLPMmmlOW3}jf9`^vUc03={e4AS&64=uzdyWrZu5Cp-M*#%&R4|Wam+jA#O5DA zb=&-#m%V7K)w{LnxO-pwnnLsOzyGPb|F8S&N-zKPmOuS)+m?}iUVXovFaD8>Kf%Rp zbLH&)3tU}~x%eg*V?5i{`+ip!<9iCfYWcwYuWws2@rf3TKmOqdnqTc)j;}R;_UrFxzUPh?HM=%6|Kx)Y-TShax3<)GKeolyv1Rz+maSL6D>QK zx9=h|oU^@OIOp~!TA0AI8PPK$ZGug&xqkD(# z_=%ghc8>UVx!KGI<5-Sy+qphF#gD{CJ&a>H#*O>(td9#Fot2JbImXTL-!HK~#bJ)i zV>!m{_^8k8PVIcF`}JT=eEoQ%tAgbi*YGjKu|6#?9mjHvYx8lek8#(}TprJ|oh-+= zAs@&37&kgA9mjHv+w9|5ALFi{nQkY`F>cJqu|CE{QC~cK*-n;YT)iK+tdDWm&rHX$ z9OIfe-u-eJ_k|hhIF@4^w-?r@ILxt~EXO#OV}0c7VqT;#r>YV?Ms! zPq`h2!no4WIPu@8jA2Qu$+f#<%-;*30&X+Z&h9@{Awx@vN8Y&Fz@un(-{p_%R>f z?x$RCsd$!We8Z>w`Ummh_RHn7JmcGaJnQ9hOU1K1<41fv>+SU3Zwj_+E}!KYKj!1x z{giR^OPD{FXMBU-pR-C#)Uv1CC(_0+j);q`jAwBE&}L_(-`GQm+c~#uZs(i-3ELaDfBJ>K zm0|wg!(yc|Eyo$Xk~t59Jiw#neq4g?Z*GUq$1PChvkX+@n4C=uk#<~iFsk3+8;okm_L^1RC(Ha z?}Kai3uc~dy_hF|I*zLvPnjp?g?So!5P4$$Qb7)sr@i++xOTtbtUS3x#+@F_6Z676 zjXZ=rF@IrTB2RnmeQ@o5!C85#4_DSP^TfO`PorN%o|wNdRC(Ha?}Kai3uc~@e%dEo z*+ib07v_nd3z)w!RC$`(eQc|Z-yQeCo#XR#OR#d2-3OO>VV)Su{E<1;dhWgV!95@` zo@~A9{K`#sA6%YKu^%t`U8Rr8p0LjBclZ2P^*iKrTPKdjeUj3z!cUvri^cO>Zr<`V z`fd1$=fU`WBfozv^*!Rf?x6oVe*n_!DypgZSNDq$WIp-(@;To^{hV(1=hy1Lj@Mli zCViM!hh4Rd<9U_#uVln;v+G0b5ufjBinhHv$#`p$f4}KJ$i(N{hfi~{c0S)vGtYPZ ztGfo=p1Xb|^ObczAGPRwetEU-dbv+m3HA&7f&H@M5%dfD3(Mbg@9Sm#Vo&Qs8^__J zCOY4}y7%4Ji~YcU8TuOfh5d!~)P1~+_oVxJCHp07`@;9Bd*6M%*bnR%dXW8vesTBl z+SdIL=Ivj{(ddIV_YwExeZAi1$LsC(hI{b*u(5sr#rN&K#3MdGoW2jwbPoj>o~$T#3A+rJFC z?;ps#PUhmm&usjr9v5sJXi2@`U{AeH=2f$9ZC-cNEye3({_T#BHJ@?ZNbx$EIal9y z?@iCTsCb>s%x@jKwQs{`i`U8gOT&ZnpZxEy%^!a1A$Oh3*Y5e%zkK4p4;;1mtt?l*U8Lw*U8-Pu9Nxx%MV)c(5ENv|B$;*=F{#vnJ`Z|KeHKlUF}DA z8o%Yf=K6Q1>tvGm^}4C|;S|2*~WeV^yp5A2ui zetTnoA&>JGM$s!DWKJh0<}I9<7?1fQ?nV3DV2?Mr&%5^cKbRChH;{jwF`iw~jNg^q z6a8n6J$*%!Ouk=-&kgVKehG`B7W>?QM|rhI(Z=s#d~W`JdHxBPJ5{#r#eP@9s zvNY_f9cP`rXtDj(VE2as-4{rMU4;t&B5t+u3p!R^w%RRws_SiW=exg$Yh&eo?rG=y z`N$du%oFp%JTZp(BXi32Tsg(|RvZ6x=85Z=oYKGCuDPAF47dL%z7LN5wAJo^6D^u? z-j^PH+b32nik`S_%YPpfE&8(CfNWc{&;Q(xA9idHo*yvQ`*z%C&p(`E&;NMC=*jzj z=b#pRCsAu*agG03^X0lnvpU#H1ds2zh*I16_v_NO2sx=(nSGN249B^<)@R?<}dBtmc?|=03Us$lKoE%=)#P2!yy$4F;-_QH~q@5R@HOsDeMQc*uZ~OxL zojHEG`BCu5&&%5%al2<6xBI4_WW|p!M9ci|dAA+2D86jN-Xm3i5Q18CJY0UQK}F9HvR~K_?3W#np$s{tc>J1E>^b@Pt^D)c(9bY_IV~flyQK)nFPB^K_#If~J~%8N zaDOwqyOLdLar{m(eyJ_CacR8R3O}+G^Y)M*zef~bDLupS%kj$b%LtBZ@UZi(J=}Eo zO?^+T?-0YLB#&p@7mJOgJrROdxT+*?wdoX;X0?umD_(521=kqZg@zb$Gzzv6DI{Lh??0h}9 zTXuMTQS#oL`Wq?M$YWD2-S(C*#(W&> zW8D1N={S~ST)iK+tdDU~bXh#h^?rc3Rp5+!L-|pjCFUL)| z{TJ8YmuLJ4_ouAKFSk@Y%QJq=$FUt8f2G>b@{H&9&3f7YSuz_vIK98& z^5+B|;<(`QY&zfFi25pLMcb3kp4~kA5FGKizY{hin$!Hz__(6|)i}Nwx#X1iw$E*KCk<))0$F=#X<$c(Rl5xDgC^LS=rxu|ef8Fh)KTk6kQetZBV-MU{^y4np z?kno2J6(4hxxW);>uk^R9?5)#5mw7FE`Kxp8_Xul?Px(h$-8UX`TW0**LwW&g?{bJ ztC{`6eqg^an*9Z~zpZGG%?skmw#UIM-n-}+x7238
tyF2}J^rY|Oz6h2#ci*R4 zH;wycRoyYOSCy!5rv*e|1l=oj`E>g#j&6+QAH)$Mr2dt?5Qd+|yCMyc)PSChXVU#Fh_yHig_ ztLp5jB~CUsS^cQR{l!#YL0D_kDcSu}|G*-Q_n~3GwNKW9-S-~*h5f*O8F~-;h5Z#T z@zIADVafjQ8-~1#W}W3flO1Q}wpm?^78IwM+soOrj*slQ>xYdA+rJ#=`Y>x;pq9FL z4{fy>Cq34=IJ;kVz2v8-1p9^kz<%M<*k9o9Er?cJ`w-uYtY01l&v!XL+db_*I>)-) z*n|DR`|KDe-$yC_i~UQzL;M|J`#WuC&pNK|>{&1I^|55ul>K7warwz|R?}p>ec_(h zFP*NzJf8can@^4-9`Dg->_47lYJ1fQsqK6FHQ4TxIY`crd>_Y+kvpoi`?=V-c+}Ov zdaToJ`Aa+27aCg!8W(gIdR7 zf%QFe2RjP`T?2D3E%Xdt;oh6Oq+?*P(7z0?uI^adF?V&xV8`6G?xs5319R6FF6&s? zJ9zY}-k$Y^p}GCt18ex&G5)pInT6=ssq!bKTmNmvjvsgSRj5ulS}md+0jn&B`-S%)l{2^H#t9mB&nVbYt(1 z+UlcvcL%qcsLl?${KNM9o7_ClSMmH+Q#;Nh@w^t#-wpZma6FI5^OCIZGQZzjOC%vgfWJ%-088t}I{S z!)iIs^%;)^!&=+tKRw5>4NrVEKC~RW{Y$Ci%CLPQvtQT`>=%|}e}SzZ7TBR?{Fv$b zW#+a*%#XWQe&=6*zt78Tp9FrsV88HvU!0SS&*Q&~K2U2<_xF&uwZ`kkyfTPW_KR^= z{Z>oz^CN0ywEI5k_1XP0dN{^+)3WSw-hQ5c|NQLtcZ@EG+dY0QwgWA3@;U1lyKfwq z|ClRo>pu3f^l~7lrS4m4IVO90Fh^TIqeyc~IA{*)oiDNlR%-+}&EV#VtG{Nah$ILkaS zFU(WZE08DVZ_b6K#?#*Ycc5)N**zQaz<5d=e(;U>{Db+4d10Q~=O9na-{@bJ%G2Kc zcc3j#C%Px@CyqSrQ_PNLIG&gn=4t3i1@0>?q`k`5P~k%+p@`cc43cp5E<~!aO}YOp;^fiFsk3 z#*apxn7@skrSi1*{vGHCe4Z>VNk8pBNuHP&=BZ&W^2Gc#TvjSid+*+&L>r=@(sPhS+UA@jt%Fi#`%kSFFZ3@xtb zWrYo0J!_T^6e??Wwee@fi)~z5;bK#(vGq?FPm5EpM$usb8!}JK3-dJkYUGLe3qykGbdGy9nWvYeN&%QB=7o70e=YLF{Dq;#^<1@XV6b;> z{P(pg8C2EAFN_!4c+M36tXI4`KXS(f=5ZTO_Nc=oYV_0Ogn43Kn5Tv&8y~i3Dtv(RxclR`(IY`{L%@d26Z676HN6gb zV*bL=#Copn=<9PT4@*qW)y6NG%0h!CEpgkO<>`~b>+$zE!E4MD^TIr}pNKp$e?eGs zJazS4(!I|8eUmar5^751X-e^@O=Y3MO8m$jXIh@ZzyFZ+{T1`Xyf9BguScGkzhDv3 z*$Ylzyl|QQYi2~$|OUztsQyE`ISxfcX%$UHGG z%+tt8$P@DyhFYA@QY5|g>)jtEEetJR z)8D(UuaZ$!ZT$K1avM*rbh&K5O@Hb3cedS~nS9aBPjghrCLXYu`&TFU(WZ0_2JL%Zf9P zuUlW)@g?hFo~9aq-uaF05UPqKxrQ9+^Avs#K8TG>OqnO*=?< zRlVK4{gt%3+IYX+Ev$68$@O@|eQvSsF3eN%vmVPcPs|JRG_(kLV*Xg3Q?6(7s04wp3fH&Q|5_zVV*`7BTvjrv|XX|nHIm>1@0^c3WY`AgQHTu+QA`z?J~Vsd7lrW${0!Ts)kuzy42qKX$? zY?ys7mE7NPJRMvtp&5=R=7o70I~93i{uF_^;(Gd%1>Np10ET5I<7(q4tGnFyY&<>X z3Lg;!O!m7T=7o70Z$qA#zo4q(cGK5iSl?B+JbZhX%sfps{+uZ;H`%ZTpQnw<7v211 zzgJ;in5Tx*ktgOasH&K!O2-lFVVbRhS!NELFHGbi4IPW{?^Tc(l^D~qE4ug4No`#knPs|_d;*{&z;r~}rP3-dH`7V^aWZGLlamxV-nA@|PH{fxG^@M4tTR8>s;1iFsk38kQnY%wHldNX=X+!^TfO`Pb|v(kvW}wJ$JqPt2RE&)2^4umTP+TQ^?bmL7q}Oc3<4` zwB60~I-{Stc?)YQalKJ;{mwgcIWBI&-fp?CvZ6`Q#EN3eDa`fb`f&Xi%k?G)>*u$Q zfhnz<)%i@UUwl5=UpIMgnaj*_3v;kHOlJg{-F}qaX~*5Y;^-*al(7Of4(xSa$GXGK zTi=Yo5&IWj?;76Mj`w%t^{y_Y_&C*XP?x$__TS&`c!}P&`)ADAAJ@&*`}#TE;jg0| zx(LfHR_14#{tDOeja-zzu9b1TeljzD_~u2ZhS#z3K04%ZX=&#A#J`7F@jh3VyRMbf z%ib<@?&) z-B}iV^^r&1&s-Z@9oS=r+pgW^+-V#$G-URc*iLAkL=%FP3brG1N((>>@V>9T`o_5kncrN!SPFCe%!ri=U&WTcliR3 z`6>NooP6KE?I-A$TU_F-U!rI~cV94f4~gjU=(cphOiGU9toyZDO|MNv8YdqcpZ)ao z%h2T*|3iJ4CYL$cy!FemE*IS1?sJ7XrY4JXiQ6k5oo_!iKCa`m;l?(cyc=*IB3G^J z?yKN)q~&SjV(eEekM?^Z);H6=Y41PZos75V*gt+PUXGPp@%Li8DXG104?70s{rl}V z5Vm!bpBM1K@w@5!{ag9^Cw`ChiOaiwy=XkeV=qYaXj_`cevytJ-vPGoJd^EtvAf%f ztsmR>62Ck#+$6>kwz$^SmyE|f4)y-b;Qd(v&kndg;C%w#H{fRlykEf24){3%?;r31 z0Y5k30|P!N;O7NwJ)F$X^8hHK9~SV71Aa-sjRC(j;KKuc zS-?jG{J#QzdBCp-cuv4a2K>r^Uls6C0UsT(-Q_viA9DjfHpTh&k#8UA@v>)a9~_@; zzl8tE&*lG>NEp&D+13=Aj>?dCt$$Joc+JZ~X5x zH`V?jmH!?4rFrD}VD69Ezh-M2k7DeP#n>NNDj=lkdMeVEeS4eE+oppAc|Uz^@DV#DHHP@JRum z9Ps>rn*(kMxHaGf0WS=AQNW8+O#k!q0hym4itImckokFpy!rTt&N~-eLK%iS4QK{QN|Ja(_sFis4T&{3(V%#qg&X{uINX zV)#=Ge~RHxG5jfpKgIB;82%K)pJMn^41bE@Pci%{hCjvdrx^Ye!=GaKQw)EK;ZHIA zDTY7A@TVC56vLll_)`pjis4T&{3(V%#qg&X{uINXV)#=Ge~RHxG5jfpKgIB;82%K) zpJMn^41bE@Pci%{hCjvdrx^Ye!=GaKQw)EK;ZHIADTY7A@TVC56vLll_)`pjis4T& z{3(V%#qg&%ihauCYx+eDzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&QbWKd;j-V)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiUwHnHei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5o^s6X+K) z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ej{C<*t5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{KDTm&@W>6MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2 zzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8Ff1`ziWG48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+3xAJEzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=GdJyXhA({33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejyk3NU5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{KD(c=oc~k zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLOMo|S$P!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd z!t3Md7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Nww2K^$2U&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkzG_wS)!#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zwmxw^otmN5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2 zzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XFBUyyzg!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd!uyrdFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF^I9WBNr5zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&QbW z@25_`h~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ej zV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4e&OF|pkKuBix_?p!!Kg^MGU`);TJLd zB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97M zFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8 z{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU|2@4e73V)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p z!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-% zG5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ z5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU-5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs z7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4 zei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLP1dvx@R7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`) z;TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc> z7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crA zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7yf-q`b7-C zh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ zix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2 zzlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XD8{33>5#PAFMUM~G2hF`?+ix_?p!!Kg^MGU`);TJLdB8FeY z@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zg@1pWei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH z_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5j*}{6EZge|9{gU&Qc>7=97MFJkyb z48Mrs7cu-IhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5 z#PEw4ei6ejV)#W2zlh-%G5jKiU&Qc>7=97MFJkyb48Mrs7cu-IhF`?+ix_?p!!Kg^ zMGU`);TJLdB8FeY@QWCJ5yLNH_(crAh~XD8{33>5#PEw4ei6ejV)#W2zlh-%G5jKi zU&Qc>7=97MFJkyb48M%;_7=97MFJkyb48Mrs7cu-I zhF`?+ix_?p!!Kg^MGU`);TJLdB8FeY@QWCJ5yLNH^v~EY()}Yw|A^5)V)Ty~{Ub*I zh|xb{^p6<*BS!y-(LZAJj~M+UM*oP>KVtNc82uwg|A^5)V)Ty~{Ub*Ih|xb{^p6<* zBZmLQ@V^-T7sLNz_+RY%`vv2v?QyKgzQ2p?`@6`#zl-eqyU4!3i|qTm$iBae?EAaO zzQ2p?`@6`#zl-eqyU4!3i|qTm$iBae?EAaOzQ2p?`@6`#zl-eqyU4!3i|qTm$iBae z?EAaOzQ2p?`@6`#zl-eqyU4!3i;Vrf`nNHvamRUL?C-^g2k*Zu;3ES5Ujbu(ullgR z7h``f#{OQ6{k<6bdolL+V(jn5*x!q>zZYYFFUI~}jQzbB`+G6=_hRht#n|7AvA-8% ze=o-VUX1;{82fuM_V;4!@5R{Pi?P2Kw*>u#{k`5_5WK%I;6(v14)~OSPYt*&;L`#= zJ>W9}J~QAY0iPA{*#Vyu@EZa?H{hiK!=KwPO8Zj`e~RHxG5jfpKgIB;82%K)pJMn^ z41bE@Pci%{hCjvdrx^Ye!=GaKQw)EK;ZHIADTY7A@TVC56vLll_)`pjis4T&{3(V% z#qg&X{uINXV)#=Ge~RHxG5jfpKgIB;82%K)pJMn^41bE@Pci%{hCjvdrx^Ye!=GaK zQw)EK;ZHHPpUuZVJTrN|L5%H3jO|B^?MIC5M~v-9jO|B^?MIC5M~wE3-I;Em80{0I zePXmvjP{AqJ~7%SM*GBQpBU}iap0Fz`4gjkVzf_;_KDFxG1@0a`^0FU80{0Ief2BT z?GvMYVzf_;_KDFxG1@0a`^0FU80{1L@i*%$sr+p&vLAm%_T#U}e*6{LkG~@O@mFL& z{)+6!Uy=RzD>B;GaKuoiP1hW+9yW)#Au%w`)4us&tmMK z#n?ZKv40k0|18G-S&aR&82e{2@-;TGJvH9M$d?%T5+h$?tw&MAJ{LQN1|WYU#RaT3!~v352|j* z+YWok_&WEz&A+kUul%i^pX;Y&zVBb=#Pv(ma*bOm8nk1M~c7$BLbQ+Tsi5En0rg zvgL!lz1;)LdskjsST(q|cXa{p@9N)b{%K<3J#M<8 zSOBSVV`8TV^TfO`PumYco|wNdFkH`-{p$ug!$OmAwebroTwYdF?sIv%-o5cE8yJa4 z*1%$(m>1@0$Dzm*^OvY5p3Pj(cx;6wv$@*%Wo{s4*IfRqr~5pe>_e!BeKM+Go|qTr zss1qU0Y9$7(Cqab80_!8tgJ1s+W4hqFDY!f_)ecEzQR21%NG(;=81V>p60w5d1C$& zA@OYXdahd6zrL(AMb*YHEPF{|%f)|FB2Uj!k>VWl#Jn(1Z7)Hdn7?9xpUGa&j=sJ^ zM}J4ps$C|l+W6M8mlU>Kysku^o}(hgIp&FZVV*i0ktgP_7~p5Z^;}=*A1n;@b#(O% zhD9^E+W52k2D^HDrnIXow&&(Q!sG8NzJeJZHzi+Yo|qTrY2!(l;`gb{)c0>HKvX>OLT>PdI}m(VV>$=jyy4cEYE4F^(=S$t2RE)Qsi*2sy4pLp%kyqhyMrT>6gLE9T2b~^TfO`PeY%; zc?RY$3=P+_ziUm`>Xp5#EB843RB8OVw!Fp#Zh=!DQ;)du#B)!!esz8&4+>Y-G4sT{ zFi)LN;=B&?*WNR^#|Pa}_`oH-{cAIpk@ZrT=St(3Rk*yc4d(G{CvaXx$9pf2i=|G4 z`9S80c`4@U&{N{m3(Vh+zRB~1^G{)GN^_W}O5+z-uy4(3h2?3RJAShBPoFFnfWbMg ziZ8pFVxD|nn5WIrU2&e6zmcKI^VDDH?x^IGM3|>a=MQAcldoz!%;Y%;`cyUZsWozYJ7lg*!TLzg+KW5{SO)^zwf!)4`hD7!}Ato zzR!C6H1qqO;hNhbYhO7JtN$JDIWyR+{e92)D}5gP6w&4X z+x7&$=h=QM_LJpCTEE!$JzRdc-LszYpxxSTyE_K#Y(=5J!+in6;=7zy8^5e~&6@5) zqwRL%FPScDT+}hxvCGA#3XHk!ev^Ae$F;9Wy`Kb*UyfIfUw#kGagCT)FN{{)`jFyZ z1|Gid!H>8X@9}SZ%O3#U?wRA4%=cAKJQt7OeO;gF`^tNwZ`XdrJ%f@NXx|~*)5dSs z_m%dW2|JR-uSrmWy~4-PLD}P%??2O1_6z%g{la#zzsP&))ILW{)-NBQ`TN=v6OA{< zo(C^(KJe-3mmPOvzgB+-zE4gxA#=8AE<9%aGUQrF{;VsFar9mrzrkbY*RGp2yw&|) z!aebL);G_LKeo?!+sx)?pMO#FaqIu(UVG=}o{P3N^vrC2&HdNKyzq(de*UKQPn|UT z$5*G8GjZsXE`GSV#>L;{V&=PY7H@S~{EaTg_*hr(Yh7KleEeH)UU2W$$7bI9>p%T! zzQrFh^T6g8f32ta8^ix{l54|BzuD2V_0lJw+x*wtuRF=L;iM0~@rloW_pkRk`K3=> zz16j$*#1+tzH7c~!~7S#+tUi*zL5B}z`czrL}XP>Qq`0|J6x7K#WeC_dV_w6?`I{D*2eSvGsaP!GW z?Z5T3(>HGY;y3=|URTGx2Yq8z^GgqSe9QNqI&7<}W9tb&Ie2T$`#&{*?*3g{T^(EJ z|Nf%;-Z68(lYg-G;rXtPxK7K{^nKXxc)~~dul=!gdGk?qEARd3qW}B)3%mXhj|tZH z_s{v|>p9P9O;Wz@#fb^N6HbSlhoAf2*T3#fmo?X~8{Dal@%HHI;_s+NU3gG+SYgao zX5PGcJJn}nDIL(*`qf9yoXuc94M{QH|4_iuf}4X)b#7Fheg z`p6^htNAMy{eSkp1+cE7T6-sLAuW%VhZ-wa14YfPg1n8;Hfj1GEp34oB|O7va?*2b zl9N9tp$S(dqDWO9f>#Kr5CI{Aa1l^bXlZyTRRP6&l?tdu5vpFVT)k@K)qj06^PN3= zXYZVIa*{S}_OvJST5HYBT5D$3to;gaXNEJ)*;{Xk;Xos*S+zoJF2Use+b>8OeeM6g zzE6(#o%@NeT6uD;IbOCbwI*5b9C_4HNBaSC$fF&9D6QA+u8-@upYca^e$d3Fy*ls5 z?|H(#j}UcYV&oN|pJjr5!E^?2ul88q*;`JFk(j#8~ zUS2%H5pS!(BRv;Sr`R6hh*#2}`AK@jbDWP)g5nX6aKx)Hc%(k;t@Py9}UPr7Wk#K?>NB0k}X-*50qm+gk(6Q1~k2EWt9 z#IFcxpYX)5SYyV|euU^J`%ie{cN%=s<-GOlDe(zU{C5}hZ_=G1u>9Zf~cMyKB01uk>wo4l8 z=av>Ne@Uvq{&OAdH1mmaB^=^@F={?B$#Gx_?7jDfz4Q~fUYor1Hcg*#-&&ooX!f>i z)3wu(TeozSc=Trk;&~({PG7)#eH5OcdC9$J10-MP!5y}Tc^BK{*~rM!n*<1IotlkGe%WPjzqiz zANq)ZG6eenT1=kxx|V;nT#6+t=b1?o%X1{%dlw58l;s+r!`h6jS)m8wfbA6-BHu|>;@4wIh`G9XL2po;C=V4yTy-mbILJ#A)Q zeIhqKw{Z(eLoT>Z#r9tmVi-VwdiZ`+fB1|uPF=AI4<^;8T5#WSe!VCZf5Au^^>y)i zxlRRLIowwslqH|Y7xHOqyXF)5=f_>SXvM-sE5W9=cuPY(_X~N3P{H^kYSlZ6%M73R zybWtTif#(YC-Q}S8tl+~BL7H(u{+MDSXaC)@4H(I#a}j}R@r+Ur-V;ji%>GzR0r+& z~|NMyVIMaz(Ltd(+NEM2|YDBGiM{$_NC)AKnLDv+> zC-Q}S>iIX#C-TqRf~`+-=L+tp&E?@Xi-^mok>Q^TpUm;m157@VFXU7I z$26bFKM#^*tZ}B~KA+aMRDC?1#}ZX2{%O*x+z6RxtKL!kMec*7t&JM$Q;8Q$<;W-U zg?!rjam^?4&yVVkGuQ^@qE@}5C^vk%!CNfXiiZaBiF_fS2uc1i&)DVD>R4`1auZX> zh2mF_s8w$tW?1@!8qT|YykIIvKGCm&n|Xrlc0Vd<`pb8hynd_G(BAGi!f|?s7AyM+ z<@9gS-&ML^uTS)Y`L7Gn??peDP5RTu0D=GJfCF$vS99L>clBSU=`-GL{A=Z((d9P1 zpfu#$Eo6yDze?w)g7BNX{;gi0pF5}ltBm7O{;qA0EmZz4#)1B>OQ+0q@XIZD==)GK z71ytwJ5?W{os^|qC zpxWOh#*6Fkdfr)9gr6alB?5iOFvt(7sZ7qC-EyT`a;er&##y>BYSmm1*{*-z2y1BB zsV6U405^_UYGRqTC*%3KCEB*bTtbsN1J5T_rzbBY=k^0*=SyR>etFOa2&Z~>{5BfV$IZX~J z&|kTyT;3z~jmgW3@MCYnV~iK;N|^rosrd8Zly^-HVUO^wwhCW6wT# zm8Rcs;w@(1Ex$5oA0u@)roIx7`da(B0Q{!__`G zu%FP9>pqMF_rcfYnh$>2gUv7O>;9mrxcgvkRQ*(TUY>HH94HscmGV+O>b`e@Q}wpT z+}=&k<{`% z9QMHgq4|NW{Pxdl{Vcg6Ku;~W(N01xxbDODUz7&W^KAV%V^QrH1#E*(q4=Y*5AG-X zAoPiL({Q{cpU4;Ti8$mR^Ncyp#$-za%kqf}#a}$acI`f%FMcra={mbm(m@)|dCqyw zc}`T$f0gh4wq9?$pH=ZCUv?IvoH232Vy?f8ZMbRA%$mb{&v9S61i6pn^&?9dSUO z9SLLt^tV@PXn)ckQ~mcV(k`W)O5%r$ay}?ZN_(`ZsAp1;J-Yrzy&p3!|Dw(( zuFq|s&a8(9kLzLozX#wCB-Hw+?NRi!(U)iMgJa$YsO-_IZow6MlyRUv+B0dU+@+R_ zJ!s-=YOd9Cp`3MJV1F)t%5`{5Pr`LJ^q^q2nhMo`JlZ9OH3)`oPWY3c)>GQTnJ&o+d z4CO*OP%c}q({iD_beCp`-SAY#-|%vyo44h%&h$S_F0A(r(=QkCH}pE4&Q(sM4=^Ze z%LTIW2YpV!dkk_oboh~XL7sA<94HsAgOr!jHz2< z^P^AH)MO%*`$Je+Sb1*vBj~?HxV!S{woUV`0+sy22TvbTwqwUXAN9it8v@2T6e=ni zI}V)jj&)Uj>baI_`FUmdrQ?5`k^L#ZT&5n)vnReXz3Pfo%`{=|}(m z(4_zV!$U=?-b>d)QAsr)1(0_9gnd50WCYLW%Q`mN0rKb-qCCIxJjZr;&Z{ublkhn* zK8MD09^nz=nE;;WCQX_Zczt2}EqZ-syv00kUwgAIx9J6?x!)3x`)we8_n_E42z;*O zYHwawhW^EP5cG2;UlUwBS7PG8^V}@Cwt!!5f&2|c`kRVxwSpoP?QVhK)J9T z%1h_36<+?|BRV}}zFf1E{NEl$9?z64lpoG(ydFR~&^|>T^+A3|u5mX^(%&Hxe}FP8xNVRjHG*);rlyKX$BA(x}1$DD7Qq*I;&gmhBaw?~BSKVIm$uA0xF zY(9aHa?RTzy(vcbL_3eK>w-S( zfsYdZ_uo*?fO>wf6=lft`_Rnu`+>|OW>E0Ici(e@yd97q+^*~2A{EH9e|+By-|zB* zs+Z?{&G#|+9vGV*(yLaQJI>`rm-TD&zn>d4yuCz;tkjR|{iNcDI!>6l?gd<+*4>Vs$k9glVW-I$i zIO5e9JkoRVKCYHN;t`H`od%Eeh$mLDN)nH7#OpJ7q({8|y}WpYBi>enM|#9_oNdKO zvpvEQuY~$;@QK&Imluz4#N&J+J>pH91^P$i5lkn8j za-$C{$2iL^c;avO&2QrS^@#X{Cw}>lwEnOkY}c<(#3wxQ69%7j*=`s<;fdd8@JW~R zyEbh62A=raO`dd#@7FW-pYX&lf5MF4&|$lNeIq{MiJvg|q|0{0@Ci@+K7&uX#OFL1 zB7Xx<{Ou-By5xTtKH-U9{-hbdp+mX(^*=Ly15f;f$&)U}9fnVM;`bT+Oh3$g4Z|lq z@wXfNgo!!s65qUH{|Qh0aJmr~++hheR;e;D`t zShrXHw6|TGuAPS5x}~GUB*`8^mJ6%He%4 zQu)`-yf$&-KXrcazw(>s#G^h1;%~#Zml2F#YaG583B6N(GbF6AyS^8Ra-du|B+AQi zss`lkSqpS|O?B$uL@1BG6kCk4MQmgn{l-murFiifUm>wl-|Gp=~XtZ%=~ zZ+#;k=h2p}LHNHj^JZtPZ@4cNt5WW7Xd}Naw3%qqyX*Q!IZ!UO&uY0)UV3MjsHLbypsnP*;@eHZ7E}rKWaUT|bxdqS%?f(e?*Hql^$>d6P`*WHPi~~rINfG3tp4Tw#zbLKbqMi$u zEjbO(YmDq`GLBOy{;BfRqWXYM%gEU>^m{Vlw5Y$-SL*N9ZCY;BYfSdi<<=xLh@lTfTfTiPQr;V(2-QDf-yiu>|x&8i+puvz&?&EGz^IGR+-VY?LythH_OZGm6^HIOp2txzTOWls-=293Q=dFgInv_NczhvhdvIG@kpx&>H% za&FzRs-=WB@8qUOLw;azT)|Z2Evxc50Q=ecWcJ z>RIe*Swq(p4H9JO20x$IH6>Y$UslpeCZ)sdi+(EpeD)T0E(GRFkEjsOw?C2QbI~a5 zBSV9HhihnI&h~NuY92-YyEeS22Vh_lg8QxO#>3xiOE%=yD;=fZgMMD#&q4o)|9TLw zEHCe#(2B&yR83fZgw2kW#V!Ecm6&I z|G&)q=lzRo7wZ0+JUbr}-({Gn{IC~%N^s@+1LGn0FTxLUw>*o6U-n@0>(zkuLQ`?? zU(Aha_IAe#f^wl8D3_8yYPnEes(rj4!8zj*w=ZJXn7n;nInD*}q^>l%kb11`Ro43v zlpS-toP>_|PzlaJF8IA>^wHm|K3+1JHs^p^m9=hj{ zOSm7zKRU_AJIH2ESQUtlc55jg|%(3S@-|Q+s z$cp&7vQ_nM@pyrL5X^Jj51K7df2pt3-^43gZq#cZ-Cd|({h`skNZf7x!n`n$XPL7-0zkXl%v{!(A5 zzk~m)v%hu>lK`M!9MIp6a<&+|RCg6DqT@5=i&dEY0`{e(w6Rn{8!d_OJl zeBU=&f8U*P=Rfp5S2{_T+w_9cod3k*{4e>ZrsKu&pYN*|>iXQy_ZSa?I^Pe}3a*^* z83&&4r^(qKzuW@(6?DGWRNV7@?o@MYd$ge_7s`Qh>3LPlh4NDEj^pz^`4YBY?yl#1 z%7JpJc|*&E@^a-eKF{~L$tC~uefjH}4~*H)SjU(zIN!6~e9uP{?R-ytrTz}?&~l?* zyZWoo^ICrHd1+Ul@2OA2uPZny=4bD1eN*#+G20pInEK0h^VQ#pcD|>+Qh(PMX?ury zt>q>9I!>?OQ=f*{UmTe7(_hlv*)i=E%7JpB9ZGrWehq*99_M(T-x1SpWI6Jzm-DAU z$S?f*y(|LLaz5V+G1Xp}Tr?&3e4ig>P~W+Ma-ke37xsekV&08;u4nAlgr&YTw134=Wk}T-WS1s{6-o;KewBH z`P*Y2>rt6x2uHlq65VgoBfMO(Q(gn&5sr8@29NZJ=YL-W;fU91@JP?a(`lW@e_YVb&pc>Q~M@d!t}lBt?6q({6Pr!1WWezTv1BVL8UBRv;S%ZYe| zBVNMbksk3J=VYaZ#3LN>dJG=v5%0z+Cl}fMBpmU!7(CJ=-d)As_6SG3L4!wn#Jh3I zE$V3?_LFeL<9s1K;`Q%!OEJ>KBOLJvM|#ZPRqV>ITnaf4e=BK>yT{B+!c$L6jXtm( z?E;_h#NXTf#P2cqq)WW5VdFRO z#NTT2q+4U~N{syd{3AT^OZPS7H*~nZRD|FYp7^x}pL99?Fnq!jzsKN{F30WHck-X` z#NTT0Yfa2?hv5^R_@(=q@f&>hyC-b?2A=q}CQrI-Hw>Tf#P2cq><9b5C8T}A6Mw70 zuVp`s{KN1GPyEvT&G-#I^=~kweZmvJ*5H#a^)C#c@Wk&i_@v8zhv5^R_*)Hrt%<3B zT%U&Mzkwrusj&k{m--imPk7?j(w;DMDfcjZ!V|xTc8G~94BrzW{3kr|IX=?m{4EK< z?-k&!rX5~?={rcvpLEDSuA`+!pQsmvLyYUZr%cio2;P^m!koqJ`zt$VYx|1v`Wd>t z(gVHi+H~zS=6$zp6vX5CED(P;cwffFhF|s=k>+!z%81D1{ZQj4Pq|PIlnZ-EdFlK! z3w6A0zK(xp@~2hzi4JXm8(qS&I&$z14Fuk=aJ#Qw*YdBvj|9eve3xdD#OnFq`!M8$Wkt-V*552C=Hjl>+E!5Q0w=W$-#aE8+J6)kPEKovHcf?IM}!TpTp0$>JOiB z#;Ge-;nC&#R7-ojvpv6F6^g%LB#rvI_`E#NSSo`(+*clyC7;L_@~Q7t%_s8DkL!Mq zye;0+5O4F>XUi9iKcZH>y}Hcs$@da?r6*oUeXfT-kuT)ame(|&$Ui@xJ5G5lHr|%s z$9siXq4>*2)T(zBDdE#{Odb;^o7l4;m@?`U`9eNze_iv5{39*K?l>Eg&GD9WGS!k7 zuL{LqIHFeBdmY~@-z~(v!?&~T5MVYbKN0kad?BAo-qd^||7bE;jGscv;s zM?Q;Gq4=v}&8)Ta^_STXrTzK~CSlQf^mKMO@A-EpSdWvTF2XU!Li zziLFSdb{9&`*^`rj(nm& zWuuf@CTakNE+WlPfN@??95TusN9gy4_`452^-3ZATl9DJ9jwMu1AT`45C1ThX6}?hi9Ps|c(t|X8#{I^>Hn^WI_xIDEN58wJ4dT(SQZqFGf5>-i z=PcCpa`Sin*&JlFzw30tg}=+hf&Q*nif20bWe+yLVgU-OskqM-AAAIuP=9y{TrT{KK$0-0wc$?_4C`u?=~TAn{a;H6Oq5`2u0>e&4aB94HqKn(|_P zyvE#L!sPNwG1f6R`15Yfu1&3F~lcx4<-X7XJC^dB=Y1$%p!HJYC@|UYD%AYU$#6v);eqA=KY|##tM0J2YN7d+v+# zkZ1V$f2JN5dX65IEjSjCdW{Q==Y%}1Gl89QD;^?VG+K@DJzJ@(iD+Wz*+=0Eww zvUz4pQ+U{)f&+0G2SbfUDf*9}EJYGea!Rc4*y?u;yefNhSePMa`@MlS>H+fT6{LQ?H*q=kY!#|NTiITXTLJxKGYx2)Ui-I3E2TxGjQ<_rRH0>ATh+yf<~Sd@psHbK{hm>Ze=D z_SZw-2MkKk80xdm`+&w#mU5vSC>M5-@>2O;%3-CJPw%(1T)MAaaE0j5jYf~&kBJiy zE+4iYGU=`a-`x9@Zk%#N(G~IwAQn&rxq$o7V}Af8yUd@r>&8PGaw(UN)E=y_b3G|( z&j3s(S+?b7a#vRXf3hU)a>Al+y<|9-p9-OEn#e>rTLgvug9@dLeP=vx-n_C9&x5g8XYe^u!|6AowA@`_#Rn{Z;>`WZE#^-;J8u+z| z3%RACyhn{yyURUllmq3$AyHmBZ-1*?O1eKSyw%?>=RImz2R?6*OU$BT-=k*N8!!{; zHU0*{(eEtBx5{T0UG7XRy2uL{n4=y)Wc1h%1WI=B=k2=jkj6YeN_fF}H_^UT-gi<> zn4zClJVxyl9QZgxQl#hqR(a>`-fxvNKT*C_p4m^#{=xl(Oy)krvjU%S;4>P$Hbi*D z-;_C6BSOG_GIi=*f!Bcg->dfx##>DLDeZVy#owwfsQ^n2H1ym`%<29rn{ssHp(dr$U^NX)?=7-SpkyqI;->JUV zFj9G$-g!%yrr>f!QIQA z6#FrI;QIS=Kt}@J?I}K+yX49Se%WaQ0`$Y?xu1$ZpIZw%4+?VWlksq0eO#K(g$+}4 z=;AvK%)Z743%Zjn`uHv@Wb{}0T_nGc$&Y!!As>Z^1DXT-1~P*0LgBklUJxj#P0tN_ zzvMeo{K%_Te)uD0iyD&ZWhnm29P>fyS^h5F?)qgq?l*D8sXE_j;+oIuyuYc@dKU`& z@f&FX{j4?p^0&u4)`2p~5RQ234Ib$cUO$QKzN3P0#OpVBq(?meyHE&6yzS(lufKdQ zlKmtc@yf|>AD-iUT;5Gmr2JqQAK{2sYw$?V?WY%yaKxj0NsoAICwcJ*M?Auj9`kGE z?1O;u!BW3en@WdZ9_?;#u-$=)gPk7>U{UKe>yRh~NPkhoRUE;GJtOx&lCBt=&{(+iR z-t~@rqaLm|^6=9GUCezvFOIh_;oS%CP&2}NO|izT_l(O=Gx9#&+b-w@1@yaHCK~Z* zpY{jg?*{Ka0Kcx2pFi;32gRl$_b+$*Deas*9p~e)F7o)Ti|y z4#FQ?fc7)@3JjcW^eMM{2RI(>2TTht{D3A7^aHMy_sip#Tkz2Lp=c_uA24^SK0-Sw z%Xv;YP%b^^Xt_{cx;y8JT%LWz?V98VY9B)$&&xhTN%AP4#UG7tUVl;ifY7B6%MZ__4Hw8K@`Ze=JxlY6{PWYuj5FCB zTNBUUZCWrsn)P=o&wRi50ipAc`tZ2V+QsA(`9eNXugO0f2kFc>*TkAfz@~!nPnKr! zENCIl0?A@pbvDlgp44;;9 zP$mvoPStrCc02b8?i;iRxSuEz>iSXlV=mcKI1GHJ?|7x z{*nA_D#2;&<@kl|8`?h1{~4n4^Yr?|IJouEFQxvnUBCW@wV2W0biK^Ay0m)rK^SmA zd7=2L&}^B0<3gU7t}?xOO!f`v)8Uzt@C5h-{iVKAe~Cf8)_M7sxeAE)+AJ$><&#gG zy}7aRPtd)r;VQGxd#xG#zhixsr^@Zhod=fd|!GMw4eDq ztKJhaqsm{b@(osL*t545h$LT`kNgeSU$34c0Y1_;9n?o5;y}cKhyxJ^A`V0xh&T{& zAmTv8frtYU2OTpKoD1ynmN?ynlE7 z=L7Kl-xjG_wNTT^?Rm0gG7bd&JlR^o#q(q)4t$<$xjajTU-n@0OVRhCXe#dWWVuoG z5!s1Z%7t>ETxzeir&byC?a96II@Ruhi!Z|8FvYe4dQ?KLkC<;W*I$ zD(~}Tz0Mzt@pD@YOF=ICOm>`W1R&^nGED`~1?bS5<5Oy-S7<&|Tp6IJVVxO;a>zwJ zPiESGQD|aC$kvaKELn8su?z7)S$itgl&(vy{%E|uy*bs83~xsy-i3;D#hDL>{J`^VXqT$5~AooeVJK$f^r{FP|0tXdizIj^2Dd}3Ec z{Z$CsIXKTbuQ|_4uF-nU`L8J)D)YST5ktkI(rwSS(oo^(tc zIL|wsUZ>Ls7?kBa$69@L0Dz`~Z`J6K8&!FK+ZQw+7zdCZlOpOb+x6>jSfj4~HO1tc zk9giL)}Cq$10PaeDE_HzaF};14{6j_uvMP_`I?mBJ)+qH^_Tie{iXduz1DQ_O`lIZ z=F*(CV8>>izeNi9O`m+8O@`HL@q zU;5o$`Q)hwRQ}|j+a5aVe*I0Ki?07#<>fEb&YM}Ozv)xka_z>azH(9J=g#nc)2Cte z$|~tY)nC7U-Mn>QFR$G8#v%Bo(0z|i-}ularyM_T>&NkpqJjI;%Nrh^an}#3zWwim z13&u5O#{DQdglDUANkNg?MMGmbwo*Tm5*^zb|-USpnSg}`kQMR^vC~AALs;!&{Z+* zB&HdU_BVZae(skBg6uT5%NQ_w>NkDxUQ5S$Rcy_$Fm~Vc;rkHz{=*lf3${G?o% zjz7jeQznIkBVNf@bU#VY#nW$fA|Bz0S7Go-k9hv~Arg*w34=#^E}l-YJ;D*M$Ka73 z@%-;YBpmU!7(CJ=UjJU+_Zkw8c!LIy^jy3Lm0GZ$gd<+L(Ff8ap5vUWlEfn%@oEho z=@IYsVsAeQN4)jaKNAzralHK`9Py~Xq({8hi@kV+BOc*MkNN(+-0|UkkK0Xuek*A( zto%mre4yTx7(SB@_yc^x6F*__NtgJ3xe}l7#P2isq|0{w@+CguiND?8Cm4t52k{9{ z{PLU3JTv%g*RLnUCp_^J2A^~}U;X+*e8LmI&)}0T`Bv`J8{!k5_}dMB!o+OXuRp{m zJn_qW&G-#I@%(y3e8LkyVem9YMG{9Xa(KFsSb6}NfUAGXhRq$FfMqg|Xgv%Rmgc8jLZxbzky z?_0g?f?iO7-gnDFNj#p<`-1SJ_jLxba7@Z57s`QhVPlk+&cCuy$A?s_Sii4xzT=e5 zkKWfwj*U(Xx%3Jt&TG!|!8`PP0fXC>n3`Id5&<7{H9OeAQp`>^*q;COALL+ z+s(St*_YouCm!`F5P#b>MxV^})Us#1dDYwSKOB#~{t4Zb>#Gi9{r*>AyWjf6+jDb& zgRYmpw;#LfdwD4b%7vq%yyVj7fb0efba_p6>!t$+{=WF*nLOd`n0%t&8hQAwMHmtw zhni~VW7pIm)@SXq`I14vtJWr$h)nc?q6@SA1%3Ffp~wEs!tJdY$3A$90W%5bYwrU5NohFV2(r0byWC$%eho zH%>GA{*jXVG=0W>cj|oSxAI%xh{t(UaaRETz`MQc**IL^z^@CzJYU#d*Eh<6a@qbL zS}v5A9_Aggp55`NJ7jsUq;s>%+wYZJU?w8o0gAx&jqjCYy{^stg@D%$68rPn zS_-M}K54Ndzi)o;y&rT=d-P-tB@5~Z!t$NB-g2W|n>znqfW z?AJ)3AGWUeDf#nmv*RNLx#0V`+{Yi0Zb>$4D9H*jz5zH!eXmM)74swQHTc*o$h5m? zhw=Ij?K9e6^efS?=J$`GAFmZV&PM4N?td&Ue!ckN06VPWLA@U_9yE4e--ZA?3PgQ@ z^OAU+m+QY1gnyo_lL)+Tx6+r_wPAlT9t3sH95_R8aUZXV)%gZz9Q&O4x_lcJzuW@( z^|JtBYAWu1ytz}&t?kiwX%$#?&!vctAW$uH!G_3)pD zFOM52+F@Hw{2qgy<>%zP5c+%Lj(i{X7tZZP_!-135$OM1V1w@C)l`JCp^-b) zERBv)HRVD%P%fNrl-C$FKWbz#SMUpyi?%Cvzx&oG2g-#EqrBwq#D^W{5}7Z(1M;iV z^{_Wku55*j9fA3Pd2^WX34!(n@+e1r>cCH(h@Y}APFrB?J;zBZ4E1NSCu0pLrkloEcfFa><^ z-}eE`(F}gxqaVG}0PPgoEo_ta4DA!zE4(g9KN8{JkYU1qM7yP=WaFeDyQTDT%_qj4 zn{2tBtST8E*>qrE@&3}`-VeI!Uv?H-J78ghaEi0!{9)&M(U$)@j^B;LkehVLW-v5~VWY5VS zxKDY`apC^R$+AmNy1fX$?6kR0g{_C0iX0M6$c-wYcYaK{P!5y}dqR2Xd~W{8Q-qH= z7yQ5|0?!M`qa5{4c7LQ(;{339Sq?G*wQRxl504VTYz-Dz54pe}NxSe7p_fa~_Y{Am zUQ@cOg4U9JSi4GAlG=mZ^TfAvsvgH3+zyFoA`k@c}Wq_?jt!bxpU;TCD z1B%O>v!@rzb*q6WsW>noe;0mJoqi2Rw2#+hLLV4e{4}S?)3aE!C#gE^Us9bj`46-=w|>B+qbTA)#DR&$fp^KZ z=Y1#EkfYH?92mlZC!bg*-+3(^IJ`f? zPlJ1N^|D1P7RudID^*1LZmjJ_Hy@=U4n!P?IIzcapx7zKNhK4Cig{$o6pbW-vm(~w z#@p@`4@P$-&tm@dIh6KaKN#q57+9&#`NSK1me)P3F|abH*ga?3;Nknp6bH|2;5*i` zZ_Rsd`jX1V#zu9G>W1szE^*cT#>U%_pD*_%%-5HS2dX&kC!aV(${nXn{feA!XNvQz zq~}OnBtH|XB(B1~NIW+th>joq+aV7Jja;sAzQ+rxb1PEf6e=Jrj5o$Qn%WDX092m4 zT{7vFCs(_<{8NSEvqj}kmJIz}Qzae5UoBT+jeU%Ml}j`9r(I|IwbkdBLtok7Psm#r zJ73ZM3*r-=_@ys+{dBQHTbnA20mvI@N0{__=G2Z#!qSCQ?~8SWlsNVUj7lD_@=84>7sou zT);2=yNh2TjHSQwTLK5zz87`fug^d4_Mv+o((Efc*Z+d!oPUA% z_nvW_r4nQOxYt|PzpB<=@ItS#1F}B8GQZ}9i{uP}ch=~$0pbO6D`IhmI_S7pP>^HD zcD(`DerCzrP0pOk{{)u)ED~-=we*p(Ifr$&PCaC(|;hpB~_S@ zRZ>pzx13Kz$&eas6tzK)Te&FuGf|Xgwoc$}fyI=;E3P_4`gq1Gn@CzWz2e zbfcVfyJzUMT_)9`0qx)&PW0D)RnnwoBk3#a%VJ$}c|Gq7>^32j-m$}d0&&O1?iy&S zl`L&En_pUY9p?|_Z>{QlNv{WtF`jNgWPXMq290M~vL!B;!|f*WN@LC5M}DN;AZd>x z8EQ3Udc8UGRJqeq`oil!*IKv+G%z~z)H73UO`tyVz&;K~p{@S3x%@qT!r^oH^WxAB zVT}2v?K8(Ilih&o!apO~~9p?+eLfSQ-HT1a8x{%(~snx3z zvDSEXs?%GZM{aUZzy0{R!1!@SGry(hdw!+$kgr&)?I9MTzqmGsD`WcV7)MZ~ZgU-4 zPt4JYJD1+AmYLES`do+h@H?^k{c~SEw`lJDn?53QCOAC##N{%l^v?^yxzw%pOR4L| zo;ei8E^*fYx704P(^w}i-@NQoPu)k@&$L~4`?621I2Qdu8S0RhG6mxu5Bo=K#@;q` zX;@iUIcYHthCA|s#OCf*7v28aop-4Iy(;l*cg{Xm%2od*{tD8s-Z@*Tx*5 zk=0<`hi%RI4JvlKsGlrlocDG;*Lbe!T;q8bBrB`?Rn!8wbuGu$v1D! z_h^mJmwCg$50>cppD5Mwu3qCgztLq&<__0*&U?F_YdqIw``=T{IWIgulvTG;$Yl7EvKNRqzHGU{paw`Fk zt=~Aa<7JIk^Iz6@74Pabp7R^L4O-(l@9lc7@m$ln#`BsE*M7ge!q)g>{D9&4-C~We zSo#&UR)!5@eed{M<2yHgS@pM~@6(<&e(~?$IPrw*E_>krE}m479sjAtU#mRo?hl=G z<7K1ktNGTCF5mpCjgvNhu5#If;Pu`KN)!%&Rg8e?D?B1VF+i&Cf`+lbKz4O1R z>|*bDxJLM;l=~VTW}o{hhQXcFpV++LLCUiatP?`KWe8h@-GFg(9otnu65@01T`#}D2+ zzSj8uhqOPwoenPjjvd&eKn=O*Z0ms4{Tis z7l*p;x!YWG^^SwgaA3XC(bw5zF#`_g9Xgx()Sb1*v(HigPQ?7aP-o)d~j+ZrF&3{?rRlKX$c+PKd zH)xILytnI@&zE~AfTA68R1{Mk3l3J8mOua z`USzF?Dwy{BKIgDP;YcvKQrYhzo@EKe*l9(*xX|Mj(Omf2#=4Ed;XS*e^uimEw`oz zgkIAYV}RiKw_>MEy*X6lA1H5@0Aqa4U93rbSY=ulyvKwMpZHrv9O7 zECT2wxbHC0dDV|9NtNjes`PqeP&*WD({m0p6!p; zyyraUyx%@Y&wH*1z9~yPU-tVvuEP3=MDsqH_q*G??=kaYSIv92KU(vi^PKa3Yn7h& zTn~Ix)|&TuT$%F`iROJY?{~L(zuwG?T{Z97{%Fm6&U4QDEerL$=X&6qvevxM<7$nM zNHp)GdB3~O`%W`2cGbLR`=d4QInO!oIYqf1FwfXM-=DyuyyJZ4eJ;ecZyk`fpH#gw z17|Vcc?>WJgv~7;ZGZln$e%BApe(dR#`E7qjouHXk3M~3uY>hywEX#OztDMq#v;e* zl?m8y#`7-eezy6D5uUN=jQGf3f1-Ibd^>oTO>fok^AdEF&Ip_%zaXAVO(v98At^6% zP+@Pm7UvDb$5lG;0oSVtts&WGxh5meLj(uFc;6Qm3>Q?ISentRpz2H+uj>$=dQfH{ z7-JMOoas(~7P_E^S0dYR9BZc0C=qcW;y}cKhyxJ^A`V0xh&T{&AmTv8frtYU2O- zfA&(9C!Nk8F81VE9u{x;frjr{GW`2hh~L-h@I z&>xAcK%cVmQ)kK-NDB1v%?TB$Ke_}-_+!xq*E5u%me=Q0y||{i-rOyfYQY2G7zVC~ zW7tGQdK5SS{pb}slozhfLZ7NHh;RJ2gOA*Vc;C#r$13EyzmHY>5#8K40R8xa zfKpz#yO`^+da}(q%t5Tz!oyUoSJlHTds3I{Z!;aHzD=O7@*SqG_7NWS+E_eH#aags zQ{SW_JnGr5BvqXweV`t5zoQ<{1kf;H#mT9bGQ4j5h>yhE+Vj7}ny-C3Ojn|+G2{UB zV?gLrULTS)><8!)^bh(A9Yfk)`%n%T=q6#11{~n2v(QVd_rRShKhyyp<@h#-)>%nN zz_)q;2Y3XeK@YTm2Yi$P4*2+?4m3a$uta5iGLv<0Z{;&~8CL_q0&{`JwU{EB=Fbh0q>O9-Wu%ym4R*g^Y#c;685a z6!vb|7YtZGu{I73h50M&^$h*t`v7PcaJ`{jFtq*AE#Z1Nx>O@-qs;;6$MZsz@`Aqt zI_nQRE-rF@)O^s~r{1&Xqz`{)=De#u{CLH6_Z2zccy8~xr=9#S8&P(0<@I+}eH+^6 zIDf3yW$*mX<@ass*JUdXz5c;9|Fdk~@9ul-$*0fKWltq%&N=Ss_s*Mr$A6zcwOE(E zy3gC@fZn$r`1$ht4ZZ#D8#rmn*G``I#(&(ua-WJKr@nswxi5XL=YgN>y<*;7OU|5H znJ994mrkF1$kyjhI_$Lt^Y&Zy+&Sl#6*)Ic*&EOQ<-wWFHS^}4_Vm}UoL!W$mAQ9u zPQcb4%aE&WFqVCYXlLgD=7gw@LwUj1fi)a9khYm;DZ5v%_p{VFOzX}pb#Bw&V4S7S zbxZ>f=Q(_d7e#W^D<#^8r z(n0$i7jRjQGWHW`eFm77nOEGqIj_dr_mZ!zE?thoF5m#>RktV-_=t)?6?@_^Smt>+8&G~_{#a}IL@Kjc9RG;uaS zU-p+D;OTq8m!VOP7&w3fJm)p+I?_NHZ~>24&lQ~pUCg7m$Pe(q1KfV{LpfsPIY#si z<%l_Eqz^LXsKa={H_lg-p&oGH7wS<)SiqqTw2yw!M&#Ln^LDI#NB%RnbR`PokOR<< z0qGaz1>X_$76G~i%|pyIbeC!98Pk|EOk*A~jXB9Q^pR=oxlF&qO25-eA8Mr!x6<#m z(zC7f5muT$EBdIo7V(=s^koT(CxrQ|@_Ew|=3c&G@R;9W>B)rtn_M3f3QNA?&1V2Z z5`ACN@clix;jRCo3s=awe`nx=zgT;Nd{#Zz>T%fp0E_JWcu8{{d$P}}=c_~IF;@I9 zRL;Z6WBc_xZyexHA!FelymPciGV%;d(=R#NW@+&T~B+ZMqS?(d7X2 z13oLtYdD`3T82OABjQh5y5!bnXBb};{8K2qc*%kH|KPht&S%z^Y_gc56$eA;1+NNp0KSK?r@GPa=x~7`lg5aZmsy$50}q7^SdkF z`dXuEIG#Va2>`>pTR?cVZ_zdU&4r8V>Z$gO<;Vdl%<~wvSX- z$K+40w!xS*9udu%1DF${b`Is0i_Z%75&ceDkG%dX*zvI6^YK~X%t@L!XZrnDFktnb zGfSPLaV7-}&-=t>yF3S@9BFL;YoC~%=2+0aO_Sq741CZ54C!;P;oi-8HP$|>d~J2r z_2|z|=K%DhTjmwzW&5n4XV6=oS)pUdqa3R^bPT#iUlQt24mkYaqk-NcMxH(_Nvd+h z)PLXsA36`;7Ru@C!uc6<3TJYZqaJYdQ6WYiKlF!vL)(A{9`KPypAjPuIKab)gmT23 zJE*gLV#t#Q=z<4;MV~Q#q;VEQIb!75C;Gl%cY+V#C-49Rc+>-yegeR8-tz3gc{|oV zEB~2Wx)OzP$N}ibfb@&<+S7bi^ik1g#cz<(m*p2pn9mA!LaqUGJl{~V|9@cWWr#kbF}kZ z4@aABL~nFC0R4c^it-xHXEpukBj>K2Hf2t_5aEh&3`>3ItG8{es3zV8NI_6Otdy5ZXwZ20^# zUG`7o7rXY`>lWWFWncW{)VUQ)-=ch5hs=HRl$Tc)Ij?@CWbTRQYQNZz-}B{flzybh zxpBj+xkoJ4Z9ISCyU)5<+GxD;pt)cC+4mlVPp$Q=(|><|t$Uvp_b$!}*!W`^a>R+HC=*qryn=jIQmxK@^b2X-@%pK-AK;uw9}#^!z{MGoxHwZH4I4}EAv&!M zRPB#qIq+}}20ZFXA8FDDJ;I|cmIIG8K?m)D4*JeCa5)y>l0M2v6KVDzG3j%!;oi-8 zHP$|>d~J2`pvn+`3F6x?+pDx+wc{k96!L(=L0y0Y&Y>Tm0eJeX0E0fEf8-J1QBT^y!I=l;^tmAoJm7QQ^6bEQ zJJvoc|Cw955`}Td0qDno^o#P^(|lI+QPF3`?`_kUU>a-!)^;Kvh(95 z&2j9>KC8}0hRS2C_+O};hm*&ahj!jLz@I|K!g0U`@Q0n{v$EGS^oQRNqdmg)hW3cR zpQD}UdN|s2BYLCD0q6&OR+QIpKC2xExPGUlOHN(BkNAX8M*q|)OP;>>58|Kt{!`_f zHcYNlKC2h+`L}P!#g7Fz`l7m)HZA^!_@ch|_ro?_GUHt3$4Y&B*@{m-SmbmT9kgl2 zogY03KBnf|FFo+mvo$V#TkT6*H(VjOFaKumP4B7H_jjH2%Z|Q2@mc-7qGVI+6K_?% zE$68RR{m~Pk#qOS2W@J8{1?h+bw%H^zkcLQ*Js7Oi*rJs)kl}VHnm)B0~;qw?|cqm zPL#uI+mQ z9qK<~j z{}pIpe12aR%79BB6vsl}9ol5u;3N8r{vnNW#K>bj96RSN&kmfoW9_r@pSh(=Q5c6D zfPM@}zbLOg&1Xd)6@6A)pV4Pe`m+2Y3G`X{fwJT=kMj+kx9Imq6R*Vdllj{J)cs~Y zTRixLhA;U^Zg^XN=)#SaPhqs^a-9tFS#5t(kHc;Yyt4D-CCzc{$v&&?|20$|W5xeM zjp6lUg(~anjE(f3= z@L5q_!}+Yf^wOeDmCkSGw3V!wyXMZfFFAEyk@K_ZQ|4Z?_>fH~oBF}>dp;|EqEnJ5 z&n4VI?F}pD9#!PLRPw=1hadB&jevXk&aQ`ky12+Gd98a+!>!9Vz2)#%PMkJ#@t4!` z?yA2pJ!|7Ni#j&m|Cj6UdGVzqUc2^^B4?jxZkh9iS57}NdB6?#eDCNx%1^tx$hrD| z_uF*zKYupolUA=9;U%Ngl?p>S{u;<4z~8scI@1&1DlP1zE z2Ois{Zvb?7?nN3fq{+R8dpGCRSo^H3>fPQp~5>j5a&k8yR9ivYOx(eNb z&j#hFM;Y`JItg7zIqCt2vx(MK4MX1%bQ8J_I}9{X4jS-jp`5-R_@+<~IFy4H+QSd} z4mi-_{ZycVI{1E2ju?610iW{%G4k}OffnEqg9ZX{;EO{!eR3ENaCx5gzDZs|%C#vuow9|O`a%4<*a zS1ASKV4))^-kVA~MBHvKE^$ASfOz8Z*>qA1}mfv~v8NiT4;@29! z^EbKS)%?(!@kQPAFHc?ny!eTVbdXS zyWt<-DstfO0`9+8rsf`h_p={<`p4p*`q<%fzdlLdXLVE6{~iC)3yPdKU!60z^U9xY z{NY#cn|ssg=Wh7^!XoFJpMKvaXWOajzO8NFzGrKnz}isdg_o@6W$@pR{}C%|~zg*AM;g#&_Is``p&MZ~uDFdtILu_b$!}*!E)? za>R+HD3e8$@(S`<@hnPTkTxc@Ur6hb*O!HJr9PwTd#-SP1TM;Oex&~g z=Sb2dJl1ox$8yj@8tsq{%18%&(R)$&Glpn~xS&s5w8=i8O^yp`!lNyY5i$G5y@q=? z=hayItn#(hrOQ#+1ss5Wbc?c4UbfE)b`tc8J|yZDeNm``o`1@_N*aqvZ<9A_DfAAAEIc>~`T(%=i~0S9>c<}eo21CH~S zX9v#PvG!T{&)m|LD2zi6KtBegUzFFL;j|(Ax~LQrV@qaf6@IB%Q^_A;Ig7(tPpnaeh;kMRC%HJZF4WI`GUtcieC`^BM>;ZKrMX0KOL zk_p`lq%QQw^9J|N+oU}-i5~*&WjCM=grTt>9@^3M`#<(CGO8+FKE1p z^4FG?op#3$x#0RB`F5)a#8sgT|L48y(zQk=Rh848xkdB{f%T3<`;GP*?YF)+w7o>T zPUE?Mt5;SxrB*vf9d)!@mS<`bbtns->i^c)BKu9tjk5FW#c=t^esg(e^C_2f7VV6x zBMw9yn4la`){n8@+}#(<7|wo^YO^P6U!q|i%7(Sy4!-;GdG^n&X`!~8)Gwg@#{DzM zesgU&tcM6gW54~jZO6r%kF4AA0OGdTjt3IPUeNdx{cqU5;_`*|8~GMyzddtHtC2}n z^JV8LH3(V&0d#L>gN6So8SLdYU~A<)sRizhQfd%NN>j$H8Z!Rxv zJ*Ui2%XH*_i|&7OwIxbL9EdouCvm`Y{S=Q=WJ0djPc5Y3>^Ehr6=J_}{|vI^D~zAOTxPvgITHo0nfU@3N)A+bBdFh&T{&z|R4X{pP96)qcaXy(Wa(Z@ueQ zNL^w6H}0Q7_M3Z85Y|G3p>a0dd*H3HSKYr}DV1F}Z2L3P|`QIY{n}6m+`G^A%2lfmO;7u&Ne(D|3 zaQ54=#~y3!B-|66v7SQhH=)dHrOJ-;wv^lbZ`?nF>^GO*P`gdnbyxcBH~;-_TaVED zvrB6tr`-MDwgqgC(0(J|!tA$P?|-AcM*D5c2emwC*V%0&E%sYmJeDrRfXmDOHhBE_ zvEN)?*!oVHp_b{$ev9lkS6iY~#DRzddlCmM|Jz>L!r|zKv)^QY5PM7qWdZ7BR{O1x z>!;j5{q`Gt5pK`z{S2LQ^M3p7#n^v5bj+t(E1&)A#ha&n_p2M%8+$zuFcCE9g%+elZhTo`Lx8*g!r!rPKZ6!P-F z^;Jgpo2v`px2+@D^3nBEFTZTwWlN7pwzy`b?X`roiU#pMg_H}Wmae#_PWMthC+Tlp#4 zUZP#+99-1PZ@i!vV!yS;*5UmjBYpu~amI7(4l5|7bg6d9__5!j>!+@mvc2~>^1r#f zic%2=A`a|H95@7nQO}<`lg;O1%^GMew!TwlsAW33ej3?tuC_#}hyxJ^_9PBi*H3*PU>M$hb29cDzC&h0 zR{IV6ig|B{eLviS;e2rL^K^^Df%|8W{pR}M?EMVAa`S%wo8NxxG4=unGqGcL|F>-c zn`>iR~-X3rHz=Bjuds{5sp0^Q~m;Kg%Ze+i? zx&R5-I+86PT|f2m%jR9SGe*oGC71Hv5e}x6HE-8a223-?)E{ zmHjrjM(@w=a3*ppY)^4{Li>$;E7X3Yy+-?O`~TDOpk3#-tW(u1m$WpB2QDs`P*t3_ z`_0MA|5n->*>A250vXskk}V(EZ(e@cyvvr>`X2p_I1q6l;((U}h5O&!XFr`R_FI+I z^M~hGGryd!pK|{kEBmd_*b83%Ow?T1p5pR@_8a+DsQpHJjrLp5ziE4kcAeX@PF1g5 z7VC<)SVFs-1qmo?IV?&|Bd_SSlMs2#$NFDZKCGF_7s;NwBN|LLhU!&YqZ~LF4guD?K-z* zof7*kxh5g^zd6VIt8&ff_5P5~Pet~dYlDErwvJ@WNA{bSUpDWurE^v12rlA4#DR&$ zfl+vWh-$4!uhD)Ryi(gswCmiKb*g&h@>qJUzcjCWUiMr06}#4c=^( z%XQwp*MarBCN7dUeUC-h)88M`x3b<{VaI}j5zUAL5eIft4#5A`UC{UI4{}GY>^Ei) zl>~pf%=N$VJ-)`C%jx#*OLi>$;3$x#HeSZk;HQH}|J=$KPUFWu}Q)0g*JDr5TIG=o8_S@ELcdh-_ZALae z>^F4A){$)a$p7Z$m(9CuX(RY3iZ~E)AmV_B10(aldB2~PAvmV~H}0Q7_FJY00d||N z8~Xk?zyB>^>;;$BL{5e6DK1ZFzmacY_FJz0H`;5o-)e8x_7d$nw`H9Y`>ms?J=xmS z<*&&(pO^i%zBjVpTpI*Dwsj<1KC<7u{IYqMEuFJIM}QFrA`VO_4vfrxbFazB`+Hr7 zz?j-^+&{<4ek(Qh!h{lk=wQS46c>T^8~IkK{YHC@_FKs}wY@~U&TUzzs#mV)XjoIo z=TGx{{2NkvxZ**Yl^_?~Cj=*9L(MY#qs#kL))u zzii%ROKW|P{ze>#I1q8b%Ynk}H`o2q@KUbyF*~p<#hiW_s_Ai-#U%G;N{Om z&4ukLE`48*dpXb6dyv7fwqxCDVzK7;c76UiMqhrpSJC zZ4hwK){$)a$bR$k%jR9Sw9(cmiZ~E)AmV_B10MU$eGEWghI@anR2x5+%yP zz+=C8s&cj80B1rL|C?T?Mryxt{~Rm(ZR-}jKXWh>I}Y1ZT&~c5Bi{ zEf3mteNX<>a`nRhwyM6PskMD!TWp=%tGrT^-0SYc;;FOB;7=m^&9y3Emz2RH$ym(msj4C4zL>!oq94Op=vz&IJ_FM0|6;fB&`$M>Y2H9`!#*VcR zVQ8G~{u&9frtY^ z9GHPZ^Zqw){c!#_cTbS#Po0bxBh-Eq%6xV~*>T>Ma=ZVH`)82-=F;POH#GL!Z~pg( zR2X}~r8SXL_FinKU7pZ>Bj3X8w_M*JLVJz&Tlq`cUZP#+wyaaI-%_deop%3Q?Th2b zesg(Y>pA6wTBalW%~_X>H~WqIXOR8o_5tf7!qC`nzu~>T_VcIPf2a3n zjX%-2E!XEyX|K_K+xllM588EZ%Q_|YTT5(hysRdbT05e<-<GB-0U~*pJQde^%#4By_(o@*q-8Yh4vfyR;c|(dyV$n`hRMBiFTda zvQCNpmTJW3Pmemj zp5k{a-DbYbzuEy#NIZL^V%o=d}P0Q`IC%yOU=+T;;9k5O zQ~Qnk=UCZqgT;D(_AzLJX2bRummRd<$hSi6H`;5o-?s0o0}%%_2R#0_5}PZ-T|X`K`==xMem(ck zAp6brNx<$v7#jQiZ~pt=`i#Ax@hAG<-0e5=EzEw)_5L^7YqZ~b-m2{-+I4=3i2au6 zXkI2vSzq!1y^_((8Ez{BS3(@lnuC_#}hyxJ^_9PCt_rGcT#vR*m z_M1Q%JIQgB2T!AA^S>2z{~PzuAp6aA0owZ+I_2iG*>APRUeH6C=zrb)-?jy8uF(HR zz7=Y}(O#qd#}yt3bu}9%SYEwz5KFymn}_=kK%{} z5eFg;*c@=}Hz{>5%SdK;`weT34*N5a_4!lv%`Cw~Y=_+Lf8+i+R`y#-ncko6o=x0z z*q-8Yg!UWxHd6a-*(%4`BAQoY_3mCOxTTtCl5O;;Y)bn&O`Fd@{MTqv?Sk zRaFMQvbbFL5qa(V-BRsox9X6^b{=pV*PS>1dON>6r^^r1^N2C@Bq0N0zAQw(t76Tq zP05xuBON=Qmxqny`r^yxqh#TV`A6USp(3Z|nIGv-#Yh=su}Ugd%wN9fU#C0H?3Q?E zyED7BEqS%Q?j5XnRjMLuL8h6rieX-~Dsnvjq_ ztV=dXi^8?g+oy3x^-6kbGukUCBpJz9;B?VJu zbE0lhuofcH59sPHYdpgEe)x<)g6tFN?>d%p-9!I znp>d+PP1w>jqau6@wHAvd#A7T=FnT-T6lY`{T!wj}CA8w_M)vK^d1=YygH z>H4?~y|GP3+tQ|EX|J&{9dCEiQY@+(uS+&dhq~&U9C@EWb4OEqvM$-u5bt!FVqGF; zjKG;)AFEFY4_y^>X2)8R%_5{W2uk4F(&vcQ>118HDb+6c>GnFiAe|D9##OoMlGENA zTN78aRK&MhT6H?x;;l{>{)vFN56 z)8`y3i<4*#;x^%%;HvJauAtQ>r&YJ8BQ)6pWo}jdbk-%3^@+MvN4u;K&g!;~bfQk` zbbn=mbXGf}i}A)fnfVxAW2_#F03xA+NVKRG@w!->iUmm6SC69RWSas}EYPs>UKFVy zK)gBGj(j54)_}MzCX2Mjku{|yt(uE9uST8FCAcJIdaFuFDo8*yh_WM=$ZtPQ)5g>ri!3yrn}?mV^|wpbYDW0u$vFVaW=lB#%8nEm5;Eon#qVExXQn zj%3=;Iqp39@1$0%%(3Swc`Kv~MT7OcZ%MVwbdx1#b-Ya$BdwLP^2cQL!8}rHLZfV0 zGI{G1E;DI)m{iuUv~a#5DchE?Q`QYL)ue}Nqm;F{L9NQ^E=kItIyIr|v;w78d$M|O zt!r)(dES)s19*Y6%QZP`>Otai& z27%dX%2ZEf$E{DThB;uyjLj!5%S$@d1afNgZ#A5d)wj;9?y{3%!ALi!WT(~D=(|qU zfdztDr&c*JdSrP^whyA?nI=%~)(vDVmWo{s8Z1>GkG06WRNI%Cc4~NvHL^di z?r4&Em|T+(yi|)Qw=B}>m{iC{m}+s9TCY*Mgg;^rh^i~x<~4OSj{Iqg)pxYS+C*WI zOVziF>5^7Sy>v_Anwad(SpMr`&8ZHtE?Ux90<<<=*iyIdXa|3fQGbtBe~-i8=6I)= zOS0|>YBLg;elV8Q2rP-Zg<6!VUL}u#R_hf?j3Q;7)k{JdXGkbhO_zw(fYnTm(1|r- zZ^sHBmwgzEJYv~b#42i2J6TI?byLg{Ef&GdZjqHw>tMV^tix8Zx-OKT%sHvAL#=Gu zsd}?&B68=Nm=n676Oqy+HE%K6l$a9d>1kXi{BKXSnT#4Sc21B|i@jJZ*l-)x!NzG= zw?_SyjaJf7CD~is)^sT;h*qccBt=5CB}<~{nj;I@(f9+6?hw(dDJ(l$EbU!ZgMG>rAiB(>f-#P`$L>E?MRdi7% zrDuZ}rLj6$>qPcCiHV&_b-BrloLGZwcy*?Sq$jE*c8kn4wOnGyQ9Tfr;n66RCSpyg zbi3^3>5i7Vxb(eVh$sVnZI@z^$|O>4$&19))-y&eWohAv@E2%ysbm#1R*M~Nb_ki| zO=_Y67K=hl8nY(W-du-?m~3D!*((N71x_bandZt%bk>hd7U~d-IoO84oNv&;ll7t}-L+u1?4%nyA zRoNfYX)F?MZ)MSIY!cR?l+~aQHB}p@L1CE-&JshMCMGPNy84cG*-FIb>1q}^wuyNu zf&zDqghYJWGJ_yZp-4q<8)_NuP(31=)0`Hr2}OxrIY`FHQrl2^Vh9)Gbs}{+6zLUF zCT_ef8EZ0ai|rv3PX5Y-lfSE#6@ou&@MpCn=0qF*sMH#yz!;foVow1|aso2F<;u4zZEzyPOMCP0kv1Dv;5&#GB;s1B*G6u1jWepwAjfqeicA z?VX~H=!qma(=lDlcFvS+tuYu(I3~ym34f1q*2r8*t44JSFqp}8ZiSUatvxFhqNhMX zv?S9hi-6iM)VM^Z?J0$%<*ODEEP8cKYVA8l|COB7h}cCvVsaY7AxUgJnM1Jn)MQlk zdX4H>?Ut-g$oac7faqG)$XiIITNbAmB~!8ngR+QKsuMH zl(tjruqYg>@MNN7AdyyZv$e~ku`Q|BgvJC{2&XZjw$aWmRp~Tz$pHi#Sz0tpn}=95 zkTdHCl5sUjkkZBjQb~wHgQ+D?lEP6Y<-jc)8|twVtAyetO0buSy(G*P{W7Z@_lQ(W zQh>8V8vBVXX1Vrp)vuTo$m<<6zJ?zo*s){Bj=lGLy|$~r&-eSxyyu(*{Qt9g&O7a$KF>UD<_!jOiCW|#Gm@lk zFqj1yh>4;>(YgbCae)%z`5}Q>Rg%C7B?zbm*82+2nm6HEjBQl zllsTl62jl_6skFLqt*i1rsXEp*FKn8S~>H!XNi zT2qVhSVCC9JY9^(k|h|6{)Ix?3lqW1@mxv}whKnZb4Yf~8x$WRr@7|nN`mZ~Ny}+6 z&9GI{VF*xSU|0>a5*R2vdMsRxu_YK>28QUlaIufIW`a1^`xan$GAu~RpP6Pmp~-dY z^!zj=&`^k*Fr4sv@z9T-PPy9 zR9+18lloXmP*KbDUTn&IfKEc3smU0;mDYIL2k5ORpLr&f$24cmLsC;;R>vV!S>Q+0 zXk5!+e0aJ!wa>gj|B^%ELC4wK%+Cgng@z_tqlK(t#1G{K=hTv{$xnKLRkl{W!E;@H zt`$RXaX}8R{7j;CL0qVwk~~b$wx;&+fbsKls?|aeIIYJblf({9_5NuJfWey<`_3~z zrrn?Y(_@IvkSt}NUtl#utcpl=>+6jLdzQ=`h7fezZi!=t)0BT{ue0Lma(L#N;&K&v zx{h>-$StsyCkm4RIo@dC3naRu%_RwTd4QVOY1lAKK6)U8&-s*3Af;oaSIwg&TaA^dhlO3s%7qmnstbzW~Wer*m9BFCY&-hoh zjybZF$ahHvj;CgtKX2VV?+Kc%Yg+Rv({L8C1!9J@reB`IXwWm?c#evId!` z$5A~Xd7I@la;f)tXdvKsluLeq!^QV8b66Vie`Cv2OH;IEVoXnFiync;%^*{yvu|2T1ng~eL!u191i` ztd^K0pF%Jf%^H(5$GeCnHPXI}Eo}f{Gl9r;Vr;?qHuNgZ8LxI$k;>O7_Iv7rs#$z7 zi^)#|HG)`ra!1VB{&~iN9H8agqs1KpFY`HRcEL|lpmADZh4I^(VyfjuSC6pD*NzaT zjipS_$J)gaA!;L1>3BHP#?oX+I(Th#I*mYXCaIf(JJRb6jvG^iY!htYCRF+*4zGl7 z)KvbMve`4j_>a(cyf0^9bVx&GL2>(LI^V_{wap1!2JR6QB3Y=CeX&idG)NbrTL!>| z2c|5AQ}7xGk1x)Q81G5^XtWqxjSyt)Hg>6tq&#YxyNo4Xul$GuM^L9^{gFiJ3(Vgn z{5J28%F0DP4roGgG3evcU&O3IX|cGn+Y=~f(OzVG$Hry{Az5JQ*^2iXNriLAESOh| zXPbFDxz-CO+n6aK~BmO<3RTwUL=E-Q;Z}eMcNn(jEV{Qjo89Y1^PjTNK>}5u@ z4lZhqNFHHo4P|6~84)B3f~7GC_U6P4`lN;MwsDYSgNGQIY|R$I2uw)Din_PYaQ2>R}TksR%)=r$p zOgShZoZcNHFtCie1Z__l@u-pv8(6`j7fm)=Wf>aWI=C0Ex?q?x%hAv?#IT;rY&+&a z{eatyK+!&nwyl7z#Jz0(g)JQ36DD*yjV`9qr39tiPqRd`Hc@AhrHLORhw~|<(;5_198CL6?h2vKgU&I9&}xvt01FAEha(mj zjAs3VP`?NdZ^_{(6y+#eltYTZ0{?m@gu^=Aa+++^3*l-t+B>VO+@^FS)esw;_g$+F zTgbtvnt2`5PV|y?N4wpBcA?M|w=^>qDjf8e_Osy1bE!FRCsNDoSe&I(NBKp*%YzZr zL&zI^Bw3iGT@$F*m~>5KqoUqog3gt=X?9(9MYtg{o!H;=kp!i7?pduSRkL!pBgdEAr?oz-5#FegEl1kRFug(>;AH%J`o zdB^AlAviP^$m1cQHB}bo$WUq*T7=L^q4NmNM;0{IB{6nq6~{Vone{rFI1~LDM&5=!6fTx+zo{_RgL0>qBok*JG3lCy_=v2BWFI^TATBCmYKX*l=HM*}7 z+RsL9;1n=^fx;asHVh(J*}P-#XO+r^XLQgwNQ>6qP0bnXdsO@&4E%O=?+AL0*0ebJ z=x#;}ON-_V8)i5W*qMNt9l=(L6-K?Ln)E+a6g@QR+6DIP3~4u5%0$s9#=oKZn`#9! zLw1?8CL}~8vP+@sWly9RRhd*Me4C>(PLUy&yRx7`M$keN zvj^7yOQ8dI>Md6*UM29QVn%1AreOJR75x>ehRxXLyIAo-g&n+{quc1?s($`QgFqA#x?ZE;Y46Y(#W7SI zyXr$bx9!fc9qysFd(VbVY46}pU~}5L4foDnY44s5_;GLFo%U|nLI7D)fPU8VQ=v`a zDX`GuH1;+0H&zH$y_T_%5u#_*Q0vKsm7xqVh4dm|dLHuySw_kcA`q$Sy-$c%9o@6J z4rZBmPitn-siV!|nA3B6L)I`mxo^HXBHf`jfQi;H_DC*H&PdAIkw=TnPu7s1qI-fc zD5VWC;}zu+#~1hS-)FrI3gO6;aTg}G>7;5mstpCM5dNJVie`h{GDonKrr(|R4{^UU9#@Ty*V?BA(#jthNsL~tKgv*3yY2_Wm;=; zid~eaou<5thtjfb44bv0`^Trj0q{M;AbTmR>cgW;qUT0iMm{E(nDjzKEBp3)iDBf# zW+)%8O&LW_EH>e_MKW&}mJMNGX9zS1G7GqjJ(i+XUMH`78&Sj0h!fRBQuSo{H)Jwe zu8rU;ahVY!mqNUjcZ4C$giwgOd)L@F)QdK@J!4ZV`MEDY_rp8RO>DR1TO#j)0eJs8 z%er^AZG{>Qm!oRnWFwGEw8p03EG@%36FztZyF;m)!3kwg?XWWticaQe%o|G*x)XMV=9HS+ z6RlRp;~KwRqBXE?Fu?|&GY3V44FEq4ndZ&uXF@;d|BFEe4he>lG=Pn@!%ekpYE?EN z6Av_CptX|A#azP$v_^#Rn76y=fsBDR&Oo$64m7pEsEgL+1ei(NkdlZ)!AZD$c0zi( z&de-7GYNow51IjHTgXQlFx;p$`9*`uuh)efg)2L8WAu)GUBz! za|@~kXnr`_GsgC9(&oPrl#h0Exy=93<$-+*WAi)5=7x;#iOTDId8-)wsWD__@e-D& zGF~3Bs3vUlM@FMaC{k8cEW!(6DZ5hH>l)cL1YLrZu2jHb?Ap8%1$!6=ZO$BT!s4{% z+AlCs4#pVy2%*}&5wvX*IPdG#US~G@Zj^%B8ey5Pmw!tA1p-&NI zyZpP^zXJ%opx%(GlW0Y4O#A#Rw#g1{fQX%(lZEi0cCb>Q-BGqwto#r@RYo#MN z?hPlzl%(K2&uEtker=`_zQVrr*kL)F+AJ#=D( zPK40L2YEsZBV=1g`sifn5)|r;zn&fvIUvpuZObJKrIH3*4CAjr(1Y!8P_Ja+M&N)& z37ur1(~iIbTlAUFU1$K}_?r%jl@`?zp};OhKM46tz%xo=(FYEJng}BY*N6JLE;_IlSA=J>GYX#@n*cSi zRmH9qKA9ufFSeG=XU-Ng*lrFtr=kU(qMZTc9T^Ghn9ip;f_#NEd{~%9gOQ z8XYtB?Q~XUXfz>m72Mv-m>=YIU?`Fp<`M@&W+k_mN)CA!!`$|;7unbc$pv_jvrrZK zsWe4uqHvti*cfU_2t@=888gJh4D>FcRl}5k<&u6Smx&af!H^7OZcO|>4pf73S&8M1 z*DjsFlU*|1;ZX{^C$9rZkDO5Q=-4Qvuq<*WO%>^5vCY=hi{TBrB)0_;1w~q+xifQ9 z=nxB6QADy9HBr!i#ObGEt|O`wIrUQXo{&uH=RkwH(jKWDLK?6*1Gz7A671~r{Ix7? zj>V>qiPL6C4`S@yn$Stnt;G=)uY3|7t92Y(nRh1aK}b33o*PU?HBI;g%r%xJNFk2R z$wf0sW!lbwvzalIm;xFc(-t!7$S3(g$txJwIu78q^?1J4Jn(GPFAo5XL-LJ%IdK=DO>c>qpih8 zh{$5j8aE7M%5TG^Y}*E!z#5HRX(Z^h#ii=mF$Hsqtd~(9O;p%Avm(?qfp%x4STkc1Q`Po2d zUEvib>3n^TRVJIHu-+;|6&Y1=x!A06Js?u(!Hh#!bRpIvv8W&xV{S$EG1)j@46o}B zi>|cpD-M-9)IE(YA~F{wg$|NoHLb%M!%A+Lo{>py72V#vnxOa&%v}n34l3q|s*T+h zu7agMD|x^Pf$k){lwdzH7Q$|aX;X|1zj84IsIIc%=KM@K+iI7D%aPn(=DHEAJ)UTG z#Q=3pS9>C{G=9}A4qX+yL}#G+G|gYs9Y_(TfUY$CfH3RQ&S3NqGZ0FTAXIg|I)yF@H%Dy)8=M;!{#0k!21mv(2o>j7PoNJMtbS z%z5D=gkLCHVsGrna9d_~>Qi$L{rs|D$fn1NnAn>2?!t1h0$f-I$3_q+Rt^Xuy~Lv) zN5;blAB2O&0yYK=LDk8!B9)?FG6jgAIc(*NZk-tb*8n?(+{tnP1{g_Km#5Cgf&{4@ zHn-Slhha2He%Vhh<5i8PIGjNkmeJvfpjBd1tb;>YGHQP1LMqH%3hbptR@t5) z*f}<54^-W1stYfUUFc)F5&)F_vE$9Q&NjLn{V$W+r&JKpVEBP~n8<^$_ftr>uWh2h zE`;$|Nhx1DF2C1mv?7!di64GcsNs6HH_YK%?VH0LAqi#2R>#fuBy{uXv**bJ$@ z2!Q>owutw3_m~M6TZwfa_TL1H&{$X&VPtG%wGsA;yj04XihLY~BBME~NZvtd9i}5J zk!%=jS2i9Ae!;83lQHN{6`2`QIb#-DiP}J5#UgZ5vRk$CYg!Se{Jb=Dg@ViqwU7`D z+m6e$vlogg#_3W^&}@V%CIB-JDPmAn&DM4E zihDv-9rIkau5kcBPWR(NRGjex|I=9x9OkpibEZL&cF5qr9f0T%okbNdZ%(sc+@7ON zeL&{OqKGk(CIs{oY>e!hs2$o+){yCcv=G!66A57%23a^pkLHYL30^;$d*1&1s4q5I zz|2h!G3)6Ra>%NaU1fsfIL(Z1{K*`swh;jDS}FXY0pZEV+e;ryq+S*$?xQ zb7!W2?ewcI6CH@s0&~6C>&24i5RQK&EL%0S+EAR@S?74US*FT~6NYForD>d)g!7#J#IphOFS1^V7SiGDlASArXk|SKu&~IOs_mU7&CZ(TA{4;U(09703IrnNC#2Gucj>e2|SPuc0CDUfX>XTAH z#lUDa=wsigewN198LzV6#WFA`h(*DaxdU#mgI_#6b(x(s|Hd_IZ*4QkgS9vx>$heQe=HHj*n|tmu2ceD72=D3J||A zy&J}fUhY=#QpVK)SLrO7PZFW|o?2wv(Ybu|{tQSSeWo8YLh%QqrCoP%dZtvqK03?h zrFj-A`aA~1BlN8LuYWd7*6e_Sm!$QP$j~E)zsfrG}n^74xXy$l( z&=hITE`$!sw^T&{oJ-VKMg%0lk^{*JhovPaVFoXV_HgGL&4-<=iEd|Q<4o{C94Nu~ z5M(BVVG~gK9K=>urB=w9 z4lIpHUsN7F$HXGyCQAafVxZpQ>>eZmDt{l(js+ZU?^7sqNA~LEUw#^qsrrRfC0wIG zW*w%O&|KXCnHS64cHx|5L#*}J(c_J&ae9JlsfsX|djJq!a8`6iniB-wIOcsUQ{E7hJL614#{Z(UeBz;UK#5w0 z$3pZ;Yi&u2)U(8SzQmDY&ai`iG=FqEPv|X>VQ`^HzoLM&Oh2>kEc*

Zt_z<`KkMz+#YIUOrNa)YfDhMWH6-;~r$2DGC=0EbSk&@`rV|B{ zs9rj7Uvca&4$pK&d5%mr-OU~vXnbwY>h|om|CTj4m9Hu$HD=k zaa6Qo%CjRw1#_dG+fMIutB2nMe>=~1h=qmiFu!-5VU(z3Auy6Fx3C=$;Xu*~>aQ<~3{oQdmWq#&wQ95@ zj{ZC#wL+>lOllC|T}&AU^NCJl%=u@p$oGy|%;5qvT3!+yN=LM1ZayLx(;;V~f)B`7 zK?mgR>UHPuRARI`$|!HfQM@Q;lq)hQ3$&$#_+UUg0@x}STocaQgZ7U+LAbDdL1!U-q#TqMRZ35AD@d2Pe%e!E<$&->b^}-sY-}d zYTW_YOLru&*0D1nvjH7R=;=Hh@Y=>$c}oEitGuQ=ED{@>CWfTOw zhbElf8^S4>QcmFRj!>Vn52vr&2&dOwIK7dJu4S@eVAF1YJ1kRIX`XurS zSqc1vgS97IM{2eBI)dXRStDLY5o7+ZU1L|;`@4lF>OYc7U)YeKJAejn+nLbRP%v&U(w5KW1a zuFNZ?kh?R^Li3U^OVBgjj}SahtiZz(0#pG$D697zTH%|vuR8%29Gq=;Tbv~OyAvs< z%F@ZSe5;VrvBqLM2m7k`L6os`FCf-ifWSjRuyiu!@giZd*Wzws*gB;8oNz;iK~E%v zUl$UH6`e{!uE7l=39~tjFcySV5?7&MUz`@iiZUg~6GoxN$T%d_hpk00z`YJJZs=Lr zYPj}d3}fTg=pr-C9JwTzP~A*<+ZbUv5|<1~<(^MfEDulZJ;+%s2uv(?9>vRU-JB#< znZ@TKXryX)bJ-s|z08>q>R|;N&4YTBkSuJTkT_PJ5YUAHO}A$oeO9rv`?zFK_Qbg* zk{VaO=GxQRQAU2IWI@Pr^R{QXq=4{g2Zh+k0F4SFQ(K5y%q%UM>MPSh7QODc&&|S$ zsWAnKAk~yxR8IWC_)Lyr6C~MGNQhwYWpx&hb&%2_oRB&&236gg8SfR@BB@kk>QQ8( z81LC_>r=b3@uc0E2%$Dej-Zk;`DQ~jPKP1X5v7^MN>9GF+sidqnl2nlwgf^?H&G%7 zZdGS0s)izJ?7^yqxo3In*vi<5QK*wLB{4FUWJ{Bc0YNyc`v&Bap%=oL3E4HwOlmWW z!*2wPEz)}!`?LeN85LP0QI*LoMc;>rcLzaqI*VgGixlz|lKtejfZOHKIx;ju) zlV3ESS4YL74b&1dFiKtbg)l(5wf35pl9*})G2r|H%EaPa9wx((<-l0sWX~a zwT^o2sTf`xuR*tX7Sz$4u_|=obkcnyjF8d3E>VsE4q@mJ=z+l=j@ATwxo#3KMlrEA z)#pXE&CyMrLkXnDI3fDbCF1JQdqZ*{H}P zWmMWO!i=6(WFi;r5P}Y+8C4B!@!XiYV?O4u?24JASc{_ap*Sp>6sso_kTIDoL3IoQ zty9lQ!VDlwNlTb!bedmg?40ff&%rkO)63fAkfEC2G!P_gszD&)r!4 zo^uvCw1v0G(Zy;OEnnq9fwdx?Ct^vE86rx4_ksBkDoVFC$4ym~7mZbsNYay)IMQl_ zB{5nH2`-0G?M6Lqx!oZ-wlsttSA_>f9HZs%jC$<`lXKyg1X1EiCCu&cMc(Dg&U!<4 zBu0Z`LF54miLq)I0lFwBuE8#pVy=l-A9JyP>15y(v@IG-Q3Em&a36-e$-50-vZVE-DMFsC*qQ~)`#TX5 z=t~%zAJ|tcj7@;6b7e?|rUPw(9J!4LrIn&xW~zDeM8nt!O1Rr0Qb3yn!_=k0j^+PV8e)Hz7JzlF3n+$joNCwD& zeqEpDJX9@m&|@0yCZtA$OC6{PKV>5i*0tQlcqzyqu!p`z!H6I(Lqo;tG;W45DrdHZ zh4VBg8H*=A9KjT^&27HASr)2j|9n+@xG~7N5M;qG=z`yq5g=X|crFge}zsmLkQvavwc-1L#O**SgNzJ z-p9AINYnTRn@Eih_$J)ZLDp6peQ-XC(>SxWfsH2($ueqXE6MHJCzri;L0TvPt&lCh z!^l<^S~fw_tDqan{e;QEpj^j@Vu*ZyR7X(AO>%N;^pIy`x2>!s zD%Y7<5u-@3G}AT5Wl<)>Q%h9g&#^qwFWjd;#{h*_yt+tEmyp21vuah8mjfml+6u7b zAV@K4ny{48>&e2JvPdZGmP9m){-NPYsd}KR_9;)!@-2RFrb!$^ z=XRkm;H@^9wzs|%yc*P;5u<94TANm*BIE~F3ydIXD(D^pnKd5z+$C8&z(Vq(k9PS7 z+TKQ}XO`V;p(T}2<>jTt*yiYlwue$MoER;iCMYH@)oVJl9>`uSWz`DORc(c)aeZOqRJS*OCU=xLCOX&sojW-NH+vN2=Mc3mDj~Dt|7ZoxOxr`O7H% zO#4`+(n2wFJyA-Rup4o-DBrb#1ZWN&x=yErsp@W!4d28VUb1oR1g4@vF8cFjY>4H< zV&=H9VuVQJG(pD0pb=)ERG5_ws`e&WE-u%I6=@-#@8Mzij0nAt+u}uJp2kpzN%XXG zN;op#f{i_FNrHHaOWz`y+)5R;qVhSnm5}f6kB8K9T=dK@H$B5mDNO=MslbJE*FaJU9sU(m`!nQ)6T^SLd9TwHcV)jScb;1;bijYiY$8B7G{tV zetNsG%NvmdY3(2`e~QE)7)8VbQJs7ZT@$|mUmKX4nlmTGLwFw+q6n9BsF$qxI7Z}I z=lzHxhj6$CIk_$v2xlN%N{S6#Wg@O3+Ac{I+9`B0uI7iKKdYTYT*Lfy(VgT+7yqiLYa%)RG)bl z!At`Uz3y1&>vjwrO^YYT3FXgOje`PgMgr0UQ~0hmVM?J%$=oV=V082b`05ct!&I`n zlA&GU^M%q0*f>xd27{eVGqp)--wr<5Lk)&t=i6$gLHwIY0o#=5Oc|0P5gR8XL_xI~ zMm|jTaEu}N)}6Z=OD|=HARn`2V6scsvV!+P)UpW>2^KGtVuw!`6EAZX9vCn2T)h9P8T^%xoQ7lNb)JTn21h4i9SM&h==Jj2?ZU)>2~nSJkkL&N?QDBrIB6 ze8@(o>b~C9RKE5fw*5fo;daTa*c`}UL~MLm#D$yQ=96MkA8V$>Qo;mEK%qg6Mv*`Q z7090{kydVl>}8?V8MEj}=HkRg@o||L3YPx(V(S7#tPnniq5A9*L?{G) zq|fOz+udYnzj!Jn`UTT-4GuSq(^!bOEHG9w369io+HEO*?p21^6r9vFO6J~|w!O{) z5MRp?lJCkpGPy`LsHk}+THn3kE;|^J)(+jr8(~Wd%;uw?Vg5l@R z8a5&NZ*Ta6x~vlLi3(jBHpkEWC_jt*1h>eThXX7fju4nw#vA&U*d@b8K{sQ)BE9=s}wP_!G z5Z@KT???Cumyb9aP%$=*y`H)7j9dh*(d9d+;8P!;p=1P^bg*vyNR3dYL0&@bA|A9M zx782rt;~7ZQ7MlN$?dp#Dky&_$QSK8f zeRzr!hkUQag4!5VRXN^p?Zc_71=vCY=gC&>!Zgo<2k&&aD9o_GbI8B>+`#Mgo zqu8BIE9skQozV?$-?EZkxIA{q5+pf&9t8IqHZzQSbP8HOb|5eSdM2c&OxbWq0~zPI zk^ZNKX7)NFHS z%F$S+BsoHXDi>64`#ii*eVv0O!(l0HZ$5WocRtf$ccUXsPS1t8>->G3e00YutBzwl z+G42XFw}%a2x8<}AC)K2ONsJVb&Dq>MBC$?>-szTFx~pqCob4sGe33gW3=^PqMwS=tF6dI;7UjM@d4mve#20R;cR1*Fm7k z^_50#Rv4Vg1q~oMDqE(n)3i-G*SjF5wo|eovC-MQBy4+&>YC$^?zS+)6nbL^tm~#; zt~G%AXDzET+MU?^!XN+~uFEiF+|6Y%-GN|bh(M$xyv)b#JU_B_-0VawlxPqp06KI| z2f+~vX}|(loI;dES#xhS9eP{vv>gI83x;P=pbt471LW2b{VQ+P*mI7TuiOC7O!n#uD z9d|A$eQmxm19G@t^f@@JoP3X`kjN>BOC^?;v4OBhI3!0li8-s@h8PP0i5GFfq=07Sp*)xMGwu&vA$g5c zpLjsKG2i`XXIiwar9y*;T5GTI<*aP4L;4a;s~-0hi7gX3-60b+~;T z*j-bq*jQ}sLnI?IDQr zHDM?mJYm}bnlzQqIMha-?Jyx%+dNtAB|A|l5cUY66pLqs-#`ztG)BtI?2|#AtIn-^ zMRdmUiC`%I(EhUg^B1g@am;qRARo0xv@Vn_voAj&Z4v)^TonSArRhp4X*U6mmqXpg z5-iTHa5tY_PVdQFMu{4nrF0>BF$-oa-K@{>!C6g#wl5Z=mb~8=#r&dhH$2x(t^)$B!7`SA=4a$@Z_!ToIzLd-?B z5RrH8S*TromLd=#SVTzD+D(>|z5|g1e4@5H$mi@e25b}7QjDYx5J_pnl5Q)GyCIS7 zG$_xE2~s+_we>MhiVr7ZUhjwW2&O!IlbPCPWX&`Txv}jPG!HBp4r!mU1#d8E9SsUH zrCgWQUeS!@kN$}1k^w2k82Qr~O5rajsL1$OmnU;^3gv;cbxZFiD`40mt%IWaQ9D&G zB<;a#4hmJ?K#X{>;61qRFeOsBuQo^emRw&GD z%PP7;D(U$u3p zc!&}WH=A!TRd|BllBJvOrgTNQWrK~)2e(C8B68aW>E#q zV;#VUY)#k(Y3VJTwZQN|!pLg5l8?$y+hyb&PLL4yY!m2ulF+m;g-5*+eT2yd-+qQcpoLE~M5x-K#DxC>)%?$9C9*`VrA-^i|n76|4>qmktRt zJdl9)QwhoTE8|8Sd#9T^FONu*g)ebsziXY7OO94`C38sSV;_<=j)5Dw3_)tOu%?Si zXbU>-QR{EbNiB;s;r> zdcB`v$*(JCf(y*S5|Xm|A|iV%gATGLx)1@U6!=<>vF7;L%CLooX;uP-5R*vJU{Y;^ z#9|0k)#b6n%X5P3j$tr$BWs`6 z1QkiuP*I7;5Sv?AK@qlrBskY;8yiLeW>G9H@>#^T8h-``6KYuT9BL#V>J(=ymI-;U zO6W&8+i^V>OA1Y^C!k$U!&p;-@sD`j(GlE27@Q2L z>iXD;PNkrk0GEiaf}Kk}_pzM5;k)JT-~@;BMSgdh`pOKjN|ACv{^PjGq7SsGJxjVem@v4m2yw1IJy zCa@)89y85l?tczzCObpa zXQ!Axxcl)%2)E43##aa+R&;6xxkY@PrM;@nhDqAv?WV}fx;$lv3CgqNRFZm?=Tc}; z{+^7f--0^K@>ib9#!$F}BZIP=l%Sg(ts}rzg%OZ5k0ilx1b2Rb={utVhg;8yvTQYTrk*#yH#Y?tMpjC0bwp76IS^7?u zMNgW``FN2ib$vcCD-L~72)U9zxs9w2KF9YqLZ|Zn2v>+ssjv2~O?%g+y(g2IPL7ck zA#L|M5sF@2aX_4oL|Nl=zzWTmr-83KeV`HI*ddKviZeo^ZS%TFOPfRKxE#!&`no_B z3Vu=+tQMFo_h`7?|J-tDg9K7Y=t({@@}K6z+f`>&`p0;UI&xdMJ_*b>W8k^9*K{`q zPG2`6#bltHIy_W2^swa+KrwdcDzO9}P;v>rt{RlM(he`h5|~@v71q`Il91jLRxaL> zS#(MXbw}p<+6^`1+?WB`g}_H&m4PUM!&Xl^9ZQ()JfF%CGg9UshyPchgV zmZkBocD-C-=!OPY=QASFSUWo^u3ej6gCz8mR;se$;gAoP1#ozt{1z4vcx4a zhKio`*In%pVOJ5!dFK!HR`y84S4nZ~iEQi??;SHT$4Iti{a+{fnsI^+tvYQh*t~S; zrD}YKf1O#1{#gjeygOHf2mV0vPEye>X?bkH#B#NHXDwaj55-x?AKL2-xuvif0w}ms zNv!PB1}Myl{!el_J_sm&3)OWrF88||9iNETawrlp6oZSLKN4#mLSF5d9%r$)b_xSj zZssifVVO^woNgL(h~BEa;e_wyYsTIzJc~1Kj$o`biCKil-EV1UeUWcI13|20EwR7$ zApFFsB`+6aaD)NA-!98n9UvdF6HZ~~(BfjD;28rS_UBK!lQxj0 z`Wa?Nb4JWB7W?{|otKGka^!ppe3SX&EcENJDD5v_oy?a_7jItcRdklFmroJX;kq^j zD?gdLLZ))7N1QsK=GC-@+^XCPpNGc-EBFKQI&9G$z}Bv{oHt)uiB7!LSchOfuIK1j zu-<)Ta#vr0Y|&?DJ3|&{A?-UtFmOH~jjqD(PP6}@H2b^KsJ7i@MM!5p3h6E@LJmyR zU6#_6va;~FtrpZdE3JLze9;23;SlGKy-^fj|b|pUBT$yxq1;eXZ=2nBtvH{ z@pV3mYE%_ME~ut3{8NjiThl%Lgk=|DY-x4KKz0lBof%JOHB@V40X#3Ua~wOw$_~0f zR@>#aO>RsnPDDQF(UdieRjG9Lh233=E1Ae*8YJhfLW3@11*0#A))(^=X{%BZPQ_V7 z$PtXtHCSyQ_zwgbltC3LyMtgN+d;NP#~3lp@Y!o=u@F|J(^o0cuPPzC2+Lif!0e3I zMzLjDo3of0o-IxVuWJVvr-Dyz2jheX@pY|2y;41kax|j|Jz&v(6yU5QQ=IFtOjbrX zF}bx}8#BqOICexC5>~1?XsXg@9bprE-)sz9+K!;z581i#5w#@aC(QEv%T1R|aExg5 zpn{N!zSylQOPg@6fBEx2f+2?oKUSh}rEhqNBn=s&U^iF2u*r>c|XYia`MRKLhJI~sk zsj02AtwDV#eJ<@VF_;M0AfaX&*r}~84UFyI4edh~#H2IE_6>-Wlq0Q&>2W#AjK+*5 zInoB?Ol`U#|R9C zvf|M4DBq;zQeS)}U9LyGv`sY59)H@ls>x=WSb4T1g7h8gn*9>`h@aBRG z+FmxO=DQr|puxxXD9^Zqg=(+k1`Qt$dMfMibHG zm^T`o?VaI6@$I#)ux+7f?+S~_*ZJmvRJX2x^-@xFg=}xm&9N>z^HI%*gqFKP z2h{wokRgc>4-OghhnuSz>{N{7a(4)0Fja+Ucy#%9S7vAJVQj@qc7+adM45fFJ1J#w z%Uf5v4eaP$0cW$Db_J}@Ut8%4+=9ZPD?ndE*Gbl{zztIe6{nEo@F6~_U9gG+x|(VP z5;#iXmRxn^J+NnsQN~b+K)d1w!3F4cy?S!GO{kN?k0~8^rz^cy9}_Ger z{A8@luGBlBsAM`aq%Sj1|A(klQf|$msA3)E*!Ga zfUKLlUZ$7XH?E@r3h5DXS2~- z=Q1i0+nX!b`2w>$7}~DbLEW#@90}CYnO$eZhT)l|;rXhII->?;cU#5m()DHC3qx3{ zt3-BSC@p=CuzSq54QovjcO9$itUU+ygC>=`s4Md-lj|6%v%&b5P<6ebeiXh-8R?}) zyc!$ew$^Ci;USyr4j~m2PtaH&yg_3p$754t^UhIGJq-~Ndz$;J?r3bcoOLHE&@{lc zLt_hC-UBRePiYDglaZ=GZuh zs--m-vtT~$-0gfe>iA*tY-i&x;j}sp4QQW)a8Nm!Lc%p-IG5T zpU(CdpG@PeUute(0giZ^d9c0>B?kZcf~wBhv}yb7*hD+odVR{td6>ouVrrWWd8=)W z4$$Y5O@3{%jLt8B*(zFV588;TjLwKa`unQ50hHK&J4)(svQi`jOrng~UBa;mR!ekO z?8i>+cn$n++Pgh;5nf2it0JoDfU3}f$(+EMln~9sDp}07bkLRmZ$kwZi1b4;RZ7d# z>gTzX^Kk3Tb|_%oU~0dyZZO_(5|?7vfbJBrYlrUj9N4y%lc^jihD_8J=yy!r#(S^` zjX@ZcAxn@Qb|!a(+M$}nLan?JF~mV4Aim)>6kn?mSrl1{G&TVzJ|^g1#$VrpalE-3 z{fK{}y*uEJY@qD0_~J`sWY#BVzlFpcDIA{8RTJOB($&X8oH)BH?!f5CzOtW+0di6? z5aHV9drnzz2;!&?JdYFPfbeKs;l;*tlqNzo=DBW*O%wX@7_v-cv00vH`g(Dz z+5u}xoQ5(UB{d;zp=w<)vMOOcqQmG%r&=G&CFQ5XGzm8QhP5PKWHzR%TpQq{Bdo#@ z;dL*-p4q_4FNq3Zu=Q3oPid*xIrDN+?X$TmYY$fiB+6U1qsrJmcb+p3uS^n{8oD+x z0`dyz+G#s0(;Z>MqpqMWi;N&znggiu0hq2yhM$s#51_ZJMRyPr5?do1FzgC$Z@uLy z`ZI}CS3rdXm?>E@0Z)xab;#=C#CE8?g zavIdVP9>6#3BtSt?81hmO1jHJwsutYT45+k6cmwEcEwwsd0em~OpOP%ptaecOB}Q_ zm|P@{QqgSR<{R!(Wv`x~G&+Jz|5Sd@AMkoiq$;?f?c=~#y_K|+l%8sb9QXpVns#Ie zWIFuT!iq6&hnaM1d!qx}{@hRP0PW*#ANyoey2pim?Xca;twEL_vXOQeh#OSY_8W1v zy=8RTAwvse@KZArRfy}EX}AHMZEKX5EH{auHVJ7YWQr3pi?ybWt!H@qNR6#rr^f*a zvSuuUbTvYZfD%!?#|Y1}gy^;F2uh81^zJx1(w-RkwbVF+JpsnJInqwd@LL_U^^DFi zFvrN=-CUah$_@(L#7b=~$2QWgIM`Ho+8ofvLcl*rqQ}mheeYm*;te{4vSYk6 zm0N?M>U3w|PKn1m1E~5oX(>Cy=-q?Dq8ATH2t|AyDJ%ZBGtX%FLH!Y{k=y5V^?zaYzrA>wy zTS<`Bnl6=lBfHV;JPZwjM){p87%?a14uLA`!GTWSfRCBa4NrB2vX>8GOi^VeI;QQj zsOEZtqUlb%VG_a9u$>^|a~?8ZobK)LZO)1gM+Lu1)9n*a&-EpCLv2AD59;%Ks?%n! zy^H$n1_#R$TA|z6<+VQS>7-oR0Y0#A@1WbgagO)wueuIlwpnE5hj~eW zPol9u=QyYwNXP6!9nhR>&G-i498}2QlH^QTL>AAU7O7j!;@zIFDky%@I>o(xSl=>G zrUh-*@mT*gRvJ#>S zlVo9N=N3y}DyF@}RspI+$HEnl;Gf{cKv{ z^l>CREj+Ue;+5&T%cq7iuX?tR2Zh258=2|w%stDyX>lfqqjvCy?R8cc z60O;oh<>evB>OhRX%M@EIF4{{u=C-L<>w@jcvx$UrcguXK@Jamk~!Q%uNB zo{?5S(t5-=bHy#Y4u~CNM{Vy&B4>JT6t`dLjF70fpsDxZ5>@dy09CuhSry7 z!@eP#pqIc+W}@XY37j@j2AzsvuS?6E)+ED!y9WRfu=x5?o&|O9hsSju})**2_HNKPTB; zEGGVQvhKn}8AzrgZCIXI*Hh+yN_lY6|0(tL*C0=%{~t9tFy())!GWo}YfzaATu-?N z#~)nU!D$K&SB(a|o|wvs_Mje=1hWnf{skJXDsxb(q2|n@NIDSX2y#Q__J2q_3uik# z6`1|{lkMb!nC6UAt(D0Nb6ZpSprSj{A*a6nbOX>ovbbUzi=hPZUVqx%%~`ZmP1H!H#Xf5;KaeoXqI|I~Zy26x1TC)Z!vI;fDW%V-yN@ch_- zWl0m!HnyH=HycS$>Pa>J`tskQNq;FFm5v4aa39X|sC0a~D6OPRi8?BsM*Jn|l2xFRV9zvtX!WfckdcX~Rl=dzw-)1kdr;hRhs^_5|?{($fi*lTISPV_X|vprk8%4t1SV&+)vc z+Mdqu;r#aDR^9v3Ea@&zSMqmJ{#_yDlC-6E1?3#uv!>@NYJXKao##0{v*~hjzMS^0 zS#>3@OM%3j>XAumeMwDutq}5yKDBi=T|-_+xwR+tOw!iLo{MS8EGd-g%5+K3rA|q2 z_MGFEUBx?>(w1XMaap>ihjx-O^;||tJ4x|2o<{-tN6**RP`^uQ(-z{cpk{yNt<%%a zRTm$r)@m%SAcy1ARjW_Kce(R8oxIQI{Wa;dTJ+6M4QV>(2Io+_L(@vHeDQCk=QMKE zSRK`K61Ac1p4s#Z^1e2m)N_*ayms{@DbzRT+~tyE)*N$r?ebNplT#n<+d?T9_e`cs zY5B2z$Mfd#{2j&LWbakAqtcpF&Pm7io<`V}C;XM)HIzd})blDm81u{cy@;^W`ws0n zirSr+j_SL(_xzr#$?b6Jq1=w8PcKV<==nnr28|B8SZ@$>J~xrBZ@C*9hAw48U2V*IvH`bp`0ay>0w&2OTtWA*Sq z^;WJypXTnd^D5$x?7?62{2IcyQ0B4pUFw;o6x@d>9c!ZJTH-Gu#Z^7WGycj~vqCFQa4~NA zG&11|xBNTTR$8jyaq%ZiMRy;K+1S;%-X$ zH>G^dzeMgea!k%aeR@;U-3+)nzc(b81oYrOmXKTEyQS0jrCX8a*1&PRaU0@RljgPn zI4|9fbhigiAp8!zbw}PhgtT`8?#%mZfV<%CCzrdD%OT`)B4Kv}?hdH+s?$BlS-B^m zhulvh_qEh?9dL3-`crV<6F3#P7jQIiTGbDI>E5{S1Kbz5ALZSj8b*DONDm;d2a;Z8 zpAM`C2B`g!Zo%y-cXis}_o7~d#BT&N3Y&n<^bdnfF3c{{Z3P}g%a3$_+##JoKHG@f zPTDhp0Y+j62or@}jpSz~VGCv;2%y>Mb^910Dq|ikX{J9h_Dxv<|V*OnT;_N$qduOa@m!0P~EuGa%^;QcoOZvx&-+P4621>Od{9e4-uPSU*#SR&24f%gFK z1+D!}(@J-+v;9J1Af$sp{1-=J-pA~or&(8Y(0RIO1@PVvM;V-Sf zYXPmRACmq@tkxU5ulm!E(<$jEr2i@KGvYP>e~!D%wO^3WFA4h<@N3+U1~j(60e;IW zzXea_|2y9KJ@5zIngf3%-JgIzyPUrC--P`S@E7L!|B~*nz~Auy9ry?EPvHLu`xo$U zAoZ+HJw5AEt>@I#+jB3^slJ}Rw5kVu45-Z2JP!qK01Qyp4SO{H;9Alh&O*Hrc^rZJ zNZ`?oo@Vr`8Q-Ju-xwHRt~{_>Z(wrL-vl@YxG8Wm;O4-wz%77V0>_d6t$5yAZs0b+ zZGq!~+X1%+P5|xz+!44Fb-OdL2Dl5*58M?v5x5(mc9cH9JL&HMoCK_;e(QjfNplKt zPeAQ`B&`tMX|Lne=~U9+3m9arpVo8lbnhPFGmWkK@8oo!o?E8pFjn`aAMe+5TDm`d z^8jE8EPNx{^FZD`9e5M@3eR`18__4L(|Y0ufDQEViD2#rW?4?F>QBJd>OV&KWZQ-G%ePvhOE1J3}S30y+hvw&v<&jFs>^8k8UV*+kvES?Vx zGTR^5F&;1AJ&jrC7+lJ`F9co$ycl>1@KWGqz{`QlfL8#o1YQNa8h8!xTHtlS<-qHK zHvn&>J#V5OZ^r!=;H|*hfVTth0Nx3_i#og;cn|Pi`r-=UeT2Us_yA!a1U`iO!@x&? zD}j#^_A%h&v}r5w3E-2!rwIEra24Z_WqzIK zH-K*f*O1q@2>UiL4SWZ90Qr3v(3pJ>|MvmynLogPE${pg_!019;3vRO36H&LUHVzi zy7Y6>{{r|W@GIcg#Qz5PEopxT{JuwXqO9H1;e51aSEoM`_b1@bz<&e(!#jTgH0S>p z|6hT>0e=Vn0sIsAKj2@$ze$&BwbWDV<55e!Kp(IQIHYz&T3uVu{!sRJwMMkzEz+U2 z4bUMQzyupo53}Y5q!*47uDT)a!)l%M@9K0o{u=>D07n8x0XGJY25v?@Z^HAK+D2%y zf(wpFH>LcW0XMG+S3MBUA(4Mdw;=yp0@|MkcvrYdd$#b?t;pxrz;V>?Hnro8mu`#y zc;I%xA9(*%;P&Ko0&oZ5j=-IOI|FM-a~Gf=xGVk>Yqurm)#+~dBaa&IfUoiYf$#w+ z%9{ZR=%GI9gS$IkebJZhLBF1ae=V>MI2kwvxF>Kba4+&X4Y)Vu1g%_4_aXegym!Ca zX7A1S$A5R~qPA-Uj)Q6y?-0Dk>hu8Ke_(AZVMnCXYY$56d3V5dKf|>PT2W(kMA|^Q z!P;?YBd`hB?7lq#*@ybKvoE79>f^1H{~+Sd0Jf3$cKl}ox5O>nu!HcOz=H`ZZQO-> zi1^*WS*{B>miq6(J;*y}ll~mwA;7u7dB8(~hXD@<>cIKDD;i~(X9E}kZblxXwQXsP ze8!oZ6Tl?U1TLs;Nqb2%1x(X-GeC=cc2nLg&kK2H4wwfPYTKc5%3M?5XpWVBI5REQ zcBG}+&a_;6a9XMDO8aUCv@w(tp(+k}j&9n;t`ckFA}T z9#?y4dOYw1;EBMKfQzZmJ!!|2c|HYrD)2Pm>A*9nS9|_~tLQiNx%%~)#2-g{FQL8z zJfFq$*}!vv=aTN0wTGqWQI|uZm!3~PFChJ;#A%+qka+E(FXH)P>b;usUqbv#ftLX< zCtP#tGN(U>xm4m)dIe#xB>reP6R<&g6?xx|cJ|_bHSfL#INIC|IGuE_%VoZje(0m@ z9{}$L-UGZB&PjP+&O1-fWyU-fC)Jl;Pxu??=R=@Ho}csStowjDE%phQIpqA?d8@25 zolhU}N5O?@t-hdk-FdyZR!`y$-&8xFXJ2}AZJ2jcdJ8{qtu-9?g4&3mZ>)`yqA$IT zeBVy{-@)^pwJ}0gQ)cIWI8OR8`hCLfd>857o!g=QU0V}()|cMn@Fx6ulM}c+55@ogTRM?4+9?ot^_^`d<;06m8CiNMEdvR z_&-s*fc(|Iy^Psvm;ZL>JB1sb1NYHzha}}G3Cm1}y9M3WBDCc^#HVTh{FL7p&n!MM zrBByp8M9Wps&-QP40z;5hO`N9UYUzu>2Y@dD=Q2;Pt{s-XT$`h>6d$zq zO-TI}-aoN6e?WLGeUpfH^@u-%r`0Pn%ZLZ&bLS_%&7Vv4dr^HT*kL4 z=R3f6f$#DD_kkZcpVjGF^7tX}BS5qF$F=30UoHK_<*-ll-p^_)^rh;&I{n;f_c4~? z{{{YEx_$6KJbw-RhIGFLen*{tU)!JS|A_R5+9T5+YmZ8QBJR(;cNAR5Vb15e`ceG? zU*tU4*KrTPfghgR^%v&({}QHp|CRjy2K*iP2k=kcDdRB!#~x*{?^Cyb5%+IEdnb*e ze$k)mx1L_%oX6xoVD5Cp_x3&(TvNtPaj^%EGapJGM?pQ_^m^L^=iZT@%3nnuhXAVq z?IVZsya8}S;4t8D;6}h85`{9Sj_9qWBVEtn<&JWmPsrmDbLz&tb2M-h;4so21Kbq% z%}9F_q!K-@fJf@*Fxl-MaVebR2LS;I_c= z!0mc>r`wb73BVo5`;Ne!dY_)|-2052Z@jmr_nGM~y_XP<{LJYk-6;Lom+nf~0MZWO zi4)1=cD3i&Eg8(+dY{WKRnkU3-<|er{;#b)JKckKPvV`mJcUEn^*$$^-23cwiu}N- zz}<+y7jPPIZ{R+_eR~f}_v?LL9?$2e`@4>P=>epFAaHsvV*p7@8FR_|#G|WhtqqOe zdh#0Ry)@5n_UruKAmJP7>(?ToiT9z9@NWi$x3=)y3Y^Q_SzCKiURy6t4|3nXq?+Sr z^d6VCk#0Nrok`w1aPI^}Lp+%0E?@{)TYG6$&)xWy{w!b*?yb<$KcUREwU^~_e|a8P z^(Q#|`fb`->mwR3KF0gUXiN|8<044!j!&G{3j>yu)rIfD8P5KmP3ZG{#l~8 zMeBTqdTCq+pgvcb0(}qZpic-tm-x@o&rhuC``+|<>Ls4-3&ejB_!4k6b^9{u?!bFr z;rUhIYrxlCAMpxTq;K?Ik-pjczH|+JSVQ9bt=O-aq)PP=~ z4_E~p0;~oO1#SS`un!&|I2^bUME?=Mk+>%ri=%Mgm^4QNH|aYf9Ru7HxEXMB!j2_f zAM@lExG$wIZi#;LR(&5zx8}X$0LhJSL)>jie>`wI;P$`?eIG_X`H^&ozSGkkNp~mU z&g3;fKRvVd;?XpWxk3 z_}vppcVEi&9?ARnBh4FWv)1wbsrLhjdtl%5)9JKHdNqyRdbI^OjIr9la}d}FYyvj( z{uW>>@F3s}U>mR;xVR>;i^>-N0GE9^h=?9N;0qxxjhALxG0@4+rYN`M@yH z=#zfrlW7F^DD}Js`gg4FQ|$4QIkDFeK0%#S=SjEm)2y{m)3Q&~_Q0{tKCO$Zz$sS| zewD*7AnjgY3OE{UI8B-v`o7io)O2$+K?%_NTEDZTxe%BG=79xZ5m*8Sh*v(EL(A0T zG~SdhZ-su{2kZwPLB5ad`%HQiWjwm?v*aro&WF%SDu4Dc+Heu@81i{6@HpV{z!M02 zBJd>OV&KWZQ-G%ePXnF~JOg+pa0&1%;Mu@)fae0w1D+4OfV?gRUWofeKwsZSkUK@a zU)=Y(^pd{MrwwFF*8^`L{ToU9CZ2D` z{}$k__}@l(kD!dV^Lz(!?*!gO+ux1C^bH0zLzLmV7_g_eJ;b=lfnv8();ZK-d=n>0Pxx zzC>PE179ZnS9pFE_!{o7^ZW+zP2AT2-vYkPd*1=R3w#fd4D-@Dvd!c-J3k_vr4?$m%*Ed zrTeaeA0h7kzyp8>0;dD(fdOCxFbHgvpBy)>`U*Jbu(X-?wh*=z5Pk8WRbNGK*_Y11 zzYW+9oC)jzb^;Fub^$}cZs06n4|O>kI0yGbfOCOCw5!TT^rG@O4|pi>FyP@p9XOx% z5A$pQ;=xCFjsj!AI54qFmJnYD2lk~&(l&t$fW5>`xevkj^y6cgH^-sHJpxET&@~TC z)2mKTGo)3&wRp|~7Xov@Jg`7si>tnwmR4QkePwx7(6B2!MHB7gxgU50@JPyg6!2)? z`7itz0gnN`R{K_Z?5c04$F2Gf<8V!SJYgp=K0CmztJ#P8Sf3i}C-9#7_ld+m3Ah-* zA}T$3)pxNW(0gA_Phm`+O8-A?)z{L~sh@b=z(?Rr{Lcg~0iFdsJGcLfwEa2c{aoOA z!1I9@5O*o?Lf}Qfi-BKLrge>|RY#;N z2zwv!e(L)H;Df-2fDe=3M|fTdd=&T?@Nv?80{A5GDd5wU+%F?=j-v^L+e0>Hh%y5%?1z z{`=2<_xreNmVXI4*Uc7 zC-8s3zkq)O=@9VgA$_UFvlr+)B*y5t^h4-#^2UD%aPVAV{t|vDa08{OeLvlh=V8Fh z$oKF=u1z;0zZ>AbA#E24xSzm-9%h@hThJ!qj9c=&)geCxPyRUFTKQ5B>v(YA2DmNp zgW$R25BVAI$9$h2Ekw$0zmLwnu8R z?TMOVdq&x0Zvg(L!E~4bGvQ~j)-7Zw5BmU+Jqucmksk8=2{%~11g$J7GSypXsT!Edk_mJm+9e@ii!nR2atDa&orzj&!u@IF`CUa3{K zOUwwIR;!V<2G&v**TH(&02^VG?X}vBj4kj8ownldcbl{!*VQ)LbM=Q!#_=!IcH0}Z z!zN=#r`l=reIK)^KW%T-F55fm+B-_!JIc50pOO7E;{Uz+3w?cSmr~Am6VDz~XKTNc zmz_-MvEPfoeXt)6z(F_!hv5kPZHrJxZ6DMz+edZW_DP+veO4#Y|CH^EI&J%^&fw=P zoP!F~qw|;-;3CNWwM)E%%Wwtuz*V>gk@&riJ~!Ydes5vkhC4jpg?n%x9@vx?%FZe_ zSn-dc9+LNuuz!r-Cz!r?pCa>_Dc4^;$IlDgufQJOV?20i3s$el=3|j z2h6~`6VqjPDYw0_^4R75>g<{bR@a~~F&g$D6$mly>_>ng2!`0i69?i#JcthoKy*xq znFta?2qb}z=$X{+uaZG>yPsygCru;S|B{dXTEM@$u|EO5yRnlk?!WrcwUor03Q|KF zNDHD{I!F&0kYUY@xl~5<$^@D1aa9)bBdgt}#r&VLnJ=;1wd}~qVGq!9B2Utu3o|!_ zA|sF8p&9>EhEogUedNWzd|UGozw{;ZV}7)`Gc!kcnJsFToj@(Z9#f0K z&cI^iOK~Uxk>Iiik)M2TcrFE{p$wFTa>ytT6`&%rWlSu2S&8S$u$H{3g1@Tv;2*pb z#wWEuj^(hL5(GS{r*pE%`s<^R*ReR9n*A z4%!pG7IHdZb|h>k=!|_A=nCDi?+!hnC-g#x-qg!J&=>c9(4Q~^U?A>;U@*^_SWg~; z-=X$In$!HYxYRJp=5QDRBViO_rLQ#_|3ASPdt&_lsO%-u#v<3!)9QDPvxm^!gpd;< z1dwk|5^X&4WZX6ZSrhF^+3olvS<+TY`HHJ1f$VmWcP{=Nd8oqCZ>lC}l z&#R^)cN%d_hsTtS8R#?f{{({}G2lm1~*bfKbAb8p7>qM_Z#CsTyz~68b zj^TbBPQXbxWzWF3g8hfMoq@A(4$i{`;@r)*$IFgkhFIz%c9#fq8Lp5&UUm^P3{h9H zzsB$D5W=qFM8to?o?g2Nx8OG1fxB=I?!yCk2#??~Jb|b144%Ua^m=K}sJ%jm*TnY* zyu|gE-|vX;J$!(V_AJ_J>@V^B2_%i5L3I5BUx7}hl0@p@2mTNPY+#1~aDWqB;10;B zc>*$N2G4;I6JkLS1Ve0y192f9#D@fs5E4OR2!SM!6p}%5NC7D!6{LnVkQUNGddL77 zAroYVERYqlL3YRiIUyJ1hET`@VUQQ{L4GIz1)&fWhHxkXUMLC?Pz;Jg35bM}Pzp*z z87K?opghP~zKT!@Dnk{h3e})G)PR~$3u;3hs0;O=J~V)a&U^t9`kuVBI z!%r{<#=~ffPJJHGN>*d7W8gt1vYC0X|Kj{!> z)^llc)@&Egf5C3p1AAd#R9Ygn+*(V*?kCOzApNg{n1_&k7>>Z-a1@TgaX0}d;S~N( zBj*g9g>!HoF2F_HF2QBE!tbkajpyrd18%}CxDB&upYGs(7w*A*co4uC1RlX-cmhx1 z89XQM7x;Mzui!Pjfw%Au-ouB0oZ3gsPw*MOz*k@)S81SwpM&)zh{3ZB><|DBaDofm z-~j^y9ke+R3xfC^46z{&#D#bepFv0hNQm4-{7wuZ{7!;t%@r`e!*eo64wW4H6p)hN zsgRi(q%BQD*tC!ixAc&~kxR?y2-W1QUsArwnH+}73|ZizIj56eWyOCskh#q4$jbpa zAs6I^P{;#ekQeene(-Xtrhvnx3Oe#IZplO0%0t=8qZM)ls=~O-H+ixi#& z++G2e@!nqoF{6xEV&I)>apzVr=)RC8pu_)bJFehM%yr%7&cgq1{GiX}g>eFR7hF#(9UF){@_$ z>Vl*Cch5DV{4p;>35uiDM6UP?BrUnrMMo}m2`yiNNn0h-DEsm5V0Rbp!F_lD z4?*_*jedgp6rQ2mb9ezS;T61wH}DqTft-DLj~N&91MmGKd?GBf(b{K+ z?9Zsj96~+xuJ;4IS$`&e8`$Cd{kC6_A-cK2;}^htwesvMaY?(ToHCBB&wH@WP-{*( zRoQ@)G$5`9#3k?7m(T3ArKIZ4hR6|nYo5~2Nvi=~PSvrZ6FmDEz*~vIXX60fq zX(#iVUQXS~nupCvi36E831HAf)1;ivrpUJHwtOdL|Az~Ex3ih4qqWaZ?3|Ci`7mAy>l4`}J2IXKOT+-{OaU0C5K) zM`T3cC)nA>Oiyg=6%tVkFto)I< zWKT_dEyQV^y-&`3=o-pF68v~Map;OllgvXU#ZJ^u()r;>;oPrGGv~*_tSTcQeNMtac!agfxg8|6Mj+q0bjm$~8$mQ&2wo$ox z4uw1r26-VL6EXSlZ=oT4Cgh4zkuOXF$W9J;+1OBa>&A zZlZ5lRfKmX@7YWEqVScn5<%Ev&YscrMB-pfZ?37uv-L8|rtDLacVU%Hk<~j|FOe^K zsQ4}vM`j6-`T4q}Q}zVP{=Z1aZ`Ky7;Z<987tXZ^;m|{$`4PPwdA)egmhJtTh;v7kwB9{{$#Px`@ozlbcZH*5)pyvSOc65%?5_2+`5j6f~ z{5VQWMJ?@Q>c$ym;_L!lp&Majp1wQJJ)kG_0!hE*Rd1fpVD`c63;m!!3;;PFF7=@@Rt#rYNH?ndw|bIo$TL)I!rn!0l?3R$D! zCl~``u^$KHVFFBqNif+dr=3|V(nbGmtV55{reH69lBt-}Ac&h8q+Ctsc?QgcpON_s z%!1h<^Q?0)=fXVr6+iP~0W5??&aqlLPE|Ae5S5p*Pt~dmQeJ)|jO@Q%Ox`YmrLc@N zFDG0o!mJ<CT$>=zDEtFd20-ucb}uH{+w{>r}Jhsg0zcco6Q!+t%;zTXX)8(|Y{ zhApraeur)3>mSZ7q|;E_ou$+c^bx(JJ=%%>G6yXu0{_JCF7)^dyWOydaC>2&Q}!~m zYtuQ7^ojj=+6yt+JBF+SaFFLiaG2*KrhNK}{5}fD;J8yxnol5)CLqI5Cy+1o@uXSa zvTCQCo7s0@mC@7aupQ388p?tAJB$Bw;AQ`B;6BHRS+s#ynR|F-BL?~{EEj>)v;lkqbd zKh_>Yal7W6LN9#^_EWHz@3QZkq11KaxnZW$dT%$$k6Tgo`!>&aoKtB_rxJE5VMEki z{K|Qyd*tJNGcPS!51iA;Luu2bzFPV6kUV-syJLl!&bL&aY5SwXJ;8ix$_r7?FrO3O z3y^yI67v=AR=Y3tc?NBWglF#+_OIa$NLhL7oEhat-6W6SgVhF!u0PYpN;pfWcV>LQ z{J?J35A0@}ZLzd31O4al>`TjB+E7d82lVMh-iscsm{b0UPS!V$bzw8Ec~O3?w5;>D z#&*&Vx4w50R{9vC>#xx|yyCrnHtpvBhn@5vWBDzJ&I{{25c}eZ*V;qBFgh>3l4chB zlm;w45pEIvZP7bKt-wvb6Mne)LkzHi9Rk1sPH?$=_0gBE-^_lYFFzCLiz##8@>lA< z+l*@o{W4#E(Jmmzz&;RSA~zNUK`_LII1m@&L3~I62_X?Ab}fyHL((8;B6$<0UdyNx z=nD>Tf(w!mCTW!33H0Uv4?ipZAAaP<2VZ)u?@J9zguHj@hkDK1Amke>Zr0f^Iq#JW zUF7UnCVe&GWgM@)SJr$*{#W9RB#r54 z!%8AA747;Y)@Q?bE`@z*^s#iZ#-=hxErVTID2G1f(Ype2DncdfDnk{Xt3ox>QQZ}+ zYCuh>g1v68>2tKgY#kN0 zJn^&vnctGN%eFkXgZ8+0K>v=>`Lt8(gzlZO_j0RA7t+}ky79X^W)J8Iy`VSraqXh! zaCZ^Nx#ZHcNoAaJ3yRpu7}Qs;c2lCcZ-jp$HMtqZa_>u?T5afF(oNsawa*;Ci9Bg1 z`@7`k6swL7a2=pNS@#UdKHsm52L_UlgGh&$n^k0&D&?#+l;(L{Eon1FMsjJ8WnWW&zia|M*b353Uar`GR)<$f^aKg zmFpa3o3SF#YhW#`!+kw$fQ_)pb)J0V8wNIRxskH62sXPeQZA&vU!qS)Ye2kPAsyN9 zJ8~pXw-Npi*bX~D+Btb&J6)HN<5GW8PItMk&}XyusLL2x@{I$0rmSW>W=HS82(ugH zjOHH9y{3$-=6A(r_7SXdwH&|uaFcr(_LDC$)iv^!ek%GLghSv}*Ud6=7=Ksre+2W} z{PYdnxT^qvN3lN!$KeE=blo)5?n1Y2>K4z;ZxY98m)zcyPn~h)S7%*!D6_Y<`Fv;2 z5#~HxfQzoX$Q66pcf%SO;Vxr;1@oBW9{DJ4_oKsJ#r_)Z(*L;bdO(Q(4*QVuW5sg= zzg}(!vSd7tw!dlGKZ*W*%l!Q``uA<~_p|8VGWYG}1|jR6z93Gkt-6E1yQbflQEsnH z^PcN9@13y;dOm=M_<4l+7@ojWem{ff@B&`KE0^3xL|a2SdF^^j+)BOSxftdt{av)% zTi1K?!Z!yc=MdOsiNE)*4}|eoACPqmK_6Wo&G&GhzT8LGCsVJFuFvT1E3a1j^vU%F zU0F+E{3QKNId}6J9lyX=Q0~u~20Hk;>9au$cPJ&)YTpZE+T2KW2de;ZxW8yl{J6jk z9x&VqD98Th_$H9wF(DQNK`_JyX)oj}Zq2nIkMbPH9iP6Obyr?o;)sX8_?QVW6G9@M z6Jv&8Cc#WfJjpPVLkdU15vt%ZFUCl92}uZ`?FP}glo8fS=jt`80H(-0a#W7B_t&b_^q@&NRdzNU3AqSeQ= zbTL?vrc~j_5#>kD0$63eakJelevOcykm*CwcDjj-{Bdw!EbG73+8dc?ABZ%^0ACb4J@xN8RD-m^(xrhZAlY z8_5~&?dl}yJ_W4evZg+j8ab7A$*rGuJM}Zvkrhtg*o)XrZbO}i3-00SqI;aW z1ecL{#T}?$#gw_sM|=-tp8hsuAb+l*({=Qb^_m-)QWhouZ}NN#Zo?gPkoms5nD^j5 zZP5eFhhh(pX*-{|eP>_UcjC6`&j|M%UbtiGFWqwAODz2ralHnoHj-8~NFRg_a$ffh zc5gx2gP8o5_x6t8a_`xD%n$GpKEY@B0$)MS`LbbMX`sVWe*4Y=`|;Z!Vt@_o9Ka6% znV)fBIz9BVzzrTSAP{0gEC{0Gl}VR+H;P;f(u0u^8{&Z6B^Vbo9>h0gvQ9ymgdSO2 zWKD`^X&XYgu}|7ZtAB_N{GXUGFZI~8U$JSMV$(JS>r<6 zo^C^CI>M!g3}$#~&%UaRp7^xQ5-x$B$&*0O>|x&w?pX<&4YKn)2joOXF3j8z3V9&R zlTgnK`5-^P3wXY&g6L8R3L`5SGUaAMnF|a@rtG&Vf=n+ruX;V9T2cH(@Vgik2j8BK z67mfBXyaxvekjRvDJTsg+-6wDlUOh73DL_TvpiHFjTMPMC&(U;N|=?QiYJL4#EpmS zXha7Y-&?nES4B=WkaktpvsVOV86=>R#vegMX<0k!xAeF`p<6A$IwXsx? zT2G688lJ3k<6Q`2`AJ8faVHP?&<(mn4^MjhrBP$e`P&Ti1As2t6q@sSN)Q4 zZ(=rmIR50^d;#>8@?)o8Hv-vxu^)--Ncz{KFumrDknGvS?I%x8@+c=Vb0Tvy^LmCF zKtKmv=e=d2;{T_w#B0Igh5RiKKTDNFO04 zWn*$wdP2By(+2Fyjf%&54^%tkhfFUX`SZDLw_?5 z{_~i!rjxdc=2|FwOnIIe?T@u3PZ;kq48LLc^~sTWm{iE#+(Cl zqx6<<(>&z;O4{dp@=~6B^G*4Xn-979kn1b6+&2^>Kk3Y;FYs7>$AyGjgsk7-gtGwe zSln30!hW%*AZ@kJueJWP1bg{*%9`Us{4MnqGUHi*{W6fd5FNOOapR~Z%bEjO&ZPx1 z{#t>bReU#BqH{?toKsoh=ooJ1(<;)n8rG0UPieQ4n)QskDhRVKT1RUQ)aB>V*xp5CeuHEy@3 z2z^kO+Qav4FC3%4vd`ny_j?j?2TCG!0P`RmBHUp(0)N9%I0nbz1UjC?JO!sg`X7(U zzcbjMg>!HoF5q?%rsH;r-15f5NkuvVDls>1SB&u-xzNk9{rGmv6N% zE?*p$AFnE^fBTyYvL}Q71oCWPhX9bZa0jLnTwv|ru5i;>n4Rg8X{%-t5(W3sRk3wc4LLE2Z@ zKPYR+!G`QNOwGER_4f>7;~od%LOi2{9^c5N5{5Q19|ZrDBHS3*yMeNv+& zbw}*DQ<&dHv{KX)zOML90kYnc68lt;n%`+40=u;QP6z2B17w6u#3|pf%sgj-tdPx& zPxOw|69O~5X4@m}Xm;FlMEgSy{n(uN&xM@a*oQ(geoLD3V21HKlJQtxbdb9s@?qx3 zz5w zRQfDG)A^>=GYnPVD6cobuccQ-(@#UA68+msgsH@DDGye?k#*)q_-zbLps7)rcUl>L zmGQ^i3UndDzHl%&=jepqd%O+y!Yt5%j zNT0GRI&_2X&;xoxFXT!acA50`=D81i)1N&fMmE(CIsLI80MfnE{JVHgaD z5ik-)!D#pi#=uw@M|inU;t;tt9+?whqOpXxwOCCuqKB-WyxDM@e3*kNb#^Z9^WayQZ^U9Q z-q+?BY5{sKghk++)3^G8auYV+XY6C*U;1{7Ny8FkEQMu84YOV?=eZC%1~GDsp^~W; z`1cZSCGM+?>Uw>5Ey`9ca-kOQPs#=NK_O=i{?-~b8Hb6Vn)*6JZrZMmzuNet?MB9W z{Ip^rLc(<87H5Atg}?7&Ux)nodjJB>eyi?spT-Cejz*(&NU?*8g8e(wg! zV;Mio7!vQ!5haf`jVy}OQI&6ffBT@2v@%@dv$U2I7435JII0>iV zG@OC6a1PGH1-J;8;4)l+t8fjj!wt9zx6uE#QI|ZdOCHvZ%0sJc-9eAL5J8&mk@oxW z03Je!GWYK4kBs`f-};2DPgof{Fb6@HNbM{mXU0$Xm9fiHOu5hS8F4;`7rdjFMg!h$ z1Hv|lj#v8r(#MywzuVSO*KylVO@C!HqBO~~%=23AUT#>o{f8ZW24ue>F81O^`IoTt zA>f_S^dJ5$d-30lzUBAwePO#8-1!M|FYI8ZZc05!438D4kf-HyLXO`|BD%am+0SL&EH+4e_Q%> zi~ik literal 0 HcmV?d00001 diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.original.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.original.wrl new file mode 100644 index 0000000..d28d9c6 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.original.wrl @@ -0,0 +1,350 @@ +#VRML V2.0 utf8 + +Transform { + children [ + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.0486844 0.027588006 0.058410246, + 0.00018439814 0.027588006 0.017622577, + 0.046976272 0.027588006 0.030211996, + 0.00018439814 0.028586103 0.053412903, + 0.0486844 0.028749999 0.050281703, + 0.048683621 0.027588008 0.035596237, + 0.00018439814 0.027588006 0.058410246, + 0.048683602 0.028725101 0.0355938, + 0.00018439814 0.028315915 0.020725725, + 0.00018439814 0.028749999 0.036560003 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 0, 4, -1, + 5, 4, 0, -1, 5, 0, 2, -1, + 6, 1, 0, -1, 6, 0, 3, -1, + 6, 3, 1, -1, 7, 4, 5, -1, + 7, 5, 2, -1, 8, 2, 1, -1, + 8, 7, 2, -1, 8, 1, 3, -1, + 9, 7, 8, -1, 9, 8, 3, -1, + 9, 3, 4, -1, 9, 4, 7, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.035993379 0.0035270932 0.15090306, + 0.033168469 -0.0095995218 0.15090306, + 0 -0.0096063418 0.15090306, + 0 -0.0046731597 0.20012818, + 0 0.0094246399 0.16388398, + 0 0.009219164 0.15090306, + 0 0.0058807195 0.19495119, + 0.034762751 -0.0011638075 0.20120168, + 0.034983277 0.0067091119 0.19138768, + 0.034983285 -0.0074115978 0.19572869 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 2, -1, + 5, 0, 2, -1, 5, 2, 4, -1, + 6, 4, 3, -1, 6, 3, 7, -1, + 8, 4, 6, -1, 8, 6, 7, -1, + 8, 0, 5, -1, 8, 5, 4, -1, + 9, 0, 8, -1, 9, 8, 7, -1, + 9, 7, 3, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 1, 0, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0 0.009219164 0.15090308, + 0 -0.0096063418 0.15090308, + -0.033305667 -0.009532637 0.15090308, + 0 -0.0011638099 0.20120169, + -0.033725008 0.0090277288 0.15090308, + -0.035397753 0.0063928161 0.19251639, + -0.03519712 -0.0070392122 0.19698757, + -0.034983281 7.8515601e-05 0.20096919, + -4.6566129e-10 0.0065600597 0.19254768, + 0 -0.0074147745 0.19582054 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 4, 2, 5, -1, + 4, 5, 0, -1, 6, 5, 2, -1, + 7, 5, 6, -1, 7, 6, 3, -1, + 8, 5, 7, -1, 8, 7, 3, -1, + 8, 3, 0, -1, 8, 0, 5, -1, + 9, 1, 3, -1, 9, 3, 6, -1, + 9, 2, 1, -1, 9, 6, 2, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.042527255 0.0081201596 0.10060205, + 0.041568972 -0.013609005 0.10060205, + 0.00018507987 -0.013717981 0.10060205, + 0.00018507987 0.013506617 0.10060205, + 0.00018507987 -0.0096063409 0.15090308, + 0.00018507987 0.0092191631 0.15090308, + 0.033570837 0.0091119334 0.15090308, + 0.033286072 -0.0095434729 0.15090308, + 0.03997194 0.013505501 0.10060205, + 0.036024474 -0.0060374229 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 0, 2, -1, + 4, 3, 2, -1, 5, 3, 4, -1, + 5, 4, 6, -1, 7, 6, 4, -1, + 7, 2, 1, -1, 7, 4, 2, -1, + 8, 3, 5, -1, 8, 5, 6, -1, + 8, 6, 0, -1, 8, 0, 3, -1, + 9, 1, 0, -1, 9, 7, 1, -1, + 9, 0, 6, -1, 9, 6, 7, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.00018507986 0.013506617 0.10060205, + 0.00018507986 -0.013717981 0.10060205, + -0.04121282 -0.013611966 0.10060205, + 0.00018507986 0.0092191631 0.15090308, + -0.039786119 0.01343167 0.10060205, + -0.035890073 0.0035807528 0.15090308, + 0.00018507986 -0.0096063409 0.15090308, + -0.033175375 -0.0095975753 0.15090308, + -0.033257447 0.0092040151 0.15090308, + -0.035957031 -0.0066460879 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 5, 4, 2, -1, + 6, 1, 3, -1, 6, 3, 5, -1, + 7, 6, 5, -1, 7, 2, 1, -1, + 7, 1, 6, -1, 8, 4, 5, -1, + 8, 5, 3, -1, 8, 3, 0, -1, + 8, 0, 4, -1, 9, 5, 2, -1, + 9, 2, 7, -1, 9, 7, 5, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.00018439814 0.027588008 0.058410242, + -0.031500004 0.027588008 0.010762727, + 0.00018439814 0.027588008 0.017622577, + -0.048315603 0.027588008 0.058410242, + -0.023637401 0.10556971 0.028017199, + -0.040500008 0.027588008 0.015975006, + -0.024737252 0.099855907 0.035417106, + -0.038262755 0.10620452 0.028000053, + -0.024737252 0.10129601 0.022182798, + -0.038697127 0.10080991 0.0221607 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 1, 0, -1, + 4, 0, 2, -1, 5, 1, 3, -1, + 6, 0, 4, -1, 6, 4, 7, -1, + 6, 7, 3, -1, 6, 3, 0, -1, + 8, 7, 4, -1, 8, 2, 1, -1, + 8, 4, 2, -1, 9, 7, 8, -1, + 9, 8, 1, -1, 9, 3, 7, -1, + 9, 5, 3, -1, 9, 1, 5, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.0486844 0.027588004 0.050301023, + 0.032857958 -0.037940212 0.050301015, + -0.042499546 -0.03033125 0.050301023, + -0.048315603 0.027588004 0.058410242, + 0.040158235 0.013428603 0.10060205, + 0.046137802 -0.0257027 0.087703303, + -0.041874573 -0.012687683 0.10060205, + -0.03967829 0.01349124 0.10060205, + 0.048493259 -0.023162942 0.050301023, + -0.04336771 -0.029446201 0.081836902 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 0, -1, + 3, 0, 2, -1, 5, 4, 6, -1, + 5, 0, 4, -1, 7, 4, 3, -1, + 7, 3, 6, -1, 7, 6, 4, -1, + 8, 1, 0, -1, 8, 0, 5, -1, + 8, 5, 1, -1, 9, 1, 5, -1, + 9, 5, 6, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 6, 3, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.048315603 0.027588008 0.050301023, + 0.032485802 -0.038153239 0.050301023, + 0.0486844 0.027588008 0.050301023, + -0.044686221 -0.028954573 0.050301023, + 0.015744701 -0.050205603 0.00183213, + -0.013262501 -0.0149702 -1.1201196e-09, + 0.020000001 4.7734761e-11 -1.1209923e-09, + -0.034654204 0.0261198 0.0098788505, + -0.039072301 -0.025067603 0.01081, + 0.045006908 -0.022869501 0.025559999 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 1, 0, -1, + 4, 1, 3, -1, 4, 5, 6, -1, + 7, 6, 5, -1, 7, 2, 6, -1, + 7, 0, 2, -1, 8, 3, 0, -1, + 8, 0, 7, -1, 8, 7, 5, -1, + 8, 5, 4, -1, 8, 4, 3, -1, + 9, 2, 1, -1, 9, 1, 4, -1, + 9, 6, 2, -1, 9, 4, 6, -1 ] + + } + + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.grasp.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.grasp.wrl new file mode 100644 index 0000000..7d8a9a4 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.grasp.wrl @@ -0,0 +1,192 @@ +#VRML V2.0 utf8 + +#Created by boundingmesh +Shape { + appearance Appearance { + material Material { + diffuseColor 1 1 1 + } + } + geometry IndexedFaceSet { + convex FALSE, + solid TRUE + coord Coordinate { + point [ + -0.0574553 0.099177 0.0161828, + -0.0574553 0.00567701 0.0161828, + -0.0574553 0.00567701 0.0469828, + -0.0574553 0.099177 0.0469828, + -0.0266553 0.099177 0.0469828, + -0.0266553 0.099177 0.0161828, + -0.0266553 0.00567701 0.0469828, + -0.0266553 0.00567701 0.0161828, + -0.0531472 0.0303468 0.0553311, + 0.0357344 -0.0419686 0.0553311, + 0.0535528 0.0303468 0.0553311, + -0.0491548 -0.03185 0.0553311, + 0.0173192 -0.0552262 0.00201534, + -0.0145888 -0.0164672 -6.76547e-10, + 0.022 5.25083e-11 -3.15639e-09, + -0.0381196 0.0287318 0.0108667, + -0.0429795 -0.0275744 0.011891, + 0.0495076 -0.0251565 0.028116, + 0.0535528 0.0303468 0.0553311, + 0.0361438 -0.0417342 0.0553311, + -0.0467495 -0.0333644 0.0553311, + -0.0531472 0.0303468 0.0642513, + 0.0441741 0.0147715 0.110662, + 0.0507516 -0.028273 0.0964736, + -0.046062 -0.0139565 0.110662, + -0.0436461 0.0148404 0.110662, + 0.0533426 -0.0254792 0.0553311, + -0.0477045 -0.0323908 0.0900206, + -0.000860711 0.0158862 0.0997755, + -0.000874538 -0.0126256 0.108935, + -0.0464108 -0.0123856 0.109232, + -0.00042987 0.0283191 0.153896, + -0.0448277 0.0159323 0.100122, + -0.0401142 0.0225265 0.156083, + -0.000439432 0.00860343 0.16023, + -0.0371348 0.00871658 0.160495, + -0.0372155 0.0284074 0.15417, + -0.040193 0.0118163 0.159524, + 0.0457115 0.0101131 0.101247, + 0.0446464 -0.0126405 0.108566, + 0.0362933 0.0281027 0.153664, + 0.0359706 0.00856611 0.159942, + 0.0429035 0.0157611 0.099456, + 0.0389845 0.0122294 0.158741, + 0.00107159 0.0211526 0.142467, + 0.00219777 0.0098046 0.159752, + -0.0343652 0.0098538 0.162069, + 0.00367258 0.0611748 0.182255, + -0.0359358 0.0210421 0.145057, + -0.0359763 0.0577435 0.172627, + -0.0347765 0.0537607 0.187636, + -0.0348109 0.0617148 0.18348, + 0.00286988 0.057868 0.169958, + 0.00383471 0.0524554 0.184758, + 0.0409208 0.0177163 0.145115, + 0.0386053 0.00980394 0.15737, + 0.00219777 0.00980458 0.159752, + 0.00384026 0.0580716 0.184832, + 0.00157026 0.0332206 0.150086, + 0.00107159 0.0211526 0.142466, + 0.00300513 0.05967 0.172027, + 0.0418305 0.0611698 0.179766, + 0.0412153 0.0568855 0.166618, + 0.0422309 0.0523678 0.182195, + ] + } + coordIndex [ + 0, 1, 2, -1, + 2, 3, 0, -1, + 3, 4, 5, -1, + 5, 0, 3, -1, + 4, 6, 7, -1, + 7, 5, 4, -1, + 1, 7, 6, -1, + 6, 2, 1, -1, + 1, 0, 5, -1, + 5, 7, 1, -1, + 6, 4, 3, -1, + 3, 2, 6, -1, + 8, 9, 10, -1, + 11, 9, 8, -1, + 12, 9, 11, -1, + 12, 13, 14, -1, + 15, 14, 13, -1, + 15, 10, 14, -1, + 15, 8, 10, -1, + 16, 11, 8, -1, + 16, 8, 15, -1, + 16, 15, 13, -1, + 16, 13, 12, -1, + 16, 12, 11, -1, + 17, 10, 9, -1, + 17, 9, 12, -1, + 17, 14, 10, -1, + 17, 12, 14, -1, + 18, 19, 20, -1, + 21, 22, 18, -1, + 21, 18, 20, -1, + 23, 22, 24, -1, + 23, 18, 22, -1, + 25, 22, 21, -1, + 25, 21, 24, -1, + 25, 24, 22, -1, + 26, 19, 18, -1, + 26, 18, 23, -1, + 26, 23, 19, -1, + 27, 19, 23, -1, + 27, 23, 24, -1, + 27, 20, 19, -1, + 27, 21, 20, -1, + 27, 24, 21, -1, + 28, 29, 30, -1, + 29, 28, 31, -1, + 32, 28, 30, -1, + 33, 32, 30, -1, + 34, 29, 31, -1, + 34, 31, 33, -1, + 35, 34, 33, -1, + 35, 30, 29, -1, + 35, 29, 34, -1, + 36, 32, 33, -1, + 36, 33, 31, -1, + 36, 31, 28, -1, + 36, 28, 32, -1, + 37, 33, 30, -1, + 37, 30, 35, -1, + 37, 35, 33, -1, + 38, 39, 29, -1, + 28, 38, 29, -1, + 34, 28, 29, -1, + 31, 28, 34, -1, + 31, 34, 40, -1, + 41, 40, 34, -1, + 41, 29, 39, -1, + 41, 34, 29, -1, + 42, 28, 31, -1, + 42, 31, 40, -1, + 42, 40, 38, -1, + 42, 38, 28, -1, + 43, 39, 38, -1, + 43, 41, 39, -1, + 43, 38, 40, -1, + 43, 40, 41, -1, + 44, 45, 46, -1, + 45, 44, 47, -1, + 48, 44, 46, -1, + 48, 46, 49, -1, + 48, 49, 44, -1, + 50, 49, 46, -1, + 51, 49, 50, -1, + 51, 50, 47, -1, + 52, 49, 51, -1, + 52, 51, 47, -1, + 52, 47, 44, -1, + 52, 44, 49, -1, + 53, 45, 47, -1, + 53, 47, 50, -1, + 53, 46, 45, -1, + 53, 50, 46, -1, + 54, 55, 56, -1, + 57, 58, 56, -1, + 59, 54, 56, -1, + 59, 56, 58, -1, + 60, 58, 57, -1, + 60, 57, 61, -1, + 62, 58, 60, -1, + 62, 60, 61, -1, + 62, 54, 59, -1, + 62, 59, 58, -1, + 63, 54, 62, -1, + 63, 62, 61, -1, + 63, 61, 57, -1, + 63, 56, 55, -1, + 63, 57, 56, -1, + 63, 55, 54, -1, + ] + } +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.wrl new file mode 100644 index 0000000..e8d473a --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.thumbfix.wrl @@ -0,0 +1,285 @@ +#VRML V2.0 utf8 + + +DEF solid_H2R3_hand__________________________________________________________ Transform { + #scale 0.90 0.90 0.90 + scale 1.1 1.1 1.1 + children [ + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.035993379 0.0035270932 0.15090306, + 0.033168469 -0.0095995218 0.15090306, + 0 -0.0096063418 0.15090306, + 0 -0.0046731597 0.20012818, + 0 0.0094246399 0.16388398, + 0 0.009219164 0.15090306, + 0 0.0058807195 0.19495119, + 0.034762751 -0.0011638075 0.20120168, + 0.034983277 0.0067091119 0.19138768, + 0.034983285 -0.0074115978 0.19572869 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 2, -1, + 5, 0, 2, -1, 5, 2, 4, -1, + 6, 4, 3, -1, 6, 3, 7, -1, + 8, 4, 6, -1, 8, 6, 7, -1, + 8, 0, 5, -1, 8, 5, 4, -1, + 9, 0, 8, -1, 9, 8, 7, -1, + 9, 7, 3, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 1, 0, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0 0.009219164 0.15090308, + 0 -0.0096063418 0.15090308, + -0.033305667 -0.009532637 0.15090308, + 0 -0.0011638099 0.20120169, + -0.033725008 0.0090277288 0.15090308, + -0.035397753 0.0063928161 0.19251639, + -0.03519712 -0.0070392122 0.19698757, + -0.034983281 7.8515601e-05 0.20096919, + -4.6566129e-10 0.0065600597 0.19254768, + 0 -0.0074147745 0.19582054 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 4, 2, 5, -1, + 4, 5, 0, -1, 6, 5, 2, -1, + 7, 5, 6, -1, 7, 6, 3, -1, + 8, 5, 7, -1, 8, 7, 3, -1, + 8, 3, 0, -1, 8, 0, 5, -1, + 9, 1, 3, -1, 9, 3, 6, -1, + 9, 2, 1, -1, 9, 6, 2, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.042527255 0.0081201596 0.10060205, + 0.041568972 -0.013609005 0.10060205, + 0.00018507987 -0.013717981 0.10060205, + 0.00018507987 0.013506617 0.10060205, + 0.00018507987 -0.0096063409 0.15090308, + 0.00018507987 0.0092191631 0.15090308, + 0.033570837 0.0091119334 0.15090308, + 0.033286072 -0.0095434729 0.15090308, + 0.03997194 0.013505501 0.10060205, + 0.036024474 -0.0060374229 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 0, 2, -1, + 4, 3, 2, -1, 5, 3, 4, -1, + 5, 4, 6, -1, 7, 6, 4, -1, + 7, 2, 1, -1, 7, 4, 2, -1, + 8, 3, 5, -1, 8, 5, 6, -1, + 8, 6, 0, -1, 8, 0, 3, -1, + 9, 1, 0, -1, 9, 7, 1, -1, + 9, 0, 6, -1, 9, 6, 7, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.00018507986 0.013506617 0.10060205, + 0.00018507986 -0.013717981 0.10060205, + -0.04121282 -0.013611966 0.10060205, + 0.00018507986 0.0092191631 0.15090308, + -0.039786119 0.01343167 0.10060205, + -0.035890073 0.0035807528 0.15090308, + 0.00018507986 -0.0096063409 0.15090308, + -0.033175375 -0.0095975753 0.15090308, + -0.033257447 0.0092040151 0.15090308, + -0.035957031 -0.0066460879 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 5, 4, 2, -1, + 6, 1, 3, -1, 6, 3, 5, -1, + 7, 6, 5, -1, 7, 2, 1, -1, + 7, 1, 6, -1, 8, 4, 5, -1, + 8, 5, 3, -1, 8, 3, 0, -1, + 8, 0, 4, -1, 9, 5, 2, -1, + 9, 2, 7, -1, 9, 7, 5, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.0486844 0.027588004 0.050301023, + 0.032857958 -0.037940212 0.050301015, + -0.042499546 -0.03033125 0.050301023, + -0.048315603 0.027588004 0.058410242, + 0.040158235 0.013428603 0.10060205, + 0.046137802 -0.0257027 0.087703303, + -0.041874573 -0.012687683 0.10060205, + -0.03967829 0.01349124 0.10060205, + 0.048493259 -0.023162942 0.050301023, + -0.04336771 -0.029446201 0.081836902 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 0, -1, + 3, 0, 2, -1, 5, 4, 6, -1, + 5, 0, 4, -1, 7, 4, 3, -1, + 7, 3, 6, -1, 7, 6, 4, -1, + 8, 1, 0, -1, 8, 0, 5, -1, + 8, 5, 1, -1, 9, 1, 5, -1, + 9, 5, 6, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 6, 3, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.048315603 0.027588008 0.050301023, + 0.032485802 -0.038153239 0.050301023, + 0.0486844 0.027588008 0.050301023, + -0.044686221 -0.028954573 0.050301023, + 0.015744701 -0.050205603 0.00183213, + -0.013262501 -0.0149702 -1.1201196e-09, + 0.020000001 4.7734761e-11 -1.1209923e-09, + -0.034654204 0.0261198 0.0098788505, + -0.039072301 -0.025067603 0.01081, + 0.045006908 -0.022869501 0.025559999 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 1, 0, -1, + 4, 1, 3, -1, 4, 5, 6, -1, + 7, 6, 5, -1, 7, 2, 6, -1, + 7, 0, 2, -1, 8, 3, 0, -1, + 8, 0, 7, -1, 8, 7, 5, -1, + 8, 5, 4, -1, 8, 4, 3, -1, + 9, 2, 1, -1, 9, 1, 4, -1, + 9, 6, 2, -1, 9, 4, 6, -1 ] + + } + + } + + DEF simpleHand Transform { + # dimensions: 1) left 2) away from me 3) top + translation -0.077 0.01 0.025 # original pose: -0.024 0.066 0.03 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.75294101 0.75294101 0.75294101 # 1.0 1.0 0.0 + } + } + geometry Box { + size 0.085 0.028 0.028 # original pose: 0.035 0.08 0.035 + } + } + ] + } + + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.wrl new file mode 100644 index 0000000..0262a1b --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/mekabot-h2r3-right.minimal.wrl @@ -0,0 +1,284 @@ +#VRML V2.0 utf8 + + +DEF solid_H2R3_hand__________________________________________________________ Transform { + scale 0.90 0.90 0.90 + children [ + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.035993379 0.0035270932 0.15090306, + 0.033168469 -0.0095995218 0.15090306, + 0 -0.0096063418 0.15090306, + 0 -0.0046731597 0.20012818, + 0 0.0094246399 0.16388398, + 0 0.009219164 0.15090306, + 0 0.0058807195 0.19495119, + 0.034762751 -0.0011638075 0.20120168, + 0.034983277 0.0067091119 0.19138768, + 0.034983285 -0.0074115978 0.19572869 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 2, -1, + 5, 0, 2, -1, 5, 2, 4, -1, + 6, 4, 3, -1, 6, 3, 7, -1, + 8, 4, 6, -1, 8, 6, 7, -1, + 8, 0, 5, -1, 8, 5, 4, -1, + 9, 0, 8, -1, 9, 8, 7, -1, + 9, 7, 3, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 1, 0, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0 0.009219164 0.15090308, + 0 -0.0096063418 0.15090308, + -0.033305667 -0.009532637 0.15090308, + 0 -0.0011638099 0.20120169, + -0.033725008 0.0090277288 0.15090308, + -0.035397753 0.0063928161 0.19251639, + -0.03519712 -0.0070392122 0.19698757, + -0.034983281 7.8515601e-05 0.20096919, + -4.6566129e-10 0.0065600597 0.19254768, + 0 -0.0074147745 0.19582054 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 4, 2, 5, -1, + 4, 5, 0, -1, 6, 5, 2, -1, + 7, 5, 6, -1, 7, 6, 3, -1, + 8, 5, 7, -1, 8, 7, 3, -1, + 8, 3, 0, -1, 8, 0, 5, -1, + 9, 1, 3, -1, 9, 3, 6, -1, + 9, 2, 1, -1, 9, 6, 2, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.042527255 0.0081201596 0.10060205, + 0.041568972 -0.013609005 0.10060205, + 0.00018507987 -0.013717981 0.10060205, + 0.00018507987 0.013506617 0.10060205, + 0.00018507987 -0.0096063409 0.15090308, + 0.00018507987 0.0092191631 0.15090308, + 0.033570837 0.0091119334 0.15090308, + 0.033286072 -0.0095434729 0.15090308, + 0.03997194 0.013505501 0.10060205, + 0.036024474 -0.0060374229 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 0, 2, -1, + 4, 3, 2, -1, 5, 3, 4, -1, + 5, 4, 6, -1, 7, 6, 4, -1, + 7, 2, 1, -1, 7, 4, 2, -1, + 8, 3, 5, -1, 8, 5, 6, -1, + 8, 6, 0, -1, 8, 0, 3, -1, + 9, 1, 0, -1, 9, 7, 1, -1, + 9, 0, 6, -1, 9, 6, 7, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.00018507986 0.013506617 0.10060205, + 0.00018507986 -0.013717981 0.10060205, + -0.04121282 -0.013611966 0.10060205, + 0.00018507986 0.0092191631 0.15090308, + -0.039786119 0.01343167 0.10060205, + -0.035890073 0.0035807528 0.15090308, + 0.00018507986 -0.0096063409 0.15090308, + -0.033175375 -0.0095975753 0.15090308, + -0.033257447 0.0092040151 0.15090308, + -0.035957031 -0.0066460879 0.15090308 ] + + } + coordIndex [ 0, 1, 2, -1, 1, 0, 3, -1, + 4, 0, 2, -1, 5, 4, 2, -1, + 6, 1, 3, -1, 6, 3, 5, -1, + 7, 6, 5, -1, 7, 2, 1, -1, + 7, 1, 6, -1, 8, 4, 5, -1, + 8, 5, 3, -1, 8, 3, 0, -1, + 8, 0, 4, -1, 9, 5, 2, -1, + 9, 2, 7, -1, 9, 7, 5, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 0.0486844 0.027588004 0.050301023, + 0.032857958 -0.037940212 0.050301015, + -0.042499546 -0.03033125 0.050301023, + -0.048315603 0.027588004 0.058410242, + 0.040158235 0.013428603 0.10060205, + 0.046137802 -0.0257027 0.087703303, + -0.041874573 -0.012687683 0.10060205, + -0.03967829 0.01349124 0.10060205, + 0.048493259 -0.023162942 0.050301023, + -0.04336771 -0.029446201 0.081836902 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 4, 0, -1, + 3, 0, 2, -1, 5, 4, 6, -1, + 5, 0, 4, -1, 7, 4, 3, -1, + 7, 3, 6, -1, 7, 6, 4, -1, + 8, 1, 0, -1, 8, 0, 5, -1, + 8, 5, 1, -1, 9, 1, 5, -1, + 9, 5, 6, -1, 9, 2, 1, -1, + 9, 3, 2, -1, 9, 6, 3, -1 ] + + } + + } + + Shape { + appearance + Appearance { + material + Material { + diffuseColor 0.75294101 0.75294101 0.75294101 + ambientIntensity 0.117647 + specularColor 0.75294101 0.75294101 0.75294101 + emissiveColor 0 0 0 + shininess 0.0625 + + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -0.048315603 0.027588008 0.050301023, + 0.032485802 -0.038153239 0.050301023, + 0.0486844 0.027588008 0.050301023, + -0.044686221 -0.028954573 0.050301023, + 0.015744701 -0.050205603 0.00183213, + -0.013262501 -0.0149702 -1.1201196e-09, + 0.020000001 4.7734761e-11 -1.1209923e-09, + -0.034654204 0.0261198 0.0098788505, + -0.039072301 -0.025067603 0.01081, + 0.045006908 -0.022869501 0.025559999 ] + + } + coordIndex [ 0, 1, 2, -1, 3, 1, 0, -1, + 4, 1, 3, -1, 4, 5, 6, -1, + 7, 6, 5, -1, 7, 2, 6, -1, + 7, 0, 2, -1, 8, 3, 0, -1, + 8, 0, 7, -1, 8, 7, 5, -1, + 8, 5, 4, -1, 8, 4, 3, -1, + 9, 2, 1, -1, 9, 1, 4, -1, + 9, 6, 2, -1, 9, 4, 6, -1 ] + + } + + } + + DEF simpleHand Transform { + # dimensions: 1) left 2) away from me 3) top + translation -0.08 0.0 0.03 # original pose: -0.024 0.066 0.03 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.75294101 0.75294101 0.75294101 # 1.0 1.0 0.0 + } + } + geometry Box { + size 0.08 0.035 0.035 # original pose: 0.035 0.08 0.035 + } + } + ] + } + + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 1.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 1.wrl new file mode 100644 index 0000000..afa5b67 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 1.wrl @@ -0,0 +1,1772 @@ +#VRML V2.0 utf8 + +WorldInfo { + title "pliers" + info [ "File produced by AccuTrans 3D" ] +} +NavigationInfo { + type [ "EXAMINE", "ANY" ] +} +DEF VP1 Viewpoint { + position -0.493699 2.249096 12.945078 + orientation 0 0 1 0 + fieldOfView 0.785398 + description "Front" +} +DEF VP2 Viewpoint { + position 10.306009 2.249096 2.145371 + orientation 0 1 0 1.570796 + fieldOfView 0.785398 + description "Right" +} +DEF VP3 Viewpoint { + position -0.493699 2.249096 -8.654337 + orientation 0 1 0 3.141592 + fieldOfView 0.785398 + description "Back" +} +DEF VP4 Viewpoint { + position -11.293407 2.249096 2.145371 + orientation 0 1 0 -1.570796 + fieldOfView 0.785398 + description "Left" +} +DEF VP5 Viewpoint { + position -0.493699 13.048804 2.145371 + orientation 1 0 0 -1.570796 + fieldOfView 0.785398 + description "Top" +} +DEF VP6 Viewpoint { + position -0.493699 -8.550612 2.145371 + orientation 1 0 0 1.570796 + fieldOfView 0.785398 + description "Bottom" +} +Transform { +scale 0.01 0.01 0.01 +rotation 1 0 0 1.6 +translation 0 0.02 0 + children [ + DEF Cylinder Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.574426 -1.350807 3.703954, + -0.574426 0.646338 3.717323, + -0.4216 -1.350807 3.719007, + -0.424208 0.646338 3.732118, + -0.274647 -1.350807 3.763584, + -0.279763 0.646338 3.775935, + -0.139215 -1.350807 3.835974, + -0.146642 0.646338 3.84709, + -0.020507 -1.350807 3.933395, + -0.02996 0.646338 3.942848, + 0.076914 -1.350807 4.052103, + 0.065798 0.646338 4.05953, + 0.149304 -1.350807 4.187535, + 0.136953 0.646338 4.192651, + 0.193881 -1.350807 4.334488, + 0.180769 0.646338 4.337096, + 0.208933 -1.350807 4.487314, + 0.195564 0.646338 4.487313, + 0.193881 -1.350807 4.640139, + 0.180769 0.646338 4.637531, + 0.149304 -1.350807 4.787092, + 0.136952 0.646338 4.781976, + 0.076913 -1.350807 4.922524, + 0.065798 0.646338 4.915097, + -0.020507 -1.350807 5.041232, + -0.029961 0.646338 5.031779, + -0.139215 -1.350807 5.138653, + -0.146642 0.646338 5.127537, + -0.274647 -1.350807 5.211043, + -0.279763 0.646338 5.198692, + -0.4216 -1.350807 5.25562, + -0.424208 0.646338 5.242509, + -0.574426 -1.350807 5.270673, + -0.574426 0.646338 5.257304, + -0.727252 -1.350807 5.25562, + -0.724644 0.646338 5.242509, + -0.874205 -1.350807 5.211043, + -0.869089 0.646338 5.198692, + -1.009637 -1.350807 5.138653, + -1.00221 0.646338 5.127537, + -1.128345 -1.350807 5.041232, + -1.118892 0.646338 5.031779, + -1.225765 -1.350807 4.922524, + -1.21465 0.646338 4.915097, + -1.298156 -1.350807 4.787092, + -1.285805 0.646338 4.781976, + -1.342733 -1.350807 4.640139, + -1.329621 0.646338 4.637531, + -1.357785 -1.350807 4.487313, + -1.344416 0.646338 4.487313, + -1.342733 -1.350807 4.334487, + -1.329621 0.646338 4.337095, + -1.298155 -1.350807 4.187534, + -1.285804 0.646338 4.19265, + -1.225765 -1.350807 4.052102, + -1.214649 0.646338 4.059529, + -1.128344 -1.350807 3.933394, + -1.118891 0.646338 3.942847, + -1.009636 -1.350807 3.835974, + -1.002209 0.646338 3.847089, + -0.874203 -1.350807 3.763584, + -0.869087 0.646338 3.775935, + -0.72725 -1.350807 3.719006, + -0.724642 0.646338 3.732118, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-001 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.495188 -1.164218 -0.979932, + -0.495188 0.801614 -0.933546, + -0.342362 -1.164218 -0.96488, + -0.351411 0.801614 -0.919385, + -0.195409 -1.164218 -0.920302, + -0.21316 0.801614 -0.877447, + -0.059977 -1.164218 -0.847912, + -0.085747 0.801614 -0.809344, + 0.058731 -1.164218 -0.750491, + 0.025931 0.801614 -0.717691, + 0.156152 -1.164218 -0.631783, + 0.117584 0.801614 -0.606013, + 0.228542 -1.164218 -0.496351, + 0.185687 0.801614 -0.4786, + 0.27312 -1.164218 -0.349398, + 0.227625 0.801614 -0.340349, + 0.288172 -1.164218 -0.196573, + 0.241786 0.801614 -0.196573, + 0.27312 -1.164218 -0.043747, + 0.227625 0.801614 -0.052796, + 0.228542 -1.164218 0.103206, + 0.185687 0.801614 0.085455, + 0.156152 -1.164218 0.238638, + 0.117584 0.801614 0.212868, + 0.058731 -1.164218 0.357346, + 0.025931 0.801614 0.324546, + -0.059977 -1.164218 0.454767, + -0.085747 0.801614 0.416199, + -0.195409 -1.164218 0.527157, + -0.21316 0.801614 0.484302, + -0.342362 -1.164218 0.571735, + -0.351411 0.801614 0.52624, + -0.495188 -1.164218 0.586787, + -0.495188 0.801614 0.540401, + -0.648014 -1.164218 0.571734, + -0.638964 0.801614 0.52624, + -0.794966 -1.164218 0.527157, + -0.777215 0.801614 0.484302, + -0.930399 -1.164218 0.454766, + -0.904629 0.801614 0.416198, + -1.049106 -1.164218 0.357346, + -1.016307 0.801614 0.324546, + -1.146527 -1.164218 0.238638, + -1.107959 0.801614 0.212868, + -1.218917 -1.164219 0.103205, + -1.176063 0.801614 0.085455, + -1.263495 -1.164218 -0.043747, + -1.218 0.801614 -0.052797, + -1.278547 -1.164218 -0.196573, + -1.232161 0.801614 -0.196573, + -1.263494 -1.164219 -0.349399, + -1.218 0.801614 -0.34035, + -1.218917 -1.164219 -0.496352, + -1.176062 0.801614 -0.478601, + -1.146526 -1.164218 -0.631784, + -1.107958 0.801614 -0.606014, + -1.049105 -1.164218 -0.750492, + -1.016306 0.801614 -0.717692, + -0.930398 -1.164218 -0.847912, + -0.904627 0.801614 -0.809344, + -0.794965 -1.164219 -0.920302, + -0.777214 0.801614 -0.877448, + -0.648012 -1.164218 -0.96488, + -0.638963 0.801614 -0.919386, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-002 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.585476 0.602835 3.700898, + -0.585476 3.16733 1.943742, + -0.43265 0.602835 3.71595, + -0.435258 3.16733 1.958537, + -0.285697 0.602835 3.760528, + -0.290813 3.16733 2.002354, + -0.150264 0.602835 3.832918, + -0.157692 3.16733 2.073509, + -0.031557 0.602835 3.930339, + -0.04101 3.16733 2.169267, + 0.065864 0.602835 4.049047, + 0.054748 3.16733 2.285948, + 0.138254 0.602835 4.184479, + 0.125903 3.16733 2.419069, + 0.182832 0.602835 4.331432, + 0.16972 3.16733 2.563514, + 0.197884 0.602835 4.484258, + 0.184515 3.16733 2.713732, + 0.182832 0.602835 4.637083, + 0.16972 3.16733 2.86395, + 0.138254 0.602835 4.784036, + 0.125903 3.16733 3.008394, + 0.065864 0.602835 4.919468, + 0.054748 3.16733 3.141516, + -0.031557 0.602835 5.038176, + -0.04101 3.16733 3.258197, + -0.150265 0.602835 5.135597, + -0.157692 3.16733 3.353956, + -0.285697 0.602835 5.207987, + -0.290813 3.16733 3.42511, + -0.43265 0.602835 5.252564, + -0.435258 3.16733 3.468927, + -0.585476 0.602835 5.267616, + -0.585476 3.16733 3.483722, + -0.738302 0.602835 5.252564, + -0.735693 3.16733 3.468927, + -0.885254 0.602835 5.207987, + -0.880138 3.16733 3.42511, + -1.020687 0.602835 5.135596, + -1.01326 3.16733 3.353955, + -1.139394 0.602835 5.038176, + -1.129941 3.16733 3.258197, + -1.236815 0.602835 4.919468, + -1.225699 3.16733 3.141515, + -1.309205 0.602834 4.784036, + -1.296854 3.16733 3.008394, + -1.353783 0.602835 4.637083, + -1.340671 3.16733 2.863949, + -1.368834 0.602835 4.484257, + -1.355466 3.16733 2.713731, + -1.353782 0.602834 4.331431, + -1.340671 3.16733 2.563514, + -1.309204 0.602834 4.184478, + -1.296853 3.16733 2.419069, + -1.236814 0.602835 4.049046, + -1.225698 3.16733 2.285948, + -1.139393 0.602835 3.930338, + -1.12994 3.16733 2.169266, + -1.020685 0.602835 3.832918, + -1.013258 3.16733 2.073508, + -0.885253 0.602834 3.760528, + -0.880137 3.16733 2.002353, + -0.7383 0.602835 3.71595, + -0.735692 3.16733 1.958537, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-003 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.445154 0.812967 0.622434, + -0.342043 3.189795 2.268354, + -0.5986 0.812715 0.616381, + -0.492871 3.189548 2.262405, + -0.747915 0.811222 0.580535, + -0.639638 3.18808 2.22717, + -0.887362 0.808546 0.516272, + -0.776705 3.18545 2.164004, + -1.011582 0.80479 0.426063, + -0.898805 3.181758 2.075335, + -1.115801 0.800098 0.313375, + -1.001245 3.177146 1.964569, + -1.196013 0.79465 0.182537, + -1.080089 3.171791 1.835965, + -1.249137 0.788656 0.038578, + -1.132306 3.165899 1.694462, + -1.273131 0.782346 -0.11297, + -1.15589 3.159697 1.545501, + -1.267073 0.775962 -0.266283, + -1.149936 3.153422 1.394804, + -1.231196 0.76975 -0.415469, + -1.11467 3.147316 1.248164, + -1.166878 0.763949 -0.554795, + -1.05145 3.141613 1.111216, + -1.07659 0.758781 -0.678907, + -0.962704 3.136534 0.989222, + -0.963804 0.754445 -0.783036, + -0.851842 3.132272 0.88687, + -0.832853 0.751108 -0.863179, + -0.723126 3.128992 0.808095, + -0.688769 0.748898 -0.916257, + -0.581501 3.12682 0.755922, + -0.53709 0.7479 -0.94023, + -0.43241 3.125838 0.732358, + -0.383644 0.748152 -0.934177, + -0.281583 3.126086 0.738308, + -0.234329 0.749644 -0.898331, + -0.134816 3.127553 0.773543, + -0.094882 0.75232 -0.834068, + 0.002251 3.130183 0.836709, + 0.029338 0.756076 -0.743859, + 0.124351 3.133875 0.925378, + 0.133557 0.760768 -0.63117, + 0.226791 3.138488 1.036144, + 0.213769 0.766216 -0.500332, + 0.305635 3.143842 1.164749, + 0.266893 0.772211 -0.356373, + 0.357852 3.149734 1.306251, + 0.290887 0.778521 -0.204825, + 0.381437 3.155937 1.455213, + 0.284829 0.784905 -0.051512, + 0.375482 3.162212 1.605909, + 0.248951 0.791116 0.097674, + 0.340216 3.168318 1.75255, + 0.184633 0.796918 0.237, + 0.276995 3.17402 1.889498, + 0.094345 0.802086 0.361112, + 0.188249 3.1791 2.011492, + -0.018441 0.806422 0.46524, + 0.077387 3.183362 2.113843, + -0.149393 0.809759 0.545383, + -0.051329 3.186642 2.192619, + -0.293476 0.811969 0.598461, + -0.192954 3.188814 2.244791, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-004 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.437396 3.206373 2.914586, + -0.381931 4.774627 3.785861, + -0.549946 3.206189 2.910146, + -0.427748 4.773128 3.784562, + -0.659466 3.205094 2.883854, + -0.472837 4.768367 3.775377, + -0.761747 3.203131 2.836719, + -0.516108 4.760221 3.758628, + -0.85286 3.200376 2.770552, + -0.556699 4.748534 3.734807, + -0.929302 3.196934 2.687897, + -0.594018 4.733227 3.704406, + -0.988136 3.192939 2.591931, + -0.627649 4.714481 3.667699, + -1.027102 3.188542 2.48634, + -0.656989 4.692984 3.624568, + -1.044701 3.183913 2.375183, + -0.680655 4.670081 3.574621, + -1.040257 3.179231 2.262731, + -0.696033 4.647597 3.517839, + -1.013942 3.174675 2.153306, + -0.699628 4.627272 3.455525, + -0.966766 3.17042 2.051113, + -0.688284 4.610205 3.390795, + -0.900542 3.166629 1.960079, + -0.660432 4.596736 3.328116, + -0.817815 3.163449 1.883703, + -0.616566 4.586709 3.272326, + -0.721765 3.161001 1.82492, + -0.558983 4.579797 3.227767, + -0.616083 3.15938 1.785988, + -0.491253 4.575701 3.197805, + -0.504829 3.158648 1.768404, + -0.417731 4.574235 3.184615, + -0.39228 3.158833 1.772844, + -0.343167 4.575346 3.189119, + -0.28276 3.159928 1.799137, + -0.272383 4.579111 3.210957, + -0.180479 3.16189 1.846272, + -0.209958 4.585739 3.248474, + -0.089366 3.164645 1.912439, + -0.159829 4.595547 3.298747, + -0.012924 3.168087 1.995093, + -0.124782 4.608874 3.357729, + 0.04591 3.172083 2.09106, + -0.105868 4.62588 3.420674, + 0.084876 3.17648 2.196651, + -0.10205 4.646214 3.482962, + 0.102475 3.181108 2.307809, + -0.110563 4.668762 3.541134, + 0.098031 3.18579 2.42026, + -0.128097 4.691765 3.593492, + 0.071715 3.190347 2.529685, + -0.152068 4.713386 3.63975, + 0.024539 3.194602 2.631878, + -0.181067 4.732274 3.680135, + -0.041685 3.198392 2.722912, + -0.214486 4.747742 3.714694, + -0.124411 3.201573 2.799288, + -0.251945 4.759607 3.743103, + -0.220461 3.20402 2.858071, + -0.292914 4.767948 3.764802, + -0.326144 3.205642 2.897003, + -0.336591 4.772915 3.779205, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-005 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.553443 3.212656 1.410033, + -0.553429 4.777171 0.530312, + -0.441038 3.209718 1.416633, + -0.507697 4.774548 0.532497, + -0.3321 3.206061 1.445028, + -0.462923 4.768725 0.542569, + -0.230816 3.201826 1.494127, + -0.420194 4.759603 0.560184, + -0.141078 3.197174 1.562042, + -0.380367 4.747045 0.584836, + -0.066334 3.192285 1.646165, + -0.344025 4.730983 0.616021, + -0.009458 3.187346 1.743261, + -0.311574 4.711607 0.653457, + 0.027366 3.182548 1.849601, + -0.283604 4.689621 0.697246, + 0.042722 3.178075 1.961096, + -0.261469 4.666406 0.747747, + 0.036021 3.174099 2.073463, + -0.247737 4.64385 0.804922, + 0.007519 3.170772 2.182384, + -0.245836 4.623772 0.86739, + -0.041689 3.168222 2.283671, + -0.258832 4.607333 0.931973, + -0.10971 3.166548 2.373434, + -0.288199 4.594887 0.99417, + -0.193931 3.165813 2.448223, + -0.333355 4.586241 1.049155, + -0.291116 3.166047 2.505163, + -0.391932 4.580986 1.092633, + -0.397529 3.167239 2.542066, + -0.460301 4.578721 1.121309, + -0.509082 3.169345 2.557515, + -0.534075 4.579139 1.133093, + -0.621487 3.172282 2.550915, + -0.608489 4.582065 1.127153, + -0.730425 3.175939 2.52252, + -0.678729 4.58746 1.103943, + -0.831709 3.180175 2.473421, + -0.740244 4.595428 1.065203, + -0.921447 3.184827 2.405506, + -0.789147 4.606203 1.01393, + -0.99619 3.189716 2.321383, + -0.822722 4.620078 0.954223, + -1.053067 3.194654 2.224287, + -0.840005 4.637212 0.890845, + -1.08989 3.199452 2.117947, + -0.842129 4.657305 0.828398, + -1.105247 3.203926 2.006451, + -0.831953 4.679328 0.770292, + -1.098545 3.207902 1.894084, + -0.812859 4.701614 0.718171, + -1.070042 3.211229 1.785164, + -0.787483 4.722392 0.672278, + -1.020835 3.213778 1.683876, + -0.75726 4.740345 0.632365, + -0.952814 3.215453 1.594113, + -0.722816 4.754801 0.598381, + -0.868593 3.216187 1.519325, + -0.684539 4.765588 0.570639, + -0.771408 3.215954 1.462385, + -0.64297 4.772801 0.54969, + -0.664994 3.214762 1.425482, + -0.598916 4.776613 0.536105, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-006 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.417471 4.62188 3.214553, + -0.383292 5.829119 3.176633, + -0.366204 4.621978 3.219418, + -0.366026 5.829238 3.178442, + -0.31698 4.621546 3.234548, + -0.349433 5.828958 3.183247, + -0.271899 4.620595 3.259277, + -0.333882 5.828283 3.190925, + -0.232853 4.619149 3.292487, + -0.319824 5.827244 3.20131, + -0.20142 4.617244 3.332684, + -0.307702 5.825886 3.214175, + -0.178789 4.614928 3.378093, + -0.297956 5.824273 3.229237, + -0.165714 4.612271 3.426769, + -0.291016 5.822482 3.24613, + -0.16251 4.609363 3.476716, + -0.287294 5.820601 3.264389, + -0.169077 4.606317 3.52598, + -0.287146 5.818717 3.283425, + -0.18496 4.603263 3.572731, + -0.290826 5.816913 3.302523, + -0.209397 4.600342 3.615307, + -0.298428 5.815257 3.320859, + -0.241373 4.597683 3.65224, + -0.309834 5.813803 3.337551, + -0.279652 4.595408 3.682282, + -0.324694 5.812589 3.351729, + -0.322817 4.593613 3.704423, + -0.342426 5.811639 3.362603, + -0.3693 4.592367 3.71792, + -0.362245 5.810968 3.369542, + -0.417425 4.591719 3.722327, + -0.383211 5.810584 3.372122, + -0.465465 4.591681 3.717503, + -0.4043 5.81049 3.370167, + -0.511702 4.592251 3.703635, + -0.424468 5.810688 3.363765, + -0.554481 4.593395 3.681211, + -0.442729 5.811177 3.353257, + -0.592267 4.595063 3.651014, + -0.458222 5.811954 3.339219, + -0.62369 4.597186 3.614083, + -0.470269 5.813008 3.322411, + -0.647579 4.599678 3.571689, + -0.478415 5.814322 3.303716, + -0.662992 4.602438 3.5253, + -0.482454 5.815866 3.284068, + -0.669254 4.605364 3.476552, + -0.482413 5.817593 3.264378, + -0.665981 4.608338 3.427209, + -0.478526 5.819442 3.245474, + -0.653113 4.611246 3.37912, + -0.47118 5.821337 3.228053, + -0.630949 4.613976 3.334168, + -0.460861 5.823193 3.212667, + -0.600166 4.616421 3.294195, + -0.448091 5.824923 3.199708, + -0.56185 4.618521 3.260898, + -0.43343 5.826442 3.189485, + -0.517388 4.620152 3.235807, + -0.417337 5.827682 3.182146, + -0.468579 4.621416 3.219946, + -0.400524 5.828576 3.177867, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-007 Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 1.0 1.0 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.656396 4.642282 1.039134, + -0.535197 5.842075 1.115541, + -0.698175 4.649765 1.009971, + -0.549173 5.844676 1.105574, + -0.733258 4.656164 0.972817, + -0.561162 5.846708 1.093301, + -0.76016 4.661199 0.929279, + -0.570906 5.848124 1.079008, + -0.777792 4.664647 0.881249, + -0.578095 5.848892 1.063062, + -0.785521 4.666348 0.830803, + -0.582449 5.848999 1.045877, + -0.78318 4.666223 0.780069, + -0.58372 5.848449 1.027918, + -0.771061 4.664277 0.731112, + -0.581705 5.847267 1.009716, + -0.749853 4.660604 0.685834, + -0.576265 5.845489 0.991883, + -0.720579 4.655381 0.645895, + -0.567366 5.843165 0.97511, + -0.684507 4.64885 0.612678, + -0.555128 5.840357 0.960148, + -0.643085 4.641302 0.587268, + -0.539862 5.837142 0.947764, + -0.597886 4.633054 0.570458, + -0.522093 5.83361 0.938674, + -0.550565 4.624436 0.562745, + -0.502541 5.829874 0.933469, + -0.502824 4.615776 0.564325, + -0.482092 5.826062 0.932555, + -0.456366 4.607394 0.575086, + -0.461725 5.82232 0.936103, + -0.412847 4.599592 0.594607, + -0.442457 5.818803 0.944026, + -0.37382 4.59264 0.622169, + -0.425256 5.815671 0.95598, + -0.340675 4.586783 0.656776, + -0.410978 5.813075 0.971381, + -0.314605 4.582217 0.697194, + -0.400306 5.81115 0.989451, + -0.296556 4.579097 0.741993, + -0.393701 5.810004 1.009269, + -0.287211 4.57753 0.789596, + -0.391379 5.809708 1.029842, + -0.286972 4.577569 0.83832, + -0.3933 5.810288 1.050178, + -0.295946 4.579217 0.886422, + -0.399194 5.811721 1.069361, + -0.313932 4.582429 0.932143, + -0.408596 5.813934 1.086605, + -0.340418 4.5871 0.973749, + -0.420912 5.816811 1.101299, + -0.374565 4.593079 1.009593, + -0.435478 5.820203 1.113021, + -0.415215 4.600164 1.038171, + -0.451616 5.82394 1.121521, + -0.460901 4.608105 1.058201, + -0.4687 5.827849 1.126704, + -0.509867 4.616637 1.068727, + -0.486106 5.831758 1.12857, + -0.560187 4.625399 1.069082, + -0.503378 5.835527 1.127211, + -0.6098 4.6342 1.059254, + -0.519826 5.838983 1.122815, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 2.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 2.wrl new file mode 100644 index 0000000..c4e7a5b --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 2.wrl @@ -0,0 +1,1772 @@ +#VRML V2.0 utf8 + +WorldInfo { + title "pliers2" + info [ "File produced by AccuTrans 3D" ] +} +NavigationInfo { + type [ "EXAMINE", "ANY" ] +} +DEF VP1 Viewpoint { + position -0.448555 2.405584 13.485098 + orientation 0 0 1 0 + fieldOfView 0.785398 + description "Front" +} +DEF VP2 Viewpoint { + position 10.891172 2.405584 2.145371 + orientation 0 1 0 1.570796 + fieldOfView 0.785398 + description "Right" +} +DEF VP3 Viewpoint { + position -0.448555 2.405584 -9.194357 + orientation 0 1 0 3.141592 + fieldOfView 0.785398 + description "Back" +} +DEF VP4 Viewpoint { + position -11.788282 2.405584 2.145371 + orientation 0 1 0 -1.570796 + fieldOfView 0.785398 + description "Left" +} +DEF VP5 Viewpoint { + position -0.448555 13.745312 2.145371 + orientation 1 0 0 -1.570796 + fieldOfView 0.785398 + description "Top" +} +DEF VP6 Viewpoint { + position -0.448555 -8.934143 2.145371 + orientation 1 0 0 1.570796 + fieldOfView 0.785398 + description "Bottom" +} +Transform { +scale 0.01 0.01 0.01 +rotation 1 0 0 1.6 +translation 0 0.02 0 + children [ + DEF Cylinder Shape { + appearance Appearance { + material Material { + ambientIntensity 0 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.469519 -1.350807 3.703954, + -0.469519 0.646338 3.717323, + -0.316693 -1.350807 3.719007, + -0.319301 0.646338 3.732118, + -0.16974 -1.350807 3.763584, + -0.174856 0.646338 3.775935, + -0.034307 -1.350807 3.835974, + -0.041735 0.646338 3.84709, + 0.0844 -1.350807 3.933395, + 0.074947 0.646338 3.942848, + 0.181821 -1.350807 4.052103, + 0.170705 0.646338 4.05953, + 0.254211 -1.350807 4.187535, + 0.24186 0.646338 4.192651, + 0.298789 -1.350807 4.334488, + 0.285677 0.646338 4.337096, + 0.313841 -1.350807 4.487314, + 0.300472 0.646338 4.487313, + 0.298789 -1.350807 4.640139, + 0.285677 0.646338 4.637531, + 0.254211 -1.350807 4.787092, + 0.24186 0.646338 4.781976, + 0.181821 -1.350807 4.922524, + 0.170705 0.646338 4.915097, + 0.0844 -1.350807 5.041232, + 0.074947 0.646338 5.031779, + -0.034308 -1.350807 5.138653, + -0.041735 0.646338 5.127537, + -0.16974 -1.350807 5.211043, + -0.174856 0.646338 5.198692, + -0.316693 -1.350807 5.25562, + -0.319301 0.646338 5.242509, + -0.469519 -1.350807 5.270673, + -0.469519 0.646338 5.257304, + -0.622345 -1.350807 5.25562, + -0.619736 0.646338 5.242509, + -0.769297 -1.350807 5.211043, + -0.764181 0.646338 5.198692, + -0.90473 -1.350807 5.138653, + -0.897303 0.646338 5.127537, + -1.023437 -1.350807 5.041232, + -1.013984 0.646338 5.031779, + -1.120858 -1.350807 4.922524, + -1.109742 0.646338 4.915097, + -1.193248 -1.350807 4.787092, + -1.180897 0.646338 4.781976, + -1.237826 -1.350807 4.640139, + -1.224714 0.646338 4.637531, + -1.252877 -1.350807 4.487313, + -1.239509 0.646338 4.487313, + -1.237825 -1.350807 4.334487, + -1.224714 0.646338 4.337095, + -1.193248 -1.350807 4.187534, + -1.180897 0.646338 4.19265, + -1.120857 -1.350807 4.052102, + -1.109742 0.646338 4.059529, + -1.023436 -1.350807 3.933394, + -1.013983 0.646338 3.942847, + -0.904729 -1.350807 3.835974, + -0.897301 0.646338 3.847089, + -0.769296 -1.350807 3.763584, + -0.76418 0.646338 3.775935, + -0.622343 -1.350807 3.719006, + -0.619735 0.646338 3.732118, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-001 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9255 + diffuseColor 0.9255 0.4431 0.051 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.495188 -1.374325 -0.979932, + -0.495188 0.766596 -0.933546, + -0.342362 -1.374325 -0.96488, + -0.351411 0.766596 -0.919385, + -0.195409 -1.374325 -0.920302, + -0.21316 0.766596 -0.877447, + -0.059977 -1.374325 -0.847912, + -0.085747 0.766596 -0.809344, + 0.058731 -1.374325 -0.750491, + 0.025931 0.766596 -0.717691, + 0.156152 -1.374325 -0.631783, + 0.117584 0.766596 -0.606013, + 0.228542 -1.374325 -0.496351, + 0.185687 0.766596 -0.4786, + 0.27312 -1.374325 -0.349398, + 0.227625 0.766596 -0.340349, + 0.288172 -1.374325 -0.196573, + 0.241786 0.766596 -0.196573, + 0.27312 -1.374325 -0.043747, + 0.227625 0.766596 -0.052796, + 0.228542 -1.374325 0.103206, + 0.185687 0.766596 0.085455, + 0.156152 -1.374325 0.238638, + 0.117584 0.766597 0.212868, + 0.058731 -1.374325 0.357346, + 0.025931 0.766596 0.324546, + -0.059977 -1.374325 0.454767, + -0.085747 0.766597 0.416199, + -0.195409 -1.374325 0.527157, + -0.21316 0.766596 0.484302, + -0.342362 -1.374325 0.571735, + -0.351411 0.766597 0.52624, + -0.495188 -1.374325 0.586787, + -0.495188 0.766596 0.540401, + -0.648014 -1.374325 0.571734, + -0.638964 0.766596 0.52624, + -0.794966 -1.374325 0.527157, + -0.777215 0.766596 0.484302, + -0.930399 -1.374325 0.454766, + -0.904629 0.766596 0.416198, + -1.049106 -1.374325 0.357346, + -1.016307 0.766596 0.324546, + -1.146527 -1.374325 0.238638, + -1.107959 0.766596 0.212868, + -1.218917 -1.374325 0.103205, + -1.176063 0.766596 0.085455, + -1.263495 -1.374325 -0.043747, + -1.218 0.766596 -0.052797, + -1.278547 -1.374325 -0.196573, + -1.232161 0.766597 -0.196573, + -1.263494 -1.374325 -0.349399, + -1.218 0.766596 -0.34035, + -1.218917 -1.374325 -0.496352, + -1.176062 0.766596 -0.478601, + -1.146526 -1.374325 -0.631784, + -1.107958 0.766596 -0.606014, + -1.049105 -1.374325 -0.750492, + -1.016306 0.766596 -0.717692, + -0.930398 -1.374325 -0.847912, + -0.904627 0.766596 -0.809344, + -0.794965 -1.374325 -0.920302, + -0.777214 0.766597 -0.877448, + -0.648012 -1.374325 -0.96488, + -0.638963 0.766596 -0.919386, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-002 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5216 0 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.41063 0.602835 3.700898, + -0.41063 3.16733 1.943742, + -0.257804 0.602835 3.71595, + -0.260412 3.16733 1.958537, + -0.110851 0.602835 3.760528, + -0.115967 3.16733 2.002354, + 0.024581 0.602835 3.832918, + 0.017154 3.16733 2.073509, + 0.143289 0.602835 3.930339, + 0.133836 3.16733 2.169267, + 0.24071 0.602835 4.049047, + 0.229594 3.16733 2.285948, + 0.3131 0.602835 4.184479, + 0.300749 3.16733 2.419069, + 0.357677 0.602835 4.331432, + 0.344565 3.16733 2.563514, + 0.372729 0.602835 4.484258, + 0.359361 3.16733 2.713732, + 0.357677 0.602835 4.637083, + 0.344566 3.16733 2.86395, + 0.3131 0.602835 4.784036, + 0.300749 3.16733 3.008394, + 0.24071 0.602835 4.919468, + 0.229594 3.16733 3.141516, + 0.143289 0.602835 5.038176, + 0.133836 3.16733 3.258197, + 0.024581 0.602835 5.135597, + 0.017154 3.16733 3.353956, + -0.110851 0.602835 5.207987, + -0.115967 3.16733 3.42511, + -0.257804 0.602835 5.252564, + -0.260412 3.16733 3.468927, + -0.41063 0.602835 5.267616, + -0.41063 3.16733 3.483722, + -0.563456 0.602835 5.252564, + -0.560848 3.16733 3.468927, + -0.710409 0.602835 5.207987, + -0.705293 3.16733 3.42511, + -0.845841 0.602835 5.135596, + -0.838414 3.16733 3.353955, + -0.964549 0.602835 5.038176, + -0.955096 3.16733 3.258197, + -1.061969 0.602835 4.919468, + -1.050854 3.16733 3.141515, + -1.134359 0.602834 4.784036, + -1.122008 3.16733 3.008394, + -1.178937 0.602835 4.637083, + -1.165825 3.16733 2.863949, + -1.193989 0.602835 4.484257, + -1.18062 3.16733 2.713731, + -1.178937 0.602834 4.331431, + -1.165825 3.16733 2.563514, + -1.134359 0.602834 4.184478, + -1.122008 3.16733 2.419069, + -1.061969 0.602835 4.049046, + -1.050853 3.16733 2.285948, + -0.964548 0.602835 3.930338, + -0.955095 3.16733 2.169266, + -0.84584 0.602835 3.832918, + -0.838413 3.16733 2.073508, + -0.710407 0.602834 3.760528, + -0.705291 3.16733 2.002353, + -0.563454 0.602835 3.71595, + -0.560846 3.16733 1.958537, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-003 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5569 0.0314 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.445154 0.812967 0.622434, + -0.342043 3.189795 2.268354, + -0.5986 0.812715 0.616381, + -0.492871 3.189548 2.262405, + -0.747915 0.811222 0.580535, + -0.639638 3.18808 2.22717, + -0.887362 0.808546 0.516272, + -0.776705 3.18545 2.164004, + -1.011582 0.80479 0.426063, + -0.898805 3.181758 2.075335, + -1.115801 0.800098 0.313375, + -1.001245 3.177146 1.964569, + -1.196013 0.79465 0.182537, + -1.080089 3.171791 1.835965, + -1.249137 0.788656 0.038578, + -1.132306 3.165899 1.694462, + -1.273131 0.782346 -0.11297, + -1.15589 3.159697 1.545501, + -1.267073 0.775962 -0.266283, + -1.149936 3.153422 1.394804, + -1.231196 0.76975 -0.415469, + -1.11467 3.147316 1.248164, + -1.166878 0.763949 -0.554795, + -1.05145 3.141613 1.111216, + -1.07659 0.758781 -0.678907, + -0.962704 3.136534 0.989222, + -0.963804 0.754445 -0.783036, + -0.851842 3.132272 0.88687, + -0.832853 0.751108 -0.863179, + -0.723126 3.128992 0.808095, + -0.688769 0.748898 -0.916257, + -0.581501 3.12682 0.755922, + -0.53709 0.7479 -0.94023, + -0.43241 3.125838 0.732358, + -0.383644 0.748152 -0.934177, + -0.281583 3.126086 0.738308, + -0.234329 0.749644 -0.898331, + -0.134816 3.127553 0.773543, + -0.094882 0.75232 -0.834068, + 0.002251 3.130183 0.836709, + 0.029338 0.756076 -0.743859, + 0.124351 3.133875 0.925378, + 0.133557 0.760768 -0.63117, + 0.226791 3.138488 1.036144, + 0.213769 0.766216 -0.500332, + 0.305635 3.143842 1.164749, + 0.266893 0.772211 -0.356373, + 0.357852 3.149734 1.306251, + 0.290887 0.778521 -0.204825, + 0.381437 3.155937 1.455213, + 0.284829 0.784905 -0.051512, + 0.375482 3.162212 1.605909, + 0.248951 0.791116 0.097674, + 0.340216 3.168318 1.75255, + 0.184633 0.796918 0.237, + 0.276995 3.17402 1.889498, + 0.094345 0.802086 0.361112, + 0.188249 3.1791 2.011492, + -0.018441 0.806422 0.46524, + 0.077387 3.183362 2.113843, + -0.149393 0.809759 0.545383, + -0.051329 3.186642 2.192619, + -0.293476 0.811969 0.598461, + -0.192954 3.188814 2.244791, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-004 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5569 0.0314 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.367458 3.206373 2.914586, + -0.311993 4.774627 3.785861, + -0.480008 3.206189 2.910146, + -0.35781 4.773128 3.784562, + -0.589527 3.205094 2.883854, + -0.402899 4.768367 3.775377, + -0.691809 3.203131 2.836719, + -0.44617 4.760221 3.758628, + -0.782921 3.200376 2.770552, + -0.48676 4.748534 3.734807, + -0.859364 3.196934 2.687897, + -0.52408 4.733227 3.704406, + -0.918198 3.192939 2.591931, + -0.55771 4.714481 3.667699, + -0.957163 3.188542 2.48634, + -0.587051 4.692984 3.624568, + -0.974762 3.183913 2.375183, + -0.610716 4.670081 3.574621, + -0.970319 3.179231 2.262731, + -0.626095 4.647597 3.517839, + -0.944003 3.174675 2.153306, + -0.62969 4.627272 3.455525, + -0.896827 3.17042 2.051113, + -0.618345 4.610205 3.390795, + -0.830604 3.166629 1.960079, + -0.590494 4.596736 3.328116, + -0.747877 3.163449 1.883703, + -0.546628 4.586709 3.272326, + -0.651827 3.161001 1.82492, + -0.489044 4.579797 3.227767, + -0.546145 3.15938 1.785988, + -0.421315 4.575701 3.197805, + -0.434891 3.158648 1.768404, + -0.347793 4.574235 3.184615, + -0.322342 3.158833 1.772844, + -0.273228 4.575346 3.189119, + -0.212822 3.159928 1.799137, + -0.202445 4.579111 3.210957, + -0.11054 3.16189 1.846272, + -0.140019 4.585739 3.248474, + -0.019428 3.164645 1.912439, + -0.089891 4.595547 3.298747, + 0.057014 3.168087 1.995093, + -0.054844 4.608874 3.357729, + 0.115848 3.172083 2.09106, + -0.03593 4.62588 3.420674, + 0.154814 3.17648 2.196651, + -0.032112 4.646214 3.482962, + 0.172413 3.181108 2.307809, + -0.040625 4.668762 3.541134, + 0.167969 3.18579 2.42026, + -0.058159 4.691765 3.593492, + 0.141654 3.190347 2.529685, + -0.08213 4.713386 3.63975, + 0.094477 3.194602 2.631878, + -0.111129 4.732274 3.680135, + 0.028254 3.198392 2.722912, + -0.144548 4.747742 3.714694, + -0.054473 3.201573 2.799288, + -0.182007 4.759607 3.743103, + -0.150523 3.20402 2.858071, + -0.222975 4.767948 3.764802, + -0.256206 3.205642 2.897003, + -0.266653 4.772915 3.779205, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-005 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5569 0.0314 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.448535 3.212656 1.410033, + -0.448522 4.777171 0.530312, + -0.33613 3.209718 1.416633, + -0.402789 4.774548 0.532497, + -0.227193 3.206061 1.445028, + -0.358015 4.768725 0.542569, + -0.125909 3.201826 1.494127, + -0.315286 4.759603 0.560184, + -0.036171 3.197174 1.562042, + -0.275459 4.747045 0.584836, + 0.038573 3.192285 1.646165, + -0.239117 4.730983 0.616021, + 0.09545 3.187346 1.743261, + -0.206667 4.711607 0.653457, + 0.132274 3.182548 1.849601, + -0.178696 4.689621 0.697246, + 0.14763 3.178075 1.961096, + -0.156562 4.666406 0.747747, + 0.140928 3.174099 2.073463, + -0.14283 4.64385 0.804922, + 0.112426 3.170772 2.182384, + -0.140928 4.623772 0.86739, + 0.063219 3.168222 2.283671, + -0.153924 4.607333 0.931973, + -0.004802 3.166548 2.373434, + -0.183291 4.594887 0.99417, + -0.089024 3.165813 2.448223, + -0.228448 4.586241 1.049155, + -0.186208 3.166047 2.505163, + -0.287024 4.580986 1.092633, + -0.292622 3.167239 2.542066, + -0.355393 4.578721 1.121309, + -0.404174 3.169345 2.557515, + -0.429167 4.579139 1.133093, + -0.516579 3.172282 2.550915, + -0.503582 4.582065 1.127153, + -0.625517 3.175939 2.52252, + -0.573822 4.58746 1.103943, + -0.726801 3.180175 2.473421, + -0.635337 4.595428 1.065203, + -0.816539 3.184827 2.405506, + -0.684239 4.606203 1.01393, + -0.891283 3.189716 2.321383, + -0.717814 4.620078 0.954223, + -0.948159 3.194654 2.224287, + -0.735098 4.637212 0.890845, + -0.984983 3.199452 2.117947, + -0.737222 4.657305 0.828398, + -1.000339 3.203926 2.006451, + -0.727046 4.679328 0.770292, + -0.993637 3.207902 1.894084, + -0.707952 4.701614 0.718171, + -0.965135 3.211229 1.785164, + -0.682575 4.722392 0.672278, + -0.915928 3.213778 1.683876, + -0.652353 4.740345 0.632365, + -0.847907 3.215453 1.594113, + -0.617908 4.754801 0.598381, + -0.763685 3.216187 1.519325, + -0.579632 4.765588 0.570639, + -0.666501 3.215954 1.462385, + -0.538063 4.772801 0.54969, + -0.560087 3.214762 1.425482, + -0.494009 4.776613 0.536105, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-006 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5569 0.0314 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.382515 4.62188 3.214553, + -0.348055 6.185362 3.199083, + -0.331248 4.621978 3.219418, + -0.3355 6.185493 3.200465, + -0.282023 4.621546 3.234548, + -0.323449 6.185206 3.203833, + -0.236943 4.620595 3.259277, + -0.312017 6.184526 3.209164, + -0.197897 4.619149 3.292487, + -0.301465 6.183477 3.216414, + -0.166464 4.617244 3.332684, + -0.292088 6.182104 3.225525, + -0.143833 4.614928 3.378093, + -0.284226 6.180468 3.236402, + -0.130758 4.612271 3.426769, + -0.278261 6.178646 3.248881, + -0.127553 4.609363 3.476716, + -0.274599 6.176722 3.262693, + -0.134121 4.606317 3.52598, + -0.273638 6.174783 3.277433, + -0.150004 4.603263 3.572731, + -0.275706 6.172915 3.292547, + -0.174441 4.600342 3.615307, + -0.280995 6.171188 3.307345, + -0.206416 4.597683 3.65224, + -0.289509 6.169662 3.321049, + -0.244696 4.595408 3.682282, + -0.301023 6.168382 3.332862, + -0.287861 4.593613 3.704423, + -0.315078 6.167376 3.342042, + -0.334344 4.592367 3.71792, + -0.331014 6.166662 3.347983, + -0.382469 4.591719 3.722327, + -0.348008 6.166252 3.350273, + -0.430509 4.591681 3.717503, + -0.365146 6.166152 3.348731, + -0.476746 4.592251 3.703635, + -0.381494 6.166363 3.343431, + -0.519525 4.593395 3.681211, + -0.396172 6.166883 3.334692, + -0.557311 4.595063 3.651014, + -0.408429 6.167708 3.323053, + -0.588734 4.597186 3.614083, + -0.417695 6.168823 3.309222, + -0.612622 4.599678 3.571689, + -0.423626 6.170206 3.294012, + -0.628035 4.602438 3.5253, + -0.426118 6.171822 3.278255, + -0.634298 4.605364 3.476552, + -0.425289 6.173618 3.262747, + -0.631024 4.608338 3.427209, + -0.421441 6.175529 3.248166, + -0.618157 4.611246 3.37912, + -0.415 6.177476 3.235044, + -0.595993 4.613976 3.334168, + -0.406458 6.179372 3.223754, + -0.56521 4.616421 3.294195, + -0.396293 6.181131 3.214502, + -0.526893 4.618521 3.260898, + -0.384999 6.182669 3.207423, + -0.482432 4.620152 3.235807, + -0.37288 6.183922 3.202485, + -0.433622 4.621416 3.219946, + -0.360557 6.184824 3.199758, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-007 Shape { + appearance Appearance { + material Material { + ambientIntensity 1.0 + diffuseColor 1.0 0.5569 0.0314 + specularColor 1.0 1.0 1.0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.586419 4.642282 1.039134, + -0.456754 6.171029 1.092211, + -0.628198 4.649765 1.009971, + -0.466379 6.172939 1.085189, + -0.663281 4.656164 0.972817, + -0.474726 6.174306 1.07677, + -0.690183 4.661199 0.929279, + -0.481733 6.175146 1.067006, + -0.707816 4.664647 0.881249, + -0.487212 6.175446 1.056042, + -0.715544 4.666348 0.830803, + -0.490941 6.17521 1.044042, + -0.713204 4.666223 0.780069, + -0.49267 6.174452 1.031228, + -0.701084 4.664277 0.731112, + -0.492137 6.173196 1.017901, + -0.679876 4.660604 0.685834, + -0.489099 6.171473 1.004471, + -0.650602 4.655381 0.645895, + -0.48338 6.169319 0.991463, + -0.61453 4.64885 0.612678, + -0.474933 6.166784 0.979507, + -0.573108 4.641302 0.587268, + -0.46389 6.163927 0.969291, + -0.527909 4.633054 0.570458, + -0.450594 6.160826 0.961497, + -0.480588 4.624436 0.562745, + -0.435595 6.157575 0.95672, + -0.432847 4.615776 0.564325, + -0.419624 6.154291 0.955394, + -0.386389 4.607394 0.575086, + -0.403528 6.151102 0.957744, + -0.34287 4.599592 0.594607, + -0.388207 6.148151 0.963745, + -0.303843 4.59264 0.622169, + -0.374529 6.145584 0.973125, + -0.270698 4.586783 0.656776, + -0.363263 6.143536 0.985377, + -0.244628 4.582217 0.697194, + -0.35501 6.142129 0.999805, + -0.226579 4.579097 0.741993, + -0.350157 6.141454 1.01558, + -0.217234 4.57753 0.789596, + -0.348849 6.141564 1.031812, + -0.216995 4.577569 0.83832, + -0.35099 6.142467 1.047627, + -0.22597 4.579217 0.886422, + -0.35626 6.144122 1.062251, + -0.243955 4.582429 0.932143, + -0.364175 6.146439 1.075053, + -0.270441 4.5871 0.973749, + -0.374144 6.149288 1.085595, + -0.304588 4.593079 1.009593, + -0.385549 6.152514 1.093632, + -0.345238 4.600164 1.038171, + -0.397796 6.155947 1.099091, + -0.390924 4.608105 1.058201, + -0.410392 6.159424 1.102044, + -0.43989 4.616637 1.068727, + -0.422867 6.162782 1.102626, + -0.49021 4.625399 1.069082, + -0.43501 6.165917 1.101031, + -0.539823 4.6342 1.059254, + -0.446271 6.168671 1.097507, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 3.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 3.wrl new file mode 100644 index 0000000..0709e8b --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers 3.wrl @@ -0,0 +1,1772 @@ +#VRML V2.0 utf8 + +WorldInfo { + title "pliers2" + info [ "File produced by AccuTrans 3D" ] +} +NavigationInfo { + type [ "EXAMINE", "ANY" ] +} +DEF VP1 Viewpoint { + position -0.448555 2.405584 13.485098 + orientation 0 0 1 0 + fieldOfView 0.785398 + description "Front" +} +DEF VP2 Viewpoint { + position 10.891172 2.405584 2.145371 + orientation 0 1 0 1.570796 + fieldOfView 0.785398 + description "Right" +} +DEF VP3 Viewpoint { + position -0.448555 2.405584 -9.194357 + orientation 0 1 0 3.141592 + fieldOfView 0.785398 + description "Back" +} +DEF VP4 Viewpoint { + position -11.788282 2.405584 2.145371 + orientation 0 1 0 -1.570796 + fieldOfView 0.785398 + description "Left" +} +DEF VP5 Viewpoint { + position -0.448555 13.745312 2.145371 + orientation 1 0 0 -1.570796 + fieldOfView 0.785398 + description "Top" +} +DEF VP6 Viewpoint { + position -0.448555 -8.934143 2.145371 + orientation 1 0 0 1.570796 + fieldOfView 0.785398 + description "Bottom" +} +Transform { +scale 0.01 0.01 0.01 +rotation 1 0 0 1.6 +translation 0 0.02 0 + children [ + DEF Cylinder Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.469519 -1.350807 3.703954, + -0.469519 0.646338 3.717323, + -0.316693 -1.350807 3.719007, + -0.319301 0.646338 3.732118, + -0.16974 -1.350807 3.763584, + -0.174856 0.646338 3.775935, + -0.034307 -1.350807 3.835974, + -0.041735 0.646338 3.84709, + 0.0844 -1.350807 3.933395, + 0.074947 0.646338 3.942848, + 0.181821 -1.350807 4.052103, + 0.170705 0.646338 4.05953, + 0.254211 -1.350807 4.187535, + 0.24186 0.646338 4.192651, + 0.298789 -1.350807 4.334488, + 0.285677 0.646338 4.337096, + 0.313841 -1.350807 4.487314, + 0.300472 0.646338 4.487313, + 0.298789 -1.350807 4.640139, + 0.285677 0.646338 4.637531, + 0.254211 -1.350807 4.787092, + 0.24186 0.646338 4.781976, + 0.181821 -1.350807 4.922524, + 0.170705 0.646338 4.915097, + 0.0844 -1.350807 5.041232, + 0.074947 0.646338 5.031779, + -0.034308 -1.350807 5.138653, + -0.041735 0.646338 5.127537, + -0.16974 -1.350807 5.211043, + -0.174856 0.646338 5.198692, + -0.316693 -1.350807 5.25562, + -0.319301 0.646338 5.242509, + -0.469519 -1.350807 5.270673, + -0.469519 0.646338 5.257304, + -0.622345 -1.350807 5.25562, + -0.619736 0.646338 5.242509, + -0.769297 -1.350807 5.211043, + -0.764181 0.646338 5.198692, + -0.90473 -1.350807 5.138653, + -0.897303 0.646338 5.127537, + -1.023437 -1.350807 5.041232, + -1.013984 0.646338 5.031779, + -1.120858 -1.350807 4.922524, + -1.109742 0.646338 4.915097, + -1.193248 -1.350807 4.787092, + -1.180897 0.646338 4.781976, + -1.237826 -1.350807 4.640139, + -1.224714 0.646338 4.637531, + -1.252877 -1.350807 4.487313, + -1.239509 0.646338 4.487313, + -1.237825 -1.350807 4.334487, + -1.224714 0.646338 4.337095, + -1.193248 -1.350807 4.187534, + -1.180897 0.646338 4.19265, + -1.120857 -1.350807 4.052102, + -1.109742 0.646338 4.059529, + -1.023436 -1.350807 3.933394, + -1.013983 0.646338 3.942847, + -0.904729 -1.350807 3.835974, + -0.897301 0.646338 3.847089, + -0.769296 -1.350807 3.763584, + -0.76418 0.646338 3.775935, + -0.622343 -1.350807 3.719006, + -0.619735 0.646338 3.732118, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-001 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.495188 -1.374325 -0.979932, + -0.495188 0.766596 -0.933546, + -0.342362 -1.374325 -0.96488, + -0.351411 0.766596 -0.919385, + -0.195409 -1.374325 -0.920302, + -0.21316 0.766596 -0.877447, + -0.059977 -1.374325 -0.847912, + -0.085747 0.766596 -0.809344, + 0.058731 -1.374325 -0.750491, + 0.025931 0.766596 -0.717691, + 0.156152 -1.374325 -0.631783, + 0.117584 0.766596 -0.606013, + 0.228542 -1.374325 -0.496351, + 0.185687 0.766596 -0.4786, + 0.27312 -1.374325 -0.349398, + 0.227625 0.766596 -0.340349, + 0.288172 -1.374325 -0.196573, + 0.241786 0.766596 -0.196573, + 0.27312 -1.374325 -0.043747, + 0.227625 0.766596 -0.052796, + 0.228542 -1.374325 0.103206, + 0.185687 0.766596 0.085455, + 0.156152 -1.374325 0.238638, + 0.117584 0.766597 0.212868, + 0.058731 -1.374325 0.357346, + 0.025931 0.766596 0.324546, + -0.059977 -1.374325 0.454767, + -0.085747 0.766597 0.416199, + -0.195409 -1.374325 0.527157, + -0.21316 0.766596 0.484302, + -0.342362 -1.374325 0.571735, + -0.351411 0.766597 0.52624, + -0.495188 -1.374325 0.586787, + -0.495188 0.766596 0.540401, + -0.648014 -1.374325 0.571734, + -0.638964 0.766596 0.52624, + -0.794966 -1.374325 0.527157, + -0.777215 0.766596 0.484302, + -0.930399 -1.374325 0.454766, + -0.904629 0.766596 0.416198, + -1.049106 -1.374325 0.357346, + -1.016307 0.766596 0.324546, + -1.146527 -1.374325 0.238638, + -1.107959 0.766596 0.212868, + -1.218917 -1.374325 0.103205, + -1.176063 0.766596 0.085455, + -1.263495 -1.374325 -0.043747, + -1.218 0.766596 -0.052797, + -1.278547 -1.374325 -0.196573, + -1.232161 0.766597 -0.196573, + -1.263494 -1.374325 -0.349399, + -1.218 0.766596 -0.34035, + -1.218917 -1.374325 -0.496352, + -1.176062 0.766596 -0.478601, + -1.146526 -1.374325 -0.631784, + -1.107958 0.766596 -0.606014, + -1.049105 -1.374325 -0.750492, + -1.016306 0.766596 -0.717692, + -0.930398 -1.374325 -0.847912, + -0.904627 0.766596 -0.809344, + -0.794965 -1.374325 -0.920302, + -0.777214 0.766597 -0.877448, + -0.648012 -1.374325 -0.96488, + -0.638963 0.766596 -0.919386, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-002 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.41063 0.602835 3.700898, + -0.41063 3.16733 1.943742, + -0.257804 0.602835 3.71595, + -0.260412 3.16733 1.958537, + -0.110851 0.602835 3.760528, + -0.115967 3.16733 2.002354, + 0.024581 0.602835 3.832918, + 0.017154 3.16733 2.073509, + 0.143289 0.602835 3.930339, + 0.133836 3.16733 2.169267, + 0.24071 0.602835 4.049047, + 0.229594 3.16733 2.285948, + 0.3131 0.602835 4.184479, + 0.300749 3.16733 2.419069, + 0.357677 0.602835 4.331432, + 0.344565 3.16733 2.563514, + 0.372729 0.602835 4.484258, + 0.359361 3.16733 2.713732, + 0.357677 0.602835 4.637083, + 0.344566 3.16733 2.86395, + 0.3131 0.602835 4.784036, + 0.300749 3.16733 3.008394, + 0.24071 0.602835 4.919468, + 0.229594 3.16733 3.141516, + 0.143289 0.602835 5.038176, + 0.133836 3.16733 3.258197, + 0.024581 0.602835 5.135597, + 0.017154 3.16733 3.353956, + -0.110851 0.602835 5.207987, + -0.115967 3.16733 3.42511, + -0.257804 0.602835 5.252564, + -0.260412 3.16733 3.468927, + -0.41063 0.602835 5.267616, + -0.41063 3.16733 3.483722, + -0.563456 0.602835 5.252564, + -0.560848 3.16733 3.468927, + -0.710409 0.602835 5.207987, + -0.705293 3.16733 3.42511, + -0.845841 0.602835 5.135596, + -0.838414 3.16733 3.353955, + -0.964549 0.602835 5.038176, + -0.955096 3.16733 3.258197, + -1.061969 0.602835 4.919468, + -1.050854 3.16733 3.141515, + -1.134359 0.602834 4.784036, + -1.122008 3.16733 3.008394, + -1.178937 0.602835 4.637083, + -1.165825 3.16733 2.863949, + -1.193989 0.602835 4.484257, + -1.18062 3.16733 2.713731, + -1.178937 0.602834 4.331431, + -1.165825 3.16733 2.563514, + -1.134359 0.602834 4.184478, + -1.122008 3.16733 2.419069, + -1.061969 0.602835 4.049046, + -1.050853 3.16733 2.285948, + -0.964548 0.602835 3.930338, + -0.955095 3.16733 2.169266, + -0.84584 0.602835 3.832918, + -0.838413 3.16733 2.073508, + -0.710407 0.602834 3.760528, + -0.705291 3.16733 2.002353, + -0.563454 0.602835 3.71595, + -0.560846 3.16733 1.958537, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-003 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.445154 0.812967 0.622434, + -0.342043 3.189795 2.268354, + -0.5986 0.812715 0.616381, + -0.492871 3.189548 2.262405, + -0.747915 0.811222 0.580535, + -0.639638 3.18808 2.22717, + -0.887362 0.808546 0.516272, + -0.776705 3.18545 2.164004, + -1.011582 0.80479 0.426063, + -0.898805 3.181758 2.075335, + -1.115801 0.800098 0.313375, + -1.001245 3.177146 1.964569, + -1.196013 0.79465 0.182537, + -1.080089 3.171791 1.835965, + -1.249137 0.788656 0.038578, + -1.132306 3.165899 1.694462, + -1.273131 0.782346 -0.11297, + -1.15589 3.159697 1.545501, + -1.267073 0.775962 -0.266283, + -1.149936 3.153422 1.394804, + -1.231196 0.76975 -0.415469, + -1.11467 3.147316 1.248164, + -1.166878 0.763949 -0.554795, + -1.05145 3.141613 1.111216, + -1.07659 0.758781 -0.678907, + -0.962704 3.136534 0.989222, + -0.963804 0.754445 -0.783036, + -0.851842 3.132272 0.88687, + -0.832853 0.751108 -0.863179, + -0.723126 3.128992 0.808095, + -0.688769 0.748898 -0.916257, + -0.581501 3.12682 0.755922, + -0.53709 0.7479 -0.94023, + -0.43241 3.125838 0.732358, + -0.383644 0.748152 -0.934177, + -0.281583 3.126086 0.738308, + -0.234329 0.749644 -0.898331, + -0.134816 3.127553 0.773543, + -0.094882 0.75232 -0.834068, + 0.002251 3.130183 0.836709, + 0.029338 0.756076 -0.743859, + 0.124351 3.133875 0.925378, + 0.133557 0.760768 -0.63117, + 0.226791 3.138488 1.036144, + 0.213769 0.766216 -0.500332, + 0.305635 3.143842 1.164749, + 0.266893 0.772211 -0.356373, + 0.357852 3.149734 1.306251, + 0.290887 0.778521 -0.204825, + 0.381437 3.155937 1.455213, + 0.284829 0.784905 -0.051512, + 0.375482 3.162212 1.605909, + 0.248951 0.791116 0.097674, + 0.340216 3.168318 1.75255, + 0.184633 0.796918 0.237, + 0.276995 3.17402 1.889498, + 0.094345 0.802086 0.361112, + 0.188249 3.1791 2.011492, + -0.018441 0.806422 0.46524, + 0.077387 3.183362 2.113843, + -0.149393 0.809759 0.545383, + -0.051329 3.186642 2.192619, + -0.293476 0.811969 0.598461, + -0.192954 3.188814 2.244791, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-004 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.367458 3.206373 2.914586, + -0.311993 4.774627 3.785861, + -0.480008 3.206189 2.910146, + -0.35781 4.773128 3.784562, + -0.589527 3.205094 2.883854, + -0.402899 4.768367 3.775377, + -0.691809 3.203131 2.836719, + -0.44617 4.760221 3.758628, + -0.782921 3.200376 2.770552, + -0.48676 4.748534 3.734807, + -0.859364 3.196934 2.687897, + -0.52408 4.733227 3.704406, + -0.918198 3.192939 2.591931, + -0.55771 4.714481 3.667699, + -0.957163 3.188542 2.48634, + -0.587051 4.692984 3.624568, + -0.974762 3.183913 2.375183, + -0.610716 4.670081 3.574621, + -0.970319 3.179231 2.262731, + -0.626095 4.647597 3.517839, + -0.944003 3.174675 2.153306, + -0.62969 4.627272 3.455525, + -0.896827 3.17042 2.051113, + -0.618345 4.610205 3.390795, + -0.830604 3.166629 1.960079, + -0.590494 4.596736 3.328116, + -0.747877 3.163449 1.883703, + -0.546628 4.586709 3.272326, + -0.651827 3.161001 1.82492, + -0.489044 4.579797 3.227767, + -0.546145 3.15938 1.785988, + -0.421315 4.575701 3.197805, + -0.434891 3.158648 1.768404, + -0.347793 4.574235 3.184615, + -0.322342 3.158833 1.772844, + -0.273228 4.575346 3.189119, + -0.212822 3.159928 1.799137, + -0.202445 4.579111 3.210957, + -0.11054 3.16189 1.846272, + -0.140019 4.585739 3.248474, + -0.019428 3.164645 1.912439, + -0.089891 4.595547 3.298747, + 0.057014 3.168087 1.995093, + -0.054844 4.608874 3.357729, + 0.115848 3.172083 2.09106, + -0.03593 4.62588 3.420674, + 0.154814 3.17648 2.196651, + -0.032112 4.646214 3.482962, + 0.172413 3.181108 2.307809, + -0.040625 4.668762 3.541134, + 0.167969 3.18579 2.42026, + -0.058159 4.691765 3.593492, + 0.141654 3.190347 2.529685, + -0.08213 4.713386 3.63975, + 0.094477 3.194602 2.631878, + -0.111129 4.732274 3.680135, + 0.028254 3.198392 2.722912, + -0.144548 4.747742 3.714694, + -0.054473 3.201573 2.799288, + -0.182007 4.759607 3.743103, + -0.150523 3.20402 2.858071, + -0.222975 4.767948 3.764802, + -0.256206 3.205642 2.897003, + -0.266653 4.772915 3.779205, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-005 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.448535 3.212656 1.410033, + -0.448522 4.777171 0.530312, + -0.33613 3.209718 1.416633, + -0.402789 4.774548 0.532497, + -0.227193 3.206061 1.445028, + -0.358015 4.768725 0.542569, + -0.125909 3.201826 1.494127, + -0.315286 4.759603 0.560184, + -0.036171 3.197174 1.562042, + -0.275459 4.747045 0.584836, + 0.038573 3.192285 1.646165, + -0.239117 4.730983 0.616021, + 0.09545 3.187346 1.743261, + -0.206667 4.711607 0.653457, + 0.132274 3.182548 1.849601, + -0.178696 4.689621 0.697246, + 0.14763 3.178075 1.961096, + -0.156562 4.666406 0.747747, + 0.140928 3.174099 2.073463, + -0.14283 4.64385 0.804922, + 0.112426 3.170772 2.182384, + -0.140928 4.623772 0.86739, + 0.063219 3.168222 2.283671, + -0.153924 4.607333 0.931973, + -0.004802 3.166548 2.373434, + -0.183291 4.594887 0.99417, + -0.089024 3.165813 2.448223, + -0.228448 4.586241 1.049155, + -0.186208 3.166047 2.505163, + -0.287024 4.580986 1.092633, + -0.292622 3.167239 2.542066, + -0.355393 4.578721 1.121309, + -0.404174 3.169345 2.557515, + -0.429167 4.579139 1.133093, + -0.516579 3.172282 2.550915, + -0.503582 4.582065 1.127153, + -0.625517 3.175939 2.52252, + -0.573822 4.58746 1.103943, + -0.726801 3.180175 2.473421, + -0.635337 4.595428 1.065203, + -0.816539 3.184827 2.405506, + -0.684239 4.606203 1.01393, + -0.891283 3.189716 2.321383, + -0.717814 4.620078 0.954223, + -0.948159 3.194654 2.224287, + -0.735098 4.637212 0.890845, + -0.984983 3.199452 2.117947, + -0.737222 4.657305 0.828398, + -1.000339 3.203926 2.006451, + -0.727046 4.679328 0.770292, + -0.993637 3.207902 1.894084, + -0.707952 4.701614 0.718171, + -0.965135 3.211229 1.785164, + -0.682575 4.722392 0.672278, + -0.915928 3.213778 1.683876, + -0.652353 4.740345 0.632365, + -0.847907 3.215453 1.594113, + -0.617908 4.754801 0.598381, + -0.763685 3.216187 1.519325, + -0.579632 4.765588 0.570639, + -0.666501 3.215954 1.462385, + -0.538063 4.772801 0.54969, + -0.560087 3.214762 1.425482, + -0.494009 4.776613 0.536105, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-006 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.382515 4.62188 3.214553, + -0.348055 6.185362 3.199083, + -0.331248 4.621978 3.219418, + -0.3355 6.185493 3.200465, + -0.282023 4.621546 3.234548, + -0.323449 6.185206 3.203833, + -0.236943 4.620595 3.259277, + -0.312017 6.184526 3.209164, + -0.197897 4.619149 3.292487, + -0.301465 6.183477 3.216414, + -0.166464 4.617244 3.332684, + -0.292088 6.182104 3.225525, + -0.143833 4.614928 3.378093, + -0.284226 6.180468 3.236402, + -0.130758 4.612271 3.426769, + -0.278261 6.178646 3.248881, + -0.127553 4.609363 3.476716, + -0.274599 6.176722 3.262693, + -0.134121 4.606317 3.52598, + -0.273638 6.174783 3.277433, + -0.150004 4.603263 3.572731, + -0.275706 6.172915 3.292547, + -0.174441 4.600342 3.615307, + -0.280995 6.171188 3.307345, + -0.206416 4.597683 3.65224, + -0.289509 6.169662 3.321049, + -0.244696 4.595408 3.682282, + -0.301023 6.168382 3.332862, + -0.287861 4.593613 3.704423, + -0.315078 6.167376 3.342042, + -0.334344 4.592367 3.71792, + -0.331014 6.166662 3.347983, + -0.382469 4.591719 3.722327, + -0.348008 6.166252 3.350273, + -0.430509 4.591681 3.717503, + -0.365146 6.166152 3.348731, + -0.476746 4.592251 3.703635, + -0.381494 6.166363 3.343431, + -0.519525 4.593395 3.681211, + -0.396172 6.166883 3.334692, + -0.557311 4.595063 3.651014, + -0.408429 6.167708 3.323053, + -0.588734 4.597186 3.614083, + -0.417695 6.168823 3.309222, + -0.612622 4.599678 3.571689, + -0.423626 6.170206 3.294012, + -0.628035 4.602438 3.5253, + -0.426118 6.171822 3.278255, + -0.634298 4.605364 3.476552, + -0.425289 6.173618 3.262747, + -0.631024 4.608338 3.427209, + -0.421441 6.175529 3.248166, + -0.618157 4.611246 3.37912, + -0.415 6.177476 3.235044, + -0.595993 4.613976 3.334168, + -0.406458 6.179372 3.223754, + -0.56521 4.616421 3.294195, + -0.396293 6.181131 3.214502, + -0.526893 4.618521 3.260898, + -0.384999 6.182669 3.207423, + -0.482432 4.620152 3.235807, + -0.37288 6.183922 3.202485, + -0.433622 4.621416 3.219946, + -0.360557 6.184824 3.199758, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-007 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.9529 + diffuseColor 1.0 0.2 0.2 + specularColor 0 0 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.586419 4.642282 1.039134, + -0.456754 6.171029 1.092211, + -0.628198 4.649765 1.009971, + -0.466379 6.172939 1.085189, + -0.663281 4.656164 0.972817, + -0.474726 6.174306 1.07677, + -0.690183 4.661199 0.929279, + -0.481733 6.175146 1.067006, + -0.707816 4.664647 0.881249, + -0.487212 6.175446 1.056042, + -0.715544 4.666348 0.830803, + -0.490941 6.17521 1.044042, + -0.713204 4.666223 0.780069, + -0.49267 6.174452 1.031228, + -0.701084 4.664277 0.731112, + -0.492137 6.173196 1.017901, + -0.679876 4.660604 0.685834, + -0.489099 6.171473 1.004471, + -0.650602 4.655381 0.645895, + -0.48338 6.169319 0.991463, + -0.61453 4.64885 0.612678, + -0.474933 6.166784 0.979507, + -0.573108 4.641302 0.587268, + -0.46389 6.163927 0.969291, + -0.527909 4.633054 0.570458, + -0.450594 6.160826 0.961497, + -0.480588 4.624436 0.562745, + -0.435595 6.157575 0.95672, + -0.432847 4.615776 0.564325, + -0.419624 6.154291 0.955394, + -0.386389 4.607394 0.575086, + -0.403528 6.151102 0.957744, + -0.34287 4.599592 0.594607, + -0.388207 6.148151 0.963745, + -0.303843 4.59264 0.622169, + -0.374529 6.145584 0.973125, + -0.270698 4.586783 0.656776, + -0.363263 6.143536 0.985377, + -0.244628 4.582217 0.697194, + -0.35501 6.142129 0.999805, + -0.226579 4.579097 0.741993, + -0.350157 6.141454 1.01558, + -0.217234 4.57753 0.789596, + -0.348849 6.141564 1.031812, + -0.216995 4.577569 0.83832, + -0.35099 6.142467 1.047627, + -0.22597 4.579217 0.886422, + -0.35626 6.144122 1.062251, + -0.243955 4.582429 0.932143, + -0.364175 6.146439 1.075053, + -0.270441 4.5871 0.973749, + -0.374144 6.149288 1.085595, + -0.304588 4.593079 1.009593, + -0.385549 6.152514 1.093632, + -0.345238 4.600164 1.038171, + -0.397796 6.155947 1.099091, + -0.390924 4.608105 1.058201, + -0.410392 6.159424 1.102044, + -0.43989 4.616637 1.068727, + -0.422867 6.162782 1.102626, + -0.49021 4.625399 1.069082, + -0.43501 6.165917 1.101031, + -0.539823 4.6342 1.059254, + -0.446271 6.168671 1.097507, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers.wrl new file mode 100644 index 0000000..52e3701 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/A2R3/pliers.wrl @@ -0,0 +1,2202 @@ +#VRML V2.0 utf8 + +WorldInfo { + title "pliers3ds" + info [ "File produced by AccuTrans 3D" ] +} +NavigationInfo { + type [ "EXAMINE", "ANY" ] +} +DEF VP1 Viewpoint { + position -0.448555 2.70388 14.379984 + orientation 0 0 1 0 + fieldOfView 0.785398 + description "Front" +} +DEF VP2 Viewpoint { + position 11.786058 2.70388 2.145371 + orientation 0 1 0 1.570796 + fieldOfView 0.785398 + description "Right" +} +DEF VP3 Viewpoint { + position -0.448555 2.70388 -10.089243 + orientation 0 1 0 3.141592 + fieldOfView 0.785398 + description "Back" +} +DEF VP4 Viewpoint { + position -12.683169 2.70388 2.145371 + orientation 0 1 0 -1.570796 + fieldOfView 0.785398 + description "Left" +} +DEF VP5 Viewpoint { + position -0.448555 14.938494 2.145371 + orientation 1 0 0 -1.570796 + fieldOfView 0.785398 + description "Top" +} +DEF VP6 Viewpoint { + position -0.448555 -9.530734 2.145371 + orientation 1 0 0 1.570796 + fieldOfView 0.785398 + description "Bottom" +} +Transform { +scale 0.01 0.012 0.01 +rotation 1 0 0 1.6 +translation 0 0.02 0 + children [ + DEF Cylinder Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.469519 -1.350807 3.703954, + -0.469519 0.646338 3.717323, + -0.316693 -1.350807 3.719007, + -0.319301 0.646338 3.732118, + -0.16974 -1.350807 3.763584, + -0.174856 0.646338 3.775935, + -0.034307 -1.350807 3.835974, + -0.041735 0.646338 3.84709, + 0.0844 -1.350807 3.933395, + 0.074947 0.646338 3.942848, + 0.181821 -1.350807 4.052103, + 0.170705 0.646338 4.05953, + 0.254211 -1.350807 4.187535, + 0.24186 0.646338 4.192651, + 0.298789 -1.350807 4.334488, + 0.285677 0.646338 4.337096, + 0.313841 -1.350807 4.487314, + 0.300472 0.646338 4.487313, + 0.298789 -1.350807 4.640139, + 0.285677 0.646338 4.637531, + 0.254211 -1.350807 4.787092, + 0.24186 0.646338 4.781976, + 0.181821 -1.350807 4.922524, + 0.170705 0.646338 4.915097, + 0.0844 -1.350807 5.041232, + 0.074947 0.646338 5.031779, + -0.034308 -1.350807 5.138653, + -0.041735 0.646338 5.127537, + -0.16974 -1.350807 5.211043, + -0.174856 0.646338 5.198692, + -0.316693 -1.350807 5.25562, + -0.319301 0.646338 5.242509, + -0.469519 -1.350807 5.270673, + -0.469519 0.646338 5.257304, + -0.622345 -1.350807 5.25562, + -0.619736 0.646338 5.242509, + -0.769297 -1.350807 5.211043, + -0.764181 0.646338 5.198692, + -0.90473 -1.350807 5.138653, + -0.897303 0.646338 5.127537, + -1.023437 -1.350807 5.041232, + -1.013984 0.646338 5.031779, + -1.120858 -1.350807 4.922524, + -1.109742 0.646338 4.915097, + -1.193248 -1.350807 4.787092, + -1.180897 0.646338 4.781976, + -1.237826 -1.350807 4.640139, + -1.224714 0.646338 4.637531, + -1.252877 -1.350807 4.487313, + -1.239509 0.646338 4.487313, + -1.237825 -1.350807 4.334487, + -1.224714 0.646338 4.337095, + -1.193248 -1.350807 4.187534, + -1.180897 0.646338 4.19265, + -1.120857 -1.350807 4.052102, + -1.109742 0.646338 4.059529, + -1.023436 -1.350807 3.933394, + -1.013983 0.646338 3.942847, + -0.904729 -1.350807 3.835974, + -0.897301 0.646338 3.847089, + -0.769296 -1.350807 3.763584, + -0.76418 0.646338 3.775935, + -0.622343 -1.350807 3.719006, + -0.619735 0.646338 3.732118, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-001 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.495188 -1.374325 -0.979932, + -0.495188 0.766596 -0.933546, + -0.342362 -1.374325 -0.96488, + -0.351411 0.766596 -0.919385, + -0.195409 -1.374325 -0.920302, + -0.21316 0.766596 -0.877447, + -0.059977 -1.374325 -0.847912, + -0.085747 0.766596 -0.809344, + 0.058731 -1.374325 -0.750491, + 0.025931 0.766596 -0.717691, + 0.156152 -1.374325 -0.631783, + 0.117584 0.766596 -0.606013, + 0.228542 -1.374325 -0.496351, + 0.185687 0.766596 -0.4786, + 0.27312 -1.374325 -0.349398, + 0.227625 0.766596 -0.340349, + 0.288172 -1.374325 -0.196573, + 0.241786 0.766596 -0.196573, + 0.27312 -1.374325 -0.043747, + 0.227625 0.766596 -0.052796, + 0.228542 -1.374325 0.103206, + 0.185687 0.766596 0.085455, + 0.156152 -1.374325 0.238638, + 0.117584 0.766597 0.212868, + 0.058731 -1.374325 0.357346, + 0.025931 0.766596 0.324546, + -0.059977 -1.374325 0.454767, + -0.085747 0.766597 0.416199, + -0.195409 -1.374325 0.527157, + -0.21316 0.766596 0.484302, + -0.342362 -1.374325 0.571735, + -0.351411 0.766597 0.52624, + -0.495188 -1.374325 0.586787, + -0.495188 0.766596 0.540401, + -0.648014 -1.374325 0.571734, + -0.638964 0.766596 0.52624, + -0.794966 -1.374325 0.527157, + -0.777215 0.766596 0.484302, + -0.930399 -1.374325 0.454766, + -0.904629 0.766596 0.416198, + -1.049106 -1.374325 0.357346, + -1.016307 0.766596 0.324546, + -1.146527 -1.374325 0.238638, + -1.107959 0.766596 0.212868, + -1.218917 -1.374325 0.103205, + -1.176063 0.766596 0.085455, + -1.263495 -1.374325 -0.043747, + -1.218 0.766596 -0.052797, + -1.278547 -1.374325 -0.196573, + -1.232161 0.766597 -0.196573, + -1.263494 -1.374325 -0.349399, + -1.218 0.766596 -0.34035, + -1.218917 -1.374325 -0.496352, + -1.176062 0.766596 -0.478601, + -1.146526 -1.374325 -0.631784, + -1.107958 0.766596 -0.606014, + -1.049105 -1.374325 -0.750492, + -1.016306 0.766596 -0.717692, + -0.930398 -1.374325 -0.847912, + -0.904627 0.766596 -0.809344, + -0.794965 -1.374325 -0.920302, + -0.777214 0.766597 -0.877448, + -0.648012 -1.374325 -0.96488, + -0.638963 0.766596 -0.919386, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-002 Shape { + appearance Appearance { + material Material { +ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.41063 0.602835 3.700898, + -0.41063 3.16733 1.943742, + -0.257804 0.602835 3.71595, + -0.260412 3.16733 1.958537, + -0.110851 0.602835 3.760528, + -0.115967 3.16733 2.002354, + 0.024581 0.602835 3.832918, + 0.017154 3.16733 2.073509, + 0.143289 0.602835 3.930339, + 0.133836 3.16733 2.169267, + 0.24071 0.602835 4.049047, + 0.229594 3.16733 2.285948, + 0.3131 0.602835 4.184479, + 0.300749 3.16733 2.419069, + 0.357677 0.602835 4.331432, + 0.344565 3.16733 2.563514, + 0.372729 0.602835 4.484258, + 0.359361 3.16733 2.713732, + 0.357677 0.602835 4.637083, + 0.344566 3.16733 2.86395, + 0.3131 0.602835 4.784036, + 0.300749 3.16733 3.008394, + 0.24071 0.602835 4.919468, + 0.229594 3.16733 3.141516, + 0.143289 0.602835 5.038176, + 0.133836 3.16733 3.258197, + 0.024581 0.602835 5.135597, + 0.017154 3.16733 3.353956, + -0.110851 0.602835 5.207987, + -0.115967 3.16733 3.42511, + -0.257804 0.602835 5.252564, + -0.260412 3.16733 3.468927, + -0.41063 0.602835 5.267616, + -0.41063 3.16733 3.483722, + -0.563456 0.602835 5.252564, + -0.560848 3.16733 3.468927, + -0.710409 0.602835 5.207987, + -0.705293 3.16733 3.42511, + -0.845841 0.602835 5.135596, + -0.838414 3.16733 3.353955, + -0.964549 0.602835 5.038176, + -0.955096 3.16733 3.258197, + -1.061969 0.602835 4.919468, + -1.050854 3.16733 3.141515, + -1.134359 0.602834 4.784036, + -1.122008 3.16733 3.008394, + -1.178937 0.602835 4.637083, + -1.165825 3.16733 2.863949, + -1.193989 0.602835 4.484257, + -1.18062 3.16733 2.713731, + -1.178937 0.602834 4.331431, + -1.165825 3.16733 2.563514, + -1.134359 0.602834 4.184478, + -1.122008 3.16733 2.419069, + -1.061969 0.602835 4.049046, + -1.050853 3.16733 2.285948, + -0.964548 0.602835 3.930338, + -0.955095 3.16733 2.169266, + -0.84584 0.602835 3.832918, + -0.838413 3.16733 2.073508, + -0.710407 0.602834 3.760528, + -0.705291 3.16733 2.002353, + -0.563454 0.602835 3.71595, + -0.560846 3.16733 1.958537, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-003 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.445154 0.812967 0.622434, + -0.342044 3.189795 2.268354, + -0.5986 0.812715 0.616381, + -0.492871 3.189548 2.262405, + -0.747916 0.811222 0.580534, + -0.639639 3.18808 2.22717, + -0.887363 0.808546 0.516272, + -0.776706 3.18545 2.164004, + -1.011582 0.80479 0.426063, + -0.898806 3.181758 2.075335, + -1.115801 0.800098 0.313374, + -1.001246 3.177146 1.964569, + -1.196013 0.79465 0.182537, + -1.080089 3.171791 1.835964, + -1.249137 0.788656 0.038578, + -1.132307 3.165899 1.694462, + -1.273131 0.782346 -0.11297, + -1.155891 3.159697 1.545501, + -1.267073 0.775962 -0.266283, + -1.149936 3.153422 1.394804, + -1.231196 0.76975 -0.415469, + -1.114671 3.147316 1.248164, + -1.166877 0.763949 -0.554796, + -1.05145 3.141613 1.111215, + -1.07659 0.758781 -0.678908, + -0.962704 3.136534 0.989221, + -0.963804 0.754445 -0.783036, + -0.851842 3.132272 0.88687, + -0.832852 0.751108 -0.863179, + -0.723126 3.128992 0.808095, + -0.688769 0.748898 -0.916257, + -0.581501 3.12682 0.755922, + -0.537089 0.7479 -0.94023, + -0.43241 3.125838 0.732358, + -0.383644 0.748152 -0.934177, + -0.281583 3.126086 0.738308, + -0.234328 0.749644 -0.898331, + -0.134816 3.127553 0.773543, + -0.094881 0.75232 -0.834068, + 0.002251 3.130183 0.836709, + 0.029338 0.756076 -0.743859, + 0.124351 3.133875 0.925378, + 0.133557 0.760768 -0.63117, + 0.226791 3.138488 1.036144, + 0.213769 0.766216 -0.500332, + 0.305634 3.143842 1.164749, + 0.266893 0.772211 -0.356373, + 0.357852 3.149734 1.306252, + 0.290887 0.778521 -0.204825, + 0.381436 3.155937 1.455213, + 0.284829 0.784904 -0.051512, + 0.375481 3.162212 1.60591, + 0.248951 0.791116 0.097674, + 0.340215 3.168318 1.75255, + 0.184633 0.796918 0.237, + 0.276995 3.17402 1.889498, + 0.094345 0.802086 0.361112, + 0.188248 3.1791 2.011492, + -0.018441 0.806422 0.46524, + 0.077386 3.183362 2.113843, + -0.149393 0.809759 0.545384, + -0.05133 3.186642 2.192619, + -0.293477 0.811969 0.598461, + -0.192955 3.188814 2.244791, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 47, 17, -1, + 47, 19, 17, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-004 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.367458 3.206373 2.914586, + -0.311992 4.774627 3.785861, + -0.480007 3.206189 2.910146, + -0.357809 4.773128 3.784562, + -0.589527 3.205094 2.883854, + -0.402898 4.768367 3.775377, + -0.691809 3.203131 2.836719, + -0.446169 4.760221 3.758628, + -0.782921 3.200376 2.770552, + -0.48676 4.748534 3.734807, + -0.859364 3.196934 2.687897, + -0.524079 4.733227 3.704406, + -0.918198 3.192939 2.591931, + -0.55771 4.714481 3.667699, + -0.957163 3.188542 2.48634, + -0.58705 4.692984 3.624568, + -0.974762 3.183913 2.375183, + -0.610716 4.670081 3.574621, + -0.970319 3.179231 2.262731, + -0.626094 4.647597 3.517839, + -0.944004 3.174675 2.153306, + -0.62969 4.627272 3.455525, + -0.896828 3.17042 2.051113, + -0.618345 4.610205 3.390795, + -0.830604 3.166629 1.960079, + -0.590493 4.596736 3.328116, + -0.747878 3.163449 1.883703, + -0.546627 4.586709 3.272325, + -0.651828 3.161001 1.82492, + -0.489044 4.579797 3.227767, + -0.546145 3.15938 1.785988, + -0.421314 4.575701 3.197804, + -0.434892 3.158648 1.768404, + -0.347793 4.574235 3.184614, + -0.322342 3.158833 1.772844, + -0.273228 4.575346 3.189119, + -0.212823 3.159928 1.799136, + -0.202444 4.579111 3.210956, + -0.110541 3.16189 1.846272, + -0.140019 4.585739 3.248473, + -0.019428 3.164645 1.912438, + -0.08989 4.595547 3.298746, + 0.057014 3.168087 1.995093, + -0.054843 4.608874 3.357728, + 0.115848 3.172083 2.09106, + -0.035929 4.62588 3.420673, + 0.154814 3.176479 2.196651, + -0.032112 4.646214 3.482961, + 0.172413 3.181108 2.307808, + -0.040625 4.668762 3.541134, + 0.167969 3.18579 2.42026, + -0.058159 4.691765 3.593491, + 0.141653 3.190347 2.529685, + -0.08213 4.713386 3.639749, + 0.094477 3.194602 2.631878, + -0.111128 4.732274 3.680135, + 0.028254 3.198392 2.722911, + -0.144547 4.747742 3.714693, + -0.054473 3.201573 2.799287, + -0.182006 4.759607 3.743102, + -0.150523 3.20402 2.858071, + -0.222975 4.767948 3.764802, + -0.256206 3.205642 2.897002, + -0.266652 4.772915 3.779205, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-005 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.448535 3.212656 1.410033, + -0.448522 4.77717 0.530311, + -0.33613 3.209718 1.416633, + -0.402789 4.774548 0.532497, + -0.227193 3.206061 1.445028, + -0.358015 4.768725 0.542569, + -0.125909 3.201825 1.494127, + -0.315286 4.759603 0.560184, + -0.03617 3.197173 1.562042, + -0.275459 4.747044 0.584835, + 0.038573 3.192284 1.646165, + -0.239117 4.730982 0.616021, + 0.09545 3.187346 1.743261, + -0.206667 4.711607 0.653456, + 0.132274 3.182548 1.8496, + -0.178696 4.68962 0.697245, + 0.14763 3.178075 1.961096, + -0.156562 4.666405 0.747747, + 0.140928 3.174098 2.073463, + -0.14283 4.643849 0.804922, + 0.112426 3.170771 2.182383, + -0.140928 4.623772 0.86739, + 0.063219 3.168222 2.283671, + -0.153924 4.607333 0.931972, + -0.004802 3.166548 2.373434, + -0.183291 4.594887 0.994169, + -0.089024 3.165813 2.448223, + -0.228448 4.58624 1.049155, + -0.186208 3.166046 2.505163, + -0.287024 4.580986 1.092632, + -0.292622 3.167239 2.542066, + -0.355393 4.578721 1.121309, + -0.404174 3.169344 2.557515, + -0.429167 4.579139 1.133092, + -0.516579 3.172282 2.550915, + -0.503582 4.582065 1.127153, + -0.625517 3.175939 2.52252, + -0.573822 4.587459 1.103942, + -0.726801 3.180175 2.473421, + -0.635337 4.595427 1.065202, + -0.816539 3.184826 2.405505, + -0.684239 4.606202 1.01393, + -0.891283 3.189715 2.321383, + -0.717814 4.620078 0.954222, + -0.948159 3.194654 2.224286, + -0.735098 4.637211 0.890845, + -0.984983 3.199452 2.117947, + -0.737222 4.657305 0.828398, + -1.000339 3.203925 2.006451, + -0.727046 4.679327 0.770292, + -0.993637 3.207901 1.894084, + -0.707952 4.701613 0.71817, + -0.965135 3.211228 1.785164, + -0.682575 4.722391 0.672277, + -0.915928 3.213778 1.683876, + -0.652353 4.740345 0.632365, + -0.847907 3.215452 1.594113, + -0.617908 4.7548 0.59838, + -0.763685 3.216187 1.519325, + -0.579632 4.765588 0.570639, + -0.666501 3.215953 1.462384, + -0.538063 4.7728 0.54969, + -0.560087 3.214761 1.425481, + -0.494009 4.776612 0.536104, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 7, 5, -1, + 61, 59, 7, -1, + 59, 9, 7, -1, + 59, 57, 9, -1, + 57, 11, 9, -1, + 57, 55, 11, -1, + 55, 13, 11, -1, + 55, 53, 13, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 17, 15, -1, + 51, 49, 17, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 45, 19, -1, + 45, 21, 19, -1, + 45, 43, 21, -1, + 43, 23, 21, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 39, 25, -1, + 39, 27, 25, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 35, 29, -1, + 35, 31, 29, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 60, 62, -1, + 2, 4, 60, -1, + 4, 58, 60, -1, + 4, 6, 58, -1, + 6, 56, 58, -1, + 6, 8, 56, -1, + 8, 54, 56, -1, + 8, 10, 54, -1, + 10, 52, 54, -1, + 10, 12, 52, -1, + 12, 50, 52, -1, + 12, 14, 50, -1, + 14, 48, 50, -1, + 14, 16, 48, -1, + 16, 46, 48, -1, + 16, 18, 46, -1, + 18, 44, 46, -1, + 18, 20, 44, -1, + 20, 42, 44, -1, + 20, 22, 42, -1, + 22, 40, 42, -1, + 22, 24, 40, -1, + 24, 38, 40, -1, + 24, 26, 38, -1, + 26, 36, 38, -1, + 26, 28, 36, -1, + 28, 34, 36, -1, + 28, 30, 34, -1, + 30, 32, 34, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-006 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.382515 4.685706 3.214553, + -0.348055 6.249187 3.199083, + -0.331248 4.685804 3.219418, + -0.3355 6.249319 3.200465, + -0.282023 4.685371 3.234548, + -0.323449 6.249032 3.203833, + -0.236943 4.68442 3.259277, + -0.312017 6.248352 3.209164, + -0.197897 4.682974 3.292487, + -0.301465 6.247303 3.216414, + -0.166464 4.681069 3.332684, + -0.292088 6.245929 3.225525, + -0.143833 4.678754 3.378093, + -0.284226 6.244294 3.236402, + -0.130758 4.676097 3.426769, + -0.278261 6.242471 3.248881, + -0.127553 4.673188 3.476716, + -0.274599 6.240547 3.262693, + -0.134121 4.670142 3.52598, + -0.273638 6.238609 3.277433, + -0.150004 4.667089 3.572731, + -0.275706 6.23674 3.292547, + -0.174441 4.664167 3.615307, + -0.280995 6.235013 3.307345, + -0.206416 4.661509 3.65224, + -0.289509 6.233488 3.321049, + -0.244696 4.659234 3.682282, + -0.301023 6.232208 3.332862, + -0.287861 4.657438 3.704423, + -0.315078 6.231201 3.342042, + -0.334344 4.656193 3.71792, + -0.331014 6.230488 3.347983, + -0.382469 4.655544 3.722327, + -0.348008 6.230078 3.350273, + -0.430509 4.655506 3.717503, + -0.365146 6.229978 3.348731, + -0.476746 4.656076 3.703635, + -0.381494 6.230188 3.343431, + -0.519525 4.657221 3.681211, + -0.396172 6.230709 3.334692, + -0.557311 4.658889 3.651014, + -0.408429 6.231534 3.323053, + -0.588734 4.661012 3.614083, + -0.417695 6.232649 3.309222, + -0.612622 4.663503 3.571689, + -0.423626 6.234032 3.294012, + -0.628035 4.666264 3.5253, + -0.426118 6.235647 3.278255, + -0.634298 4.66919 3.476552, + -0.425289 6.237443 3.262747, + -0.631024 4.672164 3.427209, + -0.421441 6.239355 3.248166, + -0.618157 4.675072 3.37912, + -0.415 6.241302 3.235044, + -0.595993 4.677802 3.334168, + -0.406458 6.243197 3.223754, + -0.56521 4.680247 3.294195, + -0.396293 6.244957 3.214502, + -0.526893 4.682346 3.260898, + -0.384999 6.246495 3.207423, + -0.482432 4.683978 3.235807, + -0.37288 6.247748 3.202485, + -0.433622 4.685241 3.219946, + -0.360557 6.24865 3.199758, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-007 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.586419 4.642282 1.039134, + -0.456754 6.171029 1.092211, + -0.628198 4.649765 1.009971, + -0.466379 6.172939 1.085189, + -0.663281 4.656164 0.972817, + -0.474726 6.174306 1.07677, + -0.690183 4.661199 0.929279, + -0.481733 6.175146 1.067006, + -0.707815 4.664647 0.881249, + -0.487212 6.175446 1.056042, + -0.715544 4.666348 0.830803, + -0.490941 6.17521 1.044042, + -0.713204 4.666223 0.780069, + -0.49267 6.174452 1.031228, + -0.701084 4.664277 0.731112, + -0.492137 6.173196 1.017901, + -0.679876 4.660604 0.685834, + -0.489098 6.171473 1.004471, + -0.650602 4.655381 0.645895, + -0.483379 6.169319 0.991463, + -0.61453 4.64885 0.612678, + -0.474933 6.166784 0.979507, + -0.573108 4.641302 0.587268, + -0.46389 6.163927 0.969291, + -0.527909 4.633054 0.570458, + -0.450594 6.160826 0.961497, + -0.480588 4.624436 0.562745, + -0.435595 6.157575 0.95672, + -0.432847 4.615776 0.564325, + -0.419624 6.154291 0.955394, + -0.386389 4.607394 0.575086, + -0.403528 6.151102 0.957744, + -0.34287 4.599592 0.594607, + -0.388207 6.148151 0.963745, + -0.303843 4.59264 0.622169, + -0.374529 6.145584 0.973124, + -0.270698 4.586783 0.656776, + -0.363263 6.143536 0.985377, + -0.244628 4.582217 0.697194, + -0.35501 6.142129 0.999805, + -0.226579 4.579097 0.741993, + -0.350157 6.141454 1.01558, + -0.217234 4.57753 0.789596, + -0.348849 6.141564 1.031812, + -0.216995 4.577569 0.83832, + -0.35099 6.142467 1.047627, + -0.225969 4.579217 0.886422, + -0.35626 6.144122 1.062251, + -0.243955 4.582429 0.932143, + -0.364175 6.146439 1.075053, + -0.270441 4.5871 0.973749, + -0.374144 6.149288 1.085595, + -0.304588 4.593079 1.009592, + -0.385549 6.152514 1.093632, + -0.345238 4.600164 1.038171, + -0.397796 6.155947 1.099091, + -0.390924 4.608105 1.058201, + -0.410392 6.159424 1.102044, + -0.43989 4.616637 1.068727, + -0.422867 6.162782 1.102626, + -0.49021 4.625399 1.069082, + -0.43501 6.165917 1.101031, + -0.539823 4.6342 1.059254, + -0.446271 6.168671 1.097507, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 61, -1, + 3, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 51, 13, -1, + 51, 15, 13, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 25, 23, -1, + 43, 41, 25, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 29, 27, -1, + 39, 37, 29, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 0, 2, 62, -1, + 2, 4, 62, -1, + 4, 6, 62, -1, + 6, 8, 62, -1, + 8, 10, 62, -1, + 10, 12, 62, -1, + 12, 14, 62, -1, + 14, 16, 62, -1, + 16, 18, 62, -1, + 18, 20, 62, -1, + 20, 22, 62, -1, + 22, 24, 62, -1, + 24, 26, 62, -1, + 26, 28, 62, -1, + 28, 30, 62, -1, + 30, 32, 62, -1, + 32, 34, 62, -1, + 34, 36, 62, -1, + 36, 38, 62, -1, + 38, 40, 62, -1, + 40, 42, 62, -1, + 42, 44, 62, -1, + 44, 46, 62, -1, + 46, 48, 62, -1, + 48, 50, 62, -1, + 50, 52, 62, -1, + 52, 54, 62, -1, + 54, 56, 62, -1, + 56, 58, 60, -1, + 62, 56, 60, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-008 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.32139 6.235866 3.342746, + -0.32139 6.782084 3.2428, + -0.338113 6.235865 3.341099, + -0.318483 6.782084 3.243087, + -0.354197 6.235866 3.336221, + -0.315689 6.782084 3.243934, + -0.369018 6.235869 3.3283, + -0.313113 6.782084 3.245311, + -0.382011 6.235869 3.31764, + -0.310857 6.782084 3.247163, + -0.392675 6.235873 3.304647, + -0.309004 6.782084 3.24942, + -0.400599 6.235876 3.289827, + -0.307628 6.782084 3.251996, + -0.405481 6.235878 3.273744, + -0.30678 6.782084 3.25479, + -0.407131 6.235882 3.257015, + -0.306494 6.782084 3.257696, + -0.405485 6.235886 3.240289, + -0.30678 6.782084 3.260602, + -0.400608 6.235888 3.224203, + -0.307628 6.782084 3.263396, + -0.392687 6.235893 3.209378, + -0.309004 6.782084 3.265971, + -0.382024 6.235893 3.196382, + -0.310857 6.782084 3.268228, + -0.369029 6.235898 3.185716, + -0.313113 6.782084 3.270081, + -0.354206 6.235899 3.177792, + -0.315689 6.782084 3.271457, + -0.338118 6.235898 3.172911, + -0.318483 6.782084 3.272305, + -0.321389 6.235901 3.171263, + -0.321389 6.782084 3.272591, + -0.30466 6.235898 3.172911, + -0.324295 6.782084 3.272305, + -0.288572 6.235899 3.177792, + -0.327089 6.782084 3.271457, + -0.273749 6.235897 3.185716, + -0.329665 6.782084 3.270081, + -0.260755 6.235894 3.196382, + -0.331922 6.782084 3.268228, + -0.250091 6.235892 3.209378, + -0.333774 6.782084 3.265971, + -0.24217 6.235889 3.224203, + -0.335151 6.782084 3.263396, + -0.237293 6.235885 3.240289, + -0.335998 6.782084 3.260602, + -0.235648 6.235883 3.257017, + -0.336284 6.782084 3.257696, + -0.237297 6.235879 3.273743, + -0.335998 6.782084 3.25479, + -0.242178 6.235875 3.289827, + -0.33515 6.782084 3.251996, + -0.250103 6.235873 3.304648, + -0.333774 6.782084 3.24942, + -0.260767 6.235868 3.31764, + -0.331922 6.782084 3.247163, + -0.273761 6.235869 3.3283, + -0.329665 6.782084 3.245311, + -0.288579 6.235867 3.33622, + -0.327089 6.782084 3.243934, + -0.304664 6.235864 3.3411, + -0.324294 6.782084 3.243087, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 30, 32, 34, -1, + 30, 34, 36, -1, + 28, 30, 36, -1, + 28, 36, 38, -1, + 26, 28, 38, -1, + 24, 26, 38, -1, + 24, 38, 40, -1, + 22, 24, 40, -1, + 22, 40, 42, -1, + 20, 22, 42, -1, + 20, 42, 44, -1, + 20, 44, 46, -1, + 18, 20, 46, -1, + 18, 46, 48, -1, + 16, 18, 48, -1, + 14, 16, 48, -1, + 14, 48, 50, -1, + 14, 50, 52, -1, + 12, 14, 52, -1, + 12, 52, 54, -1, + 10, 12, 54, -1, + 8, 10, 54, -1, + 8, 54, 56, -1, + 6, 8, 56, -1, + 6, 56, 58, -1, + 4, 6, 58, -1, + 4, 58, 60, -1, + 4, 60, 62, -1, + 2, 4, 62, -1, + 0, 2, 62, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + DEF Cylinder-009 Shape { + appearance Appearance { + material Material { + ambientIntensity 0.5 + diffuseColor 1.0 0.2 0.2 + specularColor 0.8 0.2 0 + emissiveColor 0 0 0 + shininess 0 + transparency 0 + } + texture NULL + textureTransform NULL + } + geometry IndexedFaceSet { + color NULL + coord Coordinate { + point [ + -0.413738 6.055436 1.105973, + -0.413739 6.5789 1.033741, + -0.425056 6.055435 1.104858, + -0.410833 6.5789 1.034027, + -0.435939 6.055435 1.101557, + -0.408038 6.5789 1.034875, + -0.445969 6.055436 1.096195, + -0.405463 6.5789 1.036251, + -0.45476 6.055435 1.088982, + -0.403206 6.5789 1.038104, + -0.461974 6.055436 1.080191, + -0.401353 6.578899 1.040361, + -0.467336 6.055436 1.07016, + -0.399977 6.5789 1.042936, + -0.470637 6.055435 1.059278, + -0.399129 6.5789 1.045731, + -0.471752 6.055436 1.047959, + -0.398843 6.5789 1.048636, + -0.470637 6.055436 1.036641, + -0.399129 6.5789 1.051542, + -0.467336 6.055435 1.025759, + -0.399977 6.5789 1.054336, + -0.461974 6.055436 1.015729, + -0.401353 6.578899 1.056912, + -0.454761 6.055434 1.006937, + -0.403206 6.5789 1.059169, + -0.445969 6.055436 0.999724, + -0.405463 6.5789 1.061021, + -0.435938 6.055436 0.994362, + -0.408038 6.5789 1.062398, + -0.425056 6.055435 0.99106, + -0.410832 6.5789 1.063245, + -0.413739 6.055436 0.989947, + -0.413738 6.5789 1.063532, + -0.40242 6.055435 0.99106, + -0.416644 6.5789 1.063246, + -0.391538 6.055436 0.994362, + -0.419438 6.5789 1.062398, + -0.381508 6.055436 0.999723, + -0.422014 6.5789 1.061021, + -0.372717 6.055435 1.006938, + -0.424271 6.5789 1.059169, + -0.365502 6.055436 1.015729, + -0.426123 6.5789 1.056912, + -0.360141 6.055436 1.02576, + -0.4275 6.5789 1.054337, + -0.356839 6.055435 1.036642, + -0.428347 6.5789 1.051542, + -0.355725 6.055436 1.047959, + -0.428634 6.5789 1.048637, + -0.35684 6.055435 1.059278, + -0.428347 6.5789 1.04573, + -0.360141 6.055435 1.07016, + -0.4275 6.5789 1.042936, + -0.365502 6.055436 1.08019, + -0.426123 6.5789 1.040361, + -0.372717 6.055434 1.088982, + -0.424271 6.5789 1.038104, + -0.381508 6.055436 1.096195, + -0.422014 6.5789 1.036251, + -0.391538 6.055436 1.101557, + -0.419438 6.5789 1.034875, + -0.402421 6.055434 1.104859, + -0.416644 6.5789 1.034027, + ] + } + colorIndex [ ] + coordIndex [ + 0, 1, 3, -1, + 0, 3, 2, -1, + 2, 3, 5, -1, + 2, 5, 4, -1, + 4, 5, 7, -1, + 4, 7, 6, -1, + 6, 7, 9, -1, + 6, 9, 8, -1, + 8, 9, 11, -1, + 8, 11, 10, -1, + 10, 11, 13, -1, + 10, 13, 12, -1, + 12, 13, 15, -1, + 12, 15, 14, -1, + 14, 15, 17, -1, + 14, 17, 16, -1, + 16, 17, 19, -1, + 16, 19, 18, -1, + 18, 19, 21, -1, + 18, 21, 20, -1, + 20, 21, 23, -1, + 20, 23, 22, -1, + 22, 23, 25, -1, + 22, 25, 24, -1, + 24, 25, 27, -1, + 24, 27, 26, -1, + 26, 27, 29, -1, + 26, 29, 28, -1, + 28, 29, 31, -1, + 28, 31, 30, -1, + 30, 31, 33, -1, + 30, 33, 32, -1, + 32, 33, 35, -1, + 32, 35, 34, -1, + 34, 35, 37, -1, + 34, 37, 36, -1, + 36, 37, 39, -1, + 36, 39, 38, -1, + 38, 39, 41, -1, + 38, 41, 40, -1, + 40, 41, 43, -1, + 40, 43, 42, -1, + 42, 43, 45, -1, + 42, 45, 44, -1, + 44, 45, 47, -1, + 44, 47, 46, -1, + 46, 47, 49, -1, + 46, 49, 48, -1, + 48, 49, 51, -1, + 48, 51, 50, -1, + 50, 51, 53, -1, + 50, 53, 52, -1, + 52, 53, 55, -1, + 52, 55, 54, -1, + 54, 55, 57, -1, + 54, 57, 56, -1, + 56, 57, 59, -1, + 56, 59, 58, -1, + 58, 59, 61, -1, + 58, 61, 60, -1, + 3, 1, 63, -1, + 3, 63, 5, -1, + 63, 61, 5, -1, + 61, 59, 5, -1, + 59, 7, 5, -1, + 59, 57, 7, -1, + 57, 9, 7, -1, + 57, 55, 9, -1, + 55, 11, 9, -1, + 55, 53, 11, -1, + 53, 13, 11, -1, + 53, 15, 13, -1, + 53, 51, 15, -1, + 51, 49, 15, -1, + 49, 17, 15, -1, + 49, 19, 17, -1, + 49, 47, 19, -1, + 47, 21, 19, -1, + 47, 45, 21, -1, + 45, 23, 21, -1, + 45, 43, 23, -1, + 43, 41, 23, -1, + 41, 25, 23, -1, + 41, 27, 25, -1, + 41, 39, 27, -1, + 39, 37, 27, -1, + 37, 29, 27, -1, + 37, 31, 29, -1, + 37, 35, 31, -1, + 35, 33, 31, -1, + 1, 0, 62, -1, + 1, 62, 63, -1, + 60, 61, 63, -1, + 60, 63, 62, -1, + 30, 32, 34, -1, + 28, 30, 34, -1, + 28, 34, 36, -1, + 26, 28, 36, -1, + 26, 36, 38, -1, + 26, 38, 40, -1, + 24, 26, 40, -1, + 22, 24, 40, -1, + 22, 40, 42, -1, + 20, 22, 42, -1, + 20, 42, 44, -1, + 18, 20, 44, -1, + 18, 44, 46, -1, + 16, 18, 46, -1, + 16, 46, 48, -1, + 16, 48, 50, -1, + 14, 16, 50, -1, + 12, 14, 50, -1, + 12, 50, 52, -1, + 10, 12, 52, -1, + 10, 52, 54, -1, + 10, 54, 56, -1, + 8, 10, 56, -1, + 6, 8, 56, -1, + 6, 56, 58, -1, + 4, 6, 58, -1, + 4, 58, 60, -1, + 4, 60, 62, -1, + 2, 4, 62, -1, + 0, 2, 62, -1, + ] + normal NULL + creaseAngle 0 + solid TRUE + } + } + ] +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ0_base.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ0_base.wrl new file mode 100644 index 0000000..a3aa114 --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ0_base.wrl @@ -0,0 +1,1564 @@ +#VRML V2.0 utf8 + + +DEF solid_T2R3_TJ0_base_____________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -217.213 -81.044998 -1.2595552e-006, + -220 -81.044998 -1.2574804e-006, + -220 35.507 -1.2585908e-006, + -220 88.997498 4.23314, + -220 81.044998 -1.2538399e-006, + -114.074 -85.350502 -1.2607405e-006, + -208.939 -81.805397 -1.2607975e-006, + -212.177 -83.791 -1.260507e-006, + -219.952 -92.376297 -1.2547333e-006, + -219.80901 -92.910896 -1.2453886e-006, + -220 -91.824997 -1.2512645e-006, + -219.575 -93.412498 -1.2581938e-006, + -219.257 -93.865898 -1.2518078e-006, + -218.866 -94.257202 -1.2496137e-006, + -217.911 -94.808502 -1.2506969e-006, + -219.575 -93.412498 51.825001, + 44.4641 -69.014099 -1.2595042e-006, + 10.3357 -86.544998 -1.2595222e-006, + 92.867699 20.0145 90.150002, + 44.148701 84.118301 -1.2542164e-006, + 49.232601 81.044998 -1.2454431e-006, + 39.1306 86.566704 90.150002, + -33.939201 81.805397 -1.2607867e-006, + 43 67.550003 -1.2605224e-006, + 38.428902 74.0783 -1.2605309e-006, + 84 3.4640999 -1.2604436e-006, + -26.060801 -81.805397 -1.2607684e-006, + 38.756802 86.544998 -1.2583346e-006, + 88.007599 35.507 -1.2557899e-006, + -220 71.414101 8.6852999, + -220 90.507797 5.2906299, + -220 90.681 49.809399, + -220 91 6.3812499, + -218.41299 -94.5746 -1.2534804e-006, + -220 91.824997 -1.2608516e-006, + -216.825 95 -1.255747e-006, + 10.3357 94.374802 -1.2481487e-006, + 11.451 94.307297 -1.2454773e-006, + 33.6875 88.8265 -1.2539538e-006, + 16.038799 93.538399 91.252701, + 31.6483 89.573402 90.150002, + 22.725599 92.1959 90.150002, + 23.937901 91.934601 90.150002, + 22.735001 92.239502 -1.2430874e-006, + 16.055099 93.633499 90.150002, + -37.8228 83.673599 95.6493, + 91.980598 -11.7786 95.014397, + 92.773399 19.9942 91.252701, + 91.081299 -11.6634 95.6493, + 90.8358 27.818199 90.150002, + 92.239502 22.735001 -1.2563827e-006, + 88.8265 33.6875 -1.2486533e-006, + 92.164497 22.7155 90.150002, + 90.743599 27.7899 91.252701, + 10.3357 -94.374802 -1.2447267e-006, + 65.7342 68.5858 90.150002, + 62.9967 71.108498 -1.2602509e-006, + 61.5 72.281097 -1.2466968e-006, + -220 -66.9571 17.877001, + -220 -16.128 31.309999, + -220 -88.997498 4.23314, + -220 90.020798 50.2897, + -220 90.289703 50.020802, + -220 88.618797 50.799999, + -220 -69.247597 50.067299, + -220 -90.8564 49.433201, + -220 -0.75244403 50.067299, + -220 -40.469501 50.799999, + -220 -90.442902 50.149399, + -218.41299 91.824997 54.5746, + -218.866 91.824997 54.257198, + -219.257 91.824997 53.865799, + -219.257 -92.845398 53.5924, + -218.866 -93.0411 53.931301, + 22.6157 -86.856598 96.403503, + 89.764 -19.3456 95.6493, + 78.088501 -23.205 102.8, + 38.756802 -86.544998 -1.2467672e-006, + 71.108498 -62.9967 -1.2584571e-006, + -217.806 94.844597 -1.2425601e-006, + 23.8414 91.564003 92.3218, + 23.913601 91.841301 91.252701, + 31.6161 89.482399 91.252701, + 50.259201 74.361 96.403503, + 57.056099 70.662598 96.117104, + 50.857899 75.246803 96.117104, + 76.448303 27.3862 102.8, + 76.940002 -18.918699 102.8, + -30.590599 86.579697 95.6493, + -219.65401 93.266403 -1.2535471e-006, + -219.845 92.806099 -1.255023e-006, + -219.575 91.824997 53.412498, + -219.961 92.321701 -1.2522154e-006, + -15.9113 92.794998 93.324997, + -216.825 94.5746 53.412498, + -8.0483799 94.5616 91.252701, + -1.0671354e-009 94.903503 91.252701, + -216.825 95 51.825001, + 94.283096 11.4489 90.150002, + 94.307297 11.451 -1.2520348e-006, + 94.230499 12.0667 90.150002, + 94.134804 12.0544 91.252701, + 94.914398 4.0319099 90.150002, + 76.010902 -27.5497 102.8, + 75.854202 -27.556601 102.8, + 76.3797 56.4902 90.150002, + 78.183502 53.966099 -1.2595164e-006, + 71.108498 62.9967 -1.2586183e-006, + 71.313904 62.764099 90.150002, + 84.118301 44.148701 -1.2560098e-006, + 88.149498 35.421398 90.150002, + 76.0718 56.262402 92.3218, + 88.059898 35.385399 91.252701, + 87.794098 35.278599 92.3218, + 92.036102 19.8353 93.324997, + 90.469704 27.705999 92.3218, + 92.493401 19.933901 92.3218, + 92.757004 -11.878 94.231697, + 91.742302 -3.8971601 95.6493, + 16.055099 -93.633499 90.150002, + 11.451 -94.307297 -1.2531644e-006, + 22.725599 -92.1959 90.150002, + -0.21892299 -95 54.998901, + -8.7490877e-009 -95 -1.2558098e-006, + 71.241501 62.700401 91.252701, + -218.41299 -92.302498 54.532902, + -217.911 -92.343102 54.763199, + -217.911 -91.824997 54.808498, + -218.41299 -91.824997 54.5746, + -218.41299 -92.765404 54.408798, + -218.866 -92.656898 54.1105, + -218.866 -92.247299 54.2202, + -218.866 -91.824997 54.257198, + -219.952 -92.376297 51.825001, + -219.80901 -92.910896 51.825001, + -219.257 -92.523003 53.742802, + -219.257 -92.179398 53.834801, + -219.257 -91.824997 53.865799, + 7.70223 -90.494598 96.117104, + 7.6115599 -89.429298 96.403503, + 15.1683 -88.4617 96.403503, + 15.349 -89.515404 96.117104, + 29.9002 -84.625801 96.403503, + 22.885099 -87.891296 96.117104, + 76.311699 -27.463499 102.8, + 78.183502 -53.966099 -1.2428725e-006, + 84.118301 -44.148701 -1.2455948e-006, + 59.6203 -73.838303 91.252701, + 22.735001 -92.239502 -1.2472476e-006, + 23.937901 -91.934601 90.150002, + 33.6875 -88.8265 -1.2542753e-006, + 44.148701 -84.118301 -1.2505534e-006, + -68.965202 95 52.3209, + -7.9844098 93.810097 93.324997, + 36.9692 81.785202 96.403503, + 43.7719 78.355301 96.403503, + 31.5207 89.212303 92.3218, + 59.6203 73.838303 91.252701, + 65.667397 68.516197 91.252701, + 53.9454 78.155403 90.150002, + 53.197601 78.708397 90.150002, + 59.680901 73.913399 90.150002, + 53.966099 78.183502 -1.2561113e-006, + 58.255901 72.148598 95.014397, + 57.686298 71.4431 95.6493, + 51.419701 76.077904 95.6493, + 51.927399 76.829102 95.014397, + 65.4692 68.309303 92.3218, + 58.747601 72.7575 94.231697, + 64.7062 67.513298 94.231697, + 62.843201 65.569397 96.117104, + 63.5373 66.293602 95.6493, + 64.164703 66.948196 95.014397, + 80.170799 49.363098 93.324997, + 84.068298 42.386299 93.324997, + 79.630203 49.0303 94.231697, + -219.257 92.179398 53.834801, + -218.866 92.247299 54.2202, + -219.257 92.845398 53.5924, + -218.866 93.931297 53.0411, + -219.952 91.9207 52.368, + -216.825 94.771202 52.991001, + -8.0240898 94.276199 92.3218, + -216.825 94.636803 53.279301, + -217.37601 94.951797 51.825001, + -216.825 94.951797 52.376301, + -216.825 94.808502 52.9109, + 37.409599 82.759399 96.117104, + 44.7826 80.164497 95.6493, + 44.293301 79.288696 96.117104, + 90.8358 -27.818199 90.150002, + 88.8265 -33.6875 -1.2516074e-006, + 92.239502 -22.735001 -1.2537748e-006, + 92.164497 -22.7155 90.150002, + 80.813103 49.758598 91.252701, + 84.828003 42.769402 90.150002, + 84.741798 42.725899 91.252701, + 80.895302 49.8092 90.150002, + 84.486 42.597 92.3218, + 80.569199 49.608398 92.3218, + 76.3022 56.4328 91.252701, + 91.415497 19.7015 94.231697, + 93.430099 3.9688599 94.231697, + 92.648102 -3.9356401 95.014397, + 93.430099 -3.9688599 94.231697, + 93.386703 11.9586 93.324997, + 93.8507 12.0181 92.3218, + 94.0644 3.99581 93.324997, + -6.4354239e-010 -91.824997 95.6493, + -3.4882848e-009 -93.514397 94.231697, + -76.442101 -95 51.825001, + -182.631 -95 -1.2602217e-006, + -137.679 -95 -1.2599299e-006, + -21.164301 -95 -1.2456742e-006, + -217.37601 -94.951797 -1.2497219e-006, + -216.825 -95 -1.2492329e-006, + 6.1329819e-010 -95 90.150002, + -216.825 -95 51.825001, + -8.0483799 -94.5616 91.252701, + 70.675201 62.202 93.324997, + 65.1455 67.971603 93.324997, + 71.026398 62.511101 92.3218, + 70.1987 61.7826 94.231697, + 75.695702 55.984299 93.324997, + -84.272598 -33.863499 96.117104, + -86.840797 -26.5947 96.117104, + -217.37601 -92.894402 54.763199, + -217.37601 -92.367996 54.904301, + -217.911 -92.845398 54.628601, + -57.056099 -70.662598 96.117104, + -219.952 -92.367996 51.9207, + -220 -91.824997 51.825001, + -216.825 -94.771202 52.991001, + -8.0240898 -94.276199 92.3218, + -7.9844098 -93.810097 93.324997, + -216.825 -94.5746 53.412498, + -216.825 -94.636803 53.279301, + -219.575 -93.388397 52.1007, + -218.41299 -94.5746 51.825001, + -217.911 -94.808502 51.825001, + -219.952 -92.013603 52.343102, + -219.80901 -91.824997 52.9109, + -219.80901 91.824997 52.9109, + -219.575 -91.824997 53.412498, + -219.575 -92.1007 53.388401, + -219.80901 -92.013603 52.894402, + -219.952 -91.824997 52.376301, + -219.952 91.824997 52.376301, + -219.952 -91.9207 52.368, + 7.7873001 -91.494202 95.6493, + 7.9844098 -93.810097 93.324997, + 15.9113 -92.794998 93.324997, + 7.9305701 -93.177498 94.231697, + 7.7501316e-010 -94.1493 93.324997, + 8.0483799 -94.5616 91.252701, + 5.0429598e-009 -94.903503 91.252701, + 8.0565596 -94.657799 90.150002, + 16.038799 -93.538399 91.252701, + 4.4950825e-009 -94.617104 92.3218, + 8.0240898 -94.276199 92.3218, + 50.259201 -74.361 96.403503, + 91.415497 -19.7015 94.231697, + 90.650398 -19.5366 95.014397, + 71.313904 -62.764099 90.150002, + 65.7342 -68.5858 90.150002, + 76.571098 -27.2885 102.8, + 76.448303 -27.3862 102.8, + 57.056099 -70.662598 96.117104, + 62.843201 -65.569397 96.117104, + 68.177399 -60.0037 96.117104, + 76.164703 -27.5184 102.8, + 65.667397 -68.516197 91.252701, + 30.256399 -85.633904 96.117104, + 15.9904 -93.256104 92.3218, + -137.679 95 -1.2469708e-006, + -210.213 95 -1.2523005e-006, + -1.0237998e-009 95 55, + -3.5039401 95 54.935398, + -8.3593541e-009 95 90.150002, + 5.78255e-009 95 -1.2573106e-006, + 8.0565596 94.657799 90.150002, + 15.5185 90.504204 95.6493, + 23.563601 90.496902 94.231697, + 23.3664 89.739502 95.014397, + 15.6717 91.397797 95.014397, + 23.723499 91.111298 93.324997, + 8.0483799 94.5616 91.252701, + 46.284 82.852097 91.252701, + 38.9729 86.217796 92.3218, + 39.0909 86.478798 91.252701, + 44.115898 84.0532 90.150002, + 46.331001 82.936302 90.150002, + 15.349 89.515404 96.117104, + 74.556 55.1413 95.014397, + 78.963799 48.6199 95.014397, + 75.185303 55.6068 94.231697, + 69.611099 61.265499 95.014397, + -88.783401 -19.1343 96.117104, + -90.086197 -11.536 96.117104, + -43.7719 78.355301 96.403503, + -37.409599 82.759399 96.117104, + -44.293301 79.288696 96.117104, + -217.37601 92.894402 54.763199, + -219.257 92.523003 53.742802, + -219.575 92.1007 53.388401, + -219.575 93.199799 52.618698, + -219.062 94.061501 51.825001, + -218.866 94.110497 52.656898, + -217.911 94.808502 51.825001, + -217.911 94.628601 52.845402, + -217.37601 94.763199 52.894402, + -217.37601 94.904297 52.368, + -217.911 94.763199 52.343102, + -218.41299 94.408798 52.7654, + -218.866 93.0411 53.931301, + -218.41299 92.765404 54.408798, + -218.866 92.656898 54.1105, + -219.80901 92.013603 52.894402, + -219.575 92.367996 53.316799, + -219.957 92.321297 51.825001, + -219.952 92.376297 51.825001, + -7.9305701 93.177498 94.231697, + -15.804 92.169296 94.231697, + -218.26601 94.6539 -1.2509158e-006, + -219.07001 94.070099 -1.2462687e-006, + -219.394 93.6912 -1.2555001e-006, + -217.32201 94.960899 -1.2598287e-006, + 38.780201 85.791496 93.324997, + 31.364901 88.771202 93.324997, + 23.137899 88.862099 95.6493, + 30.256399 85.633904 96.117104, + 92.493401 -19.933901 92.3218, + 92.036102 -19.8353 93.324997, + 94.914398 -8.0457667e-009 90.150002, + 95 1.7712968e-009 -1.2585485e-006, + 89.415298 27.383101 94.231697, + 87.3601 35.104198 93.324997, + 90.0224 27.569 93.324997, + 83.501404 42.100498 94.231697, + 94.531799 -4.0156598 92.3218, + 94.818001 4.0278201 91.252701, + 94.531799 4.0156598 92.3218, + 94.0644 -3.99581 93.324997, + 93.386703 -11.9586 93.324997, + 78.168198 22.293301 102.8, + 78.088501 -21.381701 102.8, + 78.168198 -22.293301 102.8, + 91.980598 11.7786 95.014397, + 92.757004 11.878 94.231697, + 92.648102 3.9356401 95.014397, + 91.742302 3.8971601 95.6493, + -7.8642001 -92.397598 95.014397, + -7.9305701 -93.177498 94.231697, + 7.6994855e-009 -92.731697 95.014397, + -217.911 -93.316803 54.408798, + -7.7873001 -91.494202 95.6493, + 5.950394e-009 -90.8218 96.117104, + -5.5298632e-009 -89.752701 96.403503, + -85.818497 -26.281601 96.403503, + -87.738197 -18.909 96.403503, + -86.660301 -18.676701 96.5, + 75.547096 -27.496901 102.8, + -81.097198 -40.888302 96.117104, + -77.337402 -47.6185 96.117104, + -62.843201 -65.569397 96.117104, + -15.9113 -92.794998 93.324997, + -218.866 -93.931297 53.0411, + -218.41299 -94.408798 52.7654, + -217.37601 -94.904297 52.368, + -217.911 -94.763199 52.343102, + -217.37601 -94.951797 51.825001, + -216.825 -94.951797 52.376301, + -217.37601 -94.763199 52.894402, + -216.825 -94.808502 52.9109, + 15.6717 -91.397797 95.014397, + 7.8642001 -92.397598 95.014397, + 15.5185 -90.504204 95.6493, + 23.137899 -88.862099 95.6493, + 23.3664 -89.739502 95.014397, + 15.804 -92.169296 94.231697, + 90.469704 -27.705999 92.3218, + 90.743599 -27.7899 91.252701, + 69.611099 -61.265499 95.014397, + 76.3797 -56.4902 90.150002, + 80.895302 -49.8092 90.150002, + 61.5 -72.281097 -1.2470146e-006, + 49.232601 -81.044998 -1.2541136e-006, + 54.742001 -77.5756 -1.2572616e-006, + 62.9967 -71.108498 -1.2534254e-006, + 53.9454 -78.155403 90.150002, + 59.680901 -73.913399 90.150002, + 53.197601 -78.708397 90.150002, + 53.966099 -78.183502 -1.2527939e-006, + 39.1306 -86.566704 90.150002, + 23.8414 -91.564003 92.3218, + 5.2864237e-009 94.617104 92.3218, + 8.0240898 94.276199 92.3218, + 15.9113 92.794998 93.324997, + 15.9904 93.256104 92.3218, + 53.1436 78.628502 91.252701, + 59.4403 73.615402 92.3218, + 7.6115599 89.429298 96.403503, + 22.6157 86.856598 96.403503, + 22.885099 87.891296 96.117104, + 29.9002 84.625801 96.403503, + 15.1683 88.4617 96.403503, + 76.164703 27.5184 102.8, + 5.7502403e-009 89.752701 96.403503, + 7.70223 90.494598 96.117104, + 76.677101 27.1728 102.8, + 76.571098 27.2885 102.8, + 76.763702 27.042 102.8, + 68.930496 60.6665 95.6493, + 73.827003 54.6022 95.6493, + 78.191704 48.144501 95.6493, + 68.177399 60.0037 96.117104, + -80.142502 40.407001 96.403503, + -79.157898 39.910599 96.5, + -49.6418 73.447403 96.5, + -43.2342 77.3927 96.5, + -61.340401 64.001404 96.5, + 75.854202 27.556601 102.8, + 76.010902 27.5497 102.8, + 76.311699 27.463499 102.8, + -14.9819 87.374802 96.5, + -15.1683 88.4617 96.403503, + -7.6115599 89.429298 96.403503, + -56.384399 69.830803 96.403503, + -57.056099 70.662598 96.117104, + -50.857899 75.246803 96.117104, + -50.259201 74.361 96.403503, + -62.843201 65.569397 96.117104, + -62.103401 64.797501 96.403503, + -55.6917 68.9729 96.5, + -86.660301 18.676701 96.5, + -82.257401 33.053699 96.5, + 66.902298 -23.615101 102.8, + 66.909103 23.7719 102.8, + 66.909103 -23.7719 102.8, + 66.940399 23.925699 102.8, + -85.818497 26.281601 96.403503, + -84.272598 33.863499 96.117104, + -83.280502 33.464901 96.403503, + -88.783401 19.1343 96.117104, + -87.738197 18.909 96.403503, + -84.764198 25.9587 96.5, + -89.025703 -11.4002 96.403503, + -87.931999 -11.2601 96.5, + -29.9002 84.625801 96.403503, + -36.9692 81.785202 96.403503, + -22.3379 85.789497 96.5, + -22.6157 86.856598 96.403503, + -30.256399 85.633904 96.117104, + -77.337402 47.6185 96.117104, + -81.097198 40.888302 96.117104, + -217.911 92.343102 54.763199, + -86.840797 26.5947 96.117104, + -217.37601 92.367996 54.904301, + -218.41299 92.302498 54.532902, + -219.575 92.845398 53.0411, + -219.575 92.618797 53.199799, + -219.257 93.388397 53.136799, + -219.575 93.0411 52.845402, + -219.257 93.5924 52.845402, + -219.257 93.136803 53.388401, + -219.575 93.388397 52.1007, + -219.575 93.316803 52.368, + -219.575 93.412498 51.825001, + -219.80901 92.910896 51.825001, + -219.257 93.865898 51.825001, + -219.257 93.834801 52.179401, + -219.257 93.742798 52.522999, + -218.685 94.384102 51.825001, + -218.866 94.257202 51.825001, + -218.866 94.2202 52.247299, + -218.41299 94.532898 52.302502, + -218.41299 94.5746 51.825001, + -218.69099 94.3936 -1.2503151e-006, + -218.866 93.388397 53.688202, + -218.866 93.688202 53.388401, + -219.952 92.343102 52.013599, + -219.952 92.367996 51.9207, + -219.80901 92.845398 52.1964, + -219.80901 92.765404 52.368, + -219.80901 92.894402 52.013599, + -219.952 92.1007 52.302502, + -219.952 92.013603 52.343102, + -219.80901 92.196404 52.845402, + -219.80901 92.367996 52.7654, + -219.952 92.247299 52.179401, + -219.952 92.302498 52.1007, + -220 91.824997 51.825001, + -219.952 92.179398 52.247299, + -219.80901 92.656898 52.522999, + -219.80901 92.523003 52.656898, + 38.196301 84.499802 95.014397, + 30.590599 86.579697 95.6493, + 37.8228 83.673599 95.6493, + 30.892599 87.434601 95.014397, + 45.2248 80.9561 95.014397, + 38.5187 85.212997 94.231697, + 31.1534 88.1726 94.231697, + 92.867699 -20.0145 90.150002, + 76.828796 26.8992 102.8, + 77.851601 24.0889 102.8, + 89.764 19.3456 95.6493, + 91.081299 11.6634 95.6493, + 90.650398 19.5366 95.014397, + 78.088501 23.205 102.8, + 87.800003 26.8885 95.6493, + -218.866 -93.388397 53.688202, + -218.41299 -93.199799 54.206299, + -23.137899 -88.862099 95.6493, + -30.590599 -86.579697 95.6493, + -37.8228 -83.673599 95.6493, + -37.409599 -82.759399 96.117104, + -15.5185 -90.504204 95.6493, + -29.9002 -84.625801 96.403503, + -30.256399 -85.633904 96.117104, + -36.514999 -80.780403 96.5, + -29.532801 -83.586098 96.5, + -84.764198 -25.9587 96.5, + -83.280502 -33.464901 96.403503, + -80.142502 -40.407001 96.403503, + 67.5597 -24.589701 102.8, + 67.170303 -24.332001 102.8, + -72.160896 -53.3699 96.403503, + -76.427002 -47.057999 96.403503, + -71.2743 -52.714199 96.5, + -73.0205 -54.005699 96.117104, + -66.547096 -58.568802 96.5, + -67.374802 -59.297298 96.403503, + -68.177399 -60.0037 96.117104, + -43.7719 -78.355301 96.403503, + -50.857899 -75.246803 96.117104, + -44.293301 -79.288696 96.117104, + -36.9692 -81.785202 96.403503, + -219.952 -92.302498 52.1007, + -219.952 -92.247299 52.179401, + -219.952 -92.179398 52.247299, + -219.80901 -92.656898 52.522999, + -219.257 -93.388397 53.136799, + -217.37601 -93.834801 54.2202, + -217.911 -93.742798 54.1105, + -217.37601 -94.2202 53.834801, + -217.37601 -93.388397 54.532902, + -23.3664 -89.739502 95.014397, + -15.6717 -91.397797 95.014397, + -15.804 -92.169296 94.231697, + -218.866 -94.2202 52.247299, + -219.257 -93.742798 52.522999, + -219.257 -93.834801 52.179401, + -218.866 -94.110497 52.656898, + -219.257 -93.865898 51.825001, + -218.866 -94.257202 51.825001, + -218.41299 -94.532898 52.302502, + -217.911 -94.408798 53.316799, + -217.911 -94.628601 52.845402, + -217.37601 -94.532898 53.388401, + 38.196301 -84.499802 95.014397, + 30.892599 -87.434601 95.014397, + 30.590599 -86.579697 95.6493, + 87.800003 -26.8885 95.6493, + 77.851601 -24.0889 102.8, + 89.415298 -27.383101 94.231697, + 90.0224 -27.569 93.324997, + 88.667 -27.153999 95.014397, + 87.794098 -35.278599 92.3218, + 71.241501 -62.700401 91.252701, + 68.930496 -60.6665 95.6493, + 76.677101 -27.1728 102.8, + 65.4692 -68.309303 92.3218, + 44.293301 -79.288696 96.117104, + 37.409599 -82.759399 96.117104, + 37.8228 -83.673599 95.6493, + 44.7826 -80.164497 95.6493, + 43.7719 -78.355301 96.403503, + 36.9692 -81.785202 96.403503, + 50.857899 -75.246803 96.117104, + 46.331001 -82.936302 90.150002, + 44.115898 -84.0532 90.150002, + 31.6161 -89.482399 91.252701, + 39.0909 -86.478798 91.252701, + 31.6483 -89.573402 90.150002, + 23.913601 -91.841301 91.252701, + 31.364901 -88.771202 93.324997, + 31.5207 -89.212303 92.3218, + 23.723499 -91.111298 93.324997, + 23.563601 -90.496902 94.231697, + 31.1534 -88.1726 94.231697, + 7.9305701 93.177498 94.231697, + -2.1448674e-009 93.514397 94.231697, + 4.5508055e-009 94.1493 93.324997, + 7.9844098 93.810097 93.324997, + 7.8642001 92.397598 95.014397, + 15.804 92.169296 94.231697, + 52.721199 78.003601 93.324997, + 45.9161 82.193604 93.324997, + 46.144299 82.601997 92.3218, + 52.9832 78.391098 92.3218, + 52.3657 77.4776 94.231697, + 45.606499 81.639397 94.231697, + 59.1465 73.251503 93.324997, + -72.160896 53.3699 96.403503, + -76.427002 47.057999 96.403503, + -66.547096 58.568802 96.5, + -67.374802 59.297298 96.403503, + -73.0205 54.005699 96.117104, + -68.177399 60.0037 96.117104, + 67.5597 24.589701 102.8, + -36.514999 80.780403 96.5, + -29.532801 83.586098 96.5, + 67.416901 24.524599 102.8, + 75.547096 27.496901 102.8, + 75.698303 27.538799 102.8, + 67.286003 24.438 102.8, + 67.072701 24.2092 102.8, + -71.2743 52.714199 96.5, + -75.488098 46.479801 96.5, + 66.995399 24.072599 102.8, + 66.995399 -24.072599 102.8, + 67.170303 24.332001 102.8, + 67.072701 -24.2092 102.8, + 66.902298 23.615101 102.8, + 66.940399 -23.925699 102.8, + -75.488098 -46.479801 96.5, + -79.157898 -39.910599 96.5, + -82.257401 -33.053699 96.5, + -90.086197 11.536 96.117104, + -217.911 91.824997 54.808498, + -218.41299 93.931297 53.5924, + -217.37601 94.2202 53.834801, + -217.37601 94.532898 53.388401, + -217.911 94.408798 53.316799, + -218.41299 94.206299 53.199799, + -217.911 92.845398 54.628601, + -1.9138993e-009 91.824997 95.6493, + 2.5600209e-009 92.731697 95.014397, + -3.3771107e-011 90.8218 96.117104, + 7.7873001 91.494202 95.6493, + -15.5185 90.504204 95.6493, + -15.349 89.515404 96.117104, + -7.70223 90.494598 96.117104, + -7.7873001 91.494202 95.6493, + -7.8642001 92.397598 95.014397, + -15.6717 91.397797 95.014397, + -23.137899 88.862099 95.6493, + -23.3664 89.739502 95.014397, + -22.885099 87.891296 96.117104, + 94.914398 -4.0319099 90.150002, + 94.307297 -11.451 -1.245527e-006, + 86.044701 34.5756 95.014397, + 86.771004 34.867401 94.231697, + 88.667 27.153999 95.014397, + 85.2034 34.237499 95.6493, + 82.802498 41.748199 95.014397, + 81.992897 41.34 95.6493, + -218.41299 -93.931297 53.5924, + -218.41299 -94.206299 53.199799, + -217.911 -94.110497 53.742802, + -218.41299 -93.5924 53.931301, + -218.866 -93.688202 53.388401, + -15.1683 -88.4617 96.403503, + -7.70223 -90.494598 96.117104, + -7.6115599 -89.429298 96.403503, + -15.349 -89.515404 96.117104, + -22.885099 -87.891296 96.117104, + -22.6157 -86.856598 96.403503, + 75.698303 -27.538799 102.8, + -14.9819 -87.374802 96.5, + -22.3379 -85.789497 96.5, + -56.384399 -69.830803 96.403503, + -61.340401 -64.001404 96.5, + -62.103401 -64.797501 96.403503, + -219.80901 -92.845398 52.1964, + -219.952 -92.343102 52.013599, + -219.80901 -92.894402 52.013599, + -219.80901 -92.367996 52.7654, + -219.80901 -92.196404 52.845402, + -219.952 -92.1007 52.302502, + -219.575 -92.367996 53.316799, + -219.575 -92.845398 53.0411, + -219.80901 -92.523003 52.656898, + -219.575 -92.618797 53.199799, + -219.257 -93.136803 53.388401, + -219.575 -93.199799 52.618698, + -219.80901 -92.765404 52.368, + -219.575 -93.316803 52.368, + -219.575 -93.0411 52.845402, + -219.257 -93.5924 52.845402, + 58.255901 -72.148598 95.014397, + 58.747601 -72.7575 94.231697, + 51.927399 -76.829102 95.014397, + 51.419701 -76.077904 95.6493, + 57.686298 -71.4431 95.6493, + 63.5373 -66.293602 95.6493, + 64.164703 -66.948196 95.014397, + 64.7062 -67.513298 94.231697, + 86.771004 -34.867401 94.231697, + 84.741798 -42.725899 91.252701, + 88.059898 -35.385399 91.252701, + 88.149498 -35.421398 90.150002, + 84.828003 -42.769402 90.150002, + 80.813103 -49.758598 91.252701, + 76.3022 -56.4328 91.252701, + 76.0718 -56.262402 92.3218, + 87.3601 -35.104198 93.324997, + 84.486 -42.597 92.3218, + 80.569199 -49.608398 92.3218, + 70.675201 -62.202 93.324997, + 70.1987 -61.7826 94.231697, + 71.026398 -62.511101 92.3218, + 65.1455 -67.971603 93.324997, + 45.2248 -80.9561 95.014397, + 38.5187 -85.212997 94.231697, + 38.780201 -85.791496 93.324997, + 52.3657 -77.4776 94.231697, + 45.606499 -81.639397 94.231697, + -89.671799 3.8092101 96.403503, + -90.739998 3.8545899 96.117104, + -89.025703 11.4002 96.403503, + -89.671799 -3.8092101 96.403503, + -90.739998 -3.8545899 96.117104, + -88.570099 3.7624099 96.5, + -87.931999 11.2601 96.5, + -88.570099 -3.7624099 96.5, + -217.911 93.742798 54.1105, + -217.911 94.110497 53.742802, + -218.41299 93.5924 53.931301, + -218.41299 93.199799 54.206299, + -217.911 93.316803 54.408798, + -217.37601 93.834801 54.2202, + -217.37601 93.388397 54.532902, + 94.134804 -12.0544 91.252701, + 94.283096 -11.4489 90.150002, + 94.818001 -4.0278201 91.252701, + 94.230499 -12.0667 90.150002, + 93.8507 -12.0181 92.3218, + 92.773399 -19.9942 91.252701, + -49.6418 -73.447403 96.5, + -50.259201 -74.361 96.403503, + -43.2342 -77.3927 96.5, + -55.6917 -68.9729 96.5, + 67.286003 -24.438 102.8, + 67.416901 -24.524599 102.8, + 76.763702 -27.042 102.8, + 76.828796 -26.8992 102.8, + 85.2034 -34.237499 95.6493, + 86.044701 -34.5756 95.014397, + 84.068298 -42.386299 93.324997, + 80.170799 -49.363098 93.324997, + 75.695702 -55.984299 93.324997, + 45.9161 -82.193604 93.324997, + 46.284 -82.852097 91.252701, + 38.9729 -86.217796 92.3218, + 52.9832 -78.391098 92.3218, + 59.1465 -73.251503 93.324997, + 59.4403 -73.615402 92.3218, + 52.721199 -78.003601 93.324997, + 53.1436 -78.628502 91.252701, + 46.144299 -82.601997 92.3218, + 78.963799 -48.6199 95.014397, + 82.802498 -41.748199 95.014397, + 83.501404 -42.100498 94.231697, + 79.630203 -49.0303 94.231697, + 81.992897 -41.34 95.6493, + 78.191704 -48.144501 95.6493, + 73.827003 -54.6022 95.6493, + 74.556 -55.1413 95.014397, + 75.185303 -55.6068 94.231697 ] + + } + coordIndex [ 26, 6, 34, -1, 32, 491, 34, -1, + 0, 11, 34, -1, 5, 6, 26, -1, + 1, 34, 11, -1, 25, 16, 26, -1, + 40, 43, 42, -1, 3, 34, 4, -1, + 7, 11, 0, -1, 7, 34, 6, -1, + 7, 0, 34, -1, 8, 1, 11, -1, + 8, 11, 9, -1, 2, 4, 34, -1, + 2, 34, 1, -1, 15, 9, 11, -1, + 278, 96, 280, -1, 38, 43, 40, -1, + 21, 38, 40, -1, 21, 27, 38, -1, + 30, 32, 34, -1, 30, 34, 3, -1, + 30, 3, 60, -1, 17, 212, 26, -1, + 17, 123, 212, -1, 17, 26, 16, -1, + 10, 1, 8, -1, 10, 2, 1, -1, + 10, 60, 3, -1, 10, 3, 4, -1, + 10, 4, 2, -1, 211, 5, 26, -1, + 211, 26, 212, -1, 211, 6, 5, -1, + 211, 7, 6, -1, 211, 11, 7, -1, + 211, 33, 11, -1, 134, 9, 15, -1, + 12, 33, 13, -1, 12, 11, 33, -1, + 554, 13, 33, -1, 71, 91, 243, -1, + 279, 38, 27, -1, 302, 429, 301, -1, + 92, 34, 491, -1, 92, 90, 34, -1, + 650, 192, 334, -1, 650, 502, 192, -1, + 115, 116, 53, -1, 18, 100, 99, -1, + 47, 116, 206, -1, 47, 100, 18, -1, + 47, 53, 116, -1, 47, 52, 53, -1, + 47, 18, 52, -1, 162, 20, 291, -1, + 106, 334, 25, -1, 65, 60, 10, -1, + 65, 10, 231, -1, 150, 123, 17, -1, + 150, 17, 387, -1, 150, 151, 77, -1, + 214, 14, 33, -1, 214, 33, 211, -1, + 133, 8, 9, -1, 133, 9, 134, -1, + 133, 231, 10, -1, 133, 10, 8, -1, + 553, 15, 11, -1, 553, 11, 12, -1, + 553, 12, 13, -1, 553, 13, 554, -1, + 239, 33, 14, -1, 239, 14, 214, -1, + 237, 134, 15, -1, 237, 15, 553, -1, + 137, 71, 243, -1, 137, 132, 70, -1, + 137, 70, 71, -1, 78, 146, 145, -1, + 78, 334, 192, -1, 78, 25, 334, -1, + 78, 16, 25, -1, 78, 17, 16, -1, + 78, 387, 17, -1, 326, 279, 34, -1, + 35, 326, 97, -1, 35, 279, 326, -1, + 81, 40, 42, -1, 44, 43, 37, -1, + 44, 39, 81, -1, 44, 280, 39, -1, + 44, 37, 280, -1, 286, 280, 96, -1, + 286, 39, 280, -1, 289, 21, 40, -1, + 289, 290, 21, -1, 300, 45, 302, -1, + 300, 302, 301, -1, 395, 182, 153, -1, + 395, 286, 96, -1, 395, 96, 95, -1, + 395, 95, 182, -1, 94, 153, 182, -1, + 732, 635, 302, -1, 732, 302, 45, -1, + 732, 45, 88, -1, 191, 78, 192, -1, + 191, 146, 78, -1, 203, 118, 46, -1, + 563, 76, 346, -1, 48, 262, 46, -1, + 48, 46, 118, -1, 48, 118, 346, -1, + 48, 346, 76, -1, 443, 629, 628, -1, + 113, 115, 53, -1, 50, 28, 51, -1, + 50, 18, 99, -1, 50, 99, 334, -1, + 50, 52, 18, -1, 50, 334, 106, -1, + 50, 106, 28, -1, 213, 212, 123, -1, + 158, 124, 55, -1, 19, 20, 162, -1, + 19, 162, 27, -1, 19, 291, 20, -1, + 19, 290, 291, -1, 19, 27, 21, -1, + 19, 21, 290, -1, 56, 27, 162, -1, + 56, 107, 106, -1, 56, 162, 57, -1, + 56, 24, 27, -1, 56, 55, 107, -1, + 56, 23, 24, -1, 56, 25, 23, -1, + 56, 106, 25, -1, 160, 162, 291, -1, + 22, 24, 23, -1, 22, 25, 26, -1, + 22, 23, 25, -1, 22, 26, 34, -1, + 22, 34, 279, -1, 22, 27, 24, -1, + 22, 279, 27, -1, 109, 28, 106, -1, + 109, 51, 28, -1, 109, 110, 51, -1, + 29, 60, 62, -1, 29, 62, 32, -1, + 29, 30, 60, -1, 29, 32, 30, -1, + 31, 491, 32, -1, 31, 62, 491, -1, + 31, 32, 62, -1, 59, 62, 60, -1, + 59, 66, 62, -1, 59, 65, 66, -1, + 67, 231, 491, -1, 67, 491, 63, -1, + 67, 62, 66, -1, 120, 150, 148, -1, + 120, 123, 150, -1, 120, 54, 123, -1, + 224, 227, 362, -1, 224, 225, 227, -1, + 127, 225, 297, -1, 238, 554, 33, -1, + 238, 33, 239, -1, 176, 71, 70, -1, + 176, 70, 177, -1, 551, 237, 553, -1, + 377, 376, 378, -1, 251, 273, 587, -1, + 383, 78, 145, -1, 149, 121, 148, -1, + 388, 387, 78, -1, 325, 34, 90, -1, + 325, 326, 34, -1, 275, 35, 97, -1, + 275, 279, 35, -1, 36, 279, 280, -1, + 36, 280, 37, -1, 36, 38, 279, -1, + 36, 43, 38, -1, 36, 37, 43, -1, + 398, 81, 39, -1, 398, 39, 286, -1, + 82, 40, 81, -1, 82, 81, 156, -1, + 82, 289, 40, -1, 41, 42, 43, -1, + 41, 43, 44, -1, 41, 81, 42, -1, + 41, 44, 81, -1, 85, 165, 188, -1, + 428, 429, 302, -1, 452, 88, 45, -1, + 452, 45, 300, -1, 458, 69, 629, -1, + 458, 70, 69, -1, 458, 177, 70, -1, + 299, 301, 429, -1, 179, 463, 479, -1, + 247, 180, 491, -1, 320, 90, 92, -1, + 320, 468, 90, -1, 184, 308, 312, -1, + 184, 97, 326, -1, 476, 308, 323, -1, + 632, 153, 94, -1, 186, 182, 95, -1, + 731, 732, 647, -1, 731, 322, 631, -1, + 193, 192, 502, -1, 193, 502, 738, -1, + 117, 203, 46, -1, 117, 332, 343, -1, + 117, 261, 332, -1, 117, 46, 262, -1, + 117, 262, 261, -1, 117, 343, 342, -1, + 101, 206, 340, -1, 101, 47, 206, -1, + 101, 100, 47, -1, 102, 334, 99, -1, + 668, 270, 361, -1, 668, 664, 104, -1, + 357, 104, 664, -1, 139, 104, 357, -1, + 75, 262, 48, -1, 75, 48, 76, -1, + 49, 50, 51, -1, 49, 110, 53, -1, + 49, 51, 110, -1, 49, 53, 52, -1, + 49, 52, 50, -1, 197, 109, 106, -1, + 108, 107, 55, -1, 108, 55, 124, -1, + 345, 87, 361, -1, 112, 110, 196, -1, + 112, 53, 110, -1, 112, 113, 53, -1, + 205, 206, 116, -1, 201, 507, 348, -1, + 336, 115, 113, -1, 336, 337, 115, -1, + 256, 54, 120, -1, 256, 123, 54, -1, + 256, 216, 123, -1, 221, 223, 111, -1, + 221, 200, 124, -1, 221, 111, 200, -1, + 161, 158, 55, -1, 161, 55, 56, -1, + 161, 56, 57, -1, 161, 57, 162, -1, + 58, 59, 60, -1, 58, 60, 65, -1, + 58, 65, 59, -1, 61, 491, 62, -1, + 61, 63, 491, -1, 61, 62, 67, -1, + 61, 67, 63, -1, 68, 65, 231, -1, + 68, 231, 67, -1, 64, 66, 65, -1, + 64, 67, 66, -1, 64, 65, 68, -1, + 64, 68, 67, -1, 532, 227, 364, -1, + 532, 529, 227, -1, 126, 227, 225, -1, + 126, 225, 127, -1, 722, 629, 127, -1, + 128, 629, 69, -1, 128, 127, 629, -1, + 128, 69, 70, -1, 128, 70, 132, -1, + 228, 354, 545, -1, 228, 227, 126, -1, + 536, 535, 515, -1, 218, 258, 233, -1, + 234, 548, 365, -1, 234, 233, 258, -1, + 304, 91, 71, -1, 304, 71, 176, -1, + 680, 683, 135, -1, 72, 683, 684, -1, + 72, 135, 683, -1, 72, 73, 135, -1, + 72, 684, 510, -1, 72, 510, 73, -1, + 676, 134, 237, -1, 136, 135, 131, -1, + 136, 132, 137, -1, 136, 131, 132, -1, + 511, 73, 510, -1, 511, 228, 129, -1, + 511, 354, 228, -1, 130, 131, 135, -1, + 130, 135, 73, -1, 130, 511, 129, -1, + 130, 73, 511, -1, 74, 142, 270, -1, + 74, 270, 140, -1, 143, 376, 377, -1, + 143, 74, 140, -1, 143, 142, 74, -1, + 252, 353, 209, -1, 144, 270, 142, -1, + 144, 142, 577, -1, 565, 332, 261, -1, + 701, 146, 191, -1, 562, 262, 75, -1, + 562, 76, 563, -1, 562, 75, 76, -1, + 263, 78, 383, -1, 693, 694, 267, -1, + 693, 267, 578, -1, 584, 273, 257, -1, + 584, 121, 149, -1, 393, 77, 151, -1, + 393, 150, 77, -1, 264, 388, 78, -1, + 264, 78, 263, -1, 79, 323, 308, -1, + 79, 326, 323, -1, 79, 308, 184, -1, + 79, 184, 326, -1, 152, 97, 278, -1, + 152, 275, 97, -1, 80, 398, 285, -1, + 80, 81, 398, -1, 80, 285, 156, -1, + 80, 156, 81, -1, 397, 285, 398, -1, + 288, 82, 156, -1, 288, 289, 82, -1, + 399, 160, 291, -1, 423, 86, 155, -1, + 423, 410, 86, -1, 423, 361, 87, -1, + 83, 155, 86, -1, 83, 86, 85, -1, + 83, 85, 155, -1, 189, 155, 85, -1, + 189, 85, 188, -1, 170, 171, 164, -1, + 170, 410, 415, -1, 84, 85, 86, -1, + 84, 86, 410, -1, 84, 410, 170, -1, + 84, 170, 164, -1, 84, 164, 165, -1, + 84, 165, 85, -1, 503, 410, 423, -1, + 503, 87, 345, -1, 503, 423, 87, -1, + 646, 647, 732, -1, 646, 732, 88, -1, + 646, 88, 452, -1, 646, 452, 648, -1, + 316, 177, 458, -1, 178, 314, 478, -1, + 469, 325, 467, -1, 469, 306, 324, -1, + 469, 324, 325, -1, 89, 325, 90, -1, + 89, 467, 325, -1, 89, 90, 468, -1, + 89, 468, 467, -1, 634, 307, 179, -1, + 634, 179, 479, -1, 246, 491, 231, -1, + 246, 247, 491, -1, 486, 491, 180, -1, + 494, 488, 460, -1, 242, 180, 247, -1, + 242, 243, 91, -1, 242, 91, 304, -1, + 319, 92, 491, -1, 319, 320, 92, -1, + 321, 153, 322, -1, 93, 631, 322, -1, + 93, 632, 631, -1, 93, 322, 153, -1, + 93, 153, 632, -1, 183, 94, 182, -1, + 183, 632, 94, -1, 185, 95, 96, -1, + 185, 186, 95, -1, 185, 96, 278, -1, + 185, 278, 97, -1, 185, 97, 184, -1, + 310, 632, 183, -1, 403, 404, 330, -1, + 329, 403, 330, -1, 381, 193, 738, -1, + 381, 700, 701, -1, 98, 99, 100, -1, + 98, 102, 99, -1, 98, 100, 101, -1, + 98, 101, 340, -1, 98, 340, 102, -1, + 333, 334, 102, -1, 333, 102, 340, -1, + 103, 104, 139, -1, 103, 270, 668, -1, + 103, 668, 104, -1, 103, 140, 270, -1, + 103, 139, 140, -1, 105, 197, 106, -1, + 105, 200, 197, -1, 105, 106, 107, -1, + 105, 107, 108, -1, 105, 124, 200, -1, + 105, 108, 124, -1, 195, 109, 197, -1, + 195, 196, 110, -1, 195, 110, 109, -1, + 199, 223, 173, -1, 199, 111, 223, -1, + 199, 200, 111, -1, 199, 173, 174, -1, + 198, 112, 196, -1, 198, 113, 112, -1, + 198, 199, 174, -1, 198, 336, 113, -1, + 198, 174, 336, -1, 338, 336, 174, -1, + 114, 337, 201, -1, 114, 116, 115, -1, + 114, 115, 337, -1, 114, 205, 116, -1, + 114, 348, 205, -1, 114, 201, 348, -1, + 335, 201, 337, -1, 204, 117, 342, -1, + 204, 203, 117, -1, 207, 205, 348, -1, + 350, 118, 203, -1, 350, 203, 349, -1, + 350, 346, 118, -1, 350, 344, 346, -1, + 255, 216, 256, -1, 255, 258, 218, -1, + 119, 257, 256, -1, 119, 256, 120, -1, + 119, 120, 148, -1, 119, 148, 121, -1, + 119, 121, 584, -1, 119, 584, 257, -1, + 514, 545, 513, -1, 512, 545, 546, -1, + 512, 513, 545, -1, 122, 210, 213, -1, + 122, 213, 123, -1, 122, 216, 210, -1, + 122, 123, 216, -1, 373, 232, 372, -1, + 373, 233, 232, -1, 373, 218, 233, -1, + 217, 210, 216, -1, 167, 158, 400, -1, + 167, 220, 221, -1, 167, 124, 158, -1, + 167, 221, 124, -1, 222, 172, 296, -1, + 523, 224, 362, -1, 523, 522, 224, -1, + 298, 127, 297, -1, 298, 722, 127, -1, + 125, 126, 127, -1, 125, 127, 128, -1, + 125, 129, 228, -1, 125, 228, 126, -1, + 125, 130, 129, -1, 125, 131, 130, -1, + 125, 132, 131, -1, 125, 128, 132, -1, + 229, 364, 227, -1, 741, 536, 519, -1, + 741, 519, 744, -1, 230, 231, 133, -1, + 230, 133, 134, -1, 230, 134, 676, -1, + 235, 233, 234, -1, 253, 234, 258, -1, + 253, 252, 209, -1, 661, 510, 684, -1, + 689, 366, 661, -1, 687, 676, 237, -1, + 244, 680, 135, -1, 244, 135, 136, -1, + 244, 245, 680, -1, 244, 137, 243, -1, + 244, 136, 137, -1, 141, 376, 143, -1, + 141, 143, 140, -1, 379, 251, 587, -1, + 208, 353, 249, -1, 208, 249, 356, -1, + 138, 356, 249, -1, 138, 357, 356, -1, + 138, 139, 357, -1, 138, 140, 139, -1, + 138, 141, 140, -1, 138, 249, 376, -1, + 138, 376, 141, -1, 272, 577, 142, -1, + 272, 142, 143, -1, 272, 143, 377, -1, + 272, 377, 561, -1, 576, 144, 577, -1, + 266, 270, 144, -1, 266, 578, 267, -1, + 266, 144, 576, -1, 564, 565, 261, -1, + 384, 145, 146, -1, 384, 383, 145, -1, + 702, 146, 701, -1, 702, 384, 146, -1, + 702, 703, 384, -1, 269, 569, 570, -1, + 268, 267, 694, -1, 268, 569, 269, -1, + 757, 147, 271, -1, 757, 759, 147, -1, + 390, 147, 759, -1, 390, 388, 264, -1, + 390, 271, 147, -1, 390, 264, 271, -1, + 574, 272, 561, -1, 583, 150, 393, -1, + 583, 148, 150, -1, 583, 149, 148, -1, + 583, 584, 149, -1, 386, 579, 151, -1, + 386, 150, 387, -1, 386, 151, 150, -1, + 580, 393, 151, -1, 580, 151, 579, -1, + 277, 275, 152, -1, 277, 152, 278, -1, + 282, 283, 501, -1, 592, 395, 153, -1, + 592, 153, 321, -1, 154, 423, 155, -1, + 154, 404, 423, -1, 154, 155, 189, -1, + 154, 189, 187, -1, 154, 330, 404, -1, + 154, 187, 330, -1, 328, 288, 156, -1, + 328, 327, 288, -1, 328, 156, 285, -1, + 328, 285, 282, -1, 328, 282, 501, -1, + 499, 600, 601, -1, 499, 166, 600, -1, + 499, 188, 165, -1, 499, 165, 166, -1, + 157, 399, 400, -1, 157, 161, 399, -1, + 157, 400, 158, -1, 157, 158, 161, -1, + 159, 160, 399, -1, 159, 399, 161, -1, + 159, 162, 160, -1, 159, 161, 162, -1, + 169, 172, 222, -1, 169, 222, 220, -1, + 163, 165, 164, -1, 163, 166, 165, -1, + 163, 600, 166, -1, 163, 168, 600, -1, + 163, 171, 172, -1, 163, 164, 171, -1, + 163, 172, 169, -1, 163, 169, 168, -1, + 602, 167, 400, -1, 602, 220, 167, -1, + 602, 600, 168, -1, 602, 169, 220, -1, + 602, 168, 169, -1, 412, 170, 415, -1, + 412, 171, 170, -1, 412, 296, 172, -1, + 412, 172, 171, -1, 407, 401, 408, -1, + 175, 173, 223, -1, 175, 174, 173, -1, + 175, 338, 174, -1, 295, 223, 222, -1, + 295, 222, 296, -1, 295, 175, 223, -1, + 294, 656, 655, -1, 294, 175, 295, -1, + 294, 655, 338, -1, 294, 338, 175, -1, + 414, 294, 413, -1, 414, 656, 294, -1, + 435, 619, 417, -1, 618, 417, 619, -1, + 432, 420, 433, -1, 432, 605, 420, -1, + 447, 360, 438, -1, 447, 359, 360, -1, + 613, 450, 611, -1, 608, 432, 431, -1, + 456, 629, 443, -1, 442, 445, 435, -1, + 425, 648, 451, -1, 425, 451, 450, -1, + 425, 450, 424, -1, 315, 458, 635, -1, + 315, 316, 458, -1, 303, 178, 460, -1, + 303, 304, 176, -1, 303, 176, 177, -1, + 303, 177, 316, -1, 303, 316, 314, -1, + 303, 314, 178, -1, 464, 460, 178, -1, + 464, 478, 479, -1, 464, 178, 478, -1, + 471, 179, 307, -1, 471, 463, 179, -1, + 471, 307, 474, -1, 313, 307, 634, -1, + 630, 634, 479, -1, 248, 231, 240, -1, + 248, 246, 231, -1, 248, 240, 245, -1, + 317, 180, 242, -1, 317, 486, 180, -1, + 317, 242, 304, -1, 490, 493, 483, -1, + 645, 731, 647, -1, 645, 322, 731, -1, + 473, 324, 306, -1, 473, 306, 474, -1, + 181, 182, 186, -1, 181, 183, 182, -1, + 181, 186, 310, -1, 181, 310, 183, -1, + 311, 184, 312, -1, 311, 185, 184, -1, + 311, 186, 185, -1, 311, 310, 186, -1, + 497, 330, 187, -1, 497, 188, 499, -1, + 497, 189, 188, -1, 497, 187, 189, -1, + 498, 501, 283, -1, 498, 283, 329, -1, + 380, 332, 565, -1, 190, 701, 191, -1, + 190, 381, 701, -1, 190, 191, 192, -1, + 190, 192, 193, -1, 190, 193, 381, -1, + 194, 196, 195, -1, 194, 195, 197, -1, + 194, 198, 196, -1, 194, 199, 198, -1, + 194, 197, 200, -1, 194, 200, 199, -1, + 653, 507, 201, -1, 653, 201, 335, -1, + 202, 348, 349, -1, 202, 207, 348, -1, + 202, 349, 203, -1, 202, 203, 204, -1, + 202, 204, 342, -1, 202, 342, 207, -1, + 341, 206, 205, -1, 341, 205, 207, -1, + 341, 340, 206, -1, 341, 207, 342, -1, + 506, 344, 350, -1, 355, 353, 208, -1, + 355, 208, 356, -1, 352, 548, 234, -1, + 352, 209, 353, -1, 352, 253, 209, -1, + 352, 234, 253, -1, 516, 546, 547, -1, + 516, 512, 546, -1, 215, 210, 217, -1, + 215, 211, 212, -1, 215, 214, 211, -1, + 215, 213, 210, -1, 215, 212, 213, -1, + 370, 239, 214, -1, 370, 214, 215, -1, + 370, 215, 217, -1, 371, 216, 255, -1, + 371, 217, 216, -1, 371, 255, 218, -1, + 371, 218, 373, -1, 371, 370, 217, -1, + 219, 221, 220, -1, 219, 220, 222, -1, + 219, 223, 221, -1, 219, 222, 223, -1, + 358, 225, 224, -1, 358, 224, 522, -1, + 358, 297, 225, -1, 358, 359, 297, -1, + 525, 530, 672, -1, 622, 361, 423, -1, + 363, 362, 227, -1, 363, 227, 529, -1, + 625, 626, 523, -1, 226, 229, 227, -1, + 226, 534, 229, -1, 226, 227, 228, -1, + 226, 535, 534, -1, 226, 228, 545, -1, + 226, 515, 535, -1, 226, 545, 514, -1, + 226, 514, 515, -1, 671, 364, 229, -1, + 671, 229, 534, -1, 675, 537, 231, -1, + 675, 231, 230, -1, 675, 230, 676, -1, + 679, 240, 231, -1, 679, 231, 539, -1, + 538, 231, 537, -1, 538, 539, 231, -1, + 236, 232, 233, -1, 236, 233, 235, -1, + 236, 372, 232, -1, 558, 234, 365, -1, + 558, 235, 234, -1, 558, 372, 236, -1, + 558, 236, 235, -1, 550, 366, 689, -1, + 550, 689, 687, -1, 550, 237, 551, -1, + 550, 687, 237, -1, 369, 239, 370, -1, + 555, 554, 238, -1, 555, 238, 239, -1, + 555, 239, 369, -1, 678, 680, 245, -1, + 678, 245, 240, -1, 678, 240, 679, -1, + 241, 243, 242, -1, 241, 244, 243, -1, + 241, 245, 244, -1, 241, 247, 246, -1, + 241, 242, 247, -1, 241, 246, 248, -1, + 241, 248, 245, -1, 541, 661, 684, -1, + 541, 689, 661, -1, 375, 252, 379, -1, + 375, 353, 252, -1, 375, 249, 353, -1, + 375, 376, 249, -1, 250, 251, 379, -1, + 250, 379, 252, -1, 250, 273, 251, -1, + 250, 259, 273, -1, 250, 252, 253, -1, + 250, 253, 258, -1, 250, 258, 259, -1, + 254, 255, 256, -1, 254, 256, 257, -1, + 254, 258, 255, -1, 254, 259, 258, -1, + 254, 257, 273, -1, 254, 273, 259, -1, + 260, 576, 578, -1, 260, 578, 266, -1, + 260, 266, 576, -1, 566, 261, 262, -1, + 566, 564, 261, -1, 566, 262, 562, -1, + 706, 380, 565, -1, 568, 263, 383, -1, + 568, 271, 264, -1, 568, 264, 263, -1, + 745, 570, 766, -1, 745, 563, 346, -1, + 745, 746, 563, -1, 697, 712, 710, -1, + 697, 710, 696, -1, 382, 696, 710, -1, + 382, 569, 696, -1, 382, 710, 769, -1, + 695, 696, 569, -1, 695, 569, 268, -1, + 695, 268, 694, -1, 265, 266, 267, -1, + 265, 267, 268, -1, 265, 570, 745, -1, + 265, 269, 570, -1, 265, 268, 269, -1, + 265, 270, 266, -1, 265, 361, 270, -1, + 265, 745, 346, -1, 265, 345, 361, -1, + 265, 346, 345, -1, 571, 757, 271, -1, + 571, 271, 568, -1, 391, 759, 579, -1, + 385, 388, 390, -1, 573, 577, 272, -1, + 573, 272, 574, -1, 394, 587, 273, -1, + 394, 273, 584, -1, 274, 279, 275, -1, + 274, 277, 279, -1, 274, 275, 277, -1, + 276, 277, 278, -1, 276, 279, 277, -1, + 276, 278, 280, -1, 276, 280, 279, -1, + 281, 329, 283, -1, 281, 283, 284, -1, + 281, 292, 403, -1, 281, 403, 329, -1, + 281, 639, 408, -1, 281, 408, 292, -1, + 594, 637, 639, -1, 594, 639, 281, -1, + 594, 281, 284, -1, 595, 283, 282, -1, + 595, 284, 283, -1, 595, 285, 397, -1, + 595, 282, 285, -1, 595, 594, 284, -1, + 591, 321, 637, -1, 591, 592, 321, -1, + 396, 398, 286, -1, 396, 286, 395, -1, + 597, 327, 601, -1, 597, 288, 327, -1, + 597, 598, 288, -1, 287, 289, 288, -1, + 287, 288, 598, -1, 287, 291, 290, -1, + 287, 290, 289, -1, 287, 399, 291, -1, + 287, 598, 399, -1, 405, 403, 292, -1, + 405, 408, 401, -1, 405, 292, 408, -1, + 405, 401, 422, -1, 642, 426, 407, -1, + 642, 425, 426, -1, 293, 413, 294, -1, + 293, 294, 295, -1, 293, 295, 296, -1, + 293, 296, 412, -1, 293, 412, 413, -1, + 411, 503, 656, -1, 411, 656, 414, -1, + 615, 418, 433, -1, 615, 433, 420, -1, + 615, 622, 423, -1, 430, 419, 299, -1, + 430, 418, 419, -1, 430, 299, 429, -1, + 430, 433, 418, -1, 437, 434, 724, -1, + 437, 724, 723, -1, 444, 724, 434, -1, + 444, 434, 445, -1, 446, 359, 447, -1, + 446, 297, 359, -1, 446, 298, 297, -1, + 446, 722, 298, -1, 725, 436, 723, -1, + 725, 438, 436, -1, 725, 447, 438, -1, + 720, 724, 444, -1, 720, 443, 628, -1, + 720, 444, 443, -1, 449, 299, 419, -1, + 449, 419, 610, -1, 449, 300, 301, -1, + 449, 301, 299, -1, 449, 452, 300, -1, + 457, 607, 608, -1, 457, 608, 431, -1, + 457, 302, 635, -1, 457, 428, 302, -1, + 457, 431, 428, -1, 457, 441, 454, -1, + 457, 456, 441, -1, 318, 303, 460, -1, + 318, 304, 303, -1, 318, 460, 488, -1, + 318, 317, 304, -1, 462, 463, 305, -1, + 462, 493, 494, -1, 462, 305, 483, -1, + 462, 483, 493, -1, 466, 484, 482, -1, + 466, 483, 305, -1, 466, 482, 483, -1, + 466, 305, 463, -1, 466, 463, 471, -1, + 470, 471, 474, -1, 470, 306, 469, -1, + 470, 474, 306, -1, 475, 474, 307, -1, + 475, 307, 313, -1, 475, 312, 308, -1, + 475, 308, 476, -1, 309, 632, 310, -1, + 309, 633, 632, -1, 309, 311, 312, -1, + 309, 310, 311, -1, 309, 312, 475, -1, + 309, 475, 313, -1, 309, 313, 634, -1, + 309, 634, 633, -1, 729, 478, 314, -1, + 729, 315, 635, -1, 729, 314, 316, -1, + 729, 316, 315, -1, 487, 486, 317, -1, + 487, 318, 488, -1, 487, 317, 318, -1, + 481, 320, 319, -1, 481, 319, 491, -1, + 481, 468, 320, -1, 481, 484, 468, -1, + 644, 637, 321, -1, 644, 321, 322, -1, + 644, 322, 645, -1, 477, 476, 323, -1, + 477, 324, 473, -1, 477, 325, 324, -1, + 477, 323, 326, -1, 477, 326, 325, -1, + 500, 601, 327, -1, 500, 499, 601, -1, + 500, 327, 328, -1, 500, 328, 501, -1, + 496, 329, 330, -1, 496, 498, 329, -1, + 496, 330, 497, -1, 331, 332, 380, -1, + 331, 738, 737, -1, 331, 381, 738, -1, + 331, 380, 381, -1, 331, 343, 332, -1, + 331, 737, 343, -1, 649, 333, 340, -1, + 649, 340, 735, -1, 649, 334, 333, -1, + 649, 650, 334, -1, 509, 507, 653, -1, + 652, 653, 335, -1, 652, 337, 336, -1, + 652, 335, 337, -1, 652, 338, 655, -1, + 652, 336, 338, -1, 339, 735, 340, -1, + 339, 340, 341, -1, 339, 341, 342, -1, + 339, 737, 735, -1, 339, 342, 343, -1, + 339, 343, 737, -1, 508, 344, 506, -1, + 508, 504, 503, -1, 508, 503, 345, -1, + 508, 509, 504, -1, 508, 346, 344, -1, + 508, 345, 346, -1, 347, 348, 507, -1, + 347, 507, 506, -1, 347, 349, 348, -1, + 347, 350, 349, -1, 347, 506, 350, -1, + 351, 547, 548, -1, 351, 548, 352, -1, + 351, 516, 547, -1, 351, 355, 516, -1, + 351, 353, 355, -1, 351, 352, 353, -1, + 543, 545, 354, -1, 543, 354, 511, -1, + 658, 661, 366, -1, 663, 516, 355, -1, + 663, 355, 356, -1, 663, 357, 664, -1, + 663, 356, 357, -1, 666, 512, 516, -1, + 670, 669, 668, -1, 670, 668, 361, -1, + 670, 361, 520, -1, 521, 358, 522, -1, + 521, 360, 359, -1, 521, 359, 358, -1, + 624, 438, 360, -1, 624, 360, 521, -1, + 524, 361, 622, -1, 524, 520, 361, -1, + 524, 744, 519, -1, 524, 519, 520, -1, + 527, 625, 523, -1, 527, 523, 362, -1, + 527, 362, 363, -1, 527, 363, 529, -1, + 528, 622, 625, -1, 528, 530, 525, -1, + 528, 525, 622, -1, 673, 364, 671, -1, + 673, 531, 532, -1, 673, 532, 364, -1, + 673, 530, 531, -1, 673, 672, 530, -1, + 740, 671, 534, -1, 540, 538, 537, -1, + 544, 365, 548, -1, 544, 558, 365, -1, + 544, 659, 558, -1, 552, 366, 550, -1, + 552, 658, 366, -1, 552, 367, 658, -1, + 552, 555, 367, -1, 557, 658, 367, -1, + 557, 367, 555, -1, 557, 555, 369, -1, + 557, 372, 558, -1, 368, 369, 370, -1, + 368, 370, 371, -1, 368, 372, 557, -1, + 368, 557, 369, -1, 368, 373, 372, -1, + 368, 371, 373, -1, 374, 376, 375, -1, + 374, 375, 379, -1, 374, 378, 376, -1, + 374, 379, 378, -1, 560, 378, 589, -1, + 560, 377, 378, -1, 560, 561, 377, -1, + 588, 589, 378, -1, 588, 379, 587, -1, + 588, 378, 379, -1, 567, 380, 706, -1, + 567, 700, 381, -1, 567, 381, 380, -1, + 751, 769, 710, -1, 768, 569, 382, -1, + 768, 382, 769, -1, 704, 568, 383, -1, + 704, 384, 703, -1, 704, 383, 384, -1, + 392, 385, 390, -1, 392, 386, 387, -1, + 392, 387, 388, -1, 392, 388, 385, -1, + 392, 579, 386, -1, 392, 391, 579, -1, + 389, 390, 759, -1, 389, 759, 391, -1, + 389, 392, 390, -1, 389, 391, 392, -1, + 575, 693, 578, -1, 575, 713, 693, -1, + 575, 574, 713, -1, 582, 583, 393, -1, + 582, 393, 580, -1, 586, 394, 584, -1, + 586, 587, 394, -1, 593, 395, 592, -1, + 593, 396, 395, -1, 593, 595, 397, -1, + 593, 397, 398, -1, 593, 398, 396, -1, + 599, 399, 598, -1, 599, 400, 399, -1, + 599, 602, 400, -1, 406, 423, 404, -1, + 406, 422, 423, -1, 406, 405, 422, -1, + 421, 401, 407, -1, 421, 422, 401, -1, + 421, 407, 426, -1, 402, 404, 403, -1, + 402, 403, 405, -1, 402, 406, 404, -1, + 402, 405, 406, -1, 638, 407, 408, -1, + 638, 642, 407, -1, 638, 408, 639, -1, + 641, 648, 425, -1, 641, 425, 642, -1, + 409, 410, 503, -1, 409, 503, 411, -1, + 409, 413, 412, -1, 409, 414, 413, -1, + 409, 411, 414, -1, 409, 415, 410, -1, + 409, 412, 415, -1, 606, 605, 432, -1, + 606, 432, 608, -1, 416, 604, 454, -1, + 416, 454, 441, -1, 416, 441, 442, -1, + 416, 435, 417, -1, 416, 442, 435, -1, + 416, 417, 618, -1, 416, 618, 604, -1, + 612, 419, 418, -1, 612, 418, 615, -1, + 612, 610, 419, -1, 621, 420, 605, -1, + 621, 615, 420, -1, 621, 605, 617, -1, + 621, 622, 615, -1, 614, 422, 421, -1, + 614, 423, 422, -1, 614, 615, 423, -1, + 614, 424, 450, -1, 614, 450, 613, -1, + 614, 425, 424, -1, 614, 426, 425, -1, + 614, 421, 426, -1, 427, 429, 428, -1, + 427, 430, 429, -1, 427, 428, 431, -1, + 427, 431, 432, -1, 427, 432, 433, -1, + 427, 433, 430, -1, 439, 445, 434, -1, + 439, 434, 437, -1, 439, 435, 445, -1, + 439, 619, 435, -1, 623, 723, 436, -1, + 623, 437, 723, -1, 623, 436, 438, -1, + 623, 438, 624, -1, 623, 619, 439, -1, + 623, 439, 437, -1, 623, 621, 619, -1, + 440, 441, 456, -1, 440, 442, 441, -1, + 440, 456, 443, -1, 440, 443, 444, -1, + 440, 445, 442, -1, 440, 444, 445, -1, + 721, 446, 447, -1, 721, 447, 725, -1, + 721, 722, 446, -1, 448, 610, 611, -1, + 448, 449, 610, -1, 448, 450, 451, -1, + 448, 611, 450, -1, 448, 452, 449, -1, + 448, 451, 648, -1, 448, 648, 452, -1, + 453, 604, 607, -1, 453, 607, 457, -1, + 453, 454, 604, -1, 453, 457, 454, -1, + 455, 629, 456, -1, 455, 456, 457, -1, + 455, 457, 635, -1, 455, 458, 629, -1, + 455, 635, 458, -1, 459, 460, 464, -1, + 459, 464, 462, -1, 459, 494, 460, -1, + 459, 462, 494, -1, 461, 463, 462, -1, + 461, 462, 464, -1, 461, 479, 463, -1, + 461, 464, 479, -1, 465, 484, 466, -1, + 465, 467, 468, -1, 465, 468, 484, -1, + 465, 469, 467, -1, 465, 470, 469, -1, + 465, 466, 471, -1, 465, 471, 470, -1, + 472, 473, 474, -1, 472, 474, 475, -1, + 472, 475, 476, -1, 472, 476, 477, -1, + 472, 477, 473, -1, 728, 478, 729, -1, + 728, 479, 478, -1, 728, 630, 479, -1, + 480, 491, 490, -1, 480, 481, 491, -1, + 480, 483, 482, -1, 480, 490, 483, -1, + 480, 482, 484, -1, 480, 484, 481, -1, + 485, 491, 486, -1, 485, 492, 491, -1, + 485, 487, 488, -1, 485, 486, 487, -1, + 485, 488, 494, -1, 485, 494, 492, -1, + 489, 490, 491, -1, 489, 491, 492, -1, + 489, 493, 490, -1, 489, 494, 493, -1, + 489, 492, 494, -1, 643, 637, 644, -1, + 643, 642, 638, -1, 495, 496, 497, -1, + 495, 498, 496, -1, 495, 497, 499, -1, + 495, 499, 500, -1, 495, 501, 498, -1, + 495, 500, 501, -1, 736, 738, 502, -1, + 736, 502, 650, -1, 654, 503, 504, -1, + 654, 504, 509, -1, 654, 656, 503, -1, + 654, 509, 653, -1, 505, 506, 507, -1, + 505, 508, 506, -1, 505, 507, 509, -1, + 505, 509, 508, -1, 660, 659, 543, -1, + 660, 510, 661, -1, 660, 511, 510, -1, + 660, 543, 511, -1, 518, 513, 512, -1, + 518, 512, 666, -1, 518, 515, 514, -1, + 518, 514, 513, -1, 518, 536, 515, -1, + 665, 516, 663, -1, 665, 666, 516, -1, + 517, 536, 518, -1, 517, 519, 536, -1, + 517, 520, 519, -1, 517, 667, 670, -1, + 517, 670, 520, -1, 517, 666, 667, -1, + 517, 518, 666, -1, 627, 521, 522, -1, + 627, 523, 626, -1, 627, 522, 523, -1, + 627, 624, 521, -1, 743, 744, 524, -1, + 743, 524, 622, -1, 743, 622, 525, -1, + 743, 525, 672, -1, 526, 625, 527, -1, + 526, 528, 625, -1, 526, 527, 529, -1, + 526, 531, 530, -1, 526, 530, 528, -1, + 526, 532, 531, -1, 526, 529, 532, -1, + 533, 534, 535, -1, 533, 740, 534, -1, + 533, 535, 536, -1, 533, 536, 741, -1, + 533, 741, 740, -1, 686, 540, 537, -1, + 686, 537, 675, -1, 682, 539, 538, -1, + 682, 538, 540, -1, 682, 679, 539, -1, + 688, 682, 540, -1, 688, 540, 686, -1, + 688, 541, 684, -1, 688, 689, 541, -1, + 542, 543, 659, -1, 542, 659, 544, -1, + 542, 545, 543, -1, 542, 546, 545, -1, + 542, 547, 546, -1, 542, 548, 547, -1, + 542, 544, 548, -1, 549, 550, 551, -1, + 549, 552, 550, -1, 549, 553, 554, -1, + 549, 551, 553, -1, 549, 554, 555, -1, + 549, 555, 552, -1, 556, 659, 658, -1, + 556, 658, 557, -1, 556, 558, 659, -1, + 556, 557, 558, -1, 559, 714, 713, -1, + 559, 713, 574, -1, 559, 589, 714, -1, + 559, 560, 589, -1, 559, 574, 561, -1, + 559, 561, 560, -1, 692, 693, 713, -1, + 692, 713, 716, -1, 747, 566, 562, -1, + 747, 748, 566, -1, 747, 562, 563, -1, + 747, 563, 746, -1, 698, 565, 564, -1, + 698, 706, 565, -1, 698, 564, 566, -1, + 698, 566, 748, -1, 763, 706, 698, -1, + 707, 700, 567, -1, 707, 567, 706, -1, + 711, 705, 751, -1, 711, 704, 705, -1, + 711, 568, 704, -1, 711, 712, 571, -1, + 711, 571, 568, -1, 767, 569, 768, -1, + 767, 570, 569, -1, 767, 766, 570, -1, + 756, 691, 716, -1, 756, 571, 712, -1, + 756, 757, 571, -1, 756, 712, 697, -1, + 756, 697, 691, -1, 572, 573, 574, -1, + 572, 574, 575, -1, 572, 576, 577, -1, + 572, 577, 573, -1, 572, 578, 576, -1, + 572, 575, 578, -1, 753, 754, 582, -1, + 753, 579, 759, -1, 753, 580, 579, -1, + 753, 582, 580, -1, 752, 715, 754, -1, + 581, 582, 754, -1, 581, 754, 586, -1, + 581, 583, 582, -1, 581, 584, 583, -1, + 581, 586, 584, -1, 585, 587, 586, -1, + 585, 588, 587, -1, 585, 589, 588, -1, + 585, 714, 589, -1, 585, 715, 714, -1, + 585, 754, 715, -1, 585, 586, 754, -1, + 590, 592, 591, -1, 590, 593, 592, -1, + 590, 637, 594, -1, 590, 591, 637, -1, + 590, 594, 595, -1, 590, 595, 593, -1, + 596, 598, 597, -1, 596, 599, 598, -1, + 596, 601, 600, -1, 596, 597, 601, -1, + 596, 600, 602, -1, 596, 602, 599, -1, + 603, 618, 617, -1, 603, 604, 618, -1, + 603, 617, 605, -1, 603, 605, 606, -1, + 603, 607, 604, -1, 603, 608, 607, -1, + 603, 606, 608, -1, 609, 611, 610, -1, + 609, 610, 612, -1, 609, 613, 611, -1, + 609, 614, 613, -1, 609, 612, 615, -1, + 609, 615, 614, -1, 616, 617, 618, -1, + 616, 621, 617, -1, 616, 618, 619, -1, + 616, 619, 621, -1, 620, 622, 621, -1, + 620, 623, 624, -1, 620, 621, 623, -1, + 620, 626, 625, -1, 620, 625, 622, -1, + 620, 627, 626, -1, 620, 624, 627, -1, + 719, 720, 628, -1, 719, 628, 629, -1, + 719, 629, 722, -1, 727, 630, 728, -1, + 727, 731, 631, -1, 727, 631, 632, -1, + 727, 632, 633, -1, 727, 633, 634, -1, + 727, 634, 630, -1, 730, 635, 732, -1, + 730, 729, 635, -1, 636, 637, 643, -1, + 636, 643, 638, -1, 636, 639, 637, -1, + 636, 638, 639, -1, 640, 641, 642, -1, + 640, 642, 643, -1, 640, 644, 645, -1, + 640, 643, 644, -1, 640, 647, 646, -1, + 640, 645, 647, -1, 640, 646, 648, -1, + 640, 648, 641, -1, 734, 649, 735, -1, + 734, 650, 649, -1, 734, 736, 650, -1, + 651, 653, 652, -1, 651, 654, 653, -1, + 651, 652, 655, -1, 651, 655, 656, -1, + 651, 656, 654, -1, 657, 658, 659, -1, + 657, 659, 660, -1, 657, 661, 658, -1, + 657, 660, 661, -1, 662, 663, 664, -1, + 662, 665, 663, -1, 662, 667, 666, -1, + 662, 666, 665, -1, 662, 664, 668, -1, + 662, 668, 669, -1, 662, 669, 670, -1, + 662, 670, 667, -1, 742, 671, 740, -1, + 742, 743, 672, -1, 742, 672, 673, -1, + 742, 673, 671, -1, 674, 675, 676, -1, + 674, 686, 675, -1, 674, 676, 687, -1, + 674, 687, 686, -1, 677, 678, 679, -1, + 677, 679, 682, -1, 677, 682, 683, -1, + 677, 683, 680, -1, 677, 680, 678, -1, + 681, 683, 682, -1, 681, 682, 688, -1, + 681, 684, 683, -1, 681, 688, 684, -1, + 685, 686, 687, -1, 685, 688, 686, -1, + 685, 687, 689, -1, 685, 689, 688, -1, + 690, 716, 691, -1, 690, 692, 716, -1, + 690, 694, 693, -1, 690, 693, 692, -1, + 690, 695, 694, -1, 690, 696, 695, -1, + 690, 697, 696, -1, 690, 691, 697, -1, + 762, 698, 748, -1, 762, 763, 698, -1, + 699, 700, 707, -1, 699, 701, 700, -1, + 699, 702, 701, -1, 699, 703, 702, -1, + 699, 707, 703, -1, 708, 703, 707, -1, + 708, 704, 703, -1, 708, 705, 704, -1, + 708, 750, 751, -1, 708, 751, 705, -1, + 749, 706, 763, -1, 749, 707, 706, -1, + 749, 750, 708, -1, 749, 708, 707, -1, + 709, 751, 710, -1, 709, 711, 751, -1, + 709, 710, 712, -1, 709, 712, 711, -1, + 717, 716, 713, -1, 717, 713, 714, -1, + 717, 714, 715, -1, 717, 715, 752, -1, + 758, 756, 716, -1, 758, 716, 717, -1, + 758, 717, 752, -1, 718, 720, 719, -1, + 718, 722, 721, -1, 718, 719, 722, -1, + 718, 723, 724, -1, 718, 724, 720, -1, + 718, 725, 723, -1, 718, 721, 725, -1, + 726, 727, 728, -1, 726, 728, 729, -1, + 726, 729, 730, -1, 726, 731, 727, -1, + 726, 732, 731, -1, 726, 730, 732, -1, + 733, 734, 735, -1, 733, 736, 734, -1, + 733, 735, 737, -1, 733, 737, 738, -1, + 733, 738, 736, -1, 739, 740, 741, -1, + 739, 742, 740, -1, 739, 743, 742, -1, + 739, 741, 744, -1, 739, 744, 743, -1, + 765, 745, 766, -1, 765, 746, 745, -1, + 765, 747, 746, -1, 765, 748, 747, -1, + 765, 762, 748, -1, 764, 750, 749, -1, + 764, 749, 763, -1, 764, 751, 750, -1, + 764, 769, 751, -1, 760, 758, 752, -1, + 760, 754, 753, -1, 760, 752, 754, -1, + 760, 753, 759, -1, 755, 757, 756, -1, + 755, 756, 758, -1, 755, 759, 757, -1, + 755, 760, 759, -1, 755, 758, 760, -1, + 761, 763, 762, -1, 761, 764, 763, -1, + 761, 765, 766, -1, 761, 762, 765, -1, + 761, 766, 767, -1, 761, 767, 768, -1, + 761, 768, 769, -1, 761, 769, 764, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ1_pan.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ1_pan.wrl new file mode 100644 index 0000000..9ef7edc --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ1_pan.wrl @@ -0,0 +1,1884 @@ +#VRML V2.0 utf8 + + +DEF solid_T2R3_TJ1_pan______________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ 35.6469 -96.519997 36.193001, + 29.495001 102.408 41.360401, + 29.495001 106.98 41.360401, + -3.3633399 114.22 -21.2353, + 29.708099 114.22 -46.512199, + 25.6506 114.22 -54.768799, + -42.298698 -106.98 28.132999, + -40.137901 -106.98 31.1383, + 3.3633399 114.22 21.2353, + -28.043301 114.22 -49.942501, + -30.1805 114.22 -45.528198, + 81.045097 32.983898 -58.799999, + 49.062199 -114.22 13.1735, + -35.068401 114.22 -37.117901, + -35.091801 109.652 -65.701302, + -25.4 113.477 -67.190804, + -25.4 113.795 -66.737503, + -25.4 113.086 -67.582199, + -15.2108 42.351299 -68.824997, + -5.5423899 -106.98 50.496799, + -7.8705802 -96.519997 50.1866, + -2.6329601 -96.519997 50.731701, + -2.6576099 -114.22 50.7304, + -2.6329601 96.519997 50.731701, + 36.855499 -114.22 -34.9673, + 35.091801 -109.652 -65.701302, + 36.030102 -107.657 -66.737503, + 36.2327 -107.774 -66.235901, + 50.18 -114.22 -7.9124699, + 49.078602 -114.22 -13.1123, + 81.045097 -32.983898 -65.150002, + 50.732101 -114.22 -2.6259999, + 81.045097 -32.983898 -58.799999, + 50.170101 -114.22 7.9750099, + 50.728802 -114.22 2.68923, + 73.208702 -43.9944 -68.133499, + 34.589298 -106.825 -68.133499, + -1.85074 -106.98 50.7663, + 2.6576099 114.22 50.7304, + 5.5423899 106.98 50.496799, + 1.85074 106.98 50.7663, + -1.85074 106.98 50.7663, + 47.417198 -114.22 18.2278, + 87.047798 6.7424102 -57.7141, + 87.308502 1.3711035e-009 -57.7141, + 47.417198 114.22 18.2278, + 35.189602 -106.98 36.637901, + 31.7087 -96.519997 39.688801, + 31.7087 96.519997 39.688801, + 29.495001 -106.98 41.360401, + 29.495001 -103.332 41.360401, + -25.4 114.172 -65.701302, + 25.4 114.029 -66.235901, + 25.4 113.795 -66.737503, + 14 113.22 -68.186401, + -25.4 114.029 -66.235901, + 25.4 114.172 -65.701302, + 50.18 114.22 -7.9124699, + 3.4351599 45.839001 -68.824997, + 50.728802 114.22 2.68923, + 83.350304 26.6266 -58.799999, + -27.5721 113.838 -66.235901, + -27.597 113.98 -65.701302, + -45.281799 114.22 -23.025999, + -27.605301 114.027 -65.150002, + -25.4 114.22 -65.150002, + -47.439899 114.22 -18.1686, + -14 112.98 -68.324997, + 14 112.98 -68.324997, + -14 113.22 -68.186401, + -14.3204 113.21 -68.186401, + -22.9837 39.808998 -68.824997, + -28.660299 35.938801 -68.824997, + -33.696602 31.2658 -68.824997, + -16.7938 42.789902 -68.824997, + -78.212799 39.122501 -65.701302, + -74.958 45.0457 -65.701302, + -49.078602 114.22 -13.1123, + -50.18 114.22 -7.9124699, + -50.732101 114.22 -2.6259999, + -73.208702 43.9944 -68.133499, + -45.015099 -96.519997 23.5431, + -44.234901 -106.98 24.9783, + -49.062199 114.22 13.1735, + -86.408699 13.4666 -58.248699, + -86.267197 13.4445 -57.7141, + -50.170101 114.22 7.9750099, + -12.818 106.98 49.1563, + -9.2046099 106.98 49.959099, + -35.6469 -96.519997 36.193001, + -35.6469 96.519997 36.193001, + -35.189602 -106.98 36.637901, + 45.281799 -114.22 -23.025999, + 27.605301 -114.027 -65.150002, + 47.439899 -114.22 -18.1686, + 34.982101 -109.56 -66.235901, + 35.023701 -107.076 -67.899597, + 84.396698 -22.854 -58.799999, + 83.350304 -26.6266 -58.799999, + 83.304398 -26.612 -58.248699, + 85.1576 -20.110399 -58.799999, + 85.1576 -20.110399 -65.150002, + 85.110703 -20.0993 -58.248699, + 75.9095 -37.970299 -68.276802, + 72.750504 -43.719101 -68.276802, + 76.387604 -38.209499 -68.133499, + 34.1264 -106.558 -68.276802, + 33.648899 -106.283 -68.324997, + -87.238701 -6.7571902 -65.150002, + -86.456398 -13.474 -65.150002, + -85.1576 -20.110399 -65.150002, + 2.6329601 -96.519997 50.731701, + 1.85074 -103.332 50.7663, + 1.85074 -106.98 50.7663, + 2.6576099 -114.22 50.7304, + 2.6329601 96.519997 50.731701, + 1.85074 -98.760101 50.7663, + 7.8705802 -96.519997 50.1866, + 5.5423899 -106.98 50.496799, + 7.8705802 96.519997 50.1866, + 22.856001 -96.519997 45.367901, + 19.821699 -106.98 46.7733, + 23.1749 -106.98 45.205799, + 23.0543 -114.22 45.267399, + 27.429701 96.519997 42.757999, + 27.6579 114.22 42.610802, + 27.6579 -114.22 42.610802, + 23.1749 106.98 45.205799, + 23.1749 98.760101 45.205799, + 23.0543 114.22 45.267399, + 26.405001 106.98 43.3983, + 35.909801 -114.22 35.932201, + 86.408699 -13.4666 -58.248699, + 86.267197 -13.4445 -57.7141, + 87.047798 -6.7424102 -57.7141, + 31.958799 -114.22 39.487598, + 31.958799 114.22 39.487598, + -83.350304 26.6266 -58.799999, + -81.045097 32.983898 -65.150002, + -83.350304 26.6266 -65.150002, + -81.045097 32.983898 -58.799999, + -50.728802 114.22 2.68923, + -83.304398 26.612 -58.248699, + -84.396698 22.854 -65.150002, + 5.1607499 44.703098 -68.824997, + 25.4 113.477 -67.190804, + 86.456398 -13.474 -65.150002, + 86.408699 -13.4666 -65.701302, + 86.267197 -13.4445 -66.235901, + 87.190598 -6.7534699 -65.701302, + 87.238701 6.7571902 -65.150002, + 87.238701 6.7571902 -58.799999, + 87.5 -2.7626421e-009 -65.150002, + 50.170101 114.22 7.9750099, + 83.304398 26.612 -58.248699, + 85.1576 20.110399 -58.799999, + 84.396698 22.854 -65.150002, + 84.396698 22.854 -58.799999, + 85.1576 20.110399 -65.150002, + -27.5315 113.608 -66.737503, + -36.2327 107.774 -66.235901, + -43.925301 13.5492 -68.824997, + -30.158199 -114.22 -45.586102, + 32.273701 -114.22 -41.501202, + -19.156601 -114.22 9.7608004, + 25.4125 -114.22 -55.2169, + -37.980099 25.8944 -68.824997, + -78.614998 31.994801 -68.276802, + -76.387604 38.209499 -68.133499, + -28.6577 110.471 -68.324997, + -80.357101 32.7038 -67.190804, + -78.084702 39.058399 -66.235901, + -81.000504 32.965698 -65.701302, + -87.190598 -6.7534699 -65.701302, + -86.408699 -13.4666 -65.701302, + -77.875504 38.9538 -66.737503, + -74.835197 44.971901 -66.235901, + -36.030102 107.657 -66.737503, + -79.574699 32.385399 -67.899597, + -76.836098 38.433899 -67.899597, + -79.110199 32.1964 -68.133499, + -79.994698 32.556301 -67.582199, + -40.137901 -98.760101 31.1383, + -40.137901 103.332 31.1383, + -37.764 -106.98 33.978298, + -39.467701 -114.22 31.9834, + -39.467701 114.22 31.9834, + -44.234901 103.332 24.9783, + -44.234901 98.760101 24.9783, + -44.234901 -98.760101 24.9783, + -85.1576 20.110399 -58.799999, + -85.1576 20.110399 -65.150002, + -85.110703 20.0993 -58.248699, + -84.396698 22.854 -58.799999, + -86.456398 13.474 -58.799999, + -87.190598 6.7534699 -58.248699, + -87.5 -4.2564867e-009 -58.799999, + -86.4981 -6.6998301 -67.190804, + -85.110703 20.0993 -65.701302, + -86.757202 -1.1931841e-009 -67.190804, + -83.1679 26.568399 -66.235901, + -82.945099 26.4972 -66.737503, + -84.971298 20.066401 -66.235901, + -83.304398 26.612 -65.701302, + -80.867798 32.911701 -66.235901, + -80.651199 32.823502 -66.737503, + -87.238701 -6.7571902 -58.799999, + -87.047798 -6.7424102 -57.7141, + -87.451797 -3.5373715e-009 -58.248699, + -13.1429 114.22 49.0704, + -13.0236 96.519997 49.1022, + -13.1429 -114.22 49.0704, + -9.2046099 -106.98 49.959099, + -9.2046099 103.332 49.959099, + -7.9437399 -114.22 50.175098, + -7.9437399 114.22 50.175098, + -27.6579 114.22 42.610802, + -26.405001 106.98 43.3983, + -27.429701 96.519997 42.757999, + -26.405001 -102.408 43.3983, + -26.405001 -106.98 43.3983, + -23.1749 -106.98 45.205799, + -27.429701 -96.519997 42.757999, + -23.1749 98.760101 45.205799, + -23.0543 114.22 45.267399, + -23.1749 106.98 45.205799, + -23.1749 -102.408 45.205799, + -26.405001 102.408 43.3983, + -26.405001 -98.760101 43.3983, + 44.234901 106.98 24.9783, + 45.253101 114.22 23.0825, + 44.234901 98.760101 24.9783, + 40.137901 106.98 31.1383, + 40.137901 -106.98 31.1383, + 40.137901 -98.760101 31.1383, + 42.298698 -106.98 28.132999, + 35.189602 98.760101 36.637901, + 32.428398 106.98 39.102901, + 35.189602 106.98 36.637901, + 35.6469 96.519997 36.193001, + 34.259998 -108.954 -67.582199, + 78.212799 -39.122501 -65.701302, + 74.835197 -44.971901 -66.235901, + 74.958 -45.0457 -65.701302, + 83.350304 -26.6266 -65.150002, + 84.396698 -22.854 -65.150002, + 85.110703 -20.0993 -65.701302, + 84.971298 -20.066401 -66.235901, + 82.945099 -26.4972 -66.737503, + 81.838097 -26.1436 -67.899597, + 79.574699 -32.385399 -67.899597, + 83.346603 -12.75 -68.324997, + 83.319199 -12.9851 -68.324997, + 85.410896 3.5523064e-011 -68.133499, + 84.622902 -6.5545802 -68.276802, + 84.876297 1.4146992e-009 -68.276802, + 32.696602 -107.643 -68.324997, + 75.416397 -37.723701 -68.324997, + 72.277901 -43.435101 -68.324997, + 22.9837 -39.808998 -68.824997, + 28.660299 -35.938801 -68.824997, + 33.1189 -107.997 -68.276802, + 31.5226 -108.817 -68.324997, + 33.912701 -108.663 -67.899597, + 33.5284 -108.341 -68.133499, + 29.7272 -113.409 -65.701302, + 31.725901 -112.477 -65.701302, + 33.532398 -111.212 -65.701302, + 33.4403 -111.102 -66.235901, + 86.814598 -6.72435 -66.737503, + 87.047798 -6.7424102 -66.235901, + 86.757202 1.6246533e-009 -67.190804, + 87.0746 -1.4562577e-009 -66.737503, + 81.360298 -25.9909 -68.133499, + 79.110199 -32.1964 -68.133499, + 78.614998 -31.994801 -68.276802, + 78.104401 -31.787001 -68.324997, + 84.392197 -13.1523 -68.133499, + 83.612602 -19.745501 -67.899597, + 86.4981 -6.6998301 -67.190804, + -87.047798 -6.7424102 -66.235901, + -86.814598 -6.72435 -66.737503, + -87.0746 -2.9380329e-009 -66.737503, + -87.238701 6.7571902 -58.799999, + -87.5 4.0775032e-009 -65.150002, + -84.396698 -22.854 -58.799999, + -85.1576 -20.110399 -58.799999, + -84.396698 -22.854 -65.150002, + -45.253101 -114.22 23.0825, + -36.857101 -114.22 -34.966801, + 7.9437399 114.22 50.175098, + 9.2046099 -98.760101 49.959099, + 9.2046099 98.760101 49.959099, + 7.9437399 -114.22 50.175098, + 18.1982 -114.22 47.428501, + 19.821699 103.332 46.7733, + 19.821699 106.98 46.7733, + 19.821699 102.408 46.7733, + 22.856001 96.519997 45.367901, + 9.2046099 106.98 49.959099, + 9.2046099 102.408 49.959099, + 12.818 -103.332 49.1563, + 12.818 -106.98 49.1563, + 9.2046099 -102.408 49.959099, + 9.2046099 -106.98 49.959099, + 26.405001 -103.332 43.3983, + 23.1749 -103.332 45.205799, + 26.405001 -106.98 43.3983, + 26.405001 103.332 43.3983, + 27.429701 -96.519997 42.757999, + 39.467701 -114.22 31.9834, + 37.764 -106.98 33.978298, + 87.238701 -6.7571902 -58.799999, + 86.456398 -13.474 -58.799999, + 87.238701 -6.7571902 -65.150002, + 87.190598 -6.7534699 -58.248699, + 87.5 3.0996199e-009 -58.799999, + 87.451797 8.4070439e-010 -58.248699, + 32.428398 -103.332 39.102901, + 32.428398 -106.98 39.102901, + 35.189602 -98.760101 36.637901, + 32.428398 -98.760101 39.102901, + 35.091801 109.652 -65.701302, + 84.073196 -6.5120001 -68.324997, + 74.958 45.0457 -65.701302, + 36.2327 107.774 -66.235901, + 74.835197 44.971901 -66.235901, + 36.030102 107.657 -66.737503, + 25.4 113.086 -67.582199, + 14.3204 113.21 -68.186401, + 27.054001 110.9 -68.324997, + 10.2287 44.814999 -68.824997, + 86.408699 13.4666 -65.701302, + 86.456398 13.474 -65.150002, + 85.110703 20.0993 -65.701302, + 87.047798 6.7424102 -66.235901, + 87.190598 6.7534699 -65.701302, + 86.814598 6.72435 -66.737503, + 87.308502 -2.1225861e-009 -66.235901, + 87.451797 1.0141553e-009 -65.701302, + 86.408699 13.4666 -58.248699, + 86.267197 13.4445 -57.7141, + 49.062199 114.22 13.1735, + 85.110703 20.0993 -58.248699, + 86.456398 13.474 -58.799999, + 87.190598 6.7534699 -58.248699, + -29.0291 111.491 -68.133499, + -29.200701 111.962 -67.899597, + -27.3297 112.464 -67.899597, + -27.4084 112.91 -67.582199, + -30.9562 111.144 -67.899597, + -34.982101 109.56 -66.235901, + -34.5597 109.206 -67.190804, + -34.802898 109.41 -66.737503, + -33.085899 110.68 -67.190804, + -32.8344 110.38 -67.582199, + -34.259998 108.954 -67.582199, + -82.067596 -19.380699 -68.324997, + -85.655899 -6.6346002 -67.899597, + -86.107903 -6.66961 -67.582199, + -84.392197 13.1523 -68.133499, + -81.360298 25.9909 -68.133499, + -82.604202 19.507401 -68.276802, + -82.067596 19.380699 -68.324997, + -80.851097 25.828199 -68.276802, + -80.325897 25.6605 -68.324997, + -45.281799 -114.22 -23.025999, + -39.507599 -114.22 -31.9342, + -25.4 -114.22 -58.799999, + -42.627998 -114.22 -27.631399, + 25.4 -114.22 -65.150002, + -27.605301 -114.027 -65.150002, + -75.416397 37.723701 -68.324997, + -78.104401 31.787001 -68.324997, + -72.277901 43.435101 -68.324997, + -75.9095 37.970299 -68.276802, + -72.750504 43.719101 -68.276802, + -30.4382 110.246 -68.276802, + -30.1625 109.769 -68.324997, + -28.8463 110.989 -68.276802, + -34.589298 106.825 -68.133499, + -35.023701 107.076 -67.899597, + -33.912701 108.663 -67.899597, + -33.1189 107.997 -68.276802, + -31.5226 108.817 -68.324997, + -32.696602 107.643 -68.324997, + -33.648899 106.283 -68.324997, + -34.1264 106.558 -68.276802, + -32.2206 109.648 -68.133499, + -30.7055 110.709 -68.133499, + -32.542999 110.033 -67.899597, + -31.8769 109.239 -68.276802, + -33.5284 108.341 -68.133499, + -14.9099 112.892 -68.324997, + -27.054001 110.9 -68.324997, + -10.2287 44.814999 -68.824997, + -14.305 112.97 -68.324997, + -3.4351599 45.839001 -68.824997, + -27.1497 111.443 -68.276802, + -27.242599 111.97 -68.133499, + -82.6427 26.4006 -67.190804, + -84.743698 20.0126 -66.737503, + -85.110703 -20.0993 -65.701302, + -83.304398 -26.612 -65.701302, + -35.416302 107.303 -67.582199, + -73.638603 44.2528 -67.899597, + -77.2416 38.6367 -67.582199, + -40.137901 106.98 31.1383, + -37.764 103.332 33.978298, + -39.202099 96.519997 32.308399, + -37.764 106.98 33.978298, + -37.764 -98.760101 33.978298, + -35.909801 -114.22 35.932201, + -39.202099 -96.519997 32.308399, + -35.909801 114.22 35.932201, + -45.253101 114.22 23.0825, + -44.234901 106.98 24.9783, + -45.015099 96.519997 23.5431, + -47.417198 114.22 18.2278, + -87.0746 4.3491353e-009 -57.212502, + -87.308502 -4.2623736e-009 -57.7141, + -87.047798 6.7424102 -57.7141, + -85.655899 6.6346002 -67.899597, + -85.155899 6.59586 -68.133499, + -85.912498 2.6906386e-009 -67.899597, + -86.365898 3.2934189e-009 -67.582199, + -85.155899 -6.59586 -68.133499, + -86.408699 -13.4666 -58.248699, + -87.190598 -6.7534699 -58.248699, + -86.456398 -13.474 -58.799999, + -86.267197 -13.4445 -57.7141, + -16.3633 103.332 48.092499, + -18.1982 114.22 47.428501, + -16.3633 106.98 48.092499, + -12.818 -103.332 49.1563, + -9.2046099 -102.408 49.959099, + -12.818 -106.98 49.1563, + -12.818 -98.760101 49.1563, + -13.0236 -96.519997 49.1022, + -5.5423899 103.332 50.496799, + -5.5423899 -103.332 50.496799, + -2.6576099 114.22 50.7304, + -5.5423899 106.98 50.496799, + -7.8705802 96.519997 50.1866, + -27.6579 -114.22 42.610802, + -29.495001 106.98 41.360401, + -32.428398 -102.408 39.102901, + -32.428398 -106.98 39.102901, + -35.189602 -102.408 36.637901, + -32.428398 106.98 39.102901, + -32.428398 102.408 39.102901, + -31.958799 114.22 39.487598, + -35.189602 106.98 36.637901, + -19.821699 106.98 46.7733, + -22.856001 -96.519997 45.367901, + -19.821699 -106.98 46.7733, + -23.0543 -114.22 45.267399, + -22.856001 96.519997 45.367901, + -19.821699 -103.332 46.7733, + 87.0746 3.618881e-009 -57.212502, + 45.015099 96.519997 23.5431, + 44.234901 -106.98 24.9783, + 44.234901 -102.408 24.9783, + 45.253101 -114.22 23.0825, + 45.015099 -96.519997 23.5431, + 42.336102 96.519997 28.076599, + 42.298698 106.98 28.132999, + 42.298698 -98.760101 28.132999, + 42.336102 -96.519997 28.076599, + 42.593498 114.22 27.6845, + 42.593498 -114.22 27.6845, + 33.290001 -110.923 -66.737503, + 34.5597 -109.206 -67.190804, + 34.802898 -109.41 -66.737503, + 80.867798 -32.911701 -66.235901, + 78.084702 -39.058399 -66.235901, + 81.000504 -32.965698 -65.701302, + 83.1679 -26.568399 -66.235901, + 83.304398 -26.612 -65.701302, + 76.836098 -38.433899 -67.899597, + 84.4347 -19.939699 -67.190804, + 82.6427 -26.4006 -67.190804, + 84.743698 -20.0126 -66.737503, + 82.269897 -26.2815 -67.582199, + 84.053802 -19.849701 -67.582199, + 85.335701 -13.2994 -67.582199, + 85.722397 -13.3596 -67.190804, + 86.036102 -13.4085 -66.737503, + 10.2287 -44.814999 -68.824997, + 45.967499 4.0639714e-009 -68.824997, + 84.324997 -2.0705417e-009 -68.324997, + 43.925301 -13.5492 -68.824997, + 31.654301 -112.353 -66.235901, + 31.378599 -111.875 -67.190804, + 31.5373 -112.15 -66.737503, + 33.085899 -110.68 -67.190804, + 82.604202 -19.507401 -68.276802, + 83.124496 -19.630199 -68.133499, + 83.863998 -13.07 -68.276802, + 80.851097 -25.828199 -68.276802, + 82.067596 -19.380699 -68.324997, + 80.325897 -25.6605 -68.324997, + 85.655899 -6.6346002 -67.899597, + 84.887802 -13.2296 -67.899597, + 85.155899 -6.59586 -68.133499, + 86.107903 -6.66961 -67.582199, + 85.912498 -2.7335758e-009 -67.899597, + 86.365898 -1.3250614e-009 -67.582199, + -86.408699 13.4666 -65.701302, + -86.456398 13.474 -65.150002, + -87.238701 6.7571902 -65.150002, + -81.045097 -32.983898 -65.150002, + -83.350304 -26.6266 -65.150002, + -50.18 -114.22 -7.9124699, + -49.078602 -114.22 -13.1123, + -81.045097 -32.983898 -58.799999, + -83.350304 -26.6266 -58.799999, + 13.0236 96.519997 49.1022, + 12.818 106.98 49.1563, + 13.1429 114.22 49.0704, + 13.0236 -96.519997 49.1022, + 12.818 102.408 49.1563, + 12.818 -98.760101 49.1563, + 18.036699 96.519997 47.4902, + 18.1982 114.22 47.428501, + 16.3633 106.98 48.092499, + 16.3633 98.760101 48.092499, + 35.909801 114.22 35.932201, + 34.982101 109.56 -66.235901, + 45.281799 114.22 -23.025999, + 27.605301 114.027 -65.150002, + 25.4 114.22 -65.150002, + 47.439899 114.22 -18.1686, + 49.078602 114.22 -13.1123, + 27.5721 113.838 -66.235901, + 27.597 113.98 -65.701302, + 27.5315 113.608 -66.737503, + 29.200701 111.962 -67.899597, + 27.4084 112.91 -67.582199, + 34.5597 109.206 -67.190804, + 34.802898 109.41 -66.737503, + 35.755199 107.499 -67.190804, + 34.259998 108.954 -67.582199, + 27.242599 111.97 -68.133499, + 27.3297 112.464 -67.899597, + 27.1497 111.443 -68.276802, + 14.9099 112.892 -68.324997, + 14.305 112.97 -68.324997, + 84.622902 6.5545802 -68.276802, + 83.346603 12.75 -68.324997, + 84.073196 6.5120001 -68.324997, + 85.155899 6.59586 -68.133499, + 85.655899 6.6346002 -67.899597, + 84.971298 20.066401 -66.235901, + 86.267197 13.4445 -66.235901, + 81.000504 32.965698 -65.701302, + 78.212799 39.122501 -65.701302, + 50.732101 114.22 -2.6259999, + 81.045097 32.983898 -65.150002, + 83.304398 26.612 -65.701302, + 83.350304 26.6266 -65.150002, + -29.489599 112.756 -67.190804, + -27.476299 113.296 -67.190804, + -29.355801 112.388 -67.582199, + -31.378599 111.875 -67.190804, + -31.182899 111.536 -67.582199, + -31.654301 112.353 -66.235901, + -31.725901 112.477 -65.701302, + -33.532398 111.212 -65.701302, + -33.4403 111.102 -66.235901, + -31.5373 112.15 -66.737503, + -33.290001 110.923 -66.737503, + -29.7272 113.409 -65.701302, + -29.6782 113.274 -66.235901, + -29.5982 113.054 -66.737503, + -83.346603 -12.75 -68.324997, + -83.319199 -12.9851 -68.324997, + -83.346603 12.75 -68.324997, + -83.319199 12.9851 -68.324997, + -83.863998 13.07 -68.276802, + -27.242599 -111.97 -68.133499, + -27.3297 -112.464 -67.899597, + -85.722397 13.3596 -67.190804, + -86.107903 6.66961 -67.582199, + -86.4981 6.6998301 -67.190804, + -83.124496 19.630199 -68.133499, + -85.722397 -13.3596 -67.190804, + -85.335701 -13.2994 -67.582199, + -74.362602 44.687901 -67.190804, + -74.634697 44.851398 -66.737503, + -77.591599 38.811798 -67.190804, + -74.027199 44.486301 -67.582199, + -35.755199 107.499 -67.190804, + -42.336102 96.519997 28.076599, + -42.298698 106.98 28.132999, + -42.593498 114.22 27.6845, + -42.336102 -96.519997 28.076599, + -42.593498 -114.22 27.6845, + -42.298698 102.408 28.132999, + -42.298698 -102.408 28.132999, + -85.410896 -2.2836231e-009 -68.133499, + -18.036699 -96.519997 47.4902, + -16.3633 -106.98 48.092499, + -16.3633 -102.408 48.092499, + -18.036699 96.519997 47.4902, + -18.1982 -114.22 47.428501, + -31.7087 -96.519997 39.688801, + -29.495001 -106.98 41.360401, + -31.958799 -114.22 39.487598, + -31.7087 96.519997 39.688801, + -29.495001 -103.332 41.360401, + -29.495001 98.760101 41.360401, + 77.875504 -38.9538 -66.737503, + 74.634697 -44.851398 -66.737503, + 80.651199 -32.823502 -66.737503, + 80.357101 -32.7038 -67.190804, + 79.994698 -32.556301 -67.582199, + 74.027199 -44.486301 -67.582199, + 77.2416 -38.6367 -67.582199, + 73.638603 -44.2528 -67.899597, + 35.416302 -107.303 -67.582199, + 77.591599 -38.811798 -67.190804, + 74.362602 -44.687901 -67.190804, + 35.755199 -107.499 -67.190804, + -27.054001 -110.9 -68.324997, + -10.2287 -44.814999 -68.824997, + -27.1497 -111.443 -68.276802, + 3.4351599 -45.839001 -68.824997, + -14 -112.98 -68.324997, + -3.4351599 -45.839001 -68.824997, + -14.6087 -112.941 -68.324997, + 14 -112.98 -68.324997, + -14 -113.22 -68.186401, + 34.716999 -28.630899 -68.824997, + 33.696602 -31.2658 -68.824997, + 24.460501 -37.7714 -68.824997, + 38.680599 -22.9958 -68.824997, + 45.454102 -6.8511 -68.824997, + 37.980099 -25.8944 -68.824997, + 41.415298 -19.9445 -68.824997, + 16.7938 -42.789902 -68.824997, + 31.182899 -111.536 -67.582199, + 32.8344 -110.38 -67.582199, + 30.1625 -109.769 -68.324997, + 27.1497 -111.443 -68.276802, + 28.6577 -110.471 -68.324997, + 27.054001 -110.9 -68.324997, + 27.597 -113.98 -65.701302, + 25.4 -113.086 -67.582199, + -87.047798 6.7424102 -66.235901, + -87.190598 6.7534699 -65.701302, + -86.267197 13.4445 -66.235901, + -86.814598 6.72435 -66.737503, + -86.036102 13.4085 -66.737503, + -87.308502 -1.6984117e-010 -66.235901, + -87.451797 1.1744705e-009 -65.701302, + -50.170101 -114.22 7.9750099, + -83.304398 -26.612 -58.248699, + -85.110703 -20.0993 -58.248699, + -50.728802 -114.22 2.68923, + -49.062199 -114.22 13.1735, + -47.417198 -114.22 18.2278, + -50.732101 -114.22 -2.6259999, + 16.3633 -103.332 48.092499, + 18.036699 -96.519997 47.4902, + 16.3633 -106.98 48.092499, + 16.3633 -98.760101 48.092499, + 13.1429 -114.22 49.0704, + 39.202099 96.519997 32.308399, + 37.764 102.408 33.978298, + 37.764 106.98 33.978298, + 39.467701 114.22 31.9834, + 39.202099 -96.519997 32.308399, + 37.764 -102.408 33.978298, + 33.085899 110.68 -67.190804, + 31.654301 112.353 -66.235901, + 33.4403 111.102 -66.235901, + 33.290001 110.923 -66.737503, + 33.532398 111.212 -65.701302, + 31.725901 112.477 -65.701302, + 29.7272 113.409 -65.701302, + 29.6782 113.274 -66.235901, + 73.208702 43.9944 -68.133499, + 28.6577 110.471 -68.324997, + 22.9837 39.808998 -68.824997, + 16.7938 42.789902 -68.824997, + 28.660299 35.938801 -68.824997, + 72.277901 43.435101 -68.324997, + 72.750504 43.719101 -68.276802, + 35.416302 107.303 -67.582199, + 83.319199 12.9851 -68.324997, + 45.454102 6.8511 -68.824997, + 84.392197 13.1523 -68.133499, + 83.863998 13.07 -68.276802, + 84.887802 13.2296 -67.899597, + 86.107903 6.66961 -67.582199, + -72.750504 -43.719101 -68.276802, + -84.324997 6.5378297e-010 -68.324997, + -84.073196 -6.5120001 -68.324997, + -84.073196 6.5120001 -68.324997, + -84.622902 -6.5545802 -68.276802, + -84.876297 -9.2973096e-010 -68.276802, + -84.622902 6.5545802 -68.276802, + -44.472599 6.8692198 -68.824997, + -45.454102 6.8511 -68.824997, + -29.7272 -113.409 -65.701302, + -31.725901 -112.477 -65.701302, + -35.091801 -109.652 -65.701302, + -47.439899 -114.22 -18.1686, + 25.4 -114.172 -65.701302, + -25.4 -113.282 -67.386497, + -25.4 -113.477 -67.190804, + -14.6394 -113.179 -68.186401, + -25.4 -113.086 -67.582199, + -27.4084 -112.91 -67.582199, + -84.053802 19.849701 -67.582199, + -85.335701 13.2994 -67.582199, + -84.4347 19.939699 -67.190804, + -82.269897 26.2815 -67.582199, + -84.887802 13.2296 -67.899597, + -83.612602 19.745501 -67.899597, + -81.838097 26.1436 -67.899597, + -84.971298 -20.066401 -66.235901, + -86.036102 -13.4085 -66.737503, + -86.267197 -13.4445 -66.235901, + -28.6577 -110.471 -68.324997, + -22.9837 -39.808998 -68.824997, + -30.4382 -110.246 -68.276802, + -28.8463 -110.989 -68.276802, + -41.415298 19.9445 -68.824997, + 11.9242 -43.391399 -68.824997, + 27.242599 -111.97 -68.133499, + 14.6087 -112.941 -68.324997, + 14.6394 -113.179 -68.186401, + -80.325897 -25.6605 -68.324997, + -76.387604 -38.209499 -68.133499, + -84.4347 -19.939699 -67.190804, + 29.6782 -113.274 -66.235901, + 27.5721 -113.838 -66.235901, + -78.084702 -39.058399 -66.235901, + -80.867798 -32.911701 -66.235901, + -77.875504 -38.9538 -66.737503, + -78.212799 -39.122501 -65.701302, + -81.000504 -32.965698 -65.701302, + -74.958 -45.0457 -65.701302, + 29.489599 112.756 -67.190804, + 31.5373 112.15 -66.737503, + 29.5982 113.054 -66.737503, + 31.378599 111.875 -67.190804, + 27.476299 113.296 -67.190804, + 29.355801 112.388 -67.582199, + 31.182899 111.536 -67.582199, + 73.638603 44.2528 -67.899597, + 77.2416 38.6367 -67.582199, + 74.634697 44.851398 -66.737503, + 74.362602 44.687901 -67.190804, + 74.027199 44.486301 -67.582199, + 75.416397 37.723701 -68.324997, + 41.415298 19.9445 -68.824997, + 32.696602 107.643 -68.324997, + 37.980099 25.8944 -68.824997, + 33.696602 31.2658 -68.824997, + 33.648899 106.283 -68.324997, + 86.4981 6.6998301 -67.190804, + 84.743698 20.0126 -66.737503, + 85.335701 13.2994 -67.582199, + 85.722397 13.3596 -67.190804, + 86.036102 13.4085 -66.737503, + 82.945099 26.4972 -66.737503, + 77.875504 38.9538 -66.737503, + 80.867798 32.911701 -66.235901, + 83.1679 26.568399 -66.235901, + 78.084702 39.058399 -66.235901, + 84.4347 19.939699 -67.190804, + -34.1264 -106.558 -68.276802, + -73.208702 -43.9944 -68.133499, + -27.476299 -113.296 -67.190804, + -25.4 -113.795 -66.737503, + -32.2206 -109.648 -68.133499, + -30.7055 -110.709 -68.133499, + -29.0291 -111.491 -68.133499, + -29.200701 -111.962 -67.899597, + -74.835197 -44.971901 -66.235901, + -25.4 -114.177 -65.646301, + -25.4 -114.22 -65.150002, + -25.4 -114.172 -65.701302, + 25.4 -114.177 -65.646301, + -82.945099 -26.4972 -66.737503, + -84.743698 -20.0126 -66.737503, + -83.1679 -26.568399 -66.235901, + -80.651199 -32.823502 -66.737503, + -30.1625 -109.769 -68.324997, + -31.8769 -109.239 -68.276802, + -33.1189 -107.997 -68.276802, + -16.7938 -42.789902 -68.824997, + -45.967499 4.4617274e-009 -68.824997, + -45.454102 -6.8511 -68.824997, + -33.648899 -106.283 -68.324997, + 30.7055 -110.709 -68.133499, + 30.4382 -110.246 -68.276802, + 28.8463 -110.989 -68.276802, + 32.542999 -110.033 -67.899597, + 32.2206 -109.648 -68.133499, + 31.8769 -109.239 -68.276802, + 29.200701 -111.962 -67.899597, + 30.9562 -111.144 -67.899597, + 29.0291 -111.491 -68.133499, + 27.3297 -112.464 -67.899597, + -78.614998 -31.994801 -68.276802, + -75.9095 -37.970299 -68.276802, + -82.604202 -19.507401 -68.276802, + -83.863998 -13.07 -68.276802, + -84.392197 -13.1523 -68.133499, + -84.887802 -13.2296 -67.899597, + -80.357101 -32.7038 -67.190804, + -82.6427 -26.4006 -67.190804, + -77.2416 -38.6367 -67.582199, + -77.591599 -38.811798 -67.190804, + -82.269897 -26.2815 -67.582199, + -83.612602 -19.745501 -67.899597, + -84.053802 -19.849701 -67.582199, + 29.5982 -113.054 -66.737503, + 29.489599 -112.756 -67.190804, + 29.355801 -112.388 -67.582199, + 27.4084 -112.91 -67.582199, + 25.4 -113.282 -67.386497, + 25.4 -113.795 -66.737503, + 27.5315 -113.608 -66.737503, + 25.4 -114.029 -66.235901, + 14 -113.22 -68.186401, + 27.476299 -113.296 -67.190804, + 25.4 -113.477 -67.190804, + 35.023701 107.076 -67.899597, + 34.589298 106.825 -68.133499, + 34.1264 106.558 -68.276802, + 33.912701 108.663 -67.899597, + 32.8344 110.38 -67.582199, + 29.0291 111.491 -68.133499, + 30.9562 111.144 -67.899597, + 32.542999 110.033 -67.899597, + 28.8463 110.989 -68.276802, + 31.8769 109.239 -68.276802, + 33.1189 107.997 -68.276802, + 31.5226 108.817 -68.324997, + 33.5284 108.341 -68.133499, + 32.2206 109.648 -68.133499, + 30.7055 110.709 -68.133499, + 30.4382 110.246 -68.276802, + 30.1625 109.769 -68.324997, + 80.357101 32.7038 -67.190804, + 82.6427 26.4006 -67.190804, + 80.651199 32.823502 -66.737503, + 77.591599 38.811798 -67.190804, + 79.994698 32.556301 -67.582199, + 82.269897 26.2815 -67.582199, + 84.053802 19.849701 -67.582199, + 83.612602 19.745501 -67.899597, + -27.5721 -113.838 -66.235901, + -25.4 -114.029 -66.235901, + -27.597 -113.98 -65.701302, + -27.5315 -113.608 -66.737503, + -29.6782 -113.274 -66.235901, + -33.532398 -111.212 -65.701302, + -31.5373 -112.15 -66.737503, + -31.654301 -112.353 -66.235901, + -29.5982 -113.054 -66.737503, + -33.290001 -110.923 -66.737503, + -33.4403 -111.102 -66.235901, + -34.982101 -109.56 -66.235901, + -36.2327 -107.774 -66.235901, + -74.362602 -44.687901 -67.190804, + -74.634697 -44.851398 -66.737503, + -36.030102 -107.657 -66.737503, + -34.802898 -109.41 -66.737503, + -31.182899 -111.536 -67.582199, + -30.9562 -111.144 -67.899597, + -29.355801 -112.388 -67.582199, + -31.378599 -111.875 -67.190804, + -33.085899 -110.68 -67.190804, + -29.489599 -112.756 -67.190804, + -34.589298 -106.825 -68.133499, + -36.806801 -25.889299 -68.824997, + -45 -1.0902854e-009 -68.824997, + -33.696602 -31.2658 -68.824997, + -32.4235 -31.2045 -68.824997, + -28.660299 -35.938801 -68.824997, + -32.696602 -107.643 -68.324997, + -31.5226 -108.817 -68.324997, + -79.574699 -32.385399 -67.899597, + -79.994698 -32.556301 -67.582199, + -76.836098 -38.433899 -67.899597, + -81.360298 -25.9909 -68.133499, + -83.124496 -19.630199 -68.133499, + -80.851097 -25.828199 -68.276802, + -81.838097 -26.1436 -67.899597, + -79.110199 -32.1964 -68.133499, + 82.067596 19.380699 -68.324997, + 43.925301 13.5492 -68.824997, + 81.838097 26.1436 -67.899597, + 79.574699 32.385399 -67.899597, + 76.836098 38.433899 -67.899597, + 76.387604 38.209499 -68.133499, + 75.9095 37.970299 -68.276802, + 80.851097 25.828199 -68.276802, + 80.325897 25.6605 -68.324997, + 82.604202 19.507401 -68.276802, + 83.124496 19.630199 -68.133499, + 81.360298 25.9909 -68.133499, + 79.110199 32.1964 -68.133499, + 78.614998 31.994801 -68.276802, + 78.104401 31.787001 -68.324997, + -34.5597 -109.206 -67.190804, + -35.755199 -107.499 -67.190804, + -74.027199 -44.486301 -67.582199, + -73.638603 -44.2528 -67.899597, + -33.912701 -108.663 -67.899597, + -35.023701 -107.076 -67.899597, + -33.5284 -108.341 -68.133499, + -32.542999 -110.033 -67.899597, + -35.416302 -107.303 -67.582199, + -34.259998 -108.954 -67.582199, + -32.8344 -110.38 -67.582199, + -41.415298 -19.9445 -68.824997, + -40.3274 -19.9674 -68.824997, + -37.980099 -25.8944 -68.824997, + -42.902802 -13.5774 -68.824997, + -43.925301 -13.5492 -68.824997, + -78.104401 -31.787001 -68.324997, + -75.416397 -37.723701 -68.324997, + -72.277901 -43.435101 -68.324997 ] + + } + coordIndex [ 214, 164, 131, -1, 176, 77, 160, -1, + 444, 214, 605, -1, 102, 12, 33, -1, + 22, 114, 37, -1, 0, 131, 239, -1, + 0, 46, 131, -1, 2, 48, 136, -1, + 2, 136, 125, -1, 126, 307, 123, -1, + 5, 531, 10, -1, 42, 131, 33, -1, + 42, 33, 12, -1, 599, 7, 182, -1, + 288, 597, 82, -1, 288, 214, 444, -1, + 211, 605, 214, -1, 8, 59, 5, -1, + 8, 5, 3, -1, 26, 27, 473, -1, + 31, 33, 29, -1, 109, 286, 429, -1, + 658, 429, 286, -1, 116, 41, 37, -1, + 293, 114, 22, -1, 667, 214, 131, -1, + 667, 22, 214, -1, 667, 293, 22, -1, + 320, 0, 239, -1, 320, 46, 0, -1, + 1, 48, 2, -1, 309, 307, 126, -1, + 50, 126, 49, -1, 50, 1, 2, -1, + 50, 2, 125, -1, 50, 125, 126, -1, + 50, 48, 1, -1, 141, 209, 8, -1, + 141, 8, 3, -1, 141, 3, 5, -1, + 141, 5, 10, -1, 4, 59, 531, -1, + 4, 5, 59, -1, 4, 531, 5, -1, + 144, 397, 58, -1, 144, 685, 686, -1, + 533, 531, 59, -1, 133, 42, 12, -1, + 348, 346, 347, -1, 387, 80, 380, -1, + 76, 77, 176, -1, 78, 79, 141, -1, + 185, 7, 597, -1, 185, 597, 288, -1, + 185, 182, 7, -1, 185, 444, 412, -1, + 185, 288, 444, -1, 6, 7, 599, -1, + 6, 597, 7, -1, 6, 599, 596, -1, + 6, 596, 597, -1, 420, 421, 208, -1, + 420, 288, 419, -1, 414, 90, 452, -1, + 414, 412, 90, -1, 19, 214, 22, -1, + 603, 211, 209, -1, 210, 87, 209, -1, + 210, 209, 211, -1, 40, 41, 116, -1, + 23, 41, 441, -1, 671, 59, 8, -1, + 671, 45, 59, -1, 671, 209, 136, -1, + 671, 8, 209, -1, 93, 370, 647, -1, + 163, 131, 164, -1, 95, 473, 27, -1, + 623, 26, 473, -1, 623, 613, 26, -1, + 28, 31, 29, -1, 98, 30, 244, -1, + 104, 107, 258, -1, 104, 106, 107, -1, + 36, 619, 96, -1, 113, 37, 114, -1, + 118, 39, 114, -1, 118, 114, 293, -1, + 290, 136, 209, -1, 290, 209, 441, -1, + 292, 290, 293, -1, 294, 131, 123, -1, + 294, 667, 131, -1, 520, 302, 667, -1, + 298, 123, 129, -1, 298, 129, 296, -1, + 128, 129, 123, -1, 342, 59, 45, -1, + 44, 459, 463, -1, 44, 230, 459, -1, + 135, 131, 46, -1, 135, 49, 126, -1, + 135, 136, 48, -1, 135, 123, 131, -1, + 135, 126, 123, -1, 142, 192, 86, -1, + 142, 86, 141, -1, 140, 141, 79, -1, + 64, 65, 62, -1, 13, 141, 10, -1, + 13, 10, 65, -1, 9, 10, 531, -1, + 9, 531, 65, -1, 9, 65, 10, -1, + 55, 61, 62, -1, 55, 69, 16, -1, + 53, 329, 54, -1, 684, 686, 685, -1, + 331, 685, 144, -1, 331, 144, 58, -1, + 325, 533, 326, -1, 11, 59, 60, -1, + 11, 557, 59, -1, 11, 558, 557, -1, + 560, 558, 11, -1, 560, 11, 60, -1, + 132, 12, 102, -1, 132, 133, 12, -1, + 399, 379, 346, -1, 399, 348, 396, -1, + 399, 346, 348, -1, 66, 567, 568, -1, + 66, 568, 14, -1, 66, 572, 567, -1, + 66, 160, 77, -1, 66, 62, 572, -1, + 66, 64, 62, -1, 66, 77, 78, -1, + 66, 13, 65, -1, 66, 78, 141, -1, + 66, 141, 13, -1, 351, 14, 568, -1, + 351, 160, 66, -1, 351, 66, 14, -1, + 70, 396, 348, -1, 70, 16, 69, -1, + 159, 16, 562, -1, 159, 55, 16, -1, + 159, 61, 55, -1, 15, 562, 16, -1, + 15, 17, 562, -1, 15, 16, 70, -1, + 15, 70, 17, -1, 349, 562, 17, -1, + 349, 17, 70, -1, 349, 70, 348, -1, + 68, 58, 397, -1, 68, 547, 58, -1, + 68, 69, 54, -1, 68, 54, 329, -1, + 68, 329, 547, -1, 395, 397, 144, -1, + 395, 144, 74, -1, 18, 144, 729, -1, + 18, 74, 144, -1, 73, 18, 729, -1, + 73, 74, 18, -1, 171, 76, 176, -1, + 184, 185, 412, -1, 187, 416, 417, -1, + 187, 417, 188, -1, 195, 421, 85, -1, + 195, 85, 84, -1, 195, 208, 421, -1, + 191, 198, 509, -1, 203, 139, 172, -1, + 206, 208, 196, -1, 206, 196, 108, -1, + 206, 109, 429, -1, 206, 108, 109, -1, + 81, 419, 288, -1, 81, 417, 419, -1, + 81, 288, 82, -1, 81, 188, 417, -1, + 432, 453, 605, -1, 216, 218, 217, -1, + 216, 444, 218, -1, 216, 209, 414, -1, + 418, 141, 86, -1, 418, 209, 141, -1, + 418, 414, 209, -1, 418, 85, 421, -1, + 88, 209, 87, -1, 88, 87, 213, -1, + 20, 443, 214, -1, 20, 214, 19, -1, + 440, 22, 441, -1, 440, 19, 22, -1, + 440, 443, 20, -1, 440, 20, 19, -1, + 602, 605, 211, -1, 602, 211, 603, -1, + 115, 40, 116, -1, 21, 441, 22, -1, + 21, 23, 441, -1, 21, 22, 37, -1, + 21, 37, 41, -1, 21, 41, 23, -1, + 608, 412, 444, -1, 608, 91, 412, -1, + 469, 230, 45, -1, 469, 45, 671, -1, + 469, 671, 232, -1, 527, 671, 136, -1, + 527, 239, 131, -1, 94, 265, 266, -1, + 94, 647, 265, -1, 94, 25, 95, -1, + 94, 93, 647, -1, 94, 27, 29, -1, + 94, 95, 27, -1, 165, 368, 370, -1, + 165, 370, 163, -1, 24, 33, 131, -1, + 24, 131, 163, -1, 24, 29, 33, -1, + 24, 94, 29, -1, 24, 163, 370, -1, + 24, 370, 94, -1, 786, 647, 370, -1, + 786, 709, 647, -1, 267, 95, 25, -1, + 267, 94, 266, -1, 267, 25, 94, -1, + 472, 623, 473, -1, 242, 26, 613, -1, + 242, 27, 26, -1, 242, 29, 27, -1, + 242, 243, 29, -1, 241, 31, 28, -1, + 241, 28, 29, -1, 241, 29, 243, -1, + 476, 244, 30, -1, 476, 30, 31, -1, + 476, 31, 241, -1, 246, 146, 101, -1, + 246, 247, 148, -1, 32, 31, 30, -1, + 32, 30, 98, -1, 34, 33, 31, -1, + 34, 31, 32, -1, 34, 32, 98, -1, + 99, 102, 33, -1, 99, 33, 34, -1, + 99, 34, 98, -1, 245, 98, 244, -1, + 245, 246, 101, -1, 260, 262, 643, -1, + 637, 500, 491, -1, 264, 96, 263, -1, + 264, 36, 96, -1, 264, 106, 36, -1, + 35, 619, 36, -1, 35, 105, 619, -1, + 35, 104, 105, -1, 35, 106, 104, -1, + 35, 36, 106, -1, 737, 265, 647, -1, + 147, 146, 246, -1, 147, 246, 148, -1, + 270, 148, 487, -1, 277, 498, 504, -1, + 173, 174, 109, -1, 173, 109, 108, -1, + 284, 108, 196, -1, 110, 286, 109, -1, + 112, 116, 37, -1, 112, 37, 113, -1, + 119, 290, 39, -1, 119, 293, 290, -1, + 119, 39, 118, -1, 38, 39, 290, -1, + 38, 40, 115, -1, 38, 290, 441, -1, + 38, 114, 39, -1, 38, 115, 114, -1, + 38, 441, 41, -1, 38, 41, 40, -1, + 304, 667, 302, -1, 304, 293, 667, -1, + 121, 294, 123, -1, 122, 123, 307, -1, + 130, 125, 129, -1, 341, 342, 45, -1, + 310, 311, 131, -1, 310, 470, 233, -1, + 310, 463, 470, -1, 310, 131, 42, -1, + 310, 42, 463, -1, 134, 42, 133, -1, + 134, 463, 42, -1, 134, 44, 463, -1, + 317, 316, 151, -1, 317, 151, 345, -1, + 317, 44, 134, -1, 43, 230, 44, -1, + 43, 45, 230, -1, 43, 317, 345, -1, + 43, 44, 317, -1, 43, 345, 341, -1, + 43, 341, 45, -1, 319, 135, 46, -1, + 319, 46, 320, -1, 47, 135, 48, -1, + 47, 49, 135, -1, 47, 48, 50, -1, + 47, 50, 49, -1, 138, 172, 139, -1, + 138, 79, 172, -1, 138, 140, 79, -1, + 51, 62, 65, -1, 51, 55, 62, -1, + 51, 65, 531, -1, 530, 535, 531, -1, + 145, 329, 53, -1, 145, 53, 749, -1, + 536, 749, 53, -1, 56, 51, 531, -1, + 56, 55, 51, -1, 56, 531, 535, -1, + 52, 53, 54, -1, 52, 54, 69, -1, + 52, 69, 55, -1, 52, 55, 56, -1, + 52, 536, 53, -1, 52, 534, 536, -1, + 52, 535, 534, -1, 52, 56, 535, -1, + 324, 326, 533, -1, 324, 533, 556, -1, + 57, 556, 533, -1, 57, 557, 556, -1, + 57, 533, 59, -1, 57, 59, 557, -1, + 546, 58, 547, -1, 546, 331, 58, -1, + 330, 546, 545, -1, 330, 331, 546, -1, + 344, 151, 333, -1, 344, 345, 151, -1, + 344, 333, 155, -1, 152, 316, 314, -1, + 154, 60, 59, -1, 153, 59, 342, -1, + 153, 154, 59, -1, 157, 560, 60, -1, + 157, 60, 154, -1, 158, 157, 155, -1, + 158, 333, 334, -1, 158, 155, 333, -1, + 398, 379, 399, -1, 573, 61, 159, -1, + 573, 62, 61, -1, 573, 572, 62, -1, + 63, 65, 64, -1, 63, 66, 65, -1, + 63, 64, 66, -1, 389, 346, 379, -1, + 67, 397, 396, -1, 67, 68, 397, -1, + 67, 69, 68, -1, 67, 70, 69, -1, + 67, 396, 70, -1, 161, 373, 729, -1, + 161, 365, 373, -1, 744, 782, 514, -1, + 744, 514, 742, -1, 289, 164, 214, -1, + 289, 214, 288, -1, 289, 367, 368, -1, + 168, 180, 179, -1, 361, 721, 180, -1, + 166, 385, 73, -1, 166, 386, 385, -1, + 166, 73, 729, -1, 376, 387, 386, -1, + 376, 80, 387, -1, 376, 168, 80, -1, + 71, 72, 378, -1, 71, 378, 74, -1, + 71, 73, 72, -1, 71, 74, 73, -1, + 384, 378, 72, -1, 384, 72, 73, -1, + 384, 73, 385, -1, 169, 395, 74, -1, + 169, 74, 378, -1, 169, 378, 379, -1, + 169, 379, 398, -1, 177, 176, 160, -1, + 205, 590, 170, -1, 175, 171, 176, -1, + 175, 590, 205, -1, 175, 205, 171, -1, + 75, 77, 76, -1, 75, 76, 171, -1, + 75, 78, 77, -1, 75, 79, 78, -1, + 75, 171, 172, -1, 75, 172, 79, -1, + 723, 197, 586, -1, 587, 586, 197, -1, + 405, 80, 168, -1, 405, 168, 179, -1, + 405, 380, 80, -1, 405, 381, 380, -1, + 406, 405, 179, -1, 181, 406, 179, -1, + 181, 721, 718, -1, 181, 170, 590, -1, + 181, 590, 406, -1, 186, 410, 414, -1, + 186, 409, 410, -1, 186, 407, 183, -1, + 186, 182, 185, -1, 186, 183, 182, -1, + 194, 84, 192, -1, 194, 195, 84, -1, + 508, 509, 198, -1, 193, 192, 142, -1, + 143, 139, 203, -1, 143, 191, 193, -1, + 143, 198, 191, -1, 143, 203, 198, -1, + 423, 360, 579, -1, 423, 579, 702, -1, + 202, 198, 203, -1, 207, 661, 288, -1, + 207, 420, 208, -1, 207, 288, 420, -1, + 189, 188, 81, -1, 189, 81, 82, -1, + 189, 82, 597, -1, 433, 209, 432, -1, + 224, 217, 225, -1, 224, 216, 217, -1, + 224, 453, 432, -1, 224, 432, 209, -1, + 224, 209, 216, -1, 83, 84, 85, -1, + 83, 85, 418, -1, 83, 418, 86, -1, + 83, 86, 192, -1, 83, 192, 84, -1, + 437, 213, 87, -1, 437, 87, 210, -1, + 212, 436, 211, -1, 212, 211, 214, -1, + 215, 214, 443, -1, 215, 441, 209, -1, + 215, 209, 88, -1, 215, 213, 214, -1, + 215, 88, 213, -1, 448, 452, 90, -1, + 89, 90, 412, -1, 89, 412, 91, -1, + 89, 448, 90, -1, 89, 91, 448, -1, + 607, 608, 444, -1, 447, 91, 608, -1, + 447, 448, 91, -1, 451, 445, 216, -1, + 451, 216, 414, -1, 451, 414, 452, -1, + 456, 444, 605, -1, 456, 220, 444, -1, + 456, 221, 220, -1, 238, 136, 237, -1, + 238, 527, 136, -1, 238, 239, 527, -1, + 92, 370, 93, -1, 92, 94, 370, -1, + 92, 93, 94, -1, 828, 647, 709, -1, + 268, 473, 95, -1, 268, 95, 267, -1, + 620, 623, 472, -1, 620, 263, 96, -1, + 620, 96, 619, -1, 612, 242, 613, -1, + 482, 148, 247, -1, 482, 487, 148, -1, + 477, 614, 248, -1, 477, 482, 247, -1, + 477, 248, 482, -1, 313, 146, 314, -1, + 313, 101, 146, -1, 313, 100, 101, -1, + 313, 132, 102, -1, 313, 102, 100, -1, + 97, 98, 245, -1, 97, 99, 98, -1, + 97, 101, 100, -1, 97, 245, 101, -1, + 97, 102, 99, -1, 97, 100, 102, -1, + 257, 104, 258, -1, 501, 491, 500, -1, + 501, 276, 491, -1, 252, 498, 500, -1, + 252, 500, 637, -1, 255, 548, 253, -1, + 549, 691, 690, -1, 638, 258, 107, -1, + 638, 107, 256, -1, 646, 732, 488, -1, + 926, 357, 796, -1, 103, 105, 104, -1, + 103, 104, 257, -1, 103, 275, 274, -1, + 103, 274, 105, -1, 103, 276, 275, -1, + 103, 257, 276, -1, 479, 250, 616, -1, + 479, 274, 250, -1, 479, 105, 274, -1, + 479, 619, 105, -1, 261, 106, 264, -1, + 261, 107, 106, -1, 261, 256, 107, -1, + 261, 262, 256, -1, 551, 253, 548, -1, + 506, 504, 253, -1, 506, 552, 507, -1, + 506, 253, 551, -1, 506, 551, 552, -1, + 695, 763, 507, -1, 695, 507, 552, -1, + 497, 498, 277, -1, 655, 173, 108, -1, + 655, 108, 284, -1, 655, 280, 173, -1, + 287, 286, 110, -1, 402, 109, 174, -1, + 402, 110, 109, -1, 402, 287, 110, -1, + 515, 516, 512, -1, 111, 112, 113, -1, + 111, 113, 114, -1, 111, 114, 115, -1, + 111, 115, 116, -1, 111, 116, 112, -1, + 117, 118, 293, -1, 117, 293, 119, -1, + 117, 119, 118, -1, 303, 293, 304, -1, + 297, 121, 298, -1, 120, 123, 298, -1, + 120, 121, 123, -1, 120, 298, 121, -1, + 524, 294, 121, -1, 524, 121, 297, -1, + 524, 296, 129, -1, 524, 136, 290, -1, + 524, 125, 136, -1, 524, 129, 125, -1, + 519, 667, 526, -1, 519, 524, 290, -1, + 519, 290, 299, -1, 665, 667, 294, -1, + 522, 521, 292, -1, 306, 122, 307, -1, + 306, 128, 123, -1, 306, 123, 122, -1, + 308, 128, 306, -1, 124, 125, 130, -1, + 124, 126, 125, -1, 124, 309, 126, -1, + 124, 308, 309, -1, 124, 130, 308, -1, + 127, 129, 128, -1, 127, 130, 129, -1, + 127, 128, 308, -1, 127, 308, 130, -1, + 673, 527, 131, -1, 673, 131, 311, -1, + 315, 133, 132, -1, 315, 134, 133, -1, + 315, 132, 313, -1, 315, 317, 134, -1, + 321, 320, 237, -1, 321, 135, 319, -1, + 321, 237, 136, -1, 321, 136, 135, -1, + 137, 138, 139, -1, 137, 140, 138, -1, + 137, 141, 140, -1, 137, 193, 142, -1, + 137, 142, 141, -1, 137, 139, 143, -1, + 137, 143, 193, -1, 897, 729, 144, -1, + 897, 144, 686, -1, 328, 329, 145, -1, + 328, 145, 749, -1, 327, 325, 326, -1, + 544, 547, 329, -1, 149, 314, 146, -1, + 149, 146, 147, -1, 149, 147, 148, -1, + 149, 148, 270, -1, 339, 270, 338, -1, + 339, 149, 270, -1, 339, 152, 314, -1, + 339, 314, 149, -1, 337, 763, 767, -1, + 337, 338, 272, -1, 150, 151, 316, -1, + 150, 316, 152, -1, 150, 333, 151, -1, + 150, 336, 333, -1, 150, 152, 339, -1, + 150, 339, 336, -1, 343, 154, 153, -1, + 343, 155, 157, -1, 343, 157, 154, -1, + 343, 344, 155, -1, 343, 153, 342, -1, + 553, 334, 554, -1, 553, 559, 334, -1, + 553, 771, 559, -1, 156, 560, 157, -1, + 156, 157, 158, -1, 156, 559, 560, -1, + 156, 158, 334, -1, 156, 334, 559, -1, + 574, 159, 562, -1, 574, 573, 159, -1, + 355, 382, 356, -1, 355, 390, 382, -1, + 353, 571, 354, -1, 353, 592, 177, -1, + 353, 160, 351, -1, 353, 177, 160, -1, + 810, 811, 357, -1, 696, 928, 929, -1, + 359, 813, 587, -1, 359, 587, 197, -1, + 359, 197, 425, -1, 364, 167, 373, -1, + 364, 373, 365, -1, 364, 180, 167, -1, + 364, 361, 180, -1, 704, 161, 729, -1, + 363, 365, 161, -1, 363, 578, 579, -1, + 363, 704, 578, -1, 363, 161, 704, -1, + 708, 369, 367, -1, 162, 163, 164, -1, + 162, 164, 289, -1, 162, 165, 163, -1, + 162, 368, 165, -1, 162, 289, 368, -1, + 371, 366, 708, -1, 712, 630, 632, -1, + 374, 376, 386, -1, 374, 386, 166, -1, + 374, 166, 729, -1, 375, 373, 167, -1, + 375, 168, 376, -1, 375, 167, 180, -1, + 375, 180, 168, -1, 391, 378, 384, -1, + 394, 395, 169, -1, 394, 169, 398, -1, + 400, 201, 205, -1, 400, 205, 170, -1, + 400, 401, 201, -1, 400, 170, 181, -1, + 400, 181, 718, -1, 204, 172, 171, -1, + 204, 171, 205, -1, 204, 203, 172, -1, + 724, 280, 723, -1, 724, 174, 173, -1, + 724, 173, 280, -1, 724, 402, 174, -1, + 281, 723, 280, -1, 281, 197, 723, -1, + 820, 587, 813, -1, 589, 175, 176, -1, + 589, 590, 175, -1, 589, 176, 177, -1, + 589, 177, 592, -1, 404, 381, 405, -1, + 404, 356, 382, -1, 404, 382, 381, -1, + 178, 179, 180, -1, 178, 181, 179, -1, + 178, 180, 721, -1, 178, 721, 181, -1, + 598, 599, 182, -1, 598, 182, 183, -1, + 598, 183, 407, -1, 411, 184, 412, -1, + 413, 185, 184, -1, 413, 186, 185, -1, + 413, 409, 186, -1, 413, 184, 411, -1, + 595, 407, 186, -1, 595, 414, 418, -1, + 595, 186, 414, -1, 595, 416, 187, -1, + 595, 187, 188, -1, 595, 189, 597, -1, + 595, 188, 189, -1, 190, 191, 509, -1, + 190, 509, 194, -1, 190, 194, 192, -1, + 190, 192, 193, -1, 190, 193, 191, -1, + 283, 194, 509, -1, 283, 195, 194, -1, + 283, 208, 195, -1, 283, 196, 208, -1, + 283, 284, 196, -1, 719, 360, 423, -1, + 600, 423, 702, -1, 600, 426, 424, -1, + 600, 424, 423, -1, 199, 425, 197, -1, + 199, 281, 282, -1, 199, 197, 281, -1, + 199, 282, 652, -1, 651, 401, 653, -1, + 651, 202, 401, -1, 651, 508, 198, -1, + 651, 198, 202, -1, 584, 653, 582, -1, + 584, 652, 653, -1, 584, 199, 652, -1, + 584, 583, 425, -1, 584, 425, 199, -1, + 200, 201, 401, -1, 200, 401, 202, -1, + 200, 202, 203, -1, 200, 203, 204, -1, + 200, 205, 201, -1, 200, 204, 205, -1, + 430, 661, 207, -1, 428, 206, 429, -1, + 428, 430, 207, -1, 428, 208, 206, -1, + 428, 207, 208, -1, 431, 603, 209, -1, + 431, 209, 433, -1, 438, 437, 210, -1, + 438, 210, 211, -1, 438, 211, 436, -1, + 435, 436, 212, -1, 435, 213, 437, -1, + 435, 212, 214, -1, 435, 214, 213, -1, + 442, 441, 215, -1, 442, 215, 443, -1, + 611, 216, 445, -1, 611, 444, 216, -1, + 450, 608, 451, -1, 450, 452, 448, -1, + 222, 218, 444, -1, 222, 444, 220, -1, + 222, 228, 218, -1, 227, 225, 217, -1, + 227, 217, 218, -1, 227, 218, 228, -1, + 226, 221, 456, -1, 219, 220, 221, -1, + 219, 221, 226, -1, 219, 226, 228, -1, + 219, 222, 220, -1, 219, 228, 222, -1, + 455, 456, 605, -1, 457, 453, 224, -1, + 457, 224, 456, -1, 223, 224, 225, -1, + 223, 456, 224, -1, 223, 226, 456, -1, + 223, 225, 227, -1, 223, 227, 228, -1, + 223, 228, 226, -1, 460, 459, 230, -1, + 229, 230, 469, -1, 229, 469, 231, -1, + 229, 460, 230, -1, 229, 231, 460, -1, + 462, 469, 470, -1, 462, 231, 469, -1, + 462, 460, 231, -1, 234, 310, 233, -1, + 234, 232, 671, -1, 234, 671, 310, -1, + 466, 469, 232, -1, 466, 232, 234, -1, + 466, 234, 467, -1, 235, 233, 470, -1, + 235, 234, 233, -1, 235, 467, 234, -1, + 468, 235, 470, -1, 468, 467, 235, -1, + 236, 237, 320, -1, 236, 238, 237, -1, + 236, 320, 239, -1, 236, 239, 238, -1, + 471, 473, 268, -1, 240, 263, 620, -1, + 240, 620, 472, -1, 240, 642, 263, -1, + 240, 472, 642, -1, 475, 476, 241, -1, + 475, 242, 612, -1, 475, 612, 614, -1, + 475, 243, 242, -1, 475, 241, 243, -1, + 622, 613, 623, -1, 478, 244, 476, -1, + 478, 245, 244, -1, 478, 246, 245, -1, + 478, 247, 246, -1, 478, 477, 247, -1, + 481, 482, 248, -1, 481, 248, 614, -1, + 481, 614, 615, -1, 481, 616, 483, -1, + 481, 615, 616, -1, 249, 616, 250, -1, + 249, 483, 616, -1, 249, 250, 274, -1, + 249, 274, 273, -1, 249, 497, 278, -1, + 249, 273, 497, -1, 249, 278, 484, -1, + 249, 484, 483, -1, 629, 630, 625, -1, + 251, 323, 498, -1, 251, 498, 252, -1, + 251, 637, 323, -1, 251, 252, 637, -1, + 254, 253, 504, -1, 254, 255, 253, -1, + 254, 504, 498, -1, 254, 498, 323, -1, + 490, 254, 323, -1, 490, 255, 254, -1, + 490, 548, 255, -1, 634, 638, 256, -1, + 634, 262, 260, -1, 634, 256, 262, -1, + 639, 257, 258, -1, 639, 258, 638, -1, + 639, 491, 276, -1, 639, 276, 257, -1, + 259, 260, 643, -1, 259, 643, 640, -1, + 259, 640, 635, -1, 259, 635, 634, -1, + 259, 634, 260, -1, 645, 646, 488, -1, + 645, 488, 640, -1, 645, 640, 643, -1, + 797, 774, 696, -1, 797, 696, 929, -1, + 734, 357, 926, -1, 734, 810, 357, -1, + 803, 262, 261, -1, 803, 643, 262, -1, + 803, 264, 802, -1, 803, 261, 264, -1, + 801, 263, 642, -1, 801, 264, 263, -1, + 801, 802, 264, -1, 492, 266, 265, -1, + 492, 265, 737, -1, 492, 267, 266, -1, + 492, 268, 267, -1, 492, 471, 268, -1, + 492, 494, 471, -1, 271, 279, 507, -1, + 271, 507, 763, -1, 271, 763, 337, -1, + 271, 337, 272, -1, 269, 487, 279, -1, + 269, 270, 487, -1, 269, 279, 271, -1, + 269, 271, 272, -1, 269, 338, 270, -1, + 269, 272, 338, -1, 499, 497, 273, -1, + 499, 274, 275, -1, 499, 273, 274, -1, + 499, 275, 276, -1, 499, 276, 501, -1, + 505, 279, 485, -1, 505, 507, 279, -1, + 503, 277, 504, -1, 503, 505, 485, -1, + 503, 278, 497, -1, 503, 497, 277, -1, + 503, 484, 278, -1, 503, 485, 484, -1, + 486, 279, 487, -1, 486, 485, 279, -1, + 654, 280, 655, -1, 654, 282, 281, -1, + 654, 281, 280, -1, 654, 652, 282, -1, + 510, 283, 509, -1, 510, 284, 283, -1, + 510, 655, 284, -1, 285, 512, 516, -1, + 285, 287, 512, -1, 285, 286, 287, -1, + 285, 516, 657, -1, 285, 658, 286, -1, + 285, 657, 658, -1, 403, 512, 287, -1, + 403, 287, 402, -1, 403, 743, 512, -1, + 403, 740, 743, -1, 403, 789, 740, -1, + 660, 661, 430, -1, 662, 743, 742, -1, + 662, 288, 661, -1, 662, 289, 288, -1, + 662, 367, 289, -1, 662, 708, 367, -1, + 300, 290, 292, -1, 300, 299, 290, -1, + 300, 292, 521, -1, 291, 292, 293, -1, + 291, 293, 303, -1, 291, 522, 292, -1, + 291, 303, 522, -1, 664, 294, 524, -1, + 664, 665, 294, -1, 295, 296, 524, -1, + 295, 524, 297, -1, 295, 298, 296, -1, + 295, 297, 298, -1, 518, 519, 299, -1, + 518, 300, 521, -1, 518, 299, 300, -1, + 525, 519, 526, -1, 525, 524, 519, -1, + 301, 302, 520, -1, 301, 520, 522, -1, + 301, 522, 303, -1, 301, 304, 302, -1, + 301, 303, 304, -1, 305, 306, 307, -1, + 305, 308, 306, -1, 305, 307, 309, -1, + 305, 309, 308, -1, 670, 671, 527, -1, + 672, 311, 310, -1, 672, 673, 311, -1, + 672, 310, 671, -1, 312, 313, 314, -1, + 312, 315, 313, -1, 312, 314, 316, -1, + 312, 316, 317, -1, 312, 317, 315, -1, + 318, 319, 320, -1, 318, 320, 321, -1, + 318, 321, 319, -1, 322, 528, 678, -1, + 532, 679, 680, -1, 532, 678, 679, -1, + 532, 680, 535, -1, 532, 322, 678, -1, + 532, 535, 530, -1, 532, 528, 322, -1, + 532, 325, 528, -1, 532, 533, 325, -1, + 747, 749, 536, -1, 489, 897, 691, -1, + 489, 637, 897, -1, 489, 323, 637, -1, + 489, 490, 323, -1, 760, 897, 686, -1, + 760, 686, 761, -1, 760, 758, 897, -1, + 760, 687, 758, -1, 772, 769, 326, -1, + 772, 326, 324, -1, 772, 324, 556, -1, + 835, 836, 542, -1, 756, 541, 755, -1, + 540, 327, 541, -1, 540, 528, 325, -1, + 540, 325, 327, -1, 754, 326, 769, -1, + 754, 327, 326, -1, 754, 541, 327, -1, + 754, 755, 541, -1, 538, 328, 749, -1, + 538, 329, 328, -1, 538, 544, 329, -1, + 838, 751, 836, -1, 683, 330, 545, -1, + 683, 545, 840, -1, 683, 685, 331, -1, + 683, 331, 330, -1, 837, 544, 537, -1, + 837, 537, 838, -1, 332, 333, 336, -1, + 332, 336, 554, -1, 332, 334, 333, -1, + 332, 554, 334, -1, 335, 554, 336, -1, + 335, 338, 337, -1, 335, 337, 767, -1, + 335, 767, 554, -1, 335, 339, 338, -1, + 335, 336, 339, -1, 340, 342, 341, -1, + 340, 343, 342, -1, 340, 344, 343, -1, + 340, 341, 345, -1, 340, 345, 344, -1, + 770, 559, 771, -1, 350, 347, 346, -1, + 350, 346, 389, -1, 350, 389, 390, -1, + 350, 390, 355, -1, 563, 347, 350, -1, + 563, 348, 347, -1, 563, 349, 348, -1, + 563, 562, 349, -1, 570, 564, 354, -1, + 570, 354, 571, -1, 565, 354, 564, -1, + 565, 355, 354, -1, 565, 350, 355, -1, + 565, 563, 350, -1, 569, 351, 568, -1, + 569, 353, 351, -1, 569, 571, 353, -1, + 352, 353, 354, -1, 352, 355, 356, -1, + 352, 354, 355, -1, 352, 592, 353, -1, + 352, 356, 404, -1, 352, 404, 592, -1, + 576, 796, 357, -1, 576, 357, 811, -1, + 812, 426, 811, -1, 812, 813, 426, -1, + 817, 816, 913, -1, 358, 426, 813, -1, + 358, 813, 359, -1, 358, 424, 426, -1, + 358, 425, 424, -1, 358, 359, 425, -1, + 585, 579, 360, -1, 585, 361, 364, -1, + 585, 360, 719, -1, 585, 721, 361, -1, + 699, 702, 579, -1, 362, 363, 579, -1, + 362, 579, 585, -1, 362, 585, 364, -1, + 362, 364, 365, -1, 362, 365, 363, -1, + 784, 366, 371, -1, 784, 368, 367, -1, + 784, 367, 369, -1, 784, 708, 366, -1, + 784, 369, 708, -1, 784, 370, 368, -1, + 784, 786, 370, -1, 869, 708, 514, -1, + 869, 868, 708, -1, 869, 514, 782, -1, + 859, 371, 708, -1, 859, 784, 371, -1, + 711, 632, 777, -1, 711, 712, 632, -1, + 372, 729, 373, -1, 372, 374, 729, -1, + 372, 373, 375, -1, 372, 376, 374, -1, + 372, 375, 376, -1, 377, 379, 378, -1, + 377, 378, 391, -1, 377, 389, 379, -1, + 377, 391, 389, -1, 392, 387, 380, -1, + 392, 380, 381, -1, 392, 381, 382, -1, + 392, 382, 390, -1, 383, 384, 385, -1, + 383, 391, 384, -1, 383, 386, 387, -1, + 383, 385, 386, -1, 383, 387, 392, -1, + 383, 392, 391, -1, 388, 390, 389, -1, + 388, 389, 391, -1, 388, 392, 390, -1, + 388, 391, 392, -1, 393, 395, 394, -1, + 393, 396, 397, -1, 393, 397, 395, -1, + 393, 394, 398, -1, 393, 399, 396, -1, + 393, 398, 399, -1, 717, 401, 400, -1, + 717, 400, 718, -1, 717, 653, 401, -1, + 717, 582, 653, -1, 722, 402, 724, -1, + 722, 403, 402, -1, 722, 789, 403, -1, + 591, 404, 405, -1, 591, 405, 406, -1, + 591, 592, 404, -1, 591, 406, 590, -1, + 594, 598, 407, -1, 594, 407, 595, -1, + 408, 410, 409, -1, 408, 411, 412, -1, + 408, 409, 413, -1, 408, 413, 411, -1, + 408, 412, 414, -1, 408, 414, 410, -1, + 415, 416, 595, -1, 415, 417, 416, -1, + 415, 595, 418, -1, 415, 419, 417, -1, + 415, 420, 419, -1, 415, 418, 421, -1, + 415, 421, 420, -1, 422, 583, 719, -1, + 422, 719, 423, -1, 422, 423, 424, -1, + 422, 424, 425, -1, 422, 425, 583, -1, + 700, 426, 600, -1, 700, 811, 426, -1, + 700, 698, 811, -1, 427, 428, 429, -1, + 427, 430, 428, -1, 427, 429, 658, -1, + 427, 658, 660, -1, 427, 660, 430, -1, + 604, 603, 431, -1, 604, 432, 605, -1, + 604, 433, 432, -1, 604, 431, 433, -1, + 434, 436, 435, -1, 434, 435, 437, -1, + 434, 438, 436, -1, 434, 437, 438, -1, + 439, 440, 441, -1, 439, 441, 442, -1, + 439, 443, 440, -1, 439, 442, 443, -1, + 610, 607, 444, -1, 610, 444, 611, -1, + 609, 451, 608, -1, 609, 445, 451, -1, + 609, 611, 445, -1, 446, 447, 608, -1, + 446, 608, 450, -1, 446, 448, 447, -1, + 446, 450, 448, -1, 449, 450, 451, -1, + 449, 452, 450, -1, 449, 451, 452, -1, + 458, 453, 457, -1, 458, 605, 453, -1, + 458, 455, 605, -1, 454, 456, 455, -1, + 454, 457, 456, -1, 454, 455, 458, -1, + 454, 458, 457, -1, 464, 463, 459, -1, + 464, 459, 460, -1, 464, 460, 462, -1, + 461, 462, 470, -1, 461, 470, 463, -1, + 461, 463, 464, -1, 461, 464, 462, -1, + 465, 466, 467, -1, 465, 467, 468, -1, + 465, 469, 466, -1, 465, 470, 469, -1, + 465, 468, 470, -1, 495, 471, 494, -1, + 495, 641, 642, -1, 495, 642, 472, -1, + 495, 472, 473, -1, 495, 473, 471, -1, + 474, 475, 614, -1, 474, 476, 475, -1, + 474, 614, 477, -1, 474, 478, 476, -1, + 474, 477, 478, -1, 618, 479, 616, -1, + 618, 619, 479, -1, 480, 482, 481, -1, + 480, 483, 484, -1, 480, 481, 483, -1, + 480, 484, 485, -1, 480, 485, 486, -1, + 480, 487, 482, -1, 480, 486, 487, -1, + 794, 625, 725, -1, 794, 629, 625, -1, + 631, 732, 829, -1, 627, 640, 488, -1, + 627, 488, 732, -1, 627, 732, 631, -1, + 627, 631, 629, -1, 626, 630, 580, -1, + 626, 580, 728, -1, 626, 728, 725, -1, + 550, 691, 549, -1, 550, 489, 691, -1, + 550, 490, 489, -1, 550, 548, 490, -1, + 636, 637, 491, -1, 636, 491, 639, -1, + 800, 645, 643, -1, 927, 734, 926, -1, + 823, 641, 822, -1, 821, 822, 494, -1, + 821, 492, 737, -1, 821, 494, 492, -1, + 493, 822, 641, -1, 493, 494, 822, -1, + 493, 641, 495, -1, 493, 495, 494, -1, + 496, 498, 497, -1, 496, 497, 499, -1, + 496, 500, 498, -1, 496, 501, 500, -1, + 496, 499, 501, -1, 502, 503, 504, -1, + 502, 505, 503, -1, 502, 504, 506, -1, + 502, 506, 507, -1, 502, 507, 505, -1, + 650, 509, 508, -1, 650, 510, 509, -1, + 650, 508, 651, -1, 650, 655, 510, -1, + 511, 743, 662, -1, 511, 662, 515, -1, + 511, 512, 743, -1, 511, 515, 512, -1, + 513, 742, 514, -1, 513, 662, 742, -1, + 513, 514, 708, -1, 513, 708, 662, -1, + 659, 516, 515, -1, 659, 515, 662, -1, + 659, 657, 516, -1, 790, 815, 814, -1, + 790, 740, 789, -1, 790, 814, 817, -1, + 666, 664, 526, -1, 666, 526, 667, -1, + 517, 519, 518, -1, 517, 520, 667, -1, + 517, 667, 519, -1, 517, 518, 521, -1, + 517, 522, 520, -1, 517, 521, 522, -1, + 523, 664, 524, -1, 523, 524, 525, -1, + 523, 526, 664, -1, 523, 525, 526, -1, + 669, 527, 673, -1, 669, 670, 527, -1, + 676, 678, 528, -1, 676, 528, 540, -1, + 676, 540, 677, -1, 674, 836, 751, -1, + 674, 677, 540, -1, 529, 530, 531, -1, + 529, 532, 530, -1, 529, 531, 533, -1, + 529, 533, 532, -1, 681, 534, 535, -1, + 681, 535, 680, -1, 681, 536, 534, -1, + 681, 747, 536, -1, 750, 838, 537, -1, + 750, 751, 838, -1, 750, 537, 544, -1, + 750, 544, 538, -1, 750, 538, 749, -1, + 746, 677, 674, -1, 682, 833, 752, -1, + 757, 758, 687, -1, 757, 687, 688, -1, + 901, 682, 752, -1, 901, 688, 682, -1, + 843, 761, 686, -1, 689, 835, 542, -1, + 689, 541, 756, -1, 689, 756, 752, -1, + 539, 540, 541, -1, 539, 541, 689, -1, + 539, 689, 542, -1, 539, 674, 540, -1, + 539, 542, 836, -1, 539, 836, 674, -1, + 543, 544, 837, -1, 543, 840, 545, -1, + 543, 837, 840, -1, 543, 545, 546, -1, + 543, 547, 544, -1, 543, 546, 547, -1, + 693, 551, 548, -1, 693, 692, 551, -1, + 693, 549, 690, -1, 693, 548, 550, -1, + 693, 550, 549, -1, 694, 552, 551, -1, + 694, 551, 692, -1, 694, 695, 552, -1, + 694, 856, 855, -1, 764, 771, 553, -1, + 764, 554, 767, -1, 764, 553, 554, -1, + 555, 772, 556, -1, 555, 770, 772, -1, + 555, 557, 558, -1, 555, 556, 557, -1, + 555, 559, 770, -1, 555, 558, 560, -1, + 555, 560, 559, -1, 561, 574, 562, -1, + 561, 562, 563, -1, 561, 564, 570, -1, + 561, 570, 574, -1, 561, 565, 564, -1, + 561, 563, 565, -1, 566, 568, 567, -1, + 566, 569, 568, -1, 566, 570, 571, -1, + 566, 571, 569, -1, 566, 567, 572, -1, + 566, 572, 573, -1, 566, 573, 574, -1, + 566, 574, 570, -1, 575, 698, 796, -1, + 575, 796, 576, -1, 575, 811, 698, -1, + 575, 576, 811, -1, 819, 820, 813, -1, + 809, 928, 696, -1, 809, 696, 735, -1, + 809, 927, 928, -1, 914, 913, 816, -1, + 577, 578, 704, -1, 577, 704, 699, -1, + 577, 579, 578, -1, 577, 699, 579, -1, + 795, 699, 704, -1, 795, 796, 698, -1, + 727, 728, 779, -1, 727, 779, 792, -1, + 870, 871, 817, -1, 870, 817, 913, -1, + 776, 711, 777, -1, 858, 777, 632, -1, + 858, 828, 709, -1, 858, 632, 829, -1, + 858, 829, 828, -1, 876, 776, 879, -1, + 876, 714, 776, -1, 581, 714, 876, -1, + 581, 876, 781, -1, 581, 580, 630, -1, + 581, 712, 714, -1, 581, 630, 712, -1, + 780, 779, 728, -1, 780, 728, 580, -1, + 780, 580, 581, -1, 780, 581, 781, -1, + 713, 714, 712, -1, 716, 582, 717, -1, + 716, 719, 583, -1, 716, 583, 584, -1, + 716, 584, 582, -1, 720, 585, 719, -1, + 720, 721, 585, -1, 736, 723, 586, -1, + 736, 586, 587, -1, 736, 587, 820, -1, + 588, 590, 589, -1, 588, 591, 590, -1, + 588, 589, 592, -1, 588, 592, 591, -1, + 593, 594, 595, -1, 593, 597, 596, -1, + 593, 595, 597, -1, 593, 598, 594, -1, + 593, 596, 599, -1, 593, 599, 598, -1, + 701, 600, 702, -1, 701, 700, 600, -1, + 601, 602, 603, -1, 601, 603, 604, -1, + 601, 605, 602, -1, 601, 604, 605, -1, + 606, 608, 607, -1, 606, 609, 608, -1, + 606, 607, 610, -1, 606, 610, 611, -1, + 606, 611, 609, -1, 621, 612, 613, -1, + 621, 613, 622, -1, 621, 614, 612, -1, + 621, 615, 614, -1, 621, 616, 615, -1, + 621, 618, 616, -1, 617, 619, 618, -1, + 617, 620, 619, -1, 617, 621, 622, -1, + 617, 618, 621, -1, 617, 623, 620, -1, + 617, 622, 623, -1, 624, 625, 630, -1, + 624, 725, 625, -1, 624, 630, 626, -1, + 624, 626, 725, -1, 885, 794, 726, -1, + 730, 629, 794, -1, 730, 640, 627, -1, + 730, 627, 629, -1, 628, 630, 629, -1, + 628, 629, 631, -1, 628, 632, 630, -1, + 628, 829, 632, -1, 628, 631, 829, -1, + 633, 634, 635, -1, 633, 637, 636, -1, + 633, 638, 634, -1, 633, 639, 638, -1, + 633, 636, 639, -1, 633, 635, 640, -1, + 633, 640, 730, -1, 633, 897, 637, -1, + 633, 730, 897, -1, 805, 641, 823, -1, + 805, 642, 641, -1, 805, 801, 642, -1, + 799, 643, 803, -1, 799, 800, 643, -1, + 644, 646, 645, -1, 644, 645, 800, -1, + 644, 732, 646, -1, 644, 800, 731, -1, + 644, 731, 732, -1, 895, 809, 735, -1, + 738, 737, 647, -1, 738, 647, 828, -1, + 825, 648, 824, -1, 733, 824, 648, -1, + 733, 829, 732, -1, 733, 648, 825, -1, + 733, 831, 829, -1, 733, 825, 831, -1, + 649, 650, 651, -1, 649, 653, 652, -1, + 649, 651, 653, -1, 649, 652, 654, -1, + 649, 654, 655, -1, 649, 655, 650, -1, + 656, 658, 657, -1, 656, 657, 659, -1, + 656, 660, 658, -1, 656, 661, 660, -1, + 656, 662, 661, -1, 656, 659, 662, -1, + 741, 790, 817, -1, 741, 817, 871, -1, + 741, 871, 782, -1, 663, 665, 664, -1, + 663, 664, 666, -1, 663, 667, 665, -1, + 663, 666, 667, -1, 668, 670, 669, -1, + 668, 671, 670, -1, 668, 672, 671, -1, + 668, 673, 672, -1, 668, 669, 673, -1, + 748, 674, 751, -1, 748, 746, 674, -1, + 675, 676, 677, -1, 675, 677, 746, -1, + 675, 679, 678, -1, 675, 678, 676, -1, + 675, 680, 679, -1, 675, 681, 680, -1, + 675, 747, 681, -1, 675, 746, 747, -1, + 753, 752, 756, -1, 902, 757, 688, -1, + 902, 688, 901, -1, 834, 833, 682, -1, + 834, 682, 688, -1, 848, 683, 840, -1, + 848, 684, 685, -1, 848, 685, 683, -1, + 848, 686, 684, -1, 848, 843, 686, -1, + 762, 687, 760, -1, 762, 688, 687, -1, + 762, 834, 688, -1, 762, 842, 834, -1, + 832, 835, 689, -1, 832, 752, 833, -1, + 832, 689, 752, -1, 896, 693, 690, -1, + 896, 905, 693, -1, 896, 690, 691, -1, + 896, 691, 897, -1, 906, 856, 694, -1, + 906, 694, 692, -1, 906, 692, 693, -1, + 906, 693, 905, -1, 765, 695, 694, -1, + 765, 763, 695, -1, 765, 694, 855, -1, + 775, 735, 696, -1, 775, 914, 735, -1, + 775, 696, 774, -1, 697, 795, 698, -1, + 697, 699, 795, -1, 697, 698, 700, -1, + 697, 700, 701, -1, 697, 702, 699, -1, + 697, 701, 702, -1, 703, 729, 882, -1, + 703, 882, 795, -1, 703, 704, 729, -1, + 703, 795, 704, -1, 793, 917, 774, -1, + 793, 792, 917, -1, 793, 797, 886, -1, + 793, 774, 797, -1, 865, 861, 864, -1, + 865, 879, 776, -1, 705, 861, 859, -1, + 705, 859, 708, -1, 705, 708, 706, -1, + 705, 864, 861, -1, 705, 706, 864, -1, + 707, 708, 868, -1, 862, 864, 706, -1, + 862, 707, 868, -1, 862, 706, 708, -1, + 862, 708, 707, -1, 785, 859, 858, -1, + 785, 858, 709, -1, 785, 709, 786, -1, + 710, 712, 711, -1, 710, 713, 712, -1, + 710, 711, 776, -1, 710, 776, 714, -1, + 710, 714, 713, -1, 715, 716, 717, -1, + 715, 717, 718, -1, 715, 719, 716, -1, + 715, 720, 719, -1, 715, 718, 721, -1, + 715, 721, 720, -1, 788, 789, 722, -1, + 788, 736, 815, -1, 788, 723, 736, -1, + 788, 724, 723, -1, 788, 722, 724, -1, + 791, 794, 725, -1, 791, 726, 794, -1, + 791, 885, 726, -1, 791, 727, 792, -1, + 791, 725, 728, -1, 791, 728, 727, -1, + 881, 882, 729, -1, 881, 730, 794, -1, + 881, 729, 897, -1, 881, 897, 730, -1, + 806, 731, 800, -1, 807, 732, 731, -1, + 807, 733, 732, -1, 807, 824, 733, -1, + 807, 823, 824, -1, 807, 731, 806, -1, + 893, 734, 927, -1, 893, 810, 734, -1, + 890, 895, 735, -1, 890, 914, 816, -1, + 890, 735, 914, -1, 818, 815, 736, -1, + 818, 736, 820, -1, 827, 821, 737, -1, + 827, 737, 738, -1, 827, 738, 828, -1, + 739, 740, 790, -1, 739, 790, 741, -1, + 739, 742, 743, -1, 739, 743, 740, -1, + 739, 741, 782, -1, 739, 782, 744, -1, + 739, 744, 742, -1, 745, 747, 746, -1, + 745, 746, 748, -1, 745, 749, 747, -1, + 745, 750, 749, -1, 745, 751, 750, -1, + 745, 748, 751, -1, 900, 753, 853, -1, + 900, 901, 752, -1, 900, 752, 753, -1, + 852, 853, 753, -1, 852, 754, 769, -1, + 852, 755, 754, -1, 852, 756, 755, -1, + 852, 753, 756, -1, 910, 757, 902, -1, + 910, 758, 757, -1, 910, 897, 758, -1, + 847, 848, 840, -1, 759, 760, 761, -1, + 759, 762, 760, -1, 759, 761, 843, -1, + 759, 843, 842, -1, 759, 842, 762, -1, + 899, 900, 853, -1, 766, 767, 763, -1, + 766, 763, 765, -1, 768, 771, 764, -1, + 768, 764, 850, -1, 773, 850, 764, -1, + 773, 765, 855, -1, 773, 766, 765, -1, + 773, 764, 767, -1, 773, 767, 766, -1, + 851, 768, 850, -1, 851, 852, 769, -1, + 851, 770, 771, -1, 851, 771, 768, -1, + 851, 769, 772, -1, 851, 772, 770, -1, + 854, 773, 855, -1, 854, 850, 773, -1, + 854, 853, 850, -1, 880, 774, 917, -1, + 880, 775, 774, -1, 880, 914, 775, -1, + 860, 865, 776, -1, 860, 776, 777, -1, + 860, 861, 865, -1, 860, 777, 858, -1, + 778, 917, 792, -1, 778, 918, 917, -1, + 778, 792, 779, -1, 778, 779, 918, -1, + 875, 918, 779, -1, 875, 779, 780, -1, + 875, 780, 781, -1, 875, 781, 876, -1, + 872, 782, 871, -1, 872, 869, 782, -1, + 921, 878, 911, -1, 921, 918, 875, -1, + 920, 921, 911, -1, 783, 784, 859, -1, + 783, 859, 785, -1, 783, 786, 784, -1, + 783, 785, 786, -1, 787, 788, 815, -1, + 787, 789, 788, -1, 787, 815, 790, -1, + 787, 790, 789, -1, 887, 885, 791, -1, + 887, 791, 792, -1, 887, 793, 886, -1, + 887, 792, 793, -1, 884, 794, 885, -1, + 884, 881, 794, -1, 925, 796, 795, -1, + 925, 795, 882, -1, 925, 926, 796, -1, + 924, 886, 797, -1, 924, 881, 884, -1, + 924, 797, 929, -1, 798, 800, 799, -1, + 798, 806, 800, -1, 798, 805, 806, -1, + 798, 802, 801, -1, 798, 801, 805, -1, + 798, 803, 802, -1, 798, 799, 803, -1, + 804, 805, 823, -1, 804, 806, 805, -1, + 804, 823, 807, -1, 804, 807, 806, -1, + 808, 927, 809, -1, 808, 893, 927, -1, + 808, 809, 895, -1, 808, 895, 893, -1, + 892, 810, 893, -1, 892, 811, 810, -1, + 892, 812, 811, -1, 892, 813, 812, -1, + 892, 819, 813, -1, 889, 814, 815, -1, + 889, 815, 818, -1, 889, 890, 816, -1, + 889, 816, 817, -1, 889, 817, 814, -1, + 894, 889, 818, -1, 894, 819, 892, -1, + 894, 820, 819, -1, 894, 818, 820, -1, + 830, 822, 821, -1, 830, 821, 827, -1, + 830, 824, 823, -1, 830, 823, 822, -1, + 830, 825, 824, -1, 830, 831, 825, -1, + 826, 827, 828, -1, 826, 828, 829, -1, + 826, 830, 827, -1, 826, 829, 831, -1, + 826, 831, 830, -1, 844, 832, 833, -1, + 844, 835, 832, -1, 844, 833, 834, -1, + 844, 834, 842, -1, 839, 836, 835, -1, + 839, 838, 836, -1, 839, 835, 844, -1, + 839, 844, 845, -1, 846, 837, 838, -1, + 846, 838, 839, -1, 846, 839, 845, -1, + 846, 840, 837, -1, 846, 847, 840, -1, + 841, 842, 843, -1, 841, 844, 842, -1, + 841, 845, 844, -1, 841, 847, 846, -1, + 841, 846, 845, -1, 841, 843, 848, -1, + 841, 848, 847, -1, 909, 910, 902, -1, + 849, 850, 853, -1, 849, 851, 850, -1, + 849, 853, 852, -1, 849, 852, 851, -1, + 898, 899, 853, -1, 898, 853, 854, -1, + 898, 855, 856, -1, 898, 854, 855, -1, + 898, 856, 906, -1, 898, 906, 907, -1, + 857, 858, 859, -1, 857, 860, 858, -1, + 857, 859, 861, -1, 857, 861, 860, -1, + 867, 864, 862, -1, 867, 866, 864, -1, + 867, 862, 868, -1, 863, 878, 877, -1, + 863, 866, 878, -1, 863, 864, 866, -1, + 863, 865, 864, -1, 863, 879, 865, -1, + 863, 877, 879, -1, 873, 911, 878, -1, + 873, 878, 866, -1, 873, 867, 868, -1, + 873, 866, 867, -1, 873, 868, 869, -1, + 873, 869, 872, -1, 912, 871, 870, -1, + 912, 872, 871, -1, 912, 911, 873, -1, + 912, 873, 872, -1, 912, 870, 913, -1, + 874, 921, 875, -1, 874, 875, 876, -1, + 874, 877, 878, -1, 874, 878, 921, -1, + 874, 876, 879, -1, 874, 879, 877, -1, + 916, 914, 880, -1, 916, 880, 917, -1, + 923, 882, 881, -1, 923, 925, 882, -1, + 923, 881, 924, -1, 883, 884, 885, -1, + 883, 924, 884, -1, 883, 886, 924, -1, + 883, 887, 886, -1, 883, 885, 887, -1, + 888, 894, 895, -1, 888, 889, 894, -1, + 888, 895, 890, -1, 888, 890, 889, -1, + 891, 892, 893, -1, 891, 894, 892, -1, + 891, 893, 895, -1, 891, 895, 894, -1, + 904, 905, 896, -1, 904, 896, 897, -1, + 904, 897, 910, -1, 908, 899, 898, -1, + 908, 898, 907, -1, 908, 901, 900, -1, + 908, 900, 899, -1, 908, 902, 901, -1, + 908, 909, 902, -1, 903, 905, 904, -1, + 903, 906, 905, -1, 903, 907, 906, -1, + 903, 909, 908, -1, 903, 908, 907, -1, + 903, 910, 909, -1, 903, 904, 910, -1, + 919, 920, 911, -1, 919, 911, 912, -1, + 919, 912, 913, -1, 919, 913, 914, -1, + 919, 914, 916, -1, 915, 916, 917, -1, + 915, 917, 918, -1, 915, 920, 919, -1, + 915, 919, 916, -1, 915, 918, 921, -1, + 915, 921, 920, -1, 922, 923, 924, -1, + 922, 926, 925, -1, 922, 925, 923, -1, + 922, 928, 927, -1, 922, 927, 926, -1, + 922, 929, 928, -1, 922, 924, 929, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ2.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ2.wrl new file mode 100644 index 0000000..a411a9c --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ2.wrl @@ -0,0 +1,3954 @@ +#VRML V2.0 utf8 + + +DEF solid_T2R3_TJ2__________________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -39.633301 41.086201 -95.25, + 184.99001 -34.752602 -97.25, + 184.99001 -34.752602 97.25, + 181.888 -38.459499 110.9, + 178.062 -42.0812 -112.554, + 168.244 -49.439098 97.25, + 168.244 -49.439098 -97.25, + 82.1894 -58.387402 93.801498, + -57.0495 -2.0544102 -95.25, + -55.985699 -11.156701 -67.8993, + -39.633301 41.086201 95.25, + 147.14301 56.540401 110.9, + 147.151 56.598999 97.25, + 147.151 56.598999 -97.25, + -55.872898 -11.660999 -67.061996, + 1.5224114e-006 -56.981201 -112.318, + 169.75301 -48.536701 -110.9, + 174.44099 -45.276199 -110.9, + 174.103 -45.556702 -110.9, + 174.453 -45.290501 97.25, + 174.103 -45.556702 110.9, + 174.44099 -45.276199 110.9, + 174.453 -45.290501 -97.25, + 180.067 -40.366901 97.25, + 185.14101 -34.315601 -112.554, + 196.299 7.4514003 -97.25, + 169.67599 -48.4137 112.554, + 169.75301 -48.536701 110.9, + -27.999399 -45.2206 118.587, + -27.948 -49.777302 95.25, + -21.3706 -52.935501 95.25, + -20.328699 -52.474499 114.75, + -16.6998 -54.622601 95.25, + 147.151 -56.598999 97.25, + -57.0495 2.0544107 80.598297, + -57.0495 2.0544102 -80.598297, + -57.0495 2.0544105 95.25, + -57.0495 2.0544102 -95.25, + -54.512798 16.9478 -57.696201, + -52.891602 21.4778 -47.768002, + -52.9347 21.372601 -48.0298, + -52.7127 21.9144 -46.681702, + -52.847801 21.586599 47.5028, + -56.673801 -6.8523397 74.3078, + -56.6516 -7.0331612 -74.054497, + -56.949799 -3.9486194 78.208702, + -56.808899 -5.4453306 -76.2005, + -56.930599 -4.2158909 -77.862099, + -56.264801 -9.6506691 70.236504, + -56.321499 -9.3143911 -95.25, + -56.250801 -9.7323303 -70.112503, + -56.027 -10.947299 68.231003, + 161.54601 52.741901 97.25, + 161.54601 52.741901 -97.25, + 185.257 -34.402802 110.9, + 168.244 49.439098 -97.25, + -21.200399 42.576099 120.425, + 139.7 49.182499 120.283, + 139.7 47.562401 120.425, + 144.089 47.359501 120.425, + 9.5439987e-007 50.521198 119.954, + 1.3528586e-006 49.060398 120.306, + 139.7 49.2164 120.28, + -4.3885002 47.359501 120.425, + 7.9312616e-007 47.562401 120.425, + -4.5267305 48.851101 120.306, + 144.914 56.2719 114.158, + -4.6615095 50.305599 119.954, + 1.2372865e-006 50.749599 119.859, + -53.695499 19.372999 52.643799, + -52.9557 21.320499 48.157299, + -53.740601 19.256701 -52.916901, + -49.816502 27.871401 -27.068899, + -50.055599 27.446501 29.0452, + -49.597801 28.265301 -25.3183, + -34.068901 45.805901 95.25, + -44.550098 35.695301 95.25, + -44.550098 35.695301 -95.25, + -27.948 49.777302 95.25, + -27.948 49.777302 -95.25, + -25.083799 50.375 114.75, + -34.068901 45.805901 -95.25, + 147.14301 56.540401 -110.9, + 82.550003 58.380299 93.975403, + 154.468 55.109299 -110.9, + 150.19 56.115398 -110.9, + 150.16299 55.973099 -112.554, + 154.47501 55.1422 -97.25, + 144.95399 56.699799 112.554, + 144.528 52.1017 -119.149, + 144.653 53.455898 -118.197, + 154.019 50.3274 -119.149, + 154.392 51.635601 -118.197, + 158.058 47.388401 -119.851, + 153.608 48.8801 -119.851, + 149.315 51.433998 -119.149, + 144.241 49.0065 -120.28, + 144.38901 50.603401 -119.851, + 149.03799 49.9548 -119.851, + 148.743 48.378399 -120.28, + -54.521301 -16.920401 -57.749901, + -54.512798 -16.9478 57.696201, + -55.234001 -14.375 62.452801, + -55.439899 -13.6119 63.834, + -55.217201 -14.444399 -62.333599, + -54.761501 -16.125999 59.283699, + -54.734798 -16.216299 -59.1119, + -55.402199 -13.7646 -63.5695, + -27.948 -49.777302 -95.25, + 5.34338 -58.380299 -93.328499, + 147.14301 -56.540401 -110.9, + 147.151 -56.598999 -97.25, + 154.47501 -55.1422 -97.25, + 154.47501 -55.1422 97.25, + 155.323 -54.9081 -110.9, + -1.5277501 -56.923302 112.514, + -50.486198 -26.637501 -32.209, + -51.025799 -25.5977 -36.005798, + -50.913799 -25.8197 35.247601, + -49.452599 -28.5186 -24.043301, + -50.306999 -26.9828 -30.9482, + -48.516998 -30.082701 13.667, + -48.400799 -30.2694 -11.8225, + -53.9342 -15.3456 -115.174, + -55.119999 -10.303701 -115.174, + -55.316502 -10.3404 -114.75, + -52.474499 -20.328699 -114.75, + -52.2882 -20.2565 -115.174, + -54.1264 -15.4003 -114.75, + -50.375 -25.083799 -114.75, + -50.196098 -24.994699 -115.174, + -44.550098 -35.695301 -95.25, + 192.93201 -20.622299 -110.9, + 192.39999 -21.8279 -110.9, + 173.334 -44.538399 -115.662, + 177.77299 -41.763599 -114.158, + 172.75999 -43.7784 -117.023, + 169.45 -48.048302 -114.158, + 173.757 -45.098301 -114.158, + 164.89 -50.588299 -114.158, + 169.67599 -48.4137 -112.554, + 174.01601 -45.4412 -112.554, + 165.082 -50.973 -112.554, + 180.024 -40.323799 -110.9, + 180.067 -40.366901 -97.25, + 178.16 -42.188099 -110.9, + 181.888 -38.459499 -110.9, + 181.78101 -38.362 -112.554, + 192.442 21.846399 97.25, + 192.39999 21.8279 110.9, + 189.13901 28.543699 -97.25, + 189.13901 28.543699 97.25, + 195.815 10.489799 -110.9, + 144.914 -56.2719 -114.158, + 144.85001 -55.5732 -115.662, + 161.528 -52.7001 110.9, + 161.54601 -52.741901 -97.25, + 165.146 -51.102501 -110.9, + 165.146 -51.102501 110.9, + 161.54601 -52.741901 97.25, + 161.528 -52.7001 -110.9, + 160.32201 -53.232399 -110.9, + 160.32201 -53.232399 110.9, + 183.478 33.059898 -117.023, + 176.658 40.541302 -117.023, + 180.241 36.958302 -117.023, + 179.37399 36.167301 -118.197, + -5.0125804 -54.094398 -117.607, + 8.9595096e-007 -53.562599 -118.264, + 164.577 -49.960201 -115.662, + 169.08099 -47.451698 -115.662, + -28.599001 -46.188999 117.607, + -24.994699 -50.196098 115.174, + -20.2565 -52.2882 115.174, + -25.083799 -50.375 114.75, + -4.5267296 -48.851101 120.306, + 121.56 -58.387402 -93.284203, + -47.562401 1.6827114e-007 120.425, + -56.034599 5.1923704 114.75, + -54.486401 17.025 57.533699, + -54.5089 16.959499 -57.672001, + -53.755402 19.2152 53.0075, + -54.521301 16.920401 57.749901, + -50.913799 25.8197 -35.247601, + -51.025799 25.5977 36.005798, + -50.219601 27.145201 -30.296101, + -50.486198 26.637501 32.209, + -50.306999 26.9828 30.9482, + -51.257301 25.122101 -37.524799, + -51.132198 25.384399 -36.718399, + -52.036201 23.4757 42.522202, + -51.799 23.9944 41.034599, + -51.909 23.7554 -41.7272, + -52.132099 23.261801 -95.25, + -49.452599 28.5186 24.043301, + -55.217201 14.444399 62.333599, + -54.734798 16.216299 59.1119, + 2.2633237e-006 -50.521198 -119.954, + 152.716 -45.7467 -120.425, + -4.3884997 -47.359501 -120.425, + -4.5267301 -48.851101 -120.306, + -51.562599 -19.9755 -116.459, + -49.499599 -24.6479 -116.459, + -52.252201 -14.867 -117.607, + -53.4011 -9.9823999 -117.607, + -53.185799 -15.1327 -116.459, + -51.156799 -14.5554 -118.587, + -44.9081 33.912998 -114.75, + -44.7486 33.792599 -115.174, + -50.196098 24.994699 -115.174, + -50.375 25.083799 -114.75, + -47.675701 29.5196 -115.174, + -47.845699 29.6248 -114.75, + -52.474499 20.328699 -114.75, + -27.999399 45.2206 -118.587, + -28.599001 46.188999 -117.607, + -27.3262 44.133301 -119.376, + -36.5993 40.147499 -117.607, + -32.7388 43.353199 -117.607, + 184.23801 33.633801 -115.662, + 180.94501 37.5998 -115.662, + 178.062 42.0812 -112.554, + 181.464 38.072498 -114.158, + 174.44099 45.276199 -110.9, + 174.453 45.290501 -97.25, + 165.146 51.102501 -110.9, + 149.565 52.770901 -118.197, + 194.608 -15.6227 110.9, + 196.213 1.2749294e-007 114.158, + 196.299 7.4513993 97.25, + 196.787 2.019019e-007 110.9, + 196.64301 -3.7257001e-007 112.554, + 195.27299 5.1496196 115.662, + 180.138 -25.038401 120.425, + 178.062 -42.0812 112.554, + 181.78101 -38.362 112.554, + 178.16 -42.188099 110.9, + 174.01601 -45.4412 112.554, + 177.77299 -41.763599 114.158, + 190.673 -25.3815 112.554, + 189.13901 -28.543699 97.25, + 192.442 -21.846399 -97.25, + 139.7 50.820099 119.851, + 144.241 49.0065 120.28, + 152.716 45.7467 120.425, + 149.03799 49.9548 119.851, + 148.743 48.378399 120.28, + 148.44 46.752602 120.425, + 149.78 53.9249 117.023, + 174.103 45.556702 110.9, + 168.244 49.439098 97.25, + 174.103 45.556702 -110.9, + -9.0148296 48.225101 120.306, + -15.132699 53.185799 116.459, + 2.3899274e-006 54.326099 117.607, + 9.033464e-007 54.726101 117.134, + 2.1904455e-006 51.908199 119.376, + -52.474499 20.328699 114.75, + -52.132099 23.261801 95.25, + -54.673401 16.422199 95.25, + -50.375 25.083799 114.75, + -14.444001 55.229 -90.487503, + -7.6432199 56.604698 -95.25, + -16.6998 54.622601 95.25, + -16.6998 54.622601 -90.487503, + -21.3706 52.935501 -95.25, + -21.3706 52.935501 95.25, + -20.328699 52.474499 114.75, + -15.400301 54.1264 114.75, + -37.253101 40.8647 -116.459, + -41.587502 37.911999 -114.75, + -41.4398 37.777302 -115.174, + -40.8647 37.253101 -116.459, + 144.914 56.2719 -114.158, + 144.95399 56.699799 -112.554, + -1.52775 56.923302 -112.514, + 5.6659303 58.380299 93.738602, + 154.468 55.109299 110.9, + 154.47501 55.1422 97.25, + 150.19 56.115398 110.9, + 158.60201 48.7915 -119.149, + 157.479 45.892899 -120.28, + 139.7 49.2164 -120.28, + 139.7 47.562401 -120.425, + 2.0893237e-006 47.562401 -120.425, + 139.7 49.182499 -120.283, + -52.9557 -21.320499 -48.157299, + -53.755402 -19.2152 -53.0075, + -54.673401 -16.422199 -95.25, + -53.695499 -19.372999 -52.643799, + -54.486401 -17.025 -57.533699, + -53.740601 -19.256701 52.916901, + -54.5089 -16.959499 57.672001, + 139.7 -55.811298 -115.662, + 139.7 -56.513 -114.158, + 5.2745705 -58.380299 -93.129601, + 5.2546401 -58.380299 -93.026199, + -1.3080797 -56.957802 -112.317, + 5.4050002 -58.387402 -93.195801, + 5.3042302 -58.380299 -93.230698, + 5.37819 -58.387402 -93.1045, + 139.7 -56.942699 -112.554, + 150.19 -56.115398 -110.9, + 154.468 -55.109299 -110.9, + 144.95399 -56.699799 -112.554, + 150.084 -55.550701 -114.158, + 150.16299 -55.973099 -112.554, + 155.283 -54.768902 -112.554, + 160.11501 -52.6968 -114.158, + 160.27 -53.0975 -112.554, + -1.6565493 -56.904202 112.633, + 1.7485205e-006 -56.981201 112.318, + -52.036201 -23.4757 -42.522202, + -52.132099 -23.261801 -95.25, + -51.257301 -25.122101 37.524799, + -51.799 -23.9944 -41.034599, + -51.909 -23.7554 41.7272, + -51.132198 -25.384399 36.718399, + -48.944599 -29.3818 -19.044701, + -49.387798 -28.630699 23.4564, + -49.816502 -27.871401 27.068899, + -50.055599 -27.446501 -29.0452, + -49.597801 -28.265301 25.3183, + -50.219601 -27.145201 30.296101, + -48.376099 -30.3088 11.394799, + -55.060799 -5.1021304 -116.459, + -54.355202 -10.1607 -116.459, + -56.074799 4.3186589e-007 -115.174, + -55.835602 -5.1739306 -115.174, + -56.274601 7.4117366e-008 -114.75, + -56.034599 -5.1923695 -114.75, + -56.034599 5.1923704 -114.75, + 188.237 -30.052601 -110.9, + 189.13901 -28.543699 -97.25, + 185.257 -34.402802 -110.9, + 188.237 -30.052601 110.9, + 190.80299 -25.445999 -110.9, + 192.797 -20.570101 -112.554, + 174.44099 45.276199 110.9, + 174.453 45.290501 97.25, + 178.16 42.188099 -110.9, + 180.067 40.366901 97.25, + 180.067 40.366901 -97.25, + 174.01601 45.4412 112.554, + 190.673 25.3815 112.554, + 192.797 20.570101 112.554, + 190.80299 25.445999 110.9, + 185.34399 28.261499 118.197, + 183.478 33.059898 117.023, + 186.342 28.879499 117.023, + 184.23801 33.633801 115.662, + 189.66 24.877199 115.662, + 192.93201 20.622299 110.9, + 194.608 15.6227 -110.9, + 194.842 14.775301 97.25, + 194.842 14.7753 -97.25, + 194.561 10.2553 115.662, + 195.972 5.2143598 114.158, + 194.056 15.465499 114.158, + 192.397 20.414801 114.158, + 175.867 -39.673698 -118.197, + 171.233 -41.756199 -119.149, + 156.882 -44.350601 -120.425, + 192.02499 6.3456966e-008 -119.149, + 190.30299 -4.6890903 -119.851, + 188.078 -9.0434914 -120.28, + 188.70599 -4.5411191 -120.28, + 171.743 35.148998 -120.425, + 173.937 37.556499 -119.851, + 172.85699 36.371399 -120.28, + 181.45599 31.532801 -119.149, + 178.369 35.251099 -119.149, + 176.658 -40.541302 -117.023, + 177.3 -41.244999 -115.662, + 184.23801 -33.633801 -115.662, + 184.798 -34.056702 -114.158, + 180.94501 -37.5998 -115.662, + 181.464 -38.072498 -114.158, + 192.39999 21.8279 -110.9, + 192.93201 20.622299 -110.9, + 192.442 21.846399 -97.25, + 196.54401 5.2673607 -110.9, + 139.7 -54.859001 -117.023, + 139.7 -55.694099 -115.83, + 1.7360998e-006 -55.2967 -116.459, + 1.2977815e-006 -54.326099 -117.607, + 1.0393917e-006 -54.726101 -117.134, + 185.257 34.402802 -110.9, + 188.237 30.052601 110.9, + 188.237 30.052601 -110.9, + 184.99001 34.752602 97.25, + 184.99001 34.752602 -97.25, + 181.888 38.459499 -110.9, + 185.14101 34.315601 -112.554, + 181.78101 38.362 -112.554, + 181.78101 38.362 112.554, + 185.14101 34.315601 112.554, + 178.062 42.0812 112.554, + 185.257 34.402802 110.9, + 181.888 38.459499 110.9, + 180.024 40.323799 110.9, + 178.16 42.188099 110.9, + 186.539 23.3232 -119.149, + 185.192 22.6525 -119.851, + 184.188 27.5455 -119.149, + 182.54201 32.352402 -118.197, + 192.47099 9.8645802 -118.197, + 193.15601 4.9534202 -118.197, + 187.088 18.3584 -119.851, + 190.02699 14.319399 -119.149, + 173.334 44.538399 -115.662, + 177.3 41.244999 -115.662, + 173.757 45.098301 -114.158, + 177.77299 41.763599 -114.158, + 174.951 38.668598 -119.149, + -13.426001 -47.187599 -120.306, + 139.7 -50.820099 -119.851, + -9.2832403 -49.6609 -119.954, + -13.8258 -48.592499 -119.954, + -9.0148296 -48.225101 -120.306, + -4.7894902 -51.686798 -119.376, + 1.5926508e-006 -53.187199 -118.587, + 2.0040304e-006 -52.2243 -119.181, + -4.9075003 -52.9603 -118.587, + 1.310843e-006 -51.908199 -119.376, + -9.5381107 -51.024399 -119.376, + -4.6615095 -50.305599 -119.954, + 1.0025879e-006 -50.749599 -119.859, + 157.479 -45.892899 -120.28, + 153.608 -48.8801 -119.851, + 144.38901 -50.603401 -119.851, + 139.7 -52.324902 -119.149, + 139.7 -53.685001 -118.197, + 162.35201 -45.492298 -119.851, + 158.058 -47.388401 -119.851, + 172.052 -42.841499 -118.197, + 165.082 -50.973 112.554, + 147.14301 -56.540401 110.9, + 120.851 -58.387402 93.848396, + 121.031 -58.387402 93.793404, + 120.943 -58.387402 93.824799, + -19.6248 -50.6576 117.607, + -14.5554 -51.156799 118.587, + -19.2134 -49.5956 118.587, + -14.867001 -52.252201 117.607, + -19.9755 -51.562599 116.459, + -23.7076 -47.611198 118.587, + -24.2152 -48.630699 117.607, + -24.6479 -49.499599 116.459, + -10.160699 -54.355202 116.459, + -15.1327 -53.185799 116.459, + -9.9824009 -53.4011 117.607, + -5.1021304 -55.060799 116.459, + -15.345601 -53.9342 115.174, + -15.4003 -54.1264 114.75, + -10.3037 -55.119999 115.174, + -18.7514 -48.403 119.376, + -9.2832403 -49.6609 119.954, + -14.2054 -49.926701 119.376, + -13.825799 -48.592499 119.954, + -4.7894907 -51.686798 119.376, + -9.5381098 -51.024399 119.376, + -4.66151 -50.305599 119.954, + -9.7731199 -52.281601 118.587, + -14.443999 -55.229 -90.487503, + -16.6998 -54.622601 -90.487503, + 5.3601799 -58.387402 -93.011101, + 5.3500004 -58.387402 -92.868797, + 5.2446299 -58.380299 -92.921402, + -10.608899 -56.1245 90.487503, + -10.608901 -56.1245 95.25, + -14.444001 -55.229 90.487503, + -7.6432195 -56.604698 -95.25, + 6.4568896 -58.387402 93.862999, + 6.0508804 -58.380299 93.934196, + 6.0796995 -58.387402 93.831497, + 119.894 -58.387402 -93.523598, + 121.551 -58.387402 -92.435997, + 7.22191 -58.387402 93.358398, + 44.8106 -58.387402 91.935997, + -8.7395697 -46.752602 120.425, + -9.0148306 -48.225101 120.306, + -4.3885002 -47.359501 120.425, + -13.426001 -47.187599 120.306, + -17.181499 -44.350601 120.425, + -21.200399 -42.576099 120.425, + -13.0161 -45.7467 120.425, + -35.148998 -32.042599 120.425, + -37.955601 -28.6628 120.425, + -48.225101 9.0148296 120.306, + -46.752602 8.7395697 120.425, + -48.851101 4.5267205 120.306, + -47.359501 4.3884997 120.425, + -56.034599 -5.1923695 114.75, + -56.321499 -9.3143892 95.25, + -57.0495 -2.0544105 95.25, + -56.274601 6.0758344e-007 114.75, + -55.2967 3.9192858e-007 116.459, + -55.835602 -5.1739306 115.174, + -55.060799 -5.1021299 116.459, + -56.074799 -3.301684e-007 115.174, + -54.326099 1.8792061e-008 117.607, + -55.835602 5.1739297 115.174, + -55.060799 5.102129 116.459, + -54.094398 5.0125804 117.607, + -29.110001 -47.014198 116.459, + -29.5196 -47.675701 115.174, + -29.6248 -47.845699 114.75, + 178.369 35.251099 119.149, + 181.45599 31.532801 119.149, + 182.54201 32.352402 118.197, + -53.9342 15.3456 115.174, + -54.1264 15.4003 114.75, + -55.316502 10.340401 114.75, + -55.119999 10.3037 115.174, + -54.355202 10.1607 116.459, + -52.2882 20.2565 115.174, + -50.196098 24.994699 115.174, + -45.2206 27.999399 118.587, + -48.400799 30.2694 11.8225, + -48.516998 30.082701 -13.667001, + -48.901501 29.453501 -18.5672, + -49.387798 28.630699 -23.4564, + -48.944599 29.3818 19.044701, + -48.745602 29.7108 16.740101, + -48.739201 29.7213 95.25, + -55.234001 14.375 -62.452801, + -54.761501 16.125999 -59.283699, + -54.673401 16.422199 -95.25, + -55.872898 11.660999 67.061996, + -55.439899 13.6119 -63.834, + -55.402199 13.764601 63.5695, + -55.985699 11.156699 67.8993, + -48.630699 24.2152 -117.607, + -55.2967 -1.1664019e-007 -116.459, + 139.7 -49.182499 -120.283, + 2.0764455e-006 -49.060398 -120.306, + 139.7 -47.562401 -120.425, + 139.7 -49.2164 -120.28, + 144.089 -47.359501 -120.425, + -40.147499 36.5993 -117.607, + -44.127701 33.3237 -116.459, + -47.014198 29.110001 -116.459, + 8.1077053e-007 49.060398 -120.306, + 1.091449e-006 54.326099 -117.607, + -24.2152 48.630699 -117.607, + -22.519199 45.224701 -119.954, + -31.2817 41.423698 -119.376, + -32.052399 42.444302 -118.587, + -35.832001 39.305801 -118.587, + 169.67599 48.4137 -112.554, + 169.75301 48.536701 -110.9, + 174.01601 45.4412 -112.554, + 160.27 53.0975 -112.554, + 160.32201 53.232399 -110.9, + 161.528 52.7001 -110.9, + 155.323 54.9081 -110.9, + 155.283 54.768902 -112.554, + 149.955 54.861 -115.662, + 154.97301 53.680698 -115.662, + 155.166 54.355598 -114.158, + 150.084 55.550701 -114.158, + 154.713 52.764801 -117.023, + 149.78 53.9249 -117.023, + 195.27299 -5.1496201 115.662, + 194.325 -5.061749 117.023, + 195.511 5.9291938e-007 115.662, + 192.465 -15.0129 117.023, + 190.854 -19.817301 117.023, + 189.75999 -19.3932 118.197, + 191.336 -14.6916 118.197, + 193.625 -10.0803 117.023, + 173.937 -37.556499 119.851, + 177.257 -34.237301 119.851, + 169.36 -39.275501 120.28, + 168.36301 -37.955601 120.425, + 165.60899 -41.844601 120.28, + 1.7549121e-006 -52.2243 119.181, + 171.743 -35.148998 120.425, + 178.976 -29.6595 120.28, + 176.071 -33.156898 120.28, + 172.85699 -36.371399 120.28, + 181.545 -25.9091 120.28, + 192.47099 -9.8645792 118.197, + 183.757 -21.937599 120.28, + 166.453 -43.208199 119.851, + 178.369 -35.251099 119.149, + 189.66 -24.877199 115.662, + 191.742 -20.1614 115.662, + 192.397 -20.414801 114.158, + 190.28799 -25.190001 114.158, + 192.39999 -21.8279 110.9, + 192.93201 -20.622299 110.9, + 192.442 -21.846399 97.25, + 190.80299 -25.445999 110.9, + 192.797 -20.570101 112.554, + 139.7 52.324902 119.149, + 144.38901 50.603401 119.851, + 156.882 44.350601 120.425, + 153.16901 47.337601 120.28, + 171.743 35.148998 120.425, + 168.36301 37.955601 120.425, + 164.73801 40.4384 120.425, + 186.539 23.3232 119.149, + 158.058 47.388401 119.851, + 153.608 48.8801 119.851, + 157.479 45.892899 120.28, + 177.3 41.244999 115.662, + 177.77299 41.763599 114.158, + 180.241 36.958302 117.023, + 180.94501 37.5998 115.662, + 181.464 38.072498 114.158, + 165.146 51.102501 110.9, + 169.67599 48.4137 112.554, + 169.75301 48.536701 110.9, + 154.019 50.3274 119.149, + 149.315 51.433998 119.149, + -13.0161 45.7467 120.425, + -8.7395687 46.752602 120.425, + -17.181499 44.350601 120.425, + -13.425999 47.187599 120.306, + -10.303701 55.119999 115.174, + -10.160701 54.355202 116.459, + -10.3404 55.316502 114.75, + -15.345599 53.9342 115.174, + 139.7 55.694099 115.83, + 144.85001 55.5732 115.662, + 139.7 54.859001 117.023, + 139.7 55.811298 115.662, + -4.9074993 52.9603 118.587, + -5.0125794 54.094398 117.607, + -4.7894897 51.686798 119.376, + 2.1535773e-006 53.187199 118.587, + 1.3709584e-006 53.562599 118.264, + -14.867 52.252201 117.607, + -9.9823999 53.4011 117.607, + -46.188999 28.599001 117.607, + -33.912998 44.9081 114.75, + -29.5196 47.675701 115.174, + -29.6248 47.845699 114.75, + -29.110001 47.014198 116.459, + -19.9755 51.562599 116.459, + -24.994699 50.196098 115.174, + -20.2565 52.2882 115.174, + -10.608899 56.1245 90.487503, + -10.6089 56.1245 -90.487503, + -14.444 55.229 90.487503, + -10.608901 56.1245 95.25, + -7.6432199 56.604698 95.25, + 5.2546391 58.380299 93.026199, + -16.6998 54.622601 -95.25, + -10.6089 56.1245 -95.25, + -24.994699 50.196098 -115.174, + -25.083799 50.375 -114.75, + -20.328699 52.474499 -114.75, + -33.792599 44.7486 -115.174, + -37.777302 41.4398 -115.174, + -33.3237 44.127701 -116.459, + -29.110001 47.014198 -116.459, + -29.5196 47.675701 -115.174, + -33.912998 44.9081 -114.75, + -29.6248 47.845699 -114.75, + -37.911999 41.587502 -114.75, + 1.0367662e-006 56.640999 -113.782, + -2.8908205 56.655602 -113.458, + -2.0330799 56.833801 -112.923, + 139.7 56.513 -114.158, + -1.6565499 56.904202 -112.633, + 139.7 56.942699 -112.554, + 1.2011474e-006 56.981201 -112.318, + 139.7 55.694099 -115.83, + 139.7 54.859001 -117.023, + 139.7 55.811298 -115.662, + 144.76199 54.625 -117.023, + 144.85001 55.5732 -115.662, + 6.3500004 58.380299 93.975403, + 5.2546401 58.380299 -93.026199, + 5.2745709 58.380299 -93.129601, + 5.3433805 58.380299 -93.328499, + 5.8429098 58.380299 -93.852402, + 6.2448096 58.380299 93.970398, + 5.58634 58.380299 93.669701, + 5.7318401 58.387402 93.6548, + 148.44 46.752602 -120.425, + 153.16901 47.337601 -120.28, + 165.60899 41.844601 -120.28, + 169.36 39.275501 -120.28, + 8.6224151e-007 50.521198 -119.954, + 139.7 50.820099 -119.851, + 164.89 50.588299 -114.158, + 165.082 50.973 -112.554, + 160.11501 52.6968 -114.158, + 169.45 48.048302 -114.158, + 164.153 49.1077 -117.023, + 164.577 49.960201 -115.662, + 169.08099 47.451698 -115.662, + 159.093 50.0597 -118.197, + 159.517 51.154499 -117.023, + 159.86099 52.0425 -115.662, + -52.891602 -21.4778 47.768002, + -52.847801 -21.586599 -47.5028, + -52.7127 -21.9144 46.681702, + -52.9347 -21.372601 48.0298, + -52.132099 -23.261801 95.25, + -56.673801 6.8523397 -74.3078, + -56.808899 5.4453311 76.2005, + -56.6516 7.0331597 74.054497, + -56.930599 4.2158895 77.862099, + -56.949799 3.9486203 -78.208702, + -8.7395687 -46.752602 -120.425, + 2.137348e-006 -47.562401 -120.425, + -18.250299 -47.1096 -119.954, + -18.7514 -48.403 -119.376, + -48.630699 -24.2152 -117.607, + -49.5956 -19.2134 -118.587, + -50.6576 -19.624901 -117.607, + -44.7486 -33.792599 -115.174, + -44.9081 -33.912998 -114.75, + -47.014198 -29.110001 -116.459, + -47.675701 -29.5196 -115.174, + -47.845699 -29.6248 -114.75, + 1.66924e-006 -56.640999 -113.782, + -1.6565498 -56.904202 -112.633, + -10.6089 -56.1245 -95.25, + 121.516 -58.387402 -93.368698, + 121.465 -58.387402 -93.448799, + 144.967 -56.843899 -110.9, + 154.97301 -53.680698 -115.662, + 159.86099 -52.0425 -115.662, + 155.166 -54.355598 -114.158, + 149.955 -54.861 -115.662, + -10.340399 -55.316502 114.75, + 5.277751 -58.380299 93.142403, + -48.745602 -29.7108 -16.740101, + -48.739201 -29.7213 -16.648399, + -48.739201 -29.7213 -95.25, + -48.901501 -29.453501 18.5672, + -48.099899 -30.7453 -4.4291005, + -48.170898 -30.6339 -6.9121904, + -48.1576 -30.6548 6.5188999, + 196.787 -5.9043816e-007 -110.9, + 196.54401 -5.2673593 110.9, + 196.787 -3.2476731e-008 97.25, + 194.842 -14.7753 -97.25, + 196.299 -7.4513993 -97.25, + 194.842 -14.7753 97.25, + 195.815 -10.4898 110.9, + 196.299 -7.4513993 97.25, + 173.757 45.098301 114.158, + 173.334 44.538399 115.662, + 163.02299 46.839298 119.149, + 162.35201 45.492298 119.851, + 161.638 44.056702 120.28, + 165.60899 41.844601 120.28, + 187.757 23.929399 118.197, + 194.325 5.0617495 117.023, + 187.748 29.7502 114.158, + 184.798 34.056702 114.158, + 188.114 29.9765 112.554, + 187.15199 29.380899 115.662, + 190.28799 25.190001 114.158, + 195.673 10.4632 112.554, + 195.25101 10.3842 114.158, + 194.46899 15.5831 112.554, + 194.608 15.6227 110.9, + 195.815 10.489799 110.9, + 196.39999 5.2540107 112.554, + 196.54401 5.2673593 110.9, + 174.951 -38.668598 -119.149, + 186.453 -8.7395706 -120.425, + 166.453 -43.208199 -119.851, + 164.73801 -40.4384 -120.425, + 161.638 -44.056702 -120.28, + 165.60899 -41.844601 -120.28, + 168.36301 -37.955601 -120.425, + 194.056 -15.465501 -114.158, + 191.134 -9.6146803 -119.149, + 189.655 -9.3381796 -119.851, + 190.02699 -14.3194 -119.149, + 191.742 -20.1614 -115.662, + 186.453 8.7395697 -120.425, + 178.976 29.6595 -120.28, + 177.65601 28.6628 -120.425, + 174.849 32.042599 -120.425, + 176.071 33.156898 -120.28, + 181.545 25.9091 -120.28, + 182.908 26.753401 -119.851, + 180.255 30.625999 -119.851, + 177.257 34.237301 -119.851, + 183.478 -33.059898 -117.023, + 180.241 -36.958302 -117.023, + 179.37399 -36.167301 -118.197, + 178.369 -35.251099 -119.149, + 190.28799 -25.190001 -114.158, + 190.673 -25.3815 -112.554, + 192.397 -20.414801 -114.158, + 189.66 -24.877199 -115.662, + 188.114 -29.9765 -112.554, + 187.748 -29.7502 -114.158, + 187.15199 -29.380899 -115.662, + 190.80299 25.445999 -110.9, + 194.325 5.0617495 -117.023, + 185.34399 28.261499 -118.197, + 186.342 28.879499 -117.023, + 184.05099 17.181499 -120.425, + 183.757 21.937599 -120.28, + 182.276 21.200399 -120.425, + 185.593 17.778999 -120.28, + 180.138 25.038401 -120.425, + 188.58 13.9076 -119.851, + 187.03799 13.4687 -120.28, + 188.078 9.0434904 -120.28, + 191.134 9.6146803 -119.149, + 170.326 40.555401 -119.851, + 166.453 43.208199 -119.851, + 162.35201 45.492298 -119.851, + 163.02299 46.839298 -119.149, + 163.629 48.056801 -118.197, + 172.052 42.841499 -118.197, + 168.58 46.641998 -117.023, + 167.961 45.643902 -118.197, + 172.75999 43.7784 -117.023, + 167.246 44.487499 -119.149, + 171.233 41.756199 -119.149, + 175.867 39.673698 -118.197, + -14.5554 -51.156799 -118.587, + -14.2054 -49.926701 -119.376, + -9.7731199 -52.281601 -118.587, + -9.9824009 -53.4011 -117.607, + -14.867 -52.252201 -117.607, + 148.743 -48.378399 -120.28, + 149.03799 -49.9548 -119.851, + 153.16901 -47.337601 -120.28, + 144.241 -49.0065 -120.28, + 154.019 -50.3274 -119.149, + 159.517 -51.154499 -117.023, + 149.565 -52.770901 -118.197, + 144.653 -53.455898 -118.197, + 144.76199 -54.625 -117.023, + 149.78 -53.9249 -117.023, + 144.528 -52.1017 -119.149, + 149.315 -51.433998 -119.149, + 154.392 -51.635601 -118.197, + 154.713 -52.764801 -117.023, + 163.629 -48.056801 -118.197, + 159.093 -50.0597 -118.197, + 164.153 -49.1077 -117.023, + 163.02299 -46.839298 -119.149, + 158.60201 -48.7915 -119.149, + 167.246 -44.487499 -119.149, + 167.961 -45.643902 -118.197, + 168.58 -46.641998 -117.023, + 160.11501 -52.6968 114.158, + 144.967 -56.843899 110.9, + 121.641 -58.387402 93.001503, + 121.649 -58.387402 92.904404, + 121.65 -58.387402 92.856796, + 121.565 -58.387402 93.2733, + 121.468 -58.387402 92.295303, + 121.482 -58.387402 93.4226, + 121.471 -58.387402 93.439102, + 121.522 -58.387402 93.358398, + 121.605 -58.387402 -93.160599, + 121.551 -58.387402 -93.301498, + 121.595 -58.387402 -93.195801, + 121.639 -58.387402 -93.013298, + 121.622 -58.387402 -93.1045, + 121.65 -58.387402 -92.868797, + 121.64 -58.387402 -93.011101, + 121.649 -58.387402 -92.916298, + 120.662 -58.387402 93.868698, + 120.437 -58.387402 93.844597, + 44.366798 -58.387402 93.865303, + 44.4632 -58.380299 93.975304, + 120.768 -58.380299 93.969002, + 120.663 -58.380299 93.975304, + 120.757 -58.387402 93.862999, + 121.119 -58.387402 93.752098, + 121.033 -58.387402 93.792603, + 121.201 -58.387402 93.703499, + 121.16 -58.387402 93.728798, + 139.7 -57.087399 110.9, + -17.7227 -45.747501 120.306, + -18.250299 -47.1096 119.954, + -7.6432195 -56.604698 95.25, + 5.2440801 -58.380299 92.829201, + 6.2668004 -58.387402 93.865303, + 6.1724505 -58.387402 93.852898, + 6.3618994 -58.387402 93.868698, + 6.3631706 -58.380299 93.975304, + 6.2579308 -58.380299 93.971497, + 6.1535096 -58.380299 93.957802, + 6.7216606 -58.387402 -93.797096, + 7.1057506 -58.387402 -93.523598, + -48.592499 13.8258 119.954, + -41.423698 31.2817 119.376, + -22.519199 45.224701 119.954, + -17.7227 45.747501 120.306, + -27.3262 44.133301 119.376, + -31.2817 41.423698 119.376, + -27.999399 45.2206 118.587, + -28.662701 37.955601 120.425, + -25.827 41.712002 120.306, + -26.596001 42.953999 119.954, + -21.868099 43.917099 120.306, + -30.445801 40.316799 119.954, + -34.0359 37.335602 119.954, + -29.5655 39.1511 120.306, + -32.042599 35.148998 120.425, + -49.060398 -3.5797555e-007 120.306, + -47.359501 -4.3884997 120.425, + -45.224701 -22.519199 119.954, + -41.712002 -25.827 120.306, + -39.1511 -29.5655 120.306, + -43.917099 -21.868099 120.306, + -40.4384 -25.038401 120.425, + -25.038401 -40.4384 120.425, + -28.662701 -37.955601 120.425, + -32.042599 -35.148998 120.425, + -36.2561 -33.0518 120.306, + -50.305599 4.6615 119.954, + -52.9603 4.9074888 118.587, + -52.9603 -4.9074903 118.587, + -54.094398 -5.0125799 117.607, + -52.281601 -9.7731199 118.587, + -54.673401 -16.422199 95.25, + -52.474499 -20.328699 114.75, + 175.867 39.673698 118.197, + 179.37399 36.167301 118.197, + 176.658 40.541302 117.023, + 172.75999 43.7784 117.023, + -51.562599 19.9755 116.459, + -48.630699 24.2152 117.607, + -49.499599 24.6479 116.459, + -44.133301 27.3262 119.376, + -56.264801 9.6506701 -70.236504, + -56.027 10.947299 -68.231003, + -56.321499 9.3143902 -95.25, + -56.250801 9.7323303 70.112503, + -56.321499 9.3143892 95.25, + -48.376099 30.3088 -11.394799, + -49.499599 24.6479 -116.459, + -47.611198 23.7076 -118.587, + -55.060799 5.1021304 -116.459, + -55.835602 5.1739306 -115.174, + -47.359501 -4.3885007 -120.425, + -46.752602 -8.7395697 -120.425, + -45.7467 -13.016099 -120.425, + -44.350601 -17.181499 -120.425, + -42.444302 32.052399 -118.587, + -46.188999 28.599001 -117.607, + -45.2206 27.999399 -118.587, + -43.353199 32.7388 -117.607, + -44.133301 27.3262 -119.376, + -39.305801 35.832001 -118.587, + -13.016099 45.7467 -120.425, + -17.7227 45.747501 -120.306, + -17.181499 44.350601 -120.425, + 144.089 47.359501 -120.425, + -13.825799 48.592499 -119.954, + 1.9320714e-006 50.749599 -119.859, + -9.0148287 48.225101 -120.306, + -13.426 47.187599 -120.306, + -8.7395706 46.752602 -120.425, + -4.5267296 48.851101 -120.306, + -4.6615095 50.305599 -119.954, + -4.3884997 47.359501 -120.425, + 8.3399851e-007 54.726101 -117.134, + 1.2541085e-006 55.2967 -116.459, + 195.25101 -10.384201 114.158, + 195.673 -10.4632 112.554, + 194.46899 -15.583101 112.554, + 194.056 -15.465501 114.158, + 195.972 -5.2143602 114.158, + 194.561 -10.2553 115.662, + 193.381 -15.2735 115.662, + 196.39999 -5.2540097 112.554, + 192.47099 9.8645811 118.197, + 193.38499 3.7688736e-007 118.197, + 193.15601 4.9534202 118.197, + 194.55901 2.2355269e-007 117.023, + 193.15601 -4.9534202 118.197, + 160.89999 -42.576099 120.425, + 164.73801 -40.4384 120.425, + 157.479 -45.892899 120.28, + 156.882 -44.350601 120.425, + 161.638 -44.056702 120.28, + 158.058 -47.388401 119.851, + 152.716 -45.7467 120.425, + 139.7 -49.182499 120.283, + 144.089 -47.359501 120.425, + 139.7 -47.562401 120.425, + 2.140672e-006 -49.060398 120.306, + 148.743 -48.378399 120.28, + 153.16901 -47.337601 120.28, + 148.44 -46.752602 120.425, + 144.241 -49.0065 120.28, + 2.1652324e-006 -53.562599 118.264, + 2.2970041e-006 -53.187199 118.587, + -5.0125804 -54.094398 117.607, + -4.9074998 -52.9603 118.587, + 177.65601 28.6628 120.425, + 177.65601 -28.6628 120.425, + 174.849 -32.042599 120.425, + 160.89999 42.576099 120.425, + -25.038401 40.4384 120.425, + 1.6764369e-006 -47.562401 120.425, + 184.188 27.5455 119.149, + 180.255 30.625999 119.851, + 185.192 -22.6525 119.851, + 182.908 -26.753401 119.851, + 186.539 -23.3232 119.149, + 180.255 -30.625999 119.851, + 181.45599 -31.532801 119.149, + 187.748 -29.7502 114.158, + 185.14101 -34.315601 112.554, + 188.114 -29.9765 112.554, + 167.961 -45.643902 118.197, + 163.02299 -46.839298 119.149, + 162.35201 -45.492298 119.851, + 180.241 -36.958302 117.023, + 177.3 -41.244999 115.662, + 144.653 53.455898 118.197, + 149.565 52.770901 118.197, + 144.76199 54.625 117.023, + 144.528 52.1017 119.149, + 139.7 53.685001 118.197, + 176.071 33.156898 120.28, + 174.849 32.042599 120.425, + 178.976 29.6595 120.28, + 182.908 26.753401 119.851, + 181.545 25.9091 120.28, + 185.192 22.6525 119.851, + 169.45 48.048302 114.158, + 169.08099 47.451698 115.662, + 159.093 50.0597 118.197, + 154.392 51.635601 118.197, + 158.60201 48.7915 119.149, + 159.517 51.154499 117.023, + 164.153 49.1077 117.023, + 154.713 52.764801 117.023, + 139.7 56.513 114.158, + -5.1021304 55.060799 116.459, + 1.5853864e-006 55.2967 116.459, + 139.7 56.942699 112.554, + -23.137501 46.4664 119.376, + -14.2054 49.926701 119.376, + -9.773119 52.281601 118.587, + -9.5381098 51.024399 119.376, + -14.5554 51.156799 118.587, + -19.2134 49.5956 118.587, + -18.7514 48.403 119.376, + -9.2832403 49.6609 119.954, + -13.8258 48.592499 119.954, + -18.250299 47.1096 119.954, + -5.9906502 56.020401 114.594, + -7.1774507 55.820099 114.739, + -44.7486 33.792599 115.174, + -44.9081 33.912998 114.75, + -41.587502 37.911999 114.75, + -47.845699 29.6248 114.75, + -47.675701 29.5196 115.174, + -47.014198 29.110001 116.459, + -24.2152 48.630699 117.607, + -23.7076 47.611198 118.587, + -28.599001 46.188999 117.607, + -24.6479 49.499599 116.459, + -19.6248 50.6576 117.607, + -1.3080804 56.957802 112.317, + 5.274569 58.380299 93.129601, + -0.84870821 57.0284 111.9, + -1.6565498 56.904202 112.633, + 1.3832852e-006 56.981201 112.318, + 5.3511305 58.387402 92.916298, + 5.3500004 58.387402 92.868797, + 5.2446294 58.380299 92.921402, + 5.3601794 58.387402 93.011101, + -19.9755 51.562599 -116.459, + -24.6479 49.499599 -116.459, + -20.2565 52.2882 -115.174, + -15.400301 54.1264 -114.75, + -3.4993205 56.527 -113.781, + 1.5590156e-006 56.074799 -115.174, + -3.19561 56.5923 -113.648, + -4.4654303 56.319199 -114.204, + -0.70178246 57.0453 -111.747, + 5.7300897 58.387402 -93.653297, + 5.6659298 58.380299 -93.738602, + 121.649 58.387402 -92.916298, + 121.649 58.387402 -92.821198, + 82.550003 58.380299 -93.975403, + 5.4403701 58.387402 92.4533, + 5.3511305 58.387402 92.821198, + 5.6195593 58.387402 92.187302, + 5.3499999 58.387402 -92.868797, + 5.2446303 58.380299 -92.921402, + 5.36062 58.387402 -93.013298, + 5.3601799 58.387402 -93.011101, + 5.35113 58.387402 -92.916298, + 5.4050012 58.387402 -93.195801, + 5.3042302 58.380299 -93.230698, + 5.809361 58.387402 -93.709999, + 5.7517099 58.380299 -93.799698, + 5.6195598 58.387402 -93.550201, + 5.7318401 58.387402 -93.6548, + 5.6599207 58.387402 -93.592499, + 5.5942512 58.387402 -93.523598, + 5.586339 58.380299 -93.669701, + 5.5136695 58.380299 -93.593399, + 5.5248904 58.387402 -93.432404, + 5.4403706 58.387402 -93.284203, + 5.3781905 58.387402 -93.1045, + 5.4839702 58.387402 -93.368698, + 5.3916306 58.380299 -93.422096, + 5.4485693 58.380299 -93.510696, + 5.9783411 58.387402 93.797096, + 5.9387107 58.380299 93.896103, + 6.0682707 58.387402 93.828201, + 5.9805193 58.387402 93.797897, + 6.2744093 58.387402 93.865196, + 6.2549405 58.387402 93.864197, + 6.1607504 58.387402 93.8507, + 6.0382299 58.380299 93.930496, + 6.1405697 58.380299 93.955399, + 5.3781896 58.387402 93.1045, + 5.8499994 58.387402 93.734802, + 5.8093605 58.387402 93.709999, + 5.7517104 58.380299 93.799698, + 5.8429093 58.380299 93.852402, + 160.89999 42.576099 -120.425, + 156.882 44.350601 -120.425, + 161.638 44.056702 -120.28, + 164.73801 40.4384 -120.425, + 168.36301 37.955601 -120.425, + 152.716 45.7467 -120.425, + -17.181499 -44.350601 -120.425, + -13.0161 -45.7467 -120.425, + -17.7227 -45.747501 -120.306, + -21.200399 -42.576099 -120.425, + -19.2134 -49.5956 -118.587, + -35.148998 -32.042599 -120.425, + -15.132699 -53.185799 -116.459, + -20.328699 -52.474499 -114.75, + -15.4003 -54.1264 -114.75, + -21.3706 -52.935501 -95.25, + -16.6998 -54.622601 -95.25, + 82.550003 -58.380299 -93.975403, + -2.8908205 -56.655602 113.458, + -2.0330794 -56.833801 112.923, + -3.4993193 -56.527 113.781, + -3.1956103 -56.5923 113.648, + -4.4654303 -56.319199 114.204, + -48.121498 -30.711399 5.3098207, + -48.050701 -30.8221 0.43807036, + -48.125999 -30.704399 5.4595308, + 195.673 -10.463199 -112.554, + 195.25101 -10.3842 -114.158, + 194.46899 -15.5831 -112.554, + 194.608 -15.6227 -110.9, + 195.815 -10.4898 -110.9, + 196.39999 -5.2540102 -112.554, + 196.54401 -5.2673597 -110.9, + 167.961 45.643902 118.197, + 172.052 42.841499 118.197, + 168.58 46.641998 117.023, + 163.629 48.056801 118.197, + 177.257 34.237301 119.851, + 188.808 24.4527 117.023, + 191.742 20.1614 115.662, + 182.276 -21.200399 -120.425, + 180.138 -25.038401 -120.425, + 160.89999 -42.576099 -120.425, + 148.44 -46.752602 -120.425, + 185.44701 13.016099 -120.425, + 185.44701 -13.0161 -120.425, + 172.85699 -36.371399 -120.28, + 171.743 -35.148998 -120.425, + 169.36 -39.275501 -120.28, + 173.937 -37.556499 -119.851, + 170.326 -40.555401 -119.851, + 193.625 -10.080299 -117.023, + 193.381 -15.2735 -115.662, + 193.15601 -4.9534202 -118.197, + 192.47099 -9.8645792 -118.197, + 191.802 -4.82793 -119.149, + 193.38499 -3.415748e-007 -118.197, + 188.58 -13.907599 -119.851, + 189.75999 -19.3932 -118.197, + 192.465 -15.0129 -117.023, + 191.336 -14.6916 -118.197, + 190.854 -19.817301 -117.023, + 188.492 -18.901899 -119.149, + 186.539 -23.3232 -119.149, + 181.45599 -31.532801 -119.149, + 185.192 -22.6525 -119.851, + 195.27299 5.149621 -115.662, + 196.213 1.712768e-007 -114.158, + 196.64301 5.9974161e-007 -112.554, + 195.27299 -5.149621 -115.662, + 194.325 -5.0617499 -117.023, + 194.55901 5.1433034e-007 -117.023, + 195.511 7.2298428e-007 -115.662, + 195.972 -5.2143607 -114.158, + 194.561 -10.2553 -115.662, + 190.30299 4.6890893 -119.851, + 191.802 4.8279309 -119.149, + 190.52 2.666367e-007 -119.851, + 189.655 9.3381786 -119.851, + 188.70599 4.5411201 -120.28, + 154.97301 -53.680698 115.662, + 160.27 -53.0975 112.554, + 155.323 -54.9081 110.9, + 158.60201 -48.7915 119.149, + 1.4581352e-006 -56.640999 113.782, + 139.7 -56.942699 112.554, + 2.2810207e-006 -56.074799 115.174, + 121.609 -58.387402 93.1492, + 121.599 -58.387402 93.184502, + 121.625 -58.387402 93.092903, + 121.641 -58.387402 92.999298, + 121.388 -58.387402 93.541397, + 121.413 -58.387402 93.514603, + 121.349 -58.387402 93.584198, + 121.279 -58.387402 93.645897, + 121.277 -58.387402 93.6474, + -26.596001 -42.953999 119.954, + -27.3262 -44.133301 119.376, + -23.137501 -46.4664 119.376, + -22.519199 -45.224701 119.954, + -29.5655 -39.1511 120.306, + -25.827 -41.712002 120.306, + -21.868099 -43.917099 120.306, + 5.2565899 -58.380299 93.039299, + 5.3619394 -58.387402 93.022797, + 5.2453303 -58.380299 92.934601, + 5.3500695 -58.387402 92.880699, + 5.35113 -58.387402 -92.916298, + 5.3606205 -58.387402 -93.013298, + 5.30861 -58.380299 93.243103, + 5.3810606 -58.387402 93.116096, + 5.5223494 -58.380299 93.603302, + 5.3624101 -58.387402 93.025101, + 5.3517694 -58.387402 92.9282, + 5.3589706 -58.387402 92.736, + 5.8546491 -58.380299 93.858299, + 5.90238 -58.387402 93.763, + 5.9509597 -58.380299 93.900902, + 5.9894099 -58.387402 93.801498, + 5.6763306 -58.380299 93.746696, + 6.7326899 -58.387402 93.792603, + 5.8194094 -58.387402 93.7164, + 5.7628293 -58.380299 93.806801, + 5.8603406 -58.387402 93.7407, + 5.7412395 -58.387402 93.662102, + 5.440371 -58.387402 -93.284203, + 5.4839702 -58.387402 -93.368698, + 5.3916292 -58.380299 -93.422096, + 121.406 -58.387402 -93.523598, + 121.27 -58.387402 -93.653297, + 121.34 -58.387402 -93.592499, + 6.6317306 -58.387402 -93.828201, + 6.1607494 -58.387402 -93.8507, + 6.2448111 -58.380299 -93.970398, + 6.2549405 -58.387402 -93.864197, + 6.1405697 -58.380299 -93.955399, + -45.747501 17.7227 120.306, + -47.1096 18.250299 119.954, + -45.224701 22.519199 119.954, + -43.917099 21.868099 120.306, + -47.187599 13.426 120.306, + -45.7467 13.0161 120.425, + -44.350601 17.181499 120.425, + -42.576099 21.200399 120.425, + -40.316799 30.445801 119.954, + -42.953999 26.596001 119.954, + -41.712002 25.827 120.306, + -40.4384 25.038401 120.425, + -46.752602 -8.7395687 120.425, + -44.350601 -17.181499 120.425, + -45.7467 -13.016101 120.425, + -42.576099 -21.200399 120.425, + -45.747501 -17.7227 120.306, + -33.0518 -36.2561 120.306, + -42.953999 -26.596001 119.954, + -51.908199 8.1534944e-007 119.376, + -53.187199 -5.916628e-007 118.587, + -51.024399 9.5381107 119.376, + -51.686798 4.7894897 119.376, + -49.6609 9.2832403 119.954, + -47.187599 -13.426001 120.306, + -51.686798 -4.7894902 119.376, + -48.851101 -4.52672 120.306, + -50.521198 -5.8616382e-007 119.954, + -51.562599 -19.9755 116.459, + -32.7388 -43.353199 117.607, + -39.633301 -41.086201 95.25, + -33.912998 -44.9081 114.75, + -34.068901 -45.805901 95.25, + -52.252201 -14.867001 117.607, + -51.156799 -14.5554 118.587, + -53.4011 -9.9823999 117.607, + -53.9342 -15.3456 115.174, + -55.119999 -10.3037 115.174, + -54.355202 -10.160699 116.459, + -53.185799 -15.132699 116.459, + -55.316502 -10.340401 114.75, + -54.1264 -15.400299 114.75, + -48.403 -18.7514 119.376, + -47.1096 -18.250299 119.954, + -52.281601 9.7731199 118.587, + -49.5956 19.2134 118.587, + -47.611198 23.7076 118.587, + -46.4664 23.137501 119.376, + -48.403 18.7514 119.376, + -49.926701 14.2054 119.376, + -48.099899 30.7453 4.4291, + -48.170898 30.6339 6.912189, + -48.1576 30.6548 -6.5189009, + -43.917099 -21.868099 -120.306, + -42.576099 -21.200399 -120.425, + -47.1096 -18.250299 -119.954, + -48.592499 -13.8258 -119.954, + -47.187599 -13.425999 -120.306, + -45.747501 -17.7227 -120.306, + -45.224701 -22.519199 -119.954, + -48.403 -18.7514 -119.376, + -49.926701 -14.2054 -119.376, + -51.562599 19.9755 -116.459, + -41.712002 25.827 -120.306, + -21.200399 42.576099 -120.425, + -46.4664 23.137501 -119.376, + -52.281601 -9.7731199 -118.587, + -18.250299 47.1096 -119.954, + -9.5381098 51.024399 -119.376, + -9.2832413 49.6609 -119.954, + -9.7731199 52.281601 -118.587, + 1.0069649e-006 53.187199 -118.587, + -4.7894897 51.686798 -119.376, + -4.9074998 52.9603 -118.587, + 1.494239e-006 53.562599 -118.264, + 2.3179168e-006 51.908199 -119.376, + 139.7 52.324902 -119.149, + 139.7 53.685001 -118.197, + -14.866999 52.252201 -117.607, + -10.3404 55.316502 -114.75, + -10.1607 54.355202 -116.459, + -9.9823999 53.4011 -117.607, + -5.0125799 54.094398 -117.607, + -5.1021299 55.060799 -116.459, + -15.1327 53.185799 -116.459, + -10.303701 55.119999 -115.174, + -15.3456 53.9342 -115.174, + 139.7 -50.820099 119.851, + 1.6935586e-006 -50.521198 119.954, + 1.3637299e-006 -50.749599 119.859, + 139.7 -49.2164 120.28, + 1.690211e-006 -51.908199 119.376, + 2.3504181e-006 -54.726101 117.134, + 1.1577818e-006 -54.326099 117.607, + 139.7 -56.513 114.158, + 144.914 -56.2719 114.158, + 154.019 -50.3274 119.149, + 149.03799 -49.9548 119.851, + 153.608 -48.8801 119.851, + 149.955 -54.861 115.662, + 185.34399 -28.261499 118.197, + 186.342 -28.879499 117.023, + 182.54201 -32.352402 118.197, + 184.188 -27.5455 119.149, + 187.757 -23.929399 118.197, + 188.808 -24.4527 117.023, + 188.492 -18.901899 119.149, + 190.02699 -14.3194 119.149, + 191.134 -9.6146803 119.149, + 192.02499 5.7436415e-007 119.149, + 184.23801 -33.633801 115.662, + 180.94501 -37.5998 115.662, + 181.464 -38.072498 114.158, + 184.798 -34.056702 114.158, + 183.478 -33.059898 117.023, + 187.15199 -29.380899 115.662, + 179.37399 -36.167301 118.197, + 176.658 -40.541302 117.023, + 172.75999 -43.7784 117.023, + 171.233 -41.756199 119.149, + 172.052 -42.841499 118.197, + 167.246 -44.487499 119.149, + 170.326 -40.555401 119.851, + 174.951 -38.668598 119.149, + 175.867 -39.673698 118.197, + 173.334 -44.538399 115.662, + 173.757 -45.098301 114.158, + 169.45 -48.048302 114.158, + 164.89 -50.588299 114.158, + 164.153 -49.1077 117.023, + 168.58 -46.641998 117.023, + 163.629 -48.056801 118.197, + 169.08099 -47.451698 115.662, + 164.577 -49.960201 115.662, + 159.517 -51.154499 117.023, + 159.86099 -52.0425 115.662, + 159.093 -50.0597 118.197, + 190.02699 14.3194 119.149, + 188.492 18.901899 119.149, + 185.593 17.778999 120.28, + 187.088 18.3584 119.851, + 183.757 21.937599 120.28, + 184.05099 17.181499 120.425, + 191.134 9.6146803 119.149, + 188.58 13.9076 119.851, + 187.03799 13.468699 120.28, + 164.577 49.960201 115.662, + 164.89 50.588299 114.158, + -4.0567598 56.406101 114.049, + 2.0335542e-006 56.640999 113.782, + -2.8025196 56.676498 113.428, + 1.5300262e-006 56.074799 115.174, + -37.777302 41.4398 115.174, + -33.792599 44.7486 115.174, + -37.911999 41.587502 114.75, + -33.3237 44.127701 116.459, + -41.4398 37.777302 115.174, + -5.2046895 56.170898 -114.414, + -7.6432195 55.753201 -114.75, + -6.2480607 55.971699 -114.647, + -4.88587 56.2318 -114.342, + -5.1739306 55.835602 -115.174, + 120.65 58.380299 93.975403, + 120.755 58.380299 93.970398, + 5.3511295 58.387402 -92.821198, + 120.555 58.387402 -93.864197, + 121.56 58.387402 -93.284203, + 121.622 58.387402 93.1045, + 121.64 58.387402 93.011101, + 121.022 58.387402 93.797096, + 121.108 58.387402 93.757599, + 6.1405702 58.380299 -93.955399, + 6.2448101 58.380299 -93.970398, + 44.545101 58.387402 -93.864197, + 82.625603 58.387402 -93.865196, + 5.4839706 58.387402 93.368698, + 5.5942502 58.387402 93.523598, + 5.7300901 58.387402 93.653297, + 5.6599197 58.387402 93.592499, + 5.6195602 58.387402 93.550201, + 5.5248899 58.387402 93.432404, + 5.5354295 58.387402 93.448799, + 5.5136709 58.380299 93.593399, + 5.4485703 58.380299 93.510696, + 5.4403701 58.387402 93.284203, + 5.4050007 58.387402 93.195801, + 5.4492993 58.387402 93.301498, + 5.3433809 58.380299 93.328499, + 5.3916297 58.380299 93.422096, + 5.3042297 58.380299 93.230698, + -23.7076 -47.611198 -118.587, + -32.052399 -42.444302 -118.587, + -27.999399 -45.2206 -118.587, + -28.662701 -37.955601 -120.425, + -25.038401 -40.4384 -120.425, + -39.1511 -29.5655 -120.306, + -41.712002 -25.827 -120.306, + -37.955601 -28.6628 -120.425, + -40.4384 -25.038401 -120.425, + -2.8025196 -56.676498 -113.428, + -5.1021299 -55.060799 -116.459, + -19.6248 -50.6576 -117.607, + -24.2152 -48.630699 -117.607, + -19.9755 -51.562599 -116.459, + 44.450001 -58.387402 -93.868698, + 6.2744093 -58.387402 -93.865196, + 6.3499994 -58.387402 -93.868698, + 6.3500004 -58.380299 -93.975403, + 6.4450588 -58.387402 -93.864197, + 82.625603 -58.387402 -93.865196, + 82.739304 -58.387402 -93.8507, + 82.550003 -58.387402 -93.868698, + 44.545101 -58.387402 -93.864197, + 121.38 -58.387402 -93.550201, + 121.268 -58.387402 -93.6548, + 121.191 -58.387402 -93.709999, + 120.574 -58.387402 -93.865196, + -5.2046895 -56.170898 114.414, + -6.2480602 -55.971699 114.647, + -5.1739302 -55.835602 115.174, + -4.8858705 -56.2318 114.342, + -7.6432204 -55.753201 114.75, + 170.326 40.555401 119.851, + 171.233 41.756199 119.149, + 167.246 44.487499 119.149, + 166.453 43.208199 119.851, + 174.951 38.668598 119.149, + 173.937 37.556499 119.851, + 169.36 39.275501 120.28, + 172.85699 36.371399 120.28, + 192.465 15.0129 117.023, + 190.854 19.817301 117.023, + 193.381 15.273499 115.662, + 193.625 10.0803 117.023, + 191.336 14.6916 118.197, + 189.75999 19.3932 118.197, + 178.976 -29.6595 -120.28, + 182.908 -26.753401 -119.851, + 181.545 -25.9091 -120.28, + 180.255 -30.625999 -119.851, + 177.65601 -28.6628 -120.425, + 177.257 -34.237301 -119.851, + 176.071 -33.156898 -120.28, + 174.849 -32.042599 -120.425, + 185.593 -17.778999 -120.28, + 187.088 -18.3584 -119.851, + 187.03799 -13.4687 -120.28, + 183.757 -21.937599 -120.28, + 184.05099 -17.181499 -120.425, + 187.26199 2.1023168e-007 -120.425, + 187.06 4.3884993 -120.425, + 188.916 -1.9217717e-007 -120.28, + 187.26199 1.5681734e-007 -120.425, + 187.06 -4.3885002 -120.425, + 185.34399 -28.261499 -118.197, + 184.188 -27.5455 -119.149, + 187.757 -23.929399 -118.197, + 188.808 -24.4527 -117.023, + 186.342 -28.879499 -117.023, + 182.54201 -32.352402 -118.197, + 187.748 29.7502 -114.158, + 187.15199 29.380899 -115.662, + 188.114 29.9765 -112.554, + 184.798 34.056702 -114.158, + 192.397 20.414801 -114.158, + 190.673 25.3815 -112.554, + 192.797 20.570101 -112.554, + 190.28799 25.190001 -114.158, + 189.66 24.877199 -115.662, + 191.742 20.1614 -115.662, + 195.25101 10.3842 -114.158, + 195.972 5.2143598 -114.158, + 194.561 10.2553 -115.662, + 196.39999 5.2540112 -112.554, + 195.673 10.4632 -112.554, + 194.46899 15.5831 -112.554, + 194.056 15.465501 -114.158, + 193.381 15.2735 -115.662, + 193.625 10.080301 -117.023, + 189.75999 19.3932 -118.197, + 191.336 14.6916 -118.197, + 188.492 18.901899 -119.149, + 187.757 23.929399 -118.197, + 192.465 15.0129 -117.023, + 190.854 19.817301 -117.023, + 188.808 24.4527 -117.023, + 150.16299 -55.973099 112.554, + 144.95399 -56.699799 112.554, + 150.19 -56.115398 110.9, + 150.084 -55.550701 114.158, + 154.468 -55.109299 110.9, + 155.283 -54.768902 112.554, + 155.166 -54.355598 114.158, + 5.4562693 -58.380299 93.521301, + -0.70178348 -57.0453 111.747, + 5.6685801 -58.387402 93.600601, + 5.5959201 -58.380299 93.678703, + 5.6020999 -58.387402 93.5326, + 5.7394695 -58.387402 93.660599, + 5.7517109 -58.380299 -93.799698, + 5.8093596 -58.387402 -93.709999, + 5.6659303 -58.380299 -93.738602, + 5.8499994 -58.387402 -93.734802, + -36.2561 33.0518 120.306, + -33.0518 36.2561 120.306, + -37.335602 34.0359 119.954, + -39.1511 29.5655 120.306, + -35.148998 32.042599 120.425, + -37.955601 28.6628 120.425, + -30.445801 -40.316799 119.954, + -31.2817 -41.423698 119.376, + -34.0359 -37.335602 119.954, + -32.052399 -42.444302 118.587, + -49.6609 -9.2832413 119.954, + -50.305599 -4.6614995 119.954, + -51.024399 -9.5381107 119.376, + -49.926701 -14.2054 119.376, + -48.592499 -13.8258 119.954, + -48.225101 -9.0148296 120.306, + -52.2882 -20.2565 115.174, + -50.375 -25.083799 114.75, + -44.550098 -35.695301 95.25, + -48.739201 -29.7213 95.25, + -44.9081 -33.912998 114.75, + -41.587502 -37.911999 114.75, + -52.252201 14.867 117.607, + -53.185799 15.132701 116.459, + -53.4011 9.9823999 117.607, + -51.156799 14.555401 118.587, + -50.6576 19.624901 117.607, + -48.121498 30.711399 -5.3098197, + -48.739201 29.7213 -95.25, + -48.050701 30.8221 -0.4380694, + -48.125999 30.704399 -5.4595304, + -53.9342 15.345599 -115.174, + -54.1264 15.4003 -114.75, + -52.2882 20.2565 -115.174, + -55.316502 10.340399 -114.75, + -55.119999 10.3037 -115.174, + -54.355202 10.1607 -116.459, + -52.252201 14.866999 -117.607, + -53.185799 15.1327 -116.459, + -50.6576 19.624901 -117.607, + -53.4011 9.9823999 -117.607, + -28.662701 37.955601 -120.425, + -32.042599 35.148998 -120.425, + -30.445801 40.316799 -119.954, + -37.955601 28.6628 -120.425, + -40.4384 25.038401 -120.425, + -35.148998 32.042599 -120.425, + -42.953999 26.596001 -119.954, + -41.423698 31.2817 -119.376, + -47.359501 4.3884997 -120.425, + -46.752602 8.7395687 -120.425, + -48.403 18.7514 -119.376, + -51.156799 14.555399 -118.587, + -49.5956 19.2134 -118.587, + -52.9603 -4.9074893 -118.587, + -54.094398 -5.0125804 -117.607, + -54.326099 6.6414441e-007 -117.607, + -54.094398 5.0125799 -117.607, + -19.2134 49.5956 -118.587, + -14.205401 49.926701 -119.376, + -14.555401 51.156799 -118.587, + -18.7514 48.403 -119.376, + -19.6248 50.6576 -117.607, + -23.7076 47.611198 -118.587, + -23.137501 46.4664 -119.376, + 139.7 -55.694099 115.83, + 139.7 -54.859001 117.023, + 144.85001 -55.5732 115.662, + 139.7 -55.811298 115.662, + 1.7990044e-006 -55.2967 116.459, + 149.78 -53.9249 117.023, + 154.392 -51.635601 118.197, + 154.713 -52.764801 117.023, + 144.38901 -50.603401 119.851, + 139.7 -52.324902 119.149, + 149.315 -51.433998 119.149, + 191.802 -4.82793 119.149, + 185.593 -17.778999 120.28, + 187.088 -18.3584 119.851, + 188.58 -13.9076 119.851, + 190.30299 4.6890893 119.851, + 191.802 4.8279305 119.149, + 189.655 9.3381796 119.851, + 154.97301 53.680698 115.662, + 159.86099 52.0425 115.662, + 150.16299 55.973099 112.554, + 150.084 55.550701 114.158, + 149.955 54.861 115.662, + 160.27 53.0975 112.554, + 160.11501 52.6968 114.158, + 165.082 50.973 112.554, + 161.528 52.7001 110.9, + 160.32201 53.232399 110.9, + 155.323 54.9081 110.9, + 155.283 54.768902 112.554, + 155.166 54.355598 114.158, + -5.2046103 56.1716 114.407, + -7.6432209 55.753201 114.75, + -5.8064594 56.051498 114.571, + -4.4654293 56.319199 114.204, + -5.1739302 55.835602 115.174, + -32.7388 43.353199 117.607, + -32.052399 42.444302 118.587, + -34.970402 38.360699 119.376, + -44.127701 33.3237 116.459, + -40.8647 37.253101 116.459, + -36.5993 40.147499 117.607, + -37.253101 40.8647 116.459, + 121.551 58.387402 93.301498, + 121.465 58.387402 93.448799, + 121.516 58.387402 93.368698, + 121.56 58.387402 93.284203, + 82.550003 58.387402 93.868698, + 6.3500004 58.387402 93.868698, + 120.65 58.387402 93.868698, + 44.374401 58.387402 93.865196, + 5.8917704 58.387402 93.757599, + 7.1751099 58.387402 92.305099, + 6.5748906 58.387402 -93.842003, + 121.465 58.387402 -93.448799, + 121.551 58.387402 -93.301498, + 121.516 58.387402 -93.368698, + 121.406 58.387402 -93.523598, + 121.108 58.387402 -93.757599, + 120.726 58.387402 -93.865196, + 120.839 58.387402 -93.8507, + 120.745 58.387402 -93.864197, + 120.65 58.387402 -93.868698, + 120.65 58.380299 -93.975403, + 120.755 58.380299 -93.970398, + 121.605 58.387402 -93.160599, + 121.622 58.387402 -93.1045, + 121.64 58.387402 -93.011101, + 121.595 58.387402 -93.195801, + 121.65 58.387402 92.868797, + 121.595 58.387402 93.195801, + 121.639 58.387402 93.013298, + 121.649 58.387402 92.916298, + 144.967 56.843899 110.9, + 121.65 58.387402 -92.868797, + 144.967 56.843899 -110.9, + 121.15 58.387402 93.734802, + 6.1607494 58.387402 -93.8507, + 5.9805202 58.387402 -93.797897, + 5.8500004 58.387402 -93.734802, + 5.8917704 58.387402 -93.757599, + 5.9783401 58.387402 -93.797096, + 6.1251106 58.387402 -93.842003, + 6.0682707 58.387402 -93.828201, + 5.5354304 58.387402 -93.448799, + 5.9387102 58.380299 -93.896103, + 6.0382304 58.380299 -93.930496, + 6.3499994 58.387402 -93.868698, + 6.2744088 58.387402 -93.865196, + 6.3500004 58.380299 -93.975403, + 6.4255905 58.387402 -93.865196, + 44.450001 58.387402 -93.868698, + 6.25494 58.387402 -93.864197, + 44.450001 58.380299 -93.975403, + -26.596001 -42.953999 -119.954, + -31.2817 -41.423698 -119.376, + -27.3262 -44.133301 -119.376, + -23.137501 -46.4664 -119.376, + -22.519199 -45.224701 -119.954, + -21.868099 -43.917099 -120.306, + -25.827 -41.712002 -120.306, + -28.599001 -46.188999 -117.607, + -44.127701 -33.3237 -116.459, + -36.5993 -40.147499 -117.607, + -35.832001 -39.305801 -118.587, + -40.147499 -36.5993 -117.607, + -32.7388 -43.353199 -117.607, + -41.4398 -37.777302 -115.174, + -40.8647 -37.253101 -116.459, + -37.253101 -40.8647 -116.459, + -33.3237 -44.127701 -116.459, + -32.042599 -35.148998 -120.425, + -4.0567589 -56.406101 -114.049, + 1.8894834e-006 -56.074799 -115.174, + -5.9906507 -56.020401 -114.594, + -7.1774502 -55.820099 -114.739, + -10.3037 -55.119999 -115.174, + -10.1607 -54.355202 -116.459, + -10.3404 -55.316502 -114.75, + -15.345599 -53.9342 -115.174, + -20.2565 -52.2882 -115.174, + -25.083799 -50.375 -114.75, + -24.6479 -49.499599 -116.459, + 120.65 -58.387402 -93.868698, + 120.755 -58.380299 -93.970398, + 120.65 -58.380299 -93.975403, + 120.745 -58.387402 -93.864197, + 120.726 -58.387402 -93.865196, + 120.875 -58.387402 -93.842003, + 120.839 -58.387402 -93.8507, + 120.932 -58.387402 -93.828201, + 5.5423803 -58.387402 93.458504, + 5.5136695 -58.380299 -93.593399, + 6.0682707 -58.387402 -93.828201, + 5.8917704 -58.387402 -93.757599, + 5.9387093 -58.380299 -93.896103, + 5.9783392 -58.387402 -93.797096, + 5.8429108 -58.380299 -93.852402, + -0.84870952 -57.0284 -111.9, + 6.0382304 -58.380299 -93.930496, + 5.9805198 -58.387402 -93.797897, + -38.360699 -34.970402 119.376, + -34.970402 -38.360699 119.376, + -37.335602 -34.0359 119.954, + -40.316799 -30.445801 119.954, + -41.423698 -31.2817 119.376, + -35.832001 -39.305801 118.587, + -49.499599 -24.6479 116.459, + -42.444302 -32.052399 118.587, + -47.611198 -23.7076 118.587, + -45.2206 -27.999399 118.587, + -44.133301 -27.3262 119.376, + -46.4664 -23.137501 119.376, + -46.188999 -28.599001 117.607, + -48.630699 -24.2152 117.607, + -49.5956 -19.2134 118.587, + -50.6576 -19.624901 117.607, + -37.777302 -41.4398 115.174, + -41.4398 -37.777302 115.174, + -37.911999 -41.587502 114.75, + -33.792599 -44.7486 115.174, + -37.253101 -40.8647 116.459, + -33.3237 -44.127701 116.459, + -47.675701 -29.5196 115.174, + -44.7486 -33.792599 115.174, + -47.014198 -29.110001 116.459, + -47.845699 -29.6248 114.75, + -50.196098 -24.994699 115.174, + -40.147499 -36.5993 117.607, + -36.5993 -40.147499 117.607, + -39.305801 -35.832001 118.587, + -40.8647 -37.253101 116.459, + -43.353199 -32.7388 117.607, + -44.127701 -33.3237 116.459, + -25.827 41.712002 -120.306, + -25.038401 40.4384 -120.425, + -21.868099 43.917099 -120.306, + -29.5655 39.1511 -120.306, + -26.596001 42.953999 -119.954, + -37.335602 34.0359 -119.954, + -39.1511 29.5655 -120.306, + -36.2561 33.0518 -120.306, + -40.316799 30.445801 -119.954, + -33.0518 36.2561 -120.306, + -34.0359 37.335602 -119.954, + -38.360699 34.970402 -119.376, + -34.970402 38.360699 -119.376, + -47.562401 1.4275354e-008 -120.425, + -45.747501 17.7227 -120.306, + -47.187599 13.426 -120.306, + -47.1096 18.250299 -119.954, + -45.224701 22.519199 -119.954, + -43.917099 21.868099 -120.306, + -42.576099 21.200399 -120.425, + -44.350601 17.181499 -120.425, + -45.7467 13.0161 -120.425, + 144.653 -53.455898 118.197, + 149.565 -52.770901 118.197, + 144.76199 -54.625 117.023, + 144.528 -52.1017 119.149, + 139.7 -53.685001 118.197, + 190.30299 -4.6890898 119.851, + 189.655 -9.3381796 119.851, + 188.078 -9.0434904 120.28, + 187.03799 -13.4687 120.28, + 185.44701 -13.016101 120.425, + 184.05099 -17.181499 120.425, + -39.305801 35.832001 118.587, + -35.832001 39.305801 118.587, + -38.360699 34.970402 119.376, + -40.147499 36.5993 117.607, + -42.444302 32.052399 118.587, + -43.353199 32.7388 117.607, + 120.839 58.387402 93.8507, + 120.574 58.387402 93.865196, + 120.932 58.387402 93.828201, + 120.726 58.387402 93.865196, + 120.875 58.387402 93.842003, + 120.745 58.387402 93.864197, + 120.03 58.387402 92.084198, + 43.624901 58.387402 93.432404, + 82.739304 58.387402 -91.886803, + 120.368 58.387402 93.828201, + 119.651 58.387402 -92.821198, + 121.649 58.387402 92.821198, + 120.932 58.387402 -93.828201, + 120.875 58.387402 -93.842003, + 121.022 58.387402 -93.797096, + 121.38 58.387402 -93.550201, + 121.34 58.387402 -93.592499, + 121.191 58.387402 -93.709999, + 121.268 58.387402 -93.6548, + 139.7 57.087399 -110.9, + 121.15 58.387402 -93.734802, + 121.27 58.387402 -93.653297, + 121.34 58.387402 93.592499, + 121.019 58.387402 93.797897, + 121.38 58.387402 93.550201, + 121.191 58.387402 93.709999, + 121.268 58.387402 93.6548, + 121.27 58.387402 93.653297, + 139.7 57.087399 110.9, + 121.406 58.387402 93.523598, + -43.353199 -32.7388 -117.607, + -46.188999 -28.599001 -117.607, + -39.305801 -35.832001 -118.587, + -29.5196 -47.675701 -115.174, + -29.6248 -47.845699 -114.75, + -29.110001 -47.014198 -116.459, + -24.994699 -50.196098 -115.174, + -37.911999 -41.587502 -114.75, + -33.912998 -44.9081 -114.75, + -33.792599 -44.7486 -115.174, + -37.777302 -41.4398 -115.174, + -39.633301 -41.086201 -95.25, + -34.068901 -45.805901 -95.25, + -41.587502 -37.911999 -114.75, + -34.0359 -37.335602 -119.954, + -37.335602 -34.0359 -119.954, + -36.2561 -33.0518 -120.306, + -33.0518 -36.2561 -120.306, + -34.970402 -38.360699 -119.376, + -30.445801 -40.316799 -119.954, + -29.5655 -39.1511 -120.306, + -5.2046099 -56.1716 -114.407, + -7.6432195 -55.753201 -114.75, + -5.8064594 -56.051498 -114.571, + -4.4654303 -56.319199 -114.204, + -5.1739302 -55.835602 -115.174, + 121.108 -58.387402 -93.757599, + 121.019 -58.387402 -93.797897, + 121.022 -58.387402 -93.797096, + 121.15 -58.387402 -93.734802, + 139.7 -57.087399 -110.9, + 5.4545107 -58.387402 93.312202, + 5.4089608 -58.387402 93.207001, + 5.4453802 -58.387402 93.294998, + 5.4899807 -58.387402 93.378998, + 5.3489203 -58.380299 93.340401, + 5.3982797 -58.380299 93.433403, + 5.53543 -58.387402 -93.448799, + 5.5248904 -58.387402 -93.432404, + 5.4485698 -58.380299 -93.510696, + 5.6599207 -58.387402 -93.592499, + 5.5942497 -58.387402 -93.523598, + 5.7318401 -58.387402 -93.6548, + 5.6195602 -58.387402 -93.550201, + 5.5863404 -58.380299 -93.669701, + -48.225101 9.0148306 -120.306, + -48.592499 13.8258 -119.954, + 190.52 -7.3526627e-007 119.851, + 188.70599 -4.5411201 120.28, + 186.453 -8.7395706 120.425, + 180.138 25.038401 120.425, + 182.276 -21.200399 120.425, + 182.276 21.200399 120.425, + 185.44701 13.0161 120.425, + 186.453 8.7395687 120.425, + 188.078 9.0434895 120.28, + 188.70599 4.5411201 120.28, + -45.2206 -27.999399 -118.587, + -46.4664 -23.137501 -119.376, + -47.611198 -23.7076 -118.587, + -49.060398 2.9135697e-007 -120.306, + -48.851101 4.52672 -120.306, + -50.305599 4.6615005 -119.954, + -52.9603 4.9074898 -118.587, + -53.187199 7.1931032e-007 -118.587, + -51.908199 -1.1344596e-007 -119.376, + 187.26199 7.3827891e-007 120.425, + 187.06 4.3885002 120.425, + 187.26199 5.3848265e-007 120.425, + 188.916 7.5270165e-008 120.28, + 187.06 -4.3884997 120.425, + -41.423698 -31.2817 -119.376, + -38.360699 -34.970402 -119.376, + -42.444302 -32.052399 -118.587, + -44.133301 -27.3262 -119.376, + -40.316799 -30.445801 -119.954, + -42.953999 -26.596001 -119.954, + -50.305599 -4.6614995 -119.954, + -50.521198 7.1757967e-007 -119.954, + -48.851101 -4.5267205 -120.306, + -48.225101 -9.0148306 -120.306, + -49.6609 -9.2832403 -119.954, + -51.686798 -4.7894897 -119.376, + -51.024399 -9.5381107 -119.376, + -51.024399 9.5381088 -119.376, + -49.6609 9.2832403 -119.954, + -49.926701 14.2054 -119.376, + -51.686798 4.7894907 -119.376, + -52.281601 9.773119 -118.587 ] + + } + coordIndex [ 1887, 1888, 1297, -1, 1887, 1297, 1295, -1, + 1887, 1295, 1586, -1, 1887, 1586, 131, -1, + 108, 1888, 1880, -1, 33, 111, 1553, -1, + 1597, 76, 77, -1, 10, 77, 76, -1, + 10, 75, 81, -1, 79, 81, 75, -1, + 1044, 1874, 1070, -1, 1427, 1070, 1874, -1, + 103, 925, 494, -1, 15, 722, 721, -1, + 15, 721, 301, -1, 29, 507, 1297, -1, + 29, 1297, 1888, -1, 29, 1888, 108, -1, + 1153, 735, 131, -1, 1153, 131, 1586, -1, + 1153, 1586, 1587, -1, 720, 735, 129, -1, + 1144, 29, 108, -1, 2, 334, 54, -1, + 2, 54, 3, -1, 236, 237, 21, -1, + 4, 135, 377, -1, 373, 136, 372, -1, + 373, 377, 135, -1, 741, 746, 747, -1, + 6, 157, 16, -1, 6, 158, 157, -1, + 6, 16, 27, -1, 1249, 7, 871, -1, + 513, 259, 939, -1, 531, 939, 259, -1, + 330, 125, 49, -1, 8, 49, 47, -1, + 8, 495, 35, -1, 8, 35, 37, -1, + 8, 330, 49, -1, 9, 49, 14, -1, + 9, 14, 103, -1, 44, 49, 494, -1, + 554, 556, 1661, -1, 554, 1661, 1660, -1, + 335, 54, 334, -1, 235, 3, 54, -1, + 235, 236, 3, -1, 1004, 64, 1005, -1, + 525, 76, 1597, -1, 0, 77, 10, -1, + 0, 10, 81, -1, 0, 81, 662, -1, + 1419, 75, 10, -1, 270, 77, 0, -1, + 270, 0, 662, -1, 78, 79, 75, -1, + 661, 81, 79, -1, 1085, 668, 669, -1, + 1085, 669, 275, -1, 1074, 1095, 1075, -1, + 291, 703, 925, -1, 313, 129, 735, -1, + 36, 495, 496, -1, 297, 722, 15, -1, + 118, 1587, 703, -1, 130, 720, 129, -1, + 465, 1144, 1145, -1, 465, 471, 32, -1, + 333, 240, 335, -1, 22, 145, 236, -1, + 141, 18, 16, -1, 141, 135, 4, -1, + 141, 4, 145, -1, 20, 18, 22, -1, + 20, 21, 237, -1, 20, 237, 27, -1, + 20, 16, 18, -1, 20, 27, 16, -1, + 26, 237, 1392, -1, 26, 27, 237, -1, + 1, 146, 334, -1, 1, 334, 2, -1, + 1, 3, 146, -1, 1, 2, 3, -1, + 23, 236, 145, -1, 23, 146, 3, -1, + 23, 3, 236, -1, 230, 741, 742, -1, + 230, 231, 741, -1, 360, 372, 136, -1, + 808, 958, 1133, -1, 381, 25, 229, -1, + 838, 730, 154, -1, 294, 301, 721, -1, + 305, 154, 730, -1, 147, 4, 377, -1, + 147, 377, 24, -1, 147, 145, 4, -1, + 147, 334, 146, -1, 147, 24, 334, -1, + 160, 161, 309, -1, 142, 16, 157, -1, + 142, 157, 160, -1, 142, 160, 309, -1, + 169, 170, 139, -1, 308, 139, 142, -1, + 308, 142, 309, -1, 308, 169, 139, -1, + 308, 728, 169, -1, 148, 352, 380, -1, + 150, 389, 151, -1, 740, 381, 742, -1, + 745, 227, 743, -1, 745, 746, 227, -1, + 197, 416, 427, -1, 1210, 1211, 162, -1, + 1555, 1553, 113, -1, 1555, 113, 1211, -1, + 5, 27, 158, -1, 5, 158, 6, -1, + 5, 6, 27, -1, 454, 173, 31, -1, + 454, 31, 32, -1, 479, 7, 1249, -1, + 479, 871, 7, -1, 1006, 1005, 487, -1, + 1305, 494, 925, -1, 853, 867, 726, -1, + 853, 856, 867, -1, 853, 111, 33, -1, + 853, 726, 111, -1, 853, 1214, 881, -1, + 708, 37, 35, -1, 1596, 1597, 77, -1, + 528, 196, 259, -1, 45, 8, 47, -1, + 45, 495, 8, -1, 45, 494, 495, -1, + 329, 330, 8, -1, 329, 37, 331, -1, + 329, 8, 37, -1, 50, 49, 9, -1, + 51, 103, 494, -1, 51, 9, 103, -1, + 51, 50, 9, -1, 954, 540, 217, -1, + 52, 554, 1660, -1, 392, 342, 399, -1, + 341, 399, 342, -1, 340, 342, 392, -1, + 552, 551, 251, -1, 1391, 1392, 237, -1, + 1380, 1014, 590, -1, 1016, 590, 1014, -1, + 1016, 54, 335, -1, 244, 58, 64, -1, + 244, 59, 58, -1, 66, 1654, 88, -1, + 66, 626, 1654, -1, 249, 339, 251, -1, + 61, 64, 58, -1, 627, 254, 1026, -1, + 258, 181, 259, -1, 258, 193, 41, -1, + 639, 78, 75, -1, 639, 80, 78, -1, + 1059, 10, 76, -1, 1059, 1419, 10, -1, + 208, 541, 542, -1, 208, 542, 211, -1, + 272, 217, 540, -1, 272, 540, 541, -1, + 544, 671, 1342, -1, 544, 1342, 1339, -1, + 1865, 668, 1085, -1, 1865, 1708, 668, -1, + 1696, 1865, 1085, -1, 680, 1070, 675, -1, + 1706, 12, 1708, -1, 1706, 1678, 1874, -1, + 1706, 1874, 1044, -1, 1706, 1044, 88, -1, + 1706, 11, 12, -1, 1706, 88, 11, -1, + 1094, 1095, 1074, -1, 557, 560, 86, -1, + 87, 1661, 556, -1, 279, 85, 12, -1, + 279, 12, 11, -1, 279, 87, 85, -1, + 279, 11, 88, -1, 13, 1708, 12, -1, + 13, 12, 85, -1, 82, 1708, 13, -1, + 82, 13, 85, -1, 94, 280, 93, -1, + 281, 94, 93, -1, 817, 280, 696, -1, + 92, 95, 226, -1, 92, 696, 280, -1, + 92, 226, 562, -1, 178, 513, 939, -1, + 178, 939, 36, -1, 178, 36, 496, -1, + 707, 36, 939, -1, 707, 708, 36, -1, + 105, 106, 925, -1, 107, 103, 14, -1, + 107, 14, 49, -1, 100, 101, 925, -1, + 1771, 297, 15, -1, 1771, 15, 301, -1, + 302, 1553, 111, -1, 114, 161, 162, -1, + 114, 162, 1211, -1, 114, 309, 161, -1, + 1559, 875, 881, -1, 1559, 1214, 311, -1, + 1559, 881, 1214, -1, 117, 313, 735, -1, + 319, 1587, 322, -1, 323, 118, 120, -1, + 323, 1587, 118, -1, 121, 734, 735, -1, + 121, 735, 122, -1, 121, 1587, 734, -1, + 738, 122, 735, -1, 204, 205, 326, -1, + 288, 49, 125, -1, 288, 125, 128, -1, + 288, 107, 49, -1, 288, 290, 100, -1, + 288, 925, 106, -1, 288, 100, 925, -1, + 127, 202, 130, -1, 127, 130, 129, -1, + 201, 202, 127, -1, 201, 127, 205, -1, + 719, 720, 130, -1, 1889, 1887, 131, -1, + 592, 593, 241, -1, 592, 241, 132, -1, + 133, 132, 241, -1, 140, 141, 16, -1, + 140, 16, 142, -1, 138, 135, 141, -1, + 17, 141, 145, -1, 17, 18, 141, -1, + 17, 145, 22, -1, 17, 22, 18, -1, + 19, 21, 20, -1, 19, 20, 22, -1, + 19, 236, 21, -1, 19, 22, 236, -1, + 144, 23, 145, -1, 144, 146, 23, -1, + 346, 148, 380, -1, 435, 360, 136, -1, + 435, 136, 851, -1, 361, 435, 849, -1, + 361, 360, 435, -1, 785, 806, 808, -1, + 797, 334, 24, -1, 375, 24, 377, -1, + 375, 798, 797, -1, 375, 797, 24, -1, + 791, 372, 360, -1, 379, 380, 352, -1, + 152, 25, 381, -1, 152, 355, 354, -1, + 152, 354, 765, -1, 152, 229, 25, -1, + 152, 765, 229, -1, 293, 154, 294, -1, + 304, 301, 294, -1, 304, 726, 301, -1, + 1197, 381, 740, -1, 1206, 363, 1184, -1, + 220, 163, 165, -1, 219, 1528, 1526, -1, + 219, 1526, 163, -1, 219, 163, 220, -1, + 813, 686, 814, -1, 813, 368, 369, -1, + 813, 369, 686, -1, 405, 165, 163, -1, + 166, 164, 165, -1, 166, 824, 164, -1, + 166, 165, 405, -1, 166, 405, 371, -1, + 167, 1465, 1750, -1, 421, 431, 432, -1, + 421, 422, 431, -1, 436, 26, 1392, -1, + 436, 158, 27, -1, 436, 27, 26, -1, + 448, 171, 505, -1, 1575, 1577, 1226, -1, + 28, 1577, 171, -1, 28, 1226, 1577, -1, + 28, 171, 446, -1, 28, 446, 1226, -1, + 30, 32, 31, -1, 30, 29, 1144, -1, + 30, 465, 32, -1, 30, 1144, 465, -1, + 174, 507, 29, -1, 174, 29, 30, -1, + 174, 30, 31, -1, 174, 31, 173, -1, + 175, 1006, 482, -1, 1637, 1357, 452, -1, + 444, 450, 451, -1, 453, 173, 454, -1, + 453, 450, 173, -1, 1227, 446, 443, -1, + 1227, 1226, 446, -1, 999, 463, 451, -1, + 999, 1000, 463, -1, 999, 452, 1357, -1, + 470, 32, 471, -1, 470, 454, 32, -1, + 477, 858, 871, -1, 478, 479, 1249, -1, + 1279, 1280, 487, -1, 1279, 487, 910, -1, + 908, 487, 1005, -1, 1292, 909, 491, -1, + 504, 515, 503, -1, 1585, 703, 1587, -1, + 510, 347, 349, -1, 510, 1007, 347, -1, + 754, 347, 1007, -1, 873, 1559, 889, -1, + 873, 875, 1559, -1, 437, 33, 1553, -1, + 437, 853, 33, -1, 512, 259, 513, -1, + 34, 708, 35, -1, 34, 36, 708, -1, + 34, 35, 495, -1, 34, 495, 36, -1, + 937, 37, 708, -1, 937, 331, 37, -1, + 182, 528, 259, -1, 182, 38, 528, -1, + 180, 528, 38, -1, 180, 38, 182, -1, + 71, 70, 40, -1, 71, 180, 181, -1, + 71, 528, 180, -1, 71, 40, 193, -1, + 71, 193, 528, -1, 184, 189, 191, -1, + 184, 191, 258, -1, 184, 525, 186, -1, + 184, 258, 525, -1, 522, 1596, 74, -1, + 42, 40, 70, -1, 42, 70, 258, -1, + 42, 258, 41, -1, 39, 193, 40, -1, + 39, 41, 193, -1, 39, 40, 42, -1, + 39, 42, 41, -1, 527, 196, 528, -1, + 1623, 204, 326, -1, 1623, 1331, 204, -1, + 1959, 1326, 1331, -1, 46, 47, 49, -1, + 46, 49, 44, -1, 43, 44, 494, -1, + 43, 494, 45, -1, 43, 46, 44, -1, + 43, 45, 47, -1, 43, 47, 46, -1, + 534, 1624, 1623, -1, 48, 494, 49, -1, + 48, 49, 50, -1, 48, 51, 494, -1, + 48, 50, 51, -1, 362, 1172, 1171, -1, + 362, 428, 832, -1, 710, 537, 536, -1, + 710, 1172, 537, -1, 200, 536, 197, -1, + 200, 419, 709, -1, 206, 1331, 1326, -1, + 206, 1326, 714, -1, 206, 204, 1331, -1, + 1325, 1934, 714, -1, 1325, 714, 1326, -1, + 1602, 331, 937, -1, 1602, 937, 528, -1, + 210, 193, 1596, -1, 213, 528, 193, -1, + 213, 193, 210, -1, 213, 210, 1601, -1, + 966, 543, 284, -1, 216, 1631, 1632, -1, + 548, 216, 547, -1, 1659, 52, 1660, -1, + 1659, 612, 52, -1, 53, 52, 612, -1, + 53, 555, 554, -1, 53, 554, 52, -1, + 394, 340, 392, -1, 224, 251, 339, -1, + 224, 339, 340, -1, 225, 55, 551, -1, + 225, 555, 53, -1, 225, 612, 55, -1, + 225, 53, 612, -1, 821, 164, 824, -1, + 412, 552, 413, -1, 412, 692, 552, -1, + 697, 562, 698, -1, 697, 92, 562, -1, + 697, 696, 92, -1, 559, 698, 562, -1, + 559, 560, 698, -1, 691, 698, 560, -1, + 971, 595, 592, -1, 971, 592, 227, -1, + 755, 232, 356, -1, 1002, 582, 233, -1, + 238, 1391, 237, -1, 1390, 238, 1021, -1, + 1390, 1391, 238, -1, 586, 573, 1388, -1, + 586, 1013, 573, -1, 589, 595, 971, -1, + 239, 590, 1016, -1, 239, 595, 589, -1, + 239, 589, 590, -1, 1015, 235, 54, -1, + 1015, 54, 1016, -1, 597, 242, 62, -1, + 597, 62, 243, -1, 598, 64, 1004, -1, + 598, 244, 64, -1, 598, 1004, 752, -1, + 247, 59, 244, -1, 247, 246, 243, -1, + 247, 243, 59, -1, 1655, 1654, 626, -1, + 1040, 1655, 248, -1, 613, 1033, 343, -1, + 748, 343, 1033, -1, 250, 551, 55, -1, + 250, 55, 612, -1, 56, 1005, 619, -1, + 56, 904, 1005, -1, 897, 56, 619, -1, + 897, 904, 56, -1, 65, 64, 61, -1, + 65, 67, 252, -1, 57, 62, 61, -1, + 57, 61, 58, -1, 57, 243, 62, -1, + 57, 59, 243, -1, 57, 58, 59, -1, + 60, 68, 67, -1, 60, 61, 62, -1, + 60, 67, 65, -1, 60, 65, 61, -1, + 60, 242, 68, -1, 60, 62, 242, -1, + 63, 618, 619, -1, 63, 1005, 64, -1, + 63, 619, 1005, -1, 63, 64, 65, -1, + 63, 252, 618, -1, 63, 65, 252, -1, + 1041, 626, 66, -1, 1041, 88, 1044, -1, + 1041, 66, 88, -1, 1024, 1655, 626, -1, + 1024, 248, 1655, -1, 1024, 627, 1026, -1, + 1052, 252, 67, -1, 1052, 1053, 252, -1, + 256, 68, 242, -1, 635, 630, 622, -1, + 635, 622, 253, -1, 633, 254, 630, -1, + 633, 1026, 254, -1, 631, 1048, 1052, -1, + 631, 1052, 67, -1, 631, 67, 68, -1, + 631, 68, 256, -1, 642, 643, 80, -1, + 642, 80, 639, -1, 1051, 1045, 1054, -1, + 641, 1067, 253, -1, 641, 253, 643, -1, + 69, 258, 70, -1, 69, 181, 258, -1, + 69, 70, 71, -1, 69, 71, 181, -1, + 260, 1060, 525, -1, 260, 525, 258, -1, + 187, 186, 525, -1, 187, 525, 73, -1, + 187, 73, 185, -1, 194, 73, 525, -1, + 194, 74, 73, -1, 194, 522, 74, -1, + 72, 73, 74, -1, 72, 185, 73, -1, + 72, 74, 1596, -1, 72, 1596, 185, -1, + 637, 75, 1419, -1, 637, 639, 75, -1, + 1058, 1059, 76, -1, 1058, 76, 525, -1, + 1058, 525, 1060, -1, 207, 77, 270, -1, + 207, 270, 208, -1, 207, 1596, 77, -1, + 271, 208, 270, -1, 271, 541, 208, -1, + 271, 272, 541, -1, 261, 651, 650, -1, + 267, 80, 643, -1, 267, 643, 268, -1, + 665, 651, 262, -1, 665, 1344, 651, -1, + 648, 1075, 1095, -1, 648, 1095, 262, -1, + 653, 661, 79, -1, 653, 79, 265, -1, + 264, 650, 265, -1, 264, 261, 650, -1, + 264, 646, 261, -1, 266, 79, 78, -1, + 266, 265, 79, -1, 266, 78, 80, -1, + 266, 80, 267, -1, 658, 1078, 215, -1, + 269, 657, 217, -1, 269, 217, 272, -1, + 660, 662, 81, -1, 660, 81, 661, -1, + 545, 1631, 215, -1, 545, 215, 1078, -1, + 274, 668, 1708, -1, 274, 1708, 82, -1, + 274, 85, 86, -1, 274, 82, 85, -1, + 666, 668, 274, -1, 561, 86, 560, -1, + 561, 274, 86, -1, 673, 226, 90, -1, + 673, 1342, 671, -1, 673, 90, 1342, -1, + 967, 968, 671, -1, 967, 671, 544, -1, + 1090, 1696, 1085, -1, 83, 1070, 1427, -1, + 83, 675, 1070, -1, 1682, 83, 1427, -1, + 1682, 675, 83, -1, 1854, 1856, 1686, -1, + 84, 86, 85, -1, 84, 557, 86, -1, + 84, 556, 557, -1, 84, 87, 556, -1, + 84, 85, 87, -1, 278, 1661, 87, -1, + 278, 87, 279, -1, 1653, 88, 1654, -1, + 1653, 279, 88, -1, 89, 226, 95, -1, + 89, 90, 226, -1, 89, 97, 1341, -1, + 89, 95, 97, -1, 89, 1341, 1342, -1, + 89, 1342, 90, -1, 91, 94, 95, -1, + 91, 280, 94, -1, 91, 95, 92, -1, + 91, 92, 280, -1, 815, 93, 280, -1, + 1131, 815, 814, -1, 1131, 281, 93, -1, + 1131, 93, 815, -1, 684, 94, 281, -1, + 683, 99, 684, -1, 688, 1341, 97, -1, + 688, 1340, 1341, -1, 688, 97, 282, -1, + 98, 684, 99, -1, 98, 94, 684, -1, + 98, 95, 94, -1, 98, 97, 95, -1, + 285, 543, 282, -1, 96, 282, 97, -1, + 96, 98, 99, -1, 96, 97, 98, -1, + 96, 683, 958, -1, 96, 99, 683, -1, + 96, 958, 285, -1, 96, 285, 282, -1, + 695, 692, 412, -1, 292, 100, 290, -1, + 292, 101, 100, -1, 292, 291, 925, -1, + 292, 925, 101, -1, 701, 313, 703, -1, + 289, 286, 291, -1, 289, 313, 286, -1, + 706, 939, 937, -1, 102, 103, 107, -1, + 102, 107, 105, -1, 102, 925, 103, -1, + 102, 105, 925, -1, 104, 106, 105, -1, + 104, 105, 107, -1, 104, 288, 106, -1, + 104, 107, 288, -1, 415, 419, 418, -1, + 415, 1137, 1136, -1, 415, 709, 419, -1, + 415, 1136, 709, -1, 1901, 1465, 384, -1, + 1754, 108, 1880, -1, 1754, 1144, 108, -1, + 1256, 109, 1771, -1, 1256, 1255, 1254, -1, + 1256, 1254, 109, -1, 299, 1771, 109, -1, + 299, 109, 1254, -1, 110, 111, 726, -1, + 110, 302, 111, -1, 110, 726, 304, -1, + 110, 304, 302, -1, 112, 302, 303, -1, + 112, 303, 114, -1, 112, 113, 1553, -1, + 112, 1553, 302, -1, 112, 1211, 113, -1, + 112, 114, 1211, -1, 307, 114, 303, -1, + 307, 309, 114, -1, 115, 310, 732, -1, + 115, 732, 1559, -1, 115, 311, 310, -1, + 115, 1559, 311, -1, 116, 120, 118, -1, + 116, 118, 117, -1, 116, 735, 120, -1, + 116, 117, 735, -1, 315, 313, 117, -1, + 317, 117, 118, -1, 317, 118, 703, -1, + 317, 315, 117, -1, 119, 735, 318, -1, + 119, 318, 319, -1, 119, 319, 322, -1, + 321, 119, 322, -1, 321, 323, 120, -1, + 321, 735, 119, -1, 321, 120, 735, -1, + 737, 735, 1153, -1, 737, 738, 735, -1, + 324, 121, 122, -1, 324, 122, 738, -1, + 324, 1587, 121, -1, 123, 205, 127, -1, + 123, 127, 128, -1, 123, 326, 205, -1, + 123, 124, 326, -1, 123, 128, 125, -1, + 123, 125, 124, -1, 328, 326, 124, -1, + 328, 125, 330, -1, 328, 124, 125, -1, + 126, 128, 127, -1, 126, 313, 288, -1, + 126, 288, 128, -1, 126, 129, 313, -1, + 126, 127, 129, -1, 713, 1877, 202, -1, + 718, 202, 1877, -1, 718, 130, 202, -1, + 718, 719, 130, -1, 717, 1889, 131, -1, + 717, 131, 735, -1, 717, 735, 720, -1, + 1158, 132, 1157, -1, 1158, 743, 227, -1, + 1158, 227, 592, -1, 1158, 592, 132, -1, + 337, 1157, 132, -1, 337, 795, 1157, -1, + 337, 132, 133, -1, 336, 133, 241, -1, + 336, 240, 333, -1, 336, 337, 133, -1, + 134, 373, 135, -1, 134, 135, 138, -1, + 134, 136, 373, -1, 134, 138, 170, -1, + 134, 851, 136, -1, 134, 170, 851, -1, + 137, 170, 138, -1, 137, 139, 170, -1, + 137, 141, 140, -1, 137, 138, 141, -1, + 137, 142, 139, -1, 137, 140, 142, -1, + 143, 144, 145, -1, 143, 146, 144, -1, + 143, 145, 147, -1, 143, 147, 146, -1, + 388, 346, 151, -1, 388, 758, 346, -1, + 388, 398, 758, -1, 388, 151, 389, -1, + 149, 352, 148, -1, 149, 148, 346, -1, + 338, 249, 343, -1, 338, 339, 249, -1, + 400, 399, 341, -1, 350, 611, 610, -1, + 350, 757, 611, -1, 1497, 359, 1168, -1, + 345, 352, 149, -1, 345, 149, 346, -1, + 351, 1168, 359, -1, 351, 359, 760, -1, + 763, 352, 345, -1, 763, 345, 359, -1, + 1200, 407, 801, -1, 783, 808, 1133, -1, + 376, 377, 373, -1, 799, 789, 1523, -1, + 799, 798, 375, -1, 799, 1523, 1522, -1, + 353, 1540, 379, -1, 353, 355, 152, -1, + 353, 379, 352, -1, 800, 389, 150, -1, + 800, 346, 380, -1, 800, 150, 151, -1, + 800, 151, 346, -1, 1531, 379, 1540, -1, + 1539, 152, 381, -1, 1539, 1540, 353, -1, + 1539, 353, 152, -1, 383, 293, 384, -1, + 383, 838, 154, -1, 383, 154, 293, -1, + 153, 294, 154, -1, 153, 304, 294, -1, + 153, 154, 305, -1, 153, 305, 304, -1, + 155, 159, 158, -1, 155, 162, 159, -1, + 155, 158, 436, -1, 155, 1210, 162, -1, + 155, 436, 1210, -1, 156, 157, 158, -1, + 156, 158, 159, -1, 156, 160, 157, -1, + 156, 161, 160, -1, 156, 162, 161, -1, + 156, 159, 162, -1, 391, 392, 399, -1, + 396, 757, 758, -1, 396, 758, 398, -1, + 396, 611, 757, -1, 1546, 408, 403, -1, + 803, 163, 1526, -1, 803, 405, 163, -1, + 805, 806, 785, -1, 805, 403, 408, -1, + 809, 810, 408, -1, 809, 408, 1546, -1, + 1205, 363, 1206, -1, 411, 164, 821, -1, + 411, 165, 164, -1, 411, 220, 165, -1, + 414, 368, 813, -1, 414, 824, 166, -1, + 414, 166, 371, -1, 1466, 829, 1141, -1, + 426, 197, 427, -1, 426, 200, 197, -1, + 426, 419, 200, -1, 386, 384, 1465, -1, + 386, 1465, 167, -1, 386, 167, 385, -1, + 828, 167, 1750, -1, 828, 827, 167, -1, + 828, 1141, 829, -1, 828, 1750, 1141, -1, + 168, 432, 385, -1, 168, 421, 432, -1, + 168, 385, 167, -1, 423, 167, 827, -1, + 423, 168, 167, -1, 423, 421, 168, -1, + 430, 431, 416, -1, 837, 838, 432, -1, + 843, 835, 728, -1, 846, 169, 728, -1, + 846, 728, 835, -1, 846, 851, 170, -1, + 846, 170, 169, -1, 1393, 436, 1392, -1, + 176, 726, 864, -1, 1294, 171, 1577, -1, + 1294, 505, 171, -1, 1294, 1795, 505, -1, + 445, 173, 450, -1, 445, 448, 173, -1, + 447, 171, 448, -1, 447, 446, 171, -1, + 172, 173, 448, -1, 172, 174, 173, -1, + 172, 448, 505, -1, 172, 505, 506, -1, + 172, 507, 174, -1, 172, 506, 507, -1, + 481, 175, 482, -1, 481, 462, 175, -1, + 481, 483, 459, -1, 1353, 462, 1354, -1, + 1353, 175, 462, -1, 992, 991, 1006, -1, + 992, 1006, 175, -1, 992, 175, 1353, -1, + 456, 443, 458, -1, 456, 1227, 443, -1, + 1231, 882, 485, -1, 1231, 916, 1230, -1, + 1231, 485, 916, -1, 442, 463, 458, -1, + 442, 458, 443, -1, 442, 444, 451, -1, + 442, 451, 463, -1, 461, 458, 463, -1, + 723, 1145, 1143, -1, 723, 722, 472, -1, + 468, 472, 296, -1, 468, 885, 472, -1, + 468, 296, 466, -1, 884, 472, 885, -1, + 884, 310, 1148, -1, 884, 1148, 470, -1, + 884, 732, 310, -1, 888, 873, 889, -1, + 863, 176, 864, -1, 863, 726, 176, -1, + 1277, 1279, 910, -1, 1276, 492, 1572, -1, + 1276, 1572, 1573, -1, 177, 908, 1572, -1, + 177, 1572, 492, -1, 177, 910, 487, -1, + 177, 487, 908, -1, 177, 909, 910, -1, + 177, 491, 909, -1, 177, 492, 491, -1, + 917, 487, 918, -1, 917, 485, 487, -1, + 917, 916, 485, -1, 486, 1006, 487, -1, + 486, 487, 485, -1, 486, 482, 1006, -1, + 486, 882, 483, -1, 1282, 918, 487, -1, + 502, 503, 515, -1, 502, 513, 178, -1, + 921, 1309, 504, -1, 921, 504, 1285, -1, + 1288, 894, 1314, -1, 1592, 504, 1309, -1, + 1592, 515, 504, -1, 498, 1303, 499, -1, + 500, 178, 496, -1, 500, 502, 178, -1, + 501, 1285, 504, -1, 1296, 1297, 507, -1, + 926, 925, 703, -1, 926, 703, 1585, -1, + 509, 1007, 510, -1, 438, 440, 881, -1, + 514, 513, 502, -1, 514, 502, 515, -1, + 1591, 515, 1592, -1, 932, 636, 933, -1, + 179, 181, 180, -1, 179, 180, 182, -1, + 179, 259, 181, -1, 179, 182, 259, -1, + 183, 189, 184, -1, 183, 185, 1596, -1, + 183, 184, 186, -1, 183, 193, 189, -1, + 183, 1596, 193, -1, 183, 186, 187, -1, + 183, 187, 185, -1, 188, 191, 189, -1, + 188, 192, 191, -1, 188, 189, 193, -1, + 188, 193, 192, -1, 190, 258, 191, -1, + 190, 191, 192, -1, 190, 193, 258, -1, + 190, 192, 193, -1, 1316, 519, 525, -1, + 520, 1596, 525, -1, 520, 525, 519, -1, + 523, 194, 525, -1, 523, 522, 194, -1, + 195, 527, 531, -1, 195, 196, 527, -1, + 195, 531, 259, -1, 195, 259, 196, -1, + 530, 528, 937, -1, 1622, 1331, 1623, -1, + 944, 943, 534, -1, 944, 331, 1602, -1, + 538, 416, 197, -1, 538, 197, 536, -1, + 538, 430, 416, -1, 538, 833, 430, -1, + 539, 537, 1172, -1, 539, 1172, 833, -1, + 198, 832, 1172, -1, 198, 362, 832, -1, + 198, 1172, 362, -1, 199, 710, 536, -1, + 199, 536, 200, -1, 199, 709, 710, -1, + 199, 200, 709, -1, 715, 206, 714, -1, + 715, 201, 205, -1, 715, 202, 201, -1, + 715, 713, 202, -1, 203, 205, 204, -1, + 203, 204, 206, -1, 203, 715, 205, -1, + 203, 206, 715, -1, 950, 533, 941, -1, + 950, 941, 542, -1, 942, 533, 950, -1, + 942, 950, 951, -1, 212, 210, 1596, -1, + 212, 1596, 207, -1, 212, 208, 211, -1, + 212, 207, 208, -1, 209, 941, 1601, -1, + 209, 1601, 210, -1, 209, 211, 542, -1, + 209, 542, 941, -1, 209, 212, 211, -1, + 209, 210, 212, -1, 1600, 1602, 528, -1, + 1600, 528, 213, -1, 1600, 213, 1601, -1, + 1332, 959, 962, -1, 1811, 216, 1632, -1, + 1811, 547, 216, -1, 1811, 1611, 547, -1, + 218, 217, 657, -1, 218, 215, 548, -1, + 218, 658, 215, -1, 218, 657, 658, -1, + 214, 548, 215, -1, 214, 216, 548, -1, + 214, 215, 1631, -1, 214, 1631, 216, -1, + 549, 954, 217, -1, 549, 217, 218, -1, + 549, 218, 548, -1, 222, 393, 1528, -1, + 222, 394, 393, -1, 222, 1528, 219, -1, + 222, 219, 220, -1, 222, 411, 413, -1, + 222, 220, 411, -1, 221, 340, 394, -1, + 221, 413, 552, -1, 221, 552, 340, -1, + 221, 222, 413, -1, 221, 394, 222, -1, + 223, 251, 224, -1, 223, 224, 340, -1, + 223, 552, 251, -1, 223, 340, 552, -1, + 690, 225, 551, -1, 690, 555, 225, -1, + 563, 562, 226, -1, 563, 226, 673, -1, + 565, 571, 974, -1, 975, 974, 571, -1, + 975, 588, 589, -1, 975, 568, 588, -1, + 228, 973, 231, -1, 228, 566, 973, -1, + 976, 741, 231, -1, 976, 231, 973, -1, + 970, 227, 746, -1, 970, 971, 227, -1, + 970, 746, 741, -1, 970, 741, 976, -1, + 357, 356, 232, -1, 357, 232, 566, -1, + 357, 566, 228, -1, 357, 231, 766, -1, + 357, 228, 231, -1, 767, 229, 765, -1, + 767, 381, 229, -1, 767, 231, 230, -1, + 767, 766, 231, -1, 767, 230, 742, -1, + 767, 742, 381, -1, 1498, 755, 356, -1, + 1498, 356, 1497, -1, 980, 566, 232, -1, + 980, 232, 755, -1, 980, 981, 565, -1, + 1358, 999, 1357, -1, 578, 983, 575, -1, + 580, 581, 573, -1, 1009, 1371, 1646, -1, + 579, 1010, 582, -1, 579, 580, 573, -1, + 579, 582, 1002, -1, 1012, 573, 1013, -1, + 1012, 579, 573, -1, 1012, 1010, 579, -1, + 583, 565, 981, -1, 583, 571, 565, -1, + 583, 570, 571, -1, 583, 1373, 570, -1, + 1372, 1371, 570, -1, 1372, 570, 1373, -1, + 1927, 233, 582, -1, 1927, 1002, 233, -1, + 1377, 1021, 238, -1, 1377, 235, 1015, -1, + 234, 236, 235, -1, 234, 237, 236, -1, + 234, 238, 237, -1, 234, 235, 1377, -1, + 234, 1377, 238, -1, 1367, 1013, 586, -1, + 569, 570, 1371, -1, 569, 1371, 1369, -1, + 1370, 569, 1369, -1, 1370, 568, 569, -1, + 1370, 588, 568, -1, 594, 595, 239, -1, + 594, 240, 336, -1, 594, 335, 240, -1, + 594, 241, 593, -1, 594, 336, 241, -1, + 594, 1016, 335, -1, 594, 239, 1016, -1, + 605, 615, 616, -1, 596, 242, 597, -1, + 596, 256, 242, -1, 245, 243, 246, -1, + 245, 597, 243, -1, 245, 616, 597, -1, + 245, 605, 616, -1, 599, 244, 598, -1, + 599, 245, 246, -1, 599, 605, 245, -1, + 599, 246, 247, -1, 599, 247, 244, -1, + 1037, 615, 605, -1, 1023, 1040, 248, -1, + 1023, 248, 1024, -1, 614, 343, 249, -1, + 614, 613, 343, -1, 614, 250, 612, -1, + 614, 551, 250, -1, 614, 251, 551, -1, + 614, 249, 251, -1, 608, 611, 397, -1, + 608, 397, 343, -1, 608, 343, 748, -1, + 608, 748, 749, -1, 620, 618, 252, -1, + 620, 252, 1053, -1, 620, 1053, 1054, -1, + 620, 1054, 897, -1, 624, 623, 268, -1, + 624, 268, 643, -1, 624, 643, 253, -1, + 624, 253, 622, -1, 628, 626, 1041, -1, + 1415, 623, 1665, -1, 1047, 630, 635, -1, + 1047, 1048, 631, -1, 634, 253, 1067, -1, + 634, 635, 253, -1, 255, 630, 254, -1, + 255, 254, 627, -1, 255, 627, 1043, -1, + 1042, 630, 255, -1, 1042, 255, 1043, -1, + 1042, 622, 630, -1, 1042, 1665, 622, -1, + 632, 631, 256, -1, 632, 256, 596, -1, + 632, 1026, 633, -1, 632, 596, 1026, -1, + 1669, 640, 1420, -1, 638, 640, 642, -1, + 638, 642, 639, -1, 1065, 640, 1669, -1, + 1065, 1670, 900, -1, 1065, 1669, 1670, -1, + 1064, 1065, 900, -1, 257, 516, 260, -1, + 257, 260, 258, -1, 257, 512, 516, -1, + 257, 258, 259, -1, 257, 259, 512, -1, + 517, 516, 933, -1, 517, 260, 516, -1, + 517, 1060, 260, -1, 517, 1061, 1060, -1, + 645, 651, 261, -1, 645, 261, 646, -1, + 645, 262, 651, -1, 645, 648, 262, -1, + 647, 268, 623, -1, 647, 623, 1415, -1, + 649, 1075, 648, -1, 667, 677, 275, -1, + 667, 262, 677, -1, 667, 665, 262, -1, + 667, 275, 669, -1, 676, 262, 1095, -1, + 676, 677, 262, -1, 652, 661, 653, -1, + 652, 1078, 658, -1, 654, 265, 650, -1, + 654, 653, 265, -1, 263, 264, 265, -1, + 263, 265, 266, -1, 263, 646, 264, -1, + 263, 647, 646, -1, 263, 267, 268, -1, + 263, 266, 267, -1, 263, 268, 647, -1, + 659, 661, 652, -1, 659, 652, 658, -1, + 656, 657, 269, -1, 656, 270, 662, -1, + 656, 271, 270, -1, 656, 272, 271, -1, + 656, 269, 272, -1, 1083, 1344, 665, -1, + 1083, 665, 664, -1, 672, 666, 674, -1, + 273, 674, 666, -1, 273, 666, 274, -1, + 273, 561, 674, -1, 273, 274, 561, -1, + 1726, 1085, 1722, -1, 1726, 1090, 1085, -1, + 1697, 1865, 1696, -1, 1087, 1102, 1085, -1, + 1087, 1104, 1102, -1, 679, 1718, 1085, -1, + 679, 1085, 1102, -1, 1437, 1722, 1085, -1, + 1437, 1085, 1436, -1, 1719, 1085, 1718, -1, + 1719, 1436, 1085, -1, 1429, 1094, 1074, -1, + 1429, 1074, 1092, -1, 1694, 1865, 1697, -1, + 1724, 1090, 1726, -1, 1689, 1708, 1865, -1, + 1113, 1085, 678, -1, 1113, 1114, 1085, -1, + 1100, 678, 1085, -1, 1100, 1085, 275, -1, + 1100, 275, 677, -1, 1111, 1100, 677, -1, + 1713, 1718, 679, -1, 1123, 1070, 680, -1, + 1123, 1122, 1070, -1, 1448, 1070, 1447, -1, + 1448, 1453, 1070, -1, 1452, 1454, 1070, -1, + 1452, 1070, 1453, -1, 1119, 1681, 1684, -1, + 1119, 675, 1681, -1, 1119, 1120, 680, -1, + 1119, 680, 675, -1, 1116, 1684, 1128, -1, + 1116, 1128, 1070, -1, 1116, 1070, 1122, -1, + 1442, 276, 682, -1, 1127, 1070, 1128, -1, + 1127, 276, 1070, -1, 1127, 682, 276, -1, + 681, 1447, 1070, -1, 681, 1070, 276, -1, + 681, 1442, 1443, -1, 681, 276, 1442, -1, + 277, 1661, 278, -1, 277, 278, 279, -1, + 277, 1662, 1661, -1, 277, 1653, 1662, -1, + 277, 279, 1653, -1, 816, 280, 817, -1, + 816, 815, 280, -1, 685, 814, 686, -1, + 685, 1131, 814, -1, 1130, 281, 1131, -1, + 1130, 684, 281, -1, 687, 282, 543, -1, + 687, 688, 282, -1, 283, 284, 543, -1, + 283, 543, 285, -1, 283, 285, 958, -1, + 283, 958, 966, -1, 283, 966, 284, -1, + 694, 698, 691, -1, 819, 820, 817, -1, + 700, 286, 313, -1, 700, 313, 701, -1, + 702, 291, 286, -1, 702, 286, 700, -1, + 702, 703, 291, -1, 287, 288, 313, -1, + 287, 313, 289, -1, 287, 290, 288, -1, + 287, 289, 291, -1, 287, 292, 290, -1, + 287, 291, 292, -1, 705, 707, 939, -1, + 705, 939, 706, -1, 1732, 1137, 1731, -1, + 1746, 1901, 384, -1, 1746, 384, 293, -1, + 1746, 294, 721, -1, 1746, 293, 294, -1, + 1745, 1746, 721, -1, 1752, 1141, 1750, -1, + 1237, 466, 300, -1, 295, 299, 300, -1, + 295, 466, 296, -1, 295, 300, 466, -1, + 295, 472, 722, -1, 295, 296, 472, -1, + 295, 722, 297, -1, 295, 297, 1771, -1, + 295, 1771, 299, -1, 298, 299, 1254, -1, + 298, 300, 299, -1, 298, 1254, 1237, -1, + 298, 1237, 300, -1, 1906, 1771, 301, -1, + 1906, 1758, 1771, -1, 1906, 301, 726, -1, + 1906, 725, 1257, -1, 306, 303, 302, -1, + 306, 307, 303, -1, 306, 304, 305, -1, + 306, 302, 304, -1, 729, 305, 730, -1, + 729, 306, 305, -1, 729, 307, 306, -1, + 729, 308, 309, -1, 729, 309, 307, -1, + 729, 728, 308, -1, 1213, 1148, 310, -1, + 1213, 311, 1214, -1, 1213, 310, 311, -1, + 1484, 1151, 1215, -1, 1484, 1215, 1637, -1, + 1484, 1637, 452, -1, 1484, 452, 1486, -1, + 312, 313, 315, -1, 312, 315, 316, -1, + 312, 703, 313, -1, 312, 316, 703, -1, + 314, 316, 315, -1, 314, 315, 317, -1, + 314, 703, 316, -1, 314, 317, 703, -1, + 736, 318, 735, -1, 736, 1587, 319, -1, + 736, 319, 318, -1, 320, 321, 322, -1, + 320, 323, 321, -1, 320, 322, 1587, -1, + 320, 1587, 323, -1, 739, 324, 738, -1, + 739, 1587, 324, -1, 325, 534, 1623, -1, + 325, 328, 534, -1, 325, 1623, 326, -1, + 325, 326, 328, -1, 327, 534, 328, -1, + 327, 944, 534, -1, 327, 330, 329, -1, + 327, 328, 330, -1, 327, 329, 331, -1, + 327, 331, 944, -1, 332, 336, 333, -1, + 332, 797, 336, -1, 332, 334, 797, -1, + 332, 335, 334, -1, 332, 333, 335, -1, + 794, 336, 797, -1, 794, 337, 336, -1, + 794, 795, 337, -1, 401, 339, 338, -1, + 401, 340, 339, -1, 401, 341, 342, -1, + 401, 342, 340, -1, 401, 400, 341, -1, + 401, 343, 397, -1, 401, 338, 343, -1, + 348, 510, 349, -1, 348, 609, 510, -1, + 348, 350, 610, -1, 348, 610, 609, -1, + 1499, 1403, 1402, -1, 1499, 1402, 1408, -1, + 344, 760, 359, -1, 344, 359, 345, -1, + 344, 345, 346, -1, 344, 346, 758, -1, + 344, 758, 760, -1, 1167, 349, 347, -1, + 1167, 347, 754, -1, 1167, 1168, 351, -1, + 759, 348, 349, -1, 759, 350, 348, -1, + 759, 349, 1167, -1, 759, 1167, 351, -1, + 759, 757, 350, -1, 759, 351, 760, -1, + 764, 352, 763, -1, 764, 353, 352, -1, + 764, 765, 354, -1, 764, 354, 355, -1, + 764, 355, 353, -1, 762, 1497, 356, -1, + 762, 356, 357, -1, 762, 357, 766, -1, + 358, 359, 1497, -1, 358, 763, 359, -1, + 358, 1497, 762, -1, 358, 762, 763, -1, + 768, 360, 361, -1, 768, 792, 791, -1, + 768, 791, 360, -1, 1179, 849, 770, -1, + 1179, 361, 849, -1, 1179, 768, 361, -1, + 1179, 1178, 768, -1, 772, 773, 770, -1, + 772, 434, 428, -1, 772, 362, 1171, -1, + 772, 428, 362, -1, 1202, 1160, 1156, -1, + 1202, 1156, 1203, -1, 1202, 1197, 1160, -1, + 775, 1157, 795, -1, 775, 1156, 1157, -1, + 778, 1189, 1191, -1, 1185, 1184, 363, -1, + 1185, 407, 1200, -1, 1185, 363, 1205, -1, + 1185, 1205, 407, -1, 1516, 366, 1518, -1, + 1516, 1208, 1206, -1, 1516, 1206, 366, -1, + 364, 777, 366, -1, 364, 366, 1206, -1, + 364, 1184, 777, -1, 364, 1206, 1184, -1, + 365, 769, 1518, -1, 365, 1518, 366, -1, + 365, 1511, 769, -1, 365, 366, 777, -1, + 365, 777, 1511, -1, 367, 783, 1133, -1, + 367, 369, 783, -1, 367, 1133, 686, -1, + 367, 686, 369, -1, 782, 785, 808, -1, + 782, 808, 783, -1, 784, 783, 369, -1, + 788, 368, 414, -1, 788, 414, 371, -1, + 788, 369, 368, -1, 788, 784, 369, -1, + 370, 404, 787, -1, 370, 405, 404, -1, + 370, 371, 405, -1, 370, 788, 371, -1, + 370, 787, 788, -1, 786, 805, 785, -1, + 786, 403, 805, -1, 786, 404, 403, -1, + 786, 787, 404, -1, 790, 789, 376, -1, + 790, 372, 791, -1, 790, 373, 372, -1, + 790, 376, 373, -1, 374, 789, 799, -1, + 374, 799, 375, -1, 374, 376, 789, -1, + 374, 375, 377, -1, 374, 377, 376, -1, + 796, 1522, 779, -1, 796, 799, 1522, -1, + 796, 779, 795, -1, 378, 380, 379, -1, + 378, 800, 380, -1, 378, 379, 1531, -1, + 378, 1531, 800, -1, 1527, 389, 800, -1, + 1527, 1528, 393, -1, 1195, 1200, 801, -1, + 1538, 381, 1197, -1, 1538, 1539, 381, -1, + 382, 838, 383, -1, 382, 432, 838, -1, + 382, 383, 384, -1, 382, 385, 432, -1, + 382, 384, 386, -1, 382, 386, 385, -1, + 390, 399, 398, -1, 390, 391, 399, -1, + 387, 388, 389, -1, 387, 398, 388, -1, + 387, 390, 398, -1, 387, 391, 390, -1, + 387, 392, 391, -1, 387, 1527, 393, -1, + 387, 389, 1527, -1, 387, 393, 394, -1, + 387, 394, 392, -1, 395, 611, 396, -1, + 395, 397, 611, -1, 395, 398, 399, -1, + 395, 396, 398, -1, 395, 399, 400, -1, + 395, 401, 397, -1, 395, 400, 401, -1, + 402, 403, 404, -1, 402, 1546, 403, -1, + 402, 404, 1547, -1, 402, 1547, 1546, -1, + 802, 1547, 404, -1, 802, 404, 405, -1, + 802, 405, 803, -1, 406, 801, 407, -1, + 406, 1543, 801, -1, 406, 1205, 812, -1, + 406, 407, 1205, -1, 406, 812, 1545, -1, + 406, 1545, 1543, -1, 807, 408, 810, -1, + 807, 805, 408, -1, 1173, 810, 780, -1, + 1173, 958, 808, -1, 1173, 1172, 948, -1, + 811, 780, 810, -1, 409, 812, 809, -1, + 409, 809, 1546, -1, 409, 1545, 812, -1, + 409, 1546, 1545, -1, 410, 411, 821, -1, + 410, 695, 412, -1, 410, 412, 413, -1, + 410, 413, 411, -1, 410, 821, 819, -1, + 410, 819, 695, -1, 823, 414, 813, -1, + 823, 824, 414, -1, 711, 1731, 1137, -1, + 711, 415, 418, -1, 711, 1137, 415, -1, + 826, 711, 418, -1, 826, 712, 711, -1, + 826, 425, 827, -1, 826, 1139, 712, -1, + 424, 427, 416, -1, 424, 416, 431, -1, + 424, 431, 422, -1, 417, 418, 419, -1, + 417, 419, 426, -1, 417, 426, 425, -1, + 417, 826, 418, -1, 417, 425, 826, -1, + 420, 422, 421, -1, 420, 421, 423, -1, + 420, 424, 422, -1, 420, 827, 425, -1, + 420, 423, 827, -1, 420, 425, 426, -1, + 420, 426, 427, -1, 420, 427, 424, -1, + 429, 834, 841, -1, 429, 848, 834, -1, + 429, 434, 848, -1, 429, 832, 428, -1, + 429, 428, 434, -1, 831, 430, 833, -1, + 831, 832, 429, -1, 831, 841, 430, -1, + 831, 429, 841, -1, 840, 431, 430, -1, + 840, 430, 841, -1, 840, 432, 431, -1, + 840, 837, 432, -1, 839, 730, 838, -1, + 839, 843, 730, -1, 845, 846, 835, -1, + 433, 847, 848, -1, 433, 848, 434, -1, + 433, 770, 849, -1, 433, 849, 847, -1, + 433, 772, 770, -1, 433, 434, 772, -1, + 850, 849, 435, -1, 850, 435, 851, -1, + 852, 1210, 436, -1, 852, 436, 1393, -1, + 852, 1398, 1400, -1, 852, 1393, 1398, -1, + 1636, 1637, 1215, -1, 1640, 1400, 1399, -1, + 1552, 1214, 853, -1, 1552, 853, 437, -1, + 1552, 437, 1553, -1, 854, 853, 1218, -1, + 1217, 853, 857, -1, 1217, 1218, 853, -1, + 861, 860, 857, -1, 861, 853, 881, -1, + 861, 857, 853, -1, 866, 858, 477, -1, + 866, 864, 726, -1, 866, 726, 868, -1, + 876, 857, 878, -1, 876, 871, 858, -1, + 876, 858, 857, -1, 876, 878, 440, -1, + 876, 440, 438, -1, 876, 438, 881, -1, + 1221, 1224, 878, -1, 1221, 878, 857, -1, + 1221, 857, 860, -1, 1221, 860, 881, -1, + 1221, 881, 1222, -1, 439, 881, 440, -1, + 439, 878, 881, -1, 439, 440, 878, -1, + 869, 726, 867, -1, 869, 868, 726, -1, + 441, 442, 443, -1, 441, 444, 442, -1, + 441, 450, 444, -1, 441, 445, 450, -1, + 441, 443, 446, -1, 441, 446, 447, -1, + 441, 448, 445, -1, 441, 447, 448, -1, + 1779, 1294, 1577, -1, 449, 450, 453, -1, + 449, 453, 455, -1, 449, 451, 450, -1, + 449, 999, 451, -1, 449, 452, 999, -1, + 449, 1486, 452, -1, 449, 455, 1486, -1, + 731, 453, 454, -1, 731, 455, 453, -1, + 731, 1486, 455, -1, 731, 454, 470, -1, + 731, 470, 1148, -1, 883, 458, 459, -1, + 883, 456, 458, -1, 883, 459, 483, -1, + 883, 483, 882, -1, 883, 1227, 456, -1, + 457, 459, 458, -1, 457, 458, 461, -1, + 457, 461, 462, -1, 457, 481, 459, -1, + 457, 462, 481, -1, 460, 462, 461, -1, + 460, 1354, 462, -1, 460, 1356, 1354, -1, + 460, 577, 1356, -1, 460, 463, 1000, -1, + 460, 461, 463, -1, 460, 1000, 998, -1, + 460, 998, 577, -1, 464, 1145, 723, -1, + 464, 723, 471, -1, 464, 465, 1145, -1, + 464, 471, 465, -1, 1236, 468, 466, -1, + 1236, 466, 1237, -1, 467, 1235, 885, -1, + 467, 885, 468, -1, 467, 1236, 1235, -1, + 467, 468, 1236, -1, 469, 884, 470, -1, + 469, 470, 471, -1, 469, 471, 723, -1, + 469, 723, 472, -1, 469, 472, 884, -1, + 1232, 732, 884, -1, 1232, 1239, 732, -1, + 473, 1249, 872, -1, 473, 872, 888, -1, + 890, 889, 1559, -1, 890, 1559, 891, -1, + 887, 473, 888, -1, 1247, 1245, 1252, -1, + 1247, 887, 475, -1, 1247, 473, 887, -1, + 1247, 1249, 473, -1, 474, 475, 887, -1, + 474, 887, 891, -1, 474, 1247, 475, -1, + 474, 1246, 1247, -1, 474, 891, 1559, -1, + 474, 1559, 1246, -1, 1767, 1260, 1254, -1, + 1478, 476, 1475, -1, 1478, 477, 476, -1, + 1478, 866, 477, -1, 1478, 863, 866, -1, + 1478, 725, 863, -1, 1478, 1257, 725, -1, + 1473, 1477, 1260, -1, 893, 1475, 476, -1, + 893, 1477, 1475, -1, 893, 476, 477, -1, + 893, 1249, 1254, -1, 893, 478, 1249, -1, + 893, 479, 478, -1, 893, 871, 479, -1, + 893, 477, 871, -1, 490, 1270, 1269, -1, + 490, 1276, 1272, -1, 490, 492, 1276, -1, + 1271, 1270, 490, -1, 1271, 490, 1272, -1, + 1671, 906, 905, -1, 1844, 518, 934, -1, + 1844, 636, 518, -1, 899, 1670, 1671, -1, + 899, 1671, 905, -1, 903, 899, 905, -1, + 907, 903, 905, -1, 1583, 1277, 910, -1, + 480, 481, 482, -1, 480, 482, 486, -1, + 480, 483, 481, -1, 480, 486, 483, -1, + 484, 485, 882, -1, 484, 882, 486, -1, + 484, 486, 485, -1, 488, 915, 913, -1, + 488, 487, 1280, -1, 488, 1280, 915, -1, + 914, 915, 1280, -1, 1283, 914, 911, -1, + 1785, 1784, 1283, -1, 1785, 1283, 911, -1, + 919, 1282, 487, -1, 919, 487, 488, -1, + 919, 488, 913, -1, 920, 1292, 491, -1, + 489, 1269, 894, -1, 489, 894, 1288, -1, + 489, 490, 1269, -1, 489, 920, 491, -1, + 489, 1288, 920, -1, 489, 491, 492, -1, + 489, 492, 490, -1, 923, 499, 1303, -1, + 923, 1285, 501, -1, 1302, 1303, 498, -1, + 1302, 498, 1305, -1, 493, 494, 1305, -1, + 493, 1305, 498, -1, 493, 495, 494, -1, + 493, 496, 495, -1, 493, 500, 496, -1, + 493, 498, 500, -1, 497, 498, 499, -1, + 497, 500, 498, -1, 497, 499, 923, -1, + 497, 923, 501, -1, 497, 503, 502, -1, + 497, 502, 500, -1, 497, 504, 503, -1, + 497, 501, 504, -1, 1793, 505, 1795, -1, + 1793, 506, 505, -1, 1793, 507, 506, -1, + 1793, 1296, 507, -1, 1589, 1586, 1295, -1, + 1300, 923, 1303, -1, 1300, 924, 923, -1, + 1299, 1581, 924, -1, 1299, 924, 1300, -1, + 928, 510, 609, -1, 928, 609, 929, -1, + 1008, 1166, 1029, -1, 1008, 509, 1166, -1, + 1008, 1007, 509, -1, 508, 1491, 1166, -1, + 508, 1166, 509, -1, 508, 928, 1491, -1, + 508, 509, 510, -1, 508, 510, 928, -1, + 511, 516, 512, -1, 511, 1591, 516, -1, + 511, 512, 513, -1, 511, 513, 514, -1, + 511, 514, 515, -1, 511, 515, 1591, -1, + 931, 933, 516, -1, 931, 516, 1591, -1, + 1062, 933, 636, -1, 1062, 517, 933, -1, + 1062, 1061, 517, -1, 1311, 518, 636, -1, + 1311, 636, 932, -1, 1311, 934, 518, -1, + 938, 939, 532, -1, 936, 938, 532, -1, + 936, 530, 937, -1, 936, 532, 530, -1, + 1315, 525, 1597, -1, 1315, 1316, 525, -1, + 940, 519, 1316, -1, 940, 520, 519, -1, + 940, 1596, 520, -1, 524, 525, 1596, -1, + 521, 1596, 522, -1, 521, 522, 523, -1, + 521, 524, 1596, -1, 521, 523, 525, -1, + 521, 525, 524, -1, 526, 531, 527, -1, + 526, 530, 531, -1, 526, 527, 528, -1, + 526, 528, 530, -1, 529, 531, 530, -1, + 529, 530, 532, -1, 529, 939, 531, -1, + 529, 532, 939, -1, 1322, 1956, 946, -1, + 1607, 941, 533, -1, 1607, 533, 942, -1, + 1603, 944, 1602, -1, 1625, 1624, 534, -1, + 1625, 534, 943, -1, 535, 536, 537, -1, + 535, 538, 536, -1, 535, 833, 538, -1, + 535, 537, 539, -1, 535, 539, 833, -1, + 1820, 1618, 948, -1, 1613, 1827, 1826, -1, + 1613, 1618, 1827, -1, 1613, 1826, 1825, -1, + 1613, 1825, 1328, -1, 953, 1330, 942, -1, + 953, 942, 951, -1, 952, 540, 954, -1, + 952, 541, 540, -1, 952, 542, 541, -1, + 952, 950, 542, -1, 964, 687, 543, -1, + 964, 965, 687, -1, 964, 543, 966, -1, + 1334, 962, 959, -1, 1347, 544, 1339, -1, + 1347, 967, 544, -1, 1630, 1631, 545, -1, + 1630, 545, 1078, -1, 1338, 1347, 1339, -1, + 1338, 1335, 1347, -1, 956, 1332, 962, -1, + 956, 1329, 1809, -1, 956, 957, 1329, -1, + 546, 1632, 1332, -1, 546, 1811, 1632, -1, + 546, 1809, 1811, -1, 546, 956, 1809, -1, + 546, 1332, 956, -1, 1819, 547, 1611, -1, + 1819, 548, 547, -1, 1819, 549, 548, -1, + 1819, 1818, 954, -1, 1819, 954, 549, -1, + 550, 692, 690, -1, 550, 690, 551, -1, + 550, 552, 692, -1, 550, 551, 552, -1, + 553, 690, 691, -1, 553, 554, 555, -1, + 553, 555, 690, -1, 553, 556, 554, -1, + 553, 557, 556, -1, 553, 560, 557, -1, + 553, 691, 560, -1, 558, 560, 559, -1, + 558, 561, 560, -1, 558, 559, 562, -1, + 558, 562, 563, -1, 558, 674, 561, -1, + 558, 673, 674, -1, 558, 563, 673, -1, + 564, 974, 973, -1, 564, 565, 974, -1, + 564, 973, 566, -1, 564, 566, 980, -1, + 564, 980, 565, -1, 972, 589, 971, -1, + 972, 975, 589, -1, 567, 568, 975, -1, + 567, 570, 569, -1, 567, 569, 568, -1, + 567, 571, 570, -1, 567, 975, 571, -1, + 979, 980, 755, -1, 572, 573, 581, -1, + 572, 581, 1387, -1, 572, 1388, 573, -1, + 572, 1387, 1388, -1, 574, 585, 1387, -1, + 574, 576, 585, -1, 574, 1387, 581, -1, + 574, 581, 578, -1, 574, 578, 575, -1, + 574, 575, 983, -1, 574, 983, 576, -1, + 986, 576, 983, -1, 986, 1019, 585, -1, + 986, 585, 576, -1, 985, 983, 1006, -1, + 985, 1006, 988, -1, 985, 988, 994, -1, + 1355, 992, 1353, -1, 1642, 1356, 577, -1, + 1642, 577, 998, -1, 1362, 1363, 994, -1, + 1833, 1642, 998, -1, 1031, 1029, 1001, -1, + 1003, 983, 578, -1, 1003, 579, 1002, -1, + 1003, 580, 579, -1, 1003, 578, 581, -1, + 1003, 581, 580, -1, 1003, 1006, 983, -1, + 584, 1646, 1645, -1, 584, 1009, 1646, -1, + 584, 1927, 582, -1, 584, 582, 1010, -1, + 584, 1010, 1009, -1, 1011, 1369, 1371, -1, + 1011, 1371, 1009, -1, 1644, 583, 981, -1, + 1644, 1373, 583, -1, 1839, 584, 1645, -1, + 1839, 1927, 584, -1, 1376, 1021, 1377, -1, + 1383, 1021, 1382, -1, 1383, 1390, 1021, -1, + 1386, 1387, 585, -1, 1386, 585, 1019, -1, + 1381, 1367, 586, -1, 1381, 586, 1388, -1, + 1366, 1367, 1379, -1, 1366, 1379, 1380, -1, + 1366, 1380, 1370, -1, 587, 588, 1370, -1, + 587, 590, 589, -1, 587, 589, 588, -1, + 587, 1380, 590, -1, 587, 1370, 1380, -1, + 591, 593, 592, -1, 591, 594, 593, -1, + 591, 592, 595, -1, 591, 595, 594, -1, + 1025, 1026, 596, -1, 1025, 616, 1023, -1, + 1025, 597, 616, -1, 1025, 596, 597, -1, + 606, 598, 752, -1, 606, 599, 598, -1, + 606, 605, 599, -1, 1028, 1004, 1001, -1, + 1028, 1001, 1029, -1, 1028, 1494, 600, -1, + 602, 600, 601, -1, 602, 1004, 1028, -1, + 602, 1028, 600, -1, 602, 752, 1004, -1, + 602, 753, 752, -1, 1493, 600, 1494, -1, + 1493, 601, 600, -1, 1493, 602, 601, -1, + 1493, 753, 602, -1, 603, 1007, 1032, -1, + 603, 1032, 1403, -1, 603, 754, 1007, -1, + 603, 1403, 754, -1, 604, 751, 1037, -1, + 604, 1037, 605, -1, 604, 605, 606, -1, + 604, 752, 751, -1, 604, 606, 752, -1, + 607, 608, 749, -1, 607, 749, 930, -1, + 607, 930, 929, -1, 607, 609, 610, -1, + 607, 929, 609, -1, 607, 610, 611, -1, + 607, 611, 608, -1, 1658, 612, 1659, -1, + 1658, 1033, 613, -1, 1658, 614, 612, -1, + 1658, 613, 614, -1, 1036, 1038, 1040, -1, + 1036, 615, 1037, -1, 1036, 1040, 1023, -1, + 1036, 616, 615, -1, 1036, 1023, 616, -1, + 1652, 1039, 1411, -1, 1652, 1038, 1039, -1, + 1652, 1040, 1038, -1, 617, 619, 618, -1, + 617, 618, 620, -1, 617, 897, 619, -1, + 617, 620, 897, -1, 621, 622, 1665, -1, + 621, 1665, 623, -1, 621, 624, 622, -1, + 621, 623, 624, -1, 625, 1024, 626, -1, + 625, 626, 628, -1, 625, 627, 1024, -1, + 625, 1043, 627, -1, 625, 628, 1043, -1, + 1416, 628, 1041, -1, 1416, 1043, 628, -1, + 1071, 648, 647, -1, 1071, 647, 1415, -1, + 629, 630, 1047, -1, 629, 1047, 631, -1, + 629, 631, 632, -1, 629, 633, 630, -1, + 629, 632, 633, -1, 1049, 634, 1067, -1, + 1049, 1047, 635, -1, 1049, 635, 634, -1, + 1845, 636, 1844, -1, 1845, 1062, 636, -1, + 1845, 1672, 1062, -1, 1421, 1419, 1059, -1, + 1418, 637, 1419, -1, 1418, 1420, 640, -1, + 1418, 640, 638, -1, 1418, 639, 637, -1, + 1418, 638, 639, -1, 1066, 640, 1065, -1, + 1066, 1067, 641, -1, 1066, 642, 640, -1, + 1066, 643, 642, -1, 1066, 641, 643, -1, + 644, 645, 646, -1, 644, 646, 647, -1, + 644, 648, 645, -1, 644, 647, 648, -1, + 1069, 1454, 1124, -1, 1069, 1070, 1454, -1, + 1069, 649, 648, -1, 1069, 648, 1071, -1, + 1076, 1092, 1074, -1, 1076, 1124, 1092, -1, + 1076, 1075, 649, -1, 1076, 1069, 1124, -1, + 1076, 649, 1069, -1, 1080, 654, 650, -1, + 1080, 651, 1344, -1, 1080, 650, 651, -1, + 1079, 652, 653, -1, 1079, 653, 654, -1, + 1079, 1078, 652, -1, 1079, 654, 1080, -1, + 655, 657, 656, -1, 655, 658, 657, -1, + 655, 659, 658, -1, 655, 660, 661, -1, + 655, 661, 659, -1, 655, 662, 660, -1, + 655, 656, 662, -1, 1082, 672, 968, -1, + 1082, 666, 672, -1, 1082, 968, 1426, -1, + 1082, 1426, 1084, -1, 663, 1083, 664, -1, + 663, 664, 665, -1, 663, 666, 1082, -1, + 663, 1082, 1083, -1, 663, 665, 667, -1, + 663, 668, 666, -1, 663, 667, 669, -1, + 663, 669, 668, -1, 670, 671, 968, -1, + 670, 968, 672, -1, 670, 673, 671, -1, + 670, 674, 673, -1, 670, 672, 674, -1, + 1107, 1087, 1085, -1, 1680, 1681, 675, -1, + 1680, 675, 1682, -1, 1859, 1686, 1856, -1, + 1859, 1430, 1686, -1, 1093, 1684, 1429, -1, + 1438, 1686, 1430, -1, 1690, 1865, 1862, -1, + 1703, 1857, 1855, -1, 1097, 676, 1095, -1, + 1097, 677, 676, -1, 1097, 1111, 677, -1, + 1110, 1113, 678, -1, 1110, 1112, 1113, -1, + 1110, 678, 1100, -1, 1712, 679, 1102, -1, + 1712, 1713, 679, -1, 1717, 1429, 1686, -1, + 1717, 1111, 1429, -1, 1717, 1712, 1104, -1, + 1717, 1106, 1114, -1, 1121, 680, 1120, -1, + 1121, 1123, 680, -1, 1118, 1116, 1122, -1, + 1451, 1092, 1124, -1, 1451, 1453, 1440, -1, + 1451, 1684, 1092, -1, 1451, 1442, 1684, -1, + 1444, 1447, 681, -1, 1444, 681, 1443, -1, + 1126, 682, 1127, -1, 1126, 1442, 682, -1, + 1134, 683, 684, -1, 1134, 684, 1130, -1, + 1134, 1133, 958, -1, 1134, 958, 683, -1, + 1132, 1131, 685, -1, 1132, 686, 1133, -1, + 1132, 685, 686, -1, 960, 687, 965, -1, + 960, 1340, 688, -1, 960, 688, 687, -1, + 689, 691, 690, -1, 689, 694, 691, -1, + 689, 690, 692, -1, 689, 692, 695, -1, + 689, 695, 694, -1, 693, 694, 695, -1, + 693, 695, 819, -1, 693, 819, 817, -1, + 693, 817, 696, -1, 693, 696, 697, -1, + 693, 697, 698, -1, 693, 698, 694, -1, + 699, 700, 701, -1, 699, 702, 700, -1, + 699, 701, 703, -1, 699, 703, 702, -1, + 704, 705, 706, -1, 704, 708, 707, -1, + 704, 707, 705, -1, 704, 937, 708, -1, + 704, 706, 937, -1, 1138, 709, 1136, -1, + 1138, 1137, 1732, -1, 1138, 710, 709, -1, + 1138, 1172, 710, -1, 1138, 948, 1172, -1, + 1138, 1319, 948, -1, 1138, 1458, 1319, -1, + 1463, 1319, 1462, -1, 1730, 1731, 711, -1, + 1730, 711, 712, -1, 1730, 712, 1139, -1, + 1876, 1735, 718, -1, 1876, 718, 1877, -1, + 1935, 1877, 713, -1, 1935, 1933, 1877, -1, + 1935, 714, 1934, -1, 1935, 715, 714, -1, + 1935, 713, 715, -1, 716, 1889, 717, -1, + 716, 1740, 1889, -1, 716, 1735, 1740, -1, + 716, 718, 1735, -1, 716, 719, 718, -1, + 716, 720, 719, -1, 716, 717, 720, -1, + 1464, 721, 722, -1, 1464, 1745, 721, -1, + 1464, 722, 723, -1, 1751, 723, 1143, -1, + 1751, 1143, 1752, -1, 1751, 1464, 723, -1, + 1753, 1141, 1752, -1, 1753, 1752, 1143, -1, + 1146, 1472, 1771, -1, 1146, 1771, 1758, -1, + 724, 863, 725, -1, 724, 725, 1906, -1, + 724, 726, 863, -1, 724, 1906, 726, -1, + 727, 843, 728, -1, 727, 728, 729, -1, + 727, 730, 843, -1, 727, 729, 730, -1, + 1150, 731, 1148, -1, 1150, 1213, 1215, -1, + 1150, 1486, 731, -1, 1483, 1484, 1486, -1, + 1238, 732, 1239, -1, 1238, 1559, 732, -1, + 1238, 1911, 1559, -1, 733, 735, 734, -1, + 733, 736, 735, -1, 733, 734, 1587, -1, + 733, 1587, 736, -1, 1154, 738, 737, -1, + 1154, 739, 738, -1, 1154, 737, 1153, -1, + 1154, 1587, 739, -1, 1161, 1160, 1197, -1, + 1161, 1197, 740, -1, 1161, 741, 747, -1, + 1161, 747, 744, -1, 1161, 742, 741, -1, + 1161, 740, 742, -1, 1159, 743, 1158, -1, + 1159, 1161, 744, -1, 1159, 745, 743, -1, + 1159, 746, 745, -1, 1159, 747, 746, -1, + 1159, 744, 747, -1, 1034, 1411, 1039, -1, + 1034, 749, 748, -1, 1034, 748, 1033, -1, + 1164, 1163, 930, -1, 1164, 1039, 1165, -1, + 1164, 1034, 1039, -1, 1164, 930, 749, -1, + 1164, 749, 1034, -1, 750, 1165, 1037, -1, + 750, 1489, 1165, -1, 750, 1037, 751, -1, + 750, 751, 1489, -1, 1488, 1163, 1489, -1, + 1490, 1489, 751, -1, 1490, 751, 752, -1, + 1490, 752, 753, -1, 1490, 753, 1493, -1, + 1500, 754, 1403, -1, 1500, 1403, 1499, -1, + 1500, 1167, 754, -1, 977, 1499, 1408, -1, + 977, 1498, 1499, -1, 977, 755, 1498, -1, + 977, 979, 755, -1, 756, 758, 757, -1, + 756, 757, 759, -1, 756, 760, 758, -1, + 756, 759, 760, -1, 761, 763, 762, -1, + 761, 765, 764, -1, 761, 764, 763, -1, + 761, 762, 766, -1, 761, 767, 765, -1, + 761, 766, 767, -1, 1505, 1508, 1170, -1, + 1505, 1170, 1503, -1, 1506, 1193, 792, -1, + 1506, 792, 768, -1, 1506, 768, 1178, -1, + 1512, 1194, 1502, -1, 1512, 1502, 1503, -1, + 1174, 1511, 1513, -1, 1174, 769, 1511, -1, + 1174, 1518, 769, -1, 1177, 770, 773, -1, + 1177, 1179, 770, -1, 1176, 1177, 774, -1, + 771, 772, 1171, -1, 771, 773, 772, -1, + 771, 1171, 1176, -1, 771, 1176, 774, -1, + 771, 1177, 773, -1, 771, 774, 1177, -1, + 1181, 1203, 1156, -1, 1181, 1156, 775, -1, + 1181, 779, 1188, -1, 1181, 795, 779, -1, + 1181, 775, 795, -1, 1186, 1511, 777, -1, + 1186, 778, 1191, -1, 776, 777, 1184, -1, + 776, 1184, 1183, -1, 776, 1186, 777, -1, + 776, 778, 1186, -1, 776, 1183, 1189, -1, + 776, 1189, 778, -1, 1190, 779, 1522, -1, + 1190, 1188, 779, -1, 1515, 1518, 1174, -1, + 1515, 1208, 1516, -1, 1515, 811, 1208, -1, + 1515, 780, 811, -1, 1515, 1173, 780, -1, + 781, 782, 783, -1, 781, 783, 784, -1, + 781, 785, 782, -1, 781, 786, 785, -1, + 781, 787, 786, -1, 781, 788, 787, -1, + 781, 784, 788, -1, 1192, 1194, 1191, -1, + 1192, 1191, 1521, -1, 1524, 1523, 789, -1, + 1524, 789, 790, -1, 1524, 790, 791, -1, + 1524, 791, 792, -1, 1524, 792, 1193, -1, + 793, 795, 794, -1, 793, 796, 795, -1, + 793, 797, 798, -1, 793, 794, 797, -1, + 793, 798, 799, -1, 793, 799, 796, -1, + 1530, 800, 1531, -1, 1530, 1527, 800, -1, + 1537, 801, 1543, -1, 1537, 1195, 801, -1, + 1201, 1200, 1195, -1, 1196, 1197, 1202, -1, + 1196, 1202, 1201, -1, 1550, 1547, 802, -1, + 1550, 802, 803, -1, 1550, 803, 1526, -1, + 1542, 1537, 1543, -1, 804, 806, 805, -1, + 804, 805, 807, -1, 804, 808, 806, -1, + 804, 1173, 808, -1, 804, 807, 810, -1, + 804, 810, 1173, -1, 1207, 810, 809, -1, + 1207, 811, 810, -1, 1207, 809, 812, -1, + 1207, 812, 1205, -1, 1207, 1208, 811, -1, + 822, 813, 814, -1, 822, 823, 813, -1, + 822, 814, 815, -1, 822, 815, 816, -1, + 822, 817, 820, -1, 822, 816, 817, -1, + 818, 820, 819, -1, 818, 819, 821, -1, + 818, 822, 820, -1, 818, 823, 822, -1, + 818, 821, 824, -1, 818, 824, 823, -1, + 825, 826, 827, -1, 825, 828, 829, -1, + 825, 827, 828, -1, 825, 1139, 826, -1, + 825, 829, 1466, -1, 825, 1466, 1139, -1, + 830, 832, 831, -1, 830, 831, 833, -1, + 830, 1172, 832, -1, 830, 833, 1172, -1, + 842, 841, 834, -1, 842, 834, 848, -1, + 842, 848, 845, -1, 842, 835, 843, -1, + 842, 845, 835, -1, 836, 838, 837, -1, + 836, 839, 838, -1, 836, 840, 841, -1, + 836, 837, 840, -1, 836, 841, 842, -1, + 836, 843, 839, -1, 836, 842, 843, -1, + 844, 846, 845, -1, 844, 848, 847, -1, + 844, 845, 848, -1, 844, 847, 849, -1, + 844, 849, 850, -1, 844, 851, 846, -1, + 844, 850, 851, -1, 1396, 1017, 1386, -1, + 1396, 1212, 1401, -1, 1557, 852, 1400, -1, + 1557, 1210, 852, -1, 1639, 1399, 1401, -1, + 1639, 1640, 1399, -1, 1639, 1401, 1212, -1, + 855, 856, 853, -1, 855, 853, 854, -1, + 1219, 854, 1218, -1, 1219, 856, 855, -1, + 1219, 855, 854, -1, 1219, 1217, 857, -1, + 1219, 867, 856, -1, 1219, 866, 867, -1, + 1219, 857, 858, -1, 1219, 858, 866, -1, + 1223, 881, 1224, -1, 1223, 1222, 881, -1, + 859, 881, 860, -1, 859, 861, 881, -1, + 859, 860, 861, -1, 862, 863, 864, -1, + 862, 864, 866, -1, 862, 866, 863, -1, + 865, 867, 866, -1, 865, 866, 868, -1, + 865, 869, 867, -1, 865, 868, 869, -1, + 870, 871, 876, -1, 870, 1249, 871, -1, + 870, 872, 1249, -1, 870, 888, 872, -1, + 870, 873, 888, -1, 870, 875, 873, -1, + 870, 876, 875, -1, 874, 881, 875, -1, + 874, 876, 881, -1, 874, 875, 876, -1, + 879, 1224, 881, -1, 879, 881, 880, -1, + 877, 878, 1224, -1, 877, 1224, 879, -1, + 877, 879, 880, -1, 877, 881, 878, -1, + 877, 880, 881, -1, 1228, 882, 1231, -1, + 1228, 883, 882, -1, 1228, 1227, 883, -1, + 1234, 884, 885, -1, 1234, 1232, 884, -1, + 1234, 885, 1235, -1, 1241, 1239, 1232, -1, + 1241, 1232, 1233, -1, 886, 887, 888, -1, + 886, 888, 889, -1, 886, 889, 890, -1, + 886, 890, 891, -1, 886, 891, 887, -1, + 1909, 1911, 1238, -1, 1558, 1240, 1559, -1, + 1561, 1559, 1240, -1, 1561, 1248, 1559, -1, + 1561, 1240, 1562, -1, 1251, 1559, 1248, -1, + 1253, 1251, 1248, -1, 1915, 1256, 1771, -1, + 1766, 1260, 1767, -1, 892, 1260, 1477, -1, + 892, 1477, 893, -1, 892, 1254, 1260, -1, + 892, 893, 1254, -1, 1266, 1314, 894, -1, + 1266, 1313, 1314, -1, 1266, 894, 1269, -1, + 1268, 1276, 1275, -1, 1268, 1272, 1276, -1, + 895, 1844, 934, -1, 895, 1842, 1844, -1, + 895, 1273, 1842, -1, 1570, 1842, 1273, -1, + 1570, 906, 1671, -1, 1570, 1671, 1842, -1, + 1274, 895, 934, -1, 1274, 1273, 895, -1, + 1274, 1268, 1275, -1, 1274, 1267, 1268, -1, + 896, 903, 904, -1, 896, 897, 1054, -1, + 896, 904, 897, -1, 896, 1054, 1045, -1, + 896, 1045, 903, -1, 898, 903, 1045, -1, + 898, 899, 903, -1, 898, 1045, 1064, -1, + 898, 1064, 900, -1, 898, 900, 1670, -1, + 898, 1670, 899, -1, 901, 908, 1005, -1, + 901, 1005, 907, -1, 901, 907, 908, -1, + 902, 904, 903, -1, 902, 903, 907, -1, + 902, 1005, 904, -1, 902, 907, 1005, -1, + 1569, 905, 906, -1, 1569, 907, 905, -1, + 1569, 906, 1570, -1, 1569, 1572, 908, -1, + 1569, 908, 907, -1, 1291, 909, 1292, -1, + 1291, 910, 909, -1, 1291, 1583, 910, -1, + 1308, 1785, 911, -1, 1281, 914, 1280, -1, + 1281, 911, 914, -1, 1281, 1308, 911, -1, + 1777, 913, 1283, -1, 1777, 919, 913, -1, + 912, 1283, 913, -1, 912, 914, 1283, -1, + 912, 913, 915, -1, 912, 915, 914, -1, + 1229, 1282, 1574, -1, 1229, 1230, 916, -1, + 1229, 916, 917, -1, 1229, 917, 918, -1, + 1229, 918, 1282, -1, 1776, 1282, 919, -1, + 1776, 919, 1777, -1, 1287, 1292, 920, -1, + 1287, 921, 1285, -1, 1287, 1309, 921, -1, + 1287, 920, 1288, -1, 922, 923, 924, -1, + 922, 924, 1290, -1, 922, 1285, 923, -1, + 922, 1290, 1285, -1, 1580, 924, 1581, -1, + 1580, 1290, 924, -1, 1306, 1305, 925, -1, + 1306, 925, 926, -1, 1584, 926, 1585, -1, + 1584, 1306, 926, -1, 1304, 1300, 1303, -1, + 1304, 1293, 1789, -1, 1304, 1584, 1293, -1, + 1788, 1299, 1789, -1, 1788, 1581, 1299, -1, + 927, 1491, 928, -1, 927, 928, 929, -1, + 927, 1488, 1491, -1, 927, 1163, 1488, -1, + 927, 929, 930, -1, 927, 930, 1163, -1, + 1594, 931, 1591, -1, 1594, 1311, 932, -1, + 1594, 932, 933, -1, 1594, 933, 931, -1, + 1312, 934, 1311, -1, 1312, 1274, 934, -1, + 1312, 1267, 1274, -1, 1312, 1313, 1266, -1, + 1312, 1266, 1267, -1, 935, 936, 937, -1, + 935, 938, 936, -1, 935, 937, 939, -1, + 935, 939, 938, -1, 1317, 940, 1316, -1, + 1317, 1596, 940, -1, 947, 1322, 946, -1, + 947, 1820, 948, -1, 1321, 1956, 1322, -1, + 1323, 948, 1319, -1, 1323, 947, 948, -1, + 1323, 1322, 947, -1, 1327, 1601, 941, -1, + 1327, 941, 1607, -1, 1621, 942, 1330, -1, + 1621, 1607, 942, -1, 1604, 1625, 943, -1, + 1604, 1608, 1625, -1, 1604, 943, 944, -1, + 1604, 944, 1603, -1, 1615, 953, 1616, -1, + 1615, 1825, 1824, -1, 1615, 1328, 1825, -1, + 1615, 1824, 1330, -1, 1615, 1330, 953, -1, + 1828, 1827, 1618, -1, 1957, 1956, 1321, -1, + 1957, 1326, 1959, -1, 1957, 1321, 1326, -1, + 945, 1955, 1820, -1, 945, 946, 1956, -1, + 945, 1956, 1955, -1, 945, 947, 946, -1, + 945, 1820, 947, -1, 1617, 1618, 1820, -1, + 1609, 1618, 1613, -1, 1609, 1329, 958, -1, + 1609, 948, 1618, -1, 1609, 1614, 1610, -1, + 1609, 1613, 1614, -1, 1609, 958, 1173, -1, + 1609, 1173, 948, -1, 1823, 1330, 1824, -1, + 949, 951, 950, -1, 949, 950, 952, -1, + 949, 1616, 953, -1, 949, 953, 951, -1, + 949, 952, 954, -1, 949, 1818, 1616, -1, + 949, 954, 1818, -1, 955, 962, 963, -1, + 955, 956, 962, -1, 955, 957, 956, -1, + 955, 1329, 957, -1, 955, 963, 966, -1, + 955, 958, 1329, -1, 955, 966, 958, -1, + 1627, 1334, 959, -1, 1627, 1628, 1335, -1, + 1627, 959, 1332, -1, 1337, 965, 1334, -1, + 1337, 1335, 1338, -1, 1337, 1340, 960, -1, + 1337, 960, 965, -1, 961, 962, 1334, -1, + 961, 963, 962, -1, 961, 965, 964, -1, + 961, 1334, 965, -1, 961, 966, 963, -1, + 961, 964, 966, -1, 1346, 1347, 1335, -1, + 1346, 1335, 1628, -1, 1348, 968, 967, -1, + 1348, 967, 1347, -1, 1348, 1426, 968, -1, + 969, 971, 970, -1, 969, 972, 971, -1, + 969, 973, 974, -1, 969, 974, 975, -1, + 969, 975, 972, -1, 969, 976, 973, -1, + 969, 970, 976, -1, 1649, 977, 1408, -1, + 1649, 979, 977, -1, 978, 980, 979, -1, + 978, 981, 980, -1, 978, 1649, 1374, -1, + 978, 979, 1649, -1, 978, 1644, 981, -1, + 978, 1374, 1644, -1, 987, 1019, 986, -1, + 987, 1212, 1019, -1, 987, 1363, 1212, -1, + 982, 986, 983, -1, 982, 983, 985, -1, + 982, 985, 986, -1, 984, 985, 994, -1, + 984, 986, 985, -1, 984, 987, 986, -1, + 984, 994, 1363, -1, 984, 1363, 987, -1, + 995, 990, 996, -1, 995, 994, 988, -1, + 995, 991, 990, -1, 995, 1006, 991, -1, + 995, 988, 1006, -1, 989, 1355, 996, -1, + 989, 990, 991, -1, 989, 996, 990, -1, + 989, 991, 992, -1, 989, 992, 1355, -1, + 993, 1362, 994, -1, 993, 996, 1362, -1, + 993, 994, 995, -1, 993, 995, 996, -1, + 1641, 1362, 996, -1, 1641, 996, 1355, -1, + 997, 1833, 998, -1, 997, 1358, 1833, -1, + 997, 999, 1358, -1, 997, 1000, 999, -1, + 997, 998, 1000, -1, 1926, 1031, 1001, -1, + 1926, 1928, 1031, -1, 1926, 1002, 1927, -1, + 1926, 1003, 1002, -1, 1926, 1001, 1004, -1, + 1926, 1004, 1005, -1, 1926, 1005, 1006, -1, + 1926, 1006, 1003, -1, 1030, 1032, 1007, -1, + 1030, 1007, 1008, -1, 1030, 1008, 1029, -1, + 1030, 1029, 1031, -1, 1368, 1009, 1010, -1, + 1368, 1011, 1009, -1, 1368, 1012, 1013, -1, + 1368, 1010, 1012, -1, 1368, 1013, 1367, -1, + 1368, 1369, 1011, -1, 1835, 1373, 1644, -1, + 1378, 1014, 1380, -1, 1378, 1377, 1015, -1, + 1378, 1016, 1014, -1, 1378, 1015, 1016, -1, + 1385, 1386, 1017, -1, 1395, 1390, 1383, -1, + 1395, 1017, 1396, -1, 1395, 1385, 1017, -1, + 1395, 1383, 1385, -1, 1018, 1019, 1212, -1, + 1018, 1386, 1019, -1, 1018, 1212, 1396, -1, + 1018, 1396, 1386, -1, 1020, 1379, 1367, -1, + 1020, 1367, 1381, -1, 1020, 1376, 1379, -1, + 1020, 1381, 1382, -1, 1020, 1382, 1021, -1, + 1020, 1021, 1376, -1, 1022, 1023, 1024, -1, + 1022, 1025, 1023, -1, 1022, 1024, 1026, -1, + 1022, 1026, 1025, -1, 1027, 1494, 1028, -1, + 1027, 1028, 1029, -1, 1027, 1166, 1494, -1, + 1027, 1029, 1166, -1, 1406, 1032, 1030, -1, + 1406, 1030, 1031, -1, 1406, 1031, 1928, -1, + 1406, 1928, 1407, -1, 1405, 1403, 1032, -1, + 1405, 1032, 1406, -1, 1931, 1410, 1930, -1, + 1412, 1033, 1658, -1, 1412, 1034, 1033, -1, + 1412, 1411, 1034, -1, 1035, 1036, 1037, -1, + 1035, 1038, 1036, -1, 1035, 1037, 1165, -1, + 1035, 1165, 1039, -1, 1035, 1039, 1038, -1, + 1651, 1655, 1040, -1, 1651, 1040, 1652, -1, + 1414, 1416, 1041, -1, 1414, 1041, 1044, -1, + 1414, 1071, 1415, -1, 1668, 1042, 1043, -1, + 1668, 1043, 1416, -1, 1668, 1665, 1042, -1, + 1668, 1056, 1665, -1, 1072, 1414, 1044, -1, + 1072, 1071, 1414, -1, 1072, 1044, 1070, -1, + 1050, 1049, 1067, -1, 1050, 1067, 1064, -1, + 1050, 1045, 1051, -1, 1050, 1064, 1045, -1, + 1046, 1048, 1047, -1, 1046, 1047, 1049, -1, + 1046, 1050, 1051, -1, 1046, 1049, 1050, -1, + 1046, 1052, 1048, -1, 1046, 1053, 1052, -1, + 1046, 1054, 1053, -1, 1046, 1051, 1054, -1, + 1055, 1666, 1665, -1, 1055, 1665, 1056, -1, + 1055, 1668, 1666, -1, 1055, 1056, 1668, -1, + 1057, 1672, 1421, -1, 1057, 1059, 1058, -1, + 1057, 1421, 1059, -1, 1057, 1058, 1060, -1, + 1057, 1060, 1061, -1, 1057, 1061, 1062, -1, + 1057, 1062, 1672, -1, 1063, 1065, 1064, -1, + 1063, 1066, 1065, -1, 1063, 1064, 1067, -1, + 1063, 1067, 1066, -1, 1068, 1070, 1069, -1, + 1068, 1069, 1071, -1, 1068, 1072, 1070, -1, + 1068, 1071, 1072, -1, 1073, 1074, 1075, -1, + 1073, 1075, 1076, -1, 1073, 1076, 1074, -1, + 1077, 1630, 1078, -1, 1077, 1078, 1079, -1, + 1077, 1349, 1630, -1, 1077, 1079, 1349, -1, + 1351, 1349, 1079, -1, 1351, 1079, 1080, -1, + 1351, 1080, 1344, -1, 1425, 1084, 1426, -1, + 1423, 1344, 1083, -1, 1423, 1424, 1426, -1, + 1423, 1084, 1425, -1, 1423, 1426, 1348, -1, + 1081, 1083, 1082, -1, 1081, 1082, 1084, -1, + 1081, 1423, 1083, -1, 1081, 1084, 1423, -1, + 1108, 1085, 1114, -1, 1108, 1107, 1085, -1, + 1108, 1114, 1106, -1, 1086, 1104, 1087, -1, + 1086, 1087, 1107, -1, 1086, 1105, 1104, -1, + 1086, 1107, 1105, -1, 1683, 1684, 1681, -1, + 1088, 1708, 1700, -1, 1088, 1707, 1708, -1, + 1088, 1700, 1707, -1, 1089, 1700, 1857, -1, + 1089, 1707, 1700, -1, 1089, 1857, 1707, -1, + 1688, 1857, 1700, -1, 1688, 1859, 1857, -1, + 1688, 1708, 1689, -1, 1688, 1431, 1708, -1, + 1695, 1696, 1090, -1, 1695, 1090, 1724, -1, + 1091, 1092, 1684, -1, 1091, 1684, 1093, -1, + 1091, 1429, 1092, -1, 1091, 1093, 1429, -1, + 1860, 1691, 1865, -1, 1699, 1700, 1708, -1, + 1848, 1703, 1855, -1, 1848, 1874, 1434, -1, + 1679, 1706, 1703, -1, 1098, 1095, 1094, -1, + 1098, 1097, 1095, -1, 1098, 1094, 1429, -1, + 1096, 1429, 1111, -1, 1096, 1111, 1097, -1, + 1096, 1098, 1429, -1, 1096, 1097, 1098, -1, + 1099, 1100, 1111, -1, 1099, 1110, 1100, -1, + 1099, 1111, 1110, -1, 1101, 1102, 1104, -1, + 1101, 1712, 1102, -1, 1101, 1104, 1712, -1, + 1103, 1104, 1105, -1, 1103, 1717, 1104, -1, + 1103, 1106, 1717, -1, 1103, 1105, 1107, -1, + 1103, 1108, 1106, -1, 1103, 1107, 1108, -1, + 1109, 1110, 1111, -1, 1109, 1111, 1717, -1, + 1109, 1112, 1110, -1, 1109, 1113, 1112, -1, + 1109, 1114, 1113, -1, 1109, 1717, 1114, -1, + 1721, 1722, 1437, -1, 1721, 1437, 1725, -1, + 1115, 1684, 1116, -1, 1115, 1118, 1684, -1, + 1115, 1116, 1118, -1, 1117, 1684, 1118, -1, + 1117, 1120, 1119, -1, 1117, 1119, 1684, -1, + 1117, 1121, 1120, -1, 1117, 1118, 1122, -1, + 1117, 1122, 1123, -1, 1117, 1123, 1121, -1, + 1450, 1124, 1454, -1, 1450, 1451, 1124, -1, + 1125, 1684, 1442, -1, 1125, 1442, 1126, -1, + 1125, 1126, 1127, -1, 1125, 1128, 1684, -1, + 1125, 1127, 1128, -1, 1129, 1130, 1131, -1, + 1129, 1131, 1132, -1, 1129, 1132, 1133, -1, + 1129, 1133, 1134, -1, 1129, 1134, 1130, -1, + 1459, 1458, 1138, -1, 1459, 1138, 1732, -1, + 1135, 1136, 1137, -1, 1135, 1137, 1138, -1, + 1135, 1138, 1136, -1, 1733, 1459, 1732, -1, + 1455, 1730, 1139, -1, 1455, 1466, 1467, -1, + 1455, 1139, 1466, -1, 1455, 1467, 1734, -1, + 1455, 1734, 1457, -1, 1738, 1735, 1876, -1, + 1140, 1458, 1744, -1, 1140, 1319, 1458, -1, + 1140, 1462, 1319, -1, 1892, 1140, 1744, -1, + 1892, 1462, 1140, -1, 1952, 1934, 1324, -1, + 1468, 1466, 1141, -1, 1468, 1141, 1753, -1, + 1142, 1753, 1143, -1, 1142, 1145, 1144, -1, + 1142, 1143, 1145, -1, 1142, 1144, 1754, -1, + 1142, 1754, 1753, -1, 1476, 1756, 1481, -1, + 1476, 1472, 1146, -1, 1476, 1758, 1756, -1, + 1476, 1146, 1758, -1, 1762, 1478, 1475, -1, + 1762, 1475, 1481, -1, 1147, 1148, 1213, -1, + 1147, 1150, 1148, -1, 1147, 1213, 1150, -1, + 1149, 1151, 1486, -1, 1149, 1486, 1150, -1, + 1149, 1215, 1151, -1, 1149, 1150, 1215, -1, + 1485, 1151, 1484, -1, 1485, 1486, 1151, -1, + 1152, 1153, 1587, -1, 1152, 1587, 1154, -1, + 1152, 1154, 1153, -1, 1155, 1157, 1156, -1, + 1155, 1158, 1157, -1, 1155, 1159, 1158, -1, + 1155, 1156, 1160, -1, 1155, 1160, 1161, -1, + 1155, 1161, 1159, -1, 1162, 1489, 1163, -1, + 1162, 1163, 1164, -1, 1162, 1165, 1489, -1, + 1162, 1164, 1165, -1, 1492, 1166, 1491, -1, + 1492, 1494, 1166, -1, 1496, 1168, 1167, -1, + 1496, 1167, 1500, -1, 1496, 1497, 1168, -1, + 1504, 1193, 1506, -1, 1169, 1170, 1508, -1, + 1169, 1508, 1176, -1, 1169, 1176, 1171, -1, + 1169, 1513, 1512, -1, 1169, 1171, 1172, -1, + 1169, 1172, 1173, -1, 1169, 1173, 1515, -1, + 1169, 1503, 1170, -1, 1169, 1512, 1503, -1, + 1169, 1174, 1513, -1, 1169, 1515, 1174, -1, + 1175, 1177, 1176, -1, 1175, 1508, 1507, -1, + 1175, 1176, 1508, -1, 1175, 1507, 1506, -1, + 1175, 1506, 1178, -1, 1175, 1178, 1179, -1, + 1175, 1179, 1177, -1, 1180, 1199, 1203, -1, + 1180, 1183, 1199, -1, 1180, 1203, 1181, -1, + 1180, 1181, 1188, -1, 1180, 1189, 1183, -1, + 1180, 1188, 1189, -1, 1182, 1183, 1184, -1, + 1182, 1199, 1183, -1, 1182, 1184, 1185, -1, + 1182, 1185, 1200, -1, 1182, 1200, 1199, -1, + 1510, 1511, 1186, -1, 1510, 1194, 1512, -1, + 1510, 1191, 1194, -1, 1510, 1186, 1191, -1, + 1187, 1189, 1188, -1, 1187, 1188, 1190, -1, + 1187, 1191, 1189, -1, 1187, 1521, 1191, -1, + 1187, 1522, 1521, -1, 1187, 1190, 1522, -1, + 1517, 1518, 1515, -1, 1520, 1192, 1521, -1, + 1520, 1524, 1193, -1, 1520, 1193, 1504, -1, + 1520, 1504, 1502, -1, 1520, 1502, 1194, -1, + 1520, 1194, 1192, -1, 1532, 1527, 1530, -1, + 1536, 1195, 1537, -1, 1536, 1201, 1195, -1, + 1536, 1196, 1201, -1, 1536, 1538, 1197, -1, + 1536, 1197, 1196, -1, 1198, 1199, 1200, -1, + 1198, 1200, 1201, -1, 1198, 1201, 1202, -1, + 1198, 1202, 1203, -1, 1198, 1203, 1199, -1, + 1549, 1550, 1534, -1, 1549, 1534, 1542, -1, + 1204, 1205, 1206, -1, 1204, 1207, 1205, -1, + 1204, 1206, 1208, -1, 1204, 1208, 1207, -1, + 1209, 1400, 1640, -1, 1209, 1557, 1400, -1, + 1209, 1640, 1364, -1, 1209, 1364, 1557, -1, + 1556, 1211, 1210, -1, 1556, 1210, 1557, -1, + 1556, 1555, 1211, -1, 1361, 1212, 1363, -1, + 1361, 1639, 1212, -1, 1554, 1557, 1364, -1, + 1554, 1360, 1552, -1, 1359, 1213, 1214, -1, + 1359, 1215, 1213, -1, 1359, 1636, 1215, -1, + 1359, 1214, 1552, -1, 1359, 1552, 1360, -1, + 1216, 1218, 1217, -1, 1216, 1219, 1218, -1, + 1216, 1217, 1219, -1, 1220, 1221, 1222, -1, + 1220, 1222, 1223, -1, 1220, 1224, 1221, -1, + 1220, 1223, 1224, -1, 1225, 1575, 1226, -1, + 1225, 1574, 1575, -1, 1225, 1226, 1227, -1, + 1225, 1227, 1228, -1, 1225, 1230, 1229, -1, + 1225, 1229, 1574, -1, 1225, 1231, 1230, -1, + 1225, 1228, 1231, -1, 1242, 1233, 1232, -1, + 1242, 1232, 1234, -1, 1242, 1234, 1235, -1, + 1242, 1235, 1236, -1, 1242, 1241, 1233, -1, + 1242, 1236, 1237, -1, 1242, 1237, 1254, -1, + 1242, 1254, 1243, -1, 1908, 1909, 1238, -1, + 1908, 1238, 1239, -1, 1908, 1239, 1241, -1, + 1764, 1562, 1240, -1, 1764, 1240, 1558, -1, + 1764, 1908, 1241, -1, 1764, 1241, 1242, -1, + 1764, 1242, 1243, -1, 1764, 1243, 1254, -1, + 1244, 1252, 1245, -1, 1244, 1251, 1252, -1, + 1244, 1245, 1247, -1, 1244, 1247, 1246, -1, + 1244, 1246, 1559, -1, 1244, 1559, 1251, -1, + 1563, 1247, 1252, -1, 1563, 1248, 1561, -1, + 1563, 1253, 1248, -1, 1563, 1249, 1247, -1, + 1563, 1254, 1249, -1, 1563, 1764, 1254, -1, + 1250, 1252, 1251, -1, 1250, 1251, 1253, -1, + 1250, 1563, 1252, -1, 1250, 1253, 1563, -1, + 1914, 1254, 1255, -1, 1914, 1767, 1254, -1, + 1914, 1255, 1256, -1, 1914, 1256, 1915, -1, + 1565, 1567, 1767, -1, 1565, 1767, 1914, -1, + 1565, 1914, 1918, -1, 1566, 1920, 1771, -1, + 1566, 1918, 1920, -1, 1259, 1258, 1906, -1, + 1259, 1906, 1257, -1, 1259, 1257, 1478, -1, + 1479, 1480, 1906, -1, 1479, 1906, 1258, -1, + 1479, 1259, 1478, -1, 1479, 1258, 1259, -1, + 1262, 1771, 1472, -1, 1262, 1264, 1771, -1, + 1470, 1473, 1260, -1, 1470, 1260, 1766, -1, + 1470, 1472, 1471, -1, 1470, 1262, 1472, -1, + 1470, 1263, 1262, -1, 1261, 1766, 1264, -1, + 1261, 1264, 1262, -1, 1261, 1262, 1263, -1, + 1261, 1263, 1470, -1, 1261, 1470, 1766, -1, + 1770, 1767, 1567, -1, 1772, 1771, 1264, -1, + 1772, 1264, 1766, -1, 1265, 1267, 1266, -1, + 1265, 1268, 1267, -1, 1265, 1266, 1269, -1, + 1265, 1269, 1270, -1, 1265, 1270, 1271, -1, + 1265, 1271, 1272, -1, 1265, 1272, 1268, -1, + 1571, 1570, 1273, -1, 1571, 1274, 1275, -1, + 1571, 1273, 1274, -1, 1571, 1275, 1276, -1, + 1571, 1276, 1573, -1, 1289, 1308, 1281, -1, + 1289, 1281, 1279, -1, 1289, 1279, 1277, -1, + 1289, 1277, 1583, -1, 1278, 1280, 1279, -1, + 1278, 1281, 1280, -1, 1278, 1279, 1281, -1, + 1576, 1574, 1282, -1, 1576, 1282, 1776, -1, + 1778, 1283, 1784, -1, 1778, 1777, 1283, -1, + 1284, 1290, 1292, -1, 1284, 1292, 1287, -1, + 1284, 1285, 1290, -1, 1284, 1287, 1285, -1, + 1286, 1314, 1309, -1, 1286, 1309, 1287, -1, + 1286, 1288, 1314, -1, 1286, 1287, 1288, -1, + 1582, 1289, 1583, -1, 1582, 1581, 1308, -1, + 1582, 1308, 1289, -1, 1579, 1290, 1580, -1, + 1579, 1583, 1291, -1, 1579, 1292, 1290, -1, + 1579, 1291, 1292, -1, 1799, 1585, 1587, -1, + 1780, 1293, 1584, -1, 1780, 1789, 1293, -1, + 1802, 1779, 1803, -1, 1802, 1294, 1779, -1, + 1802, 1795, 1294, -1, 1802, 1794, 1795, -1, + 1792, 1589, 1295, -1, 1792, 1296, 1793, -1, + 1792, 1295, 1297, -1, 1792, 1297, 1296, -1, + 1298, 1299, 1300, -1, 1298, 1300, 1304, -1, + 1298, 1789, 1299, -1, 1298, 1304, 1789, -1, + 1301, 1303, 1302, -1, 1301, 1304, 1303, -1, + 1301, 1302, 1305, -1, 1301, 1305, 1306, -1, + 1301, 1306, 1584, -1, 1301, 1584, 1304, -1, + 1307, 1581, 1788, -1, 1307, 1788, 1785, -1, + 1307, 1308, 1581, -1, 1307, 1785, 1308, -1, + 1593, 1309, 1314, -1, 1593, 1592, 1309, -1, + 1310, 1311, 1594, -1, 1310, 1313, 1312, -1, + 1310, 1312, 1311, -1, 1310, 1594, 1593, -1, + 1310, 1314, 1313, -1, 1310, 1593, 1314, -1, + 1598, 1316, 1315, -1, 1598, 1317, 1316, -1, + 1598, 1315, 1597, -1, 1598, 1596, 1317, -1, + 1318, 1323, 1319, -1, 1318, 1463, 1461, -1, + 1318, 1319, 1463, -1, 1318, 1324, 1323, -1, + 1318, 1461, 1952, -1, 1318, 1952, 1324, -1, + 1320, 1321, 1322, -1, 1320, 1322, 1323, -1, + 1320, 1323, 1324, -1, 1320, 1934, 1325, -1, + 1320, 1324, 1934, -1, 1320, 1325, 1326, -1, + 1320, 1326, 1321, -1, 1606, 1601, 1327, -1, + 1606, 1327, 1607, -1, 1606, 1608, 1604, -1, + 1620, 1607, 1621, -1, 1816, 1610, 1614, -1, + 1816, 1614, 1814, -1, 1813, 1613, 1328, -1, + 1813, 1328, 1615, -1, 1808, 1809, 1329, -1, + 1808, 1329, 1609, -1, 1619, 1621, 1330, -1, + 1619, 1330, 1823, -1, 1958, 1959, 1331, -1, + 1958, 1331, 1622, -1, 1629, 1332, 1632, -1, + 1629, 1627, 1332, -1, 1333, 1334, 1627, -1, + 1333, 1337, 1334, -1, 1333, 1627, 1335, -1, + 1333, 1335, 1337, -1, 1336, 1337, 1338, -1, + 1336, 1338, 1339, -1, 1336, 1340, 1337, -1, + 1336, 1341, 1340, -1, 1336, 1342, 1341, -1, + 1336, 1339, 1342, -1, 1343, 1349, 1346, -1, + 1343, 1346, 1628, -1, 1343, 1630, 1349, -1, + 1343, 1628, 1630, -1, 1350, 1351, 1344, -1, + 1350, 1344, 1423, -1, 1345, 1347, 1346, -1, + 1345, 1348, 1347, -1, 1345, 1346, 1349, -1, + 1345, 1423, 1348, -1, 1345, 1350, 1423, -1, + 1345, 1349, 1351, -1, 1345, 1351, 1350, -1, + 1352, 1642, 1641, -1, 1352, 1353, 1354, -1, + 1352, 1355, 1353, -1, 1352, 1641, 1355, -1, + 1352, 1354, 1356, -1, 1352, 1356, 1642, -1, + 1634, 1831, 1833, -1, 1634, 1357, 1637, -1, + 1634, 1358, 1357, -1, 1634, 1833, 1358, -1, + 1635, 1636, 1359, -1, 1635, 1359, 1360, -1, + 1635, 1364, 1831, -1, 1635, 1554, 1364, -1, + 1635, 1360, 1554, -1, 1643, 1639, 1361, -1, + 1643, 1362, 1641, -1, 1643, 1363, 1362, -1, + 1643, 1361, 1363, -1, 1638, 1364, 1640, -1, + 1638, 1831, 1364, -1, 1365, 1367, 1366, -1, + 1365, 1368, 1367, -1, 1365, 1369, 1368, -1, + 1365, 1370, 1369, -1, 1365, 1366, 1370, -1, + 1647, 1646, 1371, -1, 1647, 1371, 1372, -1, + 1647, 1372, 1373, -1, 1647, 1373, 1835, -1, + 1923, 1644, 1374, -1, 1923, 1374, 1649, -1, + 1375, 1376, 1377, -1, 1375, 1377, 1378, -1, + 1375, 1379, 1376, -1, 1375, 1380, 1379, -1, + 1375, 1378, 1380, -1, 1389, 1381, 1388, -1, + 1389, 1382, 1381, -1, 1389, 1383, 1382, -1, + 1389, 1385, 1383, -1, 1384, 1386, 1385, -1, + 1384, 1388, 1387, -1, 1384, 1387, 1386, -1, + 1384, 1389, 1388, -1, 1384, 1385, 1389, -1, + 1397, 1390, 1395, -1, 1397, 1392, 1391, -1, + 1397, 1391, 1390, -1, 1397, 1393, 1392, -1, + 1397, 1398, 1393, -1, 1394, 1395, 1396, -1, + 1394, 1398, 1397, -1, 1394, 1397, 1395, -1, + 1394, 1399, 1400, -1, 1394, 1400, 1398, -1, + 1394, 1401, 1399, -1, 1394, 1396, 1401, -1, + 1929, 1930, 1410, -1, 1929, 1410, 1407, -1, + 1929, 1407, 1928, -1, 1409, 1402, 1403, -1, + 1409, 1403, 1405, -1, 1409, 1405, 1410, -1, + 1409, 1408, 1402, -1, 1404, 1410, 1405, -1, + 1404, 1405, 1406, -1, 1404, 1407, 1410, -1, + 1404, 1406, 1407, -1, 1650, 1931, 1932, -1, + 1650, 1649, 1408, -1, 1650, 1408, 1409, -1, + 1650, 1410, 1931, -1, 1650, 1409, 1410, -1, + 1657, 1652, 1411, -1, 1657, 1411, 1412, -1, + 1657, 1412, 1658, -1, 1667, 1668, 1416, -1, + 1413, 1414, 1415, -1, 1413, 1416, 1414, -1, + 1413, 1415, 1665, -1, 1413, 1665, 1667, -1, + 1413, 1667, 1416, -1, 1417, 1420, 1418, -1, + 1417, 1675, 1420, -1, 1417, 1418, 1419, -1, + 1417, 1419, 1421, -1, 1417, 1421, 1675, -1, + 1674, 1669, 1420, -1, 1674, 1420, 1675, -1, + 1673, 1421, 1672, -1, 1673, 1675, 1421, -1, + 1422, 1424, 1423, -1, 1422, 1423, 1425, -1, + 1422, 1426, 1424, -1, 1422, 1425, 1426, -1, + 1428, 1427, 1874, -1, 1428, 1874, 1851, -1, + 1435, 1874, 1709, -1, 1435, 1434, 1874, -1, + 1677, 1703, 1870, -1, 1677, 1874, 1678, -1, + 1849, 1682, 1427, -1, 1849, 1427, 1428, -1, + 1849, 1428, 1851, -1, 1685, 1686, 1429, -1, + 1685, 1429, 1684, -1, 1861, 1690, 1862, -1, + 1693, 1865, 1694, -1, 1693, 1859, 1865, -1, + 1693, 1430, 1859, -1, 1693, 1695, 1430, -1, + 1439, 1438, 1430, -1, 1439, 1430, 1695, -1, + 1701, 1431, 1688, -1, 1701, 1708, 1431, -1, + 1701, 1699, 1708, -1, 1701, 1688, 1700, -1, + 1432, 1703, 1706, -1, 1432, 1706, 1433, -1, + 1432, 1704, 1703, -1, 1432, 1433, 1704, -1, + 1705, 1433, 1706, -1, 1705, 1704, 1433, -1, + 1869, 1870, 1703, -1, 1869, 1703, 1848, -1, + 1869, 1848, 1434, -1, 1869, 1435, 1709, -1, + 1869, 1434, 1435, -1, 1710, 1436, 1719, -1, + 1710, 1719, 1716, -1, 1710, 1437, 1436, -1, + 1710, 1725, 1437, -1, 1714, 1718, 1713, -1, + 1723, 1686, 1438, -1, 1723, 1717, 1686, -1, + 1723, 1695, 1724, -1, 1723, 1438, 1439, -1, + 1723, 1439, 1695, -1, 1445, 1451, 1440, -1, + 1445, 1440, 1453, -1, 1445, 1442, 1451, -1, + 1445, 1453, 1448, -1, 1445, 1448, 1446, -1, + 1441, 1443, 1442, -1, 1441, 1444, 1443, -1, + 1441, 1442, 1445, -1, 1441, 1445, 1446, -1, + 1441, 1447, 1444, -1, 1441, 1448, 1447, -1, + 1441, 1446, 1448, -1, 1449, 1451, 1450, -1, + 1449, 1452, 1453, -1, 1449, 1453, 1451, -1, + 1449, 1454, 1452, -1, 1449, 1450, 1454, -1, + 1894, 1895, 1728, -1, 1729, 1455, 1457, -1, + 1729, 1730, 1455, -1, 1456, 1729, 1457, -1, + 1456, 1728, 1729, -1, 1456, 1457, 1734, -1, + 1456, 1734, 1739, -1, 1456, 1739, 1737, -1, + 1456, 1737, 1894, -1, 1456, 1894, 1728, -1, + 1896, 1744, 1458, -1, 1896, 1458, 1459, -1, + 1896, 1459, 1733, -1, 1460, 1892, 1951, -1, + 1460, 1952, 1461, -1, 1460, 1951, 1952, -1, + 1460, 1462, 1892, -1, 1460, 1461, 1463, -1, + 1460, 1463, 1462, -1, 1898, 1745, 1464, -1, + 1898, 1464, 1751, -1, 1898, 1901, 1748, -1, + 1898, 1750, 1465, -1, 1898, 1465, 1901, -1, + 1755, 1467, 1466, -1, 1755, 1466, 1468, -1, + 1755, 1734, 1467, -1, 1755, 1468, 1753, -1, + 1469, 1476, 1477, -1, 1469, 1470, 1471, -1, + 1469, 1471, 1472, -1, 1469, 1472, 1476, -1, + 1469, 1477, 1473, -1, 1469, 1473, 1470, -1, + 1474, 1481, 1475, -1, 1474, 1476, 1481, -1, + 1474, 1475, 1477, -1, 1474, 1477, 1476, -1, + 1905, 1478, 1762, -1, 1905, 1480, 1479, -1, + 1905, 1479, 1478, -1, 1905, 1906, 1480, -1, + 1759, 1481, 1756, -1, 1759, 1762, 1481, -1, + 1759, 1906, 1762, -1, 1763, 1906, 1904, -1, + 1482, 1484, 1483, -1, 1482, 1485, 1484, -1, + 1482, 1483, 1486, -1, 1482, 1486, 1485, -1, + 1487, 1488, 1489, -1, 1487, 1489, 1490, -1, + 1487, 1491, 1488, -1, 1487, 1492, 1491, -1, + 1487, 1490, 1493, -1, 1487, 1493, 1494, -1, + 1487, 1494, 1492, -1, 1495, 1497, 1496, -1, + 1495, 1498, 1497, -1, 1495, 1499, 1498, -1, + 1495, 1500, 1499, -1, 1495, 1496, 1500, -1, + 1501, 1503, 1502, -1, 1501, 1502, 1504, -1, + 1501, 1505, 1503, -1, 1501, 1506, 1507, -1, + 1501, 1504, 1506, -1, 1501, 1507, 1508, -1, + 1501, 1508, 1505, -1, 1509, 1511, 1510, -1, + 1509, 1510, 1512, -1, 1509, 1513, 1511, -1, + 1509, 1512, 1513, -1, 1514, 1515, 1516, -1, + 1514, 1517, 1515, -1, 1514, 1516, 1518, -1, + 1514, 1518, 1517, -1, 1519, 1520, 1521, -1, + 1519, 1522, 1523, -1, 1519, 1521, 1522, -1, + 1519, 1523, 1524, -1, 1519, 1524, 1520, -1, + 1533, 1534, 1550, -1, 1533, 1550, 1526, -1, + 1533, 1526, 1532, -1, 1525, 1532, 1526, -1, + 1525, 1527, 1532, -1, 1525, 1526, 1528, -1, + 1525, 1528, 1527, -1, 1529, 1530, 1531, -1, + 1529, 1532, 1530, -1, 1529, 1534, 1533, -1, + 1529, 1533, 1532, -1, 1529, 1531, 1540, -1, + 1529, 1540, 1541, -1, 1529, 1542, 1534, -1, + 1529, 1541, 1542, -1, 1535, 1536, 1537, -1, + 1535, 1539, 1538, -1, 1535, 1538, 1536, -1, + 1535, 1540, 1539, -1, 1535, 1541, 1540, -1, + 1535, 1537, 1542, -1, 1535, 1542, 1541, -1, + 1548, 1549, 1542, -1, 1548, 1543, 1545, -1, + 1548, 1542, 1543, -1, 1544, 1545, 1546, -1, + 1544, 1546, 1547, -1, 1544, 1548, 1545, -1, + 1544, 1549, 1548, -1, 1544, 1547, 1550, -1, + 1544, 1550, 1549, -1, 1551, 1552, 1553, -1, + 1551, 1554, 1552, -1, 1551, 1553, 1555, -1, + 1551, 1555, 1556, -1, 1551, 1556, 1557, -1, + 1551, 1557, 1554, -1, 1912, 1764, 1558, -1, + 1912, 1559, 1911, -1, 1912, 1558, 1559, -1, + 1560, 1561, 1562, -1, 1560, 1563, 1561, -1, + 1560, 1562, 1764, -1, 1560, 1764, 1563, -1, + 1765, 1771, 1920, -1, 1765, 1915, 1771, -1, + 1564, 1565, 1918, -1, 1564, 1918, 1566, -1, + 1564, 1567, 1565, -1, 1564, 1770, 1567, -1, + 1564, 1566, 1771, -1, 1564, 1771, 1770, -1, + 1769, 1767, 1770, -1, 1568, 1569, 1570, -1, + 1568, 1570, 1571, -1, 1568, 1572, 1569, -1, + 1568, 1573, 1572, -1, 1568, 1571, 1573, -1, + 1775, 1575, 1574, -1, 1775, 1574, 1576, -1, + 1775, 1577, 1575, -1, 1775, 1779, 1577, -1, + 1775, 1576, 1776, -1, 1578, 1579, 1580, -1, + 1578, 1580, 1581, -1, 1578, 1581, 1582, -1, + 1578, 1582, 1583, -1, 1578, 1583, 1579, -1, + 1800, 1584, 1585, -1, 1800, 1780, 1584, -1, + 1800, 1585, 1799, -1, 1800, 1798, 1780, -1, + 1787, 1789, 1780, -1, 1791, 1589, 1792, -1, + 1781, 1784, 1783, -1, 1781, 1778, 1784, -1, + 1588, 1586, 1589, -1, 1588, 1587, 1586, -1, + 1588, 1799, 1587, -1, 1797, 1806, 1798, -1, + 1797, 1799, 1588, -1, 1797, 1791, 1806, -1, + 1797, 1589, 1791, -1, 1797, 1588, 1589, -1, + 1805, 1803, 1781, -1, 1805, 1798, 1806, -1, + 1804, 1794, 1802, -1, 1804, 1806, 1791, -1, + 1590, 1591, 1592, -1, 1590, 1592, 1593, -1, + 1590, 1594, 1591, -1, 1590, 1593, 1594, -1, + 1595, 1597, 1596, -1, 1595, 1598, 1597, -1, + 1595, 1596, 1598, -1, 1599, 1600, 1601, -1, + 1599, 1601, 1606, -1, 1599, 1602, 1600, -1, + 1599, 1603, 1602, -1, 1599, 1604, 1603, -1, + 1599, 1606, 1604, -1, 1964, 1608, 1620, -1, + 1964, 1625, 1608, -1, 1964, 1939, 1625, -1, + 1605, 1606, 1607, -1, 1605, 1607, 1620, -1, + 1605, 1608, 1606, -1, 1605, 1620, 1608, -1, + 1810, 1609, 1610, -1, 1810, 1610, 1816, -1, + 1810, 1808, 1609, -1, 1810, 1611, 1811, -1, + 1817, 1819, 1611, -1, 1817, 1611, 1810, -1, + 1817, 1810, 1816, -1, 1612, 1614, 1613, -1, + 1612, 1613, 1813, -1, 1612, 1814, 1614, -1, + 1612, 1813, 1814, -1, 1815, 1615, 1616, -1, + 1815, 1813, 1615, -1, 1815, 1616, 1818, -1, + 1937, 1618, 1617, -1, 1937, 1921, 1618, -1, + 1937, 1617, 1820, -1, 1822, 1922, 1823, -1, + 1822, 1921, 1922, -1, 1822, 1828, 1618, -1, + 1822, 1618, 1921, -1, 1962, 1823, 1922, -1, + 1962, 1619, 1823, -1, 1962, 1964, 1620, -1, + 1962, 1620, 1621, -1, 1962, 1621, 1619, -1, + 1940, 1958, 1622, -1, 1940, 1623, 1624, -1, + 1940, 1622, 1623, -1, 1940, 1624, 1625, -1, + 1940, 1625, 1939, -1, 1626, 1628, 1627, -1, + 1626, 1627, 1629, -1, 1626, 1630, 1628, -1, + 1626, 1631, 1630, -1, 1626, 1632, 1631, -1, + 1626, 1629, 1632, -1, 1633, 1831, 1634, -1, + 1633, 1636, 1635, -1, 1633, 1635, 1831, -1, + 1633, 1637, 1636, -1, 1633, 1634, 1637, -1, + 1830, 1831, 1638, -1, 1830, 1639, 1643, -1, + 1830, 1640, 1639, -1, 1830, 1638, 1640, -1, + 1832, 1641, 1642, -1, 1832, 1643, 1641, -1, + 1832, 1642, 1833, -1, 1832, 1830, 1643, -1, + 1834, 1835, 1644, -1, 1834, 1644, 1923, -1, + 1837, 1839, 1645, -1, 1837, 1838, 1839, -1, + 1837, 1645, 1646, -1, 1837, 1646, 1647, -1, + 1837, 1647, 1835, -1, 1837, 1835, 1836, -1, + 1648, 1923, 1649, -1, 1648, 1649, 1650, -1, + 1648, 1932, 1923, -1, 1648, 1650, 1932, -1, + 1663, 1651, 1652, -1, 1663, 1652, 1657, -1, + 1663, 1653, 1654, -1, 1663, 1662, 1653, -1, + 1663, 1654, 1655, -1, 1663, 1655, 1651, -1, + 1656, 1657, 1658, -1, 1656, 1659, 1660, -1, + 1656, 1658, 1659, -1, 1656, 1660, 1661, -1, + 1656, 1661, 1662, -1, 1656, 1662, 1663, -1, + 1656, 1663, 1657, -1, 1664, 1665, 1666, -1, + 1664, 1667, 1665, -1, 1664, 1666, 1668, -1, + 1664, 1668, 1667, -1, 1841, 1670, 1669, -1, + 1841, 1669, 1674, -1, 1841, 1671, 1670, -1, + 1841, 1842, 1671, -1, 1843, 1672, 1845, -1, + 1843, 1673, 1672, -1, 1843, 1841, 1674, -1, + 1843, 1674, 1675, -1, 1843, 1675, 1673, -1, + 1875, 1874, 1677, -1, 1875, 1677, 1870, -1, + 1676, 1677, 1678, -1, 1676, 1703, 1677, -1, + 1676, 1679, 1703, -1, 1676, 1678, 1706, -1, + 1676, 1706, 1679, -1, 1847, 1848, 1855, -1, + 1847, 1855, 1683, -1, 1847, 1681, 1680, -1, + 1847, 1683, 1681, -1, 1847, 1680, 1682, -1, + 1847, 1682, 1849, -1, 1850, 1874, 1848, -1, + 1853, 1684, 1683, -1, 1853, 1685, 1684, -1, + 1853, 1683, 1855, -1, 1853, 1854, 1686, -1, + 1853, 1686, 1685, -1, 1687, 1859, 1688, -1, + 1687, 1861, 1859, -1, 1687, 1688, 1689, -1, + 1687, 1690, 1861, -1, 1687, 1689, 1865, -1, + 1687, 1865, 1690, -1, 1866, 1691, 1860, -1, + 1866, 1865, 1691, -1, 1692, 1693, 1694, -1, + 1692, 1695, 1693, -1, 1692, 1696, 1695, -1, + 1692, 1697, 1696, -1, 1692, 1694, 1697, -1, + 1698, 1700, 1699, -1, 1698, 1701, 1700, -1, + 1698, 1699, 1701, -1, 1702, 1857, 1703, -1, + 1702, 1703, 1704, -1, 1702, 1704, 1705, -1, + 1702, 1705, 1706, -1, 1702, 1707, 1857, -1, + 1702, 1706, 1708, -1, 1702, 1708, 1707, -1, + 1871, 1869, 1709, -1, 1871, 1709, 1874, -1, + 1715, 1725, 1710, -1, 1715, 1710, 1716, -1, + 1715, 1723, 1725, -1, 1711, 1713, 1712, -1, + 1711, 1714, 1713, -1, 1711, 1723, 1715, -1, + 1711, 1715, 1716, -1, 1711, 1712, 1717, -1, + 1711, 1717, 1723, -1, 1711, 1718, 1714, -1, + 1711, 1719, 1718, -1, 1711, 1716, 1719, -1, + 1720, 1722, 1721, -1, 1720, 1723, 1724, -1, + 1720, 1721, 1725, -1, 1720, 1725, 1723, -1, + 1720, 1726, 1722, -1, 1720, 1724, 1726, -1, + 1878, 1894, 1737, -1, 1878, 1738, 1876, -1, + 1891, 1951, 1892, -1, 1727, 1728, 1895, -1, + 1727, 1729, 1728, -1, 1727, 1731, 1730, -1, + 1727, 1730, 1729, -1, 1727, 1732, 1731, -1, + 1727, 1733, 1732, -1, 1727, 1895, 1896, -1, + 1727, 1896, 1733, -1, 1881, 1739, 1734, -1, + 1881, 1734, 1755, -1, 1884, 1880, 1888, -1, + 1884, 1885, 1880, -1, 1741, 1740, 1735, -1, + 1741, 1735, 1738, -1, 1743, 1739, 1881, -1, + 1743, 1881, 1885, -1, 1736, 1878, 1737, -1, + 1736, 1738, 1878, -1, 1736, 1737, 1739, -1, + 1736, 1741, 1738, -1, 1736, 1742, 1741, -1, + 1736, 1739, 1743, -1, 1736, 1743, 1742, -1, + 1886, 1889, 1740, -1, 1886, 1740, 1741, -1, + 1886, 1741, 1742, -1, 1886, 1743, 1885, -1, + 1886, 1742, 1743, -1, 1893, 1892, 1744, -1, + 1893, 1744, 1896, -1, 1900, 1745, 1898, -1, + 1900, 1901, 1746, -1, 1900, 1746, 1745, -1, + 1747, 1898, 1748, -1, 1747, 1899, 1898, -1, + 1747, 1748, 1901, -1, 1747, 1901, 1899, -1, + 1749, 1750, 1898, -1, 1749, 1898, 1751, -1, + 1749, 1752, 1750, -1, 1749, 1751, 1752, -1, + 1882, 1753, 1754, -1, 1882, 1755, 1753, -1, + 1882, 1754, 1880, -1, 1882, 1881, 1755, -1, + 1760, 1756, 1758, -1, 1760, 1759, 1756, -1, + 1757, 1758, 1906, -1, 1757, 1906, 1759, -1, + 1757, 1760, 1758, -1, 1757, 1759, 1760, -1, + 1761, 1762, 1906, -1, 1761, 1906, 1763, -1, + 1761, 1763, 1762, -1, 1903, 1905, 1762, -1, + 1903, 1762, 1763, -1, 1903, 1763, 1904, -1, + 1910, 1764, 1912, -1, 1910, 1908, 1764, -1, + 1919, 1765, 1920, -1, 1917, 1915, 1765, -1, + 1917, 1765, 1919, -1, 1917, 1918, 1914, -1, + 1773, 1766, 1767, -1, 1773, 1767, 1769, -1, + 1773, 1772, 1766, -1, 1768, 1769, 1770, -1, + 1768, 1770, 1771, -1, 1768, 1771, 1772, -1, + 1768, 1772, 1773, -1, 1768, 1773, 1769, -1, + 1774, 1775, 1776, -1, 1774, 1776, 1777, -1, + 1774, 1777, 1778, -1, 1774, 1781, 1803, -1, + 1774, 1778, 1781, -1, 1774, 1803, 1779, -1, + 1774, 1779, 1775, -1, 1786, 1780, 1798, -1, + 1786, 1787, 1780, -1, 1786, 1798, 1805, -1, + 1786, 1781, 1783, -1, 1786, 1805, 1781, -1, + 1782, 1783, 1784, -1, 1782, 1784, 1785, -1, + 1782, 1786, 1783, -1, 1782, 1787, 1786, -1, + 1782, 1785, 1788, -1, 1782, 1788, 1789, -1, + 1782, 1789, 1787, -1, 1790, 1791, 1792, -1, + 1790, 1792, 1793, -1, 1790, 1794, 1804, -1, + 1790, 1804, 1791, -1, 1790, 1793, 1795, -1, + 1790, 1795, 1794, -1, 1796, 1797, 1798, -1, + 1796, 1799, 1797, -1, 1796, 1798, 1800, -1, + 1796, 1800, 1799, -1, 1801, 1802, 1803, -1, + 1801, 1804, 1802, -1, 1801, 1803, 1805, -1, + 1801, 1805, 1806, -1, 1801, 1806, 1804, -1, + 1807, 1809, 1808, -1, 1807, 1808, 1810, -1, + 1807, 1811, 1809, -1, 1807, 1810, 1811, -1, + 1812, 1814, 1813, -1, 1812, 1813, 1815, -1, + 1812, 1816, 1814, -1, 1812, 1817, 1816, -1, + 1812, 1815, 1818, -1, 1812, 1818, 1819, -1, + 1812, 1819, 1817, -1, 1936, 1820, 1955, -1, + 1936, 1937, 1820, -1, 1938, 1921, 1937, -1, + 1821, 1822, 1823, -1, 1821, 1824, 1825, -1, + 1821, 1823, 1824, -1, 1821, 1825, 1826, -1, + 1821, 1826, 1827, -1, 1821, 1827, 1828, -1, + 1821, 1828, 1822, -1, 1829, 1831, 1830, -1, + 1829, 1830, 1832, -1, 1829, 1833, 1831, -1, + 1829, 1832, 1833, -1, 1924, 1834, 1923, -1, + 1924, 1836, 1835, -1, 1924, 1835, 1834, -1, + 1924, 1946, 1836, -1, 1925, 1836, 1946, -1, + 1925, 1838, 1837, -1, 1925, 1837, 1836, -1, + 1925, 1839, 1838, -1, 1925, 1927, 1839, -1, + 1840, 1842, 1841, -1, 1840, 1841, 1843, -1, + 1840, 1844, 1842, -1, 1840, 1845, 1844, -1, + 1840, 1843, 1845, -1, 1846, 1848, 1847, -1, + 1846, 1847, 1849, -1, 1846, 1850, 1848, -1, + 1846, 1849, 1851, -1, 1846, 1851, 1874, -1, + 1846, 1874, 1850, -1, 1852, 1854, 1853, -1, + 1852, 1853, 1855, -1, 1852, 1856, 1854, -1, + 1852, 1855, 1857, -1, 1852, 1859, 1856, -1, + 1852, 1857, 1859, -1, 1858, 1859, 1861, -1, + 1858, 1861, 1866, -1, 1858, 1866, 1860, -1, + 1858, 1865, 1859, -1, 1858, 1860, 1865, -1, + 1867, 1866, 1861, -1, 1867, 1861, 1862, -1, + 1867, 1862, 1865, -1, 1867, 1865, 1864, -1, + 1863, 1864, 1865, -1, 1863, 1865, 1866, -1, + 1863, 1867, 1864, -1, 1863, 1866, 1867, -1, + 1872, 1874, 1873, -1, 1872, 1871, 1874, -1, + 1868, 1870, 1869, -1, 1868, 1869, 1871, -1, + 1868, 1871, 1872, -1, 1868, 1872, 1873, -1, + 1868, 1873, 1874, -1, 1868, 1874, 1875, -1, + 1868, 1875, 1870, -1, 1949, 1878, 1876, -1, + 1949, 1877, 1933, -1, 1949, 1876, 1877, -1, + 1948, 1951, 1891, -1, 1948, 1878, 1949, -1, + 1948, 1894, 1878, -1, 1948, 1891, 1894, -1, + 1879, 1880, 1885, -1, 1879, 1885, 1881, -1, + 1879, 1882, 1880, -1, 1879, 1881, 1882, -1, + 1883, 1885, 1884, -1, 1883, 1886, 1885, -1, + 1883, 1888, 1887, -1, 1883, 1884, 1888, -1, + 1883, 1887, 1889, -1, 1883, 1889, 1886, -1, + 1890, 1891, 1892, -1, 1890, 1892, 1893, -1, + 1890, 1895, 1894, -1, 1890, 1894, 1891, -1, + 1890, 1896, 1895, -1, 1890, 1893, 1896, -1, + 1897, 1898, 1899, -1, 1897, 1900, 1898, -1, + 1897, 1899, 1901, -1, 1897, 1901, 1900, -1, + 1902, 1903, 1904, -1, 1902, 1905, 1903, -1, + 1902, 1904, 1906, -1, 1902, 1906, 1905, -1, + 1907, 1909, 1908, -1, 1907, 1908, 1910, -1, + 1907, 1911, 1909, -1, 1907, 1912, 1911, -1, + 1907, 1910, 1912, -1, 1913, 1914, 1915, -1, + 1913, 1915, 1917, -1, 1913, 1917, 1914, -1, + 1916, 1918, 1917, -1, 1916, 1917, 1919, -1, + 1916, 1920, 1918, -1, 1916, 1919, 1920, -1, + 1941, 1958, 1940, -1, 1961, 1922, 1921, -1, + 1961, 1921, 1938, -1, 1961, 1962, 1922, -1, + 1945, 1923, 1932, -1, 1945, 1924, 1923, -1, + 1945, 1946, 1924, -1, 1943, 1925, 1946, -1, + 1943, 1946, 1944, -1, 1943, 1926, 1927, -1, + 1943, 1927, 1925, -1, 1943, 1928, 1926, -1, + 1943, 1930, 1929, -1, 1943, 1929, 1928, -1, + 1943, 1931, 1930, -1, 1943, 1932, 1931, -1, + 1943, 1945, 1932, -1, 1950, 1949, 1933, -1, + 1950, 1934, 1952, -1, 1950, 1935, 1934, -1, + 1950, 1933, 1935, -1, 1954, 1937, 1936, -1, + 1954, 1938, 1937, -1, 1954, 1958, 1941, -1, + 1954, 1936, 1955, -1, 1963, 1961, 1938, -1, + 1963, 1939, 1964, -1, 1963, 1940, 1939, -1, + 1963, 1941, 1940, -1, 1963, 1938, 1954, -1, + 1963, 1954, 1941, -1, 1942, 1943, 1944, -1, + 1942, 1945, 1943, -1, 1942, 1944, 1946, -1, + 1942, 1946, 1945, -1, 1947, 1948, 1949, -1, + 1947, 1949, 1950, -1, 1947, 1951, 1948, -1, + 1947, 1952, 1951, -1, 1947, 1950, 1952, -1, + 1953, 1954, 1955, -1, 1953, 1955, 1956, -1, + 1953, 1956, 1957, -1, 1953, 1958, 1954, -1, + 1953, 1957, 1959, -1, 1953, 1959, 1958, -1, + 1960, 1962, 1961, -1, 1960, 1961, 1963, -1, + 1960, 1964, 1962, -1, 1960, 1963, 1964, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ3.wrl b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ3.wrl new file mode 100644 index 0000000..067e13c --- /dev/null +++ b/data/models/mekabot-convex/rlsg/mekabot.convex/T2R3/T2R3_TJ3.wrl @@ -0,0 +1,2906 @@ +#VRML V2.0 utf8 + + +DEF solid_T2R3_TJ3__________________________________________________________________ Transform { + scale 0.001 0.001 0.001 + children + Shape { + appearance + Appearance { + material + Material { + } + + } + geometry + IndexedFaceSet { + coord + Coordinate { + point [ -5.0732899 50.546001 109.214, + -23.9622 44.7934 106.974, + -19.652 46.844898 -98.753799, + 154.745 -10.3801 95.25, + 154.745 10.3801 95.25, + 153.431 17.195601 95.25, + 82.550003 72.937401 95.25, + -29.020399 41.694801 96.513603, + -29.020399 41.694801 -96.513603, + -36.8195 34.9995 -96.513603, + -24.653299 44.416801 96.513603, + -24.653299 44.416801 -96.513603, + -27.1213 42.9543 106.974, + -17.2889 47.767502 -106.974, + -19.9849 46.7038 -109.214, + -23.9622 44.7934 -106.974, + -22.981001 45.304699 -98.753799, + -23.9622 44.7934 103.326, + -24.601601 44.445499 98.753799, + 145.716 36.4687 95.25, + 144.869 37.897099 97.917, + 155.405 -3.4705 95.25, + 154.745 -10.3801 -95.25, + 155.405 -3.4705 -95.25, + 155.317 -4.9774199 -97.917, + 153.96201 14.8395 97.917, + 154.745 10.3801 -95.25, + 155.405 3.4705 -95.25, + 155.317 4.9774199 -97.917, + 155.405 3.4705 95.25, + 145.716 -36.4687 -95.25, + 153.431 17.195601 -95.25, + 5.21451 50.5317 109.214, + 82.550003 72.937401 97.917, + 121.983 -61.358799 95.25, + 121.983 -61.358799 -95.25, + -17.2889 -47.767502 -106.974, + -23.9622 -44.7934 106.974, + -23.9622 -44.7934 102.402, + 103.091 -69.958801 97.917, + 50.799999 -72.937401 95.25, + 50.799999 -72.937401 -97.917, + 89.483101 -72.607101 95.25, + 40.1749 -30.4911 -109.214, + 40.745998 -28.5306 -109.214, + -50.130798 8.2185202 -98.753799, + -49.801399 10.023 98.753799, + -28.984699 41.719601 109.214, + -33.089699 38.544899 96.513603, + -33.089699 38.544899 -96.513603, + -50.734798 -2.5729799 -96.513603, + -50.734798 -2.5729799 96.513603, + -33.002499 38.619598 106.974, + -30.1399 40.892799 -106.974, + -27.1213 42.9543 -106.974, + -27.1213 42.9543 -103.326, + -26.1901 43.528301 -98.753799, + -24.6113 44.440102 -109.214, + -28.984699 41.719601 -109.214, + -27.744499 42.554401 98.753799, + 41.672298 26.938601 109.214, + 9.3241196 18.175501 109.214, + 50.7831 72.937401 97.926804, + 50.799999 72.937401 95.25, + 50.7831 72.937401 -97.926804, + -20.6791 46.4006 -102.402, + -20.6791 46.4006 -106.974, + -20.0333 46.683102 -96.513603, + -20.0333 46.683102 96.513603, + -20.6791 46.4006 106.974, + -21.3304 46.104801 98.753799, + 148.896 30.299299 95.25, + 132.883 52.7873 -95.25, + 132.883 52.7873 95.25, + 148.866 30.2848 97.917, + 149.44901 29.0583 97.917, + 149.27299 28.982 99.002899, + 139.994 40.5485 101.044, + 121.983 61.358799 95.25, + 153.431 -17.195601 95.25, + 153.431 -17.195601 -95.25, + 153.96201 -14.8395 -97.917, + 154.808 -9.9316397 -97.917, + 154.769 -9.9263096 -98.413696, + 155.448 -2.5949662e-009 -98.413696, + 155.369 -3.46927 -97.917, + 155.487 -3.814181e-009 -97.917, + 155.369 3.46927 -97.917, + 155.317 -4.9774199 97.917, + 153.96201 -14.8395 97.917, + 155.317 4.9774199 97.917, + 155.062 -3.3287564e-009 99.504501, + 151.254 -19.25 100.667, + 149.78 -23.8936 100.667, + 147.533 -28.226 100.901, + 132.883 -52.7873 95.25, + 132.334 -53.305302 97.917, + 148.896 -30.299299 95.25, + 10.3044 49.7439 109.214, + 151.459 23.85 97.917, + 82.550003 70.848297 100.901, + 0.070971809 50.7999 109.214, + 96.3535 71.619301 95.25, + 89.478996 72.566704 97.917, + 87.514397 72.576302 99.002899, + 87.524101 72.7192 98.4683, + 92.475098 72.210197 98.4683, + 96.348701 71.591301 97.917, + 97.389503 71.411797 97.917, + 109.658 67.7127 -95.25, + 109.658 67.7127 95.25, + 109.643 67.674103 -97.917, + 49.843899 72.8806 98.466904, + 50.288601 72.923599 98.211998, + 82.550003 72.889099 98.4683, + 82.550003 72.8983 -98.413696, + 87.527397 72.767303 -97.917, + 82.550003 72.937401 -97.917, + 82.550003 72.937401 -95.25, + 87.527397 72.767303 97.917, + -44.488201 24.5243 -102.402, + -44.488201 24.5243 -106.974, + -33.580898 38.117802 98.753799, + 120.447 -62.319099 -97.917, + 46.703098 -71.997597 100.153, + 47.252602 -72.252197 99.887199, + -19.652 -46.844898 98.753799, + -19.9849 -46.7038 -109.214, + -19.9849 -46.7038 109.214, + -17.2889 -47.767502 106.974, + 0.070971802 -50.7999 -109.214, + -5.0732899 -50.546001 -109.214, + -10.1654 -49.772499 -109.214, + 103.099 -69.982903 95.25, + 109.658 -67.7127 95.25, + 106.975 -68.725998 97.917, + 109.643 -67.674103 97.917, + 49.090698 -72.7668 98.893303, + 49.146 -72.792702 95.25, + 48.593201 -72.6782 99.173401, + 50.7831 -72.937401 -97.926804, + 50.7831 -72.937401 97.926804, + 87.524101 -72.7192 98.4683, + 89.478996 -72.566704 97.917, + 87.527397 -72.767303 97.917, + 82.550003 -72.889099 98.4683, + 82.550003 -72.937401 97.917, + 82.550003 -72.745903 99.002899, + 89.483101 -72.607101 -95.25, + 87.527397 -72.767303 -97.917, + 89.478996 -72.566704 -97.917, + 96.348701 -71.591301 97.917, + 96.3535 -71.619301 95.25, + 97.389503 -71.411797 97.917, + 92.481598 -72.258003 97.917, + -24.653299 -44.416801 96.513603, + -24.6113 -44.440102 109.214, + -24.653299 -44.416801 -96.513603, + -50.2132 7.6993198 109.214, + -47.840099 17.087 98.753799, + -47.632198 17.6581 109.214, + -50.274601 7.2871399 -102.402, + -50.274601 7.2871399 106.974, + -49.620399 10.8835 106.974, + -24.6113 44.440102 109.214, + -38.201099 33.486099 106.974, + -36.8195 34.9995 96.513603, + -44.882401 23.795099 98.753799, + -44.488201 24.5243 102.402, + -40.510201 30.652399 102.402, + -40.510201 30.652399 106.974, + -40.990002 30.0077 98.753799, + -45.608501 22.372 96.513603, + -45.608501 22.372 -96.513603, + -46.1366 21.2616 106.974, + -50.725498 2.7502601 98.753799, + -50.799999 5.699223e-011 106.974, + -33.002499 38.619598 -106.974, + -32.1828 39.305302 -98.753799, + -33.0602 38.570301 -109.214, + -33.002499 38.619598 102.402, + -33.0602 38.570301 109.214, + -30.1399 40.892799 103.326, + -30.1399 40.892799 106.974, + -30.7428 40.441502 98.753799, + -30.1399 40.892799 -102.402, + -29.2628 41.525101 -98.753799, + -42.609501 27.659901 -106.974, + -42.0466 28.508301 -98.753799, + -42.609501 27.659901 103.326, + -40.171398 31.094999 -96.513603, + -40.510201 30.652399 -106.974, + -40.171398 31.094999 96.513603, + 6.4279799 20.2034 -109.214, + 119.055 60.030701 -101.053, + -10.1654 49.772499 -109.214, + 144.869 37.897099 -97.917, + 145.683 36.450199 -97.917, + 145.716 36.4687 -95.25, + 142.09801 42.033699 98.4683, + 137.672 47.763802 95.25, + 137.672 47.763802 -95.25, + 147.267 33.533699 98.4683, + 149.405 29.039101 98.4683, + 147.31 33.555901 97.917, + 145.683 36.450199 97.917, + 144.828 37.872002 98.4683, + 135.026 49.009499 100.349, + 137.093 44.3741 101.044, + 146.93201 33.360199 99.504501, + 147.14 33.4678 99.002899, + 154.465 -9.8845196 -99.358398, + 155.14101 -5.1257607e-009 -99.358398, + 155.439 1.6873054e-009 98.4683, + 155.29601 -1.9035016e-009 99.002899, + 155.369 -3.46927 97.917, + 155.487 -3.0667635e-009 97.917, + 155.369 3.46927 97.917, + 154.75999 -9.9250698 98.4683, + 155.269 -4.9741302 98.4683, + 154.808 -9.9316397 97.917, + 153.774 -14.8006 99.002899, + 154.618 -9.9055595 99.002899, + 155.12601 -4.9643602 99.002899, + 152.408 -14.5166 100.667, + 149.05901 28.888901 99.504501, + 155.269 4.9741302 98.4683, + 154.808 9.9316397 97.917, + 154.576 4.9267302 99.957901, + 154.89301 4.94839 99.504501, + 154.07201 9.8304901 99.957901, + 151.239 24.4121 -98.413696, + 151.459 -23.85 97.917, + 151.476 -23.855499 95.25, + 152.783 -19.678301 97.917, + 153.91499 -14.8297 98.4683, + 147.993 -28.4259 100.667, + 131.25 -52.1451 100.667, + 135.026 -49.009499 100.349, + 135.312 -49.2766 99.957901, + 139.12801 -46.0299 -97.917, + 137.672 -47.763802 95.25, + 152.783 -19.678301 -97.917, + 145.683 -36.450199 -97.917, + 137.897 -45.028 100.667, + 138.24899 -45.314098 100.349, + 138.798 -45.761501 99.504501, + 138.552 -45.5611 99.957901, + 145.716 -36.4687 95.25, + 148.866 -30.2848 -97.917, + 148.896 -30.299299 -95.25, + 147.31 -33.555901 -97.917, + 147.27499 -33.537899 -98.413696, + 150.256 -18.9704 101.044, + 150.771 -19.114599 100.901, + 149.308 -23.725599 100.901, + 144.491 -32.0952 101.092, + 147.043 -28.0131 101.044, + 137.093 -44.3741 101.044, + 96.9645 69.366402 100.901, + 92.197197 70.1884 100.901, + 92.124397 69.658798 101.044, + 96.855698 68.843002 101.044, + 151.476 23.855499 -95.25, + 151.476 23.855499 95.25, + 151.459 23.85 -97.917, + 151.276 24.4252 -97.917, + 151.276 24.4252 97.917, + 87.419098 71.183502 100.667, + 87.384903 70.683098 100.901, + 92.265503 70.685303 100.667, + 45.547199 71.341599 100.652, + 82.550003 71.349899 100.667, + 45.070599 71.0215 100.832, + -10.1654 49.772499 109.214, + 15.2884 48.444801 109.214, + 101.52 67.706299 101.044, + 97.066597 69.857498 100.667, + 97.158798 70.301399 100.349, + 103.099 69.982903 95.25, + 92.455597 72.068298 99.002899, + 97.3797 71.364601 98.4683, + 106.975 68.725998 97.917, + 103.091 69.958801 97.917, + 102.215 70.186203 98.4683, + 102.228 70.232697 97.917, + 102.028 69.517403 99.957901, + 106.911 68.545601 99.002899, + 102.177 70.048302 99.002899, + 111.608 66.899002 -97.917, + 115.972 64.8293 -95.25, + 115.97 64.824799 -97.917, + 115.972 64.8293 95.25, + 116.106 64.760002 97.917, + 87.4767 72.026299 99.957901, + 87.449997 71.635803 100.349, + 87.498398 72.343002 99.504501, + 92.380501 71.522102 99.957901, + 92.327202 71.134399 100.349, + 47.992599 72.498299 99.496101, + 46.8559 72.082397 100.084, + 47.2799 72.263 99.873299, + 82.550003 72.194603 99.957901, + 82.550003 72.512001 99.504501, + 47.583199 72.363197 99.712799, + 47.113998 72.192398 99.956001, + 47.578899 72.376198 95.25, + 47.542301 72.3629 95.25, + -17.947901 47.5238 98.753799, + -17.2889 47.767502 106.974, + -19.9849 46.7038 109.214, + 48.9049 72.7295 98.997002, + 82.550003 72.745903 99.002899, + 87.524803 72.728302 -98.413696, + 92.481598 72.258003 -97.917, + 89.478996 72.566704 -97.917, + 89.483101 72.607101 -95.25, + 89.483101 72.607101 95.25, + 92.481598 72.258003 97.917, + 96.3535 71.619301 -95.25, + -43.111099 -26.871401 -96.513603, + -43.097801 -26.8927 -109.214, + -43.994099 -25.4 98.753799, + -43.111099 -26.871401 96.513603, + -39.879902 -31.468 98.753799, + -48.4258 15.3487 -98.753799, + -45.5994 22.390499 -109.214, + -35.694199 36.1464 -106.974, + -36.795799 35.024399 -109.214, + -34.935101 36.8806 -98.753799, + -35.694199 36.1464 106.974, + 124.589 -59.555698 -98.413696, + 127.637 -57.3326 -95.25, + 128.58 -56.5783 -97.917, + 124.612 -59.587601 -97.917, + 127.637 -57.3326 95.25, + 132.203 -53.165298 99.002899, + 132.30099 -53.27 98.4683, + 132.043 -52.9944 99.504501, + 135.715 -49.652901 99.002899, + 135.54401 -49.493301 99.504501, + 128.311 -56.248402 99.504501, + 131.827 -52.762402 99.957901, + 131.56 -52.476398 100.349, + -10.1654 -49.772499 109.214, + 0.070971794 -50.7999 109.214, + -20.6791 -46.4006 106.974, + -20.0333 -46.683102 96.513603, + -23.9622 -44.7934 -106.974, + -24.6113 -44.440102 -109.214, + -24.601601 -44.445499 -98.753799, + -23.9622 -44.7934 -103.326, + -22.981001 -45.304699 98.753799, + -35.694199 -36.1464 -103.326, + -34.935101 -36.8806 98.753799, + -35.694199 -36.1464 -106.974, + -15.153 -48.4874 -109.214, + 96.3535 -71.619301 -95.25, + 92.481598 -72.258003 -97.917, + 103.091 -69.958801 -97.917, + 103.099 -69.982903 -95.25, + 102.228 -70.232697 -97.917, + 109.658 -67.7127 -95.25, + 111.608 -66.899002 97.917, + 106.911 -68.545601 99.002899, + 116.084 -64.717201 98.4683, + 115.97 -64.824799 97.917, + 111.589 -66.854698 98.4683, + 120.447 -62.319099 97.917, + 97.303001 -70.9953 99.504501, + 102.114 -69.823097 99.504501, + 47.579601 -72.3741 99.718399, + 48.261799 -72.578796 99.351601, + 82.550003 -72.512001 99.504501, + 49.165199 -72.795998 -95.25, + 49.165199 -72.795998 95.25, + 92.455597 -72.068298 99.002899, + 87.514397 -72.576302 99.002899, + 92.475098 -72.210197 98.4683, + 97.350601 -71.224297 99.002899, + 49.146 -72.792702 -95.25, + 82.550003 -72.937401 -97.917, + 97.389503 -71.411797 -97.917, + 96.348701 -71.591301 -97.917, + 41.672298 26.938601 -109.214, + 96.844597 -68.789497 -101.053, + 10.3044 -49.7439 -109.214, + -47.192001 -18.802999 98.753799, + -48.7094 -14.4236 103.326, + -48.7094 -14.4236 -106.974, + -48.4258 -15.3487 98.753799, + -48.7094 -14.4236 106.974, + -48.948299 -13.5904 -98.753799, + -30.1399 -40.892799 106.974, + -27.1213 -42.9543 103.326, + -26.1901 -43.528301 98.753799, + -27.1213 -42.9543 -106.974, + -27.1213 -42.9543 106.974, + -27.744499 -42.554401 -98.753799, + -43.097801 26.8927 109.214, + -36.795799 35.024399 109.214, + -45.5994 22.390499 109.214, + -42.609501 27.659901 106.974, + -44.488201 24.5243 106.974, + -43.048401 26.971701 98.753799, + -43.097801 26.8927 -109.214, + -43.994099 25.4 -98.753799, + -43.111099 26.871401 96.513603, + -43.111099 26.871401 -96.513603, + -49.1754 -12.7442 109.214, + -49.620399 -10.8835 -106.974, + -49.620399 -10.8835 102.402, + -50.130798 -8.2185202 98.753799, + -49.801399 -10.023 -98.753799, + -49.620399 -10.8835 106.974, + -50.593102 4.5797801 -98.753799, + -50.274601 7.2871399 -106.974, + -50.394798 6.4033298 98.753799, + -50.668499 3.6530299 -106.974, + -50.668499 3.6530299 102.402, + -50.668499 3.6530299 106.974, + -50.734798 2.5729799 -96.513603, + -50.734798 2.5729799 96.513603, + -50.734699 2.5752599 109.214, + -50.799999 5.5735443e-009 -106.974, + -50.734699 2.5752599 -109.214, + -50.791698 0.91715097 -98.753799, + -50.791698 -0.91715097 98.753799, + -50.799999 1.8070304e-010 102.402, + -47.632198 -17.6581 109.214, + -47.546101 -17.888901 106.974, + -40.510201 -30.652399 -106.974, + -39.879902 31.468 -98.753799, + -40.153198 31.1185 -109.214, + -40.153198 31.1185 109.214, + -38.201099 33.486099 -102.402, + -37.505299 34.263599 -98.753799, + -38.201099 33.486099 103.326, + -38.201099 33.486099 -106.974, + -38.7178 32.887199 98.753799, + 47.3325 -14.2099 109.214, + 45.200901 13.9958 109.214, + 42.448299 -19.741699 109.214, + 0.070971802 50.7999 -109.214, + -5.0732899 50.546001 -109.214, + 49.090698 72.7668 -98.893303, + 49.673901 72.870598 -98.564903, + 49.1679 72.7826 98.849899, + 48.359901 72.619499 99.301697, + 46.703098 71.997597 -100.153, + 149.306 28.996401 -98.898102, + 147.172 33.484402 -98.898102, + 144.836 37.876801 -98.413696, + 148.866 30.2848 -97.917, + 149.44901 29.0583 -97.917, + 149.41299 29.042801 -98.413696, + 147.27499 33.537899 -98.413696, + 147.31 33.555901 -97.917, + 148.896 30.299299 -95.25, + 141.78999 41.8162 99.504501, + 141.981 41.951099 99.002899, + 144.506 37.676102 99.504501, + 144.70599 37.7976 99.002899, + 141.53101 41.633202 99.957901, + 138.798 45.761501 99.504501, + 138.552 45.5611 99.957901, + 141.963 42.3078 95.25, + 139.12801 46.0299 97.917, + 142.138 42.061501 97.917, + 141.963 42.3078 -95.25, + 135.60201 49.547401 -99.358398, + 128.48199 56.457802 -98.898102, + 132.097 53.052299 -99.358398, + 135.855 49.7836 -97.917, + 132.228 53.1917 -98.898102, + 135.742 49.677601 -98.898102, + 132.30701 53.276699 -98.413696, + 132.334 53.305302 -97.917, + 128.58 56.5783 97.917, + 128.549 56.540901 98.4683, + 127.637 57.3326 95.25, + 135.312 49.2766 99.957901, + 106.726 68.0261 99.957901, + 33.167801 38.477699 109.214, + 36.893501 34.921501 109.214, + 134.328 48.3577 100.901, + 134.69501 48.7001 100.667, + 133.938 47.992802 101.044, + 128.58 56.5783 -97.917, + 127.637 57.3326 -95.25, + 128.55499 56.548 -98.413696, + 121.983 61.358799 -95.25, + 120.267 62.023399 -99.358398, + 115.308 63.220798 -100.746, + 120.132 61.800999 -99.783203, + 124.412 59.304901 -99.358398, + 128.362 56.309898 -99.358398, + 155.162 4.9668198 -98.898102, + 155.278 4.97475 -98.413696, + 155.162 -4.9668198 -98.898102, + 154.65401 -9.9104795 -98.898102, + 155.278 -4.97475 -98.413696, + 154.972 -4.9538102 -99.358398, + 155.332 -5.2794613e-009 -98.898102, + 153.235 -9.7154703 100.667, + 154.89301 -4.94839 99.504501, + 152.851 -14.6088 100.349, + 153.545 -14.753 99.504501, + 154.618 9.9055595 99.002899, + 155.12601 4.9643602 99.002899, + 154.38699 9.8737202 99.504501, + 154.75999 9.9250698 98.4683, + 152.73599 19.6653 98.4683, + 153.91499 14.8297 98.4683, + 152.783 19.678301 97.917, + 151.231 24.4091 98.4683, + 152.373 19.563499 99.504501, + 153.774 14.8006 99.002899, + 153.545 14.753 99.504501, + 152.59801 19.6266 99.002899, + 153.235 14.6884 99.957901, + 152.067 19.4779 99.957901, + 150.875 24.282801 99.504501, + 151.09599 24.361099 99.002899, + 135.412 49.369801 -99.783203, + 40.2985 29.463699 -109.214, + 49.5042 11.4008 -109.214, + 150.207 -24.045401 100.349, + 151.69099 -19.372299 100.349, + 152.067 -19.4779 99.957901, + 152.73599 -19.6653 98.4683, + 152.59801 -19.6266 99.002899, + 152.373 -19.563499 99.504501, + 145.89999 -32.8256 100.667, + 143.513 -37.0723 100.667, + 141.211 -41.407501 100.349, + 140.841 -41.146099 100.667, + 148.59599 -28.687799 -100.162, + 141.981 -41.951099 99.002899, + 141.78999 -41.8162 99.504501, + 138.98 -45.9091 99.002899, + 135.82001 -49.750702 98.4683, + 137.64101 -47.736099 97.917, + 142.138 -42.061501 97.917, + 144.869 -37.897099 97.917, + 142.09801 -42.033699 98.4683, + 141.963 -42.3078 95.25, + 139.12801 -46.0299 97.917, + 141.963 -42.3078 -95.25, + 142.138 -42.061501 -97.917, + 144.869 -37.897099 -97.917, + 139.091 -45.9995 98.4683, + 134.328 -48.3577 100.901, + 130.908 -51.7785 100.901, + 134.69501 -48.7001 100.667, + 133.938 -47.992802 101.044, + 137.508 -44.711498 100.901, + 142.627 -36.533901 101.044, + 143.084 -36.8116 100.901, + 140.431 -40.8568 100.901, + 139.994 -40.5485 101.044, + 144.98 -32.3489 101.044, + 145.455 -32.594799 100.901, + 46.092201 71.6828 100.433, + 45.925701 71.595703 100.509, + 82.550003 71.8032 100.349, + 46.302502 71.792801 100.337, + -15.153 48.4874 109.214, + 101.665 68.221001 100.901, + 101.8 68.704002 100.667, + 101.922 69.140602 100.349, + 103.099 69.982903 -95.25, + 97.303001 70.9953 99.504501, + 92.423698 71.836601 99.504501, + 97.238403 70.684502 99.957901, + 97.350601 71.224297 99.002899, + 102.114 69.823097 99.504501, + 111.589 66.854698 98.4683, + 106.959 68.680603 98.4683, + 109.643 67.674103 97.917, + 111.608 66.899002 97.917, + 115.97 64.824799 97.917, + 116.106 64.760002 -97.917, + 120.447 62.319099 -97.917, + 124.612 59.587601 -97.917, + 124.589 59.555698 -98.413696, + 124.522 59.460701 -98.898102, + 111.238 66.045998 -100.162, + 111.087 65.698502 -100.486, + 115.827 64.221603 -99.783203, + 115.678 63.934299 -100.162, + 115.504 63.598 -100.486, + 96.348701 71.591301 -97.917, + 101.636 68.120102 -100.937, + -44.882401 -23.795099 -98.753799, + -44.488201 -24.5243 -106.974, + -45.5994 -22.390499 -109.214, + -44.488201 -24.5243 -103.326, + -44.488201 -24.5243 103.326, + -44.488201 -24.5243 106.974, + -36.795799 -35.024399 109.214, + -36.8195 -34.9995 96.513603, + -35.694199 -36.1464 106.974, + -36.243801 -35.595299 -98.753799, + -36.795799 -35.024399 -109.214, + -36.8195 -34.9995 -96.513603, + -48.7094 14.4236 -102.402, + -48.7094 14.4236 106.974, + -46.1366 21.2616 -102.402, + -46.1366 21.2616 102.402, + -46.482399 20.494499 98.753799, + -46.1366 21.2616 -106.974, + -45.7122 22.1593 -98.753799, + -35.694199 36.1464 102.402, + -36.243801 35.595299 98.753799, + -35.694199 36.1464 -102.402, + -35.694199 36.1464 103.326, + 139.09801 -46.005199 -98.413696, + 142.106 -42.039001 -98.413696, + 128.19701 -56.108002 -99.783203, + 124.412 -59.304901 -99.358398, + 124.584 -59.548199 98.4683, + 120.348 -62.155499 99.002899, + 124.501 -59.431198 99.002899, + 120.422 -62.277901 98.4683, + 124.612 -59.587601 97.917, + 128.58 -56.5783 97.917, + 128.549 -56.540901 98.4683, + 128.459 -56.429798 99.002899, + -15.153 -48.4874 109.214, + -5.0732899 -50.546001 109.214, + 45.070599 -71.0215 100.832, + 5.21451 -50.5317 109.214, + -20.6791 -46.4006 -102.402, + -20.6791 -46.4006 -106.974, + -21.3304 -46.104801 -98.753799, + -20.6791 -46.4006 103.326, + -20.0333 -46.683102 -96.513603, + -29.020399 -41.694801 96.513603, + -28.984699 -41.719601 109.214, + -29.020399 -41.694801 -96.513603, + -28.984699 -41.719601 -109.214, + -33.089699 -38.544899 -96.513603, + -33.089699 -38.544899 96.513603, + -33.0602 -38.570301 -109.214, + -33.580898 -38.117802 -98.753799, + 82.550003 -70.7435 -100.937, + 45.070599 -71.0215 -100.832, + 45.547199 -71.341599 -100.652, + 47.113998 -72.192398 -99.956001, + 46.8559 -72.082397 -100.084, + 46.302502 -71.792801 -100.337, + 46.092201 -71.6828 -100.433, + 45.925701 -71.595703 -100.509, + 29.1012 -41.6385 -109.214, + 131.14999 -52.0383 -100.746, + 115.972 -64.8293 95.25, + 116.106 -64.760002 97.917, + 102.215 -70.186203 98.4683, + 106.959 -68.680603 98.4683, + 102.228 -70.232697 97.917, + 102.177 -70.048302 99.002899, + 97.3797 -71.364601 98.4683, + 92.124397 -69.658798 101.044, + 127.864 -55.698601 100.349, + 82.550003 -72.194603 99.957901, + 87.498398 -72.343002 99.504501, + 47.578899 -72.376198 95.25, + 48.9049 -72.7295 -98.997002, + 49.1679 -72.7826 -98.849899, + 49.843899 -72.8806 -98.466904, + 49.478401 -72.8452 -98.6763, + 50.288601 -72.923599 -98.211998, + 49.673901 -72.870598 98.564903, + 102.186 -70.083 -98.898102, + 97.381599 -71.373497 -98.413696, + 41.528198 -9.88381 -109.214, + 22.6759 15.1438 -109.214, + 5.21451 -50.5317 -109.214, + 123.067 -57.399502 -101.053, + -46.1366 -21.2616 -103.326, + -46.482399 -20.494499 -98.753799, + -46.1366 -21.2616 -106.974, + -46.1366 -21.2616 106.974, + -45.608501 -22.372 96.513603, + -45.7122 -22.1593 98.753799, + -45.5994 -22.390499 109.214, + -45.608501 -22.372 -96.513603, + -33.002499 -38.619598 103.326, + -32.1828 -39.305302 98.753799, + -33.002499 -38.619598 -106.974, + -33.002499 -38.619598 106.974, + -33.0602 -38.570301 109.214, + -30.1399 -40.892799 -102.402, + -30.7428 -40.441502 -98.753799, + -30.1399 -40.892799 -106.974, + -30.1399 -40.892799 102.402, + -29.2628 -41.525101 98.753799, + -49.178299 -12.7331 -96.513603, + -49.407101 -11.8144 98.753799, + -49.1754 -12.7442 -109.214, + -49.178299 -12.7331 96.513603, + -50.2132 -7.6993198 109.214, + -50.274601 -7.2871399 106.974, + -50.593102 -4.5797801 98.753799, + -50.274601 -7.2871399 -106.974, + -50.274601 -7.2871399 -102.402, + -50.2132 -7.6993198 -109.214, + -50.394798 -6.4033298 -98.753799, + -47.637798 -17.643101 -96.513603, + -47.840099 -17.087 -98.753799, + -47.632198 -17.6581 -109.214, + -47.637798 -17.643101 96.513603, + -47.546101 -17.888901 -106.974, + -40.171398 -31.094999 -96.513603, + -40.153198 -31.1185 -109.214, + 151.39301 -14.3057 101.044, + 151.916 -14.4145 100.901, + 150.853 -14.1936 101.092, + 47.912899 -13.3635 109.214, + 40.240002 -31.006201 109.214, + 50.748001 -2.29896 109.214, + 50.332199 -6.8780499 109.214, + 50.748001 2.29896 109.214, + 152.312 -2.3984763e-009 101.092, + 15.2884 48.444801 -109.214, + 29.1012 41.6385 -109.214, + 24.735399 44.371201 -109.214, + 96.844597 68.789497 -101.053, + 101.506 67.653702 -101.053, + 47.578899 72.376198 -95.25, + 49.165199 72.795998 95.25, + 49.165199 72.795998 -95.25, + 49.478401 72.8452 98.6763, + 49.146 72.792702 95.25, + 49.146 72.792702 -95.25, + 47.579601 72.3741 -99.718399, + 48.261799 72.578796 -99.351601, + 48.593201 72.6782 -99.173401, + 47.252602 72.252197 -99.887199, + 47.5411 72.362503 -99.739098, + -15.153 48.4874 -109.214, + 140.841 41.146099 100.667, + 140.431 40.8568 100.901, + 137.508 44.711498 100.901, + 137.897 45.028 100.667, + 138.24899 45.314098 100.349, + 141.211 41.407501 100.349, + 139.091 45.9995 98.4683, + 137.64101 47.736099 97.917, + 135.855 49.7836 97.917, + 132.30099 53.27 98.4683, + 132.334 53.305302 97.917, + 139.09801 46.005199 -98.413696, + 135.827 49.757 -98.413696, + 139.008 45.931801 -98.898102, + 142.106 42.039001 -98.413696, + 137.64101 47.736099 -97.917, + 139.12801 46.0299 -97.917, + 142.138 42.061501 -97.917, + 120.422 62.277901 98.4683, + 120.447 62.319099 97.917, + 124.612 59.587601 97.917, + 127.262 54.957802 100.901, + 131.25 52.1451 100.667, + 130.908 51.7785 100.901, + 130.543 51.387798 101.044, + 126.924 54.543098 101.044, + 116.084 64.717201 98.4683, + 123.407 57.880901 100.901, + 123.696 58.290699 100.667, + 106.097 66.253899 101.044, + 119.546 60.837898 -100.746, + 131.92 52.862099 -99.783203, + 128.19701 56.108002 -99.783203, + 124.262 59.0923 -99.783203, + 146.992 -27.991301 -101.053, + 45.200901 13.9958 -109.214, + 152.73801 -9.6471701 100.901, + 154.745 2.8524769e-010 99.957901, + 154.07201 -9.8304901 99.957901, + 153.235 -14.6884 99.957901, + 153.68401 -9.7771997 100.349, + 154.38699 -9.8737202 99.504501, + 154.576 -4.9267302 99.957901, + 150.576 24.1765 99.957901, + 138.86 45.811501 -99.358398, + 36.893501 34.921501 -109.214, + 133.89799 47.955502 -101.053, + 33.167801 38.477699 -109.214, + 40.240002 31.006201 -109.214, + 137.05099 44.3396 -101.053, + 142.58099 36.505501 -101.053, + 146.992 27.991301 -101.053, + 150.576 -24.1765 99.957901, + 150.875 -24.282801 99.504501, + 148.409 -28.606501 100.349, + 151.231 -24.4091 98.4683, + 149.44901 -29.0583 97.917, + 148.866 -30.2848 97.917, + 148.76801 -28.7624 99.957901, + 144.23399 -37.511101 99.957901, + 141.53101 -41.633202 99.957901, + 143.89999 -37.3078 100.349, + 146.64999 -33.214199 99.957901, + 146.30299 -33.034199 100.349, + 144.73599 -37.816299 -98.898102, + 144.836 -37.876801 -98.413696, + 147.172 -33.484402 -98.898102, + 146.48399 -33.128101 -100.162, + 137.784 -44.935902 -100.746, + 134.588 -48.600399 -100.746, + 148.89301 -28.8167 -99.783203, + 153.924 -14.8316 -98.413696, + 153.81 -14.8079 -98.898102, + 151.276 -24.4252 -97.917, + 151.459 -23.85 -97.917, + 151.476 -23.855499 -95.25, + 151.276 -24.4252 97.917, + 149.44901 -29.0583 -97.917, + 106.276 66.757599 100.901, + 116.034 64.622002 -98.898102, + 116.088 64.725304 -98.413696, + 111.593 66.863098 -98.413696, + 111.546 66.756401 -98.898102, + 115.947 64.452797 -99.358398, + 120.366 62.186298 -98.898102, + 120.427 62.285702 -98.413696, + 92.476303 72.219299 -98.413696, + 97.389503 71.411797 -97.917, + 102.228 70.232697 -97.917, + 97.381599 71.373497 -98.413696, + 106.962 68.689201 -98.413696, + 103.091 69.958801 -97.917, + 106.975 68.725998 -97.917, + 106.395 67.092499 -100.746, + 106.537 67.492798 -100.486, + 110.918 65.308899 -100.746, + -38.201099 -33.486099 106.974, + -49.1754 12.7442 -109.214, + -48.948299 13.5904 98.753799, + -48.7094 14.4236 -106.974, + -49.1754 12.7442 109.214, + -49.178299 12.7331 96.513603, + -49.178299 12.7331 -96.513603, + -47.632198 17.6581 -109.214, + -50.2132 7.6993198 -109.214, + -49.620399 10.8835 -106.974, + -49.407101 11.8144 -98.753799, + -47.546101 17.888901 102.402, + -47.546101 17.888901 -106.974, + -47.637798 17.643101 -96.513603, + -47.637798 17.643101 96.513603, + -47.192001 18.802999 -98.753799, + -47.546101 17.888901 106.974, + 135.855 -49.7836 -97.917, + 132.883 -52.7873 -95.25, + 135.855 -49.7836 97.917, + 137.672 -47.763802 -95.25, + 137.64101 -47.736099 -97.917, + 128.362 -56.309898 -99.358398, + 132.30701 -53.276699 -98.413696, + 135.827 -49.757 -98.413696, + 132.334 -53.305302 -97.917, + 128.55499 -56.548 -98.413696, + 128.48199 -56.457802 -98.898102, + 139.008 -45.931801 -98.898102, + 142.011 -41.971901 -98.898102, + 124.522 -59.460701 -98.898102, + 124.075 -58.8279 -100.162, + 124.262 -59.0923 -99.783203, + 120.267 -62.023399 -99.358398, + 120.132 -61.800999 -99.783203, + 127.754 -55.563099 -100.486, + 127.993 -55.856998 -100.162, + 131.44 -52.348701 -100.486, + 45.991501 -71.620003 100.474, + 46.0938 -71.681 100.431, + 82.550003 -71.998901 100.154, + 46.352299 -71.835197 100.322, + 92.182899 -70.084602 -100.937, + 97.036797 -69.7145 -100.746, + 87.409103 -71.037804 -100.746, + 82.550003 -71.203796 -100.746, + 87.377701 -70.578598 -100.937, + 130.506 -51.347801 -101.053, + 130.836 -51.7019 -100.937, + 126.89 -54.500702 -101.053, + 134.252 -48.286201 -100.937, + 133.89799 -47.955502 -101.053, + 33.167801 -38.477699 -109.214, + 36.893501 -34.921501 -109.214, + 106.962 -68.689201 -98.413696, + 102.218 -70.195 -98.413696, + 106.975 -68.725998 -97.917, + 109.643 -67.674103 -97.917, + 115.97 -64.824799 -97.917, + 111.608 -66.899002 -97.917, + 115.972 -64.8293 -95.25, + 116.106 -64.760002 -97.917, + 33.167801 -38.477699 109.214, + 36.893501 -34.921501 109.214, + 130.543 -51.387798 101.044, + 111.532 -66.723396 99.002899, + 116.018 -64.589996 99.002899, + 127.578 -55.346901 100.667, + 124.183 -58.980801 99.957901, + 128.11099 -56.002102 99.957901, + 124.366 -59.240101 99.504501, + 92.423698 -71.836601 99.504501, + 87.4767 -72.026299 99.957901, + 47.542301 -72.3629 -95.25, + 47.2799 -72.263 -99.873299, + 47.5411 -72.362503 99.739098, + -17.947901 -47.5238 -98.753799, + 47.992599 -72.498299 -99.496101, + 47.583199 -72.363197 -99.712799, + 47.578899 -72.376198 -95.25, + 48.359901 -72.619499 -99.301697, + 82.550003 -72.007401 -100.162, + 82.550003 -71.628601 -100.486, + 102.135 -69.899399 -99.358398, + 152.67999 -14.5733 -100.486, + 151.814 -14.3932 -100.937, + 152.26401 -14.4868 -100.746, + 123.346 -57.7953 -100.937, + 127.486 -55.233601 -100.746, + 123.857 -58.518398 -100.486, + 127.195 -54.876499 -100.937, + 114.874 -62.382 -101.053, + 119.055 -60.030701 -101.053, + 24.735399 -44.371201 -109.214, + 106.078 -66.2024 -101.053, + 15.2884 -48.444801 -109.214, + 20.115299 -46.6478 -109.214, + 101.636 -68.120102 -100.937, + 101.506 -67.653702 -101.053, + 96.943199 -69.263802 -100.937, + 115.678 -63.934299 -100.162, + 115.827 -64.221603 -99.783203, + 119.964 -61.524502 -100.162, + 110.734 -64.886703 -100.937, + 110.541 -64.442398 -101.053, + -50.725498 -2.7502601 -98.753799, + -50.668499 -3.6530299 -106.974, + -50.734699 -2.5752599 -109.214, + -50.668499 -3.6530299 106.974, + -50.734699 -2.5752599 109.214, + -40.153198 -31.1185 109.214, + -43.097801 -26.8927 109.214, + -40.510201 -30.652399 103.326, + -40.510201 -30.652399 -103.326, + -40.990002 -30.0077 -98.753799, + -40.510201 -30.652399 106.974, + -40.171398 -31.094999 96.513603, + 148.284 -23.362 101.092, + 149.72501 -18.821699 101.092, + 148.804 -23.5466 101.044, + 49.5042 -11.4008 109.214, + 146.537 -27.7934 101.092, + 110.541 64.442398 -101.053, + 20.115299 46.6478 -109.214, + 114.874 62.382 -101.053, + 106.078 66.2024 -101.053, + 115.097 62.812099 -100.937, + 110.734 64.886703 -100.937, + 106.241 66.658798 -100.937, + 82.550003 72.591301 -99.358398, + 87.5168 72.612297 -98.898102, + 82.550003 72.781998 -98.898102, + 45.991501 71.620003 -100.474, + 46.0938 71.681 -100.431, + 46.352299 71.835197 -100.322, + 135.715 49.652901 99.002899, + 135.54401 49.493301 99.504501, + 138.98 45.9091 99.002899, + 135.82001 49.750702 98.4683, + 132.203 53.165298 99.002899, + 124.501 59.431198 99.002899, + 124.584 59.548199 98.4683, + 128.311 56.248402 99.504501, + 132.043 52.9944 99.504501, + 131.827 52.762402 99.957901, + 128.459 56.429798 99.002899, + 127.864 55.698601 100.349, + 127.578 55.346901 100.667, + 128.11099 56.002102 99.957901, + 131.56 52.476398 100.349, + 111.532 66.723396 99.002899, + 106.833 68.325203 99.504501, + 119.622 60.9627 100.667, + 123.958 58.661098 100.349, + 120.348 62.155499 99.002899, + 124.366 59.240101 99.504501, + 124.183 58.980801 99.957901, + 120.061 61.684399 99.957901, + 123.099 57.444199 101.044, + 29.1012 41.6385 109.214, + 119.307 60.444599 -100.937, + 123.067 57.399502 -101.053, + 131.69901 52.625599 -100.162, + 154.55701 -5.7196449e-011 -100.162, + 154.881 1.8693105e-009 -99.783203, + 154.71201 -4.9360399 -99.783203, + 154.207 -9.8490696 -99.783203, + 148.752 -23.528299 -101.053, + 150.20399 -18.9557 -101.053, + 151.34 -14.2946 -101.053, + 152.63499 -9.6329098 -100.937, + 41.672298 -26.938601 -109.214, + 152.7 -4.7983799 101.044, + 152.209 -9.5743799 101.044, + 152.14999 -4.7607498 101.092, + 151.66299 -9.4993095 101.092, + 152.864 -6.0321241e-009 101.044, + 153.233 -4.8348598 100.901, + 153.233 4.8348598 100.901, + 144.573 37.7173 -99.358398, + 147.00301 33.396702 -99.358398, + 144.73599 37.816299 -98.898102, + 142.011 41.971901 -98.898102, + 138.407 45.443001 -100.162, + 135.17599 49.148899 -100.162, + 130.506 51.347801 -101.053, + 139.95 40.516998 -101.053, + 148.752 23.528299 -101.053, + 151.13 24.373199 -98.898102, + 154.71201 4.9360399 -99.783203, + 151.09599 -24.361099 99.002899, + 149.27299 -28.982 99.002899, + 144.506 -37.676102 99.504501, + 146.93201 -33.360199 99.504501, + 149.05901 -28.888901 99.504501, + 135.17599 -49.148899 -100.162, + 131.69901 -52.625599 -100.162, + 134.899 -48.890301 -100.486, + 138.11301 -45.203899 -100.486, + 138.407 -45.443001 -100.162, + 138.658 -45.647202 -99.783203, + 144.351 -37.582001 -99.783203, + 141.642 -41.711899 -99.783203, + 146.772 -33.277 -99.783203, + 144.573 -37.7173 -99.358398, + 141.855 -41.862 -99.358398, + 147.00301 -33.396702 -99.358398, + 141.06799 -41.306801 -100.486, + 144.075 -37.413898 -100.162, + 141.37801 -41.525299 -100.162, + 140.72099 -41.061798 -100.746, + 144.93201 -32.3237 -101.053, + 139.95 -40.516998 -101.053, + 140.345 -40.796398 -100.937, + 137.427 -44.645401 -100.937, + 137.05099 -44.3396 -101.053, + 142.58099 -36.505501 -101.053, + 40.240002 -31.006201 -109.214, + 152.19901 -19.5147 -99.783203, + 152.44901 -19.5849 -99.358398, + 150.705 -24.2222 -99.783203, + 151.88699 -19.427401 -100.162, + 150.39999 -24.1138 -100.162, + 153.368 -14.7162 -99.783203, + 153.05099 -14.6503 -100.162, + 153.623 -14.7691 -99.358398, + 151.13 -24.373199 -98.898102, + 152.633 -19.636299 -98.898102, + 150.95 -24.309401 -99.358398, + 151.239 -24.4121 -98.413696, + 152.745 -19.6677 -98.413696, + 149.306 -28.996401 -98.898102, + 149.132 -28.9205 -99.358398, + 149.41299 -29.042801 -98.413696, + 106.595 67.657402 100.349, + 106.444 67.230202 100.667, + 92.460503 72.104103 -98.898102, + 111.47 66.581596 -99.358398, + -38.201099 -33.486099 -103.326, + -38.201099 -33.486099 -106.974, + -37.505299 -34.263599 98.753799, + -38.201099 -33.486099 103.326, + -38.7178 -32.887199 -98.753799, + 135.60201 -49.547401 -99.358398, + 138.86 -45.811501 -99.358398, + 135.742 -49.677601 -98.898102, + 135.412 -49.369801 -99.783203, + 132.228 -53.1917 -98.898102, + 132.097 -53.052299 -99.358398, + 131.92 -52.862099 -99.783203, + 82.550003 -71.349899 100.667, + 82.550003 -71.8032 100.349, + 45.503502 -71.329002 100.679, + 45.147701 -71.079002 100.806, + 82.550003 -70.848297 100.901, + 87.384903 -70.683098 100.901, + 87.419098 -71.183502 100.667, + 87.449997 -71.635803 100.349, + 92.245598 -70.540604 -100.746, + 111.47 -66.581596 -99.358398, + 106.859 -68.400002 -99.358398, + 106.923 -68.579597 -98.898102, + 116.034 -64.622002 -98.898102, + 111.546 -66.756401 -98.898102, + 115.947 -64.452797 -99.358398, + 120.366 -62.186298 -98.898102, + 111.593 -66.863098 -98.413696, + 116.088 -64.725304 -98.413696, + 120.427 -62.285702 -98.413696, + 106.726 -68.0261 99.957901, + 106.833 -68.325203 99.504501, + 123.958 -58.661098 100.349, + 96.9645 -69.366402 100.901, + 92.197197 -70.1884 100.901, + 82.550003 -72.591301 -99.358398, + 92.476303 -72.219299 -98.413696, + 119.546 -60.837898 -100.746, + 123.612 -58.171398 -100.746, + 119.307 -60.444599 -100.937, + 119.767 -61.200901 -100.486, + 115.097 -62.812099 -100.937, + 115.308 -63.220798 -100.746, + 115.504 -63.598 -100.486, + 106.664 -67.8498 -100.162, + 101.977 -69.337196 -100.162, + 102.065 -69.648804 -99.783203, + 106.772 -68.154701 -99.783203, + 101.875 -68.972397 -100.486, + 111.367 -66.342796 -99.783203, + 111.238 -66.045998 -100.162, + 111.087 -65.698502 -100.486, + 106.395 -67.092499 -100.746, + 110.918 -65.308899 -100.746, + 106.241 -66.658798 -100.937, + 106.537 -67.492798 -100.486, + 101.761 -68.5634 -100.746, + -42.609501 -27.659901 103.326, + -42.0466 -28.508301 98.753799, + -42.609501 -27.659901 -106.974, + -42.609501 -27.659901 106.974, + -43.048401 -26.971701 -98.753799, + 92.182899 70.084602 -100.937, + 96.943199 69.263802 -100.937, + 10.3044 49.7439 -109.214, + 5.21451 50.5317 -109.214, + 87.503799 72.422096 -99.358398, + 82.550003 71.203796 -100.746, + 45.503502 71.329002 -100.679, + 45.147701 71.079002 -100.806, + 87.409103 71.037804 -100.746, + 45.070599 71.0215 -100.832, + 82.550003 70.7435 -100.937, + 87.377701 70.578598 -100.937, + 115.584 63.752998 100.349, + 119.858 61.350101 100.349, + 115.376 63.350498 100.667, + 110.976 65.442902 100.667, + 111.156 65.858704 100.349, + 111.312 66.217697 99.957901, + 115.91 64.382301 99.504501, + 111.439 66.508797 99.504501, + 116.018 64.589996 99.002899, + 115.764 64.100502 99.957901, + 120.226 61.9557 99.504501, + 114.899 62.4305 101.044, + 119.084 60.0774 101.044, + 24.735399 44.371201 109.214, + 20.115299 46.6478 109.214, + 110.563 64.4925 101.044, + 110.776 64.982803 100.901, + 115.145 62.905102 100.901, + 119.362 60.5341 100.901, + 127.195 54.876499 -100.937, + 123.346 57.7953 -100.937, + 126.89 54.500702 -101.053, + 123.857 58.518398 -100.486, + 123.612 58.171398 -100.746, + 127.754 55.563099 -100.486, + 119.767 61.200901 -100.486, + 127.993 55.856998 -100.162, + 124.075 58.8279 -100.162, + 119.964 61.524502 -100.162, + 153.511 -9.7534199 -100.486, + 154.39 -4.91396 -100.162, + 153.88699 -9.8050098 -100.162, + 145.771 -32.7584 -100.746, + 145.362 -32.5466 -100.937, + 146.14799 -32.9538 -100.486, + 142.995 -36.757198 -100.937, + 143.388 -36.9963 -100.746, + 143.75101 -37.217098 -100.486, + 149.64301 -23.8447 -100.746, + 147.85899 -28.367701 -100.746, + 147.437 -28.184299 -100.937, + 149.209 -23.690599 -100.937, + 150.043 -23.987 -100.486, + 148.24899 -28.5369 -100.486, + 151.522 -19.325199 -100.486, + 151.11301 -19.2106 -100.746, + 150.67 -19.086399 -100.937, + 50.748001 2.29896 -109.214, + 49.5042 -11.4008 -109.214, + 49.064899 -11.6775 -109.214, + 152.645 4.7946501 -101.053, + 50.332199 6.8780499 -109.214, + 46.870098 -14.4482 -109.214, + 152.645 -4.7946501 -101.053, + 152.155 -9.5669403 -101.053, + 50.332199 -6.8780499 -109.214, + 50.748001 -2.29896 -109.214, + 152.851 14.6088 100.349, + 153.235 9.7154703 100.667, + 153.68401 9.7771997 100.349, + 152.73801 9.6471701 100.901, + 153.89999 7.9430362e-010 100.667, + 153.39799 6.003845e-009 100.901, + 153.73399 -4.8690901 100.667, + 154.186 -4.9000301 100.349, + 154.353 5.7663208e-009 100.349, + 153.73399 4.8690901 100.667, + 154.186 4.9000301 100.349, + 143.89999 37.3078 100.349, + 144.23399 37.511101 99.957901, + 146.64999 33.214199 99.957901, + 148.76801 28.7624 99.957901, + 146.30299 33.034199 100.349, + 149.78 23.8936 100.667, + 148.409 28.606501 100.349, + 150.207 24.045401 100.349, + 151.69099 19.372299 100.349, + 141.642 41.711899 -99.783203, + 141.855 41.862 -99.358398, + 138.658 45.647202 -99.783203, + 144.351 37.582001 -99.783203, + 144.075 37.413898 -100.162, + 140.345 40.796398 -100.937, + 137.427 44.645401 -100.937, + 141.06799 41.306801 -100.486, + 138.11301 45.203899 -100.486, + 141.37801 41.525299 -100.162, + 137.784 44.935902 -100.746, + 131.14999 52.0383 -100.746, + 134.588 48.600399 -100.746, + 134.252 48.286201 -100.937, + 130.836 51.7019 -100.937, + 131.44 52.348701 -100.486, + 134.899 48.890301 -100.486, + 127.486 55.233601 -100.746, + 140.72099 41.061798 -100.746, + 144.93201 32.3237 -101.053, + 152.26401 14.4868 -100.746, + 150.67 19.086399 -100.937, + 149.209 23.690599 -100.937, + 150.20399 18.9557 -101.053, + 151.11301 19.2106 -100.746, + 153.511 9.7534199 -100.486, + 154.39 4.91396 -100.162, + 154.01199 4.8881102 -100.486, + 146.48399 33.128101 -100.162, + 146.772 33.277 -99.783203, + 147.267 -33.533699 98.4683, + 149.405 -29.039101 98.4683, + 147.31 -33.555901 97.917, + 147.14 -33.4678 99.002899, + 145.683 -36.450199 97.917, + 144.828 -37.872002 98.4683, + 144.70599 -37.7976 99.002899, + 106.276 -66.757599 100.901, + 97.123299 70.130402 -100.486, + 101.761 68.5634 -100.746, + 97.036797 69.7145 -100.746, + 92.245598 70.540604 -100.746, + 92.303398 70.961403 -100.486, + 87.438103 -71.461601 -100.486, + 92.303398 -70.961403 -100.486, + 97.266197 -70.8181 -99.783203, + 97.200302 -70.501297 -100.162, + 97.123299 -70.130402 -100.486, + 106.595 -67.657402 100.349, + 106.444 -67.230202 100.667, + 127.262 -54.957802 100.901, + 126.924 -54.543098 101.044, + 115.145 -62.905102 100.901, + 119.622 -60.9627 100.667, + 123.407 -57.880901 100.901, + 123.696 -58.290699 100.667, + 97.158798 -70.301399 100.349, + 101.8 -68.704002 100.667, + 101.922 -69.140602 100.349, + 97.066597 -69.857498 100.667, + 102.028 -69.517403 99.957901, + 97.238403 -70.684502 99.957901, + 92.380501 -71.522102 99.957901, + 92.327202 -71.134399 100.349, + 92.265503 -70.685303 100.667, + 82.550003 -72.331001 -99.783203, + 82.550003 -72.187202 -99.951599, + 87.463997 -71.8396 -100.162, + 82.550003 -72.504601 -99.5, + 92.355003 -71.3368 -100.162, + 87.5168 -72.612297 -98.898102, + 82.550003 -72.781998 -98.898102, + 82.550003 -72.8983 -98.413696, + 87.524803 -72.728302 -98.413696, + 92.434502 -71.915199 -99.358398, + 97.319099 -71.072998 -99.358398, + 97.357903 -71.259697 -98.898102, + 92.460503 -72.104103 -98.898102, + 92.399101 -71.657303 -99.783203, + 87.503799 -72.422096 -99.358398, + 87.486 -72.162399 -99.783203, + 152.63499 9.6329098 -100.937, + 153.091 9.6955795 -100.746, + 152.155 9.5669403 -101.053, + 151.814 14.3932 -100.937, + 151.34 14.2946 -101.053, + 153.129 4.8277102 -100.937, + 153.588 4.8591199 -100.746, + 152.80901 -1.5860211e-009 -101.053, + 87.463997 71.8396 -100.162, + 82.550003 71.628601 -100.486, + 82.550003 72.007401 -100.162, + 87.438103 71.461601 -100.486, + 82.550003 72.331001 -99.783203, + 87.486 72.162399 -99.783203, + 153.588 -4.8591199 -100.746, + 153.29401 5.9746585e-010 -100.937, + 153.129 -4.8277102 -100.937, + 153.754 1.4435084e-009 -100.746, + 153.091 -9.6955795 -100.746, + 154.01199 -4.8881102 -100.486, + 154.179 4.7407873e-009 -100.486, + 148.804 23.5466 101.044, + 148.284 23.362 101.092, + 146.537 27.7934 101.092, + 144.491 32.0952 101.092, + 40.240002 31.006201 109.214, + 150.771 19.114599 100.901, + 149.308 23.725599 100.901, + 151.254 19.25 100.667, + 150.256 18.9704 101.044, + 152.408 14.5166 100.667, + 151.916 14.4145 100.901, + 149.72501 18.821699 101.092, + 49.5042 11.4008 109.214, + 145.771 32.7584 -100.746, + 143.75101 37.217098 -100.486, + 146.14799 32.9538 -100.486, + 143.388 36.9963 -100.746, + 142.995 36.757198 -100.937, + 145.362 32.5466 -100.937, + 147.85899 28.367701 -100.746, + 147.437 28.184299 -100.937, + 153.924 14.8316 -98.413696, + 152.745 19.6677 -98.413696, + 152.783 19.678301 -97.917, + 153.96201 14.8395 -97.917, + 154.808 9.9316397 -97.917, + 154.769 9.9263096 -98.413696, + 152.633 19.636299 -98.898102, + 152.44901 19.5849 -99.358398, + 148.59599 28.687799 -100.162, + 110.563 -64.4925 101.044, + 110.776 -64.982803 100.901, + 20.115299 -46.6478 109.214, + 101.52 -67.706299 101.044, + 106.097 -66.253899 101.044, + 15.2884 -48.444801 109.214, + 10.3044 -49.7439 109.214, + 96.855698 -68.843002 101.044, + 101.665 -68.221001 100.901, + 92.355003 71.3368 -100.162, + 102.186 70.083 -98.898102, + 102.218 70.195 -98.413696, + 106.923 68.579597 -98.898102, + 101.875 68.972397 -100.486, + 111.367 66.342796 -99.783203, + 110.976 -65.442902 100.667, + 115.376 -63.350498 100.667, + 111.156 -65.858704 100.349, + 119.084 -60.0774 101.044, + 29.1012 -41.6385 109.214, + 24.735399 -44.371201 109.214, + 123.099 -57.444199 101.044, + 114.899 -62.4305 101.044, + 119.362 -60.5341 100.901, + 145.455 32.594799 100.901, + 143.084 36.8116 100.901, + 142.627 36.533901 101.044, + 144.98 32.3489 101.044, + 143.513 37.0723 100.667, + 145.89999 32.8256 100.667, + 147.993 28.4259 100.667, + 147.533 28.226 100.901, + 147.043 28.0131 101.044, + 151.66299 9.4993095 101.092, + 151.39301 14.3057 101.044, + 152.209 9.5743799 101.044, + 150.853 14.1936 101.092, + 50.332199 6.8780499 109.214, + 152.14999 4.7607498 101.092, + 152.7 4.7983799 101.044, + 153.368 14.7162 -99.783203, + 153.88699 9.8050098 -100.162, + 154.465 9.8845196 -99.358398, + 153.81 14.8079 -98.898102, + 154.65401 9.9104795 -98.898102, + 153.623 14.7691 -99.358398, + 154.207 9.8490696 -99.783203, + 154.972 4.9538102 -99.358398, + 149.64301 23.8447 -100.746, + 148.24899 28.5369 -100.486, + 151.88699 19.427401 -100.162, + 153.05099 14.6503 -100.162, + 150.043 23.987 -100.486, + 151.522 19.325199 -100.486, + 152.67999 14.5733 -100.486, + 150.705 24.2222 -99.783203, + 152.19901 19.5147 -99.783203, + 150.95 24.309401 -99.358398, + 150.39999 24.1138 -100.162, + 148.89301 28.8167 -99.783203, + 149.132 28.9205 -99.358398, + 97.357903 71.259697 -98.898102, + 92.434502 71.915199 -99.358398, + 92.399101 71.657303 -99.783203, + 102.065 69.648804 -99.783203, + 97.319099 71.072998 -99.358398, + 102.135 69.899399 -99.358398, + 97.266197 70.8181 -99.783203, + 97.200302 70.501297 -100.162, + 101.977 69.337196 -100.162, + 106.859 68.400002 -99.358398, + 106.772 68.154701 -99.783203, + 106.664 67.8498 -100.162, + 115.764 -64.100502 99.957901, + 115.584 -63.752998 100.349, + 111.312 -66.217697 99.957901, + 111.439 -66.508797 99.504501, + 115.91 -64.382301 99.504501, + 120.226 -61.9557 99.504501, + 120.061 -61.684399 99.957901, + 119.858 -61.350101 100.349 ] + + } + coordIndex [ 118, 63, 6, -1, 33, 6, 63, -1, + 328, 58, 57, -1, 59, 58, 47, -1, + 12, 47, 164, -1, 12, 59, 47, -1, + 310, 69, 164, -1, 310, 164, 567, -1, + 1, 164, 69, -1, 1, 17, 18, -1, + 1, 18, 164, -1, 70, 1, 69, -1, + 20, 198, 196, -1, 1354, 31, 25, -1, + 1354, 25, 26, -1, 179, 58, 328, -1, + 912, 914, 36, -1, 401, 949, 61, -1, + 0, 101, 273, -1, 0, 273, 274, -1, + 0, 567, 101, -1, 0, 274, 567, -1, + 60, 401, 61, -1, 60, 567, 401, -1, + 740, 13, 308, -1, 740, 308, 307, -1, + 67, 310, 14, -1, 16, 17, 1, -1, + 16, 1, 70, -1, 309, 308, 310, -1, + 2, 308, 13, -1, 2, 13, 14, -1, + 2, 310, 308, -1, 2, 14, 310, -1, + 71, 458, 204, -1, 19, 198, 20, -1, + 19, 204, 198, -1, 73, 752, 750, -1, + 73, 477, 752, -1, 21, 86, 216, -1, + 81, 22, 89, -1, 3, 220, 89, -1, + 3, 89, 22, -1, 3, 22, 220, -1, + 23, 86, 21, -1, 24, 88, 220, -1, + 24, 21, 88, -1, 24, 23, 21, -1, + 4, 25, 227, -1, 4, 26, 25, -1, + 4, 227, 26, -1, 29, 216, 86, -1, + 28, 87, 498, -1, 28, 227, 90, -1, + 28, 90, 29, -1, 5, 25, 31, -1, + 234, 233, 242, -1, 817, 242, 233, -1, + 818, 798, 819, -1, 818, 817, 233, -1, + 30, 248, 550, -1, 251, 248, 30, -1, + 1260, 248, 251, -1, 514, 25, 5, -1, + 514, 5, 31, -1, 32, 269, 101, -1, + 32, 275, 98, -1, 32, 101, 567, -1, + 261, 32, 98, -1, 119, 6, 33, -1, + 119, 118, 6, -1, 306, 740, 307, -1, + 9, 166, 328, -1, 626, 863, 96, -1, + 899, 123, 657, -1, 368, 657, 123, -1, + 35, 334, 625, -1, 35, 123, 334, -1, + 346, 352, 635, -1, 132, 356, 349, -1, + 647, 132, 131, -1, 678, 386, 880, -1, + 678, 131, 132, -1, 678, 132, 349, -1, + 678, 1009, 44, -1, 660, 153, 361, -1, + 660, 361, 133, -1, 141, 40, 146, -1, + 649, 356, 650, -1, 649, 912, 356, -1, + 375, 673, 138, -1, 41, 146, 40, -1, + 41, 381, 146, -1, 149, 146, 381, -1, + 1294, 912, 649, -1, 677, 193, 525, -1, + 677, 678, 193, -1, 599, 598, 322, -1, + 599, 322, 949, -1, 948, 692, 949, -1, + 948, 715, 324, -1, 639, 156, 949, -1, + 639, 949, 692, -1, 702, 401, 947, -1, + 702, 949, 401, -1, 702, 409, 949, -1, + 419, 175, 420, -1, 427, 176, 428, -1, + 427, 51, 947, -1, 427, 947, 176, -1, + 8, 58, 186, -1, 53, 58, 179, -1, + 53, 186, 58, -1, 7, 183, 47, -1, + 7, 186, 183, -1, 7, 8, 186, -1, + 7, 47, 58, -1, 7, 58, 8, -1, + 120, 167, 168, -1, 436, 9, 328, -1, + 436, 166, 9, -1, 436, 437, 165, -1, + 436, 165, 166, -1, 11, 57, 56, -1, + 11, 18, 57, -1, 10, 12, 164, -1, + 10, 56, 12, -1, 10, 11, 56, -1, + 10, 164, 18, -1, 10, 18, 11, -1, + 55, 12, 56, -1, 55, 59, 12, -1, + 483, 60, 1334, -1, 483, 997, 1164, -1, + 483, 1164, 275, -1, 483, 275, 32, -1, + 483, 567, 60, -1, 483, 32, 567, -1, + 1342, 1334, 60, -1, 741, 57, 14, -1, + 741, 328, 57, -1, 739, 14, 13, -1, + 739, 13, 740, -1, 739, 741, 14, -1, + 68, 69, 310, -1, 68, 310, 67, -1, + 66, 16, 70, -1, 66, 67, 14, -1, + 66, 14, 57, -1, 15, 17, 16, -1, + 15, 18, 17, -1, 15, 57, 18, -1, + 15, 66, 57, -1, 15, 16, 66, -1, + 468, 206, 20, -1, 468, 20, 196, -1, + 1020, 452, 1019, -1, 74, 75, 71, -1, + 74, 71, 204, -1, 205, 19, 20, -1, + 205, 204, 19, -1, 205, 20, 206, -1, + 480, 489, 762, -1, 215, 21, 216, -1, + 215, 88, 21, -1, 80, 81, 89, -1, + 80, 242, 81, -1, 82, 220, 22, -1, + 82, 24, 220, -1, 82, 22, 81, -1, + 85, 86, 23, -1, 85, 23, 24, -1, + 501, 82, 83, -1, 501, 24, 82, -1, + 501, 85, 24, -1, 223, 214, 505, -1, + 1386, 77, 1334, -1, 217, 216, 29, -1, + 217, 29, 90, -1, 513, 25, 514, -1, + 513, 227, 25, -1, 1355, 1354, 26, -1, + 1355, 26, 227, -1, 1355, 227, 28, -1, + 1355, 28, 498, -1, 27, 87, 28, -1, + 27, 28, 29, -1, 27, 86, 87, -1, + 27, 29, 86, -1, 527, 528, 93, -1, + 255, 957, 257, -1, 255, 236, 93, -1, + 241, 857, 858, -1, 541, 96, 857, -1, + 856, 96, 863, -1, 243, 30, 550, -1, + 243, 251, 30, -1, 539, 1264, 1030, -1, + 544, 550, 248, -1, 97, 1260, 251, -1, + 97, 819, 798, -1, 959, 257, 957, -1, + 276, 98, 275, -1, 1165, 275, 1164, -1, + 1353, 264, 514, -1, 1353, 514, 31, -1, + 1353, 31, 1354, -1, 515, 267, 75, -1, + 260, 269, 32, -1, 260, 32, 261, -1, + 105, 119, 33, -1, 280, 296, 573, -1, + 297, 574, 573, -1, 110, 834, 282, -1, + 289, 580, 290, -1, 293, 761, 583, -1, + 303, 296, 312, -1, 303, 312, 448, -1, + 62, 33, 63, -1, 62, 113, 33, -1, + 114, 33, 113, -1, 114, 105, 33, -1, + 114, 312, 105, -1, 733, 312, 114, -1, + 829, 592, 319, -1, 829, 319, 108, -1, + 829, 285, 830, -1, 829, 108, 285, -1, + 321, 604, 715, -1, 321, 596, 604, -1, + 321, 715, 1136, -1, 607, 159, 325, -1, + 121, 167, 120, -1, 845, 325, 159, -1, + 845, 159, 851, -1, 49, 329, 122, -1, + 49, 179, 329, -1, 49, 122, 48, -1, + 327, 179, 328, -1, 327, 329, 179, -1, + 337, 96, 541, -1, 337, 626, 96, -1, + 335, 626, 625, -1, 34, 368, 123, -1, + 34, 123, 35, -1, 34, 625, 368, -1, + 34, 35, 625, -1, 345, 1365, 156, -1, + 345, 631, 1092, -1, 127, 36, 914, -1, + 127, 349, 356, -1, 127, 347, 637, -1, + 127, 356, 912, -1, 127, 912, 36, -1, + 37, 346, 156, -1, 37, 352, 346, -1, + 37, 156, 350, -1, 37, 38, 352, -1, + 37, 350, 38, -1, 128, 346, 347, -1, + 128, 347, 127, -1, 128, 129, 125, -1, + 128, 125, 629, -1, 128, 629, 156, -1, + 128, 156, 346, -1, 351, 352, 38, -1, + 351, 38, 350, -1, 155, 350, 156, -1, + 644, 604, 349, -1, 644, 690, 692, -1, + 653, 356, 132, -1, 654, 934, 678, -1, + 654, 931, 934, -1, 654, 44, 891, -1, + 654, 678, 44, -1, 382, 361, 153, -1, + 39, 133, 135, -1, 39, 660, 133, -1, + 662, 153, 660, -1, 659, 39, 135, -1, + 659, 660, 39, -1, 913, 665, 125, -1, + 913, 125, 129, -1, 913, 129, 914, -1, + 145, 147, 673, -1, 145, 141, 146, -1, + 145, 673, 141, -1, 671, 673, 375, -1, + 140, 40, 141, -1, 140, 41, 40, -1, + 140, 381, 41, -1, 144, 146, 149, -1, + 144, 149, 42, -1, 144, 42, 143, -1, + 148, 358, 42, -1, 148, 42, 149, -1, + 1301, 149, 381, -1, 154, 143, 42, -1, + 154, 378, 143, -1, 154, 42, 358, -1, + 43, 44, 1009, -1, 43, 1009, 1055, -1, + 43, 891, 44, -1, 43, 1055, 891, -1, + 384, 677, 525, -1, 384, 525, 790, -1, + 384, 790, 526, -1, 933, 386, 678, -1, + 933, 678, 934, -1, 937, 880, 386, -1, + 393, 639, 692, -1, 397, 156, 639, -1, + 160, 947, 401, -1, 160, 158, 947, -1, + 160, 159, 607, -1, 423, 947, 158, -1, + 423, 158, 420, -1, 423, 176, 947, -1, + 423, 420, 175, -1, 162, 417, 420, -1, + 162, 420, 158, -1, 162, 158, 846, -1, + 163, 46, 158, -1, 163, 847, 46, -1, + 45, 846, 158, -1, 45, 158, 46, -1, + 45, 847, 846, -1, 45, 46, 847, -1, + 181, 47, 183, -1, 181, 164, 47, -1, + 181, 184, 52, -1, 181, 183, 184, -1, + 181, 48, 122, -1, 181, 52, 180, -1, + 181, 179, 49, -1, 181, 49, 48, -1, + 402, 189, 404, -1, 170, 434, 192, -1, + 170, 171, 402, -1, 170, 402, 434, -1, + 439, 165, 437, -1, 439, 434, 165, -1, + 174, 160, 401, -1, 50, 51, 427, -1, + 50, 427, 945, -1, 50, 947, 51, -1, + 50, 945, 947, -1, 707, 945, 700, -1, + 425, 846, 845, -1, 425, 596, 700, -1, + 425, 700, 945, -1, 425, 604, 596, -1, + 425, 423, 175, -1, 425, 349, 604, -1, + 425, 678, 349, -1, 425, 193, 678, -1, + 425, 845, 328, -1, 711, 596, 682, -1, + 711, 682, 713, -1, 711, 700, 596, -1, + 178, 184, 53, -1, 178, 53, 179, -1, + 178, 52, 184, -1, 178, 180, 52, -1, + 185, 53, 184, -1, 185, 186, 53, -1, + 188, 171, 191, -1, 188, 402, 171, -1, + 188, 189, 402, -1, 433, 328, 845, -1, + 433, 192, 434, -1, 54, 55, 56, -1, + 54, 56, 57, -1, 54, 57, 58, -1, + 54, 58, 59, -1, 54, 59, 55, -1, + 484, 483, 1334, -1, 441, 1342, 60, -1, + 441, 60, 61, -1, 441, 61, 949, -1, + 441, 949, 442, -1, 443, 1149, 1150, -1, + 443, 1150, 1142, -1, 727, 962, 194, -1, + 64, 446, 113, -1, 64, 113, 62, -1, + 64, 62, 63, -1, 64, 118, 117, -1, + 64, 63, 118, -1, 115, 969, 446, -1, + 115, 117, 313, -1, 115, 64, 117, -1, + 115, 446, 64, -1, 65, 67, 66, -1, + 65, 69, 68, -1, 65, 68, 67, -1, + 65, 70, 69, -1, 65, 66, 70, -1, + 451, 1019, 452, -1, 454, 266, 455, -1, + 454, 75, 267, -1, 454, 267, 266, -1, + 454, 458, 71, -1, 454, 71, 75, -1, + 72, 477, 73, -1, 200, 758, 201, -1, + 199, 206, 468, -1, 199, 468, 748, -1, + 467, 748, 468, -1, 467, 758, 200, -1, + 759, 468, 196, -1, 759, 196, 452, -1, + 473, 477, 72, -1, 473, 750, 200, -1, + 473, 200, 201, -1, 473, 73, 750, -1, + 473, 72, 73, -1, 203, 74, 204, -1, + 203, 210, 76, -1, 203, 75, 74, -1, + 203, 515, 75, -1, 203, 76, 523, -1, + 203, 523, 515, -1, 209, 1221, 1222, -1, + 225, 523, 76, -1, 225, 209, 1222, -1, + 225, 76, 210, -1, 225, 210, 209, -1, + 208, 77, 744, -1, 208, 1334, 77, -1, + 208, 484, 1334, -1, 462, 206, 199, -1, + 462, 199, 460, -1, 743, 744, 77, -1, + 743, 77, 1386, -1, 78, 583, 761, -1, + 78, 491, 583, -1, 78, 761, 762, -1, + 78, 762, 491, -1, 998, 194, 962, -1, + 998, 999, 194, -1, 585, 490, 471, -1, + 79, 234, 242, -1, 79, 242, 80, -1, + 79, 89, 234, -1, 79, 80, 89, -1, + 813, 81, 242, -1, 813, 82, 81, -1, + 813, 83, 82, -1, 1182, 1061, 1062, -1, + 1182, 1062, 922, -1, 1182, 922, 1180, -1, + 500, 501, 83, -1, 500, 814, 211, -1, + 500, 83, 813, -1, 500, 813, 814, -1, + 503, 497, 498, -1, 84, 86, 85, -1, + 84, 85, 501, -1, 84, 501, 503, -1, + 84, 503, 498, -1, 84, 87, 86, -1, + 84, 498, 87, -1, 219, 220, 88, -1, + 219, 88, 215, -1, 219, 214, 223, -1, + 224, 717, 254, -1, 1014, 1399, 1398, -1, + 235, 89, 220, -1, 235, 234, 89, -1, + 782, 504, 224, -1, 91, 505, 214, -1, + 91, 779, 505, -1, 226, 90, 227, -1, + 226, 217, 90, -1, 226, 509, 214, -1, + 229, 509, 510, -1, 229, 779, 91, -1, + 229, 214, 509, -1, 229, 91, 214, -1, + 230, 1210, 1218, -1, 517, 518, 510, -1, + 1356, 1355, 498, -1, 1243, 1000, 1244, -1, + 793, 526, 790, -1, 92, 93, 528, -1, + 92, 528, 224, -1, 92, 224, 254, -1, + 92, 255, 93, -1, 92, 254, 255, -1, + 797, 798, 818, -1, 562, 533, 236, -1, + 796, 527, 93, -1, 796, 93, 236, -1, + 94, 255, 257, -1, 94, 236, 255, -1, + 94, 257, 562, -1, 94, 562, 236, -1, + 664, 343, 905, -1, 244, 554, 245, -1, + 244, 556, 554, -1, 237, 905, 343, -1, + 237, 343, 554, -1, 342, 239, 343, -1, + 342, 340, 239, -1, 542, 241, 547, -1, + 542, 857, 241, -1, 542, 541, 857, -1, + 95, 857, 96, -1, 95, 96, 856, -1, + 95, 856, 857, -1, 1068, 813, 242, -1, + 1070, 808, 1044, -1, 247, 245, 239, -1, + 247, 239, 340, -1, 540, 339, 541, -1, + 540, 340, 339, -1, 250, 819, 97, -1, + 250, 97, 251, -1, 799, 97, 798, -1, + 799, 1260, 97, -1, 716, 254, 717, -1, + 561, 562, 257, -1, 901, 156, 1365, -1, + 901, 949, 156, -1, 901, 442, 949, -1, + 258, 720, 901, -1, 767, 997, 483, -1, + 767, 996, 997, -1, 262, 261, 98, -1, + 262, 98, 276, -1, 262, 276, 568, -1, + 265, 1353, 1352, -1, 99, 515, 514, -1, + 99, 267, 515, -1, 99, 514, 264, -1, + 99, 264, 267, -1, 100, 273, 101, -1, + 100, 272, 273, -1, 100, 101, 269, -1, + 100, 269, 272, -1, 270, 269, 260, -1, + 270, 260, 277, -1, 295, 565, 272, -1, + 295, 270, 298, -1, 564, 272, 565, -1, + 564, 567, 274, -1, 278, 574, 297, -1, + 278, 297, 298, -1, 278, 298, 270, -1, + 278, 270, 277, -1, 102, 108, 319, -1, + 102, 319, 318, -1, 107, 318, 106, -1, + 107, 108, 102, -1, 107, 102, 318, -1, + 103, 119, 105, -1, 103, 317, 119, -1, + 103, 318, 317, -1, 103, 106, 318, -1, + 103, 105, 106, -1, 279, 282, 834, -1, + 104, 106, 105, -1, 104, 280, 106, -1, + 104, 296, 280, -1, 104, 312, 296, -1, + 104, 105, 312, -1, 281, 106, 280, -1, + 281, 107, 106, -1, 281, 108, 107, -1, + 281, 284, 285, -1, 281, 285, 108, -1, + 579, 580, 110, -1, 579, 110, 282, -1, + 111, 832, 834, -1, 109, 110, 580, -1, + 109, 580, 289, -1, 109, 289, 111, -1, + 109, 834, 110, -1, 109, 111, 834, -1, + 823, 1372, 832, -1, 823, 111, 289, -1, + 823, 832, 111, -1, 582, 293, 583, -1, + 292, 290, 580, -1, 292, 582, 290, -1, + 292, 293, 582, -1, 768, 761, 293, -1, + 302, 300, 565, -1, 302, 296, 303, -1, + 447, 312, 733, -1, 112, 113, 446, -1, + 112, 446, 733, -1, 112, 114, 113, -1, + 112, 733, 114, -1, 589, 1374, 825, -1, + 968, 969, 115, -1, 968, 115, 313, -1, + 315, 828, 313, -1, 116, 313, 117, -1, + 116, 117, 118, -1, 116, 118, 119, -1, + 116, 317, 316, -1, 116, 119, 317, -1, + 116, 316, 315, -1, 116, 315, 313, -1, + 1373, 1432, 836, -1, 595, 321, 322, -1, + 595, 596, 321, -1, 323, 949, 322, -1, + 323, 321, 949, -1, 1138, 949, 321, -1, + 1138, 321, 1136, -1, 838, 948, 324, -1, + 602, 354, 692, -1, 841, 325, 845, -1, + 406, 121, 120, -1, 406, 120, 168, -1, + 406, 408, 405, -1, 406, 405, 121, -1, + 406, 407, 408, -1, 326, 612, 173, -1, + 326, 121, 405, -1, 326, 167, 121, -1, + 326, 405, 433, -1, 326, 433, 845, -1, + 326, 401, 167, -1, 615, 329, 327, -1, + 330, 181, 122, -1, 330, 122, 329, -1, + 333, 863, 626, -1, 1106, 899, 1105, -1, + 1106, 123, 899, -1, 1106, 334, 123, -1, + 331, 868, 865, -1, 331, 334, 1106, -1, + 331, 1106, 868, -1, 930, 931, 654, -1, + 627, 337, 628, -1, 627, 626, 337, -1, + 338, 340, 342, -1, 338, 342, 341, -1, + 338, 341, 628, -1, 908, 628, 341, -1, + 908, 623, 628, -1, 908, 1438, 622, -1, + 908, 622, 623, -1, 366, 656, 657, -1, + 366, 363, 656, -1, 136, 135, 134, -1, + 136, 134, 363, -1, 136, 659, 135, -1, + 124, 125, 665, -1, 124, 665, 879, -1, + 124, 629, 125, -1, 124, 879, 629, -1, + 878, 879, 665, -1, 344, 156, 629, -1, + 344, 345, 156, -1, 344, 629, 1090, -1, + 1093, 345, 1092, -1, 632, 345, 1093, -1, + 634, 127, 637, -1, 634, 349, 127, -1, + 126, 127, 914, -1, 126, 128, 127, -1, + 126, 914, 129, -1, 126, 129, 128, -1, + 157, 349, 350, -1, 157, 350, 155, -1, + 157, 396, 349, -1, 641, 695, 644, -1, + 641, 644, 349, -1, 641, 349, 396, -1, + 641, 640, 695, -1, 355, 604, 644, -1, + 355, 603, 604, -1, 643, 692, 354, -1, + 643, 644, 692, -1, 651, 650, 356, -1, + 884, 678, 880, -1, 130, 131, 678, -1, + 130, 647, 131, -1, 130, 646, 647, -1, + 130, 678, 884, -1, 130, 884, 646, -1, + 648, 132, 647, -1, 648, 653, 132, -1, + 890, 654, 891, -1, 357, 153, 152, -1, + 357, 382, 153, -1, 357, 154, 358, -1, + 357, 152, 154, -1, 360, 133, 361, -1, + 360, 135, 133, -1, 360, 894, 135, -1, + 362, 134, 135, -1, 362, 135, 894, -1, + 362, 363, 134, -1, 364, 903, 1108, -1, + 364, 659, 903, -1, 367, 903, 659, -1, + 367, 363, 366, -1, 367, 136, 363, -1, + 367, 659, 136, -1, 373, 665, 913, -1, + 373, 372, 139, -1, 373, 139, 147, -1, + 666, 373, 147, -1, 666, 665, 373, -1, + 369, 1289, 909, -1, 369, 370, 1289, -1, + 667, 139, 372, -1, 137, 138, 673, -1, + 137, 139, 138, -1, 137, 673, 147, -1, + 137, 147, 139, -1, 918, 139, 667, -1, + 380, 375, 138, -1, 380, 138, 139, -1, + 380, 139, 918, -1, 672, 381, 140, -1, + 672, 141, 673, -1, 672, 140, 141, -1, + 377, 666, 147, -1, 142, 143, 378, -1, + 142, 144, 143, -1, 142, 378, 377, -1, + 142, 145, 146, -1, 142, 146, 144, -1, + 142, 147, 145, -1, 142, 377, 147, -1, + 150, 358, 148, -1, 150, 148, 149, -1, + 150, 149, 1301, -1, 1113, 358, 150, -1, + 1113, 150, 1301, -1, 151, 152, 153, -1, + 151, 154, 152, -1, 151, 153, 662, -1, + 151, 662, 378, -1, 151, 378, 154, -1, + 1202, 384, 526, -1, 1202, 526, 1313, -1, + 385, 937, 386, -1, 686, 429, 683, -1, + 686, 949, 409, -1, 686, 409, 429, -1, + 686, 599, 949, -1, 685, 686, 683, -1, + 389, 700, 711, -1, 391, 429, 409, -1, + 391, 390, 429, -1, 689, 393, 692, -1, + 395, 155, 156, -1, 395, 156, 397, -1, + 395, 396, 157, -1, 395, 157, 155, -1, + 398, 397, 639, -1, 398, 639, 641, -1, + 398, 641, 396, -1, 842, 158, 160, -1, + 842, 160, 607, -1, 842, 163, 158, -1, + 854, 610, 853, -1, 854, 174, 610, -1, + 854, 160, 174, -1, 852, 851, 159, -1, + 852, 159, 160, -1, 852, 160, 854, -1, + 161, 416, 417, -1, 161, 417, 162, -1, + 161, 846, 416, -1, 161, 162, 846, -1, + 848, 847, 163, -1, 848, 842, 843, -1, + 848, 163, 842, -1, 400, 164, 181, -1, + 400, 567, 164, -1, 400, 401, 567, -1, + 400, 181, 330, -1, 400, 165, 434, -1, + 400, 166, 165, -1, 400, 328, 166, -1, + 403, 167, 401, -1, 403, 168, 167, -1, + 403, 406, 168, -1, 169, 192, 191, -1, + 169, 170, 192, -1, 169, 191, 171, -1, + 169, 171, 170, -1, 414, 409, 702, -1, + 414, 699, 409, -1, 414, 411, 699, -1, + 172, 612, 174, -1, 172, 174, 401, -1, + 172, 173, 612, -1, 172, 401, 326, -1, + 172, 326, 173, -1, 609, 174, 612, -1, + 609, 610, 174, -1, 413, 411, 414, -1, + 418, 416, 846, -1, 418, 846, 425, -1, + 418, 175, 419, -1, 418, 425, 175, -1, + 426, 428, 176, -1, 426, 423, 422, -1, + 426, 176, 423, -1, 710, 429, 390, -1, + 710, 390, 389, -1, 710, 389, 711, -1, + 431, 1136, 715, -1, 431, 952, 1136, -1, + 431, 951, 952, -1, 1135, 1136, 952, -1, + 177, 178, 179, -1, 177, 180, 178, -1, + 177, 179, 181, -1, 177, 181, 180, -1, + 182, 184, 183, -1, 182, 185, 184, -1, + 182, 183, 186, -1, 182, 186, 185, -1, + 187, 188, 191, -1, 187, 433, 405, -1, + 187, 191, 433, -1, 187, 405, 404, -1, + 187, 189, 188, -1, 187, 404, 189, -1, + 438, 436, 328, -1, 438, 328, 433, -1, + 190, 191, 192, -1, 190, 192, 433, -1, + 190, 433, 191, -1, 722, 1342, 441, -1, + 1148, 1149, 443, -1, 444, 1146, 1148, -1, + 444, 1148, 443, -1, 444, 328, 741, -1, + 444, 741, 195, -1, 444, 525, 193, -1, + 444, 193, 425, -1, 444, 425, 328, -1, + 726, 525, 444, -1, 726, 999, 1172, -1, + 726, 194, 999, -1, 726, 727, 194, -1, + 730, 448, 738, -1, 730, 306, 448, -1, + 730, 740, 306, -1, 449, 741, 739, -1, + 449, 972, 741, -1, 1145, 195, 741, -1, + 1145, 444, 195, -1, 1145, 1146, 444, -1, + 1420, 1026, 1417, -1, 197, 196, 198, -1, + 197, 452, 196, -1, 457, 197, 198, -1, + 457, 452, 197, -1, 457, 204, 458, -1, + 457, 198, 204, -1, 975, 460, 199, -1, + 975, 199, 748, -1, 746, 207, 486, -1, + 746, 747, 463, -1, 481, 207, 746, -1, + 749, 200, 750, -1, 749, 467, 200, -1, + 749, 748, 467, -1, 469, 759, 758, -1, + 469, 468, 759, -1, 476, 471, 490, -1, + 476, 474, 471, -1, 476, 490, 477, -1, + 757, 201, 758, -1, 757, 473, 201, -1, + 756, 1020, 755, -1, 756, 452, 1020, -1, + 756, 759, 452, -1, 202, 203, 204, -1, + 202, 210, 203, -1, 202, 205, 206, -1, + 202, 204, 205, -1, 202, 206, 462, -1, + 202, 462, 210, -1, 987, 486, 207, -1, + 987, 207, 481, -1, 487, 208, 744, -1, + 487, 484, 208, -1, 1219, 463, 747, -1, + 1219, 1220, 463, -1, 461, 1221, 209, -1, + 461, 1220, 1221, -1, 461, 209, 210, -1, + 461, 210, 462, -1, 461, 463, 1220, -1, + 1385, 1388, 743, -1, 1385, 743, 1386, -1, + 488, 752, 477, -1, 488, 477, 490, -1, + 588, 591, 837, -1, 588, 837, 836, -1, + 588, 836, 1432, -1, 965, 966, 837, -1, + 493, 837, 591, -1, 586, 585, 471, -1, + 494, 1179, 589, -1, 494, 589, 825, -1, + 1176, 591, 1179, -1, 1407, 503, 212, -1, + 1407, 497, 503, -1, 1002, 1407, 212, -1, + 1059, 922, 1062, -1, 1063, 211, 814, -1, + 1004, 1061, 1182, -1, 1004, 211, 1063, -1, + 1004, 1063, 1061, -1, 502, 500, 211, -1, + 502, 211, 1004, -1, 502, 1004, 1003, -1, + 502, 212, 503, -1, 502, 1002, 212, -1, + 502, 1003, 1002, -1, 213, 214, 219, -1, + 213, 226, 214, -1, 213, 215, 216, -1, + 213, 219, 215, -1, 213, 216, 217, -1, + 213, 217, 226, -1, 1217, 1218, 1210, -1, + 778, 717, 224, -1, 778, 224, 504, -1, + 221, 531, 235, -1, 221, 507, 532, -1, + 221, 532, 531, -1, 221, 235, 222, -1, + 218, 219, 223, -1, 218, 223, 222, -1, + 218, 220, 219, -1, 218, 235, 220, -1, + 218, 222, 235, -1, 783, 507, 221, -1, + 783, 221, 222, -1, 783, 223, 505, -1, + 783, 222, 223, -1, 506, 782, 224, -1, + 506, 224, 528, -1, 522, 523, 225, -1, + 522, 225, 1222, -1, 522, 1222, 785, -1, + 511, 509, 226, -1, 511, 226, 227, -1, + 511, 227, 513, -1, 228, 1218, 779, -1, + 228, 779, 229, -1, 228, 230, 1218, -1, + 228, 229, 510, -1, 228, 510, 230, -1, + 520, 510, 518, -1, 520, 230, 510, -1, + 520, 1210, 230, -1, 520, 1208, 1210, -1, + 519, 517, 513, -1, 1022, 1244, 1000, -1, + 1022, 1000, 773, -1, 1022, 773, 524, -1, + 786, 475, 755, -1, 786, 755, 1020, -1, + 1024, 792, 790, -1, 1024, 790, 791, -1, + 1247, 790, 792, -1, 1247, 793, 790, -1, + 1251, 1313, 526, -1, 1018, 1019, 451, -1, + 1018, 451, 1420, -1, 231, 1352, 1026, -1, + 231, 266, 265, -1, 231, 265, 1352, -1, + 231, 455, 266, -1, 231, 1026, 455, -1, + 232, 234, 797, -1, 232, 797, 818, -1, + 232, 233, 234, -1, 232, 818, 233, -1, + 530, 797, 234, -1, 530, 234, 235, -1, + 530, 235, 531, -1, 805, 236, 533, -1, + 805, 796, 236, -1, 1278, 905, 237, -1, + 1278, 902, 1279, -1, 553, 237, 554, -1, + 553, 902, 1278, -1, 553, 1278, 237, -1, + 238, 554, 343, -1, 238, 343, 239, -1, + 238, 245, 554, -1, 238, 239, 245, -1, + 240, 549, 548, -1, 240, 617, 549, -1, + 240, 546, 547, -1, 240, 548, 546, -1, + 240, 547, 241, -1, 240, 241, 858, -1, + 240, 858, 859, -1, 240, 859, 617, -1, + 888, 811, 655, -1, 1049, 1055, 776, -1, + 1049, 1054, 1055, -1, 816, 1068, 242, -1, + 816, 242, 817, -1, 807, 251, 243, -1, + 807, 243, 550, -1, 807, 550, 549, -1, + 252, 808, 1071, -1, 252, 251, 807, -1, + 252, 807, 808, -1, 1041, 1070, 1044, -1, + 537, 1194, 1060, -1, 1069, 1071, 808, -1, + 1069, 808, 1070, -1, 802, 539, 1030, -1, + 802, 245, 247, -1, 802, 535, 245, -1, + 536, 559, 556, -1, 536, 556, 244, -1, + 536, 244, 245, -1, 536, 245, 535, -1, + 246, 540, 539, -1, 246, 539, 802, -1, + 246, 802, 247, -1, 246, 247, 340, -1, + 246, 340, 540, -1, 1262, 1263, 544, -1, + 1262, 248, 1260, -1, 1262, 544, 248, -1, + 545, 1263, 1264, -1, 249, 819, 250, -1, + 249, 250, 251, -1, 249, 1071, 819, -1, + 249, 251, 252, -1, 249, 252, 1071, -1, + 253, 254, 716, -1, 253, 957, 255, -1, + 253, 255, 254, -1, 253, 956, 957, -1, + 253, 716, 956, -1, 256, 959, 720, -1, + 256, 720, 561, -1, 256, 257, 959, -1, + 256, 561, 257, -1, 555, 556, 258, -1, + 555, 902, 553, -1, 555, 901, 902, -1, + 555, 258, 901, -1, 560, 556, 559, -1, + 560, 258, 556, -1, 560, 720, 258, -1, + 259, 260, 261, -1, 259, 261, 262, -1, + 259, 277, 260, -1, 259, 568, 277, -1, + 259, 262, 568, -1, 263, 264, 1353, -1, + 263, 1353, 265, -1, 263, 265, 266, -1, + 263, 266, 267, -1, 263, 267, 264, -1, + 268, 272, 269, -1, 268, 295, 272, -1, + 268, 269, 270, -1, 268, 270, 295, -1, + 566, 565, 300, -1, 566, 300, 567, -1, + 271, 273, 272, -1, 271, 272, 564, -1, + 271, 274, 273, -1, 271, 564, 274, -1, + 771, 275, 1165, -1, 771, 1165, 1166, -1, + 771, 276, 275, -1, 771, 568, 276, -1, + 771, 820, 568, -1, 286, 576, 574, -1, + 286, 574, 278, -1, 286, 278, 570, -1, + 286, 1072, 482, -1, 286, 570, 1072, -1, + 569, 277, 568, -1, 569, 278, 277, -1, + 569, 570, 278, -1, 283, 282, 279, -1, + 283, 279, 285, -1, 571, 279, 834, -1, + 571, 830, 285, -1, 571, 285, 279, -1, + 288, 284, 281, -1, 575, 280, 573, -1, + 575, 281, 280, -1, 575, 576, 288, -1, + 575, 288, 281, -1, 578, 287, 988, -1, + 578, 579, 282, -1, 578, 282, 283, -1, + 578, 284, 288, -1, 578, 288, 287, -1, + 578, 285, 284, -1, 578, 283, 285, -1, + 989, 286, 482, -1, 989, 576, 286, -1, + 989, 988, 287, -1, 989, 288, 576, -1, + 989, 287, 288, -1, 1075, 825, 1374, -1, + 291, 289, 290, -1, 291, 290, 582, -1, + 291, 823, 289, -1, 822, 823, 291, -1, + 822, 291, 582, -1, 581, 292, 580, -1, + 581, 293, 292, -1, 581, 768, 293, -1, + 294, 565, 295, -1, 294, 302, 565, -1, + 294, 296, 302, -1, 294, 573, 296, -1, + 294, 297, 573, -1, 294, 298, 297, -1, + 294, 295, 298, -1, 299, 303, 448, -1, + 299, 304, 303, -1, 299, 448, 306, -1, + 299, 306, 304, -1, 305, 300, 302, -1, + 305, 567, 300, -1, 301, 302, 303, -1, + 301, 303, 304, -1, 301, 305, 302, -1, + 301, 304, 306, -1, 301, 306, 307, -1, + 301, 307, 308, -1, 301, 308, 309, -1, + 301, 309, 310, -1, 301, 310, 567, -1, + 301, 567, 305, -1, 311, 448, 312, -1, + 311, 447, 448, -1, 311, 312, 447, -1, + 590, 1179, 591, -1, 590, 589, 1179, -1, + 1074, 313, 828, -1, 1074, 968, 313, -1, + 314, 315, 316, -1, 314, 828, 315, -1, + 314, 316, 317, -1, 314, 317, 318, -1, + 314, 318, 319, -1, 314, 319, 592, -1, + 314, 592, 828, -1, 593, 966, 729, -1, + 593, 729, 1140, -1, 597, 322, 598, -1, + 597, 595, 322, -1, 320, 322, 321, -1, + 320, 323, 322, -1, 320, 321, 323, -1, + 1080, 838, 324, -1, 1080, 324, 715, -1, + 606, 607, 325, -1, 606, 325, 841, -1, + 611, 326, 845, -1, 611, 612, 326, -1, + 611, 853, 610, -1, 614, 327, 328, -1, + 614, 615, 327, -1, 614, 328, 400, -1, + 614, 400, 330, -1, 616, 329, 615, -1, + 616, 330, 329, -1, 616, 614, 330, -1, + 864, 863, 333, -1, 864, 331, 865, -1, + 864, 333, 334, -1, 864, 334, 331, -1, + 332, 334, 333, -1, 332, 625, 334, -1, + 332, 335, 625, -1, 332, 626, 335, -1, + 332, 333, 626, -1, 860, 865, 868, -1, + 620, 860, 868, -1, 620, 870, 860, -1, + 872, 870, 620, -1, 895, 362, 894, -1, + 336, 628, 337, -1, 336, 338, 628, -1, + 336, 541, 339, -1, 336, 337, 541, -1, + 336, 339, 340, -1, 336, 340, 338, -1, + 624, 368, 625, -1, 904, 622, 1438, -1, + 907, 908, 341, -1, 907, 341, 342, -1, + 907, 343, 664, -1, 907, 342, 343, -1, + 877, 629, 879, -1, 630, 631, 345, -1, + 630, 345, 344, -1, 630, 344, 1090, -1, + 1111, 632, 1093, -1, 1366, 1365, 345, -1, + 1366, 345, 632, -1, 636, 346, 635, -1, + 636, 347, 346, -1, 636, 637, 347, -1, + 348, 349, 634, -1, 348, 350, 349, -1, + 348, 351, 350, -1, 348, 634, 635, -1, + 348, 635, 352, -1, 348, 352, 351, -1, + 697, 639, 393, -1, 697, 393, 696, -1, + 697, 695, 640, -1, 645, 354, 355, -1, + 645, 355, 644, -1, 645, 643, 354, -1, + 353, 354, 602, -1, 353, 355, 354, -1, + 353, 602, 603, -1, 353, 603, 355, -1, + 652, 356, 653, -1, 652, 651, 356, -1, + 887, 654, 890, -1, 383, 357, 358, -1, + 383, 382, 357, -1, 383, 358, 1113, -1, + 893, 361, 382, -1, 1098, 921, 1123, -1, + 359, 360, 361, -1, 359, 894, 360, -1, + 359, 361, 893, -1, 359, 893, 894, -1, + 897, 363, 362, -1, 897, 656, 363, -1, + 897, 362, 895, -1, 661, 659, 364, -1, + 661, 1108, 370, -1, 661, 364, 1108, -1, + 365, 366, 657, -1, 365, 367, 366, -1, + 365, 903, 367, -1, 365, 904, 903, -1, + 365, 657, 368, -1, 365, 368, 624, -1, + 365, 624, 622, -1, 365, 622, 904, -1, + 1288, 1289, 370, -1, 1288, 370, 1108, -1, + 1285, 1286, 1277, -1, 379, 369, 909, -1, + 379, 662, 661, -1, 379, 370, 369, -1, + 379, 661, 370, -1, 371, 667, 372, -1, + 371, 913, 667, -1, 371, 372, 373, -1, + 371, 373, 913, -1, 374, 671, 375, -1, + 374, 375, 380, -1, 374, 380, 671, -1, + 376, 909, 666, -1, 376, 666, 377, -1, + 376, 377, 378, -1, 376, 379, 909, -1, + 376, 378, 662, -1, 376, 662, 379, -1, + 1112, 1299, 918, -1, 669, 1299, 671, -1, + 669, 671, 380, -1, 669, 380, 918, -1, + 1300, 1301, 381, -1, 1300, 381, 672, -1, + 1300, 671, 1299, -1, 675, 893, 382, -1, + 675, 382, 383, -1, 675, 383, 1113, -1, + 777, 384, 1202, -1, 777, 677, 384, -1, + 881, 880, 937, -1, 936, 937, 385, -1, + 936, 386, 933, -1, 936, 385, 386, -1, + 430, 683, 429, -1, 430, 387, 683, -1, + 430, 713, 387, -1, 681, 713, 682, -1, + 681, 387, 713, -1, 681, 683, 387, -1, + 687, 682, 596, -1, 687, 685, 682, -1, + 687, 596, 686, -1, 392, 409, 700, -1, + 392, 700, 389, -1, 392, 391, 409, -1, + 388, 389, 390, -1, 388, 390, 391, -1, + 388, 392, 389, -1, 388, 391, 392, -1, + 691, 689, 692, -1, 694, 696, 393, -1, + 694, 393, 689, -1, 694, 689, 690, -1, + 694, 644, 695, -1, 694, 690, 644, -1, + 394, 396, 395, -1, 394, 395, 397, -1, + 394, 398, 396, -1, 394, 397, 398, -1, + 844, 848, 843, -1, 399, 401, 400, -1, + 399, 400, 434, -1, 399, 434, 402, -1, + 399, 403, 401, -1, 399, 402, 404, -1, + 399, 404, 405, -1, 399, 407, 406, -1, + 399, 406, 403, -1, 399, 405, 408, -1, + 399, 408, 407, -1, 701, 700, 409, -1, + 701, 409, 699, -1, 410, 707, 700, -1, + 410, 413, 707, -1, 410, 700, 699, -1, + 410, 699, 411, -1, 410, 411, 413, -1, + 412, 702, 707, -1, 412, 707, 413, -1, + 412, 414, 702, -1, 412, 413, 414, -1, + 415, 417, 416, -1, 415, 416, 418, -1, + 415, 418, 419, -1, 415, 420, 417, -1, + 415, 419, 420, -1, 421, 426, 422, -1, + 421, 425, 426, -1, 421, 422, 423, -1, + 421, 423, 425, -1, 424, 425, 945, -1, + 424, 426, 425, -1, 424, 945, 427, -1, + 424, 427, 428, -1, 424, 428, 426, -1, + 712, 429, 710, -1, 712, 430, 429, -1, + 712, 713, 430, -1, 714, 431, 715, -1, + 714, 951, 431, -1, 432, 439, 438, -1, + 432, 438, 433, -1, 432, 434, 439, -1, + 432, 433, 434, -1, 435, 437, 436, -1, + 435, 436, 438, -1, 435, 439, 437, -1, + 435, 438, 439, -1, 440, 441, 442, -1, + 440, 722, 441, -1, 440, 442, 901, -1, + 440, 719, 722, -1, 440, 720, 719, -1, + 440, 901, 720, -1, 1012, 722, 1013, -1, + 718, 716, 1013, -1, 718, 1013, 722, -1, + 718, 956, 716, -1, 723, 1342, 722, -1, + 963, 729, 966, -1, 963, 725, 729, -1, + 1141, 729, 725, -1, 1141, 443, 1142, -1, + 1141, 444, 443, -1, 1141, 726, 444, -1, + 736, 740, 730, -1, 732, 733, 446, -1, + 732, 446, 735, -1, 445, 735, 446, -1, + 445, 738, 735, -1, 445, 446, 969, -1, + 445, 969, 738, -1, 734, 447, 733, -1, + 734, 448, 447, -1, 734, 738, 448, -1, + 734, 735, 738, -1, 1319, 972, 449, -1, + 1319, 449, 739, -1, 971, 741, 972, -1, + 450, 455, 1026, -1, 450, 1026, 1420, -1, + 450, 451, 455, -1, 450, 1420, 451, -1, + 456, 455, 451, -1, 456, 451, 452, -1, + 456, 452, 457, -1, 453, 454, 455, -1, + 453, 455, 456, -1, 453, 456, 457, -1, + 453, 458, 454, -1, 453, 457, 458, -1, + 459, 464, 463, -1, 459, 460, 975, -1, + 459, 975, 464, -1, 459, 463, 461, -1, + 459, 462, 460, -1, 459, 461, 462, -1, + 465, 463, 464, -1, 465, 746, 463, -1, + 465, 481, 746, -1, 745, 486, 744, -1, + 745, 746, 486, -1, 974, 464, 975, -1, + 974, 465, 464, -1, 974, 481, 465, -1, + 466, 467, 468, -1, 466, 468, 469, -1, + 466, 758, 467, -1, 466, 469, 758, -1, + 470, 475, 786, -1, 470, 786, 524, -1, + 470, 474, 475, -1, 470, 472, 474, -1, + 470, 524, 773, -1, 470, 773, 472, -1, + 496, 471, 474, -1, 496, 474, 472, -1, + 496, 773, 774, -1, 496, 472, 773, -1, + 496, 586, 471, -1, 496, 495, 586, -1, + 754, 473, 757, -1, 754, 475, 474, -1, + 754, 474, 476, -1, 754, 477, 473, -1, + 754, 476, 477, -1, 754, 755, 475, -1, + 983, 977, 751, -1, 983, 751, 479, -1, + 983, 479, 979, -1, 478, 751, 752, -1, + 478, 479, 751, -1, 478, 752, 488, -1, + 478, 480, 762, -1, 478, 489, 480, -1, + 478, 488, 489, -1, 478, 762, 979, -1, + 478, 979, 479, -1, 764, 765, 486, -1, + 764, 486, 987, -1, 985, 764, 987, -1, + 982, 987, 481, -1, 982, 481, 974, -1, + 1156, 482, 1072, -1, 1156, 989, 482, -1, + 766, 767, 483, -1, 766, 484, 487, -1, + 766, 487, 765, -1, 766, 483, 484, -1, + 485, 486, 765, -1, 485, 765, 487, -1, + 485, 744, 486, -1, 485, 487, 744, -1, + 584, 489, 488, -1, 584, 490, 585, -1, + 584, 488, 490, -1, 584, 762, 489, -1, + 584, 491, 762, -1, 584, 583, 491, -1, + 964, 998, 962, -1, 964, 965, 837, -1, + 964, 837, 493, -1, 492, 495, 494, -1, + 492, 586, 495, -1, 492, 826, 586, -1, + 492, 825, 826, -1, 492, 494, 825, -1, + 772, 493, 591, -1, 772, 591, 1176, -1, + 772, 998, 964, -1, 772, 964, 493, -1, + 775, 1179, 494, -1, 775, 1178, 1179, -1, + 775, 494, 495, -1, 775, 495, 496, -1, + 775, 496, 774, -1, 1404, 497, 1407, -1, + 1404, 498, 497, -1, 1404, 1356, 498, -1, + 1027, 1002, 1254, -1, 1027, 1407, 1002, -1, + 1193, 1059, 1060, -1, 1193, 1060, 1194, -1, + 1195, 922, 1059, -1, 1195, 1059, 1193, -1, + 1199, 1007, 1006, -1, 1199, 1006, 1005, -1, + 1199, 1055, 1009, -1, 1199, 776, 1055, -1, + 1199, 1005, 776, -1, 499, 501, 500, -1, + 499, 500, 502, -1, 499, 503, 501, -1, + 499, 502, 503, -1, 1016, 1399, 1014, -1, + 1214, 504, 782, -1, 1214, 782, 1215, -1, + 1214, 778, 504, -1, 784, 783, 505, -1, + 784, 505, 779, -1, 784, 779, 1215, -1, + 781, 782, 506, -1, 781, 507, 783, -1, + 781, 532, 507, -1, 781, 529, 532, -1, + 781, 528, 529, -1, 781, 506, 528, -1, + 508, 510, 509, -1, 508, 509, 511, -1, + 508, 517, 510, -1, 508, 513, 517, -1, + 508, 511, 513, -1, 1227, 520, 521, -1, + 1227, 1208, 520, -1, 1227, 521, 785, -1, + 1227, 785, 1226, -1, 1332, 1334, 1342, -1, + 512, 513, 514, -1, 512, 519, 513, -1, + 512, 514, 515, -1, 512, 515, 523, -1, + 512, 523, 519, -1, 516, 518, 517, -1, + 516, 517, 519, -1, 516, 520, 518, -1, + 516, 521, 520, -1, 516, 785, 521, -1, + 516, 522, 785, -1, 516, 523, 522, -1, + 516, 519, 523, -1, 1230, 1022, 524, -1, + 1230, 524, 786, -1, 789, 726, 1172, -1, + 789, 1172, 1023, -1, 789, 790, 525, -1, + 789, 525, 726, -1, 1025, 526, 793, -1, + 1025, 1251, 526, -1, 794, 527, 796, -1, + 794, 528, 527, -1, 794, 529, 528, -1, + 794, 532, 529, -1, 794, 795, 532, -1, + 1028, 530, 531, -1, 1028, 797, 530, -1, + 1028, 531, 532, -1, 1028, 532, 795, -1, + 1032, 1028, 795, -1, 534, 805, 533, -1, + 534, 533, 562, -1, 534, 562, 558, -1, + 534, 559, 536, -1, 534, 558, 559, -1, + 803, 805, 534, -1, 803, 535, 802, -1, + 803, 536, 535, -1, 803, 534, 536, -1, + 1035, 655, 811, -1, 1035, 875, 655, -1, + 1042, 867, 1043, -1, 809, 1041, 1046, -1, + 809, 1194, 537, -1, 809, 537, 1041, -1, + 618, 549, 617, -1, 618, 807, 549, -1, + 618, 867, 807, -1, 1052, 888, 889, -1, + 812, 1070, 1041, -1, 812, 1041, 537, -1, + 812, 537, 1060, -1, 1067, 1068, 816, -1, + 538, 1264, 539, -1, 538, 545, 1264, -1, + 538, 539, 540, -1, 538, 540, 545, -1, + 551, 545, 540, -1, 551, 540, 541, -1, + 551, 542, 547, -1, 551, 541, 542, -1, + 543, 544, 1263, -1, 543, 1263, 545, -1, + 543, 547, 546, -1, 543, 546, 548, -1, + 543, 548, 549, -1, 543, 550, 544, -1, + 543, 549, 550, -1, 543, 551, 547, -1, + 543, 545, 551, -1, 552, 553, 554, -1, + 552, 555, 553, -1, 552, 554, 556, -1, + 552, 556, 555, -1, 557, 559, 558, -1, + 557, 560, 559, -1, 557, 562, 561, -1, + 557, 558, 562, -1, 557, 561, 720, -1, + 557, 720, 560, -1, 563, 564, 565, -1, + 563, 565, 566, -1, 563, 567, 564, -1, + 563, 566, 567, -1, 1073, 568, 820, -1, + 1073, 569, 568, -1, 1073, 1072, 570, -1, + 1073, 570, 569, -1, 833, 571, 834, -1, + 833, 830, 571, -1, 572, 573, 574, -1, + 572, 575, 573, -1, 572, 574, 576, -1, + 572, 576, 575, -1, 577, 578, 988, -1, + 577, 988, 768, -1, 577, 580, 579, -1, + 577, 579, 578, -1, 577, 581, 580, -1, + 577, 768, 581, -1, 824, 1372, 823, -1, + 824, 1075, 1372, -1, 824, 825, 1075, -1, + 827, 582, 583, -1, 827, 822, 582, -1, + 827, 583, 584, -1, 827, 584, 585, -1, + 827, 586, 826, -1, 827, 585, 586, -1, + 587, 1432, 1374, -1, 587, 588, 1432, -1, + 587, 1374, 589, -1, 587, 589, 590, -1, + 587, 591, 588, -1, 587, 590, 591, -1, + 831, 828, 592, -1, 831, 592, 829, -1, + 1267, 1140, 1268, -1, 1267, 593, 1140, -1, + 1267, 966, 593, -1, 1267, 1373, 836, -1, + 594, 596, 595, -1, 594, 595, 597, -1, + 594, 597, 598, -1, 594, 686, 596, -1, + 594, 598, 599, -1, 594, 599, 686, -1, + 605, 601, 1078, -1, 1077, 604, 605, -1, + 1077, 605, 1078, -1, 1077, 715, 604, -1, + 1077, 1080, 715, -1, 600, 838, 1078, -1, + 600, 948, 838, -1, 600, 1078, 601, -1, + 600, 692, 948, -1, 600, 602, 692, -1, + 600, 603, 602, -1, 600, 604, 603, -1, + 600, 605, 604, -1, 600, 601, 605, -1, + 840, 606, 841, -1, 840, 842, 607, -1, + 840, 607, 606, -1, 850, 611, 845, -1, + 850, 853, 611, -1, 850, 845, 851, -1, + 608, 610, 609, -1, 608, 611, 610, -1, + 608, 609, 612, -1, 608, 612, 611, -1, + 613, 615, 614, -1, 613, 616, 615, -1, + 613, 614, 616, -1, 862, 617, 859, -1, + 1085, 1083, 862, -1, 1085, 865, 860, -1, + 866, 617, 862, -1, 866, 862, 1083, -1, + 866, 618, 617, -1, 866, 867, 618, -1, + 619, 870, 874, -1, 619, 860, 870, -1, + 619, 874, 1087, -1, 619, 1087, 860, -1, + 871, 872, 620, -1, 871, 620, 868, -1, + 940, 870, 872, -1, 939, 940, 872, -1, + 925, 887, 928, -1, 926, 655, 875, -1, + 621, 623, 622, -1, 621, 622, 624, -1, + 621, 624, 625, -1, 621, 625, 626, -1, + 621, 626, 627, -1, 621, 628, 623, -1, + 621, 627, 628, -1, 876, 1090, 629, -1, + 876, 629, 877, -1, 1091, 631, 630, -1, + 1091, 630, 1090, -1, 1091, 1092, 631, -1, + 663, 632, 1111, -1, 663, 1366, 632, -1, + 663, 1367, 1366, -1, 633, 635, 634, -1, + 633, 636, 635, -1, 633, 634, 637, -1, + 633, 637, 636, -1, 638, 639, 697, -1, + 638, 697, 640, -1, 638, 641, 639, -1, + 638, 640, 641, -1, 642, 644, 643, -1, + 642, 645, 644, -1, 642, 643, 645, -1, + 883, 646, 884, -1, 883, 647, 646, -1, + 883, 648, 647, -1, 883, 653, 648, -1, + 883, 920, 653, -1, 919, 649, 650, -1, + 919, 1294, 649, -1, 919, 650, 651, -1, + 919, 651, 652, -1, 919, 652, 653, -1, + 919, 653, 920, -1, 679, 930, 654, -1, + 679, 654, 887, -1, 679, 887, 925, -1, + 886, 928, 887, -1, 886, 888, 655, -1, + 886, 655, 926, -1, 886, 926, 928, -1, + 1099, 893, 674, -1, 1099, 674, 921, -1, + 1099, 921, 1098, -1, 898, 656, 897, -1, + 898, 899, 657, -1, 898, 657, 656, -1, + 1104, 897, 895, -1, 658, 660, 659, -1, + 658, 659, 661, -1, 658, 662, 660, -1, + 658, 661, 662, -1, 1107, 1288, 1108, -1, + 1110, 1367, 663, -1, 1110, 663, 1111, -1, + 1379, 901, 1365, -1, 1379, 1365, 1380, -1, + 1437, 904, 1438, -1, 1109, 664, 905, -1, + 1109, 907, 664, -1, 910, 878, 665, -1, + 910, 1095, 878, -1, 910, 665, 666, -1, + 910, 666, 909, -1, 1291, 1095, 910, -1, + 917, 918, 667, -1, 917, 912, 916, -1, + 917, 667, 913, -1, 1293, 916, 912, -1, + 1293, 912, 1294, -1, 668, 918, 1299, -1, + 668, 669, 918, -1, 668, 1299, 669, -1, + 670, 671, 1300, -1, 670, 1300, 672, -1, + 670, 673, 671, -1, 670, 672, 673, -1, + 1304, 921, 674, -1, 1304, 674, 893, -1, + 1304, 893, 675, -1, 1304, 675, 1113, -1, + 676, 678, 677, -1, 676, 677, 777, -1, + 676, 1009, 678, -1, 676, 777, 1009, -1, + 1311, 1202, 1313, -1, 1274, 1123, 1273, -1, + 1274, 1122, 1123, -1, 1116, 930, 679, -1, + 1116, 679, 925, -1, 1133, 881, 937, -1, + 1133, 1275, 881, -1, 1124, 1126, 1098, -1, + 1124, 1098, 1123, -1, 1127, 1128, 1120, -1, + 1127, 939, 1126, -1, 1130, 1120, 1128, -1, + 680, 681, 682, -1, 680, 683, 681, -1, + 680, 682, 685, -1, 680, 685, 683, -1, + 684, 686, 685, -1, 684, 687, 686, -1, + 684, 685, 687, -1, 688, 690, 689, -1, + 688, 689, 691, -1, 688, 692, 690, -1, + 688, 691, 692, -1, 693, 694, 695, -1, + 693, 696, 694, -1, 693, 695, 697, -1, + 693, 697, 696, -1, 698, 699, 700, -1, + 698, 700, 701, -1, 698, 701, 699, -1, + 703, 704, 708, -1, 703, 708, 706, -1, + 703, 707, 702, -1, 703, 706, 707, -1, + 946, 702, 947, -1, 946, 704, 703, -1, + 946, 703, 702, -1, 944, 708, 704, -1, + 944, 945, 707, -1, 944, 704, 946, -1, + 705, 707, 706, -1, 705, 706, 708, -1, + 705, 944, 707, -1, 705, 708, 944, -1, + 709, 710, 711, -1, 709, 712, 710, -1, + 709, 711, 713, -1, 709, 713, 712, -1, + 954, 951, 714, -1, 954, 715, 948, -1, + 954, 714, 715, -1, 953, 1135, 952, -1, + 953, 954, 948, -1, 1011, 1013, 716, -1, + 1011, 716, 717, -1, 1011, 717, 778, -1, + 958, 956, 718, -1, 958, 718, 722, -1, + 958, 722, 719, -1, 958, 719, 720, -1, + 958, 720, 959, -1, 1397, 1342, 723, -1, + 1397, 723, 1398, -1, 724, 1014, 1398, -1, + 724, 1398, 723, -1, 724, 1012, 1014, -1, + 721, 722, 1012, -1, 721, 723, 722, -1, + 721, 1012, 724, -1, 721, 724, 723, -1, + 961, 725, 963, -1, 961, 727, 726, -1, + 961, 962, 727, -1, 961, 726, 1141, -1, + 961, 1141, 725, -1, 728, 1140, 729, -1, + 728, 729, 1141, -1, 728, 1141, 1140, -1, + 737, 730, 738, -1, 737, 736, 730, -1, + 731, 733, 732, -1, 731, 734, 733, -1, + 731, 732, 735, -1, 731, 735, 734, -1, + 967, 740, 736, -1, 967, 736, 737, -1, + 967, 738, 969, -1, 967, 737, 738, -1, + 1321, 739, 740, -1, 1321, 1319, 739, -1, + 1321, 740, 967, -1, 970, 1145, 741, -1, + 970, 741, 971, -1, 742, 744, 743, -1, + 742, 745, 744, -1, 742, 743, 1388, -1, + 742, 747, 746, -1, 742, 746, 745, -1, + 742, 1388, 1219, -1, 742, 1219, 747, -1, + 976, 975, 748, -1, 976, 749, 750, -1, + 976, 748, 749, -1, 976, 751, 977, -1, + 976, 750, 752, -1, 976, 752, 751, -1, + 753, 755, 754, -1, 753, 756, 755, -1, + 753, 757, 758, -1, 753, 754, 757, -1, + 753, 758, 759, -1, 753, 759, 756, -1, + 760, 992, 979, -1, 760, 762, 761, -1, + 760, 979, 762, -1, 760, 761, 768, -1, + 760, 768, 992, -1, 991, 770, 985, -1, + 991, 990, 770, -1, 763, 765, 764, -1, + 763, 764, 985, -1, 763, 766, 765, -1, + 763, 767, 766, -1, 763, 769, 996, -1, + 763, 996, 767, -1, 763, 770, 769, -1, + 763, 985, 770, -1, 981, 974, 977, -1, + 981, 982, 974, -1, 981, 977, 983, -1, + 986, 993, 994, -1, 986, 994, 991, -1, + 986, 987, 982, -1, 1159, 992, 768, -1, + 1159, 768, 988, -1, 995, 991, 994, -1, + 1169, 996, 769, -1, 1169, 769, 770, -1, + 1169, 770, 990, -1, 1169, 990, 1153, -1, + 1169, 1153, 1168, -1, 1167, 1168, 1153, -1, + 1167, 771, 1166, -1, 1167, 820, 771, -1, + 1174, 772, 1176, -1, 1174, 998, 772, -1, + 1177, 773, 1000, -1, 1177, 774, 773, -1, + 1177, 775, 774, -1, 1177, 1178, 775, -1, + 1001, 1254, 1002, -1, 1001, 1329, 1254, -1, + 1196, 924, 922, -1, 1196, 922, 1195, -1, + 1191, 776, 1005, -1, 1191, 1049, 776, -1, + 1191, 1184, 1049, -1, 1206, 1007, 1199, -1, + 1203, 1009, 777, -1, 1203, 777, 1202, -1, + 1015, 778, 1214, -1, 1015, 1011, 778, -1, + 1216, 1215, 779, -1, 1216, 779, 1218, -1, + 780, 782, 781, -1, 780, 781, 783, -1, + 780, 783, 784, -1, 780, 1215, 782, -1, + 780, 784, 1215, -1, 1225, 785, 1222, -1, + 1225, 1226, 785, -1, 1333, 1334, 1332, -1, + 1021, 1022, 1230, -1, 1229, 786, 1020, -1, + 1229, 1230, 786, -1, 1234, 791, 788, -1, + 1234, 1024, 791, -1, 1241, 788, 1023, -1, + 1241, 1234, 788, -1, 787, 1023, 788, -1, + 787, 789, 1023, -1, 787, 790, 789, -1, + 787, 791, 790, -1, 787, 788, 791, -1, + 1347, 792, 1024, -1, 1347, 1247, 792, -1, + 1350, 1025, 793, -1, 1350, 793, 1247, -1, + 1312, 1313, 1251, -1, 1253, 1310, 1414, -1, + 1257, 1232, 1231, -1, 1257, 1231, 1018, -1, + 1257, 1420, 1419, -1, 1257, 1018, 1420, -1, + 800, 795, 794, -1, 800, 1032, 795, -1, + 800, 794, 796, -1, 800, 796, 805, -1, + 800, 805, 804, -1, 1259, 798, 797, -1, + 1259, 797, 1028, -1, 1259, 799, 798, -1, + 1259, 1260, 799, -1, 1031, 804, 1030, -1, + 1031, 800, 804, -1, 1031, 1032, 800, -1, + 801, 802, 1030, -1, 801, 803, 802, -1, + 801, 1030, 804, -1, 801, 804, 805, -1, + 801, 805, 803, -1, 1265, 1277, 1375, -1, + 1034, 875, 1035, -1, 1034, 1087, 874, -1, + 1037, 1036, 1047, -1, 1037, 1047, 1038, -1, + 1040, 1047, 1046, -1, 1040, 1043, 1038, -1, + 1040, 1038, 1047, -1, 1045, 1047, 1036, -1, + 806, 808, 807, -1, 806, 1044, 808, -1, + 806, 1042, 1044, -1, 806, 807, 867, -1, + 806, 867, 1042, -1, 1185, 1194, 809, -1, + 1185, 809, 1046, -1, 810, 1045, 1036, -1, + 810, 1048, 1045, -1, 810, 1051, 1048, -1, + 810, 1052, 1051, -1, 810, 1036, 1035, -1, + 810, 1035, 811, -1, 810, 811, 888, -1, + 810, 888, 1052, -1, 1053, 1052, 889, -1, + 1053, 889, 891, -1, 1053, 891, 1055, -1, + 1058, 1066, 1070, -1, 1058, 1070, 812, -1, + 1058, 812, 1060, -1, 1065, 1066, 1057, -1, + 1065, 814, 813, -1, 1065, 813, 1068, -1, + 1065, 1063, 814, -1, 1065, 1057, 1063, -1, + 815, 816, 817, -1, 815, 1067, 816, -1, + 815, 818, 819, -1, 815, 817, 818, -1, + 815, 819, 1071, -1, 815, 1071, 1067, -1, + 1154, 1167, 1153, -1, 1154, 1073, 820, -1, + 1154, 820, 1167, -1, 821, 823, 822, -1, + 821, 824, 823, -1, 821, 825, 824, -1, + 821, 826, 825, -1, 821, 827, 826, -1, + 821, 822, 827, -1, 1421, 1074, 828, -1, + 1421, 828, 831, -1, 1371, 829, 830, -1, + 1371, 831, 829, -1, 1371, 1421, 831, -1, + 1371, 832, 1372, -1, 1371, 830, 833, -1, + 1371, 834, 832, -1, 1371, 833, 834, -1, + 835, 1267, 836, -1, 835, 966, 1267, -1, + 835, 836, 837, -1, 835, 837, 966, -1, + 1079, 1078, 838, -1, 1079, 838, 1080, -1, + 839, 840, 841, -1, 839, 842, 840, -1, + 839, 843, 842, -1, 839, 844, 843, -1, + 839, 845, 846, -1, 839, 841, 845, -1, + 839, 846, 847, -1, 839, 847, 848, -1, + 839, 848, 844, -1, 849, 850, 851, -1, + 849, 851, 852, -1, 849, 853, 850, -1, + 849, 852, 854, -1, 849, 854, 853, -1, + 855, 863, 862, -1, 855, 856, 863, -1, + 855, 857, 856, -1, 855, 858, 857, -1, + 855, 859, 858, -1, 855, 862, 859, -1, + 1086, 860, 1087, -1, 1086, 1085, 860, -1, + 861, 862, 863, -1, 861, 1085, 862, -1, + 861, 863, 864, -1, 861, 864, 865, -1, + 861, 865, 1085, -1, 1082, 866, 1083, -1, + 1082, 1084, 1038, -1, 1082, 1038, 1043, -1, + 1082, 1043, 867, -1, 1082, 867, 866, -1, + 1103, 868, 1106, -1, 1103, 871, 868, -1, + 869, 870, 940, -1, 869, 940, 927, -1, + 869, 874, 870, -1, 869, 927, 874, -1, + 1102, 1126, 939, -1, 1102, 871, 1103, -1, + 1102, 872, 871, -1, 1102, 939, 872, -1, + 873, 874, 927, -1, 873, 927, 926, -1, + 873, 926, 875, -1, 873, 1034, 874, -1, + 873, 875, 1034, -1, 1089, 876, 877, -1, + 1089, 879, 878, -1, 1089, 877, 879, -1, + 1089, 1090, 876, -1, 1089, 878, 1095, -1, + 1096, 884, 880, -1, 1096, 880, 881, -1, + 1096, 881, 1275, -1, 882, 920, 883, -1, + 882, 1271, 920, -1, 882, 883, 884, -1, + 882, 884, 1096, -1, 882, 1096, 1271, -1, + 885, 886, 887, -1, 885, 889, 888, -1, + 885, 888, 886, -1, 885, 887, 890, -1, + 885, 891, 889, -1, 885, 890, 891, -1, + 892, 894, 893, -1, 892, 893, 1099, -1, + 892, 1099, 1104, -1, 892, 895, 894, -1, + 892, 1104, 895, -1, 896, 897, 1104, -1, + 896, 899, 898, -1, 896, 898, 897, -1, + 896, 1105, 899, -1, 896, 1104, 1105, -1, + 1101, 1104, 1099, -1, 1276, 1286, 1288, -1, + 1276, 1288, 1107, -1, 1276, 1277, 1286, -1, + 900, 1379, 1279, -1, 900, 901, 1379, -1, + 900, 1279, 902, -1, 900, 902, 901, -1, + 1439, 1109, 1440, -1, 1436, 1108, 903, -1, + 1436, 903, 904, -1, 1436, 904, 1437, -1, + 1283, 905, 1278, -1, 1283, 1109, 905, -1, + 906, 908, 907, -1, 906, 907, 1109, -1, + 906, 1109, 1439, -1, 906, 1438, 908, -1, + 906, 1439, 1438, -1, 1290, 909, 1289, -1, + 1290, 910, 909, -1, 1290, 1291, 910, -1, + 1292, 1094, 1095, -1, 1292, 1095, 1291, -1, + 1292, 1111, 1093, -1, 1292, 1093, 1094, -1, + 911, 912, 917, -1, 911, 917, 913, -1, + 911, 914, 912, -1, 911, 913, 914, -1, + 915, 1293, 918, -1, 915, 916, 1293, -1, + 915, 918, 917, -1, 915, 917, 916, -1, + 1296, 1112, 918, -1, 1296, 918, 1293, -1, + 1295, 1294, 919, -1, 1295, 919, 920, -1, + 1295, 920, 1271, -1, 1303, 921, 1304, -1, + 1303, 1123, 921, -1, 1303, 1273, 1123, -1, + 1303, 1306, 1273, -1, 1201, 1202, 1311, -1, + 1327, 1180, 922, -1, 1327, 922, 924, -1, + 1325, 1327, 1008, -1, 923, 1007, 1008, -1, + 923, 1327, 924, -1, 923, 1008, 1327, -1, + 923, 1006, 1007, -1, 923, 1197, 1006, -1, + 923, 924, 1196, -1, 923, 1196, 1197, -1, + 1117, 927, 940, -1, 1117, 940, 1120, -1, + 1115, 1116, 925, -1, 1115, 926, 927, -1, + 1115, 927, 1117, -1, 1115, 925, 928, -1, + 1115, 928, 926, -1, 929, 1118, 942, -1, + 929, 930, 1116, -1, 929, 1116, 1118, -1, + 929, 931, 930, -1, 929, 934, 931, -1, + 929, 942, 934, -1, 932, 1131, 936, -1, + 932, 942, 1131, -1, 932, 936, 933, -1, + 932, 933, 934, -1, 932, 934, 942, -1, + 1132, 1130, 1128, -1, 935, 937, 936, -1, + 935, 1133, 937, -1, 935, 936, 1131, -1, + 935, 1131, 1133, -1, 938, 1127, 1120, -1, + 938, 939, 1127, -1, 938, 1120, 940, -1, + 938, 940, 939, -1, 941, 1131, 942, -1, + 941, 1130, 1131, -1, 941, 942, 1118, -1, + 941, 1118, 1130, -1, 1119, 1120, 1130, -1, + 1119, 1130, 1118, -1, 943, 945, 944, -1, + 943, 944, 946, -1, 943, 947, 945, -1, + 943, 946, 947, -1, 1137, 1135, 953, -1, + 1137, 948, 949, -1, 1137, 953, 948, -1, + 1137, 949, 1138, -1, 950, 952, 951, -1, + 950, 953, 952, -1, 950, 951, 954, -1, + 950, 954, 953, -1, 955, 957, 956, -1, + 955, 956, 958, -1, 955, 959, 957, -1, + 955, 958, 959, -1, 960, 962, 961, -1, + 960, 961, 963, -1, 960, 964, 962, -1, + 960, 965, 964, -1, 960, 966, 965, -1, + 960, 963, 966, -1, 1269, 1150, 1147, -1, + 1269, 1147, 1320, -1, 1143, 1321, 967, -1, + 1143, 969, 968, -1, 1143, 967, 969, -1, + 1143, 968, 1074, -1, 1318, 970, 971, -1, + 1318, 972, 1319, -1, 1318, 971, 972, -1, + 1318, 1145, 970, -1, 1318, 1320, 1147, -1, + 973, 974, 975, -1, 973, 975, 976, -1, + 973, 977, 974, -1, 973, 976, 977, -1, + 978, 979, 992, -1, 978, 992, 993, -1, + 978, 983, 979, -1, 978, 993, 983, -1, + 980, 982, 981, -1, 980, 986, 982, -1, + 980, 981, 983, -1, 980, 983, 993, -1, + 980, 993, 986, -1, 984, 991, 985, -1, + 984, 986, 991, -1, 984, 985, 987, -1, + 984, 987, 986, -1, 1158, 1159, 988, -1, + 1158, 988, 989, -1, 1158, 989, 1156, -1, + 1152, 1153, 990, -1, 1152, 990, 991, -1, + 1152, 991, 995, -1, 1161, 992, 1159, -1, + 1161, 993, 992, -1, 1161, 994, 993, -1, + 1161, 995, 994, -1, 1160, 1152, 995, -1, + 1160, 1158, 1156, -1, 1160, 995, 1161, -1, + 1163, 996, 1169, -1, 1163, 1164, 997, -1, + 1163, 997, 996, -1, 1171, 999, 998, -1, + 1171, 998, 1174, -1, 1171, 1172, 999, -1, + 1175, 1243, 1245, -1, 1175, 1000, 1243, -1, + 1175, 1177, 1000, -1, 1181, 1329, 1001, -1, + 1181, 1002, 1003, -1, 1181, 1001, 1002, -1, + 1181, 1003, 1004, -1, 1181, 1004, 1182, -1, + 1255, 1254, 1329, -1, 1255, 1329, 1315, -1, + 1255, 1315, 1310, -1, 1255, 1310, 1253, -1, + 1192, 1191, 1005, -1, 1192, 1005, 1006, -1, + 1192, 1006, 1197, -1, 1205, 1007, 1206, -1, + 1205, 1008, 1007, -1, 1205, 1325, 1008, -1, + 1200, 1199, 1009, -1, 1200, 1009, 1203, -1, + 1211, 1016, 1217, -1, 1010, 1015, 1014, -1, + 1010, 1011, 1015, -1, 1010, 1014, 1012, -1, + 1010, 1012, 1013, -1, 1010, 1013, 1011, -1, + 1213, 1016, 1014, -1, 1213, 1014, 1015, -1, + 1213, 1217, 1016, -1, 1213, 1015, 1214, -1, + 1331, 1332, 1342, -1, 1395, 1211, 1340, -1, + 1395, 1399, 1016, -1, 1395, 1016, 1211, -1, + 1237, 1021, 1230, -1, 1017, 1231, 1229, -1, + 1017, 1019, 1018, -1, 1017, 1018, 1231, -1, + 1017, 1020, 1019, -1, 1017, 1229, 1020, -1, + 1236, 1021, 1237, -1, 1236, 1244, 1022, -1, + 1236, 1022, 1021, -1, 1242, 1241, 1023, -1, + 1242, 1023, 1172, -1, 1233, 1347, 1024, -1, + 1233, 1246, 1347, -1, 1233, 1024, 1234, -1, + 1344, 1237, 1232, -1, 1344, 1232, 1345, -1, + 1349, 1409, 1408, -1, 1349, 1408, 1350, -1, + 1250, 1251, 1025, -1, 1250, 1025, 1350, -1, + 1250, 1350, 1408, -1, 1357, 1026, 1352, -1, + 1357, 1417, 1026, -1, 1357, 1358, 1417, -1, + 1406, 1407, 1027, -1, 1406, 1027, 1254, -1, + 1256, 1345, 1232, -1, 1256, 1232, 1257, -1, + 1256, 1409, 1345, -1, 1029, 1028, 1032, -1, + 1029, 1259, 1028, -1, 1261, 1259, 1029, -1, + 1261, 1030, 1264, -1, 1261, 1031, 1030, -1, + 1261, 1032, 1031, -1, 1261, 1029, 1032, -1, + 1362, 1380, 1365, -1, 1362, 1382, 1380, -1, + 1361, 1265, 1375, -1, 1361, 1375, 1376, -1, + 1361, 1376, 1280, -1, 1361, 1280, 1382, -1, + 1368, 1367, 1110, -1, 1368, 1285, 1277, -1, + 1368, 1277, 1265, -1, 1033, 1034, 1035, -1, + 1033, 1035, 1036, -1, 1033, 1036, 1037, -1, + 1033, 1038, 1084, -1, 1033, 1037, 1038, -1, + 1033, 1084, 1087, -1, 1033, 1087, 1034, -1, + 1039, 1040, 1046, -1, 1039, 1046, 1041, -1, + 1039, 1042, 1043, -1, 1039, 1043, 1040, -1, + 1039, 1041, 1044, -1, 1039, 1044, 1042, -1, + 1188, 1048, 1187, -1, 1188, 1045, 1048, -1, + 1188, 1185, 1046, -1, 1188, 1046, 1047, -1, + 1188, 1047, 1045, -1, 1186, 1187, 1048, -1, + 1186, 1048, 1051, -1, 1186, 1054, 1049, -1, + 1186, 1049, 1184, -1, 1050, 1051, 1052, -1, + 1050, 1052, 1053, -1, 1050, 1054, 1186, -1, + 1050, 1186, 1051, -1, 1050, 1055, 1054, -1, + 1050, 1053, 1055, -1, 1056, 1057, 1066, -1, + 1056, 1066, 1058, -1, 1056, 1060, 1059, -1, + 1056, 1058, 1060, -1, 1056, 1062, 1061, -1, + 1056, 1059, 1062, -1, 1056, 1061, 1063, -1, + 1056, 1063, 1057, -1, 1064, 1066, 1065, -1, + 1064, 1068, 1067, -1, 1064, 1065, 1068, -1, + 1064, 1069, 1070, -1, 1064, 1070, 1066, -1, + 1064, 1071, 1069, -1, 1064, 1067, 1071, -1, + 1155, 1156, 1072, -1, 1155, 1072, 1073, -1, + 1155, 1073, 1154, -1, 1422, 1074, 1421, -1, + 1422, 1143, 1074, -1, 1430, 1372, 1075, -1, + 1430, 1075, 1374, -1, 1076, 1077, 1078, -1, + 1076, 1078, 1079, -1, 1076, 1080, 1077, -1, + 1076, 1079, 1080, -1, 1081, 1082, 1083, -1, + 1081, 1084, 1082, -1, 1081, 1083, 1085, -1, + 1081, 1085, 1086, -1, 1081, 1087, 1084, -1, + 1081, 1086, 1087, -1, 1088, 1090, 1089, -1, + 1088, 1092, 1091, -1, 1088, 1091, 1090, -1, + 1088, 1093, 1092, -1, 1088, 1094, 1093, -1, + 1088, 1095, 1094, -1, 1088, 1089, 1095, -1, + 1272, 1271, 1096, -1, 1272, 1096, 1275, -1, + 1097, 1126, 1102, -1, 1097, 1102, 1101, -1, + 1097, 1098, 1126, -1, 1097, 1099, 1098, -1, + 1097, 1101, 1099, -1, 1100, 1101, 1102, -1, + 1100, 1102, 1103, -1, 1100, 1105, 1104, -1, + 1100, 1104, 1101, -1, 1100, 1106, 1105, -1, + 1100, 1103, 1106, -1, 1435, 1276, 1107, -1, + 1435, 1107, 1108, -1, 1435, 1108, 1436, -1, + 1282, 1283, 1278, -1, 1281, 1440, 1109, -1, + 1281, 1109, 1283, -1, 1281, 1376, 1440, -1, + 1287, 1285, 1368, -1, 1287, 1368, 1110, -1, + 1287, 1110, 1111, -1, 1287, 1111, 1292, -1, + 1307, 1112, 1296, -1, 1307, 1299, 1112, -1, + 1305, 1304, 1113, -1, 1305, 1113, 1301, -1, + 1314, 1201, 1311, -1, 1314, 1310, 1315, -1, + 1314, 1316, 1201, -1, 1326, 1315, 1329, -1, + 1114, 1116, 1115, -1, 1114, 1115, 1117, -1, + 1114, 1118, 1116, -1, 1114, 1119, 1118, -1, + 1114, 1117, 1120, -1, 1114, 1120, 1119, -1, + 1125, 1133, 1132, -1, 1125, 1275, 1133, -1, + 1125, 1274, 1275, -1, 1125, 1122, 1274, -1, + 1121, 1123, 1122, -1, 1121, 1124, 1123, -1, + 1121, 1122, 1125, -1, 1121, 1125, 1132, -1, + 1121, 1126, 1124, -1, 1121, 1127, 1126, -1, + 1121, 1128, 1127, -1, 1121, 1132, 1128, -1, + 1129, 1131, 1130, -1, 1129, 1130, 1132, -1, + 1129, 1133, 1131, -1, 1129, 1132, 1133, -1, + 1134, 1136, 1135, -1, 1134, 1135, 1137, -1, + 1134, 1138, 1136, -1, 1134, 1137, 1138, -1, + 1270, 1320, 1369, -1, 1270, 1269, 1320, -1, + 1139, 1268, 1140, -1, 1139, 1269, 1268, -1, + 1139, 1140, 1141, -1, 1139, 1150, 1269, -1, + 1139, 1141, 1142, -1, 1139, 1142, 1150, -1, + 1322, 1321, 1143, -1, 1322, 1143, 1422, -1, + 1144, 1145, 1318, -1, 1144, 1146, 1145, -1, + 1144, 1318, 1147, -1, 1144, 1148, 1146, -1, + 1144, 1149, 1148, -1, 1144, 1150, 1149, -1, + 1144, 1147, 1150, -1, 1151, 1153, 1152, -1, + 1151, 1152, 1160, -1, 1151, 1154, 1153, -1, + 1151, 1155, 1154, -1, 1151, 1160, 1156, -1, + 1151, 1156, 1155, -1, 1157, 1159, 1158, -1, + 1157, 1158, 1160, -1, 1157, 1161, 1159, -1, + 1157, 1160, 1161, -1, 1162, 1164, 1163, -1, + 1162, 1165, 1164, -1, 1162, 1166, 1165, -1, + 1162, 1167, 1166, -1, 1162, 1168, 1167, -1, + 1162, 1169, 1168, -1, 1162, 1163, 1169, -1, + 1170, 1172, 1171, -1, 1170, 1242, 1172, -1, + 1170, 1245, 1242, -1, 1170, 1174, 1245, -1, + 1170, 1171, 1174, -1, 1173, 1245, 1174, -1, + 1173, 1175, 1245, -1, 1173, 1174, 1176, -1, + 1173, 1178, 1177, -1, 1173, 1177, 1175, -1, + 1173, 1176, 1179, -1, 1173, 1179, 1178, -1, + 1328, 1180, 1327, -1, 1328, 1329, 1181, -1, + 1328, 1182, 1180, -1, 1328, 1181, 1182, -1, + 1183, 1184, 1191, -1, 1183, 1191, 1190, -1, + 1183, 1194, 1185, -1, 1183, 1190, 1194, -1, + 1183, 1187, 1186, -1, 1183, 1186, 1184, -1, + 1183, 1188, 1187, -1, 1183, 1185, 1188, -1, + 1189, 1190, 1191, -1, 1189, 1191, 1192, -1, + 1189, 1193, 1194, -1, 1189, 1194, 1190, -1, + 1189, 1195, 1193, -1, 1189, 1196, 1195, -1, + 1189, 1197, 1196, -1, 1189, 1192, 1197, -1, + 1198, 1206, 1199, -1, 1198, 1207, 1206, -1, + 1198, 1199, 1200, -1, 1198, 1202, 1201, -1, + 1198, 1203, 1202, -1, 1198, 1200, 1203, -1, + 1198, 1201, 1316, -1, 1198, 1316, 1207, -1, + 1204, 1205, 1206, -1, 1204, 1206, 1207, -1, + 1204, 1207, 1316, -1, 1204, 1316, 1325, -1, + 1204, 1325, 1205, -1, 1339, 1210, 1208, -1, + 1339, 1340, 1211, -1, 1339, 1208, 1227, -1, + 1339, 1227, 1337, -1, 1209, 1217, 1210, -1, + 1209, 1211, 1217, -1, 1209, 1210, 1339, -1, + 1209, 1339, 1211, -1, 1212, 1213, 1214, -1, + 1212, 1214, 1215, -1, 1212, 1215, 1216, -1, + 1212, 1217, 1213, -1, 1212, 1218, 1217, -1, + 1212, 1216, 1218, -1, 1223, 1219, 1388, -1, + 1223, 1390, 1225, -1, 1223, 1221, 1220, -1, + 1223, 1220, 1219, -1, 1223, 1222, 1221, -1, + 1223, 1225, 1222, -1, 1389, 1223, 1388, -1, + 1389, 1390, 1223, -1, 1392, 1333, 1332, -1, + 1224, 1226, 1225, -1, 1224, 1225, 1390, -1, + 1224, 1390, 1336, -1, 1224, 1336, 1337, -1, + 1224, 1337, 1227, -1, 1224, 1227, 1226, -1, + 1341, 1331, 1342, -1, 1394, 1395, 1340, -1, + 1394, 1338, 1341, -1, 1228, 1230, 1229, -1, + 1228, 1237, 1230, -1, 1228, 1229, 1231, -1, + 1228, 1231, 1232, -1, 1228, 1232, 1237, -1, + 1238, 1246, 1233, -1, 1238, 1233, 1234, -1, + 1238, 1234, 1241, -1, 1238, 1241, 1240, -1, + 1238, 1244, 1236, -1, 1238, 1240, 1244, -1, + 1235, 1236, 1237, -1, 1235, 1344, 1246, -1, + 1235, 1237, 1344, -1, 1235, 1246, 1238, -1, + 1235, 1238, 1236, -1, 1239, 1240, 1241, -1, + 1239, 1241, 1242, -1, 1239, 1243, 1244, -1, + 1239, 1244, 1240, -1, 1239, 1245, 1243, -1, + 1239, 1242, 1245, -1, 1346, 1347, 1246, -1, + 1346, 1246, 1344, -1, 1348, 1247, 1347, -1, + 1348, 1350, 1247, -1, 1248, 1252, 1414, -1, + 1248, 1312, 1252, -1, 1248, 1414, 1310, -1, + 1248, 1310, 1312, -1, 1413, 1414, 1252, -1, + 1413, 1252, 1408, -1, 1249, 1251, 1250, -1, + 1249, 1312, 1251, -1, 1249, 1252, 1312, -1, + 1249, 1250, 1408, -1, 1249, 1408, 1252, -1, + 1401, 1253, 1414, -1, 1401, 1406, 1254, -1, + 1401, 1254, 1255, -1, 1401, 1255, 1253, -1, + 1359, 1409, 1256, -1, 1359, 1257, 1419, -1, + 1359, 1256, 1257, -1, 1258, 1260, 1259, -1, + 1258, 1259, 1261, -1, 1258, 1262, 1260, -1, + 1258, 1263, 1262, -1, 1258, 1264, 1263, -1, + 1258, 1261, 1264, -1, 1364, 1265, 1361, -1, + 1364, 1362, 1365, -1, 1364, 1368, 1265, -1, + 1266, 1428, 1373, -1, 1266, 1267, 1268, -1, + 1266, 1373, 1267, -1, 1266, 1268, 1269, -1, + 1266, 1269, 1270, -1, 1266, 1369, 1428, -1, + 1266, 1270, 1369, -1, 1423, 1369, 1322, -1, + 1423, 1322, 1422, -1, 1426, 1372, 1430, -1, + 1297, 1295, 1271, -1, 1297, 1271, 1272, -1, + 1297, 1273, 1306, -1, 1297, 1274, 1273, -1, + 1297, 1275, 1274, -1, 1297, 1272, 1275, -1, + 1377, 1276, 1435, -1, 1377, 1375, 1277, -1, + 1377, 1277, 1276, -1, 1381, 1278, 1279, -1, + 1381, 1282, 1278, -1, 1381, 1279, 1379, -1, + 1383, 1280, 1376, -1, 1383, 1376, 1281, -1, + 1383, 1282, 1381, -1, 1383, 1283, 1282, -1, + 1383, 1281, 1283, -1, 1383, 1382, 1280, -1, + 1284, 1286, 1285, -1, 1284, 1285, 1287, -1, + 1284, 1289, 1288, -1, 1284, 1288, 1286, -1, + 1284, 1290, 1289, -1, 1284, 1291, 1290, -1, + 1284, 1292, 1291, -1, 1284, 1287, 1292, -1, + 1308, 1293, 1294, -1, 1308, 1294, 1295, -1, + 1308, 1296, 1293, -1, 1308, 1307, 1296, -1, + 1308, 1297, 1306, -1, 1308, 1295, 1297, -1, + 1298, 1299, 1307, -1, 1298, 1301, 1300, -1, + 1298, 1300, 1299, -1, 1298, 1305, 1301, -1, + 1298, 1307, 1305, -1, 1302, 1303, 1304, -1, + 1302, 1304, 1305, -1, 1302, 1306, 1303, -1, + 1302, 1305, 1307, -1, 1302, 1308, 1306, -1, + 1302, 1307, 1308, -1, 1309, 1310, 1314, -1, + 1309, 1314, 1311, -1, 1309, 1312, 1310, -1, + 1309, 1311, 1313, -1, 1309, 1313, 1312, -1, + 1324, 1314, 1315, -1, 1324, 1315, 1326, -1, + 1324, 1316, 1314, -1, 1324, 1325, 1316, -1, + 1317, 1318, 1319, -1, 1317, 1320, 1318, -1, + 1317, 1319, 1321, -1, 1317, 1321, 1322, -1, + 1317, 1369, 1320, -1, 1317, 1322, 1369, -1, + 1323, 1325, 1324, -1, 1323, 1324, 1326, -1, + 1323, 1327, 1325, -1, 1323, 1328, 1327, -1, + 1323, 1326, 1329, -1, 1323, 1329, 1328, -1, + 1330, 1332, 1331, -1, 1330, 1392, 1332, -1, + 1330, 1341, 1338, -1, 1330, 1331, 1341, -1, + 1330, 1338, 1336, -1, 1330, 1336, 1392, -1, + 1387, 1333, 1392, -1, 1387, 1386, 1334, -1, + 1387, 1334, 1333, -1, 1391, 1336, 1390, -1, + 1391, 1392, 1336, -1, 1335, 1337, 1336, -1, + 1335, 1336, 1338, -1, 1335, 1339, 1337, -1, + 1335, 1340, 1339, -1, 1335, 1394, 1340, -1, + 1335, 1338, 1394, -1, 1396, 1341, 1342, -1, + 1396, 1394, 1341, -1, 1396, 1342, 1397, -1, + 1343, 1344, 1345, -1, 1343, 1346, 1344, -1, + 1343, 1347, 1346, -1, 1343, 1348, 1347, -1, + 1343, 1345, 1409, -1, 1343, 1409, 1349, -1, + 1343, 1349, 1350, -1, 1343, 1350, 1348, -1, + 1411, 1401, 1414, -1, 1416, 1417, 1358, -1, + 1351, 1357, 1352, -1, 1351, 1403, 1357, -1, + 1351, 1353, 1354, -1, 1351, 1352, 1353, -1, + 1351, 1354, 1355, -1, 1351, 1355, 1356, -1, + 1351, 1356, 1404, -1, 1351, 1404, 1403, -1, + 1405, 1358, 1357, -1, 1405, 1357, 1403, -1, + 1405, 1416, 1358, -1, 1418, 1409, 1359, -1, + 1418, 1359, 1419, -1, 1360, 1361, 1382, -1, + 1360, 1364, 1361, -1, 1360, 1382, 1362, -1, + 1360, 1362, 1364, -1, 1363, 1364, 1365, -1, + 1363, 1366, 1367, -1, 1363, 1365, 1366, -1, + 1363, 1367, 1368, -1, 1363, 1368, 1364, -1, + 1427, 1428, 1369, -1, 1427, 1369, 1423, -1, + 1370, 1421, 1371, -1, 1370, 1426, 1421, -1, + 1370, 1371, 1372, -1, 1370, 1372, 1426, -1, + 1429, 1373, 1428, -1, 1429, 1432, 1373, -1, + 1431, 1374, 1432, -1, 1431, 1430, 1374, -1, + 1434, 1376, 1375, -1, 1434, 1375, 1377, -1, + 1434, 1440, 1376, -1, 1434, 1377, 1435, -1, + 1378, 1379, 1380, -1, 1378, 1381, 1379, -1, + 1378, 1380, 1382, -1, 1378, 1382, 1383, -1, + 1378, 1383, 1381, -1, 1384, 1385, 1386, -1, + 1384, 1386, 1387, -1, 1384, 1388, 1385, -1, + 1384, 1389, 1388, -1, 1384, 1390, 1389, -1, + 1384, 1391, 1390, -1, 1384, 1387, 1392, -1, + 1384, 1392, 1391, -1, 1393, 1395, 1394, -1, + 1393, 1394, 1396, -1, 1393, 1396, 1397, -1, + 1393, 1397, 1398, -1, 1393, 1398, 1399, -1, + 1393, 1399, 1395, -1, 1400, 1411, 1416, -1, + 1400, 1416, 1405, -1, 1400, 1405, 1406, -1, + 1400, 1406, 1401, -1, 1400, 1401, 1411, -1, + 1402, 1403, 1404, -1, 1402, 1405, 1403, -1, + 1402, 1406, 1405, -1, 1402, 1404, 1407, -1, + 1402, 1407, 1406, -1, 1412, 1413, 1408, -1, + 1412, 1408, 1409, -1, 1412, 1409, 1418, -1, + 1410, 1418, 1416, -1, 1410, 1416, 1411, -1, + 1410, 1413, 1412, -1, 1410, 1412, 1418, -1, + 1410, 1414, 1413, -1, 1410, 1411, 1414, -1, + 1415, 1417, 1416, -1, 1415, 1416, 1418, -1, + 1415, 1418, 1419, -1, 1415, 1419, 1420, -1, + 1415, 1420, 1417, -1, 1425, 1421, 1426, -1, + 1425, 1422, 1421, -1, 1425, 1423, 1422, -1, + 1425, 1427, 1423, -1, 1424, 1425, 1426, -1, + 1424, 1427, 1425, -1, 1424, 1428, 1427, -1, + 1424, 1429, 1428, -1, 1424, 1426, 1430, -1, + 1424, 1430, 1431, -1, 1424, 1432, 1429, -1, + 1424, 1431, 1432, -1, 1433, 1434, 1435, -1, + 1433, 1436, 1437, -1, 1433, 1435, 1436, -1, + 1433, 1437, 1438, -1, 1433, 1438, 1439, -1, + 1433, 1439, 1440, -1, 1433, 1440, 1434, -1 ] + + } + + } + +} diff --git a/data/models/mekabot-convex/scene-hd.xml b/data/models/mekabot-convex/scene-hd.xml new file mode 100644 index 0000000..aa1beaa --- /dev/null +++ b/data/models/mekabot-convex/scene-hd.xml @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/scene.xml b/data/models/mekabot-convex/scene.xml new file mode 100644 index 0000000..8293b25 --- /dev/null +++ b/data/models/mekabot-convex/scene.xml @@ -0,0 +1,51 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mekabot-convex/workspace-hd.wrl b/data/models/mekabot-convex/workspace-hd.wrl new file mode 100644 index 0000000..40f8b5c --- /dev/null +++ b/data/models/mekabot-convex/workspace-hd.wrl @@ -0,0 +1,126 @@ +#VRML V2.0 utf8 + +DEF mekabot Group { + children [ + Inline { + url "rlsg/mekabot-torso-rightarm.convex-hd.wrl" + } + ] +} + +#DEF package1 Transform{ +# translation 0.0376622556475922 -0.353289011970628 0.299010842949152 #-0.1 -0.4 0.146 # 0.145, to avoid contact with table: 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 1.0 0.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package2 Transform{ +# translation 0.16 0.0 0.146 #0.04 0.0 0.196 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 1.0 0.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} +# +#DEF package3 Transform{ +# translation 0.25 -0.3 -0.094 #-0.1 0.4 0.146 +# rotation 1 0 0 1.5707963 +# children[ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 1.0 +# } +# } +# geometry Cylinder { +# radius 0.031831 +# height 0.24 +# } +# } +# ] +#} + +DEF package1 Transform { + translation 0.16 -0.35 0.146 # 0.025, to avoid contact with table: 0.026 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-red.wrl" + } + ] +} +DEF package2 Transform { + translation 0.0 -0.2 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-green.wrl" + } + ] +} +DEF package3 Transform { + translation -0.1 0.4 0.196 + rotation 0 0 0 0 + children [ + Inline { + url "bottle-blue.wrl" + } + ] +} +#DEF package4 Transform { +# translation 0.13 -0.3 0.146 # 0.025, to avoid contact with table: 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-red-trans.wrl" +# } +# ] +#} +#DEF package5 Transform { +# translation 0.13 -0.2 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-green-trans.wrl" +# } +# ] +#} +#DEF package6 Transform { +# translation 0.13 -0.1 0.146 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-blue-trans.wrl" +# } +# ] +#} + +DEF workspace Group { + children [ + Inline { + url "environment.wrl" + } + ] +} diff --git a/data/models/mekabot-convex/workspace.wrl b/data/models/mekabot-convex/workspace.wrl new file mode 100644 index 0000000..9149e85 --- /dev/null +++ b/data/models/mekabot-convex/workspace.wrl @@ -0,0 +1,99 @@ +#VRML V2.0 utf8 + +DEF mekabot Group { + children [ + Inline { + url "rlsg/mekabot-torso-rightarm.convex.wrl" + } + ] +} + +DEF package1 Transform{ + translation 0 -0.4 0.146 #0.1 -0.4 0.146 # 0.145, to avoid contact with table: 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +DEF package2 Transform{ + translation 0 0.2 0.146 #-0.05 0.0 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +DEF package3 Transform{ + translation 0 0 0.146 #-0.1 0.4 0.146 + rotation 1 0 0 1.5707963 + children[ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 1.0 + } + } + geometry Cylinder { + radius 0.031831 + height 0.24 + } + } + ] +} + +#DEF package1 Transform { +# translation -0.1 -0.4 0.026 # 0.025, to avoid contact with table: 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-red.wrl" +# } +# ] +#} +#DEF package2 Transform { +# translation 0.025 0.0 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-green.wrl" +# } +# ] +#} +#DEF package3 Transform { +# translation 0.15 0.4 0.026 +# rotation 0 0 0 0 +# children [ +# Inline { +# url "bottle-blue.wrl" +# } +# ] +#} + +DEF workspace Group { + children [ + Inline { + url "environment.wrl" + } + ] +} diff --git a/data/models/mobile-robot/LICENSE.md b/data/models/mobile-robot/LICENSE.md new file mode 100644 index 0000000..49c8c16 --- /dev/null +++ b/data/models/mobile-robot/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Sören Jentzsch, Markus Rickert +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/data/models/mobile-robot/box-2d-050505_boxes.onePackage.wrl b/data/models/mobile-robot/box-2d-050505_boxes.onePackage.wrl new file mode 100644 index 0000000..7ff7248 --- /dev/null +++ b/data/models/mobile-robot/box-2d-050505_boxes.onePackage.wrl @@ -0,0 +1,128 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF box-2d-050505 Transform { + translation -0.1 -0.1 0.5 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.2 + diffuseColor 1.0 1.0 0.0 + } + } + geometry Sphere { + radius 0.2 + #size 0.5 0.5 0.5 + } + } + ] + } + ] + } + DEF package1 Transform { + translation 2.0 2.0 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 1.0 0.0 #1.0 0.0 0.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } +# DEF package2 Transform { +# translation 1.0 2.0 0.5 +# rotation 1 0 0 1.5707963 +# children [ +# DEF link0 Transform { +# children [ +# ] +# } +# DEF link1 Transform { +# children [ +# ] +# } +# DEF body1 Transform { +# children [ +# Shape { +# appearance Appearance { +# material Material { +# transparency 0.3 +# diffuseColor 0.0 1.0 0.0 +# } +# } +# geometry Cylinder { +# height 0.5 +# radius 0.2 +# } +# } +# ] +# } +# ] +# } +# DEF package3 Transform { +# translation 0.0 2.0 0.5 +# rotation 1 0 0 1.5707963 +# children [ +# DEF link0 Transform { +# children [ +# ] +# } +# DEF link1 Transform { +# children [ +# ] +# } +# DEF body1 Transform { +# children [ +# Shape { +# appearance Appearance { +# material Material { +# transparency 0.3 +# diffuseColor 0.0 0.0 1.0 +# } +# } +# geometry Cylinder { +# height 0.5 +# radius 0.2 +# } +# } +# ] +# } +# ] +# } + DEF boxes Inline { + url "boxes.noObstacles.wrl" #boxes.wrl + } + ] +} + diff --git a/data/models/mobile-robot/box-2d-050505_boxes.onePackage.xml b/data/models/mobile-robot/box-2d-050505_boxes.onePackage.xml new file mode 100644 index 0000000..45d2ad0 --- /dev/null +++ b/data/models/mobile-robot/box-2d-050505_boxes.onePackage.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/data/models/mobile-robot/box-2d-050505_boxes.wrl b/data/models/mobile-robot/box-2d-050505_boxes.wrl new file mode 100644 index 0000000..f6b2138 --- /dev/null +++ b/data/models/mobile-robot/box-2d-050505_boxes.wrl @@ -0,0 +1,128 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF box-2d-050505 Transform { + translation 1.9 1.9 0.5 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.2 + diffuseColor 1.0 1.0 0.0 + } + } + geometry Sphere { + radius 0.2 + #size 0.5 0.5 0.5 + } + } + ] + } + ] + } + DEF package1 Transform { + translation -2.0 0.3 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF package2 Transform { + translation 0.8 -0.1 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF package3 Transform { + translation -0.9 -0.9 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 0.0 1.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF boxes Inline { + url "boxes.wrl" + } + ] +} + diff --git a/data/models/mobile-robot/box-2d-050505_boxes.xml b/data/models/mobile-robot/box-2d-050505_boxes.xml new file mode 100644 index 0000000..625ccf1 --- /dev/null +++ b/data/models/mobile-robot/box-2d-050505_boxes.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/models/mobile-robot/boxes-scenario1.wrl b/data/models/mobile-robot/boxes-scenario1.wrl new file mode 100644 index 0000000..76d5ef4 --- /dev/null +++ b/data/models/mobile-robot/boxes-scenario1.wrl @@ -0,0 +1,146 @@ +#VRML V2.0 utf8 +DEF room2 Transform { + children [ + DEF floor Transform { + translation 0 0 -0.05 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 1.0 1.0 1.0 + } + } + geometry Box { + size 5.2 5.2 0.1 + } + } + ] + } + DEF north Transform { + translation 0 2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF south Transform { + translation 0 -2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF west Transform { + translation -2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } + DEF east Transform { + translation 2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } + DEF box1 Transform { + translation -1 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1 1 + } + } + ] + } + DEF box2 Transform { + translation 0 -1 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1 1 + } + } + ] + } + #DEF box3 Transform { + # translation 0.75 0.75 0.5 + # children [ + # Shape { + # appearance Appearance { + # material Material { + # diffuseColor 0.0 0.0 0.0 + # } + # } + # geometry Box { + # size 1 1 1 + # } + # } + # ] + #} + DEF box4 Transform { + translation 1.7 0.8 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1.3 1 + } + } + ] + } + ] +} + diff --git a/data/models/mobile-robot/boxes.noObstacles.wrl b/data/models/mobile-robot/boxes.noObstacles.wrl new file mode 100644 index 0000000..b3434ad --- /dev/null +++ b/data/models/mobile-robot/boxes.noObstacles.wrl @@ -0,0 +1,146 @@ +#VRML V2.0 utf8 +DEF room2 Transform { + children [ + DEF floor Transform { + translation 0 0 -0.05 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 1.0 1.0 1.0 + } + } + geometry Box { + size 5.2 5.2 0.1 + } + } + ] + } + DEF north Transform { + translation 0 2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF south Transform { + translation 0 -2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF west Transform { + translation -2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } + DEF east Transform { + translation 2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } +# DEF box1 Transform { +# translation -1 0 0.5 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 0.0 +# } +# } +# geometry Box { +# size 1 1 1 +# } +# } +# ] +# } +# DEF box2 Transform { +# translation 0 -1 0.5 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 0.0 +# } +# } +# geometry Box { +# size 1 1 1 +# } +# } +# ] +# } + #DEF box3 Transform { + # translation 0.75 0.75 0.5 + # children [ + # Shape { + # appearance Appearance { + # material Material { + # diffuseColor 0.0 0.0 0.0 + # } + # } + # geometry Box { + # size 1 1 1 + # } + # } + # ] + #} +# DEF box4 Transform { +# translation 1.7 0.75 0.5 +# children [ +# Shape { +# appearance Appearance { +# material Material { +# diffuseColor 0.0 0.0 0.0 +# } +# } +# geometry Box { +# size 1 1 1 +# } +# } +# ] +# } + ] +} + diff --git a/data/models/mobile-robot/boxes.wrl b/data/models/mobile-robot/boxes.wrl new file mode 100644 index 0000000..0ea2f4a --- /dev/null +++ b/data/models/mobile-robot/boxes.wrl @@ -0,0 +1,146 @@ +#VRML V2.0 utf8 +DEF room2 Transform { + children [ + DEF floor Transform { + translation 0 0 -0.05 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 1.0 1.0 1.0 + } + } + geometry Box { + size 5.2 5.2 0.1 + } + } + ] + } + DEF north Transform { + translation 0 2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF south Transform { + translation 0 -2.55 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 5.2 0.1 1 + } + } + ] + } + DEF west Transform { + translation -2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } + DEF east Transform { + translation 2.55 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.0 + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 0.1 5 1 + } + } + ] + } + DEF box1 Transform { + translation -1 0 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1 1 + } + } + ] + } + DEF box2 Transform { + translation 0 -1 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1 1 + } + } + ] + } + #DEF box3 Transform { + # translation 0.75 0.75 0.5 + # children [ + # Shape { + # appearance Appearance { + # material Material { + # diffuseColor 0.0 0.0 0.0 + # } + # } + # geometry Box { + # size 1 1 1 + # } + # } + # ] + #} + DEF box4 Transform { + translation 1.7 0.75 0.5 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.0 0.0 0.0 + } + } + geometry Box { + size 1 1 1 + } + } + ] + } + ] +} + diff --git a/data/models/mobile-robot/mobile-robot-kin.xml b/data/models/mobile-robot/mobile-robot-kin.xml new file mode 100644 index 0000000..1322fa1 --- /dev/null +++ b/data/models/mobile-robot/mobile-robot-kin.xml @@ -0,0 +1,94 @@ + + + + + 2D Box (0.5m x 0.5m x 0.5m) + + + 0 + 0 + 0 + + + 0 + 0 + 0.5 + + + + + + + + + 0 + 90 + 0 + + + 0 + 0 + 0 + + + + + + + + + + + + + + 0 + 0 + 0 + -90 + + 2.5 + -2.5 + + + + + + + + + + + + + 0 + -90 + 0 + 90 + + 2.5 + -2.5 + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + diff --git a/data/models/mobile-robot/mobile-robot-mdl.xml b/data/models/mobile-robot/mobile-robot-mdl.xml new file mode 100644 index 0000000..3921505 --- /dev/null +++ b/data/models/mobile-robot/mobile-robot-mdl.xml @@ -0,0 +1,118 @@ + + + + Jentzsch + Mobile + + + 0 + 0 + 0 + + + 0 + 0 + 0.5 + + + 0 + 0 + 9.86055 + + + + + + + + + + + + + + + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + + 0 + 90 + 0 + + + 0 + 0 + 0 + + + + + + + + 2.5 + -2.5 + + + + + + + + -90 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 2.5 + -2.5 + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + diff --git a/data/models/mobile-robot/mobile-robot-scenario1.wrl b/data/models/mobile-robot/mobile-robot-scenario1.wrl new file mode 100644 index 0000000..f0d462b --- /dev/null +++ b/data/models/mobile-robot/mobile-robot-scenario1.wrl @@ -0,0 +1,158 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF box-2d-050505 Transform { + translation 1.9 1.9 0.5 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.2 + diffuseColor 1.0 1.0 0.0 + } + } + geometry Sphere { + radius 0.2 + #size 0.5 0.5 0.5 + } + } + ] + } + ] + } + DEF package1 Transform { + translation -2.0 0.3 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 1.0 0.0 0.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF package2 Transform { + translation 0.8 -0.1 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 1.0 0.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF package3 Transform { + translation -0.9 -0.9 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 0.0 1.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF package4 Transform { + translation -0.9 -0.9 0.5 + rotation 1 0 0 1.5707963 + children [ + DEF link0 Transform { + children [ + ] + } + DEF link1 Transform { + children [ + ] + } + DEF body1 Transform { + children [ + Shape { + appearance Appearance { + material Material { + transparency 0.3 + diffuseColor 0.0 1.0 1.0 + } + } + geometry Cylinder { + height 0.5 + radius 0.2 + } + } + ] + } + ] + } + DEF boxes Inline { + url "boxes-scenario1.wrl" + } + ] +} + diff --git a/data/models/mobile-robot/mobile-robot-scenario1.xml b/data/models/mobile-robot/mobile-robot-scenario1.xml new file mode 100644 index 0000000..443d8ef --- /dev/null +++ b/data/models/mobile-robot/mobile-robot-scenario1.xml @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/scripts/DamaRrt-graph.py b/data/scripts/DamaRrt-graph.py new file mode 100644 index 0000000..a016619 --- /dev/null +++ b/data/scripts/DamaRrt-graph.py @@ -0,0 +1,245 @@ +## in console: execfile('DamaRrt-graph.py') + +from math import sqrt +from itertools import izip +from numpy.random import randint +from functools import partial +from graph_tool.all import * + +def markEdges(g, v, e_prop): + for e in v.out_edges(): + e_prop[e] = 1 + markEdges(g, e.target(), e_prop) + +def getFirstIndex(g, v_prop, v_value): + for v in g.vertices(): + if v_prop[v] == v_value: + return g.vertex_index[v] + +## Load the meta properties from the meta file +lines = [line.strip() for line in open('DamaRrt-graph-meta')] +metaTwoTreeVersion = int(lines[0]) +metaFinished = 0 +metaEnd0Index = 0 +metaEnd1Index = 0 +if len(lines) > 1: + metaFinished = 1 + metaEnd0Index = int(lines[1]) + if metaTwoTreeVersion: + metaEnd1Index = int(lines[2]) +print 'metaTwoTreeVersion: ' + str(metaTwoTreeVersion) +print 'metaFinished: ' + str(metaFinished) +print 'metaEnd0Index: ' + str(metaEnd0Index) +print 'metaEnd1Index: ' + str(metaEnd1Index) + +## Load the graphs and retrieve the existing properties + +g = load_graph("DamaRrt-graph-0.xml") +g.set_directed(True) +num_vertices_g0 = g.num_vertices() +num_edges_g0 = g.num_edges() + +v_index = g.vertex_properties["index"] +v_q = g.vertex_properties["q"] +v_radius = g.vertex_properties["radius"] + +e_action = g.edge_properties["action"] + +if metaTwoTreeVersion: + g1 = load_graph("DamaRrt-graph-1.xml") + g1.set_directed(True) + num_vertices_g1 = g1.num_vertices() + num_edges_g1 = g1.num_edges() + + v1_index = g1.vertex_properties["index"] + v1_q = g1.vertex_properties["q"] + v1_radius = g1.vertex_properties["radius"] + + e1_action = g1.edge_properties["action"] + +## Add g1 to g to create the final connected-tree and create a new property storing the origin of the vertices (0, resp. 1) + +v_tree = g.new_vertex_property("bool") + +for v in g.vertices(): + v_tree[v] = 0 + +def copyTree(v1, v0): + v_index[v0] = v1_index[v1] + num_vertices_g0 + v_q[v0] = v1_q[v1] + v_radius[v0] = v1_radius[v1] + v_tree[v0] = 1 + for e1 in v1.out_edges(): + v0e = g.add_vertex() + e0 = g.add_edge(v0, v0e) + e_action[e0] = e1_action[e1] + copyTree(e1.target(), v0e) +if metaTwoTreeVersion: + for v1 in g1.vertices(): + if v1.in_degree() == 0: + v0 = g.add_vertex() + copyTree(v1, v0) +num_vertices_g = g.num_vertices() +num_edges_g = g.num_edges() + +g.vertex_properties["tree"] = v_tree + +## Print some information + +print 'Forward-Tree: ' + str(num_vertices_g0) + ' Vertices and ' + str(num_edges_g0) + ' Edges' +if metaTwoTreeVersion: + print 'Backward-Tree: ' + str(num_vertices_g1) + ' Vertices and ' + str(num_edges_g1) + ' Edges' + print '=> Compound Tree: ' + str(num_vertices_g) + ' Vertices and ' + str(num_edges_g) + ' Edges' + +## Create new properties: v_q2 and v_pos + +v_q2 = g.new_vertex_property("vector") +v_pos = g.new_vertex_property("vector") + +for v in g.vertices(): + v_q2[v] = map(float, v_q[v].split(',')) + v_pos[v] = v_q2[v][0:2] + v_pos[v][1] = -v_pos[v][1] + +g.vertex_properties["q2"] = v_q2 +g.vertex_properties["pos"] = v_pos + +## Calculate some vertices: v_end0, v_start0, v_end1, v_start1 + +if metaFinished: + v_end0 = g.vertex(getFirstIndex(g, v_index, metaEnd0Index)) + v = v_end0 + #print v_q2[v_end0] + while v.in_degree() > 0: + v = v.in_edges().next().source() + #print v_q2[v] + v_start0 = v + + if metaTwoTreeVersion: + v_end1 = g.vertex(getFirstIndex(g, v_index, metaEnd1Index + num_vertices_g0)) + v = v_end1 + #print v_q2[v_end1] + while v.in_degree() > 0: + v = v.in_edges().next().source() + #print v_q2[v] + v_start1 = v + +## Set filtering properties + +e_special = g.new_edge_property("bool") +for e in g.edges(): + if (v_q2[e.source()][4] == -1.0) and (v_q2[e.source()][5] == 1.5) and (v_q2[e.target()][4] == -1.0) and (v_q2[e.target()][5] == 1.5): + e_special[e] = 0 + else: + e_special[e] = 1 +g_special = GraphView(g, efilt=e_special) + +# Color edges according to the action +e_color = g.new_edge_property("string") +for e in g.edges(): + if e_action[e] == "Transit": + e_color[e] = "#000000" + elif e_action[e].endswith("Object 1"): + e_color[e] = "#ff0000" + elif e_action[e].endswith("Object 2"): + e_color[e] = "#00b500" + elif e_action[e].endswith("Object 3"): + e_color[e] = "#0000ff" + else: + e_color[e] = "#bdbf00" + +# Mark start, connection point, goal, direction (arrows) +v_size = g.new_vertex_property("int") +v_shape = g.new_vertex_property("string") +v_fill_color = g.new_vertex_property("string") +for v in g.vertices(): + v_size[v] = 0 + v_shape[v] = "circle" + v_fill_color[v] = "#000000" +if metaFinished: + v_size[v_start0] = 15 + v_shape[v_start0] = "double_circle" + if metaTwoTreeVersion: + v_size[v_end0] = 20 + v_shape[v_end0] = "square" + v_fill_color[v_end0] = "#d5801b" + v_size[v_start1] = 15 + v_shape[v_start1] = "circle" + else: + v_size[v_end0] = 15 + v_shape[v_end0] = "circle" +e_mid_marker = g.new_edge_property("string") +for e in g.edges(): + e_mid_marker[e] = "none" +if metaFinished: + e_mid_marker[v_end0.in_edges().next()] = "arrow" + v = v_end0 + while v != v_start0: + for e in v.in_edges(): + if e.source() == v_start0: + e_mid_marker[e] = "arrow" + v = e.source() + +# Strengthen edges belonging to the path from start to goal (= last added vertex) +e_size = g.new_edge_property("double") +for e in g.edges(): + e_size[e] = 0.5 +if metaFinished: + v = v_end0 + while v.in_degree() > 0: + for e in v.in_edges(): + e_size[e] = 5.0 + v = e.source() + if metaTwoTreeVersion: + v = v_end1 + while v.in_degree() > 0: + for e in v.in_edges(): + e_size[e] = 5.0 + v = e.source() + +e_action_transit = g.new_edge_property("bool") +for e in g.edges(): + if e_action[e] == "Transit": + e_action_transit[e] = 1 + else: + e_action_transit[e] = 0 +g_f2 = GraphView(g, efilt=e_action_transit) +g_f2.set_edge_filter(e_action_transit, inverted=False) + +e_tree = g.new_edge_property("bool") +for e in g.edges(): + if (v_tree[e.source()] == 0) and (v_tree[e.target()] == 0): + e_tree[e] = 1 + else: + e_tree[e] = 0 +g_f3 = GraphView(g, efilt=e_tree) +g_f3.set_edge_filter(e_tree, inverted=False) + +e_color_tree = g.new_edge_property("string") +for e in g.edges(): + if e_tree[e] == 0: + e_color_tree[e] = "#ff0000" + else: + e_color_tree[e] = "#0000ff" + +e_succ_of_v = g.new_edge_property("bool") +for e in g.edges(): + e_succ_of_v[e] = 0 +markEdges(g, g.vertex(0), e_succ_of_v) # mark here which vertex index +g_f4 = GraphView(g, efilt=e_succ_of_v) +g_f4.set_edge_filter(e_succ_of_v, inverted=False) + +## Draw the graph + +graph_draw(g, vertex_size=v_size, vertex_shape=v_shape, vertex_color="#000000", vertex_fill_color=v_fill_color, vertex_pen_width=1.7, pos=v_pos, edge_pen_width=e_size, edge_color=e_color, edge_marker_size=20, edge_start_marker="none", edge_mid_marker=e_mid_marker, edge_end_marker="none", output_size=(800, 800), output="graph-draw1.pdf") # increasing the output_size = zooming out = not good + +graph_draw(g, vertex_size=v_size, vertex_shape=v_shape, vertex_color="#000000", vertex_fill_color=v_fill_color, vertex_pen_width=1.7, pos=v_pos, edge_pen_width=e_size, edge_color=e_color, edge_marker_size=20, edge_start_marker="none", edge_mid_marker=e_mid_marker, edge_end_marker="none", display_props=[v_tree, v_index, v_q], display_props_size=15, output_size=(800, 800), geometry=(800, 800)) + +if metaTwoTreeVersion: + graph_draw(g, vertex_size=v_size, vertex_shape=v_shape, vertex_color="#000000", vertex_fill_color=v_fill_color, vertex_pen_width=1.7, pos=v_pos, edge_pen_width=e_size, edge_color=e_color_tree, edge_marker_size=20, edge_start_marker="none", edge_mid_marker=e_mid_marker, edge_end_marker="none", display_props=[v_tree, v_index, v_q], display_props_size=15, output_size=(800, 800), geometry=(800, 800)) + + graph_draw(g_f3, vertex_size=v_size, vertex_shape=v_shape, vertex_color="#000000", vertex_fill_color=v_fill_color, vertex_pen_width=1.7, pos=v_pos, edge_pen_width=e_size, edge_color=e_color, edge_marker_size=20, edge_start_marker="none", edge_mid_marker=e_mid_marker, edge_end_marker="none", display_props=[v_tree, v_index, v_q], display_props_size=15, output_size=(800, 800), geometry=(800, 800)) + + g_f3.set_edge_filter(e_tree, inverted=True) + + graph_draw(g_f3, vertex_size=v_size, vertex_shape=v_shape, vertex_color="#000000", vertex_fill_color=v_fill_color, vertex_pen_width=1.7, pos=v_pos, edge_pen_width=e_size, edge_color=e_color, edge_marker_size=20, edge_start_marker="none", edge_mid_marker=e_mid_marker, edge_end_marker="none", display_props=[v_tree, v_index, v_q], display_props_size=15, output_size=(800, 800), geometry=(800, 800)) diff --git a/data/scripts/LICENSE.md b/data/scripts/LICENSE.md new file mode 100644 index 0000000..08291cc --- /dev/null +++ b/data/scripts/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Sören Jentzsch +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/data/tasks-test/LICENSE.md b/data/tasks-test/LICENSE.md new file mode 100644 index 0000000..15442a5 --- /dev/null +++ b/data/tasks-test/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Andre Gaschler, Sören Jentzsch +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/data/tasks-test/kuka-transfer-3-objects.xml b/data/tasks-test/kuka-transfer-3-objects.xml new file mode 100644 index 0000000..6798b0b --- /dev/null +++ b/data/tasks-test/kuka-transfer-3-objects.xml @@ -0,0 +1,92 @@ + + + + + + + + + + + + + + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.6 + 0.12 + 0.55 + 0.61 + 0 + 0.55 + 0.45 + -0.1 + 0.55 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.2 + -0.5 + 0.55 + 0.03 + -0.5 + 0.55 + 0.37 + -0.5 + 0.55 + + + + + + + + + + + + + + + + + + 2.0 + 0.2 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks-test/meka-simple-push.xml b/data/tasks-test/meka-simple-push.xml new file mode 100644 index 0000000..55902e4 --- /dev/null +++ b/data/tasks-test/meka-simple-push.xml @@ -0,0 +1,97 @@ + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.35 + 0.146 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.3 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks-test/mobile-robot-move-blocked-object.xml b/data/tasks-test/mobile-robot-move-blocked-object.xml new file mode 100644 index 0000000..9575131 --- /dev/null +++ b/data/tasks-test/mobile-robot-move-blocked-object.xml @@ -0,0 +1,81 @@ + + + + + + + + + + + + + + + + 1.9 + 1.9 + -2.0 + 0.3 + 0.5 + 0.8 + -0.1 + 0.5 + -1.5 + -1.5 + 0.5 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.5 + 0.0 + 0.0 + 0.5 + -0.9 + -0.9 + 0.5 + + + + + + + + + + + + + + + + + + 0.05 + 0.35 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/LICENSE.md b/data/tasks/LICENSE.md new file mode 100644 index 0000000..bf1c2c1 --- /dev/null +++ b/data/tasks/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Sören Jentzsch, Andre Gaschler +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/data/tasks/kuka-scenario1.xml b/data/tasks/kuka-scenario1.xml new file mode 100644 index 0000000..ef57a0f --- /dev/null +++ b/data/tasks/kuka-scenario1.xml @@ -0,0 +1,92 @@ + + + + + + + + + + + + + + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.6 + 0.12 + 0.55 + 0.61 + 0 + 0.55 + 0.45 + -0.1 + 0.55 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.18 + -0.5 + 0.55 + 0.03 + -0.5 + 0.55 + 0.33 + -0.5 + 0.55 + + + + + + + + + + + + + + + + + + 2.0 + 0.2 + 1e-3 + 60 + + 200 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/kuka-scenario2.xml b/data/tasks/kuka-scenario2.xml new file mode 100644 index 0000000..7a9aa25 --- /dev/null +++ b/data/tasks/kuka-scenario2.xml @@ -0,0 +1,92 @@ + + + + + + + + + + + + + + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.6 + 0.12 + 0.55 + 0.61 + 0 + 0.55 + 0.45 + -0.1 + 0.55 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0.18 + -0.68 + 0.55 + 0.03 + -0.68 + 0.55 + 0.33 + -0.68 + 0.55 + + + + + + + + + + + + + + + + + + 2.0 + 0.2 + 1e-3 + 180 + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/kuka-test-push.xml b/data/tasks/kuka-test-push.xml new file mode 100644 index 0000000..81c0ee7 --- /dev/null +++ b/data/tasks/kuka-test-push.xml @@ -0,0 +1,94 @@ + + + + + + + + + + + + + + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + 0.6 + 0.12 + 0.55 + 0.61 + 0 + 0.55 + 0.45 + -0.1 + 0.55 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + 0.6 + 0.12 + 0.55 + 0.61 + 0 + 0.55 + 0.55 + -0.1 + 0.55 + + + + + + + + + + + + + + + + + + 2.0 + 0.2 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/meka-scenario1.xml b/data/tasks/meka-scenario1.xml new file mode 100644 index 0000000..0be492c --- /dev/null +++ b/data/tasks/meka-scenario1.xml @@ -0,0 +1,112 @@ + + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.16 + -0.35 + 0.146 + 0.0 + -0.2 + 0.196 + -0.1 + 0.4 + 0.196 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + + + 0.13 + -0.3 + 0.146 + + + 0.13 + -0.2 + 0.146 + + + 0.13 + -0.1 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + 600 + + 5 + + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/meka-simple-test.xml b/data/tasks/meka-simple-test.xml new file mode 100644 index 0000000..0cb32e6 --- /dev/null +++ b/data/tasks/meka-simple-test.xml @@ -0,0 +1,98 @@ + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.3 + 0.146 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.2 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/meka-simple.xml b/data/tasks/meka-simple.xml new file mode 100644 index 0000000..a235dea --- /dev/null +++ b/data/tasks/meka-simple.xml @@ -0,0 +1,97 @@ + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.3 + 0.146 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.0 + 0.146 + 0.0 + 0.2 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/meka-swap.xml b/data/tasks/meka-swap.xml new file mode 100644 index 0000000..fc8354a --- /dev/null +++ b/data/tasks/meka-swap.xml @@ -0,0 +1,98 @@ + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.1 + 0.146 + 0.0 + 0.3 + 0.146 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.3 + 0.146 + 0.0 + 0.1 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/meka-test.xml b/data/tasks/meka-test.xml new file mode 100644 index 0000000..f421049 --- /dev/null +++ b/data/tasks/meka-test.xml @@ -0,0 +1,98 @@ + + + + + + + + + + + + + + + + 0.0 + 0.0 + 0.0 + 0.0 + 15.0 + -20.0 + 12.0 + 112.0 + -10.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.2 + 0.146 + 0.0 + 0.3 + 0.146 + + + 0.0 + 0.0 + 0.0 + 85.0 + 30.0 + 0.0 + 5.0 + 90.0 + -30.0 + 0.0 + 0.0 + -0.4 + 0.146 + 0.0 + 0.15 + 0.146 + 0.0 + 0.0 + 0.146 + + + + + + + + + + + + + + + + + + 0.005 + 0.1 + 1e-3 + + + 1 + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/mobile-robot-scenario1.xml b/data/tasks/mobile-robot-scenario1.xml new file mode 100644 index 0000000..a920a3f --- /dev/null +++ b/data/tasks/mobile-robot-scenario1.xml @@ -0,0 +1,88 @@ + + + + + + + + + + + + + + 1.9 + 1.9 + -2.0 + 0.3 + 0.5 + 0.8 + -0.1 + 0.5 + -1.5 + -1.5 + 0.5 + 1.2 + 1.9 + 0.5 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.5 + 0.0 + 0.0 + 0.5 + -0.9 + -0.9 + 0.5 + 0.0 + 0.0 + 0.5 + + + + + + + + + + + + + + + + + + 0.05 + 0.35 + 1e-3 + 120 + + 1 + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/tasks/mobile-robot-test.xml b/data/tasks/mobile-robot-test.xml new file mode 100644 index 0000000..5331780 --- /dev/null +++ b/data/tasks/mobile-robot-test.xml @@ -0,0 +1,81 @@ + + + + + + + + + + + + + + + + 1.9 + 1.9 + -2.0 + 0.3 + 0.5 + 0.8 + -0.1 + 0.5 + -1.5 + -1.5 + 0.5 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.5 + 0.0 + 0.0 + 0.5 + -0.9 + -0.9 + 0.5 + + + + + + + + + + + + + + + + + + 0.05 + 0.35 + 1e-3 + 120 + + 30 + + + + + + + + + + + + + + + + + + + diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt new file mode 100644 index 0000000..990ae0e --- /dev/null +++ b/src/CMakeLists.txt @@ -0,0 +1,90 @@ +PROJECT(moplPlan) + +FIND_PACKAGE(Cgal REQUIRED) +FIND_PACKAGE(Coin REQUIRED) +FIND_PACKAGE(Eigen REQUIRED) +FIND_PACKAGE(LibXml2 REQUIRED) +FIND_PACKAGE(Boost COMPONENTS system REQUIRED) +FIND_PACKAGE(OpenGL REQUIRED) +FIND_PACKAGE(Qt4 REQUIRED) +FIND_PACKAGE(Solid REQUIRED) +FIND_PACKAGE(SoQt REQUIRED) + +find_package(RL 0.6.3 COMPONENTS KIN MDL SG PLAN REQUIRED) + + +ADD_DEFINITIONS( + -DCGAL_DISABLE_ROUNDING_MATH_CHECK + ${COIN_DEFINITIONS} +) + +INCLUDE_DIRECTORIES( + BEFORE + ${Boost_INCLUDE_DIR} + ${CGAL_INCLUDE_DIRS} + ${COIN_INCLUDE_DIRS} + ${EIGEN_INCLUDE_DIRS} + ${LIBXML2_INCLUDE_DIRS} +) + +LINK_DIRECTORIES( + ${Boost_LIBRARY_DIRS} +) + +SET( + HDRS + DamaRrtGoalBias.h + DamaRrtAction.h + DamaRrtCon.h + DamaModel.h + DamaPrim.h + DamaPrimPickup.h + DamaPrimPush.h + DamaPrimPushInterior.h + DamaPrimPushExterior.h + DamaPrimPushFrontal.h + DamaPrimPushMobile.h + DamaPrimTransferRigid.h + DamaPrimTransit.h + DamaRrt.h + DamaSampler.h + DamaSupportSurface.h + Timer.h + XmlFactory.h +) + +SET( + SRCS + DamaRrtGoalBias.cpp + DamaRrtAction.cpp + DamaRrtCon.cpp + DamaModel.cpp + DamaPrimPickup.cpp + DamaPrimPush.cpp + DamaPrimPushInterior.cpp + DamaPrimPushExterior.cpp + DamaPrimPushFrontal.cpp + DamaPrimPushMobile.cpp + DamaPrimTransferRigid.cpp + DamaPrimTransit.cpp + DamaRrt.cpp + DamaSampler.cpp + DamaSupportSurface.cpp + XmlFactory.cpp +) + +ADD_LIBRARY( + moplplan + SHARED + ${HDRS} + ${SRCS} +) + +TARGET_LINK_LIBRARIES( + moplplan + ${RL_LIBRARIES} + ${Boost_LIBRARIES} + ${CGAL_LIBRARIES} + ${COIN_LIBRARIES} + ${LIBXML2_LIBRARIES} +) diff --git a/src/DamaModel.cpp b/src/DamaModel.cpp new file mode 100644 index 0000000..fdcd7f9 --- /dev/null +++ b/src/DamaModel.cpp @@ -0,0 +1,1436 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include + +#include "DamaModel.h" + +#include + +namespace dama +{ + rl::math::Real DamaModel::ikPostureGainMaxStep = 20.0 * rl::math::DEG2RAD; + bool DamaModel::ikPrematureQuit = false; + + DamaModel::DamaModel() : + DistanceModel() + { + // TODO: currently no wraparound implemented -> affects (only?) DamaModel::interpolate and DamaModel::minDistanceToRectangle + + // temporary variables; will change during planning + this->timeIK = 0.0; + this->forwardSearch = true; + this->checkCollisionRobotObjects = true; + } + + DamaModel::~DamaModel() + { + } + + void DamaModel::printQLine(const ::rl::math::Vector& q, bool showDefinedState, bool addNewLine, bool printFullState, bool jointsInDeg, ::std::ostream& os) const + { + ::std::size_t robotDoF = 0; + if(NULL != this->kin) + robotDoF = this->kin->getDof(); + else + robotDoF = this->mdl->getDof(); + + for(::std::size_t i=0; iallRevoluteJoints) + os << (q(i) * rl::math::RAD2DEG); + else + os << q(i); + + if(showDefinedState) + os << " (" << this->currIsChosen.at(i) << ")"; + + if(i < q.size()-1) + { + if(i < robotDoF && printFullState) + os << " | "; + else + os << ", "; + } + } + if(addNewLine) + os << std::endl; + } + + void DamaModel::printTransform(::rl::math::Transform& t, bool addNewLine) const + { + rl::math::Transform::TranslationPart position = t.translation(); + rl::math::Vector3 orientation = t.rotation().eulerAngles(2, 1, 0).reverse(); + + ::std::cout << position.x() << " | " << position.y() << " | " << position.z() << " || " << (orientation.x() * rl::math::RAD2DEG) << " | " << (orientation.y() * rl::math::RAD2DEG) << " | " << (orientation.z() * rl::math::RAD2DEG); + + if(addNewLine) + std::cout << std::endl; + } + + ::std::size_t DamaModel::getDof() const + { + ::std::size_t sumDoF = 0; + if (NULL != this->kin) + { + sumDoF += this->numRobots * this->kin->getDof(); + } + else + { + sumDoF += this->numRobots * this->mdl->getDof(); + } + sumDoF += this->numObjects * this->dimObjects; + return sumDoF; + } + + ::std::size_t DamaModel::getDof(::std::size_t index) const + { + if(index < this->numRobots) + { + if (NULL != this->kin) + { + return this->kin->getDof(); + } + else + { + return this->mdl->getDof(); + } + } + else + return this->dimObjects; + } + + void DamaModel::getMaximum(::rl::math::Vector& maximum) const + { + std::cerr << "getMaximum() should not be used within DamaModel without specifying a subspace" << std::endl; + } + + void DamaModel::getMaximum(::rl::math::Vector& maximum, ::std::size_t subspace) const + { + if(subspace < this->numRobots) + { + if (NULL != this->kin) + { + this->kin->getMaximum(maximum); + } + else + { + this->mdl->getMaximum(maximum); + } + ::rl::math::Vector min(this->getDof(subspace)); + ::rl::math::Vector max(this->getDof(subspace)); + this->mdl->getMinimum(min); + this->mdl->getMaximum(max); + ::rl::math::Vector range = max - min; + maximum.segment(0, this->getDof(subspace)) -= (1.0 - this->kinematicSoftRangeScale) * range / 2; + //::std::cout << "Final Maximum:" << ::std::endl; + //::std::cout << maximum << ::std::endl; + } + else + { + for(::std::size_t i=0; idimObjects; i++) + { + maximum(i) = this->maximumObjects(i); + } + } + } + + void DamaModel::getMinimum(::rl::math::Vector& minimum) const + { + std::cerr << "getMinimum() should not be used within DamaModel without specifying a subspace" << std::endl; + } + + void DamaModel::getMinimum(::rl::math::Vector& minimum, ::std::size_t subspace) const + { + if(subspace < this->numRobots) + { + if (NULL != this->kin) + { + this->kin->getMinimum(minimum); + } + else + { + this->mdl->getMinimum(minimum); + } + ::rl::math::Vector min(this->getDof(subspace)); + ::rl::math::Vector max(this->getDof(subspace)); + this->mdl->getMinimum(min); + this->mdl->getMaximum(max); + ::rl::math::Vector range = max - min; + minimum.segment(0, this->getDof(subspace)) += (1.0 - this->kinematicSoftRangeScale) * range / 2; + //::std::cout << "Final Minimum:" << ::std::endl; + //::std::cout << minimum << ::std::endl; + } + else + { + for(::std::size_t i=0; idimObjects; i++) + { + minimum(i) = this->minimumObjects(i); + } + } + } + + bool DamaModel::isValid(const ::rl::math::Vector& q) const + { + if (NULL != this->kin) + { + return this->kin->isValid(this->getSubspace(q, 0)); + } + else + { + return this->mdl->isValid(this->getSubspace(q, 0)); + } + + // TODO: check also other subspaces + } + + ::rl::math::Vector DamaModel::getSubspace(const ::rl::math::Vector& q, ::std::size_t subspace) const + { + ::std::size_t currIndex = this->indexFromSubspace(subspace); + + ::rl::math::Vector res(this->getDof(subspace)); + + for(::std::size_t i=0; igetDof(subspace); ++i) + res(i) = q(currIndex+i); + + return res; + } + + ::std::size_t DamaModel::getNumMovableComponents() const + { + return this->numRobots + this->numObjects; + } + + ::rl::math::Real DamaModel::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + return this->inverseOfTransformedDistance(this->transformedDistance(q1, q2)); + } + + ::rl::math::Real DamaModel::inverseOfTransformedDistance(const ::rl::math::Real& d) const + { + return ::std::sqrt(d); + } + + ::rl::math::Real DamaModel::transformedDistance(const ::rl::math::Real& d) const + { + return ::std::pow(d, 2); + } + + ::rl::math::Real DamaModel::transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + ::rl::math::Real dist = 0; + ::rl::math::Vector q2Full(this->getDof()); + this->completePartialSample(q2, q1, q2Full); + + // return max distance if the completed full sample has two (or more) objects not on a support surface + bool anObjectIsNotOnSS = false; + ::std::size_t objectSubspaceNotOnSS = 0; + for(::std::size_t i=this->numRobots; igetNumMovableComponents(); ++i) + { + if(!this->isOnSupportSurface(q2Full, i)) + { + if(anObjectIsNotOnSS) + return ::std::numeric_limits< ::rl::math::Real >::max(); + anObjectIsNotOnSS = true; + objectSubspaceNotOnSS = i; + } + } + // return max distance if the completed sample received an object not on a support surface but the robot pose was already set -> object won't be grasped! + if(anObjectIsNotOnSS && !this->currIsChosen.at(this->indexFromSubspace(objectSubspaceNotOnSS)) && this->currIsChosen.at(0)) + { + return ::std::numeric_limits< ::rl::math::Real >::max(); + } + + if(this->dRrt->getUseAccurateDistance()) + { + ::std::vector< ::rl::math::Vector > vecRes; + ::std::vector< ::std::string > vecEdgeAction; + ESP::Res res = this->emptySpacePlanner(vecRes, q1, q2Full, vecEdgeAction, false); + switch(res) + { + case ESP::OK: + for(::std::size_t u=0; u::max(); + break; + case ESP::ALREADY_THERE: + dist = 0; + break; + default: + std::cerr << "DamaModel::transformedDistance: Unhandled case of ESP::Res res." << std::endl; + } + dist = this->transformedDistance(dist); + } + else + { + ::rl::math::Real metMovingObjectPenalty; + ::rl::math::Real metMoveToObjectPenalty; + ::rl::math::Real metMoveToObjectFactor; + + if(this->metType == "MaxComponentMovement") + { + ::rl::math::Real maxDist = 0; + for(::std::size_t i=0; igetNumMovableComponents(); ++i) + { + ::rl::math::Real currSubspaceDist = this->metricSubspaceDistance(q1, q2Full, i); + if(currSubspaceDist > maxDist) + maxDist = currSubspaceDist; + } + dist = this->transformedDistance(maxDist); + } + else if(this->metType == "SumComponentMovementWithObjectPenalty") + { + for(::std::size_t i=0; igetNumMovableComponents(); ++i) + { + ::rl::math::Real currSubspaceDist = this->metricSubspaceDistance(q1, q2Full, i); + dist += currSubspaceDist; + + // if an object has to be moved, consider adding an extra penalty to the distance + if(i > 0 && currSubspaceDist > this->epsilon) + { + // add the moving object penalty only if object is on support surface on both configurations or if the robot first has to move to the object which is on a support surface + bool q1OnSS = this->isOnSupportSurface(q1, i); + bool q2OnSS = this->isOnSupportSurface(q2Full, i); + if((q1OnSS && q2OnSS) || (this->forwardSearch && q1OnSS && !q2OnSS) || (!this->forwardSearch && !q1OnSS && q2OnSS)) + dist += this->metMovingObjectPenalty; + } + } + dist = this->transformedDistance(dist); + } + else if(this->metType == "ForwardDistanceWithObjectPenalty") + { + // Andre's FK metric + // TODO: copy metricSubspaceDistance(q1, q2Full, 0) in this function, so you don't need to do the double FK twice! + rl::math::Transform robot_tool_from = this->calcForwardKinematics(q1.segment(0, this->getDof(0)), 0); + rl::math::Transform robot_tool_to = this->calcForwardKinematics(q2Full.segment(0, this->getDof(0)), 0); + dist = metricSubspaceDistance(q1, q2Full, 0); + for(::std::size_t i=1; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->indexFromSubspace(i); + rl::math::Vector object_from = q1.segment(offset, this->getDof(i)); + rl::math::Vector object_to = q2Full.segment(offset, this->getDof(i)); + rl::math::Real distance_object = (object_to - object_from).norm(); + if(distance_object > this->epsilon) + { + dist += this->metMovingObjectPenalty + distance_object; + rl::math::Real manip_eps = 0.08f; + rl::math::Real distance_from = (robot_tool_from.translation() - object_from).norm(); + if(distance_from > manip_eps) + { + dist += this->metMoveToObjectPenalty + this->metMoveToObjectFactor*distance_from; + } + rl::math::Real distance_to = (robot_tool_to.translation() - object_to).norm(); + if(distance_to > manip_eps) + { + dist += this->metMoveToObjectPenalty + this->metMoveToObjectFactor*distance_to; + } + } + } + } + else if(this->metType == "MiniESPMetricWithPenalties") + { + //::std::cout << "okay, here we go ..." << ::std::endl; + //printQLine(q1, true, true, true, true); + //printQLine(q2Full, true, true, true, true); + //while(std::cin.get()!='\n'); + + // TODO: consider forward/backward control?! + + // TODO: here we always add the robot traversal from start to goal although it might look stupid + dist = metricSubspaceDistance(q1, q2Full, 0); + + //::std::cout << "dist is: " << dist << ::std::endl; + //while(std::cin.get()!='\n'); + + ::std::vector vecObjectInGoal(this->getNumMovableComponents(), false); + ::std::vector vecObjectMoveDistance(this->getNumMovableComponents(), 0.0); + for(::std::size_t i=1; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->indexFromSubspace(i); + ::std::size_t dof = this->getDof(i); + vecObjectMoveDistance.at(i) = (q1.segment(offset, dof) - q2Full.segment(offset, dof)).norm(); + if(vecObjectMoveDistance.at(i) < this->epsilon) + vecObjectInGoal.at(i) = true; + } + + rl::math::Transform robotToolStart = this->calcForwardKinematics(q1.segment(0, this->getDof(0)), 0); + rl::math::Transform robotToolGoal = this->calcForwardKinematics(q2Full.segment(0, this->getDof(0)), 0); + rl::math::Vector currLocation = robotToolStart.translation(); + + ::std::size_t manipSubspace; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject = bestDistRobotObject; + bool manipAtLeastOnce = false; + bool allObjectsInGoal = false; + while(!allObjectsInGoal) + { + bestDistRobotObject = ::std::numeric_limits< double >::max(); + currDistRobotObject = bestDistRobotObject; + allObjectsInGoal = true; + + // search for the nearest object to be moved + for(::std::size_t i=1; igetNumMovableComponents(); ++i) + { + if(vecObjectInGoal.at(i)) + continue; + + allObjectsInGoal = false; + ::std::size_t offset = this->indexFromSubspace(i); + ::std::size_t dof = this->getDof(i); + currDistRobotObject = (currLocation - q1.segment(offset, dof)).norm(); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + manipSubspace = i; + } + } + + // found one -> traverse it! + if(!allObjectsInGoal) + { + // TODO: reasonable value ?! YEAH, for meka!! but what about the other robots ?! + // FIXME: this belons to the xml, also for the forwardMetric, there is the same value !! + rl::math::Real manipDist = 0.08f; + + ::std::size_t offset = this->indexFromSubspace(manipSubspace); + ::std::size_t dof = this->getDof(manipSubspace); + + //::std::cout << "traverse for moving object " << manipSubspace << ::std::endl; + //while(std::cin.get()!='\n'); + + dist += this->metMovingObjectPenalty + vecObjectMoveDistance.at(manipSubspace); + + //::std::cout << "dist is now: " << dist << ::std::endl; + //while(std::cin.get()!='\n'); + + if(currDistRobotObject > manipDist) + { + dist += this->metMoveToObjectPenalty + this->metMoveToObjectFactor*currDistRobotObject; + + //::std::cout << "dist is now (after move to object): " << dist << ::std::endl; + //while(std::cin.get()!='\n'); + } + + currLocation = q2Full.segment(offset, dof); + vecObjectInGoal.at(manipSubspace) = true; + manipAtLeastOnce = true; + } + } + + if(manipAtLeastOnce) + dist += (currLocation - robotToolGoal.translation()).norm(); + + //::std::cout << "final robot move to goal, dist final: " << dist << ::std::endl; + //while(std::cin.get()!='\n'); + } + else + std::cerr << "DamaModel::transformedDistance: no metric defined." << std::endl; + } + + return dist; + } + + ::rl::math::Real DamaModel::maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const + { + std::cout << "NOT IMPLEMENTED YET: call to maxDistanceToRectangle(vector): "; + this->printQLine(q, false, false); + std::cout << " with min: "; + this->printQLine(min, false, false); + std::cout << " with max: "; + this->printQLine(max, false, true); + while(std::cin.get()!='\n'); + + ::rl::math::Real d = 0; + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + if(!this->currIsChosen.at(i)) + continue; + + ::rl::math::Real delta = ::std::max(::std::fabs(q(i) - min(i)), ::std::fabs(q(i) - max(i))); + + /*if (this->joints[i]->wraparound) + { + ::rl::math::Real range = ::std::fabs(this->joints[i]->max - this->joints[i]->min); + d += this->transformedDistance(::std::max(delta, ::std::fabs(range - delta))); + } + else + { + d += this->transformedDistance(delta); + }*/ + + d += this->transformedDistance(delta); + } + + return d; + } + + ::rl::math::Real DamaModel::minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const + { + ::rl::math::Real d = 0; + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + if(this->currIsChosen.at(i) && (q(i) < min(i) || q(i) > max(i))) + d += this->transformedDistance(::std::min(::std::fabs(q(i) - min(i)), ::std::fabs(q(i) - max(i)))); + } + + /*std::cout << "call to minDistanceToRectangle(vector): "; + this->printQLine(q, false, false); + std::cout << " with min: "; + this->printQLine(min, false, false); + std::cout << " with max: "; + this->printQLine(max, false, false); + std::cout << " => final dist: " << d << std::endl; + while(std::cin.get()!='\n');*/ + + return d; + } + + // TODO: now this function will only be called if creating new bucket -> what if q is 0, i.e. not currently chosen ... ? currently just return 0 ... + ::rl::math::Real DamaModel::minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const + { + //std::cout << "call to minDistanceToRectangle: q = " << q << ", min = " << min << ", max = " << max << ", cuttingDimension = " << cuttingDimension << std::endl; + //while(std::cin.get()!='\n'); + + ::rl::math::Real d = 0; + + if (this->currIsChosen.at(cuttingDimension) && (q < min || q > max)) + { + ::rl::math::Real delta = ::std::min(::std::fabs(q - min), ::std::fabs(q - max)); + + /*if (this->joints[cuttingDimension]->wraparound) + { + ::rl::math::Real range = ::std::fabs(this->joints[cuttingDimension]->max - this->joints[cuttingDimension]->min); + ::rl::math::Real size = ::std::fabs(max - min); + d += ::std::min(delta, ::std::fabs(range - size - delta)); + } + else + { + d += delta; + }*/ + + d += delta; + } + + return d; + } + + ::rl::math::Real DamaModel::newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const + { + //std::cout << "call to newDistance" << std::endl; + //while(std::cin.get()!='\n'); + + return dist - this->transformedDistance(oldOff) + this->transformedDistance(newOff); + } + + ::std::size_t DamaModel::indexFromSubspace(::std::size_t subspace) const + { + ::std::size_t currIndex = 0; + + for(::std::size_t i=0; igetDof(i); + } + + return currIndex; + } + + ::rl::math::Real DamaModel::metricSubspaceDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::size_t subspace) const + { + if(subspace == 0) + { + rl::math::Real distResult = (q1.segment(0, this->getDof(0)) - q2.segment(0, this->getDof(0))).norm(); + + if(this->allRevoluteJoints) + { + distResult *= this->metRadToMeter; + rl::math::Transform T1 = this->calcForwardKinematics(q1.segment(0, this->getDof(0)), 0); + rl::math::Transform T2 = this->calcForwardKinematics(q2.segment(0, this->getDof(0)), 0); + rl::math::Real distCartesian = (T1.translation() - T2.translation()).norm(); + distResult += distCartesian; + ::rl::math::Quaternion quat1(T1.rotation()); + ::rl::math::Quaternion quat2(T2.rotation()); + ::rl::math::Real angDist = ::std::fabs(quat1.dot(quat2)); + if(angDist >= 1.0) // ATTENTION: somehow the Eigen dot product can become a bit larger than 1.0 !!! + angDist = 0.0; + else + angDist = 1.0 - angDist; + distResult += this->metQuatToMeter * angDist; + //weight * ::std::pow(2 * ::std::acos(::Eigen::internal::abs(quat1.dot(quat2))), 2); + // = nearly = + //weight * ::std::pow(quat1.angularDistance(quat2), 2); + } + + return (this->metOverallRobotWeight * distResult); + } + else + { + ::std::size_t offset = this->indexFromSubspace(subspace); + ::std::size_t dof = this->getDof(subspace); + + assert(subspace >= this->numRobots && subspace < this->getNumMovableComponents() && this->getDof(subspace) == 3); + + return (q1.segment(offset, dof) - q2.segment(offset, dof)).norm(); + } + } + + bool DamaModel::isMovingSubspace(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::size_t subspace) const + { + ::std::size_t offset = this->indexFromSubspace(subspace); + ::std::size_t dof = this->getDof(subspace); + + for(::std::size_t i=offset; i this->epsilon) + return true; + + return false; + } + + bool DamaModel::isMovingObject(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + for(::std::size_t i=this->getDof(0); i this->epsilon) + return true; + + return false; + } + + bool DamaModel::isMoving(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + for(::std::size_t i=0; i this->epsilon) + return true; + + return false; + } + + bool DamaModel::isGoal(const ::rl::math::Vector& q) const + { + for(::std::size_t i=0; idRrt->goalDimDefined->at(i) && ::std::fabs(q(i)-(*this->dRrt->goal)(i)) > this->epsilon) + return false; + + return true; + } + + ::rl::math::Real DamaModel::robotMovementDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + // TODO: maybe implement something more time-related, like the time needed to drive from q1 to q2 + + ::std::size_t dof = this->getDof(0); + rl::math::Real distJoints = (q1.segment(0, dof) - q2.segment(0, dof)).norm(); + + return distJoints; // TODO: this->metRadianInMeters * ? but only for all-joints-revolute robots + } + + ::rl::math::Real DamaModel::metricConnectInterpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + // TODO: maybe implement something more time-related, like the time needed to drive from q1 to q2 + + rl::math::Real dist = 0; + + for(::std::size_t i=0; i<1/*this->getNumMovableComponents()*/; ++i) + { + ::std::size_t offset = this->indexFromSubspace(i); + ::std::size_t dof = this->getDof(i); + + dist += (q1.segment(offset, dof) - q2.segment(offset, dof)).norm(); + if(i == 0 && this->allRevoluteJoints) + dist *= this->metRadToMeter; + } + + return dist; + } + + ::rl::math::Real DamaModel::cartesianRobotDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + { + rl::math::Transform T1 = this->calcForwardKinematics(q1.segment(0, this->getDof(0)), 0); + rl::math::Transform T2 = this->calcForwardKinematics(q2.segment(0, this->getDof(0)), 0); + + return (T1.translation() - T2.translation()).norm(); + } + + ::rl::math::Real DamaModel::cartesianRobotDistanceToObject(const ::rl::math::Transform& T, const ::rl::math::Vector& q, ::std::size_t subspace) const + { + assert(subspace >= this->numRobots && subspace < this->getNumMovableComponents() && this->getDof(subspace) == 3); + + ::std::size_t offset = this->indexFromSubspace(subspace); + + return ::std::sqrt( + ::std::pow(T.translation().x() - q(offset+0), 2) + + ::std::pow(T.translation().y() - q(offset+1), 2) + + ::std::pow(T.translation().z() - q(offset+2), 2) + ); + } + + const ::rl::math::Transform& DamaModel::calcForwardKinematics(const ::rl::math::Vector& q, const ::std::size_t positionIndex, ::rl::mdl::Dynamic* currMdl) const + { + if(currMdl == NULL) + currMdl = this->mdl; + + assert(q.size() == currMdl->getDof()); + + currMdl->setPosition(q); + currMdl->forwardPosition(); + + return currMdl->getOperationalPosition(positionIndex); + } + + bool + DamaModel::calcInversePositionTaskPosture(::rl::mdl::Kinematic* kin, const ::rl::math::Transform& x_target, ::rl::math::Vector& q_current, const rl::math::Matrix& task_space_projection, const bool coupleJoint1And2, const ::std::size_t& iterations, rl::math::Real limit_q_target_step_norm, rl::math::Real limit_q_posture_step_norm) + { + if(coupleJoint1And2) + { + return calcInversePositionTaskPostureMeka(kin, x_target, q_current, task_space_projection, iterations, limit_q_target_step_norm, limit_q_posture_step_norm); + } + + std::size_t dof = kin->getDof(); + + assert(q_current.size() == dof); + + //TODO currently add a little noise, work-around for degenerate toDelta at exact 180 deg rotation + ::rl::math::Vector noise = ::rl::math::Vector::Ones(q_current.size()) * ::rl::math::DEG2RAD; + + kin->setPosition(q_current + noise); + ::rl::math::Vector dx(6); + ::rl::math::Vector dq(dof); + ::rl::math::Vector qDelta(dof); + ::rl::math::Transform xi; + ::rl::math::Transform x = x_target; + ::rl::math::Real norm = 1; + ::rl::math::Real norm_target = 1.0e-3f; + ::rl::math::Real norm_qDelta; + rl::math::Vector q_normalized; + bool warning_written = false; + + /*::std::ofstream myfile; + myfile.open("iv-kin-new.data", std::ofstream::app); + myfile << "Calculate IK to T = ("; + rl::math::Transform::TranslationPart position = x.translation(); + rl::math::Vector3 orientation = x.rotation().eulerAngles(2, 1, 0).reverse(); + myfile << position.x() << " | " << position.y() << " | " << position.z() << " || " << (orientation.x() * rl::math::RAD2DEG) << " | " << (orientation.y() * rl::math::RAD2DEG) << " | " << (orientation.z() * rl::math::RAD2DEG); + myfile << ") starting at q_deg = (" << q_current.matrix().transpose() << ")" << std::endl;*/ + + // Posture Optimization (preprocessing steps) + + // Normalize angles on -1..+1 + rl::math::Vector kin_minimum(dof), kin_maximum(dof); + kin->getMinimum(kin_minimum); + kin->getMaximum(kin_maximum); + + rl::math::Vector kin_mean = (kin_minimum + kin_maximum) / 2; + rl::math::Vector kin_range = kin_maximum - kin_minimum; + + for (::std::size_t i = 0; i < iterations; ++i) + { + kin->forwardPosition(); + + //myfile << "Debug-inversePositionTaskPosture: q_current: " << q_current.transpose() << ::std::endl; + + xi = kin->getOperationalPosition(0); + ::rl::math::transform::toDelta(xi, x, dx, true); // useApproximation true for RL > 0.6.2 + + /*::std::cout << ::std::endl; + ::std::cout << "xi: " << ::std::endl; + ::std::cout << xi.matrix().transpose() << ::std::endl; + ::std::cout << "x: " << ::std::endl; + ::std::cout << x.matrix().transpose() << ::std::endl; + ::std::cout << "dx: " << ::std::endl; + ::std::cout << dx.matrix().transpose() << ::std::endl; + ::std::cout << "norm: " << ::std::endl; + ::std::cout << (task_space_projection * dx).norm() << ::std::endl; + ::std::cout << ::std::endl;*/ + + kin->calculateJacobian(); + ::rl::math::Matrix J = kin->getJacobian(); + + if(coupleJoint1And2) + J.col(1) = J.col(2); + + //myfile << "Debug-my: jacobian: " << J.matrix().transpose() << std::endl; + + kin->calculateJacobianInverse(1e-3, true); + ::rl::math::Matrix invJ = kin->getJacobianInverse(); + + // Joint space direction + dq = invJ * task_space_projection * dx; + + /*myfile << "Debug-my: dx: " << dx.matrix().transpose() << std::endl; + myfile << "Debug-my: this->invJ: " << invJ.matrix().transpose() << std::endl; + myfile << "Debug-my: task_space_projection: " << task_space_projection.matrix().transpose() << std::endl; + myfile << "Debug-my: dq: " << dq.matrix().transpose() << std::endl;*/ + + if(coupleJoint1And2) + dq(1) = dq(2) = (dq(1) + dq(2)) / 2; + + // Limit iteration according to reasonable step size + rl::math::Real limit_q_step_factor = dq.norm() / limit_q_target_step_norm; + if(limit_q_step_factor > 1) + dq /= limit_q_step_factor; + rl::math::Matrix null_space_projection = rl::math::Matrix::Identity(dof,dof) - (invJ * task_space_projection * J); + + // Posture Optimization + q_normalized = (q_current - kin_mean).cwiseQuotient(kin_range) * 2; + rl::math::Vector posture_update = -q_normalized.array() * q_normalized.array().abs() * DamaModel::ikPostureGainMaxStep; + rl::math::Vector dq_posture = null_space_projection * posture_update; + + if(coupleJoint1And2) + dq_posture(1) = dq_posture(2) = (dq_posture(1) + dq_posture(2)) / 2; + + //dq_posture += 1 * rl::math::DEG2RAD * posture_update; + + // Limit iteration according to reasonable step size + rl::math::Real limit_q_posture_step_factor = dq_posture.norm() / limit_q_posture_step_norm; + if(limit_q_posture_step_factor > 1) + dq_posture /= limit_q_posture_step_factor; + + qDelta = dq + dq_posture; + norm_qDelta = qDelta.norm(); + #if 0 + myfile << i << ": q: " << q_current.matrix().transpose() * rl::math::RAD2DEG << std::endl; + myfile << i << ": dx: " << dx.matrix().transpose() << std::endl; + //myfile << i << ": this->invJ: " << this->invJ << std::endl; + //myfile << i << ": task_space_projection: " << task_space_projection << std::endl; + myfile << i << ": dq: " << dq.matrix().transpose() << std::endl; + myfile << i << ": qDelta: " << qDelta.matrix().transpose() << std::endl; + myfile << i << ": norm_qDelta: " << norm_qDelta << std::endl; + //myfile << i << ": q_normalized: " << q_normalized.matrix().transpose() << std::endl; + myfile << i << ": posture_update: " << posture_update.matrix().transpose() << std::endl; + myfile << i << ": dq_posture: " << dq_posture.matrix().transpose() << std::endl; + myfile << i << ": (task_space_projection * dx).norm(): " << (task_space_projection * dx).norm() << std::endl; + myfile << i << ": posture_update.norm(): " << posture_update.norm() << std::endl; + #endif + /*q_current.matrix().transpose() * rl::math::RAD2DEG; + dx.matrix().transpose(); + //std::cout << "Debug: this->invJ: " << this->invJ << std::endl; + //std::cout << "Debug: task_space_projection: " << task_space_projection << std::endl; + dq.matrix().transpose(); + q_normalized.matrix().transpose(); + posture_update.matrix().transpose(); + dq_posture.matrix().transpose(); + (task_space_projection * dx).norm(); + posture_update.norm();*/ + q_current += qDelta; + /*if(norm_qDelta < 1e-6 && !warning_written) + { + //std::cerr << "Notice: IK in local minimum" << std::endl; // TODO: uncomment ?! + std::cout << "Debug: q: " << q_current.matrix().transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "Debug: dx: " << dx.matrix().transpose() << std::endl; + //std::cout << "Debug: this->invJ: " << this->invJ << std::endl; + //std::cout << "Debug: task_space_projection: " << task_space_projection << std::endl; + std::cout << "Debug: dq: " << dq.matrix().transpose() << std::endl; + std::cout << "Debug: q_normalized: " << q_normalized.matrix().transpose() << std::endl; + std::cout << "Debug: posture_update: " << posture_update.matrix().transpose() << std::endl; + std::cout << "Debug: dq_posture: " << dq_posture.matrix().transpose() << std::endl; + std::cout << "Debug: (task_space_projection * dx).norm(): " << (task_space_projection * dx).norm() << std::endl; + std::cout << "Debug: posture_update.norm(): " << posture_update.norm() << std::endl; + warning_written = true; + }*/ + kin->setPosition(q_current); + //std::cout << "q_current: " << q_current.matrix().transpose() * rl::math::RAD2DEG << std::endl; + norm = (task_space_projection * dx).norm(); + + if(norm_qDelta < 1e-8) + { + // Local minimum, not sure if valid + break; + } + + if(DamaModel::ikPrematureQuit) + { + //FIXME: check if joint angles are in valid range ?? + // or: if(norm < 3*norm_target && q_normalized.maxCoeff() < 1 && q_normalized.minCoeff() > -1) ?? + if(norm < norm_target && q_normalized.maxCoeff() < 0.9 && q_normalized.minCoeff() > -0.9) + { + // Use without further optimizing posture, generates different grasps wrt start value + return true; //break; + } + /*else + { + return false; + }*/ + } + } + + /*myfile << "calc-end" << std::endl; + myfile.close();*/ + + if(norm < norm_target) + { + return true; + } + + return false; + } + + bool + DamaModel::calcInversePositionTaskPostureMeka(::rl::mdl::Kinematic* kin, const ::rl::math::Transform& x_target, ::rl::math::Vector& q_current, const rl::math::Matrix& task_space_projection, const ::std::size_t& iterations, rl::math::Real limit_q_target_step_norm, rl::math::Real limit_q_posture_step_norm) + { + std::size_t dof = kin->getDof(); + + assert(q_current.size() == dof); + + //currently add a little noise, work-around for degenerate toDelta at exact 180 deg rotation + ::rl::math::Vector noise = ::rl::math::Vector::Ones(q_current.size()) * ::rl::math::DEG2RAD; + + kin->setPosition(q_current + noise); + ::rl::math::Vector dx(6); + ::rl::math::Vector dq(dof); + ::rl::math::Vector qDelta(dof); + ::rl::math::Transform xi; + ::rl::math::Transform x = x_target; + ::rl::math::Real norm = 1; + ::rl::math::Real norm_target = 1.0e-3f; + ::rl::math::Real norm_qDelta; + rl::math::Vector q_normalized; + bool warning_written = false; + + // Posture Optimization (preprocessing steps) + + // Normalize angles on -1..+1 + rl::math::Vector kin_minimum(dof), kin_maximum(dof); + kin->getMinimum(kin_minimum); + kin->getMaximum(kin_maximum); + + rl::math::Vector kin_mean = (kin_minimum + kin_maximum) / 2; + rl::math::Vector kin_range = kin_maximum - kin_minimum; + + ::rl::math::Matrix motor_to_joints = ::rl::math::Matrix::Zero(10, 9); + motor_to_joints.topLeftCorner(2, 2) = ::rl::math::Matrix::Identity(2, 2); + motor_to_joints.bottomRightCorner(8, 8) = ::rl::math::Matrix::Identity(8, 8); + + ::rl::math::Matrix joints_to_motor = ::rl::math::Matrix::Zero(9, 10); + joints_to_motor(0,0) = 1; + joints_to_motor(1,1) = joints_to_motor(1,2) = 0.5; + joints_to_motor.bottomRightCorner(7, 7) = ::rl::math::Matrix::Identity(7, 7); + + //std::cout << "Debug: motor_to_joints: " << std::endl << motor_to_joints.matrix() << std::endl; + //std::cout << "Debug: joints_to_motor: " << std::endl << joints_to_motor.matrix() << std::endl; + + for (::std::size_t i = 0; i < iterations; ++i) + { + kin->forwardPosition(); + + xi = kin->getOperationalPosition(0); + ::rl::math::transform::toDelta(xi, x, dx, false); // useApproximation for RL > 0.6.2 + + kin->calculateJacobian(); + ::rl::math::Matrix J_motor = kin->getJacobian() * motor_to_joints; + + ::rl::math::Real tolerance = 1e-8; + ::Eigen::JacobiSVD< ::rl::math::Matrix > svd(J_motor, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); + ::rl::math::Matrix s = ::rl::math::Matrix::Zero(svd.matrixV().cols(), svd.matrixU().rows()); + for(int i = 0; i < svd.singularValues().size(); ++i) + { + ::rl::math::Real sing = svd.singularValues()(i); + s(i,i) = (sing > tolerance) ? (1 / sing) : 0; + } + ::rl::math::Matrix invJ_motor = svd.matrixV() * s * svd.matrixU().transpose(); + + // Joint space direction + ::rl::math::Vector dq_motor = invJ_motor * task_space_projection * dx; + + dq = motor_to_joints * dq_motor; + + // Limit iteration according to reasonable step size + rl::math::Real limit_q_step_factor = dq.norm() / limit_q_target_step_norm; + if(limit_q_step_factor > 1) + dq /= limit_q_step_factor; + + + rl::math::Matrix null_space_projection = rl::math::Matrix::Identity(9, 9) - (invJ_motor * task_space_projection * J_motor); + + // Posture Optimization + q_normalized = (q_current - kin_mean).cwiseQuotient(kin_range) * 2; + rl::math::Vector posture_update = -q_normalized.array() * q_normalized.array().abs() * DamaModel::ikPostureGainMaxStep; + rl::math::Vector dq_posture = motor_to_joints * null_space_projection * joints_to_motor * posture_update; + + // Limit iteration according to reasonable step size + rl::math::Real limit_q_posture_step_factor = dq_posture.norm() / limit_q_posture_step_norm; + if(limit_q_posture_step_factor > 1) + dq_posture /= limit_q_posture_step_factor; + + qDelta = dq + dq_posture; + norm_qDelta = qDelta.norm(); + q_current += qDelta; + + kin->setPosition(q_current); + norm = (task_space_projection * dx).norm(); + + if(norm_qDelta < 1e-8) + { + // Local minimum, not sure if valid + break; + } + + if (DamaModel::ikPrematureQuit) + { + //FIXME: check if joint angles are in valid range ?? + // or: if(norm < 3*norm_target && q_normalized.maxCoeff() < 1 && q_normalized.minCoeff() > -1) ?? + if(norm < norm_target && q_normalized.maxCoeff() < 0.9 && q_normalized.minCoeff() > -0.9) + { + // Use without further optimizing posture, generates different grasps wrt start value + return true; //break; + } + } + } + + if(norm < norm_target) + { + return true; + } + + return false; + } + + /** Note: depends on this->currIsChosen !!! */ + void DamaModel::completePartialSample(const ::rl::math::Vector& samplePart, const ::rl::math::Vector& nearest, ::rl::math::Vector& sampleFull) const + { + // complete the values of sample using the values of 'nearest' if current currIsChosen is false + for(::std::size_t i=0; igetDof(); ++i) + { + if(!this->currIsChosen.at(i)) + { + assert(samplePart(i) == 0.0); + sampleFull(i) = nearest(i); + } + else + { + sampleFull(i) = samplePart(i); + } + } + } + + /** Note: depends on this->currIsChosen !!! */ + // TODO: "must be deterministic in the choice of useful primitives for multi-modal hierarchical planning" (-> PHD thesis barry) + ESP::Res DamaModel::emptySpacePlanner(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::vector< ::std::string >& vecEdgeAction, const bool usePreciseVersion) const + { + //std::cout << "emptySpacePlanner started ..." << std::endl; + + ::std::vector< DamaPrim* > vecDamaPrimRand(this->vecDamaPrim); + // TODO: just test if it yields another result if turned off, and if it is still deterministic inside + ::std::random_shuffle(vecDamaPrimRand.begin(), vecDamaPrimRand.end()); + + bool foundUsefulPrim = false; + ::std::vector vecDamaPrimFailed(this->vecDamaPrim.size(), false); + + const ::rl::math::Vector* qEnd; + + if(this->forwardSearch) + { + vecRes.push_back(q1); + qEnd = &q2; + } + else + { + vecRes.push_back(q2); + qEnd = &q1; + } + + do + { + foundUsefulPrim = false; + + for(::std::size_t i=0; iisUseful(vecRes.back(), *qEnd)) + { + if(this->debugMode) + std::cout << "* Found useful primitive: " << vecDamaPrimRand.at(i)->getName() << std::endl; + foundUsefulPrim = true; + + // TODO: somewhat hardcoded here, this config-information can also be stored in the node/vertex itself? + // TODO: STORE THE INFO (= whether the robot currently is in a grasp, push position of object x etc.) IN THE VERTICES ! + /*::std::size_t qStatus = 0; + const ::rl::math::Transform T = this->calcForwardKinematics(vecRes.back().segment(0, this->getDof(0)), 0); + if(usePreciseVersion) + { + for(::std::size_t u=this->numRobots; ugetNumMovableComponents(); ++u) + ... + qStatus = u; + }*/ + + if(!vecDamaPrimRand.at(i)->propagate(vecRes, *qEnd, vecEdgeAction)) + { + vecDamaPrimFailed.at(i) = true; + } + else + { + std::fill(vecDamaPrimFailed.begin(), vecDamaPrimFailed.end(), false); + } + + /*for(::std::size_t u=0; uprintQLine(qProp.at(u)); + }*/ + } + } + + /*std::cout << "~ List of Configuration Points: " << std::endl; + for(::std::size_t u=0; u> "; + this->printQLine(vecRes.at(u), false, false); + if(u < vecRes.size()-1) + std::cout << " [-> " << vecEdgeAction.at(u) << "]"; + std::cout << std::endl; + }*/ + + } while(foundUsefulPrim); + + //std::cout << "emptySpacePlanner done." << std::endl; + + // if we searched backwards, reverse the list -> nearestNeighbor is always first, sample is last element + if(!this->forwardSearch) + { + std::reverse(vecRes.begin(), vecRes.end()); + std::reverse(vecEdgeAction.begin(), vecEdgeAction.end()); + } + + // TODO: handle this case not here?! make it elsewhere, refactor and test it !!!!!?? + // If the robot's end position was not specified and the last state was due to 'Transit', skip the last state + // -> so the robot does not drive to the robot position of the nearest neighbor -> not needed! + /*if(!this->currIsChosen.at(0) && vecEdgeAction.back().compare(DamaPrimTransit::getInstance()->getName()) == 0) + { + vecRes.pop_back(); + vecEdgeAction.pop_back(); + }*/ + + /*this->printQLine(vecRes.back(), false, true); + this->printQLine(*qEnd, false, true); + ::std::cout << this->isMoving(vecRes.back(), *qEnd) << ::std::endl; + ::std::cout << this->getNumMovableComponents() << ::std::endl; + ::std::cout << this->metricSubspaceDistance(vecRes.back(), *qEnd, 2) << ::std::endl; + ::std::cout << this->metricSubspaceDistance(vecRes.back(), *qEnd, 3) << ::std::endl; + ::std::cout << this->epsilon << ::std::endl;*/ + + if(this->forwardSearch && this->isMoving(vecRes.back(), *qEnd)) + return ESP::UNREACHABLE; + else if(!this->forwardSearch && this->isMoving(vecRes.front(), *qEnd)) + return ESP::UNREACHABLE; + else if(vecRes.size() < 2) + return ESP::ALREADY_THERE; + else + return ESP::OK; + } + + void DamaModel::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q, ::std::string edgeAction) const + { + assert(q1.size() == this->getDof()); + assert(q2.size() == this->getDof()); + assert(alpha >= 0.0f); + assert(alpha <= 1.0f); + assert(q.size() == this->getDof()); + + for(::std::size_t i=0; igetDof(); ++i) + { + q(i) = (1.0f - alpha) * q1(i) + alpha * q2(i); + } + + if(edgeAction != "") + { + // for DamaPrimPickup and DamaPrimTransferRigid make the moved object attached to the grasp pose of the robot arm + if((edgeAction.substr(0, DamaPrimPickup::getInstance()->getName().size()) == DamaPrimPickup::getInstance()->getName()) || (edgeAction.substr(0, DamaPrimTransferRigid::getInstance()->getName().size()) == DamaPrimTransferRigid::getInstance()->getName())) + { + const ::rl::math::Transform T = this->calcForwardKinematics(q.segment(0, this->getDof(0)), 0, this->mdlGrasp); + + ::std::size_t primNameObjectNr = boost::lexical_cast< ::std::size_t >(edgeAction.substr(edgeAction.find_last_of(" ")+1)); + ::std::size_t startIndex = this->indexFromSubspace(primNameObjectNr); + + //std::cout << "hi, this is " << edgeAction << ", I change object " << primNameObjectNr << " from " << q(startIndex) << ", " << q(startIndex+1) << ", " << q(startIndex+2) << " to " << T.translation().x() << ", " << T.translation().y() << ", " << (T.translation().z() - DamaPrimPickup::HEIGHT_OFFSET_OBJECT) << std::endl; + + q(startIndex) = T.translation().x(); + q(startIndex+1) = T.translation().y(); + q(startIndex+2) = T.translation().z() - DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + } + } + + // TODO: under construction by Mr. Gaschler + //::rl::math::Transform toolQ1 = this->calcForwardKinematics(q1.segment(0, this->getDof(0)), 0, this->mdlGrasp); + //::rl::math::Transform toolQ = this->calcForwardKinematics(q.segment(0, this->getDof(0)), 0, this->mdlGrasp); + //::rl::math::Transform toolMotion = toolQ * toolQ1.inverse(); + } + + void DamaModel::setPosition(const ::rl::math::Vector& q) + { + for(::std::size_t i=0; igetNumMovableComponents(); ++i) + this->setPosition(q, i); + } + + void DamaModel::setPosition(const ::rl::math::Vector& q, ::std::size_t subspace) + { + if(subspace == 0) + { + if(NULL != kin) + { + assert(this->getSubspace(q, 0).size() == this->kin->getDof()); + this->kin->setPosition(this->getSubspace(q, 0)); + } + else + { + assert(this->getSubspace(q, 0).size() == this->mdl->getDof()); + + if(!this->isViewerModel) + { + /*::std::ofstream myfile("iv-kin.data", std::ofstream::app); + myfile.precision(18); + myfile << "Debug-DamaModel: setPosition start" << ::std::endl;*/ + this->mdl->setPosition(this->getSubspace(q, 0)); + //myfile << "Debug-DamaModel: setPosition end" << ::std::endl; + } + else + { + this->mdl->setPosition(this->getSubspace(q, 0)); + } + } + } + else + { + // draw the manipulable object + ::rl::math::Transform currT; + this->scene->getModel(subspace)->getBody(0)->getFrame(currT); + ::std::size_t startIndex = this->indexFromSubspace(subspace); + ::rl::math::Translation t(q(startIndex), q(startIndex+1), q(startIndex+2)); + currT.translation() = t.vector(); + this->scene->getModel(subspace)->getBody(0)->setFrame(currT); + } + } + + void DamaModel::updateFrames(const bool& doUpdateModel) + { + if(NULL != kin) + { + assert(this->model->getNumBodies() == this->kin->getBodies()); + + this->kin->updateFrames(); + + if (doUpdateModel) + { + for (::std::size_t i = 0; i < this->model->getNumBodies(); ++i) + { + this->model->getBody(i)->setFrame(this->kin->getFrame(i)); + } + } + } + else + { + assert(this->model->getNumBodies() == this->mdl->getBodies()); + + this->mdl->forwardPosition(); + + if (doUpdateModel) + { + for (::std::size_t i = 0; i < this->model->getNumBodies(); ++i) + { + this->model->getBody(i)->setFrame(this->mdl->getFrame(i)); + } + } + } + } + + bool DamaModel::isColliding(::std::string primName) + { + ++this->totalQueries; + + //this->checkCollisionRobotObjects = false; + + /*if ROBOT == 3 && SCENARIO > 1 //Andre's collision routine + ::rl::sg::SimpleScene* collision_scene = dynamic_cast< ::rl::sg::SimpleScene* >(this->scene); + ::rl::sg::Model *robot_model, *package1_model, *package2_model, *package3_model, *workspace_model; + robot_model = this->scene->getModel(0); + package1_model = this->scene->getModel(1); + package2_model = this->scene->getModel(2); + if(numObjects >= 3) + { + package3_model = this->scene->getModel(3); + workspace_model = this->scene->getModel(4); + } + else + { + workspace_model = this->scene->getModel(3); + } + //robot must not collide with itself, with an object or environment + for (int k = 0; k < robot_model->getNumBodies(); ++k) + { + for (int l = k + 1; l < robot_model->getNumBodies(); ++l) + { + if(this->mdl->areColliding(k, l)) + { + if(collision_scene->areColliding(robot_model->getBody(k), robot_model->getBody(l))) return true; + } + } + } + //robot must not collide with an object or environment + if(collision_scene->areColliding(robot_model, workspace_model)) return true; + if(primName != "Transfer-Rigid Object 1" && primName != "Pickup Object 1") + { + if(collision_scene->areColliding(robot_model, package1_model)) return true; + } + if(primName != "Transfer-Rigid Object 2" && primName != "Pickup Object 2") + { + if(collision_scene->areColliding(robot_model, package2_model)) return true; + } + if(numObjects >= 3) + { + if(primName != "Transfer-Rigid Object 3" && primName != "Pickup Object 3") + { + if(collision_scene->areColliding(robot_model, package3_model)) return true; + } + if(collision_scene->areColliding(package1_model, package2_model)) return true; + if(collision_scene->areColliding(package2_model, package3_model)) return true; + if(collision_scene->areColliding(package1_model, package3_model)) return true; + } + else + { + //objects must not collide with other objects or environment + if(collision_scene->areColliding(package1_model, package2_model)) return true; + } + return false;*/ + + + // set the right end-effector body depending on the current active primitive + ::std::size_t indexNumber = 0; + ::std::string primNameRaw = DamaPrimTransit::getInstance()->getName(); + ::std::size_t primNameObjectNr = 0; + if(primName.compare(DamaPrimTransit::getInstance()->getName()) != 0) + { + indexNumber = primName.find_last_of(" "); + primNameRaw = primName.substr(0,indexNumber); + primNameObjectNr = boost::lexical_cast< ::std::size_t >(primName.substr(indexNumber+1)); + } + //::std::cout << "process primitive " << primNameRaw << ::std::endl; + ::rl::sg::Body* myBody = NULL; + for(int i=0; ivecDamaPrim.size(); i++) + { + //::std::cout << dModel2->vecDamaPrim.at(i)->getName() << " == " << primNameRaw << " ??" << ::std::endl; + if(this->vecDamaPrim.at(i)->getName() == primNameRaw) + { + myBody = this->vecDamaPrim.at(i)->endEffectorBody; + break; + } + } + if(myBody != this->currEndEffectorBody) + { + //::std::cout << "isColliding: change to end-effector body " << myBody->getName() << ::std::endl; + this->scene->getModel(0)->remove(this->scene->getModel(0)->getBody(this->scene->getModel(0)->getNumBodies()-1)); + this->scene->getModel(0)->add(myBody); + this->currEndEffectorBody = myBody; + } + //::std::cout << "#bodies: " << dModel2->getBodies() << ::std::endl; + //::std::cout << "#shapes of last body '" << dModel2->getBody(dModel2->getBodies())->getName() << "': " << dModel2->getBody(dModel2->getBodies())->getNumShapes() << ::std::endl; + //::std::cout << "#shapes of second last body '" << dModel2->getBody(dModel2->getBodies()-1)->getName() << "': " << dModel2->getBody(dModel2->getBodies()-1)->getNumShapes() << ::std::endl; + //::rl::sg::so::Scene* sceneVis = static_cast< ::rl::sg::so::Scene* >(dModel2->scene); + //MainWindow::instance()->viewer->viewer->setSceneGraph(sceneVis->root); + + + + + // go through bodies of my model (box-2d-050505): link0, link1, body1 + for (::std::size_t i = 0; i < this->model->getNumBodies(); ++i) + { + if (this->isColliding(i)) + { + // go through: box-2d-050505, package1, package2, package3, boxes + for (::rl::sg::Scene::Iterator j = this->scene->begin(); j != this->scene->end(); ++j) + { + // only check collision of the own model with the model 'boxes' + ::rl::sg::Model* currModel = *j; + if (this->model != *j) + { + if(this->checkCollisionRobotObjects || (!this->checkCollisionRobotObjects && (currModel->getName() != "package1" && currModel->getName() != "package2" && currModel->getName() != "package3"))) + { + // go through bodies of the current model: ... + for (::rl::sg::Model::Iterator k = (*j)->begin(); k != (*j)->end(); ++k) + { + if (dynamic_cast< ::rl::sg::SimpleScene* >(this->scene)->areColliding(this->model->getBody(i), *k)) + { + this->body = i; + return true; + } + } + } + } + } + } + + // check for self-collision of the bodies of the own model + + for (::std::size_t j = 0; j < i; ++j) + { + if (this->areColliding(i, j)) + { + if (dynamic_cast< ::rl::sg::SimpleScene* >(this->scene)->areColliding(this->model->getBody(i), this->model->getBody(j))) + { + this->body = i; + return true; + } + } + } + } + + // if not using the primitive "Transit", then also check for object-collisions + if(primName.compare(DamaPrimTransit::getInstance()->getName()) != 0) + { + // moved object (primNameObjectNr) should not collide with the other ones and also not with the scene + for(::std::size_t j=this->numRobots; jgetNumMovableComponents(); ++j) + { + if(primNameObjectNr != j && dynamic_cast< ::rl::sg::SimpleScene* >(this->scene)->areColliding(this->scene->getModel(primNameObjectNr), this->scene->getModel(j))) + return true; + } + + if(dynamic_cast< ::rl::sg::SimpleScene* >(this->scene)->areColliding(this->scene->getModel(primNameObjectNr), this->scene->getModel(this->getNumMovableComponents()))) + return true; + } + + this->body = this->getBodies(); + ++this->freeQueries; + return false; + } + + bool DamaModel::isCollidingWithScene(::std::size_t subspace) + { + ++this->totalQueries; + if(dynamic_cast< ::rl::sg::SimpleScene* >(this->scene)->areColliding(this->scene->getModel(subspace), this->scene->getModel(this->getNumMovableComponents()))) + return true; + ++this->freeQueries; + return false; + } + + bool DamaModel::isOnSupportSurface(const ::rl::math::Vector& q, const ::std::size_t subspace, ::std::size_t* supportSurface) const + { + ::std::size_t offset = this->indexFromSubspace(subspace); + + for(::std::size_t s=0; svecSupportSurface.size(); ++s) + { + // TODO: epsilon should be higher than this->epsilon, otherwise I had the case of transferring without picking up before, due to "false" intermediate vertices + if((::std::fabs(q(offset+2) - this->vecSupportSurface.at(s)->getHeight()) < 1.0e-4f) && + (q(offset) >= this->vecSupportSurface.at(s)->getMin(0)-this->epsilon && q(offset) <= this->vecSupportSurface.at(s)->getMax(0)+this->epsilon) && + (q(offset+1) >= this->vecSupportSurface.at(s)->getMin(1)-this->epsilon && q(offset+1) <= this->vecSupportSurface.at(s)->getMax(1)+this->epsilon)) + { + if(supportSurface != NULL) + *supportSurface = s; + return true; + } + } + + return false; + } + + void DamaModel::updateRobotPosition(::rl::math::Vector& q, ::rl::mdl::Dynamic* myMdl) + { + rl::math::Vector robotPos(this->getDof(0));// = q.segment(0, ); + if(myMdl == NULL) + this->mdl->getPosition(robotPos); + else + myMdl->getPosition(robotPos); + q.segment(0, this->getDof(0)) = robotPos; + } +} diff --git a/src/DamaModel.h b/src/DamaModel.h new file mode 100644 index 0000000..70c8b62 --- /dev/null +++ b/src/DamaModel.h @@ -0,0 +1,243 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAMODEL_H_ +#define _DAMA_DAMAMODEL_H_ + +#include +#include +#include +#include +#include + +#include "DamaRrt.h" +#include "DamaSupportSurface.h" +#include "DamaPrimPickup.h" +#include "DamaPrimPushExterior.h" +#include "DamaPrimPushInterior.h" +#include "DamaPrimPushFrontal.h" +#include "DamaPrimPushMobile.h" +#include "DamaPrimTransferRigid.h" +#include "DamaPrimTransit.h" +#include "Timer.h" + +namespace dama +{ + namespace ESP + { + enum Res {OK, UNREACHABLE, ALREADY_THERE}; + static const int nRes = 3; + static const char * cRes[nRes] = {"OK", "UNREACHABLE", "ALREADY_THERE"}; + } + + class DamaModel : public ::rl::plan::DistanceModel + { + public: + DamaModel(); + + virtual ~DamaModel(); + + virtual void printQLine(const ::rl::math::Vector& q, bool showDefinedState = false, bool addNewLine = true, bool printFullState = false, bool jointsInDeg = true, ::std::ostream& os = ::std::cout) const; + + virtual void printTransform(::rl::math::Transform& t, bool addNewLine = true) const; + + virtual ::std::size_t getDof() const; + + virtual ::std::size_t getDof(::std::size_t index) const; + + virtual void getMaximum(::rl::math::Vector& maximum) const; + + virtual void getMaximum(::rl::math::Vector& maximum, ::std::size_t subspace) const; + + virtual void getMinimum(::rl::math::Vector& minimum) const; + + virtual void getMinimum(::rl::math::Vector& minimum, ::std::size_t subspace) const; + + virtual bool isValid(const ::rl::math::Vector& q) const; + + virtual ::rl::math::Vector getSubspace(const ::rl::math::Vector& q, ::std::size_t subspace) const; + + virtual ::std::size_t getNumMovableComponents() const; + + virtual ::rl::math::Real distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual ::rl::math::Real inverseOfTransformedDistance(const ::rl::math::Real& d) const; + + virtual ::rl::math::Real transformedDistance(const ::rl::math::Real& d) const; + + virtual ::rl::math::Real transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual ::rl::math::Real maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; + + virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; + + virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const; + + virtual ::rl::math::Real newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const; + + virtual ::std::size_t indexFromSubspace(::std::size_t subspace) const; + + virtual ::rl::math::Real metricSubspaceDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::size_t subspace) const; + + virtual bool isMovingSubspace(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::size_t subspace) const; + + virtual bool isMovingObject(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual bool isMoving(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual bool isGoal(const ::rl::math::Vector& q) const; + + virtual ::rl::math::Real robotMovementDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual ::rl::math::Real metricConnectInterpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual ::rl::math::Real cartesianRobotDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + + virtual ::rl::math::Real cartesianRobotDistanceToObject(const ::rl::math::Transform& T, const ::rl::math::Vector& q, ::std::size_t subspace) const; + + virtual const ::rl::math::Transform& calcForwardKinematics(const ::rl::math::Vector& q, const ::std::size_t positionIndex, ::rl::mdl::Dynamic* currMdl = NULL) const; + + static bool calcInversePositionTaskPosture(::rl::mdl::Kinematic* kin, + const ::rl::math::Transform& x_target, + ::rl::math::Vector& q_current, + const rl::math::Matrix& task_space_projection = rl::math::Matrix::Identity(6,6), + const bool coupleJoint1And2 = true, + const ::std::size_t& iterations = 100, + rl::math::Real limit_q_target_step_norm = 30 * rl::math::DEG2RAD, + rl::math::Real limit_q_posture_step_norm = 30 * rl::math::DEG2RAD + ); + + static bool calcInversePositionTaskPostureMeka(::rl::mdl::Kinematic* kin, + const ::rl::math::Transform& x_target, + ::rl::math::Vector& q_current, + const rl::math::Matrix& task_space_projection = rl::math::Matrix::Identity(6,6), + const ::std::size_t& iterations = 100, + rl::math::Real limit_q_target_step_norm = 30 * rl::math::DEG2RAD, + rl::math::Real limit_q_posture_step_norm = 30 * rl::math::DEG2RAD + ); + + virtual void completePartialSample(const ::rl::math::Vector& samplePart, const ::rl::math::Vector& nearest, ::rl::math::Vector& sampleFull) const; + + virtual ESP::Res emptySpacePlanner(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, ::std::vector< ::std::string >& vecEdgeAction, const bool usePreciseVersion = false) const; + + virtual void interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q, ::std::string edgeAction = "") const; + + virtual void setPosition(const ::rl::math::Vector& q); + + virtual void setPosition(const ::rl::math::Vector& q, ::std::size_t subspace); + + virtual void updateFrames(const bool& doUpdateModel = true); + + using Model::isColliding; + + virtual bool isColliding(::std::string primName = DamaPrimTransit::getInstance()->getName()); + + virtual bool isCollidingWithScene(::std::size_t subspace); + + virtual bool isOnSupportSurface(const ::rl::math::Vector& q, const ::std::size_t subspace, ::std::size_t* supportSurface = NULL) const; + + virtual void updateRobotPosition(::rl::math::Vector& q, ::rl::mdl::Dynamic* myMdl = NULL); + + DamaRrt* dRrt; + + // task description names + ::std::string prefixName; + ::std::string description; + + ::std::size_t numRobots; // number of robots + ::std::size_t numObjects; // number of objects + ::std::size_t dimObjects; // dimensions of each object (= DoF) + + ::rl::math::Vector maximumObjects; // vector containing max. joint values for the objects + ::rl::math::Vector minimumObjects; // vector containing min. joint values for the objects + + ::std::vector< DamaSupportSurface* > vecSupportSurface; + + ::rl::math::Real epsilon; // distance threshold for equal-check in configuration comparison + ::rl::math::Real epsilonTransformed; // distance threshold for equal-check in configuration comparison + + ::rl::math::Real timeIK; // store the time needed for IK + + ::std::string seedType; + unsigned int groupSeed; + ::std::size_t singleSeed; + + ::std::size_t numRuns; // number of runs of the same problem given the group seed + + bool debugMode; // TODO: not so nice to store it here ... + + bool workspaceSampling; // TODO: not so nice to store it here ... + ::std::size_t workspaceSamplingEdges; // TODO: not so nice to store it here ... + + double kinematicSoftRangeScale; + + ::std::vector currIsChosen; // TODO: not so nice to store it here ... + bool forwardSearch; // TODO: not so nice to store it here ... + bool checkCollisionRobotObjects; // TODO: not so nice to store it here ... + bool allRevoluteJoints; // TODO: not so nice to store it here ... + bool allPrismaticJoints; // TODO: not so nice to store it here ... + bool coupleJoint1And2; // TODO: not so nice to store it here ... + + // for dRrt config stuff + bool bidirectional; + bool hierarchical; + bool accurateDistance; + + // for hierarchical planning only + ::rl::math::Real objectPathTimeout; + ::rl::math::Real subProblemTimeout; + + bool isViewerModel; // TODO: delete me later after debugging ... + + // Metric-related for Robot + ::rl::math::Real metRadToMeter; + ::rl::math::Real metQuatToMeter; + ::rl::math::Real metOverallRobotWeight; + + // Metric-related for composed space + ::std::string metType; + ::rl::math::Real metMovingObjectPenalty; + ::rl::math::Real metMoveToObjectPenalty; + ::rl::math::Real metMoveToObjectFactor; + + // Sample-related constants + ::rl::math::Real sampleRobotPoseProb; + ::rl::math::Real sampleObjectsFreeProb; + ::rl::math::Real sampleRobotRandProb; + + // IK-related + static rl::math::Real ikPostureGainMaxStep; // reasonable maximum step per iteration + static bool ikPrematureQuit; // not further optimizing posture, generates different grasps wrt start value + + // PostProc + bool pathSmoothing; + bool extendPushes; + + // Viewer-related + ::std::string viewerMode; + ::std::string viewerOnlyResult; + bool showFullTree; + bool showExportableTree; + double pointSize; + double lineWidth; + double speedFactor; + + ::rl::mdl::Dynamic* mdlGrasp; // second mdl file for alternative operational points + + // Primitives and Collision-Detection-related (-> individual end-effector bodies) + ::std::vector< DamaPrim* > vecDamaPrim; // Thread.cpp needs it to be public ... + ::std::size_t numEndEffectorBodies; + // TODO: only have one currEndEffectorBody, replace the vis one by using also the default one, should work according to Andre + ::rl::sg::Body* currEndEffectorBody; + ::rl::sg::so::Body* currEndEffectorBodyVis; + + protected: + + private: + + }; +} + +#endif /* _DAMA_DAMAMODEL_H_ */ diff --git a/src/DamaPrim.h b/src/DamaPrim.h new file mode 100644 index 0000000..ce1d989 --- /dev/null +++ b/src/DamaPrim.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIM_H_ +#define _DAMA_DAMAPRIM_H_ + +#include +#include +#include +#include + +namespace dama +{ + class DamaModel; + + class DamaPrim + { + public: + virtual ~DamaPrim() {} + + virtual ::std::string getName() const = 0; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) = 0; + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) = 0; + virtual ::rl::math::Transform getToolObjectTransform() = 0; + + ::rl::sg::Body* endEffectorBody; + ::rl::sg::so::Body* endEffectorBodyVis; + DamaModel* dModel; + }; +} + +#endif /* _DAMA_DAMAPRIM_H_ */ diff --git a/src/DamaPrimPickup.cpp b/src/DamaPrimPickup.cpp new file mode 100644 index 0000000..59fe20f --- /dev/null +++ b/src/DamaPrimPickup.cpp @@ -0,0 +1,211 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPickup.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + // default values + rl::math::Real DamaPrimPickup::HEIGHT_OFFSET_OBJECT = 0; + rl::math::Real DamaPrimPickup::HEIGHT_PICKUP_DIST_OBJECT = 0.10; + rl::math::Real DamaPrimPickup::MIN_PLANE_DIST_FOR_PICKUP = 0.20; + rl::math::Real DamaPrimPickup::PICKUP_Z_AXIS = 45 * rl::math::DEG2RAD; + rl::math::Real DamaPrimPickup::PICKUP_Y_AXIS = 90 * rl::math::DEG2RAD; + rl::math::Real DamaPrimPickup::PICKUP_X_AXIS = 180 * rl::math::DEG2RAD; + + ::std::string DamaPrimPickup::getName() const + { + return "Pickup Object"; + } + + bool DamaPrimPickup::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + bool foundObjectForPickup = false; + + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlaneTransformed = ::std::pow(startState(offset+0) - endState(offset+0), 2) + ::std::pow(startState(offset+1) - endState(offset+1), 2); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(this->dModel->isOnSupportSurface(startState, i)) + { + if(distHeight > 1.0e-4f/*dModel->epsilon*/ || dModel->inverseOfTransformedDistance(distPlaneTransformed) > DamaPrimPickup::MIN_PLANE_DIST_FOR_PICKUP) + foundObjectForPickup = true; + } + else + return false; + } + + return foundObjectForPickup; + } + + bool DamaPrimPickup::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0, this->dModel->mdlGrasp); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlaneTransformed = ::std::pow(startState(offset+0) - endState(offset+0), 2) + ::std::pow(startState(offset+1) - endState(offset+1), 2); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(distHeight > 1.0e-4f/*dModel->epsilon*/ || dModel->inverseOfTransformedDistance(distPlaneTransformed) > DamaPrimPickup::MIN_PLANE_DIST_FOR_PICKUP) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimPickup::propagate: pickup object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") towards (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + // calculate the robot grasp start position + rl::math::Transform T1_grasp; + T1_grasp.translation().x() = startState(indexObject); + T1_grasp.translation().y() = startState(indexObject+1); + T1_grasp.translation().z() = startState(indexObject+2) + DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T1_grasp.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 0; + + rl::math::Vector q_ik_start1 = startState.segment(0, dModel->getDof(0)); + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK1 to T = ("; + this->dModel->printTransform(T1_grasp, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start1 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + timerIK.start(); + bool calcInverse1a = DamaModel::calcInversePositionTaskPosture(dModel->mdlGrasp, T1_grasp, q_ik_start1, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + if(!calcInverse1a) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK1 failed. Exit." << ::std::endl; + return false; + } + + ::rl::math::Vector interConf1(startState); + this->dModel->updateRobotPosition(interConf1, this->dModel->mdlGrasp); + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK1 succeeded with q_deg = ("; + this->dModel->printQLine(interConf1, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + // first move to the pushing position if not already there + if(dModel->isMovingSubspace(startState, interConf1, 0)) + { + // TODO: investigate why algorithm currently needs about 5.7% more time just by using the uncommented code instead of the one in comments?! + //vecResSim.push_back(interConf1); + //vecEdgeActionSim.push_back(DamaPrimTransit::getInstance()->getName()); + DamaPrimTransit::getInstance()->propagate(vecResSim, interConf1, vecEdgeActionSim); + } + + // calculate the robot pickup end position + rl::math::Transform T2_pickup; + T2_pickup.translation().x() = startState(indexObject); + T2_pickup.translation().y() = startState(indexObject+1); + T2_pickup.translation().z() = startState(indexObject+2) + DamaPrimPickup::HEIGHT_PICKUP_DIST_OBJECT + DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T2_pickup.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Vector q_ik_start2 = interConf1.segment(0, dModel->getDof(0)); + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK2 to T = ("; + this->dModel->printTransform(T2_pickup, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start2 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + timerIK.start(); + bool calcInverse2 = DamaModel::calcInversePositionTaskPosture(dModel->mdlGrasp, T2_pickup, q_ik_start2, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(!calcInverse2) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK2 failed. Exit." << ::std::endl; + return false; + } + + // now pickup the object + ::rl::math::Vector interConf2(startState); + this->dModel->updateRobotPosition(interConf2, this->dModel->mdlGrasp); + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK2 succeeded with q_deg = ("; + this->dModel->printQLine(interConf2, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + interConf2(indexObject+2) += DamaPrimPickup::HEIGHT_PICKUP_DIST_OBJECT; + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + /*::rl::math::Vector* test = NULL; + test->normalize();*/ + + return true; + } + + ::rl::math::Transform DamaPrimPickup::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimPickup.h b/src/DamaPrimPickup.h new file mode 100644 index 0000000..fd8e004 --- /dev/null +++ b/src/DamaPrimPickup.h @@ -0,0 +1,47 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPICKUP_H_ +#define _DAMA_DAMAPRIMPICKUP_H_ + +#include "DamaPrim.h" + +namespace dama +{ + class DamaPrimPickup : public DamaPrim + { + public: + static DamaPrimPickup* getInstance() + { + static DamaPrimPickup instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + /* offset in meters from the object origin to the robot end-effector in the z-plane */ + static rl::math::Real HEIGHT_OFFSET_OBJECT; + + /* offset in meters the object will be lifted for pickup in the z-plane */ + static rl::math::Real HEIGHT_PICKUP_DIST_OBJECT; + + /* distance in meters the object will also be picked up if it will be moved within a support surface */ + static rl::math::Real MIN_PLANE_DIST_FOR_PICKUP; + + static rl::math::Real PICKUP_Z_AXIS; + static rl::math::Real PICKUP_Y_AXIS; + static rl::math::Real PICKUP_X_AXIS; + + private: + DamaPrimPickup() {}; + DamaPrimPickup(DamaPrimPickup const&); // Don't Implement + void operator=(DamaPrimPickup const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMPICKUP_H_ */ diff --git a/src/DamaPrimPush.cpp b/src/DamaPrimPush.cpp new file mode 100644 index 0000000..e724ac3 --- /dev/null +++ b/src/DamaPrimPush.cpp @@ -0,0 +1,26 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPush.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + DamaPrimPush::DamaPrimPush() + { + this->POSTPROC_EXTEND_DIST = 0.1; + this->TILT_HAND_INWARD_ANGLE = 0.0 * rl::math::DEG2RAD; + this->TILT_HAND_DOWNWARD_ANGLE = 0.0 * rl::math::DEG2RAD; + } + + // default values + rl::math::Real DamaPrimPush::DIST_TO_OBJECT_XY = 0.01; // important for the xml file: add a small epsilon (here: 0.01), because we need a safety distance + rl::math::Real DamaPrimPush::HEIGHT_OFFSET_OBJECT = 0.0; + rl::math::Real DamaPrimPush::MAX_PUSH_DIST = std::numeric_limits::max(); + rl::math::Real DamaPrimPush::MAX_PUSH_DIST_JOINT = std::numeric_limits::max(); +} diff --git a/src/DamaPrimPush.h b/src/DamaPrimPush.h new file mode 100644 index 0000000..ac28b56 --- /dev/null +++ b/src/DamaPrimPush.h @@ -0,0 +1,43 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPUSH_H_ +#define _DAMA_DAMAPRIMPUSH_H_ + +#include "DamaPrim.h" + +namespace dama +{ + class DamaPrimPush : public DamaPrim + { + public: + DamaPrimPush(); + + /* distance in meters between the object origin and the robot end-effector in the x-y-plane */ + static rl::math::Real DIST_TO_OBJECT_XY; + + /* offset in meters from the object origin to the robot end-effector in the z-plane */ + static rl::math::Real HEIGHT_OFFSET_OBJECT; + + /* maximum distance in meters the robot is allowed to push an object with a single push operation */ + static rl::math::Real MAX_PUSH_DIST; + + /* maximum joint space distance in radians the robot is allowed to push an object with a single push operation */ + static rl::math::Real MAX_PUSH_DIST_JOINT; + + + /* distance in meters that pushing operations will be extended in the x-y-plane [P1 -> P2 => P1 -> P3 (new point further away than P2) -> P2] */ + rl::math::Real POSTPROC_EXTEND_DIST; + + rl::math::Real TILT_HAND_INWARD_ANGLE; + + rl::math::Real TILT_HAND_DOWNWARD_ANGLE; + + protected: + + }; +} + +#endif /* _DAMA_DAMAPRIMPUSH_H_ */ diff --git a/src/DamaPrimPushExterior.cpp b/src/DamaPrimPushExterior.cpp new file mode 100644 index 0000000..603bda8 --- /dev/null +++ b/src/DamaPrimPushExterior.cpp @@ -0,0 +1,270 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPushExterior.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimPushExterior::getName() const + { + return "Push Exterior Object"; + } + + bool DamaPrimPushExterior::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + // TODO: Add some constraint, pushing with exterior hand surface only when object moves to the right?! + + bool foundObjectForPush = false; + + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(this->dModel->isOnSupportSurface(startState, i)) + { + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + foundObjectForPush = true; + } + else + return false; + } + + return foundObjectForPush; + } + + bool DamaPrimPushExterior::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimPushExterior::propagate: pushing object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") to (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + // calculate the 2D surface directional vector from object start to object goal position + ::rl::math::Vector dirVecMovingObject(2); + dirVecMovingObject(0) = endState(indexObject) - startState(indexObject); + dirVecMovingObject(1) = endState(indexObject+1) - startState(indexObject+1); + ::rl::math::Real lengthMovingObject = dirVecMovingObject.norm(); + + // calculate the real endstate, because we have a limited push distance -> endstate might get cut + ::rl::math::Vector realEndState(3); + for(::std::size_t i=0; i<3; ++i) + realEndState(i) = endState(indexObject+i); + if(lengthMovingObject > DamaPrimPush::MAX_PUSH_DIST) + { + realEndState(0) = startState(indexObject) + dirVecMovingObject(0)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + realEndState(1) = startState(indexObject+1) + dirVecMovingObject(1)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + + if(this->dModel->debugMode) + ::std::cout << "Adjusting goal (cut from " << lengthMovingObject << " down to " << DamaPrimPush::MAX_PUSH_DIST << " length): (" << realEndState(0) << ", " << realEndState(1) << ", " << realEndState(2) << ")" << ::std::endl; + } + + // TODO: uncomment for mobile robot! + /* + dirVecMovingObject.normalize(); + dirVecMovingObject *= this->dModel->radiusObject + this->dModel->radiusRobot; + // ... + interConf1(0) = startState(indexObject) - dirVecMovingObject(0); + interConf1(1) = startState(indexObject+1) - dirVecMovingObject(1); + // ... + interConf2(0) = endState(indexObject) - dirVecMovingObject(0); + interConf2(1) = endState(indexObject+1) - dirVecMovingObject(1); + */ + + // TODO: check if the following still holds for a mobile robot + + // calculate the rotational angle for the end-effector in order to push the object from the right angle + double theta = atan(- dirVecMovingObject(0) / dirVecMovingObject(1)); + double theta_in = theta; + if(dirVecMovingObject(1) >= 0.0) + theta_in += M_PI; + double theta_ex = theta; + if(dirVecMovingObject(1) < 0.0) + theta_ex += M_PI; + // TODO: following two maybe not needed -> test! + /*if(theta < 0) + theta += 2*M_PI; + if(theta >= 2*M_PI) + theta -= 2*M_PI;*/ + + if(this->dModel->debugMode) + ::std::cout << "#### theta_ex: " << theta_ex << " (rad), resp. " << (theta_ex * rl::math::RAD2DEG) << " (deg)" << ::std::endl; + + // calculate the robot pushing start position + rl::math::Transform T1_ex; + T1_ex.translation().x() = startState(indexObject) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T1_ex.translation().y() = startState(indexObject+1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T1_ex.translation().z() = startState(indexObject+2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T1_ex.linear() = ( + rl::math::AngleAxis(theta_ex, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 1; + + rl::math::Vector q_ik_start1 = startState.segment(0, dModel->getDof(0)); + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK1 to T = ("; + this->dModel->printTransform(T1_ex, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start1 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + timerIK.start(); + bool calcInverse1a = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T1_ex, q_ik_start1, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + if(!calcInverse1a) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK1 failed. Exit." << ::std::endl; + return false; + } + + ::rl::math::Vector interConf1(startState); + this->dModel->updateRobotPosition(interConf1); + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK1 succeeded with q_deg = ("; + this->dModel->printQLine(interConf1, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + // first move to the pushing position if not already there + if(dModel->isMovingSubspace(startState, interConf1, 0)) + { + // TODO: investigate why algorithm currently needs about 5.7% more time just by using the uncommented code instead of the one in comments?! + //vecResSim.push_back(interConf1); + //vecEdgeActionSim.push_back(DamaPrimTransit::getInstance()->getName()); + DamaPrimTransit::getInstance()->propagate(vecResSim, interConf1, vecEdgeActionSim); + } + + // calculate the robot pushing end position via IK + rl::math::Transform T2_ex; + T2_ex.translation().x() = realEndState(0) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T2_ex.translation().y() = realEndState(1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T2_ex.translation().z() = realEndState(2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T2_ex.linear() = ( + rl::math::AngleAxis(theta_ex, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Vector q_ik_start2 = interConf1.segment(0, dModel->getDof(0)); + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK2 to T = ("; + this->dModel->printTransform(T2_ex, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start2 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + timerIK.start(); + bool calcInverse2 = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T2_ex, q_ik_start2, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(!calcInverse2) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK2 failed. Exit." << ::std::endl; + return false; + } + + // now push the object to its end position + ::rl::math::Vector interConf2(startState); + this->dModel->updateRobotPosition(interConf2); + + // check for maximum joint space distance + ::rl::math::Real robotJointPushDistance = (interConf2.segment(0, dModel->getDof(0)) - interConf1.segment(0, dModel->getDof(0))).norm(); + if(robotJointPushDistance > DamaPrimPush::MAX_PUSH_DIST_JOINT) + { + if(this->dModel->debugMode) + ::std::cout << "Result: (interConf2 - interConf1).norm() > DamaPrimPushExterior::MAX_PUSH_DIST_JOINT, factor " << (DamaPrimPush::MAX_PUSH_DIST_JOINT / robotJointPushDistance) << std::endl; + + return false; + //TODO: try to fix (would also need to fix cartesian sample) <-- ask Andre! + //interConf2 = factor * (interConf2 - interConf1) + interConf1; + } + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK2 succeeded with q_deg = ("; + this->dModel->printQLine(interConf2, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + interConf2(indexObject) = realEndState(0); + interConf2(indexObject+1) = realEndState(1); + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + /*::rl::math::Vector* test = NULL; + test->normalize();*/ + + return true; + } + + ::rl::math::Transform DamaPrimPushExterior::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimPushExterior.h b/src/DamaPrimPushExterior.h new file mode 100644 index 0000000..a2115ef --- /dev/null +++ b/src/DamaPrimPushExterior.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPUSHEXTERIOR_H_ +#define _DAMA_DAMAPRIMPUSHEXTERIOR_H_ + +#include "DamaPrimPush.h" + +namespace dama +{ + class DamaPrimPushExterior : public DamaPrimPush + { + public: + static DamaPrimPushExterior* getInstance() + { + static DamaPrimPushExterior instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimPushExterior() {}; + DamaPrimPushExterior(DamaPrimPushExterior const&); // Don't Implement + void operator=(DamaPrimPushExterior const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMPUSHEXTERIOR_H_ */ diff --git a/src/DamaPrimPushFrontal.cpp b/src/DamaPrimPushFrontal.cpp new file mode 100644 index 0000000..d77a44a --- /dev/null +++ b/src/DamaPrimPushFrontal.cpp @@ -0,0 +1,270 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPushFrontal.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimPushFrontal::getName() const + { + return "Push Frontal Object"; + } + + bool DamaPrimPushFrontal::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + // TODO: Add some constraint, pushing with exterior hand surface only when object moves to the right?! + + bool foundObjectForPush = false; + + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(this->dModel->isOnSupportSurface(startState, i)) + { + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + foundObjectForPush = true; + } + else + return false; + } + + return foundObjectForPush; + } + + bool DamaPrimPushFrontal::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimPushFrontal::propagate: pushing object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") to (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + // calculate the 2D surface directional vector from object start to object goal position + ::rl::math::Vector dirVecMovingObject(2); + dirVecMovingObject(0) = endState(indexObject) - startState(indexObject); + dirVecMovingObject(1) = endState(indexObject+1) - startState(indexObject+1); + ::rl::math::Real lengthMovingObject = dirVecMovingObject.norm(); + + // calculate the real endstate, because we have a limited push distance -> endstate might get cut + ::rl::math::Vector realEndState(3); + for(::std::size_t i=0; i<3; ++i) + realEndState(i) = endState(indexObject+i); + if(lengthMovingObject > DamaPrimPush::MAX_PUSH_DIST) + { + realEndState(0) = startState(indexObject) + dirVecMovingObject(0)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + realEndState(1) = startState(indexObject+1) + dirVecMovingObject(1)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + + if(this->dModel->debugMode) + ::std::cout << "Adjusting goal (cut from " << lengthMovingObject << " down to " << DamaPrimPush::MAX_PUSH_DIST << " length): (" << realEndState(0) << ", " << realEndState(1) << ", " << realEndState(2) << ")" << ::std::endl; + } + + // TODO: uncomment for mobile robot! + /* + dirVecMovingObject.normalize(); + dirVecMovingObject *= this->dModel->radiusObject + this->dModel->radiusRobot; + // ... + interConf1(0) = startState(indexObject) - dirVecMovingObject(0); + interConf1(1) = startState(indexObject+1) - dirVecMovingObject(1); + // ... + interConf2(0) = endState(indexObject) - dirVecMovingObject(0); + interConf2(1) = endState(indexObject+1) - dirVecMovingObject(1); + */ + + // TODO: check if the following still holds for a mobile robot + + // calculate the rotational angle for the end-effector in order to push the object from the right angle + double theta = atan(- dirVecMovingObject(0) / dirVecMovingObject(1)); + double theta_in = theta; + if(dirVecMovingObject(1) >= 0.0) + theta_in += M_PI; + double theta_ex = theta; + if(dirVecMovingObject(1) < 0.0) + theta_ex += M_PI; + // TODO: following two maybe not needed -> test! + /*if(theta < 0) + theta += 2*M_PI; + if(theta >= 2*M_PI) + theta -= 2*M_PI;*/ + + if(this->dModel->debugMode) + ::std::cout << "#### theta_ex: " << theta_ex << " (rad), resp. " << (theta_ex * rl::math::RAD2DEG) << " (deg)" << ::std::endl; + + // calculate the robot pushing start position + rl::math::Transform T1_ex; + T1_ex.translation().x() = startState(indexObject) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T1_ex.translation().y() = startState(indexObject+1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T1_ex.translation().z() = startState(indexObject+2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T1_ex.linear() = ( + rl::math::AngleAxis(theta_ex, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 1; + + rl::math::Vector q_ik_start1 = startState.segment(0, dModel->getDof(0)); + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK1 to T = ("; + this->dModel->printTransform(T1_ex, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start1 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + timerIK.start(); + bool calcInverse1a = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T1_ex, q_ik_start1, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + if(!calcInverse1a) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK1 failed. Exit." << ::std::endl; + return false; + } + + ::rl::math::Vector interConf1(startState); + this->dModel->updateRobotPosition(interConf1); + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK1 succeeded with q_deg = ("; + this->dModel->printQLine(interConf1, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + // first move to the pushing position if not already there + if(dModel->isMovingSubspace(startState, interConf1, 0)) + { + // TODO: investigate why algorithm currently needs about 5.7% more time just by using the uncommented code instead of the one in comments?! + //vecResSim.push_back(interConf1); + //vecEdgeActionSim.push_back(DamaPrimTransit::getInstance()->getName()); + DamaPrimTransit::getInstance()->propagate(vecResSim, interConf1, vecEdgeActionSim); + } + + // calculate the robot pushing end position via IK + rl::math::Transform T2_ex; + T2_ex.translation().x() = realEndState(0) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T2_ex.translation().y() = realEndState(1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T2_ex.translation().z() = realEndState(2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T2_ex.linear() = ( + rl::math::AngleAxis(theta_ex, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Vector q_ik_start2 = interConf1.segment(0, dModel->getDof(0)); + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK2 to T = ("; + this->dModel->printTransform(T2_ex, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start2 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + timerIK.start(); + bool calcInverse2 = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T2_ex, q_ik_start2, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(!calcInverse2) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK2 failed. Exit." << ::std::endl; + return false; + } + + // now push the object to its end position + ::rl::math::Vector interConf2(startState); + this->dModel->updateRobotPosition(interConf2); + + // check for maximum joint space distance + ::rl::math::Real robotJointPushDistance = (interConf2.segment(0, dModel->getDof(0)) - interConf1.segment(0, dModel->getDof(0))).norm(); + if(robotJointPushDistance > DamaPrimPush::MAX_PUSH_DIST_JOINT) + { + if(this->dModel->debugMode) + ::std::cout << "Result: (interConf2 - interConf1).norm() > DamaPrimPushExterior::MAX_PUSH_DIST_JOINT, factor " << (DamaPrimPush::MAX_PUSH_DIST_JOINT / robotJointPushDistance) << std::endl; + + return false; + //TODO: try to fix (would also need to fix cartesian sample) <-- ask Andre! + //interConf2 = factor * (interConf2 - interConf1) + interConf1; + } + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK2 succeeded with q_deg = ("; + this->dModel->printQLine(interConf2, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + interConf2(indexObject) = realEndState(0); + interConf2(indexObject+1) = realEndState(1); + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + /*::rl::math::Vector* test = NULL; + test->normalize();*/ + + return true; + } + + ::rl::math::Transform DamaPrimPushFrontal::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimPushFrontal.h b/src/DamaPrimPushFrontal.h new file mode 100644 index 0000000..171aac3 --- /dev/null +++ b/src/DamaPrimPushFrontal.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPUSHFRONTAL_H_ +#define _DAMA_DAMAPRIMPUSHFRONTAL_H_ + +#include "DamaPrimPush.h" + +namespace dama +{ + class DamaPrimPushFrontal : public DamaPrimPush + { + public: + static DamaPrimPushFrontal* getInstance() + { + static DamaPrimPushFrontal instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimPushFrontal() {}; + DamaPrimPushFrontal(DamaPrimPushFrontal const&); // Don't Implement + void operator=(DamaPrimPushFrontal const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMPUSHFRONTAL_H_ */ diff --git a/src/DamaPrimPushInterior.cpp b/src/DamaPrimPushInterior.cpp new file mode 100644 index 0000000..bd49d6f --- /dev/null +++ b/src/DamaPrimPushInterior.cpp @@ -0,0 +1,270 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPushInterior.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimPushInterior::getName() const + { + return "Push Interior Object"; + } + + bool DamaPrimPushInterior::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + // TODO: Add some constraint, pushing with interior hand surface only when object moves to the left?! + + bool foundObjectForPush = false; + + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(this->dModel->isOnSupportSurface(startState, i)) + { + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + foundObjectForPush = true; + } + else + return false; + } + + return foundObjectForPush; + } + + bool DamaPrimPushInterior::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + ::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + ::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + + if(distPlane > dModel->epsilon && distHeight < dModel->epsilon) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimPushInterior::propagate: pushing object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") to (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + // calculate the 2D surface directional vector from object start to object goal position + ::rl::math::Vector dirVecMovingObject(2); + dirVecMovingObject(0) = endState(indexObject) - startState(indexObject); + dirVecMovingObject(1) = endState(indexObject+1) - startState(indexObject+1); + ::rl::math::Real lengthMovingObject = dirVecMovingObject.norm(); + + // calculate the real endstate, because we have a limited push distance -> endstate might get cut + ::rl::math::Vector realEndState(3); + for(::std::size_t i=0; i<3; ++i) + realEndState(i) = endState(indexObject+i); + if(lengthMovingObject > DamaPrimPush::MAX_PUSH_DIST) + { + realEndState(0) = startState(indexObject) + dirVecMovingObject(0)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + realEndState(1) = startState(indexObject+1) + dirVecMovingObject(1)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + + if(this->dModel->debugMode) + ::std::cout << "Adjusting goal (cut from " << lengthMovingObject << " down to " << DamaPrimPush::MAX_PUSH_DIST << " length): (" << realEndState(0) << ", " << realEndState(1) << ", " << realEndState(2) << ")" << ::std::endl; + } + + // TODO: uncomment for mobile robot! + /* + dirVecMovingObject.normalize(); + dirVecMovingObject *= this->dModel->radiusObject + this->dModel->radiusRobot; + // ... + interConf1(0) = startState(indexObject) - dirVecMovingObject(0); + interConf1(1) = startState(indexObject+1) - dirVecMovingObject(1); + // ... + interConf2(0) = endState(indexObject) - dirVecMovingObject(0); + interConf2(1) = endState(indexObject+1) - dirVecMovingObject(1); + */ + + // TODO: check if the following still holds for a mobile robot + + // calculate the rotational angle for the end-effector in order to push the object from the right angle + double theta = atan(- dirVecMovingObject(0) / dirVecMovingObject(1)); + double theta_in = theta; + if(dirVecMovingObject(1) >= 0.0) + theta_in += M_PI; + // TODO: following two maybe not needed -> test! + /*if(theta < 0) + theta += 2*M_PI; + if(theta >= 2*M_PI) + theta -= 2*M_PI;*/ + + if(this->dModel->debugMode) + ::std::cout << "#### theta_in: " << theta_in << " (rad), resp. " << (theta_in * rl::math::RAD2DEG) << " (deg)" << ::std::endl; + + // calculate the robot pushing start position + rl::math::Transform T1_in; + T1_in.translation().x() = startState(indexObject) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T1_in.translation().y() = startState(indexObject+1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T1_in.translation().z() = startState(indexObject+2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T1_in.linear() = ( + rl::math::AngleAxis(theta_in, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 1; + + // TODO: start here with a good pose on top of the table, also do this in the other push primitives !! + // TODO: TEST THIS !!! + //rl::math::Vector q_ik_start1 = (rl::math::Vector(10) << 6.0, 2.0, 2.0, 80.0, 0.0, -40.0, 30.0, 120.0, 0.0, 15.0).finished() * rl::math::DEG2RAD; + rl::math::Vector q_ik_start1 = startState.segment(0, dModel->getDof(0)); + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK1 to T = ("; + this->dModel->printTransform(T1_in, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start1 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + timerIK.start(); + bool calcInverse1a = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T1_in, q_ik_start1, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + if(!calcInverse1a) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK1 failed. Exit." << ::std::endl; + return false; + } + + ::rl::math::Vector interConf1(startState); + this->dModel->updateRobotPosition(interConf1); + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK1 succeeded with q_deg = ("; + this->dModel->printQLine(interConf1, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + // first move to the pushing position if not already there + if(dModel->isMovingSubspace(startState, interConf1, 0)) + { + // TODO: investigate why algorithm currently needs about 5.7% more time just by using the uncommented code instead of the one in comments?! + //vecResSim.push_back(interConf1); + //vecEdgeActionSim.push_back(DamaPrimTransit::getInstance()->getName()); + DamaPrimTransit::getInstance()->propagate(vecResSim, interConf1, vecEdgeActionSim); + } + + // calculate the robot pushing end position via IK + rl::math::Transform T2_in; + T2_in.translation().x() = realEndState(0) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + T2_in.translation().y() = realEndState(1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + T2_in.translation().z() = realEndState(2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + T2_in.linear() = ( + rl::math::AngleAxis(theta_in, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(this->TILT_HAND_INWARD_ANGLE, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(this->TILT_HAND_DOWNWARD_ANGLE, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Vector q_ik_start2 = interConf1.segment(0, dModel->getDof(0)); + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK2 to T = ("; + this->dModel->printTransform(T2_in, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start2 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + timerIK.start(); + bool calcInverse2 = DamaModel::calcInversePositionTaskPosture(dModel->mdl, T2_in, q_ik_start2, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(!calcInverse2) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK2 failed. Exit." << ::std::endl; + return false; + } + + // now push the object to its end position + ::rl::math::Vector interConf2(startState); + this->dModel->updateRobotPosition(interConf2); + + // check for maximum joint space distance + ::rl::math::Real robotJointPushDistance = (interConf2.segment(0, dModel->getDof(0)) - interConf1.segment(0, dModel->getDof(0))).norm(); + if(robotJointPushDistance > DamaPrimPush::MAX_PUSH_DIST_JOINT) + { + if(this->dModel->debugMode) + ::std::cout << "Result: (interConf2 - interConf1).norm() > DamaPrimPushExterior::MAX_PUSH_DIST_JOINT, factor " << (DamaPrimPush::MAX_PUSH_DIST_JOINT / robotJointPushDistance) << std::endl; + + return false; + //TODO: try to fix (would also need to fix cartesian sample) <-- ask Andre! + //interConf2 = factor * (interConf2 - interConf1) + interConf1; + } + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK2 succeeded with q_deg = ("; + this->dModel->printQLine(interConf2, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + interConf2(indexObject) = realEndState(0); + interConf2(indexObject+1) = realEndState(1); + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + /*::rl::math::Vector* test = NULL; + test->normalize();*/ + + return true; + } + + ::rl::math::Transform DamaPrimPushInterior::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimPushInterior.h b/src/DamaPrimPushInterior.h new file mode 100644 index 0000000..c906464 --- /dev/null +++ b/src/DamaPrimPushInterior.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPUSHINTERIOR_H_ +#define _DAMA_DAMAPRIMPUSHINTERIOR_H_ + +#include "DamaPrimPush.h" + +namespace dama +{ + class DamaPrimPushInterior : public DamaPrimPush + { + public: + static DamaPrimPushInterior* getInstance() + { + static DamaPrimPushInterior instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimPushInterior() {}; + DamaPrimPushInterior(DamaPrimPushInterior const&); // Don't Implement + void operator=(DamaPrimPushInterior const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMPUSHINTERIOR_H_ */ diff --git a/src/DamaPrimPushMobile.cpp b/src/DamaPrimPushMobile.cpp new file mode 100644 index 0000000..b598e9b --- /dev/null +++ b/src/DamaPrimPushMobile.cpp @@ -0,0 +1,132 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimPushMobile.h" +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimPushMobile::getName() const + { + return "Push Mobile Object"; + } + + bool DamaPrimPushMobile::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + // TODO: only inspect the distance on a surface + + // TODO: Add some constraint, pushing with interior hand surface only when object moves to the left?! + + return dModel->isMovingObject(startState, endState); + } + + bool DamaPrimPushMobile::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // TODO: only inspect the distance on a surface + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + if(dModel->isMovingSubspace(startState, endState, i)) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimPushMobile::propagate: pushing object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") to (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + // calculate the 2D surface directional vector from object start to object goal position + ::rl::math::Vector dirVecMovingObject(2); + dirVecMovingObject(0) = endState(indexObject) - startState(indexObject); + dirVecMovingObject(1) = endState(indexObject+1) - startState(indexObject+1); + ::rl::math::Real lengthMovingObject = dirVecMovingObject.norm(); + + // calculate the real endstate, because we have a limited push distance -> endstate might get cut + ::rl::math::Vector realEndState(3); + for(::std::size_t i=0; i<3; ++i) + realEndState(i) = endState(indexObject+i); + if(lengthMovingObject > DamaPrimPush::MAX_PUSH_DIST) + { + realEndState(0) = startState(indexObject) + dirVecMovingObject(0)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + realEndState(1) = startState(indexObject+1) + dirVecMovingObject(1)/lengthMovingObject*DamaPrimPush::MAX_PUSH_DIST; + + if(this->dModel->debugMode) + ::std::cout << "Adjusting goal (cut from " << lengthMovingObject << " down to " << DamaPrimPush::MAX_PUSH_DIST << " length): (" << realEndState(0) << ", " << realEndState(1) << ", " << realEndState(2) << ")" << ::std::endl; + } + + // special code for mobile robot + dirVecMovingObject.normalize(); + dirVecMovingObject *= DamaPrimPush::DIST_TO_OBJECT_XY; + + ::rl::math::Vector interConf1(startState); + interConf1(0) = startState(indexObject) - dirVecMovingObject(0); + interConf1(1) = startState(indexObject+1) - dirVecMovingObject(1); + + // first move to the pushing position if not already there + if(dModel->isMovingSubspace(startState, interConf1, 0)) + { + // TODO: investigate why algorithm currently needs about 5.7% more time just by using the uncommented code instead of the one in comments?! + //vecResSim.push_back(interConf1); + //vecEdgeActionSim.push_back(DamaPrimTransit::getInstance()->getName()); + DamaPrimTransit::getInstance()->propagate(vecResSim, interConf1, vecEdgeActionSim); + } + + // now push the object to its end position + ::rl::math::Vector interConf2(startState); + interConf2(0) = realEndState(0) - dirVecMovingObject(0); + interConf2(1) = realEndState(1) - dirVecMovingObject(1); + + interConf2(indexObject) = realEndState(0); + interConf2(indexObject+1) = realEndState(1); + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + /*::rl::math::Vector* test = NULL; + test->normalize();*/ + + return true; + } + + ::rl::math::Transform DamaPrimPushMobile::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimPushMobile.h b/src/DamaPrimPushMobile.h new file mode 100644 index 0000000..f7ce50b --- /dev/null +++ b/src/DamaPrimPushMobile.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMPUSHMOBILE_H_ +#define _DAMA_DAMAPRIMPUSHMOBILE_H_ + +#include "DamaPrimPush.h" + +namespace dama +{ + class DamaPrimPushMobile : public DamaPrimPush + { + public: + static DamaPrimPushMobile* getInstance() + { + static DamaPrimPushMobile instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimPushMobile() {}; + DamaPrimPushMobile(DamaPrimPushMobile const&); // Don't Implement + void operator=(DamaPrimPushMobile const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMPUSHMOBILE_H_ */ diff --git a/src/DamaPrimTransferRigid.cpp b/src/DamaPrimTransferRigid.cpp new file mode 100644 index 0000000..5e7bb27 --- /dev/null +++ b/src/DamaPrimTransferRigid.cpp @@ -0,0 +1,160 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaPrimTransferRigid.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimTransferRigid::getName() const + { + return "Transfer-Rigid Object"; + } + + bool DamaPrimTransferRigid::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + //::rl::math::Real distPlaneTransformed = ::std::pow(startState(offset+0) - endState(offset+0), 2) + ::std::pow(startState(offset+1) - endState(offset+1), 2); + //::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + ::rl::math::Real distEuclidTransformed = ::std::pow(startState(offset+0) - endState(offset+0), 2) + ::std::pow(startState(offset+1) - endState(offset+1), 2) + ::std::pow(startState(offset+2) - endState(offset+2), 2); + + // if the object is in the air, and either the object has to move or we change the grasp + if(!this->dModel->isOnSupportSurface(startState, i) && (distEuclidTransformed > dModel->epsilonTransformed || dModel->isMovingSubspace(startState, endState, 0))) + return true; + } + + return false; + } + + bool DamaPrimTransferRigid::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + dama::Timer timerIK; + + ::std::vector< ::rl::math::Vector > vecResSim = vecRes; + ::std::vector< ::std::string > vecEdgeActionSim = vecEdgeAction; + ::rl::math::Vector startState = vecResSim.back(); + + // choose the object which to move depending on the robot travel distance to the location of the respective object + // TODO: solve traveling salesman problem? Or maybe a bit better (but more time consuming): take pushing pose instead of object's location + // TODO: optimize: there should be only one object which could possibly "fly in the air" + ::std::size_t subspacePushObject; + ::rl::math::Real bestDistRobotObject = ::std::numeric_limits< double >::max(); + ::rl::math::Real currDistRobotObject; + const ::rl::math::Transform T = dModel->calcForwardKinematics(startState.segment(0, dModel->getDof(0)), 0, this->dModel->mdlGrasp); + for(::std::size_t i=dModel->numRobots; igetNumMovableComponents(); ++i) + { + ::std::size_t offset = this->dModel->indexFromSubspace(i); + //::rl::math::Real distPlane = ::std::fabs(startState(offset+0) - endState(offset+0)) + ::std::fabs(startState(offset+1) - endState(offset+1)); + //::rl::math::Real distHeight = ::std::fabs(startState(offset+2) - endState(offset+2)); + ::rl::math::Real distEuclidTransformed = ::std::pow(startState(offset+0) - endState(offset+0), 2) + ::std::pow(startState(offset+1) - endState(offset+1), 2) + ::std::pow(startState(offset+2) - endState(offset+2), 2); + + if(!this->dModel->isOnSupportSurface(startState, i) && (distEuclidTransformed > dModel->epsilonTransformed || dModel->isMovingSubspace(startState, endState, 0))) + { + currDistRobotObject = dModel->cartesianRobotDistanceToObject(T, startState, i); + if(currDistRobotObject < bestDistRobotObject) + { + bestDistRobotObject = currDistRobotObject; + subspacePushObject = i; + } + } + } + ::std::size_t indexObject = dModel->indexFromSubspace(subspacePushObject); + + if(this->dModel->debugMode) + ::std::cout << "DamaPrimTransferRigid::propagate: transfer object nr. " << (subspacePushObject) << " from (" << startState(indexObject) << ", " << startState(indexObject+1) << ", " << startState(indexObject+2) << ") to (" << endState(indexObject) << ", " << endState(indexObject+1) << ", " << endState(indexObject+2) << ")" << std::endl; + + //TODO: maybe we don't need the IK anymore, because sample comes with right robot arm pose already now?! + + ::rl::math::Vector interConf2(startState); + if(this->dModel->isOnSupportSurface(endState, subspacePushObject)) + { + // calculate the robot transfer end position + rl::math::Transform T2_transfer; + T2_transfer.translation().x() = endState(indexObject); + T2_transfer.translation().y() = endState(indexObject+1); + T2_transfer.translation().z() = endState(indexObject+2) + DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T2_transfer.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 0; + + rl::math::Vector q_ik_start2 = startState.segment(0, dModel->getDof(0)); + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK2 to T = ("; + this->dModel->printTransform(T2_transfer, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start2 * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + timerIK.start(); + bool calcInverse2 = DamaModel::calcInversePositionTaskPosture(dModel->mdlGrasp, T2_transfer, q_ik_start2, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(!calcInverse2) + { + if(this->dModel->debugMode) + ::std::cout << "Result: IK2 failed. Exit." << ::std::endl; + return false; + } + + this->dModel->updateRobotPosition(interConf2, this->dModel->mdlGrasp); + } + else + { + if(this->dModel->debugMode) + ::std::cout << "Calculate IK2 not needed, just take the pose from the sample, resp. end-state" << ::std::endl; + for(::std::size_t i=0; idModel->getDof(0); ++i) + interConf2(i) = endState(i); + } + + if(this->dModel->debugMode) + { + ::std::cout << "Result: IK2 succeeded with q_deg = ("; + this->dModel->printQLine(interConf2, false, false, false, true); + ::std::cout << ")" << ::std::endl; + } + + interConf2(indexObject) = endState(indexObject+0); + interConf2(indexObject+1) = endState(indexObject+1); + interConf2(indexObject+2) = endState(indexObject+2); + + vecResSim.push_back(interConf2); + vecEdgeActionSim.push_back(this->getName() + " " + boost::lexical_cast(subspacePushObject)); + + vecRes = vecResSim; + vecEdgeAction = vecEdgeActionSim; + + return true; + } + + ::rl::math::Transform DamaPrimTransferRigid::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimTransferRigid.h b/src/DamaPrimTransferRigid.h new file mode 100644 index 0000000..676d6a8 --- /dev/null +++ b/src/DamaPrimTransferRigid.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMTRANSFERRIGID_H_ +#define _DAMA_DAMAPRIMTRANSFERRIGID_H_ + +#include "DamaPrim.h" + +namespace dama +{ + class DamaPrimTransferRigid : public DamaPrim + { + public: + static DamaPrimTransferRigid* getInstance() + { + static DamaPrimTransferRigid instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimTransferRigid() {}; + DamaPrimTransferRigid(DamaPrimTransferRigid const&); // Don't Implement + void operator=(DamaPrimTransferRigid const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMTRANSFERRIGID_H_ */ diff --git a/src/DamaPrimTransit.cpp b/src/DamaPrimTransit.cpp new file mode 100644 index 0000000..ab430eb --- /dev/null +++ b/src/DamaPrimTransit.cpp @@ -0,0 +1,58 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include "DamaPrimTransit.h" +#include "DamaModel.h" + +namespace dama +{ + ::std::string DamaPrimTransit::getName() const + { + return "Transit"; + } + + bool DamaPrimTransit::isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState) + { + ::rl::math::Real dist = 0; + for(::std::size_t i=this->dModel->numRobots; idModel->getNumMovableComponents(); ++i) + { + if(this->dModel->isMovingSubspace(startState, endState, i)) + return false; + + if(!this->dModel->isOnSupportSurface(startState, i)) + return false; + } + + return this->dModel->isMovingSubspace(startState, endState, 0); + } + + bool DamaPrimTransit::propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction) + { + ::rl::math::Vector interConf1(vecRes.back()); + for(::std::size_t i=0; idModel->getDof(0); ++i) + interConf1(i) = endState(i); + vecRes.push_back(interConf1); + vecEdgeAction.push_back(this->getName()); + + return true; + } + + ::rl::math::Transform DamaPrimTransit::getToolObjectTransform() + { + rl::math::Transform T; + + // TODO: do it! + /*T.translation().x() = 0; + T.translation().y() = 0; + T.translation().z() = DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix();*/ + + return T; + } +} diff --git a/src/DamaPrimTransit.h b/src/DamaPrimTransit.h new file mode 100644 index 0000000..9f21613 --- /dev/null +++ b/src/DamaPrimTransit.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMAPRIMTRANSIT_H_ +#define _DAMA_DAMAPRIMTRANSIT_H_ + +#include "DamaPrim.h" + +namespace dama +{ + class DamaPrimTransit : public DamaPrim + { + public: + static DamaPrimTransit* getInstance() + { + static DamaPrimTransit instance; + return &instance; + } + + virtual ::std::string getName() const; + virtual bool isUseful(const ::rl::math::Vector& startState, const ::rl::math::Vector& endState); + virtual bool propagate(::std::vector< ::rl::math::Vector >& vecRes, const ::rl::math::Vector& endState, ::std::vector< ::std::string >& vecEdgeAction); + virtual ::rl::math::Transform getToolObjectTransform(); + + private: + DamaPrimTransit() {}; + DamaPrimTransit(DamaPrimTransit const&); // Don't Implement + void operator=(DamaPrimTransit const&); // Don't implement + }; +} + +#endif /* _DAMA_DAMAPRIMTRANSIT_H_ */ diff --git a/src/DamaRrt.cpp b/src/DamaRrt.cpp new file mode 100644 index 0000000..e964239 --- /dev/null +++ b/src/DamaRrt.cpp @@ -0,0 +1,2200 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "DamaRrt.h" +#include "DamaModel.h" +#include "DamaSampler.h" +#include + +#include +#include +#include +#include + +#if _MSC_VER < 1600 +#define nullptr NULL // TODO +#endif + +namespace std +{ + std::ostream& operator<<(std::ostream &os, const rl::plan::VectorPtr q) + { + for (::std::size_t i = 0; i < q.get()->size(); ++i) + { + os << q.get()->data()[i]; + if(i < q.get()->size()-1) + os << ", "; + } + + return os; + } + + std::istream& operator>>(std::istream &is, rl::plan::VectorPtr &q) + { + return is; + } +} + +namespace dama +{ + DamaRrt::DamaRrt(::std::size_t numMovableComponents, ::std::size_t numSupportSurfaces) : + DamaRrtCon(), + dModel(NULL), + dSampler(NULL), + randSubspace( + ::boost::mt19937(static_cast< ::boost::mt19937::result_type >(0)), + ::boost::uniform_int<>(0, numMovableComponents-1) + ), + randSupportSurface( + ::boost::mt19937(static_cast< ::boost::mt19937::result_type >(0)), + ::boost::uniform_int<>(0, numSupportSurfaces) + ), + extendStep(0.1f) // set from outside manually, currently in MainWindow.cpp + { + this->seed(static_cast< ::boost::mt19937::result_type >(0)); + + this->metaFileName = "DamaRrt-graph-meta"; + this->tree0FileName = "DamaRrt-graph-0.xml"; + this->tree1FileName = "DamaRrt-graph-1.xml"; + this->treeSolFileName = "DamaRrt-graph-sol.xml"; + this->pathSolVerticesFileName = "solution.vertices"; + this->pathSolEdgesFileName = "solution.edges"; + + this->resetStatistics(); + } + + DamaRrt::~DamaRrt() + { + } + + ::std::string DamaRrt::getName() const + { + return "RRT Dama"; + } + + void DamaRrt::seed(const ::boost::mt19937::result_type& value) + { + this->rand.engine().seed(value); + this->randSubspace.engine().seed(value); + this->randSupportSurface.engine().seed(value); + if(dSampler != NULL) + this->dSampler->seed(value); + } + + void DamaRrt::choose(::rl::math::Vector& chosen, std::vector& currIsChosen, bool forwardSearch) + { + if(this->dModel->workspaceSampling) + { + // For Workspace drawing! + ::std::size_t currIndex2 = this->dModel->getDof(0); + for(::std::size_t i=1; idModel->getNumMovableComponents(); ++i) + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex2+u) = 0.0f; + currIsChosen.at(currIndex2+u) = false; + } + currIndex2 += this->dModel->getDof(i); + } + this->dSampler->generateOnlyCollisionFree(chosen, 0, this->dModel->vecSupportSurface.size()); + for(::std::size_t u=0; udModel->getDof(0); ++u) + currIsChosen.at(u) = true; + return; + } + + std::deque dequeNames; + + ::std::size_t randSubspace = 0; + ::std::size_t randSupportSurface = this->dModel->vecSupportSurface.size(); + if(this->rand() > this->dModel->sampleRobotPoseProb) + { + while(randSubspace == 0) + randSubspace = this->randSubspace(); + randSupportSurface = this->randSupportSurface(); + + this->dSampler->generateOnlyCollisionFree(chosen, randSubspace, randSupportSurface); + } + + bool allObjectFree = true; + + ::std::size_t currIndex = this->dModel->getDof(0); + for(::std::size_t i=1; idModel->getNumMovableComponents(); ++i) + { + if(i != randSubspace) + { + // TODO: fix this stuff!!! I can't understand it anymore !!! + + /*if(randVal > 0.5f && forwardSearch && this->goalDimDefined->at(this->dModel->indexFromSubspace(i))) + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = (*this->goal)(currIndex+u); + currIsChosen.at(currIndex+u) = true; + } + + dequeNames.push_back("goal"); + allObjectFree = false; + } + else if(randVal > 0.5f && !forwardSearch) + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = (*this->start)(currIndex+u); + currIsChosen.at(currIndex+u) = true; + } + + dequeNames.push_back("start"); + allObjectFree = false; + }*/ + if(this->rand() > this->dModel->sampleObjectsFreeProb) + { + if(this->rand() > 0.5f) + { + if(this->goalDimDefined->at(this->dModel->indexFromSubspace(i))) + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = (*this->goal)(currIndex+u); + currIsChosen.at(currIndex+u) = true; + } + + dequeNames.push_back("goal"); + allObjectFree = false; + } + else + { + if(this->rand() > 0.5f) + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = (*this->start)(currIndex+u); + currIsChosen.at(currIndex+u) = true; + } + + dequeNames.push_back("start"); + allObjectFree = false; + } + else + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = 0.0f; + currIsChosen.at(currIndex+u) = false; + } + + dequeNames.push_back("free"); + } + } + } + else + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = (*this->start)(currIndex+u); + currIsChosen.at(currIndex+u) = true; + } + + dequeNames.push_back("start"); + allObjectFree = false; + } + } + else + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + chosen(currIndex+u) = 0.0f; + currIsChosen.at(currIndex+u) = false; + } + + dequeNames.push_back("free"); + /*if((forwardSearch && this->goalDimDefined->at(this->dModel->indexFromSubspace(i))) || !forwardSearch) + allObjectGoal = false;*/ + } + } + else + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + currIsChosen.at(currIndex+u) = true; + } + dequeNames.push_back("rand"); + allObjectFree = false; + } + + currIndex += this->dModel->getDof(i); + } + + // now determine the robot position sample values + if(randSubspace > 0 && randSupportSurface == this->dModel->vecSupportSurface.size()) + { + for(::std::size_t u=0; udModel->getDof(0); ++u) + currIsChosen.at(u) = true; + + dequeNames.push_front("coupled"); + } + else if(randSubspace == 0) + { + double randVal = this->rand(); + + if(randVal > this->dModel->sampleRobotRandProb && forwardSearch && this->goalDimDefined->at(this->dModel->indexFromSubspace(0))) + { + for(::std::size_t u=0; udModel->getDof(0); ++u) + { + chosen(u) = (*this->goal)(u); + currIsChosen.at(u) = true; + } + + dequeNames.push_front("goal"); + } + else if(randVal > this->dModel->sampleRobotRandProb && !forwardSearch) + { + for(::std::size_t u=0; udModel->getDof(0); ++u) + { + chosen(u) = (*this->start)(u); + currIsChosen.at(u) = true; + } + + dequeNames.push_front("start"); + } + else + { + this->dSampler->generateOnlyCollisionFree(chosen, 0, this->dModel->vecSupportSurface.size()); + for(::std::size_t u=0; udModel->getDof(0); ++u) + { + currIsChosen.at(u) = true; + } + + dequeNames.push_front("rand"); + } + } + else + { + for(::std::size_t u=0; udModel->getDof(0); ++u) + { + chosen(u) = 0.0f; + currIsChosen.at(u) = false; + } + + dequeNames.push_front("free"); + } + + if(this->dModel->debugMode) + { + std::cout << "Sample: "; + this->dModel->printQLine(chosen, true); + for(::std::size_t i=0; i& actions) + { + //::std::cout.precision(15); + + dama::Timer ttimer1; + ttimer1.start(); + + /*while(true) + usleep(static_cast< std::size_t >(1.0f * 1000.0f * 1000.0f));*/ + + // BEGIN TEST CODE + + // AXIS INFORMATION: + // x-axis points from the robot to its back away from the table (top -> down) + // y-axis points from the robot to the right along the table (left -> right) + + // ATTENTION: following code needs "MainWindow::instance()->toggleView(true);" in Thread.cpp + + /*rl::math::Vector qTemp(this->dModel->mdl->getDof()); + rl::math::Vector q_ik_start; + rl::math::Vector dirVecMovingObject(2); + rl::math::Transform x_grasp, x_in, x_out; + rl::math::Vector posObject(3); + + posObject(0) = 0.0; + posObject(1) = 0.2; + posObject(2) = 0.146;// + DamaPrimPickup::HEIGHT_PICKUP_DIST_OBJECT; + (*this->start)(15) = posObject(2); + bool doGrasp = true; + + ::rl::mdl::Dynamic* currMdl; + if(doGrasp) + currMdl = this->dModel->mdlGrasp; + else + currMdl = this->dModel->mdl; + double theta, theta_in, theta_out; + double thetaDeg = 0.0; + //for(; posObject(1)dModel->vecSupportSurface.at(1)->getMax(1); posObject(1)+=0.001) + for(thetaDeg=0.0; thetaDeg<2*360.0; thetaDeg+=1) + { + if(doGrasp) + { + ::std::cout << "#### position object: " << posObject(0) << " | " << posObject(1) << " | " << posObject(2) << ::std::endl; + } + else + { + dirVecMovingObject(0) = -sin(thetaDeg * rl::math::DEG2RAD); + dirVecMovingObject(1) = cos(thetaDeg * rl::math::DEG2RAD); + ::std::cout << "#### dirVecMovingObject(0): " << dirVecMovingObject(0) << ::std::endl; + ::std::cout << "#### dirVecMovingObject(1): " << dirVecMovingObject(1) << ::std::endl; + } + + // FOR GRASPING + x_grasp.translation().x() = posObject(0); + x_grasp.translation().y() = posObject(1); + x_grasp.translation().z() = posObject(2) + DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + x_grasp.linear() = ( + rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + // calculate theta for pushing configuration + theta = atan(- dirVecMovingObject(0) / dirVecMovingObject(1)); + theta_in = theta; + if(dirVecMovingObject(1) >= 0.0) // for pushing with inside surface + theta_in += M_PI; + theta_out = theta; + if(dirVecMovingObject(1) < 0.0) // for pushing with outside surface + theta_out += M_PI; + + if(!doGrasp) + { + // TODO: following two maybe not needed -> test! + //if(theta < 0) + // theta += 2*M_PI; + //if(theta >= 2*M_PI) + // theta -= 2*M_PI; + //::std::cout << "#### theta (rad): " << (theta) << ::std::endl; + ::std::cout << "#### theta (deg): " << (theta * rl::math::RAD2DEG) << ::std::endl; + //::std::cout << "#### theta_in (rad): " << (theta_in) << ::std::endl; + ::std::cout << "#### theta_in (deg): " << (theta_in * rl::math::RAD2DEG) << ::std::endl; + //::std::cout << "#### theta_out (rad): " << (theta_out) << ::std::endl; + ::std::cout << "#### theta_out (deg): " << (theta_out * rl::math::RAD2DEG) << ::std::endl; + } + + // FOR PUSHING (with the inside surface) + x_in.translation().x() = posObject(0) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + x_in.translation().y() = posObject(1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + x_in.translation().z() = posObject(2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + x_in.linear() = ( + rl::math::AngleAxis(theta_in, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(-15 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(75 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + // FOR PUSHING (with the outside surface) + x_out.translation().x() = posObject(0) - DamaPrimPush::DIST_TO_OBJECT_XY*sin(theta_in); + x_out.translation().y() = posObject(1) + DamaPrimPush::DIST_TO_OBJECT_XY*cos(theta_in); + x_out.translation().z() = posObject(2) + DamaPrimPush::HEIGHT_OFFSET_OBJECT; + x_out.linear() = ( + rl::math::AngleAxis(theta_out, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(15 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) * + rl::math::AngleAxis(75 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(180 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + //this->dModel->printTransform(x); + + rl::math::Vector qt(currMdl->getDof()); + this->dModel->updateRobotPosition(qt, currMdl); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + + // Attention: q_ik_start must be set to an initial value after each call of inversePositionTaskPosture (because it changes within the function) + q_ik_start = (rl::math::Vector(10) << 0.0, 0.0, 0.0, 0.0, 15.0 * rl::math::DEG2RAD, -20.0 * rl::math::DEG2RAD, 12.0 * rl::math::DEG2RAD, 112.0 * rl::math::DEG2RAD, -10.0 * rl::math::DEG2RAD, 0.0).finished(); + + ::rl::util::Timer ttimer2; + ttimer2.start(); + if(doGrasp) + { + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 0; + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK1 to T = ("; + this->dModel->printTransform(x_grasp, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + if(DamaModel::calcInversePositionTaskPosture(currMdl, x_grasp, q_ik_start, constraint_position_orient, this->dModel->coupleJoint1And2)) + { + ttimer2.stop(); + //::std::cout << "x_grasp: worked!" << ::std::endl; + } + else + { + //::std::cout << "grasp IK did not work!" << ::std::endl; + currMdl->setPosition(qt); + } + } + else + { + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 1; + + if(DamaModel::calcInversePositionTaskPosture(currMdl, x_in, q_ik_start, constraint_position_orient, this->dModel->coupleJoint1And2)) + { + ttimer2.stop(); + //::std::cout << "ttimer2: " << ttimer2.elapsed()*1000 << ::std::endl; + //::std::cout << "x_in: worked!" << ::std::endl; + } + else + { + q_ik_start = (rl::math::Vector(10) << 0.0, 0.0, 0.0, 0.0, 15.0 * rl::math::DEG2RAD, -20.0 * rl::math::DEG2RAD, 12.0 * rl::math::DEG2RAD, 112.0 * rl::math::DEG2RAD, -10.0 * rl::math::DEG2RAD, 0.0).finished(); + if(DamaModel::calcInversePositionTaskPosture(currMdl, x_out, q_ik_start, constraint_position_orient, this->dModel->coupleJoint1And2)) + { + //::std::cout << "x_out: worked!" << ::std::endl; + } + else + { + //::std::cout << "both did not work!" << ::std::endl; + currMdl->setPosition(qt); + } + } + } + + this->dModel->updateRobotPosition(qTemp, currMdl); + rl::math::Transform x2 = this->dModel->calcForwardKinematics(qTemp, 0); + this->dModel->printQLine(qTemp, false, true, true, false); + this->dModel->printQLine(qTemp, false, true, true, true); + this->dModel->printTransform(x2); + + ttimer1.stop(); + //::std::cout << "ttimer1: " << ttimer1.elapsed()*1000 << ::std::endl; + + rl::math::Vector qDraw(this->dModel->getDof()); + for(::std::size_t i=0; igetDof(); ++i) + qDraw(i) = qTemp(i); + for(::std::size_t i=currMdl->getDof(); idModel->getDof(); ++i) + qDraw(i) = (*this->start)(i); + //this->dModel->printQLine(qDraw, false, true, true, true); + this->dModel->updateFrames(); + this->viewer->drawConfiguration(qDraw); + + this->dModel->checkCollisionRobotObjects = false; + if(this->dModel->isColliding(DamaPrimTransit::getInstance()->getName())) + ::std::cerr << "DOES COLLIDE!" << ::std::endl; + + usleep(static_cast< std::size_t >(0.01f * 1000.0f * 1000.0f)); + } + while(true); + /* */ + + path.clear(); + actions.clear(); + bool singleSolved; + if(!this->hierarchicalVersion) + { + if(this->dModel->debugMode) + ::std::cout << "Solving with flat version ... " << ::std::endl; + this->dModel->checkCollisionRobotObjects = true; + singleSolved = solve(); + + if(!this->dModel->showFullTree) + { + if(this->viewer != NULL) + this->viewer->reset(); + } + + if(singleSolved) + { + this->getPath(path, actions); + this->postProc(path, actions); + } + this->edgeCount = this->getNumEdges(); + this->vertexCount = this->getNumVertices(); + + return singleSolved; + } + else + { + if(this->dModel->debugMode) + ::std::cout << "Solving with hierarchical version ... " << ::std::endl; + this->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(this->dModel->objectPathTimeout)); + this->dModel->checkCollisionRobotObjects = false; + singleSolved = solve(); + if(!singleSolved) + return false; + } + + this->dModel->checkCollisionRobotObjects = true; + this->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(this->dModel->subProblemTimeout) ); + ::std::size_t maxTries = 1; + + /*rl::plan::VectorList pathRe; + ::std::deque< ::std::string > actionsRe; + this->getPath(pathRe, actionsRe); + rl::plan::VectorList::iterator i3 = pathRe.begin(); + rl::plan::VectorList::iterator j3 = ++pathRe.begin(); + ::std::deque< ::std::string >::iterator e3 = actionsRe.begin(); + this->dModel->printQLine(*i3); + for(; i3 != pathRe.end() && j3 != pathRe.end() && e3 != actionsRe.end(); ++i3, ++j3, ++e3) + { + ::std::cout << *e3 << ::std::endl; + this->dModel->printQLine(*j3); + }*/ + + rl::plan::VectorList objectPath; + this->getObjectPath(objectPath); + this->edgeCount = this->getNumEdges(); + this->vertexCount = this->getNumVertices(); + + bool transitToRobotGoal = false; + ::rl::math::Vector goalFinal = *(this->goal); + ::std::vector goalFinalDimDefined(*(this->goalDimDefined)); + for(::std::size_t i=0; idModel->getDof(0); ++i) + { + if((*this->goalDimDefined).at(i)) + { + transitToRobotGoal = true; + break; + } + } + + rl::plan::VectorList robotPathSingle; + ::std::deque< ::std::string > robotActionsSingle; + rl::plan::VectorList::iterator i = objectPath.begin(); + rl::plan::VectorList::iterator j = ++objectPath.begin(); + if(this->dModel->debugMode) + { + std::cout << "Object Path:" << ::std::endl; + std::cout << ">> "; + this->dModel->printQLine(*i); + for(; i != objectPath.end() && j != objectPath.end(); ++i, ++j) + { + std::cout << ">> "; + this->dModel->printQLine(*j); + } + } + + for(i = objectPath.begin(), j = ++objectPath.begin(); i != objectPath.end() && j != objectPath.end(); ++i, ++j) + { + ::rl::math::Vector startTemp; + if(i == objectPath.begin()) + startTemp = *i; + else + startTemp = robotPathSingle.back(); + ::rl::math::Vector goalTemp = *j; + // set all object goal dim defines to true + for(::std::size_t k=0; kdModel->getDof(); ++k) + (*this->goalDimDefined).at(k) = true; + // robot pose does not matter for the next goal + for(::std::size_t k=0; kdModel->getDof(0); ++k) + { + (*this->goalDimDefined).at(k) = false; + goalTemp(k) = 0.0; + } + this->start = &startTemp; + this->goal = &goalTemp; + + ::std::size_t countTrySingle = 0; + do + { + this->reset(); + + countTrySingle++; + + if(this->dModel->debugMode) + { + ::std::cout << "Solving from < "; + this->dModel->printQLine(*this->start, false, false); + ::std::cout << " > to < "; + this->dModel->printQLine(*this->goal, false, false); + ::std::cout << " > (Attempt Nr. " << countTrySingle << ")" << ::std::endl; + } + + singleSolved = solve(); + + } while(!singleSolved && countTrySingle < maxTries); + if(!singleSolved) + return false; + this->edgeCount += this->getNumEdges(); + this->vertexCount += this->getNumVertices(); + + robotPathSingle.clear(); + robotActionsSingle.clear(); + this->getPath(robotPathSingle, robotActionsSingle); + path.insert(path.end(), robotPathSingle.begin(), robotPathSingle.end()); + actions.insert(actions.end(), robotActionsSingle.begin(), robotActionsSingle.end()); + + // one action is missing for each hierarchical step -> insert DamaPrimTransit manually + if((boost::next(i) != objectPath.end() && boost::next(j) != objectPath.end()) || transitToRobotGoal) + actions.push_back(DamaPrimTransit::getInstance()->getName()); + } + if(transitToRobotGoal) + { + if(i == objectPath.begin()) + this->start = &(*i); + else + this->start = &(path.back()); + (*this->goalDimDefined) = goalFinalDimDefined; + this->goal = &goalFinal; + + ::std::size_t countTrySingle = 0; + do + { + this->reset(); + + countTrySingle++; + + if(this->dModel->debugMode) + { + ::std::cout << "Solving from < "; + this->dModel->printQLine(*this->start, false, false); + ::std::cout << " > to < "; + this->dModel->printQLine(*this->goal, false, false); + ::std::cout << " > (Attempt Nr. " << countTrySingle << ")" << ::std::endl; + } + + singleSolved = solve(); + + } while(!singleSolved && countTrySingle < maxTries); + if(!singleSolved) + return false; + this->edgeCount += this->getNumEdges(); + this->vertexCount += this->getNumVertices(); + + robotPathSingle.clear(); + robotActionsSingle.clear(); + this->getPath(robotPathSingle, robotActionsSingle); + path.insert(path.end(), robotPathSingle.begin(), robotPathSingle.end()); + actions.insert(actions.end(), robotActionsSingle.begin(), robotActionsSingle.end()); + } + + if(this->viewer != NULL) + this->viewer->reset(); + + this->postProc(path, actions); + + return true; + } + + bool DamaRrt::solve() + { + // pause so I can capture screen + //std::cout << "Notice: Sleeping 40 sec so you can start screencasting." << std::endl; + //rl::util::Timer::sleep(40.0); + + // write meta file -> corresponds to unfinished or unsuccessful solving procedure + std::ofstream myfile; + myfile.open(metaFileName.c_str()); + myfile << this->twoTreeVersion << std::endl; + myfile.close(); + + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector >(*this->start)); + Tree* a = &this->tree[0]; + Tree* b; + + if(this->twoTreeVersion) + { + //this->begin[1] = this->addVertex(this->tree[1], ::boost::make_shared< ::rl::math::Vector >(*this->goal)); + b = &this->tree[1]; + + // TODO: part goal option 1 [mix with option 2 ?!] + /*::rl::math::Vector newGoalSample(*(this->goal)); + for(::std::size_t i=0; i<1000; ++i) + { + // TODO: fixed permutation count for each start-pose (blabla, just think how to improve this one!) + this->sampleFromGoalFull(newGoalSample); + this->addVertex(*b, ::boost::make_shared< ::rl::math::Vector >(newGoalSample)); + this->dModel->printQLine(newGoalSample, false, true); + }*/ + } + + ::rl::math::Vector samplePart(this->dModel->getDof()); + ::rl::math::Vector sampleFull(this->dModel->getDof()); + ::rl::math::Vector goalFull(this->dModel->getDof()); + this->dModel->currIsChosen.resize(this->dModel->getDof()); + this->dModel->forwardSearch = true; + + ::std::size_t countWriteGraphML = 1; + dama::Timer timerSample; + dama::Timer timerSamplePart; + ::std::vector timeSample(8, 0); + ::std::vector timeSampleGlobal(8, 0); + ::std::vector timeSampleGlobalAverage(8, 0); + ::std::size_t countSample = 0; + + timer.start(); + timer.stop(); + + while (timer.elapsedDuration() < this->duration) + { + // assure that forward/backward-search and a/b are consistent + if(!this->twoTreeVersion) + assert(this->dModel->forwardSearch && a == &this->tree[0] && b == NULL); + else + assert((this->dModel->forwardSearch && &this->tree[0] == a && &this->tree[1] == b) || (!this->dModel->forwardSearch && &this->tree[0] == b && &this->tree[1] == a)); + + timerSample.start(); + + // Take new sample + if(this->dModel->debugMode) + std::cout << "# Take new sample " << (this->dModel->forwardSearch ? "(forwardSearch)" : "(backwardSearch)") << std::endl; + timerSamplePart.start(); + samplePart.setZero(); + this->choose(samplePart, this->dModel->currIsChosen, this->dModel->forwardSearch); + timerSamplePart.stop(); + timeSample[1] = timerSamplePart.elapsed(); + + // Determine nearest neighbor to new sample in tree a + timerSamplePart.start(); + Neighbor aNearest = this->nearest(*a, samplePart); + // TODO: part goal option 2 + // In case of backward-search, test if sample lies nearer to the partially defined goal than to the nearest neighbor + if(!this->dModel->forwardSearch) + { + this->completePartialGoal(samplePart, goalFull); + + ::rl::math::Real d = this->dModel->distance(goalFull, samplePart); + + if(this->dModel->debugMode) + { + std::cout << "Test distance to goal: "; + this->dModel->printQLine(goalFull, false, false); + std::cout << " [distance: " << d << "]" << std::endl; + } + + if(d < aNearest.second) + { + if(d > this->dModel->epsilon) + aNearest.first = this->addVertex(*a, ::std::make_shared< ::rl::math::Vector >(goalFull)); + aNearest.second = d; + } + } + if(aNearest.first == NULL) + ::std::cerr << "ATTENTION: No nearest neighbor found: aNearest.first == NULL with distance " << aNearest.second << ::std::endl; + timerSamplePart.stop(); + timeSample[2] = timerSamplePart.elapsed(); + if(this->dModel->debugMode && aNearest.first != NULL) + { + std::cout << "Nearest neighbor (a): "; + this->dModel->printQLine(*((*a)[aNearest.first].q.get()), false, false); + std::cout << " [index: " << (*a)[aNearest.first].index << " | distance: " << aNearest.second << "]" << std::endl; + } + // Resume with new sample if distance was nearly 0 or max + if(aNearest.second < this->dModel->epsilon || aNearest.second == ::std::numeric_limits< ::rl::math::Real >::max()) + { + if(this->dModel->debugMode) + { + if(aNearest.second < this->dModel->epsilon) + std::cout << "=> Sample and nearest neighbor are identical. Resume with new sample." << std::endl; + else + std::cout << "=> Sample is unreachable from the nearest neighbor. Resume with new sample." << std::endl; + std::cout << std::endl << std::endl; + } + + timer.stop(); + continue; + } + + // Complete the sample with respect to the nearest neighbor + this->dModel->completePartialSample(samplePart, *(*a)[aNearest.first].q, sampleFull); + if(this->dModel->debugMode) + { + std::cout << "Sample full (a): "; + this->dModel->printQLine(sampleFull, false, true); + } + + // Propagate with FORWARD-control between the nearest neighbor and the sample - result: list of configuration points + timerSamplePart.start(); + ::std::vector< ::rl::math::Vector > vecRes; + ::std::vector< ::std::string > vecEdgeAction; + ESP::Res res = this->dModel->emptySpacePlanner(vecRes, *(*a)[aNearest.first].q, sampleFull, vecEdgeAction, true); + timerSamplePart.stop(); + timeSample[3] = timerSamplePart.elapsed(); + if(this->dModel->debugMode) + { + std::cout << "Empty Space Planner (ESP) - Result: " << ESP::cRes[res] << std::endl; + std::cout << "List of Configuration Points (NN -> Sample): " << std::endl; + for(::std::size_t u=0; u> "; + this->dModel->printQLine(vecRes.at(u), false, false); + if(u < vecRes.size()-1) + std::cout << " [-> " << vecEdgeAction.at(u) << "]"; + std::cout << std::endl; + } + } + // Sample is now completed and propagate might have skipped the last Transit -> currIsChosen to all true + for(::std::size_t i=0; idModel->getDof(); ++i) + this->dModel->currIsChosen.at(i) = true; + + // Connect the nearest neighbor with the sample (via the list of configuration points) in tree a + timerSamplePart.start(); + Vertex aConnected = NULL; + bool aReached = false; + // Only connect if ESP succeeded or it found that the goal is unreachable, but we start with nearestNeighbor (i.e. we connect forwards), so that we can quit at any time + if(res == ESP::OK || (res == ESP::UNREACHABLE && this->dModel->forwardSearch)) + { + for(::std::size_t u=0; uconnect(*a, aNearest, vecRes.at(u+1), vecEdgeAction.at(u), aConnected); + + if(!aReached) + { + if(this->dModel->debugMode) + std::cout << "Collision occurred during 'connect' in tree a." << std::endl; + break; + } + + aNearest = Neighbor(aConnected, ::std::numeric_limits< ::rl::math::Real >::max()); + } + } + if(!this->twoTreeVersion && aReached && this->dModel->isGoal(*((*a)[aConnected].q))) + { + this->finalizeWork(&aConnected, NULL); + return true; + } + timerSamplePart.stop(); + timeSample[4] = timerSamplePart.elapsed(); + + timeSample[5] = 0; + timeSample[6] = 0; + timeSample[7] = 0; + if(this->twoTreeVersion) + { + // swap forward/backward-Search + this->dModel->forwardSearch = !this->dModel->forwardSearch; + + if(aConnected != NULL) + { + if(this->dModel->debugMode) + std::cout << "# Init second phase " << (this->dModel->forwardSearch ? "(forwardSearch)" : "(backwardSearch)") << std::endl; + + // Determine nearest neighbor to aConnected in tree b + timerSamplePart.start(); + Neighbor bNearest = this->nearest(*b, *(*a)[aConnected].q); + // TODO: part goal option 2 + // In case of backward-search, test if aConnected lies nearer to the partially defined goal than to the nearest neighbor + if(!this->dModel->forwardSearch) + { + this->completePartialGoal(*(*a)[aConnected].q, goalFull); + + ::rl::math::Real d = this->dModel->distance(goalFull, *(*a)[aConnected].q); + + if(this->dModel->debugMode) + { + std::cout << "Test distance to goal: "; + this->dModel->printQLine(goalFull, false, false); + std::cout << " [distance: " << d << "]" << std::endl; + } + + if(d < bNearest.second) + { + bNearest.first = this->addVertex(*b, ::std::make_shared< ::rl::math::Vector >(goalFull)); + bNearest.second = d; + } + } + timerSamplePart.stop(); + timeSample[5] = timerSamplePart.elapsed(); + if(this->dModel->debugMode) + { + std::cout << "Nearest neighbor (b): "; + this->dModel->printQLine(*((*b)[bNearest.first].q.get()), false, false); + std::cout << " [index: " << (*b)[bNearest.first].index << " | distance: " << bNearest.second << "]" << std::endl; + } + // Resume with new sample if distance max, finish if distance nearly 0 + if(bNearest.second < this->dModel->epsilon) + { + if(this->dModel->debugMode) + std::cout << "=> Sample and nearest neighbor are identical. Finished." << std::endl << std::endl << std::endl; + + this->finalizeWork(&this->tree[0] == a ? &aConnected : &(bNearest.first), &this->tree[1] == b ? &(bNearest.first) : &aConnected); + return true; + } + else if(bNearest.second == ::std::numeric_limits< ::rl::math::Real >::max()) + { + if(this->dModel->debugMode) + std::cout << "=> Sample is unreachable from the nearest neighbor. Resume with new sample." << std::endl << std::endl << std::endl; + + timer.stop(); + + // swap forward/backward-Search to start over again! + this->dModel->forwardSearch = !this->dModel->forwardSearch; + + continue; + } + + // Propagate with FORWARD-control between aConnected and the nearest neighbor - result: list of configuration points + timerSamplePart.start(); + ::std::vector< ::rl::math::Vector > vecRes; + ::std::vector< ::std::string > vecEdgeAction; + ESP::Res res = this->dModel->emptySpacePlanner(vecRes, *(*b)[bNearest.first].q, *(*a)[aConnected].q, vecEdgeAction, true); + timerSamplePart.stop(); + timeSample[6] = timerSamplePart.elapsed(); + if(this->dModel->debugMode) + { + std::cout << "Empty Space Planner (ESP) - Result: " << ESP::cRes[res] << std::endl; + std::cout << "List of Configuration Points (NN -> Sample): " << std::endl; + for(::std::size_t u=0; u> "; + this->dModel->printQLine(vecRes.at(u), false, false); + if(u < vecRes.size()-1) + std::cout << " [-> " << vecEdgeAction.at(u) << "]"; + std::cout << std::endl; + } + } + + // Connect the nearest neighbor with aConnected (via the list of configuration points in REVERSE order) in tree b + timerSamplePart.start(); + Vertex bConnected = NULL; + bool bReached = false; + // Only connect if ESP succeeded or it found that the goal is unreachable, but we start with nearestNeighbor (i.e. we connect forwards), so that we can quit at any time + if(res == ESP::OK || (res == ESP::UNREACHABLE && this->dModel->forwardSearch)) + { + for(::std::size_t u=0; uconnect(*b, bNearest, vecRes.at(u+1), vecEdgeAction.at(u), bConnected); + + if(!bReached) + { + if(this->dModel->debugMode) + std::cout << "Collision occurred during 'connect' in tree b." << std::endl; + break; + } + + bNearest = Neighbor(bConnected, ::std::numeric_limits< ::rl::math::Real >::max()); + } + } + if(bReached && !this->dModel->isMoving(*(*a)[aConnected].q, *(*b)[bConnected].q)) + { + this->finalizeWork(&this->tree[0] == a ? &aConnected : &bConnected, &this->tree[1] == b ? &bConnected : &aConnected); + return true; + } + timerSamplePart.stop(); + timeSample[7] = timerSamplePart.elapsed(); + } + + // Swap trees + ::std::swap(a, b); + } + + // Print some final statistics + timer.stop(); + timerSample.stop(); + timeSample[0] = timerSample.elapsed(); + this->iterationCount++; + countSample++; + for(::std::size_t i=0; idModel->workspaceSampling) + { + if(this->getNumEdges() >= this->dModel->workspaceSamplingEdges) + while(true); + } + + this->timeSampling += timeSample[1]; + this->timeNNSearch += timeSample[2] + timeSample[5]; + this->timePropagate += timeSample[3] + timeSample[6]; + this->timeConnect += timeSample[4] + timeSample[7]; + + if(this->dModel->debugMode) + { + std::cout << "Edges: " << this->getNumEdges() << (this->twoTreeVersion ? ::std::string(" (") + boost::lexical_cast(::boost::num_edges(this->tree[0])) + ::std::string(", ") + boost::lexical_cast(::boost::num_edges(this->tree[1])) + ::std::string(")") : "") << " | Vertices: " << this->getNumVertices() << (this->twoTreeVersion ? ::std::string(" (") + boost::lexical_cast(::boost::num_vertices(this->tree[0])) + ::std::string(", ") + boost::lexical_cast(::boost::num_vertices(this->tree[1])) + ::std::string(")") : "") << " | Sample Nr. " << countSample << " | Global Time: " << timer.elapsed() << " | IK Time Global: " << this->dModel->timeIK << " | Sample Time Global: " << timeSampleGlobal[0] << std::endl; + std::cout << "Sample Time: " << timeSample[0] << " | 1) sample: " << (timeSample[1]/timeSample[0]*100) << "%" << " | 2) nn a: " << (timeSample[2]/timeSample[0]*100) << "%" << " | 3) propagate a: " << (timeSample[3]/timeSample[0]*100) << "%" << " | 4) connect a: " << (timeSample[4]/timeSample[0]*100) << "%" << " | 5) nn b: " << (timeSample[5]/timeSample[0]*100) << "%" << " | 6) propagate b: " << (timeSample[6]/timeSample[0]*100) << "%" << " | 7) connect b: " << (timeSample[7]/timeSample[0]*100) << "%" << " | -> all: " << ((timeSample[1]+timeSample[2]+timeSample[3]+timeSample[4]+timeSample[5]+timeSample[6]+timeSample[7])/timeSample[0]*100) << "%" << std::endl; + std::cout << "Average: " << timeSampleGlobalAverage[0] << " | 1) sample: " << (timeSampleGlobalAverage[1]/timeSampleGlobalAverage[0]*100) << "%" << " | 2) nn a: " << (timeSampleGlobalAverage[2]/timeSampleGlobalAverage[0]*100) << "%" << " | 3) propagate a: " << (timeSampleGlobalAverage[3]/timeSampleGlobalAverage[0]*100) << "%" << " | 4) connect a: " << (timeSampleGlobalAverage[4]/timeSampleGlobalAverage[0]*100) << "%" << " | 5) nn b: " << (timeSampleGlobalAverage[5]/timeSampleGlobalAverage[0]*100) << "%" << " | 6) propagate b: " << (timeSampleGlobalAverage[6]/timeSampleGlobalAverage[0]*100) << "%" << " | 7) connect b: " << (timeSampleGlobalAverage[7]/timeSampleGlobalAverage[0]*100) << "%" << " | -> all: " << ((timeSampleGlobalAverage[1]+timeSampleGlobalAverage[2]+timeSampleGlobalAverage[3]+timeSampleGlobalAverage[4]+timeSampleGlobalAverage[5]+timeSampleGlobalAverage[6]+timeSampleGlobalAverage[7])/timeSampleGlobalAverage[0]*100) << "%" << std::endl; + std::cout << "Average Steps: " << "sample: " << (timeSampleGlobalAverage[1]/timeSampleGlobalAverage[0]*100) << "%" << " | nn: " << ((timeSampleGlobalAverage[2]+timeSampleGlobalAverage[5])/timeSampleGlobalAverage[0]*100) << "%" << " | propagate: " << ((timeSampleGlobalAverage[3]+timeSampleGlobalAverage[6])/timeSampleGlobalAverage[0]*100) << "%" << " | connect: " << ((timeSampleGlobalAverage[4]+timeSampleGlobalAverage[7])/timeSampleGlobalAverage[0]*100) << "%" << std::endl; + std::cout << std::endl << std::endl; + } + + // write the GraphML file after each 5000 samples + if(countSample >= countWriteGraphML*5000) + { + this->writeGraphML(this->tree[0], tree0FileName); + if(this->twoTreeVersion) + this->writeGraphML(this->tree[1], tree1FileName); + countWriteGraphML++; + } + + + // TODO: a bit buggy, but countEqualNodes-value should be 0 in the end ... + /*::std::size_t indexI = 0; + ::std::size_t countEqualNodes = 0; + for(VertexIteratorPair i = ::boost::vertices(this->tree[0]); i.first != i.second; ++i.first) + { + for(VertexIteratorPair j = ::boost::vertices(this->tree[0]); j.first != j.second; ++j.first) + { + bool incrementedOnce = false; + for(::std::size_t w=0; wtree[0][*i.first].q; + ::rl::math::Vector qt2 = *this->tree[0][*j.first].q; + bool isEqual = true; + for(::std::size_t t = 0; t countEqualNodes: " << countEqualNodes << std::endl;*/ + + + /*std::cout << "Edge list:" << std::endl; + for(VertexIteratorPair i = ::boost::vertices(this->tree[0]); i.first != i.second; ++i.first) + { + std::cout << this->tree[0][*i.first].index << ": "; + this->dModel->printQLine(*this->tree[0][*i.first].q); + } + + for(EdgeIteratorPair i = ::boost::edges(this->tree[0]); i.first != i.second; ++i.first) + { + Edge e = *i.first; + Vertex u = ::boost::source(e, this->tree[0]); + Vertex v = ::boost::target(e, this->tree[0]); + std::cout << "["; + this->dModel->printQLine(*this->tree[0][u].q, false, false); + std::cout << "] to ["; + this->dModel->printQLine(*this->tree[0][v].q, false, false); + std::cout << "]" << std::endl; + }*/ + + // TODO: delete me if no longer waiting for ENTER-Key needed + //while(std::cin.get()!='\n'); + + timer.stop(); + } + + return false; + } + + bool DamaRrt::connectOld(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen, ::std::string edgeAction, Vertex& vertex) + { + ::rl::math::Real step = this->delta; + + ::rl::math::Real distance = this->dModel->robotMovementDistance(*tree[nearest.first].q, chosen); + + if(this->dModel->debugMode) + { + std::cout << "connecting ["; + this->dModel->printQLine(*tree[nearest.first].q, false, false); + std::cout << "] towards ["; + this->dModel->printQLine(chosen, false, false); + std::cout << "] using {" << edgeAction << "}" << std::endl; + } + + Vertex lastAddedVertex = nearest.first; + + bool reached = false; + + if(distance <= this->delta) + reached = true; + + ::rl::plan::VectorPtr last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + + //std::cout << "step: " << step << std::endl; + //std::cout << "distance: " << distance << std::endl; + + if(!reached) + this->dModel->interpolate(*tree[nearest.first].q, chosen, step / distance, *last, edgeAction); + else + *last = chosen; + + //std::cout << "last is in deg: "; + //this->dModel->printQLine(*last, false, true, false, true); + + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + return false; + + // TODO: fix this bug, why do I have to do it twice ... ? + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + { + //std::cout << "WTF?! last collides now: " << last->transpose() << ", " << edgeAction << std::endl; + return false; + } + + ::rl::math::Vector next(this->dModel->getDof()); + + ::std::size_t stepsUntilExtend = (::std::size_t)(this->extendStep / step); + ::std::size_t currStepCount = 1; + + while (!reached) + { + distance = this->dModel->robotMovementDistance(*last, chosen); + + if(distance <= this->delta) + { + reached = true; + *last = chosen; + break; + } + +// std::cout << "connecting(inner) ["; +// this->dModel->printQLine(*last, false, false); +// std::cout << "] towards ["; +// this->dModel->printQLine(chosen, false, false); +// std::cout << "]" << std::endl; +// +// std::cout << "step: " << step << std::endl; +// std::cout << "distance: " << distance << std::endl; + + this->dModel->interpolate(*last, chosen, step / distance, next, edgeAction); + +// std::cout << "*last" << last->transpose() << std::endl; +// std::cout << "chosen: " << chosen.transpose() << std::endl; +// std::cout << "next: " << next.transpose() << std::endl; + + rl::math::Real robot_distance_joint = (last->segment(0, this->dModel->getDof(0)) - next.segment(0, this->dModel->getDof(0))).norm(); + if(robot_distance_joint < 1e-5) + { + // robot and object motion do not converge + break; + } + + this->dModel->setPosition(next); + this->dModel->updateFrames(); + + if(this->dModel->isColliding(edgeAction)) + { + //std::cout << "collides!" << std::endl; + //HERE IT LEAVES my strange bug ... + break; + } + + last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + *last = next; + + currStepCount++; + if(currStepCount >= stepsUntilExtend) + { + if(this->dModel->debugMode) + { + std::cout << "Add vertex: "; + this->dModel->printQLine(*last, false, false); + std::cout << " (during connect after " << currStepCount << " steps)" << std::endl; + } + + // TODO: delete me if no longer waiting for ENTER-Key needed + //while(std::cin.get()!='\n'); + + // TODO: only add this new vertex/edge if it isn't already contains (e.g. for transit to object, the object-vertex will be added each time for now + /*for(VertexIteratorPair i = ::boost::vertices(this->tree[0]); i.first != i.second; ++i.first) + { + ::rl::math::Vector qt1 = *this->tree[0][*i.first].q; + ::rl::math::Vector qt2 = *last.get(); + bool isEqual = true; + for(::std::size_t i = 0; idModel->printQLine(qt2, false, false); + std::cout << " - with - "; + this->dModel->printQLine(qt1, false, true); + this->countEqualVec++; + } + } + std::cout << "++++++++++ countEqualVec: " << this->countEqualVec << std::endl;*/ + + vertex = this->addVertex(tree, last); + this->addEdge(lastAddedVertex, vertex, edgeAction, tree); + lastAddedVertex = vertex; + + currStepCount = 0; + } + } + + //if(reached) + //if(currStepCount > 0) + if((reached && currStepCount > 0) || currStepCount > 1) + { + /*this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + { + std::cout << "last collides (5): " << last->transpose() << ", " << edgeAction << std::endl; + std::cout << "SIMSALABIM " << currStepCount << std::endl; + for(unsigned int i=0; i<30; i++) + { + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + std::cout << "#"; + else + std::cout << "+"; + + this->dModel->setPosition(next); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)); + } + std::cout << std::endl; + }*/ + + if(this->dModel->debugMode) + { + std::cout << "Add vertex: "; + this->dModel->printQLine(*last, false, false); + if(!reached) + std::cout << " (truncated)"; + std::cout << std::endl; + } + + /*std::cout << "(Connecting "; + this->dModel->printQLine(*last, false, false); + std::cout << " with "; + this->dModel->printQLine(*tree[lastAddedVertex].q, false, false); + std::cout << ")" << std::endl;*/ + + + // TODO: delete me if no longer waiting for ENTER-Key needed + //while(std::cin.get()!='\n'); + + // TODO: only add this new vertex/edge if it isn't already contained (e.g. for transit to object, the object-vertex will be added each time for now) + + /*for(VertexIteratorPair i = ::boost::vertices(this->tree[0]); i.first != i.second; ++i.first) + { + ::rl::math::Vector qt1 = *this->tree[0][*i.first].q; + ::rl::math::Vector qt2 = *last.get(); + bool isEqual = true; + for(::std::size_t i = 0; idModel->printQLine(qt2, false, false); + std::cout << " - with - "; + this->dModel->printQLine(qt1, false, true); + this->countEqualVec++; + } + } + std::cout << "++++++++++ countEqualVec: " << this->countEqualVec << std::endl;*/ + + vertex = this->addVertex(tree, last); + this->addEdge(lastAddedVertex, vertex, edgeAction, tree); + } + + if(reached) + return true; + else + return false; + } + + // TODO: synchronize with isCollisionFree + bool DamaRrt::connect(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen, ::std::string edgeAction, Vertex& vertex) + { + if(this->dModel->debugMode) + { + std::cout << "connecting ["; + this->dModel->printQLine(*tree[nearest.first].q, false, false); + std::cout << "] towards ["; + this->dModel->printQLine(chosen, false, false); + std::cout << "] using {" << edgeAction << "}" << std::endl; + } + + Vertex lastAddedVertex = nearest.first; + ::rl::plan::VectorPtr last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + *last = *tree[nearest.first].q; + ::rl::math::Vector next(this->dModel->getDof()); + ::std::size_t stepsUntilExtend = (::std::size_t)(this->extendStep / this->delta); + ::std::size_t currStepCount = 1; + bool reached = false; + + ::rl::math::Real distance = this->dModel->metricConnectInterpolate(*last, chosen); + + if(distance <= this->delta) + reached = true; + + if(!reached) + this->dModel->interpolate(*tree[nearest.first].q, chosen, this->delta / distance, *last, edgeAction); + else + *last = chosen; + + //std::cout << "last is in deg: "; + //this->dModel->printQLine(*last, false, true, false, true); + + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + return false; + + // TODO: fix this bug, why do I have to do it twice ... ? + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + return false; + + while (!reached) + { + distance = this->dModel->metricConnectInterpolate(*last, chosen); + + if(distance <= this->delta) + { + reached = true; + *last = chosen; + break; + } + + //std::cout << "delta: " << this->delta << std::endl; + //std::cout << "distance: " << distance << std::endl; + + this->dModel->interpolate(*last, chosen, this->delta / distance, next, edgeAction); + + //std::cout << "*tree[nearest.first].q" << (tree[nearest.first].q)->transpose() << std::endl; + //std::cout << "*last" << last->transpose() << std::endl; + //std::cout << "chosen: " << chosen.transpose() << std::endl; + //std::cout << "next: " << next.transpose() << std::endl; + + /*if((last->segment(0, this->dModel->getDof(0)) - next.segment(0, this->dModel->getDof(0))).norm() < 1e-5) + { + std::cerr << "Something is wrong in DamaRrt::connect(): robot and object motion do not converge! Fix me!" << std::endl; + //break; + }*/ + + this->dModel->setPosition(next); + this->dModel->updateFrames(); + + if(this->dModel->isColliding(edgeAction)) + { + break; + } + + last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + *last = next; + + currStepCount++; + if(currStepCount >= stepsUntilExtend) + { + if(this->dModel->debugMode) + { + std::cout << "Add vertex: "; + this->dModel->printQLine(*last, false, false); + std::cout << " (during connect after " << currStepCount << " steps)" << std::endl; + } + + vertex = this->addVertex(tree, last); + this->addEdge(lastAddedVertex, vertex, edgeAction, tree); + lastAddedVertex = vertex; + + currStepCount = 0; + } + } + + if((reached && currStepCount > 0) || currStepCount > 1) + { + if(this->dModel->debugMode) + { + std::cout << "Add vertex: "; + this->dModel->printQLine(*last, false, false); + if(!reached) + std::cout << " (truncated)"; + std::cout << std::endl; + } + + vertex = this->addVertex(tree, last); + this->addEdge(lastAddedVertex, vertex, edgeAction, tree); + } + + if(reached) + return true; + else + return false; + } + + // TODO: synchronize with connect + bool DamaRrt::isCollisionFree(const ::rl::math::Vector& v1, const ::rl::math::Vector& v2, ::std::string edgeAction, ::rl::plan::VectorList& pathSegment, ::std::deque< ::std::string >& pathSegmentAction) + { + if(this->dModel->debugMode) + { + std::cout << "test collision from ["; + this->dModel->printQLine(v1, false, false); + std::cout << "] towards ["; + this->dModel->printQLine(v2, false, false); + std::cout << "] using {" << edgeAction << "}" << std::endl; + } + + pathSegment.push_back(v1); + pathSegmentAction.push_back(edgeAction); + + ::rl::plan::VectorPtr last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + *last = v1; + ::rl::math::Vector next(this->dModel->getDof()); + ::std::size_t stepsUntilExtend = (::std::size_t)(this->extendStep / this->delta); + ::std::size_t currStepCount = 1; + bool reached = false; + + ::rl::math::Real distance = this->dModel->metricConnectInterpolate(*last, v2); + + if(distance <= this->delta) + reached = true; + + if(!reached) + this->dModel->interpolate(v1, v2, this->delta / distance, *last, edgeAction); + else + *last = v2; + + //std::cout << "last is in deg: "; + //this->dModel->printQLine(*last, false, true, false, true); + + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + return false; + + // TODO: fix this bug, why do I have to do it twice ... ? + this->dModel->setPosition(*last); + this->dModel->updateFrames(); + if(this->dModel->isColliding(edgeAction)) + return false; + + while (!reached) + { + distance = this->dModel->metricConnectInterpolate(*last, v2); + + if(distance <= this->delta) + { + reached = true; + *last = v2; + break; + } + + //std::cout << "delta: " << this->delta << std::endl; + //std::cout << "distance: " << distance << std::endl; + + this->dModel->interpolate(*last, v2, this->delta / distance, next, edgeAction); + + //std::cout << "*tree[nearest.first].q" << (tree[nearest.first].q)->transpose() << std::endl; + //std::cout << "*last" << last->transpose() << std::endl; + //std::cout << "chosen: " << chosen.transpose() << std::endl; + //std::cout << "next: " << next.transpose() << std::endl; + + /*if((last->segment(0, this->dModel->getDof(0)) - next.segment(0, this->dModel->getDof(0))).norm() < 1e-5) + { + std::cerr << "Something is wrong in DamaRrt::connect(): robot and object motion do not converge! Fix me!" << std::endl; + //break; + }*/ + + this->dModel->setPosition(next); + this->dModel->updateFrames(); + + if(this->dModel->isColliding(edgeAction)) + { + break; + } + + last = ::std::make_shared< ::rl::math::Vector >(this->dModel->getDof()); + *last = next; + + currStepCount++; + if(currStepCount >= stepsUntilExtend) + { + pathSegment.push_back(*last); + pathSegmentAction.push_back(edgeAction); + currStepCount = 0; + } + } + + if((reached && currStepCount > 0) || currStepCount > 1) + { + pathSegment.push_back(*last); + pathSegmentAction.push_back(edgeAction); + } + + if(reached) + return true; + else + return false; + } + + DamaRrtAction::Edge DamaRrt::addEdge(const Vertex& u, const Vertex& v, ::std::string edgeAction, Tree& tree, bool drawIfPossible) + { + Edge e = ::boost::add_edge(u, v, tree).first; + tree[e].action = edgeAction; + + if (NULL != this->viewer && drawIfPossible) + { + this->viewer->drawConfigurationEdge(*tree[u].q, *tree[v].q); + } + + //++this->edgeCount; + + return e; + } + + DamaRrtAction::Vertex DamaRrt::addVertex(Tree& tree, const ::rl::plan::VectorPtr& q) + { + Vertex v = ::boost::add_vertex(tree); + tree[v].index = ::boost::num_vertices(tree) - 1; + tree[v].q = q; + tree[v].radius = ::std::numeric_limits< ::rl::math::Real >::max(); + + if (this->kd) + { + this->addPoint(tree[::boost::graph_bundle].nn, QueryItem(q.get(), v)); + } + + if (NULL != this->viewer) + { + //this->viewer->drawConfigurationVertex(*tree[v].q); + } + + //++this->vertexCount; + + return v; + } + + void DamaRrt::getPath(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions) + { + Vertex i = this->end[0]; + + while (::boost::in_degree(i, this->tree[0]) > 0) + { + Edge e = *::boost::in_edges(i, this->tree[0]).first; + path.push_front(*this->tree[0][i].q); + actions.push_front(this->tree[0][e].action); + //this->dModel->printQLine(path.front(), false, true); + i = ::boost::source(*::boost::in_edges(i, this->tree[0]).first, this->tree[0]); + } + //this->dModel->printQLine(path.front(), false, true); + + path.push_front(*this->tree[0][i].q); + + /*::std::cout << "--> last tree 1 node: "; + this->dModel->printQLine(path.back(), false, true); + ::std::cout << "--> nodes: " << path.size() << ::std::endl; + this->dModel->printQLine(path.front(), false, true); + ::std::cout << ::std::endl << ::std::endl;*/ + + if(this->twoTreeVersion) + { + i = this->end[1]; + while (::boost::in_degree(i, this->tree[1]) > 0) + { + Edge e = *::boost::in_edges(i, this->tree[1]).first; + i = ::boost::source(e, this->tree[1]); + path.push_back(*this->tree[1][i].q); + actions.push_back(this->tree[1][e].action); + } + } + } + + void DamaRrt::getObjectPath(::rl::plan::VectorList& path) + { + rl::plan::VectorList fullPath; + ::std::deque< ::std::string > actions; + this->getPath(fullPath, actions); + + rl::plan::VectorList::iterator i = fullPath.begin(); + rl::plan::VectorList::iterator j = ++fullPath.begin(); + ::std::deque< ::std::string >::iterator e = actions.begin(); + bool currManipulating = false; + ::std::size_t lastObjectNr = 0; + ::std::size_t currObjectNr = 0; + path.push_back(*i); + for(; i != fullPath.end() && j != fullPath.end() && e != actions.end(); ++i, ++j, ++e) + { + if(!currManipulating && *e != DamaPrimTransit::getInstance()->getName()) + { + currManipulating = true; + currObjectNr = boost::lexical_cast< ::std::size_t >(e->substr(e->find_last_of(" ")+1)); + if(currObjectNr != lastObjectNr && lastObjectNr != 0) // latter statement prevents initial push_back + path.push_back(*i); + lastObjectNr = currObjectNr; + } + else if(currManipulating && *e == DamaPrimTransit::getInstance()->getName()) + { + currManipulating = false; + } + } + path.push_back(*i); + } + + void DamaRrt::writeGraphML(Tree& tree, ::std::string fileName) + { + if(this->dModel->debugMode) + std::cout << "### Writing GraphML File '" << fileName << "' ..."; + + // define your Vertex Index Map + typedef Tree::vertex_descriptor NodeID; + typedef std::map IndexMap; + IndexMap mapIndex; + boost::associative_property_map propmapIndex(mapIndex); + + int i = 0; + BGL_FORALL_VERTICES(v, tree, Tree) + { + put(propmapIndex, v, i++); + } + + boost::dynamic_properties dp; + dp.property("index", get(&VertexBundle::index, tree)); + dp.property("q", get(&VertexBundle::q, tree)); + dp.property("radius", get(&VertexBundle::radius, tree)); + dp.property("action", get(&EdgeBundle::action, tree)); + //dp.property("t", get(&VertexBundle::t, this->tree[0])); + + std::ofstream myfile; + myfile.open(fileName.c_str()); + write_graphml(myfile, tree, propmapIndex, dp, true); + myfile.close(); + + if(this->dModel->debugMode) + { + std::cout << " done. ###" << std::endl; + std::cout << std::endl << std::endl; + } + } + + void DamaRrt::finalizeWork(Vertex* end0, Vertex* end1) + { + if(!this->twoTreeVersion) + { + this->end[0] = *end0; + this->writeGraphML(this->tree[0], tree0FileName); + + if(this->dModel->debugMode) + std::cout << "### Writing GraphML Meta File '" << metaFileName << "' ..."; + std::ofstream myfile; + myfile.open(metaFileName.c_str()); + myfile << this->twoTreeVersion << std::endl; + myfile << this->tree[0][*end0].index << std::endl; + myfile.close(); + if(this->dModel->debugMode) + { + std::cout << " done. ###" << std::endl; + std::cout << std::endl << std::endl; + } + } + else + { + this->end[0] = *end0; + this->end[1] = *end1; + this->writeGraphML(this->tree[0], tree0FileName); + this->writeGraphML(this->tree[1], tree1FileName); + + if(this->dModel->debugMode) + std::cout << "### Writing GraphML Meta File '" << metaFileName << "' ..."; + std::ofstream myfile; + myfile.open(metaFileName.c_str()); + myfile << this->twoTreeVersion << std::endl; + myfile << this->tree[0][*end0].index << std::endl; + myfile << this->tree[1][*end1].index << std::endl; + myfile.close(); + if(this->dModel->debugMode) + { + std::cout << " done. ###" << std::endl; + std::cout << std::endl << std::endl; + } + } + + /*std::cout << "end0 {" << this->tree[0][*end0].index << "}: "; + this->dModel->printQLine(*(this->tree[0][*end0].q.get()), false, true); + if(this->twoTreeVersion) + { + std::cout << "end1 {" << this->tree[1][*end1].index << "}: "; + this->dModel->printQLine(*(this->tree[1][*end1].q.get()), false, true); + } + + std::cout << "Vertex list (tree 0):" << std::endl; + for(VertexIteratorPair i = ::boost::vertices(this->tree[0]); i.first != i.second; ++i.first) + { + std::cout << "tree 0: " << this->tree[0][*i.first].index << ": "; + this->dModel->printQLine(*this->tree[0][*i.first].q); + } + + std::cout << "Edge list (tree 0):" << std::endl; + for(EdgeIteratorPair i = ::boost::edges(this->tree[0]); i.first != i.second; ++i.first) + { + Edge e = *i.first; + Vertex u = ::boost::source(e, this->tree[0]); + Vertex v = ::boost::target(e, this->tree[0]); + std::cout << "tree 0: ["; + this->dModel->printQLine(*this->tree[0][u].q, false, false); + std::cout << " {" << this->tree[0][u].index << "}] to ["; + this->dModel->printQLine(*this->tree[0][v].q, false, false); + std::cout << " {" << this->tree[0][v].index << "}]" << std::endl; + } + + if(this->twoTreeVersion) + { + std::cout << "Vertex list (tree 1):" << std::endl; + for(VertexIteratorPair i = ::boost::vertices(this->tree[1]); i.first != i.second; ++i.first) + { + std::cout << "tree 1: " << this->tree[1][*i.first].index << ": "; + this->dModel->printQLine(*this->tree[1][*i.first].q); + } + + std::cout << "Edge list (tree 1):" << std::endl; + for(EdgeIteratorPair i = ::boost::edges(this->tree[1]); i.first != i.second; ++i.first) + { + Edge e = *i.first; + Vertex u = ::boost::source(e, this->tree[1]); + Vertex v = ::boost::target(e, this->tree[1]); + std::cout << "tree 1: ["; + this->dModel->printQLine(*this->tree[1][u].q, false, false); + std::cout << " {" << this->tree[1][u].index << "}] to ["; + this->dModel->printQLine(*this->tree[1][v].q, false, false); + std::cout << " {" << this->tree[1][v].index << "}]" << std::endl; + } + }*/ + } + + bool DamaRrt::postProc(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions) + { + if(this->dModel->pathSmoothing) + pathSmoothing(path, actions); + + // Extend the pushes by manipulating the final path/actions manually + bool extendPushesSuccess = false; + extendPushesSuccess = extendPushes(path, actions); + + // Calculate the resulting trajectory, and overwrite path/actions + //calcTrajectory(path, actions); <-- not in this project anymore + + // a) Print final robot path + // b) Construct a tree for the final robot movement in order to visualize the solution path with graph-tools + // c) Write vertices and edges of the solution path in separate files + if(this->dModel->debugMode) + ::std::cout << "Final Robot Path:" << ::std::endl; + Tree treeSolution; + Vertex v1, v2; + std::ofstream pathFileVertices(this->pathSolVerticesFileName.c_str()); + std::ofstream pathFileEdges(this->pathSolEdgesFileName.c_str()); + rl::plan::VectorList::iterator i = path.begin(); + rl::plan::VectorList::iterator j = ++path.begin(); + ::std::deque< ::std::string >::iterator e = actions.begin(); + v1 = this->addVertex(treeSolution, ::std::make_shared< ::rl::math::Vector >(*i)); + if(this->dModel->debugMode) + this->dModel->printQLine(*i); + this->dModel->printQLine(*i, false, true, false, true, pathFileVertices); + for(; i != path.end() && j != path.end() && e != actions.end(); ++i, ++j, ++e) + { + v2 = this->addVertex(treeSolution, ::std::make_shared< ::rl::math::Vector >(*j)); + this->addEdge(v1, v2, *e, treeSolution, false); + + if(this->dModel->debugMode) + { + ::std::cout << *e << ::std::endl; + this->dModel->printQLine(*j); + } + + this->dModel->printQLine(*j, false, true, false, true, pathFileVertices); + pathFileEdges << *e << ::std::endl; + + v1 = v2; + } + pathFileVertices.close(); + pathFileEdges.close(); + + if(this->dModel->debugMode) + { + ::std::cout << ::std::endl << "==> " << path.size() << " vertices and " << actions.size() << " edges" << ::std::endl << ::std::endl; + ::std::cout << "Extend Pushes: " << (extendPushesSuccess?"success":"fail") << ::std::endl << ::std::endl; + } + + if(this->hierarchicalVersion) + this->writeGraphML(treeSolution, tree0FileName); + this->writeGraphML(treeSolution, treeSolFileName); + + if(this->hierarchicalVersion) + { + std::ofstream myfile; + myfile.open(metaFileName.c_str()); + myfile << false << std::endl; + myfile << treeSolution[v2].index << std::endl; + myfile.close(); + } + + return true; + } + + bool DamaRrt::extendPushes(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions) + { + bool extendedAll = true; + + if(this->dModel->extendPushes) + { + if(this->dModel->debugMode) + ::std::cout << "extendPushes:" << ::std::endl; + + rl::plan::VectorList::iterator i = path.begin(); + rl::plan::VectorList::iterator j = ++path.begin(); + ::std::deque< ::std::string >::iterator e = actions.begin(); + ::rl::math::Vector P1, P2; + ::std::string pushPrefix = "Push "; + ::std::string lastAction = DamaPrimTransit::getInstance()->getName(); + ::std::string currTraversingPushEdge = ""; + for(; i != path.end() && j != path.end() && e != actions.end(); ++i, ++j, ++e) + { + if(*e != lastAction) + { + if(e->substr(0, pushPrefix.size()) == pushPrefix) + { + P1 = *i; + currTraversingPushEdge = *e; + } + else if(currTraversingPushEdge != "") + { + P2 = *i; + + // extend here the push between p1 and p2 + ::rl::math::Transform T1 = this->dModel->calcForwardKinematics(P1.segment(0, dModel->getDof(0)), 0); + ::rl::math::Transform T2 = this->dModel->calcForwardKinematics(P2.segment(0, dModel->getDof(0)), 0); + + ::rl::math::Vector pushDir(2); + pushDir(0) = T2.translation().x() - T1.translation().x(); + pushDir(1) = T2.translation().y() - T1.translation().y(); + pushDir.normalize(); + if(currTraversingPushEdge.substr(0, DamaPrimPushInterior::getInstance()->getName().size()) == DamaPrimPushInterior::getInstance()->getName()) + pushDir *= DamaPrimPushInterior::getInstance()->POSTPROC_EXTEND_DIST; + else if(currTraversingPushEdge.substr(0, DamaPrimPushExterior::getInstance()->getName().size()) == DamaPrimPushExterior::getInstance()->getName()) + pushDir *= DamaPrimPushExterior::getInstance()->POSTPROC_EXTEND_DIST; + else if(currTraversingPushEdge.substr(0, DamaPrimPushFrontal::getInstance()->getName().size()) == DamaPrimPushFrontal::getInstance()->getName()) + pushDir *= DamaPrimPushFrontal::getInstance()->POSTPROC_EXTEND_DIST; + else if(currTraversingPushEdge.substr(0, DamaPrimPushMobile::getInstance()->getName().size()) == DamaPrimPushMobile::getInstance()->getName()) + pushDir *= DamaPrimPushMobile::getInstance()->POSTPROC_EXTEND_DIST; + + ::rl::math::Transform T3 = T2; + T3.translation().x() += pushDir(0); + T3.translation().y() += pushDir(1); + + if(this->dModel->debugMode) + { + ::std::cout << "### Extend " << currTraversingPushEdge << " from <"; + this->dModel->printQLine(P1, false, false, false, true); + ::std::cout << "> to <"; + this->dModel->printQLine(P2, false, false, false, true); + ::std::cout << "> with pushDir (" << pushDir(0) << " | " << pushDir(1) << "): "; + } + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 1; + rl::math::Vector q_ik_start = P2.segment(0, dModel->getDof(0)); + ::rl::math::Vector P3(P2); + bool calcInverse = DamaModel::calcInversePositionTaskPosture(this->dModel->mdl, T3, q_ik_start, constraint_position_orient, this->dModel->coupleJoint1And2); + if(calcInverse) + { + this->dModel->updateRobotPosition(P3); + + // insert P3 into path and actions right before the iterator i/e is pointing to + path.insert(i, P3); + actions.insert(e, DamaPrimTransit::getInstance()->getName()); + + if(this->dModel->debugMode) + { + ::std::cout << "<"; + this->dModel->printQLine(P3, false, false, false, true); + ::std::cout << ">" << ::std::endl << ::std::endl; + } + } + else + { + extendedAll = false; + + if(this->dModel->debugMode) + ::std::cout << "IK failed!" << ::std::endl << ::std::endl; + } + + currTraversingPushEdge = ""; + } + } + lastAction = *e; + } + + if(this->dModel->debugMode) + ::std::cout << "==> extendPushes: " << (extendedAll?"success":"fail") << ::std::endl << ::std::endl; + } + else + { + if(this->dModel->debugMode) + ::std::cout << "extendPushes: nothing to extend." << ::std::endl << ::std::endl; + } + + return extendedAll; + } + + bool DamaRrt::pathSmoothing(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions) + { + dama::Timer smoothTimer; + smoothTimer.start(); + + rl::plan::VectorList::iterator t1; + rl::plan::VectorList::iterator t2; + ::std::deque< ::std::string >::iterator te; + + /*t1 = path.begin(); + this->dModel->printQLine(*t1); + for(t2 = ++path.begin(), te = actions.begin(); t1 != path.end() && t2 != path.end() && te != actions.end(); ++t1, ++t2, ++te) + { + ::std::cout << *te << ::std::endl; + this->dModel->printQLine(*t2); + }*/ + + ::std::string currPrimitive = actions.front(); + ::std::size_t startIndex = 0; + ::std::size_t endIndex = 0; + + // Smooth each primitive separately + while(true) + { + // Determine endIndex for current primitive + endIndex = path.size()-1; + for(::std::size_t i=startIndex; igetName()*/) + { + if(this->dModel->debugMode) + ::std::cout << "# Start smoothing " << currPrimitive << " - from " << startIndex << " to " << endIndex << ::std::endl; + // N iterations + // TODO: iteration count should depend on the segment length etc.?! + for(::std::size_t i=0; i<100; ++i) + { + // 1) Pick two vertices at random, v1 will be different from and smaller than v2 + ::std::size_t v1index = ::std::rand() % (endIndex - startIndex + 1) + startIndex; + ::std::size_t v2index = ::std::rand() % (endIndex - startIndex + 1) + startIndex; + while(v1index == v2index) + v2index = ::std::rand() % (endIndex - startIndex + 1) + startIndex; + if(v2index < v1index) + std::swap(v1index,v2index); + + // 2) Check if there can be a shortcut at all AND if this shortcut is collision free + if(v2index - v1index > 1) + { + rl::plan::VectorList::iterator v1 = path.begin(); + ::std::advance(v1, v1index); + rl::plan::VectorList::iterator v2 = path.begin(); + ::std::advance(v2, v2index); + ::rl::plan::VectorList pathSegment; + ::std::deque< ::std::string > pathSegmentAction; + if(this->isCollisionFree(*v1, *v2, currPrimitive, pathSegment, pathSegmentAction)) + { + // TODO: is the shortcut really shorter?! check length or time ... + + // 3) Replace the original segment by the shortcut -> i.e., erase the intermediate segment + //::std::cout << "Shortcut found - from " << v1index << " to " << v2index << ::std::endl; + + /*::std::cout << "# Shortcut: " << ::std::endl; + t1 = pathSegment.begin(); + this->dModel->printQLine(*t1); + for(t2 = ++pathSegment.begin(), te = pathSegmentAction.begin(); t1 != pathSegment.end() && t2 != pathSegment.end() && te != pathSegmentAction.end(); ++t1, ++t2, ++te) + { + ::std::cout << *te << ::std::endl; + this->dModel->printQLine(*t2); + }*/ + + /*::std::cout << "# Path before: " << ::std::endl; + t1 = path.begin(); + this->dModel->printQLine(*t1); + for(t2 = ++path.begin(), te = actions.begin(); t1 != path.end() && t2 != path.end() && te != actions.end(); ++t1, ++t2, ++te) + { + ::std::cout << *te << ::std::endl; + this->dModel->printQLine(*t2); + }*/ + + rl::plan::VectorList::iterator v1next = path.begin(); + ::std::advance(v1next, v1index+1); + path.erase(v1next, v2); + rl::plan::VectorList::iterator pathSegmentInnerStart = ++pathSegment.begin(); + rl::plan::VectorList::iterator pathSegmentInnerEnd = --pathSegment.end(); + v1next = path.begin(); + ::std::advance(v1next, v1index+1); + path.insert(v1next, pathSegmentInnerStart, pathSegmentInnerEnd); + actions.erase(actions.begin()+v1index+1, actions.begin()+v2index); + actions.insert(actions.begin()+v1index+1, pathSegmentAction.begin()+1, pathSegmentAction.end()-1); + + /*::std::cout << "# Path after: " << ::std::endl; + t1 = path.begin(); + this->dModel->printQLine(*t1); + for(t2 = ++path.begin(), te = actions.begin(); t1 != path.end() && t2 != path.end() && te != actions.end(); ++t1, ++t2, ++te) + { + ::std::cout << *te << ::std::endl; + this->dModel->printQLine(*t2); + }*/ + + //::std::cout << "endIndex before: " << endIndex << ::std::endl; + endIndex = endIndex - (v2index - v1index - 1) + (pathSegment.size() - 2); + //::std::cout << "endIndex after: " << endIndex << ::std::endl; + } + } + } + } + + // Proceed with next primitive, if available + if(endIndex != path.size()-1) + { + currPrimitive = actions.at(endIndex); + startIndex = endIndex; + } + else + break; + } + + smoothTimer.stop(); + if(this->dModel->debugMode) + ::std::cout << "Path Smoothing took " << smoothTimer.elapsed() << " seconds." << ::std::endl; + + return true; + } + + /** Note: depends on this->dModel->currIsChosen !!! */ + void DamaRrt::completePartialGoal(const ::rl::math::Vector& samplePart, ::rl::math::Vector& goalFull) + { + ::std::vector goalDimDefinedTemp(*goalDimDefined); + + for(::std::size_t i=0; idModel->getDof(); ++i) + { + if(!this->goalDimDefined->at(i)) + { + assert((*this->goal)(i) == 0.0); + + if(!this->dModel->currIsChosen.at(i)) + assert(samplePart(i) == 0.0); + else + { + goalFull(i) = samplePart(i); + goalDimDefinedTemp.at(i) = true; + } + } + else + goalFull(i) = (*this->goal)(i); + } + + ::std::size_t currIndex = 0; + bool randomizeCurrSubspace = false; + for(::std::size_t i=0; idModel->getNumMovableComponents(); ++i) + { + randomizeCurrSubspace = false; + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + if(!goalDimDefinedTemp.at(currIndex+u) && !this->dModel->currIsChosen.at(currIndex+u)) + { + randomizeCurrSubspace = true; + break; + } + } + if(randomizeCurrSubspace) + this->dSampler->generateOnlyCollisionFree(goalFull, i, this->randSupportSurface(), &goalDimDefinedTemp); + + currIndex += this->dModel->getDof(i); + } + } + + void DamaRrt::sampleFromGoalFull(::rl::math::Vector &sample) + { + ::std::vector goalDimDefinedTemp(*goalDimDefined); + + ::std::size_t currIndex = 0; + bool fillCurrSubspace = false; + for(::std::size_t i=0; idModel->getNumMovableComponents(); ++i) + { + fillCurrSubspace = false; + for(::std::size_t u=0; udModel->getDof(i); ++u) + { + if(!goalDimDefinedTemp.at(currIndex+u)) + { + fillCurrSubspace = true; + break; + } + } + if(fillCurrSubspace) + { + if(this->rand() > 0.2f) + this->dSampler->generateOnlyCollisionFree(sample, i, this->randSupportSurface(), &goalDimDefinedTemp); + else + { + for(::std::size_t u=0; udModel->getDof(i); ++u) + if(!goalDimDefinedTemp.at(currIndex+u)) + sample(currIndex+u) = (*this->start)(currIndex+u); + } + } + + currIndex += this->dModel->getDof(i); + } + } + + void DamaRrt::setConfig(const bool twoTreeVersion, const bool hierarchicalVersion, const bool useAccurateDistance) + { + this->reset(); + + this->twoTreeVersion = twoTreeVersion; + if(this->twoTreeVersion) + { + begin.resize(2, NULL); + end.resize(2, NULL); + tree.resize(2); + } + else + { + begin.resize(1, NULL); + end.resize(1, NULL); + tree.resize(1); + } + + this->hierarchicalVersion = hierarchicalVersion; + + this->useAccurateDistance = useAccurateDistance; + } + + void DamaRrt::resetStatistics() + { + if(this->dModel != NULL) + { + this->dModel->reset(); + this->dModel->timeIK = 0.0; + } + this->iterationCount = 0; + this->edgeCount = 0; + this->vertexCount = 0; + this->timeSampling = 0; + this->timeNNSearch = 0; + this->timePropagate = 0; + this->timeConnect = 0; + } +} diff --git a/src/DamaRrt.h b/src/DamaRrt.h new file mode 100644 index 0000000..ebfff08 --- /dev/null +++ b/src/DamaRrt.h @@ -0,0 +1,136 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMARRT_H_ +#define _DAMA_DAMARRT_H_ + +#include "DamaRrtCon.h" + +#include +#include +#include +#include +#include + +namespace dama +{ + class DamaModel; + + class DamaSampler; + + class DamaRrt : public DamaRrtCon + { + public: + DamaRrt(::std::size_t numMovableComponents, ::std::size_t numSupportSurfaces); + + virtual ~DamaRrt(); + + virtual ::std::string getName() const; + + virtual void seed(const ::boost::mt19937::result_type& value); + + virtual bool solveAll(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions); + + virtual bool solve(); + + virtual bool connectOld(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen, ::std::string edgeAction, Vertex& vertex); + + virtual bool connect(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen, ::std::string edgeAction, Vertex& vertex); + + virtual bool isCollisionFree(const ::rl::math::Vector& v1, const ::rl::math::Vector& v2, ::std::string edgeAction, ::rl::plan::VectorList& pathSegment, ::std::deque< ::std::string >& pathSegmentAction); + + virtual Edge addEdge(const Vertex& u, const Vertex& v, ::std::string edgeAction, Tree& tree, bool drawIfPossible = true); + + virtual Vertex addVertex(Tree& tree, const ::rl::plan::VectorPtr& q); + + virtual void getPath(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions); + + virtual void getObjectPath(::rl::plan::VectorList& path); + + virtual void writeGraphML(Tree& tree, ::std::string fileName); + + virtual void finalizeWork(Vertex* end0, Vertex* end1); + + virtual bool postProc(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions); + + virtual bool extendPushes(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions); + + virtual bool pathSmoothing(::rl::plan::VectorList& path, ::std::deque< ::std::string >& actions); + + virtual void completePartialGoal(const ::rl::math::Vector& samplePart, ::rl::math::Vector& goalFull); + + virtual void setConfig(const bool twoTreeVersion, const bool hierarchicalVersion, const bool useAccurateDistance); + + virtual bool getTwoTreeVersion() const {return this->twoTreeVersion;}; + + virtual bool getUseAccurateDistance() const {return this->useAccurateDistance;}; + + virtual void resetStatistics(); + + virtual ::std::size_t getIterationCount() const {return this->iterationCount;}; + + virtual ::std::size_t getEdgeCount() const {return this->edgeCount;}; + + virtual ::std::size_t getVertexCount() const {return this->vertexCount;}; + + virtual ::rl::math::Real getTimeSampling() const {return this->timeSampling;}; + + virtual ::rl::math::Real getTimeNNSearch() const {return this->timeNNSearch;}; + + virtual ::rl::math::Real getTimePropagate() const {return this->timePropagate;}; + + virtual ::rl::math::Real getTimeConnect() const {return this->timeConnect;}; + + DamaModel* dModel; + + DamaSampler* dSampler; + + /** step size after which a new vertex/edge will be added during 'connect' */ + ::rl::math::Real extendStep; + + /** for each goal dimension defines if dimension should be reached or not */ + ::std::vector* goalDimDefined; + + protected: + virtual void choose(::rl::math::Vector& chosen, std::vector& currIsChosen, bool forwardSearch); + + virtual void sampleFromGoalFull(::rl::math::Vector &sample); + + ::boost::variate_generator< ::boost::mt19937, ::boost::uniform_int<> > randSubspace; + + ::boost::variate_generator< ::boost::mt19937, ::boost::uniform_int<> > randSupportSurface; + + /** true for spanning two trees, first one starting at the start, second one starting at the goal */ + bool twoTreeVersion; + + /** true for using hierarchical version; spanning an object path first and then for each step using the standard dama problem solver */ + bool hierarchicalVersion; + + /** true for using the accurate distance between two configurations. i.e. the robot travel distance (false: use max of euclid subspace distance) */ + bool useAccurateDistance; + + /** FOR STATISTICS, for all (sub)trees together, needs to be reset via resetStatistics() */ + ::std::size_t iterationCount; + ::std::size_t edgeCount; + ::std::size_t vertexCount; + ::rl::math::Real timeSampling; + ::rl::math::Real timeNNSearch; + ::rl::math::Real timePropagate; + ::rl::math::Real timeConnect; + + /** File Names */ + ::std::string metaFileName; + ::std::string tree0FileName; + ::std::string tree1FileName; + ::std::string treeSolFileName; + ::std::string pathSolVerticesFileName; + ::std::string pathSolEdgesFileName; + + private: + + }; +} + +#endif /* _DAMA_DAMARRT_H_ */ diff --git a/src/DamaRrtAction.cpp b/src/DamaRrtAction.cpp new file mode 100644 index 0000000..22a8e07 --- /dev/null +++ b/src/DamaRrtAction.cpp @@ -0,0 +1,447 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include "DamaRrtAction.h" +#include +#include +#include +#include + +#if _MSC_VER < 1600 +#define nullptr NULL // TODO +#endif + +namespace dama +{ + DamaRrtAction::DamaRrtAction(const ::std::size_t& trees) : + Planner(), + delta(1.0f), + epsilon(1.0e-3f), + kd(true), + sampler(NULL), + begin(trees, NULL), + end(trees, NULL), + tree(trees) + { + } + + DamaRrtAction::~DamaRrtAction() + { + } + + DamaRrtAction::Edge + DamaRrtAction::addEdge(const Vertex& u, const Vertex& v, Tree& tree) + { + Edge e = ::boost::add_edge(u, v, tree).first; + + if (NULL != this->viewer) + { + this->viewer->drawConfigurationEdge(*tree[u].q, *tree[v].q); + } + + return e; + } + + void + DamaRrtAction::addPoint(NearestNeighbors& nn, const QueryItem& p) + { + NearestNeighbors::iterator i; + + for (i = nn.begin(); i != nn.end(); ++i) + { + if (NULL == *i) + { + break; + } + } + + NeighborSearchTreePtr tree(new NeighborSearchTree()); + + if (nn.end() == i) + { + i = nn.insert(i, tree); + } + else + { + *i = tree; + } + + for (NearestNeighbors::iterator j = nn.begin(); j != i; ++j) + { + if (NULL != *j) + { + (*i)->insert((*j)->begin(), (*j)->end()); + j->reset(); + } + } + + tree->insert(p); + } + + DamaRrtAction::Vertex + DamaRrtAction::addVertex(Tree& tree, const ::rl::plan::VectorPtr& q) + { + Vertex v = ::boost::add_vertex(tree); + tree[v].index = ::boost::num_vertices(tree) - 1; + tree[v].q = q; + tree[v].radius = ::std::numeric_limits< ::rl::math::Real >::max(); + + if (this->kd) + { + this->addPoint(tree[::boost::graph_bundle].nn, QueryItem(q.get(), v)); + } + + if (NULL != this->viewer) + { + this->viewer->drawConfigurationVertex(*tree[v].q); + } + + return v; + } + + bool + DamaRrtAction::areEqual(const ::rl::math::Vector& lhs, const ::rl::math::Vector& rhs) const + { + if (this->model->distance(lhs, rhs) > this->epsilon) + { + return false; + } + else + { + return true; + } + } + + void + DamaRrtAction::choose(::rl::math::Vector& chosen) + { + this->sampler->generate(chosen); + } + + DamaRrtAction::Vertex + DamaRrtAction::connect(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen) + { + ::rl::math::Real distance = nearest.second; + ::rl::math::Real step = distance; + + bool reached = false; + + if (step <= this->delta) + { + reached = true; + } + else + { + step = this->delta; + } + + ::rl::plan::VectorPtr last = ::std::make_shared< ::rl::math::Vector >(this->model->getDof()); + + this->model->interpolate(*tree[nearest.first].q, chosen, step / distance, *last); + + if (NULL != this->viewer) + { +// this->viewer->drawConfiguration(*last); + } + + this->model->setPosition(*last); + this->model->updateFrames(); + + if (this->model->isColliding()) + { + return NULL; + } + + ::rl::math::Vector next(this->model->getDof()); + + while (!reached) + { + distance = this->model->distance(*last, chosen); + step = distance; + + if (step <= this->delta) + { + reached = true; + } + else + { + step = this->delta; + } + + this->model->interpolate(*last, chosen, step / distance, next); + + if (NULL != this->viewer) + { +// this->viewer->drawConfiguration(next); + } + + this->model->setPosition(next); + this->model->updateFrames(); + + if (this->model->isColliding()) + { + break; + } + + *last = next; + } + + Vertex connected = this->addVertex(tree, last); + this->addEdge(nearest.first, connected, tree); + return connected; + } + + DamaRrtAction::Vertex + DamaRrtAction::extend(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen) + { + ::rl::math::Real distance = nearest.second; + ::rl::math::Real step = ::std::min(distance, this->delta); + + ::rl::plan::VectorPtr next = ::std::make_shared< ::rl::math::Vector >(this->model->getDof()); + + this->model->interpolate(*tree[nearest.first].q, chosen, step / distance, *next); + + this->model->setPosition(*next); + this->model->updateFrames(); + + if (!this->model->isColliding()) + { + Vertex extended = this->addVertex(tree, next); + this->addEdge(nearest.first, extended, tree); + return extended; + } + + return NULL; + } + + ::std::string + DamaRrtAction::getName() const + { + return "RRT"; + } + + ::std::size_t + DamaRrtAction::getNumEdges() const + { + ::std::size_t edges = 0; + + for (::std::size_t i = 0; i < this->tree.size(); ++i) + { + edges += ::boost::num_edges(this->tree[i]); + } + + return edges; + } + + ::std::size_t + DamaRrtAction::getNumVertices() const + { + ::std::size_t vertices = 0; + + for (::std::size_t i = 0; i < this->tree.size(); ++i) + { + vertices += ::boost::num_vertices(this->tree[i]); + } + + return vertices; + } + + void + DamaRrtAction::getPath(::rl::plan::VectorList& path) + { + Vertex i = this->end[0]; + + while (i != this->begin[0]) + { + path.push_front(*this->tree[0][i].q); + i = ::boost::source(*::boost::in_edges(i, this->tree[0]).first, this->tree[0]); + } + + path.push_front(*this->tree[0][i].q); + } + + DamaRrtAction::Neighbor + DamaRrtAction::nearest(const Tree& tree, const ::rl::math::Vector& chosen) + { + Neighbor p(nullptr, ::std::numeric_limits< ::rl::math::Real >::max()); + + if (this->kd) + { + QueryItem query(&chosen, nullptr); + + for (NearestNeighbors::const_iterator i = tree[::boost::graph_bundle].nn.begin(); i != tree[::boost::graph_bundle].nn.end(); ++i) + { + if (NULL != *i) + { + NeighborSearch search( + *i->get(), + query, + 1, + 0, + true, + Distance(this->model) + ); + + if (search.begin()->second < p.second) + { + p.first = search.begin()->first.second; + p.second = search.begin()->second; + } + } + } + } + else + { + for (VertexIteratorPair i = ::boost::vertices(tree); i.first != i.second; ++i.first) + { + ::rl::math::Real d = this->model->transformedDistance(*tree[*i.first].q, chosen); + + if (d < p.second) + { + p.first = *i.first; + p.second = d; + } + } + } + + p.second = this->model->inverseOfTransformedDistance(p.second); + + return p; + } + + void + DamaRrtAction::reset() + { + for (::std::size_t i = 0; i < this->tree.size(); ++i) + { + this->tree[i].clear(); + this->tree[i][::boost::graph_bundle].nn.clear(); + this->begin[i] = NULL; + this->end[i] = NULL; + } + + if(this->viewer != NULL) + this->viewer->reset(); + } + + bool + DamaRrtAction::solve() + { + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector >(*this->start)); + + ::rl::math::Vector chosen(this->model->getDof()); + + timer.start(); + timer.stop(); + + while (timer.elapsedDuration() < this->duration) + { + this->choose(chosen); + + Neighbor nearest = this->nearest(this->tree[0], chosen); + + Vertex extended = this->extend(this->tree[0], nearest, chosen); + + if (NULL != extended) + { + if (this->areEqual(*this->tree[0][extended].q, *this->goal)) + { + this->end[0] = extended; + return true; + } + } + + timer.stop(); + } + + return false; + } + + const ::rl::math::Real* + DamaRrtAction::CartesianIterator::operator()(const QueryItem& p) const + { + return p.first->data(); // TODO + } + + const ::rl::math::Real* + DamaRrtAction::CartesianIterator::operator()(const QueryItem& p, const int&) const + { + return p.first->data() + p.first->size(); // TODO + } + + DamaRrtAction::Distance::Distance() : + model(NULL) + { + } + + DamaRrtAction::Distance::Distance(::rl::plan::Model* model) : + model(model) + { + } + + template<> + ::rl::math::Real +#if (CGAL_VERSION_NR > 1030801000) + DamaRrtAction::Distance::max_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< DamaRrtAction::SearchTraits::FT >& r) const +#else + DamaRrtAction::Distance::max_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< DamaRrtAction::SearchTraits >& r) const +#endif + { + ::rl::math::Vector min(r.dimension()); + ::rl::math::Vector max(r.dimension()); + + for (int i = 0; i < r.dimension(); ++i) + { + min(i) = r.min_coord(i); + max(i) = r.max_coord(i); + } + + return this->model->maxDistanceToRectangle(*q.first, min, max); + } + + template<> + ::rl::math::Real +#if (CGAL_VERSION_NR > 1030801000) + DamaRrtAction::Distance::min_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< DamaRrtAction::SearchTraits::FT >& r) const +#else + DamaRrtAction::Distance::min_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< DamaRrtAction::SearchTraits >& r) const +#endif + { + ::rl::math::Vector min(r.dimension()); + ::rl::math::Vector max(r.dimension()); + + for (int i = 0; i < r.dimension(); ++i) + { + min(i) = r.min_coord(i); + max(i) = r.max_coord(i); + } + + return this->model->minDistanceToRectangle(*q.first, min, max); + } + + ::rl::math::Real + DamaRrtAction::Distance::min_distance_to_rectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cutting_dimension) const + { + return this->model->minDistanceToRectangle(q, min, max, cutting_dimension); + } + + ::rl::math::Real + DamaRrtAction::Distance::new_distance(const ::rl::math::Real& dist, const ::rl::math::Real& old_off, const ::rl::math::Real& new_off, const int& cutting_dimension) const + { + return this->model->newDistance(dist, old_off, new_off, cutting_dimension); + } + + ::rl::math::Real + DamaRrtAction::Distance::transformed_distance(const ::rl::math::Real& d) const + { + return this->model->transformedDistance(d); + } + + ::rl::math::Real + DamaRrtAction::Distance::transformed_distance(const Query_item& q1, const Query_item& q2) const + { + return this->model->transformedDistance(*q2.first, *q1.first); + } +} diff --git a/src/DamaRrtAction.h b/src/DamaRrtAction.h new file mode 100644 index 0000000..81cd3c8 --- /dev/null +++ b/src/DamaRrtAction.h @@ -0,0 +1,188 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMARRTACTION_H_ +#define _DAMA_DAMARRTACTION_H_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "Timer.h" + +namespace dama +{ + class Model; + class Sampler; + class Verifier; + + /** + * Rapidly-Exploring Random Trees. + */ + class DamaRrtAction : public ::rl::plan::Planner + { + public: + DamaRrtAction(const ::std::size_t& trees = 1); + + virtual ~DamaRrtAction(); + + virtual ::std::string getName() const; + + virtual ::std::size_t getNumEdges() const; + + virtual ::std::size_t getNumVertices() const; + + virtual void getPath(::rl::plan::VectorList& path); + + virtual void reset(); + + virtual bool solve(); + + /** Configuration step size. */ + ::rl::math::Real delta; + + /** Epsilon for configuration comparison. */ + ::rl::math::Real epsilon; + + /** Use kd-tree for nearest neighbor search instead of brute-force. */ + bool kd; + + ::rl::plan::Sampler* sampler; + + protected: + struct VertexBundle + { + ::std::size_t index; + + ::rl::plan::VectorPtr q; + + ::rl::math::Real radius; + + ::rl::plan::TransformPtr t; + + // TODO Andre: ::std::vector< ::rl::math::Transform > objectPoses; + }; + + struct EdgeBundle + { + ::std::string action; + }; + + struct TreeBundle; + + typedef ::boost::adjacency_list< + ::boost::listS, + ::boost::listS, + ::boost::bidirectionalS, + VertexBundle, + EdgeBundle, + TreeBundle + > Tree; + + typedef ::boost::adjacency_list_traits< + ::boost::listS, + ::boost::listS, + ::boost::bidirectionalS, + ::boost::listS + >::vertex_descriptor Vertex; + + typedef ::std::pair< const ::rl::math::Vector*, Vertex > QueryItem; + + struct CartesianIterator + { + typedef const ::rl::math::Real* result_type; + + const ::rl::math::Real* operator()(const QueryItem& p) const; + + const ::rl::math::Real* operator()(const QueryItem& p, const int&) const; + }; + + struct Distance + { + typedef QueryItem Query_item; + + Distance(); + + Distance(::rl::plan::Model* model); + + template< typename SearchTraits > ::rl::math::Real max_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< SearchTraits >& r) const; + + template< typename SearchTraits > ::rl::math::Real min_distance_to_rectangle(const Query_item& q, const ::CGAL::Kd_tree_rectangle< SearchTraits >& r) const; + + ::rl::math::Real min_distance_to_rectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cutting_dimension) const; + + ::rl::math::Real new_distance(const ::rl::math::Real& dist, const ::rl::math::Real& old_off, const ::rl::math::Real& new_off, const int& cutting_dimension) const; + + ::rl::math::Real transformed_distance(const ::rl::math::Real& d) const; + + ::rl::math::Real transformed_distance(const Query_item& q1, const Query_item& q2) const; + + ::rl::plan::Model* model; + }; + + typedef ::CGAL::Search_traits< ::rl::math::Real, QueryItem, const ::rl::math::Real*, CartesianIterator > SearchTraits; + + typedef ::rl::plan::Orthogonal_k_neighbor_search< SearchTraits, Distance > NeighborSearch; + + typedef NeighborSearch::Tree NeighborSearchTree; + + typedef ::std::shared_ptr< NeighborSearchTree > NeighborSearchTreePtr; + + typedef ::std::vector< NeighborSearchTreePtr > NearestNeighbors; + + struct TreeBundle + { + NearestNeighbors nn; + }; + + typedef ::boost::graph_traits< Tree >::edge_descriptor Edge; + + typedef ::boost::graph_traits< Tree >::edge_iterator EdgeIterator; + + typedef ::std::pair< EdgeIterator, EdgeIterator > EdgeIteratorPair; + + typedef ::boost::graph_traits< Tree >::vertex_iterator VertexIterator; + + typedef ::std::pair< VertexIterator, VertexIterator > VertexIteratorPair; + + typedef ::std::pair< Vertex, ::rl::math::Real > Neighbor; + + virtual Edge addEdge(const Vertex& u, const Vertex& v, Tree& tree); + + void addPoint(NearestNeighbors& nn, const QueryItem& p); + + Vertex addVertex(Tree& tree, const ::rl::plan::VectorPtr& q); + + bool areEqual(const ::rl::math::Vector& lhs, const ::rl::math::Vector& rhs) const; + + virtual void choose(::rl::math::Vector& chosen); + + virtual Vertex connect(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen); + + virtual Vertex extend(Tree& tree, const Neighbor& nearest, const ::rl::math::Vector& chosen); + + virtual Neighbor nearest(const Tree& tree, const ::rl::math::Vector& chosen); + + ::std::vector< Vertex > begin; + + ::std::vector< Vertex > end; + + ::std::vector< Tree > tree; + + ::dama::Timer timer; + + private: + + }; +} + +#endif // _DAMA_DAMARRTACTION_H_ diff --git a/src/DamaRrtCon.cpp b/src/DamaRrtCon.cpp new file mode 100644 index 0000000..31a3ef6 --- /dev/null +++ b/src/DamaRrtCon.cpp @@ -0,0 +1,58 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include "DamaRrtCon.h" +#include + +namespace dama +{ + DamaRrtCon::DamaRrtCon() : + DamaRrtGoalBias() + { + } + + DamaRrtCon::~DamaRrtCon() + { + } + + ::std::string + DamaRrtCon::getName() const + { + return "RRT Connect"; + } + + bool + DamaRrtCon::solve() + { + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector >(*this->start)); + + ::rl::math::Vector chosen(this->model->getDof()); + + timer.start(); + timer.stop(); + + while (timer.elapsedDuration() < this->duration) + { + this->choose(chosen); + + Neighbor nearest = this->nearest(this->tree[0], chosen); + + Vertex connected = this->connect(this->tree[0], nearest, chosen); + + if (NULL != connected) + { + if (this->areEqual(*this->tree[0][connected].q, *this->goal)) + { + this->end[0] = connected; + return true; + } + } + + timer.stop(); + } + + return false; + } +} diff --git a/src/DamaRrtCon.h b/src/DamaRrtCon.h new file mode 100644 index 0000000..f050cc7 --- /dev/null +++ b/src/DamaRrtCon.h @@ -0,0 +1,31 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMARRTCON_H_ +#define _DAMA_DAMARRTCON_H_ + +#include "DamaRrtGoalBias.h" + +namespace dama +{ + class DamaRrtCon : public DamaRrtGoalBias + { + public: + DamaRrtCon(); + + virtual ~DamaRrtCon(); + + virtual ::std::string getName() const; + + bool solve(); + + protected: + + private: + + }; +} + +#endif // _DAMA_DAMARRTCON_H_ diff --git a/src/DamaRrtGoalBias.cpp b/src/DamaRrtGoalBias.cpp new file mode 100644 index 0000000..38937ee --- /dev/null +++ b/src/DamaRrtGoalBias.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaRrtGoalBias.h" +#include "Timer.h" + +namespace dama +{ + DamaRrtGoalBias::DamaRrtGoalBias() : + DamaRrtAction(), + probability(0.05f), + rand( + ::boost::mt19937(static_cast< ::boost::mt19937::result_type >(0)), + ::boost::uniform_real< ::rl::math::Real >(0.0f, 1.0f) + ) + { + } + + DamaRrtGoalBias::~DamaRrtGoalBias() + { + } + + void + DamaRrtGoalBias::choose(::rl::math::Vector& chosen) + { + if (this->rand() > this->probability) + { + DamaRrtAction::choose(chosen); + } + else + { + chosen = *this->goal; + } + } + + ::std::string + DamaRrtGoalBias::getName() const + { + return "RRT Goal Bias"; + } + + void + DamaRrtGoalBias::seed(const ::boost::mt19937::result_type& value) + { + this->rand.engine().seed(value); + } +} diff --git a/src/DamaRrtGoalBias.h b/src/DamaRrtGoalBias.h new file mode 100644 index 0000000..60a2f86 --- /dev/null +++ b/src/DamaRrtGoalBias.h @@ -0,0 +1,41 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMARRTGOALBIAS_H_ +#define _DAMA_DAMARRTGOALBIAS_H_ + +#include +#include +#include + +#include "DamaRrtAction.h" + +namespace dama +{ + class DamaRrtGoalBias : public DamaRrtAction + { + public: + DamaRrtGoalBias(); + + virtual ~DamaRrtGoalBias(); + + virtual ::std::string getName() const; + + virtual void seed(const ::boost::mt19937::result_type& value); + + /** Probability of choosing goal configuration. */ + ::rl::math::Real probability; + + protected: + virtual void choose(::rl::math::Vector& chosen); + + ::boost::variate_generator< ::boost::mt19937, ::boost::uniform_real< ::rl::math::Real > > rand; + + private: + + }; +} + +#endif // _DAMA_DAMARRTGOALBIAS_H_ diff --git a/src/DamaSampler.cpp b/src/DamaSampler.cpp new file mode 100644 index 0000000..2b10439 --- /dev/null +++ b/src/DamaSampler.cpp @@ -0,0 +1,156 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaModel.h" +#include "DamaSampler.h" + +namespace dama +{ + DamaSampler::DamaSampler() : + Sampler(), + dModel(NULL), + randReal( + ::boost::mt19937(static_cast< ::boost::mt19937::result_type >(0)), + ::boost::uniform_real< ::rl::math::Real >(0.0f, 1.0f) + ) + { + } + + DamaSampler::~DamaSampler() + { + } + + void DamaSampler::init() + { + vecMaximum.resize(this->dModel->getNumMovableComponents()); + vecMinimum.resize(this->dModel->getNumMovableComponents()); + for(::std::size_t i=0; idModel->getNumMovableComponents(); ++i) + { + ::rl::math::Vector maximum(this->dModel->getDof(i)); + this->dModel->getMaximum(maximum, i); + vecMaximum.at(i) = maximum; + ::rl::math::Vector minimum(this->dModel->getDof(i)); + this->dModel->getMinimum(minimum, i); + vecMinimum.at(i) = minimum; + } + } + + // should not be called, instead use the version with index + void DamaSampler::generate(::rl::math::Vector& q) + { + bool robotObjectCoupled = false; + this->generateOnly(q, 0, robotObjectCoupled); + } + + void DamaSampler::generateOnly(::rl::math::Vector& q, const ::std::size_t indexSubspace, const ::std::size_t supportSurface, const ::std::vector* qIsDefined) + { + ::std::size_t startIndex = this->dModel->indexFromSubspace(indexSubspace); + + ::rl::math::Vector vecCurrMinimum = vecMinimum.at(indexSubspace); + ::rl::math::Vector vecCurrMaximum = vecMaximum.at(indexSubspace); + + if(indexSubspace > 0 && supportSurface < this->dModel->vecSupportSurface.size()) + { + vecCurrMinimum = this->dModel->vecSupportSurface.at(supportSurface)->getMin(); + vecCurrMaximum = this->dModel->vecSupportSurface.at(supportSurface)->getMax(); + } + + while(true) + { + for(::std::size_t i=0; idModel->getDof(indexSubspace); ++i) + { + if(qIsDefined == NULL || qIsDefined->at(startIndex+i) == false) + { + if(this->dModel->coupleJoint1And2 && indexSubspace == 0 && ((i == 1 && qIsDefined != NULL && qIsDefined->at(startIndex+2) == true) || (i == 2))) + q(startIndex+i) = q(startIndex+(i == 1 ? 2 : 1)); + else + q(startIndex+i) = vecCurrMinimum(i) + this->randReal() * (vecCurrMaximum(i) - vecCurrMinimum(i)); + } + } + + // As sample will be in the air, sample as long as there is no valid grasp position of the arm for our object + if(indexSubspace > 0 && supportSurface == this->dModel->vecSupportSurface.size() && !this->dModel->allPrismaticJoints) + { + // calculate the robot position to grasp the object + rl::math::Transform T_grasp; + T_grasp.translation().x() = q(startIndex); + T_grasp.translation().y() = q(startIndex+1); + T_grasp.translation().z() = q(startIndex+2) + DamaPrimPickup::HEIGHT_OFFSET_OBJECT; + T_grasp.linear() = ( + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Z_AXIS, rl::math::Vector3::UnitZ()) * // WILL BE FREE AXIS + rl::math::AngleAxis(DamaPrimPickup::PICKUP_Y_AXIS, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(DamaPrimPickup::PICKUP_X_AXIS, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + rl::math::Matrix66 constraint_position_orient = rl::math::Matrix66::Zero(); + constraint_position_orient.diagonal() << 1, 1, 1, 1, 1, 0; + + // TODO: somewhat arbitrary for now -> better to begin on top of table instead of in the nullposition?! + //rl::math::Vector q_ik_start = (rl::math::Vector(10) << 0.0, 0.0, 0.0, 0.0, 15.0 * rl::math::DEG2RAD, -20.0 * rl::math::DEG2RAD, 12.0 * rl::math::DEG2RAD, 112.0 * rl::math::DEG2RAD, -10.0 * rl::math::DEG2RAD, 0.0).finished(); + + rl::math::Vector q_ik_start = (rl::math::Vector(10) << 6.0, 2.0, 2.0, 80.0, 0.0, -40.0, 30.0, 120.0, 0.0, 15.0).finished() * rl::math::DEG2RAD; + + //rl::math::Vector q_ik_start = rl::math::Vector::Ones(this->dModel->getDof(0)) * 20 * rl::math::DEG2RAD; + + if(this->dModel->debugMode) + { + ::std::cout << "Calculate IK to T = ("; + this->dModel->printTransform(T_grasp, false); + ::std::cout << ") starting at q_deg = ("; + this->dModel->printQLine(q_ik_start * rl::math::RAD2DEG, false, false, false, false); + ::std::cout << ")" << ::std::endl; + } + + dama::Timer timerIK; + timerIK.start(); + bool calcInverse = DamaModel::calcInversePositionTaskPosture(this->dModel->mdlGrasp, T_grasp, q_ik_start, constraint_position_orient, this->dModel->coupleJoint1And2); + timerIK.stop(); + this->dModel->timeIK += timerIK.elapsed(); + + if(calcInverse) + { + /*if(qIsDefined != NULL) + { + for(::std::size_t i=0; idModel->getDof(0); ++i) + assert(!(qIsDefined->at(i))); + }*/ + this->dModel->updateRobotPosition(q, this->dModel->mdlGrasp); + break; + } + } + else + break; + } + + //this->model->clip(q); // TODO: need to uncomment in the future?! + } + + void DamaSampler::generateOnlyCollisionFree(::rl::math::Vector& q, const ::std::size_t subspace, const ::std::size_t supportSurface, const ::std::vector* qIsDefined) + { + // TODO: maybe also respect robotObjectCoupled and look for robot-collisions in this case?! test it! + + do + { + this->generateOnly(q, subspace, supportSurface, qIsDefined); + if(this->dModel->debugMode) + { + ::std::string printSupportSurface = supportSurface < this->dModel->vecSupportSurface.size() ? boost::lexical_cast< ::std::string >(supportSurface) : "NONE"; + ::std::cout << "DamaSampler::generateOnlyCollisionFree for subspace " << subspace << " and support surface " << printSupportSurface << ":" << ::std::endl; + this->dModel->printQLine(q, false, true, true, true); + } + this->dModel->setPosition(q, subspace); + if(subspace == 0) + this->dModel->updateFrames(); + } + while(this->dModel->isCollidingWithScene(subspace)); + } + + void DamaSampler::seed(const ::boost::mt19937::result_type& value) + { + this->randReal.engine().seed(value); + } +} diff --git a/src/DamaSampler.h b/src/DamaSampler.h new file mode 100644 index 0000000..9002b4b --- /dev/null +++ b/src/DamaSampler.h @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMASAMPLER_H_ +#define _DAMA_DAMASAMPLER_H_ + +#include +#include +#include +#include + +#include + +namespace dama +{ + class DamaModel; + + class DamaSampler : public ::rl::plan::Sampler + { + public: + DamaSampler(); + + virtual ~DamaSampler(); + + virtual void init(); + + virtual void generate(::rl::math::Vector& q); + + virtual void generateOnly(::rl::math::Vector& q, const ::std::size_t subspace, const ::std::size_t supportSurface, const ::std::vector* qIsDefined = NULL); + + virtual void generateOnlyCollisionFree(::rl::math::Vector& q, const ::std::size_t subspace, const ::std::size_t supportSurface, const ::std::vector* qIsDefined = NULL); + + virtual void seed(const ::boost::mt19937::result_type& value); + + DamaModel* dModel; + + protected: + ::boost::variate_generator< ::boost::mt19937, ::boost::uniform_real< ::rl::math::Real > > randReal; + ::std::vector< ::rl::math::Vector > vecMaximum; + ::std::vector< ::rl::math::Vector > vecMinimum; + + private: + + }; +} + +#endif /* _DAMA_DAMASAMPLER_H_ */ diff --git a/src/DamaSupportSurface.cpp b/src/DamaSupportSurface.cpp new file mode 100644 index 0000000..f9d47a5 --- /dev/null +++ b/src/DamaSupportSurface.cpp @@ -0,0 +1,51 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaSupportSurface.h" +#include "DamaModel.h" + +namespace dama +{ + DamaSupportSurface::DamaSupportSurface(::std::string _name, ::rl::math::Real _height, const ::rl::math::Vector& _min, const ::rl::math::Vector& _max) + { + this->name = _name; + this->height = _height; + this->dim = _max.size(); + this->min = _min; + this->max = _max; + } + + ::std::string DamaSupportSurface::getName() + { + return this->name; + } + + ::rl::math::Real DamaSupportSurface::getHeight() + { + return this->height; + } + + ::rl::math::Vector DamaSupportSurface::getMin() + { + return this->min; + } + + ::rl::math::Real DamaSupportSurface::getMin(::std::size_t i) + { + return (this->min)(i); + } + + ::rl::math::Vector DamaSupportSurface::getMax() + { + return this->max; + } + + ::rl::math::Real DamaSupportSurface::getMax(::std::size_t i) + { + return (this->max)(i); + } +} diff --git a/src/DamaSupportSurface.h b/src/DamaSupportSurface.h new file mode 100644 index 0000000..fe0954d --- /dev/null +++ b/src/DamaSupportSurface.h @@ -0,0 +1,38 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_DAMASUPPORTSURFACE_H_ +#define _DAMA_DAMASUPPORTSURFACE_H_ + +#include +#include +#include + +namespace dama +{ + class DamaSupportSurface + { + public: + DamaSupportSurface(::std::string _name, ::rl::math::Real _height, const ::rl::math::Vector& _min, const ::rl::math::Vector& _max); + ~DamaSupportSurface() {}; + + ::std::string getName(); + ::rl::math::Real getHeight(); + + ::rl::math::Vector getMin(); + ::rl::math::Real getMin(::std::size_t i); + ::rl::math::Vector getMax(); + ::rl::math::Real getMax(::std::size_t i); + + private: + ::std::string name; + ::rl::math::Real height; + ::std::size_t dim; + ::rl::math::Vector min; + ::rl::math::Vector max; + }; +} + +#endif /* _DAMA_DAMASUPPORTSURFACE_H_ */ diff --git a/src/LICENSE.md b/src/LICENSE.md new file mode 100644 index 0000000..d608516 --- /dev/null +++ b/src/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/src/Timer.h b/src/Timer.h new file mode 100644 index 0000000..92340d1 --- /dev/null +++ b/src/Timer.h @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_TIMER_H_ +#define _DAMA_TIMER_H_ + +#include +#include + +namespace dama +{ + class Timer + { + private: + ::std::chrono::steady_clock::time_point startTime, stopTime; + + public: + Timer() + { + } + + virtual ~Timer() + { + } + + void start() + { + this->startTime = ::std::chrono::steady_clock::now(); + } + + void stop() + { + this->stopTime = ::std::chrono::steady_clock::now(); + } + + double elapsed() + { + ::std::chrono::steady_clock::duration elapsedTime = this->stopTime - this->startTime; + return (::std::chrono::duration_cast< ::std::chrono::duration< double > >(elapsedTime)).count(); + } + + ::std::chrono::steady_clock::duration elapsedDuration() + { + return (this->stopTime - this->startTime); + } + + static void sleep(double timeInSeconds) + { + ::std::this_thread::sleep_for( ::std::chrono::duration< double >(timeInSeconds) ); + } + }; +} + +#endif /* _DAMA_TIMER_H_ */ diff --git a/src/XmlFactory.cpp b/src/XmlFactory.cpp new file mode 100644 index 0000000..7167f65 --- /dev/null +++ b/src/XmlFactory.cpp @@ -0,0 +1,521 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "XmlFactory.h" +#include "DamaModel.h" +#include "DamaSampler.h" + +namespace dama +{ + XmlFactory::XmlFactory() + { + } + + XmlFactory::~XmlFactory() + { + } + + boost::shared_ptr< DamaModel > XmlFactory::create(const ::std::string& filename, const bool isViewerModel) + { + boost::shared_ptr< DamaModel > model; + model = boost::make_shared< DamaModel >(); + this->load(filename, model.get(), isViewerModel); + return model; + } + + void XmlFactory::load(const ::std::string& filename, DamaModel* model, const bool isViewerModel) + { + ::rl::xml::DomParser parser; + + ::rl::xml::Document doc = parser.readFile(filename, "", XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + + doc.substitute(XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + + ::rl::xml::Path path(doc); + + model->prefixName = path.eval("//dama").getNodeTab(0).getAttribute("prefixName").getValue(); + model->description = path.eval("//dama").getNodeTab(0).getAttribute("description").getValue(); + + model->debugMode = path.eval("count(//planner/debugMode) > 0").getBoolval(); + + model->workspaceSampling = path.eval("count(//planner/workspaceSampling) > 0").getBoolval(); + if(model->workspaceSampling) + { + rl::xml::Object xmlWorkspaceSampling = path.eval("//planner/workspaceSampling"); + model->workspaceSamplingEdges = boost::lexical_cast< ::std::size_t >(xmlWorkspaceSampling.getNodeTab(0).getAttribute("edges").getValue()); + } + else + model->workspaceSamplingEdges = 0; + + // TODO: work with shared pointers instead of 'new'?? but the object is not available after load returns ... + + if(!isViewerModel) + { + rl::xml::Object xmlSceneFile = path.eval("//model/sceneFile"); + rl::sg::solid::Scene* scene = new rl::sg::solid::Scene(); + scene->load(xmlSceneFile.getNodeTab(0).getUri(xmlSceneFile.getNodeTab(0).getAttribute("href").getValue())); + model->model = scene->getModel(0); + model->scene = scene; + } + else + { + rl::xml::Object xmlSceneFile; + if(path.eval("count(//model/sceneHDFile) > 0").getBoolval()) + xmlSceneFile = path.eval("//model/sceneHDFile"); + else + xmlSceneFile = path.eval("//model/sceneFile"); + rl::sg::so::Scene* scene = new rl::sg::so::Scene(); + scene->load(xmlSceneFile.getNodeTab(0).getUri(xmlSceneFile.getNodeTab(0).getAttribute("href").getValue())); + model->model = scene->getModel(0); + model->scene = scene; + } + + // TODO: init mdl2 when it is clear how to handle model2-stuff for GUI + + rl::xml::Object xmlMdlFile = path.eval("//model/mdlFile"); + rl::mdl::XmlFactory mdlFactory; + model->mdl = dynamic_cast< rl::mdl::Dynamic* >(mdlFactory.create(xmlMdlFile.getNodeTab(0).getUri(xmlMdlFile.getNodeTab(0).getAttribute("href").getValue()))); + + if(path.eval("count(//model/mdlGraspFile) > 0").getBoolval()) + { + rl::xml::Object xmlMdlGraspFile = path.eval("//model/mdlGraspFile"); + rl::mdl::XmlFactory mdlGraspFactory; + model->mdlGrasp = dynamic_cast< rl::mdl::Dynamic* >(mdlGraspFactory.create(xmlMdlGraspFile.getNodeTab(0).getUri(xmlMdlGraspFile.getNodeTab(0).getAttribute("href").getValue()))); + } + else + { + model->mdlGrasp = model->mdl; + } + + model->isViewerModel = isViewerModel; + + // allRevoluteJoints, allPrismaticJoints, coupleJoint1And2, trajSampleTime + model->allRevoluteJoints = path.eval("count(//model/allJointsAreRevolute) > 0").getBoolval(); + model->allPrismaticJoints = path.eval("count(//model/allJointsArePrismatic) > 0").getBoolval(); + model->coupleJoint1And2 = path.eval("count(//model/coupleJoint1AndJoint2) > 0").getBoolval(); + + // numRobots, numObjects, dimObjects, minimumObjects, maximumObjects + rl::xml::Object xmlModel = path.eval("//model"); + model->numRobots = 1; + model->numObjects = boost::lexical_cast< ::std::size_t >(xmlModel.getNodeTab(0).getAttribute("numOfObjects").getValue()); + model->dimObjects = boost::lexical_cast< ::std::size_t >(xmlModel.getNodeTab(0).getAttribute("dimOfObjects").getValue()); + rl::xml::Object xmlObjectSamplingSpace = path.eval("//model/objectSamplingSpace"); + model->minimumObjects.resize(model->dimObjects); + model->minimumObjects(0) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("x_min").getValue()); + model->minimumObjects(1) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("y_min").getValue()); + model->minimumObjects(2) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("z_min").getValue()); + model->maximumObjects.resize(model->dimObjects); + model->maximumObjects(0) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("x_max").getValue()); + model->maximumObjects(1) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("y_max").getValue()); + model->maximumObjects(2) = boost::lexical_cast< double >(xmlObjectSamplingSpace.getNodeTab(0).getAttribute("z_max").getValue()); + //::std::cout << "minimumObjects: " << model->minimumObjects(0) << ", " << model->minimumObjects(1) << ", " << model->minimumObjects(2) << ::std::endl; + //::std::cout << "maximumObjects: " << model->maximumObjects(0) << ", " << model->maximumObjects(1) << ", " << model->maximumObjects(2) << ::std::endl; + + // objectSupportSurfaces + rl::xml::Object xmlObjectSupportSurface = path.eval("//model/objectSupportSurface"); + for(int i=0; i(xmlObjectSupportSurface.getNodeTab(i).getAttribute("z").getValue()); + + ::rl::math::Vector minObjSS(model->dimObjects); + minObjSS(0) = boost::lexical_cast< double >(xmlObjectSupportSurface.getNodeTab(i).getAttribute("x_min").getValue()); + minObjSS(1) = boost::lexical_cast< double >(xmlObjectSupportSurface.getNodeTab(i).getAttribute("y_min").getValue()); + minObjSS(2) = z; + + ::rl::math::Vector maxObjSS(model->dimObjects); + maxObjSS(0) = boost::lexical_cast< double >(xmlObjectSupportSurface.getNodeTab(i).getAttribute("x_max").getValue()); + maxObjSS(1) = boost::lexical_cast< double >(xmlObjectSupportSurface.getNodeTab(i).getAttribute("y_max").getValue()); + maxObjSS(2) = z; + + ::std::string name = xmlObjectSupportSurface.getNodeTab(i).getAttribute("name").getValue(); + model->vecSupportSurface.push_back(new DamaSupportSurface(name, z, minObjSS, maxObjSS)); + } + + + + + // Planner + model->dRrt = new DamaRrt(model->getNumMovableComponents(), model->vecSupportSurface.size()); + model->dRrt->model = model; + model->dRrt->dModel = model; + + // start + rl::xml::Object xmlStart = path.eval("//problem/start/q"); + model->dRrt->start = new rl::math::Vector(xmlStart.getNodeNr()); + // TODO: assert xmlStart.getNodeNr() == model.dof() + for(int i=0; idRrt->start)(i) = boost::lexical_cast(xmlStart.getNodeTab(i).getContent()); + + if(xmlStart.getNodeTab(i).hasAttribute("unit")) + { + if("deg" == xmlStart.getNodeTab(i).getAttribute("unit").getValue()) + { + (*model->dRrt->start)(i) *= rl::math::DEG2RAD; + } + } + } + + // goal and goalDefined + rl::xml::Object xmlGoal = path.eval("//problem/goal/q"); + model->dRrt->goal = new rl::math::Vector(xmlGoal.getNodeNr()); + model->dRrt->goalDimDefined = new ::std::vector(xmlGoal.getNodeNr()); + // TODO: assert xmlGoal.getNodeNr() == model.dof() + for(int i=0; idRrt->goal)(i) = boost::lexical_cast(xmlGoal.getNodeTab(i).getContent()); + + if(xmlGoal.getNodeTab(i).hasAttribute("unit")) + { + if("deg" == xmlGoal.getNodeTab(i).getAttribute("unit").getValue()) + { + (*model->dRrt->goal)(i) *= rl::math::DEG2RAD; + } + } + + if(xmlGoal.getNodeTab(i).hasAttribute("free")) + { + if("true" == xmlGoal.getNodeTab(i).getAttribute("free").getValue()) + { + model->dRrt->goalDimDefined->at(i) = false; + } + else + { + model->dRrt->goalDimDefined->at(i) = true; + } + } + else + { + model->dRrt->goalDimDefined->at(i) = true; + } + } + + // set robot to start pose + model->mdl->setPosition(*model->dRrt->start); + model->mdl->forwardPosition(); + + + // Sampler + model->dRrt->dSampler = new DamaSampler(); + model->dRrt->dSampler->model = model; + model->dRrt->dSampler->dModel = model; + model->dRrt->sampler = model->dRrt->dSampler; + + + // Planner Settings + if(path.eval("count(//planner/kinematicSoftRange) > 0").getBoolval()) + { + rl::xml::Object xmlKinematicSoftRange = path.eval("//planner/kinematicSoftRange"); + model->kinematicSoftRangeScale = boost::lexical_cast< double >(xmlKinematicSoftRange.getNodeTab(0).getAttribute("scale").getValue()); + } + else + model->kinematicSoftRangeScale = 1.0; + model->dRrt->dSampler->init(); // important: init the sampler after setting the kinematicSoftRangeScale + + model->dRrt->delta = path.eval("number(//planner/delta)").getFloatval(1.0); + if("deg" == path.eval("string(//planner/delta/@unit)").getStringval()) + model->dRrt->delta *= rl::math::DEG2RAD; + + model->dRrt->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >( path.eval("number(//planner/duration)").getFloatval(0) )); + if(model->dRrt->duration <= ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(0.01f) )) + model->dRrt->duration = ::std::chrono::steady_clock::duration::max(); + + model->dRrt->extendStep = path.eval("number(//planner/extendStep)").getFloatval(0.1); + + model->dRrt->epsilon = path.eval("number(//planner/epsilon)").getFloatval(1.0e-3f); + model->epsilon = model->dRrt->epsilon; + model->epsilonTransformed = model->transformedDistance(model->epsilon); + + model->dRrt->probability = 0.5; // obsolete, is used by rl-planners to determine the probability to sample a goal + + model->dRrt->kd = path.eval("count(//planner/kdTree) > 0").getBoolval(); + + // Seed + rl::xml::Object xmlSeed = path.eval("//planner/seed"); + model->seedType = xmlSeed.getNodeTab(0).getAttribute("type").getValue(); + model->groupSeed = boost::lexical_cast< unsigned int >(path.eval("number(//planner/seed)").getFloatval(time(NULL))); + if(model->seedType == "singleOnly") + { + model->groupSeed = boost::lexical_cast< unsigned int >(xmlSeed.getNodeTab(0).getAttribute("group").getValue()); + model->singleSeed = boost::lexical_cast< ::std::size_t >(xmlSeed.getNodeTab(0).getAttribute("single").getValue()); + } + else + { + model->groupSeed = boost::lexical_cast< unsigned int >(xmlSeed.getNodeTab(0).getAttribute("group").getValue()); + model->singleSeed = boost::lexical_cast< ::std::size_t >(xmlSeed.getNodeTab(0).getAttribute("single").getValue()); + } + + model->numRuns = boost::lexical_cast< ::std::size_t >(path.eval("number(//planner/numRuns)").getFloatval(1)); + + model->bidirectional = path.eval("count(//planner/bidirectional) > 0").getBoolval(); + model->hierarchical = path.eval("count(//planner/hierarchical) > 0").getBoolval(); + if(model->hierarchical) + { + model->objectPathTimeout = boost::lexical_cast< rl::math::Real >(path.eval("//planner/hierarchical").getNodeTab(0).getAttribute("objectPathTimeout").getValue()); + if(model->objectPathTimeout <= 0.01) + model->objectPathTimeout = std::numeric_limits< rl::math::Real >::max(); + model->subProblemTimeout = boost::lexical_cast< rl::math::Real >(path.eval("//planner/hierarchical").getNodeTab(0).getAttribute("subProblemTimeout").getValue()); + if(model->subProblemTimeout <= 0.01) + model->subProblemTimeout = std::numeric_limits< rl::math::Real >::max(); + } + model->accurateDistance = path.eval("count(//planner/accurateDistance) > 0").getBoolval(); + model->dRrt->setConfig(model->bidirectional, model->hierarchical, model->accurateDistance); + + //::std::cout << "model->dRrt->duration: " << model->dRrt->duration << ::std::endl; + + // Sampling + rl::xml::Object xmlSampling = path.eval("//planner/sampling"); + model->sampleRobotPoseProb = boost::lexical_cast< rl::math::Real >(xmlSampling.getNodeTab(0).getAttribute("robotPoseProb").getValue()); + model->sampleObjectsFreeProb = boost::lexical_cast< rl::math::Real >(xmlSampling.getNodeTab(0).getAttribute("objectsFreeProb").getValue()); + model->sampleRobotRandProb = boost::lexical_cast< rl::math::Real >(xmlSampling.getNodeTab(0).getAttribute("robotRandProb").getValue()); + + // Metrics + rl::xml::Object xmlMetricRobot = path.eval("//planner/metricRobot"); + model->metRadToMeter = boost::lexical_cast< rl::math::Real >(xmlMetricRobot.getNodeTab(0).getAttribute("radToMeter").getValue()); + model->metQuatToMeter = boost::lexical_cast< rl::math::Real >(xmlMetricRobot.getNodeTab(0).getAttribute("quatToMeter").getValue()); + model->metOverallRobotWeight = boost::lexical_cast< rl::math::Real >(xmlMetricRobot.getNodeTab(0).getAttribute("overallRobotWeight").getValue()); + + rl::xml::Object xmlMetricComposed = path.eval("//planner/metricComposed"); + model->metType = xmlMetricComposed.getNodeTab(0).getAttribute("type").getValue(); + if(model->metType == "SumComponentMovementWithObjectPenalty") + { + model->metMovingObjectPenalty = boost::lexical_cast< rl::math::Real >(xmlMetricComposed.getNodeTab(0).getAttribute("movingObjectPenalty").getValue()); + } + else if(model->metType == "ForwardDistanceWithObjectPenalty" || model->metType == "MiniESPMetricWithPenalties") + { + model->metMovingObjectPenalty = boost::lexical_cast< rl::math::Real >(xmlMetricComposed.getNodeTab(0).getAttribute("movingObjectPenalty").getValue()); + model->metMoveToObjectPenalty = boost::lexical_cast< rl::math::Real >(xmlMetricComposed.getNodeTab(0).getAttribute("moveToObjectPenalty").getValue()); + model->metMoveToObjectFactor = boost::lexical_cast< rl::math::Real >(xmlMetricComposed.getNodeTab(0).getAttribute("moveToObjectFactor").getValue()); + } + + // Inverse Kinematics + if(path.eval("count(//planner/inverseKinematics) > 0").getBoolval()) + { + rl::xml::Object xmlInverseKinematics = path.eval("//planner/inverseKinematics"); + DamaModel::ikPostureGainMaxStep = boost::lexical_cast< rl::math::Real >(xmlInverseKinematics.getNodeTab(0).getAttribute("postureGainMaxStepDeg").getValue()) * rl::math::DEG2RAD; + if(xmlInverseKinematics.getNodeTab(0).hasAttribute("prematureQuit") && xmlInverseKinematics.getNodeTab(0).getAttribute("prematureQuit").getValue() == "true") + DamaModel::ikPrematureQuit = true; + else + DamaModel::ikPrematureQuit = false; + } + + // Collision-Detection-related and Primitive-related + rl::xml::Object xmlPrimitives = path.eval("//planner/primitives"); + if(xmlPrimitives.getNodeTab(0).hasAttribute("numEndEffectorBodies")) + model->numEndEffectorBodies = boost::lexical_cast< ::std::size_t >(xmlPrimitives.getNodeTab(0).getAttribute("numEndEffectorBodies").getValue()); + else + model->numEndEffectorBodies = 1; + if(model->isViewerModel) + model->currEndEffectorBodyVis = (::rl::sg::so::Body*)(model->scene->getModel(0)->getBody(model->scene->getModel(0)->getNumBodies() - model->numEndEffectorBodies)); + else + model->currEndEffectorBody = model->scene->getModel(0)->getBody(model->scene->getModel(0)->getNumBodies() - model->numEndEffectorBodies); + + // Primitives + // NOTE: also take a look at and maybe adapt DamaModel::isColliding if adding new primitives + model->vecDamaPrim.clear(); + if(path.eval("count(//planner/primitives/primTransit) > 0").getBoolval()) + { + DamaPrimTransit::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimTransit::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primTransit"); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimTransit::getInstance()); + } + if(path.eval("count(//planner/primitives/primPush) > 0").getBoolval()) + { + // set the push variables within primPush + rl::xml::Object xmlPrimPush = path.eval("//planner/primitives/primPush"); + if(xmlPrimPush.getNodeTab(0).hasAttribute("dist_to_object_xy")) + DamaPrimPush::DIST_TO_OBJECT_XY = boost::lexical_cast< rl::math::Real >(xmlPrimPush.getNodeTab(0).getAttribute("dist_to_object_xy").getValue()); + if(xmlPrimPush.getNodeTab(0).hasAttribute("height_offset_object")) + DamaPrimPush::HEIGHT_OFFSET_OBJECT = boost::lexical_cast< rl::math::Real >(xmlPrimPush.getNodeTab(0).getAttribute("height_offset_object").getValue()); + if(xmlPrimPush.getNodeTab(0).hasAttribute("max_push_dist")) + DamaPrimPush::MAX_PUSH_DIST = boost::lexical_cast< rl::math::Real >(xmlPrimPush.getNodeTab(0).getAttribute("max_push_dist").getValue()); + if(xmlPrimPush.getNodeTab(0).hasAttribute("max_push_dist_joint_angle")) + DamaPrimPush::MAX_PUSH_DIST_JOINT = boost::lexical_cast< rl::math::Real >(xmlPrimPush.getNodeTab(0).getAttribute("max_push_dist_joint_angle").getValue()) * rl::math::DEG2RAD; + + if(path.eval("count(//planner/primitives/primPush/primPushMobile) > 0").getBoolval()) + { + DamaPrimPushMobile::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimPushMobile::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primPush/primPushMobile"); + if(xmlPrim.getNodeTab(0).hasAttribute("postproc_extend_dist")) + DamaPrimPushMobile::getInstance()->POSTPROC_EXTEND_DIST = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("postproc_extend_dist").getValue()); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimPushMobile::getInstance()); + } + if(path.eval("count(//planner/primitives/primPush/primPushInterior) > 0").getBoolval()) + { + DamaPrimPushInterior::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimPushInterior::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primPush/primPushInterior"); + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_inward_angle")) + DamaPrimPushInterior::getInstance()->TILT_HAND_INWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_inward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_downward_angle")) + DamaPrimPushInterior::getInstance()->TILT_HAND_DOWNWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_downward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("postproc_extend_dist")) + DamaPrimPushInterior::getInstance()->POSTPROC_EXTEND_DIST = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("postproc_extend_dist").getValue()); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimPushInterior::getInstance()); + } + if(path.eval("count(//planner/primitives/primPush/primPushExterior) > 0").getBoolval()) + { + DamaPrimPushExterior::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimPushExterior::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primPush/primPushExterior"); + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_inward_angle")) + DamaPrimPushExterior::getInstance()->TILT_HAND_INWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_inward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_downward_angle")) + DamaPrimPushExterior::getInstance()->TILT_HAND_DOWNWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_downward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("postproc_extend_dist")) + DamaPrimPushExterior::getInstance()->POSTPROC_EXTEND_DIST = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("postproc_extend_dist").getValue()); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimPushExterior::getInstance()); + } + if(path.eval("count(//planner/primitives/primPush/primPushFrontal) > 0").getBoolval()) + { + DamaPrimPushFrontal::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimPushFrontal::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primPush/primPushFrontal"); + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_inward_angle")) + DamaPrimPushFrontal::getInstance()->TILT_HAND_INWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_inward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_downward_angle")) + DamaPrimPushFrontal::getInstance()->TILT_HAND_DOWNWARD_ANGLE = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_downward_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("postproc_extend_dist")) + DamaPrimPushFrontal::getInstance()->POSTPROC_EXTEND_DIST = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("postproc_extend_dist").getValue()); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimPushFrontal::getInstance()); + } + } + if(path.eval("count(//planner/primitives/primPickup) > 0").getBoolval()) + { + DamaPrimPickup::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimPickup::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primPickup"); + if(xmlPrim.getNodeTab(0).hasAttribute("height_offset_object")) + DamaPrimPickup::HEIGHT_OFFSET_OBJECT = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("height_offset_object").getValue()); + if(xmlPrim.getNodeTab(0).hasAttribute("height_pickup_dist_object")) + DamaPrimPickup::HEIGHT_PICKUP_DIST_OBJECT = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("height_pickup_dist_object").getValue()); + if(xmlPrim.getNodeTab(0).hasAttribute("min_plane_dist_for_pickup")) + DamaPrimPickup::MIN_PLANE_DIST_FOR_PICKUP = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("min_plane_dist_for_pickup").getValue()); + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_x_angle")) + DamaPrimPickup::PICKUP_X_AXIS = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_x_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_y_angle")) + DamaPrimPickup::PICKUP_Y_AXIS = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_y_angle").getValue()) * rl::math::DEG2RAD; + if(xmlPrim.getNodeTab(0).hasAttribute("tilt_hand_z_angle")) + DamaPrimPickup::PICKUP_Z_AXIS = boost::lexical_cast< rl::math::Real >(xmlPrim.getNodeTab(0).getAttribute("tilt_hand_z_angle").getValue()) * rl::math::DEG2RAD; + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimPickup::getInstance()); + } + if(path.eval("count(//planner/primitives/primTransferRigid) > 0").getBoolval()) + { + DamaPrimTransferRigid::getInstance()->dModel = model; + model->vecDamaPrim.push_back(DamaPrimTransferRigid::getInstance()); + rl::xml::Object xmlPrim = path.eval("//planner/primitives/primTransferRigid"); + ::std::string endEffectorBodySearch = ""; + if(xmlPrim.getNodeTab(0).hasAttribute("endEffectorBody")) + endEffectorBodySearch = xmlPrim.getNodeTab(0).getAttribute("endEffectorBody").getValue(); + this->setPrimEndEffectorBody(model, endEffectorBodySearch, DamaPrimTransferRigid::getInstance()); + } + + // Remove all end-effector bodies but the first one + ::std::size_t initialNumBodies = model->scene->getModel(0)->getNumBodies(); + for(::std::size_t i=initialNumBodies-1; i>initialNumBodies-model->numEndEffectorBodies; --i) + model->scene->getModel(0)->remove(model->scene->getModel(0)->getBody(i)); + + + + // PostProcessing + model->pathSmoothing = path.eval("count(//postProc/pathSmoothing) > 0").getBoolval(); + model->extendPushes = path.eval("count(//postProc/extendPushes) > 0").getBoolval(); + + + // Viewer + model->viewerMode = path.eval("//viewer").getNodeTab(0).getAttribute("mode").getValue(); + if(model->viewerMode != "loop" && model->viewerMode != "once" && model->viewerMode != "off") + model->viewerMode = "loop"; + model->viewerOnlyResult = path.eval("//viewer").getNodeTab(0).getAttribute("onlyResult").getValue(); + if(model->viewerOnlyResult != "on" && model->viewerOnlyResult != "off") + model->viewerOnlyResult = "off"; + model->speedFactor = boost::lexical_cast< double >(path.eval("//viewer").getNodeTab(0).getAttribute("speedFactor").getValue()); + model->showFullTree = path.eval("count(//viewer/showFullTree) > 0").getBoolval(); + model->showExportableTree = path.eval("count(//viewer/showExportableTree) > 0").getBoolval(); + if(model->showExportableTree) + { + model->pointSize = boost::lexical_cast< double >(path.eval("//viewer/showExportableTree").getNodeTab(0).getAttribute("pointSize").getValue()); + model->lineWidth = boost::lexical_cast< double >(path.eval("//viewer/showExportableTree").getNodeTab(0).getAttribute("lineWidth").getValue()); + } + else + { + model->pointSize = 8.0; + model->lineWidth = 1.0; + } + } + + void XmlFactory::setPrimEndEffectorBody(DamaModel* model, ::std::string endEffectorBodySearch, DamaPrim* damaPrim) + { + if(endEffectorBodySearch == "") + { + if(model->isViewerModel) + damaPrim->endEffectorBodyVis = model->currEndEffectorBodyVis; + else + damaPrim->endEffectorBody = model->currEndEffectorBody; + } + + bool foundBody = false; + for(::std::size_t i=model->scene->getModel(0)->getNumBodies()-1; i>model->scene->getModel(0)->getNumBodies()-1-model->numEndEffectorBodies; --i) + { + if(model->scene->getModel(0)->getBody(i)->getName() == endEffectorBodySearch) + { + if(model->isViewerModel) + damaPrim->endEffectorBodyVis = (::rl::sg::so::Body*)(model->scene->getModel(0)->getBody(i)); + else + damaPrim->endEffectorBody = model->scene->getModel(0)->getBody(i); + foundBody = true; + break; + } + } + if(!foundBody) + { + if(model->isViewerModel) + damaPrim->endEffectorBodyVis = model->currEndEffectorBodyVis; + else + damaPrim->endEffectorBody = model->currEndEffectorBody; + } + } +} diff --git a/src/XmlFactory.h b/src/XmlFactory.h new file mode 100644 index 0000000..94dc97a --- /dev/null +++ b/src/XmlFactory.h @@ -0,0 +1,39 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Markus Rickert, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_XMLFACTORY_H_ +#define _DAMA_XMLFACTORY_H_ + +#include +#include +#include + +#include "DamaPrim.h" + +namespace dama +{ + class DamaModel; + + class XmlFactory + { + public: + XmlFactory(); + + virtual ~XmlFactory(); + + boost::shared_ptr< DamaModel > create(const ::std::string& filename, const bool isViewerModel = false); + + void load(const ::std::string& filename, DamaModel* model, const bool isViewerModel = false); + + void setPrimEndEffectorBody(DamaModel* model, ::std::string endEffectorBodySearch, DamaPrim* damaPrim); + + protected: + + private: + + }; +} + +#endif /* _DAMA_XMLFACTORY_H_ */ diff --git a/src/rlDamaDemoGUI/CMakeLists.txt b/src/rlDamaDemoGUI/CMakeLists.txt new file mode 100644 index 0000000..9f8231c --- /dev/null +++ b/src/rlDamaDemoGUI/CMakeLists.txt @@ -0,0 +1,108 @@ +PROJECT(rlDamaDemoGUI) + +FIND_PACKAGE(Boost COMPONENTS system REQUIRED) +FIND_PACKAGE(OpenGL REQUIRED) +FIND_PACKAGE(Qt4 REQUIRED) + +FIND_PACKAGE(Cgal REQUIRED) +FIND_PACKAGE(Coin REQUIRED) +FIND_PACKAGE(Eigen REQUIRED) +FIND_PACKAGE(Iconv) +FIND_PACKAGE(LibXml2 REQUIRED) +FIND_PACKAGE(Solid REQUIRED) +FIND_PACKAGE(SoQt REQUIRED) +FIND_PACKAGE(ZLIB) + +find_package(RL COMPONENTS KIN MDL SG PLAN REQUIRED) + +ADD_DEFINITIONS( + -DCGAL_DISABLE_ROUNDING_MATH_CHECK + ${COIN_DEFINITIONS} + ${QT_DEFINITIONS} + ${SOQT_DEFINITIONS} +) + +INCLUDE_DIRECTORIES( + BEFORE + ${CMAKE_CURRENT_SOURCE_DIR}/.. + ${Boost_INCLUDE_DIR} + ${CGAL_INCLUDE_DIRS} + ${COIN_INCLUDE_DIRS} + ${EIGEN_INCLUDE_DIRS} + ${LIBXML2_INCLUDE_DIRS} + ${OPENGL_INCLUDE_DIR} + ${QT_INCLUDES} + ${SOQT_INCLUDE_DIRS} +) + +LINK_DIRECTORIES( + ${Boost_LIBRARY_DIRS} +) + +SET( + HDRS + ConfigurationDelegate.h + ConfigurationModel.h + ConfigurationSpaceScene.h + ConfigurationSpaceThread.h + DamaPlanner.h + MainWindow.h + PlannerModel.h + Thread.h + Viewer.h +) + +SET( + SRCS + ConfigurationDelegate.cpp + ConfigurationModel.cpp + ConfigurationSpaceScene.cpp + ConfigurationSpaceThread.cpp + DamaPlanner.cpp + MainWindow.cpp + PlannerModel.cpp + rlDamaDemoGUI.cpp + Thread.cpp + Viewer.cpp +) + +QT4_WRAP_CPP( + MOC_SRCS + ConfigurationDelegate.h + ConfigurationSpaceScene.h + ConfigurationSpaceThread.h + DamaPlanner.h + MainWindow.h + Thread.h + Viewer.h + OPTIONS + -DBOOST_TT_HAS_OPERATOR_HPP_INCLUDED +) + +ADD_EXECUTABLE( + rlDamaDemoGUI + ${HDRS} + ${SRCS} + ${MOC_SRCS} +) + +TARGET_LINK_LIBRARIES( + rlDamaDemoGUI + moplplan + rlplan + rlkin + rlsg + ${Boost_LIBRARIES} + ${CGAL_LIBRARIES} + ${COIN_LIBRARIES} + ${LIBXML2_LIBRARIES} + ${OPENGL_LIBRARIES} + ${QT_QTCORE_LIBRARY} + ${QT_QTGUI_LIBRARY} + ${QT_QTOPENGL_LIBRARY} + ${SOQT_LIBRARIES} +) + +ADD_DEFINITIONS(-DHAVE_SOLID) +INCLUDE_DIRECTORIES(${SOLID_INCLUDE_DIRS}) +TARGET_LINK_LIBRARIES(rlDamaDemoGUI ${SOLID_LIBRARIES}) diff --git a/src/rlDamaDemoGUI/ConfigurationDelegate.cpp b/src/rlDamaDemoGUI/ConfigurationDelegate.cpp new file mode 100644 index 0000000..37d7895 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationDelegate.cpp @@ -0,0 +1,76 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include + +#include "ConfigurationDelegate.h" +#include "MainWindow.h" + +ConfigurationDelegate::ConfigurationDelegate(QObject* parent) : + QItemDelegate(parent) +{ +} + +ConfigurationDelegate::~ConfigurationDelegate() +{ +} + +QWidget* +ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const +{ + QDoubleSpinBox* editor = new QDoubleSpinBox(parent); + + rl::math::Vector maximum(MainWindow::instance()->model->getDof(0)); + MainWindow::instance()->model->getMaximum(maximum, 0); + rl::math::Vector minimum(MainWindow::instance()->model->getDof(0)); + MainWindow::instance()->model->getMinimum(minimum, 0); + Eigen::Matrix< rl::math::Unit, Eigen::Dynamic, 1 > qUnits(MainWindow::instance()->model->getDof(0)); + MainWindow::instance()->model->getPositionUnits(qUnits); + + if (rl::math::UNIT_RADIAN == qUnits(index.row())) + { + editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); + editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); + editor->setSingleStep(1.0f); + } + else + { + editor->setMinimum(minimum(index.row())); + editor->setMaximum(maximum(index.row())); + editor->setSingleStep(0.1f); + } + + QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); + + return editor; +} + +void +ConfigurationDelegate::setEditorData(QWidget* editor, const QModelIndex& index) const +{ + QDoubleSpinBox* doubleSpinBox = static_cast< QDoubleSpinBox* >(editor); + doubleSpinBox->setValue(index.model()->data(index, Qt::DisplayRole).toDouble()); +} + +void +ConfigurationDelegate::setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const +{ + QDoubleSpinBox* doubleSpinBox = static_cast< QDoubleSpinBox* >(editor); + doubleSpinBox->interpretText(); + model->setData(index, doubleSpinBox->value(), Qt::EditRole); +} + +void +ConfigurationDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const +{ + editor->setGeometry(option.rect); +} + +void +ConfigurationDelegate::valueChanged(double d) +{ + emit commitData(static_cast< QWidget* >(QObject::sender())); +} diff --git a/src/rlDamaDemoGUI/ConfigurationDelegate.h b/src/rlDamaDemoGUI/ConfigurationDelegate.h new file mode 100644 index 0000000..15b9b56 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationDelegate.h @@ -0,0 +1,37 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _CONFIGURATIONDELEGATE_H_ +#define _CONFIGURATIONDELEGATE_H_ + +#include + +class ConfigurationDelegate : public QItemDelegate +{ + Q_OBJECT + +public: + ConfigurationDelegate(QObject* parent = NULL); + + virtual ~ConfigurationDelegate(); + + QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + + void setEditorData(QWidget* editor, const QModelIndex& index) const; + + void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; + + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + +public slots: + void valueChanged(double d); + +protected: + +private: + +}; + +#endif // _CONFIGURATIONDELEGATE_H_ diff --git a/src/rlDamaDemoGUI/ConfigurationModel.cpp b/src/rlDamaDemoGUI/ConfigurationModel.cpp new file mode 100644 index 0000000..6e2d574 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationModel.cpp @@ -0,0 +1,140 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include "ConfigurationModel.h" +#include "MainWindow.h" +#include "Thread.h" +#include "Viewer.h" + +ConfigurationModel::ConfigurationModel(QObject* parent) : + QAbstractTableModel(parent) +{ +} + +ConfigurationModel::~ConfigurationModel() +{ +} + +int +ConfigurationModel::columnCount(const QModelIndex& parent) const +{ + return 1; +} + +QVariant +ConfigurationModel::data(const QModelIndex& index, int role) const +{ + if (NULL == MainWindow::instance()->model) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + { + Eigen::Matrix< rl::math::Unit, Eigen::Dynamic, 1 > qUnits(MainWindow::instance()->model->getDof(0)); + MainWindow::instance()->model->getPositionUnits(qUnits); + + if (rl::math::UNIT_RADIAN == qUnits(index.row())) + { + return (*MainWindow::instance()->q)(index.row()) * rl::math::RAD2DEG; + } + else + { + return (*MainWindow::instance()->q)(index.row()); + } + } + case Qt::TextAlignmentRole: + return Qt::AlignRight; + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +ConfigurationModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +ConfigurationModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (Qt::DisplayRole == role && Qt::Vertical == orientation) + { + return QString::number(section); + } + + return QVariant(); +} + +void +ConfigurationModel::invalidate() +{ + this->reset(); +} + +int +ConfigurationModel::rowCount(const QModelIndex& parent) const +{ + if (NULL == MainWindow::instance()->model) + { + return 0; + } + + return MainWindow::instance()->model->getDof(0); +} + +bool +ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (NULL == MainWindow::instance()->model) + { + return false; + } + + if (MainWindow::instance()->thread->isRunning()) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + Eigen::Matrix< rl::math::Unit, Eigen::Dynamic, 1 > qUnits(MainWindow::instance()->model->getDof(0)); + MainWindow::instance()->model->getPositionUnits(qUnits); + + if (rl::math::UNIT_RADIAN == qUnits(index.row())) + { + (*MainWindow::instance()->q)(index.row()) = value.value< ::rl::math::Real >() * rl::math::DEG2RAD; + } + else + { + (*MainWindow::instance()->q)(index.row()) = value.value< ::rl::math::Real >(); + } + + MainWindow::instance()->viewer->drawConfiguration(*MainWindow::instance()->q); + + emit dataChanged(index, index); + + return true; + } + + return false; +} diff --git a/src/rlDamaDemoGUI/ConfigurationModel.h b/src/rlDamaDemoGUI/ConfigurationModel.h new file mode 100644 index 0000000..5422147 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationModel.h @@ -0,0 +1,38 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _CONFIGURATIONMODEL_H_ +#define _CONFIGURATIONMODEL_H_ + +#include + +class ConfigurationModel : public QAbstractTableModel +{ +public: + ConfigurationModel(QObject* parent = NULL); + + virtual ~ConfigurationModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + +protected: + +private: + +}; + +#endif // _CONFIGURATIONMODEL_H_ diff --git a/src/rlDamaDemoGUI/ConfigurationSpaceScene.cpp b/src/rlDamaDemoGUI/ConfigurationSpaceScene.cpp new file mode 100644 index 0000000..c57bd58 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationSpaceScene.cpp @@ -0,0 +1,272 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include + +#include "ConfigurationModel.h" +#include "ConfigurationSpaceScene.h" +#include "ConfigurationSpaceThread.h" +#include "MainWindow.h" +#include "Thread.h" +#include "Viewer.h" + +ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : + QGraphicsScene(parent), + delta(1.0f), + model(NULL), + x(0), + y(1), + edges(), + path(), + thread(new ConfigurationSpaceThread(this)) +{ + QObject::connect( + this->thread, + SIGNAL(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)), + this, + SLOT(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)) + ); +} + +ConfigurationSpaceScene::~ConfigurationSpaceScene() +{ + this->thread->stop(); +} + +void +ConfigurationSpaceScene::addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb) +{ + QGraphicsRectItem* rect = this->addRect( + x - w / 2.0f, + -y - h / 2.0f, + w, + h, + QPen(Qt::NoPen), + QBrush(QColor(rgb, rgb, rgb)) + ); + + rect->setZValue(1); +} + +void +ConfigurationSpaceScene::clear() +{ + QList items = this->items(); + + while (!items.isEmpty()) + { + delete items.takeFirst(); + } + + this->edges.clear(); + this->path.clear(); +} + +void +ConfigurationSpaceScene::drawConfiguration(const rl::math::Vector& q) +{ +} + +void +ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const rl::math::Vector& v, const bool& free) +{ + QGraphicsLineItem* line = this->addLine( + u(this->x), + -u(this->y), + v(this->x), + -v(this->y), + free ? QPen(QBrush(QColor(0, 128, 0)), 0.0f) : QPen(QBrush(QColor(128, 0, 0)), 0.0f) + ); + + line->setZValue(2); + + this->edges.push_back(line); +} + +void +ConfigurationSpaceScene::drawConfigurationVertex(const rl::math::Vector& q, const bool& free) +{ +} + +void +ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) +{ + this->resetPath(); + + rl::plan::VectorList::const_iterator i = path.begin(); + rl::plan::VectorList::const_iterator j = ++path.begin(); + + while (i != path.end() && j != path.end()) + { + QGraphicsLineItem* line = this->addLine( + (*i)(this->x), + -(*i)(this->y), + (*j)(this->x), + -(*j)(this->y), + QPen(QBrush(QColor(0, 255, 0)), 0.0f) + ); + + line->setZValue(3); + + this->path.push_back(line); + + ++i; + ++j; + } +} + +void +ConfigurationSpaceScene::drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1) +{ +} + +void +ConfigurationSpaceScene::drawPoint(const rl::math::Vector& xyz) +{ +} + +void +ConfigurationSpaceScene::drawSphere(const rl::math::Vector& center, const rl::math::Real& radius) +{ +} + +void +ConfigurationSpaceScene::drawSweptVolume(const rl::plan::VectorList& path) +{ +} + +void +ConfigurationSpaceScene::drawWork(const rl::math::Transform& t) +{ +} + +void +ConfigurationSpaceScene::drawWorkEdge(const rl::math::Vector& u, const rl::math::Vector& v) +{ +} + +void +ConfigurationSpaceScene::drawWorkPath(const rl::plan::VectorList& path) +{ +} + +void +ConfigurationSpaceScene::drawWorkVertex(const rl::math::Vector& q) +{ +} + +void +ConfigurationSpaceScene::eval() +{ + this->thread->stop(); + + this->clear(); + + rl::math::Vector maximum(this->model->getDof(0)); + this->model->getMaximum(maximum, 0); + rl::math::Vector minimum(this->model->getDof(0)); + this->model->getMinimum(minimum, 0); + + QGraphicsRectItem* rect = this->addRect( + minimum(this->x), + -maximum(this->y), + std::abs(maximum(this->x) - minimum(this->x)), + std::abs(maximum(this->y) - minimum(this->y)), + QPen(Qt::NoPen), + QBrush(Qt::white) + ); + + rect->setZValue(0); + + this->thread->delta = this->delta; + this->thread->model = this->model; + this->thread->x = this->x; + this->thread->y = this->y; + + this->thread->start(); +} + +void +ConfigurationSpaceScene::mouseMoveEvent(QGraphicsSceneMouseEvent* mouseEvent) +{ + this->mousePressEvent(mouseEvent); +} + +void +ConfigurationSpaceScene::mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent) +{ + if (Qt::LeftButton == mouseEvent->buttons()) + { + if (!MainWindow::instance()->thread->isRunning()) + { + rl::math::Vector maximum(this->model->getDof(0)); + this->model->getMaximum(maximum, 0); + rl::math::Vector minimum(this->model->getDof(0)); + this->model->getMinimum(minimum, 0); + + if (mouseEvent->scenePos().x() > minimum(this->x) && + mouseEvent->scenePos().x() < maximum(this->x)) + { + (*MainWindow::instance()->q)(this->x) = mouseEvent->scenePos().x(); + } + + if (mouseEvent->scenePos().y() > minimum(this->y) && + mouseEvent->scenePos().y() < maximum(this->y)) + { + (*MainWindow::instance()->q)(this->y) = -mouseEvent->scenePos().y(); + } + + MainWindow::instance()->configurationModel->invalidate(); + MainWindow::instance()->viewer->drawConfiguration(*MainWindow::instance()->q); + } + } +} + +void +ConfigurationSpaceScene::reset() +{ + this->resetEdges(); + this->resetLines(); + this->resetPath(); +} + +void +ConfigurationSpaceScene::resetEdges() +{ + while (!this->edges.isEmpty()) + { + delete this->edges.takeFirst(); + } +} + +void +ConfigurationSpaceScene::resetLines() +{ +} + +void +ConfigurationSpaceScene::resetPath() +{ + while (!this->path.isEmpty()) + { + delete this->path.takeFirst(); + } +} + +void +ConfigurationSpaceScene::resetPoints() +{ +} + +void +ConfigurationSpaceScene::resetSpheres() +{ +} + +void +ConfigurationSpaceScene::resetVertices() +{ +} diff --git a/src/rlDamaDemoGUI/ConfigurationSpaceScene.h b/src/rlDamaDemoGUI/ConfigurationSpaceScene.h new file mode 100644 index 0000000..f5c4a8d --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationSpaceScene.h @@ -0,0 +1,92 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _CONFIGURATIONSPACESCENE_H_ +#define _CONFIGURATIONSPACESCENE_H_ + +#include +#include +#include +#include "DamaModel.h" +#include + +class ConfigurationSpaceThread; + +class ConfigurationSpaceScene : public QGraphicsScene, public rl::plan::Viewer +{ + Q_OBJECT + +public: + ConfigurationSpaceScene(QObject* parent = NULL); + + virtual ~ConfigurationSpaceScene(); + + rl::math::Real delta; + + dama::DamaModel* model; + + std::size_t x; + + std::size_t y; + +public slots: + void addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb); + + void clear(); + + void drawConfiguration(const rl::math::Vector& q); + + void drawConfigurationEdge(const rl::math::Vector& u, const rl::math::Vector& v, const bool& free = true); + + void drawConfigurationPath(const rl::plan::VectorList& path); + + void drawConfigurationVertex(const rl::math::Vector& q, const bool& free = true); + + void drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1); + + void drawPoint(const rl::math::Vector& xyz); + + void drawSphere(const rl::math::Vector& center, const rl::math::Real& radius); + + void drawSweptVolume(const rl::plan::VectorList& path); + + void drawWork(const rl::math::Transform& t); + + void drawWorkEdge(const rl::math::Vector& u, const rl::math::Vector& v); + + void drawWorkPath(const rl::plan::VectorList& path); + + void drawWorkVertex(const rl::math::Vector& q); + + void eval(); + + void reset(); + + void resetEdges(); + + void resetLines(); + + void resetPath(); + + void resetPoints(); + + void resetSpheres(); + + void resetVertices(); + +protected: + void mouseMoveEvent(QGraphicsSceneMouseEvent* mouseEvent); + + void mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent); + +private: + QLinkedList edges; + + QLinkedList path; + + ConfigurationSpaceThread* thread; +}; + +#endif // _CONFIGURATIONSPACESCENE_H_ diff --git a/src/rlDamaDemoGUI/ConfigurationSpaceThread.cpp b/src/rlDamaDemoGUI/ConfigurationSpaceThread.cpp new file mode 100644 index 0000000..75d07ec --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationSpaceThread.cpp @@ -0,0 +1,94 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include "DamaModel.h" + +#include "ConfigurationSpaceThread.h" +#include "MainWindow.h" + +ConfigurationSpaceThread::ConfigurationSpaceThread(QObject* parent) : + QThread(parent), + delta(1.0f), + model(NULL), + x(0), + y(1), + running(false) +{ +} + +ConfigurationSpaceThread::~ConfigurationSpaceThread() +{ +} + +void +ConfigurationSpaceThread::run() +{ + QMutexLocker lock(&MainWindow::instance()->mutex); + + this->running = true; + + // TODO: fixme + if(dama::DamaModel* model = dynamic_cast< dama::DamaModel* >(this->model)) + { + rl::math::Vector maximum(this->model->getDof(0)); + this->model->getMaximum(maximum, 0); + rl::math::Vector minimum(this->model->getDof(0)); + this->model->getMinimum(minimum, 0); + + rl::math::Real range0 = std::abs(maximum(this->x) - minimum(this->x)); + rl::math::Real range1 = std::abs(maximum(this->y) - minimum(this->y)); + + rl::math::Real delta0 = range0 / std::ceil(range0 / this->delta); + rl::math::Real delta1 = range1 / std::ceil(range1 / this->delta); + + std::size_t steps0 = static_cast< std::size_t >(std::ceil(range0 / delta0)); + std::size_t steps1 = static_cast< std::size_t >(std::ceil(range1 / delta1)); + + rl::math::Vector q(*MainWindow::instance()->start); + + { + for (std::size_t i = 0; i < steps1 + 1 && this->running; ++i) + { + q(this->y) = maximum(this->y) - i * delta1; + + for (std::size_t j = 0; j < steps0 + 1 && this->running; ++j) + { + q(this->x) = minimum(this->x) + j * delta0; + + model->setPosition(q); + model->updateFrames(); + + if (model->isColliding()) + { + emit addCollision( + q(this->x), + q(this->y), + delta0, + delta1, + 0 + ); + } + } + } + } + } + + this->running = false; +} + +void +ConfigurationSpaceThread::stop() +{ + if (this->running) + { + this->running = false; + + while (!this->isFinished()) + { + QThread::usleep(0); + } + } +} diff --git a/src/rlDamaDemoGUI/ConfigurationSpaceThread.h b/src/rlDamaDemoGUI/ConfigurationSpaceThread.h new file mode 100644 index 0000000..92400a2 --- /dev/null +++ b/src/rlDamaDemoGUI/ConfigurationSpaceThread.h @@ -0,0 +1,42 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _CONFIGURATIONSPACETHREAD_H_ +#define _CONFIGURATIONSPACETHREAD_H_ + +#include +#include "DamaModel.h" + +class ConfigurationSpaceThread : public QThread +{ + Q_OBJECT + +public: + ConfigurationSpaceThread(QObject* parent = NULL); + + virtual ~ConfigurationSpaceThread(); + + void run(); + + void stop(); + + rl::math::Real delta; + + dama::DamaModel* model; + + std::size_t x; + + std::size_t y; + +protected: + +private: + bool running; + +signals: + void addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb); +}; + +#endif // _CONFIGURATIONSPACETHREAD_H_ diff --git a/src/rlDamaDemoGUI/DamaPlanner.cpp b/src/rlDamaDemoGUI/DamaPlanner.cpp new file mode 100644 index 0000000..8771f10 --- /dev/null +++ b/src/rlDamaDemoGUI/DamaPlanner.cpp @@ -0,0 +1,292 @@ +/* + * Copyright (c) 2015, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include + +#include "DamaPlanner.h" +#include "XmlFactory.h" + +bool DamaPlanner::init(::std::string newTaskFileName) +{ + this->taskFileName = newTaskFileName; + + SoDB::init(); + + // TODO: currently we have to initialize model2 before model such that the static primitives get the right reference to model, and not to model2. Fix this? + // TODO: we have to create the model twice, as e.g. the Viewer class executes commands right on the DamaModel (model2), which should not interfere with the model used for planning + // TODO: do not create the dModelVis if viewer is turned off ... as soon as you got the order fixed, you can read out dModel to know if viewer is turned off ;) + ::dama::XmlFactory damaFactory; + ::std::cout << "Creating DamaModels according to task \"" << this->getTaskFileName() << "\" ..." << ::std::endl; + this->dModelVis = damaFactory.create(this->getTaskFileName(), true); + this->dModel = damaFactory.create(this->getTaskFileName(), false); + + this->dModel->reset(); + this->dModelVis->reset(); + + this->startInit = boost::shared_ptr< rl::math::Vector >(this->dModel->dRrt->start); + this->goalInit = boost::shared_ptr< rl::math::Vector >(this->dModel->dRrt->goal); + this->goalDimDefinedInit = boost::shared_ptr< ::std::vector >(this->dModel->dRrt->goalDimDefined); + + // TODO: ? + + return true; +} + +bool DamaPlanner::run() +{ + ::dama::Timer timer; + + // calculate this->dModel->numRuns seeds (with value in srand you can change the seed set) + srand(this->dModel->groupSeed); + // srand(time(NULL)); + ::std::vector < ::std::size_t > vecSeeds(this->dModel->numRuns, 0); + if(this->dModel->seedType == "singleOnly") + { + for(::std::size_t u=0; udModel->numRuns; ++u) + vecSeeds.at(u) = this->dModel->singleSeed; + } + else + { + for(::std::size_t u=0; udModel->numRuns; ++u) + vecSeeds.at(u) = rand(); + } + + // write benchmark header + std::ofstream benchmarkHeader; + benchmarkHeader.open("DamaBenchmark.csv", std::ios::app); + // #iterations: not counted: if sample is unreachable from tree a or is exact a neighbor of tree a or if connected vertex is unreachable from tree b + benchmarkHeader << "date,task,nr,singleSeed,solved,tGlobal,tIK,tSampling,tNNSearch,tPropagate,tConnect,iterations,edges,vertices,totalQueries,freeQueries,solVertices,solLength,solLengthMan"; + for(::std::size_t p=0; pdModel->vecDamaPrim.size(); ++p) + benchmarkHeader << "," << this->dModel->vecDamaPrim.at(p)->getName() ; + benchmarkHeader << ::std::endl; + benchmarkHeader.close(); + + + vecSolved.resize(this->dModel->numRuns, false); + ::std::vector < ::rl::math::Real > vecTime(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecIK(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecTimeSampling(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecTimeNNSearch(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecTimePropagate(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecTimeConnect(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecIterations(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecEdges(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecVertices(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecTotalQueries(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecFreeQueries(this->dModel->numRuns, 0); + ::std::vector < ::std::size_t > vecSolutionVertices(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecSolutionLength(this->dModel->numRuns, 0); + ::std::vector < ::rl::math::Real > vecSolutionLengthManipulation(this->dModel->numRuns, 0); + ::std::vector < ::std::vector < ::std::size_t > > vecSolutionManipulationCount(this->dModel->numRuns, ::std::vector < ::std::size_t >(this->dModel->vecDamaPrim.size(), 0)); + + rl::plan::VectorList path; + ::std::deque< ::std::string > actions; + + std::ofstream benchmark; + benchmark.open("DamaBenchmark.csv", std::ios::app); + + for(::std::size_t u=0; udModel->numRuns; ++u) + { + path.clear(); + actions.clear(); + + srand(0); + ::std::size_t randSeedNumber = vecSeeds.at(u); //489012115 OR vecSeeds.at(u) + ::boost::mt19937::result_type randSeed = static_cast< ::boost::mt19937::result_type >((double)randSeedNumber); + + if(this->dModel->workspaceSampling) + this->dModel->dRrt->setConfig(false, false, false); // do NOT change this + else + this->dModel->dRrt->setConfig(this->dModel->bidirectional, this->dModel->hierarchical, this->dModel->accurateDistance); + + this->dModel->dRrt->seed(randSeed); + this->dModel->dRrt->resetStatistics(); + //this->dModel->dRrt->duration = 180.0; //900.0 //300.0; //1200.0 //boost::lexical_cast< rl::math::Real >(::std::numeric_limits< double >::max()); + // TODO: hierarchical version currently needs this to be redefined, only because of this they exist ... + rl::math::Vector startCopy(*(this->startInit.get())); + this->dModel->dRrt->start = &startCopy; + rl::math::Vector goalCopy(*(this->goalInit.get())); + this->dModel->dRrt->goal = &goalCopy; + ::std::vector < bool > goalDimDefinedCopy(*(this->goalDimDefinedInit.get())); + this->dModel->dRrt->goalDimDefined = &goalDimDefinedCopy; + + // remove me !!!! + //if(u < this->dModel->numRuns - 1) + // continue; + + std::cout << "Start solving run " << (u+1) << "/" << this->dModel->numRuns << " of task \"" << this->dModel->prefixName << "\" with singleSeed " << randSeedNumber << " ... " << std::endl; + timer.start(); + vecSolved.at(u) = this->dModel->dRrt->solveAll(path, actions); + timer.stop(); + vecPath.push_back(path); + vecActions.push_back(actions); + if(vecSolved.at(u)) + { + ::std::string lastAction = ""; + rl::plan::VectorList::iterator i = path.begin(); + rl::plan::VectorList::iterator j = ++path.begin(); + ::std::deque< ::std::string >::iterator e = actions.begin(); + for (; i != path.end() && j != path.end() && e != actions.end(); ++i, ++j, ++e) + { + ::rl::math::Real tempRobotDist = this->dModel->cartesianRobotDistance(*i, *j); + vecSolutionLength.at(u) += tempRobotDist; + if(*e != ::dama::DamaPrimTransit::getInstance()->getName()) + vecSolutionLengthManipulation.at(u) += tempRobotDist; + if(lastAction != *e) + { + for(::std::size_t p=0; psubstr(0, this->dModel->vecDamaPrim.at(p)->getName().size()) == this->dModel->vecDamaPrim.at(p)->getName()) + vecSolutionManipulationCount.at(u).at(p) ++; + } + lastAction = *e; + } + } + vecTime.at(u) = timer.elapsed(); + vecIK.at(u) = this->dModel->timeIK; + vecTimeSampling.at(u) = this->dModel->dRrt->getTimeSampling(); + vecTimeNNSearch.at(u) = this->dModel->dRrt->getTimeNNSearch(); + vecTimePropagate.at(u) = this->dModel->dRrt->getTimePropagate(); + vecTimeConnect.at(u) = this->dModel->dRrt->getTimeConnect(); + vecIterations.at(u) = this->dModel->dRrt->getIterationCount(); + vecEdges.at(u) = this->dModel->dRrt->getEdgeCount(); + vecVertices.at(u) = this->dModel->dRrt->getVertexCount(); + vecTotalQueries.at(u) = this->dModel->getTotalQueries(); + vecFreeQueries.at(u) = this->dModel->getFreeQueries(); + vecSolutionVertices.at(u) = path.size(); + std::cout << "solved: " << vecSolved.at(u) << " \t time: " << vecTime.at(u) << " \t iterations: " << vecIterations.at(u) << " \t edges: " << vecEdges.at(u) << " \t vertices: " << vecVertices.at(u) << " \t vertices (solution): " << vecSolutionVertices.at(u) << " \t length: " << vecSolutionLength.at(u) << " \t length (manipulation only): " << vecSolutionLengthManipulation.at(u) << std::endl; + + // Export statistics to benchmark file + benchmark << QDateTime::currentDateTime().toString("yyyy-MM-dd HH:mm:ss.zzz").toStdString() << ","; + benchmark << this->dModel->prefixName << ","; + benchmark << (u+1) << ","; + benchmark << randSeedNumber << ","; + benchmark << (vecSolved.at(u) ? "true" : "false") << ","; + benchmark << vecTime.at(u) << ","; + benchmark << vecIK.at(u) << ","; + benchmark << vecTimeSampling.at(u) << ","; + benchmark << vecTimeNNSearch.at(u) << ","; + benchmark << vecTimePropagate.at(u) << ","; + benchmark << vecTimeConnect.at(u) << ","; + benchmark << vecIterations.at(u) << ","; + benchmark << vecEdges.at(u) << ","; + benchmark << vecVertices.at(u) << ","; + benchmark << vecTotalQueries.at(u) << ","; + benchmark << vecFreeQueries.at(u) << ","; + benchmark << vecSolutionVertices.at(u) << ","; + benchmark << vecSolutionLength.at(u) << ","; + benchmark << vecSolutionLengthManipulation.at(u) << ","; + for(::std::size_t p=0; pdModel->numRuns > 1) + { + // Export average data to benchmark file if you run the same problem more than one + + std::size_t countSolved = 0; + for(auto it : vecSolved) + if(it == true) + countSolved++; + + std::cout << "*** Summary: " << countSolved << "/" << this->dModel->numRuns << " solved ***" << ::std::endl; + + std::cout << "avg of all: \t time: " << getAvgValue(vecTime, false) << " \t iterations: " << getAvgValue(vecIterations, false) << " \t edges: " << getAvgValue(vecEdges, false) << " \t vertices: " << getAvgValue(vecVertices, false) << " \t vertices (solution): " << getAvgValue(vecSolutionVertices, false) << " \t length: " << getAvgValue(vecSolutionLength, false) << " \t length (manipulation only): " << getAvgValue(vecSolutionLengthManipulation, false) << std::endl; + + benchmark << ","; + benchmark << ","; + benchmark << ","; + benchmark << "avg (all),"; + benchmark << countSolved << "/" << this->dModel->numRuns << ","; + benchmark << getAvgValue(vecTime, false) << ","; + benchmark << getAvgValue(vecIK, false) << ","; + benchmark << getAvgValue(vecTimeSampling, false) << ","; + benchmark << getAvgValue(vecTimeNNSearch, false) << ","; + benchmark << getAvgValue(vecTimePropagate, false) << ","; + benchmark << getAvgValue(vecTimeConnect, false) << ","; + benchmark << getAvgValue(vecIterations, false) << ","; + benchmark << getAvgValue(vecEdges, false) << ","; + benchmark << getAvgValue(vecVertices, false) << ","; + benchmark << getAvgValue(vecTotalQueries, false) << ","; + benchmark << getAvgValue(vecFreeQueries, false) << ","; + benchmark << getAvgValue(vecSolutionVertices, false) << ","; + benchmark << getAvgValue(vecSolutionLength, false) << ","; + benchmark << getAvgValue(vecSolutionLengthManipulation, false) << ","; + for(::std::size_t p=0; pdModel->numRuns; ++r) + avgValue += vecSolutionManipulationCount.at(r).at(p); + avgValue /= this->dModel->numRuns; + benchmark << avgValue << ","; + } + benchmark << std::endl; + + std::cout << "avg solved: \t time: " << getAvgValue(vecTime, true) << " \t iterations: " << getAvgValue(vecIterations, true) << " \t edges: " << getAvgValue(vecEdges, true) << " \t vertices: " << getAvgValue(vecVertices, true) << " \t vertices (solution): " << getAvgValue(vecSolutionVertices, true) << " \t length: " << getAvgValue(vecSolutionLength, true) << " \t length (manipulation only): " << getAvgValue(vecSolutionLengthManipulation, true) << std::endl; + + benchmark << ","; + benchmark << ","; + benchmark << ","; + benchmark << "avg (solved),"; + benchmark << countSolved << "/" << this->dModel->numRuns << ","; + benchmark << getAvgValue(vecTime, true) << ","; + benchmark << getAvgValue(vecIK, true) << ","; + benchmark << getAvgValue(vecTimeSampling, true) << ","; + benchmark << getAvgValue(vecTimeNNSearch, true) << ","; + benchmark << getAvgValue(vecTimePropagate, true) << ","; + benchmark << getAvgValue(vecTimeConnect, true) << ","; + benchmark << getAvgValue(vecIterations, true) << ","; + benchmark << getAvgValue(vecEdges, true) << ","; + benchmark << getAvgValue(vecVertices, true) << ","; + benchmark << getAvgValue(vecTotalQueries, true) << ","; + benchmark << getAvgValue(vecFreeQueries, true) << ","; + benchmark << getAvgValue(vecSolutionVertices, true) << ","; + benchmark << getAvgValue(vecSolutionLength, true) << ","; + benchmark << getAvgValue(vecSolutionLengthManipulation, true) << ","; + for(::std::size_t p=0; pdModel->numRuns; ++r) + { + if(vecSolved.at(r)) + { + avgValue += vecSolutionManipulationCount.at(r).at(p); + numHits++; + } + } + avgValue /= numHits; + benchmark << avgValue << ","; + } + benchmark << std::endl; + } + + benchmark.close(); + + return true; +} + +template ::rl::math::Real DamaPlanner::getAvgValue(::std::vector< T > vecValue, bool considerOnlySolvedRuns) const +{ + ::rl::math::Real avgValue = 0.0; + ::std::size_t numHits = 0; + for(::std::size_t i=0; itaskFileName; +} diff --git a/src/rlDamaDemoGUI/DamaPlanner.h b/src/rlDamaDemoGUI/DamaPlanner.h new file mode 100644 index 0000000..61ac32b --- /dev/null +++ b/src/rlDamaDemoGUI/DamaPlanner.h @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2015, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef DAMAPLANNER_H_ +#define DAMAPLANNER_H_ + +#include + +#include "DamaModel.h" + +class DamaPlanner +{ +public: + static DamaPlanner* getInstance() + { + static DamaPlanner instance; + return &instance; + } + + bool init(::std::string newTaskFileName); + + bool run(); + + boost::shared_ptr< dama::DamaModel > dModel; + boost::shared_ptr< dama::DamaModel > dModelVis; + + boost::shared_ptr< rl::math::Vector > startInit; + boost::shared_ptr< rl::math::Vector > goalInit; + boost::shared_ptr< ::std::vector > goalDimDefinedInit; + + ::std::vector< bool > vecSolved; + ::std::vector< rl::plan::VectorList > vecPath; + ::std::vector< ::std::deque< ::std::string > > vecActions; + + ::std::string getTaskFileName() const; + +private: + DamaPlanner() {}; + DamaPlanner(DamaPlanner const&); // Don't Implement + void operator=(DamaPlanner const&); // Don't implement + + template ::rl::math::Real getAvgValue(::std::vector< T > vecValue, bool considerOnlySolvedRuns) const; + + ::std::string taskFileName; +}; + +#endif /* DAMAPLANNER_H_ */ diff --git a/src/rlDamaDemoGUI/MainWindow.cpp b/src/rlDamaDemoGUI/MainWindow.cpp new file mode 100644 index 0000000..af8a571 --- /dev/null +++ b/src/rlDamaDemoGUI/MainWindow.cpp @@ -0,0 +1,1007 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "XmlFactory.h" +#include "DamaRrt.h" +#include "DamaModel.h" +#include "DamaSampler.h" +#include "DamaPlanner.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef HAVE_BULLET +#include +#endif // HAVE_BULLET +#ifdef HAVE_ODE +#include +#endif // HAVE_ODE +#ifdef HAVE_PQP +#include +#endif // HAVE_PQP +#ifdef HAVE_SOLID +#include +#endif // HAVE_SOLID + +#include "ConfigurationDelegate.h" +#include "ConfigurationModel.h" +#include "ConfigurationSpaceScene.h" +#include "MainWindow.h" +#include "PlannerModel.h" +#include "Thread.h" +#include "Viewer.h" + +MainWindow::MainWindow(QWidget* parent, Qt::WFlags f) : + QMainWindow(parent, f), + configurationModel(new ConfigurationModel(this)), + explorerGoals(), + explorers(), + explorerStarts(), + goal(), + kin(), + kin2(), + mdl(), + mdl2(), + model(), + model2(), + mutex(), + planner(), + plannerModel(new PlannerModel(this)), + q(), + sampler(), + sampler2(), + sigma(), + scene(), + scene2(), + sceneModel(NULL), + sceneModel2(NULL), + start(), + thread(new Thread(this)), + verifier(), + verifier2(), + viewer(NULL), + configurationDelegate(new ConfigurationDelegate(this)), + configurationDockWidget(new QDockWidget(this)), + configurationSpaceDockWidget(new QDockWidget(this)), + configurationSpaceScene(new ConfigurationSpaceScene(this)), + configurationSpaceView(new QGraphicsView(this)), + configurationView(new QTableView(this)), + engine(), + evalAction(new QAction(this)), + exitAction(new QAction(this)), + filename(), + getGoalConfigurationAction(new QAction(this)), + getRandomConfigurationAction(new QAction(this)), + getRandomFreeConfigurationAction(new QAction(this)), + getStartConfigurationAction(new QAction(this)), + openAction(new QAction(this)), + plannerDockWidget(new QDockWidget(this)), + plannerView(new QTableView(this)), + resetAction(new QAction(this)), + saveImageAction(new QAction(this)), + savePdfAction(new QAction(this)), + saveSceneAction(new QAction(this)), + setGoalConfigurationAction(new QAction(this)), + setStartConfigurationAction(new QAction(this)), + startThreadAction(new QAction(this)), + toggleCameraAction(new QAction(this)), + toggleConfigurationAction(new QAction(this)), + toggleConfigurationEdgesAction(new QAction(this)), + toggleConfigurationSpaceAction(new QAction(this)), + toggleConfigurationVerticesAction(new QAction(this)), + toggleLinesAction(new QAction(this)), + togglePlannerAction(new QAction(this)), + togglePointsAction(new QAction(this)), + toggleSpheresAction(new QAction(this)), + toggleViewAction(new QAction(this)), + toggleWorkFramesAction(new QAction(this)), + wait(true) +{ + MainWindow::singleton = this; + + SoQt::init(this); + SoDB::init(); + + this->viewer = new Viewer(this); + this->setCentralWidget(this->viewer); + + this->configurationSpaceView->setEnabled(false); + this->configurationSpaceView->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + this->configurationSpaceView->setScene(this->configurationSpaceScene); + this->configurationSpaceView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + this->configurationSpaceView->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + + this->configurationView->horizontalHeader()->setResizeMode(QHeaderView::Stretch); + this->configurationView->horizontalHeader()->hide(); + this->configurationView->setAlternatingRowColors(true); + this->configurationView->setItemDelegate(this->configurationDelegate); + this->configurationView->setModel(this->configurationModel); + this->configurationView->verticalHeader()->setResizeMode(QHeaderView::ResizeToContents); + + this->configurationDockWidget->hide(); + this->configurationDockWidget->resize(160, 320); + this->configurationDockWidget->setFloating(true); + this->configurationDockWidget->setWidget(this->configurationView); + this->configurationDockWidget->setWindowTitle("Configuration"); + + this->configurationSpaceDockWidget->hide(); + this->configurationSpaceDockWidget->setFloating(true); + this->configurationSpaceDockWidget->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + this->configurationSpaceDockWidget->setWidget(this->configurationSpaceView); + this->configurationSpaceDockWidget->setWindowTitle("C-Space"); + + this->plannerView->horizontalHeader()->setResizeMode(QHeaderView::Stretch); + this->plannerView->setAlternatingRowColors(true); + this->plannerView->setModel(this->plannerModel); + this->plannerView->setWordWrap(false); + this->plannerView->verticalHeader()->setResizeMode(QHeaderView::ResizeToContents); + + this->plannerDockWidget->hide(); + this->plannerDockWidget->resize(160, 320); + this->plannerDockWidget->setFloating(true); + this->plannerDockWidget->setWidget(this->plannerView); + this->plannerDockWidget->setWindowTitle("Planner"); + + this->init(); + + QStringList engines; +#ifdef HAVE_ODE + engines.push_back("ode"); + this->engine = "ode"; +#endif // HAVE_ODE +#ifdef HAVE_PQP + engines.push_back("pqp"); + this->engine = "pqp"; +#endif // HAVE_PQP +#ifdef HAVE_BULLET + engines.push_back("bullet"); + this->engine = "bullet"; +#endif // HAVE_BULLET +#ifdef HAVE_SOLID + engines.push_back("solid"); + this->engine = "solid"; +#endif // HAVE_SOLID + engines.sort(); + + QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); + QRegExp helpRegExp("--help"); + QRegExp heightRegExp("--height=(\\d*)"); + QRegExp viewerRegExp("--disable-viewer"); + QRegExp waitRegExp("--disable-wait"); + QRegExp widthRegExp("--width=(\\d*)"); + QRegExp quitRegExp("--enable-quit"); + + int width = 1024; + int height = 768; + + for (int i = 1; i < QApplication::arguments().size(); ++i) + { + if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) + { + this->engine = engineRegExp.cap(1); + } + else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) + { + std::cout << "Usage: rlPlanDemo [PLANFILE] [--engine=" << engines.join("|").toStdString() << "] [--help] [--disable-viewer] [--disable-wait] [--enable-quit] [--width=WIDTH] [--height=HEIGHT]" << std::endl; + } + else if (-1 != heightRegExp.indexIn(QApplication::arguments()[i])) + { + height = heightRegExp.cap(1).toInt(); + } + else if (-1 != viewerRegExp.indexIn(QApplication::arguments()[i])) + { + QObject::disconnect(this->toggleViewAction, SIGNAL(toggled(bool)), this, SLOT(toggleView(bool))); + this->toggleViewAction->setChecked(false); + QObject::connect(this->toggleViewAction, SIGNAL(toggled(bool)), this, SLOT(toggleView(bool))); + } + else if (-1 != waitRegExp.indexIn(QApplication::arguments()[i])) + { + this->wait = false; + } + else if (-1 != widthRegExp.indexIn(QApplication::arguments()[i])) + { + width = widthRegExp.cap(1).toInt(); + } + else if (-1 != quitRegExp.indexIn(QApplication::arguments()[i])) + { + this->thread->quit = true; + } + else + { + this->filename = QApplication::arguments()[i]; + } + } + + this->resize(width, height); + this->viewer->setMinimumSize(width, height); + + this->initAll(); + + /*if (this->filename.isEmpty()) + { + this->open(); + } + else + { + this->load(this->filename); + }*/ +} + +MainWindow::~MainWindow() +{ + this->thread->stop(); + + MainWindow::singleton = NULL; +} + +void +MainWindow::clear() +{ + this->explorerGoals.clear(); + this->explorers.clear(); + this->explorerStarts.clear(); + this->goal.reset(); + this->kin.reset(); + this->kin2.reset(); + this->mdl.reset(); + this->mdl2.reset(); + this->model.reset(); + this->model2.reset(); + this->optimizer.reset(); + this->planner.reset(); + this->q.reset(); + this->sampler.reset(); + this->sampler2.reset(); + this->sigma.reset(); + this->scene.reset(); + this->scene2.reset(); + this->sceneModel = NULL; + this->sceneModel2 = NULL; + this->start.reset(); + this->verifier.reset(); + this->verifier2.reset(); +} + +void +MainWindow::connect(const QObject* sender, const QObject* receiver) +{ + QObject::connect( + sender, + SIGNAL(configurationRequested(const rl::math::Vector&)), + receiver, + SLOT(drawConfiguration(const rl::math::Vector&)) + ); + + QObject::connect( + sender, + SIGNAL(configurationEdgeRequested(const rl::math::Vector&, const rl::math::Vector&, const bool&)), + receiver, + SLOT(drawConfigurationEdge(const rl::math::Vector&, const rl::math::Vector&, const bool&)) + ); + + QObject::connect( + sender, + SIGNAL(configurationPathRequested(const rl::plan::VectorList&)), + receiver, + SLOT(drawConfigurationPath(const rl::plan::VectorList&)) + ); + + QObject::connect( + sender, + SIGNAL(configurationVertexRequested(const rl::math::Vector&, const bool&)), + receiver, + SLOT(drawConfigurationVertex(const rl::math::Vector&, const bool&)) + ); + + QObject::connect( + sender, + SIGNAL(edgeResetRequested()), + receiver, + SLOT(resetEdges()) + ); + + QObject::connect( + sender, + SIGNAL(lineRequested(const rl::math::Vector&, const rl::math::Vector&)), + receiver, + SLOT(drawLine(const rl::math::Vector&, const rl::math::Vector&)) + ); + + QObject::connect( + sender, + SIGNAL(lineResetRequested()), + receiver, + SLOT(resetLines()) + ); + + QObject::connect( + sender, + SIGNAL(pointRequested(const rl::math::Vector&)), + receiver, + SLOT(drawPoint(const rl::math::Vector&)) + ); + + QObject::connect( + sender, + SIGNAL(pointResetRequested()), + receiver, + SLOT(resetPoints()) + ); + + QObject::connect( + sender, + SIGNAL(resetRequested()), + receiver, + SLOT(reset()) + ); + + QObject::connect( + sender, + SIGNAL(sphereRequested(const rl::math::Vector&, const rl::math::Real&)), + receiver, + SLOT(drawSphere(const rl::math::Vector&, const rl::math::Real&)) + ); + + QObject::connect( + sender, + SIGNAL(sphereResetRequested()), + receiver, + SLOT(resetSpheres()) + ); + + QObject::connect( + sender, + SIGNAL(sweptVolumeRequested(const rl::plan::VectorList&)), + receiver, + SLOT(drawSweptVolume(const rl::plan::VectorList&)) + ); + + QObject::connect( + sender, + SIGNAL(vertexResetRequested()), + receiver, + SLOT(resetVertices()) + ); + + QObject::connect( + sender, + SIGNAL(workRequested(const rl::math::Transform&)), + receiver, + SLOT(drawWork(const rl::math::Transform&)) + ); + + QObject::connect( + sender, + SIGNAL(workEdgeRequested(const rl::math::Vector&, const rl::math::Vector&)), + receiver, + SLOT(drawWorkEdge(const rl::math::Vector&, const rl::math::Vector&)) + ); + + QObject::connect( + sender, + SIGNAL(workPathRequested(const rl::plan::VectorList&)), + receiver, + SLOT(drawWorkPath(const rl::plan::VectorList&)) + ); +} + +void +MainWindow::disconnect(const QObject* sender, const QObject* receiver) +{ + QObject::disconnect(sender, NULL, receiver, NULL); +} + +void +MainWindow::eval() +{ + this->configurationSpaceScene->eval(); +} + +void +MainWindow::getGoalConfiguration() +{ + *this->q = *this->goal; + this->configurationModel->invalidate(); + this->viewer->drawConfiguration(*this->q); +} + +void +MainWindow::getRandomConfiguration() +{ + this->sampler2->generate(*this->q); + this->configurationModel->invalidate(); + this->viewer->drawConfiguration(*this->q); +} + +void +MainWindow::getRandomFreeConfiguration() +{ + this->sampler2->generateCollisionFree(*this->q); + this->configurationModel->invalidate(); + this->viewer->drawConfiguration(*this->q); +} + +void +MainWindow::getStartConfiguration() +{ + *this->q = *this->start; + this->configurationModel->invalidate(); + this->viewer->drawConfiguration(*this->q); +} + +void +MainWindow::init() +{ + QMenu* fileMenu = this->menuBar()->addMenu("File"); + + this->openAction->setText("Open..."); + this->openAction->setShortcut(QKeySequence::Open); + QObject::connect(this->openAction, SIGNAL(triggered()), this, SLOT(open())); + this->addAction(this->openAction); + fileMenu->addAction(this->openAction); + + fileMenu->addSeparator(); + + this->saveImageAction->setText("Save as PNG"); + this->saveImageAction->setShortcut(QKeySequence("Return")); + QObject::connect(this->saveImageAction, SIGNAL(triggered()), this, SLOT(saveImage())); + this->addAction(this->saveImageAction); + fileMenu->addAction(this->saveImageAction); + + this->saveSceneAction->setText("Save as VRML"); + this->saveSceneAction->setShortcut(QKeySequence("Ctrl+Return")); + QObject::connect(this->saveSceneAction, SIGNAL(triggered()), this, SLOT(saveScene())); + this->addAction(this->saveSceneAction); + fileMenu->addAction(this->saveSceneAction); + + this->savePdfAction->setText("Save as PDF"); + this->savePdfAction->setShortcut(QKeySequence("Alt+Return")); + QObject::connect(this->savePdfAction, SIGNAL(triggered()), this, SLOT(savePdf())); + this->addAction(this->savePdfAction); + fileMenu->addAction(this->savePdfAction); + + fileMenu->addSeparator(); + + this->exitAction->setText("Exit"); + QObject::connect(this->exitAction, SIGNAL(triggered()), qApp, SLOT(quit())); + this->addAction(this->exitAction); + fileMenu->addAction(this->exitAction); + + QMenu* configurationMenu = this->menuBar()->addMenu("Configuration"); + + this->toggleConfigurationAction->setText("Show/Hide"); + this->toggleConfigurationAction->setShortcut(QKeySequence("F5")); + QObject::connect(this->toggleConfigurationAction, SIGNAL(triggered()), this, SLOT(toggleConfiguration())); + this->addAction(this->toggleConfigurationAction); + configurationMenu->addAction(this->toggleConfigurationAction); + + configurationMenu->addSeparator(); + + this->getRandomConfigurationAction->setText("Random"); + this->getRandomConfigurationAction->setShortcut(QKeySequence("F3")); + QObject::connect(this->getRandomConfigurationAction, SIGNAL(triggered()), this, SLOT(getRandomConfiguration())); + this->addAction(this->getRandomConfigurationAction); + configurationMenu->addAction(this->getRandomConfigurationAction); + + this->getRandomFreeConfigurationAction->setText("Random (Collision-Free)"); + this->getRandomFreeConfigurationAction->setShortcut(QKeySequence("F4")); + QObject::connect(this->getRandomFreeConfigurationAction, SIGNAL(triggered()), this, SLOT(getRandomFreeConfiguration())); + this->addAction(this->getRandomFreeConfigurationAction); + configurationMenu->addAction(this->getRandomFreeConfigurationAction); + + QMenu* cSpaceMenu = this->menuBar()->addMenu("C-Space"); + + this->toggleConfigurationSpaceAction->setText("Show/Hide"); + this->toggleConfigurationSpaceAction->setShortcut(QKeySequence("F6")); + QObject::connect(this->toggleConfigurationSpaceAction, SIGNAL(triggered()), this, SLOT(toggleConfigurationSpace())); + this->addAction(this->toggleConfigurationSpaceAction); + cSpaceMenu->addAction(this->toggleConfigurationSpaceAction); + + cSpaceMenu->addSeparator(); + + this->evalAction->setText("Evaluate"); + this->evalAction->setShortcut(QKeySequence("F11")); + QObject::connect(this->evalAction, SIGNAL(triggered()), this, SLOT(eval())); + this->addAction(this->evalAction); + cSpaceMenu->addAction(this->evalAction); + + QMenu* plannerMenu = this->menuBar()->addMenu("Planner"); + + this->togglePlannerAction->setText("Show/Hide"); + this->togglePlannerAction->setShortcut(QKeySequence("F7")); + QObject::connect(this->togglePlannerAction, SIGNAL(triggered()), this, SLOT(togglePlanner())); + this->addAction(this->togglePlannerAction); + plannerMenu->addAction(this->togglePlannerAction); + + plannerMenu->addSeparator(); + + this->getStartConfigurationAction->setText("Get Start Configuration"); + this->getStartConfigurationAction->setShortcut(QKeySequence("F1")); + QObject::connect(this->getStartConfigurationAction, SIGNAL(triggered()), this, SLOT(getStartConfiguration())); + this->addAction(this->getStartConfigurationAction); + plannerMenu->addAction(this->getStartConfigurationAction); + + this->setStartConfigurationAction->setText("Set Start Configuration"); + this->setStartConfigurationAction->setShortcut(QKeySequence("CTRL+F1")); + QObject::connect(this->setStartConfigurationAction, SIGNAL(triggered()), this, SLOT(setStartConfiguration())); + this->addAction(this->setStartConfigurationAction); + plannerMenu->addAction(this->setStartConfigurationAction); + + plannerMenu->addSeparator(); + + this->getGoalConfigurationAction->setText("Get Goal Configuration"); + this->getGoalConfigurationAction->setShortcut(QKeySequence("F2")); + QObject::connect(this->getGoalConfigurationAction, SIGNAL(triggered()), this, SLOT(getGoalConfiguration())); + this->addAction(this->getGoalConfigurationAction); + plannerMenu->addAction(this->getGoalConfigurationAction); + + this->setGoalConfigurationAction->setText("Set Goal Configuration"); + this->setGoalConfigurationAction->setShortcut(QKeySequence("CTRL+F2")); + QObject::connect(this->setGoalConfigurationAction, SIGNAL(triggered()), this, SLOT(setGoalConfiguration())); + this->addAction(this->setGoalConfigurationAction); + plannerMenu->addAction(this->setGoalConfigurationAction); + + plannerMenu->addSeparator(); + + this->startThreadAction->setText("Start"); + this->startThreadAction->setShortcut(QKeySequence("Space")); + QObject::connect(this->startThreadAction, SIGNAL(triggered()), this, SLOT(startThread())); + this->addAction(this->startThreadAction); + plannerMenu->addAction(this->startThreadAction); + + this->resetAction->setText("Reset"); + this->resetAction->setShortcut(QKeySequence("F12")); + QObject::connect(this->resetAction, SIGNAL(triggered()), this, SLOT(reset())); + this->addAction(this->resetAction); + plannerMenu->addAction(this->resetAction); + + QMenu* viewMenu = this->menuBar()->addMenu("View"); + + this->toggleViewAction->setCheckable(true); + this->toggleViewAction->setChecked(true); + this->toggleViewAction->setText("Active"); + QObject::connect(this->toggleViewAction, SIGNAL(toggled(bool)), this, SLOT(toggleView(bool))); + this->addAction(this->toggleViewAction); + viewMenu->addAction(this->toggleViewAction); + + viewMenu->addSeparator(); + + this->toggleConfigurationEdgesAction->setCheckable(true); + this->toggleConfigurationEdgesAction->setChecked(true); + this->toggleConfigurationEdgesAction->setText("Configuration Edges"); + QObject::connect(this->toggleConfigurationEdgesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleConfigurationEdges(bool))); + this->addAction(this->toggleConfigurationEdgesAction); + viewMenu->addAction(this->toggleConfigurationEdgesAction); + + this->toggleConfigurationVerticesAction->setCheckable(true); + this->toggleConfigurationVerticesAction->setChecked(false); + this->toggleConfigurationVerticesAction->setText("Configuration Vertices"); + QObject::connect(this->toggleConfigurationVerticesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleConfigurationVertices(bool))); + this->addAction(this->toggleConfigurationVerticesAction); + viewMenu->addAction(this->toggleConfigurationVerticesAction); + + viewMenu->addSeparator(); + + this->toggleWorkFramesAction->setCheckable(true); + this->toggleWorkFramesAction->setChecked(false); + this->toggleWorkFramesAction->setText("Work Frames"); + QObject::connect(this->toggleWorkFramesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleWorkFrames(bool))); + this->addAction(this->toggleWorkFramesAction); + viewMenu->addAction(this->toggleWorkFramesAction); + + viewMenu->addSeparator(); + + this->toggleLinesAction->setCheckable(true); + this->toggleLinesAction->setChecked(true); + this->toggleLinesAction->setText("Lines"); + QObject::connect(this->toggleLinesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleLines(bool))); + this->addAction(this->toggleLinesAction); + viewMenu->addAction(this->toggleLinesAction); + + this->togglePointsAction->setCheckable(true); + this->togglePointsAction->setChecked(true); + this->togglePointsAction->setText("Points"); + QObject::connect(this->togglePointsAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePoints(bool))); + this->addAction(this->togglePointsAction); + viewMenu->addAction(this->togglePointsAction); + + this->toggleSpheresAction->setCheckable(true); + this->toggleSpheresAction->setChecked(true); + this->toggleSpheresAction->setText("Spheres"); + QObject::connect(this->toggleSpheresAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleSpheres(bool))); + this->addAction(this->toggleSpheresAction); + viewMenu->addAction(this->toggleSpheresAction); + + viewMenu->addSeparator(); + + this->toggleCameraAction->setText("Perspective/Orthographic"); + this->toggleCameraAction->setShortcut(QKeySequence("F9")); + QObject::connect(this->toggleCameraAction, SIGNAL(triggered()), this, SLOT(toggleCamera())); + this->addAction(this->toggleCameraAction); + viewMenu->addAction(this->toggleCameraAction); +} + +MainWindow* +MainWindow::instance() +{ + if (NULL == MainWindow::singleton) + { + new MainWindow(); + } + + return MainWindow::singleton; +} + +void +MainWindow::initAll() +{ + QMutexLocker lock(&this->mutex); + + this->clear(); + + this->filename = QString("DAMA"); + this->setWindowTitle(filename + " - " + this->engine + " - rlDamaDemoGUI"); + + this->model2 = boost::shared_ptr< dama::DamaModel >(DamaPlanner::getInstance()->dModelVis); + this->model = boost::shared_ptr< dama::DamaModel >(DamaPlanner::getInstance()->dModel); + + this->scene = boost::shared_ptr< rl::sg::Scene >(this->model->scene); + this->scene2 = boost::shared_ptr< rl::sg::so::Scene >(static_cast< rl::sg::so::Scene* >(this->model2->scene)); + this->sceneModel = this->model->model; + this->sceneModel2 = static_cast< rl::sg::so::Model* >(this->model2->model); + this->mdl = boost::shared_ptr< rl::mdl::Dynamic >(this->model->mdl); + this->mdl2 = boost::shared_ptr< rl::mdl::Dynamic >(this->model2->mdl); + this->sampler = boost::shared_ptr< dama::DamaSampler >(this->model->dRrt->dSampler); + this->sampler2 = boost::shared_ptr< dama::DamaSampler >(this->model2->dRrt->dSampler); + this->planner = boost::shared_ptr< dama::DamaRrt >(this->model->dRrt); + this->start = boost::shared_ptr< rl::math::Vector >(this->planner->start); + this->q = boost::make_shared< rl::math::Vector >(this->model->getDof()); + *this->q = *this->start; + this->goal = boost::shared_ptr< rl::math::Vector >(this->planner->goal); + this->mdl->setPosition(*this->q); + this->mdl->forwardPosition(); + this->goalDimDefined = boost::shared_ptr< ::std::vector >(this->planner->goalDimDefined); + + this->sigma = boost::make_shared< rl::math::Vector >(0); + this->optimizer.reset(); + + this->viewer->delta = boost::lexical_cast< rl::math::Real >(0.01f); + this->viewer->sceneGroup->addChild(this->scene2->root); + this->viewer->model = this->model2.get(); + this->viewer->customize(); + + // TODO: operates on planner model?! wtf?? + this->configurationSpaceScene->model = this->model.get(); // was this->model2.get() + + /*if (this->toggleViewAction->isChecked()) + this->toggleView(true); + else + this->toggleView(false);*/ + + this->viewer->viewer->setBackgroundColor(SbColor(0.0f, 0.0f, 0.0f)); + this->viewer->viewer->setCameraType(SoOrthographicCamera::getClassTypeId()); + this->viewer->viewer->getCamera()->setToDefaults(); + this->viewer->viewer->viewAll(); + + this->viewer->viewer->getCamera()->position.setValue( + this->viewer->viewer->getCamera()->position.getValue()[0], + this->viewer->viewer->getCamera()->position.getValue()[1], + this->viewer->viewer->getCamera()->position.getValue()[2] + ); + + this->viewer->viewer->getCamera()->scaleHeight(1.0f); + + this->evalAction->setEnabled(true); + this->savePdfAction->setEnabled(true); + this->toggleConfigurationSpaceAction->setEnabled(true); + + this->configurationSpaceScene->delta = 0.099f; + + this->configurationSpaceScene->x = static_cast< std::size_t >(0); + this->configurationSpaceScene->y = static_cast< std::size_t >(1); + + this->configurationSpaceScene->eval(); + + qreal scale = static_cast< std::size_t >(130.0f); + + this->configurationSpaceView->setEnabled(true); + + rl::math::Vector maximum(this->planner->dModel->getDof(0)); + this->planner->dModel->getMaximum(maximum, 0); + rl::math::Vector minimum(this->planner->dModel->getDof(0)); + this->planner->dModel->getMinimum(minimum, 0); + + this->configurationSpaceView->setSceneRect( + minimum(this->configurationSpaceScene->x), + -maximum(this->configurationSpaceScene->y), + std::abs(maximum(this->configurationSpaceScene->x) - minimum(this->configurationSpaceScene->x)), + std::abs(maximum(this->configurationSpaceScene->y) - minimum(this->configurationSpaceScene->y)) + ); + + this->configurationSpaceView->resetMatrix(); + this->configurationSpaceView->scale(scale, scale); + + this->configurationSpaceView->adjustSize(); + this->configurationSpaceDockWidget->adjustSize(); + + this->configurationSpaceDockWidget->setUpdatesEnabled(false); + this->configurationSpaceDockWidget->setFloating(!this->configurationSpaceDockWidget->isFloating()); + this->configurationSpaceDockWidget->setFloating(!this->configurationSpaceDockWidget->isFloating()); + this->configurationSpaceDockWidget->setUpdatesEnabled(true); + + this->viewer->drawConfiguration(*this->start); + + this->configurationModel->invalidate(); + this->plannerModel->invalidate(); + + this->startThread(); // uncomment if you want to start manually via space-key +} + +void +MainWindow::open() +{ + if (NULL != this->planner) + { + this->reset(); + } + + this->initAll(); +} + +void +MainWindow::reset() +{ + ::std::chrono::steady_clock::duration duration = this->planner->duration; + + this->thread->blockSignals(true); + QCoreApplication::processEvents(); + this->planner->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(0)); + this->thread->stop(); + this->planner->duration = duration; + this->thread->blockSignals(false); + + this->planner->reset(); + this->model->reset(); + this->viewer->reset(); + this->configurationSpaceScene->reset(); + + this->configurationView->setEnabled(true); + this->evalAction->setEnabled(true); + this->getGoalConfigurationAction->setEnabled(true); + this->getRandomConfigurationAction->setEnabled(true); + this->getRandomFreeConfigurationAction->setEnabled(true); + this->getStartConfigurationAction->setEnabled(true); + this->openAction->setEnabled(true); + this->plannerView->setEnabled(true); + this->setGoalConfigurationAction->setEnabled(true); + this->setStartConfigurationAction->setEnabled(true); + this->startThreadAction->setEnabled(true); + this->toggleViewAction->setEnabled(true); +} + +void +MainWindow::saveImage() +{ + this->viewer->saveImage("planDemo-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png"); +} + +void +MainWindow::savePdf() +{ + QPrinter printer; + printer.setOutputFileName("planDemo-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".pdf"); + printer.setOutputFormat(QPrinter::PdfFormat); + printer.setPageSize(QPrinter::A4); + + QPainter painter(&printer); + + this->configurationSpaceScene->render(&painter); +} + +void +MainWindow::saveScene() +{ + this->viewer->saveScene("planDemo-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".wrl"); +} + +void +MainWindow::setGoalConfiguration() +{ + *this->goal = *this->q; +} + +void +MainWindow::setStartConfiguration() +{ + *this->start = *this->q; +} + +void +MainWindow::startThread() +{ + this->configurationView->setEnabled(false); + this->evalAction->setEnabled(false); + this->getGoalConfigurationAction->setEnabled(false); + this->getRandomConfigurationAction->setEnabled(false); + this->getRandomFreeConfigurationAction->setEnabled(false); + this->getStartConfigurationAction->setEnabled(false); + this->openAction->setEnabled(false); + this->plannerView->setEnabled(false); + this->setGoalConfigurationAction->setEnabled(false); + this->setStartConfigurationAction->setEnabled(false); + this->startThreadAction->setEnabled(false); + this->toggleViewAction->setEnabled(false); + + this->thread->start(); +} + +void +MainWindow::toggleCamera() +{ + if (SoPerspectiveCamera::getClassTypeId() == this->viewer->viewer->getCameraType()) + { + this->viewer->viewer->setCameraType(SoOrthographicCamera::getClassTypeId()); + } + else + { + this->viewer->viewer->setCameraType(SoPerspectiveCamera::getClassTypeId()); + } + + SbVec3f position = this->viewer->viewer->getCamera()->position.getValue(); + SbRotation orientation = this->viewer->viewer->getCamera()->orientation.getValue(); + this->viewer->viewer->getCamera()->setToDefaults(); + this->viewer->viewer->getCamera()->position.setValue(position); + this->viewer->viewer->getCamera()->orientation.setValue(orientation); + this->viewer->viewer->viewAll(); +} + +void +MainWindow::toggleConfiguration() +{ + if (this->configurationDockWidget->isVisible()) + { + this->configurationDockWidget->hide(); + } + else + { + this->configurationDockWidget->show(); + } +} + +void +MainWindow::toggleConfigurationSpace() +{ + if (this->configurationSpaceView->isEnabled()) + { + if (this->configurationSpaceDockWidget->isVisible()) + { + this->configurationSpaceDockWidget->hide(); + } + else + { + this->configurationSpaceDockWidget->show(); + } + } +} + +void +MainWindow::togglePlanner() +{ + if (this->plannerDockWidget->isVisible()) + { + this->plannerDockWidget->hide(); + } + else + { + this->plannerDockWidget->show(); + } +} + +void +MainWindow::toggleView(const bool& doOn) +{ + if (doOn) + { + this->planner->viewer = this->thread; + + if (NULL != this->optimizer) + { + this->optimizer->viewer = this->thread; + } + + for (std::vector< boost::shared_ptr< rl::plan::WorkspaceSphereExplorer > >::iterator i = this->explorers.begin(); i != this->explorers.end(); ++i) + { + (*i)->viewer = this->thread; + } + + this->connect(this->thread, this->configurationSpaceScene); + this->connect(this->thread, this->viewer); + } + else + { + this->disconnect(this->thread, this->configurationSpaceScene); + this->disconnect(this->thread, this->viewer); + + this->planner->viewer = NULL; + + if (NULL != this->optimizer) + { + this->optimizer->viewer = NULL; + } + + for (std::vector< boost::shared_ptr< rl::plan::WorkspaceSphereExplorer > >::iterator i = this->explorers.begin(); i != this->explorers.end(); ++i) + { + (*i)->viewer = NULL; + } + } +} + +void MainWindow::quitAll() +{ + this->thread->stop(); + this->close(); +} + +void MainWindow::closeEvent(QCloseEvent *event) +{ + // TODO: fucking fix me, it only quits due to seg-fault ... + + MainWindow::singleton = NULL; + delete configurationModel; + delete plannerModel; + thread->exit(); + delete thread; + + event->accept(); + + QApplication::quit(); +} diff --git a/src/rlDamaDemoGUI/MainWindow.h b/src/rlDamaDemoGUI/MainWindow.h new file mode 100644 index 0000000..adbcbbf --- /dev/null +++ b/src/rlDamaDemoGUI/MainWindow.h @@ -0,0 +1,242 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _MAINWINDOW_H_ +#define _MAINWINDOW_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "XmlFactory.h" +#include "DamaRrt.h" +#include "DamaModel.h" +#include "DamaSampler.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +class ConfigurationDelegate; +class ConfigurationModel; +class ConfigurationSpaceScene; +class PlannerModel; +class Thread; +class Viewer; + +class MainWindow : public QMainWindow +{ + Q_OBJECT + +public: + virtual ~MainWindow(); + + static MainWindow* instance(); + + ConfigurationModel* configurationModel; + + std::vector< boost::shared_ptr< rl::math::Vector3 > > explorerGoals; + + std::vector< boost::shared_ptr< rl::plan::WorkspaceSphereExplorer > > explorers; + + std::vector< boost::shared_ptr< rl::math::Vector3 > > explorerStarts; + + boost::shared_ptr< rl::math::Vector > goal; + + boost::shared_ptr< ::std::vector > goalDimDefined; + + boost::shared_ptr< rl::kin::Kinematics > kin; + + boost::shared_ptr< rl::kin::Kinematics > kin2; + + boost::shared_ptr< rl::mdl::Dynamic > mdl; + + boost::shared_ptr< rl::mdl::Dynamic > mdl2; + + boost::shared_ptr< dama::DamaModel > model; + + boost::shared_ptr< dama::DamaModel > model2; + + QMutex mutex; + + boost::shared_ptr< rl::plan::Optimizer > optimizer; + + boost::shared_ptr< dama::DamaRrt > planner; + + PlannerModel* plannerModel; + + boost::shared_ptr< rl::math::Vector > q; + + boost::shared_ptr< dama::DamaSampler > sampler; + + boost::shared_ptr< dama::DamaSampler > sampler2; + + boost::shared_ptr< rl::math::Vector > sigma; + + boost::shared_ptr< rl::sg::Scene > scene; + + boost::shared_ptr< rl::sg::so::Scene > scene2; + + rl::sg::Model* sceneModel; + + rl::sg::so::Model* sceneModel2; + + boost::shared_ptr< rl::math::Vector > start; + + Thread* thread; + + boost::shared_ptr< rl::plan::Verifier > verifier; + + boost::shared_ptr< rl::plan::Verifier > verifier2; + + Viewer* viewer; + + bool threadRunning; + + void quitAll(); + +public slots: + void eval(); + + void getGoalConfiguration(); + + void getRandomConfiguration(); + + void getRandomFreeConfiguration(); + + void getStartConfiguration(); + + void open(); + + void reset(); + + void saveImage(); + + void savePdf(); + + void saveScene(); + + void setGoalConfiguration(); + + void setStartConfiguration(); + + void startThread(); + + void toggleCamera(); + + void toggleConfiguration(); + + void toggleConfigurationSpace(); + + void togglePlanner(); + + void toggleView(const bool& doOn); + +protected: + MainWindow(QWidget* parent = NULL, Qt::WindowFlags f = 0); + +private: + void clear(); + + void connect(const QObject* sender, const QObject* receiver); + + void disconnect(const QObject* sender, const QObject* receiver); + + void init(); + + void closeEvent(QCloseEvent *event); + + //void load(const QString& filename); + + void initAll(); + + ConfigurationDelegate* configurationDelegate; + + QDockWidget* configurationDockWidget; + + QDockWidget* configurationSpaceDockWidget; + + ConfigurationSpaceScene* configurationSpaceScene; + + QGraphicsView* configurationSpaceView; + + QTableView* configurationView; + + QString engine; + + QAction* evalAction; + + QAction* exitAction; + + QString filename; + + QAction* getGoalConfigurationAction; + + QAction* getRandomConfigurationAction; + + QAction* getRandomFreeConfigurationAction; + + QAction* getStartConfigurationAction; + + QAction* openAction; + + QDockWidget* plannerDockWidget; + + QTableView* plannerView; + + QAction* resetAction; + + QAction* saveImageAction; + + QAction* savePdfAction; + + QAction* saveSceneAction; + + QAction* setGoalConfigurationAction; + + QAction* setStartConfigurationAction; + + static MainWindow* singleton; + + QAction* startThreadAction; + + QAction* toggleCameraAction; + + QAction* toggleConfigurationAction; + + QAction* toggleConfigurationEdgesAction; + + QAction* toggleConfigurationSpaceAction; + + QAction* toggleConfigurationVerticesAction; + + QAction* toggleLinesAction; + + QAction* togglePlannerAction; + + QAction* togglePointsAction; + + QAction* toggleSpheresAction; + + QAction* toggleViewAction; + + QAction* toggleWorkFramesAction; + + bool wait; +}; + +#endif // _MAINWINDOW_H_ diff --git a/src/rlDamaDemoGUI/PlannerModel.cpp b/src/rlDamaDemoGUI/PlannerModel.cpp new file mode 100644 index 0000000..7547d09 --- /dev/null +++ b/src/rlDamaDemoGUI/PlannerModel.cpp @@ -0,0 +1,312 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include + +#include "MainWindow.h" +#include "PlannerModel.h" +#include "Thread.h" + +PlannerModel::PlannerModel(QObject* parent) : + QAbstractTableModel(parent) +{ + +} + +PlannerModel::~PlannerModel() +{ +} + +int +PlannerModel::columnCount(const QModelIndex& parent) const +{ + return 1; +} + +QVariant +PlannerModel::data(const QModelIndex& index, int role) const +{ + if (NULL == MainWindow::instance()->planner) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + switch (index.row()) + { + case 0: + return -1; //FIXME add duration cast: MainWindow::instance()->planner->duration; + break; + default: + break; + } + + if (rl::plan::Prm* prm = dynamic_cast< rl::plan::Prm* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 1: + return static_cast< unsigned int >(prm->degree); + break; + case 2: + return prm->verifier->delta; + break; + case 3: + return static_cast< unsigned int >(prm->k); + break; + case 4: + return prm->radius; + break; + default: + break; + } + } + + if (rl::plan::Rrt* rrt = dynamic_cast< rl::plan::Rrt* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 1: + return rrt->delta; + break; + case 2: + return rrt->epsilon; + break; + default: + break; + } + } + + if (rl::plan::RrtGoalBias* rrtGoalBias = dynamic_cast< rl::plan::RrtGoalBias* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 3: + return rrtGoalBias->probability; + break; + default: + break; + } + } + case Qt::TextAlignmentRole: + return Qt::AlignRight; + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +PlannerModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +PlannerModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (NULL == MainWindow::instance()->planner) + { + return QVariant(); + } + + if (Qt::DisplayRole == role && Qt::Horizontal == orientation) + { + if (0 == section) + { + return MainWindow::instance()->planner->getName().c_str(); + } + } + + if (Qt::DisplayRole == role && Qt::Vertical == orientation) + { + switch (section) + { + case 0: + return "duration"; + break; + default: + break; + } + + if (dynamic_cast< rl::plan::Prm* >(MainWindow::instance()->planner.get())) + { + switch (section) + { + case 1: + return "degree"; + break; + case 2: + return "delta"; + break; + case 3: + return "k"; + break; + case 4: + return "radius"; + break; + default: + break; + } + } + + if (dynamic_cast< rl::plan::Rrt* >(MainWindow::instance()->planner.get())) + { + switch (section) + { + case 1: + return "delta"; + break; + case 2: + return "epsilon"; + break; + default: + break; + } + } + + if (dynamic_cast< rl::plan::RrtGoalBias* >(MainWindow::instance()->planner.get())) + { + switch (section) + { + case 3: + return "probability"; + break; + default: + break; + } + } + } + + return QVariant(); +} + +void +PlannerModel::invalidate() +{ + this->reset(); +} + +int +PlannerModel::rowCount(const QModelIndex& parent) const +{ + if (NULL == MainWindow::instance()->planner) + { + return 0; + } + + if (dynamic_cast< rl::plan::Prm* >(MainWindow::instance()->planner.get())) + { + return 5; + } + else if (dynamic_cast< rl::plan::RrtGoalBias* >(MainWindow::instance()->planner.get())) + { + return 4; + } + else if (dynamic_cast< rl::plan::Rrt* >(MainWindow::instance()->planner.get())) + { + return 3; + } + + return 0; +} + +bool +PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (NULL == MainWindow::instance()->planner) + { + return false; + } + + if (MainWindow::instance()->thread->isRunning()) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + switch (index.row()) + { + case 0: + MainWindow::instance()->planner->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(value.value< ::rl::math::Real >())); + break; + default: + break; + } + + if (rl::plan::Prm* prm = dynamic_cast< rl::plan::Prm* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 1: + prm->degree = value.value< ::std::size_t >(); + break; + case 2: + prm->verifier->delta = value.value< ::rl::math::Real >(); + break; + case 3: + prm->k = value.value< ::std::size_t >(); + break; + case 4: + prm->radius = value.value< ::rl::math::Real >(); + break; + default: + break; + } + } + + if (rl::plan::Rrt* rrt = dynamic_cast< rl::plan::Rrt* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 1: + rrt->delta = value.value< ::rl::math::Real >(); + break; + case 2: + rrt->epsilon = value.value< ::rl::math::Real >(); + break; + default: + break; + } + } + + if (rl::plan::RrtGoalBias* rrtGoalBias = dynamic_cast< rl::plan::RrtGoalBias* >(MainWindow::instance()->planner.get())) + { + switch (index.row()) + { + case 3: + rrtGoalBias->probability = value.value< ::rl::math::Real >(); + break; + default: + break; + } + } + + emit dataChanged(index, index); + + return true; + } + + return false; +} diff --git a/src/rlDamaDemoGUI/PlannerModel.h b/src/rlDamaDemoGUI/PlannerModel.h new file mode 100644 index 0000000..7d4406f --- /dev/null +++ b/src/rlDamaDemoGUI/PlannerModel.h @@ -0,0 +1,38 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _PLANNERMODEL_H_ +#define _PLANNERMODEL_H_ + +#include + +class PlannerModel : public QAbstractTableModel +{ +public: + PlannerModel(QObject* parent = NULL); + + virtual ~PlannerModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + +protected: + +private: + +}; + +#endif // _PLANNERMODEL_H_ diff --git a/src/rlDamaDemoGUI/Thread.cpp b/src/rlDamaDemoGUI/Thread.cpp new file mode 100644 index 0000000..72ec4c1 --- /dev/null +++ b/src/rlDamaDemoGUI/Thread.cpp @@ -0,0 +1,318 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "DamaRrt.h" +#include "DamaModel.h" +#include "DamaSampler.h" +#include "Timer.h" + +#include "DamaPlanner.h" +#include "MainWindow.h" +#include "Thread.h" +#include "Viewer.h" + +Thread::Thread(QObject* parent) : + QThread(parent), + quit(false), + swept(false), + running(false) +{ +} + +Thread::~Thread() +{ +} + +void +Thread::drawConfiguration(const rl::math::Vector& q) +{ + emit configurationRequested(q); +} + +void +Thread::drawConfigurationEdge(const rl::math::Vector& q0, const rl::math::Vector& q1, const bool& free) +{ + emit configurationEdgeRequested(q0, q1, free); +} + +void +Thread::drawConfigurationPath(const rl::plan::VectorList& path) +{ + emit configurationPathRequested(path); +} + +void +Thread::drawConfigurationVertex(const rl::math::Vector& q, const bool& free) +{ + emit configurationVertexRequested(q, free); +} + +void +Thread::drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1) +{ + emit lineRequested(xyz0, xyz1); +} + +void +Thread::drawPoint(const rl::math::Vector& xyz) +{ + emit pointRequested(xyz); +} + +void +Thread::drawSphere(const rl::math::Vector& center, const rl::math::Real& radius) +{ + emit sphereRequested(center, radius); +} + +void +Thread::drawSweptVolume(const rl::plan::VectorList& path) +{ + emit sweptVolumeRequested(path); +} + +void +Thread::drawWork(const rl::math::Transform& t) +{ + emit workRequested(t); +} + +void +Thread::drawWorkEdge(const rl::math::Vector& q0, const rl::math::Vector& q1) +{ +// emit workEdgeRequested(q0, q1); +} + +void +Thread::drawWorkPath(const rl::plan::VectorList& path) +{ + emit workPathRequested(path); +} + +void +Thread::drawWorkVertex(const rl::math::Vector& q) +{ +// emit workVertexRequested(q); +} + +void +Thread::reset() +{ + emit resetRequested(); +} + +void +Thread::resetEdges() +{ + emit edgeResetRequested(); +} + +void +Thread::resetLines() +{ + emit lineResetRequested(); +} + +void +Thread::resetPoints() +{ + emit pointResetRequested(); +} + +void +Thread::resetSpheres() +{ + emit sphereResetRequested(); +} + +void +Thread::resetVertices() +{ + emit vertexResetRequested(); +} + +void +Thread::run() +{ + QMutexLocker lock(&MainWindow::instance()->mutex); + this->running = true; + ::dama::Timer timer; + + if(DamaPlanner::getInstance()->dModel->viewerOnlyResult == "on") + MainWindow::instance()->toggleView(false); + else + MainWindow::instance()->toggleView(true); + + DamaPlanner::getInstance()->run(); + + if(!this->running) return; + + if(this->quit) + { + QApplication::quit(); + return; + } + + MainWindow::instance()->toggleView(true); + + if(DamaPlanner::getInstance()->vecSolved.back()) + { + if (this->swept) + { + this->drawSweptVolume(DamaPlanner::getInstance()->vecPath.back()); + return; + } + + //this->drawConfigurationPath(path); + rl::plan::VectorList::iterator i = DamaPlanner::getInstance()->vecPath.back().begin(); + rl::plan::VectorList::iterator j = ++(DamaPlanner::getInstance()->vecPath.back().begin()); + ::std::deque< ::std::string >::iterator e = DamaPlanner::getInstance()->vecActions.back().begin(); + MainWindow::instance()->viewer->drawConfigurationVertex(*i); + for(; i != DamaPlanner::getInstance()->vecPath.back().end() && j != DamaPlanner::getInstance()->vecPath.back().end() && e != DamaPlanner::getInstance()->vecActions.back().end(); ++i, ++j, ++e) + { + MainWindow::instance()->viewer->drawConfigurationVertex(*j); + MainWindow::instance()->viewer->drawConfigurationEdge(*i, *j); + } + + if (!this->running) return; + + if (NULL != MainWindow::instance()->optimizer) + { + usleep(static_cast< std::size_t >(2.0f * 1000.0f * 1000.0f)); + + std::cout << "optimize() ... " << std::endl;; + timer.start(); + MainWindow::instance()->optimizer->process(DamaPlanner::getInstance()->vecPath.back()); + timer.stop(); + std::cout << "optimize() " << timer.elapsed() * 1000.0f << " ms" << std::endl; + + this->drawConfigurationPath(DamaPlanner::getInstance()->vecPath.back()); + } + + rl::math::Vector inter(DamaPlanner::getInstance()->dModel->getDof()); + + unsigned int maxLoopCount = 1; + if(DamaPlanner::getInstance()->dModel->viewerMode == "loop") + maxLoopCount = std::numeric_limits::max(); + + for(unsigned int l=0; lrunning) break; + + rl::plan::VectorList::iterator i = DamaPlanner::getInstance()->vecPath.back().begin(); + rl::plan::VectorList::iterator j = ++(DamaPlanner::getInstance()->vecPath.back().begin()); + ::std::deque< ::std::string >::iterator e = DamaPlanner::getInstance()->vecActions.back().begin(); + + if (i != DamaPlanner::getInstance()->vecPath.back().end() && j != DamaPlanner::getInstance()->vecPath.back().end()) + { + this->drawConfiguration(*i); + usleep(static_cast< std::size_t >(1.0f * 1000.0f * 1000.0f)); + } + + rl::math::Real deltaSpeed = DamaPlanner::getInstance()->dModel->speedFactor * 0.0025; + + for (; i != DamaPlanner::getInstance()->vecPath.back().end() && j != DamaPlanner::getInstance()->vecPath.back().end() && e != DamaPlanner::getInstance()->vecActions.back().end(); ++i, ++j, ++e) + { + // Change the end-effector body according to the current primitive if needed + dama::DamaModel* dModel2 = DamaPlanner::getInstance()->dModelVis.get(); + //MainWindow::instance()->viewer->viewer->setSceneGraph(NULL); + ::rl::sg::so::Body* myBody = NULL; + ::std::size_t indexNumber = e->find_last_of(" "); + ::std::string primNameRaw = e->substr(0,indexNumber); + for(int i=0; ivecDamaPrim.size(); i++) + { + //::std::cout << dModel2->vecDamaPrim.at(i)->getName() << " == " << primNameRaw << " ??" << ::std::endl; + if(dModel2->vecDamaPrim.at(i)->getName() == primNameRaw) + { + myBody = dModel2->vecDamaPrim.at(i)->endEffectorBodyVis; + break; + } + } + if(myBody != dModel2->currEndEffectorBodyVis) + { + //::std::cout << "Viewer: change to end-effector body " << myBody->getName() << ::std::endl; + // TODO: FIXME: crashes sometimes! if remove+add get interrupted by another Qt thread! + dModel2->scene->getModel(0)->remove(dModel2->scene->getModel(0)->getBody(dModel2->scene->getModel(0)->getNumBodies()-1)); + dModel2->scene->getModel(0)->add(myBody); + dModel2->currEndEffectorBodyVis = myBody; + } + //::std::cout << "#bodies: " << dModel2->getBodies() << ::std::endl; + //::std::cout << "#shapes of last body '" << dModel2->getBody(dModel2->getBodies())->getName() << "': " << dModel2->getBody(dModel2->getBodies())->getNumShapes() << ::std::endl; + //::std::cout << "#shapes of second last body '" << dModel2->getBody(dModel2->getBodies()-1)->getName() << "': " << dModel2->getBody(dModel2->getBodies()-1)->getNumShapes() << ::std::endl; + //::rl::sg::so::Scene* sceneVis = static_cast< ::rl::sg::so::Scene* >(dModel2->scene); + //MainWindow::instance()->viewer->viewer->setSceneGraph(sceneVis->root); + + dama::DamaModel* dModel = DamaPlanner::getInstance()->dModel.get(); + rl::math::Real steps = std::ceil(dModel->robotMovementDistance(*i, *j) / deltaSpeed); + + for (std::size_t k = 1; k < steps + 1; ++k) + { + if (!this->running) break; + + DamaPlanner::getInstance()->dModel->interpolate(*i, *j, k / steps, inter); + this->drawConfiguration(inter); + usleep(static_cast< std::size_t >(0.01f * 1000.0f * 1000.0f)); + } + } + + if(l+1 < maxLoopCount) + usleep(static_cast< std::size_t >(1.0f * 1000.0f * 1000.0f)); + + /*if (!this->running) break; + + rl::plan::VectorList::reverse_iterator ri = path.rbegin(); + rl::plan::VectorList::reverse_iterator rj = ++path.rbegin(); + + if (ri != path.rend() && rj != path.rend()) + { + this->drawConfiguration(*ri); + usleep(static_cast< std::size_t >(0.01f * 1000.0f * 1000.0f)); + } + + for (; ri != path.rend() && rj != path.rend(); ++ri, ++rj) + { + diff = *rj - *ri; + + rl::math::Real steps = std::ceil(DamaPlanner::getInstance()->dModel->distance(*ri, *rj) / delta); + + for (std::size_t k = 1; k < steps + 1; ++k) + { + if (!this->running) break; + + DamaPlanner::getInstance()->dModel->interpolate(*ri, *rj, k / steps, inter); + this->drawConfiguration(inter); + usleep(static_cast< std::size_t >(0.01f * 1000.0f * 1000.0f)); + } + }*/ + } + } + + QApplication::quit(); +} + +void +Thread::stop() +{ + if (this->running) + { + this->running = false; + + /*while (!this->isFinished()) + { + QThread::usleep(0); + }*/ + } +} diff --git a/src/rlDamaDemoGUI/Thread.h b/src/rlDamaDemoGUI/Thread.h new file mode 100644 index 0000000..9868a35 --- /dev/null +++ b/src/rlDamaDemoGUI/Thread.h @@ -0,0 +1,108 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _THREAD_H_ +#define _THREAD_H_ + +#include +#include + +class Thread : public QThread, public rl::plan::Viewer +{ + Q_OBJECT + +public: + Thread(QObject* parent = NULL); + + virtual ~Thread(); + + void drawConfiguration(const rl::math::Vector& q); + + void drawConfigurationEdge(const rl::math::Vector& q0, const rl::math::Vector& q1, const bool& free = true); + + void drawConfigurationPath(const rl::plan::VectorList& path); + + void drawConfigurationVertex(const rl::math::Vector& q, const bool& free = true); + + void drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1); + + void drawPoint(const rl::math::Vector& xyz); + + void drawSphere(const rl::math::Vector& center, const rl::math::Real& radius); + + void drawSweptVolume(const rl::plan::VectorList& path); + + void drawWork(const rl::math::Transform& t); + + void drawWorkEdge(const rl::math::Vector& q0, const rl::math::Vector& q1); + + void drawWorkPath(const rl::plan::VectorList& path); + + void drawWorkVertex(const rl::math::Vector& q); + + void reset(); + + void resetEdges(); + + void resetLines(); + + void resetPoints(); + + void resetSpheres(); + + void resetVertices(); + + void run(); + + void stop(); + + bool quit; + + bool swept; + +protected: + +private: + bool running; + +signals: + void configurationRequested(const rl::math::Vector& q); + + void configurationEdgeRequested(const rl::math::Vector& q0, const rl::math::Vector& q1, const bool& free); + + void configurationVertexRequested(const rl::math::Vector& q, const bool& free); + + void configurationPathRequested(const rl::plan::VectorList& path); + + void edgeResetRequested(); + + void lineRequested(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1); + + void lineResetRequested(); + + void pointRequested(const rl::math::Vector& xyz); + + void pointResetRequested(); + + void resetRequested(); + + void sphereRequested(const rl::math::Vector& center, const rl::math::Real& radius); + + void sphereResetRequested(); + + void sweptVolumeRequested(const rl::plan::VectorList& path); + + void vertexResetRequested(); + + void workRequested(const rl::math::Transform& t); + + void workEdgeRequested(const rl::math::Vector& q0, const rl::math::Vector& q1); + + void workPathRequested(const rl::plan::VectorList& path); + + void workVertexRequested(const rl::math::Vector& q); +}; + +#endif // _THREAD_H_ diff --git a/src/rlDamaDemoGUI/Viewer.cpp b/src/rlDamaDemoGUI/Viewer.cpp new file mode 100644 index 0000000..cb74ee1 --- /dev/null +++ b/src/rlDamaDemoGUI/Viewer.cpp @@ -0,0 +1,991 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "MainWindow.h" +#include "Viewer.h" + +Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : + QWidget(parent, f), + delta(1.0f), + model(NULL), + sceneGroup(new SoVRMLGroup()), + viewer(new SoQtExaminerViewer(this, NULL, true, SoQtFullViewer::BUILD_POPUP)), + edges(new SoVRMLSwitch()), + edgesColliding(new SoVRMLSwitch()), + edgesCollidingAppearance(new SoVRMLAppearance()), + edgesCollidingCoordinate(new SoVRMLCoordinate()), + edgesCollidingDrawStyle(new SoDrawStyle()), + edgesCollidingIndexedLineSet(new SoVRMLIndexedLineSet()), + edgesCollidingMaterial(new SoVRMLMaterial()), + edgesCollidingShape(new SoVRMLShape()), + edgesFree(new SoVRMLSwitch()), + edgesFreeAppearance(new SoVRMLAppearance()), + edgesFreeCoordinate(new SoVRMLCoordinate()), + edgesFreeDrawStyle(new SoDrawStyle()), + edgesFreeIndexedLineSet(new SoVRMLIndexedLineSet()), + edgesFreeMaterial(new SoVRMLMaterial()), + edgesFreeShape(new SoVRMLShape()), + edges3(new SoVRMLSwitch()), + edges3Appearance(new SoVRMLAppearance()), + edges3Coordinate(new SoVRMLCoordinate()), + edges3DrawStyle(new SoDrawStyle()), + edges3IndexedLineSet(new SoVRMLIndexedLineSet()), + edges3Material(new SoVRMLMaterial()), + edges3Shape(new SoVRMLShape()), + frameIndexedLineSet(new SoVRMLIndexedLineSet()), + lines(new SoVRMLSwitch()), + linesAppearance(new SoVRMLAppearance()), + linesCoordinate(new SoVRMLCoordinate()), + linesDrawStyle(new SoDrawStyle()), + linesIndexedLineSet(new SoVRMLIndexedLineSet()), + linesMaterial(new SoVRMLMaterial()), + linesShape(new SoVRMLShape()), + path(new SoVRMLSwitch()), + pathAppearance(new SoVRMLAppearance()), + pathCoordinate(new SoVRMLCoordinate()), + pathDrawStyle(new SoDrawStyle()), + pathIndexedLineSet(new SoVRMLIndexedLineSet()), + pathMaterial(new SoVRMLMaterial()), + pathShape(new SoVRMLShape()), + path3(new SoVRMLSwitch()), + path3Appearance(new SoVRMLAppearance()), + path3Coordinate(new SoVRMLCoordinate()), + path3DrawStyle(new SoDrawStyle()), + path3IndexedLineSet(new SoVRMLIndexedLineSet()), + path3Material(new SoVRMLMaterial()), + path3Shape(new SoVRMLShape()), + points(new SoVRMLSwitch()), + pointsAppearance(new SoVRMLAppearance()), + pointsCoordinate(new SoVRMLCoordinate()), + pointsDrawStyle(new SoDrawStyle()), + pointsPointSet(new SoVRMLPointSet()), + pointsMaterial(new SoVRMLMaterial()), + pointsShape(new SoVRMLShape()), + root(new SoVRMLSwitch()), + scene(new SoVRMLSwitch()), + sceneDrawStyle(new SoDrawStyle()), + spheres(new SoVRMLSwitch()), + spheresAppearance(new SoVRMLAppearance()), + spheresDrawStyle(new SoDrawStyle()), + spheresGroup(new SoVRMLGroup()), + spheresMaterial(new SoVRMLMaterial()), + swept(new SoVRMLSwitch()), + sweptGroup(new SoVRMLGroup()), + vertices(new SoVRMLSwitch()), + verticesColliding(new SoVRMLSwitch()), + verticesCollidingAppearance(new SoVRMLAppearance()), + verticesCollidingColor(new SoVRMLColor()), + verticesCollidingCoordinate(new SoVRMLCoordinate()), + verticesCollidingDrawStyle(new SoDrawStyle()), + verticesCollidingPointSet(new SoVRMLPointSet()), + verticesCollidingMaterial(new SoVRMLMaterial()), + verticesCollidingShape(new SoVRMLShape()), + verticesFree(new SoVRMLSwitch()), + verticesFreeAppearance(new SoVRMLAppearance()), + verticesFreeColor(new SoVRMLColor()), + verticesFreeCoordinate(new SoVRMLCoordinate()), + verticesFreeDrawStyle(new SoDrawStyle()), + verticesFreePointSet(new SoVRMLPointSet()), + verticesFreeMaterial(new SoVRMLMaterial()), + verticesFreeShape(new SoVRMLShape()), + work(new SoVRMLSwitch()), + workDrawStyle(new SoDrawStyle()), + workTransform(new SoVRMLTransform()) +{ + this->root->ref(); + + this->viewer->setSceneGraph(this->root); + this->viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND); + + // edgesColliding + + this->edgesColliding->setName("edgesColliding"); + this->edgesColliding->whichChoice = SO_SWITCH_ALL; + + this->edgesCollidingDrawStyle->lineWidth = 1.0f; + + this->edgesCollidingDrawStyle->pointSize = 0.0f; + this->edgesColliding->addChild(this->edgesCollidingDrawStyle); + + this->edgesCollidingMaterial->diffuseColor.setValue(0.9f, 0.0f, 0.0f); + this->edgesCollidingAppearance->material = this->edgesCollidingMaterial; + this->edgesCollidingShape->appearance = this->edgesCollidingAppearance; + + this->edgesCollidingIndexedLineSet->coord = this->edgesCollidingCoordinate; + this->edgesCollidingShape->geometry = this->edgesCollidingIndexedLineSet; + + this->edgesColliding->addChild(this->edgesCollidingShape); + + this->edges->addChild(this->edgesColliding); + + // edgesFree + + this->edgesFree->setName("edgesFree"); + this->edgesFree->whichChoice = SO_SWITCH_ALL; + + this->edgesFreeDrawStyle->lineWidth = 1.0f; + + this->edgesFreeDrawStyle->pointSize = 0.0f; + this->edgesFree->addChild(this->edgesFreeDrawStyle); + + this->edgesFreeMaterial->diffuseColor.setValue(0.2f, 0.2f, 1.0f); + this->edgesFreeAppearance->material = this->edgesFreeMaterial; + this->edgesFreeShape->appearance = this->edgesFreeAppearance; + + this->edgesFreeIndexedLineSet->coord = this->edgesFreeCoordinate; + this->edgesFreeShape->geometry = this->edgesFreeIndexedLineSet; + + this->edgesFree->addChild(this->edgesFreeShape); + + this->edges->addChild(this->edgesFree); + + // edges + + this->edges->setName("edges"); + this->edges->whichChoice = SO_SWITCH_ALL; + + this->root->addChild(this->edges); + + // edges3 + + this->edges3->setName("edges3"); + this->edges3->whichChoice = SO_SWITCH_ALL; + + this->edges3DrawStyle->lineWidth = 1.0f; + this->edges3DrawStyle->pointSize = 0.0f; + this->edges3->addChild(this->edges3DrawStyle); + + this->edges3Material->diffuseColor.setValue(0.5f, 0.5f, 0.5f); + this->edges3Appearance->material = this->edges3Material; + this->edges3Shape->appearance = this->edges3Appearance; + + this->edges3IndexedLineSet->coord = this->edges3Coordinate; + this->edges3Shape->geometry = this->edges3IndexedLineSet; + + this->edges3->addChild(this->edges3Shape); + + this->root->addChild(this->edges3); + + // frame + + this->frameIndexedLineSet->colorPerVertex = false; + + SoVRMLColor* frameColor = new SoVRMLColor(); + this->frameIndexedLineSet->color = frameColor; + frameColor->color.set1Value(0, 1.0f, 0.0f, 0.0f); + frameColor->color.set1Value(1, 0.0f, 1.0f, 0.0f); + frameColor->color.set1Value(2, 0.0f, 0.0f, 1.0f); + + this->frameIndexedLineSet->colorIndex.set1Value(0, 0); + this->frameIndexedLineSet->colorIndex.set1Value(1, 1); + this->frameIndexedLineSet->colorIndex.set1Value(2, 2); + + SoVRMLCoordinate* frameCoordinate = new SoVRMLCoordinate(); + this->frameIndexedLineSet->coord = frameCoordinate; + frameCoordinate->point.set1Value(0, 0.0f, 0.0f, 0.0f); + frameCoordinate->point.set1Value(1, 0.25f, 0.0f, 0.0f); + frameCoordinate->point.set1Value(2, 0.0f, 0.25f, 0.0f); + frameCoordinate->point.set1Value(3, 0.0f, 0.0f, 0.25f); + + this->frameIndexedLineSet->coordIndex.set1Value(0, 0); + this->frameIndexedLineSet->coordIndex.set1Value(1, 1); + this->frameIndexedLineSet->coordIndex.set1Value(2, SO_END_FACE_INDEX); + this->frameIndexedLineSet->coordIndex.set1Value(3, 0); + this->frameIndexedLineSet->coordIndex.set1Value(4, 2); + this->frameIndexedLineSet->coordIndex.set1Value(5, SO_END_FACE_INDEX); + this->frameIndexedLineSet->coordIndex.set1Value(6, 0); + this->frameIndexedLineSet->coordIndex.set1Value(7, 3); + this->frameIndexedLineSet->coordIndex.set1Value(8, SO_END_FACE_INDEX); + + // lines + + this->lines->setName("lines"); + this->lines->whichChoice = SO_SWITCH_ALL; + + this->linesDrawStyle->lineWidth = 1.0f; + this->linesDrawStyle->pointSize = 0.0f; + this->lines->addChild(this->linesDrawStyle); + + this->linesMaterial->diffuseColor.setValue(232.0f / 255.0f, 21.0f / 255.0f, 21.0f / 255.0f); + this->linesAppearance->material = this->linesMaterial; + this->linesShape->appearance = this->linesAppearance; + + this->linesIndexedLineSet->coord = this->linesCoordinate; + this->linesShape->geometry = this->linesIndexedLineSet; + + this->lines->addChild(this->linesShape); + + this->root->addChild(this->lines); + + // path + + this->path->setName("path"); + this->path->whichChoice = SO_SWITCH_ALL; + + this->pathDrawStyle->lineWidth = 3.0f; + this->pathDrawStyle->pointSize = 0.0f; + this->path->addChild(this->pathDrawStyle); + + this->pathMaterial->diffuseColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); + this->pathAppearance->material = this->pathMaterial; + this->pathShape->appearance = this->pathAppearance; + + this->pathIndexedLineSet->coord = this->pathCoordinate; + this->pathShape->geometry = this->pathIndexedLineSet; + + this->path->addChild(this->pathShape); + + this->root->addChild(this->path); + + // path3 + + this->path3->setName("path3"); + this->path3->whichChoice = SO_SWITCH_ALL; + + this->path3DrawStyle->lineWidth = 3.0f; + this->path3DrawStyle->pointSize = 0.0f; + this->path3->addChild(this->path3DrawStyle); + + this->path3Material->diffuseColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); + this->path3Appearance->material = this->path3Material; + this->path3Shape->appearance = this->path3Appearance; + + this->path3IndexedLineSet->coord = this->path3Coordinate; + this->path3Shape->geometry = this->path3IndexedLineSet; + + this->path3->addChild(this->path3Shape); + + this->root->addChild(this->path3); + + // points + + this->points->setName("points"); + this->points->whichChoice = SO_SWITCH_ALL; + + this->pointsDrawStyle->lineWidth = 0.0f; + this->pointsDrawStyle->pointSize = 4.0f; + this->points->addChild(this->pointsDrawStyle); + + this->pointsMaterial->emissiveColor.setValue(232.0f / 255.0f, 21.0f / 255.0f, 21.0f / 255.0f); + this->pointsAppearance->material = this->pointsMaterial; + this->pointsShape->appearance = this->pointsAppearance; + + this->pointsPointSet->coord = this->pointsCoordinate; + this->pointsShape->geometry = this->pointsPointSet; + + this->points->addChild(this->pointsShape); + + this->root->addChild(this->points); + + // spheres + + this->spheres->setName("spheres"); + this->spheres->whichChoice = SO_SWITCH_ALL; + + this->spheres->addChild(this->spheresDrawStyle); + + this->spheresMaterial->diffuseColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); + this->spheresMaterial->transparency.setValue(0.9f); + this->spheresAppearance->material = this->spheresMaterial; + + this->spheresAppearance->ref(); + + this->spheres->addChild(this->spheresGroup); + + this->root->addChild(this->spheres); + + // swept + + this->swept->setName("swept"); + this->swept->whichChoice = SO_SWITCH_ALL; + + this->swept->addChild(this->sweptGroup); + + this->root->addChild(this->swept); + + // verticesColliding + + this->verticesColliding->setName("verticesColliding"); + this->verticesColliding->whichChoice = SO_SWITCH_ALL; + + this->verticesCollidingDrawStyle->lineWidth = 0.0f; + this->verticesCollidingDrawStyle->pointSize = 8.0f; + this->verticesColliding->addChild(this->verticesCollidingDrawStyle); + + this->verticesCollidingMaterial->emissiveColor.setValue(232.0f / 255.0f, 21.0f / 255.0f, 21.0f / 255.0f); + this->verticesCollidingAppearance->material = this->verticesCollidingMaterial; + this->verticesCollidingShape->appearance = this->verticesCollidingAppearance; + + this->verticesCollidingPointSet->coord = this->verticesCollidingCoordinate; + this->verticesCollidingShape->geometry = this->verticesCollidingPointSet; + + this->verticesColliding->addChild(this->verticesCollidingShape); + + this->root->addChild(this->verticesColliding); + + // verticesFree -> my lovely vertices, now in pure black ! + + this->verticesFree->setName("verticesFree"); + this->verticesFree->whichChoice = SO_SWITCH_ALL; + + this->verticesFreeDrawStyle->lineWidth = 0.0f; + + this->verticesFreeDrawStyle->pointSize = 8.0f; + + this->verticesFree->addChild(this->verticesFreeDrawStyle); + + this->verticesFreeMaterial->emissiveColor.setValue(0.0f / 255.0f, 0.0f / 255.0f, 0.0f / 255.0f); // 55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f + this->verticesFreeAppearance->material = this->verticesFreeMaterial; + this->verticesFreeShape->appearance = this->verticesFreeAppearance; + + this->verticesFreePointSet->coord = this->verticesFreeCoordinate; + this->verticesFreeShape->geometry = this->verticesFreePointSet; + + this->verticesFree->addChild(this->verticesFreeShape); + + this->vertices->addChild(this->verticesFree); + + // vertices + + this->vertices->setName("vertices"); + this->vertices->whichChoice = SO_SWITCH_NONE; + + this->root->addChild(this->vertices); + + // work + + this->work->setName("work"); + this->work->whichChoice = SO_SWITCH_NONE; + + this->work->addChild(this->workDrawStyle); + + this->workTransform->addChild(this->frameIndexedLineSet); + + this->work->addChild(this->workTransform); + + this->root->addChild(this->work); + + // scene + + this->scene->setName("scene"); + this->scene->whichChoice = SO_SWITCH_ALL; + + this->scene->addChild(this->sceneDrawStyle); + + this->scene->addChild(this->sceneGroup); + + this->root->addChild(this->scene); + + // root + + this->root->setName("root"); + this->root->whichChoice = SO_SWITCH_ALL; +} + +Viewer::~Viewer() +{ + this->spheresAppearance->unref(); + this->root->unref(); +} + +void Viewer::customize() +{ + this->edgesCollidingDrawStyle->lineWidth = this->model->lineWidth; + this->edgesFreeDrawStyle->lineWidth = this->model->lineWidth; + this->verticesFreeDrawStyle->pointSize = this->model->pointSize; +} + +void +Viewer::drawConfiguration(const rl::math::Vector& q) +{ + QMutexLocker lock_(&draw_mutex); + + this->model->setPosition(q); + this->model->updateFrames(); +} + +void +Viewer::drawConfigurationEdge(const rl::math::Vector& u, const rl::math::Vector& v, const bool& free) +{ + QMutexLocker lock_(&draw_mutex); + + SoVRMLCoordinate* coordinate = NULL; + SoVRMLIndexedLineSet* indexedLineSet = NULL; + + //if (free) + bool movingObject = this->model->isMovingObject(u, v); + + //std::cout << "drawConfigurationEdge: " << u(2) << " " << u(3) << " | " << v(2) << " " << v(3) << std::endl; + + //if(u(2) == -0.9 && u(3) == -0.9 && v(2) == -0.9 && v(3) == -0.9) + //if (free) + if(!movingObject) + { + // draw TRANSIT in blue + coordinate = this->edgesFreeCoordinate; + indexedLineSet = this->edgesFreeIndexedLineSet; + } + else + { + // draw MANIPULATION in red + coordinate = this->edgesCollidingCoordinate; + indexedLineSet = this->edgesCollidingIndexedLineSet; + } + + this->edges->enableNotify(false); + + rl::math::Vector inter(this->model->getDof()); + + rl::math::Real steps = std::ceil(this->model->robotMovementDistance(u, v) / this->delta); + + if (steps > 0) + { + for (std::size_t l = 0; l < this->model->getOperationalDof(); ++l) + { + for (std::size_t i = 0; i < steps + 1; ++i) + { + this->model->interpolate(u, v, i / steps, inter); + + this->model->setPosition(inter); + this->model->updateFrames(false); // set to true if you want to see robot move while searching for a solution + + coordinate->point.set1Value( + coordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) + ); + + indexedLineSet->coordIndex.set1Value( + indexedLineSet->coordIndex.getNum(), + coordinate->point.getNum() - 1 + ); + } + + indexedLineSet->coordIndex.set1Value( + indexedLineSet->coordIndex.getNum(), + SO_END_FACE_INDEX + ); + } + } + + this->edges->enableNotify(true); + + this->edges->touch(); +} + +void +Viewer::drawConfigurationPath(const rl::plan::VectorList& path) +{ + // TODO: delete me if you want to draw the final path + return; + + this->path->enableNotify(false); + + this->pathCoordinate->point.setNum(0); + this->pathIndexedLineSet->coordIndex.setNum(0); + + rl::math::Vector inter(this->model->getDof()); + + for (std::size_t l = 0; l < this->model->getOperationalDof(); ++l) + { + rl::plan::VectorList::const_iterator i = path.begin(); + rl::plan::VectorList::const_iterator j = ++path.begin(); + + if (i != path.end() && j != path.end()) + { + this->model->setPosition(*i); + this->model->updateFrames(); + + this->pathCoordinate->point.set1Value( + this->pathCoordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) + ); + + this->pathIndexedLineSet->coordIndex.set1Value( + this->pathIndexedLineSet->coordIndex.getNum(), + this->pathCoordinate->point.getNum() - 1 + ); + } + + for (; i != path.end() && j != path.end(); ++i, ++j) + { + rl::math::Real steps = std::ceil(this->model->robotMovementDistance(*i, *j) / this->delta); + + for (std::size_t k = 1; k < steps + 1; ++k) + { + this->model->interpolate(*i, *j, k / steps, inter); + + this->model->setPosition(inter); + this->model->updateFrames(false); + + this->pathCoordinate->point.set1Value( + this->pathCoordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) + ); + + this->pathIndexedLineSet->coordIndex.set1Value( + this->pathIndexedLineSet->coordIndex.getNum(), + this->pathCoordinate->point.getNum() - 1 + ); + } + } + + this->pathIndexedLineSet->coordIndex.set1Value( + this->pathIndexedLineSet->coordIndex.getNum(), + SO_END_FACE_INDEX + ); + } + + this->path->enableNotify(true); + + this->path->touch(); +} + +void +Viewer::drawConfigurationVertex(const rl::math::Vector& q, const bool& free) +{ + QMutexLocker lock_(&draw_mutex); + + SoVRMLCoordinate* coordinate = NULL; + + if (free) + { + coordinate = this->verticesFreeCoordinate; + } + else + { + coordinate = this->verticesCollidingCoordinate; + } + + this->vertices->enableNotify(false); + + this->model->setPosition(q); + this->model->updateFrames(false); + + for (std::size_t l = 0; l < this->model->getOperationalDof(); ++l) + { + coordinate->point.set1Value( + coordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) + ); + } + + this->vertices->enableNotify(true); + + this->vertices->touch(); +} + +void +Viewer::drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1) +{ + this->linesCoordinate->point.set1Value( + this->linesCoordinate->point.getNum(), + xyz0(0), + xyz0(1), + xyz0(2) + ); + + this->linesIndexedLineSet->coordIndex.set1Value( + this->linesIndexedLineSet->coordIndex.getNum(), + this->linesCoordinate->point.getNum() - 1 + ); + + this->linesCoordinate->point.set1Value( + this->linesCoordinate->point.getNum(), + xyz1(0), + xyz1(1), + xyz1(2) + ); + + this->linesIndexedLineSet->coordIndex.set1Value( + this->linesIndexedLineSet->coordIndex.getNum(), + this->linesCoordinate->point.getNum() - 1 + ); + + this->linesIndexedLineSet->coordIndex.set1Value( + this->linesIndexedLineSet->coordIndex.getNum(), + SO_END_FACE_INDEX + ); +} + +void +Viewer::drawPoint(const rl::math::Vector& xyz) +{ + this->pointsCoordinate->point.set1Value( + this->pointsCoordinate->point.getNum(), + xyz(0), + xyz(1), + xyz(2) + ); +} + +void +Viewer::drawSphere(const rl::math::Vector& center, const rl::math::Real& radius) +{ + SoVRMLTransform* transform = new SoVRMLTransform(); + transform->translation.setValue(center(0), center(1), center(2)); + + SoVRMLShape* shape = new SoVRMLShape(); + + shape->appearance = this->spheresAppearance; + + SoVRMLSphere* sphere = new SoVRMLSphere(); + sphere->radius = radius; + + shape->geometry = sphere; + + transform->addChild(shape); + + this->spheresGroup->addChild(transform); +} + +void +Viewer::drawSweptVolume(const rl::plan::VectorList& path) +{ + this->sweptGroup->enableNotify(false); + + this->sweptGroup->removeAllChildren(); + + rl::math::Vector inter(this->model->getDof()); + + rl::plan::VectorList::const_iterator i = path.begin(); + rl::plan::VectorList::const_iterator j = ++path.begin(); + + if (i != path.end() && j != path.end()) + { + this->model->setPosition(*i); + this->model->updateFrames(); + + SoVRMLGroup* model = new SoVRMLGroup(); + + for (std::size_t i = 0; i < this->model->model->getNumBodies(); ++i) + { + SoVRMLTransform* frame = new SoVRMLTransform(); + frame->copyFieldValues(static_cast< rl::sg::so::Body* >(this->model->model->getBody(i))->root); + + for (std::size_t j = 0; j < this->model->model->getBody(i)->getNumShapes(); ++j) + { + SoVRMLTransform* transform = new SoVRMLTransform(); + transform->copyFieldValues(static_cast< rl::sg::so::Shape* >(this->model->model->getBody(i)->getShape(j))->root); + transform->addChild(static_cast< rl::sg::so::Shape* >(this->model->model->getBody(i)->getShape(j))->shape); + frame->addChild(transform); + } + + model->addChild(frame); + } + + this->sweptGroup->addChild(model); + } + + for (; i != path.end() && j != path.end(); ++i, ++j) + { + rl::math::Real steps = std::ceil(this->model->robotMovementDistance(*i, *j) / this->delta); + + for (std::size_t k = 1; k < steps + 1; ++k) + { + this->model->interpolate(*i, *j, k / steps, inter); + + this->model->setPosition(inter); + this->model->updateFrames(); + + SoVRMLGroup* model = new SoVRMLGroup(); + + for (std::size_t i = 0; i < this->model->model->getNumBodies(); ++i) + { + SoVRMLTransform* frame = new SoVRMLTransform(); + frame->copyFieldValues(static_cast< rl::sg::so::Body* >(this->model->model->getBody(i))->root); + + for (std::size_t j = 0; j < this->model->model->getBody(i)->getNumShapes(); ++j) + { + SoVRMLTransform* transform = new SoVRMLTransform(); + transform->copyFieldValues(static_cast< rl::sg::so::Shape* >(this->model->model->getBody(i)->getShape(j))->root); + transform->addChild(static_cast< rl::sg::so::Shape* >(this->model->model->getBody(i)->getShape(j))->shape); + frame->addChild(transform); + } + + model->addChild(frame); + } + + this->sweptGroup->addChild(model); + } + } + + this->sweptGroup->enableNotify(true); + + this->sweptGroup->touch(); +} + +void +Viewer::drawWork(const rl::math::Transform& t) +{ + SbMatrix matrix; + + for (int i = 0; i < 4; ++i) + { + for (int j = 0; j < 4; ++j) + { + matrix[i][j] = static_cast< float >(t(j, i)); + } + } + + this->workTransform->setMatrix(matrix); +} + +void +Viewer::drawWorkEdge(const rl::math::Vector& u, const rl::math::Vector& v) +{ + this->edges3Coordinate->point.set1Value( + this->edges3Coordinate->point.getNum(), + u(0), + u(1), + u(2) + ); + + this->edges3IndexedLineSet->coordIndex.set1Value( + this->edges3IndexedLineSet->coordIndex.getNum(), + this->edges3Coordinate->point.getNum() - 1 + ); + + this->edges3Coordinate->point.set1Value( + this->edges3Coordinate->point.getNum(), + v(0), + v(1), + v(2) + ); + + this->edges3IndexedLineSet->coordIndex.set1Value( + this->edges3IndexedLineSet->coordIndex.getNum(), + this->edges3Coordinate->point.getNum() - 1 + ); + + this->edges3IndexedLineSet->coordIndex.set1Value( + this->edges3IndexedLineSet->coordIndex.getNum(), + SO_END_FACE_INDEX + ); +} + +void +Viewer::drawWorkPath(const rl::plan::VectorList& path) +{ + this->path3->enableNotify(false); + + this->path3Coordinate->point.setNum(0); + this->path3IndexedLineSet->coordIndex.setNum(0); + + for (rl::plan::VectorList::const_iterator i = path.begin(); i != path.end(); ++i) + { + this->path3Coordinate->point.set1Value( + this->path3Coordinate->point.getNum(), + (*i)(0), + (*i)(1), + (*i)(2) + ); + + this->path3IndexedLineSet->coordIndex.set1Value( + this->path3IndexedLineSet->coordIndex.getNum(), + this->path3Coordinate->point.getNum() - 1 + ); + } + + this->path3IndexedLineSet->coordIndex.set1Value( + this->path3IndexedLineSet->coordIndex.getNum(), + SO_END_FACE_INDEX + ); + + this->path3->enableNotify(true); + + this->path3->touch(); +} + +void +Viewer::drawWorkVertex(const rl::math::Vector& q) +{ +} + +void +Viewer::reset() +{ + this->resetEdges(); + this->resetLines(); + this->resetPoints(); + this->resetSpheres(); + this->resetVertices(); + this->pathCoordinate->point.setNum(0); + this->pathIndexedLineSet->coordIndex.setNum(0); + this->path3Coordinate->point.setNum(0); + this->path3IndexedLineSet->coordIndex.setNum(0); + this->sweptGroup->removeAllChildren(); + this->workTransform->setMatrix(SbMatrix::identity()); +} + +void +Viewer::resetEdges() +{ + this->edgesCollidingCoordinate->point.setNum(0); + this->edgesCollidingIndexedLineSet->coordIndex.setNum(0); + this->edgesFreeCoordinate->point.setNum(0); + this->edgesFreeIndexedLineSet->coordIndex.setNum(0); + this->edges3Coordinate->point.setNum(0); + this->edges3IndexedLineSet->coordIndex.setNum(0); +} + +void +Viewer::resetLines() +{ + this->linesCoordinate->point.setNum(0); + this->linesIndexedLineSet->coordIndex.setNum(0); +} + +void +Viewer::resetPoints() +{ + this->pointsCoordinate->point.setNum(0); +} + +void +Viewer::resetSpheres() +{ + this->spheresGroup->removeAllChildren(); +} + +void +Viewer::resetVertices() +{ + this->verticesCollidingCoordinate->point.setNum(0); + this->verticesFreeCoordinate->point.setNum(0); +} + +void +Viewer::saveImage(const QString& filename) +{ + glReadBuffer(GL_FRONT); + QImage image = static_cast< QGLWidget* >(this->viewer->getGLWidget())->grabFrameBuffer(false); + + QString format = filename.right(filename.length() - filename.lastIndexOf('.') - 1).toUpper(); + + if (("JFIF" == format) || ("JPE" == format) || ("JPG" == format)) + { + format = "JPEG"; + } + + if (!image.save(filename, format.toStdString().c_str())) + { + QMessageBox::critical(this, this->windowTitle(), "Error writing " + filename + "."); + } +} + +void +Viewer::saveScene(const QString& filename) +{ + SoOutput output; + + if (!output.openFile(filename.toStdString().c_str())) + { + return; + } + + output.setHeaderString("#VRML V2.0 utf8"); + + SoWriteAction writeAction(&output); + writeAction.apply(this->root); + + output.closeFile(); +} + +void +Viewer::toggleConfigurationEdges(const bool& doOn) +{ + if (doOn) + { + this->edges->whichChoice = SO_SWITCH_ALL; + } + else + { + this->edges->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::toggleConfigurationVertices(const bool& doOn) +{ + if (doOn) + { + this->vertices->whichChoice = SO_SWITCH_ALL; + } + else + { + this->vertices->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::toggleLines(const bool& doOn) +{ + if (doOn) + { + this->lines->whichChoice = SO_SWITCH_ALL; + } + else + { + this->lines->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::togglePoints(const bool& doOn) +{ + if (doOn) + { + this->points->whichChoice = SO_SWITCH_ALL; + } + else + { + this->points->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::toggleSpheres(const bool& doOn) +{ + if (doOn) + { + this->spheres->whichChoice = SO_SWITCH_ALL; + } + else + { + this->spheres->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::toggleWorkFrames(const bool& doOn) +{ + if (doOn) + { + this->work->whichChoice = SO_SWITCH_ALL; + } + else + { + this->work->whichChoice = SO_SWITCH_NONE; + } +} diff --git a/src/rlDamaDemoGUI/Viewer.h b/src/rlDamaDemoGUI/Viewer.h new file mode 100644 index 0000000..eb8ba68 --- /dev/null +++ b/src/rlDamaDemoGUI/Viewer.h @@ -0,0 +1,267 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _VIEWER_H_ +#define _VIEWER_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "DamaModel.h" +#include +#include + +class Viewer : public QWidget, public rl::plan::Viewer +{ + Q_OBJECT + +public: + Viewer(QWidget* parent = NULL, Qt::WindowFlags f = 0); + + virtual ~Viewer(); + + void customize(); + + rl::math::Real delta; + + dama::DamaModel* model; + + SoVRMLGroup* sceneGroup; + + SoQtExaminerViewer* viewer; + + QMutex draw_mutex; + +public slots: + void drawConfiguration(const rl::math::Vector& q); + + void drawConfigurationEdge(const rl::math::Vector& u, const rl::math::Vector& v, const bool& free = true); + + void drawConfigurationPath(const rl::plan::VectorList& path); + + void drawConfigurationVertex(const rl::math::Vector& q, const bool& free = true); + + void drawLine(const rl::math::Vector& xyz0, const rl::math::Vector& xyz1); + + void drawPoint(const rl::math::Vector& xyz); + + void drawSphere(const rl::math::Vector& center, const rl::math::Real& radius); + + void drawSweptVolume(const rl::plan::VectorList& path); + + void drawWork(const rl::math::Transform& t); + + void drawWorkEdge(const rl::math::Vector& u, const rl::math::Vector& v); + + void drawWorkPath(const rl::plan::VectorList& path); + + void drawWorkVertex(const rl::math::Vector& q); + + void reset(); + + void resetEdges(); + + void resetLines(); + + void resetPoints(); + + void resetSpheres(); + + void resetVertices(); + + void saveImage(const QString& filename); + + void saveScene(const QString& filename); + + void toggleConfigurationEdges(const bool& doOn); + + void toggleConfigurationVertices(const bool& doOn); + + void toggleLines(const bool& doOn); + + void togglePoints(const bool& doOn); + + void toggleSpheres(const bool& doOn); + + void toggleWorkFrames(const bool& doOn); + +protected: + +private: + SoVRMLSwitch* edges; + + SoVRMLSwitch* edgesColliding; + + SoVRMLAppearance* edgesCollidingAppearance; + + SoVRMLCoordinate* edgesCollidingCoordinate; + + SoDrawStyle* edgesCollidingDrawStyle; + + SoVRMLIndexedLineSet* edgesCollidingIndexedLineSet; + + SoVRMLMaterial* edgesCollidingMaterial; + + SoVRMLShape* edgesCollidingShape; + + SoVRMLSwitch* edgesFree; + + SoVRMLAppearance* edgesFreeAppearance; + + SoVRMLCoordinate* edgesFreeCoordinate; + + SoDrawStyle* edgesFreeDrawStyle; + + SoVRMLIndexedLineSet* edgesFreeIndexedLineSet; + + SoVRMLMaterial* edgesFreeMaterial; + + SoVRMLShape* edgesFreeShape; + + SoVRMLSwitch* edges3; + + SoVRMLAppearance* edges3Appearance; + + SoVRMLCoordinate* edges3Coordinate; + + SoDrawStyle* edges3DrawStyle; + + SoVRMLIndexedLineSet* edges3IndexedLineSet; + + SoVRMLMaterial* edges3Material; + + SoVRMLShape* edges3Shape; + + SoVRMLIndexedLineSet* frameIndexedLineSet; + + SoVRMLSwitch* lines; + + SoVRMLAppearance* linesAppearance; + + SoVRMLCoordinate* linesCoordinate; + + SoDrawStyle* linesDrawStyle; + + SoVRMLIndexedLineSet* linesIndexedLineSet; + + SoVRMLMaterial* linesMaterial; + + SoVRMLShape* linesShape; + + SoVRMLSwitch* path; + + SoVRMLAppearance* pathAppearance; + + SoVRMLCoordinate* pathCoordinate; + + SoDrawStyle* pathDrawStyle; + + SoVRMLIndexedLineSet* pathIndexedLineSet; + + SoVRMLMaterial* pathMaterial; + + SoVRMLShape* pathShape; + + SoVRMLSwitch* path3; + + SoVRMLAppearance* path3Appearance; + + SoVRMLCoordinate* path3Coordinate; + + SoDrawStyle* path3DrawStyle; + + SoVRMLIndexedLineSet* path3IndexedLineSet; + + SoVRMLMaterial* path3Material; + + SoVRMLShape* path3Shape; + + SoVRMLSwitch* points; + + SoVRMLAppearance* pointsAppearance; + + SoVRMLCoordinate* pointsCoordinate; + + SoDrawStyle* pointsDrawStyle; + + SoVRMLPointSet* pointsPointSet; + + SoVRMLMaterial* pointsMaterial; + + SoVRMLShape* pointsShape; + + SoVRMLSwitch* root; + + SoVRMLSwitch* scene; + + SoDrawStyle* sceneDrawStyle; + + SoVRMLSwitch* spheres; + + SoVRMLAppearance* spheresAppearance; + + SoDrawStyle* spheresDrawStyle; + + SoVRMLGroup* spheresGroup; + + SoVRMLMaterial* spheresMaterial; + + SoVRMLSwitch* swept; + + SoVRMLGroup* sweptGroup; + + SoVRMLSwitch* vertices; + + SoVRMLSwitch* verticesColliding; + + SoVRMLAppearance* verticesCollidingAppearance; + + SoVRMLColor* verticesCollidingColor; + + SoVRMLCoordinate* verticesCollidingCoordinate; + + SoDrawStyle* verticesCollidingDrawStyle; + + SoVRMLPointSet* verticesCollidingPointSet; + + SoVRMLMaterial* verticesCollidingMaterial; + + SoVRMLShape* verticesCollidingShape; + + SoVRMLSwitch* verticesFree; + + SoVRMLAppearance* verticesFreeAppearance; + + SoVRMLColor* verticesFreeColor; + + SoVRMLCoordinate* verticesFreeCoordinate; + + SoDrawStyle* verticesFreeDrawStyle; + + SoVRMLPointSet* verticesFreePointSet; + + SoVRMLMaterial* verticesFreeMaterial; + + SoVRMLShape* verticesFreeShape; + + SoVRMLSwitch* work; + + SoDrawStyle* workDrawStyle; + + SoVRMLTransform* workTransform; +}; + +#endif // _VIEWER_H_ diff --git a/src/rlDamaDemoGUI/rlDamaDemoGUI.cpp b/src/rlDamaDemoGUI/rlDamaDemoGUI.cpp new file mode 100644 index 0000000..027b577 --- /dev/null +++ b/src/rlDamaDemoGUI/rlDamaDemoGUI.cpp @@ -0,0 +1,61 @@ +/* + * Copyright (c) 2015, Markus Rickert, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include +#include +#include +#include +#include + +#include "MainWindow.h" +#include "DamaPlanner.h" + +MainWindow* MainWindow::singleton = NULL; + +int main(int argc, char** argv) +{ + try + { + if(argc != 2) + { + std::cerr << "Usage: program task.xml" << std::endl; + return -1; + } + + DamaPlanner::getInstance()->init(argv[1]); + + if(DamaPlanner::getInstance()->dModel->viewerMode == "off") + { + DamaPlanner::getInstance()->run(); + + + + return EXIT_SUCCESS; + } + else + { + QApplication application(argc, argv); + + qRegisterMetaType< rl::math::Real >("rl::math::Real"); + qRegisterMetaType< rl::math::Transform >("rl::math::Transform"); + qRegisterMetaType< rl::math::Vector >("rl::math::Vector"); + qRegisterMetaType< rl::plan::VectorList >("rl::plan::VectorList"); + + QObject::connect(&application, SIGNAL(lastWindowClosed()), &application, SLOT(quit())); + + MainWindow::instance()->show(); + + int rc = application.exec(); + // cleanup Qt application here ? + return rc; + } + } + catch (const std::exception& e) + { + std::cerr << e.what() << std::endl; + return -1; + } +} diff --git a/src/rlDamaRun/CMakeLists.txt b/src/rlDamaRun/CMakeLists.txt new file mode 100644 index 0000000..5489671 --- /dev/null +++ b/src/rlDamaRun/CMakeLists.txt @@ -0,0 +1,119 @@ +CMAKE_MINIMUM_REQUIRED(VERSION 2.8) + +PROJECT(rlDamaRun) + +FIND_PACKAGE(Ice) +FIND_PACKAGE(Boost COMPONENTS system REQUIRED) +FIND_PACKAGE(Eigen REQUIRED) +FIND_PACKAGE(LibXml2 REQUIRED) +FIND_PACKAGE(Boost REQUIRED) +FIND_PATH(FRI_LIBRARY_DIR + NAMES + Linux/x64/release/lib/libFastResearchInterfaceLibrary.a + Linux/x64/release/lib/FastResearchInterfaceLibrary.a + PATHS + ${CMAKE_CURRENT_SOURCE_DIR}/../../../../../gaschler/FRILibrary + DOC + "Fast Research Interface Library for Kuka LWR4 robot" +) + +find_package(RL COMPONENTS KIN MDL HAL REQUIRED) + +INCLUDE_DIRECTORIES( + BEFORE + ${CMAKE_CURRENT_SOURCE_DIR}/.. + ${Boost_INCLUDE_DIR} + ${EIGEN_INCLUDE_DIRS} + ${LIBXML2_INCLUDE_DIRS} +) + +if(ICE_FOUND) + INCLUDE_DIRECTORIES( + BEFORE + ${ICE_INCLUDE_DIR} + ) + SET( + SRCS + rlDamaRun.cpp + DamaExecutor.h + DamaExecutor.cpp + ) + + ICE_WRAP_CPP_2( + ICE_SOURCES + ${CMAKE_CURRENT_SOURCE_DIR} + meka-robot.ice + ) + + ADD_EXECUTABLE( + rlDamaMekaRun + ${ICE_SOURCES} + ${SRCS} + ) + + LINK_DIRECTORIES( + ${Boost_LIBRARY_DIRS} + ) + + TARGET_LINK_LIBRARIES( + rlDamaMekaRun + ${RL_LIBRARIES} + ${Boost_LIBRARIES} + ${LIBXML2_LIBRARIES} + ${ICE_LIBRARIES} + ) +else(ICE_FOUND) + message(WARNING "ZeroC Ice not found, skipping Meka robot execution client") +endif(ICE_FOUND) + +ADD_EXECUTABLE( + rlDamaCoachRun + rlDamaKukaFRIRun.cpp + DamaKukaFRIExecutor.h + DamaKukaFRIExecutor.cpp +) +SET_TARGET_PROPERTIES( + rlDamaCoachRun + PROPERTIES + COMPILE_DEFINITIONS USE_REAL_ROBOT=0 +) +TARGET_LINK_LIBRARIES( + rlDamaCoachRun + ${RL_LIBRARIES} + ${Boost_LIBRARIES} + ${LIBXML2_LIBRARIES} +) + +if(FRI_LIBRARY_DIR) + ADD_DEFINITIONS( + -DFRI_LIBRARY_DIR="${FRI_LIBRARY_DIR}" + ) + INCLUDE_DIRECTORIES( + ${FRI_LIBRARY_DIR}/include + ) + LINK_DIRECTORIES( + ${FRI_LIBRARY_DIR}/Linux/x64/release/lib + ) + ADD_EXECUTABLE( + rlDamaKukaFRIRun + rlDamaKukaFRIRun.cpp + DamaKukaFRIExecutor.h + DamaKukaFRIExecutor.cpp + KukaFRI.cpp + ) + SET_TARGET_PROPERTIES( + rlDamaKukaFRIRun + PROPERTIES + COMPILE_DEFINITIONS USE_REAL_ROBOT=1 + ) + TARGET_LINK_LIBRARIES( + rlDamaKukaFRIRun + ${RL_LIBRARIES} + ${Boost_LIBRARIES} + ${LIBXML2_LIBRARIES} + FastResearchInterfaceLibrary pthread dl rt + #####stdc++ m rt + ) +else() + message(WARNING "FRI Library x64/release not found, skipping Kuka FRI driver") +endif() diff --git a/src/rlDamaRun/DamaExecutor.cpp b/src/rlDamaRun/DamaExecutor.cpp new file mode 100644 index 0000000..81fb895 --- /dev/null +++ b/src/rlDamaRun/DamaExecutor.cpp @@ -0,0 +1,311 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include "DamaExecutor.h" + +bool DamaExecutor::init(::std::string pathFileNameVertices, ::std::string pathFileNameEdges) const +{ + // 1) read in vertices + ::std::string damaPathSingleVertexLine; + ifstream pathFileVertices(pathFileNameVertices.c_str()); + if(pathFileVertices.is_open()) + { + // determine the vertex dimension by counting the commas in the first line and adding one + if(getline(pathFileVertices,damaPathSingleVertexLine)) + { + DamaExecutor::getInstance()->dimVertex = std::count(damaPathSingleVertexLine.begin(), damaPathSingleVertexLine.end(), ',') + 1; + pathFileVertices.seekg(0, ios::beg); + cout << "Vertex dimension: " << DamaExecutor::getInstance()->dimVertex << endl; + } + else + return false; + + while(getline(pathFileVertices,damaPathSingleVertexLine)) + { + std::stringstream linestream(damaPathSingleVertexLine); + std::string damaPathSingleVertexValue; + ::rl::math::Vector damaPathSingleVertex(DamaExecutor::getInstance()->dimVertex); + + size_t currDim = 0; + while(getline(linestream, damaPathSingleVertexValue, ',')) + { + // (left) trim the value string, otherwise lexical cast will fail + damaPathSingleVertexValue.erase(damaPathSingleVertexValue.begin(), std::find_if(damaPathSingleVertexValue.begin(), damaPathSingleVertexValue.end(), std::not1(std::ptr_fun(std::isspace)))); + damaPathSingleVertex(currDim) = boost::lexical_cast(damaPathSingleVertexValue); + currDim++; + } + DamaExecutor::getInstance()->damaPathVertices.push_back(damaPathSingleVertex); + } + pathFileVertices.close(); + } + else + return false; + + // Test output of damaPathVertices + /*rl::plan::VectorList::iterator i = DamaExecutor::getInstance()->damaPathVertices.begin(); + for(; i != DamaExecutor::getInstance()->damaPathVertices.end(); ++i) + cout << (*i)(0) << endl;*/ + + // 2) read in edges + ::std::string damaPathSingleEdge; + ifstream pathFileEdges(pathFileNameEdges.c_str()); + if(pathFileEdges.is_open()) + { + while(getline(pathFileEdges,damaPathSingleEdge)) + DamaExecutor::getInstance()->damaPathEdges.push_back(damaPathSingleEdge); + pathFileEdges.close(); + } + else + return false; + + // 3) determine number of joints + DamaExecutor::getInstance()->numJoints = 10.0; + + // 4) determine max. velocities per joint (in degree/sec) + DamaExecutor::getInstance()->maxJointVelocity.resize(DamaExecutor::getInstance()->numJoints); + DamaExecutor::getInstance()->maxJointVelocity(0) = 20.0; // 30.0 + DamaExecutor::getInstance()->maxJointVelocity(1) = 17.0; // 50.0 10.0 + DamaExecutor::getInstance()->maxJointVelocity(2) = 17.0; // 50.0 10.0 + for(::std::size_t i=3; inumJoints; ++i) + DamaExecutor::getInstance()->maxJointVelocity(i) = 40.0; // 80.0 + + // 5) determine sample time in seconds + DamaExecutor::getInstance()->sampleTime = 0.01; // 0.02 + + // 6) determine payload values + DamaExecutor::getInstance()->payloadHandNormal = 0.9f; + DamaExecutor::getInstance()->payloadHandGrasp = 1.6f; + + return true; +} + +bool DamaExecutor::calcPath(::std::string pathFileName) const +{ + std::ofstream pathFile; + pathFile.open(pathFileName.c_str()); + + rl::plan::VectorList::iterator v = DamaExecutor::getInstance()->damaPathVertices.begin(); + rl::plan::VectorList::iterator w = ++(DamaExecutor::getInstance()->damaPathVertices.begin()); + ::std::size_t segmentCount = 1; + double executionTime = 0.0; + for(; v != DamaExecutor::getInstance()->damaPathVertices.end() && w != DamaExecutor::getInstance()->damaPathVertices.end(); ++v, ++w) + { + // 1) Determine joint for which the time is limited by the max. velocity -> slowest joint + ::std::size_t slowestJoint = 0; + double maxTime = 0; + double currTime; + for(::std::size_t j=0; jnumJoints; ++j) + { + currTime = ::std::fabs((*w)(j) - (*v)(j)) / DamaExecutor::getInstance()->maxJointVelocity(j); + if(currTime > maxTime) + { + maxTime = currTime; + slowestJoint = j; + } + //cout << j << ": " << currTime << "ms" << endl; + } + executionTime += maxTime; + + cout << "segment " << segmentCount << ": slowestJoint: " << slowestJoint << " | time: " << (maxTime*1000) << "ms" << endl; + + // 2) Calculate the path for the segment using maxTime and sampleTime + for(double currTime=0; currTimesampleTime) + { + ::rl::math::Vector damaPathFinalSingle(DamaExecutor::getInstance()->numJoints); + DamaExecutor::getInstance()->damaPathFinalAction.push_back(DamaExecutor::getInstance()->damaPathEdges.at(segmentCount-1)); + pathFile << segmentCount << ", " << DamaExecutor::getInstance()->damaPathFinalAction.back() << ", " << (currTime*1000) << "ms, "; + for(::std::size_t j=0; jnumJoints; ++j) + { + damaPathFinalSingle(j) = (*v)(j) + (((*w)(j) - (*v)(j)) / maxTime * currTime); + pathFile << damaPathFinalSingle(j); + if(j < DamaExecutor::getInstance()->numJoints - 1) + pathFile << ", "; + } + pathFile << endl; + DamaExecutor::getInstance()->damaPathFinal.push_back(damaPathFinalSingle); + } + + segmentCount++; + } + // manually add the last segment point + ::rl::math::Vector damaPathFinalSingle(DamaExecutor::getInstance()->numJoints); + DamaExecutor::getInstance()->damaPathFinalAction.push_back(DamaExecutor::getInstance()->damaPathEdges.at(segmentCount-2)); + pathFile << segmentCount << ", " << DamaExecutor::getInstance()->damaPathFinalAction.back() << ", " << 0 << "ms, "; + for(::std::size_t j=0; jnumJoints; ++j) + { + damaPathFinalSingle(j) = (*v)(j); + pathFile << damaPathFinalSingle(j); + if(j < DamaExecutor::getInstance()->numJoints - 1) + pathFile << ", "; + } + pathFile << endl; + DamaExecutor::getInstance()->damaPathFinal.push_back(damaPathFinalSingle); + + cout << "overall estimated execution time: " << executionTime << "s" << endl; + cout << "path elements: " << DamaExecutor::getInstance()->damaPathFinal.size() << endl; + + pathFile.close(); + + return true; +} + +bool DamaExecutor::initRobot() const +{ + Ice::CommunicatorPtr ic; + try { + // Ice Init + ic = Ice::initialize(); + Ice::ObjectPrx base = ic->stringToProxy("Robot:default:tcp -h 192.168.21.52 -p 5001"); + DamaExecutor::getInstance()->meka = robot::RobotInterfacePrx::checkedCast(base); + if (!DamaExecutor::getInstance()->meka) throw "Invalid proxy"; + + // Set ModeThetaGc + DamaExecutor::getInstance()->meka->setModeThetaGc("right_arm"); + DamaExecutor::getInstance()->meka->setModeThetaGc("torso"); + + // Set Stiffness and SlewRate of the Arm + robot::SequenceReal stiffnessArm = robot::SequenceReal(); + robot::SequenceReal slewRateArm = robot::SequenceReal(); + for(int i=0; i<7; ++i) + { + stiffnessArm.push_back(Ice::Float(0.9)); + slewRateArm.push_back(Ice::Float(0.6)); + } + DamaExecutor::getInstance()->meka->setStiffness("right_arm", stiffnessArm); + DamaExecutor::getInstance()->meka->setSlewRateProportion("right_arm", slewRateArm); + + // Set Stiffness and SlewRate of the Torso + robot::SequenceReal stiffnessTorso = robot::SequenceReal(); + robot::SequenceReal slewRateTorso = robot::SequenceReal(); + for(int i=0; i<3; ++i) + { + stiffnessTorso.push_back(Ice::Float(0.7)); // 0.6 + slewRateTorso.push_back(Ice::Float(0.5)); // 0.4 + } + DamaExecutor::getInstance()->meka->setStiffness("torso", stiffnessTorso); + DamaExecutor::getInstance()->meka->setSlewRateProportion("torso", slewRateTorso); + + DamaExecutor::getInstance()->meka->setHandPayload(Ice::Float(DamaExecutor::getInstance()->payloadHandNormal)); + + } catch (const Ice::Exception& ex) { + std::cerr << ex << std::endl; + return false; + } catch (const char* msg) { + std::cerr << msg << std::endl; + return false; + } + + return true; +} + +bool DamaExecutor::followPathRobot() const +{ + ::std::string pickupPrefix = "Pickup "; + ::std::string transferPrefix = "Transfer-Rigid "; + ::std::string pushPrefix = "Push"; + + rl::plan::VectorList::iterator v = DamaExecutor::getInstance()->damaPathFinal.begin(); + ::std::vector< ::std::string >::iterator a = DamaExecutor::getInstance()->damaPathFinalAction.begin(); + ::std::string lastAction = "NULL"; + for(; v != DamaExecutor::getInstance()->damaPathFinal.end() && a != DamaExecutor::getInstance()->damaPathFinalAction.end(); ++v, ++a) + { + // TODO: set stiffness and slewRate according to action type? + //if((*a) == "Transit") ... + + if((a->substr(0, transferPrefix.size()) != transferPrefix) && (lastAction.substr(0, transferPrefix.size()) == transferPrefix)) + { + cout << "do hand release ... "; + cout.flush(); + + // decrease payload incrementally + float payloadHandCurr = DamaExecutor::getInstance()->payloadHandGrasp; + while(payloadHandCurr - 0.1f >= DamaExecutor::getInstance()->payloadHandNormal - 1.0e-3f) + { + payloadHandCurr -= 0.1f; + DamaExecutor::getInstance()->meka->setHandPayload(Ice::Float(payloadHandCurr)); + usleep(0.1 * 1000 * 1000); + } + + DamaExecutor::getInstance()->meka->doHandRelease(); + usleep(1.0 * 1000 * 1000); + DamaExecutor::getInstance()->meka->doHandPushPos(); + usleep(2.7 * 1000 * 1000); + cout << "done." << endl; + } + + if((a->substr(0, pickupPrefix.size()) == pickupPrefix) && (lastAction.substr(0, pickupPrefix.size()) != pickupPrefix)) + { + /*cout << "hand grasp: " << *a << endl; + cout << *v << endl;*/ + + cout << "do hand grasp ... "; + cout.flush(); + DamaExecutor::getInstance()->meka->doHandRelease(); + usleep(2.0 * 1000 * 1000); + DamaExecutor::getInstance()->meka->doHandGrasp(); + usleep(2.5 * 1000 * 1000); + + // increase payload incrementally + float payloadHandCurr = DamaExecutor::getInstance()->payloadHandNormal; + while(payloadHandCurr + 0.1f <= DamaExecutor::getInstance()->payloadHandGrasp + 1.0e-3f) + { + payloadHandCurr += 0.1f; + DamaExecutor::getInstance()->meka->setHandPayload(Ice::Float(payloadHandCurr)); + usleep(0.1 * 1000 * 1000); + } + + cout << "done." << endl; + } + + robot::SequenceReal qTorso; + for(::std::size_t j=0; j<3; ++j) + qTorso.push_back((::Ice::Float)(*v)(j)); + + robot::SequenceReal qArm; + for(::std::size_t j=3; j<10; ++j) + qArm.push_back((::Ice::Float)(*v)(j)); + + Ice::AsyncResultPtr r1 = DamaExecutor::getInstance()->meka->begin_setThetaDeg("torso", qTorso); + Ice::AsyncResultPtr r2 = DamaExecutor::getInstance()->meka->begin_setThetaDeg("right_arm", qArm); + + DamaExecutor::getInstance()->meka->end_setThetaDeg(r1); + DamaExecutor::getInstance()->meka->end_setThetaDeg(r2); + DamaExecutor::getInstance()->meka->proxyStep(); + + if(v == DamaExecutor::getInstance()->damaPathFinal.begin()) + { + // sleep 10 seconds long due to driving to starting position + cout << "driving to starting position 10 seconds long ... "; + cout.flush(); + DamaExecutor::getInstance()->meka->doHandPushPos(); + usleep(10 * 1000 * 1000); + cout << "done." << endl; + } + else if((a+1) != DamaExecutor::getInstance()->damaPathFinalAction.end() && (*a) != (*(a+1))) + { + cout << "mode change from " << (*a) << " to " << *(a+1) << ", wait 0 seconds long ... "; + cout.flush(); + //usleep(5 * 1000 * 1000); + cout << "done." << endl; + + if((a+1)->substr(0, pushPrefix.size()) == pushPrefix) + { + cout << "push pause, wait 1.0 seconds long ... "; + cout.flush(); + usleep(1.0 * 1000 * 1000); + cout << "done." << endl; + } + } + else + { + // sleep sampleTime long + usleep(DamaExecutor::getInstance()->sampleTime * 1000 * 1000); + } + + lastAction = *a; + } + + return true; +} diff --git a/src/rlDamaRun/DamaExecutor.h b/src/rlDamaRun/DamaExecutor.h new file mode 100644 index 0000000..da0fb0f --- /dev/null +++ b/src/rlDamaRun/DamaExecutor.h @@ -0,0 +1,60 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMAEXECUTOR_H_ +#define _DAMAEXECUTOR_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include "DamaPrim.h" +#include "DamaPrimTransit.h" +#include "DamaPrimPickup.h" +#include "DamaPrimTransferRigid.h" + +using namespace std; + +class DamaExecutor +{ +public: + static DamaExecutor* getInstance() + { + static DamaExecutor instance; + return &instance; + } + + ::rl::plan::VectorList damaPathVertices; + ::std::vector< ::std::string > damaPathEdges; + ::std::size_t dimVertex; + ::rl::math::Vector maxJointVelocity; // (in degree/sec) + ::std::size_t numJoints; + double sampleTime; + float payloadHandNormal; + float payloadHandGrasp; + + ::rl::plan::VectorList damaPathFinal; + ::std::vector< ::std::string > damaPathFinalAction; + + bool init(::std::string pathFileNameVertices, ::std::string pathFileNameEdges) const; + bool calcPath(::std::string pathFileName) const; + bool initRobot() const; + bool followPathRobot() const; + +private: + DamaExecutor() {}; + DamaExecutor(DamaExecutor const&); // Don't Implement + void operator=(DamaExecutor const&); // Don't implement + + robot::RobotInterfacePrx meka; +}; + +#endif /* _DAMAEXECUTOR_H_ */ diff --git a/src/rlDamaRun/DamaKukaFRIExecutor.cpp b/src/rlDamaRun/DamaKukaFRIExecutor.cpp new file mode 100644 index 0000000..41d396a --- /dev/null +++ b/src/rlDamaRun/DamaKukaFRIExecutor.cpp @@ -0,0 +1,380 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include "DamaKukaFRIExecutor.h" + +const float DamaKukaFRIExecutor::FRI_UPDATE_RATE = 0.002f; + +bool DamaKukaFRIExecutor::init(::std::string pathFileNameVertices, ::std::string pathFileNameEdges) const +{ + // 3) determine number of joints + rl::mdl::XmlFactory factory; + DamaKukaFRIExecutor::getInstance()->robot_kinematics = dynamic_cast< rl::mdl::Dynamic* >(factory.create("data2/kuka-lwr4/rlmdl/kuka-lwr4-right.xml")); + DamaKukaFRIExecutor::getInstance()->numJoints = DamaKukaFRIExecutor::getInstance()->robot_kinematics->getDof(); + + // 1) read in vertices + ::std::string damaPathSingleVertexLine; + ifstream pathFileVertices(pathFileNameVertices.c_str()); + if(pathFileVertices.is_open()) + { + // determine the vertex dimension by counting the commas in the first line and adding one + if(getline(pathFileVertices,damaPathSingleVertexLine)) + { + DamaKukaFRIExecutor::getInstance()->dimVertex = std::count(damaPathSingleVertexLine.begin(), damaPathSingleVertexLine.end(), ',') + 1; + pathFileVertices.seekg(0, ios::beg); + cout << "Vertex dimension: " << DamaKukaFRIExecutor::getInstance()->dimVertex << endl; + } + else + return false; + + while(getline(pathFileVertices,damaPathSingleVertexLine)) + { + std::stringstream linestream(damaPathSingleVertexLine); + std::string damaPathSingleVertexValue; + ::rl::math::Vector damaPathSingleVertex(DamaKukaFRIExecutor::getInstance()->dimVertex); + + size_t currDim = 0; + while(getline(linestream, damaPathSingleVertexValue, ',')) + { + // (left) trim the value string, otherwise lexical cast will fail + damaPathSingleVertexValue.erase(damaPathSingleVertexValue.begin(), std::find_if(damaPathSingleVertexValue.begin(), damaPathSingleVertexValue.end(), std::not1(std::ptr_fun(std::isspace)))); + damaPathSingleVertex(currDim) = boost::lexical_cast(damaPathSingleVertexValue); + currDim++; + } + DamaKukaFRIExecutor::getInstance()->damaPathVertices.push_back(damaPathSingleVertex); + } + pathFileVertices.close(); + } + else + return false; + + // Test output of damaPathVertices + /*rl::plan::VectorList::iterator i = DamaExecutor::getInstance()->damaPathVertices.begin(); + for(; i != DamaExecutor::getInstance()->damaPathVertices.end(); ++i) + cout << (*i)(0) << endl;*/ + + // 2) read in edges + ::std::string damaPathSingleEdge; + ifstream pathFileEdges(pathFileNameEdges.c_str()); + if(pathFileEdges.is_open()) + { + while(getline(pathFileEdges,damaPathSingleEdge)) + DamaKukaFRIExecutor::getInstance()->damaPathEdges.push_back(damaPathSingleEdge); + pathFileEdges.close(); + } + else + return false; + + // 4) determine max. velocities per joint (in degree/sec) + DamaKukaFRIExecutor::getInstance()->maxJointVelocity.resize(DamaKukaFRIExecutor::getInstance()->numJoints); + rl::math::Vector speed(DamaKukaFRIExecutor::getInstance()->numJoints); + DamaKukaFRIExecutor::getInstance()->robot_kinematics->getSpeed(speed); + for(::std::size_t i=0; inumJoints; ++i) + DamaKukaFRIExecutor::getInstance()->maxJointVelocity(i) = speed(i) * rl::math::RAD2DEG * SAFETY_LIMITS_MULTIPLIER; + + // 5) determine sample time in seconds + DamaKukaFRIExecutor::getInstance()->sampleTime = DamaKukaFRIExecutor::FRI_UPDATE_RATE; + + // 6) determine payload values + //DamaKukaFRIExecutor::getInstance()->payloadHandNormal = 0.9f; + //DamaKukaFRIExecutor::getInstance()->payloadHandGrasp = 1.6f; + + return true; +} + +bool DamaKukaFRIExecutor::calcPath(::std::string pathFileName) const +{ + std::ofstream pathFile; + pathFile.open(pathFileName.c_str()); + + rl::plan::VectorList::iterator v = DamaKukaFRIExecutor::getInstance()->damaPathVertices.begin(); + rl::plan::VectorList::iterator w = ++(DamaKukaFRIExecutor::getInstance()->damaPathVertices.begin()); + ::std::size_t segmentCount = 1; + double executionTime = 0.0; + for(; v != DamaKukaFRIExecutor::getInstance()->damaPathVertices.end() && w != DamaKukaFRIExecutor::getInstance()->damaPathVertices.end(); ++v, ++w) + { + // 1) Determine joint for which the time is limited by the max. velocity -> slowest joint + ::std::size_t slowestJoint = 0; + double maxTime = 0; + double currTime; + for(::std::size_t j=0; jnumJoints; ++j) + { + currTime = ::std::fabs((*w)(j) - (*v)(j)) / DamaKukaFRIExecutor::getInstance()->maxJointVelocity(j); + if(currTime > maxTime) + { + maxTime = currTime; + slowestJoint = j; + } + //cout << j << ": " << currTime << "ms" << endl; + } + executionTime += maxTime; + + cout << "segment " << segmentCount << ": slowestJoint: " << slowestJoint << " | time: " << (maxTime*1000) << "ms" << endl; + + // 2) Calculate the path for the segment using maxTime and sampleTime + for(double currTime=0; currTimesampleTime) + { + ::rl::math::Vector damaPathFinalSingle(DamaKukaFRIExecutor::getInstance()->numJoints); + DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.push_back(DamaKukaFRIExecutor::getInstance()->damaPathEdges.at(segmentCount-1)); + pathFile << segmentCount << ", " << DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.back() << ", " << (currTime*1000) << "ms, "; + for(::std::size_t j=0; jnumJoints; ++j) + { + damaPathFinalSingle(j) = (*v)(j) + (((*w)(j) - (*v)(j)) / maxTime * currTime); + pathFile << damaPathFinalSingle(j); + if(j < DamaKukaFRIExecutor::getInstance()->numJoints - 1) + pathFile << ", "; + } + pathFile << endl; + DamaKukaFRIExecutor::getInstance()->damaPathFinal.push_back(damaPathFinalSingle); + } + + segmentCount++; + } + // manually add the last segment point + ::rl::math::Vector damaPathFinalSingle(DamaKukaFRIExecutor::getInstance()->numJoints); + DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.push_back(DamaKukaFRIExecutor::getInstance()->damaPathEdges.at(segmentCount-2)); + pathFile << segmentCount << ", " << DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.back() << ", " << 0 << "ms, "; + for(::std::size_t j=0; jnumJoints; ++j) + { + damaPathFinalSingle(j) = (*v)(j); + pathFile << damaPathFinalSingle(j); + if(j < DamaKukaFRIExecutor::getInstance()->numJoints - 1) + pathFile << ", "; + } + pathFile << endl; + DamaKukaFRIExecutor::getInstance()->damaPathFinal.push_back(damaPathFinalSingle); + + cout << "overall estimated execution time: " << executionTime << "s" << endl; + cout << "path elements: " << DamaKukaFRIExecutor::getInstance()->damaPathFinal.size() << endl; + + pathFile.close(); + + return true; +} + +bool DamaKukaFRIExecutor::initRobot() const +{ +#if USE_REAL_ROBOT + DamaKukaFRIExecutor::getInstance()->robot = new rl::hal::KukaFRI(7, ::std::chrono::duration_cast< ::std::chrono::nanoseconds >(::std::chrono::duration< double >(DamaKukaFRIExecutor::FRI_UPDATE_RATE)), FRI_LIBRARY_DIR "/etc/980039-FRI-Driver.init"); +#else + const char *cmd = "rlmdlcoach data2/kuka-lwr4/rlsg/kuka-lwr4_scene2.xml data2/kuka-lwr4/rlmdl/kuka-lwr4-right.xml &"; + std::cout << "Notice: Running command: " << cmd << std::endl; + int notused = std::system(cmd); + int notused2 = std::system("sleep 2"); + DamaKukaFRIExecutor::getInstance()->robot = new rl::hal::Coach(7, ::std::chrono::duration_cast< ::std::chrono::nanoseconds >(::std::chrono::duration< double >(DamaKukaFRIExecutor::FRI_UPDATE_RATE))); +#endif + { + struct sched_param param; + int not_used; + pthread_getschedparam(pthread_self(), ¬_used, ¶m); + std::cout << "Debug: Demo pthread_getschedparam: " << param.__sched_priority << std::endl; + } + DamaKukaFRIExecutor::getInstance()->gripper = new rl::hal::WeissWsg50(); +#if USE_GRIPPER + DamaKukaFRIExecutor::getInstance()->gripper->open(); + std::cout << "Notice: Starting gripper." << std::endl; + DamaKukaFRIExecutor::getInstance()->gripper->start(); + DamaKukaFRIExecutor::getInstance()->gripper->doAcknowledgeFaults(); + DamaKukaFRIExecutor::getInstance()->gripper->doSetAcceleration(0.2f); + DamaKukaFRIExecutor::getInstance()->gripper->doSetForceLimit(20.0f); + std::cout << "Notice: Gripper is running." << std::endl; +#endif + DamaKukaFRIExecutor::getInstance()->robot->open(); + std::cout << "Notice: Starting robot." << std::endl; + DamaKukaFRIExecutor::getInstance()->robot->start(); +#if USE_REAL_ROBOT + //DamaKukaFRIExecutor::getInstance()->robot->getJointPosition(robot_q_current); + DamaKukaFRIExecutor::getInstance()->robot->step(); // Workaround: Init position control, then impedance + DamaKukaFRIExecutor::getInstance()->robot->stop(); + DamaKukaFRIExecutor::getInstance()->robot->start(FastResearchInterface::JOINT_IMPEDANCE_CONTROL); + DamaKukaFRIExecutor::getInstance()->robot->step(); +#endif + std::cout << "Notice: Robot is running." << std::endl; + + return true; +} + + +bool DamaKukaFRIExecutor::shutdownRobot() const +{ +#if USE_GRIPPER + DamaKukaFRIExecutor::getInstance()->gripper->stop(); + DamaKukaFRIExecutor::getInstance()->gripper->close(); +#endif + std::cout << "Notice: Done." << std::endl; + DamaKukaFRIExecutor::getInstance()->robot->stop(); +#if USE_REAL_ROBOT + DamaKukaFRIExecutor::getInstance()->robot->start(); // Workaround: Reset to position control + DamaKukaFRIExecutor::getInstance()->robot->step(); + DamaKukaFRIExecutor::getInstance()->robot->stop(); +#endif + return true; +} + +bool DamaKukaFRIExecutor::followPathRobot() const +{ + ::std::string pickupPrefix = "Pickup "; + ::std::string transferPrefix = "Transfer-Rigid "; + ::std::string pushPrefix = "Push"; + + rl::math::Vector robot_q_current(DamaKukaFRIExecutor::getInstance()->robot->getDof()); +#if USE_REAL_ROBOT + DamaKukaFRIExecutor::getInstance()->robot->getJointPosition(robot_q_current); +#else + robot_q_current = 5.0f * ::rl::math::Vector::Ones(robot_q_current.size()) * ::rl::math::DEG2RAD; +#endif + rl::plan::VectorList::iterator v = DamaKukaFRIExecutor::getInstance()->damaPathFinal.begin(); + rl::math::Vector robot_q_first = *v * rl::math::DEG2RAD; + cout << "Driving from current position to first node." << endl; cout.flush(); + for(rl::math::Real a = 0; a < 1; a += ::std::chrono::duration_cast< ::std::chrono::duration< double > >(DamaKukaFRIExecutor::getInstance()->robot->getUpdateRate()).count() / 1.5f) + { + rl::math::Vector robot_q = (1-a) * robot_q_current + (a * robot_q_first); + DamaKukaFRIExecutor::getInstance()->robot->setJointPosition(robot_q); + DamaKukaFRIExecutor::getInstance()->robot->step(); + } + + ::std::vector< ::std::string >::iterator a = DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.begin(); + ::std::string lastAction = "NULL"; + for(; v != DamaKukaFRIExecutor::getInstance()->damaPathFinal.end() && a != DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.end(); ++v, ++a) + { + // TODO: set stiffness and slewRate according to action type? + //if((*a) == "Transit") ... + + if((a->substr(0, transferPrefix.size()) != transferPrefix) && (lastAction.substr(0, transferPrefix.size()) == transferPrefix)) + { + cout << "do hand release ... "; + cout.flush(); + + // decrease payload incrementally + /* float payloadHandCurr = DamaKukaFRIExecutor::getInstance()->payloadHandGrasp; + while(payloadHandCurr - 0.1f >= DamaKukaFRIExecutor::getInstance()->payloadHandNormal - 1.0e-3f) + { + payloadHandCurr -= 0.1f; + //DamaExecutor::getInstance()->meka->setHandPayload(Ice::Float(payloadHandCurr)); + usleep(0.1 * 1000 * 1000); + } */ +#if USE_GRIPPER + try{ + gripper->doPrePositionFingers(0.10); + } catch(rl::hal::Exception& e){ + std::cout << "Warning: rl::hal::WeissWsg50::Exception " << e.what() << std::endl; + } +#endif + dama::Timer::sleep(0.01); // avoid jerk + //DamaKukaFRIExecutor::getInstance()->meka->doHandRelease(); + //usleep(1.0 * 1000 * 1000); + //DamaKukaFRIExecutor::getInstance()->meka->doHandPushPos(); + //usleep(2.7 * 1000 * 1000); + + cout << "done." << endl; + } + + if((a->substr(0, pickupPrefix.size()) == pickupPrefix) && (lastAction.substr(0, pickupPrefix.size()) != pickupPrefix)) + { + /*cout << "hand grasp: " << *a << endl; + cout << *v << endl;*/ + + cout << "do hand grasp ... "; + cout.flush(); + +#if USE_GRIPPER + try{ + DamaKukaFRIExecutor::getInstance()->gripper->doPrePositionFingers(0.01); + } catch(rl::hal::Exception& e){ + std::cout << "Warning: rl::hal::WeissWsg50::Exception " << e.what() << std::endl; + } +#endif + dama::Timer::sleep(0.5); // avoid jerk + //DamaExecutor::getInstance()->meka->doHandRelease(); + //usleep(2.0 * 1000 * 1000); + //DamaExecutor::getInstance()->meka->doHandGrasp(); + //usleep(2.5 * 1000 * 1000); + + // increase payload incrementally + /* float payloadHandCurr = DamaKukaFRIExecutor::getInstance()->payloadHandNormal; + while(payloadHandCurr + 0.1f <= DamaKukaFRIExecutor::getInstance()->payloadHandGrasp + 1.0e-3f) + { + payloadHandCurr += 0.1f; + //DamaExecutor::getInstance()->meka->setHandPayload(Ice::Float(payloadHandCurr)); + usleep(0.1 * 1000 * 1000); + } */ + + cout << "done." << endl; + } + + /* + robot::SequenceReal qTorso; + for(::std::size_t j=0; j<3; ++j) + qTorso.push_back((::Ice::Float)(*v)(j)); + + robot::SequenceReal qArm; + for(::std::size_t j=3; j<10; ++j) + qArm.push_back((::Ice::Float)(*v)(j)); + + Ice::AsyncResultPtr r1 = DamaExecutor::getInstance()->meka->begin_setThetaDeg("torso", qTorso); + Ice::AsyncResultPtr r2 = DamaExecutor::getInstance()->meka->begin_setThetaDeg("right_arm", qArm); + + DamaExecutor::getInstance()->meka->end_setThetaDeg(r1); + DamaExecutor::getInstance()->meka->end_setThetaDeg(r2); + DamaExecutor::getInstance()->meka->proxyStep(); + */ + + dama::Timer timer; + DamaKukaFRIExecutor::getInstance()->robot->setJointPosition(*v * rl::math::DEG2RAD); + // std::cout << "Debug: *v * rl::math::DEG2RAD " << (*v).transpose() * rl::math::DEG2RAD << std::endl; + timer.start(); + DamaKukaFRIExecutor::getInstance()->robot->step(); + timer.stop(); + if(timer.elapsedDuration() < DamaKukaFRIExecutor::getInstance()->robot->getUpdateRate() * 0.75) + printf("Warning: Real-time not maintained, Robot::step took only %1.7f s during trajectory.\n", timer.elapsed()); +#if !USE_REAL_ROBOT + //rl::util::Timer::sleep(DamaKukaFRIExecutor::FRI_UPDATE_RATE); +#endif + + if(v == DamaKukaFRIExecutor::getInstance()->damaPathFinal.begin()) + { + // sleep 5 seconds long due to driving to starting position + cout << "driving to starting position 1 seconds long ... "; + cout.flush(); +#if USE_GRIPPER + try{ + gripper->doPrePositionFingers(0.10); + } catch(rl::hal::Exception& e){ + std::cout << "Warning: rl::hal::WeissWsg50::Exception " << e.what() << std::endl; + } +#endif + dama::Timer::sleep(1.0); + cout << "done." << endl; + } + else if((a+1) != DamaKukaFRIExecutor::getInstance()->damaPathFinalAction.end() && (*a) != (*(a+1))) + { + cout << "mode change from " << (*a) << " to " << *(a+1) << ", wait 0.2 seconds long ... "; + cout.flush(); + dama::Timer::sleep(0.2f); + cout << "done." << endl; + + if((a+1)->substr(0, pushPrefix.size()) == pushPrefix) + { + cout << "push pause, wait 1.0 seconds long ... "; + cout.flush(); + dama::Timer::sleep(1.0f); + cout << "done." << endl; + } + } + else + { + // sleep sampleTime long + //usleep(DamaExecutor::getInstance()->sampleTime * 1000 * 1000); + } + + lastAction = *a; + } + + cout << "finishing, wait 1.0 seconds long ... "; + cout.flush(); + dama::Timer::sleep(1.0f); + + return true; +} diff --git a/src/rlDamaRun/DamaKukaFRIExecutor.h b/src/rlDamaRun/DamaKukaFRIExecutor.h new file mode 100644 index 0000000..acd84a8 --- /dev/null +++ b/src/rlDamaRun/DamaKukaFRIExecutor.h @@ -0,0 +1,93 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _DAMA_KUKA_FRI_EXECUTOR_H_ +#define _DAMA_KUKA_FRI_EXECUTOR_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include "DamaPrim.h" +#include "DamaPrimTransit.h" +#include "DamaPrimPickup.h" +#include "DamaPrimTransferRigid.h" +#include "Timer.h" + +#include +#include +#include +#if USE_REAL_ROBOT +#include "KukaFRI.h" +#endif +#include +#include + +using namespace std; + +// 1==real limits 0.5==half speed +#define SAFETY_LIMITS_MULTIPLIER 0.15 + +#if USE_REAL_ROBOT +# define USE_GRIPPER 1 +#else +# define USE_GRIPPER 0 +#endif + +class DamaKukaFRIExecutor +{ +public: + static DamaKukaFRIExecutor* getInstance() + { + static DamaKukaFRIExecutor instance; + return &instance; + } + + ::rl::plan::VectorList damaPathVertices; + ::std::vector< ::std::string > damaPathEdges; + ::std::size_t dimVertex; + ::rl::math::Vector maxJointVelocity; // (in degree/sec) + ::std::size_t numJoints; + double sampleTime; + float payloadHandNormal; + float payloadHandGrasp; + + ::rl::plan::VectorList damaPathFinal; + ::std::vector< ::std::string > damaPathFinalAction; + + bool init(::std::string pathFileNameVertices, ::std::string pathFileNameEdges) const; + bool calcPath(::std::string pathFileName) const; + bool initRobot() const; + bool followPathRobot() const; + bool shutdownRobot() const; + + static const float FRI_UPDATE_RATE; + +private: + DamaKukaFRIExecutor() {}; + ~DamaKukaFRIExecutor(){ + delete robot; + delete gripper; + //delete robot_kinematics; + } + DamaKukaFRIExecutor(DamaKukaFRIExecutor const&); // Don't Implement + void operator=(DamaKukaFRIExecutor const&); // Don't implement + +#if USE_REAL_ROBOT + rl::hal::KukaFRI* +#else + rl::hal::Coach* +#endif + robot; + + rl::hal::WeissWsg50* gripper; + rl::mdl::Dynamic* robot_kinematics; +}; + +#endif /* _DAMA_KUKA_FRI_EXECUTOR_H_ */ diff --git a/src/rlDamaRun/KukaFRI.cpp b/src/rlDamaRun/KukaFRI.cpp new file mode 100644 index 0000000..b4fd90d --- /dev/null +++ b/src/rlDamaRun/KukaFRI.cpp @@ -0,0 +1,145 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include +#include + +#include "KukaFRI.h" + +namespace rl +{ + namespace hal + { + KukaFRI::KukaFRI( + const ::std::size_t& dof, + const ::std::chrono::nanoseconds& updateRate, + const char* configuration_file + ) : + AxisController(dof, updateRate), + JointPositionActuator(dof, updateRate), + JointPositionSensor(dof, updateRate) + { + assert(dof == 7); + this->fri = new FastResearchInterface(configuration_file); + } + + KukaFRI::~KukaFRI() + { + if(isRunning()) + fri->StopRobot(); + delete fri; + } + + void + KukaFRI::close() + { + + } + + void + KukaFRI::getJointPosition(::rl::math::Vector& q) const + { + assert(q.size() >= this->getDof()); + float values[LBR_MNJ]; + fri->GetMeasuredJointPositions(values); + for(std::size_t i = 0; i < LBR_MNJ; i++) + { + q[i] = values[i]; + } + } + + void + KukaFRI::getEstimatedForcesAndTorques(::rl::math::Vector& x) + { + assert(x.size() >= FRI_CART_VEC); + float values[FRI_CART_VEC]; + fri->GetEstimatedExternalCartForcesAndTorques(values); + for(std::size_t i = 0; i < FRI_CART_VEC; i++) + { + x[i] = values[i]; + } + } + + void + KukaFRI::halt() + { + + } + + void + KukaFRI::open() + { + + } + + void + KukaFRI::release() + { + + } + + void + KukaFRI::setJointPosition(const ::rl::math::Vector& q) + { + assert(q.size() >= this->getDof()); + + float values[LBR_MNJ]; + for(std::size_t i = 0; i < LBR_MNJ; i++) + { + values[i] = q[i]; + } + fri->SetCommandedJointPositions(values); + } + + void + KukaFRI::start(FastResearchInterface::LWRControlModes mode) + { + float JointStiffnessValues[LBR_MNJ]; + float JointDampingValues[LBR_MNJ]; + for(std::size_t i = 0; i < LBR_MNJ; i++) + { + JointStiffnessValues[i] = 250.0; //1000.0; + JointDampingValues[i] = 0.7; //0.2;//0.7; + } + float CartStiffnessValues[FRI_CART_VEC]; + float CartDampingValues[FRI_CART_VEC]; + for(std::size_t i = 0; i < FRI_CART_VEC; i++) + { + CartStiffnessValues[i] = 10.0; + CartDampingValues[i] = 0.7; + } + fri->SetCommandedJointStiffness(JointStiffnessValues); + fri->SetCommandedJointDamping(JointDampingValues); + fri->SetCommandedCartStiffness(CartStiffnessValues); + fri->SetCommandedCartDamping(CartDampingValues); + fri->StartRobot(mode); + this->setRunning(true); + } + + void + KukaFRI::start() + { + this->start(FastResearchInterface::JOINT_POSITION_CONTROL); + } + + void + KukaFRI::step() + { + this->timer.start(); + fri->WaitForKRCTick(); + this->timer.stop(); + if(this->timer.elapsedDuration() < this->getUpdateRate() * 0.75) + printf("Notice: KukaFRI::step WaitForKRCTick took only %1.7f s.\n", this->timer.elapsed()); + } + + void + KukaFRI::stop() + { + fri->StopRobot(); + this->setRunning(false); + } + + } +} diff --git a/src/rlDamaRun/KukaFRI.h b/src/rlDamaRun/KukaFRI.h new file mode 100644 index 0000000..acd3c3e --- /dev/null +++ b/src/rlDamaRun/KukaFRI.h @@ -0,0 +1,63 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#ifndef _RL_HAL_KUKAFRI_H_ +#define _RL_HAL_KUKAFRI_H_ + +#include +#include +#include +#include + +#include "Timer.h" + +#include + +namespace rl +{ + namespace hal + { + class KukaFRI : public JointPositionActuator, public JointPositionSensor + { + public: + KukaFRI( + const ::std::size_t& dof, + const ::std::chrono::nanoseconds& updateRate, + const char* configuration_file + ); + + virtual ~KukaFRI(); + + void close(); + + void getJointPosition(::rl::math::Vector& q) const; + + void getEstimatedForcesAndTorques(::rl::math::Vector& x); + + void halt(); + + void open(); + + void release(); + + void setJointPosition(const ::rl::math::Vector& q); + + void start(FastResearchInterface::LWRControlModes mode); + + void start(); + + void step(); + + void stop(); + + public: + FastResearchInterface * fri; + private: + dama::Timer timer; + }; + } +} + +#endif // _RL_HAL_KUKAFRI_H_ diff --git a/src/rlDamaRun/meka-robot.ice b/src/rlDamaRun/meka-robot.ice new file mode 100644 index 0000000..25e5064 --- /dev/null +++ b/src/rlDamaRun/meka-robot.ice @@ -0,0 +1,55 @@ +module robot { + + // Important: This interface definition is not mature yet and may change often. + + + sequence SequenceReal; + sequence SequenceString; + + exception RobotError { + string reason; + }; + + /** + Methods to control the Meka robot. + **/ + interface RobotInterface + { + + // almost equivalent to https://mekabot-dev.com/m3doc/html/#m3humanoid-methods + // with one exceptional difference: get/setTheta* internally call proxy.step()! + + SequenceString getAvailableChains(); + + int getNumDof(string chain) throws RobotError; + + SequenceReal getThetaDeg(string chain) throws RobotError; + + SequenceReal getThetaDotDeg(string chain) throws RobotError; + + + void setStiffness(string chain, SequenceReal stiffness) throws RobotError; + + void setSlewRateProportion(string chain, SequenceReal slew) throws RobotError; + + void setModeThetaGc(string chain) throws RobotError; + + void setThetaDeg(string chain, SequenceReal angles) throws RobotError; + + void proxyStep(); + + + void helloWorld(string s); + + + void doHandRelease(); + + void doHandPushPos(); + + void doHandGrasp(); + + void setHandPayload(float mass); + + }; +}; + diff --git a/src/rlDamaRun/rlDamaKukaFRIRun.cpp b/src/rlDamaRun/rlDamaKukaFRIRun.cpp new file mode 100644 index 0000000..01f023c --- /dev/null +++ b/src/rlDamaRun/rlDamaKukaFRIRun.cpp @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaKukaFRIExecutor.h" + +int main(int argc, char** argv) +{ + if(DamaKukaFRIExecutor::getInstance()->init("solution.vertices", "solution.edges")) + { + ::std::cout << "Init succeeded." << ::std::endl; + if(DamaKukaFRIExecutor::getInstance()->calcPath("solution.path")) + { + ::std::cout << "calcPath succeeded." << ::std::endl; + + if(DamaKukaFRIExecutor::getInstance()->initRobot()) + { + ::std::cout << "InitRobot succeeded." << ::std::endl; + + if(DamaKukaFRIExecutor::getInstance()->followPathRobot()) + { + ::std::cout << "followPathRobot succeeded." << ::std::endl; + } + else + { + ::std::cerr << "followPathRobot failed." << ::std::endl; + } + } + else + { + ::std::cerr << "InitRobot failed." << ::std::endl; + } + DamaKukaFRIExecutor::getInstance()->shutdownRobot(); + } + else + { + ::std::cerr << "calcPath failed." << ::std::endl; + } + } + else + { + ::std::cerr << "Init failed. Could not open files." << ::std::endl; + } + + return 0; +} diff --git a/src/rlDamaRun/rlDamaRun.cpp b/src/rlDamaRun/rlDamaRun.cpp new file mode 100644 index 0000000..7ee5cfc --- /dev/null +++ b/src/rlDamaRun/rlDamaRun.cpp @@ -0,0 +1,48 @@ +/* + * Copyright (c) 2015, Sören Jentzsch, Andre Gaschler + * (See accompanying file LICENSE.md) + */ + +#include + +#include "DamaExecutor.h" + +int main(int argc, char** argv) +{ + if(DamaExecutor::getInstance()->init("solution.vertices", "solution.edges")) + { + ::std::cout << "Init succeeded." << ::std::endl; + if(DamaExecutor::getInstance()->calcPath("solution.path")) + { + ::std::cout << "calcPath succeeded." << ::std::endl; + + if(DamaExecutor::getInstance()->initRobot()) + { + ::std::cout << "InitRobot succeeded." << ::std::endl; + + if(DamaExecutor::getInstance()->followPathRobot()) + { + ::std::cout << "followPathRobot succeeded." << ::std::endl; + } + else + { + ::std::cerr << "followPathRobot failed." << ::std::endl; + } + } + else + { + ::std::cerr << "InitRobot failed." << ::std::endl; + } + } + else + { + ::std::cerr << "calcPath failed." << ::std::endl; + } + } + else + { + ::std::cerr << "Init failed. Could not open files." << ::std::endl; + } + + return 0; +} diff --git a/tests/LICENSE.md b/tests/LICENSE.md new file mode 100644 index 0000000..15442a5 --- /dev/null +++ b/tests/LICENSE.md @@ -0,0 +1,10 @@ +Copyright (c) 2015, Andre Gaschler, Sören Jentzsch +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/tests/testIK/CMakeLists.txt b/tests/testIK/CMakeLists.txt new file mode 100644 index 0000000..a3d01f4 --- /dev/null +++ b/tests/testIK/CMakeLists.txt @@ -0,0 +1,30 @@ +project(testIK) + +find_package(LibXml2 REQUIRED) +find_package(RL COMPONENTS MDL REQUIRED) + + +include_directories( + BEFORE + ${CMAKE_CURRENT_SOURCE_DIR}/../../src + ${EIGEN_INCLUDE_DIRS} + ${LIBXML2_INCLUDE_DIRS} +) + +add_executable( + testIK + testIK.cpp +) + +target_link_libraries( + testIK + moplplan + ${RL_LIBRARIES} + ${LIBXML2_LIBRARIES} +) + +add_test( + NAME testIK1 + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/../.. + COMMAND ${CMAKE_CURRENT_BINARY_DIR}/testIK +) diff --git a/tests/testIK/testIK.cpp b/tests/testIK/testIK.cpp new file mode 100644 index 0000000..5790775 --- /dev/null +++ b/tests/testIK/testIK.cpp @@ -0,0 +1,72 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include + +#include +#include + +#include "XmlFactory.h" +#include "DamaModel.h" + +rl::math::Transform +TransformFromPositionEulerDegrees(rl::math::Vector v) +{ + assert(v.size() == 6); + + rl::math::Transform x; + x.translation() = v.head(3); + x.linear() = ( + rl::math::AngleAxis(v(5) * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(v(4) * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(v(3) * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + ).toRotationMatrix(); + + return x; +} + +int main(int argc, char** argv) +{ + + rl::mdl::XmlFactory factory; + std::shared_ptr< rl::mdl::Model > model(factory.create("data/models/mekabot-convex/rlmdl/mekabot-torso-rightarm.xml")); + rl::mdl::Kinematic* kinematics = dynamic_cast< rl::mdl::Kinematic* >(model.get()); + + bool res_all = true; + + { + rl::math::Vector t(6); + t << 0, 0.26, 0.101, -45.993, 111.091, 135.993; + rl::math::Vector q(10); + q << 6, 2, 2, 80, 0, -40, 30, 120, 0, 15; + q *= rl::math::DEG2RAD; + rl::math::Transform T = TransformFromPositionEulerDegrees(t); + std::cout << "t: " << t.transpose() << std::endl; + std::cout << "q before: " << q.transpose() << std::endl; + bool res = dama::DamaModel::calcInversePositionTaskPosture(kinematics, T, q, rl::math::Matrix::Identity(6,6)); + std::cout << " IK " << ((res) ? "succeeded" : " failed") << std::endl; + std::cout << "q after: " << q.transpose() << std::endl; + res_all &= res; + } + { + rl::math::Vector t(6); + t << -5.07506e-05, 8.64659e-05, 0.101, -45.993, 111.091, 166.403; + rl::math::Vector q(10); + q << 6.57836, 2.56248, 2.56248, 80.4364, 2.59975, -20.9232, 23.294, 128.773, -15.4085, 26.8855; + q *= rl::math::DEG2RAD; + rl::math::Transform T = TransformFromPositionEulerDegrees(t); + std::cout << "t: " << t.transpose() << std::endl; + std::cout << "q before: " << q.transpose() << std::endl; + bool res = dama::DamaModel::calcInversePositionTaskPosture(kinematics, T, q, rl::math::Matrix::Identity(6,6)); + std::cout << " IK " << ((res) ? "succeeded" : " failed") << std::endl; + std::cout << "q after: " << q.transpose() << std::endl; + res_all &= res; + } + + if (res_all) + return EXIT_SUCCESS; + else + return EXIT_FAILURE; +} diff --git a/tests/testMoplPlan/CMakeLists.txt b/tests/testMoplPlan/CMakeLists.txt new file mode 100644 index 0000000..8df4e2a --- /dev/null +++ b/tests/testMoplPlan/CMakeLists.txt @@ -0,0 +1,60 @@ +project(testMoplPlan) + +find_package(Boost COMPONENTS system REQUIRED) +find_package(Cgal REQUIRED) +find_package(Coin REQUIRED) +find_package(Eigen REQUIRED) +find_package(LibXml2 REQUIRED) +find_package(Solid REQUIRED) +find_package(RL COMPONENTS KIN MDL SG PLAN REQUIRED) + +add_definitions( + -DCGAL_DISABLE_ROUNDING_MATH_CHECK + ${COIN_DEFINITIONS} + -DHAVE_SOLID +) + +include_directories( + BEFORE + ${CMAKE_CURRENT_SOURCE_DIR}/../../src + ${Boost_INCLUDE_DIR} + ${CGAL_INCLUDE_DIRS} + ${COIN_INCLUDE_DIRS} + ${EIGEN_INCLUDE_DIRS} + ${LIBXML2_INCLUDE_DIRS} +) + +add_executable( + testMoplPlan + testDamaPlan.cpp +) + +link_directories( + ${Boost_LIBRARY_DIRS} + ${SOLID_INCLUDE_DIRS} +) +target_link_libraries( + testMoplPlan + moplplan + ${RL_LIBRARIES} + ${Boost_LIBRARIES} + ${CGAL_LIBRARIES} + ${COIN_LIBRARIES} + ${LIBXML2_LIBRARIES} + ${SOLID_LIBRARIES} +) + +add_test( + NAME testMoplMekaSimplePush + COMMAND ${CMAKE_CURRENT_BINARY_DIR}/../../src/rlDamaDemoGUI/rlDamaDemoGUI ${CMAKE_CURRENT_SOURCE_DIR}/../../data/tasks-test/meka-simple-push.xml +) + +add_test( + NAME testMoplKukaTransfer3Objects + COMMAND ${CMAKE_CURRENT_BINARY_DIR}/../../src/rlDamaDemoGUI/rlDamaDemoGUI ${CMAKE_CURRENT_SOURCE_DIR}/../../data/tasks-test/kuka-transfer-3-objects.xml +) + +add_test( + NAME testMoplMobileRobotMoveBlockedObject + COMMAND ${CMAKE_CURRENT_BINARY_DIR}/../../src/rlDamaDemoGUI/rlDamaDemoGUI ${CMAKE_CURRENT_SOURCE_DIR}/../../data/tasks-test/mobile-robot-move-blocked-object.xml +) diff --git a/tests/testMoplPlan/testDamaPlan.cpp b/tests/testMoplPlan/testDamaPlan.cpp new file mode 100644 index 0000000..a346219 --- /dev/null +++ b/tests/testMoplPlan/testDamaPlan.cpp @@ -0,0 +1,166 @@ +/* + * Copyright (c) 2015, Andre Gaschler, Sören Jentzsch + * (See accompanying file LICENSE.md) + */ + +#include + +#include +#include + +#include +#include +#include +#include +#include + +#include "XmlFactory.h" +#include "DamaRrt.h" +#include "DamaModel.h" +#include "DamaSampler.h" + +int main(int argc, char** argv) +{ + ::dama::XmlFactory damaFactory; + boost::shared_ptr< ::dama::DamaModel > model = damaFactory.create("data/tasks/config.xml"); + + ::dama::Timer timer; + + /** Configurations */ + //model->debugMode = true; + + ::std::size_t numRuns = 1; // 200 + + // calculate numRuns seeds (with value in srand you can change the seed set) + srand(model->groupSeed); + // srand(time(NULL)); + ::std::vector < ::std::size_t > vecSeeds(numRuns, 0); + for(::std::size_t u=0; uvecDamaPrim.size(); ++p) + benchmarkHeader << "," << model->vecDamaPrim.at(p)->getName() ; + benchmarkHeader << ::std::endl; + benchmarkHeader.close(); + + + ::std::vector vecSolved(numRuns, false); + ::std::vector < ::rl::math::Real > vecTime(numRuns, 0); + ::std::vector < ::std::size_t > vecIterations(numRuns, 0); + ::std::vector < ::std::size_t > vecEdges(numRuns, 0); + ::std::vector < ::std::size_t > vecVertices(numRuns, 0); + ::std::vector < ::std::size_t > vecSolutionVertices(numRuns, 0); + ::std::vector < ::rl::math::Real > vecSolutionLength(numRuns, 0); + ::std::vector < ::rl::math::Real > vecSolutionLengthManipulation(numRuns, 0); + ::std::vector < ::std::vector < ::std::size_t > > vecSolutionManipulationCount(numRuns, ::std::vector < ::std::size_t >(model->vecDamaPrim.size(), 0)); + + + rl::plan::VectorList path; + ::std::deque< ::std::string > actions; + + /*std::cout << "start: " << (*model->dRrt->start).transpose() << std::endl; + std::cout << "goal: " << (*model->dRrt->goal).transpose() << std::endl; + std::cout << "goalDefined: "; + for(::std::size_t i=0; idRrt->goalDimDefined->size(); i++) + std::cout << model->dRrt->goalDimDefined->at(i) << "\t"; + std::cout << std::endl;*/ + + for(::std::size_t u=0; u((double)randSeedNumber); + + if(model->workspaceSampling) + model->dRrt->setConfig(false, false, false); // do NOT change this + + model->dRrt->seed(randSeed); + model->dRrt->resetStatistics(); + model->dRrt->duration = ::std::chrono::duration_cast< ::std::chrono::steady_clock::duration >( ::std::chrono::duration< double >(180.0)); //900.0 //300.0; //1200.0 //boost::lexical_cast< rl::math::Real >(::std::numeric_limits< double >::max()); + // TODO: hierarchical version currently needs this to be redefined ... + rl::math::Vector startCopy(*(model->dRrt->start)); + model->dRrt->start = &startCopy; + rl::math::Vector goalCopy(*(model->dRrt->goal)); + model->dRrt->goal = &goalCopy; + ::std::vector < bool > goalDimDefinedCopy(*(model->dRrt->goalDimDefined)); + model->dRrt->goalDimDefined = &goalDimDefinedCopy; + std::cout << "Start solving nr. " << (u+1) << "/" << numRuns << " with seed " << randSeedNumber << " ... " << std::endl; + timer.start(); + vecSolved.at(u) = model->dRrt->solveAll(path, actions); + timer.stop(); + if(vecSolved.at(u)) + { + ::std::string lastAction = ""; + rl::plan::VectorList::iterator i = path.begin(); + rl::plan::VectorList::iterator j = ++path.begin(); + ::std::deque< ::std::string >::iterator e = actions.begin(); + for (; i != path.end() && j != path.end() && e != actions.end(); ++i, ++j, ++e) + { + ::rl::math::Real tempRobotDist = model->cartesianRobotDistance(*i, *j); + vecSolutionLength.at(u) += tempRobotDist; + if(*e != ::dama::DamaPrimTransit::getInstance()->getName()) + vecSolutionLengthManipulation.at(u) += tempRobotDist; + if(lastAction != *e) + { + for(::std::size_t p=0; psubstr(0, model->vecDamaPrim.at(p)->getName().size()) == model->vecDamaPrim.at(p)->getName()) + vecSolutionManipulationCount.at(u).at(p) ++; + } + lastAction = *e; + } + } + vecTime.at(u) = timer.elapsed(); + vecIterations.at(u) = model->dRrt->getIterationCount(); + vecEdges.at(u) = model->dRrt->getEdgeCount(); + vecVertices.at(u) = model->dRrt->getVertexCount(); + vecSolutionVertices.at(u) = path.size(); + std::cout << "solved: " << vecSolved.at(u) << " \t time: " << vecTime.at(u) << " \t iterations: " << vecIterations.at(u) << " \t edges: " << vecEdges.at(u) << " \t vertices: " << vecVertices.at(u) << " \t vertices (solution): " << vecSolutionVertices.at(u) << " \t length: " << vecSolutionLength.at(u) << " \t length (manipulation only): " << vecSolutionLengthManipulation.at(u) << std::endl; + + // Export statistics to benchmark file + std::ofstream benchmark; + benchmark.open("DamaBenchmark.csv", std::ios::app); +#if !QT_KRAMS + // Current date/time based on current system + time_t now = time(0); + // Convert now to tm struct for local timezone + tm* localtm = localtime(&now); + benchmark << asctime(localtm) << ","; +#else + benchmark << QDateTime::currentDateTime().toString("yyyy-MM-dd HH:mm:ss.zzz").toStdString() << ","; +#endif + benchmark << model->prefixName << ","; + benchmark << (u+1) << ","; + benchmark << randSeedNumber << ","; + benchmark << (vecSolved.at(u) ? "true" : "false") << ","; + benchmark << vecTime.at(u) << ","; + benchmark << model->timeIK << ","; + benchmark << model->dRrt->getTimeSampling() << ","; + benchmark << model->dRrt->getTimeNNSearch() << ","; + benchmark << model->dRrt->getTimePropagate() << ","; + benchmark << model->dRrt->getTimeConnect() << ","; + benchmark << vecIterations.at(u) << ","; + benchmark << vecEdges.at(u) << ","; + benchmark << vecVertices.at(u) << ","; + benchmark << model->getTotalQueries() << ","; + benchmark << model->getFreeQueries() << ","; + benchmark << vecSolutionVertices.at(u) << ","; + benchmark << vecSolutionLength.at(u) << ","; + benchmark << vecSolutionLengthManipulation.at(u) << ","; + for(::std::size_t p=0; p